From fc86de9f6e514ce0acbc9c4e8cd43a24b1f4bc81 Mon Sep 17 00:00:00 2001 From: Philip ABBET <philip.abbet@idiap.ch> Date: Wed, 9 May 2018 09:54:21 +0200 Subject: [PATCH] New release from sandbox --- CMakeLists.txt | 322 +- README.md | 244 +- data/data_pose_gmm_XU.txt | 7 + data/data_pose_tpgmm_XU2.txt | 14 + data/data_quat_tpgmm_XU.txt | 8 + data/data_sphere_gmm_letter_S.txt | 3 + data/data_sphere_tpgmm_transformedXU.txt | 7 + data/data_tpbatch_lqr_frames.txt | 6 + data/data_tpbatch_lqr_trajectories.txt | 10 + data/data_txyz.txt | 4 - docs/LICENSE_gfx_ui.txt | 21 + LICENSE => docs/LICENSE_imgui.txt | 2 +- examples.md | 175 + images/demo_MPC_batch01.gif | Bin 0 -> 396388 bytes images/demo_MPC_iterative01.gif | Bin 0 -> 268207 bytes images/demo_MPC_semitied01.gif | Bin 0 -> 395779 bytes images/demo_MPC_velocity01.gif | Bin 0 -> 214623 bytes images/demo_Riemannian_cov_GMR01.gif | Bin 0 -> 297109 bytes images/demo_Riemannian_cov_interp02.gif | Bin 0 -> 670017 bytes images/demo_Riemannian_pose_batchLQR01.gif | Bin 0 -> 160040 bytes images/demo_Riemannian_pose_infHorLQR01.gif | Bin 0 -> 120036 bytes images/demo_Riemannian_quat_infHorLQR01.png | Bin 0 -> 60870 bytes images/demo_Riemannian_quat_tpgmm01.gif | Bin 0 -> 115802 bytes images/demo_Riemannian_sphere_gmm01.gif | Bin 0 -> 343123 bytes images/demo_Riemannian_sphere_infHorLQR01.gif | Bin 0 -> 652118 bytes images/demo_Riemannian_sphere_product01.gif | Bin 0 -> 647037 bytes images/demo_Riemannian_sphere_tpgmm01.gif | Bin 0 -> 588243 bytes images/demo_TPbatchLQR01.gif | Bin 0 -> 584638 bytes images/demo_online_gmm01.gif | Bin 0 -> 83631 bytes images/demo_proMP01.gif | Bin 0 -> 479562 bytes include/gfx.h | 178 - include/gfx2.h | 417 + include/gfx3.h | 1021 +- include/gfx_ui.h | 20 +- include/imconfig.h | 52 +- include/imgui.h | 1477 +- include/imgui_impl_glfw.h | 29 - include/imgui_impl_glfw_gl2.h | 32 + include/imgui_impl_glfw_gl3.h | 18 +- include/imgui_internal.h | 832 +- include/lqr.h | 120 + include/mvn.h | 38 + include/stb_rect_pack.h | 112 +- include/stb_textedit.h | 83 +- include/stb_truetype.h | 1811 ++- include/tensor.h | 328 + include/window_utils.h | 106 + src/demo_MPC_batch01.cpp | 471 + src/demo_MPC_batch_01.cpp | 344 - src/demo_MPC_iterative01.cpp | 449 + src/demo_MPC_iterative_01.cpp | 322 - src/demo_MPC_semitied01.cpp | 522 + src/demo_MPC_semitied_01.cpp | 402 - src/demo_MPC_velocity01.cpp | 513 + src/demo_MPC_velocity_01.cpp | 379 - src/demo_Riemannian_cov_GMR01.cpp | 912 ++ src/demo_Riemannian_cov_GMR_Mandel01.cpp | 706 + src/demo_Riemannian_cov_interp02.cpp | 535 +- src/demo_Riemannian_pose_batchLQR01.cpp | 625 + src/demo_Riemannian_pose_gmm01.cpp | 363 + src/demo_Riemannian_pose_infHorLQR01.cpp | 614 + src/demo_Riemannian_pose_tpgmm01.cpp | 522 + ...p => demo_Riemannian_quat_infHorLQR01.cpp} | 258 +- src/demo_Riemannian_quat_tpgmm01.cpp | 631 + src/demo_Riemannian_sphere_gmm01.cpp | 547 + src/demo_Riemannian_sphere_infHorLQR.cpp | 823 - src/demo_Riemannian_sphere_infHorLQR01.cpp | 655 + src/demo_Riemannian_sphere_product01.cpp | 571 + src/demo_Riemannian_sphere_tpgmm01.cpp | 922 ++ src/demo_TPbatchLQR01.cpp | 2031 +++ src/demo_dptpgmm.cpp | 566 - src/demo_glsl.cpp | 172 - src/demo_glsl_gfx.cpp | 165 - ...R_infHor.cpp => demo_infHorLQR01_glsl.cpp} | 189 +- src/demo_online_gmm.cpp | 275 - src/demo_online_gmm01.cpp | 452 + src/demo_online_hsmm.cpp | 386 - src/demo_online_hsmm01.cpp | 768 + src/demo_proMP01.cpp | 789 + src/demo_teleop.cpp | 568 - src/demo_tp_multiLqr.cpp | 1278 -- src/demo_tp_trajMpc.cpp | 828 - src/gfx.cpp | 909 -- src/gfx3.cpp | 1368 -- src/imgui.cpp | 9796 ----------- src/imgui_demo.cpp | 2617 --- src/imgui_impl_glfw.cpp | 288 - src/mpc_utils.cpp | 241 - src/utils/gfx2.cpp | 831 + src/utils/gfx3.cpp | 1641 ++ src/{ => utils}/gfx_ui.cpp | 106 +- src/{ => utils}/gl2ps.c | 0 src/utils/imgui.cpp | 13371 ++++++++++++++++ src/{ => utils}/imgui_draw.cpp | 1391 +- src/utils/imgui_impl_glfw_gl2.cpp | 364 + src/{ => utils}/imgui_impl_glfw_gl3.cpp | 278 +- src/utils/mpc_utils.cpp | 241 + 97 files changed, 36873 insertions(+), 24619 deletions(-) create mode 100644 data/data_pose_gmm_XU.txt create mode 100644 data/data_pose_tpgmm_XU2.txt create mode 100644 data/data_quat_tpgmm_XU.txt create mode 100644 data/data_sphere_gmm_letter_S.txt create mode 100644 data/data_sphere_tpgmm_transformedXU.txt create mode 100644 data/data_tpbatch_lqr_frames.txt create mode 100644 data/data_tpbatch_lqr_trajectories.txt delete mode 100755 data/data_txyz.txt create mode 100644 docs/LICENSE_gfx_ui.txt rename LICENSE => docs/LICENSE_imgui.txt (96%) create mode 100644 examples.md create mode 100644 images/demo_MPC_batch01.gif create mode 100644 images/demo_MPC_iterative01.gif create mode 100644 images/demo_MPC_semitied01.gif create mode 100644 images/demo_MPC_velocity01.gif create mode 100644 images/demo_Riemannian_cov_GMR01.gif create mode 100644 images/demo_Riemannian_cov_interp02.gif create mode 100644 images/demo_Riemannian_pose_batchLQR01.gif create mode 100644 images/demo_Riemannian_pose_infHorLQR01.gif create mode 100644 images/demo_Riemannian_quat_infHorLQR01.png create mode 100644 images/demo_Riemannian_quat_tpgmm01.gif create mode 100644 images/demo_Riemannian_sphere_gmm01.gif create mode 100644 images/demo_Riemannian_sphere_infHorLQR01.gif create mode 100644 images/demo_Riemannian_sphere_product01.gif create mode 100644 images/demo_Riemannian_sphere_tpgmm01.gif create mode 100644 images/demo_TPbatchLQR01.gif create mode 100644 images/demo_online_gmm01.gif create mode 100644 images/demo_proMP01.gif delete mode 100644 include/gfx.h create mode 100644 include/gfx2.h delete mode 100644 include/imgui_impl_glfw.h create mode 100644 include/imgui_impl_glfw_gl2.h create mode 100644 include/lqr.h create mode 100644 include/mvn.h create mode 100644 include/tensor.h create mode 100644 include/window_utils.h create mode 100644 src/demo_MPC_batch01.cpp delete mode 100644 src/demo_MPC_batch_01.cpp create mode 100644 src/demo_MPC_iterative01.cpp delete mode 100644 src/demo_MPC_iterative_01.cpp create mode 100644 src/demo_MPC_semitied01.cpp delete mode 100644 src/demo_MPC_semitied_01.cpp create mode 100644 src/demo_MPC_velocity01.cpp delete mode 100644 src/demo_MPC_velocity_01.cpp create mode 100644 src/demo_Riemannian_cov_GMR01.cpp create mode 100644 src/demo_Riemannian_cov_GMR_Mandel01.cpp create mode 100644 src/demo_Riemannian_pose_batchLQR01.cpp create mode 100644 src/demo_Riemannian_pose_gmm01.cpp create mode 100644 src/demo_Riemannian_pose_infHorLQR01.cpp create mode 100644 src/demo_Riemannian_pose_tpgmm01.cpp rename src/{demo_Riemannian_quat_infHorLQR.cpp => demo_Riemannian_quat_infHorLQR01.cpp} (64%) create mode 100644 src/demo_Riemannian_quat_tpgmm01.cpp create mode 100644 src/demo_Riemannian_sphere_gmm01.cpp delete mode 100644 src/demo_Riemannian_sphere_infHorLQR.cpp create mode 100644 src/demo_Riemannian_sphere_infHorLQR01.cpp create mode 100644 src/demo_Riemannian_sphere_product01.cpp create mode 100644 src/demo_Riemannian_sphere_tpgmm01.cpp create mode 100644 src/demo_TPbatchLQR01.cpp delete mode 100644 src/demo_dptpgmm.cpp delete mode 100644 src/demo_glsl.cpp delete mode 100644 src/demo_glsl_gfx.cpp rename src/{demo_LQR_infHor.cpp => demo_infHorLQR01_glsl.cpp} (59%) delete mode 100644 src/demo_online_gmm.cpp create mode 100644 src/demo_online_gmm01.cpp delete mode 100644 src/demo_online_hsmm.cpp create mode 100644 src/demo_online_hsmm01.cpp create mode 100644 src/demo_proMP01.cpp delete mode 100644 src/demo_teleop.cpp delete mode 100644 src/demo_tp_multiLqr.cpp delete mode 100644 src/demo_tp_trajMpc.cpp delete mode 100644 src/gfx.cpp delete mode 100644 src/gfx3.cpp delete mode 100644 src/imgui.cpp delete mode 100644 src/imgui_demo.cpp delete mode 100644 src/imgui_impl_glfw.cpp delete mode 100644 src/mpc_utils.cpp create mode 100644 src/utils/gfx2.cpp create mode 100644 src/utils/gfx3.cpp rename src/{ => utils}/gfx_ui.cpp (96%) rename src/{ => utils}/gl2ps.c (100%) create mode 100644 src/utils/imgui.cpp rename src/{ => utils}/imgui_draw.cpp (63%) create mode 100644 src/utils/imgui_impl_glfw_gl2.cpp rename src/{ => utils}/imgui_impl_glfw_gl3.cpp (50%) create mode 100644 src/utils/mpc_utils.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 0575cfe..14cea49 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,18 +10,8 @@ set(CMAKE_PATCH_VERSION 0) # Dependencies find_package(OpenGL REQUIRED) find_package(Armadillo 5.4 REQUIRED) -find_library(EPOXY_LIB epoxy) find_package(GLEW REQUIRED) -set(PBDLIB_SEARCH_PATH /usr/local/lib/) -find_library(PBD_LIB pbd PATHS ${PBDLIB_SEARCH_PATH} - DOC "Path to the pbdlib library file" -) - -set(PBD_LIB_INCLUDE_DIR "" CACHE STRING - "Path to the directory containing the 'pbdlib' one with the header files (only needed if PBD_LIB is manually specified)" -) - if(APPLE) set(ARMADILLO_LIBRARIES @@ -76,254 +66,274 @@ else() endif() +# Copy data/ to build so that the examples can load from that location +FILE(COPY ${PROJECT_SOURCE_DIR}/data DESTINATION ${CMAKE_CURRENT_BINARY_DIR}/) + + # Setup the include directories include_directories( ${PROJECT_SOURCE_DIR}/include/ ${PROJECT_SOURCE_DIR}/include/arpack-arma/include ${ARMADILLO_INCLUDE_DIRS} - ${PBD_LIB_INCLUDE_DIR} +) + + +# Declare the support files needed for OpenGL2 demos +set(GL2_SUPPORT_SOURCES + ${PROJECT_SOURCE_DIR}/src/utils/imgui_impl_glfw_gl2.cpp + ${PROJECT_SOURCE_DIR}/src/utils/imgui.cpp + ${PROJECT_SOURCE_DIR}/src/utils/imgui_draw.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gfx_ui.cpp +) + + +# Declare the support files needed for OpenGL2 (using gfx2.h) demos +set(GFX2_SUPPORT_SOURCES + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/utils/gfx2.cpp +) + + +# Declare the support files needed for OpenGL3 (using GLSL & gfx3.h) demos +set(GFX3_SUPPORT_SOURCES + ${PROJECT_SOURCE_DIR}/src/utils/imgui_impl_glfw_gl3.cpp + ${PROJECT_SOURCE_DIR}/src/utils/imgui.cpp + ${PROJECT_SOURCE_DIR}/src/utils/imgui_draw.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gfx_ui.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gfx3.cpp ) # Executables -add_executable(demo_online_hsmm - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_online_hsmm.cpp -) -target_link_libraries(demo_online_hsmm +add_executable(demo_infHorLQR01_glsl + ${GFX3_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_infHorLQR01_glsl.cpp +) +target_link_libraries(demo_infHorLQR01_glsl + ${OPENGL_LIBRARIES} + ${ARMADILLO_LIBRARIES} + ${GLFW_LIB} + ${GLEW_LIBRARIES} +) + +add_executable(demo_MPC_batch01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_MPC_batch01.cpp + ${PROJECT_SOURCE_DIR}/src/utils/mpc_utils.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gl2ps.c +) + +target_link_libraries(demo_MPC_batch01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_online_gmm - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_online_gmm.cpp +add_executable(demo_MPC_iterative01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_MPC_iterative01.cpp + ${PROJECT_SOURCE_DIR}/src/utils/mpc_utils.cpp ) -target_link_libraries(demo_online_gmm + +target_link_libraries(demo_MPC_iterative01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_tp_trajMpc - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_tp_trajMpc.cpp +add_executable(demo_MPC_semitied01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_MPC_semitied01.cpp + ${PROJECT_SOURCE_DIR}/src/utils/mpc_utils.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gl2ps.c ) -target_link_libraries(demo_tp_trajMpc +target_link_libraries(demo_MPC_semitied01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_tp_multiLqr - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_tp_multiLqr.cpp +add_executable(demo_MPC_velocity01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_MPC_velocity01.cpp + ${PROJECT_SOURCE_DIR}/src/utils/mpc_utils.cpp + ${PROJECT_SOURCE_DIR}/src/utils/gl2ps.c ) -target_link_libraries(demo_tp_multiLqr +target_link_libraries(demo_MPC_velocity01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_dptpgmm - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_dptpgmm.cpp +add_executable(demo_online_gmm01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_online_gmm01.cpp ) -target_link_libraries(demo_dptpgmm +target_link_libraries(demo_online_gmm01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_LQR_infHor - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw_gl3.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/gfx3.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_LQR_infHor.cpp +add_executable(demo_online_hsmm01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_online_hsmm01.cpp ) -target_link_libraries(demo_LQR_infHor +target_link_libraries(demo_online_hsmm01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${GLEW_LIBRARIES} - ${PBD_LIB} ) -add_executable(demo_Riemannian_cov_interp02 - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/gfx.cpp - ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_cov_interp02.cpp +add_executable(demo_proMP01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_proMP01.cpp ) -target_link_libraries(demo_Riemannian_cov_interp02 +target_link_libraries(demo_proMP01 ${OPENGL_LIBRARIES} ${GLEW_LIBRARIES} ${GLFW_LIB} ${ARMADILLO_LIBRARIES} - ${PBD_LIB} ) -add_executable(demo_Riemannian_sphere_infHorLQR - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw_gl3.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/gfx3.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_infHorLQR.cpp +add_executable(demo_Riemannian_cov_GMR_Mandel01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_cov_GMR_Mandel01.cpp ) -target_link_libraries(demo_Riemannian_sphere_infHorLQR +target_link_libraries(demo_Riemannian_cov_GMR_Mandel01 ${OPENGL_LIBRARIES} - ${ARMADILLO_LIBRARIES} ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} + ${ARMADILLO_LIBRARIES} ) -add_executable(demo_Riemannian_quat_infHorLQR - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_quat_infHorLQR.cpp +add_executable(demo_Riemannian_cov_GMR01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_cov_GMR01.cpp ) -target_link_libraries(demo_Riemannian_quat_infHorLQR +target_link_libraries(demo_Riemannian_cov_GMR01 ${OPENGL_LIBRARIES} - ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} + ${ARMADILLO_LIBRARIES} ) -add_executable(demo_glsl - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/demo_glsl.cpp +add_executable(demo_Riemannian_cov_interp02 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_cov_interp02.cpp ) -target_link_libraries(demo_glsl +target_link_libraries(demo_Riemannian_cov_interp02 ${OPENGL_LIBRARIES} - ${EPOXY_LIB} + ${GLEW_LIBRARIES} ${GLFW_LIB} ${ARMADILLO_LIBRARIES} - ${PBD_LIB} ) -add_executable(demo_glsl_gfx - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/gfx.cpp - ${PROJECT_SOURCE_DIR}/src/demo_glsl_gfx.cpp +add_executable(demo_Riemannian_pose_batchLQR01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_pose_batchLQR01.cpp ) -target_link_libraries(demo_glsl_gfx +target_link_libraries(demo_Riemannian_pose_batchLQR01 + ${ARMADILLO_LIBRARIES} ${OPENGL_LIBRARIES} - ${GLEW_LIBRARIES} ${GLFW_LIB} +) + +add_executable(demo_Riemannian_pose_gmm01 + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_pose_gmm01.cpp +) +target_link_libraries(demo_Riemannian_pose_gmm01 ${ARMADILLO_LIBRARIES} - ${PBD_LIB} ) -add_executable(demo_MPC_batch_01 - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_MPC_batch_01.cpp - ${PROJECT_SOURCE_DIR}/src/mpc_utils.cpp - ${PROJECT_SOURCE_DIR}/src/gl2ps.c +add_executable(demo_Riemannian_pose_infHorLQR01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_pose_infHorLQR01.cpp +) +target_link_libraries(demo_Riemannian_pose_infHorLQR01 + ${ARMADILLO_LIBRARIES} + ${OPENGL_LIBRARIES} + ${GLFW_LIB} +) + +add_executable(demo_Riemannian_pose_tpgmm01 + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_pose_tpgmm01.cpp +) +target_link_libraries(demo_Riemannian_pose_tpgmm01 + ${ARMADILLO_LIBRARIES} ) -target_link_libraries(demo_MPC_batch_01 +add_executable(demo_Riemannian_quat_infHorLQR01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_quat_infHorLQR01.cpp +) +target_link_libraries(demo_Riemannian_quat_infHorLQR01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_MPC_iterative_01 - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_MPC_iterative_01.cpp - ${PROJECT_SOURCE_DIR}/src/mpc_utils.cpp +add_executable(demo_Riemannian_quat_tpgmm01 + ${GL2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_quat_tpgmm01.cpp +) +target_link_libraries(demo_Riemannian_quat_tpgmm01 + ${ARMADILLO_LIBRARIES} + ${OPENGL_LIBRARIES} + ${GLFW_LIB} ) -target_link_libraries(demo_MPC_iterative_01 +add_executable(demo_Riemannian_sphere_gmm01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_gmm01.cpp +) +target_link_libraries(demo_Riemannian_sphere_gmm01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_MPC_velocity_01 - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_MPC_velocity_01.cpp - ${PROJECT_SOURCE_DIR}/src/mpc_utils.cpp - ${PROJECT_SOURCE_DIR}/src/gl2ps.c +add_executable(demo_Riemannian_sphere_infHorLQR01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_infHorLQR01.cpp ) -target_link_libraries(demo_MPC_velocity_01 +target_link_libraries(demo_Riemannian_sphere_infHorLQR01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_MPC_semitied_01 - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/demo_MPC_semitied_01.cpp - ${PROJECT_SOURCE_DIR}/src/mpc_utils.cpp - ${PROJECT_SOURCE_DIR}/src/gl2ps.c +add_executable(demo_Riemannian_sphere_product01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_product01.cpp ) -target_link_libraries(demo_MPC_semitied_01 +target_link_libraries(demo_Riemannian_sphere_product01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} ) -add_executable(demo_teleop - ${PROJECT_SOURCE_DIR}/src/demo_teleop.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_impl_glfw.cpp - ${PROJECT_SOURCE_DIR}/src/imgui.cpp - ${PROJECT_SOURCE_DIR}/src/imgui_draw.cpp - ${PROJECT_SOURCE_DIR}/src/gfx_ui.cpp +add_executable(demo_Riemannian_sphere_tpgmm01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_Riemannian_sphere_tpgmm01.cpp ) -target_link_libraries(demo_teleop +target_link_libraries(demo_Riemannian_sphere_tpgmm01 ${OPENGL_LIBRARIES} ${ARMADILLO_LIBRARIES} + ${GLEW_LIBRARIES} + ${GLFW_LIB} +) + +add_executable(demo_TPbatchLQR01 + ${GFX2_SUPPORT_SOURCES} + ${PROJECT_SOURCE_DIR}/src/demo_TPbatchLQR01.cpp +) +target_link_libraries(demo_TPbatchLQR01 + ${OPENGL_LIBRARIES} + ${GLEW_LIBRARIES} ${GLFW_LIB} - ${PBD_LIB} + ${ARMADILLO_LIBRARIES} ) diff --git a/README.md b/README.md index 30e8464..4bd2d9b 100644 --- a/README.md +++ b/README.md @@ -3,16 +3,23 @@ PbDlib-cpp is a set of tools in C++ combining statistical learning, optimal control and differential geometry for programming-by-demonstration applications. Other versions of the library are available at http://www.idiap.ch/software/pbdlib/ (in Matlab, C++ and Python). + ### Contributors Sylvain Calinon, Ioannis Havoutis, Ajay Tanwani, Emmanuel Pignat, Fabien Crepon, Daniel Berio, Philip Abbet This work was in part supported by the DexROV project through the EC H2020 programme (Grant \#635491). + ### Prerequisite The program requires glfw3 (lightweight and portable library for managing OpenGL contexts, windows and inputs). +ImGui (graphical user interface library for C++, [https://github.com/ocornut/imgui](https://github.com/ocornut/imgui)) and +gfx_ui (a minimal geometry editing UI, [https://github.com/colormotor/gfx\_ui](https://github.com/colormotor/gfx_ui)), are also +used and provided as part of this package. They are both distributed under the MIT license (see the docs/ folder). + + ### Compilation ``` @@ -23,7 +30,10 @@ cmake .. make ``` -### glfw3 deb package install + +### glfw3 installation + +On Debian: ``` sudo apt-get install libglfw3-dev @@ -43,158 +53,112 @@ export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/usr/local/lib ``` **Note:** The `-DBUILD_SHARED_LIBS` is necessary otherwise cmake will create a -static library. +static library. -### References +### References and list of examples -Did you find PbDlib useful for your research? Please acknowledge the authors in any academic publications that used parts of these codes. -<br><br> +See [https://gitlab.idiap.ch/rli/pbdlib-cpp/examples.md](https://gitlab.idiap.ch/rli/pbdlib-cpp/examples.md) -[1] Tutorial (GMM, TP-GMM, MFA, MPPCA, GMR, LWR, GPR, MPC, LQR, trajGMM): -``` -@article{Calinon16JIST, - author="Calinon, S.", - title="A Tutorial on Task-Parameterized Movement Learning and Retrieval", - journal="Intelligent Service Robotics", - publisher="Springer Berlin Heidelberg", - year="2016", - volume="9", - number="1", - pages="1--29", - doi="10.1007/s11370-015-0187-9", -} -``` -[2] HMM, HSMM: -``` -@article{Rozo16Frontiers, - author="Rozo, L. and Silv\'erio, J. and Calinon, S. and Caldwell, D. G.", - title="Learning Controllers for Reactive and Proactive Behaviors in Human-Robot Collaboration", - journal="Frontiers in Robotics and {AI}", - year="2016", - month="June", - volume="3", - number="30", - pages="1--11", - doi="10.3389/frobt.2016.00030" -} -``` +### Gallery -[3] Riemannian manifolds (S2,S3): -``` -@article{Zeestraten17RAL, - author="Zeestraten, M. J. A. and Havoutis, I. and Silv\'erio, J. and Calinon, S. and Caldwell, D. G.", - title="An Approach for Imitation Learning on {R}iemannian Manifolds", - journal="{IEEE} Robotics and Automation Letters ({RA-L})", - year="2017", - month="June", - volume="2", - number="3", - pages="1240--1247" - doi="10.1109/LRA.2017.2657001", -} -``` +demo\_MPC\_batch01 -[4] Riemannian manifolds (S+): -``` -@inproceedings{Jaquier17IROS, - author="Jaquier, N. and Calinon, S.", - title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: Application to Wrist Motion Estimation with {sEMG}", - booktitle="Proc. {IEEE/RSJ} Intl Conf. on Intelligent Robots and Systems ({IROS})", - year="2017", - month="September", - address="Vancouver, Canada", - pages="" -} -``` + -[5] Semi-tied GMM: -``` -@article{Tanwani16RAL, - author="Tanwani, A. K. and Calinon, S.", - title="Learning Robot Manipulation Tasks with Task-Parameterized Semi-Tied Hidden Semi-{M}arkov Model", - journal="{IEEE} Robotics and Automation Letters ({RA-L})", - year="2016", - month="January", - volume="1", - number="1", - pages="235--242", - doi="10.1109/LRA.2016.2517825" -} -``` +*** -[6] DP-means: -``` -@article{Bruno17AURO, - author="Bruno, D. and Calinon, S. and Caldwell, D. G.", - title="Learning Autonomous Behaviours for the Body of a Flexible Surgical Robot", - journal="Autonomous Robots", - year="2017", - month="February", - volume="41", - number="2", - pages="333--347", - doi="10.1007/s10514-016-9544-6" -} -``` +demo\_MPC\_iterative01 -[7] Shared control, adaptive teleoperation: -``` -@inproceedings{Havoutis17ICRA, - author="Havoutis, I. and Calinon, S.", - title="Supervisory teleoperation with online learning and optimal control", - booktitle=ICRA, - year="2017", - month="May-June", - address="Singapore", - pages="1534--1540" -} -``` + -[8] Keypoint-based motion edition through MPC: -``` -@inproceedings{Berio17GI, - author="Berio, D. and Calinon, S. and Fol Leymarie, F.", - title="Generating Calligraphic Trajectories with Model Predictive Control", - booktitle="Proc. 43rd Conf. on Graphics Interface", - year="2017", - month="May", - address="Edmonton, AL, Canada", - pages="132--139", - doi="10.20380/GI2017.17" -} -``` +*** -[9] Adaptive assistance: -``` -@article{Pignat17RAS, - author="Pignat, E. and Calinon, S.", - title="Learning adaptive dressing assistance from human demonstration", - journal="Robotics and Autonomous Systems", - year="2017", - month="July", - volume="93", - number="", - pages="61--75", - doi="10.1016/j.robot.2017.03.017", -} -``` +demo\_MPC\_semitied01 + + + +*** + +demo\_MPC\_velocity01 + + + +*** + +demo\_online\_gmm01 + + + +*** + +demo\_proMP01 + + + +*** + +demo\_Riemannian\_cov\_GMR01 + + + +*** + +demo\_Riemannian\_cov\_interp02 + + + +*** + +demo\_Riemannian\_pose\_batchLQR01 + + + +*** + +demo\_Riemannian\_pose\_infHorLQR01 + + + +*** + +demo\_Riemannian\_quat\_infHorLQR01 + + + +*** + +demo\_Riemannian\_quat\_tpgmm01 + + + +*** + +demo\_Riemannian\_sphere\_gmm01 + + + +*** + +demo\_Riemannian\_sphere\_infHorLQR01 + + + +*** + +demo\_Riemannian\_sphere\_product01 + + + +*** + +demo\_Riemannian\_sphere\_tpgmm01 -### List of examples + -This project will build a number of executables, as listed in the table below. +*** -| Filename | ref. | Description | -|----------|------|-------------| -| demo_LQR_infHor | [1] | Discrete infinite horizon linear quadratic regulation | -| demo_MPC_batch_01 | [1,8] | Model predictive control (MPC) with batch linear quadratic tracking (LQT) formulation | -| demo_MPC_iterative_01 | [1,8] | Model predictive control (MPC) with iterative linear quadratic tracking (LQT) formulation | -| demo_MPC_semitied_01 | [5,8] | MPC with semi-tied covariances | -| demo_MPC_velocity_01 | [1,8] | MPC with an objective including velocity tracking | -| demo_online_gmm | [6] | Online GMM learning and LQR-based trajectory generation | -| demo_online_hsmm | [2,7] | Online HSMM learning and sampling with LQR-based trajectory generation | -| demo_Riemannian_cov_interp02 | [4] | Covariance interpolation on Riemannian manifold from a GMM with augmented covariances | -| demo_Riemannian_quat_infHorLQR | [3] | Linear quadratic regulation on hypersphere (orientation as unit quaternions) by relying on Riemannian manifold and infinite-horizon LQR | -| demo_Riemannian_sphere_infHorLQR | [3] | Linear quadratic regulation on a sphere by relying on Riemannian manifold and infinite-horizon LQR | +demo\_TPbatchLQR01 + diff --git a/data/data_pose_gmm_XU.txt b/data/data_pose_gmm_XU.txt new file mode 100644 index 0000000..a63df0c --- /dev/null +++ b/data/data_pose_gmm_XU.txt @@ -0,0 +1,7 @@ + 5.9744990892532e-01 5.9393810913168e-01 5.8222132135379e-01 5.5641252843967e-01 5.0412101982355e-01 4.1266634288246e-01 2.9501380664681e-01 1.6780039045575e-01 3.7639347443367e-02 -8.6854969709723e-02 -2.1856896570632e-01 -3.4199928687549e-01 -4.4469818627839e-01 -5.2045944508814e-01 -5.7483149530775e-01 -5.9688695450368e-01 -5.8992817456697e-01 -5.6552297481086e-01 -5.3299382591938e-01 -4.8245048465787e-01 -3.9619427944114e-01 -2.7345853708359e-01 -1.1241115561826e-01 8.4027961150802e-02 2.8274429088599e-01 4.4110241555378e-01 5.5466540834447e-01 6.1886346745589e-01 6.5089515603163e-01 6.6253155863142e-01 6.5197523157153e-01 6.1592762121320e-01 5.5034748695497e-01 4.5475589908160e-01 3.4232054300326e-01 2.0764362369675e-01 5.7141629142848e-02 -1.0446032984505e-01 -2.6603130114801e-01 -4.0529003029011e-01 -5.0969132865613e-01 -5.7462059882847e-01 -6.0034586970168e-01 -6.0489596905769e-01 -6.1056356762659e-01 -6.1462363537227e-01 -6.1567009418296e-01 -6.1566441194994e-01 -6.1566485789486e-01 -6.1566484517304e-01 6.0109289617486e-01 5.9326524312049e-01 5.7076348981756e-01 5.3406962852304e-01 4.8864947757756e-01 4.3197019225395e-01 3.5221989005362e-01 2.5042646134249e-01 1.2805645334832e-01 -1.7725051738959e-02 -1.6665668291187e-01 -3.2007850380316e-01 -4.6596395819173e-01 -5.7198048706966e-01 -6.2769514638615e-01 -6.4397861695913e-01 -6.2816777689358e-01 -5.9611946567308e-01 -5.4781640124226e-01 -4.6297006305451e-01 -3.2679435677991e-01 -1.5675742068275e-01 4.9210525051530e-02 2.6391987909997e-01 4.2893044290604e-01 5.2833639202344e-01 5.9712226558592e-01 6.5986665880751e-01 6.9869912353068e-01 7.0485571147013e-01 6.8220764387266e-01 6.3643639723964e-01 5.7978999800420e-01 4.9950028249720e-01 3.7750785996046e-01 2.2525402805875e-01 5.0461518043145e-02 -1.4133773274265e-01 -3.0707786051091e-01 -4.3382850506589e-01 -5.3492414235269e-01 -5.9837478291401e-01 -6.2781273117507e-01 -6.3681869904758e-01 -6.3751158037808e-01 -6.3752287493572e-01 -6.3752277125928e-01 -6.3752276848299e-01 -6.3752276867584e-01 -6.3752276867031e-01 6.7395264116576e-01 6.6401255134313e-01 6.4316528296878e-01 6.0714759924104e-01 5.5251867887091e-01 4.7053074950328e-01 3.5413967167173e-01 1.9257203080729e-01 1.1564488846561e-02 -1.6265577711577e-01 -3.0047741281199e-01 -4.0370225872897e-01 -5.0237375556380e-01 -5.8188710672280e-01 -6.2224152003617e-01 -6.2214461932399e-01 -5.9634185409720e-01 -5.5116735105651e-01 -4.6442188525192e-01 -3.1482452098618e-01 -1.1872255243774e-01 6.9711401240501e-02 2.3150390738104e-01 3.7944549444327e-01 5.0175051090014e-01 5.8032642470120e-01 6.1544864230696e-01 6.2726089977972e-01 6.2555786579368e-01 6.0719280922585e-01 5.7926169598354e-01 5.3674017257404e-01 4.7292723134768e-01 3.9566911525880e-01 3.0185859790618e-01 1.9530383905608e-01 8.9618173952487e-02 -2.6151791528528e-02 -1.5375987146413e-01 -2.7635357179749e-01 -3.8425551279723e-01 -4.8786509222858e-01 -5.6952964654653e-01 -6.0632299481757e-01 -6.1192723547155e-01 -6.1202281753150e-01 -6.1202199529622e-01 -6.1202185956538e-01 -6.1202185770501e-01 -6.1202185792350e-01 6.0837887067395e-01 6.0852729712587e-01 6.0080250835041e-01 5.7284598052105e-01 5.0846431394301e-01 4.0324785490367e-01 2.7888425859812e-01 1.2452240028552e-01 -6.1876911818130e-02 -2.3961158628634e-01 -3.9182437303623e-01 -5.1705255170864e-01 -6.0099078670474e-01 -6.3845394676237e-01 -6.4729447551110e-01 -6.4082458424692e-01 -6.1773938138973e-01 -5.6476987464479e-01 -4.5330181124473e-01 -2.7306252410341e-01 -7.6387017659800e-02 9.8417676211112e-02 2.5308966223498e-01 3.7945861567452e-01 4.8546275890603e-01 5.7268733037595e-01 6.2907261076659e-01 6.4933771550415e-01 6.3339942267990e-01 5.9772078536676e-01 5.5408583524231e-01 5.0143465921394e-01 4.2856261859247e-01 3.3165685245591e-01 2.2834937642204e-01 1.2710509591581e-01 2.4427496927127e-02 -6.7787664035590e-02 -1.4527447925490e-01 -2.1812004641627e-01 -3.0061468328496e-01 -3.7875323596412e-01 -4.3635728475533e-01 -4.8128605843137e-01 -5.1768001391691e-01 -5.4222645798811e-01 -5.5281174923630e-01 -5.5371764154236e-01 -5.5373327516347e-01 -5.5373406193078e-01 6.9945355191257e-01 6.9940630858812e-01 6.9851412459747e-01 6.8740312393311e-01 6.5393146580043e-01 5.8734679687007e-01 4.9319631069989e-01 3.7561906774192e-01 2.1717091792961e-01 1.7473960697306e-02 -1.8636902540290e-01 -3.6649406986192e-01 -5.2003772987115e-01 -6.3378966544910e-01 -7.0651361656126e-01 -7.4784828403187e-01 -7.4733253736928e-01 -7.1854657207535e-01 -6.7195652863065e-01 -6.0898387873813e-01 -4.9595574668218e-01 -3.0650336019800e-01 -7.4353462192837e-02 1.2812961821809e-01 2.7320268890963e-01 3.6903909549958e-01 4.5243046294483e-01 5.3042054272781e-01 5.8678347511779e-01 6.1735611866542e-01 6.1407767400182e-01 5.8304162657744e-01 5.3861426408921e-01 4.7750176660912e-01 4.0348320185633e-01 3.1450412355723e-01 1.9726615866481e-01 6.1067849754903e-02 -7.3464133160384e-02 -2.0686604540187e-01 -3.4165319286943e-01 -4.3556209089713e-01 -4.7400230057681e-01 -4.9483048220526e-01 -5.1760210026057e-01 -5.3418968483096e-01 -5.3906963796025e-01 -5.3915746070838e-01 -5.3916173146664e-01 -5.3916211293260e-01 5.9744990892532e-01 5.9393810913168e-01 5.8222132135379e-01 5.5641252843967e-01 5.0412101982355e-01 4.1266634288246e-01 2.9501380664681e-01 1.6780039045575e-01 3.7639347443367e-02 -8.6854969709723e-02 -2.1856896570632e-01 -3.4199928687549e-01 -4.4469818627839e-01 -5.2045944508814e-01 -5.7483149530775e-01 -5.9688695450368e-01 -5.8992817456697e-01 -5.6552297481086e-01 -5.3299382591938e-01 -4.8245048465787e-01 -3.9619427944114e-01 -2.7345853708359e-01 -1.1241115561826e-01 8.4027961150802e-02 2.8274429088599e-01 4.4110241555378e-01 5.5466540834447e-01 6.1886346745589e-01 6.5089515603163e-01 6.6253155863142e-01 6.5197523157153e-01 6.1592762121320e-01 5.5034748695497e-01 4.5475589908160e-01 3.4232054300326e-01 2.0764362369675e-01 5.7141629142848e-02 -1.0446032984505e-01 -2.6603130114801e-01 -4.0529003029011e-01 -5.0969132865613e-01 -5.7462059882847e-01 -6.0034586970168e-01 -6.0489596905769e-01 -6.1056356762659e-01 -6.1462363537227e-01 -6.1567009418296e-01 -6.1566441194994e-01 -6.1566485789486e-01 -6.1566484517304e-01 6.0109289617486e-01 5.9326524312049e-01 5.7076348981756e-01 5.3406962852304e-01 4.8864947757756e-01 4.3197019225395e-01 3.5221989005362e-01 2.5042646134249e-01 1.2805645334832e-01 -1.7725051738959e-02 -1.6665668291187e-01 -3.2007850380316e-01 -4.6596395819173e-01 -5.7198048706966e-01 -6.2769514638615e-01 -6.4397861695913e-01 -6.2816777689358e-01 -5.9611946567308e-01 -5.4781640124226e-01 -4.6297006305451e-01 -3.2679435677991e-01 -1.5675742068275e-01 4.9210525051530e-02 2.6391987909997e-01 4.2893044290604e-01 5.2833639202344e-01 5.9712226558592e-01 6.5986665880751e-01 6.9869912353068e-01 7.0485571147013e-01 6.8220764387266e-01 6.3643639723964e-01 5.7978999800420e-01 4.9950028249720e-01 3.7750785996046e-01 2.2525402805875e-01 5.0461518043145e-02 -1.4133773274265e-01 -3.0707786051091e-01 -4.3382850506589e-01 -5.3492414235269e-01 -5.9837478291401e-01 -6.2781273117507e-01 -6.3681869904758e-01 -6.3751158037808e-01 -6.3752287493572e-01 -6.3752277125928e-01 -6.3752276848299e-01 -6.3752276867584e-01 -6.3752276867031e-01 6.7395264116576e-01 6.6401255134313e-01 6.4316528296878e-01 6.0714759924104e-01 5.5251867887091e-01 4.7053074950328e-01 3.5413967167173e-01 1.9257203080729e-01 1.1564488846561e-02 -1.6265577711577e-01 -3.0047741281199e-01 -4.0370225872897e-01 -5.0237375556380e-01 -5.8188710672280e-01 -6.2224152003617e-01 -6.2214461932399e-01 -5.9634185409720e-01 -5.5116735105651e-01 -4.6442188525192e-01 -3.1482452098618e-01 -1.1872255243774e-01 6.9711401240501e-02 2.3150390738104e-01 3.7944549444327e-01 5.0175051090014e-01 5.8032642470120e-01 6.1544864230696e-01 6.2726089977972e-01 6.2555786579368e-01 6.0719280922585e-01 5.7926169598354e-01 5.3674017257404e-01 4.7292723134768e-01 3.9566911525880e-01 3.0185859790618e-01 1.9530383905608e-01 8.9618173952487e-02 -2.6151791528528e-02 -1.5375987146413e-01 -2.7635357179749e-01 -3.8425551279723e-01 -4.8786509222858e-01 -5.6952964654653e-01 -6.0632299481757e-01 -6.1192723547155e-01 -6.1202281753150e-01 -6.1202199529622e-01 -6.1202185956538e-01 -6.1202185770501e-01 -6.1202185792350e-01 6.0837887067395e-01 6.0852729712587e-01 6.0080250835041e-01 5.7284598052105e-01 5.0846431394301e-01 4.0324785490367e-01 2.7888425859812e-01 1.2452240028552e-01 -6.1876911818130e-02 -2.3961158628634e-01 -3.9182437303623e-01 -5.1705255170864e-01 -6.0099078670474e-01 -6.3845394676237e-01 -6.4729447551110e-01 -6.4082458424692e-01 -6.1773938138973e-01 -5.6476987464479e-01 -4.5330181124473e-01 -2.7306252410341e-01 -7.6387017659800e-02 9.8417676211112e-02 2.5308966223498e-01 3.7945861567452e-01 4.8546275890603e-01 5.7268733037595e-01 6.2907261076659e-01 6.4933771550415e-01 6.3339942267990e-01 5.9772078536676e-01 5.5408583524231e-01 5.0143465921394e-01 4.2856261859247e-01 3.3165685245591e-01 2.2834937642204e-01 1.2710509591581e-01 2.4427496927127e-02 -6.7787664035590e-02 -1.4527447925490e-01 -2.1812004641627e-01 -3.0061468328496e-01 -3.7875323596412e-01 -4.3635728475533e-01 -4.8128605843137e-01 -5.1768001391691e-01 -5.4222645798811e-01 -5.5281174923630e-01 -5.5371764154236e-01 -5.5373327516347e-01 -5.5373406193078e-01 6.9945355191257e-01 6.9940630858812e-01 6.9851412459747e-01 6.8740312393311e-01 6.5393146580043e-01 5.8734679687007e-01 4.9319631069989e-01 3.7561906774192e-01 2.1717091792961e-01 1.7473960697306e-02 -1.8636902540290e-01 -3.6649406986192e-01 -5.2003772987115e-01 -6.3378966544910e-01 -7.0651361656126e-01 -7.4784828403187e-01 -7.4733253736928e-01 -7.1854657207535e-01 -6.7195652863065e-01 -6.0898387873813e-01 -4.9595574668218e-01 -3.0650336019800e-01 -7.4353462192837e-02 1.2812961821809e-01 2.7320268890963e-01 3.6903909549958e-01 4.5243046294483e-01 5.3042054272781e-01 5.8678347511779e-01 6.1735611866542e-01 6.1407767400182e-01 5.8304162657744e-01 5.3861426408921e-01 4.7750176660912e-01 4.0348320185633e-01 3.1450412355723e-01 1.9726615866481e-01 6.1067849754903e-02 -7.3464133160384e-02 -2.0686604540187e-01 -3.4165319286943e-01 -4.3556209089713e-01 -4.7400230057681e-01 -4.9483048220526e-01 -5.1760210026057e-01 -5.3418968483096e-01 -5.3906963796025e-01 -5.3915746070838e-01 -5.3916173146664e-01 -5.3916211293260e-01 + 8.1010452961672e-01 8.1010214846579e-01 8.1019679465723e-01 8.1234461715614e-01 8.1952949943874e-01 8.2915738418924e-01 8.3857753734010e-01 8.4235543739443e-01 8.3224600126555e-01 8.0866517662024e-01 7.7491450859197e-01 7.2506262816834e-01 6.5321024048052e-01 5.7157361598529e-01 4.7458299090816e-01 3.6794686766713e-01 2.6760108959077e-01 2.0009585481617e-01 1.7291884874092e-01 1.6299981629707e-01 1.5584317237269e-01 1.4628047010862e-01 1.2434855577362e-01 8.2820448352597e-02 2.2704875713680e-02 -4.6675211651312e-02 -1.1677728832207e-01 -1.8061551454713e-01 -2.4527149522441e-01 -3.3110841399999e-01 -4.3266101080139e-01 -5.3899792063794e-01 -6.3541128895762e-01 -7.0709676551413e-01 -7.5239595071948e-01 -7.8031125965994e-01 -7.9532163373787e-01 -7.9596084143898e-01 -7.8282580303548e-01 -7.5802868465795e-01 -7.2969980526495e-01 -7.0904855629959e-01 -6.9996617583448e-01 -6.9856851317384e-01 -6.9860702339188e-01 -6.9860626532940e-01 -6.9860627161564e-01 -6.9860627178874e-01 -6.9860627177666e-01 -6.9860627177700e-01 8.5888501742160e-01 8.5754050018284e-01 8.5595995347500e-01 8.5540674924427e-01 8.5540051522128e-01 8.5539933604762e-01 8.5546845027697e-01 8.5292062556201e-01 8.4485797199471e-01 8.2618387330244e-01 8.0016030123263e-01 7.6276187546137e-01 7.0631293433304e-01 6.3657736640733e-01 5.5072558857361e-01 4.4459542347849e-01 3.4559765193173e-01 2.7450825489014e-01 2.1479651133763e-01 1.5509668999836e-01 1.0257372663294e-01 6.9783442288738e-02 4.6335433671791e-02 2.1907341985823e-02 -7.6138024323123e-03 -4.1858887121059e-02 -9.0645585504519e-02 -1.6629919105363e-01 -2.5610966632757e-01 -3.5167965278592e-01 -4.6505316404150e-01 -5.8687112887421e-01 -6.8675280757568e-01 -7.8242181441961e-01 -8.7770593284959e-01 -9.4401875822340e-01 -9.7024026655011e-01 -9.6150837428401e-01 -9.2477248377849e-01 -8.6325902153462e-01 -8.0538125967981e-01 -7.7010533225717e-01 -7.5029001617321e-01 -7.4129966123178e-01 -7.4042573872396e-01 -7.4041804406926e-01 -7.4041811666684e-01 -7.4041811859697e-01 -7.4041811846306e-01 -7.4041811846690e-01 8.3449477351916e-01 8.3480793246426e-01 8.3837230870346e-01 8.4397827406970e-01 8.4743435764178e-01 8.4989367804623e-01 8.5152091009534e-01 8.4648624680341e-01 8.2305540586409e-01 7.7618031137154e-01 7.1253385718003e-01 6.4145522942048e-01 5.5581130737179e-01 4.5754802619767e-01 3.4786997838634e-01 2.4783335998254e-01 1.8035082121747e-01 1.3890040236892e-01 1.1104901773820e-01 8.6987442288145e-02 6.4246784932103e-02 3.9374508080638e-02 1.0766818844576e-02 -2.5216918919886e-02 -6.7155306416007e-02 -1.0752176014114e-01 -1.4674005058540e-01 -2.0157544994620e-01 -2.9559100946438e-01 -3.9050694565378e-01 -4.5878882787014e-01 -5.3926088311003e-01 -6.2906655669696e-01 -7.1102654325191e-01 -7.8308574860429e-01 -8.3787160724388e-01 -8.7019699223764e-01 -8.9392134659878e-01 -8.9867323073498e-01 -8.8171309920999e-01 -8.5263752541609e-01 -8.1955408246325e-01 -7.8906558512704e-01 -7.7382780974416e-01 -7.7176755822117e-01 -7.7177714956741e-01 -7.7177702336052e-01 -7.7177700372164e-01 -7.7177700345275e-01 -7.7177700348432e-01 8.3797909407665e-01 8.3797899196134e-01 8.3797694606950e-01 8.3795518573836e-01 8.4002698488850e-01 8.4318689586541e-01 8.4434029246476e-01 8.3209478365454e-01 8.0101203573746e-01 7.4958952204571e-01 6.7209783136808e-01 5.7306801886348e-01 4.5646300954531e-01 3.3699728253777e-01 2.4999291750894e-01 2.0520810737853e-01 1.8034979610251e-01 1.5913188255148e-01 1.4012415880676e-01 1.2058494159890e-01 9.8300049109912e-02 6.6341211193970e-02 2.5189056502944e-02 -2.0054097002625e-02 -7.6555768394988e-02 -1.4845319172523e-01 -2.3690152414278e-01 -3.3957255787581e-01 -4.5591183750056e-01 -5.7658597210442e-01 -6.9174499865388e-01 -7.8824108200108e-01 -8.5818572101218e-01 -8.9881437833479e-01 -9.1814683742377e-01 -9.2237203590426e-01 -9.1440501698442e-01 -8.9447906220441e-01 -8.6885249927638e-01 -8.4622208119111e-01 -8.2339765172625e-01 -7.9779346106006e-01 -7.7476134888982e-01 -7.5505673582322e-01 -7.4020040391251e-01 -7.3063793934303e-01 -7.2692848285365e-01 -7.2648925473468e-01 -7.2648123934130e-01 -7.2648083623693e-01 9.1811846689895e-01 9.1810944666167e-01 9.1792158944942e-01 9.1524873980464e-01 9.1212609190350e-01 9.1118573181912e-01 9.1426829727710e-01 9.1237106397253e-01 8.9752824353353e-01 8.7239388913526e-01 8.3561151115338e-01 7.7552339019355e-01 6.9526777748312e-01 6.0161490601638e-01 4.7456272308106e-01 3.3343500858248e-01 2.2938240025041e-01 1.5094262362751e-01 9.1843010610436e-02 6.5449053243376e-02 5.9232364210385e-02 5.7387609932614e-02 5.1419550710084e-02 3.3638157541887e-02 4.0612504606123e-03 -3.2137021389212e-02 -8.4194161123700e-02 -1.5624716282982e-01 -2.4907049575699e-01 -3.6412690727722e-01 -4.8713408275855e-01 -6.0559652872151e-01 -7.0266395968712e-01 -7.6726568656064e-01 -8.0298510432966e-01 -8.3341812353784e-01 -8.6211384519681e-01 -8.7582908836071e-01 -8.7222255598257e-01 -8.5606077717314e-01 -8.3294512111874e-01 -8.1395795009057e-01 -8.0388818608321e-01 -7.9387573631770e-01 -7.8169121085815e-01 -7.7374190211600e-01 -7.7172996692828e-01 -7.7177245263348e-01 -7.7177662982749e-01 -7.7177700348432e-01 8.1010452961672e-01 8.1010214846579e-01 8.1019679465723e-01 8.1234461715614e-01 8.1952949943874e-01 8.2915738418924e-01 8.3857753734010e-01 8.4235543739443e-01 8.3224600126555e-01 8.0866517662024e-01 7.7491450859197e-01 7.2506262816834e-01 6.5321024048052e-01 5.7157361598529e-01 4.7458299090816e-01 3.6794686766713e-01 2.6760108959077e-01 2.0009585481617e-01 1.7291884874092e-01 1.6299981629707e-01 1.5584317237269e-01 1.4628047010862e-01 1.2434855577362e-01 8.2820448352597e-02 2.2704875713680e-02 -4.6675211651312e-02 -1.1677728832207e-01 -1.8061551454713e-01 -2.4527149522441e-01 -3.3110841399999e-01 -4.3266101080139e-01 -5.3899792063794e-01 -6.3541128895762e-01 -7.0709676551413e-01 -7.5239595071948e-01 -7.8031125965994e-01 -7.9532163373787e-01 -7.9596084143898e-01 -7.8282580303548e-01 -7.5802868465795e-01 -7.2969980526495e-01 -7.0904855629959e-01 -6.9996617583448e-01 -6.9856851317384e-01 -6.9860702339188e-01 -6.9860626532940e-01 -6.9860627161564e-01 -6.9860627178874e-01 -6.9860627177666e-01 -6.9860627177700e-01 8.5888501742160e-01 8.5754050018284e-01 8.5595995347500e-01 8.5540674924427e-01 8.5540051522128e-01 8.5539933604762e-01 8.5546845027697e-01 8.5292062556201e-01 8.4485797199471e-01 8.2618387330244e-01 8.0016030123263e-01 7.6276187546137e-01 7.0631293433304e-01 6.3657736640733e-01 5.5072558857361e-01 4.4459542347849e-01 3.4559765193173e-01 2.7450825489014e-01 2.1479651133763e-01 1.5509668999836e-01 1.0257372663294e-01 6.9783442288738e-02 4.6335433671791e-02 2.1907341985823e-02 -7.6138024323123e-03 -4.1858887121059e-02 -9.0645585504519e-02 -1.6629919105363e-01 -2.5610966632757e-01 -3.5167965278592e-01 -4.6505316404150e-01 -5.8687112887421e-01 -6.8675280757568e-01 -7.8242181441961e-01 -8.7770593284959e-01 -9.4401875822340e-01 -9.7024026655011e-01 -9.6150837428401e-01 -9.2477248377849e-01 -8.6325902153462e-01 -8.0538125967981e-01 -7.7010533225717e-01 -7.5029001617321e-01 -7.4129966123178e-01 -7.4042573872396e-01 -7.4041804406926e-01 -7.4041811666684e-01 -7.4041811859697e-01 -7.4041811846306e-01 -7.4041811846690e-01 8.3449477351916e-01 8.3480793246426e-01 8.3837230870346e-01 8.4397827406970e-01 8.4743435764178e-01 8.4989367804623e-01 8.5152091009534e-01 8.4648624680341e-01 8.2305540586409e-01 7.7618031137154e-01 7.1253385718003e-01 6.4145522942048e-01 5.5581130737179e-01 4.5754802619767e-01 3.4786997838634e-01 2.4783335998254e-01 1.8035082121747e-01 1.3890040236892e-01 1.1104901773820e-01 8.6987442288145e-02 6.4246784932103e-02 3.9374508080638e-02 1.0766818844576e-02 -2.5216918919886e-02 -6.7155306416007e-02 -1.0752176014114e-01 -1.4674005058540e-01 -2.0157544994620e-01 -2.9559100946438e-01 -3.9050694565378e-01 -4.5878882787014e-01 -5.3926088311003e-01 -6.2906655669696e-01 -7.1102654325191e-01 -7.8308574860429e-01 -8.3787160724388e-01 -8.7019699223764e-01 -8.9392134659878e-01 -8.9867323073498e-01 -8.8171309920999e-01 -8.5263752541609e-01 -8.1955408246325e-01 -7.8906558512704e-01 -7.7382780974416e-01 -7.7176755822117e-01 -7.7177714956741e-01 -7.7177702336052e-01 -7.7177700372164e-01 -7.7177700345275e-01 -7.7177700348432e-01 8.3797909407665e-01 8.3797899196134e-01 8.3797694606950e-01 8.3795518573836e-01 8.4002698488850e-01 8.4318689586541e-01 8.4434029246476e-01 8.3209478365454e-01 8.0101203573746e-01 7.4958952204571e-01 6.7209783136808e-01 5.7306801886348e-01 4.5646300954531e-01 3.3699728253777e-01 2.4999291750894e-01 2.0520810737853e-01 1.8034979610251e-01 1.5913188255148e-01 1.4012415880676e-01 1.2058494159890e-01 9.8300049109912e-02 6.6341211193970e-02 2.5189056502944e-02 -2.0054097002625e-02 -7.6555768394988e-02 -1.4845319172523e-01 -2.3690152414278e-01 -3.3957255787581e-01 -4.5591183750056e-01 -5.7658597210442e-01 -6.9174499865388e-01 -7.8824108200108e-01 -8.5818572101218e-01 -8.9881437833479e-01 -9.1814683742377e-01 -9.2237203590426e-01 -9.1440501698442e-01 -8.9447906220441e-01 -8.6885249927638e-01 -8.4622208119111e-01 -8.2339765172625e-01 -7.9779346106006e-01 -7.7476134888982e-01 -7.5505673582322e-01 -7.4020040391251e-01 -7.3063793934303e-01 -7.2692848285365e-01 -7.2648925473468e-01 -7.2648123934130e-01 -7.2648083623693e-01 9.1811846689895e-01 9.1810944666167e-01 9.1792158944942e-01 9.1524873980464e-01 9.1212609190350e-01 9.1118573181912e-01 9.1426829727710e-01 9.1237106397253e-01 8.9752824353353e-01 8.7239388913526e-01 8.3561151115338e-01 7.7552339019355e-01 6.9526777748312e-01 6.0161490601638e-01 4.7456272308106e-01 3.3343500858248e-01 2.2938240025041e-01 1.5094262362751e-01 9.1843010610436e-02 6.5449053243376e-02 5.9232364210385e-02 5.7387609932614e-02 5.1419550710084e-02 3.3638157541887e-02 4.0612504606123e-03 -3.2137021389212e-02 -8.4194161123700e-02 -1.5624716282982e-01 -2.4907049575699e-01 -3.6412690727722e-01 -4.8713408275855e-01 -6.0559652872151e-01 -7.0266395968712e-01 -7.6726568656064e-01 -8.0298510432966e-01 -8.3341812353784e-01 -8.6211384519681e-01 -8.7582908836071e-01 -8.7222255598257e-01 -8.5606077717314e-01 -8.3294512111874e-01 -8.1395795009057e-01 -8.0388818608321e-01 -7.9387573631770e-01 -7.8169121085815e-01 -7.7374190211600e-01 -7.7172996692828e-01 -7.7177245263348e-01 -7.7177662982749e-01 -7.7177700348432e-01 + 7.0202769182780e-01 5.9746473917355e-01 7.7266326881693e-01 5.8174841646049e-01 7.0037946302047e-01 5.9652331703886e-01 8.7383775151143e-01 7.5475226835878e-01 7.8734059153105e-01 6.9708246561812e-01 8.5833900519699e-01 6.2278412513353e-01 7.2290919913264e-01 6.5626872024566e-01 4.0440805787425e-01 4.0263637088070e-01 2.7707868851853e-01 4.1026225138347e-01 7.2636444347094e-02 3.8241252851942e-03 1.8629817545433e-01 4.8798503387464e-02 6.5113430793548e-02 1.1586913756659e-01 -1.0710238735260e-01 6.0511978895148e-02 -7.4371392665625e-02 -3.7394227658900e-02 -2.7400480182934e-01 -2.3378857200684e-01 -5.3117912096766e-01 -4.8919281367551e-01 -4.8116633342957e-01 -7.1445036315495e-01 -6.7465278521065e-01 -5.4003274481420e-01 -7.9253943885589e-01 -8.2557505536504e-01 -6.1192435899056e-01 -6.8983995462509e-01 -7.7671378963234e-01 -7.4048295336491e-01 -6.0956494020511e-01 -6.1863378028121e-01 -6.7830948900279e-01 -6.2024507845760e-01 -5.8670783664360e-01 -7.1624790992127e-01 -6.7512706725042e-01 -7.1571675912308e-01 8.9110354219047e-01 6.2836629408082e-01 9.1661057740182e-01 6.9786090206215e-01 7.5463052875560e-01 8.5058681717747e-01 8.2865644860402e-01 7.1906533029830e-01 8.3673456879682e-01 6.1737823386886e-01 8.5561524391085e-01 8.0696512153895e-01 6.5088447691577e-01 6.3483590039575e-01 6.2125638180506e-01 3.9731907283394e-01 3.9329977227101e-01 3.3979350019331e-01 2.5034372317673e-01 1.2422406070627e-02 6.8827303961439e-02 -1.2789747739700e-01 8.0177090842973e-03 -5.7080190735703e-02 -1.7217767074194e-02 -4.1059902966315e-03 -7.5200524677954e-03 -1.7985039961795e-01 -2.4930469637847e-01 -2.4314681165714e-01 -3.1879900759229e-01 -5.3199921696851e-01 -5.4790379656837e-01 -7.7798915552162e-01 -6.1071302240711e-01 -8.7619904387224e-01 -9.0177495761179e-01 -7.6624328773521e-01 -8.0501707047832e-01 -9.1861395258675e-01 -6.1334806132760e-01 -6.2669031248790e-01 -5.1708841369320e-01 -6.4576306688426e-01 -6.0410396894246e-01 -7.8974160381314e-01 -4.8865013643780e-01 -4.3745076366966e-01 -7.1272861683109e-01 -7.4407473909634e-01 8.4096834669244e-01 6.2763968343331e-01 7.5891664785587e-01 7.3381071864156e-01 8.3224765399808e-01 5.5432566371392e-01 7.6462709381699e-01 7.7514841058429e-01 5.5611734486197e-01 6.8467481069047e-01 7.1667082095504e-01 4.7078499687950e-01 4.9762867205981e-01 4.6143460003467e-01 2.8863774274512e-01 4.0262212755120e-01 2.5631824392710e-01 8.0578342520755e-02 1.4398320405547e-01 1.9975944048998e-01 8.9024511934712e-02 9.5056565370949e-02 7.5080680607705e-02 4.8700285885941e-02 -1.9937930078254e-01 -1.7499406149641e-01 -1.8150279030923e-01 -3.5995599849239e-01 -4.3149376353683e-01 -3.4489268728959e-01 -4.0697154988378e-01 -4.2104201112858e-01 -5.5183047973814e-01 -7.2929014544977e-01 -7.0704212487540e-01 -8.1487198201759e-01 -6.7774016304859e-01 -9.3062895124012e-01 -6.9655679320419e-01 -7.2201955400810e-01 -6.7570914757690e-01 -7.8870336675670e-01 -6.8998212408886e-01 -7.0298158666165e-01 -8.4848802874547e-01 -6.4893156737468e-01 -6.5315037460604e-01 -7.7172037310531e-01 -5.7340696104520e-01 -8.7392212685556e-01 7.0219330604279e-01 7.0420964076665e-01 6.7191962671725e-01 6.7688225686325e-01 7.9296582912996e-01 6.5938692438863e-01 7.5442112450597e-01 6.9683125842448e-01 7.0522457435320e-01 8.7457323757773e-01 5.6844318536931e-01 6.3076460376449e-01 4.4456287623051e-01 3.3380272651217e-01 5.7136078577362e-02 3.0584824122026e-01 1.9482606414569e-01 1.1505949111780e-01 1.4340879484848e-01 1.0939216494543e-01 2.8134412979729e-01 -4.4392056858263e-02 -3.0966918291792e-02 6.2278436386118e-03 1.0893535802362e-01 -1.2217489349114e-01 -1.2357813404402e-01 -2.5782215410531e-01 -3.6838663935558e-01 -4.1641114198524e-01 -4.0875907990070e-01 -6.9435566347452e-01 -7.8565962514613e-01 -7.6386794132916e-01 -8.2479573565493e-01 -1.0281708446926e+00 -8.0379472107082e-01 -7.6309918707194e-01 -8.0021837131313e-01 -7.7046905257549e-01 -6.0983581334903e-01 -7.0756502814397e-01 -7.0253534219480e-01 -7.5146458277977e-01 -7.3016027333026e-01 -6.7743519095102e-01 -6.5178499484871e-01 -6.2538849262405e-01 -5.0071917971855e-01 -5.2858664508475e-01 6.7474067807288e-01 9.7011374514063e-01 6.9579089183209e-01 1.0498353851147e+00 8.1073553350893e-01 7.4635814373039e-01 5.8998584932257e-01 7.5115867333433e-01 9.3600246041789e-01 7.2460434567956e-01 6.9662475040165e-01 5.6878890243241e-01 5.2319896705729e-01 5.0810595389878e-01 4.9295256245867e-01 1.2106232713606e-01 2.9411161121212e-01 1.0225877324866e-01 1.7214676136231e-01 6.4967764061402e-02 1.4928387596444e-02 1.0763249476537e-01 1.0191227130654e-01 2.3614391905125e-01 -1.2605902765824e-01 -1.0233455517345e-01 -2.0643938479917e-01 -2.1262463305061e-01 -2.9704264552098e-01 -4.0027636642451e-01 -5.1498793202036e-01 -6.2029135398480e-01 -6.6996609073820e-01 -6.5134612099690e-01 -6.0806156153945e-01 -7.7672972545352e-01 -5.7647711848897e-01 -6.8079893569215e-01 -6.4379332613142e-01 -8.5328664991038e-01 -9.2273450245550e-01 -6.9431605086358e-01 -6.8562674134959e-01 -8.8310206369452e-01 -8.5306808794175e-01 -6.6361049324642e-01 -5.9373111642749e-01 -5.6177196208831e-01 -7.8923589602617e-01 -6.3694764776195e-01 7.0202769182780e-01 5.9746473917355e-01 7.7266326881693e-01 5.8174841646049e-01 7.0037946302047e-01 5.9652331703886e-01 8.7383775151143e-01 7.5475226835878e-01 7.8734059153105e-01 6.9708246561812e-01 8.5833900519699e-01 6.2278412513353e-01 7.2290919913264e-01 6.5626872024566e-01 4.0440805787425e-01 4.0263637088070e-01 2.7707868851853e-01 4.1026225138347e-01 7.2636444347094e-02 3.8241252851942e-03 1.8629817545433e-01 4.8798503387464e-02 6.5113430793548e-02 1.1586913756659e-01 -1.0710238735260e-01 6.0511978895148e-02 -7.4371392665625e-02 -3.7394227658900e-02 -2.7400480182934e-01 -2.3378857200684e-01 -5.3117912096766e-01 -4.8919281367551e-01 -4.8116633342957e-01 -7.1445036315495e-01 -6.7465278521065e-01 -5.4003274481420e-01 -7.9253943885589e-01 -8.2557505536504e-01 -6.1192435899056e-01 -6.8983995462509e-01 -7.7671378963234e-01 -7.4048295336491e-01 -6.0956494020511e-01 -6.1863378028121e-01 -6.7830948900279e-01 -6.2024507845760e-01 -5.8670783664360e-01 -7.1624790992127e-01 -6.7512706725042e-01 -7.1571675912308e-01 8.9110354219047e-01 6.2836629408082e-01 9.1661057740182e-01 6.9786090206215e-01 7.5463052875560e-01 8.5058681717747e-01 8.2865644860402e-01 7.1906533029830e-01 8.3673456879682e-01 6.1737823386886e-01 8.5561524391085e-01 8.0696512153895e-01 6.5088447691577e-01 6.3483590039575e-01 6.2125638180506e-01 3.9731907283394e-01 3.9329977227101e-01 3.3979350019331e-01 2.5034372317673e-01 1.2422406070627e-02 6.8827303961439e-02 -1.2789747739700e-01 8.0177090842973e-03 -5.7080190735703e-02 -1.7217767074194e-02 -4.1059902966315e-03 -7.5200524677954e-03 -1.7985039961795e-01 -2.4930469637847e-01 -2.4314681165714e-01 -3.1879900759229e-01 -5.3199921696851e-01 -5.4790379656837e-01 -7.7798915552162e-01 -6.1071302240711e-01 -8.7619904387224e-01 -9.0177495761179e-01 -7.6624328773521e-01 -8.0501707047832e-01 -9.1861395258675e-01 -6.1334806132760e-01 -6.2669031248790e-01 -5.1708841369320e-01 -6.4576306688426e-01 -6.0410396894246e-01 -7.8974160381314e-01 -4.8865013643780e-01 -4.3745076366966e-01 -7.1272861683109e-01 -7.4407473909634e-01 8.4096834669244e-01 6.2763968343331e-01 7.5891664785587e-01 7.3381071864156e-01 8.3224765399808e-01 5.5432566371392e-01 7.6462709381699e-01 7.7514841058429e-01 5.5611734486197e-01 6.8467481069047e-01 7.1667082095504e-01 4.7078499687950e-01 4.9762867205981e-01 4.6143460003467e-01 2.8863774274512e-01 4.0262212755120e-01 2.5631824392710e-01 8.0578342520755e-02 1.4398320405547e-01 1.9975944048998e-01 8.9024511934712e-02 9.5056565370949e-02 7.5080680607705e-02 4.8700285885941e-02 -1.9937930078254e-01 -1.7499406149641e-01 -1.8150279030923e-01 -3.5995599849239e-01 -4.3149376353683e-01 -3.4489268728959e-01 -4.0697154988378e-01 -4.2104201112858e-01 -5.5183047973814e-01 -7.2929014544977e-01 -7.0704212487540e-01 -8.1487198201759e-01 -6.7774016304859e-01 -9.3062895124012e-01 -6.9655679320419e-01 -7.2201955400810e-01 -6.7570914757690e-01 -7.8870336675670e-01 -6.8998212408886e-01 -7.0298158666165e-01 -8.4848802874547e-01 -6.4893156737468e-01 -6.5315037460604e-01 -7.7172037310531e-01 -5.7340696104520e-01 -8.7392212685556e-01 7.0219330604279e-01 7.0420964076665e-01 6.7191962671725e-01 6.7688225686325e-01 7.9296582912996e-01 6.5938692438863e-01 7.5442112450597e-01 6.9683125842448e-01 7.0522457435320e-01 8.7457323757773e-01 5.6844318536931e-01 6.3076460376449e-01 4.4456287623051e-01 3.3380272651217e-01 5.7136078577362e-02 3.0584824122026e-01 1.9482606414569e-01 1.1505949111780e-01 1.4340879484848e-01 1.0939216494543e-01 2.8134412979729e-01 -4.4392056858263e-02 -3.0966918291792e-02 6.2278436386118e-03 1.0893535802362e-01 -1.2217489349114e-01 -1.2357813404402e-01 -2.5782215410531e-01 -3.6838663935558e-01 -4.1641114198524e-01 -4.0875907990070e-01 -6.9435566347452e-01 -7.8565962514613e-01 -7.6386794132916e-01 -8.2479573565493e-01 -1.0281708446926e+00 -8.0379472107082e-01 -7.6309918707194e-01 -8.0021837131313e-01 -7.7046905257549e-01 -6.0983581334903e-01 -7.0756502814397e-01 -7.0253534219480e-01 -7.5146458277977e-01 -7.3016027333026e-01 -6.7743519095102e-01 -6.5178499484871e-01 -6.2538849262405e-01 -5.0071917971855e-01 -5.2858664508475e-01 6.7474067807288e-01 9.7011374514063e-01 6.9579089183209e-01 1.0498353851147e+00 8.1073553350893e-01 7.4635814373039e-01 5.8998584932257e-01 7.5115867333433e-01 9.3600246041789e-01 7.2460434567956e-01 6.9662475040165e-01 5.6878890243241e-01 5.2319896705729e-01 5.0810595389878e-01 4.9295256245867e-01 1.2106232713606e-01 2.9411161121212e-01 1.0225877324866e-01 1.7214676136231e-01 6.4967764061402e-02 1.4928387596444e-02 1.0763249476537e-01 1.0191227130654e-01 2.3614391905125e-01 -1.2605902765824e-01 -1.0233455517345e-01 -2.0643938479917e-01 -2.1262463305061e-01 -2.9704264552098e-01 -4.0027636642451e-01 -5.1498793202036e-01 -6.2029135398480e-01 -6.6996609073820e-01 -6.5134612099690e-01 -6.0806156153945e-01 -7.7672972545352e-01 -5.7647711848897e-01 -6.8079893569215e-01 -6.4379332613142e-01 -8.5328664991038e-01 -9.2273450245550e-01 -6.9431605086358e-01 -6.8562674134959e-01 -8.8310206369452e-01 -8.5306808794175e-01 -6.6361049324642e-01 -5.9373111642749e-01 -5.6177196208831e-01 -7.8923589602617e-01 -6.3694764776195e-01 + 3.0983056043647e-01 3.4691144294567e-01 4.0287777586692e-01 4.1630666891131e-01 3.3986361238462e-01 4.9235625163171e-01 4.5821790429571e-01 4.5773764770066e-01 4.1489515351646e-01 5.0277392473788e-01 5.4908808471514e-01 4.3496787113496e-01 4.7968533721092e-01 2.8779124420017e-01 4.5766286568088e-01 3.8011055732190e-01 2.3247337178341e-01 3.2461523080044e-01 4.2499990860973e-01 4.0557183818222e-01 2.6763854627835e-01 3.8905536866218e-01 6.4051065544958e-01 5.2176513626425e-01 4.1576219348942e-01 5.7783530075210e-01 3.9133643448499e-01 3.8972650499880e-01 3.4624864647188e-01 4.1858760804130e-01 4.8290648545070e-01 4.4395279854217e-01 2.6700871561720e-01 4.3134187292093e-01 5.0423853743121e-01 3.8293386512699e-01 4.3223251225220e-01 5.3162996247880e-01 3.9755088772108e-01 3.6242554890588e-01 4.4209323041262e-01 3.4154565869513e-01 3.8577041148701e-01 2.8331282800452e-01 4.2948646449408e-01 3.8136659357787e-01 3.0646070309465e-01 3.6184018507132e-01 3.2195850888682e-01 2.4548306148193e-01 3.5001180658917e-01 3.8419640633867e-01 2.5739590462678e-01 3.8119710233452e-01 3.6100632267761e-01 4.2718951198694e-01 4.9659166934272e-01 4.9562420654252e-01 3.9274793593528e-01 5.0372991435831e-01 4.8518266720943e-01 4.3698235057802e-01 3.4393037400646e-01 3.7647593923584e-01 3.8576289963112e-01 4.2512311261680e-01 3.3445131589890e-01 5.4079924504554e-01 5.0480364112458e-01 3.9150862262285e-01 4.5857118201317e-01 6.3201634803347e-01 4.9340494383278e-01 4.7160231093863e-01 5.5670325162051e-01 4.3148769394239e-01 2.6329825783805e-01 4.0124859568665e-01 4.3864096364494e-01 3.2697244978874e-01 3.8439068475122e-01 3.8407310436155e-01 3.5038760966504e-01 3.9487349938143e-01 4.2789727141647e-01 4.6759429465230e-01 4.6689226972870e-01 4.7177291732041e-01 4.4037962596589e-01 2.9521833615160e-01 3.6411262406407e-01 3.8164836650899e-01 3.4934189661175e-01 3.2544590749180e-01 3.2346809872084e-01 3.2096935800554e-01 2.7400589875940e-01 3.5848312571783e-01 3.1883163309998e-01 3.7323251735209e-01 3.8325465487275e-01 3.3344549761253e-01 2.3683597923422e-01 3.4818710748753e-01 2.9840076726555e-01 3.5364918647529e-01 4.5382251553339e-01 3.4577863182449e-01 4.3088777962148e-01 4.2738369062974e-01 5.2302897272900e-01 4.9163088122756e-01 3.7915650857793e-01 3.0775868108901e-01 3.8302784666839e-01 2.4555574874739e-01 4.0511965259746e-01 3.5797670260382e-01 4.5100195235178e-01 4.0588415105627e-01 5.6148021939292e-01 5.4089218861983e-01 6.3702035801202e-01 4.5549105485166e-01 4.2952395619396e-01 3.6056387952799e-01 3.5964576242123e-01 4.3049404130997e-01 3.2949430705372e-01 1.8156924130603e-01 4.4188220608722e-01 3.4537983268841e-01 4.6452544667305e-01 4.9579502092834e-01 5.1514970482714e-01 4.3018614594373e-01 4.6367379657417e-01 4.1377613890185e-01 4.5941851789824e-01 4.8935868915468e-01 4.2466102560260e-01 3.9147564242496e-01 3.2641401663110e-01 4.0967529885908e-01 4.3604652496094e-01 3.1942444193928e-01 3.8635616052950e-01 3.7174030294368e-01 3.1408980986948e-01 3.4439215941564e-01 3.2304751742049e-01 2.6656962373083e-01 2.7691232759377e-01 3.4752049103048e-01 4.0095412386836e-01 4.6930009299907e-01 4.2748992206364e-01 3.2912775077959e-01 4.2280119758881e-01 4.6231675149878e-01 5.1610720215697e-01 4.9415373464692e-01 4.2425109382733e-01 6.0618377261622e-01 3.3807020254248e-01 2.7485506557416e-01 3.7645014332476e-01 4.3517713645758e-01 3.4232174503987e-01 5.4386620412882e-01 5.8536443820036e-01 4.5641210611557e-01 5.1304809868253e-01 5.3142391974846e-01 3.7239517449422e-01 4.4335225618651e-01 2.6062274701684e-01 4.1294668276992e-01 4.1262909609664e-01 4.2100107459801e-01 3.6438971967707e-01 3.1210146678584e-01 3.7921283715232e-01 3.7501399112727e-01 3.6540029497749e-01 4.5103640280643e-01 4.0395472804319e-01 4.6535865726687e-01 3.3602880889436e-01 4.4221162504475e-01 4.7426630685306e-01 4.2475525733655e-01 4.5686948564903e-01 4.8487921848514e-01 3.7251827198704e-01 3.7102857254767e-01 3.4134701051218e-01 4.2782885341744e-01 4.2570319008726e-01 4.0859999966596e-01 3.0530037057792e-01 1.2126497523213e-01 2.4683863605064e-01 2.9870962468533e-01 2.6825198363718e-01 2.5767250391311e-01 3.2426647305928e-01 3.5132863702063e-01 4.1592454277083e-01 5.3873915367259e-01 5.0411097518633e-01 3.7473650587300e-01 4.1208164101921e-01 3.4429521922714e-01 2.9460148325705e-01 3.8549924510976e-01 3.0234011289638e-01 3.6531006341524e-01 4.6590831906951e-01 3.5813211244541e-01 5.0498471749094e-01 5.4195426664404e-01 6.4523250784177e-01 5.8295545240424e-01 4.7211354272638e-01 3.4879968770068e-01 5.4366807764669e-01 3.9722289995267e-01 3.5856551892925e-01 3.0382010480724e-01 2.8843205503208e-01 4.5237174765492e-01 3.8751545346271e-01 3.2878443145756e-01 3.9023281031060e-01 3.5715785090411e-01 3.8622675039542e-01 3.2541557839343e-01 5.7786539012143e-01 4.7279587697419e-01 4.5010041257354e-01 4.7866327867498e-01 4.2429722355300e-01 3.0632021558081e-01 3.8142967714589e-01 3.2298977123976e-01 2.7830988934799e-01 3.9397806011663e-01 4.0039888405598e-01 4.4610868095658e-01 5.9744990892532e-01 5.9393810913168e-01 5.8222132135379e-01 5.5641252843967e-01 5.0412101982355e-01 4.1266634288246e-01 2.9501380664681e-01 1.6780039045575e-01 3.7639347443367e-02 -8.6854969709723e-02 -2.1856896570632e-01 -3.4199928687549e-01 -4.4469818627839e-01 -5.2045944508814e-01 -5.7483149530775e-01 -5.9688695450368e-01 -5.8992817456697e-01 -5.6552297481086e-01 -5.3299382591938e-01 -4.8245048465787e-01 -3.9619427944114e-01 -2.7345853708359e-01 -1.1241115561826e-01 8.4027961150802e-02 2.8274429088599e-01 4.4110241555378e-01 5.5466540834447e-01 6.1886346745589e-01 6.5089515603163e-01 6.6253155863142e-01 6.5197523157153e-01 6.1592762121320e-01 5.5034748695497e-01 4.5475589908160e-01 3.4232054300326e-01 2.0764362369675e-01 5.7141629142848e-02 -1.0446032984505e-01 -2.6603130114801e-01 -4.0529003029011e-01 -5.0969132865613e-01 -5.7462059882847e-01 -6.0034586970168e-01 -6.0489596905769e-01 -6.1056356762659e-01 -6.1462363537227e-01 -6.1567009418296e-01 -6.1566441194994e-01 -6.1566485789486e-01 -6.1566484517304e-01 6.0109289617486e-01 5.9326524312049e-01 5.7076348981756e-01 5.3406962852304e-01 4.8864947757756e-01 4.3197019225395e-01 3.5221989005362e-01 2.5042646134249e-01 1.2805645334832e-01 -1.7725051738959e-02 -1.6665668291187e-01 -3.2007850380316e-01 -4.6596395819173e-01 -5.7198048706966e-01 -6.2769514638615e-01 -6.4397861695913e-01 -6.2816777689358e-01 -5.9611946567308e-01 -5.4781640124226e-01 -4.6297006305451e-01 -3.2679435677991e-01 -1.5675742068275e-01 4.9210525051530e-02 2.6391987909997e-01 4.2893044290604e-01 5.2833639202344e-01 5.9712226558592e-01 6.5986665880751e-01 6.9869912353068e-01 7.0485571147013e-01 6.8220764387266e-01 6.3643639723964e-01 5.7978999800420e-01 4.9950028249720e-01 3.7750785996046e-01 2.2525402805875e-01 5.0461518043145e-02 -1.4133773274265e-01 -3.0707786051091e-01 -4.3382850506589e-01 -5.3492414235269e-01 -5.9837478291401e-01 -6.2781273117507e-01 -6.3681869904758e-01 -6.3751158037808e-01 -6.3752287493572e-01 -6.3752277125928e-01 -6.3752276848299e-01 -6.3752276867584e-01 -6.3752276867031e-01 6.7395264116576e-01 6.6401255134313e-01 6.4316528296878e-01 6.0714759924104e-01 5.5251867887091e-01 4.7053074950328e-01 3.5413967167173e-01 1.9257203080729e-01 1.1564488846561e-02 -1.6265577711577e-01 -3.0047741281199e-01 -4.0370225872897e-01 -5.0237375556380e-01 -5.8188710672280e-01 -6.2224152003617e-01 -6.2214461932399e-01 -5.9634185409720e-01 -5.5116735105651e-01 -4.6442188525192e-01 -3.1482452098618e-01 -1.1872255243774e-01 6.9711401240501e-02 2.3150390738104e-01 3.7944549444327e-01 5.0175051090014e-01 5.8032642470120e-01 6.1544864230696e-01 6.2726089977972e-01 6.2555786579368e-01 6.0719280922585e-01 5.7926169598354e-01 5.3674017257404e-01 4.7292723134768e-01 3.9566911525880e-01 3.0185859790618e-01 1.9530383905608e-01 8.9618173952487e-02 -2.6151791528528e-02 -1.5375987146413e-01 -2.7635357179749e-01 -3.8425551279723e-01 -4.8786509222858e-01 -5.6952964654653e-01 -6.0632299481757e-01 -6.1192723547155e-01 -6.1202281753150e-01 -6.1202199529622e-01 -6.1202185956538e-01 -6.1202185770501e-01 -6.1202185792350e-01 6.0837887067395e-01 6.0852729712587e-01 6.0080250835041e-01 5.7284598052105e-01 5.0846431394301e-01 4.0324785490367e-01 2.7888425859812e-01 1.2452240028552e-01 -6.1876911818130e-02 -2.3961158628634e-01 -3.9182437303623e-01 -5.1705255170864e-01 -6.0099078670474e-01 -6.3845394676237e-01 -6.4729447551110e-01 -6.4082458424692e-01 -6.1773938138973e-01 -5.6476987464479e-01 -4.5330181124473e-01 -2.7306252410341e-01 -7.6387017659800e-02 9.8417676211112e-02 2.5308966223498e-01 3.7945861567452e-01 4.8546275890603e-01 5.7268733037595e-01 6.2907261076659e-01 6.4933771550415e-01 6.3339942267990e-01 5.9772078536676e-01 5.5408583524231e-01 5.0143465921394e-01 4.2856261859247e-01 3.3165685245591e-01 2.2834937642204e-01 1.2710509591581e-01 2.4427496927127e-02 -6.7787664035590e-02 -1.4527447925490e-01 -2.1812004641627e-01 -3.0061468328496e-01 -3.7875323596412e-01 -4.3635728475533e-01 -4.8128605843137e-01 -5.1768001391691e-01 -5.4222645798811e-01 -5.5281174923630e-01 -5.5371764154236e-01 -5.5373327516347e-01 -5.5373406193078e-01 6.9945355191257e-01 6.9940630858812e-01 6.9851412459747e-01 6.8740312393311e-01 6.5393146580043e-01 5.8734679687007e-01 4.9319631069989e-01 3.7561906774192e-01 2.1717091792961e-01 1.7473960697306e-02 -1.8636902540290e-01 -3.6649406986192e-01 -5.2003772987115e-01 -6.3378966544910e-01 -7.0651361656126e-01 -7.4784828403187e-01 -7.4733253736928e-01 -7.1854657207535e-01 -6.7195652863065e-01 -6.0898387873813e-01 -4.9595574668218e-01 -3.0650336019800e-01 -7.4353462192837e-02 1.2812961821809e-01 2.7320268890963e-01 3.6903909549958e-01 4.5243046294483e-01 5.3042054272781e-01 5.8678347511779e-01 6.1735611866542e-01 6.1407767400182e-01 5.8304162657744e-01 5.3861426408921e-01 4.7750176660912e-01 4.0348320185633e-01 3.1450412355723e-01 1.9726615866481e-01 6.1067849754903e-02 -7.3464133160384e-02 -2.0686604540187e-01 -3.4165319286943e-01 -4.3556209089713e-01 -4.7400230057681e-01 -4.9483048220526e-01 -5.1760210026057e-01 -5.3418968483096e-01 -5.3906963796025e-01 -5.3915746070838e-01 -5.3916173146664e-01 -5.3916211293260e-01 + 4.5234816983289e-01 4.5790711324066e-01 4.6091430437542e-01 4.4322436709569e-01 3.8733955090672e-01 3.4013418089810e-01 2.3951254189438e-01 1.3620263381605e-01 2.9963097163891e-02 -7.1915329192779e-02 -1.8460618824376e-01 -2.7476231545641e-01 -3.6449896289149e-01 -3.8974866360524e-01 -4.6657186982763e-01 -4.6751999914124e-01 -4.2940871034134e-01 -4.3130255616567e-01 -4.2626591737324e-01 -3.8240833045437e-01 -2.9367958004669e-01 -2.1509221710858e-01 -9.8587008636084e-02 7.0148661818584e-02 2.2517065071925e-01 3.7708051487769e-01 4.3674502469133e-01 4.8692778015523e-01 5.0165880770878e-01 5.2830974533374e-01 5.3515444916933e-01 4.9685494966679e-01 4.0781477997491e-01 3.6474881501490e-01 2.8361975704990e-01 1.6285607525880e-01 4.5850523047334e-02 -8.7575848129204e-02 -2.1008219674565e-01 -3.1479863669739e-01 -4.1081105344876e-01 -4.4186734366732e-01 -4.7148268793585e-01 -4.5195907872911e-01 -4.8930447828258e-01 -4.8169740957190e-01 -4.6536571257827e-01 -4.7806802625336e-01 -4.6893285841288e-01 -4.5119126718640e-01 4.6411562934504e-01 4.6557757742319e-01 4.2086595385818e-01 4.1853162040167e-01 3.7928899858043e-01 3.4581738917752e-01 2.9085051906060e-01 2.0670574650945e-01 1.0089854780712e-01 -1.4682329319989e-02 -1.3693235942518e-01 -2.5738649936820e-01 -3.5872674537025e-01 -4.4724403196948e-01 -4.9295975225500e-01 -5.1505588013954e-01 -4.8138422279980e-01 -5.0172325382323e-01 -4.5398891653501e-01 -3.6457322125132e-01 -2.6535613853518e-01 -1.3701097464772e-01 4.0579685694575e-02 2.1555046622273e-01 3.6344664334942e-01 4.2379411154895e-01 4.4163720304851e-01 5.2198703750551e-01 5.6227162663198e-01 5.3818655791273e-01 5.3542590576955e-01 4.9942812190488e-01 4.4774816760584e-01 3.9395825362342e-01 3.0231479187323e-01 1.8364363240992e-01 4.1127084631398e-02 -1.1544306985912e-01 -2.4731279326090e-01 -3.2608660196693e-01 -4.1582287081536e-01 -4.6902495348093e-01 -4.8459031668836e-01 -4.8587457853549e-01 -4.8593236074705e-01 -4.8534578520390e-01 -4.7409861977977e-01 -4.9424797856257e-01 -4.8483625683369e-01 -4.9772892874707e-01 5.2866464102876e-01 5.0860426444794e-01 4.6922912383793e-01 4.6837902377474e-01 4.1596051898622e-01 3.6394147358857e-01 2.8694905552934e-01 1.4838573364359e-01 9.2736809724139e-03 -1.3022700527510e-01 -2.5098248460033e-01 -3.3263992338117e-01 -3.9331429765907e-01 -4.4011332784173e-01 -4.8804913612557e-01 -4.5595717073162e-01 -4.7258387356841e-01 -4.2719630261528e-01 -3.7583092542063e-01 -2.4957781477862e-01 -1.0079975902582e-01 5.8674838378121e-02 2.0274964244717e-01 3.0768387515362e-01 4.0210877706498e-01 4.5035335735916e-01 4.7739998279480e-01 5.0291664235929e-01 4.7822802086998e-01 4.3012100518230e-01 4.6684018384225e-01 4.1350376580976e-01 3.8503836354712e-01 3.2661559369053e-01 2.5128161046563e-01 1.5656606112270e-01 7.2935812583356e-02 -2.0807611248013e-02 -1.2489994406608e-01 -2.2748118312708e-01 -3.0726367256445e-01 -3.8417128723159e-01 -4.3474078228319e-01 -4.8150755797704e-01 -4.9186343995652e-01 -4.6557918222324e-01 -4.8078471378757e-01 -4.7748215181058e-01 -4.6435716271321e-01 -4.7127589747673e-01 4.6363086939400e-01 4.5082572837645e-01 4.4745048380937e-01 4.4177542404702e-01 4.0216529315958e-01 3.2900677199992e-01 2.2329378205667e-01 9.5178163937737e-02 -4.9436761081647e-02 -1.9488999050745e-01 -3.2630832885431e-01 -4.2650850841974e-01 -4.8048238360410e-01 -5.5220712640462e-01 -4.9691417892324e-01 -4.7675950158431e-01 -4.8301802442331e-01 -4.5377940862265e-01 -3.4870744124824e-01 -2.3012238281119e-01 -6.5504491539657e-02 7.9837653074212e-02 2.1049272268881e-01 3.1809666306761e-01 3.7886185825898e-01 4.6184863754676e-01 4.6463068968575e-01 5.1644655511313e-01 5.0369637717961e-01 4.7715716066166e-01 4.3077505436870e-01 3.8007848368166e-01 3.3553560596835e-01 2.5915060778624e-01 1.7761608795818e-01 1.0286071228731e-01 1.9347641696606e-02 -5.5210494594336e-02 -1.1141367123997e-01 -1.7581410442387e-01 -2.4581032529664e-01 -3.0287692220872e-01 -3.5405105573466e-01 -3.9539269512833e-01 -4.0402820845309e-01 -4.2288705195174e-01 -4.2505608036736e-01 -4.4341276818608e-01 -4.4299488967992e-01 -4.3952590304930e-01 5.2839069038115e-01 4.7904319810119e-01 5.1226736519229e-01 5.1758723366737e-01 4.8487932475205e-01 4.3315562336557e-01 3.7607756482405e-01 2.9020654723155e-01 1.7296253745291e-01 1.4694053489328e-02 -1.5440208522658e-01 -2.8633419607555e-01 -4.1344368857904e-01 -4.8801494021992e-01 -5.3088618913747e-01 -5.8724920246530e-01 -5.6373020569339e-01 -5.5888022039327e-01 -5.4741727780349e-01 -4.7204356864440e-01 -4.1104306853730e-01 -2.5809487713432e-01 -6.5333025389343e-02 1.0976593358581e-01 2.2318261386006e-01 2.8477616840248e-01 3.8125195516360e-01 4.1880368751730e-01 4.5492959368977e-01 4.6602878518085e-01 4.6000326841670e-01 4.7211393003264e-01 4.2334812315946e-01 3.6491527083710e-01 3.1753974876673e-01 2.4366893534389e-01 1.5495651268180e-01 4.6592343207383e-02 -6.2802285441139e-02 -1.6904255789335e-01 -2.7636891264085e-01 -3.5684937936573e-01 -3.7896514844607e-01 -3.7400077747524e-01 -4.0567101894990e-01 -4.0708155620888e-01 -4.0175889457052e-01 -4.2505838062976e-01 -4.2633510466779e-01 -4.3535345394308e-01 8.1010452961672e-01 8.1010214846579e-01 8.1019679465723e-01 8.1234461715614e-01 8.1952949943874e-01 8.2915738418924e-01 8.3857753734010e-01 8.4235543739443e-01 8.3224600126555e-01 8.0866517662024e-01 7.7491450859197e-01 7.2506262816834e-01 6.5321024048052e-01 5.7157361598529e-01 4.7458299090816e-01 3.6794686766713e-01 2.6760108959077e-01 2.0009585481617e-01 1.7291884874092e-01 1.6299981629707e-01 1.5584317237269e-01 1.4628047010862e-01 1.2434855577362e-01 8.2820448352597e-02 2.2704875713680e-02 -4.6675211651312e-02 -1.1677728832207e-01 -1.8061551454713e-01 -2.4527149522441e-01 -3.3110841399999e-01 -4.3266101080139e-01 -5.3899792063794e-01 -6.3541128895762e-01 -7.0709676551413e-01 -7.5239595071948e-01 -7.8031125965994e-01 -7.9532163373787e-01 -7.9596084143898e-01 -7.8282580303548e-01 -7.5802868465795e-01 -7.2969980526495e-01 -7.0904855629959e-01 -6.9996617583448e-01 -6.9856851317384e-01 -6.9860702339188e-01 -6.9860626532940e-01 -6.9860627161564e-01 -6.9860627178874e-01 -6.9860627177666e-01 -6.9860627177700e-01 8.5888501742160e-01 8.5754050018284e-01 8.5595995347500e-01 8.5540674924427e-01 8.5540051522128e-01 8.5539933604762e-01 8.5546845027697e-01 8.5292062556201e-01 8.4485797199471e-01 8.2618387330244e-01 8.0016030123263e-01 7.6276187546137e-01 7.0631293433304e-01 6.3657736640733e-01 5.5072558857361e-01 4.4459542347849e-01 3.4559765193173e-01 2.7450825489014e-01 2.1479651133763e-01 1.5509668999836e-01 1.0257372663294e-01 6.9783442288738e-02 4.6335433671791e-02 2.1907341985823e-02 -7.6138024323123e-03 -4.1858887121059e-02 -9.0645585504519e-02 -1.6629919105363e-01 -2.5610966632757e-01 -3.5167965278592e-01 -4.6505316404150e-01 -5.8687112887421e-01 -6.8675280757568e-01 -7.8242181441961e-01 -8.7770593284959e-01 -9.4401875822340e-01 -9.7024026655011e-01 -9.6150837428401e-01 -9.2477248377849e-01 -8.6325902153462e-01 -8.0538125967981e-01 -7.7010533225717e-01 -7.5029001617321e-01 -7.4129966123178e-01 -7.4042573872396e-01 -7.4041804406926e-01 -7.4041811666684e-01 -7.4041811859697e-01 -7.4041811846306e-01 -7.4041811846690e-01 8.3449477351916e-01 8.3480793246426e-01 8.3837230870346e-01 8.4397827406970e-01 8.4743435764178e-01 8.4989367804623e-01 8.5152091009534e-01 8.4648624680341e-01 8.2305540586409e-01 7.7618031137154e-01 7.1253385718003e-01 6.4145522942048e-01 5.5581130737179e-01 4.5754802619767e-01 3.4786997838634e-01 2.4783335998254e-01 1.8035082121747e-01 1.3890040236892e-01 1.1104901773820e-01 8.6987442288145e-02 6.4246784932103e-02 3.9374508080638e-02 1.0766818844576e-02 -2.5216918919886e-02 -6.7155306416007e-02 -1.0752176014114e-01 -1.4674005058540e-01 -2.0157544994620e-01 -2.9559100946438e-01 -3.9050694565378e-01 -4.5878882787014e-01 -5.3926088311003e-01 -6.2906655669696e-01 -7.1102654325191e-01 -7.8308574860429e-01 -8.3787160724388e-01 -8.7019699223764e-01 -8.9392134659878e-01 -8.9867323073498e-01 -8.8171309920999e-01 -8.5263752541609e-01 -8.1955408246325e-01 -7.8906558512704e-01 -7.7382780974416e-01 -7.7176755822117e-01 -7.7177714956741e-01 -7.7177702336052e-01 -7.7177700372164e-01 -7.7177700345275e-01 -7.7177700348432e-01 8.3797909407665e-01 8.3797899196134e-01 8.3797694606950e-01 8.3795518573836e-01 8.4002698488850e-01 8.4318689586541e-01 8.4434029246476e-01 8.3209478365454e-01 8.0101203573746e-01 7.4958952204571e-01 6.7209783136808e-01 5.7306801886348e-01 4.5646300954531e-01 3.3699728253777e-01 2.4999291750894e-01 2.0520810737853e-01 1.8034979610251e-01 1.5913188255148e-01 1.4012415880676e-01 1.2058494159890e-01 9.8300049109912e-02 6.6341211193970e-02 2.5189056502944e-02 -2.0054097002625e-02 -7.6555768394988e-02 -1.4845319172523e-01 -2.3690152414278e-01 -3.3957255787581e-01 -4.5591183750056e-01 -5.7658597210442e-01 -6.9174499865388e-01 -7.8824108200108e-01 -8.5818572101218e-01 -8.9881437833479e-01 -9.1814683742377e-01 -9.2237203590426e-01 -9.1440501698442e-01 -8.9447906220441e-01 -8.6885249927638e-01 -8.4622208119111e-01 -8.2339765172625e-01 -7.9779346106006e-01 -7.7476134888982e-01 -7.5505673582322e-01 -7.4020040391251e-01 -7.3063793934303e-01 -7.2692848285365e-01 -7.2648925473468e-01 -7.2648123934130e-01 -7.2648083623693e-01 9.1811846689895e-01 9.1810944666167e-01 9.1792158944942e-01 9.1524873980464e-01 9.1212609190350e-01 9.1118573181912e-01 9.1426829727710e-01 9.1237106397253e-01 8.9752824353353e-01 8.7239388913526e-01 8.3561151115338e-01 7.7552339019355e-01 6.9526777748312e-01 6.0161490601638e-01 4.7456272308106e-01 3.3343500858248e-01 2.2938240025041e-01 1.5094262362751e-01 9.1843010610436e-02 6.5449053243376e-02 5.9232364210385e-02 5.7387609932614e-02 5.1419550710084e-02 3.3638157541887e-02 4.0612504606123e-03 -3.2137021389212e-02 -8.4194161123700e-02 -1.5624716282982e-01 -2.4907049575699e-01 -3.6412690727722e-01 -4.8713408275855e-01 -6.0559652872151e-01 -7.0266395968712e-01 -7.6726568656064e-01 -8.0298510432966e-01 -8.3341812353784e-01 -8.6211384519681e-01 -8.7582908836071e-01 -8.7222255598257e-01 -8.5606077717314e-01 -8.3294512111874e-01 -8.1395795009057e-01 -8.0388818608321e-01 -7.9387573631770e-01 -7.8169121085815e-01 -7.7374190211600e-01 -7.7172996692828e-01 -7.7177245263348e-01 -7.7177662982749e-01 -7.7177700348432e-01 + 6.1335569036176e-01 6.2456261103762e-01 6.4139061611198e-01 6.4709349699997e-01 6.2968250833604e-01 6.8342081337887e-01 6.8081504329156e-01 6.8373517410050e-01 6.6251594392543e-01 6.6956931281816e-01 6.5450286221404e-01 5.8251550284363e-01 5.3540685020063e-01 4.2802576662733e-01 3.8520344703427e-01 2.8819949566296e-01 1.9478682951777e-01 1.5260538917846e-01 1.3829318109367e-01 1.2919976162680e-01 1.1551897589262e-01 1.1505872506635e-01 1.0905636610987e-01 6.9140599671617e-02 1.8081608731794e-02 -3.9900740102285e-02 -9.1950748873696e-02 -1.4211003910373e-01 -1.8903598332086e-01 -2.6402938788235e-01 -3.5513690352064e-01 -4.3479749162989e-01 -4.7084818435998e-01 -5.6714538028647e-01 -6.2337584205794e-01 -6.1200255979955e-01 -6.3816718992350e-01 -6.6730543422607e-01 -6.1818952755253e-01 -5.8877933991376e-01 -5.8813781763295e-01 -5.4523872402419e-01 -5.4971967111328e-01 -5.2194823208204e-01 -5.5986233576644e-01 -5.4751690132457e-01 -5.2805456765527e-01 -5.4247300152443e-01 -5.3210676511496e-01 -5.1197506484042e-01 6.6316198865822e-01 6.7297323287875e-01 6.3116230927597e-01 6.7035224199851e-01 6.6396060917094e-01 6.8479716980626e-01 7.0641508281984e-01 7.0401344041272e-01 6.6568251930005e-01 6.8435928342194e-01 6.5744641049939e-01 6.1336392992282e-01 5.4376167017180e-01 4.9775374238921e-01 4.3251178739675e-01 3.5558865017449e-01 2.6484207435680e-01 2.3103955293475e-01 1.7800714844706e-01 1.2213338267503e-01 8.3289590073343e-02 6.0992949492344e-02 3.8208845220697e-02 1.7892315633246e-02 -6.4514211637708e-03 -3.3576240716558e-02 -6.7042321410722e-02 -1.3155085337168e-01 -2.0610187394325e-01 -2.6852199498538e-01 -3.6499372855809e-01 -4.6053297228926e-01 -5.3035118275351e-01 -6.1709981436765e-01 -7.0288201798796e-01 -7.6963344592458e-01 -7.9076403371534e-01 -7.8534922181543e-01 -7.4478852273347e-01 -6.4886746182518e-01 -6.2606250304579e-01 -6.0363275316907e-01 -5.7912695695892e-01 -5.6559058489986e-01 -5.6437692780833e-01 -5.6367981621705e-01 -5.5061751987039e-01 -5.7401896292809e-01 -5.6308820121529e-01 -5.7806173369790e-01 6.5459774609649e-01 6.3942597709555e-01 6.1164480465591e-01 6.5108010076956e-01 6.3798609656378e-01 6.5736736208692e-01 6.8996257821643e-01 6.5225714359749e-01 6.6001648303497e-01 6.2143281533413e-01 5.9516459544598e-01 5.2854204739570e-01 4.3515118289681e-01 3.4606882010398e-01 2.7284846312667e-01 1.8163204200550e-01 1.4292287067663e-01 1.0765829690390e-01 8.9865823357913e-02 6.8959481591363e-02 5.4547853852249e-02 3.3140818528078e-02 9.4295111288905e-03 -2.0447836240852e-02 -5.3819054589341e-02 -8.3440601026674e-02 -1.1382541581729e-01 -1.6161639997743e-01 -2.2597414431638e-01 -2.7662587145823e-01 -3.6974835766416e-01 -4.1544571715308e-01 -5.1216073319057e-01 -5.8693576930321e-01 -6.5187822843836e-01 -6.7168294236678e-01 -7.0821042136044e-01 -7.1124641101690e-01 -7.2999694382984e-01 -7.2578450020509e-01 -6.8179773275981e-01 -6.4536108820077e-01 -6.0231981220112e-01 -6.1453044359095e-01 -6.2034213224875e-01 -5.8710780686813e-01 -6.0628310442440e-01 -6.0211859869944e-01 -5.8556761504319e-01 -5.9429233655646e-01 6.3860366401346e-01 6.2081436806440e-01 6.2408725784016e-01 6.4622607140448e-01 6.6441181686844e-01 6.8794959583251e-01 6.7603649698628e-01 6.3600808809353e-01 6.3997118587088e-01 6.0968460290312e-01 5.5971791259663e-01 4.7271478525890e-01 3.6493477055778e-01 2.9147333482709e-01 1.9191423693597e-01 1.5267035223036e-01 1.4101772501958e-01 1.2785875238590e-01 1.0779206185035e-01 1.0162249170955e-01 8.4295668721425e-02 5.3816822421878e-02 2.0949544277887e-02 -1.6811164838173e-02 -5.9745181566407e-02 -1.1972135701475e-01 -1.7497458427881e-01 -2.7007683912178e-01 -3.6255344201408e-01 -4.6028535741462e-01 -5.3779842481281e-01 -5.9747261127145e-01 -6.7190149919965e-01 -7.0231714106808e-01 -7.1415850566186e-01 -7.4643619851283e-01 -7.2424860750044e-01 -7.2851944570115e-01 -6.6633896887393e-01 -6.8209126026125e-01 -6.7328595665255e-01 -6.3797006889997e-01 -6.2862494359561e-01 -6.2030452061081e-01 -5.7769632794251e-01 -5.6983077764095e-01 -5.5893416168527e-01 -5.8176692836091e-01 -5.8119584087036e-01 -5.7664349648580e-01 6.9357750668347e-01 6.2883917421844e-01 6.7317360883911e-01 6.8914592741817e-01 6.7632635323572e-01 6.7197986908447e-01 6.9715808366016e-01 7.0490579155415e-01 7.1482297868045e-01 7.3360600339983e-01 6.9228327766645e-01 6.0590029888482e-01 5.5275619048640e-01 4.6324053294078e-01 3.5659439486735e-01 2.6183043679449e-01 1.7302844611958e-01 1.1740205859730e-01 7.4820987238711e-02 5.0731728270734e-02 4.9091179817214e-02 4.8323933953032e-02 4.5181417421261e-02 2.8817098014038e-02 3.3176851112166e-03 -2.4799155229609e-02 -7.0948336088686e-02 -1.2336793673322e-01 -1.9310281260407e-01 -2.7487152895950e-01 -3.6491030322890e-01 -4.9037760625632e-01 -5.5229036506926e-01 -5.8635796848157e-01 -6.3194623002686e-01 -6.4570888470981e-01 -6.7720766648775e-01 -6.6822279873438e-01 -7.4563691930359e-01 -6.9953821181429e-01 -6.7378307072068e-01 -6.6686333680087e-01 -6.4270912905348e-01 -6.0002395422031e-01 -6.1265104962551e-01 -5.8963335789060e-01 -5.7515644841957e-01 -6.0844627560200e-01 -6.1027230060005e-01 -6.2318136990968e-01 7.5084715778046e-01 6.8621692832699e-01 5.8416880981161e-01 5.7735066833799e-01 7.5661698272758e-01 5.0729060063731e-01 6.3902834892306e-01 6.7975453305917e-01 7.8251355112487e-01 6.5454958025934e-01 5.7523217742813e-01 7.8326193660389e-01 7.2217083843821e-01 1.0187987912759e+00 8.0268915559318e-01 9.5016831737427e-01 1.1686495180131e+00 1.0854585146734e+00 9.8339518205027e-01 1.0346614608617e+00 1.2281555306096e+00 1.1293845003247e+00 8.5943866537141e-01 1.0150437652943e+00 1.1062277522715e+00 8.4542595568791e-01 1.0220563851266e+00 9.7691693855435e-01 9.9890875147371e-01 8.6517498901010e-01 7.2515472610154e-01 7.5098019596474e-01 9.9231688009489e-01 7.4727765965058e-01 6.3490052150272e-01 8.5748057400049e-01 7.9195366813886e-01 6.1333909780980e-01 8.1641852565156e-01 8.3723230754514e-01 6.6799862796668e-01 8.1297023449313e-01 7.2778995128163e-01 8.9084370115263e-01 6.3953224481930e-01 7.2488592303896e-01 8.4781830820013e-01 7.5778592905375e-01 8.2337861600490e-01 9.3949382942579e-01 6.1064614691050e-01 5.4471694982646e-01 8.1172236469054e-01 6.1217154215188e-01 6.8774465081387e-01 5.9772086497320e-01 4.9898539712717e-01 5.6305260019276e-01 7.9506127476547e-01 6.3617265302705e-01 6.8157342675134e-01 7.5293430717269e-01 8.7844188762009e-01 8.1937476276180e-01 8.2629612307457e-01 8.1753763611580e-01 9.9915466554661e-01 7.5372793849846e-01 8.5952160148275e-01 1.0616290795166e+00 1.0394308674040e+00 8.6988213210192e-01 1.0526283889539e+00 1.0467069716220e+00 8.8154086827616e-01 9.9194634819841e-01 1.1561034036697e+00 9.3685204868075e-01 8.3262819769350e-01 9.5467095076612e-01 8.3778225117473e-01 7.9680684593553e-01 8.1432527588842e-01 7.0372492175217e-01 6.0077344820089e-01 4.8336517685210e-01 4.8307618377228e-01 4.6993259647494e-01 5.4149980133887e-01 8.2601643804389e-01 7.0760178800236e-01 6.6290188878317e-01 7.1870470622860e-01 7.6212440581961e-01 7.6578885011254e-01 7.7005840331701e-01 8.4724055618951e-01 7.0379835808170e-01 7.7369820283579e-01 6.7632502651402e-01 4.8565710239580e-01 6.1412641424612e-01 8.1047172527107e-01 6.2903566547902e-01 7.6409648890633e-01 7.2024498383284e-01 5.9911467457048e-01 8.5395442741023e-01 7.6732726891965e-01 8.0385237418394e-01 6.6574442009139e-01 7.3651835792471e-01 9.1411695009235e-01 1.0171136485239e+00 9.3746295393102e-01 1.1406396950692e+00 9.7100093056763e-01 1.0621742991052e+00 9.9417705985613e-01 1.1056140724166e+00 9.6522894507462e-01 9.9608640034266e-01 8.4911052142770e-01 1.0299074972469e+00 1.0067195041856e+00 1.0470346298813e+00 1.0230729325299e+00 9.1281885766112e-01 1.0230339536855e+00 1.1857319607620e+00 8.3244313981106e-01 9.5131698760524e-01 7.5080045509862e-01 6.6684973629961e-01 5.9645882700102e-01 7.2658299052270e-01 6.4800038019581e-01 7.1372992755815e-01 6.0364735558192e-01 5.1829362945549e-01 6.3816448648535e-01 6.7517041270885e-01 7.6574878713684e-01 5.9419742614323e-01 5.3236633927604e-01 7.6255656325875e-01 6.3901787649741e-01 6.6759516841038e-01 7.7171077429431e-01 7.1850573827153e-01 6.8545875476551e-01 7.8739674603370e-01 7.7555850688387e-01 6.6934333859695e-01 6.1427555374966e-01 5.4570751911886e-01 6.9580104523176e-01 9.0463619933824e-01 8.0068820836020e-01 7.5446433711162e-01 6.7272820592383e-01 7.1765526213269e-01 8.4461467598311e-01 5.6953359142596e-01 1.0106530200362e+00 1.1033680486669e+00 9.9483938994282e-01 9.5465684758128e-01 1.1254882737039e+00 9.4996415908857e-01 9.3723512534501e-01 1.0903970669788e+00 1.0002338133148e+00 9.3634983805492e-01 1.0829036915719e+00 9.4092340244877e-01 1.1210405475278e+00 8.7995800517730e-01 8.3846486094840e-01 7.7545933647487e-01 8.0575924976491e-01 8.3560225767543e-01 6.9037877657712e-01 6.9974604811170e-01 7.3282609504498e-01 5.9109777412071e-01 7.0512436333062e-01 6.1347521847615e-01 8.5569724399094e-01 6.8884489000011e-01 6.2518517301184e-01 7.0833103719353e-01 6.4129759292262e-01 5.7581684342589e-01 7.7331144333710e-01 7.6803472227962e-01 8.1261929854639e-01 6.6301556110973e-01 6.6700483212393e-01 6.9844152428920e-01 5.0674506500672e-01 8.7645862572915e-01 6.4462578587502e-01 5.4428078226166e-01 6.5449809662542e-01 7.3576200497651e-01 6.7813001100282e-01 7.0353702664750e-01 6.7161880900707e-01 4.9228049268489e-01 5.9473491403678e-01 8.2003898897405e-01 7.4807369849665e-01 8.5034284076797e-01 9.4498507065487e-01 8.4278150617612e-01 9.9281828715916e-01 9.4515094090891e-01 8.4836872892702e-01 1.0371822720746e+00 9.1383815614049e-01 9.4807033854766e-01 8.6475632142384e-01 9.3913792198456e-01 1.0439449955862e+00 1.1566342771847e+00 8.8330289569066e-01 1.0223500919525e+00 1.0214807339050e+00 1.0388314558316e+00 1.0096649143205e+00 7.1157471770708e-01 7.6926062010454e-01 8.4288080407056e-01 7.4907279882928e-01 8.1234707719287e-01 7.7248288178182e-01 8.7474023687304e-01 3.8112386606431e-01 6.2223265285576e-01 6.3883618631012e-01 5.4426406669578e-01 6.4178856443241e-01 8.4331021464942e-01 7.1565247443438e-01 8.1135930279826e-01 8.8019602702753e-01 6.8764877625069e-01 6.7571102547692e-01 5.8496053733199e-01 + 5.6849006514565e-01 5.2905110461167e-01 4.6245602958351e-01 4.5990316803969e-01 5.8134390508192e-01 4.1812683757983e-01 5.1880725832052e-01 5.5175293394490e-01 6.2292603769750e-01 5.4196263834602e-01 4.8584857089386e-01 6.2927284228082e-01 5.9193072911796e-01 7.6293258029968e-01 6.5151645877539e-01 7.4423253443734e-01 8.5065996846040e-01 8.2783733436650e-01 7.8647787090970e-01 8.2011144027393e-01 9.1037205527099e-01 8.8833144042106e-01 7.5374625106507e-01 8.4738414270109e-01 8.8097277593874e-01 7.2272026500133e-01 8.0476992875822e-01 7.6864772490423e-01 7.6988032347535e-01 6.8989978236997e-01 5.9522165753751e-01 6.0579882216008e-01 7.3531995641582e-01 5.9937351312016e-01 5.2602841208318e-01 6.7252689201920e-01 6.3546472962202e-01 5.1420181959187e-01 6.4471735691471e-01 6.5029872268400e-01 5.3840668779057e-01 6.2515161957030e-01 5.7157112224905e-01 6.6561015291900e-01 5.1251992091931e-01 5.6811299023916e-01 6.4083926580201e-01 5.8842644855482e-01 6.2714199618188e-01 6.8851001439474e-01 4.7149188184391e-01 4.2747826679954e-01 5.9854267727024e-01 4.7973734849737e-01 5.3382637627978e-01 4.7851049143790e-01 4.1204419698162e-01 4.6475203707711e-01 6.2644658620455e-01 5.2696581841759e-01 5.6001029071193e-01 6.0546123302481e-01 6.7627676733999e-01 6.4068701795940e-01 6.4893082966349e-01 6.5386886400850e-01 7.6568284751803e-01 6.3437424136776e-01 7.1230667740271e-01 8.3599689090017e-01 8.4401506796630e-01 7.6030466837758e-01 8.6801205905056e-01 8.5487374615775e-01 7.4695810206340e-01 7.9566925104095e-01 8.5506487206691e-01 7.4109612744427e-01 6.7004980445810e-01 7.2893085006074e-01 6.5752755000882e-01 6.2527496590785e-01 6.2887019674237e-01 5.5503120002002e-01 4.8110971775485e-01 3.9407480355659e-01 3.9371615963730e-01 3.8383565740872e-01 4.3611033435144e-01 6.2087412492557e-01 5.5005370590888e-01 5.1960332625452e-01 5.5474717842192e-01 5.8147927349342e-01 5.8370952814422e-01 5.8624500406898e-01 6.3005683313472e-01 5.4562900808274e-01 5.8839771536472e-01 5.2802275851851e-01 3.8096109729170e-01 4.7039368843842e-01 5.9128959167221e-01 4.8526439252144e-01 5.7524565998480e-01 5.5708797148245e-01 4.8544516125584e-01 6.5801172516201e-01 6.1532752444226e-01 6.4358788374758e-01 5.5608235940148e-01 6.0687153676140e-01 7.1567286750543e-01 7.6929917757805e-01 7.3529002820185e-01 8.3595169359984e-01 7.6949048243624e-01 8.2326526134198e-01 8.0453246563738e-01 8.7647792909480e-01 8.1951443150864e-01 8.3838809019370e-01 7.4364556765011e-01 8.3512898280065e-01 8.0679688387221e-01 8.1253505056420e-01 7.9359180736320e-01 7.3186738586510e-01 7.8209152135441e-01 8.3994443789604e-01 6.7088487141855e-01 7.3289307742155e-01 6.1127158560484e-01 5.5046884915798e-01 4.9652100574534e-01 5.8246800193325e-01 5.2737555564301e-01 5.6787753345700e-01 4.9034588953470e-01 4.2663478987767e-01 5.1029785464956e-01 5.3166559912327e-01 5.8452133048894e-01 4.7187811457581e-01 4.2791286900572e-01 5.8009350460646e-01 5.0199180620665e-01 5.2083887620828e-01 5.8551736522986e-01 5.5327180273425e-01 5.2237159067278e-01 5.8334065411443e-01 5.7760083272699e-01 5.1619361450831e-01 4.8585574519234e-01 4.4523849820421e-01 5.5710583211035e-01 6.9145480883123e-01 6.3971246292865e-01 6.1364957253019e-01 5.6024288368571e-01 5.9198252556786e-01 6.7525573057204e-01 4.9259701425150e-01 7.7585679258431e-01 8.2088174186491e-01 7.7787716183422e-01 7.6704448870517e-01 8.6579432586095e-01 8.0057860957844e-01 8.0371131403839e-01 8.8454377402544e-01 8.3188675835587e-01 7.8493344635148e-01 8.4511303365264e-01 7.5881579425120e-01 8.2799637728434e-01 6.9986891191928e-01 6.6676996809571e-01 6.1904485214427e-01 6.2643901458656e-01 6.3337153350372e-01 5.4051998727115e-01 5.4676878322083e-01 5.7001120911751e-01 4.7835012152283e-01 5.5848921295402e-01 4.9965241781534e-01 6.5624996153440e-01 5.5523850013858e-01 5.1120913013754e-01 5.6642981255060e-01 5.2033527970471e-01 4.7305291652223e-01 6.0353814833174e-01 5.9899684848746e-01 6.2482169445236e-01 5.3093768961959e-01 5.3361382686545e-01 5.5438731838157e-01 3.8281223108237e-01 6.0031134680531e-01 4.7274742376255e-01 4.0982179833174e-01 4.8529947210108e-01 5.4260864554405e-01 5.1709527755821e-01 5.4355880435017e-01 5.3490078006031e-01 4.1396429902580e-01 4.9272302994457e-01 6.4067941057533e-01 5.9473828814700e-01 6.5475982526437e-01 7.1007764208925e-01 6.6179568492978e-01 7.4890578055997e-01 7.3513142597622e-01 6.9113354863779e-01 8.0395432151554e-01 7.5737975083322e-01 7.9833414349547e-01 7.5984554097362e-01 8.0453959206384e-01 8.5281141913699e-01 8.9253925049255e-01 7.4433749175903e-01 8.0721607470447e-01 7.9194768588882e-01 7.8419140384554e-01 7.5633617741935e-01 5.7619271279242e-01 6.0463500774982e-01 6.4414437476329e-01 5.8951745017861e-01 6.2938363157358e-01 6.0680075222985e-01 6.6739204830812e-01 3.2581136937594e-01 5.0846333451759e-01 5.1676514620963e-01 4.4590725058607e-01 5.1311037582550e-01 6.3738732207055e-01 5.6089314238034e-01 6.1829986053023e-01 6.5599424994886e-01 5.4212525389360e-01 5.3430967733605e-01 4.7233398682766e-01 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_pose_tpgmm_XU2.txt b/data/data_pose_tpgmm_XU2.txt new file mode 100644 index 0000000..678ae46 --- /dev/null +++ b/data/data_pose_tpgmm_XU2.txt @@ -0,0 +1,14 @@ + 2.1116563491837e-01 2.1116794708734e-01 2.1119414141609e-01 2.1122696401106e-01 2.1130236045309e-01 2.1133843351191e-01 2.1136506656268e-01 2.1146544701143e-01 2.1236486322428e-01 2.1690196313398e-01 2.2352903804325e-01 2.3277333618387e-01 2.4761270196395e-01 2.6632039813466e-01 2.8127294265677e-01 2.9763767745809e-01 3.1327178743541e-01 3.3907085346416e-01 3.6301244133304e-01 3.8240271680676e-01 4.0284005779902e-01 4.2680851129136e-01 4.4876837115591e-01 4.7284146868259e-01 4.9338309748257e-01 5.2629274166155e-01 5.4336052319801e-01 5.5820133793515e-01 5.7731999737994e-01 6.0297017674938e-01 6.2481759540824e-01 6.4455242946481e-01 6.6081884693126e-01 6.8477110004758e-01 6.9628531894032e-01 7.1158502139949e-01 7.3370208614516e-01 7.5175137211083e-01 7.6056432502470e-01 7.6922964222968e-01 7.7851672740235e-01 7.9107785617476e-01 7.9339097093832e-01 7.9371906487177e-01 7.9377067654767e-01 7.9314138487503e-01 7.9242842648028e-01 7.9215052612275e-01 7.9175187728651e-01 7.9136359323299e-01 7.9283997959213e-01 7.9204076602017e-01 7.9229192806417e-01 7.9291681802864e-01 7.9287961252133e-01 7.9266514589822e-01 7.9237868592059e-01 7.9208116409415e-01 7.9197398618782e-01 7.9197094534086e-01 7.9213127556510e-01 7.9218142495185e-01 7.9196322425872e-01 7.9165871849313e-01 7.9143375659528e-01 7.9142428133602e-01 7.9141946532040e-01 2.5897727199750e-01 2.5901936972894e-01 2.5898541237181e-01 2.5899924421341e-01 2.5897094532239e-01 2.5892089162828e-01 2.5873884838270e-01 2.5875040973924e-01 2.5873625442967e-01 2.5871967122723e-01 2.5867592682291e-01 2.5898169342347e-01 2.6377481024446e-01 2.7004003669161e-01 2.8474313260927e-01 2.9510373296163e-01 3.1714584688776e-01 3.3377783687033e-01 3.5849563354986e-01 3.8580608002309e-01 4.0657733511797e-01 4.3958818199448e-01 4.5757326328916e-01 4.6397318016431e-01 4.6938072029872e-01 4.7247415379517e-01 4.7668308530281e-01 4.8060821746416e-01 4.8223407094221e-01 4.8131883497157e-01 4.7669645537721e-01 4.7237611246584e-01 4.6853403067075e-01 4.6153670994881e-01 4.5596910227451e-01 4.5017464967224e-01 4.4578202453265e-01 4.3696101774540e-01 4.3085072677127e-01 4.2687702348242e-01 4.2649735268809e-01 4.2936693178051e-01 4.3249068241708e-01 4.3646115159673e-01 4.3782765911018e-01 4.3688460320062e-01 4.3771284822437e-01 4.3918117474436e-01 4.3951709112478e-01 4.4035609582207e-01 4.4066855899111e-01 4.3920324574939e-01 4.3830397658081e-01 4.3677067586356e-01 4.3663211525307e-01 4.3640864207994e-01 4.3622436546953e-01 4.3594944660798e-01 4.3531820264857e-01 4.3505136126459e-01 4.3497984463697e-01 4.3483497606654e-01 4.3455654433411e-01 4.3452035724279e-01 4.3448350981823e-01 4.3442396183337e-01 4.3452880188075e-01 4.3492057218174e-01 4.3485886176477e-01 4.3482762294060e-01 4.3458868182498e-01 4.3364883169095e-01 4.3085622172787e-01 4.3052593564322e-01 4.3055835340473e-01 4.3058704429654e-01 2.3010752605859e-01 2.3011078793218e-01 2.3012070147044e-01 2.3018977648244e-01 2.3019969003092e-01 2.3021510336775e-01 2.3022827881311e-01 2.3023473027367e-01 2.3029069396718e-01 2.3037537706861e-01 2.3043127696444e-01 2.3044445246030e-01 2.3108046135634e-01 2.3220624850577e-01 2.3421323538601e-01 2.3697433729648e-01 2.4223380242813e-01 2.4783930204740e-01 2.5787821225967e-01 2.7862784164039e-01 3.0490240256380e-01 3.2310207587091e-01 3.4719197003620e-01 3.6847061593919e-01 3.9809256517046e-01 4.2309335616030e-01 4.4852248976112e-01 4.6846267470422e-01 4.9313936329930e-01 5.0522990071488e-01 5.1780716065068e-01 5.3195880443142e-01 5.3961221263121e-01 5.4487137866525e-01 5.5136997119707e-01 5.5605991701647e-01 5.5823915572069e-01 5.5994483522559e-01 5.6067891887838e-01 5.6249965940186e-01 5.6410659883967e-01 5.6502113862620e-01 5.6545090417863e-01 5.6590945510669e-01 5.6591338680517e-01 5.6590671848249e-01 5.6620880384581e-01 5.6665382849369e-01 5.6668026014269e-01 5.6681890691205e-01 5.6715226690961e-01 5.6725404941978e-01 5.6770398874184e-01 5.6823166575919e-01 5.6845239292079e-01 5.6874654904024e-01 5.6886590634487e-01 5.6890514508286e-01 5.6893187662926e-01 5.6905230288727e-01 5.6906178903104e-01 5.6906187693018e-01 5.6909020942948e-01 5.6909242387061e-01 5.6908702679737e-01 5.6880386872517e-01 5.6878797312194e-01 5.6878144691756e-01 5.6875898334782e-01 5.6875091928340e-01 2.2959772088743e-01 2.2958787770866e-01 2.2956820307901e-01 2.2956328437474e-01 2.2955570706350e-01 2.2954833189738e-01 2.2955493550068e-01 2.2959455707895e-01 2.2959782681766e-01 2.2966505437355e-01 2.2977944911468e-01 2.3034055588832e-01 2.3237076341186e-01 2.3517522618007e-01 2.3992370623530e-01 2.4509949398979e-01 2.5588850098975e-01 2.6264810441634e-01 2.6851131527054e-01 2.7588760807960e-01 2.8394518889667e-01 2.9889406827633e-01 3.1077524153301e-01 3.2471265968461e-01 3.5270259123635e-01 3.7156742967184e-01 3.9144197429293e-01 4.0891027212052e-01 4.3972223532253e-01 4.7174994371353e-01 4.8895690474450e-01 5.0416721174805e-01 5.2937585734071e-01 5.4297206287792e-01 5.5410391677780e-01 5.7426159168224e-01 5.9764243720970e-01 6.1092670699665e-01 6.2487027059750e-01 6.4842568572313e-01 6.6753606575291e-01 6.8709512451437e-01 6.9240575213692e-01 6.9681236662199e-01 7.0395494029060e-01 7.0537221534919e-01 7.0787239746320e-01 7.1196372521087e-01 7.1284927075310e-01 7.1292987892880e-01 7.1301658345797e-01 7.1271857095955e-01 7.1200758672862e-01 7.1078082887435e-01 7.1039073885808e-01 7.0983216336702e-01 7.0762284294944e-01 7.0608426583973e-01 7.0544686228801e-01 7.0480706546844e-01 7.0415495225309e-01 7.0386544511018e-01 7.0361523406752e-01 7.0320514329718e-01 7.0287775652061e-01 7.0313548529309e-01 7.0310884159473e-01 7.0304201412318e-01 7.0303954427989e-01 7.0295270429198e-01 7.0295083682360e-01 2.4581567026758e-01 2.4583075140926e-01 2.4580983097362e-01 2.4578799887998e-01 2.4578314920987e-01 2.4575647270139e-01 2.4566188293369e-01 2.4565578932506e-01 2.4566483519844e-01 2.4576135185447e-01 2.4684565977300e-01 2.5031799803115e-01 2.5549833336234e-01 2.6295935111343e-01 2.7783952282102e-01 2.8476525484805e-01 2.9265419440647e-01 3.1327427236274e-01 3.3296453812336e-01 3.4873512341975e-01 3.7009225585785e-01 3.9011779168651e-01 4.2144872368040e-01 4.3810842107197e-01 4.5429994724669e-01 4.9080691106495e-01 5.1560314845453e-01 5.3351868629739e-01 5.5502858263936e-01 5.7122703539539e-01 5.9157763466748e-01 6.0980771625185e-01 6.2293329378580e-01 6.3478751964054e-01 6.5407942063905e-01 6.6320207340573e-01 6.7147688679879e-01 6.8156046882518e-01 6.8839238365853e-01 6.8943460982874e-01 6.9079317097606e-01 6.9231178246600e-01 6.9229177112118e-01 6.9219739723895e-01 6.9206195730862e-01 6.9204374296935e-01 6.9201934839970e-01 6.9191630305784e-01 6.9189428563986e-01 6.9188615115365e-01 6.9183810410818e-01 6.9201411809328e-01 6.9218974186527e-01 6.9254944422558e-01 6.9259539120730e-01 6.9265732725653e-01 6.9259317192030e-01 6.9258687836140e-01 6.9258582385948e-01 6.9262077622203e-01 6.9278687145172e-01 6.9292401740454e-01 6.9304019025947e-01 2.4251393510846e-01 2.4253152804082e-01 2.4255498319743e-01 2.4263903247325e-01 2.4264294195450e-01 2.4270353311009e-01 2.4290827238374e-01 2.4290685220539e-01 2.4291271496505e-01 2.4371233227632e-01 2.4456481076447e-01 2.4656698222957e-01 2.5125338464145e-01 2.5539285606943e-01 2.6039301912994e-01 2.6691698218867e-01 2.7133914087532e-01 2.7561785560434e-01 2.9185383990402e-01 3.0958193704849e-01 3.3411030790497e-01 3.5718873471700e-01 3.9694928065892e-01 4.2078764810428e-01 4.3133522276139e-01 4.5733289569284e-01 4.6930258421124e-01 4.7334543892442e-01 4.7527895354650e-01 4.7134003286475e-01 4.7060999056132e-01 4.7231051138418e-01 4.8165511636222e-01 4.9191620514480e-01 5.0758704144631e-01 5.2454888838739e-01 5.4577335171166e-01 5.5676931502069e-01 5.6993186725841e-01 5.8564903951654e-01 5.9979585189897e-01 6.0852397689706e-01 6.1546870947391e-01 6.2150650132480e-01 6.2594319682249e-01 6.2587325143292e-01 6.2518235274849e-01 6.2372859410592e-01 6.2187318230591e-01 6.2060307221385e-01 6.1894882972263e-01 6.1832860779102e-01 6.1791745230305e-01 6.1762749558525e-01 6.1673886650551e-01 6.1576390379765e-01 6.1543265203683e-01 6.1536433885518e-01 6.1527522161789e-01 6.1495832880089e-01 6.1459179607407e-01 6.1458347554190e-01 6.1432338824571e-01 6.1374010694850e-01 6.1327590491427e-01 6.1293533215982e-01 6.1295571146256e-01 6.1294692040189e-01 6.1287530945911e-01 6.1286773355626e-01 2.3790465194331e-01 2.3793789605356e-01 2.3845526182230e-01 2.3963728438314e-01 2.4281291485858e-01 2.5211059546807e-01 2.6315441640428e-01 2.7686416050635e-01 2.8784262425958e-01 2.9500109190019e-01 3.0463499410313e-01 3.2242946146362e-01 3.3475688492710e-01 3.6441752489845e-01 3.8948825842379e-01 4.1325804837391e-01 4.4110767475151e-01 4.5630357465463e-01 4.7079451572794e-01 4.8898424026244e-01 4.9812230579446e-01 5.1458109972888e-01 5.2996408057693e-01 5.4903977784626e-01 5.6078748600801e-01 5.6763985192715e-01 5.7351325796908e-01 5.8432779575629e-01 5.9200449416446e-01 6.0749554659559e-01 6.2504806101754e-01 6.4425373722681e-01 6.6986193141602e-01 6.8385853908345e-01 6.9727603966119e-01 7.1219558662358e-01 7.2664989167523e-01 7.2885547361077e-01 7.2887682893333e-01 7.2951862313750e-01 7.2923801137334e-01 7.2824776175601e-01 7.2714262490959e-01 7.2658030677304e-01 7.2626851677610e-01 7.2529168458212e-01 7.2476109446340e-01 7.2397097648828e-01 7.2361580169469e-01 7.2336492005649e-01 7.2302397114352e-01 7.2185030652658e-01 7.2150705927406e-01 7.2142260660789e-01 7.2144756379078e-01 7.2195964466611e-01 7.2187571752013e-01 7.2181028002012e-01 7.2174003334740e-01 7.2124684215947e-01 7.2119785630884e-01 2.2876267947325e-01 2.2879566859567e-01 2.2880888992399e-01 2.2890464839907e-01 2.2892775369163e-01 2.2893109112375e-01 2.2897562473320e-01 2.2944004297261e-01 2.3339368586883e-01 2.4457856858602e-01 2.5881285393952e-01 2.7517431292355e-01 2.8850366090326e-01 3.1007673980665e-01 3.3182627559726e-01 3.5816151572413e-01 3.8031058518853e-01 4.1263402613048e-01 4.2939692392996e-01 4.4520136665012e-01 4.8285789870196e-01 5.0377902980718e-01 5.1371840423516e-01 5.2220661563439e-01 5.2862354214789e-01 5.3620680842831e-01 5.3824623638891e-01 5.3984827245987e-01 5.5090698468636e-01 5.5242258272716e-01 5.5045713428520e-01 5.4935088351558e-01 5.4953000915580e-01 5.4986346170592e-01 5.5007373654197e-01 5.4999735455233e-01 5.5034928315702e-01 5.5042153401197e-01 5.5049789862561e-01 5.5052556277791e-01 5.5053614251155e-01 5.5055922923285e-01 5.5055904719307e-01 5.5057094650809e-01 5.5058455239524e-01 5.5059690758417e-01 5.5059919483885e-01 5.5066313507301e-01 5.5066577215322e-01 5.5066841898672e-01 5.5069898715361e-01 5.5069986136803e-01 5.5071615020487e-01 2.1116563491837e-01 2.1116794708734e-01 2.1119414141609e-01 2.1122696401106e-01 2.1130236045309e-01 2.1133843351191e-01 2.1136506656268e-01 2.1146544701143e-01 2.1236486322428e-01 2.1690196313398e-01 2.2352903804325e-01 2.3277333618387e-01 2.4761270196395e-01 2.6632039813466e-01 2.8127294265677e-01 2.9763767745809e-01 3.1327178743541e-01 3.3907085346416e-01 3.6301244133304e-01 3.8240271680676e-01 4.0284005779902e-01 4.2680851129136e-01 4.4876837115591e-01 4.7284146868259e-01 4.9338309748257e-01 5.2629274166155e-01 5.4336052319801e-01 5.5820133793515e-01 5.7731999737994e-01 6.0297017674938e-01 6.2481759540824e-01 6.4455242946481e-01 6.6081884693126e-01 6.8477110004758e-01 6.9628531894032e-01 7.1158502139949e-01 7.3370208614516e-01 7.5175137211083e-01 7.6056432502470e-01 7.6922964222968e-01 7.7851672740235e-01 7.9107785617476e-01 7.9339097093832e-01 7.9371906487177e-01 7.9377067654767e-01 7.9314138487503e-01 7.9242842648028e-01 7.9215052612275e-01 7.9175187728651e-01 7.9136359323299e-01 7.9283997959213e-01 7.9204076602017e-01 7.9229192806417e-01 7.9291681802864e-01 7.9287961252133e-01 7.9266514589822e-01 7.9237868592059e-01 7.9208116409415e-01 7.9197398618782e-01 7.9197094534086e-01 7.9213127556510e-01 7.9218142495185e-01 7.9196322425872e-01 7.9165871849313e-01 7.9143375659528e-01 7.9142428133602e-01 7.9141946532040e-01 2.5897727199750e-01 2.5901936972894e-01 2.5898541237181e-01 2.5899924421341e-01 2.5897094532239e-01 2.5892089162828e-01 2.5873884838270e-01 2.5875040973924e-01 2.5873625442967e-01 2.5871967122723e-01 2.5867592682291e-01 2.5898169342347e-01 2.6377481024446e-01 2.7004003669161e-01 2.8474313260927e-01 2.9510373296163e-01 3.1714584688776e-01 3.3377783687033e-01 3.5849563354986e-01 3.8580608002309e-01 4.0657733511797e-01 4.3958818199448e-01 4.5757326328916e-01 4.6397318016431e-01 4.6938072029872e-01 4.7247415379517e-01 4.7668308530281e-01 4.8060821746416e-01 4.8223407094221e-01 4.8131883497157e-01 4.7669645537721e-01 4.7237611246584e-01 4.6853403067075e-01 4.6153670994881e-01 4.5596910227451e-01 4.5017464967224e-01 4.4578202453265e-01 4.3696101774540e-01 4.3085072677127e-01 4.2687702348242e-01 4.2649735268809e-01 4.2936693178051e-01 4.3249068241708e-01 4.3646115159673e-01 4.3782765911018e-01 4.3688460320062e-01 4.3771284822437e-01 4.3918117474436e-01 4.3951709112478e-01 4.4035609582207e-01 4.4066855899111e-01 4.3920324574939e-01 4.3830397658081e-01 4.3677067586356e-01 4.3663211525307e-01 4.3640864207994e-01 4.3622436546953e-01 4.3594944660798e-01 4.3531820264857e-01 4.3505136126459e-01 4.3497984463697e-01 4.3483497606654e-01 4.3455654433411e-01 4.3452035724279e-01 4.3448350981823e-01 4.3442396183337e-01 4.3452880188075e-01 4.3492057218174e-01 4.3485886176477e-01 4.3482762294060e-01 4.3458868182498e-01 4.3364883169095e-01 4.3085622172787e-01 4.3052593564322e-01 4.3055835340473e-01 4.3058704429654e-01 2.3010752605859e-01 2.3011078793218e-01 2.3012070147044e-01 2.3018977648244e-01 2.3019969003092e-01 2.3021510336775e-01 2.3022827881311e-01 2.3023473027367e-01 2.3029069396718e-01 2.3037537706861e-01 2.3043127696444e-01 2.3044445246030e-01 2.3108046135634e-01 2.3220624850577e-01 2.3421323538601e-01 2.3697433729648e-01 2.4223380242813e-01 2.4783930204740e-01 2.5787821225967e-01 2.7862784164039e-01 3.0490240256380e-01 3.2310207587091e-01 3.4719197003620e-01 3.6847061593919e-01 3.9809256517046e-01 4.2309335616030e-01 4.4852248976112e-01 4.6846267470422e-01 4.9313936329930e-01 5.0522990071488e-01 5.1780716065068e-01 5.3195880443142e-01 5.3961221263121e-01 5.4487137866525e-01 5.5136997119707e-01 5.5605991701647e-01 5.5823915572069e-01 5.5994483522559e-01 5.6067891887838e-01 5.6249965940186e-01 5.6410659883967e-01 5.6502113862620e-01 5.6545090417863e-01 5.6590945510669e-01 5.6591338680517e-01 5.6590671848249e-01 5.6620880384581e-01 5.6665382849369e-01 5.6668026014269e-01 5.6681890691205e-01 5.6715226690961e-01 5.6725404941978e-01 5.6770398874184e-01 5.6823166575919e-01 5.6845239292079e-01 5.6874654904024e-01 5.6886590634487e-01 5.6890514508286e-01 5.6893187662926e-01 5.6905230288727e-01 5.6906178903104e-01 5.6906187693018e-01 5.6909020942948e-01 5.6909242387061e-01 5.6908702679737e-01 5.6880386872517e-01 5.6878797312194e-01 5.6878144691756e-01 5.6875898334782e-01 5.6875091928340e-01 2.2959772088743e-01 2.2958787770866e-01 2.2956820307901e-01 2.2956328437474e-01 2.2955570706350e-01 2.2954833189738e-01 2.2955493550068e-01 2.2959455707895e-01 2.2959782681766e-01 2.2966505437355e-01 2.2977944911468e-01 2.3034055588832e-01 2.3237076341186e-01 2.3517522618007e-01 2.3992370623530e-01 2.4509949398979e-01 2.5588850098975e-01 2.6264810441634e-01 2.6851131527054e-01 2.7588760807960e-01 2.8394518889667e-01 2.9889406827633e-01 3.1077524153301e-01 3.2471265968461e-01 3.5270259123635e-01 3.7156742967184e-01 3.9144197429293e-01 4.0891027212052e-01 4.3972223532253e-01 4.7174994371353e-01 4.8895690474450e-01 5.0416721174805e-01 5.2937585734071e-01 5.4297206287792e-01 5.5410391677780e-01 5.7426159168224e-01 5.9764243720970e-01 6.1092670699665e-01 6.2487027059750e-01 6.4842568572313e-01 6.6753606575291e-01 6.8709512451437e-01 6.9240575213692e-01 6.9681236662199e-01 7.0395494029060e-01 7.0537221534919e-01 7.0787239746320e-01 7.1196372521087e-01 7.1284927075310e-01 7.1292987892880e-01 7.1301658345797e-01 7.1271857095955e-01 7.1200758672862e-01 7.1078082887435e-01 7.1039073885808e-01 7.0983216336702e-01 7.0762284294944e-01 7.0608426583973e-01 7.0544686228801e-01 7.0480706546844e-01 7.0415495225309e-01 7.0386544511018e-01 7.0361523406752e-01 7.0320514329718e-01 7.0287775652061e-01 7.0313548529309e-01 7.0310884159473e-01 7.0304201412318e-01 7.0303954427989e-01 7.0295270429198e-01 7.0295083682360e-01 2.4581567026758e-01 2.4583075140926e-01 2.4580983097362e-01 2.4578799887998e-01 2.4578314920987e-01 2.4575647270139e-01 2.4566188293369e-01 2.4565578932506e-01 2.4566483519844e-01 2.4576135185447e-01 2.4684565977300e-01 2.5031799803115e-01 2.5549833336234e-01 2.6295935111343e-01 2.7783952282102e-01 2.8476525484805e-01 2.9265419440647e-01 3.1327427236274e-01 3.3296453812336e-01 3.4873512341975e-01 3.7009225585785e-01 3.9011779168651e-01 4.2144872368040e-01 4.3810842107197e-01 4.5429994724669e-01 4.9080691106495e-01 5.1560314845453e-01 5.3351868629739e-01 5.5502858263936e-01 5.7122703539539e-01 5.9157763466748e-01 6.0980771625185e-01 6.2293329378580e-01 6.3478751964054e-01 6.5407942063905e-01 6.6320207340573e-01 6.7147688679879e-01 6.8156046882518e-01 6.8839238365853e-01 6.8943460982874e-01 6.9079317097606e-01 6.9231178246600e-01 6.9229177112118e-01 6.9219739723895e-01 6.9206195730862e-01 6.9204374296935e-01 6.9201934839970e-01 6.9191630305784e-01 6.9189428563986e-01 6.9188615115365e-01 6.9183810410818e-01 6.9201411809328e-01 6.9218974186527e-01 6.9254944422558e-01 6.9259539120730e-01 6.9265732725653e-01 6.9259317192030e-01 6.9258687836140e-01 6.9258582385948e-01 6.9262077622203e-01 6.9278687145172e-01 6.9292401740454e-01 6.9304019025947e-01 2.4251393510846e-01 2.4253152804082e-01 2.4255498319743e-01 2.4263903247325e-01 2.4264294195450e-01 2.4270353311009e-01 2.4290827238374e-01 2.4290685220539e-01 2.4291271496505e-01 2.4371233227632e-01 2.4456481076447e-01 2.4656698222957e-01 2.5125338464145e-01 2.5539285606943e-01 2.6039301912994e-01 2.6691698218867e-01 2.7133914087532e-01 2.7561785560434e-01 2.9185383990402e-01 3.0958193704849e-01 3.3411030790497e-01 3.5718873471700e-01 3.9694928065892e-01 4.2078764810428e-01 4.3133522276139e-01 4.5733289569284e-01 4.6930258421124e-01 4.7334543892442e-01 4.7527895354650e-01 4.7134003286475e-01 4.7060999056132e-01 4.7231051138418e-01 4.8165511636222e-01 4.9191620514480e-01 5.0758704144631e-01 5.2454888838739e-01 5.4577335171166e-01 5.5676931502069e-01 5.6993186725841e-01 5.8564903951654e-01 5.9979585189897e-01 6.0852397689706e-01 6.1546870947391e-01 6.2150650132480e-01 6.2594319682249e-01 6.2587325143292e-01 6.2518235274849e-01 6.2372859410592e-01 6.2187318230591e-01 6.2060307221385e-01 6.1894882972263e-01 6.1832860779102e-01 6.1791745230305e-01 6.1762749558525e-01 6.1673886650551e-01 6.1576390379765e-01 6.1543265203683e-01 6.1536433885518e-01 6.1527522161789e-01 6.1495832880089e-01 6.1459179607407e-01 6.1458347554190e-01 6.1432338824571e-01 6.1374010694850e-01 6.1327590491427e-01 6.1293533215982e-01 6.1295571146256e-01 6.1294692040189e-01 6.1287530945911e-01 6.1286773355626e-01 2.3790465194331e-01 2.3793789605356e-01 2.3845526182230e-01 2.3963728438314e-01 2.4281291485858e-01 2.5211059546807e-01 2.6315441640428e-01 2.7686416050635e-01 2.8784262425958e-01 2.9500109190019e-01 3.0463499410313e-01 3.2242946146362e-01 3.3475688492710e-01 3.6441752489845e-01 3.8948825842379e-01 4.1325804837391e-01 4.4110767475151e-01 4.5630357465463e-01 4.7079451572794e-01 4.8898424026244e-01 4.9812230579446e-01 5.1458109972888e-01 5.2996408057693e-01 5.4903977784626e-01 5.6078748600801e-01 5.6763985192715e-01 5.7351325796908e-01 5.8432779575629e-01 5.9200449416446e-01 6.0749554659559e-01 6.2504806101754e-01 6.4425373722681e-01 6.6986193141602e-01 6.8385853908345e-01 6.9727603966119e-01 7.1219558662358e-01 7.2664989167523e-01 7.2885547361077e-01 7.2887682893333e-01 7.2951862313750e-01 7.2923801137334e-01 7.2824776175601e-01 7.2714262490959e-01 7.2658030677304e-01 7.2626851677610e-01 7.2529168458212e-01 7.2476109446340e-01 7.2397097648828e-01 7.2361580169469e-01 7.2336492005649e-01 7.2302397114352e-01 7.2185030652658e-01 7.2150705927406e-01 7.2142260660789e-01 7.2144756379078e-01 7.2195964466611e-01 7.2187571752013e-01 7.2181028002012e-01 7.2174003334740e-01 7.2124684215947e-01 7.2119785630884e-01 2.2876267947325e-01 2.2879566859567e-01 2.2880888992399e-01 2.2890464839907e-01 2.2892775369163e-01 2.2893109112375e-01 2.2897562473320e-01 2.2944004297261e-01 2.3339368586883e-01 2.4457856858602e-01 2.5881285393952e-01 2.7517431292355e-01 2.8850366090326e-01 3.1007673980665e-01 3.3182627559726e-01 3.5816151572413e-01 3.8031058518853e-01 4.1263402613048e-01 4.2939692392996e-01 4.4520136665012e-01 4.8285789870196e-01 5.0377902980718e-01 5.1371840423516e-01 5.2220661563439e-01 5.2862354214789e-01 5.3620680842831e-01 5.3824623638891e-01 5.3984827245987e-01 5.5090698468636e-01 5.5242258272716e-01 5.5045713428520e-01 5.4935088351558e-01 5.4953000915580e-01 5.4986346170592e-01 5.5007373654197e-01 5.4999735455233e-01 5.5034928315702e-01 5.5042153401197e-01 5.5049789862561e-01 5.5052556277791e-01 5.5053614251155e-01 5.5055922923285e-01 5.5055904719307e-01 5.5057094650809e-01 5.5058455239524e-01 5.5059690758417e-01 5.5059919483885e-01 5.5066313507301e-01 5.5066577215322e-01 5.5066841898672e-01 5.5069898715361e-01 5.5069986136803e-01 5.5071615020487e-01 + -9.4147085919656e-02 -9.4144696900393e-02 -9.4124822380696e-02 -9.4099919191682e-02 -9.4042716102081e-02 -9.4015348434656e-02 -9.3993238172761e-02 -9.3890429828140e-02 -9.2961918452787e-02 -8.8475870136302e-02 -8.3135421342772e-02 -8.0000462471967e-02 -7.6886910188930e-02 -7.2252938773441e-02 -6.3571960661192e-02 -5.3920025852409e-02 -4.8583559221367e-02 -4.3722607932461e-02 -4.0168263020895e-02 -3.5909439916126e-02 -3.0054110883937e-02 -2.4588049412889e-02 -1.9802039901033e-02 -1.5465066269057e-02 -1.2998173333596e-02 -1.1003524750396e-02 -9.8247419703476e-03 -1.0157902776182e-02 -1.2946761050192e-02 -1.9651257319945e-02 -2.5842250198645e-02 -3.1313053652755e-02 -3.6362103636145e-02 -4.5550635103330e-02 -4.9925588844396e-02 -5.8776715995327e-02 -7.3791528993952e-02 -8.6683423499621e-02 -9.2123642522968e-02 -9.8569241370521e-02 -1.0485443021271e-01 -1.1238446079394e-01 -1.1290067291714e-01 -1.1349842439819e-01 -1.1355718573097e-01 -1.1206753719564e-01 -1.1048547528392e-01 -1.0983427221311e-01 -1.0891566232753e-01 -1.0622844482169e-01 -1.0605927136389e-01 -1.0424449791456e-01 -1.0477085796935e-01 -1.0593786792995e-01 -1.0560624037719e-01 -1.0502113124616e-01 -1.0432201365610e-01 -1.0337282720487e-01 -1.0302264548455e-01 -1.0299371344180e-01 -1.0326624157215e-01 -1.0331495273529e-01 -1.0276108422863e-01 -1.0203691365488e-01 -1.0150735182245e-01 -1.0147506115923e-01 -1.0146273953384e-01 -1.0738527648610e-01 -1.0735926326601e-01 -1.0740146837505e-01 -1.0739212530301e-01 -1.0742097275282e-01 -1.0743403036523e-01 -1.0754282737104e-01 -1.0753379582229e-01 -1.0754823006199e-01 -1.0756045470339e-01 -1.0760036791494e-01 -1.0759412983756e-01 -1.0767571660232e-01 -1.1042641974561e-01 -1.1558651813727e-01 -1.2030538012632e-01 -1.2674067507308e-01 -1.2606192870327e-01 -1.1649930300729e-01 -1.0031447532996e-01 -8.6788350374956e-02 -6.1772676660608e-02 -4.3482541089447e-02 -3.3507783868224e-02 -1.8069769419933e-02 -3.9063545332118e-03 1.7522584957123e-02 3.1336743238493e-02 5.3874829445382e-02 6.9141700689736e-02 9.3200592835721e-02 1.1001894812706e-01 1.2367240728454e-01 1.4043755021188e-01 1.5303910921591e-01 1.6657421076154e-01 1.7629535699025e-01 1.9168176783539e-01 2.0026419555723e-01 2.0783053404823e-01 2.1648936776477e-01 2.2502719879481e-01 2.2953621934907e-01 2.3453773732829e-01 2.3760381130521e-01 2.4295416715337e-01 2.4679739629501e-01 2.4774235552771e-01 2.4770231477924e-01 2.4763194785692e-01 2.4786296803164e-01 2.4959092952505e-01 2.5051660311805e-01 2.5196977811906e-01 2.5208447261680e-01 2.5229352559793e-01 2.5237717282533e-01 2.5258918584379e-01 2.5318042009669e-01 2.5340111225264e-01 2.5346573523895e-01 2.5360412134137e-01 2.5387289559509e-01 2.5390555379128e-01 2.5394023671401e-01 2.5399956300394e-01 2.5395277358543e-01 2.5374638077338e-01 2.5382807623824e-01 2.5387599789862e-01 2.5410569695186e-01 2.5498920832963e-01 2.5770604899242e-01 2.5804756041475e-01 2.5801554060867e-01 2.5798880623998e-01 -1.1767725834358e-01 -1.1767478762488e-01 -1.1766727860480e-01 -1.1761495881612e-01 -1.1760745011911e-01 -1.1760039220162e-01 -1.1759041305492e-01 -1.1758512830358e-01 -1.1754274210305e-01 -1.1748360947993e-01 -1.1744127499375e-01 -1.1743129703058e-01 -1.1714872115953e-01 -1.1666327004807e-01 -1.1586288066353e-01 -1.1494540566153e-01 -1.1377524568311e-01 -1.1231017050988e-01 -1.0975865131741e-01 -1.1043149289208e-01 -1.1189321089591e-01 -1.1101950967930e-01 -1.0877112070228e-01 -1.0615639743462e-01 -1.1063277472609e-01 -1.2120815319456e-01 -1.3435820135955e-01 -1.4682794140431e-01 -1.6489405473660e-01 -1.7508971901685e-01 -1.8674538729313e-01 -2.0434666919264e-01 -2.1782980064896e-01 -2.2745636162157e-01 -2.3911904652940e-01 -2.4817282850747e-01 -2.5259611623358e-01 -2.5616725662630e-01 -2.5772674199301e-01 -2.5998458189437e-01 -2.6024104168328e-01 -2.5952817028620e-01 -2.5916730796086e-01 -2.5881628894113e-01 -2.5880101095460e-01 -2.5878600503138e-01 -2.5865563561324e-01 -2.5828711240195e-01 -2.5826750559279e-01 -2.5816375791754e-01 -2.5790103690464e-01 -2.5778007320657e-01 -2.5736564686814e-01 -2.5687807892710e-01 -2.5650475014429e-01 -2.5610459814041e-01 -2.5600860071305e-01 -2.5605828315266e-01 -2.5601852929964e-01 -2.5592335525471e-01 -2.5593630572169e-01 -2.5596800952021e-01 -2.5612276955288e-01 -2.5635888063149e-01 -2.5643430854403e-01 -2.5912825503400e-01 -2.6004962592405e-01 -2.6007892307864e-01 -2.6021011004841e-01 -2.6023157495013e-01 -9.9784499491374e-02 -9.9771915598545e-02 -9.9746763471613e-02 -9.9740475518564e-02 -9.9725453003076e-02 -9.9716025045212e-02 -9.9711096821696e-02 -9.9681527842137e-02 -9.9679087711317e-02 -9.9627424634337e-02 -9.9541312955183e-02 -9.9039800512748e-02 -9.6914640460767e-02 -9.3909430597978e-02 -8.8993832326979e-02 -8.3631451137210e-02 -7.2403927457540e-02 -6.5379457791838e-02 -5.9506190367634e-02 -5.3636561796505e-02 -4.7983633584296e-02 -4.0613776952848e-02 -3.6274212661400e-02 -3.2691662147787e-02 -2.3335518973659e-02 -1.7105943712628e-02 -1.0642257575567e-02 -4.9576295955421e-03 1.8217318204082e-03 1.0577102739320e-02 1.7682575129431e-02 2.5129495588051e-02 3.5888000999450e-02 3.8478470985630e-02 3.8849848258166e-02 3.5359457643842e-02 3.3573441818986e-02 3.5395766279669e-02 3.7605694905681e-02 3.8726424220234e-02 3.6493133683718e-02 3.1763315464552e-02 2.9538918279300e-02 2.7019615011782e-02 2.2454989405958e-02 2.4054745861162e-02 2.5545311869942e-02 2.7083602763662e-02 2.7846186688579e-02 2.7451633800683e-02 2.7178713403892e-02 2.7545221259980e-02 2.8490978579844e-02 3.0302063764084e-02 3.0925899109277e-02 3.1768863987717e-02 3.3989317225255e-02 3.5428429430122e-02 3.5765013399838e-02 3.6324544968372e-02 3.6892699159502e-02 3.7152775023485e-02 3.7545530370417e-02 3.8201693177107e-02 3.8610648358812e-02 3.8391353969124e-02 3.8319661073521e-02 3.8234735853554e-02 3.8239003312863e-02 3.8376116110837e-02 3.8374844004705e-02 -1.1972077222329e-01 -1.1971345064859e-01 -1.1967908108633e-01 -1.1965037511661e-01 -1.1964399867298e-01 -1.1960892486694e-01 -1.1948457357444e-01 -1.1946570025725e-01 -1.1946130810322e-01 -1.1941444804726e-01 -1.1891892220300e-01 -1.1736958041667e-01 -1.1522961941896e-01 -1.1227308073581e-01 -1.0734407058542e-01 -1.0559102951286e-01 -1.0354407004663e-01 -9.7830596361845e-02 -9.2227677690787e-02 -8.7233996164600e-02 -8.2339425556083e-02 -8.0453488432454e-02 -8.5055153393530e-02 -8.7906100482078e-02 -9.3003821126338e-02 -1.0403729625209e-01 -1.0928531394431e-01 -1.1203924696386e-01 -1.2265025808780e-01 -1.3224263006789e-01 -1.4601924179285e-01 -1.6016190894614e-01 -1.6768899844971e-01 -1.7438785556281e-01 -1.8753714096333e-01 -1.9533257026613e-01 -2.0262336775364e-01 -2.1118642462481e-01 -2.2108901161959e-01 -2.2382124979242e-01 -2.2755665577791e-01 -2.3087249061698e-01 -2.3082897404592e-01 -2.3057018162512e-01 -2.3006123758171e-01 -2.3001512513788e-01 -2.2995683263721e-01 -2.2968998977458e-01 -2.2965503505355e-01 -2.2968141752712e-01 -2.2923523533919e-01 -2.2893480790387e-01 -2.2907045285694e-01 -2.2954858588171e-01 -2.2915339274808e-01 -2.2863535522142e-01 -2.2843666265608e-01 -2.2828968436049e-01 -2.2830432335833e-01 -2.2844186741309e-01 -2.2874764993867e-01 -2.2873938073339e-01 -2.2883483835559e-01 -1.2558765794609e-01 -1.2556278932863e-01 -1.2552963461779e-01 -1.2541083258971e-01 -1.2540530679077e-01 -1.2531966712542e-01 -1.2502367168264e-01 -1.2502338950357e-01 -1.2501510450894e-01 -1.2391868665778e-01 -1.2353149227330e-01 -1.1919641352383e-01 -1.1173599953140e-01 -1.0410160919455e-01 -9.5511445487652e-02 -8.2742058436324e-02 -7.6673949884351e-02 -7.1571494310142e-02 -6.1008059585376e-02 -5.4589970654844e-02 -4.4384049930829e-02 -3.2592437122622e-02 -1.1617407490841e-02 4.0746195519348e-03 1.1718059447702e-02 3.6373060676751e-02 5.5722210109185e-02 6.7150854291432e-02 8.7435016094380e-02 1.0220541246619e-01 1.2419795926447e-01 1.2787724683857e-01 1.4195767057569e-01 1.4718693782864e-01 1.5274737382966e-01 1.5577705673585e-01 1.5796354122647e-01 1.5783469408326e-01 1.5850385117368e-01 1.6182192457079e-01 1.6420507066491e-01 1.6400676565842e-01 1.6319822047728e-01 1.6367357972567e-01 1.6278447715486e-01 1.6288602805443e-01 1.6373409056488e-01 1.6553359775693e-01 1.6781500929410e-01 1.6937164568735e-01 1.7163345072682e-01 1.7239857806771e-01 1.7289400159966e-01 1.7321319334495e-01 1.7418725012628e-01 1.7536474222193e-01 1.7572558443199e-01 1.7574980955360e-01 1.7585095076283e-01 1.7616542658759e-01 1.7659626017034e-01 1.7660448585967e-01 1.7678818914368e-01 1.7713663677469e-01 1.7729173088838e-01 1.7757731602500e-01 1.7754717340268e-01 1.7755581989878e-01 1.7764280316357e-01 1.7765271197644e-01 -1.0924759500823e-01 -1.0922483465998e-01 -1.0888042529087e-01 -1.0807700013170e-01 -1.0591738605769e-01 -9.9619523727059e-02 -9.2246267475774e-02 -8.3236219178193e-02 -7.6186285167824e-02 -7.1514932277150e-02 -6.5448222202098e-02 -5.7226433659168e-02 -5.2386488929335e-02 -3.9403791533527e-02 -3.0256924449566e-02 -2.2485617794240e-02 -1.3534115771103e-02 -6.3531597864105e-03 1.4072721221592e-03 1.3573900311384e-02 1.9731681185395e-02 2.9137206532400e-02 3.7311869197418e-02 4.7969800342117e-02 5.5102166332650e-02 6.0118061320816e-02 6.4954692205213e-02 7.0322977611386e-02 7.2195905176316e-02 7.3856622828388e-02 7.5186719531779e-02 7.5113906599189e-02 7.2163516465802e-02 6.9738793037029e-02 6.6840569268779e-02 6.4136051786828e-02 6.3957047002133e-02 6.4626499232979e-02 6.4451943181497e-02 6.3226205653452e-02 6.3249688495963e-02 6.3020806915083e-02 6.4247063108904e-02 6.5140491331909e-02 6.5594765312343e-02 6.7010204369998e-02 6.7812528926758e-02 6.9030021274813e-02 6.9433052575463e-02 6.9722455185974e-02 7.0152402899696e-02 7.0211910656268e-02 6.9851892086055e-02 6.9993730603717e-02 7.0145961239743e-02 6.9921674498410e-02 6.9973026128836e-02 7.0011257598378e-02 7.0125151987412e-02 7.0896406624960e-02 7.0959698087513e-02 -1.3599285531694e-01 -1.3596797190078e-01 -1.3595799927770e-01 -1.3588577222018e-01 -1.3586834526539e-01 -1.3586582805418e-01 -1.3584903471804e-01 -1.3567396004188e-01 -1.3418845687622e-01 -1.3001338545630e-01 -1.2484380863709e-01 -1.1926650374976e-01 -1.1521626120256e-01 -1.0837841903931e-01 -1.0269497902386e-01 -9.8759870520971e-02 -9.5444718337790e-02 -9.0504581024711e-02 -8.9700250022079e-02 -9.1823820110475e-02 -1.1123117175812e-01 -1.2864113173783e-01 -1.3818333193045e-01 -1.4896655023729e-01 -1.6078388856543e-01 -1.7698139962762e-01 -1.8232024013481e-01 -1.8750810625084e-01 -2.1276243748597e-01 -2.2193939849598e-01 -2.2508942050547e-01 -2.2718995799445e-01 -2.2877838116059e-01 -2.3265260043481e-01 -2.3507583215839e-01 -2.3567603268193e-01 -2.3747356650091e-01 -2.3756772621202e-01 -2.3748097509997e-01 -2.3745702333972e-01 -2.3745384981584e-01 -2.3743630039988e-01 -2.3742968527818e-01 -2.3741989651174e-01 -2.3741072254049e-01 -2.3740542628056e-01 -2.3739106758749e-01 -2.3735023307478e-01 -2.3734909939730e-01 -2.3734796141146e-01 -2.3732812120905e-01 -2.3732774487468e-01 -2.3730734793534e-01 -9.4147085919656e-02 -9.4144696900393e-02 -9.4124822380696e-02 -9.4099919191682e-02 -9.4042716102081e-02 -9.4015348434656e-02 -9.3993238172761e-02 -9.3890429828140e-02 -9.2961918452787e-02 -8.8475870136302e-02 -8.3135421342772e-02 -8.0000462471967e-02 -7.6886910188930e-02 -7.2252938773441e-02 -6.3571960661192e-02 -5.3920025852409e-02 -4.8583559221367e-02 -4.3722607932461e-02 -4.0168263020895e-02 -3.5909439916126e-02 -3.0054110883937e-02 -2.4588049412889e-02 -1.9802039901033e-02 -1.5465066269057e-02 -1.2998173333596e-02 -1.1003524750396e-02 -9.8247419703476e-03 -1.0157902776182e-02 -1.2946761050192e-02 -1.9651257319945e-02 -2.5842250198645e-02 -3.1313053652755e-02 -3.6362103636145e-02 -4.5550635103330e-02 -4.9925588844396e-02 -5.8776715995327e-02 -7.3791528993952e-02 -8.6683423499621e-02 -9.2123642522968e-02 -9.8569241370521e-02 -1.0485443021271e-01 -1.1238446079394e-01 -1.1290067291714e-01 -1.1349842439819e-01 -1.1355718573097e-01 -1.1206753719564e-01 -1.1048547528392e-01 -1.0983427221311e-01 -1.0891566232753e-01 -1.0622844482169e-01 -1.0605927136389e-01 -1.0424449791456e-01 -1.0477085796935e-01 -1.0593786792995e-01 -1.0560624037719e-01 -1.0502113124616e-01 -1.0432201365610e-01 -1.0337282720487e-01 -1.0302264548455e-01 -1.0299371344180e-01 -1.0326624157215e-01 -1.0331495273529e-01 -1.0276108422863e-01 -1.0203691365488e-01 -1.0150735182245e-01 -1.0147506115923e-01 -1.0146273953384e-01 -1.0738527648610e-01 -1.0735926326601e-01 -1.0740146837505e-01 -1.0739212530301e-01 -1.0742097275282e-01 -1.0743403036523e-01 -1.0754282737104e-01 -1.0753379582229e-01 -1.0754823006199e-01 -1.0756045470339e-01 -1.0760036791494e-01 -1.0759412983756e-01 -1.0767571660232e-01 -1.1042641974561e-01 -1.1558651813727e-01 -1.2030538012632e-01 -1.2674067507308e-01 -1.2606192870327e-01 -1.1649930300729e-01 -1.0031447532996e-01 -8.6788350374956e-02 -6.1772676660608e-02 -4.3482541089447e-02 -3.3507783868224e-02 -1.8069769419933e-02 -3.9063545332118e-03 1.7522584957123e-02 3.1336743238493e-02 5.3874829445382e-02 6.9141700689736e-02 9.3200592835721e-02 1.1001894812706e-01 1.2367240728454e-01 1.4043755021188e-01 1.5303910921591e-01 1.6657421076154e-01 1.7629535699025e-01 1.9168176783539e-01 2.0026419555723e-01 2.0783053404823e-01 2.1648936776477e-01 2.2502719879481e-01 2.2953621934907e-01 2.3453773732829e-01 2.3760381130521e-01 2.4295416715337e-01 2.4679739629501e-01 2.4774235552771e-01 2.4770231477924e-01 2.4763194785692e-01 2.4786296803164e-01 2.4959092952505e-01 2.5051660311805e-01 2.5196977811906e-01 2.5208447261680e-01 2.5229352559793e-01 2.5237717282533e-01 2.5258918584379e-01 2.5318042009669e-01 2.5340111225264e-01 2.5346573523895e-01 2.5360412134137e-01 2.5387289559509e-01 2.5390555379128e-01 2.5394023671401e-01 2.5399956300394e-01 2.5395277358543e-01 2.5374638077338e-01 2.5382807623824e-01 2.5387599789862e-01 2.5410569695186e-01 2.5498920832963e-01 2.5770604899242e-01 2.5804756041475e-01 2.5801554060867e-01 2.5798880623998e-01 -1.1767725834358e-01 -1.1767478762488e-01 -1.1766727860480e-01 -1.1761495881612e-01 -1.1760745011911e-01 -1.1760039220162e-01 -1.1759041305492e-01 -1.1758512830358e-01 -1.1754274210305e-01 -1.1748360947993e-01 -1.1744127499375e-01 -1.1743129703058e-01 -1.1714872115953e-01 -1.1666327004807e-01 -1.1586288066353e-01 -1.1494540566153e-01 -1.1377524568311e-01 -1.1231017050988e-01 -1.0975865131741e-01 -1.1043149289208e-01 -1.1189321089591e-01 -1.1101950967930e-01 -1.0877112070228e-01 -1.0615639743462e-01 -1.1063277472609e-01 -1.2120815319456e-01 -1.3435820135955e-01 -1.4682794140431e-01 -1.6489405473660e-01 -1.7508971901685e-01 -1.8674538729313e-01 -2.0434666919264e-01 -2.1782980064896e-01 -2.2745636162157e-01 -2.3911904652940e-01 -2.4817282850747e-01 -2.5259611623358e-01 -2.5616725662630e-01 -2.5772674199301e-01 -2.5998458189437e-01 -2.6024104168328e-01 -2.5952817028620e-01 -2.5916730796086e-01 -2.5881628894113e-01 -2.5880101095460e-01 -2.5878600503138e-01 -2.5865563561324e-01 -2.5828711240195e-01 -2.5826750559279e-01 -2.5816375791754e-01 -2.5790103690464e-01 -2.5778007320657e-01 -2.5736564686814e-01 -2.5687807892710e-01 -2.5650475014429e-01 -2.5610459814041e-01 -2.5600860071305e-01 -2.5605828315266e-01 -2.5601852929964e-01 -2.5592335525471e-01 -2.5593630572169e-01 -2.5596800952021e-01 -2.5612276955288e-01 -2.5635888063149e-01 -2.5643430854403e-01 -2.5912825503400e-01 -2.6004962592405e-01 -2.6007892307864e-01 -2.6021011004841e-01 -2.6023157495013e-01 -9.9784499491374e-02 -9.9771915598545e-02 -9.9746763471613e-02 -9.9740475518564e-02 -9.9725453003076e-02 -9.9716025045212e-02 -9.9711096821696e-02 -9.9681527842137e-02 -9.9679087711317e-02 -9.9627424634337e-02 -9.9541312955183e-02 -9.9039800512748e-02 -9.6914640460767e-02 -9.3909430597978e-02 -8.8993832326979e-02 -8.3631451137210e-02 -7.2403927457540e-02 -6.5379457791838e-02 -5.9506190367634e-02 -5.3636561796505e-02 -4.7983633584296e-02 -4.0613776952848e-02 -3.6274212661400e-02 -3.2691662147787e-02 -2.3335518973659e-02 -1.7105943712628e-02 -1.0642257575567e-02 -4.9576295955421e-03 1.8217318204082e-03 1.0577102739320e-02 1.7682575129431e-02 2.5129495588051e-02 3.5888000999450e-02 3.8478470985630e-02 3.8849848258166e-02 3.5359457643842e-02 3.3573441818986e-02 3.5395766279669e-02 3.7605694905681e-02 3.8726424220234e-02 3.6493133683718e-02 3.1763315464552e-02 2.9538918279300e-02 2.7019615011782e-02 2.2454989405958e-02 2.4054745861162e-02 2.5545311869942e-02 2.7083602763662e-02 2.7846186688579e-02 2.7451633800683e-02 2.7178713403892e-02 2.7545221259980e-02 2.8490978579844e-02 3.0302063764084e-02 3.0925899109277e-02 3.1768863987717e-02 3.3989317225255e-02 3.5428429430122e-02 3.5765013399838e-02 3.6324544968372e-02 3.6892699159502e-02 3.7152775023485e-02 3.7545530370417e-02 3.8201693177107e-02 3.8610648358812e-02 3.8391353969124e-02 3.8319661073521e-02 3.8234735853554e-02 3.8239003312863e-02 3.8376116110837e-02 3.8374844004705e-02 -1.1972077222329e-01 -1.1971345064859e-01 -1.1967908108633e-01 -1.1965037511661e-01 -1.1964399867298e-01 -1.1960892486694e-01 -1.1948457357444e-01 -1.1946570025725e-01 -1.1946130810322e-01 -1.1941444804726e-01 -1.1891892220300e-01 -1.1736958041667e-01 -1.1522961941896e-01 -1.1227308073581e-01 -1.0734407058542e-01 -1.0559102951286e-01 -1.0354407004663e-01 -9.7830596361845e-02 -9.2227677690787e-02 -8.7233996164600e-02 -8.2339425556083e-02 -8.0453488432454e-02 -8.5055153393530e-02 -8.7906100482078e-02 -9.3003821126338e-02 -1.0403729625209e-01 -1.0928531394431e-01 -1.1203924696386e-01 -1.2265025808780e-01 -1.3224263006789e-01 -1.4601924179285e-01 -1.6016190894614e-01 -1.6768899844971e-01 -1.7438785556281e-01 -1.8753714096333e-01 -1.9533257026613e-01 -2.0262336775364e-01 -2.1118642462481e-01 -2.2108901161959e-01 -2.2382124979242e-01 -2.2755665577791e-01 -2.3087249061698e-01 -2.3082897404592e-01 -2.3057018162512e-01 -2.3006123758171e-01 -2.3001512513788e-01 -2.2995683263721e-01 -2.2968998977458e-01 -2.2965503505355e-01 -2.2968141752712e-01 -2.2923523533919e-01 -2.2893480790387e-01 -2.2907045285694e-01 -2.2954858588171e-01 -2.2915339274808e-01 -2.2863535522142e-01 -2.2843666265608e-01 -2.2828968436049e-01 -2.2830432335833e-01 -2.2844186741309e-01 -2.2874764993867e-01 -2.2873938073339e-01 -2.2883483835559e-01 -1.2558765794609e-01 -1.2556278932863e-01 -1.2552963461779e-01 -1.2541083258971e-01 -1.2540530679077e-01 -1.2531966712542e-01 -1.2502367168264e-01 -1.2502338950357e-01 -1.2501510450894e-01 -1.2391868665778e-01 -1.2353149227330e-01 -1.1919641352383e-01 -1.1173599953140e-01 -1.0410160919455e-01 -9.5511445487652e-02 -8.2742058436324e-02 -7.6673949884351e-02 -7.1571494310142e-02 -6.1008059585376e-02 -5.4589970654844e-02 -4.4384049930829e-02 -3.2592437122622e-02 -1.1617407490841e-02 4.0746195519348e-03 1.1718059447702e-02 3.6373060676751e-02 5.5722210109185e-02 6.7150854291432e-02 8.7435016094380e-02 1.0220541246619e-01 1.2419795926447e-01 1.2787724683857e-01 1.4195767057569e-01 1.4718693782864e-01 1.5274737382966e-01 1.5577705673585e-01 1.5796354122647e-01 1.5783469408326e-01 1.5850385117368e-01 1.6182192457079e-01 1.6420507066491e-01 1.6400676565842e-01 1.6319822047728e-01 1.6367357972567e-01 1.6278447715486e-01 1.6288602805443e-01 1.6373409056488e-01 1.6553359775693e-01 1.6781500929410e-01 1.6937164568735e-01 1.7163345072682e-01 1.7239857806771e-01 1.7289400159966e-01 1.7321319334495e-01 1.7418725012628e-01 1.7536474222193e-01 1.7572558443199e-01 1.7574980955360e-01 1.7585095076283e-01 1.7616542658759e-01 1.7659626017034e-01 1.7660448585967e-01 1.7678818914368e-01 1.7713663677469e-01 1.7729173088838e-01 1.7757731602500e-01 1.7754717340268e-01 1.7755581989878e-01 1.7764280316357e-01 1.7765271197644e-01 -1.0924759500823e-01 -1.0922483465998e-01 -1.0888042529087e-01 -1.0807700013170e-01 -1.0591738605769e-01 -9.9619523727059e-02 -9.2246267475774e-02 -8.3236219178193e-02 -7.6186285167824e-02 -7.1514932277150e-02 -6.5448222202098e-02 -5.7226433659168e-02 -5.2386488929335e-02 -3.9403791533527e-02 -3.0256924449566e-02 -2.2485617794240e-02 -1.3534115771103e-02 -6.3531597864105e-03 1.4072721221592e-03 1.3573900311384e-02 1.9731681185395e-02 2.9137206532400e-02 3.7311869197418e-02 4.7969800342117e-02 5.5102166332650e-02 6.0118061320816e-02 6.4954692205213e-02 7.0322977611386e-02 7.2195905176316e-02 7.3856622828388e-02 7.5186719531779e-02 7.5113906599189e-02 7.2163516465802e-02 6.9738793037029e-02 6.6840569268779e-02 6.4136051786828e-02 6.3957047002133e-02 6.4626499232979e-02 6.4451943181497e-02 6.3226205653452e-02 6.3249688495963e-02 6.3020806915083e-02 6.4247063108904e-02 6.5140491331909e-02 6.5594765312343e-02 6.7010204369998e-02 6.7812528926758e-02 6.9030021274813e-02 6.9433052575463e-02 6.9722455185974e-02 7.0152402899696e-02 7.0211910656268e-02 6.9851892086055e-02 6.9993730603717e-02 7.0145961239743e-02 6.9921674498410e-02 6.9973026128836e-02 7.0011257598378e-02 7.0125151987412e-02 7.0896406624960e-02 7.0959698087513e-02 -1.3599285531694e-01 -1.3596797190078e-01 -1.3595799927770e-01 -1.3588577222018e-01 -1.3586834526539e-01 -1.3586582805418e-01 -1.3584903471804e-01 -1.3567396004188e-01 -1.3418845687622e-01 -1.3001338545630e-01 -1.2484380863709e-01 -1.1926650374976e-01 -1.1521626120256e-01 -1.0837841903931e-01 -1.0269497902386e-01 -9.8759870520971e-02 -9.5444718337790e-02 -9.0504581024711e-02 -8.9700250022079e-02 -9.1823820110475e-02 -1.1123117175812e-01 -1.2864113173783e-01 -1.3818333193045e-01 -1.4896655023729e-01 -1.6078388856543e-01 -1.7698139962762e-01 -1.8232024013481e-01 -1.8750810625084e-01 -2.1276243748597e-01 -2.2193939849598e-01 -2.2508942050547e-01 -2.2718995799445e-01 -2.2877838116059e-01 -2.3265260043481e-01 -2.3507583215839e-01 -2.3567603268193e-01 -2.3747356650091e-01 -2.3756772621202e-01 -2.3748097509997e-01 -2.3745702333972e-01 -2.3745384981584e-01 -2.3743630039988e-01 -2.3742968527818e-01 -2.3741989651174e-01 -2.3741072254049e-01 -2.3740542628056e-01 -2.3739106758749e-01 -2.3735023307478e-01 -2.3734909939730e-01 -2.3734796141146e-01 -2.3732812120905e-01 -2.3732774487468e-01 -2.3730734793534e-01 + 6.3804736142884e-01 6.3804823482159e-01 6.3805162712043e-01 6.3805588006116e-01 6.3806565891480e-01 6.3807034222527e-01 6.3807552540327e-01 6.3811272502982e-01 6.3845622682741e-01 6.4022419382321e-01 6.4265760126177e-01 6.4500637093656e-01 6.4875391077591e-01 6.5484261385118e-01 6.6279780825761e-01 6.7307185617912e-01 6.8242017467958e-01 6.9683947287202e-01 7.1023886863166e-01 7.2448715921182e-01 7.4450660335042e-01 7.6944839001724e-01 7.9254842589876e-01 8.1750440943818e-01 8.3806884163854e-01 8.7036315099824e-01 8.9181199119146e-01 9.1220283366587e-01 9.3597640933162e-01 9.5867738801083e-01 9.7404982669029e-01 9.8739872803208e-01 9.9556374993758e-01 1.0075242970393e+00 1.0158597234426e+00 1.0222177570443e+00 1.0269384318280e+00 1.0315426506909e+00 1.0372840614886e+00 1.0436253842422e+00 1.0499728464437e+00 1.0618823708773e+00 1.0657137617107e+00 1.0665535853664e+00 1.0670037923159e+00 1.0692643342630e+00 1.0716438949395e+00 1.0725083819538e+00 1.0739965506631e+00 1.0767535339652e+00 1.0752413973218e+00 1.0744132953925e+00 1.0745616423617e+00 1.0750131468837e+00 1.0750557940116e+00 1.0749016971476e+00 1.0745899110889e+00 1.0749608059936e+00 1.0750350772115e+00 1.0751738539032e+00 1.0757479882814e+00 1.0763663907841e+00 1.0767955714179e+00 1.0770667614243e+00 1.0773797161840e+00 1.0774904290122e+00 1.0774850269177e+00 6.3427817301781e-01 6.3428493282580e-01 6.3426972168344e-01 6.3427384818164e-01 6.3426306072875e-01 6.3420897703185e-01 6.3411807905055e-01 6.3411922208007e-01 6.3411387218567e-01 6.3411087028123e-01 6.3409674921086e-01 6.3414086054151e-01 6.3479287905228e-01 6.3500461453535e-01 6.3569946710424e-01 6.3619351640337e-01 6.3913590605831e-01 6.4373039887920e-01 6.5495070414045e-01 6.7277226148801e-01 6.8994941410395e-01 7.2116311527109e-01 7.4346531700012e-01 7.5447095795457e-01 7.7122585035675e-01 7.8738122523780e-01 8.1418001601485e-01 8.3169856370778e-01 8.5500218093750e-01 8.6749304005047e-01 8.8271005195369e-01 8.9268938686742e-01 9.0197301391074e-01 9.1293007393031e-01 9.2090006393005e-01 9.3008322924868e-01 9.3632399145448e-01 9.4480097943329e-01 9.4915950758254e-01 9.5389175579718e-01 9.6140847308283e-01 9.6998295693313e-01 9.7293741710655e-01 9.7399266217101e-01 9.7457391441307e-01 9.8065934147666e-01 9.8515495713908e-01 9.8523916469549e-01 9.8486663308845e-01 9.8401346402890e-01 9.8251249367886e-01 9.8211812233592e-01 9.8230694904481e-01 9.8325262505266e-01 9.8334790895553e-01 9.8352897237655e-01 9.8355321799486e-01 9.8374418657944e-01 9.8421812341207e-01 9.8437504121785e-01 9.8442548200833e-01 9.8452704272282e-01 9.8474416592180e-01 9.8477881447111e-01 9.8480705660883e-01 9.8483656120256e-01 9.8453621275682e-01 9.8346085390724e-01 9.8338773695367e-01 9.8331677149966e-01 9.8347630524761e-01 9.8420165043808e-01 9.8642456365394e-01 9.8674338861990e-01 9.8672735405960e-01 9.8670493558111e-01 6.3168786866617e-01 6.3168829151097e-01 6.3168957677866e-01 6.3169853850625e-01 6.3169982558628e-01 6.3170108417891e-01 6.3170279549987e-01 6.3170369773828e-01 6.3171097203710e-01 6.3172118705163e-01 6.3172847089868e-01 6.3173018873955e-01 6.3185072020486e-01 6.3207033667418e-01 6.3246420116539e-01 6.3299730897704e-01 6.3416024668329e-01 6.3562238406305e-01 6.3840795171449e-01 6.4373822756491e-01 6.5253916849650e-01 6.6045443212599e-01 6.7277955651824e-01 6.8585221904062e-01 7.0429990091422e-01 7.2027064340656e-01 7.3959627958206e-01 7.5853250806906e-01 7.8792242649081e-01 8.0634536242912e-01 8.2996520958708e-01 8.6550036539617e-01 8.8790364825299e-01 9.0387046616287e-01 9.1775064194508e-01 9.2308792699875e-01 9.2516750792460e-01 9.2701279379969e-01 9.2774871450915e-01 9.2987622019287e-01 9.3126469197624e-01 9.3204023400985e-01 9.3240410971142e-01 9.3276417141738e-01 9.3275009183689e-01 9.3274577547359e-01 9.3252142210694e-01 9.3279377863136e-01 9.3281334498579e-01 9.3293301747904e-01 9.3322006252219e-01 9.3330746488208e-01 9.3369108527839e-01 9.3414266711799e-01 9.3431755269266e-01 9.3455653549575e-01 9.3466068066617e-01 9.3472476312147e-01 9.3474655798470e-01 9.3485191707479e-01 9.3486194772830e-01 9.3486471105867e-01 9.3559483106415e-01 9.3593648054566e-01 9.3590165221226e-01 9.3526747097742e-01 9.3511614249708e-01 9.3495844130363e-01 9.3455273280983e-01 9.3440294248083e-01 6.3570363930354e-01 6.3570594488886e-01 6.3571055436266e-01 6.3571170696084e-01 6.3571488880092e-01 6.3571661745791e-01 6.3571759462288e-01 6.3572345972135e-01 6.3572394389580e-01 6.3573498233502e-01 6.3575249430460e-01 6.3590423074781e-01 6.3667530722990e-01 6.3783333466838e-01 6.3987522334896e-01 6.4228887385346e-01 6.4798905165805e-01 6.5202209015563e-01 6.5573210371735e-01 6.6022550505472e-01 6.6541439210063e-01 6.7406429885395e-01 6.8060256916840e-01 6.8872431560115e-01 7.0945717856949e-01 7.2398112675674e-01 7.4014106401128e-01 7.5529400168947e-01 7.8367073350792e-01 8.1808764236898e-01 8.4025937829779e-01 8.6209488865917e-01 8.9625225351365e-01 9.1009697268609e-01 9.1932241608022e-01 9.3204260069350e-01 9.4579541330027e-01 9.5316840007199e-01 9.6065045865099e-01 9.7357506587775e-01 9.7829970416877e-01 9.8224805358437e-01 9.8135258808900e-01 9.7919375635433e-01 9.7846112204599e-01 9.8083746479223e-01 9.8309177875672e-01 9.8415563586251e-01 9.8544157849067e-01 9.8452316404847e-01 9.8393802204723e-01 9.8341118316871e-01 9.8310465253200e-01 9.8272674916663e-01 9.8264586367522e-01 9.8258927694920e-01 9.8238946699332e-01 9.8219474633974e-01 9.8210789913907e-01 9.8239657186272e-01 9.8232647698325e-01 9.8226395066701e-01 9.8221692577220e-01 9.8220570636815e-01 9.8224064334537e-01 9.8253515018788e-01 9.8241982760261e-01 9.8225404257581e-01 9.8225386696996e-01 9.8223701139770e-01 9.8221487086873e-01 6.3351916623793e-01 6.3352299205154e-01 6.3352777369157e-01 6.3353163258559e-01 6.3353249002423e-01 6.3353720810733e-01 6.3355395911128e-01 6.3355764020209e-01 6.3355993502137e-01 6.3358444015562e-01 6.3385488352911e-01 6.3474320811586e-01 6.3610786495684e-01 6.3816237471211e-01 6.4258353647251e-01 6.4482968554386e-01 6.4762559564327e-01 6.5620822694905e-01 6.6621686566341e-01 6.7603322787620e-01 6.9095239421912e-01 7.0528245565138e-01 7.2711174782551e-01 7.3917291927851e-01 7.5161107096666e-01 7.8436183640058e-01 8.1221347201579e-01 8.3426990878115e-01 8.6164961486882e-01 8.8435840750294e-01 9.1391383811268e-01 9.3483974885718e-01 9.4761238568832e-01 9.5940417221827e-01 9.7405990584223e-01 9.7689286231458e-01 9.7900298886877e-01 9.8660154964161e-01 9.9146359247334e-01 9.9195041462468e-01 9.9079502999968e-01 9.9206815832174e-01 9.9215772403768e-01 9.9275337695980e-01 9.9393621492203e-01 9.9389296390810e-01 9.9381796472793e-01 9.9367155697519e-01 9.9364115905067e-01 9.9365124826066e-01 9.9374127786717e-01 9.9406846248649e-01 9.9434575573414e-01 9.9495075338183e-01 9.9513419066682e-01 9.9522275862717e-01 9.9512214607027e-01 9.9511834958639e-01 9.9511688545425e-01 9.9517194724212e-01 9.9540807233777e-01 9.9561863312823e-01 9.9579839061989e-01 6.2791258353258e-01 6.2791802329215e-01 6.2792528016403e-01 6.2795132673411e-01 6.2795253987731e-01 6.2797136008298e-01 6.2803638185520e-01 6.2803653323826e-01 6.2803836753031e-01 6.2828558522658e-01 6.2844885557971e-01 6.2967377754703e-01 6.3181287800775e-01 6.3440652442808e-01 6.3773329107430e-01 6.4399981961889e-01 6.4788619102298e-01 6.5157901360359e-01 6.6311803278724e-01 6.7308098784017e-01 6.8971376327032e-01 7.0758747867455e-01 7.3959179382208e-01 7.6387485365857e-01 7.7658639861728e-01 8.2029091470710e-01 8.5461701597221e-01 8.7263744495596e-01 8.9806655926499e-01 9.1115962930792e-01 9.2978330384919e-01 9.3360363771479e-01 9.4458567189534e-01 9.5000907278174e-01 9.5642362985487e-01 9.6042570704917e-01 9.6131946142874e-01 9.6089688451889e-01 9.6389450388367e-01 9.7159971306817e-01 9.7845326450879e-01 9.8273789623981e-01 9.8768515357078e-01 9.9210642797489e-01 9.9235407511716e-01 9.9225767374367e-01 9.9190744419380e-01 9.9196628249576e-01 9.9195927160975e-01 9.9157492500059e-01 9.9134773606315e-01 9.9154195802844e-01 9.9165728234995e-01 9.9170544564284e-01 9.9198746057358e-01 9.9238013239956e-01 9.9243238516628e-01 9.9243043329771e-01 9.9253790017885e-01 9.9283297585534e-01 9.9353484184700e-01 9.9354527607696e-01 9.9341244489356e-01 9.9313492006550e-01 9.9275356112841e-01 9.9268764493510e-01 9.9261788631784e-01 9.9255708373688e-01 9.9257821746220e-01 9.9258418068569e-01 6.3332478389158e-01 6.3333369984875e-01 6.3347078507903e-01 6.3379277640005e-01 6.3469589803260e-01 6.3760838809432e-01 6.4159176350553e-01 6.4735429489658e-01 6.5226366897614e-01 6.5596842403318e-01 6.6151124928780e-01 6.7203214755187e-01 6.7936417629636e-01 6.9757603608666e-01 7.1379091614275e-01 7.3167635479475e-01 7.5856170911026e-01 7.7865886502858e-01 8.0184852784300e-01 8.3730014978996e-01 8.5720488077194e-01 8.8736100364892e-01 9.0954187338836e-01 9.3756626443064e-01 9.5844755154918e-01 9.7531359004003e-01 9.9099906317023e-01 1.0117337742624e+00 1.0234852917402e+00 1.0441724057936e+00 1.0622000374617e+00 1.0757443003323e+00 1.0849108295601e+00 1.0908042810459e+00 1.0985312974979e+00 1.1072171937785e+00 1.1219420966064e+00 1.1269012583245e+00 1.1269239024481e+00 1.1268408829271e+00 1.1270747351788e+00 1.1275646132398e+00 1.1278988011080e+00 1.1277707000155e+00 1.1279945285096e+00 1.1282073281883e+00 1.1281619972746e+00 1.1280677061285e+00 1.1283626554171e+00 1.1285956520088e+00 1.1289716707995e+00 1.1304254519087e+00 1.1299398617000e+00 1.1298929912596e+00 1.1295370814116e+00 1.1284552612203e+00 1.1285887159656e+00 1.1287130327255e+00 1.1286884268782e+00 1.1285797737199e+00 1.1285992948386e+00 6.2878556575126e-01 6.2878906236731e-01 6.2879046443995e-01 6.2880063130106e-01 6.2880308760062e-01 6.2880344250130e-01 6.2881070000919e-01 6.2888680211180e-01 6.2956582911018e-01 6.3180153940374e-01 6.3529535179406e-01 6.4020832006002e-01 6.4479441827719e-01 6.5407326146271e-01 6.6633092230623e-01 6.8248557791998e-01 6.9808231155575e-01 7.2666922700718e-01 7.4415029093587e-01 7.6162216039816e-01 8.0190560394765e-01 8.2942531304033e-01 8.4586792022405e-01 8.5967624141565e-01 8.6565000796103e-01 8.6791639154708e-01 8.6802660880875e-01 8.6902062420335e-01 8.7494328713679e-01 8.7066087840113e-01 8.6670677712892e-01 8.6545877396106e-01 8.6559236436336e-01 8.6570758800338e-01 8.6587113569176e-01 8.6506855059871e-01 8.6391770602044e-01 8.6397162635102e-01 8.6399699975607e-01 8.6401697134370e-01 8.6406985854286e-01 8.6417147121613e-01 8.6417909928182e-01 8.6421423681706e-01 8.6426924906523e-01 8.6431546083859e-01 8.6434066049981e-01 8.6459703321285e-01 8.6460693573990e-01 8.6461687614800e-01 8.6474013544118e-01 8.6474342408564e-01 8.6482148133950e-01 6.3804736142884e-01 6.3804823482159e-01 6.3805162712043e-01 6.3805588006116e-01 6.3806565891480e-01 6.3807034222527e-01 6.3807552540327e-01 6.3811272502982e-01 6.3845622682741e-01 6.4022419382321e-01 6.4265760126177e-01 6.4500637093656e-01 6.4875391077591e-01 6.5484261385118e-01 6.6279780825761e-01 6.7307185617912e-01 6.8242017467958e-01 6.9683947287202e-01 7.1023886863166e-01 7.2448715921182e-01 7.4450660335042e-01 7.6944839001724e-01 7.9254842589876e-01 8.1750440943818e-01 8.3806884163854e-01 8.7036315099824e-01 8.9181199119146e-01 9.1220283366587e-01 9.3597640933162e-01 9.5867738801083e-01 9.7404982669029e-01 9.8739872803208e-01 9.9556374993758e-01 1.0075242970393e+00 1.0158597234426e+00 1.0222177570443e+00 1.0269384318280e+00 1.0315426506909e+00 1.0372840614886e+00 1.0436253842422e+00 1.0499728464437e+00 1.0618823708773e+00 1.0657137617107e+00 1.0665535853664e+00 1.0670037923159e+00 1.0692643342630e+00 1.0716438949395e+00 1.0725083819538e+00 1.0739965506631e+00 1.0767535339652e+00 1.0752413973218e+00 1.0744132953925e+00 1.0745616423617e+00 1.0750131468837e+00 1.0750557940116e+00 1.0749016971476e+00 1.0745899110889e+00 1.0749608059936e+00 1.0750350772115e+00 1.0751738539032e+00 1.0757479882814e+00 1.0763663907841e+00 1.0767955714179e+00 1.0770667614243e+00 1.0773797161840e+00 1.0774904290122e+00 1.0774850269177e+00 6.3427817301781e-01 6.3428493282580e-01 6.3426972168344e-01 6.3427384818164e-01 6.3426306072875e-01 6.3420897703185e-01 6.3411807905055e-01 6.3411922208007e-01 6.3411387218567e-01 6.3411087028123e-01 6.3409674921086e-01 6.3414086054151e-01 6.3479287905228e-01 6.3500461453535e-01 6.3569946710424e-01 6.3619351640337e-01 6.3913590605831e-01 6.4373039887920e-01 6.5495070414045e-01 6.7277226148801e-01 6.8994941410395e-01 7.2116311527109e-01 7.4346531700012e-01 7.5447095795457e-01 7.7122585035675e-01 7.8738122523780e-01 8.1418001601485e-01 8.3169856370778e-01 8.5500218093750e-01 8.6749304005047e-01 8.8271005195369e-01 8.9268938686742e-01 9.0197301391074e-01 9.1293007393031e-01 9.2090006393005e-01 9.3008322924868e-01 9.3632399145448e-01 9.4480097943329e-01 9.4915950758254e-01 9.5389175579718e-01 9.6140847308283e-01 9.6998295693313e-01 9.7293741710655e-01 9.7399266217101e-01 9.7457391441307e-01 9.8065934147666e-01 9.8515495713908e-01 9.8523916469549e-01 9.8486663308845e-01 9.8401346402890e-01 9.8251249367886e-01 9.8211812233592e-01 9.8230694904481e-01 9.8325262505266e-01 9.8334790895553e-01 9.8352897237655e-01 9.8355321799486e-01 9.8374418657944e-01 9.8421812341207e-01 9.8437504121785e-01 9.8442548200833e-01 9.8452704272282e-01 9.8474416592180e-01 9.8477881447111e-01 9.8480705660883e-01 9.8483656120256e-01 9.8453621275682e-01 9.8346085390724e-01 9.8338773695367e-01 9.8331677149966e-01 9.8347630524761e-01 9.8420165043808e-01 9.8642456365394e-01 9.8674338861990e-01 9.8672735405960e-01 9.8670493558111e-01 6.3168786866617e-01 6.3168829151097e-01 6.3168957677866e-01 6.3169853850625e-01 6.3169982558628e-01 6.3170108417891e-01 6.3170279549987e-01 6.3170369773828e-01 6.3171097203710e-01 6.3172118705163e-01 6.3172847089868e-01 6.3173018873955e-01 6.3185072020486e-01 6.3207033667418e-01 6.3246420116539e-01 6.3299730897704e-01 6.3416024668329e-01 6.3562238406305e-01 6.3840795171449e-01 6.4373822756491e-01 6.5253916849650e-01 6.6045443212599e-01 6.7277955651824e-01 6.8585221904062e-01 7.0429990091422e-01 7.2027064340656e-01 7.3959627958206e-01 7.5853250806906e-01 7.8792242649081e-01 8.0634536242912e-01 8.2996520958708e-01 8.6550036539617e-01 8.8790364825299e-01 9.0387046616287e-01 9.1775064194508e-01 9.2308792699875e-01 9.2516750792460e-01 9.2701279379969e-01 9.2774871450915e-01 9.2987622019287e-01 9.3126469197624e-01 9.3204023400985e-01 9.3240410971142e-01 9.3276417141738e-01 9.3275009183689e-01 9.3274577547359e-01 9.3252142210694e-01 9.3279377863136e-01 9.3281334498579e-01 9.3293301747904e-01 9.3322006252219e-01 9.3330746488208e-01 9.3369108527839e-01 9.3414266711799e-01 9.3431755269266e-01 9.3455653549575e-01 9.3466068066617e-01 9.3472476312147e-01 9.3474655798470e-01 9.3485191707479e-01 9.3486194772830e-01 9.3486471105867e-01 9.3559483106415e-01 9.3593648054566e-01 9.3590165221226e-01 9.3526747097742e-01 9.3511614249708e-01 9.3495844130363e-01 9.3455273280983e-01 9.3440294248083e-01 6.3570363930354e-01 6.3570594488886e-01 6.3571055436266e-01 6.3571170696084e-01 6.3571488880092e-01 6.3571661745791e-01 6.3571759462288e-01 6.3572345972135e-01 6.3572394389580e-01 6.3573498233502e-01 6.3575249430460e-01 6.3590423074781e-01 6.3667530722990e-01 6.3783333466838e-01 6.3987522334896e-01 6.4228887385346e-01 6.4798905165805e-01 6.5202209015563e-01 6.5573210371735e-01 6.6022550505472e-01 6.6541439210063e-01 6.7406429885395e-01 6.8060256916840e-01 6.8872431560115e-01 7.0945717856949e-01 7.2398112675674e-01 7.4014106401128e-01 7.5529400168947e-01 7.8367073350792e-01 8.1808764236898e-01 8.4025937829779e-01 8.6209488865917e-01 8.9625225351365e-01 9.1009697268609e-01 9.1932241608022e-01 9.3204260069350e-01 9.4579541330027e-01 9.5316840007199e-01 9.6065045865099e-01 9.7357506587775e-01 9.7829970416877e-01 9.8224805358437e-01 9.8135258808900e-01 9.7919375635433e-01 9.7846112204599e-01 9.8083746479223e-01 9.8309177875672e-01 9.8415563586251e-01 9.8544157849067e-01 9.8452316404847e-01 9.8393802204723e-01 9.8341118316871e-01 9.8310465253200e-01 9.8272674916663e-01 9.8264586367522e-01 9.8258927694920e-01 9.8238946699332e-01 9.8219474633974e-01 9.8210789913907e-01 9.8239657186272e-01 9.8232647698325e-01 9.8226395066701e-01 9.8221692577220e-01 9.8220570636815e-01 9.8224064334537e-01 9.8253515018788e-01 9.8241982760261e-01 9.8225404257581e-01 9.8225386696996e-01 9.8223701139770e-01 9.8221487086873e-01 6.3351916623793e-01 6.3352299205154e-01 6.3352777369157e-01 6.3353163258559e-01 6.3353249002423e-01 6.3353720810733e-01 6.3355395911128e-01 6.3355764020209e-01 6.3355993502137e-01 6.3358444015562e-01 6.3385488352911e-01 6.3474320811586e-01 6.3610786495684e-01 6.3816237471211e-01 6.4258353647251e-01 6.4482968554386e-01 6.4762559564327e-01 6.5620822694905e-01 6.6621686566341e-01 6.7603322787620e-01 6.9095239421912e-01 7.0528245565138e-01 7.2711174782551e-01 7.3917291927851e-01 7.5161107096666e-01 7.8436183640058e-01 8.1221347201579e-01 8.3426990878115e-01 8.6164961486882e-01 8.8435840750294e-01 9.1391383811268e-01 9.3483974885718e-01 9.4761238568832e-01 9.5940417221827e-01 9.7405990584223e-01 9.7689286231458e-01 9.7900298886877e-01 9.8660154964161e-01 9.9146359247334e-01 9.9195041462468e-01 9.9079502999968e-01 9.9206815832174e-01 9.9215772403768e-01 9.9275337695980e-01 9.9393621492203e-01 9.9389296390810e-01 9.9381796472793e-01 9.9367155697519e-01 9.9364115905067e-01 9.9365124826066e-01 9.9374127786717e-01 9.9406846248649e-01 9.9434575573414e-01 9.9495075338183e-01 9.9513419066682e-01 9.9522275862717e-01 9.9512214607027e-01 9.9511834958639e-01 9.9511688545425e-01 9.9517194724212e-01 9.9540807233777e-01 9.9561863312823e-01 9.9579839061989e-01 6.2791258353258e-01 6.2791802329215e-01 6.2792528016403e-01 6.2795132673411e-01 6.2795253987731e-01 6.2797136008298e-01 6.2803638185520e-01 6.2803653323826e-01 6.2803836753031e-01 6.2828558522658e-01 6.2844885557971e-01 6.2967377754703e-01 6.3181287800775e-01 6.3440652442808e-01 6.3773329107430e-01 6.4399981961889e-01 6.4788619102298e-01 6.5157901360359e-01 6.6311803278724e-01 6.7308098784017e-01 6.8971376327032e-01 7.0758747867455e-01 7.3959179382208e-01 7.6387485365857e-01 7.7658639861728e-01 8.2029091470710e-01 8.5461701597221e-01 8.7263744495596e-01 8.9806655926499e-01 9.1115962930792e-01 9.2978330384919e-01 9.3360363771479e-01 9.4458567189534e-01 9.5000907278174e-01 9.5642362985487e-01 9.6042570704917e-01 9.6131946142874e-01 9.6089688451889e-01 9.6389450388367e-01 9.7159971306817e-01 9.7845326450879e-01 9.8273789623981e-01 9.8768515357078e-01 9.9210642797489e-01 9.9235407511716e-01 9.9225767374367e-01 9.9190744419380e-01 9.9196628249576e-01 9.9195927160975e-01 9.9157492500059e-01 9.9134773606315e-01 9.9154195802844e-01 9.9165728234995e-01 9.9170544564284e-01 9.9198746057358e-01 9.9238013239956e-01 9.9243238516628e-01 9.9243043329771e-01 9.9253790017885e-01 9.9283297585534e-01 9.9353484184700e-01 9.9354527607696e-01 9.9341244489356e-01 9.9313492006550e-01 9.9275356112841e-01 9.9268764493510e-01 9.9261788631784e-01 9.9255708373688e-01 9.9257821746220e-01 9.9258418068569e-01 6.3332478389158e-01 6.3333369984875e-01 6.3347078507903e-01 6.3379277640005e-01 6.3469589803260e-01 6.3760838809432e-01 6.4159176350553e-01 6.4735429489658e-01 6.5226366897614e-01 6.5596842403318e-01 6.6151124928780e-01 6.7203214755187e-01 6.7936417629636e-01 6.9757603608666e-01 7.1379091614275e-01 7.3167635479475e-01 7.5856170911026e-01 7.7865886502858e-01 8.0184852784300e-01 8.3730014978996e-01 8.5720488077194e-01 8.8736100364892e-01 9.0954187338836e-01 9.3756626443064e-01 9.5844755154918e-01 9.7531359004003e-01 9.9099906317023e-01 1.0117337742624e+00 1.0234852917402e+00 1.0441724057936e+00 1.0622000374617e+00 1.0757443003323e+00 1.0849108295601e+00 1.0908042810459e+00 1.0985312974979e+00 1.1072171937785e+00 1.1219420966064e+00 1.1269012583245e+00 1.1269239024481e+00 1.1268408829271e+00 1.1270747351788e+00 1.1275646132398e+00 1.1278988011080e+00 1.1277707000155e+00 1.1279945285096e+00 1.1282073281883e+00 1.1281619972746e+00 1.1280677061285e+00 1.1283626554171e+00 1.1285956520088e+00 1.1289716707995e+00 1.1304254519087e+00 1.1299398617000e+00 1.1298929912596e+00 1.1295370814116e+00 1.1284552612203e+00 1.1285887159656e+00 1.1287130327255e+00 1.1286884268782e+00 1.1285797737199e+00 1.1285992948386e+00 6.2878556575126e-01 6.2878906236731e-01 6.2879046443995e-01 6.2880063130106e-01 6.2880308760062e-01 6.2880344250130e-01 6.2881070000919e-01 6.2888680211180e-01 6.2956582911018e-01 6.3180153940374e-01 6.3529535179406e-01 6.4020832006002e-01 6.4479441827719e-01 6.5407326146271e-01 6.6633092230623e-01 6.8248557791998e-01 6.9808231155575e-01 7.2666922700718e-01 7.4415029093587e-01 7.6162216039816e-01 8.0190560394765e-01 8.2942531304033e-01 8.4586792022405e-01 8.5967624141565e-01 8.6565000796103e-01 8.6791639154708e-01 8.6802660880875e-01 8.6902062420335e-01 8.7494328713679e-01 8.7066087840113e-01 8.6670677712892e-01 8.6545877396106e-01 8.6559236436336e-01 8.6570758800338e-01 8.6587113569176e-01 8.6506855059871e-01 8.6391770602044e-01 8.6397162635102e-01 8.6399699975607e-01 8.6401697134370e-01 8.6406985854286e-01 8.6417147121613e-01 8.6417909928182e-01 8.6421423681706e-01 8.6426924906523e-01 8.6431546083859e-01 8.6434066049981e-01 8.6459703321285e-01 8.6460693573990e-01 8.6461687614800e-01 8.6474013544118e-01 8.6474342408564e-01 8.6482148133950e-01 + -3.4741299135038e-01 -3.4742298995937e-01 -3.4742586857438e-01 -3.4742947530437e-01 -3.4743775904122e-01 -3.4744172174100e-01 -3.4746940515277e-01 -3.4802073277326e-01 -3.4925374078606e-01 -3.5196376905905e-01 -3.5473723794322e-01 -3.5553965783224e-01 -3.5534909849446e-01 -3.5622348488327e-01 -3.5956136574048e-01 -3.6298425460413e-01 -3.6386330148185e-01 -3.6287894868465e-01 -3.6127134647859e-01 -3.6100645633442e-01 -3.6187542684687e-01 -3.6213898942184e-01 -3.6195301287924e-01 -3.6095564376462e-01 -3.5951565638432e-01 -3.5627204118200e-01 -3.5489319343051e-01 -3.5340539094395e-01 -3.5048623637709e-01 -3.4444834317468e-01 -3.3840625774675e-01 -3.3183668262251e-01 -3.2471599693918e-01 -3.1306704814132e-01 -3.0637890175524e-01 -2.9648362284488e-01 -2.7977407541369e-01 -2.6542475599309e-01 -2.5812824548279e-01 -2.4831663609466e-01 -2.3698996965574e-01 -2.2096545696594e-01 -2.1588420777617e-01 -2.1433343228540e-01 -2.1197153960366e-01 -2.1281665959929e-01 -2.1139788314949e-01 -2.1106822828542e-01 -2.1161848888569e-01 -2.1287738798915e-01 -2.1406123559970e-01 -2.1547039826785e-01 -2.1502847492853e-01 -2.1424856143506e-01 -2.1329056110862e-01 -2.1313036871396e-01 -2.1346233223256e-01 -2.1321091088342e-01 -2.1327592169044e-01 -2.1304039957713e-01 -2.1212028826989e-01 -2.1154887516597e-01 -2.1130574204128e-01 -2.1132770746956e-01 -2.1135557848197e-01 -2.1127239589214e-01 -2.1128056770687e-01 -2.6104683665682e-01 -2.6106183308669e-01 -2.6104830283563e-01 -2.6107179541423e-01 -2.6104945612564e-01 -2.6097806858307e-01 -2.6088100903106e-01 -2.6088172201031e-01 -2.6087754912545e-01 -2.6091151236379e-01 -2.6118266457391e-01 -2.6216799625652e-01 -2.6092204335353e-01 -2.5779109965745e-01 -2.5211758167469e-01 -2.4756066588622e-01 -2.4060111822533e-01 -2.3925523598753e-01 -2.4296566332217e-01 -2.5039324195052e-01 -2.5654214259183e-01 -2.7059253245040e-01 -2.8855270805630e-01 -3.0168743403861e-01 -3.2335786986144e-01 -3.4181300080577e-01 -3.6790527947257e-01 -3.8214979439881e-01 -4.0742999757874e-01 -4.2769345511447e-01 -4.6119641622800e-01 -4.8262684267282e-01 -4.9813097841427e-01 -5.1722280250983e-01 -5.3156069103886e-01 -5.4827202851065e-01 -5.6121502128301e-01 -5.8292318480287e-01 -5.9659024816869e-01 -6.0770131133588e-01 -6.1706080884520e-01 -6.2391866438293e-01 -6.2710645408225e-01 -6.2913215465331e-01 -6.2985320386549e-01 -6.3041316869636e-01 -6.2900707733978e-01 -6.2794496519902e-01 -6.2771632566084e-01 -6.2744193322067e-01 -6.2799607000633e-01 -6.2933810794957e-01 -6.3015529371824e-01 -6.3121175933179e-01 -6.3134225021562e-01 -6.3146181634433e-01 -6.3177408224071e-01 -6.3190520136422e-01 -6.3213993842600e-01 -6.3233899012266e-01 -6.3238021049084e-01 -6.3242770602794e-01 -6.3251495367934e-01 -6.3252931912887e-01 -6.3254565075739e-01 -6.3252150625123e-01 -6.3239119178502e-01 -6.3210370913252e-01 -6.3210311375088e-01 -6.3209629754809e-01 -6.3217894170199e-01 -6.3256420873579e-01 -6.3347571461491e-01 -6.3355986699352e-01 -6.3353254378246e-01 -6.3350483619577e-01 -1.9160368171700e-01 -1.9160426796120e-01 -1.9160604967295e-01 -1.9161746472115e-01 -1.9161924641095e-01 -1.9162153143328e-01 -1.9162888916543e-01 -1.9163221712909e-01 -1.9163928069729e-01 -1.9165085238922e-01 -1.9164793581207e-01 -1.9161428973730e-01 -1.9172166647197e-01 -1.9187178607467e-01 -1.9197519205856e-01 -1.9201790759492e-01 -1.9242082468705e-01 -1.9306025584899e-01 -1.9380329648959e-01 -1.9188117734461e-01 -1.8937260965996e-01 -1.8850569809376e-01 -1.8750711096181e-01 -1.8499362369118e-01 -1.7172756368459e-01 -1.5452234736577e-01 -1.3379360632138e-01 -1.1363084502979e-01 -8.2909735631181e-02 -6.5823201088614e-02 -4.7881291358133e-02 -2.5883171736488e-02 -1.5053776374958e-02 -1.0800013835819e-02 -7.6858831508118e-03 -4.8062310072454e-03 -3.3165678220337e-03 -2.0968184065323e-03 -1.5061829608791e-03 -4.8760671406609e-04 -1.2698816603405e-04 -1.8065502327762e-04 -2.0993167918400e-04 -2.3520987639782e-04 -2.3314704575146e-04 -2.2599595595379e-04 -1.0806587773076e-04 -1.4231948328539e-04 -1.4506457065050e-04 -1.5584965227149e-04 -1.8425326888308e-04 -2.0274676578243e-04 -2.4762472138581e-04 -2.9784588074248e-04 -3.6963459890326e-04 -4.4541738980567e-04 -4.5163830979720e-04 -3.2593295650736e-04 -3.2496323101102e-04 -3.3270560847442e-04 -3.0266469053201e-04 -2.5082697865565e-04 -1.2759041843532e-05 2.6759485063888e-04 3.1201882574344e-04 3.9956751337622e-03 5.4124613301785e-03 5.4494137363118e-03 5.6176648314661e-03 5.6447144146668e-03 -3.4361265350781e-01 -3.4362226698979e-01 -3.4364148212473e-01 -3.4364628587616e-01 -3.4365707891646e-01 -3.4366428153504e-01 -3.4366991704624e-01 -3.4367422758590e-01 -3.4367458328927e-01 -3.4370831563468e-01 -3.4386891388928e-01 -3.4474090558565e-01 -3.4653943099190e-01 -3.4890748930485e-01 -3.5175067490581e-01 -3.5464635735440e-01 -3.6018882050961e-01 -3.6322203237763e-01 -3.6573133250072e-01 -3.6822271874343e-01 -3.7049610290840e-01 -3.7234534243196e-01 -3.7301585475339e-01 -3.7327203777361e-01 -3.7496117555350e-01 -3.7562288913106e-01 -3.7591308961462e-01 -3.7604303622446e-01 -3.7532681906473e-01 -3.7520278372374e-01 -3.7603333491084e-01 -3.7703056768569e-01 -3.7791351593850e-01 -3.7862631613605e-01 -3.8058031091151e-01 -3.8576049120108e-01 -3.8874187265417e-01 -3.8992567555851e-01 -3.8704952902492e-01 -3.7749201619466e-01 -3.6716046925916e-01 -3.5564945190730e-01 -3.5148513891085e-01 -3.4756953668324e-01 -3.4235637703321e-01 -3.4296155812904e-01 -3.4210177322328e-01 -3.4003437913914e-01 -3.3972912312453e-01 -3.3977995954672e-01 -3.3960676184614e-01 -3.4008068562190e-01 -3.4145472230758e-01 -3.4283020572233e-01 -3.4320792996140e-01 -3.4378171890102e-01 -3.4613562340634e-01 -3.4739288209983e-01 -3.4770131207276e-01 -3.4778962205101e-01 -3.4824393918702e-01 -3.4850870173464e-01 -3.4876503914904e-01 -3.4916977933858e-01 -3.4930333235821e-01 -3.4861121311824e-01 -3.4856142836913e-01 -3.4856031704472e-01 -3.4852053430452e-01 -3.4856163548788e-01 -3.4851457626809e-01 -2.0383431816355e-01 -2.0383746401662e-01 -2.0386159775290e-01 -2.0388272598630e-01 -2.0388741922731e-01 -2.0391323476713e-01 -2.0400476486785e-01 -2.0400816302613e-01 -2.0400045032424e-01 -2.0403016384361e-01 -2.0426065743126e-01 -2.0494802011571e-01 -2.0598229206461e-01 -2.0716389918610e-01 -2.0911994000004e-01 -2.0981185804214e-01 -2.1035615791081e-01 -2.1207278567079e-01 -2.1386643122994e-01 -2.1559628792184e-01 -2.1695712392129e-01 -2.1662271952172e-01 -2.1230021798055e-01 -2.0971275886775e-01 -2.0637388089572e-01 -1.9950702383065e-01 -1.9623280078722e-01 -1.9425041701204e-01 -1.8933946084020e-01 -1.8528867281497e-01 -1.7759198824288e-01 -1.6790341786979e-01 -1.6363067154418e-01 -1.5976906906141e-01 -1.5161738302434e-01 -1.4616189657099e-01 -1.4121574235595e-01 -1.3583324652475e-01 -1.2952567092123e-01 -1.2789291822434e-01 -1.2467788158695e-01 -1.2195835143341e-01 -1.2147667841718e-01 -1.2118884592377e-01 -1.2091388834635e-01 -1.2091008576845e-01 -1.2100454739317e-01 -1.2116572472024e-01 -1.2111122167939e-01 -1.2093523005580e-01 -1.2069928826896e-01 -1.2046259503638e-01 -1.1978594939550e-01 -1.1778408390441e-01 -1.1777880519248e-01 -1.1803226631610e-01 -1.1806783299093e-01 -1.1806438982844e-01 -1.1796181436181e-01 -1.1769088215987e-01 -1.1682721044850e-01 -1.1630445632617e-01 -1.1600880028366e-01 -3.6345337553340e-01 -3.6343368569298e-01 -3.6343823370272e-01 -3.6329717668322e-01 -3.6327371721071e-01 -3.6333278460025e-01 -3.6364366391887e-01 -3.6364488140428e-01 -3.6345807969698e-01 -3.6154905345063e-01 -3.6180176751293e-01 -3.6550994824618e-01 -3.7116085027131e-01 -3.7705660884004e-01 -3.8371181902355e-01 -3.9336903865472e-01 -3.9737722125436e-01 -4.0119242535495e-01 -4.0829064604202e-01 -4.0762478833095e-01 -4.0638251587155e-01 -4.0696522153567e-01 -4.0712246774317e-01 -4.1027332350862e-01 -4.1190077148352e-01 -4.1917229897830e-01 -4.3157797461672e-01 -4.4204583912527e-01 -4.6684532665342e-01 -4.8941735879286e-01 -5.1892283905256e-01 -5.2243883350146e-01 -5.3438906540641e-01 -5.3467134119125e-01 -5.3198915242606e-01 -5.2766149721733e-01 -5.2162174812922e-01 -5.1679518552594e-01 -5.0888227178301e-01 -4.9518404275414e-01 -4.8462058181828e-01 -4.7906530763346e-01 -4.7246402591372e-01 -4.6548220528354e-01 -4.6198340579346e-01 -4.6325032895033e-01 -4.6375065825379e-01 -4.6552283639010e-01 -4.6814040913321e-01 -4.6896010920119e-01 -4.7046746931518e-01 -4.7119690673938e-01 -4.7189163147779e-01 -4.7247175806729e-01 -4.7376499038522e-01 -4.7449650436393e-01 -4.7505457016624e-01 -4.7518717896558e-01 -4.7535345131012e-01 -4.7570937716390e-01 -4.7583022388371e-01 -4.7586853965857e-01 -4.7671779902135e-01 -4.7755528117277e-01 -4.7824687448270e-01 -4.7873952203298e-01 -4.7876837847059e-01 -4.7879641984776e-01 -4.7885443847396e-01 -4.7893122934140e-01 -2.6030565609581e-01 -2.6073060930951e-01 -2.6123713054134e-01 -2.6201590129642e-01 -2.6350265399352e-01 -2.6703988288760e-01 -2.7044216555938e-01 -2.7435820411968e-01 -2.7710281394413e-01 -2.7941442904910e-01 -2.8193901317647e-01 -2.8485507431567e-01 -2.8601164188821e-01 -2.8837431619498e-01 -2.8918321178774e-01 -2.9050236396167e-01 -2.9472774305716e-01 -2.9975504908294e-01 -3.0432303400493e-01 -3.1500097580710e-01 -3.2279562796686e-01 -3.3865869234636e-01 -3.5393322675224e-01 -3.6942009936983e-01 -3.7797026726680e-01 -3.8373202817107e-01 -3.8881604748848e-01 -3.9567897714699e-01 -3.9944499577592e-01 -4.0380093191181e-01 -4.0083644495573e-01 -3.9396980599844e-01 -3.8375691283842e-01 -3.7620525595325e-01 -3.6805996303679e-01 -3.5799013468257e-01 -3.4705668375713e-01 -3.4482082155269e-01 -3.4487593711605e-01 -3.4382935045051e-01 -3.4335101867638e-01 -3.4348059841992e-01 -3.4422498556726e-01 -3.4468820443441e-01 -3.4484194795855e-01 -3.4601257633574e-01 -3.4664349318848e-01 -3.4736717361941e-01 -3.4779910496150e-01 -3.4802030829110e-01 -3.4814302449850e-01 -3.4806105523818e-01 -3.4811884544643e-01 -3.4818369400338e-01 -3.4812161878442e-01 -3.4771621875509e-01 -3.4789666950960e-01 -3.4802086783967e-01 -3.4823551565937e-01 -3.4872883955759e-01 -3.4893451503318e-01 -1.6132081115372e-01 -1.6132812676398e-01 -1.6133105865879e-01 -1.6135229282362e-01 -1.6135741615815e-01 -1.6136407884614e-01 -1.6156090789828e-01 -1.6174285385233e-01 -1.6255909991470e-01 -1.6441980285412e-01 -1.6640894932034e-01 -1.6843892975354e-01 -1.6975711259324e-01 -1.7221783940958e-01 -1.7377584971485e-01 -1.7377844761951e-01 -1.7366141742769e-01 -1.7266918175603e-01 -1.6778036146105e-01 -1.5926425854896e-01 -1.3136702861036e-01 -1.1110050612818e-01 -9.9868000643643e-02 -8.8160308524914e-02 -7.8829914134746e-02 -6.9779122987848e-02 -6.8154964213353e-02 -6.6194869347653e-02 -5.2362226386565e-02 -4.9347009430489e-02 -4.8357027555541e-02 -4.7668345931218e-02 -4.5120086015906e-02 -3.8944715500222e-02 -3.5108094121985e-02 -3.4651342739689e-02 -3.3925215920336e-02 -3.3882615486176e-02 -3.3894556765797e-02 -3.3896518647867e-02 -3.3896782624934e-02 -3.3901735765173e-02 -3.3905248857175e-02 -3.3909792464386e-02 -3.3916031664635e-02 -3.3918846992142e-02 -3.3924367165817e-02 -3.3952855978121e-02 -3.3953230140271e-02 -3.3952534530311e-02 -3.3964181585636e-02 -3.3964842093908e-02 -3.3978547970078e-02 -7.4177931416361e-01 -7.4171887675382e-01 -7.4169390016371e-01 -7.4166260303942e-01 -7.4159070902516e-01 -7.4155631084030e-01 -7.4138387066088e-01 -7.3801213234905e-01 -7.3083327523436e-01 -7.1586059611098e-01 -6.9751694520108e-01 -6.7922887813241e-01 -6.5399992142446e-01 -6.1501166972048e-01 -5.7824137870407e-01 -5.3820527084269e-01 -5.0595239441436e-01 -4.5932023451731e-01 -4.1817099632198e-01 -3.7933738110441e-01 -3.3027659973255e-01 -2.7266669481702e-01 -2.2174454422573e-01 -1.7265116197248e-01 -1.3207745463426e-01 -7.1989985999532e-02 -3.8404930235536e-02 -7.1313830934374e-03 2.9380276970374e-02 6.1315131516009e-02 8.1208399005213e-02 8.9699894770587e-02 8.4936403754967e-02 8.0822736834278e-02 7.5980954574559e-02 6.9456953733158e-02 5.2050803167918e-02 4.0250128902526e-02 3.9183836902080e-02 3.3753553451865e-02 2.4786004173769e-02 1.9960724139841e-02 1.2662809365492e-02 1.1853799668200e-02 2.5640435173972e-03 5.1702248645159e-03 -2.6747048612294e-03 -4.6706276955619e-03 -1.8139752463024e-03 1.3291759009024e-03 7.1298994675637e-03 8.4119650176873e-03 9.8355964855379e-03 1.6232452739692e-02 1.5837276724179e-02 1.5835624282114e-02 1.6363653114875e-02 1.7973345885808e-02 1.7984895716396e-02 1.7715525143012e-02 1.7844954659141e-02 1.8619465702384e-02 1.9343673280994e-02 1.9978744744256e-02 2.0735253934457e-02 2.0980246137682e-02 2.1043612981688e-02 -7.4915323362262e-01 -7.4899109321037e-01 -7.4899458513892e-01 -7.4875271862381e-01 -7.4891328178443e-01 -7.4952657975794e-01 -7.5026939228886e-01 -7.5026637546629e-01 -7.5027053582847e-01 -7.4989183134389e-01 -7.4684578179010e-01 -7.3507071434198e-01 -7.3486417704580e-01 -7.3595411329607e-01 -7.2598451354156e-01 -7.1965683470761e-01 -6.9960111147056e-01 -6.7514379522975e-01 -6.2404383289925e-01 -5.5607761532897e-01 -5.0092096634841e-01 -4.1322019945877e-01 -3.5372233419024e-01 -3.2462847601941e-01 -2.8165272703670e-01 -2.4341967535980e-01 -1.8592956062214e-01 -1.5293647419753e-01 -1.0937930293190e-01 -8.4661974510305e-02 -5.3845320250284e-02 -3.6190333932971e-02 -2.0904415001157e-02 -4.2708069737535e-03 6.7167805935833e-03 2.1457995404080e-02 3.2769715048744e-02 4.6743235842536e-02 5.7294869613323e-02 6.9159667515935e-02 8.2732153618863e-02 9.3332281721295e-02 9.7513763351757e-02 9.5894898452741e-02 9.5436661103947e-02 1.0016679126298e-01 9.7780281094886e-02 9.6320971770843e-02 9.5742233704818e-02 9.6251104152310e-02 1.0021485589085e-01 1.0517369934384e-01 1.0848003756659e-01 1.1231141230731e-01 1.1293190002951e-01 1.1329494143972e-01 1.1505741643831e-01 1.1529693884339e-01 1.1545041293895e-01 1.1624520811525e-01 1.1637373759910e-01 1.1635904090278e-01 1.1631260399124e-01 1.1633165932443e-01 1.1636215924049e-01 1.1600914843923e-01 1.1520060804020e-01 1.1373970295289e-01 1.1353255196129e-01 1.1336610887771e-01 1.1336695624732e-01 1.1387816441997e-01 1.1438432566740e-01 1.1451248245568e-01 1.1438020404701e-01 1.1423183228069e-01 -7.7598084966011e-01 -7.7597742895550e-01 -7.7596703267048e-01 -7.7592649256129e-01 -7.7591609605599e-01 -7.7590065274160e-01 -7.7572739909675e-01 -7.7571906263647e-01 -7.7575600589481e-01 -7.7570137881457e-01 -7.7605723018274e-01 -7.7719078990779e-01 -7.7537132164002e-01 -7.7330889179039e-01 -7.7395085737200e-01 -7.7505108413600e-01 -7.6093895168716e-01 -7.4280751297603e-01 -7.1801146647600e-01 -6.7491820849451e-01 -6.1544018644506e-01 -5.7532494877147e-01 -5.2042405517101e-01 -4.7138441373556e-01 -4.1148271073616e-01 -3.6327430006546e-01 -3.0834448373146e-01 -2.5751871196093e-01 -1.7580470977722e-01 -1.2433595187745e-01 -6.4040284785202e-02 2.3461313771698e-02 7.8092087676862e-02 1.1673078321795e-01 1.5021743565471e-01 1.6063196095346e-01 1.5835444840830e-01 1.5551171136760e-01 1.4590036565806e-01 1.3178597213243e-01 1.3032947707868e-01 1.3069105311686e-01 1.3038128128820e-01 1.3083688742801e-01 1.3028684684946e-01 1.2863566385918e-01 1.2071938105809e-01 1.2274324130066e-01 1.2296436480230e-01 1.2338640605054e-01 1.2421847130981e-01 1.2443827548118e-01 1.2551485991935e-01 1.2705995378520e-01 1.2829311181047e-01 1.2997790335356e-01 1.3027425422049e-01 1.2879233323489e-01 1.2880596908697e-01 1.2906126482421e-01 1.2904430416890e-01 1.2840525793510e-01 1.2417777294328e-01 -1.2344014337348e-01 -1.2425449492136e-01 -1.2601119337251e-01 -1.2707621391030e-01 -1.2795036523198e-01 -1.3128659399098e-01 -1.3153308872384e-01 -7.4312566808323e-01 -7.4312324836304e-01 -7.4311841166978e-01 -7.4311720245664e-01 -7.4310955832147e-01 -7.4310774520403e-01 -7.4307369813439e-01 -7.4303600744290e-01 -7.4303289701560e-01 -7.4282409439035e-01 -7.4187934333041e-01 -7.3697645059977e-01 -7.2771360198107e-01 -7.1549691194800e-01 -7.0088457574716e-01 -6.8576276641401e-01 -6.5622479991345e-01 -6.3999936429974e-01 -6.2569638561457e-01 -6.0679604121067e-01 -5.8701994088067e-01 -5.5745022403017e-01 -5.3488288560503e-01 -5.0730485288213e-01 -4.4715706306570e-01 -4.0840876108054e-01 -3.7077248219784e-01 -3.3840375918357e-01 -2.7468619599343e-01 -2.0391742242693e-01 -1.6074393147739e-01 -1.2216505180706e-01 -6.4447846752549e-02 -4.4138853199140e-02 -3.2881120230018e-02 -9.9305088816490e-03 8.3949427135199e-03 1.5661234415070e-02 1.0098961008577e-02 9.0382060174166e-03 -5.4109244341757e-03 -1.5357905786061e-02 -2.2643533879266e-02 -3.0951988324331e-02 -3.7987328733294e-02 -3.6683108510957e-02 -3.9973635881767e-02 -4.5921365827994e-02 -4.5539641232875e-02 -4.5086005593015e-02 -4.5750133445820e-02 -4.4939951564783e-02 -4.1200035664825e-02 -3.9994176590717e-02 -3.9940599799100e-02 -3.9574198541253e-02 -3.5833818518683e-02 -3.4871522670080e-02 -3.4456588741296e-02 -3.3818280871817e-02 -3.3591997639774e-02 -3.3312433504786e-02 -3.3161007299466e-02 -3.2936807987280e-02 -3.3275035828979e-02 -3.3925942366202e-02 -3.4215008374769e-02 -3.4378302625838e-02 -3.4609325264590e-02 -3.4806862252635e-02 -3.5081638887080e-02 -8.4449959873575e-01 -8.4447058973813e-01 -8.4446652606290e-01 -8.4446592880768e-01 -8.4446579606866e-01 -8.4446506547247e-01 -8.4446246891069e-01 -8.4460264795606e-01 -8.4473735975302e-01 -8.4439963524370e-01 -8.4194965990012e-01 -8.3449709124753e-01 -8.2127155674271e-01 -8.0523683070978e-01 -7.6856297497295e-01 -7.4935701883821e-01 -7.3313628195084e-01 -6.8718085705869e-01 -6.3871275807693e-01 -5.9876355735518e-01 -5.4384383288640e-01 -4.9505309286695e-01 -4.2716010029071e-01 -3.9267943565723e-01 -3.5795726612291e-01 -2.7371901773152e-01 -2.0842287672833e-01 -1.6055388015318e-01 -1.0421264427334e-01 -5.7398449822279e-02 -2.6688907412420e-03 2.7557333946124e-02 4.3208989385986e-02 5.7403671988482e-02 6.6540275381401e-02 5.8302862978162e-02 5.3731852021930e-02 5.7888956308909e-02 5.1749498291201e-02 4.9575247529311e-02 3.9061944530924e-02 3.0705630029236e-02 2.5903796028172e-02 2.2292791225175e-02 1.8203727829584e-02 1.7944152233947e-02 1.8536842405375e-02 1.8791180662893e-02 1.8722528905500e-02 1.8637871421746e-02 1.9113145212178e-02 1.9800676961540e-02 2.0242806082871e-02 2.0778177796337e-02 2.1248705468157e-02 2.1838227023349e-02 2.1741068325842e-02 2.1743738044309e-02 2.1705713792818e-02 2.1771413972382e-02 2.1899967678090e-02 2.2228093025471e-02 2.2138686596593e-02 -7.2613575470794e-01 -7.2622632254208e-01 -7.2621982939991e-01 -7.2684625972902e-01 -7.2694509885558e-01 -7.2673311929415e-01 -7.2556667302497e-01 -7.2556469427344e-01 -7.2633996762456e-01 -7.3453001986949e-01 -7.3267462349153e-01 -7.2099676310315e-01 -7.0095734791194e-01 -6.8035439476683e-01 -6.5524252759400e-01 -6.1826619382888e-01 -5.9994320015337e-01 -5.8005972957913e-01 -5.1655471925814e-01 -4.8132269759367e-01 -4.3202857065177e-01 -3.8418534115037e-01 -3.0758769652061e-01 -2.5495295288066e-01 -2.3034015553783e-01 -1.5112980123052e-01 -9.3765498158738e-02 -6.1678280334162e-02 -1.4407432599378e-02 1.0991518587031e-02 4.4064632817555e-02 4.9859246200380e-02 6.1951751820239e-02 5.9827395092862e-02 5.8112181097139e-02 5.8940940225390e-02 5.1819627920139e-02 4.2812570571524e-02 3.4280316755323e-02 1.1333451037120e-02 3.4639597954155e-03 4.8186532991366e-03 -2.0244349218142e-03 -1.2965486561966e-02 -1.5295732138837e-02 -1.0317986490050e-02 -1.0712319366741e-02 -7.9093447324709e-03 -2.7087207479093e-03 -3.5527391136142e-03 -2.6038011559179e-03 -1.2718353263626e-03 5.7038563352366e-04 2.2791537077659e-03 5.4375660443947e-03 5.7930071257990e-03 7.3133181975800e-03 7.7206574571925e-03 8.2634959598747e-03 9.0666128499634e-03 8.8542230932205e-03 9.0147367541661e-03 1.2082342386341e-02 1.4032527687331e-02 1.5664885218657e-02 1.6875839506432e-02 1.7042380229556e-02 1.7114165161759e-02 1.7163538899382e-02 1.7511835822981e-02 -8.1549568646856e-01 -8.1156246010463e-01 -8.0718740793192e-01 -8.0075017615090e-01 -7.8900478883201e-01 -7.6116472986742e-01 -7.3426132822184e-01 -7.0152929690638e-01 -6.7636169842367e-01 -6.5212341453308e-01 -6.2581408327688e-01 -5.7828176160648e-01 -5.4971545023635e-01 -4.8707459062164e-01 -4.3331550654763e-01 -3.8374245815237e-01 -3.1312103214724e-01 -2.6341241982374e-01 -2.1183211984110e-01 -1.3711060098166e-01 -9.6805154616412e-02 -3.7255382991132e-02 6.9161677924916e-03 5.7796623772060e-02 9.1510201071058e-02 1.1363650844760e-01 1.2943217327104e-01 1.5560535021993e-01 1.6818293907369e-01 1.8679952743608e-01 1.9122666669364e-01 1.8474555905554e-01 1.7615096945251e-01 1.6736822329979e-01 1.5998353079586e-01 1.4931608240661e-01 1.4029153584372e-01 1.3843591180981e-01 1.3914935145847e-01 1.3700772154946e-01 1.3392710669142e-01 1.3461794220837e-01 1.3632541335955e-01 1.3586732784154e-01 1.3621289395684e-01 1.3883030035757e-01 1.3967728415008e-01 1.3962505800831e-01 1.4097753465646e-01 1.4170279074333e-01 1.4213322330813e-01 1.4472562054031e-01 1.4471279902179e-01 1.4457112070962e-01 1.4354304879936e-01 1.4153997221412e-01 1.4249774081713e-01 1.4317072245746e-01 1.4407811201986e-01 1.4425635112746e-01 1.4532307256495e-01 -8.7258775712178e-01 -8.7255359574022e-01 -8.7253990447319e-01 -8.7244074026630e-01 -8.7241681266308e-01 -8.7225773103345e-01 -8.6712479953458e-01 -8.6319133777397e-01 -8.4901280563014e-01 -8.1901641686752e-01 -7.8765114548045e-01 -7.5083924697779e-01 -7.1872996010261e-01 -6.3404024325619e-01 -5.3926619165729e-01 -4.7486113948520e-01 -4.2096409688626e-01 -3.2735345637379e-01 -2.5671845859085e-01 -1.9266020347020e-01 -8.1324771876586e-02 -1.2278910266763e-02 4.1875068884828e-02 1.0064358227393e-01 1.1797378525413e-01 1.2710272388810e-01 1.3513703066562e-01 1.4944529298392e-01 1.4697829152006e-01 1.3205799503130e-01 1.2681818519922e-01 1.2362016092428e-01 1.2322264394516e-01 1.1891745879897e-01 1.1446447842841e-01 1.1163617973370e-01 1.0987040157785e-01 1.0867687266308e-01 1.0908304944453e-01 1.0904786733701e-01 1.0820024889963e-01 1.0658023417614e-01 1.0668388397128e-01 1.0668396535778e-01 1.0660447625454e-01 1.0629178810729e-01 1.0609910790154e-01 1.0574117983145e-01 1.0563786242975e-01 1.0536514509638e-01 1.0485646490298e-01 1.0490675667211e-01 1.0513762392028e-01 + 5.7202617615401e-01 5.7198232560834e-01 5.7196385814744e-01 5.7194071717121e-01 5.7188755828871e-01 5.7186212370240e-01 5.7173677104220e-01 5.6928776826726e-01 5.6408493358192e-01 5.5324891484364e-01 5.3979014860503e-01 5.2583970707052e-01 5.0626192956490e-01 4.7628058073075e-01 4.4852043225657e-01 4.1814853007221e-01 3.9325498867753e-01 3.5684235811904e-01 3.2462477304407e-01 2.9444113047507e-01 2.5646656540087e-01 2.1175791566654e-01 1.7219556856214e-01 1.3400833305696e-01 1.0244535449218e-01 5.5752161245809e-02 2.9722794946326e-02 5.5152664379124e-03 -2.2690265732337e-02 -4.7215842492303e-02 -6.2352119351368e-02 -6.8652357118355e-02 -6.4780914527345e-02 -6.1291404620379e-02 -5.7429290106072e-02 -5.2240248661084e-02 -3.8821272346099e-02 -2.9801762052456e-02 -2.8904004419386e-02 -2.4772701676593e-02 -1.8084387021543e-02 -1.4441723005872e-02 -9.1370205483216e-03 -8.5462320969167e-03 -1.8462788189698e-03 -3.7245732812886e-03 1.9253744024585e-03 3.3615406614009e-03 1.3059353285120e-03 -9.5755465426404e-04 -5.1396994572644e-03 -6.0684343066213e-03 -7.0937855224809e-03 -1.1702581464836e-02 -1.1411874776182e-02 -1.1409712602926e-02 -1.1792242469801e-02 -1.2950515016822e-02 -1.2959284890015e-02 -1.2763588024168e-02 -1.2850549824536e-02 -1.3404216698131e-02 -1.3923774338265e-02 -1.4381073422858e-02 -1.4925844276084e-02 -1.5101528213181e-02 -1.5147205393413e-02 5.5344211904600e-01 5.5332659054240e-01 5.5332533227897e-01 5.5315331329637e-01 5.5326559592523e-01 5.5369841039152e-01 5.5421956952040e-01 5.5421754360536e-01 5.5421943110375e-01 5.5394933068530e-01 5.5177589076185e-01 5.4335063578060e-01 5.4285124852951e-01 5.4278340132263e-01 5.3386851353644e-01 5.2797014896100e-01 5.1140529463664e-01 4.9318130203068e-01 4.5673456948801e-01 4.0855982224179e-01 3.6920380119287e-01 3.0676150556623e-01 2.6498812925346e-01 2.4479525119998e-01 2.1467340481007e-01 1.8720720935394e-01 1.4479324000273e-01 1.1990470821377e-01 8.6772751753566e-02 6.7792458053937e-02 4.3773611127062e-02 2.9702096824804e-02 1.7273722158143e-02 3.5584078635818e-03 -5.6309446377860e-03 -1.8117443867957e-02 -2.7819579594892e-02 -4.0043405626768e-02 -4.9360460639259e-02 -5.9854221257011e-02 -7.1874176103692e-02 -8.1309000993710e-02 -8.5061424671324e-02 -8.3717751907562e-02 -8.3341951886963e-02 -8.7492394018885e-02 -8.5359410691695e-02 -8.4049419812668e-02 -8.3536698763222e-02 -8.3971387344766e-02 -8.7449017708000e-02 -9.1825923800846e-02 -9.4743884875276e-02 -9.8131918196836e-02 -9.8679259566566e-02 -9.9001254898062e-02 -1.0055402556680e-01 -1.0076868026546e-01 -1.0091236089950e-01 -1.0161522148296e-01 -1.0172926445166e-01 -1.0171836363170e-01 -1.0168134364723e-01 -1.0169859053032e-01 -1.0172592323750e-01 -1.0141632826863e-01 -1.0070420708887e-01 -9.9415620076314e-02 -9.9234533334532e-02 -9.9088779527691e-02 -9.9092820127524e-02 -9.9555113933749e-02 -1.0003432986177e-01 -1.0014980217431e-01 -1.0003301423536e-01 -9.9902138829958e-02 5.5268759207010e-01 5.5268533081510e-01 5.5267845834213e-01 5.5265299349503e-01 5.5264612076915e-01 5.5263580377456e-01 5.5251460089694e-01 5.5250965700383e-01 5.5253807940474e-01 5.5250262624557e-01 5.5275521434786e-01 5.5355253831913e-01 5.5228867545079e-01 5.5086431569477e-01 5.5135242400523e-01 5.5214895448861e-01 5.4221343249501e-01 5.2947651710904e-01 5.1200707125085e-01 4.8077844151275e-01 4.3781476900698e-01 4.0908527709566e-01 3.6984771944231e-01 3.3454021252554e-01 2.8991994111700e-01 2.5353054993627e-01 2.1270511020799e-01 1.7561078055299e-01 1.1775806447610e-01 8.2440163724552e-02 4.2003395125139e-02 -1.5181110631113e-02 -5.0190352657464e-02 -7.4823247980295e-02 -9.6098779577489e-02 -1.0257415291785e-01 -1.0102432085271e-01 -9.9133944278614e-02 -9.2972100022630e-02 -8.3923597176823e-02 -8.2977029488357e-02 -8.3210076999228e-02 -8.3014394382096e-02 -8.3305821339641e-02 -8.2955493283252e-02 -8.1903788737463e-02 -7.6857632005679e-02 -7.8147854006190e-02 -7.8288775150759e-02 -7.8558019067856e-02 -7.9089210693802e-02 -7.9230091416385e-02 -7.9917837572103e-02 -8.0904215886737e-02 -8.1693149819958e-02 -8.2769965415198e-02 -8.2959010139966e-02 -8.2008757949032e-02 -8.2017389985458e-02 -8.2180354858604e-02 -8.2167984101098e-02 -8.1758378799649e-02 -7.9054667671882e-02 -7.8597822786298e-02 -7.9118580327614e-02 -8.0425156945906e-02 -8.1177759342759e-02 -8.1738090477595e-02 -8.3878299686760e-02 -8.4037223409917e-02 5.7201449022345e-01 5.7201528466953e-01 5.7201687233887e-01 5.7201726920244e-01 5.7201436803863e-01 5.7201496300015e-01 5.7199031235221e-01 5.7196249067599e-01 5.7196019467780e-01 5.7180878502539e-01 5.7112584828988e-01 5.6759039777573e-01 5.6094308102720e-01 5.5215571052385e-01 5.4161932841444e-01 5.3067077151163e-01 5.0916190226753e-01 4.9729191640167e-01 4.8675961514086e-01 4.7261563195946e-01 4.5770627877621e-01 4.3503160302909e-01 4.1755273585991e-01 3.9607216841162e-01 3.4939163680217e-01 3.1921502679325e-01 2.8983800936156e-01 2.6455117308099e-01 2.1466652647432e-01 1.5935157440564e-01 1.2566290869468e-01 9.5548547890384e-02 5.0427396197017e-02 3.4548185184819e-02 2.5760295143094e-02 7.7989063503846e-03 -6.6021770529204e-03 -1.2323560228741e-02 -7.9359987193270e-03 -7.0705624929426e-03 4.2122833118587e-03 1.1890280046007e-02 1.7495906361736e-02 2.3870554026709e-02 2.9222662981318e-02 2.8227618613356e-02 3.0746891040110e-02 3.5286433123488e-02 3.4987937896856e-02 3.4640264457970e-02 3.5147574511860e-02 3.4533079221944e-02 3.1680293573132e-02 3.0773528364572e-02 3.0737915399098e-02 3.0464381905393e-02 2.7616384295170e-02 2.6891057869732e-02 2.6575032252646e-02 2.6083839888551e-02 2.5914979744826e-02 2.5702583395158e-02 2.5588906933008e-02 2.5420854504853e-02 2.5683551926606e-02 2.6177235186061e-02 2.6399645470419e-02 2.6525625993945e-02 2.6703366994987e-02 2.6856311270925e-02 2.7067710310572e-02 6.0545988289586e-01 6.0544010468273e-01 6.0544501350730e-01 6.0545143337348e-01 6.0545285937022e-01 6.0546070281169e-01 6.0548850708753e-01 6.0559011849527e-01 6.0568420789090e-01 6.0545168605370e-01 6.0376948394315e-01 5.9864530055517e-01 5.8948356082348e-01 5.7833927995593e-01 5.5257570426907e-01 5.3896588810759e-01 5.2745225366328e-01 4.9484175630371e-01 4.6037843258751e-01 4.3197992357711e-01 3.9264112438469e-01 3.5735213280914e-01 3.0763695550314e-01 2.8241497566834e-01 2.5698452883174e-01 1.9578666299485e-01 1.4881911505713e-01 1.1451704631199e-01 7.4133956315575e-02 4.0742050460588e-02 1.8864807185698e-03 -1.9375390220220e-02 -3.0308447644066e-02 -4.0179179417671e-02 -4.6363593210664e-02 -4.0500223137951e-02 -3.7221424230541e-02 -3.9979610256324e-02 -3.5612020513659e-02 -3.4084129359578e-02 -2.6806846252915e-02 -2.1039497580550e-02 -1.7744392580387e-02 -1.5268299369346e-02 -1.2465744642972e-02 -1.2287962934495e-02 -1.2694516964150e-02 -1.2869881287663e-02 -1.2822462572555e-02 -1.2763198034159e-02 -1.3086897906647e-02 -1.3555818761087e-02 -1.3853137918046e-02 -1.4203210040415e-02 -1.4524801730760e-02 -1.4929946844695e-02 -1.4863826461029e-02 -1.4865622321182e-02 -1.4838752997070e-02 -1.4881354518591e-02 -1.4961805476716e-02 -1.5181418328290e-02 -1.5117787090507e-02 5.6428378188710e-01 5.6434886647494e-01 5.6434504397456e-01 5.6479386841426e-01 5.6486435454574e-01 5.6471553764345e-01 5.6389268142319e-01 5.6389147075078e-01 5.6444374229328e-01 5.7028882868210e-01 5.6891690298532e-01 5.6083931656844e-01 5.4671691793590e-01 5.3212987603958e-01 5.1409846890614e-01 4.8728714722300e-01 4.7373068566316e-01 4.5884384979619e-01 4.0995618934362e-01 3.8187717477520e-01 3.4257062960536e-01 3.0471623889184e-01 2.4398064500051e-01 2.0252520679755e-01 1.8311121023233e-01 1.2054488017542e-01 7.5215147866121e-02 4.9711609276189e-02 1.1742082684228e-02 -9.0479309538286e-03 -3.6741278050842e-02 -4.1635818538759e-02 -5.1999417276920e-02 -5.0222381699637e-02 -4.8726680723829e-02 -4.9330122628632e-02 -4.3257664309042e-02 -3.5664567826203e-02 -2.8459289635374e-02 -9.3529997546026e-03 -2.8454356009439e-03 -3.9485504411740e-03 1.6540427842436e-03 1.0560480942104e-02 1.2439053841024e-02 8.3957140867686e-03 8.7185274092012e-03 6.4423341200916e-03 2.2088847650103e-03 2.8982140116420e-03 2.1255232098690e-03 1.0385552186768e-03 -4.6590911229465e-04 -1.8621644164335e-03 -4.4452684442526e-03 -4.7373807249109e-03 -5.9821328071722e-03 -6.3156982109971e-03 -6.7602519140322e-03 -7.4184396612813e-03 -7.2450467157900e-03 -7.3765135520036e-03 -9.8903679461757e-03 -1.1491006850562e-02 -1.2831640142477e-02 -1.3826583757838e-02 -1.3963210655964e-02 -1.4022199413371e-02 -1.4063013422651e-02 -1.4348878673397e-02 6.0222413507438e-01 5.9945016817514e-01 5.9637343678552e-01 5.9185356221127e-01 5.8361635214267e-01 5.6404212266040e-01 5.4505048281012e-01 5.2179087933567e-01 5.0377216242320e-01 4.8628753384214e-01 4.6726440470401e-01 4.3240980130648e-01 4.1128882638028e-01 3.6485515241647e-01 3.2471751274872e-01 2.8775899172849e-01 2.3529925888512e-01 1.9844248746395e-01 1.5994744874004e-01 1.0407619212362e-01 7.3763765230625e-02 2.8608327071347e-02 -5.3501781716096e-03 -4.5041697641646e-02 -7.1604328027099e-02 -8.9159215938732e-02 -1.0179507465654e-01 -1.2277280108015e-01 -1.3292948814175e-01 -1.4794281024526e-01 -1.5124074750432e-01 -1.4564825913308e-01 -1.3820968507478e-01 -1.3085213344859e-01 -1.2459684333359e-01 -1.1573197885855e-01 -1.0816781923041e-01 -1.0662203092400e-01 -1.0717436702862e-01 -1.0547153838780e-01 -1.0307618775233e-01 -1.0361437310749e-01 -1.0496634049888e-01 -1.0463703204081e-01 -1.0491095358168e-01 -1.0698729681873e-01 -1.0767276768939e-01 -1.0767006170020e-01 -1.0873563490290e-01 -1.0930667053927e-01 -1.0964517848006e-01 -1.1164061160536e-01 -1.1163382858468e-01 -1.1152801911810e-01 -1.1073161198061e-01 -1.0916508218663e-01 -1.0991333237500e-01 -1.1043903318022e-01 -1.1115046645106e-01 -1.1131441138742e-01 -1.1214864384316e-01 6.1128513568494e-01 6.1126367986428e-01 6.1125508067801e-01 6.1119279644544e-01 6.1117776735529e-01 6.1106857554462e-01 6.0753884346215e-01 6.0484382566290e-01 5.9517755493972e-01 5.7474012387333e-01 5.5333675350977e-01 5.2806608613821e-01 5.0585032440673e-01 4.4684839256069e-01 3.8038001635921e-01 3.3495136171721e-01 2.9691511989941e-01 2.3076389749317e-01 1.8048492033040e-01 1.3481302420323e-01 5.6023126068311e-02 8.3612045964642e-03 -2.8329352293691e-02 -6.7622433779126e-02 -7.8830939766416e-02 -8.4474515316359e-02 -8.9727030387775e-02 -9.9110842071188e-02 -9.6664699685737e-02 -8.6692895168762e-02 -8.3202918006212e-02 -8.1070729687630e-02 -8.0684475134289e-02 -7.7571487581785e-02 -7.4490673674744e-02 -7.2629630033503e-02 -7.1448816858297e-02 -7.0670806112954e-02 -7.0935459004572e-02 -7.0912666335230e-02 -7.0361480557850e-02 -6.9308213917244e-02 -6.9375766892827e-02 -6.9376014336902e-02 -6.9324589907125e-02 -6.9121369773065e-02 -6.8996305192457e-02 -6.8764753243931e-02 -6.8697580563771e-02 -6.8520199769311e-02 -6.8189889104743e-02 -6.8222622477831e-02 -6.8373337574099e-02 -2.0911531896753e-01 -2.0908677723278e-01 -2.0907838203623e-01 -2.0906786239338e-01 -2.0904369737307e-01 -2.0903213551153e-01 -2.0895312117925e-01 -2.0736625740283e-01 -2.0389692336491e-01 -1.9639132609690e-01 -1.8765568915743e-01 -1.8097275500059e-01 -1.7334878205890e-01 -1.6066915287644e-01 -1.4576355421452e-01 -1.2966842396770e-01 -1.1940117011762e-01 -1.0883849311100e-01 -1.0191243082340e-01 -9.3651248893605e-02 -8.1180231989325e-02 -6.8924312017455e-02 -6.0264044655772e-02 -5.5895369783171e-02 -5.5094777304334e-02 -6.0133739294221e-02 -6.3745809305889e-02 -6.8806209910501e-02 -8.0444601381985e-02 -1.0578079987249e-01 -1.3077160136800e-01 -1.5722723827650e-01 -1.8272606396917e-01 -2.2096009151842e-01 -2.4180675924057e-01 -2.6974512341039e-01 -3.1101863874373e-01 -3.4366213069895e-01 -3.5742603680227e-01 -3.7042567121918e-01 -3.8271091534644e-01 -3.9133796076596e-01 -3.9226295286345e-01 -3.9065981520892e-01 -3.9287734580766e-01 -3.9212818891235e-01 -3.9408347716988e-01 -3.9428602691859e-01 -3.9254471374029e-01 -3.9087185196029e-01 -3.8848896728423e-01 -3.8436083302203e-01 -3.8302721248015e-01 -3.7749255502238e-01 -3.7274776956832e-01 -3.6955382612646e-01 -3.6712853241422e-01 -3.6140751328680e-01 -3.6054191647707e-01 -3.5997707020583e-01 -3.5799504911258e-01 -3.5598894543320e-01 -3.5276740964639e-01 -3.4983046805034e-01 -3.4761098168808e-01 -3.4705764045218e-01 -3.4696769067946e-01 -1.3732253214317e-01 -1.3726837978721e-01 -1.3728462601235e-01 -1.3720384107113e-01 -1.3726522759781e-01 -1.3748234414855e-01 -1.3775965914088e-01 -1.3775789768828e-01 -1.3776368847770e-01 -1.3764127953018e-01 -1.3665564310403e-01 -1.3288793037935e-01 -1.3413062575544e-01 -1.3774043825000e-01 -1.4173996250250e-01 -1.4551066925618e-01 -1.4963927637905e-01 -1.4692498759630e-01 -1.3365298908153e-01 -1.1227532899456e-01 -9.4341271754724e-02 -6.9333329000628e-02 -6.0402236371574e-02 -5.9278564428459e-02 -5.6457524702361e-02 -5.0562529752613e-02 -3.8904458402260e-02 -3.1482295152275e-02 -2.3662784831914e-02 -2.4600222405121e-02 -3.1526259392858e-02 -3.5848041241337e-02 -3.6212983778229e-02 -3.5841394196472e-02 -3.7450800234393e-02 -4.1827511033238e-02 -4.7325496404285e-02 -6.0989073805280e-02 -6.9497100174915e-02 -7.6929289341145e-02 -8.8477140324754e-02 -1.0723180469099e-01 -1.2273982091480e-01 -1.4460268904427e-01 -1.5254077350489e-01 -1.4826689151152e-01 -1.5123097759055e-01 -1.5352948320247e-01 -1.5422643322760e-01 -1.5436480623730e-01 -1.5036208374687e-01 -1.4282444768706e-01 -1.3835501370161e-01 -1.3261627448657e-01 -1.3188029367462e-01 -1.3122252295343e-01 -1.2946417541790e-01 -1.2887353565882e-01 -1.2778496318633e-01 -1.2670865321839e-01 -1.2649177804612e-01 -1.2627834629679e-01 -1.2589319753286e-01 -1.2582726650128e-01 -1.2574575072754e-01 -1.2594212000367e-01 -1.2662103300645e-01 -1.2789713755891e-01 -1.2789384615468e-01 -1.2792025483561e-01 -1.2754261218715e-01 -1.2569587619193e-01 -1.2065181284591e-01 -1.1989882238402e-01 -1.2006592865255e-01 -1.2023458460104e-01 -5.0855439869795e-02 -5.0853617527590e-02 -5.0848079041104e-02 -5.0816951296995e-02 -5.0811412920856e-02 -5.0808219340234e-02 -5.0763559475209e-02 -5.0761628811634e-02 -5.0752737406931e-02 -5.0716627023258e-02 -5.0782382421503e-02 -5.1043577117581e-02 -5.0538266276407e-02 -4.9923726690363e-02 -4.9880140955500e-02 -4.9989109461387e-02 -4.6762045749675e-02 -4.2478147161517e-02 -3.6681484910199e-02 -3.0931637057904e-02 -2.3691291805647e-02 -1.7838085050283e-02 -8.9301360327307e-03 1.3908198827950e-03 1.3022281725341e-02 1.8752765247416e-02 2.4938161755683e-02 3.1429281082432e-02 4.2372520836590e-02 4.8003462629775e-02 5.2148745363290e-02 5.0885179265235e-02 4.0911315021222e-02 2.9011927460373e-02 1.1014076769073e-02 -3.0919849941735e-03 -1.0010397968246e-02 -1.5627800605873e-02 -1.8109487060944e-02 -2.1593405714986e-02 -2.1756560212366e-02 -2.0441713121301e-02 -1.9780797296237e-02 -1.9126078360476e-02 -1.9098099276816e-02 -1.9075422005919e-02 -1.8742616267609e-02 -1.8042832746404e-02 -1.8005894378722e-02 -1.7813227919910e-02 -1.7328033808547e-02 -1.7110846128249e-02 -1.6344298683753e-02 -1.5436390956600e-02 -1.4775704813618e-02 -1.4065462893597e-02 -1.3882714718078e-02 -1.3839046182507e-02 -1.3758961207640e-02 -1.3579835487303e-02 -1.3568882333240e-02 -1.3572568145940e-02 -1.3631214407546e-02 1.3761957376963e-02 1.3850854229130e-02 1.4562292008951e-02 1.4610628648685e-02 1.4617551663839e-02 1.4653300844443e-02 1.4658698769137e-02 -2.3125548967847e-01 -2.3124570031541e-01 -2.3122613366871e-01 -2.3122124204701e-01 -2.3120871608973e-01 -2.3120138167498e-01 -2.3118651296567e-01 -2.3117464610935e-01 -2.3117366679622e-01 -2.3108501925357e-01 -2.3066209873642e-01 -2.2838981340085e-01 -2.2385770850835e-01 -2.1781600517433e-01 -2.1047721608965e-01 -2.0284967327167e-01 -1.8782799232727e-01 -1.7946145650056e-01 -1.7219530760413e-01 -1.6327975777033e-01 -1.5437011002247e-01 -1.4309952470025e-01 -1.3579633069501e-01 -1.2771118212732e-01 -1.0899395255186e-01 -9.8356999159983e-02 -8.9423641488178e-02 -8.2542127484090e-02 -7.1296065355623e-02 -5.9312789099395e-02 -5.0306926065880e-02 -4.2127092040506e-02 -3.4835407338824e-02 -4.1767981070739e-02 -5.5468563308246e-02 -8.9837757011799e-02 -1.2886677949205e-01 -1.4958383786716e-01 -1.7184610956459e-01 -1.9858240251493e-01 -2.2720803489951e-01 -2.5467123248796e-01 -2.6332403962625e-01 -2.7124780498943e-01 -2.8546472792076e-01 -2.8909836417941e-01 -2.9528012172474e-01 -3.0273820334092e-01 -3.0326993529910e-01 -3.0291391283845e-01 -3.0313377391178e-01 -3.0188469522672e-01 -2.9873277310295e-01 -2.9531122303726e-01 -2.9431677778205e-01 -2.9286327627882e-01 -2.8722669087271e-01 -2.8386679310352e-01 -2.8215453711913e-01 -2.7924839515895e-01 -2.7783587585197e-01 -2.7720961485465e-01 -2.7653473074212e-01 -2.7543830953172e-01 -2.7467618492182e-01 -2.7409765370194e-01 -2.7418465978435e-01 -2.7419664250687e-01 -2.7428002669894e-01 -2.7413199469501e-01 -2.7422581649120e-01 -9.7123320574747e-02 -9.7114152954162e-02 -9.7090168499215e-02 -9.7070087164130e-02 -9.7065626505328e-02 -9.7041090519087e-02 -9.6954100087800e-02 -9.6979076105135e-02 -9.7013373033004e-02 -9.6914868145399e-02 -9.6177469784216e-02 -9.3941032107808e-02 -9.0158054105465e-02 -8.5584813100515e-02 -7.5892107570275e-02 -7.1207834187480e-02 -6.7317127300000e-02 -5.6138243039839e-02 -4.4362959341905e-02 -3.4343008834074e-02 -2.2060293270794e-02 -1.3637637780456e-02 -9.7815786667493e-03 -9.1806100406431e-03 -1.0899760824297e-02 -1.5482063508351e-02 -1.6894407807562e-02 -1.7847119375045e-02 -2.9046902209416e-02 -4.0413693785423e-02 -5.7555367678286e-02 -7.7897834014170e-02 -9.3529507547325e-02 -1.0806099443285e-01 -1.3620518668249e-01 -1.5209319614347e-01 -1.6595557394579e-01 -1.8292749217278e-01 -2.0091106589320e-01 -2.0524453513904e-01 -2.1067194878273e-01 -2.1704352835089e-01 -2.1768815072176e-01 -2.1811665146890e-01 -2.1854124401481e-01 -2.1848304930789e-01 -2.1827621118257e-01 -2.1776824335239e-01 -2.1757291941519e-01 -2.1730864531156e-01 -2.1572365411222e-01 -2.1467531643735e-01 -2.1375008128743e-01 -2.1119720407661e-01 -2.1030105584540e-01 -2.0956723529352e-01 -2.0913120556412e-01 -2.0879308134189e-01 -2.0862943691594e-01 -2.0841975149979e-01 -2.0755550939382e-01 -2.0658513546372e-01 -2.0640822197079e-01 -3.0739859796023e-01 -3.0744163121403e-01 -3.0743417300096e-01 -3.0773851257447e-01 -3.0778818839889e-01 -3.0766946156349e-01 -3.0703636389418e-01 -3.0703418778277e-01 -3.0742822144602e-01 -3.1147659147405e-01 -3.1059706811170e-01 -3.0317468667078e-01 -2.9158424394135e-01 -2.7918137371349e-01 -2.6441511032553e-01 -2.4161586925970e-01 -2.3081112490277e-01 -2.1968990552891e-01 -1.8713242533804e-01 -1.7229609154511e-01 -1.5131150826603e-01 -1.3296351913533e-01 -1.0736372217516e-01 -9.0976873281808e-02 -8.2998185302068e-02 -5.2966510293982e-02 -3.4023710283557e-02 -2.5907130344142e-02 -2.1589097856682e-02 -2.4769977254058e-02 -3.7404273233425e-02 -4.0610807247189e-02 -6.4005677028558e-02 -8.3959063121684e-02 -1.0976473449498e-01 -1.3524481544075e-01 -1.7562664697352e-01 -1.9955470006800e-01 -2.2147585740087e-01 -2.5142012617042e-01 -2.6962064747796e-01 -2.7847422944354e-01 -2.9189523446497e-01 -3.0492463434976e-01 -3.1023997004808e-01 -3.0712400438996e-01 -3.0558000058849e-01 -3.0084352773019e-01 -2.9379652823632e-01 -2.9121883127207e-01 -2.8658948159573e-01 -2.8459541249505e-01 -2.8271480315124e-01 -2.8116317385461e-01 -2.7773946797211e-01 -2.7571624670718e-01 -2.7419972997452e-01 -2.7388767353337e-01 -2.7346580597269e-01 -2.7261735000638e-01 -2.7246535185825e-01 -2.7235966963776e-01 -2.7006705523704e-01 -2.6790458367950e-01 -2.6617734234142e-01 -2.6483393131308e-01 -2.6473599871760e-01 -2.6462844973564e-01 -2.6445842378052e-01 -2.6423680513745e-01 -1.5476076260409e-01 -1.5341510429394e-01 -1.5186960255597e-01 -1.4954465075157e-01 -1.4518840558402e-01 -1.3468630543323e-01 -1.2436120093359e-01 -1.1183886462934e-01 -1.0233932711108e-01 -9.3430490610092e-02 -8.3632110640408e-02 -6.7804805775202e-02 -5.9046857795449e-02 -3.9840036735761e-02 -2.5163992791343e-02 -1.3831543051957e-02 9.9884500044942e-05 1.1030471183977e-02 2.4400908697505e-02 4.0692295844916e-02 4.6137465550354e-02 4.3980064560363e-02 3.3142572813842e-02 2.0535739333148e-02 1.3845612750829e-02 9.5424405203089e-03 3.9272119884579e-03 -9.3689887315702e-03 -2.3082211420622e-02 -5.3370901671997e-02 -8.2403709601138e-02 -1.1473875210493e-01 -1.5788391274151e-01 -1.8275087574835e-01 -2.0788161949295e-01 -2.3570736052834e-01 -2.6325066351480e-01 -2.6897710594660e-01 -2.6896813712445e-01 -2.7202360256830e-01 -2.7319278883430e-01 -2.7133099532918e-01 -2.6599355642856e-01 -2.6416226063786e-01 -2.6244901825617e-01 -2.5799583150137e-01 -2.5592825605395e-01 -2.5329855200398e-01 -2.5202250866754e-01 -2.5098805674432e-01 -2.4931319657677e-01 -2.4413539058580e-01 -2.4352995289878e-01 -2.4324886951263e-01 -2.4313207464827e-01 -2.4376358511500e-01 -2.4334472491574e-01 -2.4306806674988e-01 -2.4244340227297e-01 -2.4066206556499e-01 -2.4010756308108e-01 -6.1393516832331e-02 -6.1374929767144e-02 -6.1367480504174e-02 -6.1313528063891e-02 -6.1300510173580e-02 -6.1266617655908e-02 -6.0207004848716e-02 -5.9348848690260e-02 -5.6013414584553e-02 -4.8667677307679e-02 -4.0796756890686e-02 -3.1831291333387e-02 -2.4442306839133e-02 -5.8268214854180e-03 1.3776913350030e-02 2.5226607294646e-02 3.4613304570198e-02 5.2015800708669e-02 6.6342966848769e-02 7.8749082376858e-02 8.6705730328905e-02 8.5516777572932e-02 8.5797561027866e-02 8.3646436935592e-02 7.3684720979438e-02 5.4781506526533e-02 4.7522693509526e-02 4.1343921630086e-02 1.0546727819472e-02 -3.0283904095773e-03 -7.2689269975711e-03 -1.0063782910234e-02 -1.0339843770207e-02 -1.1166614969305e-02 -1.1749207167510e-02 -1.2423090953593e-02 -1.4863248386203e-02 -1.5037949338710e-02 -1.4898698802120e-02 -1.4865768756489e-02 -1.4896027634631e-02 -1.4939375669340e-02 -1.4927465022926e-02 -1.4917018632126e-02 -1.4912612806582e-02 -1.4920618928919e-02 -1.4909852905186e-02 -1.4891577221918e-02 -1.4894534466166e-02 -1.4903259561879e-02 -1.4905665921237e-02 -1.4903766390982e-02 -1.4875596265131e-02 + 1.6126014031423e-01 1.6123890714359e-01 1.6123265678506e-01 1.6122482469076e-01 1.6120683311079e-01 1.6119822485257e-01 1.6113944142825e-01 1.5995817509808e-01 1.5737540472137e-01 1.5177995358047e-01 1.4522183730987e-01 1.4010396722076e-01 1.3418944868024e-01 1.2442625271206e-01 1.1306339316303e-01 1.0074345944992e-01 9.2805383117202e-02 8.4555788352467e-02 7.9114285824222e-02 7.2691964905630e-02 6.3038118030789e-02 5.3527874613954e-02 4.6798001139508e-02 4.3384853276799e-02 4.2734045770642e-02 4.6570170599376e-02 4.9334905884906e-02 5.3213321352565e-02 6.2127031134858e-02 8.1456721399760e-02 1.0040693568831e-01 1.2033481798945e-01 1.3936499555661e-01 1.6756366963891e-01 1.8276672889663e-01 2.0288180757554e-01 2.3196835676929e-01 2.5445227940344e-01 2.6365574594325e-01 2.7186603210684e-01 2.7923388788172e-01 2.8313574154277e-01 2.8304261378410e-01 2.8165394600607e-01 2.8289735220800e-01 2.8248484612086e-01 2.8367923892206e-01 2.8377524352208e-01 2.8260474377422e-01 2.8158888587377e-01 2.8004834337254e-01 2.7727985795568e-01 2.7625298563265e-01 2.7214848232493e-01 2.6859105536248e-01 2.6626692274943e-01 2.6456614800000e-01 2.6040857710910e-01 2.5979385613888e-01 2.5935437900730e-01 2.5780021879752e-01 2.5627765280690e-01 2.5392559802159e-01 2.5181450141062e-01 2.5022058556569e-01 2.4981121358130e-01 2.4974755428991e-01 1.0144796788044e-01 1.0140874206044e-01 1.0142004069494e-01 1.0136158093019e-01 1.0140576992541e-01 1.0156244950851e-01 1.0176224669570e-01 1.0176098271975e-01 1.0176504261967e-01 1.0167639049191e-01 1.0096232855547e-01 9.8228292938899e-02 9.9083585690759e-02 1.0158680034842e-01 1.0423156648449e-01 1.0675267157549e-01 1.0938564414940e-01 1.0732625730334e-01 9.7819956244638e-02 8.2490622157155e-02 6.9534234901613e-02 5.1470853598176e-02 4.5249830366155e-02 4.4700672128254e-02 4.3031463542071e-02 3.8886216074651e-02 3.0296971410924e-02 2.4682636591045e-02 1.8772152491190e-02 1.9698448508471e-02 2.5629306549562e-02 2.9421170688886e-02 2.9923488424230e-02 2.9862810408960e-02 3.1396497149559e-02 3.5315861011740e-02 4.0176590248906e-02 5.2247350384829e-02 5.9872880432017e-02 6.6578439005777e-02 7.6865176194356e-02 9.3417955217390e-02 1.0706615837658e-01 1.2624041781055e-01 1.3320924746516e-01 1.2950624781444e-01 1.3202035196577e-01 1.3396941237269e-01 1.3456514011968e-01 1.3467094275033e-01 1.3120825657339e-01 1.2469835074769e-01 1.2083597852753e-01 1.1587325928976e-01 1.1523625944336e-01 1.1466702995024e-01 1.1314476204962e-01 1.1263452646495e-01 1.1169368730978e-01 1.1076179456644e-01 1.1057405051424e-01 1.1038958939304e-01 1.1005676979042e-01 1.0999976900333e-01 1.0992923016765e-01 1.1009982882367e-01 1.1068752975019e-01 1.1179010412635e-01 1.1178720041320e-01 1.1180997613851e-01 1.1148360639130e-01 1.0988645048001e-01 1.0551553435514e-01 1.0486056266695e-01 1.0500555450265e-01 1.0515188212564e-01 3.6221474560376e-02 3.6220188084869e-02 3.6216278206281e-02 3.6194330937034e-02 3.6190421083215e-02 3.6188191148223e-02 3.6156525908730e-02 3.6155215817889e-02 3.6149020875465e-02 3.6123526900892e-02 3.6170304957901e-02 3.6355682601022e-02 3.5997864974343e-02 3.5563019942197e-02 3.5533957180332e-02 3.5612406833403e-02 3.3320687921419e-02 3.0278613260406e-02 2.6157214104367e-02 2.2034172542640e-02 1.6853623922871e-02 1.2683785017899e-02 6.3463447033204e-03 -9.8706101775356e-04 -9.1751586458287e-03 -1.3087627958120e-02 -1.7203078778756e-02 -2.1432697224513e-02 -2.8382095377383e-02 -3.1828391215797e-02 -3.4203850968519e-02 -3.2926269322624e-02 -2.6293999682687e-02 -1.8596351218690e-02 -7.0460484900939e-03 1.9744373394280e-03 6.3862661666434e-03 9.9622433631236e-03 1.1539909682849e-02 1.3751056000703e-02 1.3851776119817e-02 1.3015095389113e-02 1.2594529611290e-02 1.2177862819478e-02 1.2160032148996e-02 1.2145537926100e-02 1.1932740967470e-02 1.1487464762889e-02 1.1463966968564e-02 1.1341378222972e-02 1.1032662874876e-02 1.0894508925896e-02 1.0406743936754e-02 9.8289749780336e-03 9.4087192211665e-03 8.9568907269184e-03 8.8405516343850e-03 8.8120384196848e-03 8.7610387558966e-03 8.6470227979560e-03 8.6398831394225e-03 8.6419449297057e-03 8.6779711007133e-03 8.7626266265300e-03 8.8194791152387e-03 9.2942110059203e-03 9.3334390425467e-03 9.3380801085913e-03 9.3619151984009e-03 9.3655243354542e-03 1.7800689267134e-01 1.7800018420350e-01 1.7798677533367e-01 1.7798342309946e-01 1.7797470929835e-01 1.7796968291333e-01 1.7795872212252e-01 1.7794995807119e-01 1.7794923481345e-01 1.7788389619402e-01 1.7757211869220e-01 1.7589688914838e-01 1.7255611600568e-01 1.6809066411350e-01 1.6264950374102e-01 1.5697322439780e-01 1.4573490347372e-01 1.3944503166975e-01 1.3395909515463e-01 1.2717381239147e-01 1.2036417111599e-01 1.1167421401858e-01 1.0600849443388e-01 9.9708970943616e-02 8.5163757053384e-02 7.6876490208217e-02 6.9903705056961e-02 6.4528292201008e-02 5.5717684122517e-02 4.6350067654298e-02 3.9327858904680e-02 3.2948723155884e-02 2.7257060958206e-02 3.2692465713088e-02 4.3456139936478e-02 7.0553912393992e-02 1.0134688508070e-01 1.1770498968002e-01 1.3504067440875e-01 1.5535044059350e-01 1.7687635918228e-01 1.9716960867751e-01 2.0346173722969e-01 2.0918964286817e-01 2.1960058301680e-01 2.2246092812348e-01 2.2712334088985e-01 2.3262703914617e-01 2.3300116942003e-01 2.3273337060376e-01 2.3288275034746e-01 2.3197639813048e-01 2.2970713008137e-01 2.2722728840036e-01 2.2650346418192e-01 2.2544736276395e-01 2.2135968207895e-01 2.1890292640394e-01 2.1761486548971e-01 2.1538263450082e-01 2.1434006909325e-01 2.1388420160652e-01 2.1338982331874e-01 2.1258517808929e-01 2.1201059240626e-01 2.1149357230681e-01 2.1155563466330e-01 2.1156476708848e-01 2.1162505065738e-01 2.1151502038341e-01 2.1158261688845e-01 6.9632092649512e-02 6.9625637227905e-02 6.9609341003121e-02 6.9595730752799e-02 6.9592707469984e-02 6.9576077530722e-02 6.9517113524184e-02 6.9535148074892e-02 6.9559452203581e-02 6.9489928551863e-02 6.8969706936473e-02 6.7390717104321e-02 6.4712688920816e-02 6.1468945900159e-02 5.4564344308395e-02 5.1215365477693e-02 4.8431064426441e-02 4.0425379281579e-02 3.1976423562076e-02 2.4776875862455e-02 1.5926958862674e-02 9.8442753263121e-03 7.0446071133641e-03 6.6026930004858e-03 7.8251516728507e-03 1.1074062648973e-02 1.2063027143670e-02 1.2729679245731e-02 2.0663152677017e-02 2.8686083972696e-02 4.0682478940579e-02 5.4769482936383e-02 6.5605195190998e-02 7.5636312677708e-02 9.4904354277659e-02 1.0565190227248e-01 1.1496165847286e-01 1.2633445666577e-01 1.3825929209494e-01 1.4111036524607e-01 1.4457678972816e-01 1.4871822480973e-01 1.4911883965981e-01 1.4938776837894e-01 1.4965502491302e-01 1.4961484815269e-01 1.4948128732670e-01 1.4914717124201e-01 1.4900874930327e-01 1.4881277007899e-01 1.4770742366446e-01 1.4696970652852e-01 1.4627958910172e-01 1.4436676203518e-01 1.4375375217570e-01 1.4327297174705e-01 1.4297779209848e-01 1.4274634307033e-01 1.4262607126690e-01 1.4246057764918e-01 1.4179953152524e-01 1.4109421614745e-01 1.4094944340396e-01 2.3888101126980e-01 2.3891221055650e-01 2.3890693266373e-01 2.3912735692110e-01 2.3916328296380e-01 2.3907775879548e-01 2.3862115635616e-01 2.3861960358059e-01 2.3890456746730e-01 2.4183030741914e-01 2.4117652829895e-01 2.3582946938829e-01 2.2742330848112e-01 2.1835788954907e-01 2.0745815121791e-01 1.9042980002874e-01 1.8225444080527e-01 1.7378100370351e-01 1.4851494553063e-01 1.3669819643452e-01 1.1998021004729e-01 1.0545988907183e-01 8.5161631893157e-02 7.2268667089403e-02 6.5980237454747e-02 4.2247403124413e-02 2.7292537769057e-02 2.0880691455043e-02 1.7595152388358e-02 2.0389998174325e-02 3.1187841933212e-02 3.3912750996295e-02 5.3723386508216e-02 7.0479821304208e-02 9.2037006209290e-02 1.1319200720360e-01 1.4660851193705e-01 1.6623697294052e-01 1.8386777514345e-01 2.0748599616059e-01 2.2147722098238e-01 2.2819021690602e-01 2.3848986258804e-01 2.4836328158135e-01 2.5229859257716e-01 2.4990586414588e-01 2.4870502079188e-01 2.4504362738776e-01 2.3958271657756e-01 2.3756726014934e-01 2.3394743237270e-01 2.3239490579611e-01 2.3093043587903e-01 2.2972213579960e-01 2.2705498795231e-01 2.2547405938418e-01 2.2428932477478e-01 2.2404722646222e-01 2.2371859891092e-01 2.2305963595313e-01 2.2294719501236e-01 2.2286449941799e-01 2.2107158206791e-01 2.1938267110191e-01 2.1803491205530e-01 2.1698171115115e-01 2.1690423922710e-01 2.1681880813771e-01 2.1668505458932e-01 2.1651081567289e-01 1.1428713597039e-01 1.1331809267983e-01 1.1220566120030e-01 1.1053201971482e-01 1.0739393326851e-01 9.9805924563896e-02 9.2314725025559e-02 8.3184693463532e-02 7.6225049762337e-02 6.9670988423216e-02 6.2443958096803e-02 5.0700998266710e-02 4.4177970318448e-02 2.9843155351118e-02 1.8857366114437e-02 1.0371932524339e-02 -7.5059630052681e-05 -8.3098364956088e-03 -1.8424321561962e-02 -3.0888196609051e-02 -3.5155908698021e-02 -3.3772195332452e-02 -2.5638283358611e-02 -1.6003781908425e-02 -1.0833828202134e-02 -7.4869997904330e-03 -3.0886512020470e-03 7.3921429323449e-03 1.8243863296851e-02 4.2269063990971e-02 6.5172911564533e-02 9.0456840124429e-02 1.2387718288579e-01 1.4287862719577e-01 1.6190037466386e-01 1.8269217103612e-01 2.0297197555150e-01 2.0716362490890e-01 2.0716222925254e-01 2.0940971440295e-01 2.1026117781628e-01 2.0884133663362e-01 2.0480678933243e-01 2.0344225038836e-01 2.0213781509227e-01 1.9882026136759e-01 1.9728693772168e-01 1.9532790970240e-01 1.9438435745499e-01 1.9360711729056e-01 1.9232653210736e-01 1.8832480536452e-01 1.8786300314076e-01 1.8765203199851e-01 1.8755632387066e-01 1.8800676153116e-01 1.8770002582490e-01 1.8749784752129e-01 1.8703533016109e-01 1.8570521132881e-01 1.8529568017491e-01 4.3008790761420e-02 4.2995943864112e-02 4.2990795096338e-02 4.2953503828658e-02 4.2944505885053e-02 4.2920920557592e-02 4.2183194522566e-02 4.1586127107204e-02 3.9266695290321e-02 3.4152266436153e-02 2.8660334135424e-02 2.2386982964470e-02 1.7202773684374e-02 4.1065308427829e-03 -9.7177657463720e-03 -1.7794015475782e-02 -2.4413515434196e-02 -3.6667915578855e-02 -4.6642166488175e-02 -5.5104280786747e-02 -5.9729968482823e-02 -5.8231818474400e-02 -5.8043828870656e-02 -5.6202049994023e-02 -4.9236665490751e-02 -3.6408670645038e-02 -3.1553676617249e-02 -2.7418935755467e-02 -6.9363731663552e-03 1.9880654120588e-03 4.7690000927075e-03 6.5998799698240e-03 6.7703860334386e-03 7.2841359306737e-03 7.6460957064450e-03 8.0823663259026e-03 9.6655832382005e-03 9.7789343400334e-03 9.6884533709032e-03 9.6670510427102e-03 9.6867296467640e-03 9.7149481110121e-03 9.7072237640895e-03 9.7004577493493e-03 9.6976300018736e-03 9.7028532174830e-03 9.6958851188039e-03 9.6841706770279e-03 9.6860960446805e-03 9.6917659199320e-03 9.6934004702703e-03 9.6921691246995e-03 9.6739314350779e-03 -9.4076055525591e-01 -9.4080074498276e-01 -9.4081832401220e-01 -9.4084035053127e-01 -9.4089094428716e-01 -9.4091514907870e-01 -9.4103036156910e-01 -9.4326816622119e-01 -9.4790572457709e-01 -9.5716391494547e-01 -9.6863825081779e-01 -9.8174207800916e-01 -1.0003168043521e+00 -1.0257040185826e+00 -1.0449326773567e+00 -1.0640409019372e+00 -1.0798820700861e+00 -1.1027649592735e+00 -1.1215123143121e+00 -1.1362442693165e+00 -1.1514336257367e+00 -1.1669142472807e+00 -1.1783287320599e+00 -1.1878108976163e+00 -1.1945953140799e+00 -1.2029585359362e+00 -1.2057910521802e+00 -1.2076972670553e+00 -1.2097685945071e+00 -1.2130903658423e+00 -1.2159606554061e+00 -1.2192754050855e+00 -1.2236982606260e+00 -1.2301713399236e+00 -1.2337352899169e+00 -1.2389549642361e+00 -1.2481088919693e+00 -1.2554340570268e+00 -1.2594828438911e+00 -1.2664526729774e+00 -1.2751992600818e+00 -1.2898778728075e+00 -1.2951308449856e+00 -1.2972815359889e+00 -1.2991888996657e+00 -1.2985041026284e+00 -1.2994365720805e+00 -1.2997218929041e+00 -1.2996679836806e+00 -1.2988274621620e+00 -1.2982586203890e+00 -1.2979744424337e+00 -1.2988304878614e+00 -1.3012175202813e+00 -1.3036096465395e+00 -1.3046891621445e+00 -1.3050142205653e+00 -1.3068561358228e+00 -1.3070260224478e+00 -1.3074354412356e+00 -1.3089541452876e+00 -1.3100963739867e+00 -1.3112147015531e+00 -1.3119685933528e+00 -1.3125172038038e+00 -1.3127477865946e+00 -1.3127619030874e+00 -1.0619505064942e+00 -1.0620527085612e+00 -1.0620653918606e+00 -1.0622163491930e+00 -1.0621237374154e+00 -1.0617541377281e+00 -1.0613174395887e+00 -1.0613188905524e+00 -1.0613205217651e+00 -1.0615605890820e+00 -1.0634868922841e+00 -1.0708854563482e+00 -1.0724456230684e+00 -1.0751927782287e+00 -1.0885306490601e+00 -1.0978926444699e+00 -1.1187541537687e+00 -1.1356541624578e+00 -1.1617451104886e+00 -1.1894684870019e+00 -1.2083514536426e+00 -1.2273410086166e+00 -1.2267742337623e+00 -1.2206092790370e+00 -1.2079281694427e+00 -1.1964862395534e+00 -1.1789255329745e+00 -1.1683763890255e+00 -1.1457941731250e+00 -1.1254968282346e+00 -1.0897562617264e+00 -1.0660165807377e+00 -1.0486094889586e+00 -1.0266252035225e+00 -1.0097068915645e+00 -9.8945638582278e-01 -9.7331781454991e-01 -9.4543556695451e-01 -9.2726708658007e-01 -9.1186700144613e-01 -8.9774325083927e-01 -8.8579963356423e-01 -8.7918325160407e-01 -8.7337788443632e-01 -8.7112939785315e-01 -8.7060024195143e-01 -8.7220973895383e-01 -8.7336498842306e-01 -8.7360581011078e-01 -8.7388544436503e-01 -8.7341100010564e-01 -8.7233214550253e-01 -8.7157457086661e-01 -8.7059337406672e-01 -8.7045338083014e-01 -8.7034842418000e-01 -8.6996998468564e-01 -8.6985351888940e-01 -8.6968499454561e-01 -8.6947477103714e-01 -8.6943492715627e-01 -8.6940542586893e-01 -8.6935269472656e-01 -8.6934078883070e-01 -8.6932701348821e-01 -8.6937751779486e-01 -8.6955782640450e-01 -8.6994145324750e-01 -8.6996976803333e-01 -8.6999654549638e-01 -8.6994319704840e-01 -8.6963856403967e-01 -8.6908768655674e-01 -8.6906430852069e-01 -8.6909459895816e-01 -8.6912724230587e-01 -1.1377939610003e+00 -1.1377956510042e+00 -1.1378007872263e+00 -1.1378157277617e+00 -1.1378208634378e+00 -1.1378287131132e+00 -1.1379397040537e+00 -1.1379413644316e+00 -1.1379078716515e+00 -1.1379324287208e+00 -1.1376905383561e+00 -1.1369466447903e+00 -1.1380778366016e+00 -1.1393217836663e+00 -1.1387604122378e+00 -1.1379547101121e+00 -1.1470786346265e+00 -1.1582882287119e+00 -1.1731219047887e+00 -1.2008342090843e+00 -1.2353826585883e+00 -1.2556294728787e+00 -1.2805447826328e+00 -1.3021434767628e+00 -1.3363410402977e+00 -1.3682262854122e+00 -1.4030012226444e+00 -1.4337370101348e+00 -1.4768597876315e+00 -1.4991112858622e+00 -1.5207549901073e+00 -1.5439940112411e+00 -1.5533434509466e+00 -1.5554543596316e+00 -1.5559398977755e+00 -1.5578306399605e+00 -1.5595321538268e+00 -1.5609979151813e+00 -1.5624918538107e+00 -1.5647234141098e+00 -1.5652050396506e+00 -1.5651387556764e+00 -1.5651436935029e+00 -1.5650884473586e+00 -1.5651367337617e+00 -1.5652807296148e+00 -1.5660333267967e+00 -1.5658498879465e+00 -1.5658302138208e+00 -1.5657884041476e+00 -1.5656995748613e+00 -1.5656659582991e+00 -1.5655431984963e+00 -1.5653774035915e+00 -1.5652111789077e+00 -1.5650026914566e+00 -1.5649734437840e+00 -1.5652226011425e+00 -1.5652231581614e+00 -1.5651959271038e+00 -1.5652275659800e+00 -1.5653320942189e+00 -1.5659113888436e+00 1.5657128993443e+00 1.5656031448061e+00 1.5617602901439e+00 1.5602519140103e+00 1.5601433406202e+00 1.5596969944987e+00 1.5596490309894e+00 -9.3975863316926e-01 -9.3974966513402e-01 -9.3973173987632e-01 -9.3972725854578e-01 -9.3972146204342e-01 -9.3971474274521e-01 -9.3973751965932e-01 -9.3976426704925e-01 -9.3976647430569e-01 -9.3990662296676e-01 -9.4053414966129e-01 -9.4373185724421e-01 -9.4951130658901e-01 -9.5693397570224e-01 -9.6549972493504e-01 -9.7407026596145e-01 -9.8994918893966e-01 -9.9813979547083e-01 -1.0052262214789e+00 -1.0150643460397e+00 -1.0251595753748e+00 -1.0408622153567e+00 -1.0527850563200e+00 -1.0670350364975e+00 -1.0936463210974e+00 -1.1089264802864e+00 -1.1224845878676e+00 -1.1330369416000e+00 -1.1516910638490e+00 -1.1671071246603e+00 -1.1733465229120e+00 -1.1772255958732e+00 -1.1810730890344e+00 -1.1810107433284e+00 -1.1786987845118e+00 -1.1713716846873e+00 -1.1644817877427e+00 -1.1606314114420e+00 -1.1607620866532e+00 -1.1669904736359e+00 -1.1731198340152e+00 -1.1800109480037e+00 -1.1825546945636e+00 -1.1848627317616e+00 -1.1870286291448e+00 -1.1855266081298e+00 -1.1848391014846e+00 -1.1850110092502e+00 -1.1852250468667e+00 -1.1852776118384e+00 -1.1853861475972e+00 -1.1852155219143e+00 -1.1846417040514e+00 -1.1840311736554e+00 -1.1838659896884e+00 -1.1836089956486e+00 -1.1825268149639e+00 -1.1819875670523e+00 -1.1820713411528e+00 -1.1826828793257e+00 -1.1825239680291e+00 -1.1823886246812e+00 -1.1822699254974e+00 -1.1820884968732e+00 -1.1821099665334e+00 -1.1829841575808e+00 -1.1830102102731e+00 -1.1830039135774e+00 -1.1830214310336e+00 -1.1830049123679e+00 -1.1830266061798e+00 -1.0688827217387e+00 -1.0689023568973e+00 -1.0688762527540e+00 -1.0688509779402e+00 -1.0688453635763e+00 -1.0688144810822e+00 -1.0687049825297e+00 -1.0685875561868e+00 -1.0684880747736e+00 -1.0687250179419e+00 -1.0704214666871e+00 -1.0755455747677e+00 -1.0846658099977e+00 -1.0954819809332e+00 -1.1197741436179e+00 -1.1321661048214e+00 -1.1423062159176e+00 -1.1690684785083e+00 -1.1946410979731e+00 -1.2134987068142e+00 -1.2378345682706e+00 -1.2586249727254e+00 -1.2879497773098e+00 -1.3016448093497e+00 -1.3151413461816e+00 -1.3423274703142e+00 -1.3573641135826e+00 -1.3658769784328e+00 -1.3761539980930e+00 -1.3827427708777e+00 -1.3911579293691e+00 -1.3997510446802e+00 -1.4027423377253e+00 -1.4051165887216e+00 -1.4105650705294e+00 -1.4148590201657e+00 -1.4185171443812e+00 -1.4217492875654e+00 -1.4259879742430e+00 -1.4271123779701e+00 -1.4299250752276e+00 -1.4319481836345e+00 -1.4324361232560e+00 -1.4327249963664e+00 -1.4329982545893e+00 -1.4330142745164e+00 -1.4329419902922e+00 -1.4328517127602e+00 -1.4329378270690e+00 -1.4331583754706e+00 -1.4336319544750e+00 -1.4340211157262e+00 -1.4348423565642e+00 -1.4372508152505e+00 -1.4373807194865e+00 -1.4372210897296e+00 -1.4372498754222e+00 -1.4373025000729e+00 -1.4374312329789e+00 -1.4377363857952e+00 -1.4387382703263e+00 -1.4394047214197e+00 -1.4397322399866e+00 -9.0320086460259e-01 -9.0314148728754e-01 -9.0314276474620e-01 -9.0273633144601e-01 -9.0267328983778e-01 -9.0280014882557e-01 -9.0351004118023e-01 -9.0351063514312e-01 -9.0301994455418e-01 -8.9771723770630e-01 -8.9917366241690e-01 -9.0581112024463e-01 -9.1725641746912e-01 -9.2832529599670e-01 -9.4146088848897e-01 -9.5937244073787e-01 -9.6832399107888e-01 -9.7798822840440e-01 -1.0106468276272e+00 -1.0312931103934e+00 -1.0575917940504e+00 -1.0776306852276e+00 -1.1045455026575e+00 -1.1157665873302e+00 -1.1198969555098e+00 -1.1270310125077e+00 -1.1202107913784e+00 -1.1109936018219e+00 -1.0848538132102e+00 -1.0591169157836e+00 -1.0236473930496e+00 -1.0191337045184e+00 -1.0031384998167e+00 -1.0014582266588e+00 -1.0022544383162e+00 -1.0042438464875e+00 -1.0055806943035e+00 -1.0072952188791e+00 -1.0124736378088e+00 -1.0223189948326e+00 -1.0302574540622e+00 -1.0344611813475e+00 -1.0385615789706e+00 -1.0429704420187e+00 -1.0454903089249e+00 -1.0449815581551e+00 -1.0448418252462e+00 -1.0441578837633e+00 -1.0431144568849e+00 -1.0428711643996e+00 -1.0423849919604e+00 -1.0420766441571e+00 -1.0417728383647e+00 -1.0415087556782e+00 -1.0408962063576e+00 -1.0405725607338e+00 -1.0403079516127e+00 -1.0402313814824e+00 -1.0401428114085e+00 -1.0399405768373e+00 -1.0398401992445e+00 -1.0398214773485e+00 -1.0393903539340e+00 -1.0389412536859e+00 -1.0385490321436e+00 -1.0382944388317e+00 -1.0382827761383e+00 -1.0382760492378e+00 -1.0382503508375e+00 -1.0382107000495e+00 -1.0103950615794e+00 -1.0131922046029e+00 -1.0162369276505e+00 -1.0206253529156e+00 -1.0283977035136e+00 -1.0460031783013e+00 -1.0619969182593e+00 -1.0803852499735e+00 -1.0938725183261e+00 -1.1064747328789e+00 -1.1193143863086e+00 -1.1422221738347e+00 -1.1553800520815e+00 -1.1812780386992e+00 -1.2015320912485e+00 -1.2170028924147e+00 -1.2325710266070e+00 -1.2387081640856e+00 -1.2435103961638e+00 -1.2422217435270e+00 -1.2375655751298e+00 -1.2240369194872e+00 -1.2086370622574e+00 -1.1909218634121e+00 -1.1796581637096e+00 -1.1715154990721e+00 -1.1643630813943e+00 -1.1535971407263e+00 -1.1474896522706e+00 -1.1387714914862e+00 -1.1395960534020e+00 -1.1454846902601e+00 -1.1530168758972e+00 -1.1589992183720e+00 -1.1647994952125e+00 -1.1720225384566e+00 -1.1793198621775e+00 -1.1807065293016e+00 -1.1805641260405e+00 -1.1812655973434e+00 -1.1818748486341e+00 -1.1820828000358e+00 -1.1822821780169e+00 -1.1822366318367e+00 -1.1824095669411e+00 -1.1817999880870e+00 -1.1814570258388e+00 -1.1812353584958e+00 -1.1808734975707e+00 -1.1807641667346e+00 -1.1809325188024e+00 -1.1817891933079e+00 -1.1818522762406e+00 -1.1818563581534e+00 -1.1820737164936e+00 -1.1826296202047e+00 -1.1824030508535e+00 -1.1822424995555e+00 -1.1820251803677e+00 -1.1818264754296e+00 -1.1815830634844e+00 -1.1045123440931e+00 -1.1045308965274e+00 -1.1045383316337e+00 -1.1045921768047e+00 -1.1046051675657e+00 -1.1047239989133e+00 -1.1085601300534e+00 -1.1114367053257e+00 -1.1214329222713e+00 -1.1415282436019e+00 -1.1612479374097e+00 -1.1832092411643e+00 -1.2015914435251e+00 -1.2457628453307e+00 -1.2878340433997e+00 -1.3127683045194e+00 -1.3309400489496e+00 -1.3574767097794e+00 -1.3770202062209e+00 -1.3955110025203e+00 -1.4342250594631e+00 -1.4570020857492e+00 -1.4677557542664e+00 -1.4768316484065e+00 -1.4854845459735e+00 -1.4946646529195e+00 -1.4958439782418e+00 -1.4966414930975e+00 -1.5113438297613e+00 -1.5157848182798e+00 -1.5172124087414e+00 -1.5181521311364e+00 -1.5207421619258e+00 -1.5272790732344e+00 -1.5314651332658e+00 -1.5321268195851e+00 -1.5329612044736e+00 -1.5330872941404e+00 -1.5330478331548e+00 -1.5330486869105e+00 -1.5331081716995e+00 -1.5332162295852e+00 -1.5332056145592e+00 -1.5332011528481e+00 -1.5332004649149e+00 -1.5332192675212e+00 -1.5332271776208e+00 -1.5332235002926e+00 -1.5332302166112e+00 -1.5332495908851e+00 -1.5332727492101e+00 -1.5332686657959e+00 -1.5332393819617e+00 + 7.2547138053632e-01 7.2550586875235e-01 7.2552043140580e-01 7.2553867839803e-01 7.2558059074347e-01 7.2560064220367e-01 7.2569917106045e-01 7.2761815922511e-01 7.3162971064573e-01 7.3973885439139e-01 7.4960384683231e-01 7.6003683491576e-01 7.7434614127244e-01 7.9433111545738e-01 8.1051559675205e-01 8.2668669963991e-01 8.3934578812761e-01 8.5672961682549e-01 8.7062633157700e-01 8.8195117016767e-01 8.9411186720127e-01 9.0624683345202e-01 9.1503034123638e-01 9.2195474712076e-01 9.2658312324763e-01 9.3162316030973e-01 9.3319998167591e-01 9.3400846888705e-01 9.3429925496213e-01 9.3414271854876e-01 9.3361924186659e-01 9.3317980750858e-01 9.3331350191808e-01 9.3289255351813e-01 9.3250397123149e-01 9.3184788466584e-01 9.3088237383039e-01 9.2954104894091e-01 9.2905903464594e-01 9.2948596656447e-01 9.3041204976924e-01 9.3323562912767e-01 9.3451909460528e-01 9.3530086655239e-01 9.3550087235975e-01 9.3542811251521e-01 9.3539363903955e-01 9.3543486578083e-01 9.3567006423276e-01 9.3569126602042e-01 9.3587001569356e-01 9.3636535803712e-01 9.3676320744710e-01 9.3809631106014e-01 9.3934268513599e-01 9.4004051315076e-01 9.4044062211603e-01 9.4164214717325e-01 9.4179709744559e-01 9.4197418396648e-01 9.4260707204624e-01 9.4314283626864e-01 9.4382578470134e-01 9.4437948484804e-01 9.4478840025696e-01 9.4491254325386e-01 9.4492681442180e-01 7.8452326207566e-01 7.8460479641437e-01 7.8460872416622e-01 7.8472969563787e-01 7.8465229128704e-01 7.8435054094615e-01 7.8398892522980e-01 7.8399028363539e-01 7.8398981127774e-01 7.8418080211648e-01 7.8571298333790e-01 7.9157866338871e-01 7.9222591554682e-01 7.9297986477825e-01 8.0047470533174e-01 8.0545965116759e-01 8.1780430055553e-01 8.2957645831124e-01 8.5027545329411e-01 8.7392302839636e-01 8.9061544601323e-01 9.1113884592174e-01 9.1902766039701e-01 9.2043482673717e-01 9.2067297067737e-01 9.2018383315195e-01 9.1809202942311e-01 9.1602628310244e-01 9.0898104742141e-01 9.0123336904508e-01 8.8591852741076e-01 8.7490012544680e-01 8.6648628835868e-01 8.5537726701688e-01 8.4647749432548e-01 8.3541916159267e-01 8.2629013931677e-01 8.0992381505350e-01 7.9885565388515e-01 7.8917512506763e-01 7.7992115138184e-01 7.7168887288940e-01 7.6691307317144e-01 7.6247260522232e-01 7.6073097616146e-01 7.6044064546069e-01 7.6141435147245e-01 7.6209593001507e-01 7.6223566730251e-01 7.6239513084036e-01 7.6215181208052e-01 7.6162296868600e-01 7.6121250190123e-01 7.6067957842837e-01 7.6059727220637e-01 7.6054221925005e-01 7.6030721695662e-01 7.6024560584228e-01 7.6017022204048e-01 7.6004742789215e-01 7.6002522092126e-01 7.6001397541420e-01 7.5999459275969e-01 7.5998858288464e-01 7.5998154055926e-01 7.6001829959325e-01 7.6013601764528e-01 7.6038328533800e-01 7.6040785179721e-01 7.6042916829350e-01 7.6040786133677e-01 7.6025958764901e-01 7.6005697291612e-01 7.6006228062326e-01 7.6008041001331e-01 7.6010047889618e-01 8.1038675742138e-01 8.1038821789142e-01 8.1039265652893e-01 8.1040829772102e-01 8.1041273599731e-01 8.1041932779310e-01 8.1050160425185e-01 8.1050424468842e-01 8.1048348342034e-01 8.1050604334240e-01 8.1033247669437e-01 8.0978790450126e-01 8.1064063551790e-01 8.1159252321856e-01 8.1123795867405e-01 8.1068269731438e-01 8.1736050236814e-01 8.2563302932902e-01 8.3654194777562e-01 8.5541505962116e-01 8.7883239544247e-01 8.9281636740928e-01 9.1003973162783e-01 9.2412761805766e-01 9.4155089778184e-01 9.5489045747338e-01 9.6783158262828e-01 9.7771409906589e-01 9.8923487496128e-01 9.9397622314108e-01 9.9744829293396e-01 9.9907209487571e-01 9.9834513227227e-01 9.9703046672306e-01 9.9538328969912e-01 9.9477810850930e-01 9.9492422392894e-01 9.9508827329939e-01 9.9566679125052e-01 9.9644306123061e-01 9.9652102994325e-01 9.9651286961363e-01 9.9653458344148e-01 9.9651544101534e-01 9.9654487728107e-01 9.9663202526431e-01 9.9703636718988e-01 9.9694131540090e-01 9.9693053130612e-01 9.9691075578349e-01 9.9687222241339e-01 9.9686255313238e-01 9.9681286446831e-01 9.9673915841718e-01 9.9667885152931e-01 9.9659415411710e-01 9.9657947434434e-01 9.9665840511903e-01 9.9665814470536e-01 9.9664571618624e-01 9.9664680734540e-01 9.9668048150397e-01 9.9689824929612e-01 9.9693358767855e-01 9.9689188911759e-01 9.9677507279367e-01 9.9670701929327e-01 9.9666098883281e-01 9.9648203177615e-01 9.9646845770876e-01 7.2337099709117e-01 7.2336745405807e-01 7.2336037196786e-01 7.2335860137731e-01 7.2335791166148e-01 7.2335525671921e-01 7.2337475912357e-01 7.2339685485712e-01 7.2339867824758e-01 7.2351835134943e-01 7.2405758281325e-01 7.2682531417516e-01 7.3191128534389e-01 7.3847496817245e-01 7.4610475205019e-01 7.5377469419538e-01 7.6809717074881e-01 7.7557397618599e-01 7.8201431228656e-01 7.9060383522921e-01 7.9932885021357e-01 8.1228410817630e-01 8.2184959057273e-01 8.3307478388131e-01 8.5453392056727e-01 8.6674437438566e-01 8.7746182391435e-01 8.8576513679262e-01 9.0004348181334e-01 9.1203760620947e-01 9.1727342749887e-01 9.2073956144780e-01 9.2413390981160e-01 9.2439596655779e-01 9.2343656059843e-01 9.1993453500152e-01 9.1580314481446e-01 9.1328120907962e-01 9.1215387655223e-01 9.1293328085363e-01 9.1324747919629e-01 9.1357902728207e-01 9.1372072548541e-01 9.1378070954219e-01 9.1315021970139e-01 9.1226164599103e-01 9.1135364471628e-01 9.1057421691526e-01 9.1060401906801e-01 9.1066683309278e-01 9.1067380158221e-01 9.1075179407665e-01 9.1091661348649e-01 9.1105305854653e-01 9.1109229250310e-01 9.1114710592330e-01 9.1134900804275e-01 9.1148575207412e-01 9.1168583901097e-01 9.1219630531162e-01 9.1227336367042e-01 9.1228526510943e-01 9.1230627646626e-01 9.1234401653251e-01 9.1241923418091e-01 9.1278981082116e-01 9.1278803141043e-01 9.1278268454544e-01 9.1277871482073e-01 9.1278403468217e-01 9.1278008900452e-01 7.6633027239106e-01 7.6634564035703e-01 7.6633682604738e-01 7.6632737281685e-01 7.6632527287019e-01 7.6631372137260e-01 7.6627275718197e-01 7.6618995493296e-01 7.6611546267982e-01 7.6629754091963e-01 7.6760861999754e-01 7.7156686418764e-01 7.7853988578014e-01 7.8679990270584e-01 8.0508690397652e-01 8.1429665010199e-01 8.2182808679996e-01 8.4185101083937e-01 8.6108659837237e-01 8.7548260442903e-01 8.9368441324134e-01 9.0853349850931e-01 9.2757012666417e-01 9.3614270007808e-01 9.4416571803731e-01 9.6014452425407e-01 9.6919171908840e-01 9.7422869535403e-01 9.7895741048992e-01 9.8148601433566e-01 9.8332710653381e-01 9.8415625963169e-01 9.8393744693438e-01 9.8349860845697e-01 9.8284632506159e-01 9.8283520051006e-01 9.8264300265992e-01 9.8189682494454e-01 9.8131024778664e-01 9.8117276918541e-01 9.8130756430898e-01 9.8117089004087e-01 9.8123490818638e-01 9.8127120724858e-01 9.8130396602088e-01 9.8131280097735e-01 9.8131634323723e-01 9.8134501375226e-01 9.8137338973440e-01 9.8142560094612e-01 9.8161735369261e-01 9.8175079478919e-01 9.8193249368512e-01 9.8245261975564e-01 9.8253844185690e-01 9.8257218641403e-01 9.8261191259032e-01 9.8264595001258e-01 9.8267613864444e-01 9.8273198463073e-01 9.8292940194902e-01 9.8308951625084e-01 9.8314619417427e-01 7.0188197782196e-01 7.0182924908740e-01 7.0183176312766e-01 7.0146876037523e-01 7.0141193060193e-01 7.0153025628417e-01 7.0218591723597e-01 7.0218678625206e-01 7.0174295727739e-01 6.9698732268317e-01 6.9820228361452e-01 7.0460023625018e-01 7.1542099246050e-01 7.2607692179666e-01 7.3866329019334e-01 7.5613039243889e-01 7.6461369696435e-01 7.7361668271993e-01 8.0208525211285e-01 8.1821884014833e-01 8.3860168369588e-01 8.5472175573836e-01 8.7613297677121e-01 8.8632375614266e-01 8.9027328465633e-01 8.9894790604199e-01 8.9859086731570e-01 8.9544130515461e-01 8.8415774893609e-01 8.7183737626107e-01 8.5352154526682e-01 8.5104507632400e-01 8.4198777122344e-01 8.4067870976885e-01 8.4038373879374e-01 8.4049341437105e-01 8.3943235132589e-01 8.3911683356428e-01 8.4054884067278e-01 8.4367500035763e-01 8.4629482184121e-01 8.4766881956809e-01 8.4854557050887e-01 8.4950683674506e-01 8.5023130144680e-01 8.5029830158009e-01 8.5037439417384e-01 8.5048941332838e-01 8.5063018539416e-01 8.5074184293973e-01 8.5091501284400e-01 8.5093888699073e-01 8.5095316187528e-01 8.5095644827266e-01 8.5094379030737e-01 8.5095500230574e-01 8.5094893436520e-01 8.5093627213458e-01 8.5092646814797e-01 8.5089509701704e-01 8.5085848201082e-01 8.5085759334912e-01 8.5082450996706e-01 8.5077195851289e-01 8.5071082646132e-01 8.5068745873840e-01 8.5068874936462e-01 8.5069377740207e-01 8.5069452782991e-01 8.5069089974464e-01 7.4615268006886e-01 7.4838138442804e-01 7.5082527697506e-01 7.5436855188699e-01 7.6069210830137e-01 7.7511454465497e-01 7.8833231547396e-01 8.0358036662323e-01 8.1474531342736e-01 8.2509668740477e-01 8.3573665785292e-01 8.5409586818656e-01 8.6443796593216e-01 8.8486524888472e-01 9.0040283872254e-01 9.1260041158351e-01 9.2623305146596e-01 9.3318427994981e-01 9.3893369663349e-01 9.4293007188220e-01 9.4300243518132e-01 9.3993527186205e-01 9.3497205705565e-01 9.2810166037006e-01 9.2305151912536e-01 9.1917117820900e-01 9.1574161047006e-01 9.1018947667834e-01 9.0696008147088e-01 9.0189229592835e-01 9.0130399671514e-01 9.0306826238694e-01 9.0466773926335e-01 9.0613090943531e-01 9.0715800243978e-01 9.0841177625485e-01 9.0928121144067e-01 9.0936901006098e-01 9.0928352607423e-01 9.0936407369869e-01 9.0962282996415e-01 9.0983984955931e-01 9.1032061158077e-01 9.1048918301821e-01 9.1068996178287e-01 9.1073480198625e-01 9.1074757540001e-01 9.1089440352555e-01 9.1080490101667e-01 9.1081762808479e-01 9.1100133932994e-01 9.1162620576055e-01 9.1170024565967e-01 9.1173187189811e-01 9.1187228641227e-01 9.1212296898499e-01 9.1202750853750e-01 9.1195822996749e-01 9.1188486795726e-01 9.1194819116338e-01 9.1185064985882e-01 7.7375825252429e-01 7.7377438317972e-01 7.7378084779099e-01 7.7382766566693e-01 7.7383896128860e-01 7.7392506408181e-01 7.7669712558371e-01 7.7879098111086e-01 7.8615033869948e-01 8.0106096852364e-01 8.1579410808103e-01 8.3215238891568e-01 8.4569373095943e-01 8.7796812721072e-01 9.0839429965164e-01 9.2598339736674e-01 9.3874092146049e-01 9.5693694447270e-01 9.6810873506072e-01 9.7650191980489e-01 9.8801102619219e-01 9.9213140838724e-01 9.9296719864670e-01 9.9228334376523e-01 9.9261155785864e-01 9.9337817674964e-01 9.9319659037930e-01 9.9255985717487e-01 9.9398078392977e-01 9.9507624902517e-01 9.9541323229167e-01 9.9561188181474e-01 9.9576083762793e-01 9.9626506368253e-01 9.9663992753610e-01 9.9678978926297e-01 9.9688599273667e-01 9.9694178037603e-01 9.9692346587819e-01 9.9692522802460e-01 9.9696407275529e-01 9.9703738918290e-01 9.9703264780903e-01 9.9703254190659e-01 9.9703593329286e-01 9.9704989275887e-01 9.9705843308944e-01 9.9707356995135e-01 9.9707816786335e-01 9.9709033919671e-01 9.9711256556949e-01 9.9711031645589e-01 9.9709970547040e-01 4.9132092157828e-01 4.9131791296270e-01 4.9128625291674e-01 4.9124658189176e-01 4.9115545543862e-01 4.9111185714574e-01 4.9107902630444e-01 4.9094872460474e-01 4.8977900975935e-01 4.8396153902339e-01 4.7594574332314e-01 4.6643845988525e-01 4.5195548694955e-01 4.3351371907086e-01 4.1698712738685e-01 3.9895872938060e-01 3.8327900941866e-01 3.5893159849612e-01 3.3672757153594e-01 3.1844432819955e-01 2.9900253577274e-01 2.7688382127935e-01 2.5672805529434e-01 2.3497434896845e-01 2.1685746437086e-01 1.8857843622591e-01 1.7421479359073e-01 1.6241136924106e-01 1.4797343228765e-01 1.2910122627854e-01 1.1291769459170e-01 9.8208361370556e-02 8.6085579617525e-02 6.8943221651565e-02 6.0884248912272e-02 5.1048494913816e-02 3.7389108606785e-02 2.6559439819404e-02 2.1192625032161e-02 1.6415123532918e-02 1.1007009410506e-02 3.5530187839253e-03 1.9523306319200e-03 1.9613719010121e-03 1.9729011645831e-03 2.1135766104165e-03 2.3019622654823e-03 2.3565019010317e-03 2.4601261125062e-03 1.9326264433861e-03 4.0398895055376e-04 3.2969143564730e-04 3.2656600511709e-04 2.6714727153543e-04 1.6942650392704e-04 1.1482388856801e-04 6.7257748657885e-05 -1.9461007340415e-05 -5.8616413473030e-05 -5.6947740768212e-05 -4.7905143329514e-05 -2.6204180134776e-05 -1.9872362008343e-05 -1.6394700038279e-05 -2.9586239707115e-06 1.0429658861575e-06 -4.5020617995630e-15 3.9650428365570e-01 3.9647109082315e-01 3.9651892545606e-01 3.9650720073637e-01 3.9654080688700e-01 3.9656355051838e-01 3.9670460570656e-01 3.9669364632931e-01 3.9671045997172e-01 3.9672548709433e-01 3.9677278445444e-01 3.9671153057775e-01 3.9592853339189e-01 3.9751821462897e-01 3.9997095043849e-01 4.0276442362044e-01 4.0512656903144e-01 4.0141978344869e-01 3.8741364648515e-01 3.6630902094659e-01 3.4899316089366e-01 3.1793856885928e-01 2.9633494328945e-01 2.8517996352174e-01 2.6871913600482e-01 2.5393434475730e-01 2.3160497807276e-01 2.1699064687950e-01 1.9409404195808e-01 1.7900390681600e-01 1.5587161601668e-01 1.3990667014161e-01 1.2698338759627e-01 1.1152786933542e-01 9.9970357831962e-02 8.7512061488743e-02 7.8611928071416e-02 6.4882926155729e-02 5.7443196900756e-02 5.0616726186306e-02 4.2025301842204e-02 3.2956216045415e-02 2.7910448904982e-02 2.2265285798408e-02 1.8995415177721e-02 1.3785603497257e-02 9.7736562250191e-03 8.5817198459032e-03 8.5684213140256e-03 8.5046021165575e-03 8.2498729053489e-03 6.8174726806616e-03 6.0629559436209e-03 4.8879366829291e-03 4.7979254653204e-03 4.6285609113783e-03 4.5785377590271e-03 4.4152110968654e-03 3.9367968274772e-03 3.7641332927412e-03 3.7123147107007e-03 3.5999987802305e-03 3.3809663271340e-03 3.3546160313564e-03 3.3265107113651e-03 3.2781687186073e-03 3.3111924297282e-03 3.4647560712701e-03 3.3967077820443e-03 3.3564349931252e-03 3.1699076226998e-03 2.4540566787548e-03 2.3561309801115e-04 -4.7669131915036e-05 -2.1625169569493e-05 -1.7305365416348e-15 3.8584723650338e-01 3.8584397480082e-01 3.8583406175678e-01 3.8576498912010e-01 3.8575507575920e-01 3.8573974247840e-01 3.8572656715549e-01 3.8572010883816e-01 3.8566414476155e-01 3.8557954542401e-01 3.8552364212358e-01 3.8551046564710e-01 3.8486618341528e-01 3.8372455951663e-01 3.8168831791640e-01 3.7888665889310e-01 3.7351965022234e-01 3.6776432929306e-01 3.5742842147263e-01 3.3607900406201e-01 3.0869536021262e-01 2.8944091943544e-01 2.6365580646629e-01 2.4051962602791e-01 2.0819156115411e-01 1.8077390914536e-01 1.5234711807458e-01 1.2940179860218e-01 9.9982847662908e-02 8.4881761675905e-02 6.8416162453927e-02 4.8345108337480e-02 3.6918381587125e-02 2.8966982869615e-02 2.0123975704673e-02 1.4520012323762e-02 1.1981065267259e-02 9.9563306151589e-03 9.0944739017474e-03 6.9217562234367e-03 5.1029238329996e-03 4.0785533585161e-03 3.5975214002062e-03 3.0886637465798e-03 3.0872955161778e-03 3.0947357842083e-03 2.8358640209284e-03 2.3552008564000e-03 2.3260624602231e-03 2.1703716926110e-03 1.7962759197695e-03 1.6824899401410e-03 1.1787855437825e-03 5.8778735506141e-04 3.4455829358738e-04 1.8481453070288e-05 -1.1567197800361e-04 -1.6556081001194e-04 -1.9517332001100e-04 -3.3059160681235e-04 -3.4174649827557e-04 -3.4260267779395e-04 -4.9434860612205e-04 -5.5605509146166e-04 -5.4563014390619e-04 -1.8636079515263e-04 -1.5425048743128e-04 -1.2168019713227e-04 -3.2836263742878e-05 -4.7323941794568e-16 3.7571033476907e-01 3.7571036676152e-01 3.7571043133048e-01 3.7571044760247e-01 3.7570741723627e-01 3.7570744189360e-01 3.7569956739349e-01 3.7565232106499e-01 3.7564842214761e-01 3.7556753942868e-01 3.7543078195267e-01 3.7472352552427e-01 3.7201426801766e-01 3.6824661547748e-01 3.6199114537496e-01 3.5520699001155e-01 3.4116601464417e-01 3.3246600773112e-01 3.2509858789182e-01 3.1674445339581e-01 3.0814779964767e-01 2.9395357692159e-01 2.8355387178451e-01 2.7238502627939e-01 2.4947566884727e-01 2.3419104608632e-01 2.1831935406880e-01 2.0455396252466e-01 1.8262610797955e-01 1.5973452904411e-01 1.4666068938304e-01 1.3481596429357e-01 1.1577432913204e-01 1.0660919773350e-01 9.9782603189796e-02 8.9236246341793e-02 7.5393573967910e-02 6.5670077927361e-02 5.5227880522286e-02 3.9275072123319e-02 2.7161270845411e-02 1.6114758345217e-02 1.3315326665828e-02 1.1134414860836e-02 8.4444059059339e-03 6.8422865743891e-03 4.4661758942262e-03 6.2381097910029e-04 -2.6837405047241e-04 -2.6363890576989e-04 -2.7387491023587e-04 -3.8129091290566e-04 -4.9507338908772e-04 -7.7361428857247e-04 -8.8439176255537e-04 -9.9993669136253e-04 -7.5672318046140e-04 -5.3132941053227e-04 -2.7704251924881e-04 -8.6268195509908e-05 3.7815482456907e-05 8.1823611495153e-05 1.6336173304041e-05 -8.5807093376195e-05 -8.6971641905775e-05 -8.6780667624906e-05 -4.4576367715083e-05 2.6319422538635e-05 2.5485891410710e-05 2.1522727476288e-06 -1.8004507676361e-15 4.0845892215465e-01 4.0844256833991e-01 4.0845494294735e-01 4.0846951667738e-01 4.0847275404812e-01 4.0849056204300e-01 4.0855370900790e-01 4.0855526193692e-01 4.0854545256375e-01 4.0844079032673e-01 4.0727213822946e-01 4.0353847727964e-01 3.9800822169377e-01 3.9007265352218e-01 3.7447170198476e-01 3.6733672163481e-01 3.5919849820384e-01 3.3784628625474e-01 3.1742812096194e-01 3.0096233214967e-01 2.7910241205345e-01 2.5923433094214e-01 2.2990202245884e-01 2.1440025637125e-01 1.9987666869843e-01 1.6703745236209e-01 1.4422739147852e-01 1.2751159053202e-01 1.0914128940606e-01 9.5685332349521e-02 7.9183988651175e-02 6.4804019794154e-02 5.3826940537986e-02 4.3890840122042e-02 2.8229049695206e-02 2.1177193246988e-02 1.4830419523047e-02 7.0365911617835e-03 2.7076322626049e-03 2.3301936881583e-03 1.8732682057935e-03 1.1704724896670e-03 1.1800903044241e-03 1.2135211571177e-03 1.2305286586639e-03 1.2374020549999e-03 1.2473619898703e-03 1.2851530591527e-03 1.2983540592557e-03 1.3124212352530e-03 1.2557824948973e-03 1.0158249085544e-03 8.7737698162466e-04 6.4044889417121e-04 5.0453092115418e-04 3.2425309946007e-04 3.4019186287562e-04 3.1216451415434e-04 3.1658547731947e-04 3.1470636180851e-04 2.2491634123057e-04 9.0261545951197e-05 -4.9315579835199e-15 3.8249826588296e-01 3.8246933481790e-01 3.8243076472689e-01 3.8229256410648e-01 3.8228613626085e-01 3.8218651919411e-01 3.8184474102020e-01 3.8184530526514e-01 3.8183566999343e-01 3.8054852988134e-01 3.7979952106769e-01 3.7538271136930e-01 3.6711621027667e-01 3.5908588123701e-01 3.4993967657935e-01 3.3707695152796e-01 3.3041563688598e-01 3.2458904382664e-01 3.0924804026721e-01 2.9621391088720e-01 2.7761273769771e-01 2.5872135797900e-01 2.2585426394913e-01 2.0452290991229e-01 1.9486962044590e-01 1.6856626566157e-01 1.5248978493569e-01 1.4421913454419e-01 1.3117645522368e-01 1.2357916900821e-01 1.0933037948844e-01 1.0608963362761e-01 9.1487709271980e-02 8.2637791068926e-02 7.0771315217972e-02 5.9842377211448e-02 4.6731408090353e-02 4.0812350189117e-02 3.3692013023650e-02 2.3876886046111e-02 1.5522692947809e-02 1.1748190275050e-02 9.5603207407585e-03 6.7130699516260e-03 5.0883412763075e-03 5.0251971183316e-03 4.6388123972166e-03 3.9589876740030e-03 3.0888563545624e-03 2.4279736865173e-03 1.4248559404332e-03 1.1678867541978e-03 1.0047596871891e-03 9.0843265072446e-04 6.4122351376005e-04 2.7398494038122e-04 1.6655807416114e-04 1.8326833900942e-04 1.6811624998773e-04 1.3538752969916e-04 1.0840978430669e-04 1.0806754419852e-04 7.3680576881108e-05 5.2430408486504e-05 1.0647162350015e-04 4.4239264089015e-05 4.5196846083374e-05 3.1735011939226e-05 2.9440924780718e-06 -2.0473592345676e-16 5.1277641705485e-01 5.1273601426188e-01 5.1211400768954e-01 5.1068103369061e-01 5.0682756897302e-01 4.9554213418644e-01 4.8217058830568e-01 4.6560665493784e-01 4.5243231673626e-01 4.4375368856220e-01 4.3218113018267e-01 4.1280637953741e-01 3.9996082868758e-01 3.6810436684932e-01 3.4235364788571e-01 3.1836063306509e-01 2.8990745230455e-01 2.7241770775753e-01 2.5481815319644e-01 2.3060574011016e-01 2.1825355495455e-01 1.9757619153823e-01 1.7911954838989e-01 1.5584033146697e-01 1.4084600442906e-01 1.3116758226842e-01 1.2241530998611e-01 1.0930972221173e-01 1.0154295045755e-01 8.7533476871240e-02 7.2440671091515e-02 5.7426897066688e-02 4.0010473608614e-02 3.0975065478236e-02 2.2546024499148e-02 1.2815219492692e-02 1.2590113525622e-03 -1.1805308140573e-03 -1.0795721698866e-03 -7.1208402665881e-04 -5.4039240091435e-04 3.0196019171795e-04 2.5404307304675e-04 6.9492612794820e-05 -2.7164487649200e-05 -2.8796111609551e-04 -4.4020836615651e-04 -6.8030831613502e-04 -7.1586922653232e-04 -7.4603923571525e-04 -8.1634037923125e-04 -1.0779482029921e-04 4.2368378527509e-04 3.9285686783364e-04 2.9823262187203e-04 1.5713885308117e-04 1.7367459652577e-04 1.8626744601350e-04 1.6231216752894e-04 8.5337726086292e-06 1.6728936764753e-15 3.4314151795217e-01 3.4310672946848e-01 3.4309278690725e-01 3.4299180324013e-01 3.4296743678127e-01 3.4296391716796e-01 3.4291777016886e-01 3.4243647386780e-01 3.3833525907191e-01 3.2669209163167e-01 3.1179652059865e-01 2.9457845255325e-01 2.8050614551927e-01 2.5745926112597e-01 2.3391363202641e-01 2.0542900434019e-01 1.8119915603310e-01 1.4504176235371e-01 1.2605164400012e-01 1.0821196990487e-01 6.6879439209324e-02 4.3676466117068e-02 3.2283832396233e-02 2.2768118318116e-02 1.6433225412330e-02 9.7512634752960e-03 8.0898177481121e-03 6.7302337018383e-03 -3.2564137060710e-03 -3.5393682242533e-03 -8.4343761909380e-04 5.6396765183738e-04 4.7853004478567e-04 4.0092375868784e-04 3.3828533735003e-04 5.6407586396999e-04 4.9657607309772e-04 4.2437294668428e-04 3.3948631319357e-04 3.0778872184818e-04 2.8994139670526e-04 2.5213353575175e-04 2.5082184758887e-04 2.3362177554165e-04 2.1208176525093e-04 1.9323914385344e-04 1.8656919775266e-04 8.5792532850190e-05 8.1765248614588e-05 7.7722890999636e-05 2.9428039198463e-05 2.8092128415764e-05 -3.3355529976145e-15 + 4.9132092157828e-01 4.9131791296270e-01 4.9128625291674e-01 4.9124658189176e-01 4.9115545543862e-01 4.9111185714574e-01 4.9107902630444e-01 4.9094872460474e-01 4.8977900975935e-01 4.8396153902339e-01 4.7594574332314e-01 4.6643845988525e-01 4.5195548694955e-01 4.3351371907086e-01 4.1698712738685e-01 3.9895872938060e-01 3.8327900941866e-01 3.5893159849612e-01 3.3672757153594e-01 3.1844432819955e-01 2.9900253577274e-01 2.7688382127935e-01 2.5672805529434e-01 2.3497434896845e-01 2.1685746437086e-01 1.8857843622591e-01 1.7421479359073e-01 1.6241136924106e-01 1.4797343228765e-01 1.2910122627854e-01 1.1291769459170e-01 9.8208361370556e-02 8.6085579617525e-02 6.8943221651565e-02 6.0884248912272e-02 5.1048494913816e-02 3.7389108606785e-02 2.6559439819404e-02 2.1192625032161e-02 1.6415123532918e-02 1.1007009410506e-02 3.5530187839253e-03 1.9523306319200e-03 1.9613719010121e-03 1.9729011645831e-03 2.1135766104165e-03 2.3019622654823e-03 2.3565019010317e-03 2.4601261125062e-03 1.9326264433861e-03 4.0398895055376e-04 3.2969143564730e-04 3.2656600511709e-04 2.6714727153543e-04 1.6942650392704e-04 1.1482388856801e-04 6.7257748657885e-05 -1.9461007340415e-05 -5.8616413473030e-05 -5.6947740768212e-05 -4.7905143329514e-05 -2.6204180134776e-05 -1.9872362008343e-05 -1.6394700038279e-05 -2.9586239707115e-06 1.0429658861575e-06 -4.5020617995630e-15 3.9650428365570e-01 3.9647109082315e-01 3.9651892545606e-01 3.9650720073637e-01 3.9654080688700e-01 3.9656355051838e-01 3.9670460570656e-01 3.9669364632931e-01 3.9671045997172e-01 3.9672548709433e-01 3.9677278445444e-01 3.9671153057775e-01 3.9592853339189e-01 3.9751821462897e-01 3.9997095043849e-01 4.0276442362044e-01 4.0512656903144e-01 4.0141978344869e-01 3.8741364648515e-01 3.6630902094659e-01 3.4899316089366e-01 3.1793856885928e-01 2.9633494328945e-01 2.8517996352174e-01 2.6871913600482e-01 2.5393434475730e-01 2.3160497807276e-01 2.1699064687950e-01 1.9409404195808e-01 1.7900390681600e-01 1.5587161601668e-01 1.3990667014161e-01 1.2698338759627e-01 1.1152786933542e-01 9.9970357831962e-02 8.7512061488743e-02 7.8611928071416e-02 6.4882926155729e-02 5.7443196900756e-02 5.0616726186306e-02 4.2025301842204e-02 3.2956216045415e-02 2.7910448904982e-02 2.2265285798408e-02 1.8995415177721e-02 1.3785603497257e-02 9.7736562250191e-03 8.5817198459032e-03 8.5684213140256e-03 8.5046021165575e-03 8.2498729053489e-03 6.8174726806616e-03 6.0629559436209e-03 4.8879366829291e-03 4.7979254653204e-03 4.6285609113783e-03 4.5785377590271e-03 4.4152110968654e-03 3.9367968274772e-03 3.7641332927412e-03 3.7123147107007e-03 3.5999987802305e-03 3.3809663271340e-03 3.3546160313564e-03 3.3265107113651e-03 3.2781687186073e-03 3.3111924297282e-03 3.4647560712701e-03 3.3967077820443e-03 3.3564349931252e-03 3.1699076226998e-03 2.4540566787548e-03 2.3561309801115e-04 -4.7669131915036e-05 -2.1625169569493e-05 -1.7305365416348e-15 3.8584723650338e-01 3.8584397480082e-01 3.8583406175678e-01 3.8576498912010e-01 3.8575507575920e-01 3.8573974247840e-01 3.8572656715549e-01 3.8572010883816e-01 3.8566414476155e-01 3.8557954542401e-01 3.8552364212358e-01 3.8551046564710e-01 3.8486618341528e-01 3.8372455951663e-01 3.8168831791640e-01 3.7888665889310e-01 3.7351965022234e-01 3.6776432929306e-01 3.5742842147263e-01 3.3607900406201e-01 3.0869536021262e-01 2.8944091943544e-01 2.6365580646629e-01 2.4051962602791e-01 2.0819156115411e-01 1.8077390914536e-01 1.5234711807458e-01 1.2940179860218e-01 9.9982847662908e-02 8.4881761675905e-02 6.8416162453927e-02 4.8345108337480e-02 3.6918381587125e-02 2.8966982869615e-02 2.0123975704673e-02 1.4520012323762e-02 1.1981065267259e-02 9.9563306151589e-03 9.0944739017474e-03 6.9217562234367e-03 5.1029238329996e-03 4.0785533585161e-03 3.5975214002062e-03 3.0886637465798e-03 3.0872955161778e-03 3.0947357842083e-03 2.8358640209284e-03 2.3552008564000e-03 2.3260624602231e-03 2.1703716926110e-03 1.7962759197695e-03 1.6824899401410e-03 1.1787855437825e-03 5.8778735506141e-04 3.4455829358738e-04 1.8481453070288e-05 -1.1567197800361e-04 -1.6556081001194e-04 -1.9517332001100e-04 -3.3059160681235e-04 -3.4174649827557e-04 -3.4260267779395e-04 -4.9434860612205e-04 -5.5605509146166e-04 -5.4563014390619e-04 -1.8636079515263e-04 -1.5425048743128e-04 -1.2168019713227e-04 -3.2836263742878e-05 -4.7323941794568e-16 3.7571033476907e-01 3.7571036676152e-01 3.7571043133048e-01 3.7571044760247e-01 3.7570741723627e-01 3.7570744189360e-01 3.7569956739349e-01 3.7565232106499e-01 3.7564842214761e-01 3.7556753942868e-01 3.7543078195267e-01 3.7472352552427e-01 3.7201426801766e-01 3.6824661547748e-01 3.6199114537496e-01 3.5520699001155e-01 3.4116601464417e-01 3.3246600773112e-01 3.2509858789182e-01 3.1674445339581e-01 3.0814779964767e-01 2.9395357692159e-01 2.8355387178451e-01 2.7238502627939e-01 2.4947566884727e-01 2.3419104608632e-01 2.1831935406880e-01 2.0455396252466e-01 1.8262610797955e-01 1.5973452904411e-01 1.4666068938304e-01 1.3481596429357e-01 1.1577432913204e-01 1.0660919773350e-01 9.9782603189796e-02 8.9236246341793e-02 7.5393573967910e-02 6.5670077927361e-02 5.5227880522286e-02 3.9275072123319e-02 2.7161270845411e-02 1.6114758345217e-02 1.3315326665828e-02 1.1134414860836e-02 8.4444059059339e-03 6.8422865743891e-03 4.4661758942262e-03 6.2381097910029e-04 -2.6837405047241e-04 -2.6363890576989e-04 -2.7387491023587e-04 -3.8129091290566e-04 -4.9507338908772e-04 -7.7361428857247e-04 -8.8439176255537e-04 -9.9993669136253e-04 -7.5672318046140e-04 -5.3132941053227e-04 -2.7704251924881e-04 -8.6268195509908e-05 3.7815482456907e-05 8.1823611495153e-05 1.6336173304041e-05 -8.5807093376195e-05 -8.6971641905775e-05 -8.6780667624906e-05 -4.4576367715083e-05 2.6319422538635e-05 2.5485891410710e-05 2.1522727476288e-06 -1.8004507676361e-15 4.0845892215465e-01 4.0844256833991e-01 4.0845494294735e-01 4.0846951667738e-01 4.0847275404812e-01 4.0849056204300e-01 4.0855370900790e-01 4.0855526193692e-01 4.0854545256375e-01 4.0844079032673e-01 4.0727213822946e-01 4.0353847727964e-01 3.9800822169377e-01 3.9007265352218e-01 3.7447170198476e-01 3.6733672163481e-01 3.5919849820384e-01 3.3784628625474e-01 3.1742812096194e-01 3.0096233214967e-01 2.7910241205345e-01 2.5923433094214e-01 2.2990202245884e-01 2.1440025637125e-01 1.9987666869843e-01 1.6703745236209e-01 1.4422739147852e-01 1.2751159053202e-01 1.0914128940606e-01 9.5685332349521e-02 7.9183988651175e-02 6.4804019794154e-02 5.3826940537986e-02 4.3890840122042e-02 2.8229049695206e-02 2.1177193246988e-02 1.4830419523047e-02 7.0365911617835e-03 2.7076322626049e-03 2.3301936881583e-03 1.8732682057935e-03 1.1704724896670e-03 1.1800903044241e-03 1.2135211571177e-03 1.2305286586639e-03 1.2374020549999e-03 1.2473619898703e-03 1.2851530591527e-03 1.2983540592557e-03 1.3124212352530e-03 1.2557824948973e-03 1.0158249085544e-03 8.7737698162466e-04 6.4044889417121e-04 5.0453092115418e-04 3.2425309946007e-04 3.4019186287562e-04 3.1216451415434e-04 3.1658547731947e-04 3.1470636180851e-04 2.2491634123057e-04 9.0261545951197e-05 -4.9315579835199e-15 3.8249826588296e-01 3.8246933481790e-01 3.8243076472689e-01 3.8229256410648e-01 3.8228613626085e-01 3.8218651919411e-01 3.8184474102020e-01 3.8184530526514e-01 3.8183566999343e-01 3.8054852988134e-01 3.7979952106769e-01 3.7538271136930e-01 3.6711621027667e-01 3.5908588123701e-01 3.4993967657935e-01 3.3707695152796e-01 3.3041563688598e-01 3.2458904382664e-01 3.0924804026721e-01 2.9621391088720e-01 2.7761273769771e-01 2.5872135797900e-01 2.2585426394913e-01 2.0452290991229e-01 1.9486962044590e-01 1.6856626566157e-01 1.5248978493569e-01 1.4421913454419e-01 1.3117645522368e-01 1.2357916900821e-01 1.0933037948844e-01 1.0608963362761e-01 9.1487709271980e-02 8.2637791068926e-02 7.0771315217972e-02 5.9842377211448e-02 4.6731408090353e-02 4.0812350189117e-02 3.3692013023650e-02 2.3876886046111e-02 1.5522692947809e-02 1.1748190275050e-02 9.5603207407585e-03 6.7130699516260e-03 5.0883412763075e-03 5.0251971183316e-03 4.6388123972166e-03 3.9589876740030e-03 3.0888563545624e-03 2.4279736865173e-03 1.4248559404332e-03 1.1678867541978e-03 1.0047596871891e-03 9.0843265072446e-04 6.4122351376005e-04 2.7398494038122e-04 1.6655807416114e-04 1.8326833900942e-04 1.6811624998773e-04 1.3538752969916e-04 1.0840978430669e-04 1.0806754419852e-04 7.3680576881108e-05 5.2430408486504e-05 1.0647162350015e-04 4.4239264089015e-05 4.5196846083374e-05 3.1735011939226e-05 2.9440924780718e-06 -2.0473592345676e-16 5.1277641705485e-01 5.1273601426188e-01 5.1211400768954e-01 5.1068103369061e-01 5.0682756897302e-01 4.9554213418644e-01 4.8217058830568e-01 4.6560665493784e-01 4.5243231673626e-01 4.4375368856220e-01 4.3218113018267e-01 4.1280637953741e-01 3.9996082868758e-01 3.6810436684932e-01 3.4235364788571e-01 3.1836063306509e-01 2.8990745230455e-01 2.7241770775753e-01 2.5481815319644e-01 2.3060574011016e-01 2.1825355495455e-01 1.9757619153823e-01 1.7911954838989e-01 1.5584033146697e-01 1.4084600442906e-01 1.3116758226842e-01 1.2241530998611e-01 1.0930972221173e-01 1.0154295045755e-01 8.7533476871240e-02 7.2440671091515e-02 5.7426897066688e-02 4.0010473608614e-02 3.0975065478236e-02 2.2546024499148e-02 1.2815219492692e-02 1.2590113525622e-03 -1.1805308140573e-03 -1.0795721698866e-03 -7.1208402665881e-04 -5.4039240091435e-04 3.0196019171795e-04 2.5404307304675e-04 6.9492612794820e-05 -2.7164487649200e-05 -2.8796111609551e-04 -4.4020836615651e-04 -6.8030831613502e-04 -7.1586922653232e-04 -7.4603923571525e-04 -8.1634037923125e-04 -1.0779482029921e-04 4.2368378527509e-04 3.9285686783364e-04 2.9823262187203e-04 1.5713885308117e-04 1.7367459652577e-04 1.8626744601350e-04 1.6231216752894e-04 8.5337726086292e-06 1.6728936764753e-15 3.4314151795217e-01 3.4310672946848e-01 3.4309278690725e-01 3.4299180324013e-01 3.4296743678127e-01 3.4296391716796e-01 3.4291777016886e-01 3.4243647386780e-01 3.3833525907191e-01 3.2669209163167e-01 3.1179652059865e-01 2.9457845255325e-01 2.8050614551927e-01 2.5745926112597e-01 2.3391363202641e-01 2.0542900434019e-01 1.8119915603310e-01 1.4504176235371e-01 1.2605164400012e-01 1.0821196990487e-01 6.6879439209324e-02 4.3676466117068e-02 3.2283832396233e-02 2.2768118318116e-02 1.6433225412330e-02 9.7512634752960e-03 8.0898177481121e-03 6.7302337018383e-03 -3.2564137060710e-03 -3.5393682242533e-03 -8.4343761909380e-04 5.6396765183738e-04 4.7853004478567e-04 4.0092375868784e-04 3.3828533735003e-04 5.6407586396999e-04 4.9657607309772e-04 4.2437294668428e-04 3.3948631319357e-04 3.0778872184818e-04 2.8994139670526e-04 2.5213353575175e-04 2.5082184758887e-04 2.3362177554165e-04 2.1208176525093e-04 1.9323914385344e-04 1.8656919775266e-04 8.5792532850190e-05 8.1765248614588e-05 7.7722890999636e-05 2.9428039198463e-05 2.8092128415764e-05 -3.3355529976145e-15 -4.4310515132990e-01 -4.4310570564995e-01 -4.4310944502040e-01 -4.4311412920405e-01 -4.4312488327682e-01 -4.4313002559441e-01 -4.4313449353598e-01 -4.4315818819482e-01 -4.4337138896134e-01 -4.4427460544893e-01 -4.4471267433492e-01 -4.4243340898152e-01 -4.3727770458873e-01 -4.3068248988314e-01 -4.2784501285162e-01 -4.2410856888121e-01 -4.1770979254170e-01 -4.0453217844729e-01 -3.9154286396434e-01 -3.8048309830817e-01 -3.6750774552965e-01 -3.5048975229230e-01 -3.3460464552099e-01 -3.1665164140605e-01 -3.0071213323355e-01 -2.7394903118053e-01 -2.5793443114867e-01 -2.4210965943080e-01 -2.2106240997019e-01 -1.9489393079393e-01 -1.7412289391996e-01 -1.5571272772748e-01 -1.4147126851356e-01 -1.1915244517728e-01 -1.0721981610049e-01 -9.1233370681497e-02 -6.8517349234221e-02 -4.9117886787248e-02 -3.8646427265139e-02 -2.7155811096165e-02 -1.5544871170283e-02 9.8633972987131e-04 4.1300825324897e-03 5.1299247884116e-03 5.4116291164010e-03 5.0758165733943e-03 4.6915501101167e-03 4.4844821331180e-03 4.3182963254872e-03 3.3732161069549e-03 3.0951105172740e-03 9.6006855048883e-04 1.5429753585280e-03 2.9206288069339e-03 2.6658621254023e-03 2.0484068940984e-03 1.2377567359497e-03 5.5277619186848e-04 2.7115823597397e-04 3.1360561505333e-04 8.6512769607488e-04 1.2188052726228e-03 9.0340288049271e-04 3.4482181259393e-04 -9.7149637777988e-06 1.4151748177142e-05 -1.2524622644667e-15 -1.9845657645219e-01 -1.9841955706227e-01 -1.9844849016970e-01 -1.9843592083077e-01 -1.9846060115357e-01 -1.9852093869135e-01 -1.9869932968397e-01 -1.9868969840345e-01 -1.9870202969019e-01 -1.9871636265815e-01 -1.9875460278284e-01 -1.9845510154171e-01 -1.9374003526968e-01 -1.8729647385247e-01 -1.7234536473730e-01 -1.6161880420547e-01 -1.3888866250969e-01 -1.2202837255001e-01 -9.7213887002394e-02 -6.9228820684327e-02 -4.7120367582367e-02 -1.1480533707283e-02 8.6360558032207e-03 1.6065493844912e-02 2.3248524069810e-02 2.8304077994396e-02 3.6183842886116e-02 4.2474324470260e-02 4.6725892910421e-02 4.6763168341197e-02 4.2547668006572e-02 3.8386694646355e-02 3.5032052484607e-02 2.8639315061456e-02 2.3467928325835e-02 1.8266587213240e-02 1.4211798043778e-02 5.6331513307570e-03 -3.7858909927544e-04 -4.0928880755512e-03 -3.8166298046066e-03 -1.5616252407071e-04 2.8408818571116e-03 6.0050451524932e-03 6.9206226798896e-03 6.8367439034246e-03 8.2300959508942e-03 9.4712849760909e-03 9.6879777567385e-03 1.0246137273843e-02 1.0070026718934e-02 8.2739884833723e-03 7.3187849797562e-03 5.8906889026512e-03 5.7673655299512e-03 5.5720882974650e-03 5.3908125492652e-03 5.1494026463811e-03 4.5869338340107e-03 4.3418570074511e-03 4.2776145141629e-03 4.1459922895999e-03 3.8988078012566e-03 3.8689220154046e-03 3.8362244818848e-03 3.7781870047494e-03 3.7991144246569e-03 3.8963093505859e-03 3.8029222158394e-03 3.7447728604300e-03 3.5251409997415e-03 2.6927663397058e-03 2.2280829262653e-04 -5.6844210894826e-05 -2.5289479588858e-05 -2.1818274013613e-15 -1.4350394488187e-01 -1.4350644868093e-01 -1.4351405823675e-01 -1.4356707842167e-01 -1.4357468762261e-01 -1.4358191726733e-01 -1.4359202997403e-01 -1.4359737878587e-01 -1.4364033219856e-01 -1.4370033965823e-01 -1.4374324039567e-01 -1.4375335180460e-01 -1.4404180310901e-01 -1.4453755061631e-01 -1.4535628688438e-01 -1.4629924957144e-01 -1.4751563752793e-01 -1.4902592869205e-01 -1.5165550339329e-01 -1.5115454585033e-01 -1.4987445080561e-01 -1.5084079219919e-01 -1.5317852264563e-01 -1.5583313071955e-01 -1.5141193181627e-01 -1.4087942988595e-01 -1.2771961837554e-01 -1.1517631718590e-01 -9.6915004951873e-02 -8.6553118892305e-02 -7.4646152923131e-02 -5.6605692842994e-02 -4.2830616798578e-02 -3.2993490799793e-02 -2.1174106108760e-02 -1.2090443824638e-02 -7.6604730455411e-03 -4.0803023194442e-03 -2.5179734642626e-03 -2.4692087654001e-04 1.3405902397425e-05 -6.9709380087225e-04 -1.0568387552044e-03 -1.4071818444257e-03 -1.4227519384436e-03 -1.4377413175594e-03 -1.5758909941313e-03 -1.9451095406705e-03 -1.9646987474929e-03 -2.0680518740574e-03 -2.3298298692788e-03 -2.4504894451642e-03 -2.8636804151939e-03 -3.3497689869250e-03 -3.7226421788148e-03 -4.1221310314193e-03 -4.2177655727648e-03 -4.1674759681162e-03 -4.2071664896841e-03 -4.3019702619343e-03 -4.2889702152394e-03 -4.2572344968798e-03 -4.0899834958534e-03 -3.8479679756163e-03 -3.7731255795208e-03 -1.0881330299870e-03 -1.6970069156362e-04 -1.4312774552537e-04 -1.8904447118836e-05 -2.9430062670219e-15 -3.4151078685842e-01 -3.4152471180527e-01 -3.4155254427787e-01 -3.4155950228945e-01 -3.4157326616817e-01 -3.4158369875164e-01 -3.4158235412394e-01 -3.4157428536876e-01 -3.4157361942488e-01 -3.4156052558700e-01 -3.4153751152089e-01 -3.4145326277588e-01 -3.4127416666911e-01 -3.4103909406469e-01 -3.4049594200038e-01 -3.3983781145704e-01 -3.3825331100517e-01 -3.3708438518016e-01 -3.3584603879122e-01 -3.3333794414977e-01 -3.2998867713986e-01 -3.2205270218264e-01 -3.1485576277068e-01 -3.0524068587939e-01 -2.8574943377420e-01 -2.7235950759356e-01 -2.5787122847110e-01 -2.4479063789130e-01 -2.1894471675518e-01 -1.9141196601965e-01 -1.7687077590158e-01 -1.6397362239049e-01 -1.4228788051105e-01 -1.3012933989946e-01 -1.1978179145328e-01 -9.9729639599316e-02 -7.8349135502752e-02 -6.8257037907210e-02 -5.7956766677817e-02 -3.8707638256401e-02 -2.3109525312762e-02 -5.8397239473450e-03 -1.2458444411485e-03 2.4955592938705e-03 9.8972836369997e-03 1.0619912622021e-02 1.2071669182869e-02 1.4084390621246e-02 1.4621041192496e-02 1.4599225555579e-02 1.4622588791110e-02 1.3991502887360e-02 1.2787351683203e-02 1.0645491130820e-02 9.9468442643964e-03 9.0017830649800e-03 6.0159910350003e-03 3.9878288220813e-03 3.3186146893119e-03 2.6369766705770e-03 1.8098262752639e-03 1.4258396154564e-03 9.8442719584879e-04 2.7684414565487e-04 -1.9523805127444e-04 2.2616656976690e-04 2.1441000444615e-04 1.6693484167328e-04 1.6242295829800e-04 8.4926109813140e-06 2.9074087947543e-15 -3.0352379806840e-01 -3.0352618242683e-01 -3.0356159228820e-01 -3.0359218020079e-01 -3.0359897463159e-01 -3.0363634727643e-01 -3.0376884466631e-01 -3.0378678623706e-01 -3.0378821693093e-01 -3.0380347367226e-01 -3.0394738558873e-01 -3.0436699506906e-01 -3.0482194322955e-01 -3.0533503963104e-01 -3.0536476209721e-01 -3.0482083725052e-01 -3.0418142183305e-01 -3.0249131572658e-01 -3.0050596072355e-01 -2.9888301241356e-01 -2.9448594093223e-01 -2.8774465923916e-01 -2.7031613914458e-01 -2.6054441971494e-01 -2.4867515642857e-01 -2.2102255503257e-01 -2.0276314430752e-01 -1.8999647395929e-01 -1.6760040574168e-01 -1.4865376214093e-01 -1.2295269984303e-01 -9.9805788399370e-02 -8.6261721359625e-02 -7.4050145815003e-02 -5.3351928880713e-02 -4.3241953497833e-02 -3.3995362242724e-02 -2.1616957764566e-02 -9.4839257370742e-03 -6.5646434864873e-03 -3.0992863176836e-03 6.9176892184135e-04 6.7181620268903e-04 5.7634757818773e-04 4.0302384980502e-04 3.4378470825011e-04 2.6288937306056e-04 -5.0241439503183e-05 -9.6313563021665e-05 -7.0684563533160e-05 -4.7251558514031e-04 -6.2166872516839e-04 -3.7799924548813e-04 3.1838566306656e-04 1.1371570822723e-05 -4.3331284327388e-04 -6.6130089488351e-04 -8.0092282550128e-04 -7.8790959347611e-04 -6.3629492319863e-04 -2.4754930530305e-04 -1.6550192668975e-04 -3.6515387000861e-15 -3.0296410475071e-01 -3.0295893616663e-01 -3.0295204339119e-01 -3.0292732556386e-01 -3.0292617514090e-01 -3.0290833740440e-01 -3.0285047894766e-01 -3.0285169532956e-01 -3.0284996365009e-01 -3.0259988940243e-01 -3.0202174450768e-01 -3.0187558623767e-01 -3.0060925771239e-01 -2.9968921568308e-01 -2.9822114660674e-01 -2.9626867257787e-01 -2.9392525042666e-01 -2.9133953846907e-01 -2.7853519873893e-01 -2.6327166301423e-01 -2.4165850713269e-01 -2.2145291575486e-01 -1.8647462125094e-01 -1.6495170437675e-01 -1.5499047696468e-01 -1.2831357756765e-01 -1.1418387829832e-01 -1.0914621162552e-01 -1.0694632693381e-01 -1.1173844323809e-01 -1.1505614100858e-01 -1.1386871960870e-01 -1.0842150997068e-01 -1.0039583594802e-01 -8.7767012308606e-02 -7.3883715046323e-02 -5.7365119458462e-02 -4.8580879348845e-02 -3.7095841312339e-02 -2.2932889630117e-02 -9.9462061544227e-03 -1.1655663697149e-03 6.6998332216362e-03 1.3056584707559e-02 1.7135294419175e-02 1.6996477762361e-02 1.5924665793404e-02 1.3966698593086e-02 1.1443239911117e-02 9.5730930227151e-03 7.1368944315558e-03 6.3673377189260e-03 5.8573328713546e-03 5.4985068658686e-03 4.4520315458316e-03 3.2870015284662e-03 2.8777183891453e-03 2.8109131914285e-03 2.7346718278412e-03 2.4505176960911e-03 2.2295789124906e-03 2.2231584337760e-03 1.8799646492813e-03 1.1465210697021e-03 5.5619496033885e-04 1.2791241089294e-04 1.3122390457173e-04 9.7018516021031e-05 8.2800457740897e-06 -3.1106536990197e-15 -3.6945025834725e-01 -3.6944243859737e-01 -3.6931469687577e-01 -3.6903057296041e-01 -3.6825218315264e-01 -3.6584429312535e-01 -3.6269236190615e-01 -3.5834098876132e-01 -3.5462025938075e-01 -3.5203584241853e-01 -3.4817466873864e-01 -3.3887298758195e-01 -3.3182239129941e-01 -3.1554062158980e-01 -3.0018033971069e-01 -2.8395233651503e-01 -2.6236589929714e-01 -2.4990872458904e-01 -2.3698244126882e-01 -2.1978564649650e-01 -2.1030617422204e-01 -1.9444282034796e-01 -1.8169085171315e-01 -1.6602008072248e-01 -1.5525314187824e-01 -1.4761150903471e-01 -1.4091977969517e-01 -1.2955535325778e-01 -1.2139015732701e-01 -1.0471553899438e-01 -8.7694577635330e-02 -7.0591426494646e-02 -4.9524496129617e-02 -3.7083921009501e-02 -2.3899062563184e-02 -9.5555024833502e-03 5.2872806676265e-03 8.2014730336265e-03 8.3436401315401e-03 9.5336306067064e-03 9.4479608605351e-03 9.2205079283198e-03 7.8592144207122e-03 6.8571721916599e-03 6.4525227643608e-03 4.9868885513473e-03 4.1008032849397e-03 2.7545309959114e-03 2.3889235182813e-03 2.1376873804346e-03 1.7957568502557e-03 1.6619884374710e-03 1.5034875645400e-03 1.3362309319876e-03 1.0982851022405e-03 1.1068399592753e-03 1.0771572261081e-03 1.0636875719012e-03 9.3335850488367e-04 6.4527538331524e-05 -1.1837175867595e-14 -1.2806214983673e-01 -1.2808469045086e-01 -1.2809372411291e-01 -1.2815915024913e-01 -1.2817493615443e-01 -1.2817721632269e-01 -1.2819083257491e-01 -1.2833276523220e-01 -1.2953539465207e-01 -1.3290275798745e-01 -1.3702929190713e-01 -1.4138722003208e-01 -1.4443145511642e-01 -1.4959590554238e-01 -1.5352613300886e-01 -1.5531508931001e-01 -1.5677711973516e-01 -1.5887319296167e-01 -1.5814388160255e-01 -1.5455860201162e-01 -1.3174025444528e-01 -1.1233050419984e-01 -1.0176112420808e-01 -9.0113547021751e-02 -7.7759724139668e-02 -6.1049073552675e-02 -5.5586887374706e-02 -5.0283153273636e-02 -2.4222369359590e-02 -1.5072542893745e-02 -1.2156336875326e-02 -1.0164911532536e-02 -8.5657749137352e-03 -4.6773338628498e-03 -2.2429041906638e-03 -1.6686362240357e-03 1.1977172376525e-04 2.1975988435689e-04 1.3892583420519e-04 1.1735497755757e-04 1.1615834578104e-04 1.0262196877892e-04 9.6195536109020e-05 8.8064754087492e-05 8.1136009258624e-05 7.7780637814738e-05 6.4216442906378e-05 3.3875423062781e-05 3.3156952363748e-05 3.2435739345912e-05 1.7629692348367e-05 1.7391144498937e-05 3.1830017131205e-15 + -4.4310515132990e-01 -4.4310570564995e-01 -4.4310944502040e-01 -4.4311412920405e-01 -4.4312488327682e-01 -4.4313002559441e-01 -4.4313449353598e-01 -4.4315818819482e-01 -4.4337138896134e-01 -4.4427460544893e-01 -4.4471267433492e-01 -4.4243340898152e-01 -4.3727770458873e-01 -4.3068248988314e-01 -4.2784501285162e-01 -4.2410856888121e-01 -4.1770979254170e-01 -4.0453217844729e-01 -3.9154286396434e-01 -3.8048309830817e-01 -3.6750774552965e-01 -3.5048975229230e-01 -3.3460464552099e-01 -3.1665164140605e-01 -3.0071213323355e-01 -2.7394903118053e-01 -2.5793443114867e-01 -2.4210965943080e-01 -2.2106240997019e-01 -1.9489393079393e-01 -1.7412289391996e-01 -1.5571272772748e-01 -1.4147126851356e-01 -1.1915244517728e-01 -1.0721981610049e-01 -9.1233370681497e-02 -6.8517349234221e-02 -4.9117886787248e-02 -3.8646427265139e-02 -2.7155811096165e-02 -1.5544871170283e-02 9.8633972987131e-04 4.1300825324897e-03 5.1299247884116e-03 5.4116291164010e-03 5.0758165733943e-03 4.6915501101167e-03 4.4844821331180e-03 4.3182963254872e-03 3.3732161069549e-03 3.0951105172740e-03 9.6006855048883e-04 1.5429753585280e-03 2.9206288069339e-03 2.6658621254023e-03 2.0484068940984e-03 1.2377567359497e-03 5.5277619186848e-04 2.7115823597397e-04 3.1360561505333e-04 8.6512769607488e-04 1.2188052726228e-03 9.0340288049271e-04 3.4482181259393e-04 -9.7149637777988e-06 1.4151748177142e-05 -1.2524622644667e-15 -1.9845657645219e-01 -1.9841955706227e-01 -1.9844849016970e-01 -1.9843592083077e-01 -1.9846060115357e-01 -1.9852093869135e-01 -1.9869932968397e-01 -1.9868969840345e-01 -1.9870202969019e-01 -1.9871636265815e-01 -1.9875460278284e-01 -1.9845510154171e-01 -1.9374003526968e-01 -1.8729647385247e-01 -1.7234536473730e-01 -1.6161880420547e-01 -1.3888866250969e-01 -1.2202837255001e-01 -9.7213887002394e-02 -6.9228820684327e-02 -4.7120367582367e-02 -1.1480533707283e-02 8.6360558032207e-03 1.6065493844912e-02 2.3248524069810e-02 2.8304077994396e-02 3.6183842886116e-02 4.2474324470260e-02 4.6725892910421e-02 4.6763168341197e-02 4.2547668006572e-02 3.8386694646355e-02 3.5032052484607e-02 2.8639315061456e-02 2.3467928325835e-02 1.8266587213240e-02 1.4211798043778e-02 5.6331513307570e-03 -3.7858909927544e-04 -4.0928880755512e-03 -3.8166298046066e-03 -1.5616252407071e-04 2.8408818571116e-03 6.0050451524932e-03 6.9206226798896e-03 6.8367439034246e-03 8.2300959508942e-03 9.4712849760909e-03 9.6879777567385e-03 1.0246137273843e-02 1.0070026718934e-02 8.2739884833723e-03 7.3187849797562e-03 5.8906889026512e-03 5.7673655299512e-03 5.5720882974650e-03 5.3908125492652e-03 5.1494026463811e-03 4.5869338340107e-03 4.3418570074511e-03 4.2776145141629e-03 4.1459922895999e-03 3.8988078012566e-03 3.8689220154046e-03 3.8362244818848e-03 3.7781870047494e-03 3.7991144246569e-03 3.8963093505859e-03 3.8029222158394e-03 3.7447728604300e-03 3.5251409997415e-03 2.6927663397058e-03 2.2280829262653e-04 -5.6844210894826e-05 -2.5289479588858e-05 -2.1818274013613e-15 -1.4350394488187e-01 -1.4350644868093e-01 -1.4351405823675e-01 -1.4356707842167e-01 -1.4357468762261e-01 -1.4358191726733e-01 -1.4359202997403e-01 -1.4359737878587e-01 -1.4364033219856e-01 -1.4370033965823e-01 -1.4374324039567e-01 -1.4375335180460e-01 -1.4404180310901e-01 -1.4453755061631e-01 -1.4535628688438e-01 -1.4629924957144e-01 -1.4751563752793e-01 -1.4902592869205e-01 -1.5165550339329e-01 -1.5115454585033e-01 -1.4987445080561e-01 -1.5084079219919e-01 -1.5317852264563e-01 -1.5583313071955e-01 -1.5141193181627e-01 -1.4087942988595e-01 -1.2771961837554e-01 -1.1517631718590e-01 -9.6915004951873e-02 -8.6553118892305e-02 -7.4646152923131e-02 -5.6605692842994e-02 -4.2830616798578e-02 -3.2993490799793e-02 -2.1174106108760e-02 -1.2090443824638e-02 -7.6604730455411e-03 -4.0803023194442e-03 -2.5179734642626e-03 -2.4692087654001e-04 1.3405902397425e-05 -6.9709380087225e-04 -1.0568387552044e-03 -1.4071818444257e-03 -1.4227519384436e-03 -1.4377413175594e-03 -1.5758909941313e-03 -1.9451095406705e-03 -1.9646987474929e-03 -2.0680518740574e-03 -2.3298298692788e-03 -2.4504894451642e-03 -2.8636804151939e-03 -3.3497689869250e-03 -3.7226421788148e-03 -4.1221310314193e-03 -4.2177655727648e-03 -4.1674759681162e-03 -4.2071664896841e-03 -4.3019702619343e-03 -4.2889702152394e-03 -4.2572344968798e-03 -4.0899834958534e-03 -3.8479679756163e-03 -3.7731255795208e-03 -1.0881330299870e-03 -1.6970069156362e-04 -1.4312774552537e-04 -1.8904447118836e-05 -2.9430062670219e-15 -3.4151078685842e-01 -3.4152471180527e-01 -3.4155254427787e-01 -3.4155950228945e-01 -3.4157326616817e-01 -3.4158369875164e-01 -3.4158235412394e-01 -3.4157428536876e-01 -3.4157361942488e-01 -3.4156052558700e-01 -3.4153751152089e-01 -3.4145326277588e-01 -3.4127416666911e-01 -3.4103909406469e-01 -3.4049594200038e-01 -3.3983781145704e-01 -3.3825331100517e-01 -3.3708438518016e-01 -3.3584603879122e-01 -3.3333794414977e-01 -3.2998867713986e-01 -3.2205270218264e-01 -3.1485576277068e-01 -3.0524068587939e-01 -2.8574943377420e-01 -2.7235950759356e-01 -2.5787122847110e-01 -2.4479063789130e-01 -2.1894471675518e-01 -1.9141196601965e-01 -1.7687077590158e-01 -1.6397362239049e-01 -1.4228788051105e-01 -1.3012933989946e-01 -1.1978179145328e-01 -9.9729639599316e-02 -7.8349135502752e-02 -6.8257037907210e-02 -5.7956766677817e-02 -3.8707638256401e-02 -2.3109525312762e-02 -5.8397239473450e-03 -1.2458444411485e-03 2.4955592938705e-03 9.8972836369997e-03 1.0619912622021e-02 1.2071669182869e-02 1.4084390621246e-02 1.4621041192496e-02 1.4599225555579e-02 1.4622588791110e-02 1.3991502887360e-02 1.2787351683203e-02 1.0645491130820e-02 9.9468442643964e-03 9.0017830649800e-03 6.0159910350003e-03 3.9878288220813e-03 3.3186146893119e-03 2.6369766705770e-03 1.8098262752639e-03 1.4258396154564e-03 9.8442719584879e-04 2.7684414565487e-04 -1.9523805127444e-04 2.2616656976690e-04 2.1441000444615e-04 1.6693484167328e-04 1.6242295829800e-04 8.4926109813140e-06 2.9074087947543e-15 -3.0352379806840e-01 -3.0352618242683e-01 -3.0356159228820e-01 -3.0359218020079e-01 -3.0359897463159e-01 -3.0363634727643e-01 -3.0376884466631e-01 -3.0378678623706e-01 -3.0378821693093e-01 -3.0380347367226e-01 -3.0394738558873e-01 -3.0436699506906e-01 -3.0482194322955e-01 -3.0533503963104e-01 -3.0536476209721e-01 -3.0482083725052e-01 -3.0418142183305e-01 -3.0249131572658e-01 -3.0050596072355e-01 -2.9888301241356e-01 -2.9448594093223e-01 -2.8774465923916e-01 -2.7031613914458e-01 -2.6054441971494e-01 -2.4867515642857e-01 -2.2102255503257e-01 -2.0276314430752e-01 -1.8999647395929e-01 -1.6760040574168e-01 -1.4865376214093e-01 -1.2295269984303e-01 -9.9805788399370e-02 -8.6261721359625e-02 -7.4050145815003e-02 -5.3351928880713e-02 -4.3241953497833e-02 -3.3995362242724e-02 -2.1616957764566e-02 -9.4839257370742e-03 -6.5646434864873e-03 -3.0992863176836e-03 6.9176892184135e-04 6.7181620268903e-04 5.7634757818773e-04 4.0302384980502e-04 3.4378470825011e-04 2.6288937306056e-04 -5.0241439503183e-05 -9.6313563021665e-05 -7.0684563533160e-05 -4.7251558514031e-04 -6.2166872516839e-04 -3.7799924548813e-04 3.1838566306656e-04 1.1371570822723e-05 -4.3331284327388e-04 -6.6130089488351e-04 -8.0092282550128e-04 -7.8790959347611e-04 -6.3629492319863e-04 -2.4754930530305e-04 -1.6550192668975e-04 -3.6515387000861e-15 -3.0296410475071e-01 -3.0295893616663e-01 -3.0295204339119e-01 -3.0292732556386e-01 -3.0292617514090e-01 -3.0290833740440e-01 -3.0285047894766e-01 -3.0285169532956e-01 -3.0284996365009e-01 -3.0259988940243e-01 -3.0202174450768e-01 -3.0187558623767e-01 -3.0060925771239e-01 -2.9968921568308e-01 -2.9822114660674e-01 -2.9626867257787e-01 -2.9392525042666e-01 -2.9133953846907e-01 -2.7853519873893e-01 -2.6327166301423e-01 -2.4165850713269e-01 -2.2145291575486e-01 -1.8647462125094e-01 -1.6495170437675e-01 -1.5499047696468e-01 -1.2831357756765e-01 -1.1418387829832e-01 -1.0914621162552e-01 -1.0694632693381e-01 -1.1173844323809e-01 -1.1505614100858e-01 -1.1386871960870e-01 -1.0842150997068e-01 -1.0039583594802e-01 -8.7767012308606e-02 -7.3883715046323e-02 -5.7365119458462e-02 -4.8580879348845e-02 -3.7095841312339e-02 -2.2932889630117e-02 -9.9462061544227e-03 -1.1655663697149e-03 6.6998332216362e-03 1.3056584707559e-02 1.7135294419175e-02 1.6996477762361e-02 1.5924665793404e-02 1.3966698593086e-02 1.1443239911117e-02 9.5730930227151e-03 7.1368944315558e-03 6.3673377189260e-03 5.8573328713546e-03 5.4985068658686e-03 4.4520315458316e-03 3.2870015284662e-03 2.8777183891453e-03 2.8109131914285e-03 2.7346718278412e-03 2.4505176960911e-03 2.2295789124906e-03 2.2231584337760e-03 1.8799646492813e-03 1.1465210697021e-03 5.5619496033885e-04 1.2791241089294e-04 1.3122390457173e-04 9.7018516021031e-05 8.2800457740897e-06 -3.1106536990197e-15 -3.6945025834725e-01 -3.6944243859737e-01 -3.6931469687577e-01 -3.6903057296041e-01 -3.6825218315264e-01 -3.6584429312535e-01 -3.6269236190615e-01 -3.5834098876132e-01 -3.5462025938075e-01 -3.5203584241853e-01 -3.4817466873864e-01 -3.3887298758195e-01 -3.3182239129941e-01 -3.1554062158980e-01 -3.0018033971069e-01 -2.8395233651503e-01 -2.6236589929714e-01 -2.4990872458904e-01 -2.3698244126882e-01 -2.1978564649650e-01 -2.1030617422204e-01 -1.9444282034796e-01 -1.8169085171315e-01 -1.6602008072248e-01 -1.5525314187824e-01 -1.4761150903471e-01 -1.4091977969517e-01 -1.2955535325778e-01 -1.2139015732701e-01 -1.0471553899438e-01 -8.7694577635330e-02 -7.0591426494646e-02 -4.9524496129617e-02 -3.7083921009501e-02 -2.3899062563184e-02 -9.5555024833502e-03 5.2872806676265e-03 8.2014730336265e-03 8.3436401315401e-03 9.5336306067064e-03 9.4479608605351e-03 9.2205079283198e-03 7.8592144207122e-03 6.8571721916599e-03 6.4525227643608e-03 4.9868885513473e-03 4.1008032849397e-03 2.7545309959114e-03 2.3889235182813e-03 2.1376873804346e-03 1.7957568502557e-03 1.6619884374710e-03 1.5034875645400e-03 1.3362309319876e-03 1.0982851022405e-03 1.1068399592753e-03 1.0771572261081e-03 1.0636875719012e-03 9.3335850488367e-04 6.4527538331524e-05 -1.1837175867595e-14 -1.2806214983673e-01 -1.2808469045086e-01 -1.2809372411291e-01 -1.2815915024913e-01 -1.2817493615443e-01 -1.2817721632269e-01 -1.2819083257491e-01 -1.2833276523220e-01 -1.2953539465207e-01 -1.3290275798745e-01 -1.3702929190713e-01 -1.4138722003208e-01 -1.4443145511642e-01 -1.4959590554238e-01 -1.5352613300886e-01 -1.5531508931001e-01 -1.5677711973516e-01 -1.5887319296167e-01 -1.5814388160255e-01 -1.5455860201162e-01 -1.3174025444528e-01 -1.1233050419984e-01 -1.0176112420808e-01 -9.0113547021751e-02 -7.7759724139668e-02 -6.1049073552675e-02 -5.5586887374706e-02 -5.0283153273636e-02 -2.4222369359590e-02 -1.5072542893745e-02 -1.2156336875326e-02 -1.0164911532536e-02 -8.5657749137352e-03 -4.6773338628498e-03 -2.2429041906638e-03 -1.6686362240357e-03 1.1977172376525e-04 2.1975988435689e-04 1.3892583420519e-04 1.1735497755757e-04 1.1615834578104e-04 1.0262196877892e-04 9.6195536109020e-05 8.8064754087492e-05 8.1136009258624e-05 7.7780637814738e-05 6.4216442906378e-05 3.3875423062781e-05 3.3156952363748e-05 3.2435739345912e-05 1.7629692348367e-05 1.7391144498937e-05 3.1830017131205e-15 -3.0321245171134e-01 -3.0321088567577e-01 -3.0320217954824e-01 -3.0319126863345e-01 -3.0316619782452e-01 -3.0315419914230e-01 -3.0314294445756e-01 -3.0307600747420e-01 -3.0246391528618e-01 -2.9943753030737e-01 -2.9571156552937e-01 -2.9343722140094e-01 -2.9069946768203e-01 -2.8572463529094e-01 -2.7672959404485e-01 -2.6544338358552e-01 -2.5687779900058e-01 -2.4546047422911e-01 -2.3529449044853e-01 -2.2344762108084e-01 -2.0594928853054e-01 -1.8479949765721e-01 -1.6530810784050e-01 -1.4468549516138e-01 -1.2830162074357e-01 -1.0353455895111e-01 -8.6510725275275e-02 -7.0817590416338e-02 -5.3881896975800e-02 -4.0583059076401e-02 -3.2946419078961e-02 -2.6461484915029e-02 -2.3850093665860e-02 -2.0875801572836e-02 -1.7164286791357e-02 -1.7773835043567e-02 -2.3599053047011e-02 -2.7992486439279e-02 -2.6683891592228e-02 -2.5298663742602e-02 -2.3916777204232e-02 -1.8687568368925e-02 -1.5886255159904e-02 -1.5473795696431e-02 -1.5114217567398e-02 -1.2358857098146e-02 -9.4451401903717e-03 -8.3484800293384e-03 -6.5655444660702e-03 -2.8507634470139e-03 -4.2928532531837e-03 -4.0653843412086e-03 -4.2142968278181e-03 -4.4463254826342e-03 -4.2496623118046e-03 -4.0833544665066e-03 -3.9922740058804e-03 -3.1860837095057e-03 -2.9437351629695e-03 -2.8084551295773e-03 -2.4545453301208e-03 -1.9429516470734e-03 -1.2804203264948e-03 -6.6525746583722e-04 -1.1481073854769e-04 -1.6553954426935e-06 -1.0341415904278e-14 -3.0084921402425e-01 -3.0085387245384e-01 -3.0086016948683e-01 -3.0085984827918e-01 -3.0086307585680e-01 -3.0090105091807e-01 -3.0093985557173e-01 -3.0094175547201e-01 -3.0094332595151e-01 -3.0094188155749e-01 -3.0094426820721e-01 -3.0098896527252e-01 -3.0173339741510e-01 -3.0340811146047e-01 -3.0710553147934e-01 -3.0974276219319e-01 -3.1342169648486e-01 -3.1373893184726e-01 -3.0971815574841e-01 -2.9989236569338e-01 -2.8890838405088e-01 -2.6758472376373e-01 -2.5073844749950e-01 -2.4168797781580e-01 -2.2666531636155e-01 -2.1159975025066e-01 -1.8641457711241e-01 -1.7029190181547e-01 -1.4768159329613e-01 -1.3494692704972e-01 -1.1825126081385e-01 -1.0690013995800e-01 -9.6457189231212e-02 -8.3408165419669e-02 -7.3766745751352e-02 -6.2867438944169e-02 -5.5313355874706e-02 -4.4166126588135e-02 -3.7963381048623e-02 -3.2045522879926e-02 -2.4448458530051e-02 -1.6768375088655e-02 -1.4678491608780e-02 -1.4632877441505e-02 -1.4363498891722e-02 -8.0870944832317e-03 -3.8887242265996e-03 -4.1951427544183e-03 -4.6490890324989e-03 -5.7078687717956e-03 -7.2270645667709e-03 -7.1296018755373e-03 -6.6615504454995e-03 -5.2701910444694e-03 -5.1355988973929e-03 -4.8914890093908e-03 -4.8129487836529e-03 -4.5445870456579e-03 -3.8909607306097e-03 -3.6572306410100e-03 -3.5863737015752e-03 -3.4431816988379e-03 -3.1468740373419e-03 -3.1022803103247e-03 -3.0635677980194e-03 -3.0163543303222e-03 -3.3355097088350e-03 -4.4841748887643e-03 -4.5339040161497e-03 -4.5913830235236e-03 -4.3628001985006e-03 -3.3706394353526e-03 -3.5472304039963e-04 5.6211249886981e-05 3.0544096747632e-05 -2.6264554288732e-15 -2.3892653537528e-01 -2.3892661594256e-01 -2.3892686065559e-01 -2.3892855955720e-01 -2.3892880249185e-01 -2.3893000263220e-01 -2.3893032476714e-01 -2.3893041133373e-01 -2.3893177438688e-01 -2.3893471605252e-01 -2.3893606003263e-01 -2.3893637577252e-01 -2.3891845080904e-01 -2.3888083457050e-01 -2.3881273827787e-01 -2.3873128049632e-01 -2.3844209656873e-01 -2.3791011000462e-01 -2.3679415814597e-01 -2.3502533997873e-01 -2.3077543628672e-01 -2.2600157343600e-01 -2.1783955693941e-01 -2.0846309634351e-01 -1.9532359818717e-01 -1.8397195501203e-01 -1.6943554017887e-01 -1.5435115359645e-01 -1.2986482514330e-01 -1.1392831087701e-01 -9.2979253393686e-02 -6.0665257357300e-02 -4.0127290913463e-02 -2.5457520396694e-02 -1.3091880597818e-02 -8.7932016483729e-03 -7.1947384489720e-03 -5.7312704059399e-03 -5.1592844632048e-03 -3.4111330771348e-03 -2.3164310838555e-03 -1.6910292949690e-03 -1.3971929692974e-03 -1.1121258169797e-03 -1.1263624349157e-03 -1.1292070320852e-03 -1.3983450147613e-03 -1.1971225985654e-03 -1.1818743547877e-03 -1.0850783525796e-03 -8.5276701422714e-04 -7.8127368644527e-04 -4.7030034646038e-04 -1.0391092192787e-04 3.8860219241197e-05 2.3305123832554e-04 3.1761766111124e-04 3.7324392889320e-04 3.9103368810601e-04 4.7660166173223e-04 4.8464765085117e-04 4.8673511227840e-04 1.1986417030853e-03 1.5304066334077e-03 1.4955003030202e-03 8.6494309882698e-04 7.0037141109931e-04 5.4544231549251e-04 1.4672041758061e-04 3.0135255868796e-15 -3.2455257223738e-01 -3.2454441473716e-01 -3.2452810877102e-01 -3.2452403209795e-01 -3.2451431240138e-01 -3.2450819950213e-01 -3.2450596232316e-01 -3.2449253747492e-01 -3.2449142946322e-01 -3.2446705858314e-01 -3.2442747287007e-01 -3.2414140239150e-01 -3.2277868310834e-01 -3.2078364682976e-01 -3.1740191149774e-01 -3.1354315285185e-01 -3.0487140841072e-01 -2.9902261213831e-01 -2.9384587990396e-01 -2.8810680196973e-01 -2.8189005873637e-01 -2.7250716464408e-01 -2.6597051415418e-01 -2.5850260390058e-01 -2.3860968657752e-01 -2.2473283627243e-01 -2.0937297738735e-01 -1.9500821713996e-01 -1.6948716383974e-01 -1.3779427123413e-01 -1.1644818507934e-01 -9.5073746125876e-02 -6.2137112880323e-02 -4.9835306578146e-02 -4.2389799384329e-02 -3.4216279358500e-02 -2.4729639466038e-02 -1.8591312295484e-02 -1.2261458018052e-02 -2.3674350547961e-03 -8.5019354211150e-04 -1.0937786259041e-03 -3.3292252448734e-03 -6.7439427418389e-03 -9.9588026881328e-03 -7.2896040597629e-03 -4.8816917784623e-03 -3.6925409245938e-03 -2.3015098227746e-03 -3.3040748886357e-03 -3.9550208099121e-03 -4.2562692203110e-03 -4.0821601139209e-03 -3.5718883850987e-03 -3.3545049950701e-03 -3.0097645908109e-03 -2.0754935862986e-03 -1.5188083423591e-03 -1.3989536459802e-03 -8.4720742513582e-04 -6.1688786042521e-04 -5.4001045719850e-04 -3.9915290801621e-04 -1.0338765417077e-04 1.2610013272883e-04 2.7972987202788e-04 1.4847240445994e-04 -3.0077618633713e-05 -2.8266694438405e-05 2.0458368797982e-05 2.5125910131648e-15 -2.8996330859749e-01 -2.8995857465963e-01 -2.8994327706749e-01 -2.8993035765404e-01 -2.8992748760975e-01 -2.8991169915457e-01 -2.8985569934979e-01 -2.8984662268635e-01 -2.8984378300653e-01 -2.8981346597131e-01 -2.8948599280208e-01 -2.8842619440572e-01 -2.8685421278472e-01 -2.8453902885137e-01 -2.7987566153476e-01 -2.7767237749941e-01 -2.7492112269925e-01 -2.6640708416443e-01 -2.5649655612403e-01 -2.4669264340220e-01 -2.3236669908188e-01 -2.1934616956807e-01 -2.0160806576375e-01 -1.9185109687069e-01 -1.8231773341220e-01 -1.5617955701017e-01 -1.3243011988449e-01 -1.1313132956941e-01 -9.1096942242232e-02 -7.2935659878453e-02 -4.9606644062745e-02 -3.4528222920155e-02 -2.5147092499848e-02 -1.6401482101765e-02 -7.1358004467779e-03 -7.1185794442667e-03 -7.6041825940719e-03 -3.2828091045879e-03 -1.7515384087717e-03 -2.0967805549519e-03 -4.3124242799608e-03 -4.0923386978559e-03 -3.9932180566114e-03 -3.3448110047006e-03 -2.0618150689275e-03 -2.0895765061705e-03 -2.1440926572746e-03 -2.2051864433958e-03 -2.2234263457849e-03 -2.2204524033075e-03 -2.0089789025177e-03 -1.6237362216992e-03 -1.4056531175505e-03 -9.7821541170336e-04 -6.9690222325564e-04 -4.7403746681621e-04 -5.1224705518013e-04 -4.7528909603628e-04 -4.8063341355771e-04 -4.6759342472170e-04 -3.3497457726523e-04 -1.3917051210404e-04 -2.0400904299726e-15 -3.5204331050325e-01 -3.5203364158934e-01 -3.5202074694669e-01 -3.5197450360448e-01 -3.5197235123980e-01 -3.5193897693160e-01 -3.5182256478885e-01 -3.5182199853253e-01 -3.5181875775518e-01 -3.5139133369384e-01 -3.5130367529065e-01 -3.4912089494243e-01 -3.4562380786596e-01 -3.4152655298013e-01 -3.3662574104424e-01 -3.2793318275535e-01 -3.2328578348923e-01 -3.1912286962402e-01 -3.0868680633011e-01 -3.0149399770431e-01 -2.8849197744529e-01 -2.7346763662088e-01 -2.4625235059670e-01 -2.2421521294808e-01 -2.1243430662010e-01 -1.7012656569633e-01 -1.3494511693348e-01 -1.1550580505927e-01 -8.5726638340550e-02 -6.7716386117602e-02 -4.2878982436370e-02 -3.8507785334862e-02 -2.5732410726109e-02 -2.1343079713379e-02 -1.7191990986654e-02 -1.6422728892858e-02 -1.9755811804500e-02 -2.2732185139144e-02 -2.2829452443352e-02 -1.8315053585124e-02 -1.4539758566386e-02 -1.2751259506832e-02 -1.0165665452219e-02 -7.3911412718584e-03 -8.5101006487902e-03 -8.5452109402256e-03 -8.4016735724471e-03 -7.3734597549893e-03 -6.1409557469949e-03 -5.6428697662878e-03 -4.6633789233562e-03 -4.0724347574437e-03 -3.6970335403872e-03 -3.4730407598272e-03 -2.6662950098724e-03 -1.6671731402267e-03 -1.4151391088049e-03 -1.3924885750067e-03 -1.2386281536562e-03 -7.8640104136632e-04 8.7076048923470e-05 1.0137247293834e-04 1.0644973636339e-04 1.1375887682308e-04 -6.9140490444448e-05 5.1325876112945e-05 -2.7274798658408e-05 -7.7249855612082e-05 -1.0670627681542e-05 6.8688967291472e-15 -3.3431200990259e-01 -3.3430911573417e-01 -3.3426813339506e-01 -3.3416223452370e-01 -3.3384294600410e-01 -3.3267150138022e-01 -3.3083316691919e-01 -3.2784731775307e-01 -3.2523197806198e-01 -3.2305094688001e-01 -3.1966812384598e-01 -3.1393811631507e-01 -3.1015133822574e-01 -3.0017587481308e-01 -2.9147415044374e-01 -2.8118153756834e-01 -2.6378839820857e-01 -2.4878342623072e-01 -2.3059032235648e-01 -2.0137591740279e-01 -1.8478927095397e-01 -1.6051281424232e-01 -1.4342403163701e-01 -1.2162752863374e-01 -1.0477382391687e-01 -9.0474481350448e-02 -7.6964794046252e-02 -6.0390488688980e-02 -5.1817007419291e-02 -3.7809117562493e-02 -2.6985053527287e-02 -2.1139745396178e-02 -2.2145340583929e-02 -2.2105353087123e-02 -2.0333462803353e-02 -1.8143628868063e-02 -9.6703158087269e-03 -5.7386085523943e-03 -5.7705347982566e-03 -6.3781874005892e-03 -6.0665255702116e-03 -5.3515458106222e-03 -4.3615185890365e-03 -4.0579825276475e-03 -3.6331543855055e-03 -2.7468311983540e-03 -2.4025306671373e-03 -1.9081965949201e-03 -1.4177441185277e-03 -1.0477398551917e-03 -4.8158193964427e-04 1.2429678068588e-03 8.2401017654086e-04 8.4654589506578e-04 5.5521583164783e-04 -6.5425376455925e-04 -4.9197621340170e-04 -3.4755638854252e-04 -3.1684060124183e-04 -5.0470215915565e-05 -2.7749276670939e-14 -1.8820344925576e-01 -1.8820414018916e-01 -1.8820441640434e-01 -1.8820640506718e-01 -1.8820688177736e-01 -1.8820695053498e-01 -1.8820561616151e-01 -1.8819128817434e-01 -1.8803852017584e-01 -1.8729500266373e-01 -1.8570849759270e-01 -1.8300175961859e-01 -1.8022582251998e-01 -1.7389022206270e-01 -1.6464527862644e-01 -1.5219420761617e-01 -1.3973143064187e-01 -1.1577213204689e-01 -1.0074200386156e-01 -8.5632573745962e-02 -5.1175262065742e-02 -2.7038468046775e-02 -1.2253767923882e-02 1.0235902474772e-04 4.9671947339912e-03 5.9361026946532e-03 5.6877505218001e-03 6.3768908156237e-03 1.0358563922698e-02 5.7750166699246e-03 2.0817015234287e-03 9.6636481249715e-04 1.0508875972382e-03 1.0626101452932e-03 1.1603141941755e-03 3.6705496468842e-04 -8.4734180772205e-04 -8.0521064322668e-04 -7.8926867069485e-04 -7.7292598581696e-04 -7.2194569354104e-04 -6.2420710024888e-04 -6.1652996697283e-04 -5.8321398450078e-04 -5.3045553876744e-04 -4.8629912969114e-04 -4.6144277377185e-04 -2.1567451369275e-04 -2.0621100721751e-04 -1.9671125370416e-04 -7.8523632225992e-05 -7.5380575311650e-05 -3.5603627202271e-15 + -3.0321245171134e-01 -3.0321088567577e-01 -3.0320217954824e-01 -3.0319126863345e-01 -3.0316619782452e-01 -3.0315419914230e-01 -3.0314294445756e-01 -3.0307600747420e-01 -3.0246391528618e-01 -2.9943753030737e-01 -2.9571156552937e-01 -2.9343722140094e-01 -2.9069946768203e-01 -2.8572463529094e-01 -2.7672959404485e-01 -2.6544338358552e-01 -2.5687779900058e-01 -2.4546047422911e-01 -2.3529449044853e-01 -2.2344762108084e-01 -2.0594928853054e-01 -1.8479949765721e-01 -1.6530810784050e-01 -1.4468549516138e-01 -1.2830162074357e-01 -1.0353455895111e-01 -8.6510725275275e-02 -7.0817590416338e-02 -5.3881896975800e-02 -4.0583059076401e-02 -3.2946419078961e-02 -2.6461484915029e-02 -2.3850093665860e-02 -2.0875801572836e-02 -1.7164286791357e-02 -1.7773835043567e-02 -2.3599053047011e-02 -2.7992486439279e-02 -2.6683891592228e-02 -2.5298663742602e-02 -2.3916777204232e-02 -1.8687568368925e-02 -1.5886255159904e-02 -1.5473795696431e-02 -1.5114217567398e-02 -1.2358857098146e-02 -9.4451401903717e-03 -8.3484800293384e-03 -6.5655444660702e-03 -2.8507634470139e-03 -4.2928532531837e-03 -4.0653843412086e-03 -4.2142968278181e-03 -4.4463254826342e-03 -4.2496623118046e-03 -4.0833544665066e-03 -3.9922740058804e-03 -3.1860837095057e-03 -2.9437351629695e-03 -2.8084551295773e-03 -2.4545453301208e-03 -1.9429516470734e-03 -1.2804203264948e-03 -6.6525746583722e-04 -1.1481073854769e-04 -1.6553954426935e-06 -1.0341415904278e-14 -3.0084921402425e-01 -3.0085387245384e-01 -3.0086016948683e-01 -3.0085984827918e-01 -3.0086307585680e-01 -3.0090105091807e-01 -3.0093985557173e-01 -3.0094175547201e-01 -3.0094332595151e-01 -3.0094188155749e-01 -3.0094426820721e-01 -3.0098896527252e-01 -3.0173339741510e-01 -3.0340811146047e-01 -3.0710553147934e-01 -3.0974276219319e-01 -3.1342169648486e-01 -3.1373893184726e-01 -3.0971815574841e-01 -2.9989236569338e-01 -2.8890838405088e-01 -2.6758472376373e-01 -2.5073844749950e-01 -2.4168797781580e-01 -2.2666531636155e-01 -2.1159975025066e-01 -1.8641457711241e-01 -1.7029190181547e-01 -1.4768159329613e-01 -1.3494692704972e-01 -1.1825126081385e-01 -1.0690013995800e-01 -9.6457189231212e-02 -8.3408165419669e-02 -7.3766745751352e-02 -6.2867438944169e-02 -5.5313355874706e-02 -4.4166126588135e-02 -3.7963381048623e-02 -3.2045522879926e-02 -2.4448458530051e-02 -1.6768375088655e-02 -1.4678491608780e-02 -1.4632877441505e-02 -1.4363498891722e-02 -8.0870944832317e-03 -3.8887242265996e-03 -4.1951427544183e-03 -4.6490890324989e-03 -5.7078687717956e-03 -7.2270645667709e-03 -7.1296018755373e-03 -6.6615504454995e-03 -5.2701910444694e-03 -5.1355988973929e-03 -4.8914890093908e-03 -4.8129487836529e-03 -4.5445870456579e-03 -3.8909607306097e-03 -3.6572306410100e-03 -3.5863737015752e-03 -3.4431816988379e-03 -3.1468740373419e-03 -3.1022803103247e-03 -3.0635677980194e-03 -3.0163543303222e-03 -3.3355097088350e-03 -4.4841748887643e-03 -4.5339040161497e-03 -4.5913830235236e-03 -4.3628001985006e-03 -3.3706394353526e-03 -3.5472304039963e-04 5.6211249886981e-05 3.0544096747632e-05 -2.6264554288732e-15 -2.3892653537528e-01 -2.3892661594256e-01 -2.3892686065559e-01 -2.3892855955720e-01 -2.3892880249185e-01 -2.3893000263220e-01 -2.3893032476714e-01 -2.3893041133373e-01 -2.3893177438688e-01 -2.3893471605252e-01 -2.3893606003263e-01 -2.3893637577252e-01 -2.3891845080904e-01 -2.3888083457050e-01 -2.3881273827787e-01 -2.3873128049632e-01 -2.3844209656873e-01 -2.3791011000462e-01 -2.3679415814597e-01 -2.3502533997873e-01 -2.3077543628672e-01 -2.2600157343600e-01 -2.1783955693941e-01 -2.0846309634351e-01 -1.9532359818717e-01 -1.8397195501203e-01 -1.6943554017887e-01 -1.5435115359645e-01 -1.2986482514330e-01 -1.1392831087701e-01 -9.2979253393686e-02 -6.0665257357300e-02 -4.0127290913463e-02 -2.5457520396694e-02 -1.3091880597818e-02 -8.7932016483729e-03 -7.1947384489720e-03 -5.7312704059399e-03 -5.1592844632048e-03 -3.4111330771348e-03 -2.3164310838555e-03 -1.6910292949690e-03 -1.3971929692974e-03 -1.1121258169797e-03 -1.1263624349157e-03 -1.1292070320852e-03 -1.3983450147613e-03 -1.1971225985654e-03 -1.1818743547877e-03 -1.0850783525796e-03 -8.5276701422714e-04 -7.8127368644527e-04 -4.7030034646038e-04 -1.0391092192787e-04 3.8860219241197e-05 2.3305123832554e-04 3.1761766111124e-04 3.7324392889320e-04 3.9103368810601e-04 4.7660166173223e-04 4.8464765085117e-04 4.8673511227840e-04 1.1986417030853e-03 1.5304066334077e-03 1.4955003030202e-03 8.6494309882698e-04 7.0037141109931e-04 5.4544231549251e-04 1.4672041758061e-04 3.0135255868796e-15 -3.2455257223738e-01 -3.2454441473716e-01 -3.2452810877102e-01 -3.2452403209795e-01 -3.2451431240138e-01 -3.2450819950213e-01 -3.2450596232316e-01 -3.2449253747492e-01 -3.2449142946322e-01 -3.2446705858314e-01 -3.2442747287007e-01 -3.2414140239150e-01 -3.2277868310834e-01 -3.2078364682976e-01 -3.1740191149774e-01 -3.1354315285185e-01 -3.0487140841072e-01 -2.9902261213831e-01 -2.9384587990396e-01 -2.8810680196973e-01 -2.8189005873637e-01 -2.7250716464408e-01 -2.6597051415418e-01 -2.5850260390058e-01 -2.3860968657752e-01 -2.2473283627243e-01 -2.0937297738735e-01 -1.9500821713996e-01 -1.6948716383974e-01 -1.3779427123413e-01 -1.1644818507934e-01 -9.5073746125876e-02 -6.2137112880323e-02 -4.9835306578146e-02 -4.2389799384329e-02 -3.4216279358500e-02 -2.4729639466038e-02 -1.8591312295484e-02 -1.2261458018052e-02 -2.3674350547961e-03 -8.5019354211150e-04 -1.0937786259041e-03 -3.3292252448734e-03 -6.7439427418389e-03 -9.9588026881328e-03 -7.2896040597629e-03 -4.8816917784623e-03 -3.6925409245938e-03 -2.3015098227746e-03 -3.3040748886357e-03 -3.9550208099121e-03 -4.2562692203110e-03 -4.0821601139209e-03 -3.5718883850987e-03 -3.3545049950701e-03 -3.0097645908109e-03 -2.0754935862986e-03 -1.5188083423591e-03 -1.3989536459802e-03 -8.4720742513582e-04 -6.1688786042521e-04 -5.4001045719850e-04 -3.9915290801621e-04 -1.0338765417077e-04 1.2610013272883e-04 2.7972987202788e-04 1.4847240445994e-04 -3.0077618633713e-05 -2.8266694438405e-05 2.0458368797982e-05 2.5125910131648e-15 -2.8996330859749e-01 -2.8995857465963e-01 -2.8994327706749e-01 -2.8993035765404e-01 -2.8992748760975e-01 -2.8991169915457e-01 -2.8985569934979e-01 -2.8984662268635e-01 -2.8984378300653e-01 -2.8981346597131e-01 -2.8948599280208e-01 -2.8842619440572e-01 -2.8685421278472e-01 -2.8453902885137e-01 -2.7987566153476e-01 -2.7767237749941e-01 -2.7492112269925e-01 -2.6640708416443e-01 -2.5649655612403e-01 -2.4669264340220e-01 -2.3236669908188e-01 -2.1934616956807e-01 -2.0160806576375e-01 -1.9185109687069e-01 -1.8231773341220e-01 -1.5617955701017e-01 -1.3243011988449e-01 -1.1313132956941e-01 -9.1096942242232e-02 -7.2935659878453e-02 -4.9606644062745e-02 -3.4528222920155e-02 -2.5147092499848e-02 -1.6401482101765e-02 -7.1358004467779e-03 -7.1185794442667e-03 -7.6041825940719e-03 -3.2828091045879e-03 -1.7515384087717e-03 -2.0967805549519e-03 -4.3124242799608e-03 -4.0923386978559e-03 -3.9932180566114e-03 -3.3448110047006e-03 -2.0618150689275e-03 -2.0895765061705e-03 -2.1440926572746e-03 -2.2051864433958e-03 -2.2234263457849e-03 -2.2204524033075e-03 -2.0089789025177e-03 -1.6237362216992e-03 -1.4056531175505e-03 -9.7821541170336e-04 -6.9690222325564e-04 -4.7403746681621e-04 -5.1224705518013e-04 -4.7528909603628e-04 -4.8063341355771e-04 -4.6759342472170e-04 -3.3497457726523e-04 -1.3917051210404e-04 -2.0400904299726e-15 -3.5204331050325e-01 -3.5203364158934e-01 -3.5202074694669e-01 -3.5197450360448e-01 -3.5197235123980e-01 -3.5193897693160e-01 -3.5182256478885e-01 -3.5182199853253e-01 -3.5181875775518e-01 -3.5139133369384e-01 -3.5130367529065e-01 -3.4912089494243e-01 -3.4562380786596e-01 -3.4152655298013e-01 -3.3662574104424e-01 -3.2793318275535e-01 -3.2328578348923e-01 -3.1912286962402e-01 -3.0868680633011e-01 -3.0149399770431e-01 -2.8849197744529e-01 -2.7346763662088e-01 -2.4625235059670e-01 -2.2421521294808e-01 -2.1243430662010e-01 -1.7012656569633e-01 -1.3494511693348e-01 -1.1550580505927e-01 -8.5726638340550e-02 -6.7716386117602e-02 -4.2878982436370e-02 -3.8507785334862e-02 -2.5732410726109e-02 -2.1343079713379e-02 -1.7191990986654e-02 -1.6422728892858e-02 -1.9755811804500e-02 -2.2732185139144e-02 -2.2829452443352e-02 -1.8315053585124e-02 -1.4539758566386e-02 -1.2751259506832e-02 -1.0165665452219e-02 -7.3911412718584e-03 -8.5101006487902e-03 -8.5452109402256e-03 -8.4016735724471e-03 -7.3734597549893e-03 -6.1409557469949e-03 -5.6428697662878e-03 -4.6633789233562e-03 -4.0724347574437e-03 -3.6970335403872e-03 -3.4730407598272e-03 -2.6662950098724e-03 -1.6671731402267e-03 -1.4151391088049e-03 -1.3924885750067e-03 -1.2386281536562e-03 -7.8640104136632e-04 8.7076048923470e-05 1.0137247293834e-04 1.0644973636339e-04 1.1375887682308e-04 -6.9140490444448e-05 5.1325876112945e-05 -2.7274798658408e-05 -7.7249855612082e-05 -1.0670627681542e-05 6.8688967291472e-15 -3.3431200990259e-01 -3.3430911573417e-01 -3.3426813339506e-01 -3.3416223452370e-01 -3.3384294600410e-01 -3.3267150138022e-01 -3.3083316691919e-01 -3.2784731775307e-01 -3.2523197806198e-01 -3.2305094688001e-01 -3.1966812384598e-01 -3.1393811631507e-01 -3.1015133822574e-01 -3.0017587481308e-01 -2.9147415044374e-01 -2.8118153756834e-01 -2.6378839820857e-01 -2.4878342623072e-01 -2.3059032235648e-01 -2.0137591740279e-01 -1.8478927095397e-01 -1.6051281424232e-01 -1.4342403163701e-01 -1.2162752863374e-01 -1.0477382391687e-01 -9.0474481350448e-02 -7.6964794046252e-02 -6.0390488688980e-02 -5.1817007419291e-02 -3.7809117562493e-02 -2.6985053527287e-02 -2.1139745396178e-02 -2.2145340583929e-02 -2.2105353087123e-02 -2.0333462803353e-02 -1.8143628868063e-02 -9.6703158087269e-03 -5.7386085523943e-03 -5.7705347982566e-03 -6.3781874005892e-03 -6.0665255702116e-03 -5.3515458106222e-03 -4.3615185890365e-03 -4.0579825276475e-03 -3.6331543855055e-03 -2.7468311983540e-03 -2.4025306671373e-03 -1.9081965949201e-03 -1.4177441185277e-03 -1.0477398551917e-03 -4.8158193964427e-04 1.2429678068588e-03 8.2401017654086e-04 8.4654589506578e-04 5.5521583164783e-04 -6.5425376455925e-04 -4.9197621340170e-04 -3.4755638854252e-04 -3.1684060124183e-04 -5.0470215915565e-05 -2.7749276670939e-14 -1.8820344925576e-01 -1.8820414018916e-01 -1.8820441640434e-01 -1.8820640506718e-01 -1.8820688177736e-01 -1.8820695053498e-01 -1.8820561616151e-01 -1.8819128817434e-01 -1.8803852017584e-01 -1.8729500266373e-01 -1.8570849759270e-01 -1.8300175961859e-01 -1.8022582251998e-01 -1.7389022206270e-01 -1.6464527862644e-01 -1.5219420761617e-01 -1.3973143064187e-01 -1.1577213204689e-01 -1.0074200386156e-01 -8.5632573745962e-02 -5.1175262065742e-02 -2.7038468046775e-02 -1.2253767923882e-02 1.0235902474772e-04 4.9671947339912e-03 5.9361026946532e-03 5.6877505218001e-03 6.3768908156237e-03 1.0358563922698e-02 5.7750166699246e-03 2.0817015234287e-03 9.6636481249715e-04 1.0508875972382e-03 1.0626101452932e-03 1.1603141941755e-03 3.6705496468842e-04 -8.4734180772205e-04 -8.0521064322668e-04 -7.8926867069485e-04 -7.7292598581696e-04 -7.2194569354104e-04 -6.2420710024888e-04 -6.1652996697283e-04 -5.8321398450078e-04 -5.3045553876744e-04 -4.8629912969114e-04 -4.6144277377185e-04 -2.1567451369275e-04 -2.0621100721751e-04 -1.9671125370416e-04 -7.8523632225992e-05 -7.5380575311650e-05 -3.5603627202271e-15 1.6442196877312e-01 1.6444219946016e-01 1.6444779179405e-01 1.6445479904352e-01 1.6447089456560e-01 1.6447859501598e-01 1.6453432051718e-01 1.6565684827135e-01 1.6810268569602e-01 1.7335993764835e-01 1.7938752061747e-01 1.8382737012488e-01 1.8857411884748e-01 1.9611551192142e-01 2.0502218316018e-01 2.1425038520765e-01 2.1934530001151e-01 2.2296405797872e-01 2.2389954654901e-01 2.2583142364997e-01 2.2948981451379e-01 2.3142835564755e-01 2.3102089520564e-01 2.2715278752640e-01 2.2152511182539e-01 2.0796116401085e-01 1.9954572438464e-01 1.9026669311573e-01 1.7486081186497e-01 1.4965375571185e-01 1.2697006132454e-01 1.0539545173046e-01 8.7223415026488e-02 5.9811158077492e-02 4.5510011246258e-02 2.6659214283350e-02 8.8855191230800e-04 -1.9342491369458e-02 -2.8163387845488e-02 -3.4993098843354e-02 -4.0257795213363e-02 -4.2193204794220e-02 -4.0503993883148e-02 -3.8786238028109e-02 -3.8437618549552e-02 -3.8481142456103e-02 -3.8394306291868e-02 -3.8157755731096e-02 -3.7415271678595e-02 -3.6938824917693e-02 -3.6326426287175e-02 -3.3731157828943e-02 -3.2841700828393e-02 -2.9485237609763e-02 -2.5614917514909e-02 -2.3166889071105e-02 -2.1496174759759e-02 -1.7383359904021e-02 -1.6747608008608e-02 -1.6226940986509e-02 -1.4552383592125e-02 -1.3041833725024e-02 -1.0684017627304e-02 -8.5852760718080e-03 -7.0466814158890e-03 -6.6528860698161e-03 -6.5972934487556e-03 4.1993357466146e-01 4.1987557407708e-01 4.1986333890908e-01 4.1977704186781e-01 4.1982740287816e-01 4.2003506763147e-01 4.2027416651816e-01 4.2027371861334e-01 4.2027128212321e-01 4.2013261500130e-01 4.1901825608221e-01 4.1467793983953e-01 4.1342061581277e-01 4.1090695149429e-01 4.0096660622947e-01 3.9370156482998e-01 3.7777204786648e-01 3.6513664728929e-01 3.4518901067830e-01 3.2171974164346e-01 3.0313869058668e-01 2.7130491881280e-01 2.4400842872424e-01 2.2812430354688e-01 2.0484424917190e-01 1.8593770676752e-01 1.5857652757112e-01 1.4291765544163e-01 1.1943920592447e-01 1.0075777508200e-01 7.0654306943247e-02 5.1871273813169e-02 3.8365236319882e-02 2.3366460449576e-02 1.1185858854992e-02 -6.9893469924480e-03 -2.3253201169850e-02 -5.1775564131283e-02 -7.1650826348026e-02 -9.1229001293225e-02 -1.1575929775832e-01 -1.4421239381883e-01 -1.6342042019810e-01 -1.8374889322468e-01 -1.9127627533269e-01 -1.9119464651734e-01 -1.9146447679654e-01 -1.9199559473962e-01 -1.9209476999541e-01 -1.9249327302784e-01 -1.9206498524209e-01 -1.8944791732375e-01 -1.8819991685170e-01 -1.8628095687006e-01 -1.8613495926395e-01 -1.8585466597543e-01 -1.8572851474746e-01 -1.8541999007639e-01 -1.8462020462659e-01 -1.8432273434766e-01 -1.8423831719979e-01 -1.8404673119039e-01 -1.8368593626646e-01 -1.8364528567632e-01 -1.8359984676756e-01 -1.8349514139219e-01 -1.8343740279325e-01 -1.8335608336923e-01 -1.8318884706215e-01 -1.8307904709681e-01 -1.8276052691676e-01 -1.8159491204837e-01 -1.7763935210049e-01 -1.7706617299129e-01 -1.7710707494523e-01 -1.7713652494645e-01 -5.1898676182329e-02 -5.1897275120782e-02 -5.1893017001070e-02 -5.1869620440473e-02 -5.1865362442256e-02 -5.1862879992153e-02 -5.1825871907455e-02 -5.1824639899218e-02 -5.1819407549367e-02 -5.1791902301971e-02 -5.1849407587388e-02 -5.2069529708121e-02 -5.1656597465568e-02 -5.1160300905781e-02 -5.1152427160275e-02 -5.1263748253161e-02 -4.8552665399122e-02 -4.5006157629473e-02 -4.0235311650525e-02 -3.4986908989009e-02 -2.8480850196219e-02 -2.3564517315508e-02 -1.6320325206653e-02 -8.0838035254993e-03 1.9483723138620e-03 7.7461410519264e-03 1.4008802489387e-02 2.0242559108348e-02 3.0152850202593e-02 3.5217669502265e-02 3.9286850970943e-02 4.0118568144919e-02 3.4579331454710e-02 2.7383630905887e-02 1.6239006721717e-02 7.5237692406136e-03 3.2455513893078e-03 -2.2414546581321e-04 -1.7757860765986e-03 -3.9370476342206e-03 -4.0117142723836e-03 -3.1813569166383e-03 -2.7656881226979e-03 -2.3512016313681e-03 -2.3349646437772e-03 -2.3250436055696e-03 -2.1278262671217e-03 -1.6806549945198e-03 -1.6567787746474e-03 -1.5342084630699e-03 -1.2263684320901e-03 -1.0895681222041e-03 -6.0393878910939e-04 -2.7624193874986e-05 3.8895067149157e-04 8.3804295250556e-04 9.5436325025689e-04 9.8871139854876e-04 1.0396523343888e-03 1.1534040688157e-03 1.1629823263765e-03 1.1632877896591e-03 1.1341811391951e-03 1.0711460298096e-03 1.0207817965421e-03 8.6359754760963e-04 9.4717605659602e-04 9.4838810173235e-04 9.4918104254617e-04 9.4862792638061e-04 2.3150788905906e-01 2.3151551894438e-01 2.3153076952461e-01 2.3153458218525e-01 2.3154342202747e-01 2.3154913877522e-01 2.3155452782765e-01 2.3155659247033e-01 2.3155676284185e-01 2.3158764137933e-01 2.3174579732301e-01 2.3262881405304e-01 2.3448352846143e-01 2.3695565737710e-01 2.3996604099780e-01 2.4306312325831e-01 2.4908650222634e-01 2.5242229433658e-01 2.5523061965822e-01 2.5830161698006e-01 2.6108909178604e-01 2.6338548630637e-01 2.6394194391615e-01 2.6380948562727e-01 2.6407953392180e-01 2.6282385061831e-01 2.6027969518641e-01 2.5731073405834e-01 2.4926972887600e-01 2.3948043541281e-01 2.3464172612918e-01 2.3025727779718e-01 2.1940373058508e-01 2.0782627336031e-01 1.9338044646518e-01 1.5845152768204e-01 1.2091105545231e-01 1.0164188172373e-01 8.5386369048197e-02 6.4968339043853e-02 4.7303893052812e-02 2.9581536366626e-02 2.5324558868288e-02 2.1920947152073e-02 1.3284027946212e-02 9.8814121791731e-03 5.9706961370352e-03 1.9855771686010e-03 1.4989059139229e-03 1.6488929337742e-03 1.6893112085118e-03 2.3880705100305e-03 3.6387909878689e-03 5.8309491944822e-03 6.5570805595964e-03 7.5329066795834e-03 1.0635455533782e-02 1.2874819468960e-02 1.4091851548079e-02 1.6245591824042e-02 1.7251382762703e-02 1.7635863299280e-02 1.8098004810759e-02 1.8857149873338e-02 1.9550453035942e-02 2.0313625403914e-02 2.0334214161709e-02 2.0371700174298e-02 2.0376938365032e-02 2.0547111106525e-02 2.0557607827561e-02 1.1746001135644e-01 1.1746617017040e-01 1.1748328319188e-01 1.1749763013414e-01 1.1750081706466e-01 1.1751834719611e-01 1.1758050335201e-01 1.1756468262645e-01 1.1754212030890e-01 1.1760782940881e-01 1.1810086352277e-01 1.1959006458683e-01 1.2207611075164e-01 1.2504612844259e-01 1.3113350904409e-01 1.3395603018480e-01 1.3625163342444e-01 1.4268524089962e-01 1.4919322830246e-01 1.5460347778832e-01 1.6069293039753e-01 1.6404831071934e-01 1.6263767152496e-01 1.6083052241527e-01 1.5726198299340e-01 1.4812913596214e-01 1.4239295007054e-01 1.3812859001893e-01 1.2582567922036e-01 1.1408009825504e-01 9.7701151298579e-02 8.1269469545399e-02 6.9159375747472e-02 5.7962113583756e-02 3.8025880968425e-02 2.8078417962688e-02 1.9239872454786e-02 7.5814706369838e-03 -3.7408602391715e-03 -6.3868891477049e-03 -8.9052689560940e-03 -1.2315837719006e-02 -1.2310568294620e-02 -1.2277656386530e-02 -1.2205602445062e-02 -1.2143598637477e-02 -1.2059685948537e-02 -1.1747182650682e-02 -1.1599343471084e-02 -1.1387644881338e-02 -1.0297571015198e-02 -9.5976372479647e-03 -8.9109857782040e-03 -6.9483426765347e-03 -6.3655435246170e-03 -5.9351845901564e-03 -5.6295056979662e-03 -5.3952005340249e-03 -5.2668324334590e-03 -5.0954499328490e-03 -4.4075124654678e-03 -3.7026504330891e-03 -3.5389422481987e-03 2.6231384720472e-01 2.6230932453545e-01 2.6231330673676e-01 2.6227637797250e-01 2.6226915767422e-01 2.6229483402712e-01 2.6241900266321e-01 2.6242014034296e-01 2.6235999341652e-01 2.6181219226963e-01 2.6191459548139e-01 2.6407659530480e-01 2.6674680391220e-01 2.6981824840396e-01 2.7315336993274e-01 2.7874633544015e-01 2.8101035239495e-01 2.8288199174228e-01 2.8589503709247e-01 2.8456253810000e-01 2.8255403660937e-01 2.7854325999109e-01 2.6838467059147e-01 2.5993680277301e-01 2.5611956005419e-01 2.4677166012960e-01 2.3680498527355e-01 2.2870502514538e-01 2.0912849645091e-01 1.9253491093173e-01 1.6214993066230e-01 1.5597635655318e-01 1.2729253041620e-01 1.1042413175698e-01 8.8629137471284e-02 6.6240657274746e-02 3.4903335390742e-02 1.9037963796052e-02 5.5836486929490e-03 -6.4887391701922e-03 -1.6064194155799e-02 -2.2990976639008e-02 -2.9796754738704e-02 -3.4239613772660e-02 -3.6839371312872e-02 -3.6742508140117e-02 -3.5349432248633e-02 -3.2980263427927e-02 -2.9923552937149e-02 -2.7499140563345e-02 -2.4288735445631e-02 -2.3354210568299e-02 -2.2746284936088e-02 -2.2334756947524e-02 -2.1148103164299e-02 -1.9735088289473e-02 -1.9262196463419e-02 -1.9213914031337e-02 -1.9141457261495e-02 -1.8867224754500e-02 -1.8667634263196e-02 -1.8660032489245e-02 -1.8308002527829e-02 -1.7546396436321e-02 -1.6979794999038e-02 -1.6499446945813e-02 -1.6499241981281e-02 -1.6445854277811e-02 -1.6335115126530e-02 -1.6324429465280e-02 2.5515257601700e-01 2.5526768179130e-01 2.5542986909084e-01 2.5570211835672e-01 2.5627085469265e-01 2.5768431490012e-01 2.5909533642110e-01 2.6067324682937e-01 2.6171546169212e-01 2.6248333475455e-01 2.6334390343936e-01 2.6334548044207e-01 2.6268917243106e-01 2.6101616035078e-01 2.5800398125199e-01 2.5328624634822e-01 2.4438538043951e-01 2.3860265890372e-01 2.3402002118807e-01 2.2422980077534e-01 2.1593381472421e-01 1.9485833535731e-01 1.7104151602122e-01 1.4305185311751e-01 1.2567810746729e-01 1.1413872757187e-01 1.0357891887490e-01 8.2963979609588e-02 6.6932876214498e-02 3.5184291254927e-02 1.0926722372027e-02 -1.1224497806222e-02 -4.0290116170002e-02 -5.5170250098625e-02 -7.0434195607556e-02 -8.6079411095601e-02 -1.0159422909250e-01 -1.0482183302151e-01 -1.0505566188584e-01 -1.0646944813836e-01 -1.0628253854841e-01 -1.0505182851771e-01 -1.0157093486265e-01 -1.0012511513909e-01 -9.8915510467170e-02 -9.6571829089258e-02 -9.5399034091221e-02 -9.3528004079507e-02 -9.3076662819498e-02 -9.2551101282346e-02 -9.1387951468575e-02 -8.8031772269025e-02 -8.7563770290271e-02 -8.7316938080487e-02 -8.6881715983230e-02 -8.6624452695485e-02 -8.6649506147161e-02 -8.6680436075055e-02 -8.6537238447011e-02 -8.5336475456105e-02 -8.5296167843178e-02 -2.8304787530431e-02 -2.8291654502510e-02 -2.8286391114386e-02 -2.8248270615708e-02 -2.8239072834787e-02 -2.8215804734572e-02 -2.7490498036081e-02 -2.6903608639032e-02 -2.4627627630058e-02 -1.9653669520939e-02 -1.4379658091116e-02 -8.4506637517898e-03 -3.6319036200279e-03 8.2539694387532e-03 2.0383935502632e-02 2.7161018979120e-02 3.2625517717328e-02 4.2823044396807e-02 5.1444155884815e-02 5.8894102706073e-02 6.2526115559752e-02 6.0660141882339e-02 5.9923757851882e-02 5.7490153980977e-02 5.0759446110582e-02 3.8350743566168e-02 3.3427364021809e-02 2.9104006629877e-02 9.6797657640525e-03 1.3257305451044e-03 -1.2603661241211e-03 -2.9661602475471e-03 -2.9471474780887e-03 -2.9260116993058e-03 -2.9159945882095e-03 -3.2552673472908e-03 -4.7440836928626e-03 -4.8272631183293e-03 -4.7469818291458e-03 -4.7249702776985e-03 -4.7255039905356e-03 -4.7174745489673e-03 -4.7123512370704e-03 -4.7059213249671e-03 -4.7017461624605e-03 -4.7001055412574e-03 -4.6891964510004e-03 -4.6714411391381e-03 -4.6710593552551e-03 -4.6705198595805e-03 -4.6615030153809e-03 -4.6614544218483e-03 -4.6494242127567e-03 + -6.4364216011368e-01 -6.4366799437876e-01 -6.4367986400733e-01 -6.4369473659720e-01 -6.4372889793715e-01 -6.4374524111408e-01 -6.4381970279349e-01 -6.4525841229642e-01 -6.4822190838930e-01 -6.5407780661156e-01 -6.6137856658779e-01 -6.6999945981573e-01 -6.8237877825083e-01 -6.9909201133696e-01 -7.1126099944254e-01 -7.2319994900761e-01 -7.3336937173059e-01 -7.4849306806437e-01 -7.6109147524441e-01 -7.7070058011100e-01 -7.8017091027258e-01 -7.8988267358461e-01 -7.9713928909276e-01 -8.0361823652268e-01 -8.0861086166613e-01 -8.1572305426201e-01 -8.1858874588187e-01 -8.2100203968411e-01 -8.2454652528070e-01 -8.3087251730066e-01 -8.3661574394012e-01 -8.4266012266216e-01 -8.4898419677894e-01 -8.5803614972718e-01 -8.6281985068588e-01 -8.6923483890466e-01 -8.7891268631134e-01 -8.8615471170414e-01 -8.8952536279233e-01 -8.9398912801296e-01 -8.9899546003763e-01 -9.0596760376790e-01 -9.0815006157807e-01 -9.0886057043501e-01 -9.0975751929908e-01 -9.0943567932360e-01 -9.0991551795768e-01 -9.1002633254254e-01 -9.0987114580896e-01 -9.0940583678125e-01 -9.0900327133831e-01 -9.0849631580924e-01 -9.0872466699493e-01 -9.0919379290261e-01 -9.0968100689740e-01 -9.0979375505936e-01 -9.0968273560360e-01 -9.0985038902279e-01 -9.0982968063053e-01 -9.0993403957061e-01 -9.1033959114869e-01 -9.1059467396875e-01 -9.1071181431356e-01 -9.1071006537525e-01 -9.1070074828466e-01 -9.1073604609584e-01 -9.1073259833501e-01 -3.8627370476887e-01 -3.8633358852924e-01 -3.8634645774604e-01 -3.8643455303065e-01 -3.8638330534649e-01 -3.8617243016612e-01 -3.8592802667593e-01 -3.8592867693163e-01 -3.8593119947724e-01 -3.8607250076077e-01 -3.8720724811004e-01 -3.9159523409167e-01 -3.9301618511213e-01 -3.9584239124711e-01 -4.0630090368356e-01 -4.1383025776153e-01 -4.2955220257514e-01 -4.4095556469643e-01 -4.5697790993492e-01 -4.7344593708279e-01 -4.8480650968670e-01 -4.9584277872525e-01 -4.9398053024151e-01 -4.8868939914946e-01 -4.7797707213338e-01 -4.6822307042660e-01 -4.5343932714699e-01 -4.4474227331925e-01 -4.2606272310425e-01 -4.0933226649556e-01 -3.7949387019804e-01 -3.5934938136136e-01 -3.4442828337453e-01 -3.2525562826814e-01 -3.1048884051454e-01 -2.9315829303734e-01 -2.7950186714817e-01 -2.5580284682578e-01 -2.4046623098904e-01 -2.2782409311073e-01 -2.1714461052876e-01 -2.0922682013966e-01 -2.0538771651970e-01 -2.0261152617994e-01 -2.0152629583073e-01 -2.0097620073128e-01 -2.0265815473550e-01 -2.0392300272140e-01 -2.0418545022559e-01 -2.0453499772841e-01 -2.0398238290046e-01 -2.0248313230368e-01 -2.0153893187193e-01 -2.0028136190225e-01 -2.0012385179865e-01 -1.9997858997849e-01 -1.9959724362179e-01 -1.9943515981912e-01 -1.9914461090777e-01 -1.9889743108770e-01 -1.9884609583369e-01 -1.9878698102004e-01 -1.9867829433894e-01 -1.9866035703380e-01 -1.9863997371266e-01 -1.9867021592080e-01 -1.9883288447115e-01 -1.9919011726392e-01 -1.9919077105729e-01 -1.9919912463745e-01 -1.9909667114741e-01 -1.9861819659253e-01 -1.9747514571197e-01 -1.9736854621809e-01 -1.9740321045531e-01 -1.9743832544489e-01 -7.6239925234501e-01 -7.6240088873288e-01 -7.6240586202530e-01 -7.6242344455476e-01 -7.6242841750865e-01 -7.6243584407610e-01 -7.6252774843658e-01 -7.6253080113454e-01 -7.6250770952908e-01 -7.6253299240177e-01 -7.6233925896801e-01 -7.6173123108246e-01 -7.6268429207225e-01 -7.6374915248200e-01 -7.6335518403503e-01 -7.6273600248103e-01 -7.7020500940003e-01 -7.7949259666958e-01 -7.9179505441831e-01 -8.1317361289444e-01 -8.4005259144138e-01 -8.5635543972732e-01 -8.7674772827986e-01 -8.9366791824916e-01 -9.1462511173291e-01 -9.3083973709225e-01 -9.4700834392561e-01 -9.5981815780533e-01 -9.7591941979769e-01 -9.8348232465728e-01 -9.9021591849447e-01 -9.9652657704406e-01 -9.9874495598080e-01 -9.9955298856695e-01 -9.9979013036598e-01 -9.9979948433337e-01 -9.9984774419115e-01 -9.9987895388490e-01 -9.9994903700080e-01 -9.9997710978442e-01 -9.9997416432145e-01 -9.9997808394213e-01 -9.9997950271604e-01 -9.9998115877244e-01 -9.9998087188559e-01 -9.9997915388573e-01 -9.9995534734720e-01 -9.9996507974177e-01 -9.9996597166223e-01 -9.9996780501916e-01 -9.9997131618909e-01 -9.9997233065354e-01 -9.9997629837215e-01 -9.9998061692004e-01 -9.9998329178600e-01 -9.9998558193997e-01 -9.9998578631513e-01 -9.9998360546092e-01 -9.9998358826912e-01 -9.9998387460401e-01 -9.9998368589130e-01 -9.9998254588618e-01 -9.9997132729663e-01 -9.9996735975070e-01 -9.9996985283338e-01 -9.9994690605867e-01 -9.9993471114571e-01 -9.9993576665826e-01 -9.9993657222849e-01 -9.9993628275920e-01 -5.9359388347448e-01 -5.9358590217017e-01 -5.9356994898560e-01 -5.9356596063367e-01 -5.9355964814536e-01 -5.9355366793392e-01 -5.9356651726572e-01 -5.9358257405185e-01 -5.9358389909042e-01 -5.9366344494991e-01 -5.9401517598482e-01 -5.9578722829482e-01 -5.9891560606757e-01 -6.0289831940974e-01 -6.0743470323664e-01 -6.1192854861888e-01 -6.2010910009864e-01 -6.2422400583451e-01 -6.2778181296060e-01 -6.3293471226487e-01 -6.3826136970971e-01 -6.4698865637879e-01 -6.5381338863045e-01 -6.6205486915924e-01 -6.7671070137006e-01 -6.8505420762330e-01 -6.9246429275937e-01 -6.9817556133630e-01 -7.0824242148738e-01 -7.1575339897524e-01 -7.1784516941540e-01 -7.1849651176043e-01 -7.1886145462373e-01 -7.1957236457172e-01 -7.2005511790646e-01 -7.2030038244473e-01 -7.2161555957279e-01 -7.2220716334703e-01 -7.2596673857412e-01 -7.3432862960609e-01 -7.4307489432424e-01 -7.5188966292247e-01 -7.5495296498381e-01 -7.5775647027013e-01 -7.6134501145050e-01 -7.6090134792928e-01 -7.6142679826206e-01 -7.6272306273702e-01 -7.6292770504382e-01 -7.6290125433491e-01 -7.6301330029551e-01 -7.6271095882673e-01 -7.6182528977051e-01 -7.6092133993625e-01 -7.6067142935352e-01 -7.6029068092385e-01 -7.5871283692620e-01 -7.5786015210321e-01 -7.5765423646586e-01 -7.5760381244309e-01 -7.5729069489173e-01 -7.5710710578606e-01 -7.5692929146961e-01 -7.5664792076942e-01 -7.5655558302470e-01 -7.5703895933129e-01 -7.5707383275892e-01 -7.5707468171635e-01 -7.5710248548474e-01 -7.5707388005689e-01 -7.5710669941951e-01 -7.3033472875662e-01 -7.3034886004810e-01 -7.3033502520834e-01 -7.3032126661385e-01 -7.3031821031070e-01 -7.3030139829561e-01 -7.3024178266385e-01 -7.3016099803560e-01 -7.3009066835864e-01 -7.3025992478796e-01 -7.3147411656484e-01 -7.3514034195053e-01 -7.4163605261790e-01 -7.4933005460877e-01 -7.6649599317185e-01 -7.7520283512214e-01 -7.8232488560778e-01 -8.0117335889643e-01 -8.1920446851889e-01 -8.3256998436149e-01 -8.4965226235141e-01 -8.6396416116364e-01 -8.8353582979871e-01 -8.9258192977716e-01 -9.0141267952651e-01 -9.1929958514136e-01 -9.2942226472272e-01 -9.3521610645696e-01 -9.4216265901938e-01 -9.4675361696303e-01 -9.5173421196689e-01 -9.5597978695033e-01 -9.5795265347377e-01 -9.5953209004418e-01 -9.6264537779031e-01 -9.6469327913143e-01 -9.6634054096224e-01 -9.6787584406709e-01 -9.6964542822386e-01 -9.7007838299615e-01 -9.7096233832243e-01 -9.7163991245521e-01 -9.7176536542385e-01 -9.7183490708954e-01 -9.7189430477633e-01 -9.7189508130386e-01 -9.7187492897184e-01 -9.7183998047098e-01 -9.7185397186523e-01 -9.7189719497595e-01 -9.7196217451372e-01 -9.7202392533021e-01 -9.7218826057133e-01 -9.7266747276820e-01 -9.7267091872649e-01 -9.7261305751117e-01 -9.7260538409767e-01 -9.7260665167021e-01 -9.7263086957423e-01 -9.7269451441081e-01 -9.7289681391903e-01 -9.7301876418852e-01 -9.7308740906659e-01 -4.6657688956765e-01 -4.6654728882015e-01 -4.6654616158502e-01 -4.6634622574909e-01 -4.6631588766552e-01 -4.6637186803460e-01 -4.6669364794127e-01 -4.6669348531427e-01 -4.6645919365176e-01 -4.6387783797385e-01 -4.6466839176348e-01 -4.6729296756656e-01 -4.7217365987658e-01 -4.7666084895383e-01 -4.8207866893632e-01 -4.8900959850024e-01 -4.9273059625052e-01 -4.9694059280492e-01 -5.1298796085581e-01 -5.2487442547709e-01 -5.3975129012535e-01 -5.5058333414401e-01 -5.6519710741447e-01 -5.7015998036017e-01 -5.7165722965377e-01 -5.7131347658594e-01 -5.6248199641066e-01 -5.5376817695811e-01 -5.3212845177018e-01 -5.1174330974207e-01 -4.8476990769212e-01 -4.8163989815076e-01 -4.7265070988222e-01 -4.7500405054087e-01 -4.8068285242130e-01 -4.8743684893775e-01 -4.9657352369792e-01 -5.0275670678002e-01 -5.1147735596932e-01 -5.2553483871065e-01 -5.3575718449651e-01 -5.4105518645265e-01 -5.4711137903710e-01 -5.5328201560864e-01 -5.5639866309008e-01 -5.5538899047495e-01 -5.5494952926802e-01 -5.5343875397362e-01 -5.5118356898804e-01 -5.5043981475208e-01 -5.4909274146074e-01 -5.4844324494667e-01 -5.4782725878510e-01 -5.4731070709202e-01 -5.4614032362861e-01 -5.4546151028461e-01 -5.4495049408315e-01 -5.4482859753639e-01 -5.4467587208908e-01 -5.4434553651452e-01 -5.4422969392133e-01 -5.4419457390416e-01 -5.4340768295475e-01 -5.4261928625687e-01 -5.4196357549541e-01 -5.4149406185092e-01 -5.4146653011951e-01 -5.4143973076470e-01 -5.4138421614110e-01 -5.4131073922229e-01 -5.4311313522374e-01 -5.4512835745548e-01 -5.4731869840343e-01 -5.5047423749771e-01 -5.5606314002662e-01 -5.6876742257444e-01 -5.8037307154184e-01 -5.9382548745731e-01 -6.0377836453848e-01 -6.1315580670799e-01 -6.2276990319262e-01 -6.4022380241560e-01 -6.5040927158000e-01 -6.7075995561546e-01 -6.8710916017003e-01 -7.0034192548021e-01 -7.1524391472112e-01 -7.2243476724317e-01 -7.2852560011212e-01 -7.3239964111886e-01 -7.3235451768141e-01 -7.2934348706283e-01 -7.2480417287464e-01 -7.1937282777231e-01 -7.1572184400201e-01 -7.1276239559552e-01 -7.1009361181066e-01 -7.0693129006800e-01 -7.0582245945826e-01 -7.0581694983655e-01 -7.1092805487521e-01 -7.1898950355220e-01 -7.2936859796128e-01 -7.3603264610150e-01 -7.4263358506891e-01 -7.5014795540774e-01 -7.5766421618380e-01 -7.5912757837909e-01 -7.5909208808671e-01 -7.5975611296042e-01 -7.6004806316523e-01 -7.5999801104195e-01 -7.5958074683754e-01 -7.5928309238072e-01 -7.5920155122025e-01 -7.5845220079104e-01 -7.5803651361161e-01 -7.5755464579105e-01 -7.5726702344725e-01 -7.5712148497109e-01 -7.5704686892305e-01 -7.5712752694003e-01 -7.5708855001466e-01 -7.5704380829764e-01 -7.5708644935221e-01 -7.5736423391070e-01 -7.5724131823540e-01 -7.5715631509919e-01 -7.5700862616333e-01 -7.5666619816181e-01 -7.5652318131037e-01 -7.2455832033946e-01 -7.2457549611582e-01 -7.2458237960174e-01 -7.2463223148990e-01 -7.2464425923705e-01 -7.2473711141315e-01 -7.2772825657793e-01 -7.2998805269771e-01 -7.3793576823385e-01 -7.5408571417110e-01 -7.7011672840597e-01 -7.8802339820893e-01 -8.0294753751294e-01 -8.3894747238799e-01 -8.7363885066184e-01 -8.9420213522815e-01 -9.0946126662388e-01 -9.3203970749745e-01 -9.4668454641441e-01 -9.5838210054764e-01 -9.7614578961660e-01 -9.8421509017300e-01 -9.8794010758603e-01 -9.9036014613814e-01 -9.9183799378805e-01 -9.9341968225453e-01 -9.9369987129414e-01 -9.9381317287758e-01 -9.9573063671149e-01 -9.9632982776818e-01 -9.9648773235154e-01 -9.9658112088775e-01 -9.9679144328465e-01 -9.9729609565085e-01 -9.9759305229664e-01 -9.9763496833080e-01 -9.9769013809542e-01 -9.9769511214363e-01 -9.9769366510006e-01 -9.9769359002811e-01 -9.9769481692578e-01 -9.9769600988545e-01 -9.9769570703042e-01 -9.9769539855494e-01 -9.9769502473981e-01 -9.9769500375146e-01 -9.9769471329139e-01 -9.9769289317739e-01 -9.9769289084645e-01 -9.9769297723692e-01 -9.9769217487160e-01 -9.9769213602108e-01 -9.9769121868884e-01 7.6556658859236e-01 7.6550982123449e-01 7.6548588040820e-01 7.6545588141358e-01 7.6538697047408e-01 7.6535400009569e-01 7.6519175631098e-01 7.6202388492160e-01 7.5533313431122e-01 7.4152780796319e-01 7.2438751619921e-01 7.0625469648370e-01 6.8087112079131e-01 6.4317038089368e-01 6.0959887506693e-01 5.7347336470965e-01 5.4399642924482e-01 5.0138525228373e-01 4.6443173827812e-01 4.3048799162280e-01 3.8843909444582e-01 3.3967644461171e-01 2.9720370218831e-01 2.5692589196267e-01 2.2411755745173e-01 1.7657488163364e-01 1.5047450580507e-01 1.2649011216440e-01 9.9233091813425e-02 7.7161230875121e-02 6.4498311591905e-02 6.0778343027278e-02 6.6858521354823e-02 7.3299059448423e-02 7.8609642461646e-02 8.5408478588133e-02 1.0037281372495e-01 1.1016912280899e-01 1.1103879883394e-01 1.1417687567509e-01 1.1921564340357e-01 1.1924278702984e-01 1.2301391611694e-01 1.2286940387290e-01 1.2902454743854e-01 1.2733542867354e-01 1.3271287763364e-01 1.3404354999472e-01 1.3193849299036e-01 1.2985751086392e-01 1.2577204248085e-01 1.2465638952392e-01 1.2331572177242e-01 1.1773001068017e-01 1.1699106060513e-01 1.1645192698102e-01 1.1580493809610e-01 1.1371806265320e-01 1.1359558688018e-01 1.1362850340707e-01 1.1296225499964e-01 1.1194262968819e-01 1.1086789304910e-01 1.0997712172745e-01 1.0911333020639e-01 1.0883225658072e-01 1.0877636243559e-01 7.5196242085448e-01 7.5181026385081e-01 7.5181230538494e-01 7.5158620030271e-01 7.5173570105458e-01 7.5230728496601e-01 7.5300004539873e-01 7.5299710398315e-01 7.5300069444863e-01 7.5264674974094e-01 7.4979974875183e-01 7.3880584786174e-01 7.3843702195891e-01 7.3908602611168e-01 7.2926272892662e-01 7.2312763496085e-01 7.0493296992615e-01 6.8376206222727e-01 6.4031672316846e-01 5.8280798520257e-01 5.3630723199493e-01 4.6664067815404e-01 4.2699718004386e-01 4.1076556161052e-01 3.8627762360527e-01 3.6145435357451e-01 3.2047294662021e-01 2.9548326041324e-01 2.6429461119546e-01 2.5061463725067e-01 2.3815929941225e-01 2.3124149802945e-01 2.2207730011556e-01 2.1161975230205e-01 2.0604077944006e-01 1.9936221998622e-01 1.9557985323902e-01 1.9660603056264e-01 1.9554692198120e-01 1.9198751780356e-01 1.8952752829421e-01 1.9479565242768e-01 2.0307141426357e-01 2.2142869898652e-01 2.2798400560352e-01 2.2040986627850e-01 2.2462576964027e-01 2.2752341147591e-01 2.2854704446215e-01 2.2811909880975e-01 2.2148861852267e-01 2.1139083981970e-01 2.0504690362962e-01 1.9727476874876e-01 1.9615384335568e-01 1.9533302212167e-01 1.9238832304515e-01 1.9173579324765e-01 1.9080367502303e-01 1.8926855706118e-01 1.8898920184957e-01 1.8884879077441e-01 1.8861443307103e-01 1.8854868992011e-01 1.8846062231932e-01 1.8893939014172e-01 1.9019771594001e-01 1.9249944474041e-01 1.9269259193806e-01 1.9286876858393e-01 1.9259518093912e-01 1.9077415655190e-01 1.8661256510356e-01 1.8593287311130e-01 1.8618069535303e-01 1.8644484702193e-01 6.7467992961532e-01 6.7467721253332e-01 6.7466895472892e-01 6.7463859211671e-01 6.7463033423683e-01 6.7461791497120e-01 6.7447111898115e-01 6.7446527300652e-01 6.7450012461158e-01 6.7445764917313e-01 6.7476419391744e-01 6.7573107139852e-01 6.7420135623216e-01 6.7248071878026e-01 6.7307760730325e-01 6.7404612459176e-01 6.6205628031050e-01 6.4683119909907e-01 6.2618397368640e-01 5.8977500711395e-01 5.4089247400474e-01 5.0890976651327e-01 4.6598723397883e-01 4.2798368180129e-01 3.8052502304367e-01 3.4228659506325e-01 2.9991594551487e-01 2.6182260457325e-01 2.0301724796944e-01 1.6737689176552e-01 1.2671631233662e-01 6.9331219658056e-02 3.4184276650608e-02 9.4349524819075e-03 -1.1997664648960e-02 -1.8578454181664e-02 -1.7060494492975e-02 -1.5194608603368e-02 -9.0206954265146e-03 3.8031916014624e-05 9.8374720466807e-04 7.5608930552082e-04 9.5552863114996e-04 6.6614651941890e-04 1.0177486183749e-03 2.0729469968128e-03 7.1347870858332e-03 5.8440991168305e-03 5.7029429065693e-03 5.4338098829524e-03 4.9033227461081e-03 4.7630954596392e-03 4.0768543352291e-03 3.0916141389339e-03 2.3035391615632e-03 1.2268031920641e-03 1.0379312073622e-03 1.9903253068287e-03 1.9819817274964e-03 1.8192842973990e-03 1.8314606003502e-03 2.2419013476971e-03 4.9516105412812e-03 5.4066600723267e-03 4.8835592962884e-03 3.5347913583245e-03 2.7657359503138e-03 2.2032038953580e-03 5.4039541615780e-05 -1.0571979379284e-04 7.4054056787783e-01 7.4054360416839e-01 7.4054967287993e-01 7.4055119001980e-01 7.4054918539135e-01 7.4055146008103e-01 7.4051772572438e-01 7.4048013195664e-01 7.4047702954733e-01 7.4027023739115e-01 7.3933500400111e-01 7.3449859409785e-01 7.2545087331927e-01 7.1355424315701e-01 6.9938365934104e-01 6.8476156058490e-01 6.5631928854640e-01 6.4078063152809e-01 6.2706049961357e-01 6.0862754494736e-01 5.8936715770883e-01 5.6037774661998e-01 5.3838992547220e-01 5.1170467852543e-01 4.5492180274033e-01 4.1913377986716e-01 3.8500408153610e-01 3.5611982027890e-01 3.0018182771418e-01 2.3942522901291e-01 2.0255406309798e-01 1.6978106158479e-01 1.2213597902275e-01 1.0833535248666e-01 1.0408214207650e-01 9.7707838920949e-02 9.5813585802748e-02 9.6672312211009e-02 1.0697288660105e-01 1.1303388271758e-01 1.2975411374123e-01 1.4202635404985e-01 1.4886852406847e-01 1.5632040319669e-01 1.6419023059109e-01 1.6447948379046e-01 1.6854507619561e-01 1.7460143556287e-01 1.7436247580500e-01 1.7392754261999e-01 1.7444022802599e-01 1.7361340809586e-01 1.7028996640365e-01 1.6881947312333e-01 1.6861124928884e-01 1.6809357337122e-01 1.6434747068536e-01 1.6303203587120e-01 1.6230657264308e-01 1.6097900013740e-01 1.6053660442722e-01 1.6022402182829e-01 1.5999240317813e-01 1.5962877135545e-01 1.5970597928696e-01 1.5980111864170e-01 1.6003237116680e-01 1.6016098779973e-01 1.6034992713780e-01 1.6047130339469e-01 1.6069451058895e-01 7.0847428946493e-01 7.0844898561170e-01 7.0845955434334e-01 7.0847160384323e-01 7.0847428039121e-01 7.0848900280652e-01 7.0854119976122e-01 7.0867446260148e-01 7.0879598005674e-01 7.0849732872133e-01 7.0634077230564e-01 6.9979078617980e-01 6.8812874848546e-01 6.7406174270004e-01 6.4195303648846e-01 6.2522398721888e-01 6.1120910507472e-01 5.7219097774792e-01 5.3188417439356e-01 4.9932776699861e-01 4.5494273724139e-01 4.1571526275104e-01 3.6130925567504e-01 3.3414295858906e-01 3.0704269515052e-01 2.4294777194552e-01 1.9459661889913e-01 1.5961306483155e-01 1.1905773642320e-01 8.5855835088170e-02 4.7227704537057e-02 2.6231755587724e-02 1.5974235414926e-02 6.7505992306040e-03 1.6771175410586e-03 7.9918957044724e-03 1.1631435833245e-02 9.4399241637702e-03 1.4262051014731e-02 1.5876588214229e-02 2.3046149715915e-02 2.8860453041074e-02 3.2108572673953e-02 3.4556070910271e-02 3.7329121308550e-02 3.7500419534363e-02 3.7095088964917e-02 3.6905748619684e-02 3.6929100498102e-02 3.6940182722050e-02 3.6458096224365e-02 3.5874017094384e-02 3.5402733869370e-02 3.4548998744520e-02 3.4158714428171e-02 3.3737723323467e-02 3.3774518068015e-02 3.3745656977222e-02 3.3743829368527e-02 3.3643785667155e-02 3.3364484612259e-02 3.2990808796744e-02 3.2995036716403e-02 8.3827094905937e-01 8.3836210725062e-01 8.3835668909849e-01 8.3898552694070e-01 8.3908432277463e-01 8.3887557402910e-01 8.3772237862605e-01 8.3772060196703e-01 8.3849449830670e-01 8.4669772580773e-01 8.4467019032195e-01 8.3321105068503e-01 8.1346192161334e-01 7.9313133738251e-01 7.6815854242813e-01 7.3104785765089e-01 7.1231985217984e-01 6.9192089175190e-01 6.2490326190972e-01 5.8647523376753e-01 5.3352848431390e-01 4.8518116321269e-01 4.1042587830011e-01 3.6192117777108e-01 3.3927638036143e-01 2.6556447717992e-01 2.1587966891266e-01 1.9003596946484e-01 1.5760892525421e-01 1.4499892557903e-01 1.3179211693368e-01 1.2937429074140e-01 1.3371866230521e-01 1.4528882169880e-01 1.5835154838244e-01 1.6843729711548e-01 1.9179614036432e-01 2.0916469827258e-01 2.2387026274816e-01 2.5198624879517e-01 2.6277679960726e-01 2.6348366836728e-01 2.7262022661740e-01 2.8468130887610e-01 2.8753605204846e-01 2.8256933374520e-01 2.8239603018807e-01 2.7867124428972e-01 2.7225646289982e-01 2.7210568741076e-01 2.6981957451530e-01 2.6810574682545e-01 2.6600742310177e-01 2.6412172076307e-01 2.6046572210188e-01 2.5953631905703e-01 2.5780712876672e-01 2.5738025590934e-01 2.5680426043760e-01 2.5589259882403e-01 2.5604668745058e-01 2.5588067610049e-01 2.5262710035918e-01 2.5034948328604e-01 2.4847535504759e-01 2.4704695906015e-01 2.4687518869312e-01 2.4677710482226e-01 2.4668054139016e-01 2.4631998216522e-01 8.5560905527535e-01 8.5186707283298e-01 8.4772899443093e-01 8.4167163355339e-01 8.3069298729439e-01 8.0487989672582e-01 7.8017776106250e-01 7.5033401234300e-01 7.2748711373430e-01 7.0552289411307e-01 6.8186659401749e-01 6.3913973479022e-01 6.1364722638836e-01 5.5846088262746e-01 5.1175334920062e-01 4.7009755272755e-01 4.1296498185245e-01 3.7343887638072e-01 3.3166147324824e-01 2.7302470266409e-01 2.4258849398385e-01 2.0091806474367e-01 1.7275003359831e-01 1.3914118230257e-01 1.1565002963944e-01 1.0003824201308e-01 8.9680805685630e-02 7.3327957028565e-02 6.7649151042560e-02 6.2018253043997e-02 6.6741364838596e-02 8.0737465651150e-02 9.8840364982792e-02 1.1188377082656e-01 1.2359701329364e-01 1.3811793856848e-01 1.5084910896835e-01 1.5345290295169e-01 1.5290673605935e-01 1.5521113741096e-01 1.5782987521806e-01 1.5681209745683e-01 1.5417101858043e-01 1.5411083389831e-01 1.5340359241462e-01 1.5036590394267e-01 1.4925472420584e-01 1.4870378791803e-01 1.4737878641124e-01 1.4657021644441e-01 1.4579833687039e-01 1.4234973456436e-01 1.4220369858654e-01 1.4224796645223e-01 1.4300519865150e-01 1.4466656101471e-01 1.4383801424231e-01 1.4326005559999e-01 1.4241966225001e-01 1.4187665960527e-01 1.4092913561147e-01 7.3407635681877e-01 7.3404874385916e-01 7.3403767715270e-01 7.3395752353394e-01 7.3393818336613e-01 7.3379768490710e-01 7.2926428410079e-01 7.2581419720518e-01 7.1351681793188e-01 6.8788267646837e-01 6.6152841023020e-01 6.3099452778306e-01 6.0462078990204e-01 5.3644126808333e-01 4.6232208460687e-01 4.1298662862856e-01 3.7234869239894e-01 3.0280039019444e-01 2.5063053187677e-01 2.0366406350868e-01 1.2362405996957e-01 7.5657088448891e-02 3.8790168871515e-02 -6.3936442707517e-04 -1.1674793842140e-02 -1.6905899094979e-02 -2.2014828150084e-02 -3.1310561010363e-02 -2.8188142251169e-02 -1.7879386743624e-02 -1.4286896770673e-02 -1.2089098748096e-02 -1.1711435326435e-02 -8.6109236443304e-03 -5.5353120488125e-03 -3.6577018802348e-03 -2.4261100831743e-03 -1.6425983867608e-03 -1.9108668072243e-03 -1.8887139111831e-03 -1.3354459672769e-03 -2.7854032963724e-04 -3.4649338698830e-04 -3.4693361543073e-04 -2.9542937637159e-04 -9.1509437441609e-05 3.3672816361727e-05 2.6561380261020e-04 3.3301810824685e-04 5.1101618365257e-04 8.4226843862868e-04 8.0941980525027e-04 6.5783260906385e-04 + -1.4438266249648e-01 -1.4440192092438e-01 -1.4440751789976e-01 -1.4441453101909e-01 -1.4443064025167e-01 -1.4443834737355e-01 -1.4449158994909e-01 -1.4556114656584e-01 -1.4788531537072e-01 -1.5286671166488e-01 -1.5864107579892e-01 -1.6312251002653e-01 -1.6815084307611e-01 -1.7601880781160e-01 -1.8488102647276e-01 -1.9409112348031e-01 -1.9948006683616e-01 -2.0393795074120e-01 -2.0576760709509e-01 -2.0829104965216e-01 -2.1241334902992e-01 -2.1498011780827e-01 -2.1517705167659e-01 -2.1207886764025e-01 -2.0720355754478e-01 -1.9502278128825e-01 -1.8732649868243e-01 -1.7877266051961e-01 -1.6450926270297e-01 -1.4111773273537e-01 -1.1997668616630e-01 -9.9807551785987e-02 -8.2786838836892e-02 -5.6953083349109e-02 -4.3409307121844e-02 -2.5486723261288e-02 -8.5238960795075e-04 1.8602746745155e-02 2.7118428186318e-02 3.3747581994020e-02 3.8893035169013e-02 4.0862213680304e-02 3.9256133021702e-02 3.7600600230660e-02 3.7274273365382e-02 3.7312300299964e-02 3.7234319192575e-02 3.7006342372876e-02 3.6284303370643e-02 3.5816457716794e-02 3.5217730916211e-02 3.2695899204179e-02 3.1836272248945e-02 2.8587233720666e-02 2.4839000191774e-02 2.2466007997066e-02 2.0845033364113e-02 1.6857783468506e-02 1.6241136144457e-02 1.5736786330118e-02 1.4114802599710e-02 1.2650796607243e-02 1.0364097910584e-02 8.3281955131372e-03 6.8356509285081e-03 6.4537280084314e-03 6.3997919100218e-03 -3.2987348976824e-01 -3.2983719708046e-01 -3.2982957748122e-01 -3.2977541775445e-01 -3.2980705004844e-01 -3.2993753457313e-01 -3.3008747958353e-01 -3.3008722854577e-01 -3.3008570574450e-01 -3.2999868070388e-01 -3.2929866080667e-01 -3.2655803805083e-01 -3.2578419020302e-01 -3.2423076519784e-01 -3.1792849247370e-01 -3.1325553248415e-01 -3.0275487428353e-01 -2.9414856841867e-01 -2.8009265495082e-01 -2.6297213809477e-01 -2.4903066705091e-01 -2.2396053578473e-01 -2.0126345528671e-01 -1.8772596759514e-01 -1.6777488050159e-01 -1.5163248905605e-01 -1.2846783613044e-01 -1.1532957134572e-01 -9.5568853405903e-02 -8.0003465846657e-02 -5.5324883926855e-02 -4.0230550916290e-02 -2.9542942554069e-02 -1.7826285528947e-02 -8.4719248944159e-03 5.2481205301494e-03 1.7340646975018e-02 3.8146667295108e-02 5.2372757204261e-02 6.6243805069762e-02 8.3583510774033e-02 1.0369066512878e-01 1.1726089309084e-01 1.3165162417043e-01 1.3696510423582e-01 1.3686625980499e-01 1.3718308023335e-01 1.3765684375638e-01 1.3774729950366e-01 1.3805888025641e-01 1.3771097258133e-01 1.3572549778374e-01 1.3476316323198e-01 1.3329908798841e-01 1.3318335218878e-01 1.3297242500094e-01 1.3285495704978e-01 1.3262271664653e-01 1.3203005442721e-01 1.3179981288854e-01 1.3173581600627e-01 1.3159464541416e-01 1.3132900255624e-01 1.3129867289651e-01 1.3126474779345e-01 1.3119202125013e-01 1.3116220735795e-01 1.3112923167651e-01 1.3100967671055e-01 1.3093173961909e-01 1.3069675019129e-01 1.2982979954691e-01 1.2692376070434e-01 1.2650696694418e-01 1.2653854985543e-01 1.2656198224544e-01 4.7719203400552e-02 4.7717944457612e-02 4.7714118255786e-02 4.7692920334998e-02 4.7689094157961e-02 4.7686944434981e-02 4.7654558877760e-02 4.7653480591939e-02 4.7648256691842e-02 4.7623417054128e-02 4.7672829657951e-02 4.7864300855162e-02 4.7501697681220e-02 4.7064106345661e-02 4.7049913949122e-02 4.7141360750412e-02 4.4773281578970e-02 4.1646723610843e-02 3.7402101619199e-02 3.2779664459239e-02 2.6945530356309e-02 2.2425020738045e-02 1.5644142001213e-02 7.7951967075469e-03 -1.8926027820595e-03 -7.5667287956467e-03 -1.3760467210697e-02 -1.9970698006856e-02 -2.9910426696500e-02 -3.5023550457557e-02 -3.9158638616967e-02 -4.0072107794892e-02 -3.4564864049591e-02 -2.7379550518915e-02 -1.6237870681022e-02 -7.5232663560229e-03 -3.2453866696184e-03 2.2413642176097e-04 1.7757559100344e-03 3.9370175942178e-03 4.0116797238706e-03 3.1813336756713e-03 2.7656692263053e-03 2.3511868648425e-03 2.3349497559344e-03 2.3250274495052e-03 2.1277945959982e-03 1.6806354315053e-03 1.6567599821291e-03 1.5341919984309e-03 1.2263567064281e-03 1.0895580729733e-03 6.0393401765756e-04 2.7624015394099e-05 -3.8894850526516e-04 -8.3803892484998e-04 -9.5435872857977e-04 -9.8870599538734e-04 -1.0396466468849e-03 -1.1533978691091e-03 -1.1629760020303e-03 -1.1632810215988e-03 -1.1341702991612e-03 -1.0711343756263e-03 -1.0207715386285e-03 -8.6358226362300e-04 -9.4715544315987e-04 -9.4836779559984e-04 -9.4916097431522e-04 -9.4860777831041e-04 -1.9920192712267e-01 -1.9920783715839e-01 -1.9921964996333e-01 -1.9922260314586e-01 -1.9922969112337e-01 -1.9923411910446e-01 -1.9923981095747e-01 -1.9924290569731e-01 -1.9924316107639e-01 -1.9927626190647e-01 -1.9944125041678e-01 -2.0034729964017e-01 -2.0220454811404e-01 -2.0467053608777e-01 -2.0765593695201e-01 -2.1072220807444e-01 -2.1666380703941e-01 -2.1993185377102e-01 -2.2269887199174e-01 -2.2584737998652e-01 -2.2877417505881e-01 -2.3159453593810e-01 -2.3271634543816e-01 -2.3336204046223e-01 -2.3495567098778e-01 -2.3460461110502e-01 -2.3300660022066e-01 -2.3086097146760e-01 -2.2452007869389e-01 -2.1632803932414e-01 -2.1212761555518e-01 -2.0821594405558e-01 -1.9842915540397e-01 -1.8800978226684e-01 -1.7497379513894e-01 -1.4338302944870e-01 -1.0946779946685e-01 -9.2043168048623e-02 -7.7434150417818e-02 -5.9106004145327e-02 -4.3178704886163e-02 -2.7091985013342e-02 -2.3220062734233e-02 -2.0120509557430e-02 -1.2209416267451e-02 -9.0805428754895e-03 -5.4878650088482e-03 -1.8258976091526e-03 -1.3784701037770e-03 -1.5163907538505e-03 -1.5536263607165e-03 -2.1960125804079e-03 -3.3450337364145e-03 -5.3584022780620e-03 -6.0251218113306e-03 -6.9207922405631e-03 -9.7654417464660e-03 -1.1817830023331e-02 -1.2933945422870e-02 -1.4910433389699e-02 -1.5831698099264e-02 -1.6183420652685e-02 -1.6606390624008e-02 -1.7301136425546e-02 -1.7936607936139e-02 -1.8640171594460e-02 -1.8659309002275e-02 -1.8693713305991e-02 -1.8698715592715e-02 -1.8854670213113e-02 -1.8864535213688e-02 -1.0669860258868e-01 -1.0670477251231e-01 -1.0671975438555e-01 -1.0673222655405e-01 -1.0673499701395e-01 -1.0675023615504e-01 -1.0680426731007e-01 -1.0678660451631e-01 -1.0676324519139e-01 -1.0682982850873e-01 -1.0732737890558e-01 -1.0883263195253e-01 -1.1136956111613e-01 -1.1441178676998e-01 -1.2075836606219e-01 -1.2375930228629e-01 -1.2621399899488e-01 -1.3309702834929e-01 -1.4008876023158e-01 -1.4587469776392e-01 -1.5255590802722e-01 -1.5653975037962e-01 -1.5627341881658e-01 -1.5502949091003e-01 -1.5205918152141e-01 -1.4412258155385e-01 -1.3902699334391e-01 -1.3513266866336e-01 -1.2339038702902e-01 -1.1204803391960e-01 -9.6124160096179e-02 -8.0073432968925e-02 -6.8187308280100e-02 -5.7178115100205e-02 -3.7551210440702e-02 -2.7747181251514e-02 -1.9023516232809e-02 -7.5001126503974e-03 3.7029323473094e-03 6.3230591458999e-03 8.8189048675722e-03 1.2199190017369e-02 1.2194487262885e-02 1.2162171377594e-02 1.2091037760855e-02 1.2029619090917e-02 1.1946412687577e-02 1.1636707278362e-02 1.1490312741783e-02 1.1280768753528e-02 1.0201149412565e-02 9.5079677944717e-03 8.8282215818441e-03 6.8849213115140e-03 6.3074490283652e-03 5.8809028276506e-03 5.5780051483803e-03 5.3458457723172e-03 5.2186946444313e-03 5.0489870430074e-03 4.3676208386123e-03 3.6692894506597e-03 3.5071375515535e-03 -2.1376069396397e-01 -2.1375419110674e-01 -2.1375732888817e-01 -2.1370820853774e-01 -2.1369943811236e-01 -2.1372568743134e-01 -2.1385750282273e-01 -2.1385841448659e-01 -2.1378709449410e-01 -2.1309542657211e-01 -2.1325393740392e-01 -2.1526577359563e-01 -2.1791453492787e-01 -2.2086234891519e-01 -2.2412800904317e-01 -2.2941563645953e-01 -2.3165664366074e-01 -2.3362938649665e-01 -2.3777051603396e-01 -2.3787763636347e-01 -2.3770529745777e-01 -2.3541006642410e-01 -2.2822389648577e-01 -2.2149961705350e-01 -2.1838333558133e-01 -2.1038254721639e-01 -2.0114060912315e-01 -1.9354956020580e-01 -1.7536330746042e-01 -1.6003943086146e-01 -1.3320521629293e-01 -1.2795707752446e-01 -1.0401160577097e-01 -9.0322480717003e-02 -7.2677285577047e-02 -5.4480173882063e-02 -2.8821690705188e-02 -1.5763187506635e-02 -4.6407224901927e-03 5.4257443201764e-03 1.3491410392300e-02 1.9352434516683e-02 2.5145675227650e-02 2.8970517180517e-02 3.1211187007837e-02 3.1115881729217e-02 2.9930591717349e-02 2.7906812663785e-02 2.5296224281618e-02 2.3239412705551e-02 2.0514621952102e-02 1.9719887898433e-02 1.9201558386084e-02 1.8850038134771e-02 1.7839680270465e-02 1.6642928416223e-02 1.6240610992914e-02 1.6199064871632e-02 1.6136931807447e-02 1.5903515042401e-02 1.5734503291189e-02 1.5727861551403e-02 1.5425995416677e-02 1.4779331049571e-02 1.4298099164213e-02 1.3890842758910e-02 1.3890507653951e-02 1.3845403496319e-02 1.3751850138213e-02 1.3742425109218e-02 -2.1496011206318e-01 -2.1524107441372e-01 -2.1557785835290e-01 -2.1609597276921e-01 -2.1708804481116e-01 -2.1945244297088e-01 -2.2172377888508e-01 -2.2431878527969e-01 -2.2613834841341e-01 -2.2767229071859e-01 -2.2931262102154e-01 -2.3093309772713e-01 -2.3129787581066e-01 -2.3168683726476e-01 -2.3048732660606e-01 -2.2744131007891e-01 -2.2071552690882e-01 -2.1608868273400e-01 -2.1243289070532e-01 -2.0384685878849e-01 -1.9630161839723e-01 -1.7693892009567e-01 -1.5504306922767e-01 -1.2940177185949e-01 -1.1352647064624e-01 -1.0298543475909e-01 -9.3361395506662e-02 -7.4688759203715e-02 -6.0230850868191e-02 -3.1661201555613e-02 -9.8520281809389e-03 1.0151956465806e-02 3.6585337629916e-02 5.0224594160355e-02 6.4281151079992e-02 7.8783258862325e-02 9.3246734898401e-02 9.6262078315960e-02 9.6475526158236e-02 9.7798239390483e-02 9.7637257996821e-02 9.6504842814884e-02 9.3292530788253e-02 9.1954267418455e-02 9.0840591094989e-02 8.8663263103604e-02 8.7572826252889e-02 8.5839734627495e-02 8.5416254849984e-02 8.4929298872547e-02 8.3859583482424e-02 8.0782330897895e-02 8.0351690964458e-02 8.0123840294106e-02 7.9725750202119e-02 7.9497981894226e-02 7.9517298094318e-02 7.9543138941941e-02 7.9407320774726e-02 7.8295403424580e-02 7.8254210595053e-02 2.5654872027521e-02 2.5643137109128e-02 2.5638434002848e-02 2.5604370614034e-02 2.5596151535758e-02 2.5575970030572e-02 2.4947042218675e-02 2.4435530641316e-02 2.2436148894467e-02 1.8014544304555e-02 1.3259895078389e-02 7.8446553596886e-03 3.3900546255921e-03 -7.8059123406430e-03 -1.9517897169325e-02 -2.6196227828952e-02 -3.1634818470642e-02 -4.1848487717897e-02 -5.0526608179471e-02 -5.8074796838071e-02 -6.2028150024013e-02 -6.0340633117625e-02 -5.9682672261196e-02 -5.7305302760614e-02 -5.0621271181354e-02 -3.8266586579654e-02 -3.3357135594811e-02 -2.9043961351720e-02 -9.6659863603620e-03 -1.3241082614392e-03 1.2588901972685e-03 2.9627791620222e-03 2.9439947733981e-03 2.9233740050272e-03 2.9136546637570e-03 3.2527006723194e-03 4.7404304040021e-03 4.8235537814166e-03 4.7433318911044e-03 4.7213371459896e-03 4.7218723816079e-03 4.7138509872618e-03 4.7087311347903e-03 4.7023056782106e-03 4.6981331375174e-03 4.6964937441459e-03 4.6855925828339e-03 4.6678480817071e-03 4.6674665878442e-03 4.6669276416628e-03 4.6579164854252e-03 4.6578678688949e-03 4.6458454937967e-03 3.8287309896902e-01 3.8290102996869e-01 3.8291117045495e-01 3.8292387653244e-01 3.8295306193902e-01 3.8296702476956e-01 3.8304575355481e-01 3.8459582591242e-01 3.8794945485030e-01 3.9505612834391e-01 4.0314463324153e-01 4.0912411533166e-01 4.1590943788880e-01 4.2733859997623e-01 4.4049858086435e-01 4.5440109003251e-01 4.6346066611600e-01 4.7388480460583e-01 4.8202722055949e-01 4.9089619569568e-01 5.0323307047239e-01 5.1662627117911e-01 5.2776439241359e-01 5.3733514245569e-01 5.4438038768189e-01 5.5320628756105e-01 5.5847511700448e-01 5.6304153754302e-01 5.6679336762991e-01 5.6559449456310e-01 5.6195955193060e-01 5.5542693387551e-01 5.4578581762057e-01 5.3100540445460e-01 5.2213696762673e-01 5.0934895168602e-01 4.8698404400336e-01 4.6865474626574e-01 4.6045662958672e-01 4.4901823061828e-01 4.3551272541519e-01 4.1843598138138e-01 4.1207891651242e-01 4.1050546724093e-01 4.0637500010388e-01 4.0771833068386e-01 4.0478702767785e-01 4.0408795891956e-01 4.0524470540553e-01 4.0714044980838e-01 4.0949146398670e-01 4.1132776572531e-01 4.1123122039312e-01 4.1194567332914e-01 4.1119464841140e-01 4.1121020043841e-01 4.1176176163811e-01 4.1211771420784e-01 4.1222963528854e-01 4.1198025982641e-01 4.1121035480034e-01 4.1090028946302e-01 4.1096593914726e-01 4.1125884412757e-01 4.1154149701179e-01 4.1153407852916e-01 4.1155839116381e-01 7.9820075637281e-01 7.9827902922672e-01 7.9826301706239e-01 7.9838074125883e-01 7.9829526895708e-01 7.9798401182416e-01 7.9759481708721e-01 7.9759679106668e-01 7.9759065875738e-01 7.9777207670760e-01 7.9922618391705e-01 8.0472625286219e-01 8.0346880809078e-01 7.9969140881866e-01 7.9721282949245e-01 7.9452385588367e-01 7.9382080002055e-01 8.0033932128199e-01 8.2011242445577e-01 8.4741712827008e-01 8.6834692245203e-01 9.0297643375749e-01 9.3239765677608e-01 9.5042328391905e-01 9.7928255387069e-01 1.0043954964113e+00 1.0404593227613e+00 1.0602736357818e+00 1.0928353981570e+00 1.1168820457312e+00 1.1551429743148e+00 1.1796620586561e+00 1.1981614756254e+00 1.2210753295362e+00 1.2379966180632e+00 1.2575328354732e+00 1.2723582403955e+00 1.2962649065479e+00 1.3115129382463e+00 1.3239962108376e+00 1.3335396725875e+00 1.3382399484481e+00 1.3387961668925e+00 1.3361397457527e+00 1.3351146306847e+00 1.3369725834862e+00 1.3344732054201e+00 1.3325821550946e+00 1.3321179160824e+00 1.3317678163703e+00 1.3335265202122e+00 1.3371038825053e+00 1.3392523727542e+00 1.3419972526487e+00 1.3423458359324e+00 1.3426555982420e+00 1.3434950829499e+00 1.3437996296801e+00 1.3443446411609e+00 1.3448595349929e+00 1.3449637763669e+00 1.3450711976861e+00 1.3452664027827e+00 1.3452998193909e+00 1.3453395555826e+00 1.3452552249603e+00 1.3449165704826e+00 1.3442284735814e+00 1.3442229106890e+00 1.3442039050356e+00 1.3443930446644e+00 1.3453081156784e+00 1.3476068510560e+00 1.3478869323122e+00 1.3478113442299e+00 1.3477344831523e+00 1.9370872484190e-01 1.9370937282887e-01 1.9371134218853e-01 1.9372460289296e-01 1.9372657221216e-01 1.9372877697769e-01 1.9373369441612e-01 1.9373723246543e-01 1.9374696828960e-01 1.9376022175092e-01 1.9376535965791e-01 1.9375137280037e-01 1.9383878828109e-01 1.9397237873129e-01 1.9411289962194e-01 1.9419238155653e-01 1.9435443359538e-01 1.9472610363996e-01 1.9511914850378e-01 1.9211714952899e-01 1.8835675968028e-01 1.8691845386756e-01 1.8536769295301e-01 1.8256861791610e-01 1.6866852766710e-01 1.5078504314711e-01 1.2959216817805e-01 1.0932114313898e-01 7.8939660189257e-02 6.2217528655173e-02 4.4702939676051e-02 2.3085207616055e-02 1.2048434413665e-02 7.3975973045848e-03 3.5320151953772e-03 -3.1244224594159e-05 -1.9015932269587e-03 -3.4360214106236e-03 -4.2179585705322e-03 -5.5076831969325e-03 -5.8847568354966e-03 -5.7587464291262e-03 -5.6961902806202e-03 -5.6331531451881e-03 -5.6371574549386e-03 -5.6534081353066e-03 -5.8026086832981e-03 -5.7184273632674e-03 -5.7123356372371e-03 -5.6886527501907e-03 -5.6292140357040e-03 -5.5978037009883e-03 -5.5053762300670e-03 -5.3971299083239e-03 -5.2825579758940e-03 -5.1585210141566e-03 -5.1406937865050e-03 -5.2728912997056e-03 -5.2694898748660e-03 -5.2505987227757e-03 -5.2800521964659e-03 -5.3359013610892e-03 -5.6026944982749e-03 -5.8936229927886e-03 -5.9375450437918e-03 -9.6348170603979e-03 -1.1042348886509e-02 -1.1074045826172e-02 -1.1222632098007e-02 -1.1248322688258e-02 5.2237496563098e-01 5.2238503915785e-01 5.2240517400662e-01 5.2241020772457e-01 5.2242317451588e-01 5.2243072201418e-01 5.2244754771939e-01 5.2246417638025e-01 5.2246554861510e-01 5.2256783689335e-01 5.2303884839283e-01 5.2551712339197e-01 5.3032625574395e-01 5.3662290541059e-01 5.4410424540129e-01 5.5173289060022e-01 5.6633501592971e-01 5.7424570074820e-01 5.8100040575039e-01 5.8903007067989e-01 5.9699673274376e-01 6.0715497731004e-01 6.1399933080618e-01 6.2162397407476e-01 6.3883434374243e-01 6.4909210736853e-01 6.5841656959157e-01 6.6611312704530e-01 6.7977171529451e-01 6.9498236534075e-01 7.0495364146289e-01 7.1397381397384e-01 7.2645692604874e-01 7.3095477550814e-01 7.3479746829124e-01 7.4361394100939e-01 7.4893984608665e-01 7.5081814531388e-01 7.4590430159365e-01 7.3464144145875e-01 7.2001788442842e-01 7.0510347728900e-01 6.9909102478699e-01 6.9318290888696e-01 6.8590806164394e-01 6.8659969578656e-01 6.8482374662481e-01 6.8126122578544e-01 6.8099697796923e-01 6.8115008266086e-01 6.8083992781111e-01 6.8153173406515e-01 6.8377454739548e-01 6.8556006945048e-01 6.8600132130805e-01 6.8672205721749e-01 6.9008127128946e-01 6.9169922862811e-01 6.9217030740460e-01 6.9251245277961e-01 6.9308326638629e-01 6.9343449387049e-01 6.9375544728784e-01 6.9426084953134e-01 6.9436886972381e-01 6.9356589098643e-01 6.9345715693791e-01 6.9342502491264e-01 6.9333749959337e-01 6.9334935302855e-01 6.9324574880011e-01 2.2334399332085e-01 2.2335133159591e-01 2.2337701140404e-01 2.2339907180897e-01 2.2340397215156e-01 2.2343092711116e-01 2.2352650036561e-01 2.2351042925911e-01 2.2348356463934e-01 2.2356176949832e-01 2.2414443653588e-01 2.2589834816070e-01 2.2880225092866e-01 2.3222374974880e-01 2.3917738452723e-01 2.4242437045640e-01 2.4510095518045e-01 2.5275605823489e-01 2.6065683034666e-01 2.6732464263695e-01 2.7529891749513e-01 2.8066361166138e-01 2.8393612752233e-01 2.8512148334058e-01 2.8549654806742e-01 2.8750643913151e-01 2.9104495302488e-01 2.9400148095573e-01 2.9461923598154e-01 2.9506896742987e-01 2.9247606156802e-01 2.8530975127721e-01 2.8222918052638e-01 2.7943449749228e-01 2.7153579111044e-01 2.6491853439913e-01 2.5922105957291e-01 2.5386954139006e-01 2.4658097860167e-01 2.4464651832699e-01 2.4030928427990e-01 2.3665559075128e-01 2.3570014093258e-01 2.3505684764013e-01 2.3438033042618e-01 2.3435285072340e-01 2.3450847610974e-01 2.3470459339142e-01 2.3464808700083e-01 2.3447069185134e-01 2.3431678753339e-01 2.3417062188766e-01 2.3356033179620e-01 2.3167639960349e-01 2.3173603092081e-01 2.3206092441644e-01 2.3209656033497e-01 2.3210081590744e-01 2.3199870140949e-01 2.3174005482126e-01 2.3091210105140e-01 2.3044477660918e-01 2.3014595865698e-01 6.3770597408946e-01 6.3764500190135e-01 6.3765265487552e-01 6.3722572005684e-01 6.3715708122179e-01 6.3731343827110e-01 6.3815849464856e-01 6.3816067114896e-01 6.3761969671257e-01 6.3195448625390e-01 6.3308660175150e-01 6.4221393318174e-01 6.5693906928718e-01 6.7201125121122e-01 6.8959763434558e-01 7.1499064847481e-01 7.2659073349908e-01 7.3845268325927e-01 7.7013259080873e-01 7.8223692216377e-01 7.9802483627322e-01 8.1403033817266e-01 8.3705819048950e-01 8.5494263245867e-01 8.6328465847642e-01 8.9182245891670e-01 9.1915278186680e-01 9.3790062271290e-01 9.7512951204751e-01 1.0050834085369e+00 1.0439690061532e+00 1.0488535689672e+00 1.0625614332318e+00 1.0602166611000e+00 1.0538318530170e+00 1.0460802554954e+00 1.0328915409507e+00 1.0226441236077e+00 1.0093262376579e+00 9.8573341871347e-01 9.7031057572593e-01 9.6346135671006e-01 9.5322015165098e-01 9.4181566892395e-01 9.3692906680553e-01 9.3971224432296e-01 9.4036980684838e-01 9.4346015004026e-01 9.4824927572867e-01 9.4929332152716e-01 9.5170999940445e-01 9.5302499133905e-01 9.5439234314549e-01 9.5556634482175e-01 9.5804537327498e-01 9.5916716552011e-01 9.6027435594948e-01 9.6054037107734e-01 9.6088454155547e-01 9.6154080828567e-01 9.6164660113007e-01 9.6173426744277e-01 9.6357044716059e-01 9.6514907638254e-01 9.6644940585863e-01 9.6740047815819e-01 9.6747813934839e-01 9.6753697523566e-01 9.6763162704977e-01 9.6781385540479e-01 4.4305062855948e-01 4.4479193192887e-01 4.4675986349541e-01 4.4967961313310e-01 4.5504175936736e-01 4.6757446903354e-01 4.7942552043335e-01 4.9329367615760e-01 5.0345175478436e-01 5.1270233822405e-01 5.2258822127052e-01 5.3812579616486e-01 5.4650849531196e-01 5.6407470768661e-01 5.7706344049369e-01 5.8886208313079e-01 6.0707257955546e-01 6.2169720363490e-01 6.3615402182437e-01 6.6038054303113e-01 6.7494102747044e-01 6.9950803756004e-01 7.2011022434498e-01 7.4150526782164e-01 7.5403171009663e-01 7.6240148083711e-01 7.6905137434041e-01 7.7780137301975e-01 7.8143729186579e-01 7.8398469830479e-01 7.7704286168035e-01 7.6411475492845e-01 7.4580006110066e-01 7.3306830870170e-01 7.1988164467830e-01 7.0394306374112e-01 6.8741764136171e-01 6.8402955071137e-01 6.8417251784357e-01 6.8237583690740e-01 6.8133755153879e-01 6.8184323658036e-01 6.8363688014391e-01 6.8433739828702e-01 6.8480180494863e-01 6.8699839501912e-01 6.8806288934670e-01 6.8920107572770e-01 6.9000114049496e-01 6.9047379340339e-01 6.9090978158024e-01 6.9193681646801e-01 6.9208759069938e-01 6.9218011232779e-01 6.9201162177350e-01 6.9126059166550e-01 6.9162407757368e-01 6.9187408749568e-01 6.9229806517489e-01 6.9309722582857e-01 6.9352034418751e-01 1.9667992416260e-01 1.9668848043984e-01 1.9669190954142e-01 1.9671674439891e-01 1.9672273641857e-01 1.9672924465141e-01 1.9691755700075e-01 1.9709937597020e-01 1.9794810266161e-01 1.9991581746588e-01 2.0204218026790e-01 2.0420564223751e-01 2.0559599369130e-01 2.0822432606702e-01 2.1001905374003e-01 2.1015269512318e-01 2.1020815998444e-01 2.0970400793906e-01 2.0526646914429e-01 1.9716335171558e-01 1.6942651722832e-01 1.4915630373976e-01 1.3809824255259e-01 1.2650812789906e-01 1.1676046560949e-01 1.0685740927305e-01 1.0493687723446e-01 1.0276073179538e-01 8.7506908244044e-02 8.3809467818016e-02 8.2604235978629e-02 8.1775081828928e-02 7.9215739634201e-02 7.2992041560385e-02 6.9114900070019e-02 6.8615437989537e-02 6.7773212240805e-02 6.7717206196926e-02 6.7737282752168e-02 6.7740545451191e-02 6.7735419940416e-02 6.7730701326558e-02 6.7735234497004e-02 6.7740236493767e-02 6.7746280997945e-02 6.7747240502266e-02 6.7752311216019e-02 6.7779851373864e-02 6.7779599105134e-02 6.7777211962384e-02 6.7786297232764e-02 6.7787281762361e-02 6.7803323307459e-02 + -6.7226139672271e-01 -6.7221850009078e-01 -6.7220067093088e-01 -6.7217832968741e-01 -6.7212700750383e-01 -6.7210245150026e-01 -6.7198000476604e-01 -6.6958336801178e-01 -6.6449074454145e-01 -6.5387031830463e-01 -6.4061097711588e-01 -6.2670775701236e-01 -6.0713025566269e-01 -5.7726226016225e-01 -5.4971254340298e-01 -5.1951407011313e-01 -4.9472883193163e-01 -4.5860073506718e-01 -4.2682090659611e-01 -3.9705189910480e-01 -3.5953512411955e-01 -3.1553472293832e-01 -2.7682091841659e-01 -2.3987622088315e-01 -2.0962840207863e-01 -1.6558920837758e-01 -1.4126016681319e-01 -1.1884883008556e-01 -9.3358612463550e-02 -7.2760071435385e-02 -6.0945813583081e-02 -5.7555971529729e-02 -6.3457795485235e-02 -6.9796465682351e-02 -7.4981086994051e-02 -8.1652153540882e-02 -9.6287838847474e-02 -1.0595575572998e-01 -1.0691887313393e-01 -1.1011295372596e-01 -1.1517417153666e-01 -1.1548125503176e-01 -1.1922406142315e-01 -1.1911346834556e-01 -1.2511951659723e-01 -1.2346768963295e-01 -1.2870329285837e-01 -1.2999877505736e-01 -1.2795032859982e-01 -1.2591185717005e-01 -1.2193343528639e-01 -1.2083050240077e-01 -1.1954048639063e-01 -1.1414441951576e-01 -1.1344721196605e-01 -1.1292884058794e-01 -1.1229708658962e-01 -1.1027985885641e-01 -1.1016029220306e-01 -1.1019621508545e-01 -1.0956555126824e-01 -1.0858622105785e-01 -1.0754809087590e-01 -1.0668392769872e-01 -1.0584565881695e-01 -1.0557429890502e-01 -1.0551995143526e-01 -5.9069453577703e-01 -5.9059160731115e-01 -5.9059677769101e-01 -5.9044356518515e-01 -5.9054681109718e-01 -5.9093735254711e-01 -5.9141366972698e-01 -5.9141154002415e-01 -5.9141506028552e-01 -5.9117627525730e-01 -5.8925368895791e-01 -5.8180810937657e-01 -5.8190399320523e-01 -5.8318416595721e-01 -5.7823618332000e-01 -5.7536914398978e-01 -5.6494887298739e-01 -5.5082839051156e-01 -5.1956466009519e-01 -4.7638438718279e-01 -4.4058034119448e-01 -3.8520899936371e-01 -3.5219655444948e-01 -3.3802344296145e-01 -3.1637540425374e-01 -2.9476658750651e-01 -2.5962522083970e-01 -2.3844470200683e-01 -2.1147438780932e-01 -1.9899248028888e-01 -1.8648736596720e-01 -1.7934729912245e-01 -1.7100942283201e-01 -1.6144482542583e-01 -1.5605078083245e-01 -1.4969595310926e-01 -1.4585007740100e-01 -1.4485336783715e-01 -1.4293389188866e-01 -1.3940724468011e-01 -1.3684754926752e-01 -1.4006071343491e-01 -1.4571211705918e-01 -1.5864829087093e-01 -1.6325000597839e-01 -1.5777990948571e-01 -1.6094293570595e-01 -1.6312954860727e-01 -1.6388649303130e-01 -1.6361022310749e-01 -1.5880777557662e-01 -1.5144598772454e-01 -1.4682668200022e-01 -1.4116604938677e-01 -1.4035206769394e-01 -1.3975385281807e-01 -1.3761883806477e-01 -1.3714013126851e-01 -1.3645212694437e-01 -1.3533631917209e-01 -1.3513283827396e-01 -1.3502815017750e-01 -1.3485270492889e-01 -1.3480440116780e-01 -1.3473996026293e-01 -1.3508445127427e-01 -1.3599599578527e-01 -1.3766821271009e-01 -1.3780639257890e-01 -1.3793300647634e-01 -1.3772976405737e-01 -1.3639242545115e-01 -1.3333514380434e-01 -1.3284188298171e-01 -1.3302142338657e-01 -1.3321266986397e-01 -6.2034701383281e-01 -6.2034489632750e-01 -6.2033846073701e-01 -6.2031463418290e-01 -6.2030819830973e-01 -6.2029850696571e-01 -6.2018490896267e-01 -6.2018024359949e-01 -6.2020691852863e-01 -6.2017374308138e-01 -6.2041053066410e-01 -6.2115781494288e-01 -6.1997325745962e-01 -6.1863795762984e-01 -6.1909561799430e-01 -6.1984253209261e-01 -6.1052121476329e-01 -5.9854921172182e-01 -5.8209059791952e-01 -5.5256744303172e-01 -5.1173453311195e-01 -4.8430069307396e-01 -4.4668046542023e-01 -4.1270386851159e-01 -3.6963300706535e-01 -3.3435872363631e-01 -2.9459930906650e-01 -2.5830628130139e-01 -2.0138502571783e-01 -1.6645431390063e-01 -1.2630277456787e-01 -6.9250928838069e-02 -3.4169974529711e-02 -9.4335465961313e-03 1.1996825322053e-02 1.8577212408023e-02 1.7059628631056e-02 1.5193995515642e-02 9.0205421854281e-03 -3.8031625827923e-05 -9.8373873272795e-04 -7.5608378201402e-04 -9.5552210255986e-04 -6.6614233574130e-04 -1.0177421291626e-03 -2.0729325924958e-03 -7.1346808897932e-03 -5.8440310908549e-03 -5.7028782192008e-03 -5.4337515690269e-03 -4.9032758640261e-03 -4.7630515289802e-03 -4.0768221258158e-03 -3.0915941639063e-03 -2.3035263322054e-03 -1.2267972960170e-03 -1.0379262897485e-03 -1.9903144299955e-03 -1.9819708849019e-03 -1.8192745184940e-03 -1.8314506407914e-03 -2.2418883042149e-03 -4.9515632158372e-03 -5.4066012472873e-03 -4.8835102210311e-03 -3.5347287994346e-03 -2.7656757594749e-03 -2.2031567221067e-03 -5.4038399075049e-05 1.0571754839212e-04 -6.3720121518688e-01 -6.3720173222299e-01 -6.3720276537979e-01 -6.3720302360910e-01 -6.3719964132548e-01 -6.3720002838793e-01 -6.3717437559157e-01 -6.3714624372473e-01 -6.3714392212434e-01 -6.3698686522869e-01 -6.3627431167330e-01 -6.3257344330291e-01 -6.2558537472104e-01 -6.1633273959875e-01 -6.0521550660044e-01 -5.9365018484356e-01 -5.7088856449010e-01 -5.5830279382780e-01 -5.4713523840329e-01 -5.3215670122808e-01 -5.1642136555472e-01 -4.9273946715322e-01 -4.7469581385071e-01 -4.5264652865242e-01 -4.0475100748049e-01 -3.7413163681827e-01 -3.4466189168369e-01 -3.1951316749117e-01 -2.7037718492642e-01 -2.1627817014702e-01 -1.8311879619541e-01 -1.5352880203758e-01 -1.1046001404485e-01 -9.8005443217015e-02 -9.4175226803992e-02 -8.8415972697245e-02 -8.6745602853427e-02 -8.7542907781583e-02 -9.7010268547877e-02 -1.0283441502111e-01 -1.1843876314246e-01 -1.3007356371656e-01 -1.3649740104066e-01 -1.4348130784316e-01 -1.5090805894511e-01 -1.5114874044477e-01 -1.5491537416052e-01 -1.6056003704629e-01 -1.6035259977639e-01 -1.5995102657466e-01 -1.6042925380772e-01 -1.5965074176187e-01 -1.5654256715820e-01 -1.5513814632810e-01 -1.5493226085794e-01 -1.5443450287643e-01 -1.5090332953385e-01 -1.4964752654811e-01 -1.4897008708729e-01 -1.4774879762379e-01 -1.4732541096169e-01 -1.4702839888865e-01 -1.4680603590459e-01 -1.4645687016401e-01 -1.4652261665042e-01 -1.4663656601121e-01 -1.4685069411688e-01 -1.4696876368276e-01 -1.4714367924907e-01 -1.4725347463637e-01 -1.4746011691046e-01 -6.4356554867445e-01 -6.4354603318224e-01 -6.4355223634779e-01 -6.4355980322481e-01 -6.4356148400570e-01 -6.4357072888917e-01 -6.4360350178926e-01 -6.4370470687261e-01 -6.4379780465592e-01 -6.4356810687406e-01 -6.4190643018534e-01 -6.3684281247946e-01 -6.2777718128760e-01 -6.1673727396528e-01 -5.9116239884150e-01 -5.7763196120487e-01 -5.6618143529518e-01 -5.3374068899037e-01 -4.9942611622112e-01 -4.7113614866920e-01 -4.3190576093519e-01 -3.9668779992120e-01 -3.4717068994526e-01 -3.2209068268446e-01 -2.9688460000325e-01 -2.3637659025091e-01 -1.8999664538894e-01 -1.5615115886776e-01 -1.1675343433141e-01 -8.4326518554077e-02 -4.6465403647308e-02 -2.5845704844148e-02 -1.5749710042984e-02 -6.6592902835587e-03 -1.6561823714322e-03 -7.8976165590907e-03 -1.1500638006027e-02 -9.3386228120581e-03 -1.4117450710513e-02 -1.5717919004394e-02 -2.2822646111030e-02 -2.8587105373441e-02 -3.1805808727210e-02 -3.4231032643013e-02 -3.6978741307753e-02 -3.7148441431171e-02 -3.6746665157649e-02 -3.6558671670192e-02 -3.6581976820821e-02 -3.6593489114104e-02 -3.6116719790865e-02 -3.5538850904587e-02 -3.5073917407245e-02 -3.4233650932462e-02 -3.3846968337733e-02 -3.3429166267302e-02 -3.3465537788782e-02 -3.3436955039588e-02 -3.3435417555610e-02 -3.3337004611918e-02 -3.3062508479280e-02 -3.2693560700417e-02 -3.2698508245475e-02 -6.8311063906938e-01 -6.8317591990779e-01 -6.8317116179339e-01 -6.8362273163003e-01 -6.8369399549665e-01 -6.8354094503513e-01 -6.8269909622977e-01 -6.8269759891630e-01 -6.8325700198384e-01 -6.8914824590298e-01 -6.8774038179432e-01 -6.7920377868822e-01 -6.6454470580367e-01 -6.4922536266073e-01 -6.3029002639183e-01 -6.0167180056566e-01 -5.8721547004422e-01 -5.7145049230099e-01 -5.1971371230036e-01 -4.9025898955579e-01 -4.4884351534274e-01 -4.1004951928571e-01 -3.4901022088116e-01 -3.0840343277535e-01 -2.8928797008559e-01 -2.2640416298193e-01 -1.8336678196295e-01 -1.6082453059272e-01 -1.3216191426283e-01 -1.2052643031278e-01 -1.0826645050139e-01 -1.0613375331937e-01 -1.0926244252068e-01 -1.1884038921100e-01 -1.2985075824626e-01 -1.3853264162242e-01 -1.5837709990018e-01 -1.7318566176301e-01 -1.8606467210816e-01 -2.1070548874019e-01 -2.2069140914839e-01 -2.2178485578737e-01 -2.3006598333023e-01 -2.4087201463565e-01 -2.4360734649247e-01 -2.3929759872652e-01 -2.3910653564984e-01 -2.3580242850916e-01 -2.3015517449079e-01 -2.2995541823206e-01 -2.2789356732255e-01 -2.2638381446727e-01 -2.2455346357315e-01 -2.2291285821030e-01 -2.1971829660626e-01 -2.1887129746363e-01 -2.1736593214859e-01 -2.1699480154605e-01 -2.1649515927294e-01 -2.1569636486502e-01 -2.1581564056738e-01 -2.1567249948292e-01 -2.1285907549692e-01 -2.1086938876603e-01 -2.0923251820971e-01 -2.0798821158318e-01 -2.0784116640044e-01 -2.0775622428611e-01 -2.0767002931623e-01 -2.0736001310239e-01 -7.2083073302779e-01 -7.1829219714601e-01 -7.1546683922891e-01 -7.1130365119322e-01 -7.0368328332287e-01 -6.8546220868391e-01 -6.6764598612355e-01 -6.4568963731436e-01 -6.2859386804378e-01 -6.1195509271984e-01 -5.9375065767257e-01 -5.6047485070879e-01 -5.4031652179336e-01 -4.9570890728818e-01 -4.5717380315827e-01 -4.2212952656834e-01 -3.7296741482871e-01 -3.3820207725070e-01 -3.0106742636812e-01 -2.4820620549673e-01 -2.2053291669207e-01 -1.8244138921884e-01 -1.5659177982813e-01 -1.2586425926119e-01 -1.0446799334972e-01 -9.0262806195779e-02 -8.0834259132255e-02 -6.6013879169966e-02 -6.0875404707642e-02 -5.5808212691454e-02 -6.0177039814566e-02 -7.3022708953236e-02 -8.9751742315697e-02 -1.0185411472395e-01 -1.1279973052907e-01 -1.2641096365874e-01 -1.3845458545509e-01 -1.4092193330291e-01 -1.4041849386942e-01 -1.4257025125988e-01 -1.4499160875098e-01 -1.4405391157939e-01 -1.4160551457974e-01 -1.4153440735304e-01 -1.4088056509261e-01 -1.3805197466808e-01 -1.3701038123512e-01 -1.3647991121606e-01 -1.3524919779297e-01 -1.3449981194979e-01 -1.3378774341589e-01 -1.3062719361896e-01 -1.3049127059000e-01 -1.3052969557492e-01 -1.3122665242357e-01 -1.3276504832506e-01 -1.3199856253508e-01 -1.3146397299563e-01 -1.3068551767849e-01 -1.3017048385178e-01 -1.2929418209497e-01 -6.6535157603168e-01 -6.6533092230057e-01 -6.6532264456006e-01 -6.6526268822532e-01 -6.6524822076228e-01 -6.6514450940652e-01 -6.6179182567578e-01 -6.5922959606163e-01 -6.5002483415365e-01 -6.3051294000712e-01 -6.1001431713075e-01 -5.8574506686047e-01 -5.6435900287486e-01 -5.0732117990425e-01 -4.4267972224008e-01 -3.9831686072535e-01 -3.6104203445529e-01 -2.9590933079413e-01 -2.4616033569107e-01 -2.0083078895882e-01 -1.2263950302561e-01 -7.5258587849946e-02 -3.8634108051726e-02 6.3730864384244e-04 1.1643013278393e-02 1.6868800739384e-02 2.1968576619434e-02 3.1245963329053e-02 2.8148015681907e-02 1.7857507910730e-02 1.4270166382430e-02 1.2075318549666e-02 1.1698907043625e-02 8.6031612064581e-03 5.5308702669013e-03 3.6548178984087e-03 2.4242418022765e-03 1.6413361910446e-03 1.9093975482925e-03 1.8872616382594e-03 1.3344196603461e-03 2.7832637870620e-04 3.4622720532289e-04 3.4666705989043e-04 2.9520235567143e-04 9.1439116994776e-05 -3.3646937217564e-05 -2.6540950470323e-04 -3.3276196579274e-04 -5.1062314785648e-04 -8.4162040279648e-04 -8.0879703245655e-04 -6.5732626721959e-04 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 + -3.3620955788278e-01 -3.3623756209121e-01 -3.3624806449662e-01 -3.3626122416052e-01 -3.3629145186007e-01 -3.3630591355008e-01 -3.3638507625893e-01 -3.3794080938054e-01 -3.4129155784091e-01 -3.4835575094340e-01 -3.5652033151391e-01 -3.6304361292850e-01 -3.7086490474803e-01 -3.8354758459816e-01 -3.9722447851591e-01 -4.1164555195367e-01 -4.2148687319901e-01 -4.3344697264134e-01 -4.4299146317171e-01 -4.5276818530881e-01 -4.6578721616958e-01 -4.7990824776060e-01 -4.9156932682802e-01 -5.0167743832804e-01 -5.0918630423355e-01 -5.1878834848547e-01 -5.2427677211490e-01 -5.2902813414849e-01 -5.3323988387825e-01 -5.3333384344884e-01 -5.3100742093678e-01 -5.2597907742624e-01 -5.1802468991949e-01 -5.0563132416777e-01 -4.9803556111493e-01 -4.8694742602209e-01 -4.6716475716998e-01 -4.5073126254369e-01 -4.4337208686924e-01 -4.3303622872709e-01 -4.2074861915199e-01 -4.0523635419787e-01 -3.9938344867223e-01 -3.9795692366556e-01 -3.9407573659128e-01 -3.9533412527006e-01 -3.9255740887714e-01 -3.9189457215241e-01 -3.9299519074969e-01 -3.9476969659568e-01 -3.9699363975863e-01 -3.9870351430674e-01 -3.9864162815778e-01 -3.9939943505077e-01 -3.9873889676992e-01 -3.9876962431900e-01 -3.9928907144355e-01 -3.9965755918362e-01 -3.9976321550276e-01 -3.9953589074521e-01 -3.9884551889524e-01 -3.9858014581798e-01 -3.9866007150272e-01 -3.9894396310077e-01 -3.9921685828241e-01 -3.9921456359782e-01 -3.9923766961868e-01 -6.2701647338539e-01 -6.2709558198762e-01 -6.2708679047966e-01 -6.2720519755973e-01 -6.2712296986190e-01 -6.2681642029240e-01 -6.2643884367761e-01 -6.2644058526634e-01 -6.2643651062974e-01 -6.2662055602394e-01 -6.2809700585903e-01 -6.3372029484945e-01 -6.3315041627191e-01 -6.3100552682427e-01 -6.3211416891954e-01 -6.3217679526797e-01 -6.3618554594282e-01 -6.4474126974647e-01 -6.6545416921759e-01 -6.9267460225141e-01 -7.1335339250601e-01 -7.4540147222636e-01 -7.6906185202340e-01 -7.8211364516886e-01 -8.0206798148907e-01 -8.1908608945008e-01 -8.4290884549063e-01 -8.5560390384251e-01 -8.7442833494131e-01 -8.8682421309606e-01 -9.0451882889779e-01 -9.1492749311919e-01 -9.2263775856258e-01 -9.3155904051611e-01 -9.3763156711843e-01 -9.4424899755510e-01 -9.4883774974867e-01 -9.5504871740315e-01 -9.5864279849873e-01 -9.6138887481544e-01 -9.6287667383772e-01 -9.6221265511208e-01 -9.6064147923560e-01 -9.5731171252234e-01 -9.5602088779930e-01 -9.5706883166828e-01 -9.5614156668305e-01 -9.5543365859604e-01 -9.5523498929811e-01 -9.5516259138582e-01 -9.5614114061423e-01 -9.5793658017087e-01 -9.5899025428644e-01 -9.6030755299268e-01 -9.6047576947977e-01 -9.6062248371497e-01 -9.6102626882353e-01 -9.6116043067067e-01 -9.6140017015151e-01 -9.6164065545552e-01 -9.6168866103155e-01 -9.6173491466802e-01 -9.6181829943468e-01 -9.6183291764575e-01 -9.6185078892616e-01 -9.6180613132761e-01 -9.6164807945740e-01 -9.6134059857429e-01 -9.6133695790188e-01 -9.6132768047469e-01 -9.6141002043307e-01 -9.6181705212557e-01 -9.6286846053237e-01 -9.6301334529265e-01 -9.6297730076726e-01 -9.6294057806457e-01 -1.7810909104344e-01 -1.7810979617050e-01 -1.7811193919367e-01 -1.7812530676423e-01 -1.7812744976786e-01 -1.7812997320222e-01 -1.7814063531135e-01 -1.7814409256255e-01 -1.7815150181974e-01 -1.7816537796089e-01 -1.7815715577877e-01 -1.7810366352073e-01 -1.7824773546031e-01 -1.7844180935415e-01 -1.7854470903229e-01 -1.7857635124005e-01 -1.7922570697107e-01 -1.8019099263872e-01 -1.8137963696112e-01 -1.7999691542925e-01 -1.7820299432124e-01 -1.7787973961787e-01 -1.7768754447442e-01 -1.7605057876430e-01 -1.6384061836512e-01 -1.4729263516965e-01 -1.2729487636992e-01 -1.0785294110825e-01 -7.8304999483410e-02 -6.1874586961491e-02 -4.4557051955761e-02 -2.3058473191676e-02 -1.2043393553290e-02 -7.3964950015421e-03 -3.5317681043410e-03 3.1242136247401e-05 1.9014967164407e-03 3.4358827704908e-03 4.2178869170150e-03 5.5076411728490e-03 5.8847061565139e-03 5.7587043593933e-03 5.6961513617534e-03 5.6331177666401e-03 5.6371215121615e-03 5.6533688513870e-03 5.8025223157504e-03 5.7183608001252e-03 5.7122708433286e-03 5.6885917013722e-03 5.6291602131661e-03 5.5977520717049e-03 5.5053327345374e-03 5.3970950372780e-03 5.2825285551541e-03 5.1584962221744e-03 5.1406694304147e-03 5.2728624841352e-03 5.2694610476870e-03 5.2505705000804e-03 5.2800234833229e-03 5.3358703165767e-03 5.6026409500399e-03 5.8935588695406e-03 5.9374853769519e-03 9.6346465429901e-03 1.1042108571361e-02 1.1073808717502e-02 1.1222394821489e-02 1.1248083783215e-02 -4.4947971430807e-01 -4.4948690389752e-01 -4.4950127414303e-01 -4.4950486666215e-01 -4.4951485463551e-01 -4.4952024112104e-01 -4.4953709875319e-01 -4.4955438113079e-01 -4.4955580731919e-01 -4.4965855910285e-01 -4.5012907739864e-01 -4.5259198442307e-01 -4.5732159354362e-01 -4.6350823163751e-01 -4.7084360940640e-01 -4.7832172736057e-01 -4.9261722138421e-01 -5.0033188160942e-01 -5.0694597364775e-01 -5.1502154632890e-01 -5.2310663043012e-01 -5.3387062888144e-01 -5.4136026372559e-01 -5.4987954146305e-01 -5.6838085729313e-01 -5.7939947634996e-01 -5.8942518086016e-01 -5.9764130781321e-01 -6.1227811214785e-01 -6.2779313140908e-01 -6.3731262767022e-01 -6.4562880760916e-01 -6.5700903940334e-01 -6.6125733752600e-01 -6.6485678379355e-01 -6.7289739115784e-01 -6.7805873149856e-01 -6.7991343283985e-01 -6.7643660845091e-01 -6.6835201150641e-01 -6.5722793068604e-01 -6.4576270153163e-01 -6.4099586243219e-01 -6.3624957656030e-01 -6.3042151670566e-01 -6.3095212129990e-01 -6.2944423733424e-01 -6.2647438892863e-01 -6.2627945234817e-01 -6.2641404191553e-01 -6.2615511810135e-01 -6.2672029811013e-01 -6.2857386883852e-01 -6.3000148266906e-01 -6.3034783331518e-01 -6.3091989416190e-01 -6.3363044805174e-01 -6.3491250738728e-01 -6.3529572027901e-01 -6.3559770001279e-01 -6.3604669735821e-01 -6.3632507912704e-01 -6.3657701916104e-01 -6.3697333655071e-01 -6.3705031061938e-01 -6.3642934055291e-01 -6.3633791147484e-01 -6.3630862932447e-01 -6.3623496731524e-01 -6.3623899856546e-01 -6.3615178135884e-01 -2.0288174425247e-01 -2.0288950421802e-01 -2.0291176025002e-01 -2.0293073415233e-01 -2.0293494884702e-01 -2.0295813209196e-01 -2.0304032909659e-01 -2.0301947218622e-01 -2.0298962231694e-01 -2.0307377167548e-01 -2.0369736640432e-01 -2.0557821311492e-01 -2.0873540376912e-01 -2.1247466411071e-01 -2.2025392567529e-01 -2.2397103664157e-01 -2.2704440991488e-01 -2.3577126853652e-01 -2.4475033233498e-01 -2.5223172212791e-01 -2.6135858144776e-01 -2.6781751983584e-01 -2.7282528677032e-01 -2.7483737381434e-01 -2.7605127825547e-01 -2.7973004737960e-01 -2.8416508490711e-01 -2.8762477563177e-01 -2.8891703012620e-01 -2.8981301889562e-01 -2.8775521468060e-01 -2.8111086945774e-01 -2.7826231700618e-01 -2.7565485232856e-01 -2.6814625656241e-01 -2.6179333182611e-01 -2.5630606680267e-01 -2.5114522631557e-01 -2.4408093954816e-01 -2.4220154279269e-01 -2.3797874351774e-01 -2.3441414105290e-01 -2.3347763463680e-01 -2.3284587664570e-01 -2.3218038096360e-01 -2.3215322008194e-01 -2.3230580350906e-01 -2.3249733416074e-01 -2.3244245768065e-01 -2.3227012097904e-01 -2.3212275554814e-01 -2.3198279678589e-01 -2.3139105068143e-01 -2.2956176102132e-01 -2.2962111521445e-01 -2.2993855133862e-01 -2.2997326549248e-01 -2.2997758056354e-01 -2.2987827994474e-01 -2.2962693178386e-01 -2.2882215588534e-01 -2.2836846282198e-01 -2.2807762244637e-01 -5.1966936941740e-01 -5.1961283433620e-01 -5.1961880988913e-01 -5.1922467482680e-01 -5.1916173237396e-01 -5.1930207931445e-01 -5.2006516557724e-01 -5.2006690165339e-01 -5.1957183173112e-01 -5.1436340551988e-01 -5.1546654088917e-01 -5.2350977556603e-01 -5.3667586512783e-01 -5.5008133926410e-01 -5.6582917086038e-01 -5.8845629099823e-01 -5.9897996355957e-01 -6.0988063002556e-01 -6.4049668505415e-01 -6.5390430997339e-01 -6.7135735649485e-01 -6.8797549072480e-01 -7.1180176348311e-01 -7.2852117773284e-01 -7.3608975134262e-01 -7.6031372675918e-01 -7.8072237460861e-01 -7.9373093322909e-01 -8.1768835590064e-01 -8.3544836566071e-01 -8.5761441093286e-01 -8.6043962304239e-01 -8.6822628585819e-01 -8.6721441594675e-01 -8.6415868096110e-01 -8.6035731767582e-01 -8.5291792867403e-01 -8.4673609245595e-01 -8.3887852345643e-01 -8.2424911180923e-01 -8.1490911141544e-01 -8.1098437477647e-01 -8.0442868909922e-01 -7.9688068909318e-01 -7.9378847344574e-01 -7.9580781318315e-01 -7.9621716564316e-01 -7.9832490484673e-01 -8.0161357857793e-01 -8.0224395474377e-01 -8.0382821450382e-01 -8.0471767344263e-01 -8.0566212687615e-01 -8.0647674306526e-01 -8.0816813739950e-01 -8.0888163461918e-01 -8.0963987108447e-01 -8.0982228594999e-01 -8.1005997140574e-01 -8.1049963136769e-01 -8.1054896389700e-01 -8.1061077553311e-01 -8.1188722139133e-01 -8.1294514026357e-01 -8.1381367931378e-01 -8.1445202200547e-01 -8.1450787344633e-01 -8.1454812826717e-01 -8.1460859143695e-01 -8.1473655516425e-01 -3.7325985201288e-01 -3.7504745076659e-01 -3.7705666495926e-01 -3.8002795619752e-01 -3.8546765673750e-01 -3.9820180572496e-01 -4.1027383801174e-01 -4.2449710343407e-01 -4.3501345926096e-01 -4.4470676932461e-01 -4.5505543576072e-01 -4.7189363898184e-01 -4.8120085387725e-01 -5.0069192968481e-01 -5.1551843904136e-01 -5.2877550824033e-01 -5.4827479461950e-01 -5.6303534256545e-01 -5.7747212013692e-01 -6.0035061725273e-01 -6.1357697118608e-01 -6.3518040702318e-01 -6.5275438362471e-01 -6.7075045452535e-01 -6.8112546033441e-01 -6.8790190354582e-01 -6.9318844321456e-01 -7.0021977888676e-01 -7.0319155026862e-01 -7.0548238046628e-01 -7.0061706616347e-01 -6.9110082792423e-01 -6.7722185075491e-01 -6.6735347819781e-01 -6.5699367135691e-01 -6.4427634795807e-01 -6.3093594135333e-01 -6.2817167266570e-01 -6.2829458648019e-01 -6.2680098957055e-01 -6.2591589560323e-01 -6.2636867248327e-01 -6.2791796467222e-01 -6.2849110374675e-01 -6.2889834415903e-01 -6.3073797010757e-01 -6.3161658222035e-01 -6.3254677599190e-01 -6.3321257421523e-01 -6.3361164104056e-01 -6.3399393001139e-01 -6.3495562372112e-01 -6.3508467056485e-01 -6.3515888204630e-01 -6.3501445695578e-01 -6.3439156370312e-01 -6.3469580371562e-01 -6.3490493546138e-01 -6.3525871081184e-01 -6.3591010313776e-01 -6.3626407186057e-01 -1.7826660169589e-01 -1.7827552896412e-01 -1.7827910677185e-01 -1.7830501902567e-01 -1.7831127110150e-01 -1.7832350743399e-01 -1.7869849435425e-01 -1.7901791189145e-01 -1.8033377682196e-01 -1.8324274492779e-01 -1.8630888820760e-01 -1.8956178270823e-01 -1.9190532633436e-01 -1.9692111153663e-01 -2.0109611777213e-01 -2.0268782568678e-01 -2.0382502554507e-01 -2.0493161390660e-01 -2.0160537733496e-01 -1.9442051187944e-01 -1.6807718398308e-01 -1.4837066847947e-01 -1.3754264494704e-01 -1.2610135943162e-01 -1.1644262587111e-01 -1.0662292105418e-01 -1.0471641259306e-01 -1.0254872329762e-01 -8.7382339835696e-02 -8.3706910981613e-02 -8.2507503919836e-02 -8.1681867530848e-02 -7.9130998766709e-02 -7.2926241860934e-02 -6.9059439183584e-02 -6.8561336894743e-02 -6.7721021947095e-02 -6.7665171342721e-02 -6.7685199787870e-02 -6.7688458282555e-02 -6.7683364422895e-02 -6.7678676376966e-02 -6.7683199225329e-02 -6.7688190411937e-02 -6.7694221827886e-02 -6.7695180120768e-02 -6.7700240376132e-02 -6.7727718233063e-02 -6.7727466105686e-02 -6.7725082751388e-02 -6.7734142898677e-02 -6.7735125792656e-02 -6.7751134256176e-02 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_quat_tpgmm_XU.txt b/data/data_quat_tpgmm_XU.txt new file mode 100644 index 0000000..c455139 --- /dev/null +++ b/data/data_quat_tpgmm_XU.txt @@ -0,0 +1,8 @@ + 9.3530591988591e-03 9.3530591988592e-03 9.3530591994426e-03 9.3528087653516e-03 1.1148875865041e-02 1.4347132390944e-02 1.7508379029646e-02 1.8089346299353e-02 1.6597549408599e-02 1.3318532471537e-02 2.1246523583484e-02 4.9910949699650e-02 6.7461934973391e-02 4.6693327300902e-02 -1.3470278148663e-02 -6.9035752710879e-02 -1.2398651788253e-01 -1.7004310902636e-01 -2.1373843382407e-01 -2.2605751343578e-01 4.8989467080856e-03 4.8983992400292e-03 4.8785006660565e-03 4.8271931603999e-03 4.4815022606328e-03 -4.3072943919466e-03 -2.4790840079679e-02 -1.9819068106277e-02 1.3595577471507e-02 3.1118703235325e-02 -1.8456646062096e-02 -1.0789008539523e-01 -1.8433994661185e-01 -2.3103051517563e-01 -2.5224335167821e-01 -2.6750447529619e-01 -2.8050437235707e-01 -2.9001732917380e-01 -2.9582180819201e-01 -2.9840774221965e-01 -4.0083489504646e-03 -4.0075903707486e-03 -3.8102641452895e-03 1.4499929452353e-03 7.0740080978070e-03 7.8522506722986e-03 3.4723320664230e-03 3.2074000894050e-03 -2.8638119620786e-02 -1.3958195814826e-01 -2.9909458674232e-01 -4.2314870617615e-01 -4.8179781589766e-01 -4.9746650833602e-01 -5.0098831294890e-01 -4.9838483062281e-01 -4.9231920546053e-01 -4.8417407947774e-01 -4.7606185532386e-01 -4.7207471075885e-01 9.3529367185913e-03 9.3501419985912e-03 1.1678065455945e-02 1.4844930749353e-02 1.6391580266507e-02 1.3625518338061e-02 -7.3335933909268e-04 -6.4956514545313e-02 -2.0731762462594e-01 -4.0864582240024e-01 -6.1482780513853e-01 -7.6126942116347e-01 -8.2909578489475e-01 -8.4150705477929e-01 -8.3338141622516e-01 -8.2194956366328e-01 -8.0715124260898e-01 -7.9477209939456e-01 -7.8837543577754e-01 -7.8840827471842e-01 -9.3532156145825e-03 -9.3532156145827e-03 -9.3532156146106e-03 -9.3530547806121e-03 -1.1151772857326e-02 -1.4368927036821e-02 -1.7588065730038e-02 -1.8258032869919e-02 -1.6853907418278e-02 -1.3648834474216e-02 -2.2153939967122e-02 -5.4280784082163e-02 -7.8856969008236e-02 -5.9293777427222e-02 1.7988759005344e-02 9.4564140076569e-02 1.7507238329968e-01 2.5057532140894e-01 3.3049902722168e-01 3.5586758457388e-01 -4.8993034171622e-03 -4.8993034171623e-03 -4.8993034171622e-03 -4.8993003873519e-03 -4.6218134379231e-03 4.5458479173861e-03 2.7079585149848e-02 2.2634639320502e-02 -1.6409264631938e-02 -4.0340901948682e-02 2.5930641274679e-02 1.6116905015778e-01 2.8725386176934e-01 3.7229311146541e-01 4.2276074281154e-01 4.7268918481505e-01 5.3073065507480e-01 5.9545490646174e-01 6.4931418942726e-01 6.6764143839330e-01 4.0085209776783e-03 4.0085161900498e-03 3.8155802957489e-03 -1.4570604531950e-03 -7.1554121199428e-03 -8.0260541517662e-03 -3.6103821350583e-03 -3.4378554275099e-03 3.2099351885379e-02 1.6400923215202e-01 3.6842331862788e-01 5.5166671233344e-01 6.6990144710273e-01 7.2896551179520e-01 7.7157766765765e-01 8.1587919083392e-01 8.7087151568715e-01 9.1388612595065e-01 9.4132455957061e-01 9.4823790683077e-01 -9.3532156145825e-03 -9.3515713503968e-03 -1.1693314440722e-02 -1.4921803102363e-02 -1.6613133242167e-02 -1.4004511262386e-02 7.7083155772355e-04 7.0470269398076e-02 2.3142725656635e-01 4.6485113803581e-01 7.1625572033942e-01 9.2850649271019e-01 1.0627892324144e+00 1.1204403774193e+00 1.1450964308695e+00 1.1755388805949e+00 1.2071591047934e+00 1.2301111186866e+00 1.2377601004461e+00 1.2377421996631e+00 + 9.9994983055879e-01 9.9994983055879e-01 9.9994983073696e-01 9.9992109081831e-01 9.9922070460159e-01 9.9545101083335e-01 9.8642015713384e-01 9.7233426579409e-01 9.5450769175323e-01 9.2775404095184e-01 8.7814103620852e-01 7.6247792883716e-01 5.7963042736663e-01 3.9157680566755e-01 2.8768873587923e-01 2.3809469417583e-01 1.8111616079940e-01 1.0517574081068e-01 2.4999022090093e-02 -3.4291229015735e-03 9.9978157881730e-01 9.9944636389265e-01 9.8727264280837e-01 9.5597698854637e-01 9.0948292684855e-01 8.4424853395509e-01 7.5084691048799e-01 6.3649257645274e-01 5.0426512866390e-01 3.4805675440383e-01 1.9037228075046e-01 8.1896131848929e-02 1.2637113879603e-02 -3.9388568435920e-02 -9.7129284934302e-02 -1.6976200267432e-01 -2.5556389294562e-01 -3.4723537778711e-01 -4.1417752406061e-01 -4.3213664138726e-01 9.9987125495549e-01 9.9930714272697e-01 9.9582134195031e-01 9.8546256352407e-01 9.6594823522851e-01 9.3531856535405e-01 8.8617706255155e-01 8.0165091785552e-01 6.8373875709047e-01 5.6716323779287e-01 4.5809200998733e-01 3.3634683118587e-01 2.0973153976674e-01 1.1488924523166e-01 3.1441471420647e-02 -6.2960709080792e-02 -1.7116732410890e-01 -2.5269314569183e-01 -3.0640430664573e-01 -3.2374596168048e-01 9.9991054595358e-01 9.9954147552670e-01 9.9608878918305e-01 9.8456091004731e-01 9.6009911787677e-01 9.1925659321460e-01 8.5560191298086e-01 7.6903993684830e-01 6.9420169755050e-01 6.4639344531758e-01 5.8777901089497e-01 4.8032424832974e-01 3.7158169503765e-01 2.9362652743838e-01 2.3216582564347e-01 1.5788788483281e-01 7.9914486682669e-02 2.3467136210730e-02 7.8327890040175e-04 8.7149291425924e-04 2.5354564758588e-03 2.5354564756404e-03 2.5354213405437e-03 5.9304639464744e-03 2.6780881565104e-02 6.6702392821714e-02 1.1600008613503e-01 1.6621543661397e-01 2.1377430328141e-01 2.7025892336597e-01 3.5238078526504e-01 4.9608156027942e-01 6.7122212813208e-01 8.2515563531391e-01 9.0428855866371e-01 9.3835022244766e-01 9.7410679393255e-01 1.0209516417026e+00 1.0677667460399e+00 1.0843302195090e+00 -1.4367586696533e-02 2.3274140443693e-02 1.1288243979269e-01 2.1056557303334e-01 3.0315986204427e-01 3.9995130487702e-01 5.0978475604997e-01 6.2265228127316e-01 7.3690170300717e-01 8.5887250849684e-01 9.7510817274484e-01 1.0465598178611e+00 1.0828998807461e+00 1.1077287705814e+00 1.1409997489826e+00 1.1851128364506e+00 1.2378201186977e+00 1.2947329844259e+00 1.3359897163795e+00 1.3463273886810e+00 1.0986978062055e-02 2.6170655233108e-02 6.4608762312829e-02 1.2071344164819e-01 1.8498971016996e-01 2.5565365266563e-01 3.4065192821658e-01 4.5306826626971e-01 5.7791292420193e-01 6.7439585573552e-01 7.2910118110168e-01 7.7558418778825e-01 8.3649903391454e-01 8.9093614181113e-01 9.4187719946262e-01 1.0009094265709e+00 1.0674670680849e+00 1.1180416541678e+00 1.1525236049541e+00 1.1646196745778e+00 6.7612172689568e-03 2.0367463637055e-02 6.2011259245435e-02 1.2396633337363e-01 2.0007771200480e-01 2.8592996974296e-01 3.8472494950124e-01 4.8781074493664e-01 5.4407322868081e-01 5.1828924492978e-01 4.3316087152316e-01 3.7569119741738e-01 3.7866837015458e-01 4.2695258877562e-01 4.8732255508633e-01 5.5341857506343e-01 6.1856333698603e-01 6.6371966688937e-01 6.8296811933326e-01 6.8288294416465e-01 + -2.5354140749055e-03 -2.5354140746871e-03 -2.5353789403285e-03 -5.9303079563014e-03 -2.6773924464357e-02 -6.6601219294494e-02 -1.1547452157033e-01 -1.6467976668845e-01 -2.1052266830148e-01 -2.6371865329394e-01 -3.3794741141355e-01 -4.5614488111579e-01 -5.7422881110252e-01 -6.4980279256432e-01 -6.7714612265552e-01 -6.8503466388679e-01 -6.8986385601822e-01 -6.9282876838999e-01 -6.9053998102969e-01 -6.8879831653952e-01 1.4366540619541e-02 -2.3269845150303e-02 -1.1240313383850e-01 -2.0746649798944e-01 -2.9395639294671e-01 -3.7896296661396e-01 -4.6669815258836e-01 -5.4519923177677e-01 -6.1054559219062e-01 -6.6252853599782e-01 -6.9405250051347e-01 -7.0059002029061e-01 -6.9493132302262e-01 -6.8741306422494e-01 -6.8078601393621e-01 -6.7067958748739e-01 -6.5421876834552e-01 -6.3060191134817e-01 -6.0866511168336e-01 -6.0175191838245e-01 -1.0986506551681e-02 -2.6164610777605e-02 -6.4518744576383e-02 -1.2012791809780e-01 -1.8288516242217e-01 -2.5011749585287e-01 -3.2762643110525e-01 -4.2269700642781e-01 -5.1559730902952e-01 -5.7395241033373e-01 -5.9190123270999e-01 -5.9490166482061e-01 -6.0161596796599e-01 -6.0799980855839e-01 -6.1156444638465e-01 -6.1141169015530e-01 -6.0345817878794e-01 -5.9233505505003e-01 -5.8287284667179e-01 -5.7979911165744e-01 -6.7610156616733e-03 -2.0364350548374e-02 -6.1930391775989e-02 -1.2332769850658e-01 -1.9740947285859e-01 -2.7819207490644e-01 -3.6602242328003e-01 -4.4964331794795e-01 -4.8739276032655e-01 -4.5562270887506e-01 -3.7182159995075e-01 -3.0802393159292e-01 -2.9540414975310e-01 -3.2066285966819e-01 -3.5466494363965e-01 -3.8695628345898e-01 -4.1359433408415e-01 -4.2882782299079e-01 -4.3500779230764e-01 -4.3497794935814e-01 2.5354564758588e-03 2.5354564756404e-03 2.5354213405437e-03 5.9304639464744e-03 2.6780881565104e-02 6.6702392821714e-02 1.1600008613503e-01 1.6621543661397e-01 2.1377430328141e-01 2.7025892336597e-01 3.5238078526504e-01 4.9608156027942e-01 6.7122212813208e-01 8.2515563531391e-01 9.0428855866371e-01 9.3835022244766e-01 9.7410679393255e-01 1.0209516417026e+00 1.0677667460399e+00 1.0843302195090e+00 -1.4367586696533e-02 2.3274140443693e-02 1.1288243979269e-01 2.1056557303334e-01 3.0315986204427e-01 3.9995130487702e-01 5.0978475604997e-01 6.2265228127316e-01 7.3690170300717e-01 8.5887250849684e-01 9.7510817274484e-01 1.0465598178611e+00 1.0828998807461e+00 1.1077287705814e+00 1.1409997489826e+00 1.1851128364506e+00 1.2378201186977e+00 1.2947329844259e+00 1.3359897163795e+00 1.3463273886810e+00 1.0986978062055e-02 2.6170655233108e-02 6.4608762312829e-02 1.2071344164819e-01 1.8498971016996e-01 2.5565365266563e-01 3.4065192821658e-01 4.5306826626971e-01 5.7791292420193e-01 6.7439585573552e-01 7.2910118110168e-01 7.7558418778825e-01 8.3649903391454e-01 8.9093614181113e-01 9.4187719946262e-01 1.0009094265709e+00 1.0674670680849e+00 1.1180416541678e+00 1.1525236049541e+00 1.1646196745778e+00 6.7612172689568e-03 2.0367463637055e-02 6.2011259245435e-02 1.2396633337363e-01 2.0007771200480e-01 2.8592996974296e-01 3.8472494950124e-01 4.8781074493664e-01 5.4407322868081e-01 5.1828924492978e-01 4.3316087152316e-01 3.7569119741738e-01 3.7866837015458e-01 4.2695258877562e-01 4.8732255508633e-01 5.5341857506343e-01 6.1856333698603e-01 6.6371966688937e-01 6.8296811933326e-01 6.8288294416465e-01 + 2.5354140749055e-03 2.5354140746871e-03 2.5353789403285e-03 5.9303079563014e-03 2.6773924464357e-02 6.6601219294494e-02 1.1547452157033e-01 1.6467976668845e-01 2.1052266830148e-01 2.6371865329394e-01 3.3794741141355e-01 4.5614488111579e-01 5.7422881110252e-01 6.4980279256432e-01 6.7714612265552e-01 6.8503466388679e-01 6.8986385601822e-01 6.9282876838999e-01 6.9053998102969e-01 6.8879831653952e-01 -1.4366540619541e-02 2.3269845150303e-02 1.1240313383850e-01 2.0746649798944e-01 2.9395639294671e-01 3.7896296661396e-01 4.6669815258836e-01 5.4519923177677e-01 6.1054559219062e-01 6.6252853599782e-01 6.9405250051347e-01 7.0059002029061e-01 6.9493132302262e-01 6.8741306422494e-01 6.8078601393621e-01 6.7067958748739e-01 6.5421876834552e-01 6.3060191134817e-01 6.0866511168336e-01 6.0175191838245e-01 1.0986506551681e-02 2.6164610777605e-02 6.4518744576383e-02 1.2012791809780e-01 1.8288516242217e-01 2.5011749585287e-01 3.2762643110525e-01 4.2269700642781e-01 5.1559730902952e-01 5.7395241033373e-01 5.9190123270999e-01 5.9490166482061e-01 6.0161596796599e-01 6.0799980855839e-01 6.1156444638465e-01 6.1141169015530e-01 6.0345817878794e-01 5.9233505505003e-01 5.8287284667179e-01 5.7979911165744e-01 6.7610156616733e-03 2.0364350548374e-02 6.1930391775989e-02 1.2332769850658e-01 1.9740947285859e-01 2.7819207490644e-01 3.6602242328003e-01 4.4964331794795e-01 4.8739276032655e-01 4.5562270887506e-01 3.7182159995075e-01 3.0802393159292e-01 2.9540414975310e-01 3.2066285966819e-01 3.5466494363965e-01 3.8695628345898e-01 4.1359433408415e-01 4.2882782299079e-01 4.3500779230764e-01 4.3497794935814e-01 8.5268975840405e-01 8.5268975840425e-01 8.5268979086483e-01 8.4955324203772e-01 8.2960162834810e-01 7.9148780958734e-01 7.4471076869077e-01 6.9806144884074e-01 6.5466012088456e-01 6.0370166480197e-01 5.2457619445905e-01 3.7951957864026e-01 2.0830589388683e-01 7.3576386536094e-02 3.0041844609328e-02 2.7877100259048e-02 2.5651506561687e-02 1.1266234012595e-02 -1.3998046292289e-03 -6.9943321528904e-03 6.5633999379442e-01 6.2647680383339e-01 5.5538576022705e-01 4.7788852202489e-01 4.0459745689805e-01 3.3338856104240e-01 2.5996949575716e-01 1.6771975603600e-01 5.3311172912819e-02 -5.8023430771879e-02 -1.0989582390874e-01 -8.4254298182516e-02 -3.6329238365779e-02 -4.2587058854690e-03 6.8399642084928e-05 -4.5343559489649e-03 -1.1016446000229e-02 -1.6766830365454e-02 -1.6710542406892e-02 -1.3755046987761e-02 -5.0152871544413e-02 -5.9396112354951e-02 -8.2948815685398e-02 -1.2128624760200e-01 -1.6493596700763e-01 -2.0864417638483e-01 -2.5688465992842e-01 -3.2518251588584e-01 -3.7298956612646e-01 -3.2707350927485e-01 -1.9820340301094e-01 -8.1123706103463e-02 -2.4404393111484e-02 -1.0684931690767e-02 -7.8893865514167e-03 -8.6791680915219e-03 -5.5685484383834e-03 -2.2306209998068e-03 -1.4535296707586e-03 -3.3324231588434e-03 -8.9182485469786e-01 -8.9703022065758e-01 -9.1513009980926e-01 -9.4182201482450e-01 -9.7251116374000e-01 -1.0029553479524e+00 -1.0271119130894e+00 -1.0021672550664e+00 -8.7499310939957e-01 -6.4947045950871e-01 -3.8462569341195e-01 -1.6653885691518e-01 -4.3617096814702e-02 -8.8319544298689e-03 -9.1553172141953e-03 -6.3240127839159e-03 -2.0405559266966e-03 1.8837606187004e-03 1.5844344619184e-03 1.6004914207901e-03 + -6.0422643163874e-01 -6.0422643163881e-01 -6.0422644333503e-01 -6.0309132749180e-01 -5.9495571995534e-01 -5.7848437156389e-01 -5.5672757974851e-01 -5.3387667498231e-01 -5.1139832986469e-01 -4.8315013557960e-01 -4.3157365017123e-01 -3.2339690084601e-01 -1.8413841924435e-01 -6.7407044362138e-02 -2.8431761049704e-02 -2.6932125702033e-02 -2.5191493357161e-02 -1.1188086590576e-02 1.3985219024612e-03 6.9930787377580e-03 -2.9421595275921e-01 -2.9181539518381e-01 -2.8161479926761e-01 -2.6331945127768e-01 -2.3931338257096e-01 -2.1191949107304e-01 -1.7886641321397e-01 -1.2209443458504e-01 -4.0054451636266e-02 4.5184212079779e-02 9.1665365666457e-02 7.5350533281622e-02 3.3948770938477e-02 4.0725595939521e-03 -6.6308870616383e-05 4.4493792068252e-03 1.0922892269428e-02 1.6735760419839e-02 1.6709578146601e-02 1.3753575345259e-02 2.0555546267610e-02 2.4778874766505e-02 3.6128432129020e-02 5.5805714185241e-02 8.0461572261599e-02 1.0843148467160e-01 1.4360314990844e-01 1.9713409123541e-01 2.4960859852030e-01 2.4677789612386e-01 1.6663339265545e-01 7.3202993941327e-02 2.2951379380190e-02 1.0261010979473e-02 7.6838026168675e-03 8.5558111410272e-03 5.5415786136068e-03 2.2284312187688e-03 1.4534788125879e-03 3.3324025048064e-03 4.8784852250124e-01 4.9556226219794e-01 5.1957873871572e-01 5.5530658625914e-01 5.9861148145181e-01 6.4590483448701e-01 6.9621217204890e-01 7.3147425236143e-01 7.0032485191221e-01 5.6536275842934e-01 3.5306349014211e-01 1.5729311799480e-01 4.1939929929856e-02 8.6131651788573e-03 9.0232832607763e-03 6.2852591693768e-03 2.0378256561601e-03 -1.8836558202904e-03 -1.5844011685635e-03 -1.6004584899062e-03 7.7405847099949e-01 7.7405847099957e-01 7.7405848444522e-01 7.7275910929651e-01 7.6644179873180e-01 7.5413676067829e-01 7.3824544654445e-01 7.1964783279375e-01 7.0015059969221e-01 6.7557377010918e-01 6.5200478701218e-01 6.2669421491822e-01 5.8237625550641e-01 5.0539442032977e-01 4.0371180797858e-01 3.1993054630371e-01 2.3186718068600e-01 1.4418481438910e-01 5.2429573611948e-02 2.2653515825887e-02 1.3468552161111e+00 1.3239403845068e+00 1.2693903081441e+00 1.2099245819588e+00 1.1533366050642e+00 1.0871405132506e+00 1.0024009288590e+00 9.3721794553657e-01 8.9864291591704e-01 8.4337803847368e-01 7.2004149922178e-01 5.6925265021267e-01 4.4710041514851e-01 3.6451937188948e-01 3.0422661962837e-01 2.3776137722436e-01 1.5962782245850e-01 7.3632263953105e-02 5.7873148063980e-03 -1.5045845542045e-02 1.4864375201651e+00 1.4743915020781e+00 1.4440139533626e+00 1.4027128989229e+00 1.3551880432933e+00 1.2996565817637e+00 1.2295348251294e+00 1.1402439202267e+00 1.0195643127318e+00 8.6271760950708e-01 6.9487754550356e-01 5.4644858667339e-01 4.2614484392915e-01 3.4700105811835e-01 2.8064616297660e-01 2.0684368985938e-01 1.2056275638013e-01 5.4253603965222e-02 1.0193773068862e-02 -3.6112633288382e-03 1.0941230736130e+00 1.0815519118465e+00 1.0439742077114e+00 9.8797067191148e-01 9.1830017102609e-01 8.3798475086896e-01 7.4105581225064e-01 6.1914413564857e-01 5.0556880615639e-01 4.4006264885384e-01 4.2250264221194e-01 3.9437284376538e-01 3.4023451507132e-01 2.7356357569382e-01 2.0835353627802e-01 1.3563895509022e-01 6.3352506971190e-02 1.2850142553837e-02 -7.8602472854190e-03 -7.7747053573879e-03 + 1.8218074549791e-01 1.8218074549770e-01 1.8218071113408e-01 1.8549964294935e-01 2.0438980422868e-01 2.4030331723206e-01 2.8439382419032e-01 3.3034281580567e-01 3.7443057010435e-01 4.2651753258833e-01 4.8813124816178e-01 5.7014047880024e-01 6.6032984082296e-01 7.5278558872380e-01 8.4096910163554e-01 8.9900326454791e-01 9.4639450192197e-01 9.7921964729797e-01 9.9725142012328e-01 9.9946240605438e-01 -4.2942414617772e-01 -3.9270103169559e-01 -3.0347823475205e-01 -2.0432773015001e-01 -1.0948065528498e-01 -2.3841830731531e-03 1.2918503398383e-01 2.3264895618020e-01 2.9437899754958e-01 3.6782516102599e-01 5.1977791551171e-01 6.8990265895583e-01 8.0605627985269e-01 8.7003361232472e-01 9.0886508350978e-01 9.4399005244819e-01 9.7456682221485e-01 9.9444288097441e-01 9.9982689086826e-01 9.9967903904390e-01 -5.0720792588249e-01 -4.9266881302032e-01 -4.5558718885932e-01 -4.0469343460618e-01 -3.4553897505238e-01 -2.7539455976420e-01 -1.8581521137557e-01 -7.4145011314994e-02 8.1362812424158e-02 3.0281913884679e-01 5.3820200939136e-01 7.1299122088018e-01 8.2355077960568e-01 8.8193254923546e-01 9.2223592297472e-01 9.5748277310641e-01 9.8548437122519e-01 9.9705550476615e-01 9.9989503245278e-01 9.9998140631274e-01 -2.1348245476215e-01 -2.0100629832329e-01 -1.6545611371561e-01 -1.1394845235347e-01 -5.1625896140269e-02 1.8263084560925e-02 1.0320421019501e-01 2.3770289461418e-01 4.2669479334896e-01 6.2199202307759e-01 7.5796993730405e-01 8.3533136712847e-01 8.8554189180855e-01 9.2605371985477e-01 9.5686067918780e-01 9.8163854456580e-01 9.9598706474362e-01 9.9983310420189e-01 9.9993696195864e-01 9.9993827380524e-01 7.7405847099949e-01 7.7405847099957e-01 7.7405848444522e-01 7.7275910929651e-01 7.6644179873180e-01 7.5413676067829e-01 7.3824544654445e-01 7.1964783279375e-01 7.0015059969221e-01 6.7557377010918e-01 6.5200478701218e-01 6.2669421491822e-01 5.8237625550641e-01 5.0539442032977e-01 4.0371180797858e-01 3.1993054630371e-01 2.3186718068600e-01 1.4418481438910e-01 5.2429573611948e-02 2.2653515825887e-02 1.3468552161111e+00 1.3239403845068e+00 1.2693903081441e+00 1.2099245819588e+00 1.1533366050642e+00 1.0871405132506e+00 1.0024009288590e+00 9.3721794553657e-01 8.9864291591704e-01 8.4337803847368e-01 7.2004149922178e-01 5.6925265021267e-01 4.4710041514851e-01 3.6451937188948e-01 3.0422661962837e-01 2.3776137722436e-01 1.5962782245850e-01 7.3632263953105e-02 5.7873148063980e-03 -1.5045845542045e-02 1.4864375201651e+00 1.4743915020781e+00 1.4440139533626e+00 1.4027128989229e+00 1.3551880432933e+00 1.2996565817637e+00 1.2295348251294e+00 1.1402439202267e+00 1.0195643127318e+00 8.6271760950708e-01 6.9487754550356e-01 5.4644858667339e-01 4.2614484392915e-01 3.4700105811835e-01 2.8064616297660e-01 2.0684368985938e-01 1.2056275638013e-01 5.4253603965222e-02 1.0193773068862e-02 -3.6112633288382e-03 1.0941230736130e+00 1.0815519118465e+00 1.0439742077114e+00 9.8797067191148e-01 9.1830017102609e-01 8.3798475086896e-01 7.4105581225064e-01 6.1914413564857e-01 5.0556880615639e-01 4.4006264885384e-01 4.2250264221194e-01 3.9437284376538e-01 3.4023451507132e-01 2.7356357569382e-01 2.0835353627802e-01 1.3563895509022e-01 6.3352506971190e-02 1.2850142553837e-02 -7.8602472854190e-03 -7.7747053573879e-03 + -5.4850733599422e-01 -5.4850733599421e-01 -5.4850733525878e-01 -5.4857576193715e-01 -5.4966012190252e-01 -5.5118515382020e-01 -5.5189426283926e-01 -5.5038591913103e-01 -5.4693395231186e-01 -5.4067029735513e-01 -5.3641032290864e-01 -5.3401979315220e-01 -5.1480945206791e-01 -4.6301735808721e-01 -3.8207499594839e-01 -3.0908557952239e-01 -2.2770906371321e-01 -1.4318468679311e-01 -5.2381529180541e-02 -2.2649456216061e-02 -6.0375155313321e-01 -6.1669671429274e-01 -6.4365909683047e-01 -6.6667572524825e-01 -6.8218146084485e-01 -6.9104429849845e-01 -6.8968037278821e-01 -6.8226366319467e-01 -6.7518021546318e-01 -6.5675834136116e-01 -6.0059486314967e-01 -5.0909557958199e-01 -4.1780423326111e-01 -3.4858637931189e-01 -2.9492732628556e-01 -2.3330557634093e-01 -1.5827223297617e-01 -7.3495818937161e-02 -5.7869808568635e-03 1.5044235797942e-02 -6.0922803179090e-01 -6.1508676137699e-01 -6.2894159098407e-01 -6.4541031377370e-01 -6.6110844500314e-01 -6.7542595803841e-01 -6.8733210406536e-01 -6.9124549451330e-01 -6.8230331975565e-01 -6.5092289832697e-01 -5.8419684590865e-01 -4.9309473766499e-01 -4.0077259611619e-01 -3.3323391953155e-01 -2.7333300345211e-01 -2.0390382205856e-01 -1.1997884183756e-01 -5.4200343678865e-02 -1.0193416394581e-02 3.6112409465768e-03 -5.9851025914436e-01 -5.9750084197415e-01 -5.9273189922118e-01 -5.8251624246173e-01 -5.6524289518834e-01 -5.3966350836824e-01 -5.0231339942758e-01 -4.5190859254076e-01 -4.0464592863578e-01 -3.8307367085785e-01 -3.8783227436095e-01 -3.7247844375397e-01 -3.2715179972730e-01 -2.6678673254937e-01 -2.0534875332403e-01 -1.3480775819647e-01 -6.3267741108643e-02 -1.2849427667617e-02 7.8600821198604e-03 7.7745453890706e-03 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 + 5.4850733599422e-01 5.4850733599421e-01 5.4850733525878e-01 5.4857576193715e-01 5.4966012190252e-01 5.5118515382020e-01 5.5189426283926e-01 5.5038591913103e-01 5.4693395231186e-01 5.4067029735513e-01 5.3641032290864e-01 5.3401979315220e-01 5.1480945206791e-01 4.6301735808721e-01 3.8207499594839e-01 3.0908557952239e-01 2.2770906371321e-01 1.4318468679311e-01 5.2381529180541e-02 2.2649456216061e-02 6.0375155313321e-01 6.1669671429274e-01 6.4365909683047e-01 6.6667572524825e-01 6.8218146084485e-01 6.9104429849845e-01 6.8968037278821e-01 6.8226366319467e-01 6.7518021546318e-01 6.5675834136116e-01 6.0059486314967e-01 5.0909557958199e-01 4.1780423326111e-01 3.4858637931189e-01 2.9492732628556e-01 2.3330557634093e-01 1.5827223297617e-01 7.3495818937161e-02 5.7869808568635e-03 -1.5044235797942e-02 6.0922803179090e-01 6.1508676137699e-01 6.2894159098407e-01 6.4541031377370e-01 6.6110844500314e-01 6.7542595803841e-01 6.8733210406536e-01 6.9124549451330e-01 6.8230331975565e-01 6.5092289832697e-01 5.8419684590865e-01 4.9309473766499e-01 4.0077259611619e-01 3.3323391953155e-01 2.7333300345211e-01 2.0390382205856e-01 1.1997884183756e-01 5.4200343678865e-02 1.0193416394581e-02 -3.6112409465768e-03 5.9851025914436e-01 5.9750084197415e-01 5.9273189922118e-01 5.8251624246173e-01 5.6524289518834e-01 5.3966350836824e-01 5.0231339942758e-01 4.5190859254076e-01 4.0464592863578e-01 3.8307367085785e-01 3.8783227436095e-01 3.7247844375397e-01 3.2715179972730e-01 2.6678673254937e-01 2.0534875332403e-01 1.3480775819647e-01 6.3267741108643e-02 1.2849427667617e-02 -7.8600821198604e-03 -7.7745453890706e-03 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_sphere_gmm_letter_S.txt b/data/data_sphere_gmm_letter_S.txt new file mode 100644 index 0000000..0fbf573 --- /dev/null +++ b/data/data_sphere_gmm_letter_S.txt @@ -0,0 +1,3 @@ + 3.8445830000710e-01 3.8233372922730e-01 3.7522300627103e-01 3.5937497102965e-01 3.2680375438715e-01 2.6905144263330e-01 1.9343787707607e-01 1.1051044071083e-01 2.4879333866511e-02 -5.7566895817217e-02 -1.4502597661643e-01 -2.2703087050979e-01 -2.9565536679915e-01 -3.4680051635667e-01 -3.8436935915428e-01 -4.0124539085667e-01 -3.9894295266230e-01 -3.8433445941090e-01 -3.6360209404038e-01 -3.3060837184709e-01 -2.7324887885197e-01 -1.8992099879594e-01 -7.8507365302685e-02 5.8752729875911e-02 1.9662304825552e-01 3.0383423576741e-01 3.7815807523362e-01 4.1864968396805e-01 4.3783600706438e-01 4.4327221634657e-01 4.3390257277911e-01 4.0794641198077e-01 3.6339330957708e-01 3.0027039179064e-01 2.2647505972994e-01 1.3773378078545e-01 3.7954346258595e-02 -6.9334019502254e-02 -1.7599853810827e-01 -2.6689137345134e-01 -3.3414388910187e-01 -3.7542606323971e-01 -3.9165971051810e-01 -3.9451112831121e-01 -3.9797522408396e-01 -4.0045418205124e-01 -4.0109257741915e-01 -4.0108911153641e-01 -4.0108938354105e-01 -4.0108937578136e-01 3.8400467437447e-01 3.7937858856609e-01 3.6588361454842e-01 3.4356469478266e-01 3.1558190929485e-01 2.8020697261990e-01 2.2967825718429e-01 1.6420316368210e-01 8.4388980241950e-02 -1.1727057341727e-02 -1.1039856637085e-01 -2.1174278752791e-01 -3.0743402413700e-01 -3.7686447291417e-01 -4.1478922478686e-01 -4.2857686855466e-01 -4.2148948454273e-01 -4.0275982371631e-01 -3.7271993860907e-01 -3.1780628976241e-01 -2.2657067449428e-01 -1.0946654062755e-01 3.4434516445830e-02 1.8368759647152e-01 2.9575887429345e-01 3.6140983685251e-01 4.0564473491016e-01 4.4463532431199e-01 4.6726859993250e-01 4.6877376455335e-01 4.5140057063054e-01 4.1873392359794e-01 3.7960411684622e-01 3.2555925585554e-01 2.4499071775496e-01 1.4582565635294e-01 3.2662423145975e-02 -9.1479888752470e-02 -1.9866985523679e-01 -2.8105423297437e-01 -3.4650897581007e-01 -3.8707726262514e-01 -4.0591572231891e-01 -4.1180875339503e-01 -4.1227113851752e-01 -4.1227833804646e-01 -4.1227827185849e-01 -4.1227827008680e-01 -4.1227827020986e-01 -4.1227827020633e-01 4.2867019409810e-01 4.2280610543795e-01 4.1027202591151e-01 3.8846696057870e-01 3.5523854116867e-01 3.0456725247775e-01 2.3103460083333e-01 1.2665585473524e-01 7.6545862764348e-03 -1.0810055452683e-01 -2.0021176519703e-01 -2.6951980007035e-01 -3.3576171281015e-01 -3.8933703871338e-01 -4.1771545975745e-01 -4.1972478622108e-01 -4.0433219073161e-01 -3.7571772414311e-01 -3.1907525477326e-01 -2.1846218349414e-01 -8.2982164987598e-02 4.8772439825175e-02 1.6134285554261e-01 2.6248601090555e-01 3.4392086272828e-01 3.9477043931950e-01 4.1686738357272e-01 4.2368159858614e-01 4.2097145770494e-01 4.0717383011746e-01 3.8764201065456e-01 3.5820582241656e-01 3.1455585718722e-01 2.6223307065392e-01 1.9935474259897e-01 1.2859733122714e-01 5.8884945971034e-02 -1.7133786846991e-02 -1.0047259436955e-01 -1.8023850850777e-01 -2.5017345213555e-01 -3.1669437623874e-01 -3.6854608602121e-01 -3.9171224713267e-01 -3.9521134578294e-01 -3.9526868161503e-01 -3.9526819064713e-01 -3.9526810953887e-01 -3.9526810842716e-01 -3.9526810855773e-01 3.8953816402665e-01 3.8962724615932e-01 3.8498571311404e-01 3.6809307940056e-01 3.2855360510365e-01 2.6256223646505e-01 1.8285510841635e-01 8.2213237378969e-02 -4.1066527304997e-02 -1.5937287584103e-01 -2.6091968688273e-01 -3.4458274107914e-01 -4.0139702129225e-01 -4.2813663041730e-01 -4.3549836028509e-01 -4.3217367072332e-01 -4.1794067695821e-01 -3.8431661278089e-01 -3.1150972363485e-01 -1.8975588212028e-01 -5.3403262064950e-02 6.8813143171995e-02 1.7622830837017e-01 2.6249990746376e-01 3.3316034083261e-01 3.8952017503995e-01 4.2428018130003e-01 4.3486517171213e-01 4.2165303062691e-01 3.9523202848304e-01 3.6345296730639e-01 3.2651580751060e-01 2.7795343826480e-01 2.1514453911551e-01 1.4841307301139e-01 8.2806780805237e-02 1.5954521891403e-02 -4.4393945507976e-02 -9.5368911966162e-02 -1.4333828688706e-01 -1.9747237573545e-01 -2.4855996966871e-01 -2.8610549937908e-01 -3.1527062784079e-01 -3.3870863214943e-01 -3.5441314915809e-01 -3.6114436476983e-01 -3.6172511342922e-01 -3.6173515417657e-01 -3.6173565946780e-01 4.3806161724625e-01 4.3803512300298e-01 4.3753587609242e-01 4.3132339862911e-01 4.1209624730858e-01 3.7280301218877e-01 3.1560638440742e-01 2.4252221867525e-01 1.4165215628773e-01 1.1485274090815e-02 -1.2278812353586e-01 -2.4140637476897e-01 -3.4202601897103e-01 -4.1649824542929e-01 -4.6581773408543e-01 -4.9529763257519e-01 -4.9741223795630e-01 -4.8112897437364e-01 -4.5289890647610e-01 -4.1334808959875e-01 -3.4013882362520e-01 -2.1285263025739e-01 -5.2012693347768e-02 8.9562248104749e-02 1.9007802598330e-01 2.5544213426088e-01 3.1125215815549e-01 3.6209224247269e-01 3.9725267243385e-01 4.1424591001864e-01 4.0860865214288e-01 3.8497941742439e-01 3.5335415535251e-01 3.1239935578330e-01 2.6417579151972e-01 2.0616124993022e-01 1.2943340883802e-01 4.0106939223899e-02 -4.8267075321466e-02 -1.3580644762165e-01 -2.2363814352540e-01 -2.8411165635747e-01 -3.0870078967032e-01 -3.2215213929561e-01 -3.3686796511910e-01 -3.4751497176035e-01 -3.5062682612029e-01 -3.5067922004188e-01 -3.5068167172499e-01 -3.5068189068507e-01 4.1821493624772e-01 4.1575667639217e-01 4.0755492494765e-01 3.8948876990777e-01 3.5288471387649e-01 2.8886644001772e-01 2.0650966465277e-01 1.1746027331903e-01 2.6347543210357e-02 -6.0798478796806e-02 -1.5299827599443e-01 -2.3939950081284e-01 -3.1128873039488e-01 -3.6432161156170e-01 -4.0238204671543e-01 -4.1782086815257e-01 -4.1294972219688e-01 -3.9586608236760e-01 -3.7309567814356e-01 -3.3771533926051e-01 -2.7733599560880e-01 -1.9142097595851e-01 -7.8687808932782e-02 5.8819572805562e-02 1.9792100362020e-01 3.0877169088765e-01 3.8826578584113e-01 4.3320442721912e-01 4.5562660922214e-01 4.6377209104199e-01 4.5638266210007e-01 4.3114933484924e-01 3.8524324086848e-01 3.1832912935712e-01 2.3962438010228e-01 1.4535053658773e-01 3.9999140399993e-02 -7.3122230891538e-02 -1.8622191080361e-01 -2.8370302120307e-01 -3.5678393005929e-01 -4.0223441917993e-01 -4.2024210879117e-01 -4.2342717834039e-01 -4.2739449733861e-01 -4.3023654476059e-01 -4.3096906592807e-01 -4.3096508836495e-01 -4.3096540052640e-01 -4.3096539162113e-01 4.2076502732240e-01 4.1528567018434e-01 3.9953444287229e-01 3.7384873996613e-01 3.4205463430429e-01 3.0237913457777e-01 2.4655392303753e-01 1.7529852293974e-01 8.9639517343822e-02 -1.2407536217271e-02 -1.1665967803831e-01 -2.2405495266221e-01 -3.2617477073421e-01 -4.0038634094876e-01 -4.3938660247031e-01 -4.5078503187139e-01 -4.3971744382551e-01 -4.1728362597116e-01 -3.8347148086958e-01 -3.2407904413816e-01 -2.2875604974594e-01 -1.0973019447792e-01 3.4447367536071e-02 1.8474391536998e-01 3.0025131003423e-01 3.6983547441641e-01 4.1798558591014e-01 4.6190666116526e-01 4.8908938647148e-01 4.9339899802909e-01 4.7754535071086e-01 4.4550547806775e-01 4.0585299860294e-01 3.4965019774804e-01 2.6425550197232e-01 1.5767781964112e-01 3.5323062630201e-02 -9.8936412919852e-02 -2.1495450235764e-01 -3.0367995354612e-01 -3.7444689964689e-01 -4.1886234803981e-01 -4.3946891182255e-01 -4.4577308933331e-01 -4.4625810626465e-01 -4.4626601245500e-01 -4.4626593988150e-01 -4.4626593793809e-01 -4.4626593807309e-01 -4.4626593806922e-01 4.7176684881603e-01 4.6480878594019e-01 4.5021569807815e-01 4.2500331946873e-01 3.8676307520964e-01 3.2937152465229e-01 2.4789777017021e-01 1.3480042156510e-01 8.0951421925927e-03 -1.1385904398104e-01 -2.1033418896839e-01 -2.8259158111028e-01 -3.5166162889466e-01 -4.0732097470596e-01 -4.3556906402532e-01 -4.3550123352679e-01 -4.1743929786804e-01 -3.8581714573956e-01 -3.2509531967635e-01 -2.2037716469033e-01 -8.3105786706417e-02 4.8797980868350e-02 1.6205273516673e-01 2.6561184611029e-01 3.5122535763010e-01 4.0622849729084e-01 4.3081404961487e-01 4.3908262984580e-01 4.3789050605557e-01 4.2503496645809e-01 4.0548318718848e-01 3.7571812080183e-01 3.3104906194338e-01 2.7696838068116e-01 2.1130101853433e-01 1.3671268733926e-01 6.2732721766741e-02 -1.8306254069969e-02 -1.0763191002489e-01 -1.9344750025824e-01 -2.6897885895806e-01 -3.4150556456001e-01 -3.9867075258257e-01 -4.2442609637230e-01 -4.2834906483009e-01 -4.2841597227205e-01 -4.2841539670735e-01 -4.2841530169576e-01 -4.2841530039351e-01 -4.2841530054645e-01 4.2586520947177e-01 4.2596910798811e-01 4.2056175584528e-01 4.0099218636473e-01 3.5592501976011e-01 2.8227349843257e-01 1.9521898101869e-01 8.7165680199861e-02 -4.3313838272691e-02 -1.6772811040044e-01 -2.7427706112536e-01 -3.6193678619605e-01 -4.2069355069332e-01 -4.4691776273366e-01 -4.5310613285777e-01 -4.4857720897284e-01 -4.3241756697281e-01 -3.9533891225135e-01 -3.1731126787131e-01 -1.9114376687239e-01 -5.3470912361860e-02 6.8892373347778e-02 1.7716276356448e-01 2.6562103097217e-01 3.3982393123422e-01 4.0088113126316e-01 4.4035082753661e-01 4.5453640085290e-01 4.4337959587593e-01 4.1840454975673e-01 3.8786008466962e-01 3.5100426144976e-01 2.9999383301473e-01 2.3215979671914e-01 1.5984456349543e-01 8.8973567141069e-02 1.7099247848989e-02 -4.7451364824913e-02 -1.0169213547843e-01 -1.5268403249139e-01 -2.1043027829947e-01 -2.6512726517488e-01 -3.0545009932873e-01 -3.3690024090196e-01 -3.6237600974184e-01 -3.7955852059168e-01 -3.8696822446541e-01 -3.8760234907966e-01 -3.8761329261443e-01 -3.8761384335155e-01 4.8961748633880e-01 4.8958441601168e-01 4.8895988721823e-01 4.8118218675318e-01 4.5775202606030e-01 4.1114275780905e-01 3.4523741748992e-01 2.6293334741934e-01 1.5201964255072e-01 1.2231772488114e-02 -1.3045831778203e-01 -2.5654584890334e-01 -3.6402641090980e-01 -4.4365276581437e-01 -4.9455953159288e-01 -5.2349379882231e-01 -5.2313277615849e-01 -5.0298260045274e-01 -4.7036957004145e-01 -4.2628871511669e-01 -3.4716902267753e-01 -2.1455235213860e-01 -5.2047423534986e-02 8.9690732752662e-02 1.9124188223674e-01 2.5832736684970e-01 3.1670132406138e-01 3.7129437990946e-01 4.1074843258245e-01 4.3214928306579e-01 4.2985437180128e-01 4.0812913860421e-01 3.7702998486244e-01 3.3425123662639e-01 2.8243824129943e-01 2.2015288649006e-01 1.3808631106537e-01 4.2747494828432e-02 -5.1424893212269e-02 -1.4480623178131e-01 -2.3915723500860e-01 -3.0489346362799e-01 -3.3180161040377e-01 -3.4638133754368e-01 -3.6232147018240e-01 -3.7393277938168e-01 -3.7734874657218e-01 -3.7741022249587e-01 -3.7741321202665e-01 -3.7741347905282e-01 + 5.2130129343351e-01 5.2148426025531e-01 5.2214590193221e-01 5.2467604220783e-01 5.3127187067372e-01 5.4059652364164e-01 5.4984768486090e-01 5.5476075096601e-01 5.5010853085879e-01 5.3597789659119e-01 5.1417516224050e-01 4.8132147043658e-01 4.3428356401104e-01 3.8085969431486e-01 3.1733675271782e-01 2.4734496811770e-01 1.8096706246545e-01 1.3598692823551e-01 1.1796319665204e-01 1.1169872472108e-01 1.0748255171084e-01 1.0159395016026e-01 8.6844383364695e-02 5.7908431474723e-02 1.5789184846482e-02 -3.2150191795151e-02 -7.9616060274394e-02 -1.2218305338935e-01 -1.6498615963051e-01 -2.2153082160789e-01 -2.8794456696679e-01 -3.5699367947850e-01 -4.1956076244578e-01 -4.6688833117637e-01 -4.9777590437550e-01 -5.1759460786228e-01 -5.2826482420334e-01 -5.2830739272238e-01 -5.1789468507324e-01 -4.9917664300566e-01 -4.7837723951669e-01 -4.6325403001576e-01 -4.5665101341670e-01 -4.5560404835266e-01 -4.5536337479450e-01 -4.5517253886423e-01 -4.5512327581114e-01 -4.5512354364944e-01 -4.5512352263032e-01 -4.5512352322995e-01 5.4869366039579e-01 5.4837614097603e-01 5.4870664867902e-01 5.5027948234368e-01 5.5243879343447e-01 5.5487360617250e-01 5.5784045218415e-01 5.5925505769721e-01 5.5675993549491e-01 5.4661085336822e-01 5.3005105213609e-01 5.0459285397537e-01 4.6601163863552e-01 4.1942583546731e-01 3.6392672664416e-01 2.9588453614795e-01 2.3188992102115e-01 1.8546768343387e-01 1.4614192334814e-01 1.0646628699404e-01 7.1115666309590e-02 4.8731039252620e-02 3.2422703296200e-02 1.5247456948596e-02 -5.2499179615625e-03 -2.8633676940768e-02 -6.1578518541218e-02 -1.1205672200590e-01 -1.7127831019643e-01 -2.3388927984909e-01 -3.0771461666743e-01 -3.8612318765188e-01 -4.4963554719608e-01 -5.0995899820940e-01 -5.6960352160385e-01 -6.1114181270717e-01 -6.2801119285051e-01 -6.2232977285853e-01 -5.9829912574472e-01 -5.5925924489164e-01 -5.2170357127809e-01 -4.9816648771773e-01 -4.8510407441656e-01 -4.7937299868955e-01 -4.7882449776107e-01 -4.7881940032233e-01 -4.7881944826717e-01 -4.7881944954288e-01 -4.7881944945436e-01 -4.7881944945690e-01 5.3078364070144e-01 5.3155906465919e-01 5.3479364429030e-01 5.3999665869082e-01 5.4485279223511e-01 5.5012298918617e-01 5.5551752402219e-01 5.5673941153897e-01 5.4478401060902e-01 5.1584716854138e-01 4.7477000009290e-01 4.2824849613624e-01 3.7147672324754e-01 3.0614253440370e-01 2.3352775936427e-01 1.6719875219712e-01 1.2228161102913e-01 9.4685113261112e-02 7.6294840429224e-02 6.0362091616340e-02 4.4905851480530e-02 2.7547729522515e-02 7.5037580019527e-03 -1.7444108710056e-02 -4.6031066072939e-02 -7.3142305227923e-02 -9.9392762852751e-02 -1.3615356687930e-01 -1.9891905280547e-01 -2.6186774008744e-01 -3.0702154990494e-01 -3.5988807620854e-01 -4.1840806968493e-01 -4.7123888765347e-01 -5.1716882980571e-01 -5.5169449368384e-01 -5.7177579738722e-01 -5.8566763175254e-01 -5.8722753942648e-01 -5.7505554532809e-01 -5.5511831593738e-01 -5.3200807574485e-01 -5.1060912241527e-01 -4.9992798036604e-01 -4.9844373258065e-01 -4.9844438421515e-01 -4.9844435322801e-01 -4.9844434880686e-01 -4.9844434874643e-01 -4.9844434875352e-01 5.3654861063424e-01 5.3654034670153e-01 5.3696372380578e-01 5.3844404116713e-01 5.4279894714577e-01 5.4901479188110e-01 5.5360577357441e-01 5.4937268968104e-01 5.3161642478101e-01 4.9857454591519e-01 4.4755652731921e-01 3.8191349817773e-01 3.0486805524292e-01 2.2598478987743e-01 1.6819470855527e-01 1.3839285072402e-01 1.2201831086564e-01 1.0828662935695e-01 9.6293544172262e-02 8.3796566514039e-02 6.8722977338815e-02 4.6385440500563e-02 1.7539336762136e-02 -1.3872918916601e-02 -5.2538213124013e-02 -1.0097222368808e-01 -1.5977904600086e-01 -2.2741367883543e-01 -3.0349981559415e-01 -3.8125701653468e-01 -4.5375058590004e-01 -5.1327360140218e-01 -5.5659467596244e-01 -5.8305746962648e-01 -5.9673906604372e-01 -6.0090949499454e-01 -5.9723249191714e-01 -5.8579175592598e-01 -5.7037903656621e-01 -5.5609755011903e-01 -5.4088605614532e-01 -5.2355861192370e-01 -5.0798620847597e-01 -4.9460649646544e-01 -4.8429968240170e-01 -4.7756373589320e-01 -4.7489244853416e-01 -4.7459099793537e-01 -4.7458553586459e-01 -4.7458526114606e-01 5.7500953327588e-01 5.7500794525358e-01 5.7496851199013e-01 5.7428921007051e-01 5.7480601439722e-01 5.7835130334549e-01 5.8505894188964e-01 5.8908152884760e-01 5.8542281921409e-01 5.7340651644106e-01 5.5053767243605e-01 5.1083033961695e-01 4.5727387916701e-01 3.9535443135125e-01 3.1288814138215e-01 2.2083298697728e-01 1.5267315064052e-01 1.0106911996729e-01 6.1902217331983e-02 4.4423575186018e-02 4.0623033038410e-02 3.9853082558218e-02 3.5969667642743e-02 2.3512978915033e-02 2.8255742052096e-03 -2.2244660342382e-02 -5.7921860927031e-02 -1.0666231982286e-01 -1.6862083589526e-01 -2.4432912788392e-01 -3.2414010376193e-01 -3.9987230446997e-01 -4.6097782128319e-01 -5.0197365320407e-01 -5.2574487497590e-01 -5.4631564165104e-01 -5.6566384495719e-01 -5.7520977336500e-01 -5.7306375227734e-01 -5.6199930186831e-01 -5.4522628335784e-01 -5.3093450104725e-01 -5.2354369915196e-01 -5.1684117285954e-01 -5.0874354532314e-01 -5.0335471256569e-01 -5.0195598095608e-01 -5.0197684621432e-01 -5.0197909634639e-01 -5.0197929764953e-01 5.6707317073171e-01 5.6707150392606e-01 5.6713775626006e-01 5.6864123200930e-01 5.7367064960712e-01 5.8041016893247e-01 5.8700427613807e-01 5.8964880617610e-01 5.8257220088588e-01 5.6606562363417e-01 5.4244015601438e-01 5.0754383971783e-01 4.5724716833636e-01 4.0010153118970e-01 3.3220809363571e-01 2.5756280736699e-01 1.8732076271354e-01 1.4006709837132e-01 1.2104319411864e-01 1.1409987140795e-01 1.0909022066088e-01 1.0239632907603e-01 8.7043989041531e-02 5.7974313846818e-02 1.5893412999576e-02 -3.2672648155918e-02 -8.1744101825449e-02 -1.2643086018299e-01 -1.7169004665708e-01 -2.3177588979999e-01 -3.0286270756097e-01 -3.7729854444655e-01 -4.4478790227034e-01 -4.9496773585989e-01 -5.2667716550364e-01 -5.4621788176196e-01 -5.5672514361651e-01 -5.5717258900728e-01 -5.4797806212484e-01 -5.3062007926057e-01 -5.1078986368547e-01 -4.9633398940972e-01 -4.8997632308414e-01 -4.8899795922169e-01 -4.8902491637432e-01 -4.8902438573058e-01 -4.8902439013095e-01 -4.8902439025212e-01 -4.8902439024366e-01 -4.8902439024390e-01 6.0121951219512e-01 6.0027835012799e-01 5.9917196743250e-01 5.9878472447099e-01 5.9878036065490e-01 5.9877953523333e-01 5.9882791519388e-01 5.9704443789341e-01 5.9140058039630e-01 5.7832871131171e-01 5.6011221086284e-01 5.3393331282296e-01 4.9441905403313e-01 4.4560415648513e-01 3.8550791200153e-01 3.1121679643494e-01 2.4191835635221e-01 1.9215577842309e-01 1.5035755793634e-01 1.0856768299885e-01 7.1801608643060e-02 4.8848409602117e-02 3.2434803570254e-02 1.5335139390076e-02 -5.3296617026186e-03 -2.9301220984742e-02 -6.3451909853163e-02 -1.1640943373754e-01 -1.7927676642930e-01 -2.4617575695014e-01 -3.2553721482905e-01 -4.1080979021194e-01 -4.8072696530298e-01 -5.4769527009373e-01 -6.1439415299472e-01 -6.6081313075638e-01 -6.7916818658508e-01 -6.7305586199881e-01 -6.4734073864494e-01 -6.0428131507423e-01 -5.6376688177587e-01 -5.3907373258002e-01 -5.2520301132125e-01 -5.1890976286225e-01 -5.1829801710677e-01 -5.1829263084849e-01 -5.1829268166679e-01 -5.1829268301788e-01 -5.1829268292414e-01 -5.1829268292683e-01 5.8414634146341e-01 5.8436555272498e-01 5.8686061609242e-01 5.9078479184879e-01 5.9320405034925e-01 5.9492557463236e-01 5.9606463706674e-01 5.9254037276239e-01 5.7613878410486e-01 5.4332621796008e-01 4.9877370002602e-01 4.4901866059434e-01 3.8906791516025e-01 3.2028361833837e-01 2.4350898487044e-01 1.7348335198778e-01 1.2624557485223e-01 9.7230281658244e-02 7.7734312416737e-02 6.0891209601701e-02 4.4972749452472e-02 2.7562155656447e-02 7.5367731912031e-03 -1.7651843243920e-02 -4.7008714491205e-02 -7.5265232098800e-02 -1.0271803540978e-01 -1.4110281496234e-01 -2.0691370662506e-01 -2.7335486195764e-01 -3.2115217950910e-01 -3.7748261817702e-01 -4.4034658968787e-01 -4.9771858027634e-01 -5.4816002402300e-01 -5.8651012507071e-01 -6.0913789456635e-01 -6.2574494261915e-01 -6.2907126151449e-01 -6.1719916944699e-01 -5.9684626779126e-01 -5.7368785772427e-01 -5.5234590958893e-01 -5.4167946682091e-01 -5.4023729075482e-01 -5.4024400469719e-01 -5.4024391635236e-01 -5.4024390260515e-01 -5.4024390241693e-01 -5.4024390243902e-01 5.8658536585366e-01 5.8658529437294e-01 5.8658386224865e-01 5.8656863001685e-01 5.8801888942195e-01 5.9023082710579e-01 5.9103820472533e-01 5.8246634855818e-01 5.6070842501623e-01 5.2471266543200e-01 4.7046848195765e-01 4.0114761320443e-01 3.1952410668172e-01 2.3589809777644e-01 1.7499504225626e-01 1.4364567516497e-01 1.2624485727176e-01 1.1139231778604e-01 9.8086911164733e-02 8.4409459119233e-02 6.8810034376939e-02 4.6438847835779e-02 1.7632339552061e-02 -1.4037867901838e-02 -5.3589037876491e-02 -1.0391723420766e-01 -1.6583106689995e-01 -2.3770079051307e-01 -3.1913828625039e-01 -4.0361018047309e-01 -4.8422149905772e-01 -5.5176875740076e-01 -6.0073000470853e-01 -6.2917006483435e-01 -6.4270278619664e-01 -6.4566042513298e-01 -6.4008351188910e-01 -6.2613534354309e-01 -6.0819674949346e-01 -5.9235545683377e-01 -5.7637835620838e-01 -5.5845542274204e-01 -5.4233294422288e-01 -5.2853971507625e-01 -5.1814028273876e-01 -5.1144655754012e-01 -5.0884993799755e-01 -5.0854247831428e-01 -5.0853686753891e-01 -5.0853658536585e-01 6.4268292682927e-01 6.4267661266317e-01 6.4254511261459e-01 6.4067411786325e-01 6.3848826433245e-01 6.3783001227339e-01 6.3998780809397e-01 6.3865974478077e-01 6.2826977047347e-01 6.1067572239468e-01 5.8492805780737e-01 5.4286637313548e-01 4.8668744423818e-01 4.2113043421147e-01 3.3219390615674e-01 2.3340450600774e-01 1.6056768017529e-01 1.0565983653926e-01 6.4290107427305e-02 4.5814337270363e-02 4.1462654947270e-02 4.0171326952830e-02 3.5993685497059e-02 2.3546710279321e-02 2.8428753224286e-03 -2.2495914972449e-02 -5.8935912786590e-02 -1.0937301398088e-01 -1.7434934702989e-01 -2.5488883509405e-01 -3.4099385793099e-01 -4.2391757010505e-01 -4.9186477178098e-01 -5.3708598059245e-01 -5.6208957303076e-01 -5.8339268647649e-01 -6.0347969163777e-01 -6.1308036185250e-01 -6.1055578918780e-01 -5.9924254402119e-01 -5.8306158478312e-01 -5.6977056506340e-01 -5.6272173025824e-01 -5.5571301542239e-01 -5.4718384760071e-01 -5.4161933148120e-01 -5.4021097684979e-01 -5.4024071684343e-01 -5.4024364087924e-01 -5.4024390243902e-01 + 7.6186401478230e-01 7.6280737135998e-01 7.6587946353218e-01 7.7172837250587e-01 7.8163258987156e-01 7.9709893980830e-01 8.1255726639137e-01 8.2463807314574e-01 8.3472248263884e-01 8.4226702824677e-01 8.4533506294333e-01 8.4663252118752e-01 8.5087348654940e-01 8.5713201731188e-01 8.6692420725104e-01 8.8194251687008e-01 8.9894128997600e-01 9.1312352869609e-01 9.2405530215734e-01 9.3713472849975e-01 9.5591974102634e-01 9.7652889537749e-01 9.9312368145727e-01 9.9659155640426e-01 9.8035201766334e-01 9.5218229470158e-01 9.2231109343973e-01 8.9989096204924e-01 8.8378685102704e-01 8.6858150872151e-01 8.5370749305016e-01 8.4031853351239e-01 8.3181372263899e-01 8.3177700017808e-01 8.3721454618483e-01 8.4446742242815e-01 8.4823094915801e-01 8.4621752081515e-01 8.3714372108775e-01 8.2437350385299e-01 8.1209794858026e-01 8.0277703922976e-01 7.9879441854734e-01 7.9798867207704e-01 7.9640436834003e-01 7.9527002203123e-01 7.9497644503105e-01 7.9497804034005e-01 7.9497791513930e-01 7.9497791871100e-01 7.4261408355890e-01 7.4522177541041e-01 7.5169820692910e-01 7.6102285892768e-01 7.7150465846584e-01 7.8332581578058e-01 7.9753490712556e-01 8.1257067475812e-01 8.2637574640198e-01 8.3730463459017e-01 8.4074849906062e-01 8.3698927331651e-01 8.2964900618223e-01 8.2586629523045e-01 8.3397076485617e-01 8.5368273322610e-01 8.7668334017974e-01 8.9631817051853e-01 9.1636367540587e-01 9.4215927099464e-01 9.7139502338881e-01 9.9279522676955e-01 9.9888088999045e-01 9.8286641104431e-01 9.5524820158850e-01 9.3196729683562e-01 9.1195418475597e-01 8.8867469831613e-01 8.6736601038626e-01 8.5179044514373e-01 8.3758536252948e-01 8.2193113165631e-01 8.0853484103722e-01 7.9621164967115e-01 7.8455807713030e-01 7.7797208350315e-01 7.7751855782914e-01 7.7739120381420e-01 7.7625282270230e-01 7.7989590018824e-01 7.7958765600716e-01 7.7588745528821e-01 7.7453628924587e-01 7.7499359917009e-01 7.7508683945048e-01 7.7508615898661e-01 7.7508616457430e-01 7.7508616472860e-01 7.7508616471782e-01 7.7508616471813e-01 7.3110231257712e-01 7.3394819843300e-01 7.3869657017016e-01 7.4665723671675e-01 7.5956633262801e-01 7.7756252834549e-01 7.9876360315305e-01 8.2097473901486e-01 8.3854146533948e-01 8.4983290641092e-01 8.5703482781534e-01 8.6253249383840e-01 8.6560332502600e-01 8.6873092434584e-01 8.7805385955869e-01 8.9211864743172e-01 9.0640095274790e-01 9.2188444020466e-01 9.4465341745810e-01 9.7397674113845e-01 9.9553876107200e-01 9.9842995333256e-01 9.8686988837496e-01 9.6477810772747e-01 9.3786970370965e-01 9.1586380178793e-01 9.0351683061564e-01 8.9552002168882e-01 8.8499392214227e-01 8.7500557642164e-01 8.6917860044393e-01 8.6149240355896e-01 8.5205005717490e-01 8.4212096958723e-01 8.3234253050093e-01 8.2407275894801e-01 8.1829395736508e-01 8.1037019840666e-01 8.0316192310129e-01 7.9801328299616e-01 7.9325714567057e-01 7.8528471231842e-01 7.7682179847424e-01 7.7242056542624e-01 7.7159693986920e-01 7.7156714884622e-01 7.7156742038376e-01 7.7156746479104e-01 7.7156746539960e-01 7.7156746532813e-01 7.4858239839927e-01 7.4854195968677e-01 7.5063703613311e-01 7.5801418154876e-01 7.7293067706673e-01 7.9350099576385e-01 8.1245594144614e-01 8.3152307931427e-01 8.4598907631137e-01 8.5207024863659e-01 8.5534441709231e-01 8.5755747006252e-01 8.6367580734331e-01 8.7500280024636e-01 8.8433688049465e-01 8.9110792679788e-01 9.0024281299948e-01 9.1682863559290e-01 9.4535138727972e-01 9.7824886437001e-01 9.9620542258437e-01 9.9655062201393e-01 9.8419304762579e-01 9.6483228630796e-01 9.4140529181540e-01 9.1546635289361e-01 8.9132316485945e-01 8.7130666307008e-01 8.5445689399610e-01 8.3572407587927e-01 8.1364141140403e-01 7.9368610769582e-01 7.8290756341157e-01 7.8342632991337e-01 7.8859117850543e-01 7.9501623623551e-01 8.0190947358768e-01 8.0924483087098e-01 8.1582628376155e-01 8.1866333145189e-01 8.1758604139807e-01 8.1492596066074e-01 8.1246147922425e-01 8.0991903599993e-01 8.0667854820435e-01 8.0394290709203e-01 8.0252844816880e-01 8.0244521744063e-01 8.0244392164248e-01 8.0244385633658e-01 6.9098918670081e-01 6.9100730380440e-01 6.9135632444630e-01 6.9581033981368e-01 7.0694747242420e-01 7.2562227365314e-01 7.4706000069356e-01 7.7082159143307e-01 7.9825734532322e-01 8.1919048784882e-01 8.2573079629334e-01 8.2509110184738e-01 8.2092557627253e-01 8.1867214754458e-01 8.2771664813144e-01 8.4018631685365e-01 8.5397422361849e-01 8.7080419326460e-01 8.8941030801432e-01 9.0948881400090e-01 9.3949739214626e-01 9.7627121723582e-01 9.9799842822541e-01 9.9570364242427e-01 9.8176492103186e-01 9.6656840995891e-01 9.4856056847747e-01 9.2601963125579e-01 9.0208498931428e-01 8.7675743698033e-01 8.5321284714143e-01 8.3180105089946e-01 8.1402720420150e-01 8.0649184372512e-01 8.0858115091282e-01 8.1181078997179e-01 8.1441476360931e-01 8.1702212335497e-01 8.1808815250297e-01 8.1591261387720e-01 8.0790734660375e-01 7.9836653381735e-01 7.9410693079409e-01 7.9315395805886e-01 7.9227519156450e-01 7.9111780269459e-01 7.9063330437519e-01 7.9059681917874e-01 7.9059430300719e-01 7.9059407806840e-01 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_sphere_tpgmm_transformedXU.txt b/data/data_sphere_tpgmm_transformedXU.txt new file mode 100644 index 0000000..57ffec2 --- /dev/null +++ b/data/data_sphere_tpgmm_transformedXU.txt @@ -0,0 +1,7 @@ + 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 1.0000000000000e-02 2.0000000000000e-02 3.0000000000000e-02 4.0000000000000e-02 5.0000000000000e-02 6.0000000000000e-02 7.0000000000000e-02 8.0000000000000e-02 9.0000000000000e-02 1.0000000000000e-01 1.1000000000000e-01 1.2000000000000e-01 1.3000000000000e-01 1.4000000000000e-01 1.5000000000000e-01 1.6000000000000e-01 1.7000000000000e-01 1.8000000000000e-01 1.9000000000000e-01 2.0000000000000e-01 + -9.3530692200145e-03 -9.3530692200146e-03 -9.3530692203203e-03 -9.3528635896998e-03 -1.1150208742668e-02 -1.4357780122242e-02 -1.7547742483717e-02 -1.8173066489443e-02 -1.6725037109383e-02 -1.3482867969011e-02 -2.1696504403274e-02 -5.2055629154288e-02 -7.2989499001810e-02 -5.2758065464148e-02 1.5634496461205e-02 8.1156277757946e-02 1.4785843793571e-01 2.0690643322918e-01 2.6585381933078e-01 2.8349700399625e-01 -4.8991152609932e-03 -4.8988415167255e-03 -4.8888856185989e-03 -4.8631569673810e-03 -4.5513264264259e-03 4.4256050370085e-03 2.5918598394783e-02 2.1198312314871e-02 -1.4963267998674e-02 -3.5550836359974e-02 2.2009703333596e-02 1.3269440839868e-01 2.3082160264559e-01 2.9315672031794e-01 3.2589337409434e-01 3.5448209170325e-01 3.8422286838865e-01 4.1340764553910e-01 4.3553240208090e-01 4.4324411676311e-01 4.0084295960991e-03 4.0080478972639e-03 3.8129170375009e-03 -1.4535238659031e-03 -7.1146099197320e-03 -7.9388249473692e-03 -3.5409513754782e-03 -3.3214348065308e-03 3.0336848370028e-02 1.5115531440474e-01 3.2879271555155e-01 4.7206937583486e-01 5.4883672960720e-01 5.7830344812289e-01 5.9458039142682e-01 6.0730675870022e-01 6.2039015532863e-01 6.2779592230555e-01 6.3041121557101e-01 6.2988725685162e-01 -9.3530079797210e-03 -9.3507885103352e-03 -1.1685555269654e-02 -1.4883060720615e-02 -1.6501753447790e-02 -1.3814010413446e-02 7.5195616323859e-04 6.7651555477236e-02 2.1817747701667e-01 4.2819779782067e-01 6.3549662868597e-01 7.8085439717808e-01 8.5123960949150e-01 8.7061998968315e-01 8.7158451697484e-01 8.7161032271860e-01 8.6959142617582e-01 8.6692257341267e-01 8.6477355212168e-01 8.6478801883815e-01 -9.3532156145825e-03 -9.3532156145827e-03 -9.3532156146106e-03 -9.3530547806121e-03 -1.1151772857326e-02 -1.4368927036821e-02 -1.7588065730038e-02 -1.8258032869919e-02 -1.6853907418278e-02 -1.3648834474216e-02 -2.2153939967122e-02 -5.4280784082163e-02 -7.8856969008236e-02 -5.9293777427222e-02 1.7988759005344e-02 9.4564140076569e-02 1.7507238329968e-01 2.5057532140894e-01 3.3049902722168e-01 3.5586758457388e-01 -4.8993034171622e-03 -4.8993034171623e-03 -4.8993034171622e-03 -4.8993003873519e-03 -4.6218134379231e-03 4.5458479173861e-03 2.7079585149848e-02 2.2634639320502e-02 -1.6409264631938e-02 -4.0340901948682e-02 2.5930641274679e-02 1.6116905015778e-01 2.8725386176934e-01 3.7229311146541e-01 4.2276074281154e-01 4.7268918481505e-01 5.3073065507480e-01 5.9545490646174e-01 6.4931418942726e-01 6.6764143839330e-01 4.0085209776783e-03 4.0085161900498e-03 3.8155802957489e-03 -1.4570604531950e-03 -7.1554121199428e-03 -8.0260541517662e-03 -3.6103821350583e-03 -3.4378554275099e-03 3.2099351885379e-02 1.6400923215202e-01 3.6842331862788e-01 5.5166671233344e-01 6.6990144710273e-01 7.2896551179520e-01 7.7157766765765e-01 8.1587919083392e-01 8.7087151568715e-01 9.1388612595065e-01 9.4132455957061e-01 9.4823790683077e-01 -9.3532156145825e-03 -9.3515713503968e-03 -1.1693314440722e-02 -1.4921803102363e-02 -1.6613133242167e-02 -1.4004511262386e-02 7.7083155772355e-04 7.0470269398076e-02 2.3142725656635e-01 4.6485113803581e-01 7.1625572033942e-01 9.2850649271019e-01 1.0627892324144e+00 1.1204403774193e+00 1.1450964308695e+00 1.1755388805949e+00 1.2071591047934e+00 1.2301111186866e+00 1.2377601004461e+00 1.2377421996631e+00 + 2.5354167914261e-03 2.5354167912077e-03 2.5353816567362e-03 5.9303427186147e-03 2.6777125357912e-02 6.6650647421860e-02 1.1573413875240e-01 1.6544192918691e-01 2.1213971731780e-01 2.6697264063639e-01 3.4510481072343e-01 4.7574548099927e-01 6.2127884786153e-01 7.3420208519242e-01 7.8594061247559e-01 8.0530538558836e-01 8.2268777187369e-01 8.4302580755515e-01 8.5891286874715e-01 8.6381671694396e-01 -1.4367034913996e-02 2.3271946185710e-02 1.1264240842109e-01 2.0901217574478e-01 2.9853638838649e-01 3.8937213509766e-01 4.8792868453216e-01 5.8314061625183e-01 6.7196537554246e-01 7.5689026592646e-01 8.2766335675762e-01 8.6165821383797e-01 8.7015953219543e-01 8.7226468442360e-01 8.7956193747750e-01 8.8874738552303e-01 8.9612083268143e-01 8.9889680794448e-01 8.9612520379913e-01 8.9382063477968e-01 1.0986727593762e-02 2.6167597860138e-02 6.4563665681180e-02 1.2042044514091e-01 1.8393484609438e-01 2.5287514353754e-01 3.3410089809187e-01 4.3772541953945e-01 5.4618101995321e-01 6.2154133806608e-01 6.5067313909193e-01 6.6367887576166e-01 6.8532676870428e-01 7.0679810571262e-01 7.2581379348704e-01 7.4503562099917e-01 7.6044060260126e-01 7.6804097526279e-01 7.7185259790186e-01 7.7362346180300e-01 6.7610671746503e-03 2.0365758633063e-02 6.1970111291101e-02 1.2364447206918e-01 1.9873632660219e-01 2.8204051576966e-01 3.7530416863507e-01 4.6829898559142e-01 5.1292369838841e-01 4.7742232976092e-01 3.8432122175751e-01 3.1594838139277e-01 3.0329392292100e-01 3.3175657172513e-01 3.7092316623791e-01 4.1033550720618e-01 4.4558946062194e-01 4.6775738622597e-01 4.7716255058540e-01 4.7711792370273e-01 2.5354564758588e-03 2.5354564756404e-03 2.5354213405437e-03 5.9304639464744e-03 2.6780881565104e-02 6.6702392821714e-02 1.1600008613503e-01 1.6621543661397e-01 2.1377430328141e-01 2.7025892336597e-01 3.5238078526504e-01 4.9608156027942e-01 6.7122212813208e-01 8.2515563531391e-01 9.0428855866371e-01 9.3835022244766e-01 9.7410679393255e-01 1.0209516417026e+00 1.0677667460399e+00 1.0843302195090e+00 -1.4367586696533e-02 2.3274140443693e-02 1.1288243979269e-01 2.1056557303334e-01 3.0315986204427e-01 3.9995130487702e-01 5.0978475604997e-01 6.2265228127316e-01 7.3690170300717e-01 8.5887250849684e-01 9.7510817274484e-01 1.0465598178611e+00 1.0828998807461e+00 1.1077287705814e+00 1.1409997489826e+00 1.1851128364506e+00 1.2378201186977e+00 1.2947329844259e+00 1.3359897163795e+00 1.3463273886810e+00 1.0986978062055e-02 2.6170655233108e-02 6.4608762312829e-02 1.2071344164819e-01 1.8498971016996e-01 2.5565365266563e-01 3.4065192821658e-01 4.5306826626971e-01 5.7791292420193e-01 6.7439585573552e-01 7.2910118110168e-01 7.7558418778825e-01 8.3649903391454e-01 8.9093614181113e-01 9.4187719946262e-01 1.0009094265709e+00 1.0674670680849e+00 1.1180416541678e+00 1.1525236049541e+00 1.1646196745778e+00 6.7612172689568e-03 2.0367463637055e-02 6.2011259245435e-02 1.2396633337363e-01 2.0007771200480e-01 2.8592996974296e-01 3.8472494950124e-01 4.8781074493664e-01 5.4407322868081e-01 5.1828924492978e-01 4.3316087152316e-01 3.7569119741738e-01 3.7866837015458e-01 4.2695258877562e-01 4.8732255508633e-01 5.5341857506343e-01 6.1856333698603e-01 6.6371966688937e-01 6.8296811933326e-01 6.8288294416465e-01 + 9.9995304477653e-01 9.9995304477653e-01 9.9995304486561e-01 9.9993867560862e-01 9.9957924068208e-01 9.9767306536170e-01 9.9312521157252e-01 9.8605208164746e-01 9.7709621505255e-01 9.6360978690700e-01 9.3831334388477e-01 8.7804125687927e-01 7.8018275181865e-01 6.7687804265434e-01 6.1810429231797e-01 5.8727923045418e-01 5.4892869513327e-01 4.9648485947144e-01 4.3771044155672e-01 4.1647344243458e-01 9.9988478685169e-01 9.9971716893956e-01 9.9362356384222e-01 9.7790094595247e-01 9.5438740050197e-01 9.2106989660370e-01 8.7249861035303e-01 8.1209460854782e-01 7.4043138418282e-01 6.5257433552039e-01 5.6079313551423e-01 4.8983396830485e-01 4.3536625533171e-01 3.9142490676990e-01 3.4664723691705e-01 2.9063814510088e-01 2.2212663199524e-01 1.4518487275554e-01 8.5271014146707e-02 6.7965622169842e-02 9.9993160981587e-01 9.9964953477420e-01 9.9790630559060e-01 9.9272191658109e-01 9.8291268926488e-01 9.6746634920256e-01 9.4253066345746e-01 8.9910256654057e-01 8.3711765545462e-01 7.6866015637746e-01 6.8448507380694e-01 5.8024206523366e-01 4.7864962585531e-01 4.0743288975024e-01 3.4593134479936e-01 2.7586305348743e-01 1.9195349719852e-01 1.2643314539279e-01 8.2615170486063e-02 6.8911414177098e-02 9.9993340238857e-01 9.9974886778107e-01 9.9800959569766e-01 9.9221496613905e-01 9.7991405981434e-01 9.5930303897188e-01 9.2690140552654e-01 8.8097634879465e-01 8.3024566735045e-01 7.6727737161158e-01 6.6965754937549e-01 5.3892766741274e-01 4.2825684297154e-01 3.6326080256655e-01 3.2055644513530e-01 2.6817944898188e-01 2.1274582041525e-01 1.7218675715225e-01 1.5646917865726e-01 1.5652529941061e-01 8.5268975840405e-01 8.5268975840425e-01 8.5268979086483e-01 8.4955324203772e-01 8.2960162834810e-01 7.9148780958734e-01 7.4471076869077e-01 6.9806144884074e-01 6.5466012088456e-01 6.0370166480197e-01 5.2457619445905e-01 3.7951957864026e-01 2.0830589388683e-01 7.3576386536094e-02 3.0041844609328e-02 2.7877100259048e-02 2.5651506561687e-02 1.1266234012595e-02 -1.3998046292289e-03 -6.9943321528904e-03 6.5633999379442e-01 6.2647680383339e-01 5.5538576022705e-01 4.7788852202489e-01 4.0459745689805e-01 3.3338856104240e-01 2.5996949575716e-01 1.6771975603600e-01 5.3311172912819e-02 -5.8023430771879e-02 -1.0989582390874e-01 -8.4254298182516e-02 -3.6329238365779e-02 -4.2587058854690e-03 6.8399642084928e-05 -4.5343559489649e-03 -1.1016446000229e-02 -1.6766830365454e-02 -1.6710542406892e-02 -1.3755046987761e-02 -5.0152871544413e-02 -5.9396112354951e-02 -8.2948815685398e-02 -1.2128624760200e-01 -1.6493596700763e-01 -2.0864417638483e-01 -2.5688465992842e-01 -3.2518251588584e-01 -3.7298956612646e-01 -3.2707350927485e-01 -1.9820340301094e-01 -8.1123706103463e-02 -2.4404393111484e-02 -1.0684931690767e-02 -7.8893865514167e-03 -8.6791680915219e-03 -5.5685484383834e-03 -2.2306209998068e-03 -1.4535296707586e-03 -3.3324231588434e-03 -8.9182485469786e-01 -8.9703022065758e-01 -9.1513009980926e-01 -9.4182201482450e-01 -9.7251116374000e-01 -1.0029553479524e+00 -1.0271119130894e+00 -1.0021672550664e+00 -8.7499310939957e-01 -6.4947045950871e-01 -3.8462569341195e-01 -1.6653885691518e-01 -4.3617096814702e-02 -8.8319544298689e-03 -9.1553172141953e-03 -6.3240127839159e-03 -2.0405559266966e-03 1.8837606187004e-03 1.5844344619184e-03 1.6004914207901e-03 + 6.7632133568682e-01 6.7632133568692e-01 6.7632135197745e-01 6.7474285099891e-01 6.6413301524185e-01 6.4298463582409e-01 6.1554027951835e-01 5.8685380026752e-01 5.5891677770342e-01 5.2443398430142e-01 4.6545864460512e-01 3.4646615402376e-01 1.9527627731872e-01 7.0419269679586e-02 2.9227970793574e-02 2.7400391745445e-02 2.5419477987926e-02 1.1227000619587e-02 -1.3991629491477e-03 -6.9936769160862e-03 4.3691463569077e-01 4.2531636128419e-01 3.9397906218157e-01 3.5405662073152e-01 3.1112279623051e-01 2.6604657290035e-01 2.1593338909990e-01 1.4350394841226e-01 4.6396800882747e-02 -5.1355116962919e-02 -1.0043306348504e-01 -7.9680589142327e-02 -3.5123084519133e-02 -4.1650056420144e-03 6.7349405791302e-05 -4.4917395423056e-03 -1.0969498222880e-02 -1.6750898492505e-02 -1.6709671424596e-02 -1.3754094289936e-02 -3.3603602945108e-02 -4.0070218960666e-02 -5.6905496214430e-02 -8.5004315041204e-02 -1.1827082300409e-01 -1.5340273972575e-01 -1.9446784888917e-01 -2.5416717950695e-01 -3.0391864380470e-01 -2.8260500818626e-01 -1.8139984545759e-01 -7.7059897185089e-02 -2.3670055025817e-02 -1.0471589787161e-02 -7.7861481054380e-03 -8.6173031459400e-03 -5.5550393425162e-03 -2.2295250233698e-03 -1.4535039856306e-03 -3.3324097479297e-03 -6.2381317559655e-01 -6.2965277168820e-01 -6.4823069953926e-01 -6.7543423075721e-01 -7.0739361532818e-01 -7.4084203922239e-01 -7.7371172713141e-01 -7.8594688165212e-01 -7.3348936637323e-01 -5.8486955779379e-01 -3.6403807086212e-01 -1.6149847141328e-01 -4.2766769187493e-02 -8.7220923940987e-03 -9.0890929549878e-03 -6.3045970856147e-03 -2.0391898095374e-03 1.8837076620153e-03 1.5844174837226e-03 1.6004746136515e-03 7.7405847099949e-01 7.7405847099957e-01 7.7405848444522e-01 7.7275910929651e-01 7.6644179873180e-01 7.5413676067829e-01 7.3824544654445e-01 7.1964783279375e-01 7.0015059969221e-01 6.7557377010918e-01 6.5200478701218e-01 6.2669421491822e-01 5.8237625550641e-01 5.0539442032977e-01 4.0371180797858e-01 3.1993054630371e-01 2.3186718068600e-01 1.4418481438910e-01 5.2429573611948e-02 2.2653515825887e-02 1.3468552161111e+00 1.3239403845068e+00 1.2693903081441e+00 1.2099245819588e+00 1.1533366050642e+00 1.0871405132506e+00 1.0024009288590e+00 9.3721794553657e-01 8.9864291591704e-01 8.4337803847368e-01 7.2004149922178e-01 5.6925265021267e-01 4.4710041514851e-01 3.6451937188948e-01 3.0422661962837e-01 2.3776137722436e-01 1.5962782245850e-01 7.3632263953105e-02 5.7873148063980e-03 -1.5045845542045e-02 1.4864375201651e+00 1.4743915020781e+00 1.4440139533626e+00 1.4027128989229e+00 1.3551880432933e+00 1.2996565817637e+00 1.2295348251294e+00 1.1402439202267e+00 1.0195643127318e+00 8.6271760950708e-01 6.9487754550356e-01 5.4644858667339e-01 4.2614484392915e-01 3.4700105811835e-01 2.8064616297660e-01 2.0684368985938e-01 1.2056275638013e-01 5.4253603965222e-02 1.0193773068862e-02 -3.6112633288382e-03 1.0941230736130e+00 1.0815519118465e+00 1.0439742077114e+00 9.8797067191148e-01 9.1830017102609e-01 8.3798475086896e-01 7.4105581225064e-01 6.1914413564857e-01 5.0556880615639e-01 4.4006264885384e-01 4.2250264221194e-01 3.9437284376538e-01 3.4023451507132e-01 2.7356357569382e-01 2.0835353627802e-01 1.3563895509022e-01 6.3352506971190e-02 1.2850142553837e-02 -7.8602472854190e-03 -7.7747053573879e-03 + 6.1395396607778e-01 6.1395396607780e-01 6.1395396815838e-01 6.1375044993232e-01 6.1357076144209e-01 6.1264159037282e-01 6.1019637102604e-01 6.0500127349913e-01 5.9775432259159e-01 5.8686908551777e-01 5.7852656610103e-01 5.7211365792928e-01 5.4594838893945e-01 4.8370826096905e-01 3.9277471427155e-01 3.1445961805911e-01 2.2976984534598e-01 1.4368270698725e-01 5.2405539534370e-02 2.2651393619365e-02 8.9657915354721e-01 8.9882578804210e-01 9.0047898048472e-01 8.9640531020327e-01 8.8687979483022e-01 8.6754628565279e-01 8.3260472223862e-01 8.0190001992642e-01 7.8209039787357e-01 7.4645323852109e-01 6.5804114324909e-01 5.3835101019439e-01 4.3225639667119e-01 3.5649919984461e-01 2.9955539873186e-01 2.3552676316809e-01 1.5894755121065e-01 7.3562298440920e-02 5.7870131615671e-03 -1.5044803441329e-02 9.9594808217722e-01 9.9466426302373e-01 9.9063898474834e-01 9.8310114732609e-01 9.7176624427946e-01 9.5555449377812e-01 9.3078735275153e-01 8.9123051515998e-01 8.3075944031118e-01 7.4542361329635e-01 6.3596627228113e-01 5.1907480474676e-01 4.1332197275680e-01 3.4007262203332e-01 2.7697370079633e-01 2.0536931196023e-01 1.2027027552053e-01 5.4226947410131e-02 1.0193592936064e-02 -3.6112487957677e-03 7.6531662629563e-01 7.5917415415458e-01 7.3949718308548e-01 7.0853006225126e-01 6.6796115269306e-01 6.1898501557271e-01 5.5822891847554e-01 4.8556206585890e-01 4.2380830123358e-01 3.9629092142452e-01 3.9988760355708e-01 3.8243694363444e-01 3.3360154706053e-01 2.7016067641745e-01 2.0684642753777e-01 1.3522252249909e-01 6.3310093555451e-02 1.2849781307856e-02 -7.8601630580048e-03 -7.7746237133699e-03 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 + 4.0700120200333e-01 4.0700120200314e-01 4.0700117179435e-01 4.0991763835403e-01 4.2715133005662e-01 4.5960966029841e-01 4.9876903780920e-01 5.3812273337594e-01 5.7471889252459e-01 6.1689032459042e-01 6.6981733515767e-01 7.4340242569335e-01 8.1474384448793e-01 8.7239179542686e-01 9.1917014178671e-01 9.4887531696336e-01 9.7291298085106e-01 9.8956012155397e-01 9.9862490544206e-01 9.9971896193395e-01 7.2466699550736e-02 1.0591598356471e-01 1.8416868427538e-01 2.6664851238204e-01 3.4153599398543e-01 4.2021740004196e-01 5.1004131987299e-01 5.7996808087351e-01 6.2143539199325e-01 6.6345324979466e-01 7.4625401409335e-01 8.3894528637844e-01 9.0106646617811e-01 9.3428634434961e-01 9.5407890583256e-01 9.7185748343440e-01 9.8722608660472e-01 9.9714993639261e-01 9.9984363645500e-01 9.9979221780312e-01 8.3415918604467e-02 9.5065143012030e-02 1.2408128947333e-01 1.6213081308161e-01 2.0416262857077e-01 2.5176022097438e-01 3.0954346981678e-01 3.7564240137284e-01 4.6633915799746e-01 6.0372017200708e-01 7.5009399183623e-01 8.5124797757348e-01 9.1027725190268e-01 9.4034087306185e-01 9.6084595277540e-01 9.7864661026924e-01 9.9272564304752e-01 9.9852614757589e-01 9.9994698758945e-01 9.9998792689082e-01 1.5857989616477e-01 1.6489994168905e-01 1.8149621589301e-01 2.0438627842311e-01 2.3113236788881e-01 2.6078846488536e-01 2.9958410818493e-01 3.8277536417611e-01 5.3139427285482e-01 7.0772954294886e-01 8.4116953551847e-01 9.0975833487510e-01 9.4174360165179e-01 9.6277574440881e-01 9.7833120353187e-01 9.9079519652881e-01 9.9799182048698e-01 9.9991566382660e-01 9.9996785321226e-01 9.9996849635732e-01 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 0.0000000000000e+00 diff --git a/data/data_tpbatch_lqr_frames.txt b/data/data_tpbatch_lqr_frames.txt new file mode 100644 index 0000000..5220960 --- /dev/null +++ b/data/data_tpbatch_lqr_frames.txt @@ -0,0 +1,6 @@ +ARMA_MAT_TXT_FN008 +4 8 + 1.66666671633720e-01 7.77777805924416e-02 1.66666671633720e-01 9.77777764201164e-02 1.66666671633720e-01 5.38888871669769e-02 1.66666671633720e-01 6.61111101508141e-02 + 4.58333343267441e-01 1.31666660308838e-01 4.58333343267441e-01 1.39166668057442e-01 4.58333343267441e-01 1.35000005364418e-01 4.58333343267441e-01 1.10833331942558e-01 + 0.00000000000000e+00 -5.55555569007993e-04 0.00000000000000e+00 -1.11111113801599e-03 0.00000000000000e+00 -1.11111113801599e-03 0.00000000000000e+00 -5.55555569007993e-04 + 2.50000003725290e-02 -2.08333339542150e-02 2.50000003725290e-02 -1.49999996647239e-02 2.50000003725290e-02 -1.16666667163372e-02 2.50000003725290e-02 -1.33333336561918e-02 diff --git a/data/data_tpbatch_lqr_trajectories.txt b/data/data_tpbatch_lqr_trajectories.txt new file mode 100644 index 0000000..7f6a458 --- /dev/null +++ b/data/data_tpbatch_lqr_trajectories.txt @@ -0,0 +1,10 @@ +ARMA_CUB_TXT_FN008 +2 200 4 + -2.14843750000000e-04 -2.77548768146287e-04 -3.40253786292575e-04 -4.02958804438861e-04 -4.65576580820769e-04 -5.23919510748186e-04 -5.82262440675600e-04 -6.40605370603014e-04 -6.98948300530431e-04 -7.57291230457844e-04 -8.15634160385258e-04 -8.73977090312675e-04 -9.43279766890005e-04 -1.18428514098269e-03 -1.42529051507538e-03 -1.66629588916806e-03 -1.91907890145170e-03 -2.30730475293132e-03 -2.69553060441094e-03 -3.08375645589056e-03 -3.46527559673367e-03 -3.78643434184814e-03 -4.10759308696258e-03 -4.42875183207706e-03 -4.74886367601897e-03 -5.06129824469569e-03 -5.37373281337242e-03 -5.68616738204914e-03 -5.97867811278614e-03 -6.14879955332217e-03 -6.31892099385817e-03 -6.48904243439419e-03 -6.69048366834169e-03 -7.05635381769961e-03 -7.42222396705750e-03 -7.78809411641542e-03 -8.18115098059742e-03 -8.69805843453378e-03 -9.21496588847014e-03 -9.73187334240647e-03 -1.02302419214126e-02 -1.06544550006979e-02 -1.10786680799833e-02 -1.15028811592686e-02 -1.19203766226968e-02 -1.23140550844500e-02 -1.27077335462032e-02 -1.31014120079564e-02 -1.35143272787549e-02 -1.39881591115299e-02 -1.44619909443049e-02 -1.49358227770798e-02 -1.53933513051368e-02 -1.58044781197655e-02 -1.62156049343942e-02 -1.66267317490229e-02 -1.70528205262423e-02 -1.75173829215522e-02 -1.79819453168621e-02 -1.84465077121720e-02 -1.89284094081519e-02 -1.94507694723618e-02 -1.99731295365718e-02 -2.04954896007817e-02 -2.11434778056951e-02 -2.20584258096036e-02 -2.29733738135120e-02 -2.38883218174204e-02 -2.46560711543830e-02 -2.51380819025684e-02 -2.56200926507538e-02 -2.61021033989391e-02 -2.66447689838079e-02 -2.72952653894472e-02 -2.79457617950867e-02 -2.85962582007258e-02 -2.93076711683417e-02 -3.01184743160244e-02 -3.09292774637075e-02 -3.17400806113903e-02 -3.25471759840872e-02 -3.33487096943047e-02 -3.41502434045225e-02 -3.49517771147403e-02 -3.57162112646567e-02 -3.64294126884422e-02 -3.71426141122278e-02 -3.78558155360133e-02 -3.86196389935789e-02 -3.94478904941372e-02 -4.02761419946956e-02 -4.11043934952542e-02 -4.18390891087380e-02 -4.24639582460917e-02 -4.30888273834450e-02 -4.37136965207983e-02 -4.44233646531267e-02 -4.52248983633444e-02 -4.60264320735622e-02 -4.68279657837800e-02 -4.75962385713289e-02 -4.83312504362089e-02 -4.90662623010889e-02 -4.98012741659686e-02 -5.05708773904244e-02 -5.13724111006422e-02 -5.21739448108597e-02 -5.29754785210775e-02 -5.37437404034058e-02 -5.44836596175322e-02 -5.52235788316583e-02 -5.59634980457844e-02 -5.66512030639308e-02 -5.72978826423786e-02 -5.79445622208264e-02 -5.85912417992742e-02 -5.95601815501117e-02 -6.07624821154383e-02 -6.19647826807650e-02 -6.31670832460917e-02 -6.41292508549692e-02 -6.49313298262144e-02 -6.57334087974594e-02 -6.65354877687047e-02 -6.73040986180906e-02 -6.80521967476269e-02 -6.88002948771636e-02 -6.95483930067003e-02 -7.02315832635400e-02 -7.08782628419878e-02 -7.15249424204356e-02 -7.21716219988833e-02 -7.27510054613345e-02 -7.32957212276661e-02 -7.38404369939978e-02 -7.43851527603294e-02 -7.47789620847292e-02 -7.51017566129258e-02 -7.54245511411222e-02 -7.57473456693189e-02 -7.61075451039922e-02 -7.64837752128700e-02 -7.68600053217475e-02 -7.72362354306253e-02 -7.75739919214125e-02 -7.78967864496092e-02 -7.82195809778056e-02 -7.85423755060022e-02 -7.88651700341989e-02 -7.91879645623953e-02 -7.95107590905919e-02 -7.98335536187883e-02 -8.01153227072864e-02 -8.03841363937745e-02 -8.06529500802625e-02 -8.09217637667503e-02 -8.11905774532383e-02 -8.14593911397264e-02 -8.17282048262145e-02 -8.19970185127025e-02 -8.23622343488275e-02 -8.27515507223617e-02 -8.31408670958961e-02 -8.35301834694305e-02 -8.37692695247069e-02 -8.39753781930486e-02 -8.41814868613903e-02 -8.43875955297319e-02 -8.45634749267170e-02 -8.47335963672531e-02 -8.49037178077889e-02 -8.50738392483250e-02 -8.52439606888611e-02 -8.54140821293969e-02 -8.55842035699331e-02 -8.57543250104689e-02 -8.59282850886378e-02 -8.61027686173925e-02 -8.62772521461475e-02 -8.64517356749022e-02 -8.66262192036572e-02 -8.68007027324119e-02 -8.69751862611669e-02 -8.71496697899219e-02 -8.72132908465942e-02 -8.72672716883025e-02 -8.73212525300111e-02 -8.73752333717197e-02 -8.74333145763539e-02 -8.74916575062814e-02 -8.75500004362089e-02 -8.76083433661361e-02 -8.76666862960636e-02 -8.77250292259911e-02 -8.77833721559183e-02 -8.78417150858458e-02 -8.78829586299553e-02 -8.79238532070072e-02 -8.79647477840592e-02 -8.80056423611111e-02 + -1.94430338541667e-01 -1.81771013269473e-01 -1.69111687997278e-01 -1.56452362725084e-01 -1.44025318650545e-01 -1.42980053261097e-01 -1.41934787871650e-01 -1.40889522482202e-01 -1.39838924439908e-01 -1.38660342729271e-01 -1.37481761018635e-01 -1.36303179307998e-01 -1.35124597597362e-01 -1.33946015886725e-01 -1.32767434176089e-01 -1.31588852465452e-01 -1.30335482752303e-01 -1.28222051010260e-01 -1.26108619268216e-01 -1.23995187526173e-01 -1.21947350685720e-01 -1.20489867959590e-01 -1.19032385233459e-01 -1.17574902507328e-01 -1.16134889944514e-01 -1.14822991912688e-01 -1.13511093880863e-01 -1.12199195849037e-01 -1.10941458595059e-01 -1.10016423262144e-01 -1.09091387929230e-01 -1.08166352596315e-01 -1.07215799047320e-01 -1.06131274863903e-01 -1.05046750680486e-01 -1.03962226497069e-01 -1.02845461029104e-01 -1.01581818598199e-01 -1.00318176167295e-01 -9.90545337363904e-02 -9.78267149549833e-02 -9.67421907715662e-02 -9.56576665881492e-02 -9.45731424047321e-02 -9.35429589353017e-02 -9.27054379972779e-02 -9.18679170592546e-02 -9.10303961212312e-02 -9.01624496178813e-02 -8.91981554909967e-02 -8.82338613641121e-02 -8.72695672372279e-02 -8.63052731103433e-02 -8.53409789834592e-02 -8.43766848565746e-02 -8.34123907296900e-02 -8.24705395466917e-02 -8.15863987908292e-02 -8.07022580349667e-02 -7.98181172791037e-02 -7.89641567211054e-02 -7.81806166247908e-02 -7.73970765284758e-02 -7.66135364321608e-02 -7.56096236390283e-02 -7.41374188651592e-02 -7.26652140912900e-02 -7.11930093174204e-02 -6.98823708385679e-02 -6.88853610500421e-02 -6.78883512615158e-02 -6.68913414729900e-02 -6.58345601706450e-02 -6.46715183992879e-02 -6.35084766279313e-02 -6.23454348565746e-02 -6.11671639447237e-02 -5.99640454878558e-02 -5.87609270309883e-02 -5.75578085741204e-02 -5.63550172738692e-02 -5.51527167085429e-02 -5.39504161432163e-02 -5.27481155778896e-02 -5.15623037060300e-02 -5.03992619346733e-02 -4.92362201633167e-02 -4.80731783919600e-02 -4.68284456134842e-02 -4.54797424623117e-02 -4.41310393111392e-02 -4.27823361599667e-02 -4.15799865211474e-02 -4.05494431794389e-02 -3.95188998377303e-02 -3.84883564960218e-02 -3.73753696869765e-02 -3.61730691216499e-02 -3.49707685563233e-02 -3.37684679909967e-02 -3.25158670958962e-02 -3.12129658710218e-02 -2.99100646461474e-02 -2.86071634212730e-02 -2.73565745393635e-02 -2.61542739740369e-02 -2.49519734087103e-02 -2.37496728433836e-02 -2.24895146304439e-02 -2.11800702732412e-02 -1.98706259160385e-02 -1.85611815588358e-02 -1.73296004763400e-02 -1.61591976811139e-02 -1.49887948858878e-02 -1.38183920906617e-02 -1.22808214248325e-02 -1.04773705768426e-02 -8.67391972885258e-03 -6.87046888086267e-03 -5.41936570875212e-03 -4.20316098722783e-03 -2.98695626570354e-03 -1.77075154417924e-03 -5.62660306742058e-04 6.40458150125613e-04 1.84357660699330e-03 3.04669506386096e-03 4.22887549727804e-03 5.39927829250417e-03 6.56968108773029e-03 7.74008388295646e-03 8.73450913421271e-03 9.63827928706029e-03 1.05420494399079e-02 1.14458195927554e-02 1.22822936296064e-02 1.30870989059883e-02 1.38919041823702e-02 1.46967094587521e-02 1.53893000157035e-02 1.60337985500419e-02 1.66782970843802e-02 1.73227956187186e-02 1.79672941530570e-02 1.86117926873953e-02 1.92562912217337e-02 1.99007897560720e-02 2.06046017849665e-02 2.13292536903266e-02 2.20539055956868e-02 2.27785575010469e-02 2.35641259683836e-02 2.43689312447655e-02 2.51737365211474e-02 2.59785417975293e-02 2.67833470739112e-02 2.75881523502931e-02 2.83929576266750e-02 2.91977629030569e-02 3.04206743352177e-02 3.17481123063233e-02 3.30755502774288e-02 3.44029882485343e-02 3.52146801716917e-02 3.59131595477387e-02 3.66116389237856e-02 3.73101182998325e-02 3.81989046796482e-02 3.91239400125628e-02 4.00489753454774e-02 4.09740106783920e-02 4.20136980475292e-02 4.30720497016333e-02 4.41304013557371e-02 4.51887530098408e-02 4.62355887510471e-02 4.72808541404942e-02 4.83261195299413e-02 4.93713849193887e-02 5.04166503088358e-02 5.14619156982829e-02 5.25071810877304e-02 5.35524464771775e-02 5.46097512301087e-02 5.56681028842129e-02 5.67264545383167e-02 5.77848061924204e-02 5.89561740996650e-02 6.01347558103017e-02 6.13133375209379e-02 6.24919192315746e-02 6.35425172738692e-02 6.45877826633167e-02 6.56330480527638e-02 6.66783134422108e-02 7.62038054857617e-02 8.59023633793967e-02 9.56009212730317e-02 1.05299479166667e-01 + -1.99652777777778e-04 -1.07394611948632e-04 -1.51364461194863e-05 -2.05279871580123e-04 -4.32850013958683e-04 -5.70124930206589e-04 -6.79809638470128e-04 -7.94816094360692e-04 -9.12701528475711e-04 -1.02186278615299e-03 -1.12334676856505e-03 -1.40601008514796e-03 -1.94418271915131e-03 -2.44510311976549e-03 -2.85821468453378e-03 -3.33658308905639e-03 -4.11052659128978e-03 -4.84900631630375e-03 -5.06735064209939e-03 -5.28569496789503e-03 -5.99126273729761e-03 -6.72420261027358e-03 -7.51073073701842e-03 -8.30825132607483e-03 -8.91507232342267e-03 -9.44504423157453e-03 -1.02186823876326e-02 -1.11576654976270e-02 -1.20853617043551e-02 -1.30007677275265e-02 -1.41204721524288e-02 -1.56007031686209e-02 -1.68672354829704e-02 -1.74740891959799e-02 -1.80809429089894e-02 -1.86877966219989e-02 -1.92957190466220e-02 -2.00030316513121e-02 -2.07103442560022e-02 -2.13278850851480e-02 -2.19347387981574e-02 -2.33074225293132e-02 -2.49004135259631e-02 -2.57091010608599e-02 -2.61129868090452e-02 -2.67910625174484e-02 -2.77003179962312e-02 -2.84808918725572e-02 -2.90877455855667e-02 -2.96945992985761e-02 -3.03014530115858e-02 -3.09083067245953e-02 -3.15151604376047e-02 -3.21496479794808e-02 -3.31275845372697e-02 -3.41055210950586e-02 -3.46152965347572e-02 -3.51042648136517e-02 -3.56923070212172e-02 -3.62991607342267e-02 -3.68207356225572e-02 -3.73097039014517e-02 -3.77837538386375e-02 -3.82481199399778e-02 -3.87044597989950e-02 -3.91524244486319e-02 -3.95343579878558e-02 -3.98049819409547e-02 -4.01661628454775e-02 -4.07914681916528e-02 -4.13677218558069e-02 -4.16383458089056e-02 -4.19089697620044e-02 -4.21795937151033e-02 -4.24502176682022e-02 -4.27968510085147e-02 -4.31515324015914e-02 -4.34206732446958e-02 -4.36666950202400e-02 -4.41847802379956e-02 -4.48367379431881e-02 -4.52216049867392e-02 -4.53907449574261e-02 -4.56010194200167e-02 -4.58644677379956e-02 -4.61249716464267e-02 -4.63791941478225e-02 -4.66195343034617e-02 -4.68050757258514e-02 -4.69978582146844e-02 -4.72684821677833e-02 -4.75391061208822e-02 -4.77045383165831e-02 -4.78665026521497e-02 -4.81593296342825e-02 -4.84750575795644e-02 -4.87396182300392e-02 -4.89856400055833e-02 -4.91374188651592e-02 -4.92307021217197e-02 -4.94546844465383e-02 -4.98093658396147e-02 -5.01707212276661e-02 -5.05428291631769e-02 -5.09307496684814e-02 -5.13623128664153e-02 -5.17547917539083e-02 -5.19239317245953e-02 -5.20930716952819e-02 -5.22622116659686e-02 -5.24313516366556e-02 -5.26783330716081e-02 -5.29325555730039e-02 -5.31867780743997e-02 -5.34410005757956e-02 -5.37482660699331e-02 -5.40803954669181e-02 -5.43639748220267e-02 -5.46099965975711e-02 -5.47804451947236e-02 -5.48573269995811e-02 -5.49592253803742e-02 -5.51119638993578e-02 -5.52862947550250e-02 -5.55405172564211e-02 -5.57931694060581e-02 -5.60309904557511e-02 -5.62688115054439e-02 -5.63571437918761e-02 -5.64422263225853e-02 -5.68126221384700e-02 -5.72288089754328e-02 -5.75243840731436e-02 -5.77786065745394e-02 -5.79897207391122e-02 -5.81752621615019e-02 -5.83916871684814e-02 -5.86377089440256e-02 -5.88538722257119e-02 -5.90240372871300e-02 -5.91942023485483e-02 -5.93643674099664e-02 -5.95332238449192e-02 -5.96951881804858e-02 -5.98607730492742e-02 -6.01078199155500e-02 -6.03548667818258e-02 -6.06095036816025e-02 -6.08647512737297e-02 -6.10445783605528e-02 -6.12065426961194e-02 -6.13096733668342e-02 -6.13865551716917e-02 -6.15517692629817e-02 -6.17824146775544e-02 -6.19816421517308e-02 -6.21436064872975e-02 -6.22793982935511e-02 -6.23644808242603e-02 -6.24495633549692e-02 -6.25346458856783e-02 -6.26270349141542e-02 -6.27807985238694e-02 -6.29345621335847e-02 -6.30203753140703e-02 -6.31054578447794e-02 -6.33103669388611e-02 -6.35328116275822e-02 -6.38133266157175e-02 -6.41126531092964e-02 -6.42699936313511e-02 -6.43468754362089e-02 -6.44681087730319e-02 -6.46300731085986e-02 -6.47576423785594e-02 -6.48345241834169e-02 -6.49090504606364e-02 -6.49777315396428e-02 -6.50856714126186e-02 -6.53849979061978e-02 -6.56770179020100e-02 -6.58389822375767e-02 -6.60009465731436e-02 -6.62348853643217e-02 -6.64737315047458e-02 -6.67125776451703e-02 -6.69514237855947e-02 -6.70765502861531e-02 -6.71534320910106e-02 -6.72303138958683e-02 -6.73071957007258e-02 -6.73802388679508e-02 -6.74489199469569e-02 -6.75233589824119e-02 -6.76084415131211e-02 -6.76916047250139e-02 -6.77684865298717e-02 -6.78453683347292e-02 -6.79222501395869e-02 -6.79991319444444e-02 + -1.92304687500000e-01 -1.89469286536851e-01 -1.86633885573702e-01 -1.70560910018844e-01 -1.52733557108459e-01 -1.44218782715662e-01 -1.38549518425461e-01 -1.33992831998534e-01 -1.30038031956658e-01 -1.26336778292504e-01 -1.22858645440745e-01 -1.19590399916248e-01 -1.16618149340452e-01 -1.14013230213568e-01 -1.12274163787688e-01 -1.10134379580193e-01 -1.06179579538317e-01 -1.02414497618300e-01 -1.01431948152220e-01 -1.00449398686139e-01 -9.75378520205192e-02 -9.45179347257121e-02 -9.23120485238692e-02 -9.02731430590454e-02 -8.84479526538946e-02 -8.67088862280150e-02 -8.47325658239113e-02 -8.25952516488692e-02 -8.05050480265912e-02 -7.84661425617671e-02 -7.60256850659546e-02 -7.28766063389867e-02 -7.01278364478642e-02 -6.86148025282663e-02 -6.71017686086683e-02 -6.55887346890704e-02 -6.40789069043133e-02 -6.28672496597571e-02 -6.16555924152008e-02 -6.01746198440117e-02 -5.86615859244137e-02 -5.58827830559046e-02 -5.27398548733250e-02 -5.12703327837104e-02 -5.06645041614321e-02 -4.93195305956867e-02 -4.73513563913317e-02 -4.57051042975292e-02 -4.44934470529733e-02 -4.32353008532246e-02 -4.18729552711475e-02 -4.05106096890704e-02 -3.91482641069933e-02 -3.77030170383166e-02 -3.52274229219012e-02 -3.27518288054858e-02 -3.15334975659548e-02 -3.03710446765075e-02 -2.91672391907454e-02 -2.79555819461893e-02 -2.67795193414992e-02 -2.56170664520519e-02 -2.41469227648660e-02 -2.24770499633585e-02 -2.12338221053183e-02 -2.04357889708962e-02 -1.95862286693886e-02 -1.86498082862228e-02 -1.74617390337102e-02 -1.55396939122697e-02 -1.37539585950586e-02 -1.28175382118928e-02 -1.18811178287270e-02 -1.09446974455611e-02 -1.00082770623953e-02 -9.07185667922950e-03 -8.13543629606367e-03 -7.31764290201004e-03 -6.53191085636517e-03 -4.73006307579567e-03 -2.42822183835848e-03 -1.18963960427135e-03 -8.09843488274704e-04 -2.16086945142382e-05 1.29460780464824e-03 2.43317826109715e-03 3.19277049309045e-03 3.95764630443886e-03 4.74337835008375e-03 5.54193493509212e-03 6.47835531825796e-03 7.41477570142379e-03 8.03413224979063e-03 8.64303614426300e-03 9.64191072550250e-03 1.07090301769263e-02 1.18867612803601e-02 1.31045690693048e-02 1.41487548419179e-02 1.50851752250837e-02 1.60215956082496e-02 1.69580159914154e-02 1.81753330454355e-02 1.98452058469430e-02 2.15220307265494e-02 2.32180433417085e-02 2.47745890912898e-02 2.55341813232831e-02 2.62889643530151e-02 2.68978682474875e-02 2.75067721419598e-02 2.82535398345896e-02 2.90131320665829e-02 2.97727242985762e-02 3.05323165305695e-02 3.17242789468174e-02 3.31189148869347e-02 3.40705316949330e-02 3.46794355894053e-02 3.52210106522194e-02 3.56792262091708e-02 3.61871368561558e-02 3.67960407506281e-02 3.75178136777638e-02 3.86572020257537e-02 3.97457993090452e-02 4.03547032035176e-02 4.09636070979900e-02 4.17199931951425e-02 4.24795854271358e-02 4.37863961735762e-02 4.51810321136933e-02 4.61027631647821e-02 4.68623553967754e-02 4.77329355108879e-02 4.86693558940538e-02 4.95288290410383e-02 5.03145610866833e-02 5.11002931323283e-02 5.18860251779733e-02 5.26645270623954e-02 5.34241192943887e-02 5.41596655150754e-02 5.47685694095479e-02 5.54195456448913e-02 5.70171495498325e-02 5.86147534547737e-02 6.01397776643633e-02 6.16589621283500e-02 6.24421750680487e-02 6.30510789625208e-02 6.36599828569933e-02 6.42688867514658e-02 6.51551540253350e-02 6.62468756543133e-02 6.71177338515496e-02 6.77266377460217e-02 6.83355416404942e-02 6.89444455349667e-02 6.95870138452679e-02 7.03466060772613e-02 7.10741369608458e-02 7.15323525177975e-02 7.19905680747488e-02 7.25978689018008e-02 7.32067727962729e-02 7.37740950847992e-02 7.43353322602596e-02 7.50696189279733e-02 7.58599638819096e-02 7.67464928810721e-02 7.76875261725292e-02 7.84554281825796e-02 7.90643320770521e-02 7.96123194095479e-02 8.00705349664992e-02 8.04925342860133e-02 8.08246636829983e-02 8.12737842860133e-02 8.22932370184254e-02 8.33030386306533e-02 8.41410503036013e-02 8.49790619765496e-02 8.58170736494975e-02 8.66550853224454e-02 8.80561171744138e-02 8.95814521827887e-02 9.02690045278475e-02 9.06011339248325e-02 9.18995203884004e-02 9.38830709537271e-02 9.51641508322862e-02 9.56469685667921e-02 9.65740486285596e-02 9.83223408710217e-02 9.97687002721942e-02 1.00226915829146e-01 1.00808387641332e-01 1.02319883924833e-01 1.03831380208333e-01 + 3.40711805555556e-04 2.42891977247348e-04 1.45072148939140e-04 -3.13743195142378e-05 -3.04419231574539e-04 -5.77464143634842e-04 -7.81042800809603e-04 -9.76682457426020e-04 -1.23945465173088e-03 -1.62903275055835e-03 -2.01861084938582e-03 -2.17627852805695e-03 -2.27409835636516e-03 -2.49064332077052e-03 -3.07586107621442e-03 -3.66107883165828e-03 -4.33227334589614e-03 -5.04167975293133e-03 -5.71497897473478e-03 -6.16835261376325e-03 -6.62172625279172e-03 -7.53610718523172e-03 -8.77118884352317e-03 -9.97568135817978e-03 -1.04154452819654e-02 -1.08552092057510e-02 -1.12850275683976e-02 -1.17043769193188e-02 -1.21237262702401e-02 -1.26999035978504e-02 -1.32868225676996e-02 -1.39853019437465e-02 -1.48622779697097e-02 -1.57392539956728e-02 -1.71804661327471e-02 -1.87345254920436e-02 -2.01252028371022e-02 -2.10999986913735e-02 -2.20747945456449e-02 -2.27860330297320e-02 -2.34001714300670e-02 -2.40566002756840e-02 -2.49063568711614e-02 -2.57561134666387e-02 -2.66844203657175e-02 -2.76592162199888e-02 -2.86821040968733e-02 -3.02820962451144e-02 -3.18820883933556e-02 -3.38616803636236e-02 -3.61838380269403e-02 -3.85059956902569e-02 -3.96098221140425e-02 -4.06815871894194e-02 -4.17123268250978e-02 -4.26871226793692e-02 -4.36619185336403e-02 -4.46063106330261e-02 -4.55462315919878e-02 -4.64861525509492e-02 -4.74260735099106e-02 -4.83659944688722e-02 -4.93327422703797e-02 -5.03075381246511e-02 -5.12823339789225e-02 -5.22571298331936e-02 -5.32319256874650e-02 -5.53329254780850e-02 -5.79970272368789e-02 -6.04099708612506e-02 -6.08973687883864e-02 -6.13847667155219e-02 -6.24767500697933e-02 -6.40359130723058e-02 -6.55875841883025e-02 -6.65623800425739e-02 -6.75371758968453e-02 -6.90223360727247e-02 -7.11029212904803e-02 -7.31835065082356e-02 -7.41119769856225e-02 -7.49268586857900e-02 -7.57444885015355e-02 -7.65670256665272e-02 -7.73895628315186e-02 -7.82120999965103e-02 -7.90346371615019e-02 -7.97701506665272e-02 -8.02532955576494e-02 -8.07364404487717e-02 -8.12237838498044e-02 -8.17128829913456e-02 -8.22042067978783e-02 -8.27077662618650e-02 -8.32113257258514e-02 -8.40859680346175e-02 -8.52053671133444e-02 -8.62824539363483e-02 -8.65767640284758e-02 -8.68710741206031e-02 -8.71972819828308e-02 -8.75553876151592e-02 -8.79134932474875e-02 -8.82715988798158e-02 -8.86297045121442e-02 -8.89293254466778e-02 -8.91402760329425e-02 -8.93512266192072e-02 -8.96982089265772e-02 -9.00699242741486e-02 -9.04682265494136e-02 -9.09301062604689e-02 -9.13919859715242e-02 -9.20986442629817e-02 -9.28897089614739e-02 -9.36336631072028e-02 -9.41797529313233e-02 -9.47258427554439e-02 -9.50701859994417e-02 -9.53015511585706e-02 -9.55373438372417e-02 -9.58180442141261e-02 -9.60987445910105e-02 -9.66776155080961e-02 -9.75120611739253e-02 -9.83465068397544e-02 -9.86208712835008e-02 -9.88879619451425e-02 -9.91609850467617e-02 -9.94416854236461e-02 -9.97223858005306e-02 -9.99910468139308e-02 -1.00258137475572e-01 -1.00534301280709e-01 -1.00828611372836e-01 -1.01122921464964e-01 -1.01286848740229e-01 -1.01414439820631e-01 -1.01545171604551e-01 -1.01686372400195e-01 -1.01827573195840e-01 -1.02325963585287e-01 -1.02992839632189e-01 -1.03614677118230e-01 -1.03930252390424e-01 -1.04245827662619e-01 -1.04420071276521e-01 -1.04490671674344e-01 -1.04565045278476e-01 -1.04782800722362e-01 -1.05000556166248e-01 -1.05291343872139e-01 -1.05663059219710e-01 -1.06034774567281e-01 -1.06193707251536e-01 -1.06334908047180e-01 -1.06449859976968e-01 -1.06520460374791e-01 -1.06591060772613e-01 -1.06881510416667e-01 -1.07220052083333e-01 -1.07484623639028e-01 -1.07548419179229e-01 -1.07612214719431e-01 -1.07676010259631e-01 -1.07739805799832e-01 -1.07802467197097e-01 -1.07859457879676e-01 -1.07916448562256e-01 -1.08016885643495e-01 -1.08144476723897e-01 -1.08276157262004e-01 -1.08467543882608e-01 -1.08658930503211e-01 -1.08784885800530e-01 -1.08848681340731e-01 -1.08912476880932e-01 -1.09044157419040e-01 -1.09178553357063e-01 -1.09283985029313e-01 -1.09347780569514e-01 -1.09411576109715e-01 -1.09481216848129e-01 -1.09551817245952e-01 -1.09622417643774e-01 -1.09693018041597e-01 -1.09763618439419e-01 -1.09823924309045e-01 -1.09880914991625e-01 -1.09940697410664e-01 -1.10011297808487e-01 -1.10081898206309e-01 -1.10152498604132e-01 -1.10223099001954e-01 -1.10293699399777e-01 -1.10364299797599e-01 -1.10434900195422e-01 -1.10497997801507e-01 -1.10554988484087e-01 -1.10611979166667e-01 + -1.90696614583333e-01 -1.80070829407454e-01 -1.69445044231575e-01 -1.59639686060511e-01 -1.50842281066792e-01 -1.42044876073074e-01 -1.39305920880444e-01 -1.37259359950796e-01 -1.35206174099665e-01 -1.33140474507957e-01 -1.31074774916248e-01 -1.28843763086265e-01 -1.26570090033501e-01 -1.24351739164573e-01 -1.22305178234925e-01 -1.20258617305276e-01 -1.18162590295226e-01 -1.16044578360553e-01 -1.13995302030988e-01 -1.12364688023450e-01 -1.10734074015913e-01 -1.08054530464824e-01 -1.04645296796483e-01 -1.01311685380025e-01 -9.98686302606783e-02 -9.84255751413317e-02 -9.71348114269263e-02 -9.60043544545646e-02 -9.48738974822025e-02 -9.37434405098408e-02 -9.26129835374792e-02 -9.12989917033083e-02 -8.96913440902429e-02 -8.80836964771775e-02 -8.56647822445562e-02 -8.30836146880233e-02 -8.08180551193467e-02 -7.93558613379396e-02 -7.78936675565325e-02 -7.65452261306533e-02 -7.52386934673367e-02 -7.39136110238692e-02 -7.25037295854271e-02 -7.10938481469850e-02 -6.95597289834587e-02 -6.79520813703938e-02 -6.62834844796900e-02 -6.38834962573283e-02 -6.14835080349667e-02 -5.85905765808208e-02 -5.52527939175042e-02 -5.19150112541875e-02 -5.04047254501675e-02 -4.89425316687604e-02 -4.74803378873533e-02 -4.60181441059462e-02 -4.45559503245396e-02 -4.32572694200167e-02 -4.19826345268008e-02 -4.07079996335846e-02 -3.94333647403685e-02 -3.81587298471524e-02 -3.67398188860972e-02 -3.52776251046901e-02 -3.38154313232831e-02 -3.23532375418760e-02 -3.08910437604690e-02 -2.80449120603015e-02 -2.45068114007538e-02 -2.12925957914573e-02 -2.05614989007538e-02 -1.98304020100502e-02 -1.83572484819933e-02 -1.63106875523450e-02 -1.42716185092127e-02 -1.28094247278057e-02 -1.13472309463987e-02 -9.11006857202683e-03 -5.96877617252933e-03 -2.82748377303185e-03 -1.43294597989951e-03 -2.10623429648250e-04 9.70935406197650e-04 2.07970189489112e-03 3.18846838358458e-03 4.29723487227804e-03 5.40600136097150e-03 6.44835505653267e-03 7.29811165201004e-03 8.14786824748742e-03 9.07859610552762e-03 1.00431846733668e-02 1.10140546482412e-02 1.20194723618090e-02 1.30248900753769e-02 1.46376740473199e-02 1.66510612960637e-02 1.86010455925460e-02 1.93780752721943e-02 2.01551049518425e-02 2.08121990159129e-02 2.13493574644054e-02 2.18865159128978e-02 2.24236743613903e-02 2.29608328098828e-02 2.35350090295226e-02 2.41653089667085e-02 2.47956089038945e-02 2.54528992619347e-02 2.61150969692211e-02 2.67494536484506e-02 2.73172339562395e-02 2.78850142640285e-02 2.91700527376465e-02 3.07024216132747e-02 3.21862077313651e-02 3.34659462677973e-02 3.47456848042295e-02 3.54275446241625e-02 3.57745923628560e-02 3.61470601706449e-02 3.67773601078308e-02 3.74076600450167e-02 3.86652173628559e-02 4.04604238641122e-02 4.22556303653683e-02 4.27774288107204e-02 4.32826894891121e-02 4.38424544597992e-02 4.44727543969850e-02 4.51030543341708e-02 4.56227426193467e-02 4.61280032977388e-02 4.67238536432162e-02 4.75008833228642e-02 4.82779130025125e-02 4.87605835165413e-02 4.91612195090033e-02 4.96148548733250e-02 5.02451548105108e-02 5.08754547476967e-02 5.22903580402008e-02 5.40753572550250e-02 5.57203334380233e-02 5.64131530046062e-02 5.71059725711892e-02 5.75809058312396e-02 5.78960557998325e-02 5.82198427030988e-02 5.88718331239529e-02 5.95238235448075e-02 6.04542242462313e-02 6.16931336369346e-02 6.29320430276383e-02 6.36091590766333e-02 6.42394590138192e-02 6.48232699958125e-02 6.53285306742042e-02 6.58337913525962e-02 6.68740185301508e-02 6.80312696293971e-02 6.90305040829146e-02 6.96008362123117e-02 7.01711683417083e-02 7.05298955716079e-02 7.08054923052763e-02 7.10494039206450e-02 7.11348899445142e-02 7.12203759683838e-02 7.19277212887354e-02 7.30237286693887e-02 7.40982255025125e-02 7.48586683417083e-02 7.56191111809046e-02 7.61845686767171e-02 7.65647900963150e-02 7.69450115159129e-02 7.74454629920438e-02 7.79507236704354e-02 7.86721694409546e-02 7.97043812814071e-02 8.07365931218592e-02 8.22170586002929e-02 8.37711179595896e-02 8.54739681480317e-02 8.75115977020521e-02 8.95492272560721e-02 9.02540371126467e-02 9.05296338463150e-02 9.13111455716079e-02 9.40530778894471e-02 9.67950102072862e-02 9.92366127512562e-02 1.01519217179648e-01 1.03600031407035e-01 1.03915181375628e-01 1.04230331344221e-01 1.04675607856993e-01 1.05226801324330e-01 1.05777994791667e-01 + 1.12847222222222e-04 2.08791352596315e-04 3.04735482970408e-04 2.75814838079285e-04 1.64483441513121e-04 1.30862646566331e-07 -3.70068659268564e-04 -7.40268181183697e-04 -1.08051106225572e-03 -1.41360011864880e-03 -1.74668917504188e-03 -2.07977823143495e-03 -2.41367427414852e-03 -2.81374319514239e-03 -3.21381211613622e-03 -3.83189820630933e-03 -4.58677938302625e-03 -5.58074661501953e-03 -7.43808015773311e-03 -9.29541370044667e-03 -1.03229472012842e-02 -1.11674365752373e-02 -1.20768120114461e-02 -1.30751740473199e-02 -1.40712677973199e-02 -1.49754959694305e-02 -1.58797241415410e-02 -1.66586295191234e-02 -1.73628232307370e-02 -1.81194383375209e-02 -1.90526307754048e-02 -1.99858232132887e-02 -2.19032336159966e-02 -2.40203404173646e-02 -2.57326890529034e-02 -2.69166034163875e-02 -2.81063738833053e-02 -2.94523071084589e-02 -3.07982403336125e-02 -3.21441735587661e-02 -3.34901067839197e-02 -3.47969993195142e-02 -3.59809136829983e-02 -3.71648280464825e-02 -3.83426354864600e-02 -3.95193087835008e-02 -4.08351872208264e-02 -4.23241315082356e-02 -4.38252896426578e-02 -4.55676712555833e-02 -4.73100528685092e-02 -4.85695513156058e-02 -4.95697236180906e-02 -5.05382925914294e-02 -5.14135564977667e-02 -5.22888204041039e-02 -5.31640843104411e-02 -5.40393482167783e-02 -5.48976217895031e-02 -5.57357752303183e-02 -5.66045178147683e-02 -5.79504510399219e-02 -5.92963842650753e-02 -5.99867501570353e-02 -6.03433726793692e-02 -6.07199081344222e-02 -6.11516567211056e-02 -6.15834053077889e-02 -6.21823963567839e-02 -6.28069383375208e-02 -6.35573701842547e-02 -6.44498316233947e-02 -6.53165131211614e-02 -6.58523520379675e-02 -6.63881909547739e-02 -6.73301402847572e-02 -6.84678928496650e-02 -6.94385992462311e-02 -6.99735330297319e-02 -7.05084668132328e-02 -7.10306632991344e-02 -7.15511149497489e-02 -7.20789821503350e-02 -7.26148210671414e-02 -7.31418812814069e-02 -7.35736298680906e-02 -7.40053784547739e-02 -7.45745001046900e-02 -7.52062831518706e-02 -7.57781311069236e-02 -7.62026386271636e-02 -7.66271461474036e-02 -7.76899798471525e-02 -7.88304478119767e-02 -7.96029409198772e-02 -7.99984841743439e-02 -8.03846925600222e-02 -8.06833865508097e-02 -8.09820805415969e-02 -8.12605344430486e-02 -8.15302641680625e-02 -8.18043559812953e-02 -8.20885678391958e-02 -8.23727796970967e-02 -8.29203526312117e-02 -8.34960174134561e-02 -8.38866424134561e-02 -8.40966333403128e-02 -8.43178130234506e-02 -8.46309891471245e-02 -8.49441652707983e-02 -8.53055969953936e-02 -8.56866581169736e-02 -8.59931493404522e-02 -8.61361604027081e-02 -8.62791714649636e-02 -8.64835134875767e-02 -8.66935044144333e-02 -8.70938786816025e-02 -8.76713537304578e-02 -8.82054260015356e-02 -8.84226579948353e-02 -8.86398899881350e-02 -8.87975794772472e-02 -8.89324443397544e-02 -8.90893922738694e-02 -8.92921421342825e-02 -8.94948919946958e-02 -8.96355039084311e-02 -8.97712739042433e-02 -9.00447550251256e-02 -9.04402982795925e-02 -9.08023734122000e-02 -9.09453844744555e-02 -9.10883955367114e-02 -9.14249851689000e-02 -9.18313900230320e-02 -9.21235954075936e-02 -9.21914804054997e-02 -9.22593654034058e-02 -9.23272504013122e-02 -9.23951353992183e-02 -9.24958996370742e-02 -9.26244285664433e-02 -9.27626413316583e-02 -9.29581501256281e-02 -9.31536589195981e-02 -9.32538342755445e-02 -9.33217192734506e-02 -9.34107931148800e-02 -9.35393220442492e-02 -9.36678509736180e-02 -9.37317664712450e-02 -9.37924104027081e-02 -9.38946904662200e-02 -9.40304604620325e-02 -9.41555978678114e-02 -9.42234828657175e-02 -9.42913678636236e-02 -9.43537566303742e-02 -9.44144005618369e-02 -9.45561793341708e-02 -9.48412963253769e-02 -9.51264133165831e-02 -9.51951707321328e-02 -9.52558146635958e-02 -9.54435698457567e-02 -9.57286868369625e-02 -9.59759409024289e-02 -9.60365848338917e-02 -9.60972287653544e-02 -9.61690396426578e-02 -9.62441657070072e-02 -9.63473509038247e-02 -9.64976030325236e-02 -9.66478551612228e-02 -9.67247914921831e-02 -9.67999175565328e-02 -9.68708560161919e-02 -9.69387410140983e-02 -9.70079346384703e-02 -9.70830607028197e-02 -9.71581867671692e-02 -9.72978172110553e-02 -9.74553104061978e-02 -9.75782558626467e-02 -9.76461408605528e-02 -9.77140258584589e-02 -9.77819108563653e-02 -9.78497958542714e-02 -9.79134060057231e-02 -9.79740499371858e-02 -9.80346938686489e-02 -9.80953378001117e-02 -9.81559817315744e-02 -9.82166256630375e-02 -9.82772695945003e-02 -9.83379135259631e-02 -9.83985574574261e-02 -9.84592013888889e-02 + -1.92968750000000e-01 -1.84181715871022e-01 -1.75394681742043e-01 -1.65925526067839e-01 -1.56006170173785e-01 -1.45711123979271e-01 -1.33957515441792e-01 -1.22203906904313e-01 -1.17790040698283e-01 -1.15128948780360e-01 -1.12467856862437e-01 -1.09806764944514e-01 -1.07154162740787e-01 -1.05197717101131e-01 -1.03241271461474e-01 -1.01000346786013e-01 -9.85809254606367e-02 -9.54583791352596e-02 -8.97967703098829e-02 -8.41351614845058e-02 -8.14468174204354e-02 -7.94143405831242e-02 -7.72564809725712e-02 -7.49266678444304e-02 -7.26131144001254e-02 -7.09580781511725e-02 -6.93030419022196e-02 -6.75569906825796e-02 -6.57566805381071e-02 -6.39414520519263e-02 -6.20759723094642e-02 -6.02104925670017e-02 -5.68686858773033e-02 -5.32273345896146e-02 -5.03951070456450e-02 -4.86192355004188e-02 -4.68345798000417e-02 -4.48156799623117e-02 -4.27967801245813e-02 -4.07778802868509e-02 -3.87589804491206e-02 -3.67986416457287e-02 -3.50227701005025e-02 -3.32468985552764e-02 -3.13301860866834e-02 -2.93873174466080e-02 -2.73839248324958e-02 -2.53052861966080e-02 -2.32008676193468e-02 -2.05872951999581e-02 -1.79737227805695e-02 -1.61781073335427e-02 -1.48217650753769e-02 -1.34764152795226e-02 -1.21635194200167e-02 -1.08506235605109e-02 -9.53772770100504e-03 -8.22483184149917e-03 -7.00331082495812e-03 -5.88999685929650e-03 -4.67330140284758e-03 -1.84385469011726e-03 9.85592022613058e-04 2.29457836055276e-03 2.82951214405360e-03 3.49471969221105e-03 4.52114086055275e-03 5.54756202889446e-03 6.61167163944721e-03 7.68153920644892e-03 9.00276120184254e-03 1.06075625523450e-02 1.21833123953099e-02 1.33862345582077e-02 1.45891567211055e-02 1.64021605422948e-02 1.85093108773032e-02 2.03256353381491e-02 2.13832836055276e-02 2.24409318729062e-02 2.34711153423367e-02 2.44975365106784e-02 2.55448957024707e-02 2.66147632694724e-02 2.76809666823702e-02 2.87073878507119e-02 2.97338090190536e-02 3.08049852125209e-02 3.18965759788526e-02 3.29724632275963e-02 3.40097459956030e-02 3.50470287636097e-02 3.68033363431742e-02 3.86470928863065e-02 3.99281564070352e-02 4.06328026853015e-02 4.13341773974037e-02 4.20048811767171e-02 4.26755849560300e-02 4.31603329145729e-02 4.35649275020938e-02 4.40095987751254e-02 4.45472479585425e-02 4.50848971419600e-02 4.60077732412058e-02 4.69717402114742e-02 4.77199801088779e-02 4.82576292922950e-02 4.88266364373954e-02 4.96534757118929e-02 5.04803149863904e-02 5.11257132014237e-02 5.16973048837942e-02 5.22582639761308e-02 5.27959131595479e-02 5.33335623429650e-02 5.38712115263821e-02 5.44088607097992e-02 5.52208307160804e-02 5.62879828831658e-02 5.72913395100504e-02 5.78289886934675e-02 5.83666378768846e-02 5.89042870603017e-02 5.94419362437187e-02 5.99036196608042e-02 6.02077444514237e-02 6.05118692420433e-02 6.09092009526800e-02 6.13137955402008e-02 6.18774536746229e-02 6.25820999528896e-02 6.32646140860554e-02 6.38022632694725e-02 6.43399124528896e-02 6.52258034966500e-02 6.62372899654521e-02 6.69757969535175e-02 6.71780942472779e-02 6.73803915410383e-02 6.77727995445979e-02 6.81773941321187e-02 6.85216283239113e-02 6.88148915148658e-02 6.91374025073283e-02 6.96329629920433e-02 7.01285234767588e-02 7.06920343907033e-02 7.12785607726129e-02 7.17626217022612e-02 7.20558848932163e-02 7.23491480841708e-02 7.26424112751254e-02 7.29356744660804e-02 7.32906393948912e-02 7.36952339824121e-02 7.40823911222779e-02 7.43756543132329e-02 7.46689175041875e-02 7.49621806951425e-02 7.52554438860971e-02 7.59044898974037e-02 7.71820855579983e-02 7.84596812185929e-02 7.85935373481992e-02 7.86845032453937e-02 7.92183083385679e-02 8.00913094116417e-02 8.09384323963567e-02 8.16580133741625e-02 8.23775943519683e-02 8.35944533867254e-02 8.49589418446400e-02 8.63817459694304e-02 8.79023699225292e-02 8.94229938756279e-02 9.01141776591288e-02 9.07848814384421e-02 9.15356731574537e-02 9.23448623324958e-02 9.39951711683417e-02 9.94585557998325e-02 1.04921940431323e-01 1.10229025989322e-01 1.15492828726968e-01 1.19039190091080e-01 1.19848379266122e-01 1.20657568441164e-01 1.21806117174414e-01 1.22958804438861e-01 1.23657823623325e-01 1.24042052711474e-01 1.24404820325586e-01 1.24677718017169e-01 1.24950615708752e-01 1.25456710636516e-01 1.26022871519054e-01 1.26689436767169e-01 1.27508129841918e-01 1.28326822916667e-01 diff --git a/data/data_txyz.txt b/data/data_txyz.txt deleted file mode 100755 index bf192d3..0000000 --- a/data/data_txyz.txt +++ /dev/null @@ -1,4 +0,0 @@ - 2.558000000000e+00 2.588000000000e+00 2.618000000000e+00 2.648000000000e+00 2.678000000000e+00 2.708000000000e+00 2.738000000000e+00 2.768000000000e+00 2.798000000000e+00 2.828000000000e+00 2.858000000000e+00 2.888000000000e+00 2.918000000000e+00 2.948000000000e+00 2.978000000000e+00 3.008000000000e+00 3.038000000000e+00 3.068000000000e+00 3.098000000000e+00 3.128000000000e+00 3.158000000000e+00 3.188000000000e+00 3.218000000000e+00 3.248000000000e+00 3.278000000000e+00 3.308000000000e+00 3.338000000000e+00 3.368000000000e+00 3.398000000000e+00 3.428000000000e+00 3.458000000000e+00 3.488000000000e+00 3.518000000000e+00 3.548000000000e+00 3.578000000000e+00 3.608000000000e+00 3.638000000000e+00 3.668000000000e+00 3.698000000000e+00 3.728000000000e+00 3.758000000000e+00 3.788000000000e+00 3.818000000000e+00 3.848000000000e+00 3.878000000000e+00 3.908000000000e+00 3.938000000000e+00 3.968000000000e+00 3.998000000000e+00 4.028000000000e+00 4.058000000000e+00 4.088000000000e+00 4.118000000000e+00 4.148000000000e+00 4.178000000000e+00 4.208000000000e+00 4.238000000000e+00 4.268000000000e+00 4.298000000000e+00 4.328000000000e+00 4.358000000000e+00 4.388000000000e+00 4.418000000000e+00 4.448000000000e+00 4.478000000000e+00 4.508000000000e+00 4.538000000000e+00 4.568000000000e+00 4.598000000000e+00 4.628000000000e+00 4.658000000000e+00 4.688000000000e+00 4.718000000000e+00 4.748000000000e+00 4.778000000000e+00 4.808000000000e+00 4.838000000000e+00 4.868000000000e+00 4.898000000000e+00 4.928000000000e+00 4.958000000000e+00 4.988000000000e+00 5.018000000000e+00 5.048000000000e+00 5.078000000000e+00 5.108000000000e+00 5.138000000000e+00 5.168000000000e+00 5.198000000000e+00 5.228000000000e+00 5.258000000000e+00 5.288000000000e+00 5.318000000000e+00 5.348000000000e+00 5.378000000000e+00 5.408000000000e+00 5.438000000000e+00 5.468000000000e+00 5.498000000000e+00 5.528000000000e+00 5.558000000000e+00 5.588000000000e+00 5.618000000000e+00 5.648000000000e+00 5.678000000000e+00 5.708000000000e+00 5.738000000000e+00 5.768000000000e+00 5.798000000000e+00 5.828000000000e+00 5.858000000000e+00 5.888000000000e+00 5.918000000000e+00 5.948000000000e+00 5.978000000000e+00 6.008000000000e+00 6.038000000000e+00 6.068000000000e+00 6.098000000000e+00 6.128000000000e+00 6.158000000000e+00 6.188000000000e+00 6.218000000000e+00 6.248000000000e+00 6.278000000000e+00 6.308000000000e+00 6.338000000000e+00 6.368000000000e+00 6.398000000000e+00 6.428000000000e+00 6.458000000000e+00 6.488000000000e+00 6.518000000000e+00 6.548000000000e+00 6.578000000000e+00 6.608000000000e+00 6.638000000000e+00 6.668000000000e+00 6.698000000000e+00 6.728000000000e+00 6.758000000000e+00 6.788000000000e+00 6.818000000000e+00 6.848000000000e+00 6.878000000000e+00 6.908000000000e+00 6.938000000000e+00 6.968000000000e+00 6.998000000000e+00 7.028000000000e+00 7.058000000000e+00 7.088000000000e+00 7.118000000000e+00 7.148000000000e+00 7.178000000000e+00 7.208000000000e+00 7.238000000000e+00 7.268000000000e+00 7.298000000000e+00 7.328000000000e+00 7.358000000000e+00 7.388000000000e+00 7.418000000000e+00 7.448000000000e+00 7.478000000000e+00 7.508000000000e+00 7.538000000000e+00 7.568000000000e+00 7.598000000000e+00 7.628000000000e+00 7.658000000000e+00 7.688000000000e+00 7.718000000000e+00 7.748000000000e+00 7.778000000000e+00 7.808000000000e+00 7.838000000000e+00 7.868000000000e+00 7.898000000000e+00 7.928000000000e+00 7.958000000000e+00 7.988000000000e+00 8.018000000000e+00 8.048000000000e+00 8.078000000000e+00 8.108000000000e+00 8.138000000000e+00 8.168000000000e+00 8.198000000000e+00 8.228000000000e+00 8.258000000000e+00 8.288000000000e+00 8.318000000000e+00 8.348000000000e+00 8.378000000000e+00 8.408000000000e+00 8.438000000000e+00 8.468000000000e+00 8.498000000000e+00 8.528000000000e+00 - -4.138280000000e-02 -4.128380000000e-02 -4.118460000000e-02 -4.111850000000e-02 -4.109110000000e-02 -4.122540000000e-02 -4.119490000000e-02 -4.109150000000e-02 -4.098660000000e-02 -4.093660000000e-02 -4.081370000000e-02 -4.081520000000e-02 -4.085460000000e-02 -4.085480000000e-02 -4.080270000000e-02 -4.087280000000e-02 -4.082000000000e-02 -4.082000000000e-02 -4.085010000000e-02 -4.079540000000e-02 -4.091310000000e-02 -4.112710000000e-02 -4.124570000000e-02 -4.148960000000e-02 -4.176360000000e-02 -4.201620000000e-02 -4.237480000000e-02 -4.270680000000e-02 -4.314970000000e-02 -4.384060000000e-02 -4.463840000000e-02 -4.555840000000e-02 -4.670290000000e-02 -4.799070000000e-02 -4.947540000000e-02 -5.110290000000e-02 -5.276330000000e-02 -5.465380000000e-02 -5.675500000000e-02 -5.900450000000e-02 -6.144370000000e-02 -6.413990000000e-02 -6.696350000000e-02 -6.986060000000e-02 -7.277410000000e-02 -7.567440000000e-02 -7.858980000000e-02 -8.150870000000e-02 -8.439960000000e-02 -8.721500000000e-02 -9.004500000000e-02 -9.273480000000e-02 -9.543380000000e-02 -9.809190000000e-02 -1.008210000000e-01 -1.036000000000e-01 -1.063640000000e-01 -1.091690000000e-01 -1.120610000000e-01 -1.149260000000e-01 -1.179100000000e-01 -1.209620000000e-01 -1.239490000000e-01 -1.270040000000e-01 -1.299380000000e-01 -1.328710000000e-01 -1.358440000000e-01 -1.388130000000e-01 -1.420140000000e-01 -1.452510000000e-01 -1.484770000000e-01 -1.518810000000e-01 -1.551660000000e-01 -1.585760000000e-01 -1.621550000000e-01 -1.656510000000e-01 -1.691000000000e-01 -1.728500000000e-01 -1.767700000000e-01 -1.806790000000e-01 -1.845660000000e-01 -1.886760000000e-01 -1.930510000000e-01 -1.975430000000e-01 -2.020890000000e-01 -2.066010000000e-01 -2.110510000000e-01 -2.154470000000e-01 -2.198470000000e-01 -2.242830000000e-01 -2.287530000000e-01 -2.333150000000e-01 -2.378820000000e-01 -2.425840000000e-01 -2.472870000000e-01 -2.520370000000e-01 -2.569040000000e-01 -2.618170000000e-01 -2.668180000000e-01 -2.719420000000e-01 -2.771900000000e-01 -2.824270000000e-01 -2.876570000000e-01 -2.928140000000e-01 -2.979500000000e-01 -3.030480000000e-01 -3.081280000000e-01 -3.131070000000e-01 -3.180290000000e-01 -3.228730000000e-01 -3.276080000000e-01 -3.322330000000e-01 -3.368240000000e-01 -3.413440000000e-01 -3.459410000000e-01 -3.504940000000e-01 -3.549890000000e-01 -3.592840000000e-01 -3.634110000000e-01 -3.674900000000e-01 -3.715730000000e-01 -3.754790000000e-01 -3.791470000000e-01 -3.826810000000e-01 -3.860500000000e-01 -3.892400000000e-01 -3.922160000000e-01 -3.949410000000e-01 -3.974520000000e-01 -3.997970000000e-01 -4.019670000000e-01 -4.039920000000e-01 -4.059120000000e-01 -4.077690000000e-01 -4.094900000000e-01 -4.111720000000e-01 -4.127280000000e-01 -4.141410000000e-01 -4.154280000000e-01 -4.166760000000e-01 -4.177700000000e-01 -4.187070000000e-01 -4.195150000000e-01 -4.201580000000e-01 -4.206350000000e-01 -4.209200000000e-01 -4.210500000000e-01 -4.212330000000e-01 -4.213320000000e-01 -4.215270000000e-01 -4.217630000000e-01 -4.222220000000e-01 -4.228060000000e-01 -4.235410000000e-01 -4.242920000000e-01 -4.249860000000e-01 -4.254730000000e-01 -4.258540000000e-01 -4.260700000000e-01 -4.261890000000e-01 -4.262420000000e-01 -4.261060000000e-01 -4.258510000000e-01 -4.255640000000e-01 -4.252600000000e-01 -4.249640000000e-01 -4.247250000000e-01 -4.246590000000e-01 -4.247490000000e-01 -4.248800000000e-01 -4.250620000000e-01 -4.251540000000e-01 -4.253910000000e-01 -4.258290000000e-01 -4.262490000000e-01 -4.267580000000e-01 -4.273600000000e-01 -4.280980000000e-01 -4.288740000000e-01 -4.295480000000e-01 -4.301330000000e-01 -4.304160000000e-01 -4.304660000000e-01 -4.304140000000e-01 -4.301310000000e-01 -4.298390000000e-01 -4.293690000000e-01 -4.290000000000e-01 -4.286180000000e-01 -4.283170000000e-01 -4.280460000000e-01 -4.280630000000e-01 -4.282210000000e-01 -4.285090000000e-01 -4.288780000000e-01 -4.291940000000e-01 -4.295450000000e-01 -4.299310000000e-01 -4.302640000000e-01 -4.304370000000e-01 - -5.470480000000e-01 -5.475560000000e-01 -5.481030000000e-01 -5.487480000000e-01 -5.493600000000e-01 -5.499890000000e-01 -5.507110000000e-01 -5.513950000000e-01 -5.522130000000e-01 -5.530300000000e-01 -5.538640000000e-01 -5.547440000000e-01 -5.557010000000e-01 -5.567200000000e-01 -5.577410000000e-01 -5.587940000000e-01 -5.599220000000e-01 -5.610460000000e-01 -5.622010000000e-01 -5.633260000000e-01 -5.643390000000e-01 -5.653070000000e-01 -5.661110000000e-01 -5.670120000000e-01 -5.679550000000e-01 -5.689480000000e-01 -5.699700000000e-01 -5.709140000000e-01 -5.716770000000e-01 -5.723790000000e-01 -5.730960000000e-01 -5.738260000000e-01 -5.746060000000e-01 -5.753780000000e-01 -5.760880000000e-01 -5.767600000000e-01 -5.774490000000e-01 -5.780960000000e-01 -5.786930000000e-01 -5.792780000000e-01 -5.797710000000e-01 -5.802710000000e-01 -5.807040000000e-01 -5.810770000000e-01 -5.814400000000e-01 -5.817660000000e-01 -5.820170000000e-01 -5.822400000000e-01 -5.824390000000e-01 -5.825710000000e-01 -5.826880000000e-01 -5.827830000000e-01 -5.828460000000e-01 -5.828550000000e-01 -5.828150000000e-01 -5.827290000000e-01 -5.826320000000e-01 -5.824680000000e-01 -5.822770000000e-01 -5.820650000000e-01 -5.818050000000e-01 -5.814990000000e-01 -5.811170000000e-01 -5.807800000000e-01 -5.803840000000e-01 -5.799910000000e-01 -5.795700000000e-01 -5.790970000000e-01 -5.785830000000e-01 -5.780320000000e-01 -5.774140000000e-01 -5.767530000000e-01 -5.760510000000e-01 -5.753140000000e-01 -5.744910000000e-01 -5.736740000000e-01 -5.728100000000e-01 -5.717760000000e-01 -5.706800000000e-01 -5.695310000000e-01 -5.683300000000e-01 -5.670160000000e-01 -5.655920000000e-01 -5.640050000000e-01 -5.623920000000e-01 -5.607500000000e-01 -5.591230000000e-01 -5.574120000000e-01 -5.557230000000e-01 -5.539420000000e-01 -5.521180000000e-01 -5.502060000000e-01 -5.482140000000e-01 -5.461790000000e-01 -5.440680000000e-01 -5.418440000000e-01 -5.395900000000e-01 -5.372250000000e-01 -5.347190000000e-01 -5.321310000000e-01 -5.294550000000e-01 -5.266450000000e-01 -5.238390000000e-01 -5.209370000000e-01 -5.180510000000e-01 -5.150470000000e-01 -5.120160000000e-01 -5.089810000000e-01 -5.059080000000e-01 -5.028280000000e-01 -4.997460000000e-01 -4.966700000000e-01 -4.935760000000e-01 -4.903780000000e-01 -4.870790000000e-01 -4.837260000000e-01 -4.803210000000e-01 -4.769300000000e-01 -4.735900000000e-01 -4.702860000000e-01 -4.668170000000e-01 -4.634490000000e-01 -4.601970000000e-01 -4.569380000000e-01 -4.537370000000e-01 -4.506480000000e-01 -4.476730000000e-01 -4.448370000000e-01 -4.421060000000e-01 -4.394290000000e-01 -4.368390000000e-01 -4.342900000000e-01 -4.317770000000e-01 -4.292560000000e-01 -4.267870000000e-01 -4.242550000000e-01 -4.217530000000e-01 -4.192480000000e-01 -4.168140000000e-01 -4.143290000000e-01 -4.118770000000e-01 -4.095260000000e-01 -4.072010000000e-01 -4.049520000000e-01 -4.028830000000e-01 -4.010130000000e-01 -3.992910000000e-01 -3.977090000000e-01 -3.963780000000e-01 -3.952120000000e-01 -3.944030000000e-01 -3.939610000000e-01 -3.937110000000e-01 -3.936850000000e-01 -3.937510000000e-01 -3.938700000000e-01 -3.939440000000e-01 -3.938900000000e-01 -3.937050000000e-01 -3.934050000000e-01 -3.929420000000e-01 -3.923180000000e-01 -3.915000000000e-01 -3.905960000000e-01 -3.895940000000e-01 -3.885580000000e-01 -3.876200000000e-01 -3.868580000000e-01 -3.862240000000e-01 -3.857820000000e-01 -3.853890000000e-01 -3.849920000000e-01 -3.848210000000e-01 -3.848840000000e-01 -3.850920000000e-01 -3.853750000000e-01 -3.858430000000e-01 -3.864830000000e-01 -3.871970000000e-01 -3.879600000000e-01 -3.885290000000e-01 -3.887750000000e-01 -3.889270000000e-01 -3.888950000000e-01 -3.888480000000e-01 -3.885840000000e-01 -3.883660000000e-01 -3.879370000000e-01 -3.876550000000e-01 -3.873570000000e-01 -3.871920000000e-01 -3.871290000000e-01 -3.872690000000e-01 -3.875000000000e-01 -3.878450000000e-01 -3.882720000000e-01 -3.886360000000e-01 -3.890310000000e-01 -3.892670000000e-01 -3.893340000000e-01 - -2.514030000000e-01 -2.503000000000e-01 -2.490490000000e-01 -2.477160000000e-01 -2.462920000000e-01 -2.448610000000e-01 -2.432370000000e-01 -2.415620000000e-01 -2.397740000000e-01 -2.378910000000e-01 -2.358950000000e-01 -2.337450000000e-01 -2.314530000000e-01 -2.289930000000e-01 -2.264170000000e-01 -2.237300000000e-01 -2.209010000000e-01 -2.179550000000e-01 -2.148730000000e-01 -2.117570000000e-01 -2.086180000000e-01 -2.053530000000e-01 -2.021090000000e-01 -1.987730000000e-01 -1.954750000000e-01 -1.921470000000e-01 -1.888380000000e-01 -1.856150000000e-01 -1.824310000000e-01 -1.792880000000e-01 -1.762260000000e-01 -1.731780000000e-01 -1.701980000000e-01 -1.672030000000e-01 -1.642840000000e-01 -1.614020000000e-01 -1.583950000000e-01 -1.553480000000e-01 -1.523420000000e-01 -1.492320000000e-01 -1.461700000000e-01 -1.431500000000e-01 -1.400680000000e-01 -1.369310000000e-01 -1.338380000000e-01 -1.307780000000e-01 -1.277800000000e-01 -1.248810000000e-01 -1.220200000000e-01 -1.192180000000e-01 -1.165110000000e-01 -1.138970000000e-01 -1.113670000000e-01 -1.089320000000e-01 -1.066310000000e-01 -1.044120000000e-01 -1.022080000000e-01 -9.996620000000e-02 -9.782950000000e-02 -9.574580000000e-02 -9.370660000000e-02 -9.168980000000e-02 -8.970820000000e-02 -8.778180000000e-02 -8.589490000000e-02 -8.404420000000e-02 -8.221080000000e-02 -8.032250000000e-02 -7.841050000000e-02 -7.655680000000e-02 -7.475370000000e-02 -7.300030000000e-02 -7.138830000000e-02 -6.981720000000e-02 -6.835770000000e-02 -6.707550000000e-02 -6.587930000000e-02 -6.482570000000e-02 -6.390060000000e-02 -6.322260000000e-02 -6.275050000000e-02 -6.246190000000e-02 -6.231650000000e-02 -6.231340000000e-02 -6.231340000000e-02 -6.231340000000e-02 -6.228920000000e-02 -6.229950000000e-02 -6.228920000000e-02 -6.228980000000e-02 -6.227520000000e-02 -6.227090000000e-02 -6.229950000000e-02 -6.230310000000e-02 -6.228920000000e-02 -6.231840000000e-02 -6.232150000000e-02 -6.230310000000e-02 -6.233240000000e-02 -6.233240000000e-02 -6.232150000000e-02 -6.235010000000e-02 -6.233980000000e-02 -6.238240000000e-02 -6.237210000000e-02 -6.241470000000e-02 -6.247930000000e-02 -6.252990000000e-02 -6.257680000000e-02 -6.264070000000e-02 -6.271930000000e-02 -6.282580000000e-02 -6.303730000000e-02 -6.341230000000e-02 -6.392100000000e-02 -6.457260000000e-02 -6.543600000000e-02 -6.652940000000e-02 -6.771790000000e-02 -6.896010000000e-02 -7.039470000000e-02 -7.191040000000e-02 -7.353000000000e-02 -7.529710000000e-02 -7.720660000000e-02 -7.925710000000e-02 -8.141310000000e-02 -8.375550000000e-02 -8.629870000000e-02 -8.909270000000e-02 -9.201760000000e-02 -9.515990000000e-02 -9.837280000000e-02 -1.018350000000e-01 -1.054360000000e-01 -1.091750000000e-01 -1.130820000000e-01 -1.171560000000e-01 -1.213540000000e-01 -1.256670000000e-01 -1.301290000000e-01 -1.347130000000e-01 -1.394150000000e-01 -1.443240000000e-01 -1.493140000000e-01 -1.544690000000e-01 -1.596990000000e-01 -1.648670000000e-01 -1.700940000000e-01 -1.751760000000e-01 -1.802100000000e-01 -1.849830000000e-01 -1.896530000000e-01 -1.941550000000e-01 -1.984960000000e-01 -2.027890000000e-01 -2.069810000000e-01 -2.110880000000e-01 -2.152030000000e-01 -2.192400000000e-01 -2.231620000000e-01 -2.269910000000e-01 -2.307290000000e-01 -2.343060000000e-01 -2.377300000000e-01 -2.409770000000e-01 -2.441080000000e-01 -2.469330000000e-01 -2.495310000000e-01 -2.519620000000e-01 -2.541220000000e-01 -2.560980000000e-01 -2.579000000000e-01 -2.595560000000e-01 -2.611170000000e-01 -2.625230000000e-01 -2.639600000000e-01 -2.653660000000e-01 -2.668090000000e-01 -2.683740000000e-01 -2.698980000000e-01 -2.716740000000e-01 -2.735650000000e-01 -2.756140000000e-01 -2.779150000000e-01 -2.802500000000e-01 -2.827200000000e-01 -2.852560000000e-01 -2.877360000000e-01 -2.901260000000e-01 -2.924020000000e-01 -2.944650000000e-01 -2.964280000000e-01 -2.982830000000e-01 -2.999970000000e-01 -3.015580000000e-01 -3.030000000000e-01 -3.043260000000e-01 -3.055140000000e-01 -3.065700000000e-01 diff --git a/docs/LICENSE_gfx_ui.txt b/docs/LICENSE_gfx_ui.txt new file mode 100644 index 0000000..f5cc299 --- /dev/null +++ b/docs/LICENSE_gfx_ui.txt @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2018 colormotor + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/LICENSE b/docs/LICENSE_imgui.txt similarity index 96% rename from LICENSE rename to docs/LICENSE_imgui.txt index fa86300..21b6ee7 100644 --- a/LICENSE +++ b/docs/LICENSE_imgui.txt @@ -1,6 +1,6 @@ The MIT License (MIT) -Copyright (c) 2014 Omar Cornut +Copyright (c) 2014-2018 Omar Cornut Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal diff --git a/examples.md b/examples.md new file mode 100644 index 0000000..426067a --- /dev/null +++ b/examples.md @@ -0,0 +1,175 @@ +### References + +Did you find PbDlib useful for your research? Please acknowledge the authors in any academic publications that used parts of these codes. +<br><br> + +[1] Tutorial (GMM, TP-GMM, MFA, MPPCA, GMR, LWR, GPR, MPC, LQR, trajGMM): +``` +@article{Calinon16JIST, + author="Calinon, S.", + title="A Tutorial on Task-Parameterized Movement Learning and Retrieval", + journal="Intelligent Service Robotics", + publisher="Springer Berlin Heidelberg", + year="2016", + volume="9", + number="1", + pages="1--29", + doi="10.1007/s11370-015-0187-9", +} +``` + +[2] HMM, HSMM: +``` +@article{Rozo16Frontiers, + author="Rozo, L. and Silv\'erio, J. and Calinon, S. and Caldwell, D. G.", + title="Learning Controllers for Reactive and Proactive Behaviors in Human-Robot Collaboration", + journal="Frontiers in Robotics and {AI}", + year="2016", + month="June", + volume="3", + number="30", + pages="1--11", + doi="10.3389/frobt.2016.00030" +} +``` + +[3] Riemannian manifolds (S2,S3): +``` +@article{Zeestraten17RAL, + author="Zeestraten, M. J. A. and Havoutis, I. and Silv\'erio, J. and Calinon, S. and Caldwell, D. G.", + title="An Approach for Imitation Learning on {R}iemannian Manifolds", + journal="{IEEE} Robotics and Automation Letters ({RA-L})", + year="2017", + month="June", + volume="2", + number="3", + pages="1240--1247" + doi="10.1109/LRA.2017.2657001", +} +``` + +[4] Riemannian manifolds (S+): +``` +@inproceedings{Jaquier17IROS, + author="Jaquier, N. and Calinon, S.", + title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: Application to Wrist Motion Estimation with {sEMG}", + booktitle="Proc. {IEEE/RSJ} Intl Conf. on Intelligent Robots and Systems ({IROS})", + year="2017", + month="September", + address="Vancouver, Canada", + pages="" +} +``` + +[5] Semi-tied GMM: +``` +@article{Tanwani16RAL, + author="Tanwani, A. K. and Calinon, S.", + title="Learning Robot Manipulation Tasks with Task-Parameterized Semi-Tied Hidden Semi-{M}arkov Model", + journal="{IEEE} Robotics and Automation Letters ({RA-L})", + year="2016", + month="January", + volume="1", + number="1", + pages="235--242", + doi="10.1109/LRA.2016.2517825" +} +``` + +[6] DP-means: +``` +@article{Bruno17AURO, + author="Bruno, D. and Calinon, S. and Caldwell, D. G.", + title="Learning Autonomous Behaviours for the Body of a Flexible Surgical Robot", + journal="Autonomous Robots", + year="2017", + month="February", + volume="41", + number="2", + pages="333--347", + doi="10.1007/s10514-016-9544-6" +} +``` + +[7] Shared control, adaptive teleoperation: +``` +@inproceedings{Havoutis17ICRA, + author="Havoutis, I. and Calinon, S.", + title="Supervisory teleoperation with online learning and optimal control", + booktitle=ICRA, + year="2017", + month="May-June", + address="Singapore", + pages="1534--1540" +} +``` + +[8] Keypoint-based motion edition through MPC: +``` +@inproceedings{Berio17GI, + author="Berio, D. and Calinon, S. and Fol Leymarie, F.", + title="Generating Calligraphic Trajectories with Model Predictive Control", + booktitle="Proc. 43rd Conf. on Graphics Interface", + year="2017", + month="May", + address="Edmonton, AL, Canada", + pages="132--139", + doi="10.20380/GI2017.17" +} +``` + +[9] Adaptive assistance: +``` +@article{Pignat17RAS, + author="Pignat, E. and Calinon, S.", + title="Learning adaptive dressing assistance from human demonstration", + journal="Robotics and Autonomous Systems", + year="2017", + month="July", + volume="93", + number="", + pages="61--75", + doi="10.1016/j.robot.2017.03.017", +} +``` + +[10] Gaussian Mixture Regression: +``` +@article{Jaquier17IROS, + author="Jaquier, N. and Calinon, S.", + title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: + Application to Wrist Motion Estimation with s{EMG}", + year="2017, submitted for publication", + booktitle = "{IEEE/RSJ} Intl. Conf. on Intelligent Robots and Systems ({IROS})", + address = "Vancouver, Canada" +} +``` + + +### List of examples + +This project will build a number of executables, as listed in the table below. + +| Filename | ref. | Description | +|----------|------|-------------| +| demo\_infHorLQR01\_glsl | [1] | Discrete infinite horizon linear quadratic regulation | +| demo\_MPC\_batch01 | [1,8] | Model predictive control (MPC) with batch linear quadratic tracking (LQT) formulation | +| demo\_MPC\_iterative01 | [1,8] | Model predictive control (MPC) with iterative linear quadratic tracking (LQT) formulation | +| demo\_MPC\_semitied01 | [5,8] | MPC with semi-tied covariances | +| demo\_MPC\_velocity01 | [1,8] | MPC with an objective including velocity tracking | +| demo\_online\_gmm01 | [6] | Online GMM learning and LQR-based trajectory generation | +| demo\_online\_hsmm01 | [2,7] | Online HSMM learning and sampling with LQR-based trajectory generation | +| demo\_proMP01 | [] | Conditioning on trajectory distributions with ProMP | +| demo\_Riemannian\_cov\_GMR01 | [10] | GMR with time as input and covariance data as output by relying on Riemannian manifold | +| demo\_Riemannian\_cov\_interp02 | [4] | Covariance interpolation on Riemannian manifold from a GMM with augmented covariances | +| demo\_Riemannian\_pose\_batchLQR01 | [] | Linear quadratic regulation of pose by relying on Riemannian manifold and batch LQR (MPC without constraints) | +| demo\_Riemannian\_pose\_gmm01 | [] | GMM for 3D position and unit quaternion data by relying on Riemannian manifold | +| demo\_Riemannian\_pose\_infHorLQR01 | [] | Linear quadratic regulation of pose by relying on Riemannian manifold and infinite-horizon LQR | +| demo\_Riemannian\_pose\_tpgmm01 | [] | TP-GMM of pose (R3 x S3) with two frames | +| demo\_Riemannian\_quat\_infHorLQR01 | [3] | Linear quadratic regulation on hypersphere (orientation as unit quaternions) by relying on Riemannian manifold and infinite-horizon LQR | +| demo\_Riemannian\_quat\_tpgmm01 | [] | TP-GMM on S3 (unit quaternion) with two frames | +| demo\_Riemannian\_sphere\_gmm01 | [3] | GMM for data on a sphere by relying on Riemannian manifold | +| demo\_Riemannian\_sphere\_infHorLQR01 | [3] | Linear quadratic regulation on a sphere by relying on Riemannian manifold and infinite-horizon LQR | +| demo\_Riemannian\_sphere\_product01 | [] | Gaussian product on sphere | +| demo\_Riemannian\_sphere\_tpgmm01 | [3] | TP-GMM for data on a sphere by relying on Riemannian manifold (with single frame) | +| demo\_TPbatchLQR01 | [1] | Linear quadratic control (unconstrained linear MPC) acting in multiple frames, which is equivalent to the fusion of Gaussian controllers | diff --git a/images/demo_MPC_batch01.gif b/images/demo_MPC_batch01.gif new file mode 100644 index 0000000000000000000000000000000000000000..070a1d7fbed3ef70d5870f799973d07f221d6150 GIT binary patch literal 396388 zcmW(*cTf||(+=r$q)C%r0@6glfPi!YQbI?X^r8qs0Rd4Vfq>M2AXN#yW9SH|^bXRc zsi7B9Bhp3ky}xhgx!aw&o%`qZnVWs?3=H*=Dz1@0P2e#=9zX?vK%g5+>#DeKs?jSq zabMID)ipJG^v#@Zo8=nct~K>~VfxU+>~5&pvl;Z=V6<BVI<U>${ket5Gt2*nl}DtN z=X0xvIo56=*2&ZM*m-;WsFUBEv(sJYXPtLlz3;wpb-|K66Iwl!y}Ugye0=Wt_=ot! z*Zagb{0HCodf$Ww--Jfr#O8akHTUsN4+2&m1Y`XZs{Nb&F;6oBpHBw9C=Ck!5Y!nQ z{472sF8^_Qcj(iLu<)qx&?isu6Hk(hBO;n2UamxxK7AgO{5-8R>Ul?0Bo0d?Mq^{6 zv2D>YG0`z`F}T?O+<%6T#^a;o@X<Z^|Kk54KQ{Wmwb=gw9}^cH6^D<H!*{-jjd>B< z6OVfy9~&1R`ynAVCLt~^F*!9czd0$fJt=u81s6rgE>0s%zD(Ol&%Q`6+)1xX&&<fo zDs0GpGn+G%o14?0Tho>ME;p|(Kkwt~!h)jWx1A;B7bUHuB^~pnB?}d8^_A5%l|xlk zmETES3-yfy^}QDj_>6|yx@LFJ7Im$b=65YaUs^u3wA$IfYx&Ujp{?WNLdVyR_Y-UH zXMca_`1A2&Pw(JGUr%4(x1;{Givc`-V19St>%hRu;lRqp;Ogn%>iN*x#n2jcX#HY% z?R<FcznMC`P91q1Hj+XZnOPtC@@Hh_Xk_(lWbI<KZ(ww8bZq5fyrOD+ZtPQb&Zq5* ziS>)gPcxI`!^y3)$?q4_lNZxVJ2Ue$bHC^24UFa^aSOjL7QOE+#=KZuSX}!0W9ee~ z>+T78jY|HtwNhBL^6g@kPhhR~?b@f&&4s0{jLfao?XBaBt&6Rl?-#ovVLyKU_}SI{ z>*5#X;B>#P;o$J%;NtM`;^Or5&*|CU(~Hxye;0qxsOM*Y&;K5r|2sebck%D+-@m`q zfB#PY{X4%Xt+?nPxcK_*V(;h0$;rjv|FSPG&Mz+h9bWu9z4$NT-+%G{<KjP~Qe_pW zHg~A5o>a^uYEp_2mEKg(%2G!Qt*0O>52678079o=h{u0k`o95){EsF8I2FM0pvv~s zn=TxjP0DeQRL~R4B4U(>sw?bE;JP|IUH0h`tAJ5DlH0Jpc<3d<veI#=zGNg*-hDXF zu%UD;7x`#+dC1ZWB_{CBqe|j!`D795rIgcfW5skCy2$9YQB&n?mCcW#M+YF<%d&Re z@mFp)S1&a9OjrIJe)V9n`N5~|;QJvzZQq4_>z=)NIpAAc7!CEX-4?S_AJWB>oS=No zwLcDIz~5o_+r7=RC@y1FBws5mzb>BNq^)shy4?JG`;4_w`e%~+$QzUP<{wL~0k;>% z+K>0Xb~;TneP~w>{Q5D4KBXo?WpA_pg~6>id2N2%Jtf{P<Bnm$KfXN;pu(uje}n&g z$vsv^$v6EyrmT(R-<|o2L~3-qgqf6lq*4J;1UVAS>Eq%L7cVDc8I-rlI2L`xN;JET z&kDBdz5X{mU&yvl>`{4<nW8D;(krj`{~oWzOE+(?Cdl_A))Ez)PgatUo8=-_Lc4$B znd1-VdI`FmzU!$d@rv~{BYcTl5?Wt!Bi+h|do9_{t3oX9XuD{T*%92*$7xG2+~n{n zt=P=*Yu?$+#UwA}X9UgpZoLjQeYf!@;z-gyB^L0`!A=izt*0PPymGrRQF(W}D4Ek7 z%xPclxl@wmRk>4|7qYukM#M|)mKVQ@f0bWeT6xa`y2DoPX5~W_s-PDscKHsMAy?k7 z?fAKS|83`mlpm?9l<*y{w+Fy;qBT>u8Yc9w{%9oC-22h=1V|^!k#2GAKD{()qPund z)%~CEwo9vO+xqdhtBUO%C#9PX=I;M`&o*Ac%{hPc{Z~@W2crtkdd?Lr{Yq^WrJLa` z?@zcaibubs)W+|3AD4Ia?|#0=#yfUYy!68en!oax=MBPqwXM7SYPBPbncuZX*V_`R z>qnKNevPXgFF$I)?cdy=&`l|oxeP8E)vG}eU8>;dgbCS^tJN;|XAzMj+S4W}ytOqh zEoAK(H1BO?y6Y{NqZ-Qa_v%lW0hyN9XL##_FQK=s_lF=2RDyOZf+9aCoWM}H-vxJ2 zZ}{eRe{6p^vPiv~0mt?=mi{V5>qJnkIudgwTFy<MPDIc_w?k*V=4`im+UN0C(m?Xe zSBcwa59zM6YYhHO7?lrMXjOjQJ&z!ffpq2~jt##hxh{<gXE1cf(#w$x>3*qo2*!%G zGYh}qE@@E@_`aSQpn(gfm-%}ZCgAjhZD9HyUP3w!jiZm?TO9bg@DUATzU~sm7ut!v zOd(=|H67?Xl{+qRb#WZBb<sPMuqIgrP()`hL}C)g(4h&Y>U530f<Rus{uPZdb`5hL z_`u0(a<x{0y9I3ne!No4yj(O(@gjZf`b~uLMRYMzkqF>*W9;K#7MgAgw35Aw8Ar?- z4V_Ko3(+<rn-^e3ShNdwiCr$DtR4Ho3e~Sr?|(zqcx}+AKgLV4#-{kXppfXLzM&rh zm%0Xpw?_eOd%uOaaDuw>qC!AS3DMVdrcZ`*5+*Wpk0W<JPs9MAsye&^ap~>mu<-6T z4QKVg$58TdemftVQRRDs$S3062~+(loMPbs5lD_x)8GTKCMbdy{XDOWgs#RqtMSVb zTj2nHGc1wK=>%ibZKnDs`;fInv8JhoI?v>YAg{o6BWd{8yEE@ZL_sp(ZCY8be#l<U zOB;f~wVF}L*k7@kjzJ*(2N!7H9|30FNUEBCd}mM&pMWCF2z}G!53ziTle7AcPUlAL z!<cp&CKwH^@AgCRO*=gSXN;PN@T9M;gVs)-EmGf&>9S$aXZkZ@yOuF9LL|sR%iG9O zQs|&`VRx!(d0XbBs{wMA9JL9ZgaP(3EEzr?JN|;O>s$d~IeE|uD^e{xNf0jm<;#Ix zwtC|O8OVlW8QdgRm2K{z+NbG~>E|{Pi?gkq)SFAdA$(OC=PyEIJP+STuPVn>6R^#i zgfR0fV4IPtMb5g1{pFE)c->(gQkBOn7ajeuhWuJ8x9~S>3zoauC8~cvXZU1T)6dJ& zbG|xfOFvgW?oI*Ris0++eR~N^)jDdv@~~>E^hn`xH^W1vC*1e?UMXkSaR$oXwCj$` zRqho_i1w<f2`Y1tS+=*;@aqM#ccA6%Co6-##bkwky#4ie&gb?mj)3sV_OHJ_*w8yu zvLd!_e>+<|{&4cX_Sv^biuaXQpcTd&3_w0I4R32FT!VyVV<1Cra&-Y;&AcqXy|Pe` z`N$=1^1OnQ<CR2f@{jvvoPqHwYwk%e!t{3>$ZCc2I%g7h^6&g0I#HQX%&m6UwB*O5 z?pOZIXlgRm6Jm|mg?Ud0QKt22e;WkORqwd7x04dfs&DYfrT3Ue0y#T6H)J2(x#iNY zoi!l6sqpf2)XVgG&gbe)<%U!0n1Ay1ye;W1)#=mmkn!tpj;ps6%;x)=qpoGZ#zZbb zDjnXYV%apX(fT*fCJD)n#S$hvMh<6FS>uhRH^z2MpPWq-nGQ=#kouYfUJ(}Jjg@yi zJ-rUgXf+6(5OKjM`=ztF*72s=$7A1}|DJvBz(<l|P4?V)|IQC8E0Z$E_PlQXU6@D? zskx2@$@vK>mxKhK*^E6X?Zw<O-)6oXAx}eR>;k;p3V<L8KSSF8exW3{bZp7|3NCx{ z<z&3&!}05YAh}K;{mJ7_8d(aK?VJoUYwhA-!bE<{{l=2g+ACrDJKo`Zl`9`vBSWCM zg84l2&M>&eR^|>O?&cgP)$aJ+_3`~z?H%7XN;NxaHUH!+oo^yPy&Dhw83|Mq1T{Q+ zHxX-kP-x~jcjXw%^{;`*R?;*hlA`LPyf1Zuc3oycy_;+qKg_u6Lc@iKocDDG02#=8 zK4$HUpT|QQQ(gm@;xs{4<A-fa|9-M$0tVDS1i{p`+AIWAcxyC%()wKa75DLE*z*IR zj=6L1K}yH^=Zm8^)QI0NK6Pw5)E*b#rBVKSdb2g~`l|)#n|0U=q01Mz!=8YPLwWDx zQF_YB(9*O0jFe6g|Ahbi-;3k3pK9N-&yVF%E3_tGFK^dHf|1KW`oYWe+ZkpP(~q76 zL`$@Mk9vFBhx_uI@bNwMWY#&P-T(j$FV}%e3)1{-fBvW2_AGCZ40l6f8QyX~y(pr9 zMc1RaTq%!By`NSphpvPKYY>8ewS;~B9NK6A@VxPi6$uEi1zaM4m*nBxnlwLJBKdtD zv&z%FX+b-Z;TZr}1_ka)2Af4joPYN4L_;G1kut4vg|@hfGVTf8NC?W^k?<6M9F=<< zOb>`^x)H^C5{cP@hO?-1vqWoi#pqssZrd3VOQG|O1ba~EA_@O(_&fs*wIze81`Lxd zj8+sdhC<hip~rMaWB}kPnhcTXr)o%_wwOpdL`=xmQ`Z|IC}fn<7W63z5UvUT-tsh} zHICCD#+6D2Wuj?OWC#jF8&80(QRu?R@RW&&762SWgahIrEkt-E2L2uZyQRr6hk=I? zU!X|1$0$#OwR_>HfYz*pw$_9WL;$A?%`PX#?Q&F<&l3(L_$85sp%cavN>e|VFu|2H zg-n{sO4!Q`vS)$bLepkOg6+{SGPxKr#F#ZWtXC6yi}Ktx5Z}@nUl~fD*%^UBLuI!O zvC0Y8Y)meqf_MAl96m>qk3$=66Cc=y`4j2WF!X%{#(NWh&g~Qy!$8zl;6fZYWg^Mf z=S3KX9z_)R2ZMbg#O!iGdnxd+i5S;NaQ=L1;g+#*Y|7^hCqv87S-Y3Y?-D*zxe}kF z62U5AUbZ26p5ROpttuh7GxQ}YJKbm@fm0C6PWu#tp^XJVY!SGYPFL5-h+g?*>HtJE z8+Ho~buCYejRa4%$eGPuGcVPUf8i=`6%4Zrjps_0fe|9-U$)vl<BS6YYr>f+3D*oV zvDpD^D%Wx*BQiA^GKuk#7<!os?s6YI0EK@~Vd%xcJ&0+M6RDu!lm{<dD`C<9kXf=@ zu|08_Ew;~INr1QjL5~b`Sh%rQZd}7*!JY(|8yCbA00W-zn6W^^0I;qFkM3;P`C|ws z@;P`TJKxu7fg^LVC4K77OO>I}p3v9x*{>Jhy<YSU2|NZc0%&%r%CFb&yty5g#7-Oj z?=cP)>3RD3d2+vuIoU^+E8%P_&2J%Z+}BgBFJ<c}AHYKdsuIEWL})k>u1c)8jlTJr z$h1pzJATygipXwXz!_e^l~Vw3^RLf-GXnEBmEbMOe7>Lk{Ma|ef|7PNWJBlaE)na$ z$z3$Th2e^%x#Uu$6kddEE4ooxq@Gix8DFH)R>VaDtV$N4a*8M5iSs_ef-v5t=E7?` zxa!PERzbfeD2;7fiTz@U<5`I_PpOM)shfSNM|i1Me2MKMp#2!YLVCj3SsF<9#*eP- z0o@ynR9SF**#n-kmFyB9o^oHQ@@Um^ynT6Gcsb7gJ~Ne)E^+T3TB77{MR;`?Sm8f9 zNP)8BEArYZ-YixS&ngOeDvMPsOYJKQaw=4b6;)E8nzPDko~l}@Dw1kd^I~Oocx79B zW&2`P$63_}p6brws+{-=XCVmiu((mEV%*nf37g@j40YCo&MbOTHazEZY8KmSmKSTj zp4H47L7l~Gr-wb)!)rHlYB$<yw})#NjB3d|Z}(N-9@xJ<qN}CsLX6Rpu=47W;p&zq zSDOJa*ntFnLW1X#=-NpPOC+YhBo^K})|++g4t1PQ>bU-r#4{gUNbv%ANmjc8u9u)& zMzyY(dPHu$R6@O@GF0|&{asF|+|33>hX!TplLlmNgKB$&+ERnY-v&+IM(vx8x>Z47 zclRrQ-wKQr3jO6Vi3I2HG+EqivT|s$dD3K;+hpI~<ha!2{I|)4x7qDxv&T|X83@we zRd>M?S`f&z2H=6NH2*D0k+|VE<#nHhKoj2H!bqUGms1{DRUUP-73<I%{iGG2+ZvZp z-aJ?CN`^@0G&XeM_*@0n<eB)cwP<8L6@nK{4@S{binQ&E=mEJhumF}V|G!6=qq!%g z?UDGcu(Ya1i^oi7E{yT=Dc4S(pJJFS&mLIY`|rGZ*>RFkA4|h%fB$1^$LLbW_}`8R z-uF{C-_JO_pL_CtKKK1%`}^hG_cNtIXew)=$#MB)bgVs1%i*NhHvo)(;=|7;z+M;T z4+##9?(TNv{HTghc0iCz*&{btkbGGIP_2_@5i|PT9}*u>^rFrAMh^JAlZCGfJY4W( zz)7-FK-}m9tu`m|vk#9W?`SOe5GA&Ho7X%Z&5-&5Cd9nq!X$g%eMVsBi+a}r0E!Fd zb-w`f17K$^ET;r!gWo-fy=vE$!gFNO?7~N-#~~hD02cB)qnz};X8(`#0Q`-PXF0(K zAteTeG|za-erzQMO1;^G_L)cY&&;Pc49R>y<w=^$Wn}F}Q9#3G_>R-A##C5X<iIuH zQzP;l@kGzjQ@gG2-A-xDhm@XM)N1A}0^<~gafQUg?~*F%lg6(J-N1a<Znp_~l2F3^ z$cP~-lB?ifT-e*&G<%O}l;k^v?Lb;CkRPu;T1mfAqV%qEgKv^RTIdlrLd&}dVEAQh z+4&PI1f=^8^l#v(b?7Tq)KlR~e0XB6_2BbZQntWukjU`!w=Rqap<`e3x=g${xg*9* zj==3hGV4nMS~?%|C&j=8%u58u0T#wTc?<(+hHL_DD~6%<=1?pK9#4jcVTM-8+yz~Y zl`Uvx{g;&^{%t-T3b7p?u((&T{nIb}gGqEsWCAM-m;j(pK*M?xIyol*N+dWz@C^$Z zB)~}9OQPi_J`M!X5~zZpaPLXv>weQAPZXN=lzfTPm-#g^pT9%E%Xh}RAZ>DjzLy1W zz3n4Nm!H({nj+45uQkJKr$4}P99_drk&H~%pV{V{a}}DMj0MMc@(A;d`$jo{fA_4g ze41oos3Lp{`9XUcL03lj)P#odlR?2OFje9}rX#buBa^1_pw)4;oN5mDR;-f2lklBK z$?BtP70?zIM&741EF`#o=aWh_n29@!6F{Rtgbko+!yo(ah=T%&u<zc`a18K{_i)d7 zc#PqT3>QX;IBds1P@hV&xhAyZMMMCScl0s6CpR=+{uKrTU$dL@U>WNef^>cHXnrx< zTQT6_BD_hh9=HR4I(;Rt|4LrxDPG1dPsJ`TY~stJ-Se{0fi@usVODCN#5hNwZ*}=x zCQlds?_0P!U6CMNHjzGpOjBC}RUkq=0YFC=##I)kxQK}x8L^6|L*F@v)Be3=ngD1$ zUMiQSkwC*diFCOpG-+t4k{~EeaM9#NfY=pqp!{^r6B<Sms8SHbC<w|$!}MLiBlN2u zGM8?#ym(82FNe}rr^4Q2=-;A~bL^n8EGdH~ukP0@-vYoFNXwghaFYv$*KpXJCc^_b z{Q2YA$r|oM+juvw43CTT<_dVr1ihK;=7YHS{1Y&582#|;w6~<0BU@;CIo#beHcyiG zjH)nL;4yd<Ik?Y2mrbTEmES28q$|MC6%clEWXV}?=o2tNK|qrP5hOvT@p7TBCepKf z?MXCUx!0>N8z0$yHHoEWCFS@fgc7Zil>QMxqw2Ey+>j=L2qh4q2`&&uO5*#+G~5%> z!^!@EoiP1yVCw`vjR;lx@O{xgX|xuk;P4`aFlTXxHUqFcdrrp}26>w`=gZGK<n+q7 zHO&DX|8o2JTXOu}f{c!Zj6c4~Zgz8F=&?@#_$@O0cN~P8w*g{?Z~y!iMq$8^f0;au zUp)bppdcQkv|AMT+epaFE+0DHQ)*EgRxmh)VaO-Y){^PU$aFxBotLs?1*+ViY*})o z3y>cG{Ba*>EKmCmu#@S}nA*WoQ#({QJ#<o4z%4te&lUCR@*`HhLs(_!UfF*K1?tk+ z3r9l}$g5`OE6TMn0-*CU1)xt@YZ3=ll0Y-B)`q@DSqL0I{8+#@|0Bg=J?(_<3)c%< z^z-V$RLRrlKYsqSx%hdD0)9(`e;s^&9iCt>nFg5uwOE7qLoqC9QkH#QEw4Ub(A=CP zv~Qg}Z#QJ{q%cfsZWae@n32+a{?XmJ^6)h5VC(kEDTQeY%}_+3{pYmP5wKH$rYiyb z=?<U+I`7nw;E`mI!XT_ep01XKz79iI8cE+pVB91!%O$eB{aO8h+E}+1GJRRI16dK= ztg)ck@?#d+cav!^>?*AdV6m`fukIWWC=VyA+`r5MizfK5`mO?^H2X!l8Aa_{3FsAV zJmVFOXfE?r-FOZ;!BJvQ!e!A+sehrx+XG^HVg4~;54Sm4rR<mvhuQQtjkE0t%fSDn z&^(7Qf?!xlT*;V(`M%@uAJBM%f>C~89c`>#_EqJ8D_CvlR*F$((5t9FAoN>#b8?=T zzBu!>M$fp7u)^jYYf(FlFwN;OEUi%S-&Fc#JBmwp45NU4p55=&&eMIyW^cK>?_F9Q zU$^-g&3KK!R(~#QJ)B-^eUlSXr8GQy&$d`Lr90z$uG-U0>b_p{Wu$`p*Y{7UoP2k_ z2?^K{H4C(35>jw%;wS>y@hoU}S`uv+8P$0N{6fosAQPh=(anzK8{|9x3*Wsg?l^y` zEGwJmvI0wdg9u#o3JX8Qyho5;kg$R`vZ5`7!UfSftlZKhO)MMqnj1_Bsx^qEt#yB^ z!+Z;TP4}SoCZb5bgR+ugL=eO!CQGeIG9#Vu7$)ctc6Vr{&+98PZTAP)I5Z1MI~fMg zG%FYc|CFz%zAmH@P0?{)!N$LS6ICQDngia?&MO7ir|CSCr$y<pM~U!A@5e!<OPy7~ zgSOqfdgT(~H0u(Y&(h5YK3)K2(ONL|>NnwSDy3A8QAb)Cb_0PJ#VOPckr;Nfd)&ow zh7V~x)5najd9s_EUF&0W4Ein3KQMYN7Hxai(-^thN|1cF!PLgo{XJx($(BiC5ODKH z>mQ~LAb%^__HL$U^BwQ}r?1rLghv5scl>usSff42Yp)!zgPmB|D!h;e&O5Kg5nyfZ z-X#bRl<TIw*Q(2L!HQMB`}BCD<?i#xGUl=Jjhfo2Iwxs`WE_nUKFeDJyOt)MJyZBL z+plsx8&9(^DXzDlSn28}RY1pd|ILd{PGnZ+>I(&DNgabsxl0RW^6b8LmlTTQu&!>h zl53u_Uf_gb1%DxEDWZ9_sM08+O*m194|+;9`{>fA`n{k3r9rEoz3)c7rLI`JU&AM5 zUMusUNs%~5du}l{v=&FOQvLNVJszDqvobeosGKwW!T3K>32T0bu0Z;SP7!x~8<vtI zf6|?dN4Zn`)E@b~{DKaQe&cX1%viEU03M4+5>?^fiUd{XOg^iHEO>vm1^xw_GSLa& ze_HtXO0Li9i&y1@cVbmh67|P9KHY8xIU#OWeYPGqBI!0N%AOq;zR_HzlT1Ihd?H;- zX+TKZ-_wX+pZR?4Y1Lb(+C}G&ir6>q(!5XD4Ue~|=H^?qF+8j21e?fV^MakkBHc^z zMxG*k5ijq8pT6Ynww6>Gb~Rl)-^g>(lBGWUn(9cSKoVNaAcPFHG10w_k-KY{@JLG0 zmBBMkWhr|b+y2+`5Oboz|KV-eMA7iwyp|4ry1F<6U11l|*4{oYI`e#%m~!pwdQvu% z@iyoAl8&zNS6GCVh;(Diz2)5FWMQst609nuM^~A%6x-A-SbK4p_dRsN4#EWp6(+ZF zAJyGqSjf<RlOfGn%7QPwS}efv4s{nI&0sbEg(drO-4&xWgRzEUF*(i*hx8~qPuDl1 z*TM|V+fveyik@O}*}clm3dqLOoI>48{nzHEUNtj}Nt&9|8_u{~YGaA{q8~VNEqs;h z8wsX*wrNDW+Rq<gB>*kSP}$}KYs0CAagR9VP4q)7Q)3UjkluDW%VLvxTZy8ajYLD? zI=26G<TB%|q5i=c5rL`B7@y)$y=O<3iUs>t;z8Hqu29^rcZ1hBw3M1{=7o9BFq>+* zr^c&D=0Mn`FG@;n=E)(Awm-Ez4D?hj(q7FJODOs3pmGRlUhE}uF}}v0s+KRki2t=l zch!Pb4Ii@xmfg}T)6LA{edMvmRy?0ruF+ssDr;R)IH<>$NJy~M4P=Kqx*%A~t<Be& zm8V*h&=U4thfS8WC>J2>c$-aAb4E=-aFzY192>FGjM~7M`_8}HY~LScynTLn--YI; zT^HvoQmm4n+og89kEI;tDU6;}GohOcw+yxD#@MRPw;!81hE|&Y1IhSY3XON<Dqwmy zagS5aA-*z=k$pAGSbZ+*PW4bF#<PZ2Jh<KA>(N}xM~FWr=BDE+=jYY|J^zOp?T(vF zw)EelMLkPyI_+N2HZ<1A_#dP)e%`i-GJ(j2UQtqZo^fG$hpN12rE_*lzQ;bWjV~Zo zDJ|KP+K&4Io*lN|y*T>(ks7lXymhmDVHcE79PHJYY<7XlA=%38qM4L4XseX%tk$mR zl_;dr+H4ozXW^4C02|D01Lu1s^aJCqJKQ*_jn%Ih>#FYcR63G`-{&8CC;#Q9Yvzbz zZz57On6uW(+JNi>^0D9CsKzewUz>Yn@DI~V)I6nZPxCxEC~0AA+%_t|xrmg?aGjf* zC?_O4aYB!8hDdJ_TIuI;lwW3=+A@T+Ofs6Qcg0*su12p!j6s5k5Op8z%Zn4S`ay*p z@3*zKPH$9A8OYmQ@}jqG>q-~aV>uwwAKLRgNM_}bwEvB^iJG5GP>I#h(7t-LWpVZ` zKDhcX{hDQfO40%)`YN8!+4+W2W_w;V6K5*DS!8&Y$DWe6&7*i@c99Q<<%h3)br_oN ztqj%ohcq|6|M9?EWik4Wb=sfFB)6d1(INdC-ug|-*veJEou7&2tj6Bq(tnns7fdP} z%%P%@3OUQr&`yX3hI%1B@bp;OxI*Y2*}7FYzAZYmS4<-?-ZsLoa8Or%m#l0dI=?EA zg2dbYVT@aauEY%)nC1!I!L}@K$i=>!y;!b$DFEd^o7b0iD^LzSKCdWA(ve*~nt3yD zlQ<ApQ*oa^%gRAS+9Hx}#9bq}()QnMhhFy-&Yd}&Z+E0vxTvfzxw&@L4Hg0K#}9lZ zPpENS{(>-2zgHC8t*FkdaH3`Xrv34U<1fFS!y?F#TcO>TzfxiiB33y*hW6k1`a2~y zVqNUkY42ZddehDk=55p5p>+|iJ`{;Yr@(#c*s`LdI!e^SeRk@&!P4JLPkw!}vUcU& z<~yw-C8pF8ffH)y@kiJ*O3bZ@)yv;b1`PhwQa?s)-uQO<DfZbx$*rfmw%^V^$7)<o zE<9A4dfQ)P{mYB2_N>;ql`~>qO9E9e@+nQgBDbLAs{T`6@5PJtBc#FS=1WPpk=;}( ztP{ZANh8_`RO|%lc7m-sAs(I3piWqHCp^8Awz!k7v6DWc^FJ{okaR2hPmUP|a{bY* z<Muj5OPr<Mt$OY*6b-~aUf7$yWvr^*dn%Tvv5U92i*Kgu%6b?7L6-oyTadk5NVHp6 zv0Fs9Thyvs%%fX8s9R)DGy1#2TTl$0L;F?f+*$b=N4S=>Ztmx`L={j~c<Xg;c7|Yd z>?0&B$fbv>9Mp3ox(Auwqf*?X+Sqfmw?}QJM}56V<DlmjxL1?CS4*^4dqzhw8Wt+A z^RB0?;ZE1@CsGcb;46_}!9SG->FH)FF*a~KBE4%tp$E<0XD+H2zTX?r5bNR+V~&hD zzS`!&n}IHm(JPNK@ws03MDG(q!68)eR7&s3-#!=iepgZbL1drW$j1e?SR0=PG^%_K z*Ds|CQPjERjL7vFts8eq_ao=H9rOo)2QVEs&_Rk~MO{3j_+R&K8S^#RjY6)Yu#F=E zA?x|(L(%T=SQ6{N)AfO82LlDF{WNS$Pf2(m65b6RBXCt&?x4G#9;l%ybJYU{72)7Y zuc1bs4<ybECXJ%*CN^9B#pfYu*pN{IaG;?}-vo<Rc=bT53dEX4*$EyK<}sweo6#`| zds28Sd41^3fnk87NJ?V!3V?=9-l*sxQn)kP9`!b7PXN@-UgG%CCTJL?MKq67Pdp#0 zSs$)F(5xwzc}jswQvgV0v<?7_lpl7@9m=R4MhV3zUdP&NN>zp5c4y1Lv&N?V8UAoE z@-eZF7~Pz*Tq__?qY0-~2Y|T&QGfQqRcGv$p(ABy*J#`tgxW{Yg1IKuF&Ko(L-6PX z``Bcn;KWS*qd{1J{HPiRtcS)aAfx&jpmBfL%>fy+o%+ug6YV>rWmg-8Mog%}RVJrv z{c*x$Yr5m>=Zw>8N>8sF_o_t;Q)t)#G$syUV-|!{ImE(Ot1MB^d5UIs+L)u-@cNRm zIR$(_RJp`*{3z(taff<<Cbs@O3yA_2G34+}(1^t0GzihK>G2;2U^AaCNubKF%F5cQ zlBN}$AUVbo(VVR|K?`|jOvJagqfTZf7&j)wZa3*r0BP*z%$h)BpBNJ^uqGNOJV8TW zfz!x}7MM155=Ns>YM<^im`#+Joq*Au(T}Y_j`OCxV||pfT3_9^_XY2nJg3Bir|O3B z#mHec1Q5lNVc$7rzYR9*Oi^%|6qW~Rw2m8>Lw+2vqeIpIc=S>2v%uF8z<)DQ!blo! zz_cmx_T-3h2@k~kw!%@w)GdgWtH=1m(WD3>>^?ch!47OlvNYG4{yl8*)e)>7i4%4) zzc?^ccs<!_NOHdkF-8EHDF7C(Sr!g!76cA<yL_}`xMi(gjB&;;WA=`E;v-U-{~$y< ziMQ=trG-m6u0BR#HpY?=%`SrzM`L+VSXHiQ!+EjmS0MjUMuQT`h5#u=;y$a<AQ8Bx z8HgF6TrK0et%-<T$?PM&&l0b-BZOnn|0$g!MUbX35^s#O7^7?wNG@qw-U)0bXqg0} z5h%wY(Z*LNXw>6y0)QwDO}R+n(%6{!$?*0i$}}~oX+FVvTyhUTZqIIywL6GNcN(5D z%$iX<nG%%8X~~0FG_k6HXk<C)3UWT$Y2Hyj<~(XXudl=c(e6*YMe3cmd}3`AsH3E~ z_y`^Qka4lZQ{hQ>*$9icU%D|w#!?y*;|7U#x1MK%1C``)$cZQguK84t`J>%g^18%v z_{})CMf3E;s6DMm6R<E;e{+*V--KN<hq&Citoz86r3>UbB~svorsHN58;f9$x*R2U z@HUPyU*@yc`z4k~r99OQfh4@&;PTk4<JckotgdT_<4bpWS-4NHULgDH*SUjW#>viB z<3Wfzd>)BzAaM{?xePV9=FVRj&yL-psyjIluQ(N0i1UcT?st~`@PpU@ayK71f1V#7 zJ%s92Yndr7u9VD9eX+CAMOb#~ldB8ICSp{xoU)XF9Pe#ne&D_+U2l9ZO#T6F?)xhC zCpTguHX;<}i-ewnY$5-U2fAkH)^v9w^daHq;vW?6Xwo^`*V8LwvTM@C_DR2_EPgx4 zl~;mT_3YH=qg1)(MFkz4TJKa>x_t7n9?Wor`HLw{#Rd%G9S0%&8(-(j(+`(~9V(^b z+=*s`5C;n0s{Pwic~<}h|A2z$v2qPof|d0NxYm;m8p$#Cy!V=Hlu%e<G*0@b4I2UM zAipFbYjz`deo*P1C^YX($DO)DiuLP+*pzFBS(6$Vzg620S!hn%4?5~h!Vr=;PV+S9 ztR)3y_b5M?JuLZ0$q;MuYAy%FVIEu$jzX1=qr|Nhws9^o#(K(ai12m|lX`7_5AB`$ zpmGNJ?@k_n80d}|KA%`Gc{Cdf#+V_Xz7(he%dEu}N6p$Lbch+;U)Q`mz5idM!KD~` zm&^uX#|{dOcpS)?5Un~7b_#v(z`ofQ*!m>;W;lkyS=L1H6>OlK!ED?5<SN89M9=B$ zngJk+%`UB&5~-Hu;Q!1lNgbcP?4S~I*S)9J$sS_EV(GXYZEa^{8|kV+06P(Kd7<CP z%M4yG@&1u81w~tGn1*|8L+k?tG|pZ9cw^yC_+7867$hJ{1|3a^OszL|jX%1*Tpo)d zLRt2lzx}fdPOy>x3s#5Y&4=<~BM|KgC$A-m>{_vhc=Y{2gA!}sYV#i6Jchjc2%8A0 z0?yruR`%2*8chILI~0sWj1>ESl4OA0M{Uc3-9ye3(f4CiNsw`tE!VV<E(EZ~ys7uP zN&|G$avm=>j(!`$A$as(Z9@Y>VR<9lmUaW9>Fj0`F={T6!szP)h!^#Iun+6^y^MTi z+%tx@q4!+$=nnT%UiKMAqV)ZJWV(?~p<dPi1=|b1co2sLxi4?|`!JM=t{$2%xGX>h z8ieLj(ckyxp#HzoY*Oc<kpI1p4=&bsd>bkKQC%@_U*#Cs>fOu#$%X++EgoSg^5Uq5 zIFfOOgrVy2-m>`jpO!Z_p-gq__bip7%xiG=B=eTypTDKOP;u+22Q*iZG|ZvV;asqT z5V6hVx|{c1m#V#P_q2Y$5c`bCb<romcp(~s;PRh}(tDNGaC}}60}Tw*HVbo;A6Dz! zRigk|5LjzW1KlmkZ4kt<9CzgZi$w<HJdc09hxr(dc*h9U6Z*t)Be!z@X9?e@Ha@iL zY>Y@I)Ub8Ez<sb*>Q}-#29Uq!z_pyF!G;9TT$u+Gj{@teAT~Zg*%OfZ1PIj`O|{J0 z$jfWz{Wg44Cl=KMIa>31#-rfW9j!V6Y5kpkdoso&^1H@1P74skbr^GN9z4T^PMNzl zxkMt5?fHBB>CM{jQja!3n=55mI?t25^ZxklN%61Y>}O&ek^61jO2f$q`9Tc9TsIuy z3fJ04X5)lyLVwxJCpyCMhTAyS?Wjwns4MePyz?}dBcu2cQSf<?DI72Ie6$QGQ_{WJ ziRiI1OSCH57eIpzB5`bJAWONPxZL-4<F~M-Xr4$Ec-mVr6Q391fA82pQI}o*`@{V_ z7iS(YoDuIhk7Fc72_d4jDbX%0C!YCZ&o6^7{dZenaE61&#y;PTa{H-%k=qM@Jsuk{ z%<MtfSQ0Xou>a<w#<7&J08*|st^&(@HHe)QhFEJnc^(mz3BA7CylFE5!8sqPlOy>N z(TRUzOev>~w@Icx5N8U+2@bvOgHt9SYs2v#^CV0QS>QYLQ}ug<!LQQ4QTJq)cSMJf zEDzD0)2IG@zDb6>SIpe22Cw;@CIyvZwxQ0}LmXyrC&?gZL^Sg@4gPbCS?75D&P?u= zHe(c2>^NF`K9b7^RP<S(RnA-GYQQ33gZFc+v%Il+pP2yydxZ;Z>W<;~_3+`_DAoTu zmgm=NS(`Fa&YLdxDGmRT>Ase{Y3-yMq{S80arel~MK4m-f%^NqpXqFj$ppxlfY<iH zF=KEFV@l3n67@glb~T0{Y}R|%<8KRsQJ84GZLrgJbe|&5WPW^n>p*2I5kLpD8HCUk z6-I|w-Wi7l`#hed>Lbl$4tEcpyET9R8L5t#Hg$=q1jbnaVXUIadsYZ^)4ks-FRyZy z^2<v@Mlvd9x-82SJXJYsoz<W0>!(Tk?u!nmOWD@@?d*$<W+`}2rF)O(sXy6lo}DVW zzaoh)dnhASRK#3i|Hknht5~JrOt}T*VYL!!K-h`M#LvJnOh%ZOp_&$7$(5<4Dt)eh z@cl?;x%J^z+nBFhexoB-d-#v<$8zM4Fq7B2?0%o1)Eix@b;7~%0pw0tAM3`np{=}` zK%}uf-z#>>w@U{bBadIo?#@)&PQRzEU#hb!{P4<cS87_)F+8X|yZC#$L=-`U?fB;D zOy!lppg^$tauo%4rG1jV;+4|T-eSw6Um8=v?=b_ITXOziB_(^F;@Q*Iud><x=~YUe zYN|*sw$Bdwv12Y_C-XW_cvzxo+kIR`ykO%Bj#0JT!j~LunW$gNQab4l+bJ~SR@%N6 z|E$o?$2DyK4g!s6>NN+83n?fq_+gWP-=w;>EkEH@c3VYKDi%D=kSp7(bWh<!2Fro@ ze9F4=5ypkzBn_aO>6(S1^=N^Fb+;@D^@B)5d1^jE%mlfS*F?suSH3HCEZY%bl)e72 zFT=7B5kx1X3QoOiC(@1Ba4AJvj|i(W6yEkJnBgwEYw8(fBva#2#GIR9A1;|vHe|`{ z-0C4boL3O9DwUYeB|gYfq?nywRNN+2shP4f1rw+Za+~MZX}mOw7(mCm+utjBAz9Z~ zS!^aBsL^z};;3Rp=ZZ{xH~WjX{g>$y-BwtmxdZKQdI!Ncrjs;Ov)!fJc4`%?+axx? zx#(}tZfB*vQ}|3PKtw_-JKn06q+UJxZBBH(#CXk6Wx01+wud1$eGkDMzbNJZj=@6r zQtaHS_s1e#2_u>I2Nnr=qis?wK9m(!V^eC0(z(LuZXvCQask8OuNRhDo~~CjIl6li zfuC3H@T%YQYU~Q;V+9^H@y+3sP7@zFjapY3R>=G{IxN@Eo~bwDQ|c9}k%ZBv|Ctmt zEd&X~X?O)m*8KNnLU|?6Q|W8i@kx=&+4j_Mq?j=GoMisC#USkCQw2Kl;BD3$MHZ%# zHu%=rv<<T?ln5hF`f`?y;oh#gs#8b-TZLs`Oq;b#278^(5^F4nip#)?TQtvCBh#hj z>8N7Koi1+))t*~lAzKOhK-DKv%Iw{Il5Gt2C>a9%hjv@;C@FOT9#6|p$`4Lbnbp_h zJk(~ptIS@G_-stY2M)X6-j!^N0LC#<y%O^b5uPJ=pG=$(L5AzXZl8Ji$}vJo5i@I= zy$%9k5jYzqT8HNiIn$Q2q>GVtP+lIP8`)b-uR)^o<x>-)b5JTbq-gQ%p7g8jYrPP$ z)8V&#DaiCWjqPb1PV&ZWp^uv$4UVX8#Fr`vLil<aV%F_J_(b2H0=$>eRGhs=p2c)3 zvq$D(py>64SamE7l7W9nl8DS>3|e{7k|cktO!Lx_)n%y@3YKLOZJ_!gmHA#?6wf{d z@B4GAPb+6#oMFa5S<N+mBMRzL+sY~nw!=%@k;GlDp7u~krN0iQxqPPL5@@l-f%fR( zlNAw_f*CT0civ~`WcBpO+kZhdtG))T^XXeHJ*3sB7RFE$*6!+yBFHn{d@EUyYX=1> zf!pr9_v7#yAEI7bS^T-V%Ecr7>5-OMWH;NJPOv1lD?xOS$OKV{L30+G5)(0zoI)b< zTN3d*;M)na9c5oNS(E(*>#PCkg%#M}S`I<0Y&^b&I_KPG+_aDMKS&vX0s>z=n(5&^ zLJn}BqnX3=KD{}y`o`1~WfBVQ&prHYC~v`&Xn9a@oq)hy+Am7i$m)W7p|IRD1j{SP zpKSTS4YFTLXE@+jk$%&n$zDN<|2h^W&nj+Z;@YZRe90;v$W0%tm8GfIRONhSasezB zUreBvIV1Iptrsu{Oi)Dx2wVaxn=6w=bY=p=F^+ZxbaXhkem0p55Y%4~$8$gg$B1=9 zGzm1<jkOsC0Z}kDz`~%BGE*^O{Hor;>{$OUd(A|j<BpWQ`-W)6y)SsQsn8tT_&&C| zx8xp7vD<K7yUDWS!D~KWAsf`1_y;|h@YU4OfV>|5bQZAc#I?o4e}lENIx9Su@h>!3 zn!#c|I8n~JxFfL6<;B;%qU&f7Llyvh3!%d;Zvz#`>jaCFUk(VyE-{9@;vlMje)uP$ zc51bSZ}6U8Z+X+AD#VJ(xXs#6eX>}>Ga%&823bqfy?{7Vqv%sNfGiG4@F?vm45%4U zTj#O=$0;X4-40FEue6dVdmv1EZC;a^ZZi9)c3nST>PxeD*BFL801PRw&40iG6Hr`% z@o(c~**&{q_c0<~r<Yz7MM%;bx{I*hCrM8Z=81*7H8&9)20lReY~~Ss8+1;Ae<l-d z%TM#}BYz?%errmW-M4#Q#EfaHPB6?`X-k;@WTvn(&HD(fAt)6jdjJ5k%@Cp2wlyzR zlR--70Ps_U3!aD1>jOrNZH|=dv@N~+z9Pob*vZ}5z=Lb+!9qrKMW6VI{M6VKPo=5Q zRK{R2)AzV>{>fG_=F9n9#Ar{12>)TpLm;!qikoIBrB|ms{EKnWasTaJbZTQ}f@)SK zy##`)!&f~4;NC8n%2Xy+-FNyPc19=qNME_5uIF2LxqH4*V7z=_SSz!%SK!4o%EmA% zAUNP?uJtHG1sPnLo+r}!Nj_FDWeKA)(C*}wp)aT2<<Q$VFL7NVC`Lc}0fVQ-<>jL& z!gCCeo86UG$tPgRuiqN`*jhE4>#}Zw{qNV0w`9K%q5cs*@o#9^qpMG%ub$h|*^Q{a zXyitY{WB;uM#%HYJZaJ3xkzICj^jHdMKiuK-+M^T+{!wej4ppo%TF4R&~PejYpU@P z=+$EMoWL^gqhTU>0C2=0!+7D>S*Z<uo*UsU3v9P86V}&0Zfl5G2Vbjs>MN=z8nn(# zEkWwNP25gx5@dV+etR-c5iQW$+IwUDQpy9erob+0w~phJVB>9fcC~FS-Xr%141I_g z3-EZeI>uS4SBu#uPKR%ojAMv%VRk)B-^^ZiNkUL41+UbPHrzTQ=6TuOuJKh3m8Wj2 z?7U>!yzJl5lDb0>530+Ieg6DMQrNZ*$FoQS$A-71uMB@2R+6H4_XZFV-L!fF9D1Yr z2fA0_cYllJ^OS2{>5WR|&}IfinFVS0%HMgdIPVVusiwcah!J%3p;MdJxnXrDN-&x0 z(va{Nvt%n!z(w0`)P&{E$j9otvIIlUE@$H`Ty|)Wn3|&+pY21TH}GKxjX@leoti61 z?E14z*Y@;wk;{a(F;ECO$D9?#E%+^d=JgXstfHX4P4CE_-(piER)#{pRO@O?Oxdom zzG0^`ISafBuwxXqlASm9^0Yj+qPN88GUaf8izMG(j-GoDye7Ir+PF(16@(BWs-rsU zdss#|RyDN0oJIHCk#|s#UBItfoGbguyU(<ZwqZK}aW1H}dWu%+%ukkn@15vNs=_jb zy;%8aSvwc;4zi>o<fC9ZPg0yV4Zi4L^??s-_A;DAiU~N)+)=^i8s_CW-Ib|@;xqb% z8nqmpgs&PWUUjx61_{$Yb(2xUe@_%v&C%pu1{yfxWl8p0jB)HT%%8TYSd&pVrA?9N zsW^@5F4>?Sqn#1YNdp;__ELH`^Wj&hE8GVeBP%Kb+Tk;qhm-(pl^wB4Gd&IqAd$_Y zdow!t9nh6Tv(GDfa^~ZMV(W!LdjAsF#LxBhXMo~<Skakc(Q=^BAP)_H?`ns;Q1lBs z>Fi&JDUxKY43b4Dd_9@Gw!PddwF6R;rcpn!MSAEMapX*;=j+EojQqun(zL}xv7f;> zMZo3z^B`1ckH|qcOIs93CeNZfMuUj^d`Fu>T1TUoBUwJ9iP7`!3^PKpcM!$!;hnbG zd9N9np4D|}bq2`N+O@i#hA=TF&TGrY>AcIj?YIxOOdD4VrQ$RgumVA^MWrmS8{(eH z_loWnK57N}h{oHp=TxF}Ze%SaP2hCL^?G)6<VLmCqzfG%h&wh~YaqJ$vtsl%bl-d8 z3iKdBn&b2e1A^OKw~dUwvrQyDK1r+tX;Txg8XC(mbg{4}-*YV+SCf!l?7rdQ<xS^( zw4od9hvO1Osgk|AV{|owdX!NhAwr4WcI<{GU7Xtb=DgRL=EA)^9Ss(o@H$THMC)Nx z@{>6*O8G0Qa#n2uWN|b`uu8b0iVxcD5+q?y1MSN_Qm(FdOCgznb3-+#9+p9^kEa$N zk$oIOo=;2>M@q}G)ikOdxR?c9FJ*#K2hcnily*UNOcUPGNaa@_>`^&Lx;(_Yz1@39 zy*u}mMm>7|?+(Hc<Dnr9;*rLw^k$F}!DXGaS+wT=Ji3Equ}^)?60;DD`kxMb`T|h~ zp{fGV;qjJv1m{M1<}m-Qvo*)~uS^A=8t01&H5S40g!TeY^-hplgaM~g9JB1Sh;9#V zeB&26leqg$@`bbBPLGT+O?F$hnq8K9IZibZ?1$;?%r?*cu;X3lB{wbw(}Sf}YuBW& z?6F(Pbgp@Ru^}#RmoQZtXn0!5vXMk*vlX2cJFpsr*8v&P0b=*d>-(?=jF_<=X*7<n zTwARJMDnYGzrx2%mT1^v`4st8e72qPsD{Nqr-c~@?~6ka##@5xz{q=?0;Wv1x@H0> ztPC-?2p(g$3lu*|<GV9BoR?iM<yp7W<B+<^3#GsADq2zuZmZW9-RzOo>}EylIET#i zF7}!Py~f)Bqf0?59{2m(^fkbst7=dm>1eH^tL)r4+z<8Ax3Qvv3udqLNvdX%a1>)& zd^1A^PpLF7XRdl4jkA}Jk-Vjtoz8%LUhyLC2D+Qw1IIXafB0*(YSs%4V%NWd9;x4# z&j`-yop=d`a;<$<cGt47?lDc&CCPbh236~}492*69z-#ZmQ{jXHFla+c!uBAL8gbB z!h#~|_RzQnDve@8uc&GQp=hd(8pS<x&ds!!Lp9O&bQHIpw43?nlj*tc7aMPjiJedO zaoW<_OT>KW=_r)J@FV&g`l;WV(ZbDxHQB75m&$I2ihM=Mps({fYJ1v12Dv}NK8{{j z@fjmL(mHx8sA$KlMnsU;u1;a<T4w69oD4ex<K06yU6?hzLeZ2Swb=Zp7u1*=4F1J~ z1v5YGQud>3kBi1C+{4->&HThd(Cj|q_YZ6RI$qTt)pJlQe(ox~{I8&{viE2sEcVea zzLt(fvWun-IY!(Wq?fYeWr$L&mRn@d)hA3DNQ+#=yTtAE$mVHjjOH6D@?8^M1+0zD zpn**CFSA2^)r)(gJg9O8M$)(Cf8BBFzN(v~k_enU5WWj{wl%!OGuJgHd)ul`TY>;& zQCsoM25MEWBT&=X(f$kxi{6`{D|_9q3V+V-_J~A)D4T=W3EYiNkmyXOLVC)>FW2f1 z8CBMMloNN3yrc_(B#WdT8MQhEPdjJ9b^5mMQ`z(w56@?#Kjf0MRfS~y{fKHWw0n6z z@r>m1*p5j(=;8LzQL9cfa;cdseOTg{bt4bNa!W__HigHlYG%Dhh754dVcxg!7dgga zl)lc$qc!4sB2RWcB^&vl?&gm&C!R3CwzZ|V6A<Qo2!yO}=NrNNdYLJOQGjjAFh~Vl zZ;%AqO=@_|K)r1mA+843=G((6jp7uo*M@5|7*3<?`>KrO_Z7ZiF*3O*kNY|Hy$C<b zlzzk2;5%J&*t9@ByF-TOlt|f`f~$t9I>9})=5i`UP__Iohr>}~eD|1a<(s}vY)8){ z{XkbJ-E5zAnBT5oI|vRmL8`?#)Jxq!jsq=;6%$;nN`y{21IjL#1Y_1)QyX{YtCj3< z5l7(|k@;FLtm8AfZ**V`Qxug<{M9JGN~?7Nmfts^DXLuiJa#=Y2f&i$gC~o6-vF#) z07cb<Ag1dtMd&Y=X;!qS^Ek^l(#g<U-t^XPoXphHBQ6`sM0E0~z<|xzB#--?PnGPp zCe;2=-5I}ORI{2i)PBFqdQ`svQZL2{9j9LJ#M&EfU)t=UI0H3f?fkVX6!dVyEI13A zW+Tn-7V3X=bPn<&7zGp+E9?fPJsbZy+CVq8Z$wCWc^?Uufc}|d`OE*P&4l#K*4>AF zQu+zxA%d=TXe+PxD0+SK75(jWRY=<M=YzZ5GKwq#Zxh}X?_8@kZ<3y|UVxsOXv?w> zv40>Uqz$u>xsraMa>K_*O@Tv;I&n4N>+0Id1m(8QYK>(jb+sN5pBl#z=a}IT(Ptso zmL{IKuiue>YkZKTu;7Pwu21LU(`Fei*mk8q>+`2Yap}-zd%nhgzsn$mV@%L7yESpg zoO%_UVWT+N6Zk@xWmVVysx#{?#Q#xr)^SaJZyX;mmcYhnn6S~^U5=EJE-6P!OE)@l zG)N=i=nxQ4QqX})2}nz*Us^y>KtQng@q4}QpSRAv&pqd!&-py>=X~+A{@0x+fuh-S zz{v`dm}%C%V3JTzyx4pk!OiYAdW1vH47~JCK-E(3L@|Gr%7fEJv028G;gy&kEnR4_ z>Ny2(S%N~pX2qRrNt=0&vSo@84ON<6ecKB@d}Ms_j|HIuS->Zb1MC5MOe17@n*Wwu zH_TIT3Hde7WPYb;sCRigQE}@PqbZeLN8)i;2ypOoUYZtHpn<Gn{9;u^zn4LO#jE0d zssbP1RG$Os(4NBo5@oCtx!suwhIF@i?OrL5lsw`RX`>X30Z8w@Dm<2MdR3abr}g+g zo#%f;*8*qkxH{wn7ZmVYI!BidNh?&SAFd<DlhQ3E?LU;gWi2EpEc^$|!ccs7Xtk%q z`UJO)k{Gju_Xj_7e(x@Id}Bv>ZJtUgC4%nrE1q2yI(;z_3$0a{vRU>@lH6hOr^C|K z--;*kJiK%5BT0Hi$pel#22<}7Pd5bSHN<Ib%U_QJvMA+Fs`&!kLaxWqF_qFt_2aa9 z)Nz{_$M4ccgJw^JD-@6&5=D-Zd8(Lp9gRJyC;fI_s`@^4j+Gv^X-P3`A~u5B;ax+T zc5Hsh#fqfCcL<f4k<uB3^Fr_N2P{#kd+l$sJW>|4WZhck4`YEBh3ameAFfNP0p1Th z`O^{jmj`wRy;o8^-SAldl6vFb&1<HzVLRSMY)%_29el3`KikE8<XQdr{5au>Y{eHP ztaBa4lu|iEE7|>(2+m?*&WfJvNb>!^O$M#4=d$666^^l5;gNH+9@dtDhpLmXm`+Mt z^U_@#@6eP4)%=(+8UOvyHeP_D=fhNK*K_DTD=mG_NqRIW-aw_q807i+LWk|e;Ro%0 z@q6kq3G}7=8Y6O?rEuKR)B1O1&+zrqag=i2`9c=;XkA9WwDs3^#phecK;gMY{48kk zv4Cksf8<Gn*qA^Tr&=zb^KiaWp2y8ng}|Np-n=^|kFLiJ$FSvlnmyuvv&W#Ve_J_{ z@?b%={=0csly18RpTXVBihjR44cj~dCb!jHo}BD))ED^KS98zo**~4A=zg{+PR~(f z^2x3nr}I!oAjfIo*~gB(*`(>YVbgk6UCz*^_IkS*UZKK8F+an&c<QMix+ZkIv0D!R ztOg#2`n-SQyvfLB{NDpV?qK8CErqbV6;$=+_O3S{DFz2tJ9c<vci;W2PCfTDU6)Dq zRYbv;yzp<mCeiz#y1!?Wqz$9bGmoy<e&K1ie>NA-B7|xhD10-M7`jq^|NiBt>R(Uf z26L6UMWce|K0mk%WDMX8Iv(4}@atJI=JIh$)#due&WIF_?H?OKUEk<E%>61K)1+0p z|90d}%&fFPnP1=X4hKi~<uZTSwO3O0x#7o=jW3FGW=Bv;Ti6?q05-m}V*-_KGZo;> z8lFda0S|@QpDAWY%SXRxA3@3QLoJ>^bLw>;3obsHm5bYN|AM+c-Cmb#ld{@osNnu< zqU>Tn(#(|QK&l=c`@sS(Ff@!xcvy$rvY6Eu3OyK%5}e`TobQk|oZJ!i6Oq09HSTrx zTwj{uBd2L|#>bTvFw?eMUgcM|5d-$)&c2KjR}Q`WYJo?=XEatM`@59$=vd))!+Nkz z#w*UCGx)-aPy5HcS((Ba@LOBw&gp>|+$8g3+=y8kD&#fPoO7!~BwXM+b+B36vsucJ zX_g~7;&sU%z3#MzhnHpb6@h7T3iZG03}n|!><q>cb)z#@>*-Qw=8~RC=gGCLWWTwg zuhJmc;_gmk=EH;^^g@pPRqKXtD)zrfiLnes3f%F^f+i2(eWAmjD?&l2+Xq|p&2rJx z?Qc<7%Uit_n}wnm0v-dmWN`_N^scp0=1=XuwqLp%Yb%{VZ|FHVcia)yS>opqjGEQ> z{MauyBTY#*l`UhkG(@e>J*c0aoy9s}u(rT@>hVP04}JsHB7D{||L12xOt&5f(^SI} z+!b$t%YO|O*w-~iVLeoY4C5CObE6c?C(B-U;8Rh#DD9lNX)l#;4lf%Mn^)qL1-RBz z7>Hxf{Jl<{AMRgHf-8m+^!wY5_*Ha%AM}2AVl>giQWrUNT<G$~8wgy9jiY->x$L<6 z_5K^7(o%2A_RVfQ@++LKFMF`df}=RD(KD0+D@EPt13+t>y`w$>?r8FP8#VBKiz-S@ zdHSM+P-l97$WfjyT+K{XTbkj)1eC8@&8&>b)S{Ryt6Pl-B{vBAb3oMm1EEe6+vpnh ziSHQCN*db7{Nm#U>Mtr==YS7VZ|2{?pGZ-|lEmDkyfD3Gquf_Z1uUL`xrwipsw!TP zsGm(EDqVpY%q}L;e2hARnuAEislY6HsW;jNX0T+>?}0svpoD<x-trpwwSfq2i7gG{ z`OV3Mp0Ud+^$xRCXJ`<=h2fYLx<u#Z)Hj*V5^fD?u*iI)u~Vrmw9zO@n2ukE>j_5J zPI0S#!<35U5hh8{m|i_uF)=Ih#9e527s*&<8vXgGIz4AGFSrJ7MiiZ452N6&1W2Vs zv$+U4cSu17=&YD!wiTFk6~yg?u04R&j(%N-MDQ|{Nt=B#e=U_2luu<tHHO_$W)<{e zOvtPbND|@Ix)DbglJzQs1}zeAXtt)w9-Zn`Se(k@Vo7t&Q*hX8V%fMuJ2yp1$jH19 zmnmRuQO#GLFaKp7tceftTQ{Hn&*-6S@N@!tXN})G-x{^)EXZ+jep`LWIWx)g`y<G; zB(qCeZ&Ss8$3;S_Nt$YAG+wMyhT%#xL9@~<!8yWpv12!$>Vg%cdjwOT;}dNAm#sQm zJuMAx33Y~`5I33&Bv16l84KGNf=)(n$F>vYIO#K^fSpXu<ZU4XDf)Qv!uHHsS148s z<`V!)dEL<zG~C3SKJF^JCsTVgoOH7UJ;9mfy==Aka7AF!m2<;3UU6$Cw~622SskOE zL!xUz5Kstr2WBe~f0X*eO``FQ+_ylUAMaE;xLJ=e8>Zqund?di&CcdxixHG!hSPC% z9To@Se;L>lpo6W=<$e;y)hmWK12|k#Q}Lh7vi%R^5cLhz;ykY`|9&fa`PaP(`giX# zErn1OBqlQU%cut3k&)oujhl6{gs+&WA^GVagS$^2m>v4}s0`VG*wd)GmX&i_{~H@o z$RdKwPwDbG{F21wD~S^Xm&Ce&ubF|W)2jc1v#UL+g;vt>(I2W%w%f*zQ_P4E%iZTo z+o^5C`Pt$4tXEc9Hy`kKS-l(P<-ES{<E^0E1ihCaGBQR~u8B)GbK_=dUVFtI{~%RW zeBoti*AI!KhLJyol+yh<$uz0!DR*k9ozGJ8)Y0hdphDg}$AY%UK^t>1isO9q&yH)K z20j09Ab#yAW#Q(@I;5mPkza7}S}<@n(-l9&6!}$85;RD(F5}LsE*@<OEcbD|{QmI$ zK-g&6d#yAlOUeOndObVMkeY}To@;xg{ldXU(u#-i^N^G|)!8&JKbGwnrgCmR*C6b( z09(wS>Fk$W+3bDVpNlOGZ@ACb((DK>S>atj%lCFuPxD=np*_Gm=O~hvfL&QX^><6@ zkn3g75`#aC->4xC_@!=YOUBKDl@syVLHn5xEqdRG2>qGtJg~lhIH7Ci^Y`8NJxZS3 z2A!5*bnwX3GGiZ7ry2YJe)fzeUr!yST6_}`za_g-msrEgRY%TMTy3r??`bDziYe|P z*gQu^hO4ubPm=o|BXWscKn+?WqhUs<Riv2w(GI>}Dm$$I=V}~VnmM8BlDTvDCwD+) zy3w;CX65mbNBQ}?9>M+N!-k6QD?46Dc<No-AN??gee@AIU@XdBmpTHTJk4DkL0<%D zacmf+Ij6;c>r3g3RgtE5&Z7Jl-W4c@pCD>%sWH?5b_LUBGToJE^+n?%=ATEM=&QdK zXZYej!^0Knw?p+Y-DzHtb8yNqyqdL-HJ&4WCe;{iRrKKElhj&fx?K$?c~tJw%<ww& zSCb}-z-vD7c&xkjTP&vo_D?OXiEg><bIxU3O|>$K3*a>WGkq@qrdit?^O7y5CmQTs z60FI96LpOwf3Zqc>>0lX3l7^ZxY6L2)&Am++B`xg#Q6_*LbTI_*X1t3OZ8Q__~bp= zl#MQ7uEHwCZ+8KKNPc4%jzm148(aWagQ`LFf4iF1#WAX{GhmRvmDd@3X_Kr4S*$e> z%+68<l?x|d|Ii5kU3~Iw_n^INgh|r*-&W-^r^&`tCF;fC-0LRZ`9XApGfZ3@yf+<g zn|?oFM20NpsBXM2FDg8N<-k!$vvRYlOHB1kRPt{ufGQDsmCULXWc9X1O;Z+KNtvBV zsy#@Mb|pi+2J!=mbGmZ50Y*!|&73SD(4dVF1g(m;(DAiO_SGrgo8~{yVO56p``2^K zi$<$gGBjsH1r9TT2GLHUi|Uok{H`eaeW{R2rp3Ebws+ev`6;0Zl?VcfW0qpI41TUS zF&0wAH;v_Mef=CSb==mBl&{@wh*y*~*#e4l)i^Uj9$=@aC^Zn#{ZEEhQW)baw@+Hx zn1%w`6G)y$EPB{Q$(ge)$j*)@w<MPJ3=dh-LWELZxa`lg?ePU9gM_ddQ-^2)y0_{< zqCu3Y+6UKG$4tB{nT~zAa|57H-$6yD7X_;rMR|sskXZieZ!sO;QVh1a+nJ4>ktcX$ zE`3(OO(B&wc6|-@UwDYIGgA<Dt$${`ZAX}GlCxnQE>6dzbNoE*HLa+#MF_VrW7~L^ z9|vm(m5<*f4gJYt#v;%_8h;m=a}1HvK=C@GE|~`<e&-6l_hs~@`>d|PqPY&|@Zk=s zWb!3&vk0@8(tx=RuFVaK?~+mbgZ)FtdsBBfvhW5?Z}^`j8vdJ}uG2++IRcujvm{8d zsZ{=f9ARGwu(*f~yR893f)z|~pbY|(t_E8sN{Gc3%gqzh_k`QHl0k2f*_VW{JEqsb zaujYcNzwBCJ>;Jd<Km5@!@WLM{xLfxz>&2kJ4>-L%cu3?>vQj6cIA!tF?(2u6zd8J zD5=4sTDiFOG#V1jlnVgj$UtBSj+zm;K|aaKWn|uz!VEE<zr{LeKz#;5Fl<l99c49$ z=u7yztoDzdcolMd-Oy7NSxfU>D%ndZVF7<B6+<K5h?&f<yV!eDQ|e@fe^Tu`qKpx~ z(l`p13^G*?hVB?cmuRV%4!F7y0)u5>meu8PDH?CZ8ezGAu2BgyGH7SZXIFAix~e^z zx@Q^GoqrR}?x+1&^!^T_I%u5VE>+Q3rfc7sBh8snH4b}Eh#PXGF6K<Nk71P`(!aLx zH!B}HPohhiH$BDC;?}_O&Ij6qQ(pyRNV6d6HU{hL#ja<D)HzzWp7BqOaxM~%p3NHF zOf%TUF)`Arx>IVSD=pr`Zr5O0Qp~qG3#hKeBV{O1PrhSD5oAw4rZ6(qJdQRELkAc% zeM^EE0id=Ae9?Z{s#umw<#j2<27^b7wGfX5n-^d(M8I<#fYm^|5G@~zP81_hb<`Ah zUC`#{EZ;YngyRq=B!ulG6T7841x-=$9P$QPTA7080M3#|rW(f~_VKn0B$^Eztq~dg za6ydP;5}i6p&}1kHceG2_ft01!oE@K=euPOsW8zLhr#sDttwVoV@IDVdj-asdspHx z0O(>3X0GIRIe|IG36+E(1m#%qCQ_`fC|(UPjs(fD1{>qSCwONKvhx8``$krlzn_x* zAX0^-*?m_!MJl^Om}4leTQ~F-`>2%{x8ol&YN=LR-#X8jn{R9IX8^aFt1h1cG}q}2 zTnvE5T=7FxF%TLN?AfjWQ#J591%r1bQkish2Xqr;nheaXbTZfoZx#xGrmcZPFm$L+ zFD~mw6a(XiC}@TBw<An0+UUlRwb)qIt=5hY`&haXkgs{TUwMPyZ?OM+rWu^S*5nY- z7=UEdxLUh%b|<iaem1H)qY}Fi=Y+t8wZKpkB#Z<y#(}@#^|FKLd7bfZ0cLM8!6l1c zkA$-WTDZkcxs^!BkV@!By>`x53?0sr>V5!`Is11%;DuDG^MzpvqhYb8R?eDY!dMUw zjhWFJm<}7kvKW3!#uMcrS@KaW0OwQO88Zd5{2+>xfuW}IuXiPD+8V{$6}bXqb{QKS z{D#G4GCb&vK$Q&eIi2Bu8!o+O<F{i2sOA<Ku+kSCRJnpeUMLWNlyd4{?|0MWR%QFk zH9FI=Mo_GSjR8Po5`^EDR`%y4uQP*noba;N=OB&fePfn042Xb7ZHThmI|1jOM%SN5 zL&KttG<v`7#z@71otEy1pEafgGWa}UevL&>rQTCZ@|CGCo5pgH<2$RW7!#JdOl5>X z{I7LeQa)8W+846Yog+Cl=;r}+I2_0yYXj~EQs-q0yIw7;|7LVWoX=+{th+lid$?b1 zB-HRbC;Lh1cq|)#5Y-t@YB=i;Xq+=vl+`XHA?OfoF1^3cBP6(Pc{v)w>(Twdr(SQ1 zj52n0lR%hteOo)hvKy0uYZyfGsa`07WsycnCmWkFXS`{w)G0BQjHhx^M18~QEs$aN zaPZ~``k?izh81PUF{}_OJ_633eQ%^}5(noo{hJ6UD0V6q3^}=Qj#us%50e{iRW~nR zeN$>G@+^BzyvGzs7dD)$H6n<Du__<?&+7(@q4dM)J0AcL0}`#ID|>DwM0^mFsOuSX z)sjKlC=xh=r1|to$j@R@N=ao?a9mw4;fR}w#aMrrfZC6<<BqBx<9FHOemEtwztx4# zUrN>E=IYm=A1BZ(_ThsE&m6Gt!f4=JvId>?&}ANmOS>hI!Bvlnqbn|Y0dt1@`XvR& zG8~?}ROY`7J8A5)yk-h#{<(AbY}oDTI^1Xo-Mi9!ptakVTU&gAZqlr=65#|<w!9fs z^YfQ?wLAqZ=>LRBOII@F4&H$cqA~zf8F-NY8b}w9;9qZh`i><z9r>Nn^fJ{)CQi45 z7JL(!ZrR@X6<hQ5ow9-oL3<;j5AaMwjHBxAiu{vqkF5sghiqIvjC$*;4<*?`2Ge5g zJQv@y=sN#SHr%oN#)#8kfl&IsoAFa#w7N|xo&ogB7ifC&+|B=UL>=jvB*s<O*F2bN zOUK7*t5MlG-IKGg8iJ+ECCSZbwcq^t=UZvzWzHD6#aH;y1>(gmi+L@7QfY*UaWd-H za^QVlJt(ripX{pX5AA(S>A)H2Tz>1xY4Lcui5|-d8Di%=d2-}rkI>vyW{^Jp-v5m5 zZ)xa(4VQ7K#W;4jG{x-M2b3Kp0rB-Ew!hqClXasHD}nCa%|c$W+wy1lEBhx`zhMi1 z`?T2Sc!{9rG`RYtITh#LVn-d`<Cw_&9X|0R?>^)!HYlRfM!!!;gDN5X&VRfo4!-%F z;%AFPRaHy2uQiqN_eVi<2LD0IQ%UY`eFEK;yf^eTx#FD{&x~eI)3Ktio)T&d{<PzJ z6EAbd7p3Fad-5N2v0s8pz5rviKQR+7&0`6iKufdE1+Sq&i9tVJf0k^G|Cm=7OUD<z zHJH3fFr}HSd$BLqWK4q_nfpFC>8gpABoP9+S86@SM*l324fjvu*#L*19`uY@eF^j6 zy<N1@p9w3HcLoRf_t3#c_%~`d?HGeJetP`b8(!3Ev18H=lsy^<qw!$t2Zgh!;ibRt zxu{L9G)!iG`5TYnnc~S_L1%rHBXv91b%pxfvNrfuEmHrQNu?r8vzjw!P$c%<(=$z_ zPvswg{%u)t@7QP8;QP=(EOZ}m{dA_^ON^z)xq|)sch91kH^MGkmGE=Nr}v%wX*_nl z9!$(_qg0uX_j!88O|~m@Cg;gCmw#lFB^;tPE15&G6SDpqTEwiRZIzs^Uqdx)y!)rG zNyX={0Pv#BZFK~Qh;#MDv9k}ANBjNo3F3|)q?yOCuvYvCKCrGnt)#ksL3V1k72&E| zGdl@58oAP6x9{H_8svlaF9bES2aI8v_kEtyW#A@TKed+`K%Z0OxTif1c2bdIu$t4D zap!WadewSNK^vwaniI)yz_3=}wAQVmMsoUw5@8IAL&W2m68{XxKwp}~u@7ONyVvzj z=3BT2d>$}=@beGZ;_^Bmo>MLG*W%Y%1(S-QB%1Bax$v=v1IdgccKs<*)x()+m8crq z|9e15+U4v?(zW9SqF4IZWr5Fh)=e>=D%Ap^IVrD;uSxKqQVr9U+Ue}u5yrQl8U7mf zVicVEROEg-dTk(0?(t%a!*k{&yQ_@*^fOMUw7PeXS2`UJdOPb8<+AoQy5-tz!t-wj zVt!Xm-12!qr>}U!UD#@$Z=*=qB(8~X(m}l|U&Q`XgUQF*y9_e%wY+-e3vX)-OVtM! z#Rj5)v=2)^pSjGYc$uy8A1pff#h%4?jz{k2H?F@<=TO)_wv;qVNGRvt9xpiBO{M_D z1=w0wSGu1^zdz4eYN>PUepg!b1TGg#`SSUF#G?-Hs9#-`mAZ(q&uPD!r9#<n6Ks2} zOw`tWtKSNeigRt8BIF>Kl?m1J(oimsQ4)wN{exUuVtooFOt1?$m#IWq;+jPe?z>~c zxA~Pgqxxx=XGCnbM$5!k<lAm}mTHvlZK>P4o0GOIr#8^Y>*8Z(>KBP2c*)Mha}+TR zYdwBDZVV6)<|F`yps`!#+kz5tL22TuN6B<)MlWtHD_*1&AqcFE)miFqNLYlD?hw?I zR0pjQVE=VqVs`%$I_{}uJj|CFTp43t<T&UYnJ3~N5irCoP<EIAmY&WZ6L_=~YNTM? zx9s`Y-b#AYLMiRX8~M|kP4Ct|PMzI~GfdQjTd0GTrm&BC)#)OG?v!Z)RW&C|ywb&_ zWKQ*b`jPqsUe-$^$?aVbPy0rgWuf{LQmC;mH46C9bMpmULT8}L+2jGMnq{io(NJTx z`oA=WDTR-VD2IS5(+JAWs9h2jMt~6T*5u!>=Xc+v{;D_WW1rMQ$QkbP7)LW_e-N&m zM{8_7Vl3!n8&myfiTAyG!4aUi5%VKcY32`}5|g$?F@n8Lz-6ePHZb_>=s*9u?~C%v zFjL-Qe4Vbg*Dw*XsIsVKqFw|!7FmSzb>`>V$tck~{5zZHdZ&K<IE7n_h4yq=T*SL; z_H07SSUrDt9jO+E;C$pQWBjIb?S@^R+sDM0CHV>l5d`Y#fPCj6=;Hk5`Q{OSsCYOF zG%-u{wrSpF_D02%dk^iU%_l4N8ToXKB+f#neq}u^S#$r+i9Vj1?PVxs9G0-t#`wtE z&DLkXy8gZ3%crdbU8!Tp)*sDtyH^}1hC`u-obF_ee|+ClzWwd_+#}epsyy3GGl2cP zbnn+0_)WLEr={5Oc+hOvOD?57^k#(FPf9`YmCVoR)4Y+$*X@aZOV#%w&7>O+3Z46o zCV|Vr|M7LqFu-A>LU#jGAmIh_XV@n)(#NHobUH5?#@ke%to{cQ)9f;wZ;X@qT8S8u zucwZx<2<F;R3F7Y=Q^7XJtcwIr|Icn(!9i*>y@Y{o`Z~>2p(!paAp`bJ0t{|4$+=b zJ!yw)U8W}ZT;p98k@nD$9+!&!3~?Fm8D)<o?AQphZ=$<5Zag~><2rge@<)`r-heP2 zd*62p`gS8FW~~)Vy^@T?)n!E~&c@#{;u)=J$O+np$CirL{@g!@`P8H&TU5Ui_h-_w z(0mvA%XT=2Zj8&PpF6ALtNUWw2qVbubw=!O`$s`rZ$Hn>=KXkE!SSPT!jtZs4t?)6 zt&l|S2HdpuX#`xNwz1oVcDC@5(T3)+nY>C|aJdl`Kbm7>GIUQ1nU4f3^^X}3J*eh< zZmXppu$)u#A>RK&RB((F)u-S0j??Mu=j(8{>8E21v|x=9*1Y4CyV@buzs>RG(z(~M zzEqdjKCcVTk);cQQf^{bd201<uQaSSO6tb`pyK_NC{p~*M;)l~N_wc>JQBHw8k%o3 zW3w7@g0yolm#v8J0^U}CgV(+l9P#w1&%X1a3ca7-WK#spF3GJ$pDI!+y!<8JW-7}i z66;|z1ABiy-yXK;P|32#Mi-PX-r8sWMcOGrD<vTNNg{2I+Q#6EUuv%_edgVqIkw-w ze`dzT_IJls;!8oz%C{Dpb$hj`!}mXcsHehJP0A+;3pYe_pEb+TeoC{We{n(Ebmo0f zYARfqrfN~yb<kp6X8k^`hUePu(lFbL2VDP&r-uBh)>SiA(TPm~KOArIw|080&>d6F z>2qldQg-qB2%t}6IT6m4DLB@hN)8{;r1-|W?FE&$OtSj=*I0h85^>Dw&3R%4*-f_k z55PeE96pw*6y%B!K-CERmGe%Z&_Vp!@9v^lAo9$MtkK*7-u|@oSjP=+mk6|aRg@Y~ zX)ZtfIyd4Co4&AAydnLvc|6^P<P-Nnr4=scY?gl~$x3Qz&dl&zoS!4KRV8yD0UtS| z={b+RhJ6INT&*5Egmx5M4KTIlHdyN1Jd>IAB@ufMC+%PDAuJKDQX&e?tYPUaoAykI z$B|+x-`Y!@3%ZmLw~Pmtnm_gHWy+1}zsqO)&c2V`ChTm|+kZ8B2>rX%(E}NqqY}Hc z4~BWQva-+YFnaTSYB#uX$Byiw@qYYlQQ=BZ=49jywI(_2z~;sRv%^9ipy<t5^G%xX zf{iV=Z*p<IS4@Rn!C~+JwQ`2O6WeSUv82oJZ6+(vxT^fPQ7wiKcTqGc%+XSPvCiuY z-bS-?_}@GDFfz4EWxcW3Hs_%H6en}*#=5_PE`OK&ADGbM%)nv$0j*8{z(T+=;2`t$ z`CYYFZ`faZDoRzw-PSv&NLFVTCd;X28IZLir0ZVYleqWY=9~=V6;Q(LVnJ>-#$kw= zpd5`UJN1`6k6X3gwf>NCN!U48*-jgVDxM~gqJ=Wwq&SA$q5bhI>lMALgN^!&%K&63 z@85?(QHfx300f8LK)PL}TQ;$%SVQwk7Tx~lQAaMBGb&u?orzo%?Zc=SA)i0#r>iq+ zDCr1p&=(LAz*~|`afwR#x*l%JuS$=^j*09R(>ILwI48jz@+J|81a3NdFwQrP?lumd zH7jO$gZ1Cxf{v%`I7R2rNzeP%U!DyJ1cf6UG!T&uarE*@AhfS0`%>PGxQFJciFr=- z{tL!;>OULIY^kmY9<xL4k&+e90Z{ux0!M%;#F1AEZ4$4x;;i~-v5A8qrTb30knFug zM(ezk&}}f7Qb90MLYBX4i{ort_g<*}N&0vocR(+58o&kcw9FxLtXEwkMsnaeroig} zVayuUeIyN+B=r6ud^U$|N7{C1<UR*=^s_jXIUaB!5`mYGIIza7<7q3_V0}n<69$?? zqDmkU<V_(KE-Wno&CNr|SpXir6i2V4BMXjxI~_slGB_B%#~lX`bB5KM!aH-|Gez(| zd_pHqh$|jGi$SE}2^uNZT%&5`PuVvDxJ2IjE4v^rkTlH%RLzwU@Bus&4}619O3Hy( zo3hkQ!@5jq>}%<A!O7W7oSR41V%p&R0PSf$|3eaD`4HMV%_=E%MW%!ek|`n}M8S1v z9}dzKa3f*Yp8Q_pvxeRsf@j9L&lm&U2uT!yLib`Wp~`KLK|EEuDLmjDTSJ1UOF}M? zbhic5ZpejI_FUmt)fzUVs&z3J)3k5!ESZ6@Rvb(R6Iar3wLhxW6dsF#Ud_mXiWwV4 zfh<yLzIZ5xCqrw8d7qs4q!>kO4)@Lh&L2`NzlYTvVp|WPp(MC{1a4E$E>zaEvVmuN zO(7o1@<q^1hJmK%5G&ZuDp3iKG6i-ur2aY=tv3btuE8ouW|aC_gWbrrjp)-rVDkLU z(Vd$+hqN>F53bE(z!p$tJWSp+u8$SgNr1-S;ni!<5r98VFn8AS##Xl}Lx{Q$AZ^c- zZmBSSc};Zo2%``PD<x6o;S+jEm+9q8;B*qaL=x7Fq%lDmXy3}O+p@mnC1*hejnCnF zt9a+@9gO*2BC3RMCIznF23Ayp<yT<_B_XRW{4J(%r$iGkHk%=roM<h?5nlgfO@QX& zMn0Pwz!Nh<;FlUhSwzGx-w=|RfyEG@T~}Z=0>d(rj+#3qO+RLr`bNLA++Le*s~a6e z!TWSa{o{1vJ8770ZV?7W6GH$oHV{JtVdZPtEr7f#0=&r_LHhjAT#jDs>Q7Kg?u3_) z-?PMazMP6X9CnluVFsg*e^{9Vzfvh#b7D&cuYv{KISm5^!+MZ39c&eI`WbCdxn(!R z-<qt8UgQ5tm_YoOmb24|M@yJ=dRX%`)RSD%Ys(TR1?lxH_`pinKf~bJ_~`y?=l5PA z7Hzb;b2rfjc1-V+2jhy!7oyEM@Q^ktc_d9axvcN7z*z|`j)g5x(@MEkT{F-H>W2kj zOMa2S`51(JUGQ~f#)Ad~q7jA6MU$@3c?1ev08M#-aGxXuzXuh@!jxyK`Cv6p3yj$q ziStv-^b}w1lN>a6ZM7siyB)#|0Ls|0w35N4<PwiuXpdyo6%xSx*F$PA0mZAa1Y`bU zI0JBAgS;qBong6S{zy8YzFZPpYziJ+6K&{ab&Y)V>2*!wzE-X^eUPTf?zC;@ejQZ# zL5$QTn#%<)CrLF(;BO^Bqww%3Gg!UkgRW^<*@NPmU*_T-8L?G}=x0qOiy3zxqVkl{ z{PZ*)NZ@D=LwssF3C|xL#|qP=g$R*e_nGNc@d`>itmfo0%Qe+(XPN$Lj*Vk|KMs~7 zz?Gb<a|sDC^iN7mX<Q9R8^SkSJTp$(^4|o=x;^x2X+n{gTRb+PU8eOh521sH1)WIP zgO#>HiiYL(R)C16Pb1R28iBHLE!Op%gf${^S!{9{x+I~rrj^wMcnlKWn!}2WXJxl9 z6xeM?clsyPB5&5g?jaEw!XBw?sBdYkBU0!Z40m1*;2uu$aa);DI=UKP9B_2W(6an= zMm7;^SbEgfuzQr?UB{yjfAGStg8mp)a|mV31$g3xo7>7VuzA+Yu%AV2dUNfL(bp;8 zA|d)F0bn!e+hk}{hl~)c&K#aZpzy>%m+as!LV1DvtZNX0!<X(cU}@N_0-&$iW0lSG z|G?H~k4W$&3?)ty@+$R7kOA7z5dAJ!IJdI5bk*?JAuVsODYuU`Z&SdhlZM*WwwtRk zc^J^At&vHj@ST~E4XW;433p%W^RK)D$@|PU7D&%_cGv^|`RDqVQB046@UKcy<Pw%w zGq7er(pA=VU=BRS6yArEtixq0@1vwSnyOa17gSVp<>_zAbp(+wz0SMjA<y-@eb_)C z7NPypm<KQFaIm-;FgFIMjs&}#f<wvR?8+9A-{g8+p>8$#-*f%<_Oi8Ff@fH|m>;yu zIkX#xbTVa#f96923paidNHey*EIuqM%V6n4KF19e3?BIPOKGIkgXGlWb?>1UHO~i& z2A+8#6!Gv8GQ5inYng`iti2grqYXlpUsr6dU3tk~nLL%!qgICQCsADyGX;<%{3I$J z$sh~~+!xS^n(eANq#cYHHc?frD?;%1(9V)Ue#k<BK$H>|R<Tw!B3YHU?inX~)Bh+V ze-#CO3V||Q#URM&@c-OQf+-M_17?1Us$y$ilDce&|JvCmbcGwOZ4{}l?MVF?g~Cw6 z7N=={V_!%X`1iAAMzynu*u#qsg&t*q+yf{Bk>JoaDozrJnFB`SG7-7Xx`?FH3x3sx zuK7|(`<akL%7J#`;(8;5alI@NK5+JJ^MN<yUwFD%JnBTGP|2G=u6=?;1AgZK4h$Gy zK*MOiV3m(}Av9A1iQIoFpd*L1kEWsF4RDgF(9Q))DGokjdUtTbtS^wR8vqF;fjmsX z=fbdgiu||-N}(9w9TG@@1PTQ}<{Tz{><c`kVSj(|{?|WkxW!EFp^cJ+0-wI<TLY;| zR)6_(#ZT_`FsETv9Oi5Z-VA_ff4Ee+VxLV8WqMt?ovzrN0hH2`<24Szc?Y;pI%|x> zBR=ki>y8HJCp8^Q;LbIegArC9Fjjtu-4V*1>!HoH#20?h(?6o&{Y>pnrl#Gc(9MCH zMZogfATg#OHaz8Z43)H_Sjn9^ua?(}e*CqEWgG@e0cz5BA0T$xXxnYUTrR>Dl5vHS zu;QqPJA1Db+ULw~zOx)KMo_>x52>QM2fYE5&ql$4NT3dh%AKIZp9A(VrHa9UXMD#o zB+wXYkStVazcly6cg0P+sKs-tYr1wBlHVr@jLyLbN}<V(?`E(Mdr4;fegkKRFirw6 z>c*_z6?T_!bwUt9@)A;-18>Ta^afN$0Vb!LsT$CE485$}{V!|(eq_#LG>w9FO=ou= zq8J<@92nXPym0Jfm(T$$hJNAW&qXRP@$-T3$U}nNB+Sefo*W0C^Q9~iqf-7SDS(4G zd#$P)6@GMFFW6)FkCa{?(C=usi8_GY^P1t!nt8#7ZpFhnh}`P57KlJN`7b032MGj# z`Aw<%C41}QQ5~Z|=qBG`IAv7ZuqZv6r+HfEo{kSI-SqC`Iy|a}1RliB^aW(2R_aA7 zC+GBF|BV+iwrU3#NV)|mxvx=W4h+{T4L-i2-r_-t0BC_Eq@WF&tOUy)9d28N4Nmi) z_<g>mb%{~_kT`UdSVgYIdkOcofeq9)s*qbqRLif&8yi;w&6<i+5M_D}@w=U*9A^@P z`KC~ykdFv<W*yd!Y{+=A-#5F@N=KZDOFDuQ<Atir$?yAKe5qX}%9!^s)$D7V2|NKn zA_3n6F;EA#YZy^1%!NU1VuYVg^2@ygrp=pR$~>XU7oB9V&R;0MGgZgr`|$QJw9@<a z$o!81+@Bn6LH)F5f`z~T&0qL4tSZ7*k#yLT?=p;^%p1oZL`~(A!OM`<y@5}i2S>o~ zurs!t<^sgNsq*y)aQ|XdX-^9x`(dZw>gp~`(&9587w(g61sc`J7<t&awvI+_^on1e z&`P7ZdTDpostxZR)DH{y(bN2be5w6%Bs`9yHOvIOddU3b<mm}BHjY%YRvMv%?!-W2 zN$|V&5P4I01%UX=fq@*!P!~Y+SZTrdtJSHl_G}x>_zB5|Ym0^b`26DZ?j_I3Sxs{e zgPHP)N^gD5G_)%vy|<z#PoiG#9Rr`;a7<?+&w68IV|AXv?`PK^%rDUrGA_9DIW|a{ zp)Xsm8x0P&!TNCb>yDwkPQPOYKN)b+L{Pp6eDhMMp~U+!>cA0Z{rGQP!0%SmgMTl6 zx8|w_fG@trc80aXVglYb{-%%_f6-q0*C?9r76R6!zp{3B%YhlSj7QPJk=44Fsi>=* zd5uIUL!q$Fbb(0V`tfp}&CG^Q2AiD!*3!)8jU22_7VoXuE&Y5Ut5&z=+}f*b{Ei1f za;79)f`SG$$Fl}zK@)k=g<rD!`I<GAtm>+K`?lRtr}(}ayM=wLTuJALb2jN$4pxO5 z+vw8yW*o7mYp*nI;lREpaC@rO{{1)I;GL>u72W-O+hmt(E=_rFEhOoZLPEX0nT1x& zdTQGJqTe68_c$c9E1&-4*O;!<$>wyFadDq$w0h$4aYfFd<?K9OnJI$NcCbosk6l); zNL<06Igg)i1+!$`w=v-Hso&MotJn9QxKlaCmRP-5753@l@9@L*+bfTYE}w9SzeG@P zaGoN4ZLO0+nSLQB7=+9h^%FuDyi2uPUNhu~7gz1?u&x9JPe>)t{^BoN0_6v2!bDy- zi$$L(-R(Oa>Vq~{N7!o@kyPoo^Zvl>kd;IS?3;%HRU1>9>?Xo(oFynxpEpd@LAA_* z6RB;w-08B%dRdb5H`q_K2aR=-%9`C#>bB6~Wc3h@Kny2B(=gwq&kTGcI7gPDrhj~_ zzR=o;J_)P1nIAl*q@(o4Aa=Us$VmP7$<yA3akxi8UB#6`En(QGlYNsA%u^(Gvod(r zd|FvYI_=;5d{zIrYmoBarl<4cG5gCWmX;PRBCjTuWlrQ3G=7+|T<V`gl3(B@g@os) zS@)X@@WSloRy-<l-;0etiEgWTl!l&-k-yO-cNnF1p4s_cPcwaFZ4!ChXA9L7xhlbP zSo7LMF*?lA1M2;zAb2!yydvg!tZ-<lDmS%GBJ$cz(iE>q=(}jR{Q0}CeJg=S*5w(U zw>R_6Epydt+MN+%na4Ky5{?(VrRHx-8&(p)AI8y+c1OM=;sa<sMu$G3PPd0Xi;VoS zL+!Qvceyx|Dg{lNlMrSfJYCzT?7}YcjVflljY{9BEL%8a7=+vkE2loscdZeUlZdZo zj{dr{pVa6S{F-80g!m?j=>sVAac#Da^aZZy>Q6wyr_GmxFYnUDg?DbJt>nwI3M!4> zRP$jGx$!(#ka(HzxQLBdS3uv)bHA+n;%`XGH<q;#&();1^Gy2v9E=V5stW^hpQ}V~ z1$2$QewwNEJNIFbTgJzrwS?|3TP^cpNu(Z~PGwegNw%TvH_G&*+D>faZuwUH91amX z`T5DF?}BY+7;XCEB<IF@ZSKeB?=x9<1vvPMGXA9zPAM>kLB)&z3u)YbvR}Z>5IL8m zp2$dQsJ$zvplm9rTK%kr0)Fi{fa|wtghtcrI`oH)2`UzCq{)00L%L)Fo8&Z6`4F3Q z<sK`F2~9JZ*W}`{z<~ZkaRev6GA0I<*~aW@sjPcN%k#Qi(m&PYOb)!7pa3&AjVaO; z-L5LBNK!y>k~+vyJaU%85mB<sWA2t<_fn?HL7Ep)rk}uc|Mvz9bhgAH#mmXP#`T(# zIf5>%E)&O?B>w9vi}}wQSRf}3K_f(kJO?nauU6Yu6leZen9dSc`Va>?uVsoGWth)# zb>hF!SLrZFRn$mZh2*9yMgX8!hIyJoK#C%H7AU}K)}hy!L)SaRkaKcP@NNpOIFSb} zB$8jlPRW<5lqj@Qnj$cxr+Zu1!q?+1Bd5Zqd=fy6@%DHUn<_a;c~=9%i~(NTKoS{> z$pT$&Y?^xd$a-3{hj*n4`5GBy4Jiz{KAT!lf4;mhdE4oZ*0;Q(o;8a4KcoQORIF!X zCWC`NVaq$eI+*J%mq@D7l3vp6NUH2s{5&6JqKz+`808(ytdq5BA7tzHKAJ5E9et2F zn50l@N>m=L1cl)FloxKLyDbk(Re9Pe>`IN?X*v-GDGz^&;b*ofcHzKkHJZ1iwHfVc zalLB*VmESz^#1^_*G!M`nH<gHBj&*Fg7I{2rio962Z8(ZN#Djdbjcd-PF4d=Hv)Qi z?RiC-Xq*vdjzvXO$DL2o<xo??&hbLJT_E*a972rYi$z&3sDy?DcBB_27p9WNK{1Zq z?P9JDgYcP1vmp1)sN9k65{_o`5cRLGxQr`%%zRmr;v1XZ61@A0{rVw*wVwdwEhAI8 zM|cIxV4+h@ScqSe2n&v!sJOfS*vEZa+lQVVB)4TgmwUta{^Q&wvX=ZZL>CV(hMMkb zvZEf1M;<&Dj{U%$Lk!RsT>wyCGje$vsy9TpVwe2Ynv#Lslpy>r()ikyC&XJ%06zG8 z&`|#sdRy}DAmf*^m~EarvzT_-J_@F&kn<NJJ9A3MM`?eRDGPOq-R(mOYu9n{EF}#| z;<^;`4m4G1Nupa&<29;nVG4#;&v7v>nH&qZyYcu0{&bC5=C&kJ;oB;tf`OR2wNI45 z>!yhr?m5N`yX(w--mMF-XJO`mOU+)(nja3KfK-R#c+t#6Y4K6RZHZMqkrcjXIh3)x z!+o|d-3kNI^8h=eKPK7lpVR7P=EC)n8}u<4AjXXZrv6-I4#66;9PpM1Y0=K`Q#{iV zUfQ=Bu~QY#8g_V_1C}FefH?(+o>#4~;U8_>FxoT9{#y^X{z_IjALRX;Hb)XP<XPwt zA8QkJ@$<g(TO~5Z*Uf~KQaZoYDzW<GzfYxbp4S>Ie~!_QD#hGkD<X|6b>Rc=wCQ7G zs!;)J;cRQu;JpuX%V!Lk8X(pTMb^sJ9(cju;m6q#FW-G)sE^1L)Rc(LsOFrZ*cTlA zB`uJbBuZ7bN@snf;9IdRbIDc__9k66D==o0<85GM^F<@ekG1%6tWBhbFE*9EP4X6# zqv@A_&HE2+cG1g+Amtb9ncFdndmJrWQmPcb@wjQh;w1{~;o?@9`o%oEE*E9JI3~h& z^IAdMu+j^P?5E&gy6dCE3zyO_#Z%uh>6>;B_a){D=Gklna+#`DRU#NLWRCBnp!IFK z>o&ke=NRU<8X@#V-iTVEdp^7xE*`sg3_c!(rs}F2BLRr{%{>P6-@A8g=v$F<&fGS= z8aSzE+%fTE+TFW1C7W!n5+GMEMgJlw3BQUJ22Ov{TB@tRiRN6dVa|oL)kL=D5NQsD z_9cHGzjV!>ee~~~Q}6P{&v$QekF{RjkYCoOjd}X2O~9QXwb^koNcAs<_40i5Qdhpo z_cD^3bGa>fHIDVKXO0=JTe&TJMUj8|BHa~$WTGO!Pf3nKzWn=x5KJK6C6Qk=vBb7t zBi_2E&6Z+>Q{-vOp1M`8K$+yL*L?Yd{FacqvHJ3_7Qyo{xg=eK?OC<v9N6WU1{H!f zJ4_6M#^>2<7>x1RoFh2DYD_?`b7%t)ID%HgRRI)mPr^{9F!J*k3{^~*xnkNQc%L1F z>x(4JJO^8|IRu-yKCeXp01_iH;P5LZV8qn~Q;X2l_xLyJMP#<iE8w+5T2qMj*?A)6 zhSq1nf!D!A)k_EfxYlI2o8&o~Eavvwa|pef+St!P&0>}?gi$DX&iP(QqJduRrV%u4 zbkL>^<kFVB`5bsR1*94SmbKII(&WHcvRUkAG(R3NUCK<Hqy9O~?-0fIK2p;$10LN5 z@|h+&nI;C3Dd*pUJ5`9mp2H?CLcA+T^RKz9b5y(`*<V)qgQH=Y9P0l0=@A57mmX@D z6p)MJ3wv9&hdv{wY0!ZNaNpd6;E?*4jY&F?Hq{?FpHz}=&Wgmo&ZtcX*-wC6B8a`_ zDn6d0{#zscqeN%(k|`zJ(aKe8Q^T-X7M@9V5TfN*^^A=4!0Ey82yn`lddh2U4`2On z*b2T&v#KrnR~9ny%F{_wA%zJBbSbaK-lh<PZL@;glJ8)WZF;DEOx0_?>b|Z_Uey>j zp8#4KXgr95tnOx9lxFz2jy3hefWJUK1U;W~(4vZ=ic30LdU*18Sp@_24m7@rzKeN= z|BF!5v8hgvDzyH0a$pY84?SUuVm3rwrM{+fKf5BsQdkk19vpMmU1U3%8%@<H(j1NS zy-n=d8yI9Ab1-F|l7Z>SV#2-}z0dD#!NdI<+22(TjB^ZILnzgzlj5{SBra47qi(J@ zclYLj-gtG@V07iCsaFm$1Sx90+_LpD<BezFC_U~rp4#wPTF2>xYXn9$*rPmA(!EQx z>b|OpwhFqBgY+U0J@uPjPcUA8G|4EZIB<;GYg+K+gUKzbQa-OF$`iDoCfw0BX$%H> z99eCur#}wh9NaR2xI<6BCO;BXm{z1VXHB$*#Xo_GRBep=U*Rm%Oi`yDqF=74hl#6! zMk*Qt%0CF&c0g7bs4Y+~Qp60c_R>g-*{cmPWAt!Oh2jdec}02^GZp7iO!l3A44yO- zDCec2mkQZ6t79VtvB})Xqj0bnl!6VE#+XZ52}d=upnlWZuThEW2*{06Ap<Bc;TDQ& zvaKnwSR~P(HBp-zsD`1!;pfC6h}9Vu8l4iNtCDh&Nm#4I8x4sDYw{A8yJU?_O9^<Z zoeahOO$FX7Hf@iY{(+??6IlL0UYI*M<A<fiU$KzUZryDKML^=6rTW(nkNDNB?8-?| zGfnn76At+c617&hKSI)`b<>g7&KFj$YSwNyt=%21J^ZZi#9Di1T6>jSd$(Bo3|RY4 zTKj#p_CK(```0>v)+X?pO^}#Pu$oQC>0;C^n=n6{@K~FOOq<AZo2V9>=mDFUNt@V@ zHunx}?*FwR(AvgbvyB(CO;EE<ylI={xD@U;84_!ow`Y}7ZkyI(tNd_5Wb;Nu1lYM? ziC7K`ge*@--=zJO>=&c<o^0#a&O)oy{(i$UeLJPUm>5$`jBEg_UD6v%%s0hWRr)wL z298$VKL_8p1>bilE*?nH<O2tdg0Jt!$rFe%Ymx=0>fUx)N~3XZ)5Hduw-#~GA8|x2 zTW}bj7@9-9yqnxKz?OT<ez>WKc7@7diP}&xA*yY8D&)~xR3bVh5qC)4dMe-x1;-LV zVWVgUSFrmuF}#@E9%!%GX&f{SRw4i+F~rEjt7Ge@CawyLB;rO(ydo0NeTvyFIbBHp z*dEZWQ3bl+pjgjjk5P1IXBjAo7|cqfiCcbX2#&P{$+i&#i@|rNi9)30oIRs}X|Rf9 za*QH401vb^CAK;?8c970)1w}in-5CS*SdO4%8r(ogUIuloQOb&sD#upCZI-xMO3ka zVG30=1{}3E5dk3Hf&c?jh!JbaUOiO)IG(|qwB50C!K~m|Q&8BFK#1uW)gst$8uVky zs=Xv_ZI&2n3w9462Ia6lS&)y?UyxV=h2X$fw#7h6CvOrlQqrX8DKTh?bPx3`t%0R> z3#5u!NP~#09#ThF)>)c4hU+DTE4H&&q{OhgoNE4;OV1yXlXQP{?LL65z^G4o9;|nm zaN*}1spqWJ28^6`Jo?)Kr)!O2l;v0?dbLqqSq;-{onF#9d^*j;=d#`ENiIv}jaF=5 z8c3d?K(?FdN9f_haAxaO)Zvi-q|{%AToyYhn<hnIh#?IrktDG9Ib|e{7*g!Eu98P< zkbHfV%61eCRR6eyBgOze#sG+Ewydsg35||!P>NOm2%=>GQFXY??jG?wQyuKnCURgi zruvH3N`$l$hyAqt-om5KKg!{V!42Rj0(4`6C?R<DLYm^2hi%nzX`>R91c|t{#30)& z3Vx{nG?7#M4#&6Ks(K)Q$<IpP7>2Aq9MBSf#z9$BcJ7+)<nDojM?VEb5Q8udS9E9h zfMnGdEYSoH&(;V1f=(Kw#GKRekYaFb8&FM=7~b%oZ!f+z$)PvkQN$?m#vygUnzM1v zW^Mx}K#<7!&pEpHKfQ>=n9H_>NcG&TC}NCW(p6aAm1Vwy)x@&8-CEo;igTp49!MKS zM|gtmScwb_d*4PCE11l_r7!&ql)B!Q7=a|l3|70GQ(i%>#p}Emi(#yVx@J>bDUWmd zQ^2unK-C7YzbQC2VmpT5nA(EzjiK^i8fGmd{@VuXV!&nUOj!Pn2{u)`MX;SGk^38{ zw08k}k7%CEg{w`XrXzM6F|`VMc&AW_5E4DIV6gUEAxJPb;=jn0Ool>mERM>%0UU&3 zW)t$Vg(Q06fx10=!G%cwQ6guu;=k==+-}m}*e^Mly%;>uIOTJ9MT&wXC<XpaW(*yh zLmehbZ1lIsUoL{fa;R5yz8sR=gONMmLH4nupQ^H;A9U9|cjFwFlI5p24CL<?dAf<7 zQN@x!bfv%~K(5AJPQ5#cN=pI(Z3%9p-Z5kOL3$whPrCo!fS|YizkY&nsDu665<CUL zb1e`#FQ+eRQuf2{I@T*{SA{Wm-N!4seJNH6bxCoceIw|9iOl>lx=bE*L_b?fi^|)R zH#r^+T#wcxZY*5&1ujf4m)&<Mf0pl5pV9qnCu-0o>Wy~CU_h#R;D7G#f2h01_9W`9 zB}2^_0!E2D1K%EaeJdGG4nNz4#XG)?{X`>>BlHe(#_2uW;*y2KzmmhSyeKrLzw6#c zblI7oxEurDF$I0MURC``7j*%Op8n9G8xmrh;3-LzdXU4wOq3xdN099^dX^2djxD_I z_>+@W$jO`czUg6nB^82xnr$ioz}ENbwoea&a#qR~Q)JJmZ40kL1Y`BhLq;PL=?4nK zdE8!1F_r?q`RGHuc6+@O{3v<ddwDOo$DQN-_g>6x<;i5BHsW@Vi<NCcjHJ);->l;$ z5EkNkT)VU3NM$umTuKh)jU0#|fp_VAhZe!k?}-3ii548k>+#P*#ME4C_dVmhm_zFS z0ck*%zdX=~F+r-2sC9|ghg_eX<GzDwDEK?Kke#*%P2gZi*Kn2{;$}XW*buH^An4x0 z5P2ZnWB&%<^Wl@WAl`bQ14^*%6GmZsID=)VS#U=QnDAXo5QGwLcX?>!e2{}%X!>+u z;vz8{c^KUoo{Dk6hBv?l8)e0qFd&}QlO|>O{#9omra4bS2X5$kkpJ}~u885b1Hdh5 zc~f<_r-+b;jYz);K7Iyekm{S~h;9hr$R3BrX6Up<Xodc66(`(wfQE3O2Xye~#>$jR zriL>>VHQ4meb|LHsMDfPiQ<)m%?0b<p@($Hhh-pZ`c3sxnd?A^Ws2xu>E+t-s8fB& z23y2yt2l1vt$RY_UvP+oO2`NPMX7YAdvo_|<hOlT0Efh;XNhQZ^Vso@II(&d?+$+P zg8w-&dN2fcuz4~H2gB5acZdh7ClY<mXgSEY`jQ7}7KbCqlhH?s@>qjqu>apt2Y^tQ z@7R=l-sah}CvPFch7KP>j3{v;#fl9Rp3@g7Qay0-7RD==%nrA6@$%)fC=q2meZJo0 zpb;tG$Al^?#ydHZ8#;O6!j&tR^BX5d@^YfQDGwYsJJZa?vnh{dJZ_x+<U2PtrP8im zzd}qHuA9D8?#lg~n6O(nd+kz<?FM!(-MSIYnS-Z~ow9u2CjQjtOqo8mQtcv6%n+qG zdta92qt|dAIel~}<s&ywF=vPA(&?kNq~5`Z^dyU0L#^KC&aUky&4<TVzH$w@(f_mK zOP{=;U~R?&mkiG|Y~1GL(DzND;**ymaYM>=A-HdEp2|Bc5%1A_#PD!~cakertB=a{ zO!|7g(x2^Uy^EKYV#0CuQnk}(jy-?Hc;V&4mpy+;G!{IA6((1I3sRJkHET4cPDAOC zlaDHLWY!vkbImhPXrpOn8a?9ZvxX)5kh7tR4oL+LHgA9fk38zAlMpxh=%!CR+<lc) zJTH19)H&QRGK-FgC3OxsZ&(u!a}JfG&l|=(c@sMM?DUa(4V9CR9meps;)-JJrHnoA z%vVuH+GwNCIAYGFkV50o$xxME*#pmg?bs6zVBx&;jwWcfbtjzcQKk<ibpIHX&O!;L zGh#eKz|*02hf<WN9+-s)(P<=7A_$6?V)~ko`c%S6bmM`f4<~`t!_7il-o%nVkp!aL zLfvrl1~v-O>Qz$uOoN9v;6xN9BaCE~PnZ)Wg$_2e(WB*b40So>v!$|^6It3^BM+K> zs+3PV!|2MbQudr<k3R3_BT!u}Sp$tbKasl7Pw(iX3_D}xt8QZSRCoq5`h0egJ>}Hn zhb8EUQ%^ktPc)A=_RwJo!5Ts|4?Wump^rGHQEX~TCo!UGP6;K{k}-CGgKUpnaZ`>{ zPu|E#B;8#rEKT`vf`>lQvCQSIf&AR_MCddXO^p&oscm+Kmi$|vfdA^F$-Uv^Lp6(i zc5@Cb?Vy9N*8<~}&p65*@`oZMW@JyW^x4CfKG(>SAj^g(^i7%O@M})MRd<D#$JCsG z4m#<0ShPHqSt5tXQVp&m<@V5%4>e!ZqmRT2OLh1XBA-?{;YtlV%^N{InG`(W*pbY{ zTd9-~UiP4)&MbjcyW@WLsLs@^C@Bps%^LY)8?8y%gN+@=4IfcL%omHzo3vxE&e8gu zgOcf|s|B`T%EV)s<I>kn*4XcK<K)?;dSACW&d_p={j|6%k3QcIzg9QzjLj#7LLXb) zK?`?Wjep=<Nj^a32Z+gQY6+o-qmH1s=@su#Qb9@QsBr{0?f>mjj-yOI<e&<BL`s1R zWZ+bc@dkZFiDf>*Mj(1|Bn8G#9(s8MC$NzdyyS#Pun>x!-uDpoa3dd6;#ot=<11NV z?;#j$NzjI7t?2c}Re>l+_cFLbm5gP4dNbnG*fKw5jKzH`3?ts!5sv-6=NkYcqX_+X z4nw$uPyrLm|Fou`{Y>qPH%W-Z(4h}OP-1b0)J})=;Ri}=jE-=cpgwjX2YH}_RH5@m z2~}~9cSuH%bFq~#gjSB$aYZ<HSXB-!;w=5WtRr%=2{^0)qjt?rDI&px52HxCs{Fwh z$da2EY3CB5L6KBZ!d22l*%h$>YHa#QlSSC_4tJ#D8~^QFq5s@rh>2O#9PNNcH_Xws zb>%5QeUS_x(HEF&G@~$Tbmk!0r4JlzLm&Cz(S#~Q2tm|CGd)R+IK%-l6^3O%`B=j) z^pVN;QKlY(AOynbflzufWE`^L1Po{CBP@|bIu+TQt(H{|M+I^zve}I<%XPAP^db=C zFv;?05}d2l<BAMCNhBCi4k#XxCe3?ZbXtm0iCA+`&e~Q*@bV6G(1IQMkPtWhHnw`$ z$0ymyM>DR`J_V`dKlxx&VI=sca116c**U632v$i(kt383IZbHJppOnE#vbB`OowE2 z(W&9Z8~TugB`{ezx^80$_J}K6l_If>Yy^f8iT~Mbbd<}4QYRc=ib&3O#wxJ1WEPC@ z;b(`J6L3W05jP|wIFv}God)L)$p}wr8!N@Sl}R7)FvmPcI-q_@wI2MeS{T_u3v-yy zn%<m;`NFE(dT1?e?}KKb%rZyYR;)sl&_g^9GTenkibQ9ihFj0~70p<J4JDw&Vl4_5 z#EM}XB%_GL^kI!DwD&iU0w0gK;k;?s<FiP_(Qe{FBbP3O8_8IuPHmEpX~0ZoKEqwF ztRb_SF65_9Ny%lA=%oVB%}3z4!!*KURNG30EPT<&Qw1kUo9N?Q;ULguMcBVfU9QGO z+*>zg(GGc-4<!KN3tIN4W2xxF8^d^qIRCgd-K)Jr9#KVZ2pLpm3}V^5=o29c(Xb56 z&Es}eO2}R*;RlgP453m9Xg(^z2FUCI2LYXjIsjR@(0OPXXCMtiyhg~*ZQ~2_O-Gf{ zCqqMuOmOP?YhH;N#A)2YBeg|IMqZ_l3l|fEN72W!B&{B*fFlsIpvj37svZb)gQ^&o z$6lwz;jWoiJu&+duwX4hA8{kK^hl4b#iSkL0Xx{j1~zr=F*bO-QHH}7Hg(5VH}@@j z*$Ls-yX?aw3`Tp{7zB_unjtPR`!643J4gGlt?l&L18?#)H?!@rAHDDeP-4zDz3WZy z>8ax!`reAYgPjl(3L!oeWH+oiDgOvjMXVkKuXjSU>j!h_gC6?W10}>kj#~Ho-yRZ8 zB#GH>iIM1$qw@H@$(&?s#PyUU?>Ea^PQ26Vj2zMtc1wI=2YW!V<=Mf;ACeJDnpdTU z`QWw7X`)4Q6m{7d{%}ebPP|RW)Enp+kJ5wVi$C<P=vps1ql>sNduWX<I=-zL*VkNE z!Vu!TfCVv-TaRmv-66z_xIUoK4sBk}ZnC%rJkCzQZj7U=Z0W5;)>0-wQ4>xO&&azv zn$p_YqeF>32RiVYP|zS_4Y>Q<GchL_eF$M2^*9YV&~cf1B&;im`e%j?JEFl_VzJNc z5H;w~gC2OJH*c3Df1;(2KmYWCm2fwDDf5x@V)joS!Be>0QwiyrmO3IV0U9!Oip40s zsvP6^?qW{n9Xxo%sJOn0O<RfGsfF<w%3xnxm`XRhsoU=fO$ZF%1r2D(LKbEzM_an@ zTQTEH9JNo^#E&(-Ln^S}ou$t^7=kyj58>UG|CEJ0jDy*12#>jo-&lj0Sp!xPlW#4A z#H@{(iA+8yoa5MzIZ((wX^#oUT|*d7Wefs9#Z|oILpF2)ip&G7JsG43))_2=IcNs= z-C9;uk{rZC!hKI6=>rDr!a3+!HU!ixVTz`8Pavqwq@4^m-~lm^N2WQN7UhG?Y!Fx2 zMrGBO@lXfyjDuGAlK*-vQy}D<Z#*9D7*b4;Rx4rIQh3A7$b*<o67Llr%Zx=nyaHj! zpKmEwHYH+0wGRNX!#k9NI<SMiOq2UTo?+kza?KNUnL{(Qi5rGbMhFNzltVkw%~-?( zEj+_Ckqf3^-WlitB#f6lq{Bd2#GmaIB3WETP*6Vjfh5EOV|_*EEQ1)-Lu1TN$WcNG zA|FG<pgx>ILv>2{NM6W@L+XW(TdhGcbk{uW!WuMC*Kr2*;DI%q(i^74kl=yr;9^Bg z-$sn#M0A!qgoJIl63r;lG>FIC9ELu;Ow8C=^I_76%@!8jmfz@xKmg+Tp<gt$16qW` z)6`Q?JXKV6)c^YcU^pm4JJ5+48PL5HO5Bl@2_D{V0aE-xlRIdFZtYXRIF&xINj}KM z2M!`M$pbsc0+2x<dq@RhEx|d!13iqx5^RGC%GDr-;Kb;|6o_6ZT^Y*|Og%t?AHc&w zsF^(o7Gc@L_52$>Py-rZ(&#DRLP(sRk&Z?A8FPqE1C<ULRY*9>!#9vnH%8nER^bP_ z#0#yBO-4^}zyc#AT`}<pWwBJ1ZAm`3(52NHJf4hj@Y2i;A43?JY#raP+0=_*L$z#0 zj&VggxK`5%B4?1}jzO6w$OsWygv5}AzvPKZh@C8G11B=fH<(K*z=J8i;!VUPD3;aN zG+TZoUjGr{Md$d-G!+^}1jaMq4_oBKiWm+j`2i#(nK#gbnXv{!+yss6)e*>7Qr;Hh z<ij$ErR6!6aOp!AP(#FtP&x?K6j*~ia9-``!!mq<n<xcdd09S0N=1O2KA=HEp#ud~ zl3kI*>~PDl6yI`S)>PQiV1`eEy-4Y$;Z{Tiq;bRXIc9gjf*fiEt(4(Wa07{5W|bsK zg{7nPafSBi3{A|ZMW`mXkO^Pp14?G)u$+s?4CF)LMU<?VUNDE<bX8p7&^`&yI}F3t zoYU8&A1(A9Sbfdy<ins?;7#mHS+oO9DxNvKooH}RheS-qNY+gdXfe>i;(#Yae8ygd z9{)XXj7lU*RVEq7FpfT00v!ZYnoflFkmo^ZS;t5xB%q$2Iz%Jw0$h1aG6Lu_ltYEM zSRf{ZUSMHuBqt1xL@()>h{Y6yHeV14o%OL$XaxeN22~I-0xX1Ih@}KT;=wma*dU^W z&1s)5eS;h=X~`HKo7BU&DA47E1K=DGvi&Lw5@I;$#n|xQ-drhu^vU-qYd08TJe3>Y zJX@d)N|0R(G{qP#oI{oR*1qHeek7}3vIq0{4I&{7I+#P|Aj1^s3c21E2~E`F5E`{= z9EmJJHn?e}CX~hG0}wt=pG^=woI^brrKK>(9(CnH?E-H(YvfhPbmr;h)Dgty!~dqt z+1nY?E}((P{OXRX2&HY*m@3SG&4y59>N@JfBSb=~_S#>9gJ_XzsE#P~bY`q=p)UXe zJ;;dpS*RAp3aDNm^|{HB>7|YwSoEogSRH4bJ!<F8SU&6>O%4!~`pw=A$ZpOkG|U+9 z`OiB*Lo5D-;M~@gb``7r-6y^RJmB4nx!Zn}iT1sqV$hYBGK@leN_?#=US>*#m=L{I z&VQ1ief;Tdbq+Gv)ySyjQihx*#KSneDEjyfLm?*_4QyRe(BdZ4z=fVV%mYeEo}djV zp>7DJ=>r~c6g~!3f}Ji$RVc{PP&CYJ^km?52rWd+&>LifK)`GF1<|X>!~cgW&Gc1~ zh7x2Jal#yMPs+ALvGfp4J>!NvA_I~`BW5DB!V_}!AK7&SHl4|J0aiGiLo+yoILHwy z4q^dm0^;o^*_BD2s4MrrgEBlr-?eWpKHFQc*l_YkqD-d_nq_6kX*FibJcxr3BqIei zl@R7b<mlDtDMe+lfhEKX$i}7SC7eoB2IW4KZ`Ic~9KkS>E<;FMIO@lf(8I;7fht7Y z2$!xk@RFWvnLOOc$-eGG0OT7GEFBppZ^YfO1mvr#Xo8K{G)Ty0DN7`fEIc|7IvNp6 z$io~&!W_WJ^#}|f$-{d*VArh$pm-BKG-7?^gTIsmuO{rXjf0>(VE^PojZDs_8M_mp zXo5*JqzI`m;#F-Xeggot18?=DYy4Yf2*EfEXqcIU$H)W7beuKLLpcb+IgHGkevMfg zuv5115>CuHe8GBpjhn{96l8<vAgDyt*D;`hJ+Sdza4DdD5HU_fg&-2da9*A6!WkIE zD6dF)_`)6JRE0`~_LR~RtEjuUP;ICLIA}y9Kt%-YsX7=EBjif>`PSOJ0d1(`LSTbB zT!%s=t%~M^I^2OT2;Xf5FKV5K^Vsa%u7?EfT|Jo3Us2Z>OVvE72VSt)wHC_d$c^8S z6@WZlfrNv^gk3({YoB}rI*{)<$dPuC$$R7j9OJM5+($Izga6r-rb?8s9O%_seo8*j zLBrl+9X<qTkf7p5s5}siJ$NT7tEIvwik_u#YtV{YnNU3RXWx$Jo|Q(a?G1N2(!<Qd zM}Taa<%4(LSbc2+8Vnl0_8!fQL^_C65t&vF>%*^<8cM8<JgRO*Xpu0R+R$x}5K~09 z7=vgkOoFMyX5H)%$JRlLAE`muv4F#}=t%F5$<;{hzf3D#ti@QhNsB2AzQ_VQ(8GL? z3dG5n9Bp+(1jc(@4H%KdU_7aIfUCc-4?LsWkdEzWeuc?R!7{MMKnhl<m_r7Wax&(_ z!J!D`4O};(G(FUD$9Twg1uUtYhIgFuPFD;<ECYy0GXMJcv}y;nL^Kjw67Z)0=q}{L zZ!?IGs6)!kuJ6VJs*$1B2w5_Fb*cUcj9^1p*)tv(LvQHP_7H9p>EjY9EvTi8r)4X1 zXirbs12}Zfm-uk>`sCHHq;Bm`VnAGew@XUx^Ip)x{@!mx><cYKLp?-E_?VG0I78VK zIFkZOJZOS9u*E=f#{r&&g8bD_<U=&1f;&6eg49=77A!8yr#@^04wT^gNX#2K48nly zZT+GutihZrpvBY!5H2@!6DWD!6?1c$V12Zk3c07e9wG_hSu=!t>cgf4Y(p@i3D+xU z#Ax>gSUCh!bT0&r#DkKE+L7p(I`rW*{4l9CasM(|H_a@`G(<H#x`Z8M1!i^!F$4mp z784TbEPFFKH`qfp>&T5vs)12eAilUb(Za6kM`FwvJkW1F$dQ3#&Del1_ipPLF*$2? zF9PZj8JTUkFsM{y_@HPLU3hp%?sb1yjG}NCIiS><Nt_?t0y>Pt2qX0o2q8*gv;g~o zJm~fy?x3DE&}Z28h~z^TfOg}k@~Q)2IUwxA$_+Af>?xuz2|G%WyYke8u0hQg<n4{b zm;*Wl1zyCqc?WMj`~fHMIqq&@7mE4tW@hlb`PZoTB@EqF(+mt}v(idMmn5$<f==gj zC^$f`8dk;C%>%DNL`Vz=ZTXGPh&xmFNB;`?jWYc8l|vpIHG?|5^VP&yD)>bnOZYp$ z!&ODN2))sJ!~?I=jp0=yi(Q+?zk)W{uc-q{$xD^UuLlVM;a#Qas&9(LG54QM(-CB& z=K7*V1)6;InW5oMCEd6;aNnO9k|ms(SB@E5a?&(r$c*>vJcI)RFOIG|1U=NlHiU3r zUe2noFbcUatk&qed{)2!ain$kTXRQnoT|&NE)8E@9_G1C%{3=X9rj>YOI(6r&iidC zs3{%w#GJ&YE`FyT{2g%5HBZHNfW!3=%NrmaLe`Vj><vF_!$YTyeMexmdV?WUFO-JS zV2?wplQY|z17GCkaK+Ep`3sQop#SmMj<HfYzLZfn)Wf6ChdMvxJIHh8@&{g+J>qOM zY?~8T;1zjhC;E(DXyjn(87*=j0eKnnmUZP%yPH3<%skWs$EIb7HhDfEu3M_5(P|vX zz(2^IrC6GF3cA(*##OHZguQ(E?AeotPG7QD;0g{bSWsR>i4pVZ^JS;rxq%ZWZj@LK z+Z$}?;;B=|QQpRQ_Wp267cZX2i4O(li-;}R9dI)Za#X1gRv>UNWui<uFkifL`tJDJ zd9<K8bMoSugT)9OJg7ZUdc?*JPcoZD9magbiJMk?`li|8#*Ly)c@T}Fq+1uSM4I{P zL2IWE-rc-|3x*5#4jwIb`v1C345yDBEq(9Ig%eyioH=)?v`Xa}(XhRDsoWXX$Ca?X zaNYF1QpULPTzlQZxzkkcUANeSjnbsuF4g4FsCgHcSg)QqeS!q(BUhImJ#^xP&?7gm zZozrv^7(<3j~qSY5u=OChh~|+beHwoLoQF>6l(h9dG2km{2FTcqO*^PaF;do`6eH8 zXyQ#fa`cfym3YWWr!EEMuw=UTBpN6>eX=>iIqb%xYoK`aiDZrvU&^N(|Bgz@mpAko z=Rltb>Pa1IM2crc8I{uKEN+OBt1gG^DJP#drdi3pqCATSoIiX?D<&ZC3z5k?l7TD7 zjnD~+n{wjfZJ?#_@c*Tp6jAeNnm4-aiOE1<(Fez(j8k#W*$#WhkaTpT^FxE;VGX#+ z^r;M-cl1f6oz)`ZGa}veY37=7bi?eiK=&kWFvH++hZc7xl?OS)+Mz`>!xqI9K|2F| z$JFs$EvUTZC~;07DaoTpoO<Zk#X0u0^F|-<&I#{TdlU>%A92bNk0ZL~nJ1rJ&dA3b z5A#aLn|!_~MxW^NLTH&Ol2r>;ytd0n5JHT#_PBb+S<n)D%(GRV{-{AioM&C-h)G}m z;AWmkE=j7ssqlK2kx2AGM=D=Y0|y&Bj*PM^o7nne8f?DAi!N~T351h;(D6tx`_iN* z#qp>FCy-vS6#p{BEk*KjU-RrB^P!25Lx__=@_9-rmU|&s&V7wObv1piX{MY{kG?OQ zZ}d@yn0m^o>@jCvqm5CCXdA~JL+H7bC*8(T<{5nqGtgDT-mwQ!wF^6JYIfk+?P=K@ zrRAA=TFrYfdg?*wh;5J?G(vqS5yYH%?Xu@tbkLwio^+UXbsl{zkwYG3PrC2fd@P}( zp6l{TP@gq;vB&c4?0Hv^S;a9r!R{a_9YT(xi)R}lz?%ov^6Xi|5`BO#H%Oc8Ni&^# zxT#0tawtAHpPLDCl^c6NKB;JkEPA7!Z;-DG9DNuGWZ_d$S~4VWQZ|lCZv1^|dXwaV zhnqL7VgK7z<?!HyKI=1wh&X`<eSiZU5s8QV{-BN@0q$vq=|(<eagBVC4T5@EjXka* ziwn}G8*p=nR4h}RxxI}R?YN*|3i6v&n1fZ}C{_z0^O_i%DlzS-%#3={wVA+1AAHNl z-!j;qhrH_+en3Zf26Y+ysAC&Pum?Jj!=8E2BO5|UR))rhlFT7X9NucyL$*T?D^LS+ z?5ayW)S-`Jpury1%F9xwfDHN=Bu2d1j^YTh#N(anS@xiY7)tj?jvz-lexOk9)Hj$A zjffHI_y#vdggz0`Ya;I&(^F(a7xqvx5DJ^#XYyeT7m06QMDm3JbGDVZ#H43Gb5;C& zasLOR$>ou&JYbz9Vi7##14gZs3PM1(%SDyr8zMPJRSeWcM<NB9(Tt`9-;qK|g|H^l z)aEvkLd|?AV=>uaO*7abnld$nn?fQXWS|iac&KBVv(bk(v;o86q*IzLRL7{`K^enT zDi!wl1~$=&Pi?la8}DF;EEr>%Y#J1z1Ch$P(q#^BqyuK%#7{k<xG>~MbE3HNT^Q*> zkcgu03&+3@JqoJP(1`(!fqbZt3c^NxEaM9uk_t3wA~p1&BY{VW=s=Kjj&mG=r0AR| zIqX3PO5{VPAT`Gosj-A)S#GBgjYyY_R1XD4%o<PGW<<)N59`S$ogMoaC%DJWcmG8q zlFb}yQWhwZmvIvzj9|pi;xts4FpwVS5Gqnc6bbZ+b*O8(2r#9&ReczVD)y5HNJNsr zx#qK#bt;TLY-5gkAg+jI(?_86p$}OoqiNVImN~w04!-H*YL20sHC4MW3Ccqmw{Vv^ zbYl)>IHRFH%v3n?VVmGO^J$@@11{t-4@Me=9_d&RF{oG*lqkp&en^fOyN0^LQPHbL z83;l)7msfkr#$sQ1Fz;`pN{0ir^~R1RGR53<d{PrNEPEm=8-L@7Sdr<wJJ%C;~8{- zBN=wU29D%$4x!~kE0TTX0(}99p^OqQk2Ho(?)qL$0`PP2qboM<@Rg0dSN|h={aH|p z;}LF517im9$apJh%zfo!vEz6zRS+DAiFw3hV}euBLhHJMNR1t@fropG44O(A;u`<> z$2eGpw>l*aQrD!5X-1Ws+8Rw$o5{^;G@}XO$gqf-s%E0TTx9LER|v^z9bT-X4?+k6 zJS;s^KFl*A2Q6wwsY-`}1W^grU2cp3T7y8*i>uV}Djn)D7=OQb2Ir)sVaRP4ehar> ziA1LyW?07WTz4)8ISA3GGYAzgffXFpG{N8yELrF(KU+TVnJY<CIXcXdr4&;uDx)hn z7%{NE?pPjg5eZd@e4mKq>Smmbh*S#eGietX$98zpdtsuFSqNpBK>z+&B&OKxCf7x3 z;Izk*Cw=a@NX;GEh=$b|ax`j+`BDhY2jBdL=BK$WABf^@2$OtfO%K;lieb!L+#Qj5 z)MFQNkn?j<5?y=nLJsk`qF_vt$XPw-Xwl8b8{=q5o**Q4+cqKO>ah$oBx_k-th7EZ z%4FjpQdZ&sxz27n1$n7se5QuPrA2&@kYIym1p$XQ>|l%`ONo|$pa-t=5+ZwS7#zKJ zae{q>;i?ZCu5ilH#<&5FWqX}tJ<-S;d||6c7W3M<jz>A1)O8_syBC45yIjf_%BMFx z?MJQ~JlG9*iJYSz1NlaoGWZR1G(#JL8elwDvl(~vTex-k4gaa$@s5DILmnjzt=k~e z48~-BJUEY?&UurLbciD!LdciNLG{^fOkws<%g`+ZR4rfe*&aujPk4EA8fb+}AKS1v zNA|c2I#>tO^-X<pmeZV_A4eb55SKXkbU13{bmN*9(JFstA4>l3?-DUE-F-n0l9>BK zwQkwxW-ON%>*Uy}EQiF}y5oNRVZqRjH_9quLX0lTZrQA>#gYQ?oWvX6kFeqatWpM@ zL}VH`%<wWLq43Sh0B^o@?BFs*Gg5&ssO?YYNgHs3h-havx*;Bv;T0;vH7>}Znyeej z!MI|`-F7A)<X{(Ar}feSsD$7g(t-A>sG}Z4_oVAya{sS4;KLf$U>n>6bLe3k&|n+t zCDodXJI-L#p2g;hL-nkWCkRB5rlb23Z$peF`UbEZ%;S6x=-7NoAFu>OY~sMI<ax#} z!-maG#ExX_0VcqK6BuFdjD|=ciw{-89v&eQE)4!2hecc@R}>Hdr$G=SG5)B69-6{O zj>0p}AtbT^=;9AY(j@CnECapfFl=Kr+H4hzY&Ghkg5-fV1_B=9fiyxxHX=wh=%yKH zffh_JhEPw{T*%-;kT(t|ik4^#>jHKtK^$_0_~gMPl5Yx@h~maWaJa7vzOXL#h!W_4 zTAtBdykU4$p>noxkCuQMrmDT#tqQkc3Bmy#JpT<?*uWA*CJo~O9o7ID>LDJDgO~sa zu|#CU@&QY@EgtHjDVT~6lV=cHM(h|eADRLZF=;S}WK5=l)~LdKTulI-jUpB+9P;lH zGf^We1}5r(5zwNqJVPIh0T0qa+CoGgn5WlbQQs;EHjFVAQ^RfEK@+^JGFn3$?q-6N zaWM3O7=X(ITM)PUW;jCYSC->;!h=r=g3y|S8u^Pmyu(=ZtXPCc43L2y)JQf$#}eWo z9(+&J`YRt)XQg;TE|=g7qYw2a3R;BV8_>b^3c~fW?+hx3_D}-n{NUrl@Kg@a>@?<~ z{wge{E=vdo8!#pSH8Fl7p%M(nBTP^q{{O&bs4g`kLTU_4A2b5$l&38g5064Ht1iME z7^c4F?%NJ=0S7TBq$f%q2{nfTtq5k<c5)RZ$g~y%gMt!*1cN{d&dZ3h^M(T`$)X&V zA~ip9Ia|=ToI#*!u!w%89=xM;$TICpY8$>FfvTt{gw8qiOt^AJx;AHv$g_65(0C40 zM#uxBieU}FV?Aghjke(ovZ1-+F^}#eD&SEbgg_kt^FN;@`{L|D4s;@7WpSLtKG*}u zk^v7g6Dg>I8;b3g?m{05$Z8tNbv8mZ9#bo5N)Q()5RyS-T&XlCiw-eNMbiXDSP&x4 zfg79zu|V=FxWTdlP42iM!6*}&2>;01;zA|3p=G2eB3H3eXyI)bQ#sSD8|onyqM<<M zi5RQ$I}O69sMIn><s8H`wDyQWnrj=OLqUW<DlEj|vc)^v6L7w04Ymu>ekC7-U>h_} zE%PEnj-d<W;i67Xa|A>jN-=NFMJ%;4jr76!NUb<5r+4O4)j+b<GO}ZiF8|2Nmoh>V zyTTikDIzTbBY@LrHewv|=PU9LP2S*~jz%Te?+{}mC^E9>k}W5c)c*F*7wDt@22n&q zwK(T%w9G7+vh>`jshX~#7XU#UV(2u0(pewJG`v9*;NcsHizy!`q<TkQJgqLIV$f12 z8uURO>cLs8unWZD9?6rJn*WPZ`!iR_lg1*>9|fYjRw^H^Q27Q@HWZEKP;_6;g%b1t z)#|h!&R`dQr)#b#Q^V*@H&IuG;zwr8Mm|wUBtjh)OEr779KfOJh?R$AtVL9=RY$DE zvZpc&Yp=?I#b(JSs>CT^!hS@g5+VUN!9*^w;R4~JBt8cLvB80gl}TO_CZ;q4--Vt~ zHd~){NG9X7ENH%@Z)!7$^uS4N5EgL4!{zv_Kb)z~AVIsX<6WsiiwNv!_);Dwhd&Sv z=gLb#LJ*PUVM2hgJrLqTo7LVRhaBo5UF1Oto68&OArAJ@bc%yb8-!T;Fe2K*8Yu8# z^r4udgf7M*AJA`PR{s(&`i|T*SM5sFXK1En|LP^jp-4~VT|#L{o@Qkj0T#MWvO)qJ z>J2CjrI^m)0E=WAl0s>@fivp?Su^m+@&Otaqwu!YD%V0eN~@uqx5>Je9c&R>??XA{ zU{;6(bSqRr?yMf<NFuJt<uvtCfdvhUp)UK@9##)<8;$$cfLE@sAe2Ks)*^#GDjUAQ zZ9nT?bT-5WLoU6eVbgAM!RLKAB74ve!``Lo!Zjj97fu92Ic^4?WcOwX@ec^*4n+iH zcGOnwFTr?oR>1*vk0vnC4|V4*?>rPGa(CIBw&4up95|&kz?FK7$Ud-!KooF?eQ~o! z<;*guAUbYAcK>0Cx<)E8gc{CZ_U4rOCIq%9bmayuAEsbkqr)S1CcmiRa5RlB$|~YI zr)&!XA?oN_nbMQ^?2GGx9<H_LUgTdDwvQxLB4^SL^1)Gq6Fz()5ai)0=t64Fs#J3X zltjrzIT!r~xK5&uSxn+n)np|O8QJ8=!XoS>B=8M#R~3z{Cp3vn%tS~7!GWe{#*%3o zKDkDVg*M=!9Sq?oB{+!3sFvNWg=#|+?8!S@wx(?F2%Hhw9w$}+H7%PMSL|Uz4A+WN zCA#zhZQC=e@Jnihk1tS9JLrKLj(}{*lR%~*Ju=I-++%R^OB^icG};J^2m(t_MR3re zck*G*1pfn?evRDX?vc_&9qwu)%*q(NWGj0@ivQSv5UU_WWK1l%7juL=jASf6G}%CP zB){&jYKdSN@9OLT99W8mlZR&lp-faFA1=XXVS@2;q+}IQp@9;i9_1QdF?(-WrVS6F z-T`ewFC6-~PiW$BqG1iRG1F88R-{88U@9#m0_W(rSJ?O=GUSa6*FaeZqbk*Mu$kqM zp$obhR-|ie%hnfFZ&rj*9^OT%(V>|ax{BiA3zUypSg0mMM6c>$kRK`~+Ttz9%1c~W zD8^x;<L{TLf=jT3@t7pmX6<{$OD^C+9}>D?ZgogWQ^fwt7ytoE$^@?W3OLWYV&KD+ zQ2#_FxTN0dkE|Zku#1HS_vRVSAvtH7wRaeywo|oxIdAIhzrdjl$3r<N!4Dd2sIzYh zEERAvgcsn*8_07z>S1BgAyJPeFxOxi>Y=IyS9G3lxdG>XHHQs=DI$P{en~>O#!x+K zb`z5g9Pq#xDtR?|ED&a)BB^45IH7|fJMBz`E#5#Of25*st*_73V9KgzsuP_+(h+&} z#^mA~>S0Wb>XGzH9pa9cR24-sn3L~zN<Aio_xqU)sxUO8Q*gSaE(^p%T*OD5#7lge z=0+c$K^eyE!!HYU7zA?uGom6wK^A8kk%Nn=p$j_XG(>!;<3SuICoO5>T+r4(TmL+* zAjiLkF1pX9Egd8tNqlGQVR4qI9NOqS+1g3D>6euwcFchsvZ}Ennv#1nnkKRr0P$uS zC>;!Yt{O%H1A!Q5ChCBb#6{Jxs&h$8qDMB?#RVcG78`)PSFuqOl|bBkOle_GIJBe5 zH1k2P$^jmHT%36Wzu2Lj&a1UIU8X$)I=P0HC8Bu-$&B0DnI<Y9kYNqv6*=HoAEM#q z)Hc+GXT6NaS>^#909C445K@_3&lHvpIwYn)%^qBCib7`@mSB7b)s|%=@sI_)Br&2( zEG|BH?ubF}aKy5gmJ{s!u$7kBjBQ0I4@i%9<rGMd%kGty#}3kgIO`RHo&Q2LV?xDP zwZQM^!Ej{Ke>49G8PX#O!$a#`6wY@mozoAVC$ly%yjHet*5T%18N}eK{*#sCqKOsc z2(p2kX?qup@IP64rIdqy1+qXAq#giOQ1{Xt?Bxu`vv%AOstA?^9gaJMfI!JXY^SAh z`NShaC(iDX_O!%&BH<g5RYiZsNVJ_d!Ql?3!DB)94&!Ha`)UyNu;NKFz~`>%pS~b= zO|UvT@C>5HXhw!HalDI8L|P&%8Y~|SUB+<9!2dmI5BoEATAus@9_pc;5uWeeO`>2Z zA0Y4aLcJi~Wtpi_xX@KW<U=mxat%}gy4{nh(fFp|=qu|bAC_THJ^#yHneuR~VG0a4 zcg|%AvLPPMIMk0D=E<SBAvWg!)!}eu36^Qd_e{WH5=Z5N*D7n=nf^-5ouU`$SdYS_ z>rTGWK15-`+hOT+t=qb0(nV-S*&y>{g{{Ft(-*t}-5EScbA&)5J>VgT%V=R7zP0bq zKU*iA9h%{OVr#Y?jf%NLjI*}R7S_C?LqX`ELCp10=>Z^?P0=Tg9=&||#OV_xNS`-( z5F<*QI1ypJditnM$w!W!Idk*8)w4n^-n@DC>``3FGU7aP`6%g$=gr%^Gs`&6YuWN; zK0$=^b)<+;UOat_7=c44ujtBe`2t1K7Y|{)c;N0#!*<mvPydNdxnZ-zwP`+i`h3~Z z#|@&_uSD}*<;Llc+^YG`MV(p>u3vff(%Q-QO(i#QZ>G6D`!}N1cyt+Yy9%zH9b+m} zw#+x}O*wFlLr+ZEt=qYFv`Tl=EV{Mp*RW&DZcMt{J5Ax<g$u{J^~H=`gr@85_ai-W z`XI@1m@ZvCWMAYJq&FMlynM^P5Hy%lAtg8Y(lLE~QK1}5LO-g@h(;Vb?kZ*bq(q0F z&1Gk{Q>Se&WIaDY4HZ#JMM3t5FXEXc5o_S=MU^`09K}f>@Nff<g04ZB7(^G9BbYvV zG4|SHbOmD1RppdZl~nqGCR<U0m2-|f=z!zPA6(h<*8g8&O>+k~=Rn3yV(~Op4{?uS z^9DC<VOZU0_LOE1Ezi6oWqeO&spXbj{zY1Dw6qh?Zp4LF4?X%=GY~l_VOg9x^rVB` z8fVfo4?WZ@K~OsT%@&eAXcVIld<yx2UV^VdxQ#yN*+ULQ-nn7VLx8#YTAbL?G0t@Y zIRsIeUmd5<E_CQ~Cq*BjWy~A(jPt3b5qUVFK7Gj}>l`3f3hQ5=5vgE4oZxy6sG)_W zj#lbKq>eXsOmpFEVc|gxRq@!9RD@187FIHMkb_P<*bJ#yJSoO?m6A*@)@7x;xkHOP zWAe7^y7bm-FMm=t(@Z$s$a^U{_RwL8ox{z$VE=r^(IZYiOHgAcI{H}Rhji*3X>eoq z<+BDa^1uhN5FPjF+DG0Al2CaO%Ms5v7N>OaU*On-!#06YvPV5LR_Y~z<>Z6Id-NcA zmOY)NsM3yRox5a{J#&JGKCWg9ms36C;R{s=jiZm%;ppS?%U`8*jy`V~qfUI>bmlEy zu_0v7*ne=6&Q<nY5(zk6iKy*eY5#Z?J)B6Ex6n$bD|MD1VZ;tC_IzW`y^u#Pc}pqr ztB*6X#7k`0{duGDErW{uSHcPjvCT=}0J;lDVEdJlPaD^n62wz%W00ToY$F6gCn+Qd zCHADF<wX$7u?t#LETfOkq7kpp8p;RlrvFuGJzXnHDOTGVTM&83NF?>Zqt4^7frAty z<-n7*K6YG9{*$r>l8>uc^%4l)Y{TZZUI$J#_9aT05z?l{7;exb5S+*r0P%;kBrQ!{ zUHZsT*s+dqj3YCxo16wW_?ncMV|n_}ggeNT!Gq1C9@NmzbjVW=^Xvj73R%N0O!bk? z?JOPF*+m@U(UDf=0}_7F2cK-nxjW@4A#qa35ol(y*?dhQmQYzZ&_E3x5s@V*`wmCU zl@B~{A|Ka-Que@w2Wz+}b!GF~t6pP1smNu0?JI|l^wt`ur~_EIx**&*!9Y5Sra<8M z-ekbltR{KzecFnUJy<l3e8A#<dH*vPWC8(;r5w(Q@ezkThS83*<)efg45cXjvYU74 zLmS%A2UI{QkvlCzPvYQHY+z!EH4wxe)<A<i*fczhL}N`jgb7eMQm_v8XCC7C!ZzeF z5Ao<@3e?Dl=w!nhaV#Mwez4C@T!S)(2!%K)If@&@D9Lg#0v0N=RX#3rG(UzWezbxJ zIKXk4<z3NrM;nVZ_!bCXe4|JM+#5vF_J(iFs55tbl3u(>6>QuA8`yv#Sk6+v1deA* ztl3SPQt=LPgkz1P45>(W_K|nw1C{yc24G&(NJH5JXdvYYandm=l|k&64rvo6&!mrK z1jie3LXICGAr$Gg=4*c%D*rq>k~(PWqlqtK%u51h2{uIYOc>mm2lcTH?Rd>)67diM z<2j(O&5<&c%m+N|(a5r?L>~xo=VszMmp6oKE_KOE{)}mra~vxfT+zp><e@dNx+bol zlm|DGVTYx}qiAw0YiI~`mbA>l9_mn1Imp*Q#OgyI5HrWu;BwDbl_nn7*jH&r%G%b- z)E=qQM>|sS)Ku}uAPPal4Ci6n*Q5hEN3h0cRUrpQ2`@{ytq1hrgxlQ}<hZd3Nj~I2 zR5s~@xbcwXmT;R7AnXAio)ax7S>qESd;=XPfgnNq$P%YuBN;fliaw%&hsiLnj(0)V zAi3cSK+uCJ0WB6qBmbk0vH9X@tArL~-rLx#bfz+;ooiE81y^GXhMX+XONu^%$R}B( z9;L~LA>3glmEPC2C}wSKrqm92Tq!hhVvjgZGFs83<hRe`MLqyk40yojNhp({IdC`+ zeF#AuAlardUy__4lA|Lsp@~kn8@~UV^{D+JM?KC^#b#1=pbq8AUMs?wa?pcFkm1B5 z(iz~dI1n8B4IG>0x-$|n7D!$E;%3F$wgrQupGS#AAX=ngRlVV}EGi6tA{<jv+U8xl zS&d;+OzDu;CLh<3g+BVl=#b5KAU5eOe~d#@RnP$)=)j5WSh*6?sZNONp@tarBkIZ8 zgLvXNf}@~JhyQ$dBOSHQl6wx;nvXC!%D?_dSkMKJF;BF6h?xdu@+v?&yP0q2R1sG0 zkc=j^xiuzjUp}&d2V;P-(fEbPH{{_(u}%eVQH2OL0x_+m5C&{Hdrhzp#$l@HgB{Qa zM`2i9>4JBuHuA{yrv1e^QtLwxlrYtlFGbU0<YyUTK;krG<Gd&e(RY*($D>Z{8;oq@ z2oC889ah&&gTLxHF_{TDj$0sg1a6SumPdmSC>L%-f)OXWq+cEbjz~O$T3P9~M5!4( zeIO7V+)77~_HAR$q|S>wP6}E3ERV50f{&N6l}IW35f3SY9U$to%h$do7>SUCq=hX= zJoklS1pja2&1<1N(69_rp<{)JOLCqF;=6{BqlN^J$VKcSj@mt$9_B?ybJnhzb6g0T z(p=0{<PkS;G&|=FN=iA<!40i=+uA%Ky4K_2*E<-)8+1!N_UxgSdN6_$_NDsH7Lz&_ znWNldk9Ym%;G?zWJaUN(p*!-yaJD-ia)&hK*+G1fxLXH>?Fkts*|ZEC2;y|}7@wA2 zR}Y`&gJ#cD9&}{`A&`#)sHT(r`YY`=#@l0w)mKne9ubMTIU7oC6bU_NdH{ub5{4Cl za}L9DBZi|TB*F<qFb8;(P}SiwAhasrfG&}wKSRR}QSk<Mvw@-XHKkDx3dd=(_k1cC zcmIc^KJ1_jgppW>V^;lv9Ro2PHHKv;5i!d|4^Z_auQLzmfCk9$N$79{Fa;Z|(SG{i z2ZeAB<S-6P;2x9ba`opsmLPe60Z4%`3pgiNtkE+E)=&?1dd8Fzm5~@2;WPwc4&h*1 zYDZ=R#SL>{HbQ4>1oBp^QV&WZX2-V@Uz0sf7Xn+cbQ?s1-JlPtKw>Dkf{u7_E>jw} z@eaBnFGy2k$niV+fo^}44;XPvbEGB4<~ek53lNhHQvftHXloF`gx(Yrf`ASHlY)_R zh5GOv@<1stLSYzoFo#q)<uEHDG9sT8ALg?m`JfgAL2T85ScnCL@qrNV01w!J2mjMx zKVNu;w{|4@Fb$lb4lYuEqeL3!fEtw8h>w_#&<GLyk`J=r3{mn?et}!hgbejCaZwd? zl9eT|;|+{*3xxs+%%o%_*BHi@J4=8Tl&~C8vvy7aG0U(9o(K`KMPZ6YMDF!a<sfKj zH)#ST4;PV!(zZxbQ6$V0hb*BPDEV3t!g~6^f42v3f0&Zn_(|pfM#cDLAq5Yoqz&q@ zZt576;}<2ifg0bi8=Ds@Xi^MlkW=aS8-v$`kg!yE_ZoMiI~ZX+LUd8iS6<t24t5d| zf^}%UxDq6ybsRY?v=|X>ltB5AMnYL2`S1w7@N;ukf$=dcDE1LNnF{To5C427l!7@M zAEX<8$$Wod5c<Fi5@{1pi4l2H5BV@u^&lWmauWHlaz<7V_27s;;RmW9i@aqH5+Xlk zDM^9E2xK!2r^!b4z>(~8HE~%$*gyhv;0yLOlVQV&qEs9IrfKLnn8G<S=Ab^PR1ZK2 z7a?H}fpT|``8HH!4?^$`NqCw52o%yuGgVn|^HCo*(H(iVb=PJT{ACx3u{^rT6Xuf? zH(5`2XoUsD4UAw6MxjRhI3TT68{@Eu<A8!IIh^Xq8az2$o3>J4!6(~*28(h#k60d= zX$i~FYk-GIp9u-uum(P6RL{p`__1mb!y>Io5jt{=N-_<Plb$WnApaa`Kjr{n2Do-9 zvSVBLqO^gZti_lArVOfNp8(pU{9!q?;0z0=oDpM7;&3L9=^d2tJM+UOAE6J~zy@tV z2vq5alDRMqV-M2PNFdr8RWS!SKn#|IqH$pq4mAx%mlyA;g08ZbfM}y5#h3P=34bY% zK6<D4B#EfOFX14A2Sbm`RZNfgI`nW3YrqD(U?=|xB@por^3Ve%@Iq|jr))Pn5hDoV z@D1YEMZSQTq9KNZrj{NyU|L~xcZsK{dPr#k4c>5+i;Al1m?H0B4rixIppp_X#+12O zWF7W={is|CunjhGB+&SzI~Ew#`FseWNmX?m1I1Y25G1-8ga5R$V>C)Y<e3<Fpmb{r zt1h=WzByu%_Nw0Mh!#ko%~w`&Vh@C1cxckADyW#qPz-1CgU!eoPnHgMbgd|M66bIR z*$^^)!(O66H*H5z<`fCmD3knJt_Jrt2w_Sn<srrRSu}XD7@M&gyRjVGu^#)eARDqG z%dwyJS(c*=LfS7DYgRC~1lh2SE4#8IJF_&K5-Tg2;Zd_RD6@e9SI643C9AVS`>~(p z6F^j%^8gO^6Rl>!vpf4$HVd^tE43nPu~>0ncA#`~G_+jXwO;$RA<MIiF+XWC4CSyJ zHVLl|3#%V7HX>9HE<zDn7Ll7cm~W$(Ybzfx(V<LsAphP_ZFuOWj4BVQ!;#67w*X2S z_TVlgwi~>OxTxwOFBp6hfm`O#1v9jrkh{4c*+LA13?PyZaWfgAm}2N~teh*DDH1;U zU=8n54{~&6se7ki(~j&Q3vc*QYMBoHs0tIqCOJ5$@lj*s3QmF>N=`90ODcI5HcvCk zBaBgFWLj3NAwec-h_jnw#PM0Bu{ew<Y2=!{m6lPtVGb{-vL*Xj;xL`t2qEIDgrAa* z#?eB7A`g3bLC1?x`TM>b1PhX&4bbo|DU}c8vx@vHoK6v9>@W=4a0{^D4b}h&w*Wm` zG`I)6wu-q8ys!-*m=3Y4jjR!eA-uJ7<P_6;!T<L1HGuF3%J7%*cuzGn4)9P9qBg=d z+@{7$yz_Fa9?61h1uF(j5#i%}DbX_+;SS9J2!P-X(U1pfunhH}UCj6@#+!O)Ar6|P zu~ZB;SB4HfY{B^m#9uQbUuAu|!W3>2zJn`E#DF7|I#E4S#VcVn86-3`*<LYv$D5JI z-HO6IQL^2DWS+<xCLCAF7A4%9wh&9e;&sT0s1JRrBNZcea42__C5~o692~}B&uA9) z_eos?m~K-KceKf`vdM7uS!mJ8m+XwL{K~K#%d$*0<p3eO@yK5DSqM=uu#B-Fg~?ZT z9j1~Ji<hww<XJR=FoUvVZ6eF9?8=ly$p3K#QW(2<rc$(DrGO=zlNWms%N$qFJj>z? z&9)+$mGa6U<Tc7xjAL7|9+Jz849zan$?_b{(O6mN8CP*^R`qvCXn~#xBVOS=&IDc1 z27S;7ebC?V4Gnn_5K_n#(GBG|4A)R%#7x8Fa}oL1FYnL{?XVjf1<Cmr#ARh$5TYIx z163D&(XZkm?a&O<$c`pE(igiP>~IbC<dJGjm^UdR<FL?Rw9xrxyog8BI$3|4e3fh9 z2Qx;H6Q#*L-90-dJv@aBOdXa5nSWT+nPyQgj={)J?It*Mi`7LB>oF+&7MMP`4Sqlk z8qFbGZ7=80ki>=+$-oHMfF-6}DgUv>2?->-sKQ|qL3MUqBfWro&tkDi-N=HiSe!r% z<WtEz4Y^M7HLXIdex(xAIE^6I4egK!sNfFWAPs6oiDyI1lo-?fg2e4`4pQ<A6}@;v ztl27kYxM9AGyD$p@GO+5+h9eB<A5gR(A)G-Bwf=E%7ELYbPeqw4)1^w7a}(1EDxsi z57iJ3=g=yYIN4m%&!vmWZbKvI;2zaC4p@9gmGcc)j1VM)#pb{!+t2|CKn*W}CV%HD z7jX`#Hf$g9cUY{L%V44L05sU)2jDk5SnS0wm8qKQPX6stSPT&l9>>yw#U4d?2`&%K zQ4f?*T`+MB78)cf;VL8(5&v374GIvNGk4x!ypD548Oaa`(iRWqz~HIkDnBhFWRn9} zfyRba#Ak~R3+)!4VNlAF<2{oi3!PAq(F=G@8S<$Z82t?%A{`v&U_=lI+BW3!u+Dz$ z8X0A>p{!As!!M?x4X99JlBrRWmWUeV#q!V%7Ev1JKnti)8l)}eCVNPg1DKYxY0W0l z1-hf90m)rc<|@%|2vHjDfC#S;=Y?+QdM?rb01WnEC6Fv>Q|zn58#**36oXP^9x-DG z!CTd;m?xoSmY@JosAbHACZqXOMK&lebwZ&I6O@nul?lAIE<Ja2Cp7dP`GA>0!#oFJ z5W|kv%oOVOc@V!5-2a{qY#@OVc7p2((CWf$)}OT>Pv#8@unS15n9fn#Lz%;1b*$Bw zz7UbVP@@iSkOM6uwx7c8K0CDv&h8MCzVYzTGHMi1M*^K{4=JL`J)1rGfDJ?-8Dmqj z<nqB^?i!Bk49{@s&JYbL@eKd)56%z|qYV$rfC}3%+77V}|IiGg-3>_m59?qJjdM!C z@X;c#48PzHnvhD-a1B~>^YB1IrPK`2unz5@4K2(s+VBr&XE_*e^k`=dDh~~*#2fE0 z4A9_-jNS<R;17oImlCfJ@38fkQw{$x^C^YgD*uKjJW?0UReR6|azNi&1_^D@27=NN zyTAr)FfcGt4F7Qt2{Q&|tX|*Zu=Z`=6soWcRW<kYP*rzd-;{6wC2$1bK@Z!|1$5BV z`k)SL?+3_mCsiz+cQ{*b*vAivBvulmc8MLcsJ$9HX3bKiwxVdP)@&0&V#ijrwMS8- zsz!$`=m^!KI&7iZ+Es0TUhjLo|DFHNxz2Un&-2{(^ZkB5XMX98l<S(Xhx9@6@od#6 z?9ofmkXGn9OTM@TNZ3jHy>q|1v4~zgD7VkZwU&j^meCLpp7*TS#jx|pat8xoJsgma zx{Lb?c}8(BVNK<!=OIwU-}S*Fl%NAn@aGGxHW6x@K&=@AD>Jw0i^6|<{4fG=X6C`a z)2L-a;lBt9+xxtK@sZpwwjmY_%Mc6*Fz|(I;97H6|BP&uKgZk%=ko+V5^B?m&?KZw zU-WqqFQ9iD%x}Mf&6TviZ+utfG{p3CPo|NC<;mCH;^W!C-E{<CZ|KynjM0IOtH!N{ z<AcV-meLnd@3U%y*2B*}zOI)bJ3n)=xHEnR+3hgHHmOszx!D~#6X5YCNbC9V^^)_h z-KGEjO71%U6nI?qpYQ5pvzD*tZYk8%tj=6?=#8xpxEta8_|Z#`fBPnlA3k_I#wj}8 zhMd**)r&fAf08;`Md}St_RdEWeE55=w8rJ*^KZ=M&Z{535_f)^n|N!5T2ob}ZCV;| zXd%><>2nHQf8_MCz35^tFdMS=dj5j}gIf6P+Hb<Wk0mcSKUoURIo&uN5%+yFSb8L& zE*d$3&!-czZVXI<IuFqm>sqr5pf|aotkzM%8z*ZONxiEpm!$~q`*V^EK`S!b>I{xr zBu=5wQtzU8s+YMc@2Xd7RrLOjB$zXUU;4flnMz2xP`j8yMh29NLcOQM(DyHs$zY*K z&0OjG;knAFB%#=9QDksNe-&1zHV4Wh7N~@x#0yvUTiA?OOafxHsnWu@riNXM&@NHY z-0-F`2NC5|c?S`jFR0y2?EV;5813QPVP_`to-A23GU?BEb9Qd5><;Je^#>k*C)Z^i zU*wny+!P2S-FNt`RmTzHpD6Wk5IHGTX1`Y<iB1?$9+kVb5(qhS%T0E@DfFX3(!Guj z(Yl=L`wi0$eglNsl2e1~sH?}`B!naUB*nGheudaFOIhfPuwW@i-?qAsxRJ5WnTsbJ zkoWfiqN)e&l~+Wm`Ye4B@4m2cs<m6;7~+f@DmD~~M2i|f(Bq_6WUlZ3Hq~T$vEyHI zixXXuiRTEuIGl9A0nbziyHpCtpzIdPVs|T~&&H(8kK7BSPPUeXaJMGihacjlA5<)h zl3v6-8#6;Pt;`uQB%sYPB0=<4O@hyx$!(z^?&3#8^{q*>;MixPP_oSaM)5%LnfKTD znF{UdjDohz@ww42;Mysmj{(a!qMrrYdF0dc>V$$dnfv(?-tg~QK*X4*fN{_U)0js5 z7=c4`nPC4$AR)Cn%p-JVEl2KTk4*&`njxB)6MhqHCPLc!4JpNt`_{^$uOj++LwCE+ zCt;`iQ@|drqK1|}?H$+PAXya@G$9T0N_g<;`c;p(SIp975hENaU+(z-M>=;q>GG&# z7+&mP*7W1pHK%ap4`w1A$nM(v_6H1UIw_o4A*m+l&-J9Xse!DUU9u`gyCkKf{tW-= zLHFNyh|<bpV=OsYNb&Of%l=X96<8zTZ?Pnu50cq;$}5GB>o2t&O(AZhiSnP(ZoeX7 zRedxf2EvJ#{35CzO(tp|V?gj()5r0)OF*k~sfOwyJUH5l;fG8=Y3NdRSgWzfvo7nn zEI`}>jS*TodZW9qEOc_iapx=xK1rWaQ4zmT&d$&OQR_=Z$3mZ#x3Zj%?ngZFPy*oJ zp$h8NSBOT>atMRx2X&qqWXqI$355*a4Wkp-T2}`{$;LD>1-tA+%p~WwXU^eG7-wOA zmH5l$p-d%z0ECo*j(7@-w-Vq9^~+YG_4oDNv>rPrE=P`#hcfxDWqi&V117`=M7oqS z*EW32)&Mj37a%Kw{=+(K$y6nyDEsT{!RUoz)BAk}NoK*R_vV^bDQkFimV8jbuc39U zOJdip$cF+g<7S-$71=kps|DBbB3-sl7aSF~<y*)sb^&K(1L@+<+>$6U*srv<Xj9=o z4uzmRC-%$JCq&_T+Z27*`s|ww;=(UJE;#ocq~FN!ar;{pp!LBi8^>qJzltl;RjDs( znI067VDo_Q1$O-mHZuBp^f7Wvv&v$7K-fbwQEOj0{nOSWu&z0(g5t=InXbxkEIW<L zS<}JVf`lg)D-&MeiMPr?>}E7G{lCSgu`52BMIDv0ON-O)<v!^<njeL~GYG}y?_}?k z8$(q(*rI*O0%QpeFOCU_F}ro{zU>vgkC#Sb^REd<xS8r#E{Y~doZ>QR6x~;sD%rbL z;w%eD+S448p}0iY3ni#V#w}?V7h;TS+B>a%f|S5Mqg|R<9X-@h+h>}}C)$Ojh)rhB z_KO#ttm0s19jP2Qyg_AEa<A_lJHn-siTC<5@9Ey0W)D3Y;9Z_o2tDZ4t4T4oHx2}= zE{JA^2UH2rj-W~(Chz{rta1Dfj9fsvvB!Eg3VaKwXrdNmUvU?g>A;!leay*^f>l+0 zMvt1Uj`o>0i7U*wm?dev&tNo*KKrshMgI}uVHnv2{~6|W@tIxo9if4<KLbqd)oU_h z0|rMP$c~bA)Yx1<wZ8n5z+qX!0#*mCJbz+dzr=YmCt$p_>Ip+yHwhs1BrW0PZMiV* zL%8CJ9ApCND!8!2zM#7E3Tj)apVlU%3aji0dz12p+Lm(uYqzks4zz#2tmD{fD)2Y? z<fFPu2vL0$#V|n|<xK&)Kw$PMa>$^TR4NEn_F8ws<qiLcMW*Q;fm94iE%C4~Q2kUd zhn>HXL5<1!GHx%dRZkUEzxC<M^O$a}Z7FGL!#tYbA*M#$eR~bRC1eE`x)TjL;PdJg zdPTQ5q_6$Z*O2yI7DX;#M?2TIArnzPx0c{$65w|6^TR}a`EHd$rvK_sdW`tDG)b0U zDl)4A1_krH&CZ9Cvu++$iL@EAs%}kX3HDU+3;i_Jq<-K&j9L@m{6r%5dhsO7Rh|7o zF6h^~-(00zC5&BzUf9mfzJ?w=dqDrqKIb)<bPFW>ZwsoVDV%j@rCQ`o@tE34R`?=A z+n~(J_J~gI_#i<eO?bbx<hF$;dvq{JPm<41o7P5}*{Tr!x_}G@w`JbSkKzwU!?oyb zne#)QM%!2y-8cQ5k;MmUlI6yM8*S+`9R%SO8v7TujTX*NTH?&0>kAtde$=lCnc?Ko z&qg;uvw)Z2AvJ{zZcV=h{!fV6$d60LOGq`me&@^~BDl6Sv)`3X{q<Z5%CkyC6%t=y zJN{MqnlGE-WFPP6K8Uzyf9A@jIA;bXOk#g1D&|z}OsM}Ml+phx5I0shLczlEfm%4X z2i7xYjyIxGv!W@P5hjLaS{YuXJt9abf{)9C3JE5I#hAfLgh!7YPWnuD#0teqpN*3U zDx^>#qXw56Plv=5_x(MMTRRf|$E+ok2IUs#!6}hoO(evMD9iK%%~X=vW}(+cU%Y1n zjzW6V)eqld<76YnZ)3g_NVS6Ke`8thqNSp*gb|U<u~f{zxqkNzOwkcU=(v9SGRrYl z1Pbm_SQ${<A2<gdRN@{~%qOvwl6o9Y7j)<*mBi~hs9pvw#6o`;lOj;0<8O__4_kSU zv*OW>VR&flwq(09G%^|*eFV>Iheo31Hfi@?Op#({jjB@zV{A#91X6hU%hz$3!f?q1 z7(Aia$nMiK{W9n=7b)WCu7gTeY_vhFC)e}5?7KN9P}AzH_FPg7Mj#wB6x(X_@lTI^ z8T5igsj}*b54h`Z4m6=J#SE+NQ$PF$AQ9S0{1tUDA;Y+OsPis)ph3EM3RY+#bW+tB zkE;nRCzvfj45wxDH(-AIHSzWL<k>`mmmu@)r;&gCAIG54won|JJqC-)qKf#cQi;aY zBuA?6w4u{6EUUcJtew;xClQU~C;aUJTcBd2t8W$O1SLURk9)$=g}3k=$K}~(OW5Wh z=;gjvuP)Ij95y}Dga97O;?|8+g2vLdKv$rOAB|$8Ny4$u5*=%*h)}{OYFg7U_MLdN zXKGdwbm(%Q*&^&113ebh{T^1_w0}ZwiYx}_p8gm}7_NAG5*mSo3RfZ?NAg9XNvF>t zR-{Ojc_hyAYPaRn>hUlnHePw+M*Yip>Ud{7C*H{XaYo;hCX<9d%P<(Jdzuu22VcNs z`n5uz6FDCL)oAfe1rJO_pmk%Bx-m%74bQwVpmE0lnu(iuVuf1%Cd}Ukoo&kv1fZE{ z(hY#bFe#fG*#{PYI?F=uP8)t67x54?SC_Fl*?SqbP!zrZHl5|LS%5^Jet;FJqXXKt z1?v=oM(YgR;y-=+{qXwJ;<Sm_dL6Dr0#}Yd%zw+f2y5Gi4Fz&!ei{kKQ9F`2{&h&# zfZ3Wk)eC9O6rU3)^TQM)wg=cnLtN8H_Nnv!T}s(r_Z!;9@2NQmdE1a_YG%OT&uLgt zge~IUThof{SYz{=aB8T$kUUuAY8WP;YLok^j$S?9@(#x6B#9T7=BqHsZ<2PhpM0w- z(`sp%Z&lvf_{^ghi!>SIU#-}p3AafI(km@;|2`F-BF_d-#&gylKWhfRQiz|kKb!nW zQVsgqmn#9Eqxf3b>xz9OJ!er?w`ilH!wU77Cj2lXZ>t<3_Zk{Sd#GSNrRFq#q&sQC zo+-#=hs}ANjVIM$EH4F3DmXf3E}SWvEzk^^-a^{(W;&WCJL2WuEBqzft?E1d%aAj2 zLaAl-M7+&+R$#s~EFB>+2B_&@iLy=D6>HzQkX7!KM|HG3XgMeO-q-0;E^WlD#3=@M z$=CfuV9h0_R~9WzAA+NDR;`pn4nEvqn!%l!36q=&SDT42nTd3oiSnDd88ve&c_zAG zCZ=X4_Q_1#s<6iJOv38S?Sq*+nKQwBj-SP56V+ykCbLOSv&nw5DN(be<XLjTY--JH z+LPJz;n|G$vze>2SqHP(Ommbob2*ZilU_qjwjmMdxdOkr!l=2T<hkO4xw|!UB~Ru` zqvqnNDW~DbqQAjRz5oEo!+<k@H=`sY06PH~U_#i|@_r(WOV*9rS}{oaUp)=Bt#UXW zdfD?6wXJG28)cLxWZqsqmWOtD=oS+Oo+wiC880(`T>H9IGose5!mjS^0}PSntVKut zWED0~)_uIA;awfCdj`egz2tPG%j2NW<4+oAT095S&RTXh%{>ly_t1T!vw8k0Zh8Ek z<<m!>d!zR@KTkYu`T7zMVimUPYF!*8bIDzO)z!8<N)flbZ`IwtI#GQ7`j=PTkJsOp z8>I_d_jGK$t9NL;`uhLnH21B0JHO9&MST16y7%eNuYE*T5u0aSJImBOIgdBby7$&; zRhAEIp7$Jln|*x!>zn7jzkV(Zrk{wM+h+c~M}ODo@%F{P2{Yif<G7i9`ky~Xd*3cz zx1L0(*lbCAdK6G1hvl-^>ODPLiuaB9SWRd7c{ncxEGF~$*Dt0B-J~y)P$}povP5CP zQYyN(eko19lfIO$G=g5vQ2h|FoT<51znrCeNMFvzKx9@Z#yo*5IasNNm0T<Jjg>rG zQ<>F#$4h~$1up+5r@5J0!FDx8X06zl^RlIspXuFHbYSPkS}9It!>G*YAt4DPmG5ON z#CXO)no^aKIDzqm=R<+0G9_f`osR)52Es_yI!xGKz)+-H_2V)E02ndI5}wP@N`q~! zO-y$eXHXWZxEuob@tuGff&S=r*=(s-u1JwQI_G$^<`;8HE8sbBUFjvGl11K7&>S;R zJL}B~5U0Z}(1a{|3mF2-7#K*)NR_H0ddgB{Y9r;Uq1qWS&FJ6~&NRh`)02(TmG$4m z(ZCQxBK-a)j*40J9HUp&m9+;eG;fQhDpqz?Zf1AJ%C5E0Ls<ct0RM1{+IV1r<>|yB zc?|^=_XQTc97z9x`Peg+rkJ}OHhy=!u*pX%V3!#WmBMYPRKb`YTb#|E7Grt2J&^7r z!<e&FC(QG7ZWMz)T@+P%${3p`vOl2Hn!y`}NEy4>e>8UBlhPn7u#dwa(jz%vjT~`4 z7f1hfJ()98fPYTV01DYS`k_YL?dD3|O=AJ*F-Ey1C?m&fi#O$z-7)DViFaeFZ7|g# zXb6@wL-7HH{qdVzx%$u*kXJZmMzUxiY^)J{o{B1FYwJg*1GW>=S8t?08VY*);=u?I zncILVgh}Wa)FnM{MzfsLVL?AwX@`ltqqmPj^sw#9JG9Ei7rT$%$y4Tlct*@FYlvWg zRF4&7pV+%udnz=v-b4v&kd{%f#QhM2*PWfY?>E+h<e(V+rAg<6xU&MKbfQFfPP%6o zA+m>-EG=O=a6<`qArwg!%N0egnXlZgqnU^tFR=WMsbm*HpGHH>qy?Te7G~A;ian`j z0L*>mY;EFTD+>imP6-I^+9Ts;eS8Yi-`n<>3PlpoNJSPqz31MajZwU42eKGn9>!Hc z$t%sXg8+KYiPhgSFgq8!lfEo-_pk0$2Or#<qyA44>_Te_j_xCL&?g=TK!Jb#KgH(T zzqZ@tq`I;hB9ynla*3iaEn9JsFSaYOxL-MvX-lztB}s$E(HS_GO6Z4Hs2(RXUK?VU z|7B-L*pg9;5bS-YXJJHRmm^#9s6u!jL(+qVo4MK4onZ`Pu;jeNa(iPbdzVJiShGW5 zk3>ZdP@^gvvwgXeIaa-nW1X?g__nh?Ttxs$e<%!|;KB&~K!J*#IXXETwGo2q5Hvv_ zOG$NXR3e375IJpwm-(+ID05v&YJd_VoJtgkbV<=O{C%&cAS3QUeX=aXTdpG}HA7o` zSSA|4(_}2Aep1cUWp~&j=;F2WE=H>G%h~=m(9|6rtWu)#^F;0fOU3;KWYEFX-9B-V z-*gknHwK7sI_T`RZK8f|%sr0-1-^8;k!YwbQ2@Yz#ajEJH&H}vH*=f_s+7;iJ1h1S zj<rOEYSAkYH^zO0_sZYQzN$?(DXswP(G8ec?8yJDy^#UhSlUQ6tMFET@PlGGE4<6a z8;*&5$44WYr;2|KxA%3_jT&j)igeF?uhVu3vtbym;eL`)$x}slRRE+%;C<uQ-VBj- zx0K-tWy?H607m=Sr1OQ@s>)@zwJ_5#7TYrK`UI@J57U(L?@TeSIZkY}$ef~z%y;R- z`Z|4b81tIS(~e_JUxf{{`x2WY?>!~r%_uuocTchQz4O=+IH%kN27u8kQOb5@XFA}S znBczWBiX`Mwgi{=LL&{K*Z<fis=Kk@4q)L9-Kcxfde4yi?K~#~!kg7vom)E65sE&` z@bOl;55KnBs3sjG<hnG_Gh-DjWiyjXjaBeE(S=QZl10LX4G{jtTLx|}5{$L)xXh+g z6;{LGaZSH?j<F=Ym9P|+IM9=)$|SAL9I6l4=;XFufV_cfBQjFK8r5US-GqMs2*#aA zUaEOa$yL(?G;KWS@7H6`dJV*Es*3!qH;cRhGA@-B5DcMXM33iF#ih2y@^a+?eBYFn z3|sh?yuGiMZIhmut8~y8?|^d#Y_U{O<C)H&gb<?#%5_E}y_!Tp*}JK)Akm^`zS0K# z;fx6RflQ-TFCCMdO^J{nvj(XLxb(OzXZ(lBN%W|ai~^!`N?hbvGfC*C!O$fodr^Y7 zv_*3%(qz%xP8gl|A9!hgjadM@i5utn&VT@#ex3P3C25WaFUETot53W#3p)^nHgAFe zVo-?zGQ=X<ZpInZrhw;YC%eVpieo$(%TFvC@~93D>)Nd+=~qr(jUgM=9ovpR@-Z^I zacW^yo@Gj)62hG8f0pgV?Q~)*9$L9^0^OQilcqsPcqdm#Z-R)CoqM%+IboDhI#mBf zSn9QDAAU>NHP0JkCE6dWgf^(73bV-Uwzr(XXh5BzzFtV4wmTx-lj%*p^fQX!(3vWF z5-NlSt@IY$&>e@Kl{d)lV=;bhA}W3Umet|a=|Rrh7^t@IUjgkby%)g&#G<jBES)JE zRQ<>Yw8a*S{WG2I9`e=%eBdcjcf16cHB!2N;4LgUl{823Gf3&>-dH2@rIkY^>7I)* zThCNWerkD0BY@cH-0uLI>12fgZ=ZT_iz5nlKg7D^aas~LELllV=D&ohXDo)u3bii% zM>q1BAa)N97A`;FjiuXKHZVA`I6D0<XHjlFy+(GP0N<XK@~mjRqIMoeG{lg3uX6WG zl~b;$Bk%0x`KnjOfZEuY&}N?N+>uG}*aO%^Im>MTv4XPsTgQLZ*es~lU;i3&cq{w+ zx)>PN{<jK?d4~cI6&l~lELA7Z^-fX>jl5dt{6)jV+RJR0f>;Hdo^G?{qhOVz{sAe( zD~^^M$XicQ&>dU5%~s;8NK06r(r0^CwL$2^K99~s`(-l@@R0UBOrolx4YL`v7l{Lu z%zUWaPuKj0Jej|o<RkC}WZ(K^dSUEuJbVL#&_2S+2H^OLBB#}mmT27yPZmzDIH3x~ z2Yt6o@@ymn5C;^*JOIq&;ZD>u=SbKuG}d3vh^0RN3NK5fX3T`I-Jsv8JSd#8B1U&v z?Ezjz+==yw^M>0D$E$ZNU(PVJ(OB60^lZ<IE5L%UqY&3_W?We`aX#bKYYU>3TR)}q zV;m7WwTSDe$Q26K2<y??X|<?yq5eE<L;C7nykg4-jxE(Y8Jt%FKx7re$ccI@jjl5} zU2Hs_{wxxy**oDFWB3Qs>7>VIzuezeEeX;_22kukH|)HRoL|1;lf6u#Hk+|s`N<>? zmP;WjCx&M3+vdDlJeWxT2^?7Gfc+SsleH6`%I$Hzm2DjpDZronH}X1wb1MK?6Z4Jf ziFpzgN<luLfos7`zr|K4h%dfgm#{n&ei7F&F)NhB5-$fNJxBE@i#ZIw?unb+zC7;8 z`gec;ZX=;YSxP|{2G1iUYsG9YTUuh+4f2cEqcg5{`t0ICY534h&-_#ao9nf3i?RHr z$efb842RUBA{_I6zfV`Wo>wYoY2Fo%1?Fa))(TYTTqR<{6Ssupag#te4g2$WGXJ2! z=_o?xPB^Y1RaguDtC;L&TEZDc-lSj`Y3yEH>hcWdz^4u#CGgI2*zFjx5@-f+vYpIp zR+fD^*ZUgtbsTG3HT)JoKlb<aeQN%z;XD7$_?>qy;flf@)BPA1S@w<mBq|h(mJK@E zwTA1&FsfD#c(%Whg?<KRPBn=91!(U!OZ;kK1|eCf0TE!!wi0lCXw2`b6ru%Xx1$C> zEj(&5;xkH_W|%3*Vf%!liQhxJHi*$t@Bj=uuNhK8h9`8?+9QDd=|U=p44(jh#9mka zTKV-0Ne`B3tXW7)Qb#4Y!k@lfRYB2HN#&&HDmCG3JC^JjABq)fAWMp?Js6BR$K7rN z%=0+dhlTX4K)%LXp&~(uxB}#aYE1!+b!WRuLo<nQjl~yKCEc$(dlHCzR4jIb1xRv< z(M#o7kw9ES$6nhu=T!55<;>S9VRl9H!P)}*jD`&W)IX>BvF2A7|K_Yfv0s(BdV9Q< zKNr4di=QiZ+o183b|q`@vj4_0Kkd8gUdSiNpDWw||AMLnhrySX3hbXeWZ`Z$KRux# zogZxzKwf020skux?|+mi3ET<aK-tW<Htb^95K>{CX}m=xh%&7Qh_39{4G1pDdY_aU zEQ1!k-L}6KDu3V}lqO~yRdm~vS?k*UfC~Ssoyqe`OkYt5RbI=#$Gjj71objoyoIGZ zck>YoP()$Zi)#BPz%sjM-)<pSBz+%km~Xa_8nzQoQ%ksVVuENvhE}Dv8AxQ)JM-zD z56inTN3P7A1<4;+&TLIHKPkWPZZ6@LfLIwn`*l2ASciA80DiEYTv>!@v27YT!xvfI zw$|G8T7ZDkvAZYh;l`ovZv^e&ej;Yb9EQpI@avI3gYll{!)(pM7=BCh30~#(^wZt^ zl~evvjN99>P7i|m?}eP-v_`o~#BB_7zU<RL4#IIh!Xp6wwbf2burqO@lvx@|K_afn z!LQzg+ZVWH2=W-4v0IiS<}pQ*18#;3>^tRdEv`IREjWFfNhhkSWt)ZfR#Q}4^(&^> zo$d5oe>X=9wqZ3_|HX*fxUfz+u{aa<YpB>5<<1W$PjS<&c00q5WP*5)T@XLZ5rNdw z4cm(j7Cy@uv%Tv)=9lr)<!(}jX5E)7cDK9lyYhxgM`-!6k36aQV9Tr%RTSM=8Xt5q z2n~Pk+R<oXCdJCLQ;$Q+BbFRf#O?9I%s}p?hNuev^&YEBc(~AA=Q+ybh{*oyqPaSS zDLcqpN3JDJ0$qW2PKVn}%kzzF>7vK=R_?|gv5O54=DXMNR<==<J4}N;F&RGHr%df$ z(fNj<_dGkr*f|`Sr|`M3J^ZK#GQZFs%V2zM*6qD?EblKC^_syT2IE};53^QwZn^eL z7SF@I5Cwm#L<dYNR;(GKpIqDW<FdRz=!m#^QUe?K_%O^Z^tik&+md~L8`k2<PKS(M z_eyLhL(l`G-}(43++MpFXkoAQQy!0}I957jm|Zy~ywQKPFO_$$_l&a5UQg&-l%2}c z$5D$B?#6aviH*l7a9>>dN)T_=E9bAR4FIiwoZD$+;sHlnbuko}5%Pfb`}gsAgu*Js zbDH+CryP3L_|=K%9E5jYar1irSrx<_4${r<a)oDTb^PXWvGb{X58~!l7Bz^!@*1?> zzzency1+i)+W0o_7Jz3<^kJRD(ZW0KOau&xD7#IXk7^g-eAY(k*AYvt{bz&Ug1i%t zad!X|eDd<!xQeHjn1E7?hIxO)t&{gu>XlsKt=g-FCI>iLKaQ;}MlpEcJm4wUXcF?j z_~q?)rwser5|c05$eH+w*XHmE6qte<5G#3ge*SSu*PC|m2&Y&{J^(O9Te`8g44L#^ z&G>L2am(|t2WA&Iu6l89!M}^fa=-7qxCZhf%(k-c{81un7mjVd)#vwYUj%#e&KdUS zr%|b%5&NyRamt-Ofy`m}p3V=V3NQdO9}5yK>5P9%b1D?#C#+MFpDv8-b;MhyWxOb6 z@5Zy<_cRT#*HfG`tf3T)RVr8Eb%o6^-8i;6iuD0LCe3}wjmLvo-YKzls6+K*p{#pe zbI)zm`;K7I{TdSh59&UNc@mhw8yXvXPY1q=8Zk-j%R)5~u9samMa<*anrJL-<+4E$ z#@hqBy}YNbu{LvrLKlVAn%yQirF)|8>a7FVN-Jx)Euy$SHT0PG6Bux(WO<(z-QT|c z43qF&pyY>cPuz7lvD|6C8nFf#iz*<fQP0AgOy=?t)3$6SgSQ}}H);Y*r+HXZ_~R(z z=C$QYcPTo(C5V08mzJiBS8qBOwK@#7Las=5FE+ng<6i|ax+h{_JW}26`-?Hkxt|o^ zJGeW0zVOHKON!`QMXfd3(z(A;?4uZ6>-`yI|FZ5?tx62#r8^75f8A&9Au+11+zNK_ zPgp%hO9Qp})=$*auc#p_Vnz2Em^rblksKv-z@`6N)e6cd!k7m4?|WH{SoCC%C+bOb z5Y9y!*Tdu5*IVdI%w4AvrxzQNcR&6yV<W_pcUE(}I(vx~?-)g4`Q_bwi81>qxFrhS z8NHZL@s8i7xAdX2Pv`2D685ZZwjIg&-Mz1W6*#B66ly|Q?qfdj)@Ac*y)+5@*65mW zj3J}6-Y0VS9HM%8LKlAJBp8;%mjD-%mnF5!=l<unmsNA!QbHeN*!uCT+1|Pz?s5{u zl&1@(=P(OJn{PXBvkps!UAUe-mcT2;SNAbrw5klj_G2OMIiF%C{8ReIj8OJmBy&8# z@?<+x>qLN4h4~!(qI;b!+Z4sbO+9RA8#dK@r$8U^?FFk-%~qmlx+P|1;TbBJXR1%Q zV_&}q^wej%6~dA2B?UJ=M$PxMGRNbYr>N*gW=_2q^P0l5AH&%`_c?30^$!jETXeH7 z`Yt)V<-N|n<)vQ6pNsGg&5*j2!GdL%d1f8NlRjn3*674)2Ex8CQ0SHBe6{@Dv`(KT zPv<DMQYQ*qS+sbFfj&c4PPxzR=rcJ>rbr}+I3F-Q>8-80$g8F4e@GcR(s+5bklp;B z+(MLf{6gr0THLN-sW`#-Rw#?`-of$Qc<8V0U{7ZHHeC9}>aCZ&6)QXN%c7Dm*{=$@ z{5Z*Kx)S+lS83^^DkAmHytF^dk3+pgW7~R7&ff~Rr~O&}t4VrFW6!xV$@d`T@wt)q zAACU0jrrX8eLyH*`sadS3j108BtE+(<FqphSBHx2mQAw+zbAA&rG4TE+XITvlWe`r z3KiU6_!e*b7?$jg4F8{L(Ye{?o{Ap}zTUPxvU%w-wn*Cfk#VZ5)27TTq60&Qz!@iQ zz`YLG&H?v1DMTE@KhEF1F;fzMxK?w1Vq4s)C+ho%+ud_t4Z@GXb}Vx@f4C1Mvx}Gp z7hTl`D1V2ni(PhoGtnCd$r9)*(w8tqNJ!8_o|bBN6R+XpIqpkE4c2N3eik$J2C*lQ z)rSRRP7OY*!1RQM;#UQ&-Ob57{@mU0HIDCgrIiTxm9_WH9-}{Sirul$W%wK67r5OU zJD*ya3z-9^%Z<zk+BMga58A4+-JxGq(AOO*e0yE1vkY)|Gr65r_?e14_uJ}Pp6n`< zgjZG=F6y#=6O$Iv24-1-O+~P>F^59QL}~H@zw&UAKFg?p`zJoJVjKP68x8dx;}S(C zM=mD3wr--U`E{K^GTbMZKs7whYl78g09(h;Czpc8)&&#DMrH#Drxi|d=7Tv15WA+_ zV0r#+Q)p}V8pk?Y(9jm#TI+3zoapnO{?$CsQ#Nj=o&I^wMq1WGqlSwMe=<(g3R5yJ zax%nBu9~;l2-Y+>=(d?EbkfYF?@>C-xU4Ax;J$1k%}&PA$yu+-;nJj)jc`KZ*!etO zpOq$4JI8M=g{~0(>PGQDtjSfFylFo!{Ug*iH;B+PPJLk7Z!BQGLN+r*c(51r#J)OS zDvw=S>2!-wsH_tX8X|vlQ#@mVeQ?7ya8*|CGfsT!A^J0~oI7Jj)a-lHu>h)T<Xzv( z=HYEM`JXMcs914pt(rW~Lq4$w@?%lAY;Npo`4q)lJ#6sFdwtefDDH1L7zoGc@%NT+ z1}Wz?n*OfNyW&?JhJDbcUBlxi-C&}YJ{#AZZ;QOdr_mIjrI}xc?Uy(y)=$xtdJyTE zr8OM6HfDB4`{riPmQz1#YVJ)r)l!vBea28hH#j2`-Rkg_23NzcdqMfOx(zj4dOTyp z=MxPKgz|~HUS-t!n_RC8{hS(-JxQhEtElP+-jc<J!L(r>+>~9N=%aam#crG7R5Lc; zO_{yO>1!`(!Uh10bo1`@k|&QHIyfcQuhfji*jJ{RSm!$=GN_OBEWeYqcZdHN&mZ;q zCfjEo-p|r+*AzQW-CoY~A-iHvvB<cQ_X$JMNso=;aYJ4&6aJht9=)$t$p8Dl>6jK1 zIjb-MfP9g=GYABgTCDnMH?9w5W|4_xVAk{Wj?LpU7E$f$H}I@H;hB0kEW@ZumI;J= zBb4oBFkb1d`{mHv79N`5Dxs6)b<I<Pwi+!gt6-W&dLNUgPc=Yv{%ciK`%Qj^SM4L} zDnvh^nTUFNGP_5f=Cv8Teo**<Mc>MhKh@KeZ<uey*lm#OZvC)WaMfcXOeX!0K-#Xh zvLuRIjPF6Yom9K2w7BcKIAn5E@kk|G>~NA2HAd1*YDLbSZI?uwd#m5(&gULU@vZ|* zl%(1S=3o%FAwS<GN@1!Mw>ZMbxP~umvEHC{lFM3x57-46q{WEEs-un1n2Aa_a2ur@ zU{b{!jk3csj9{&Dc}fM$T#Lwc)cwjul`EWbF&)^L!;`t!j{14$uK)n_=GM?7$G!Yo z%GB9*nD~X`Hk+Hf;u$H?$<n5Fto3D-!e1Fa?}2TC+s!3?5cjZhPX*kw*0>~}->gBN z@X%0rx&rx|s%vEobt)e>(u=P*6&plF)2alAQGO0q<c{*lN}l`VekA$YaOqizi0X_K z(E)Tu5L;EPdb25C;9}PKO^BFXn6*RoB-HKFj<oBJv2ssNcA|fW60yQezq~3NXZ)_g zIf0zI0x*ku7f5n5;`QreGmzdjx%%@6^p8RetM?MOP2?~dI|sk3QYA2e98vl&%-Ji+ zj^{@)IPqCKGSxiOzG&P;F-0kfo*;%j&`mxO?p1!|8T(#wp#mhS?R$Bm-C880LH?R_ zu26!@@|iSSV<9jY|Dde0l@R3lM)wzkB^8S`4L9*UznInY<4nuT1CmD(N4nKknrMq& z?i*bOu$J*Amp?lbEmwQ4Hmy_9hmp(RjkkN<n`Gg6<e*l2q}>mTB&lOEgkKi`5YYfw zs@_Ph)muccU<p^=m3?2=i>M6-0Z>*iDJeVHO=_eF8IvSxMT0$G%jX|=8R5_DrO3-7 zvip(7(7tX<X?^SVmkq&26IXJ`Z<d7)aa>yhTHao+1;Yq)s@6UO3{i$>bHgMeFt|jM zS;Meip{ACusWS|$#UKnFBr<*C304C<q1u>4X3j-|DryOu!Uqw1xVZ2VQuw4Je*Bs) z2ivepr}rhHV6MwL?)oo|B$sJse^*4|&poGKPektAa|&MyOX>&3L?;OY9MH2|Vtnt! zC8eYY{rb}taLZ7Y{AODsmoEx&iv|*fw845(!uSR;Osa1#XD+B1@eG<!<k*S@E=Gnv z_&wk=eJI&%e^Xqv;(de}l>x72Y$USb8usY>Q#REO%URi+_ZqF+>t;e?@E}?k|E6b( zWKjhSpc!za*+PJNQFtsiO+uod^&(Xi5(hJly?Mp?4jYJXyxdgh!=$sns`x;|?eTZ6 zXW8s#fubpTQmjz!jT4lE_$}`7y*9Z4J^*Qmgow5bTrXBhX!7D+<0FyHgnSbAf4|ML zO+o-TMkKv_-k%H-QEyJOZc5~a>g?}(Hl$mz5un}EOlq{TjD){p9RK0LjD-e2uYa1? zKmOq+MYCnpnG(`hkPMEzwZVK4!U_l!MVF3MXGcXjiMqT!9_wHNwA>PepQ_j2fBP*A zqa%ihp)kPq0lZta4)420Ci&#ur|b6^vw7r(AStcTs}h6vyg!j-89ftk{;d@0?HdOE zfVzAn#JP0o1VK|flS^Auq69_^_WDjHuKetl7s8*k;+fhq51R4PxWcjMx3067^&E>Q z3QXIkSa_T)RU3GHa!Ta%udwYRRMYM%Ds>XnTR{Tff`=}Ia^QjJ1)=ZJlFLCH8NRqm zc0sy<U~mCzUQeeBdxM0`l?v8`;^h!#lAbZ$AoE;tjZR(m%kGiTowu%fGjgfC-kO9% z@0LS*q7yE8hAcM?OZyPp=;BTOxdFb%47tdc$Vn&YmxE8ixt8TG0Duru+~<o;F~<>w z(F9R6_{!bBb$jm9o}@yP$&CW}mB)HC@sd=`cnZ!v9y9p3*rSN7WY+4W7BeTHQgrbk zO*B!3Mr0b#mKS&-YL{P6FS5hD_+AROTwoBU<JIv=h$j8mZ6YU{0dCvh+aQ+LgE-;y zC69)sX;$`k9`&bV$rAuzSx$`QtJGE%+@wOU7bgn+)xPY7Oh7_Celv4b)(CdzJYbX+ z?dHBzuk*Go$r(8av;tx1Bts+<{|=LVqGUh}tlCSVTczvIpuq**R2Tz3qMn2^ul4j9 zc2Z6^cy&SC5z3NN;OUt>+iF-y;rlb*Vr84`yWMBC4}@+rS=9^vygZbu*%;4C`g9rg z*T=+S8x(m2fj5}k`VD)2lpBBnIeK*+HKyLkN$D2N{ct1<6-u^7F<HGD0yGIYfXRwR zmOo~8W`$y1hh2?RMa9%(TI+9Y6<^q7)ox81#%sEEJo+VA6iQ`kz!{xn0uL`RpjYRT zE|r^Y{vlv8AmJ{fJuy{eoU!yka*ZrH_;3Gr7ji^2G{6uWVGc_jC#iKY`AiseHIQ&r z$i--kct!fV*(A5^KBH*J=ARTx6xfjO=|xT9G`wOtL$c#aaY+-*$psXr#L?Vgo;>@6 z-3}(kLglT>ik>9xg^9z0Q|nUAE=4nGVo1RlJYWmDPA8hUbfn7<3&xZ<xV((7fA|<Y z@tDpSq{OVPYZbbak_G~}cLu3SS@AArE@I<FN2%7c;0SVx*a8#gl-b-0G4D&Vp<!RD zRygG~T9x;Q5wNY?P#}Q+RLS%4`YYSJ(8yCjB%Tx@VSJJ#ScEHwl-gMrYBIg~1QDqx zn6yGR9g;j}!3O4iOL0b)1KHrF<WQFfO|PuUDC%*Q$j`qvstqJRdZHGwOT_pzf-2o} zJN0W@T^3%!Bri!ti4jXr5rYAmbcoZoa9zM?{e;zf`YBiP)ous5JsqlScN)5qf-}I5 zN4^c!gdDW8WWh#ifn;-+WK9^Oc~`Oz84}ya<fI9+2k@Se<nnQai{&YyN936}S_+mF zk4jOaklfQ>3p~jZF3{Y>q%MAflmltY9WYv6qZ<t*KAU8MhB(<K!GnyRCXs6w%9z3~ z3<g_mVn~o02yww)Bm}-){8Bu+mf4;8q{GE*mB5TR#l+b%ndT*#qfvIq268crm3DGS zxuSri16hDH$Lff@n|k&=w2%S6b3C%*nIq<eU@EIgM`_MXacD6CRy4=U$ETaCz+a{0 z(?U(4oS~o{No2NIvh4=8z~MQP`L1<(1V8GGddCDbfu6#m`%w4uD5Raqyq>|Fn&}wF zcU7T$kM;4_w&YMH(qH~}0-v9>bLAaGI&Ez?slnt7V=rkmo{yoiM%h9mjz%w6<T&6n zxx6RI#UrkLNo%i|ZeO-D(-obKO|#;A9C|braxfW>P9bhX#F{?ft+{5-Lvc@R9k!Fq zUt2xgce;d5oR6;YNglF|#+<m<_xqo5Ny9+Du)XsgpWQ<7S{}VQ1j7SiDS5jrqB&2J zi>Ln`-M1>|m7{^&as9AJ%QUU>OD@R!e_c{t^d8e@?mt&lG9ZSOUuw33Kc}VVzGkuy zYL0$Q)BITU4==1%Pdr5iHMLelf~}ol5dZH;0hW)7|9ZZnI*mD9chD)vf5txvvEhR+ z1Rg!N=abiD8}ZyaW3@okJhkUzwVv7wxeVC%{dSG;lr4&M+QtyQTS-;c^P3n@(at2l z!t9mz&^-3%b@b^aAM317gyev82qi}FGl?cVB3%Ir$$?@L+_dkK+^fKP0k)$dpI7<j zoARDtdB+-9o`MuhKDj7R{Is&VvYrVO4RFDTIj83pijF&)<w%o>z}YC+^f|Q{4n*f| zzP~zjdeOtxh(nShmz8XBO|=xhmTkNkji|CcF9tB2LbV;R8mB_Hjn7}wT;9HqNdHsA z7Np5|zj@NA=97fs5KigxiMB~Ofw=#kC<RJVIeHwV3ww@n`=0sGk7E0uNk%L(%cAR^ zdxTR>G9}-|fe`|PVZ654NxIv3m1r;qPc*`NVsLL8ucJSG`ohUYQiO3q-!DuAeR^@k z_#c07$34B|;;S1pD32o10>E2DC-Fn@kbhn}Zts$TH?p<qGplM>fd#0ETT-5~$u?dD zO_W^GJ3(}T6Ufl#H1BjiUL~zW$j+=rZCbpGo6w^#Nf^@95@Sk0i^@WOMC)<}?ScD| zysLum_KLX)eEMRJ@^#xJT>$^o;gpd%VxoR72JiH7n)!yNqxBD1>=9oQ+Bc4(+~$p( z&{MX%c{*K_0_cp+DXB47X5ZN+a<50SCduG)VHnESH3im@=XL>~M4@_ny&z+jD07Z$ z*G4=5bc#38KLaL};F8i9u@<!E&j-SvQ*!<I-9L4fmFW37jAzZ*sWd&@*ZI+f$dvVL zTM}mALtyf?H0o-c@H(77uX)lZ@=G%H{d#CE+-JUo5DJUMTui#;Z{`G#oK5lBG&)JC z?Rtq#4QudB`EWJzRAGQwVGdlEO>s(~C;IVm!6pOzZ1`i!!3G$pt*K^$;*uX4dc~$U zpJ$annSOHiVwou@hrz4t_S&d1(GPu3+n=6K4XCi0@AhPK(<J`va<8r3%s$H|{PEGl z4?)g{{nyJjn<3u}|B*f6jaKk)kJrAAk3&UgA;91DARhjXT0fsqiti8qF3l8gqoD3b zOQ)NuUgVjC6xOS-#?IAm8b7+?H4{TxNwKgEkxtU>?+*t*th~gKK6fleUxf|UZprdM zV}EqD{Mec_#d2{Z1~2$dUHYEU4D}H<Oj1-2pZ)ee)IIO$x~>rYwjOz|_WMcgr7ZFC zlyi^#<4{|le|(qyk2P-FFZvW1t<L&IKa_Ab19GN1>)kq~+@GHHBRj!8!6k9)eW>fr zPyqJxJC6%j*!Obb^#Iu$dvKR03&=O7*YtyL{JQCsHF7lpeKz{)mF3Q#o7VL&X{U_j zkO~Fp*V!kp=vj~BzMa4wpJUD#s6YpA2Un~P#vlC{iQ4{PO>R+U4Z@`#fAIcslz2P& zb@7+&`}feVIm2}ROZ36gxNo=zAI`kGw8o{x!2j}VHii^Se_iwCi?RzjU_0n+%cY=? zY8PD4S#L-z7q4i$xGk#hnq}1nL-03_@*yW)nl5A?+OCW<4Pj1FXZ~>w0zTo#k%b|9 zLkeCg0aTuutLLe0B&Ba^ye^Mh8D;AH&OP3%{jl!VepkQc(zcSi#wC9yEm#5rrva~P zcrhH+@}<^qAAj&DnSLPv4uN};U)_x)WP&Ww+xHa`TU!Y>C$kf+(9z=HfdBC33y}`D zoK$j1<QHt3EuUkx$o6lUTv|TZ)Pf8cU0h8)uky~m@FYKyI`sV|BCv@R!fwT1T@fR@ z_(?l-1i-Yqn1W^wjXuiH@vMoV!2mkR{p+E_6UOxL-5@>4c};Sk{iLeguiXylwu-BJ zr%&l5DEM{F#iRD<7CQ$6XxQvejYB1k7N*<3enI~gCTmhngp=K7lTOsI0GJ~^sb%sf zZuJz=WKRLHp?lZu?a~pR&OA(KzJvH%8Nl$EoC~j781TXWh5r}AUwFrs=y_HoC6aJ9 z*$DuIsg5OYt(iA=JZ7MfnU(%Tf;7XiK**5^4^zVB<4@HTvCd!hPmi^jnZ0RyvM=zB z(21G(*cRSD+nCgriVAnugEr^5G2F!fk3UaeW@$D=bk+UYqCqWipr?11_4^1t53Fn+ zkwVB>rJc*Juv@4j(92(gMOv@{>FB^#!VBlWH>UrHz*$pZjCy3Ee&4~^ulPYt0uk5p zR{Gy6CIY}Pa%;bwy7n&%mH?C!r=csusUJT)O(;SqLdykDF7nalfBj4A!?Rx|YkQu1 zgq{6z@^9rD3=2!ZXeNr2iNquIUzx=po&WoGjeM30<mkXKM{YfWd|SLHM1YX2`Hx5= zUO)feZ=sWKcM<@cDnR?I5qxqC#h-6I`TG*ar9_wqU;rbOQ$AoDHIT%@s}fA#79ApU zO4~OD?1+tI2xx?F(RakD6fwbFfxumf@qAh5_TY_O$ydcH*QS~R_oUvGY2Vu2x@*si zcLh|KBh|*Gr>ZTAR6;iQ15GP!>+G9@4rD(xxjqg5zIh-w+v+`<t8o2L{$oebOnb<; zLxoRW;p<b)*MBK~c^3O?_xrbB=N9@Bp<If=M@ma4LutI{L${8USE#wt4v&I=tE{~$ z(TMo5_4_=XR%w=}7;>z-IsMT2ap?DBwXNCqYwsR~{89h$spr<-kMDmpwigCST<1dn zYVNL#7oETH<FD2}eX7o(CG?;6;nv5e5kG(Y(>dB+`tu*s<@SP%!}83@Bfow0pQFbo z000i;0_-Zmn?*mr9>_8>owtwyAN&$YWR~qh5!tnm7A$wMXwjrIvFf5JfNg*%slcn) zizI4uxR@kX!pEN~dB3aDTjn8EEQ8p6<ei~*tR_xY->m1&68v!_?yi>$lgJ5UHuuRf zuZ^nCw$Kjb$=lV{T6M8kX%H>AeEUpIq5I9@nxYdg@2Kixzby0GyMg*nOBq2ubNOj9 zFSOQ6f~R7n@5gL*OFu|B{w-ZjV9`cbBn!l%D^q2A&{dh*$LQ)D3vHR20@qlX+PgtL zGIjT2k7epB(zIn8YD!{dA2vMfk!@`5IhJi|8`qX=e)2I^?osz<k6g?1<72tjeij}1 zw&)jC*)_i-jT*F=CU@X^V-_WEbb%uVydLA_b_lSXRCG~)X+_-jvD@TS)>Fz<9$ecH z>3gbMpUYDKKH-Vb&K)+#H<uQ$7Uqe&(>|GJXQR~=YaDEe!C}AY5n1_5uPi51_QpXM z^)qk-*1Ct)>C;11D#1e9E{x?Dbr<aAS1~6e&y*D>tP_axI*YJr-?q}r5u<0bX9f36 z*uD+2J1%xa?CPxLm!7}2fYf7Gk2q~rUxe;hQeHDR6Xj{2?V{n@`)Ol8M}E!@VkLll zaW5*DpI*De{?&W5$z|Dp_w;tF#clPMS6&OgacR&+w(krPUkiT1i7zfh`#EHb{$QI{ zzjEt}xUJT2@QZ5Q{pl)%MA&Hto5r1QofX<l{jVM8sRBNd00e|ra*L48zj%ITwkBKU zO{Db?SBrO5Z-ql#ra;Qa8CAc3KK>j+6a0X8P`Tt3ahl&}46?nb7yn!wskw;z{LF=C zA}>moF^bD3@AFGJb>}q@CQJV|rV{brN#vIOTix3An{Z&ulP#_uBsAMPsA}b(JK`i^ z1aQOD*{&fHw!g81Vy<5Ol7n!yQoONZ$=befjq*O##BH9Fs=43BE=m^{`tgljqrOPN zl+r3KI8~&)g+VgUJrdG?W=UNkv<BBGD(sc;cG3G)5{kwBxm`c#sP1I>C8YW-*qg02 z5g=jt@~(^(L_KPSXbd%5-9&=gwOzo$`P%Xn>{D*)IHJ^MPW1rgoZ8shw0b&-JYVpZ z8a+9Po774n!Vu5=7DrZSfGz(P%}iswxWM?$Igvx6pteh4v)-Fp;SO;s|G5EmpbsR> zs4TgxZ_a^Jlkt~rEWxmi@}3w7B<6p+lAcspgSbpr6x#apxqY^RE$-Q1k&_TiYg05S zWT?uOld}p1W&k2_Kh<lE$y<(d7!^i}*Kc|;%tQu(a{(dVQKl9YO)1xRnQqOvl(-r~ zviBKKloeKz&eZ4|VxZ#boMtLT_i5(2BnS0{#2Wn<qMf!kCHV13nDhsA)6657&^p;n zxLaECj-Hsv-Re*7`q4Zrndv-g^3?W6lWfr`ek{_D&jSCUDZB#tF`xQI&WaVQgxp*S ze}QsEY35`{tPpGY8b;;3NfeRe)lf@0`sMu!_M6;!qO0CA_fEZ&I>_drvNCGQ<_^rp z#SwJ_n_||+<V5;(q9FVc1eIs4>S$tKA?S-%>AoRcNGP7V!>J4%U#UpV^Ey+*Xr8Q7 zA1xi}E6;gTm07xTls$TgSQhk*`YgZpoJZL!iEZSDGrjv#=`2Y2C@)2|y#k(}StvT) zyWq@V>(YgvRy%GV6*rzz*GUO?Qw0M?8k`6=f8(1<tK$nUf!Q}PRf206Z~dTex&1Ni zg2&M$`Qyp#peAv_&$ecfW6{RRNg0nAPff)BI+XpXVT9!J{m3gmq|sPk+-k}FkDeAD z84KU4&jiY8Y*E;%Vu$0^&zl`rSI?H(VuhJ&m~`xq;2~7+w9Dx~|G@3Duk6+v?_;3w zeNiRGUnzViFiS}zLmubv%I{IR`DFb_n5Cwv#64gkSig_q<D(%Wh3cvl_}yUGvBT(W zJyVf-M^5$)8lPzCo|xo!PL)_P2k@)+E-o_qyy$KR>d9GtA?aS9qz?ADHeK)Qf`(Jn zkzM&kjF}GGjt|>Q<LF~gv-4>3OOpX39yL~pd(7cabNWHALl*CAg2l2Bu{k&Hu<aYs z2wBF?Qpm>+Fy-w7*OV3X6#|wnRm$s}Mzf5wF|BeJtVGzvyDIR3`X;9ZxoRXG)ASvc z#J_TM`x&@Kfm26|`@QMG<z9l@s5S%IWI%dSu<+h?*^u|tY9pT2CwiMn(>If2*!=_T z>W}|n?5@AsYM^()pFki4OK^wa?ygO6Z_wh!ic_StMO!4e1$P?UwYc;}QXC2tC{_v- zuK@*0mEnHx%)0Z_toaj?m9=vAKKuDRH`_u^JJ?Tuo!D`I+im`%mio!rm~He-ZzIsX zzki>5GQ31iBiyskVLaUd_dQ1NEy|s<cyz7Jegb@xPl0G1rv85I(yFYU$~_}F`(f<d zh!~RQx@2&lF6N}4VI)-^?OT00QGv9RlkwAWUGi!Yl|MO)1D)`??(4^@jFqJwrpaY+ z5;E+ssBU2*bv=)IUP_IiV2|vqGOk(2K4-@rtZOs1%_{YvW{Rk3Ie2tn!#D&<87%Pg z?DPcz4gthjhp7~^XD5JUb5Ri8eAC3;*T1wFh2!myDs1liS#IGoj(o}#r-asu>)whQ zqvy&UzPSj=onlkkUBE0C^<M^VrZ{Die=CVb`sxS?kk}^}9<hcP^7N>`f>*J9vb$te z1xC(pt1&*(UC#HZ``<CC0p7=$9;&GK{jdhERXHzl7?v?QyTqB8)g{L;mCD4leb9aG zWu1zHdCBxP8p;o1f)IX2R7ZjV5Bo1h;qgco{SX`>Yf7Y+s^g?z%#y}91*%BZPVC&g zNb71MH0~`5Pvtb@kYnj4Xhf6o0pyU!*ApX|$bcG%QT7<AMy)FslMQaO8M_*&&7}U* z!pkQNk1G_Y%#1EyGibt>sYS@wLNsPnHvU*>%7OqEyFwuFzS=|-(n{k)hY@)wW=9vw zk7n1MnB5&HCb1r6xxSgc)B@}7fJhfD6=Vr-sMzxKbbnwp#Nnf&t}%+il!Ob`X;$~X z+U4(3toKe36120bdyL5A*|BTzyr|^G#uX8sWi9htZPmC!whZ-$isu@1tg><H6GJhT zORSAq)FlaqYSJtc2FtR_lHld$M^#kbz?x0I&)?%?#>eUEQP$1ohOj6Eb7=ZUtNAc% zAjqbUZ>OG2PLU#w1jc_81fl=|f;>hJY06KJ*$W^2A!5a4&7h1NjXEn<#~Z%%D7xF2 ztOk!}#)AM6jSrfvb0q4tq~J~xjL;FMroh5&0k7ITp=#uk;sw_+C{=LFWM)1}XhI{W z4Aef9#}R#_IXsl3D>1X#ddnBhDe>WLnAq6|oE*@UD&cn<BP<d{$W)M43X#dmjibVv z)8c0?D94F`{7kt$Ysur%Uq_?8*QRfq%FTGFnHJJH&?AbCm5i<$hZrznYBKB6M`;ki z`x&Gfe*5{MgG(A*HW<!ouDXzEj<R87FqP6nv!rG2t1r`g;hU(<;XCa3&G6;#h@$LN zhQWMO)ye|ZO?KU`QPdL+xnN^yw1qsQgC>$t8Q8M1ekUxWp{ix7;5(uA#lcK7S?wrF zzmHJPoQ%!?!<-`c$5D=k?nECs-kct+s6R>NqhV6;rahLzOdqUhwfNV(Ky#_YnIKZ6 z`38JPpH^qv(7HEY)e)O(f>9%goc1LN=ww=1yKgGSYdoQ$g1-A}AVxdm%>dZc%GgBS zKmGHv24QZD_)ZDtI#W$0M$eZ?y)hj;R?dC3i5w`i;frN38dgLztL_mpqcv1T*rd6# zkd4E4GCv{>opol&LQSLD!yR=!4xE*EnFGkEx-jaQ93d9f{;FX9y%l>Q{Ie*0Pj(E; zEJm-sOf8a~2xR{*pkVfPl%UR2=^+$V*w#F?`34yI4$k&2jV|LE1`RVz(Ud>J$yM|x zwnPZKI*!=&7)XiDD|}<5zgTTxHBi2~d~8vnY17HWl^XCe`vAws^rg?_w5Gr}1R_B> zo}qY|>^ZG}X|Ey)`Tq=~Lvr|r@2;;BJ}U#8{oT_+CtS~uNaG!};<6U^G-z*&S|kbv z6?Zjt7k+dI?323;dTOZVXExsU!YLB%uW2YH9Coj<6%5~1#jv%9A2@O8scVwSih#c0 z=6;oMKTpD6y{1--UdkAO<{4$F;Zn7R4_{rA$)TAw(dqIM=~~Qq?rcJ(aKu#VOk|wq z?hbf#z|y|-&E&+$f|dI_a}S{uLY38-{4@As2ATA_p<09`NouZi2i)S+{0!<yoHQ&4 z)EBmqp9^wWvV#E=0=a5~EZPq}IR3j6D3ye1&)j7B)YscSIlH=(-flPV@28TppBnJd zFZn2Ontu^CU|cO(h%Vi&`qh&)JOAKS?C1}LOqKZuK7!_7mI*_nJWYKjdctEA3_sQJ z;=czQbhlR^eLhGvqJ-wQpUsi|#SPyvsYaO_ytMPai-m_(kM`iBUXch{;Zx3a@#mbH zA0-I>(}h-sd?d<A9+aul$v3?&I5B3e{FIu}{d2Jm&eZ1S85lRJc(ksJd6P~LcFeK- z#rXCsk;x3nqO<^Ek@hhQ-`XPD$3SMod3X6+<B9rpf;@suHf4HT-M0&^!61<S+mNk` zOG~YFDfu<oSp<==2?=*ctp@A8uC&5ewd^}2_z6bAh$-sfOdDdin`xHtQTe5MBi#wP zr5Nr7LOc&fO(8}qpRna8yNcwR(q}GeF+9twXgQh2T{@wl5e-76LlRlSFMUnMJ_&Ae zoV=JA!+^r<`8O^ngsMv5FG$v(M;dxQC;B+lb|_c3YlX!OnTZ~lN!AlpnWb`?OgU(x zl`zfkgjL%Fc_-Chx6f?S3fx^K{I7#>$;ptw*cdUJr7XaxzT~8~XQmod`FfC0MkVG4 z@i$prky9nEk)w?RF)bB=6C`VtkdS7%*4satr!m!pf6)Y-xR{4?4R4(7d}H0KMv7J^ zDplaFR<6c~>*y$UHwBZgn)CT;5~A(KZ<h^o|E%PvJFI^SzWHLjm$m2deqf+XB1c0< zPLnBfJ7|m@@K9g*v-s?Q8X(Ck++v;<aOaS1)Zrt#OO!oyj5s|WeLBYv%!>dMsMov| zTO_IN1-7l7t=?2%mmOQAK2#MkN_}w}AtkQ;?7^Ew%+*9I-PR1@0`^Z_3TU{+SIQ5y zZ9vy<Iz^88b1bPIsX;82Pj^NQZDVim&|qT0D+ru@8hf|CC^jZ5#oBy)h|7ND>md|F zj>;|xvM_2X7*(MSEVF5b#n6GH8&RzW`bX2VxgR~=SN$<3W2V(0EaIaVd+llj7GY&L z(>~rajA3()k$e2ToEd!6d#0<Bp^|cjS|$JFoD+0>)6Bgv%^yWFR-D{zWfvl9AgwT} z0O$FWzxeX&yyS1Zid{9lGI=PL=2Vt>m+Qf$C`d|0(}9W-Pb(t@!*KR#-ZU;V*K);G zj-I~?&~zjr941i2zSNzmca};=*{$pbf-3{qt~=LsHL<Lg&1-+fo!>hU-E}|UEE&J{ zAa0*|Z@8@(uEApxG^0T1ZG1=r#mpvrF<sgdn?T)eb9zHR=^u?!W%IJXZBsYmCZXy0 zz{G3lAu>XDiLX8U^Xrpd>j!gZvCVM7pV={EDxJJ{Fb8QtIuoYDwK0=lH77`D1c{oO zNwbuK_J(st<?)1~nuG~l+&%A`<-h{I1d(gxH}ojmJpHCL{eI1^KMuZiXDY7Ly4Z@I z%J+(u7vC_;URt9%Z*YlEcsEK?3`#ITijU~{ZT%`t<idxE4O)aI=Zv>OatY1#)(@BQ zLFy9int!6iH+{8Xl85>eN!Hzl=mdqmx3_(<i-w{?<2w>H4>+6z)n#~4-%hRNL|Rkl zzlv#fAPlR^Jzws{$jpA+vcWKZ8DVyvwhWX0`+0;3Pm4@4>cmQ18RO3hq?YX~<9gGX zvtrLvm~=s3jM-S_k4&_5_y1F0juxMXFTZVe7?mv;osr<@5l!YuM$?wP`$|D+Z}F0U zO86*Z-{Lst>GwkUZ}|7R*9vJSfppD^l{YbJDLyYxS`9~G2}|ib=Ba9SrP*Yd-e;iH z`<k61qfASqTeZCH#h~d*>L8;O{@?hC?FRLWQuB1fVwpEN{CEzM@47Q&KT>Q8iZIs~ zCX!8W-sTVnr`Oz(lLQ7l^Y&x(%cNH{sh#UIR;;cR=W{YY;a3&EZ%^D+N+6_!cj_ht zX$EVkT17eBu%rCbr!);D^AG*vF+Dv7KW08nc<}us7@|TbnF^%ZKgMaWBEX95nw4|W zABKybV<Zt|q~A3M1!LSG?hFlrG!L$p4`@^)f1p@-oc9AY5@4T5*F>ZCq>qGf@9=n@ zw=#U~Ss|2mwiwKehAKiMN|=SX=tg=Ixvzt4STj*<yn|t^T-GrZd-ZpC@D5&PfLs$P zHvTM3$5CU?Nh9I#<KMJesm<uo)691K4-JU|ksx~YY{4c5eA`greB_oH+IaHwZ2ucg zIle;P;*|Rwn4s9lh6-6SS8T7jHCN`swIn>>QGgK>AsU;Y-lt@M9gCV8*n)7#PZe`t z(vOCle7FH4-?KTf$@kzbW@%kRx>8-pZuBu-gr;M^RB^Tn;x~N3b(HJ<W42`O*ADl@ z{um$(97EkE&63qVk8Jd-=nnMqlFQRQHx-`3YaZGa{>@N!^PM!nKPV|=E4j+xo7cFW zj=nim@`Aa&l_Z6x-o<IOy}1Fur6Po>8@^I12^P;RW1?8hmR)o=kT2Hg{G<RB6Vkm` zG;nm$z`6fG${WpO%sz$3b~L!R4+_v}{%~a9NX!TuBV3D>1FY6Nm?#y7zRkB}KDh^0 zh>Rf`{?}nEW3+AP^^4oMQt)3&Osy>jJxa((hS5(nGW|uZa*?5YVWKRscvqSzb$XOK zTqAV^kN*>{N#3QO4@0KBJS0Y{01zrZ^IE?mcnB${c6Nfq2UHlzzN#UkINMkv2W&3M zV~$lf3;1lWQv1zyBv6#otz&%ASSw#X;6TQ+w$%6q<V~6RPwD;P;EwWr;Tkc!o|r<) zCt>+#{6NT6<ztt_H#Z#ri*|dkWR=tSruB$*w<84WW!+5@_A1BrF$It-IzE?UMf*{) z===FDt)~gEUh>0X5D8xI#c+CFJ^h2kcwVK!Jio2i1By;lUFWNlNey?4XK|J-l(CcV zniXq)S;a}`-R1S3^OIgNgG4g20BjLmgAti_BfBH~>uMz7*RvrPuJsSoPA|S?ZBBf( zwCYe=3-BH{N`Z)>#UGyS?%Rf$il{HX-63pcQg~$-W?bZHa3q$a91PDHJ+AkEb<D>a zCZjJn^vkAwmhTwJrSrmmujd<Llu<-j2{@WWbL~-{6HEM3F|QT<viJJ{acMXrAz2}j z8LtJjf`%AAJKxB7j>RZID~rLLnnzmXkIh@SrcZU<%8?E;bxq3o$?2sx`o+_%PjPJx z{5I<#9LpQsr9>fkLy&h<kdjJWMe<z0=aJ0MNiCwYi<^dN67LC2q_6uxi7Z0=HZXo# zkojz>->C{z{S~=cY8O#fgKv2z<FF+Eg%6mgEf^vC_U)HwmD&>j^VWtUag*QX7FZem z8Z*oRsPSdOt4Q&x!!AV^mJsJ<12kQ{tvCCU!{13MK*&Od3w6o$wn<)uSCBU|O;w;c zJ}Gr#HqjA^5eS=_guw2PaM8?JEIgQ=ez^IwhS~Sxn7HI>vFYh5W>N3<?Rj?pZAZ`B z<6{zAi<@#hECiou(DGH`qwwuvZms*O&*6HvL$@PSU{~P#Y{=?15Ik9xM?Nyj++Zm@ zQ;a*s-rY-f%5B;7?+byj3H?rCdLK&Lg-0ZFCbcWX9(X38ZYz7aOFzbuT}mAZta$4D zT+%alf6*GY_W+ZyIpb9_=QNquM6+AH-T*b8)LlPUyj&`y4Py3f+22v*V=CY!H{Ao5 z@f4rNd3&eYUqp#@)*4asmxam=d?^Y(y;`q|Us0>Ii9P%$!0q4D=2DnUFi@e5fu|o) zhRzoivZxyc=1RuFMpU@krT-J@^L*1}Kd1ST_*Z3r+`0YC5-r4$Wlgc6#(QoKWdC)0 z?`G|Z_ll2ca7c;YJx|u$lr<VI)@iDclOkZvcVmC(C$l+ZdB=dmigCgI-_Lz&c0;M< zX@UE%-yq#yZ|(z;FP*eiPtfsdug+pWM%8QamO*4+Z4U-*3Ok#4<p#~kv#y-QnvJ0+ zF86*=D>KFfdS~30A1p`>3f}H>8X)W`px(1%o`=wd_*YAi3{O|=Gt~>H$a$Utx~6gV z*DqOsG=HklY%zYe1qja{bb8sbD?4@Os3=}i3xnoz&MU*PMDwJB)^&J|gc3A2!N~(o z#ArJ11qBRYdibp}uONlXI;EEbB;uY}fEMJ>Gn5Smr^3`^_Bhv~tBVkG7RAFiSTzAu zd?{LjpV}ryNJ@bdvy>>Zi!9^_P8iq-c5&dh=Kee5!Icdls7WLpkFBy{LqEA95<2!p z@4RLR4f25go1zN9T9)mi@GM2cP9{8>@%HmB&ToXt_!~^q1MnY7HUwNBNf0q$TffSs z^thGYPRtlrFbkhDx04Mc<Cwp+luy!x{D(w?kn*O0f5J<zcDt$tw|V0^jz^?!|5}0Y zQPzuAoN+Ed?eXdX%iI8YsMrXJKRGrr;dbEHr%qSStO{s)8xL7Fp*)^B)d<$m(PCT} z4{6S>I<i5_I(<a9qt)Twy~`?dZ5aE@B#~QVP4YgkCbl?Gi9eMCxT!ZY860|~bbfur zlK+dQyeqrj;%_#q`5B8zU#zVCQHpA`vjo87(@^-9MCo%Iv8!&1&}%9JV0)n~?Uhz? z_U4Qp2UX(t(|L`jNTyCkaC)sxPHU_xkN-oHyqI}z4j`wlTuh2nrg1+(_>8!VorUU- zzlp$cD^x{>U?f{m)2Xw4S?22y#lws5aytejdWse7s(n5QY9_|P*IridzjldCgzpY_ z)aI4XyReM8d@*_=m^SmO3X7~wFs<rpyIU2gBrZ9I9x_P_IIakpCeo9sowhwoW8izC z*r1A^m(i<J=gpZFbv28&Ovcfv^H5C(=-pm>8b>iRQ(@Eq{+lIY)RAsI>9+?2_#VtA zh_&^%o`Z;%1N43))93|lLEM3TJ}nK!>sB2dteNFYP0d?*LFemw2)s}o+?5|f6(lJ= zHVsd5S{?otk8s95q}v-*IzGchg=6KW#?3%|lEyrH5Z&-qReHs_j5Bo+iko&DXFKRe zT#BwX{_fbe3dxs6X;xzdhGkz+*SDIL%9uxZ!uOdOOI3M2K+z?#WW_6E?cCGu!#(() z-rJ#h#XNF)oesejCWV8EgwQ{$=}z^!Y;P3vl!Hf&js@a77RjlEj7EJPUdgDKs~>L6 zSlD+Tqt%j}Y?6>|8jxkEB3O1N8OzL1Nq}StJ*A|)VT%(fa6@b7I+Lpiyw<ovHhD>x zmnLOSwqTVfRJ;<E83`XSH~guud9UJnS2RfB2-pH2Mo~(lH8`G>d}zH`ApVIZG^C*~ z0i<1FE(61SX0M@7aNu_VZi=M=BXV8)3mo<p$s2FmFmCLou%IB1b&j%_!AbS>z?+Rg z@}zh*MykZTj^CoRcFFo5cD<9P&6bReQfm%&*61Evi{-9f25CN=7Q0up;957a`YePc zH?NAdllAADDAvs#^x`J+KMEBuhaCCHQAAFv=-Us`D|dYGM;79OF)N7O=}4U+rKpda zh^og~A_B)sy_#CPCfvsEmGep{D*gMK-Y+mUH#&GV66NQnl=o{T*yg%^efZEZxdU*j zIU`bce?2KPl((BBsV^FVIqzr_2J&`$R(W3xCn~PG9HtUOM799HRmWI-nK<%TQaW2e zlKoV4&`+Dx_+5u~#h$C;n3h`Z{a$qWcLqY5H)&dl>*8d)k9w2MXwA|>5@SC;WO}b? zeY1YtNOajGucY>v<GkzsSe6bpynZSy5VRhn{=hH%A?-gLWIBdN<YdsUFYo8<_vy1i z3!}SBCh13EwOkqVkcp<2%f9Bv&T~9*#MD;1^n2TJ3ZB5R_&EldcEta1Q}Z+Zv7B6z z_K4G6g*gz}>o}{4_!E#EK`WSw>l3Cq{suo(E#YF7i<4R9x{~5&nSt?8fBbw!AszPy z9MU?wt4?=>BNngTQrVSC(wk)c$j1H}i$RMfwLr=wNcl$+9l;srQOtN8dzTXw&=FrO zQ^@{owTrqTJ;inrDU?d^PYpAlZa=C#rMUUx;8jI_=K;eKio_Kwf{laMf+z}`XU}!m zS4BCoe$tL0fo%z@HX~2Vr0Nq8@LZkafS34cNN8)A;PLoyP#n!aoFwfTO$eDLiOw5% zB6Bs4TAurrRXIf$C;O8`%C}k@#^tOljc`A1_!Bto<1=ioE^D773nL}Hw5td0(DL30 zD^G@*D-U?z^OF4&?;=)&(ud)uE}-hlRr6sYa{?!Wj<EAYE3=U^WusH)P#fzZ^!=6| z$5lFtCynK~4x6`!@5-6kmbeBxf$~-)N&OqvpJ&*(2Movn_MM6&sT!GtGKRu(4!U#f z1&D%P3gK=f4L;`-43tg+Q9L94WAjGNOIM)TjY}2GmTkZ&+|F}Jz&7v5bj}I8G3LG& zwb!MVR+;DVTx9nSv_MMv&VS|$Su~pf(S%6}#0Cl^whN@53uH(M<^&2Bv<sG;3zkU< z1=O*iKbzso*aGhgbp{H5(qaZ8>B;pt&OrjbfeKxm%+u|xkE+?4C)u)hyof1*XFF_t z5~5$u#gZjBJ2;;P%?jTL!?+g5`zr~*A<8+ZcR3<=?!-AU(jIW4huQv616xtNFm<L8 zPJ>($$p<D>?quSskCc-1#1T}SBOo-cj9Cs2)N?*91Oe5xRGU!}y~LdVKy>HB^i6LV zj}Lk8ygZrPF%REmlcNEchd;!*DD>-!KQGH~A7P^<VBgAwThK878@36h;fVvd!apii zwaVH?>z`2bZ0(3<m~n3I2v3+!sBv-h;ceEXjjZC?XPnr`X*hv#j#nb?|57z4IEjwq zPXWglaCJZ*00cmyy^ltcM%1_U<a(;HB7{F@%2+-ha21bu&N*%GO7ZJYO4d6G_$;vZ zp;Rw84PDQ!(+JSe)KQ)zPSv6c4OR`_5n{H_J`6HvrqmZ7NFIn}oNzy>+ckD(#0@L% zJ5L~|kLyi%7MvXH$aqeo*lGDgpLIBlaOz)<XgykLP4oEOrNL)RaOZLa`Blsq>%wPy zF0|Sr)H2K6GRDU5ocBk}AgY=B!>;e%#YrHg+d2%0i<SCzaTnC7A1sZA3L}93LzDpk z9C%0|^#4VaIghds>9n@i`cp+R5Zwv*KSbGNd)5CY%GM;b)Y;)WaEy#U5h`8g|4o#U zQtct>BS>G(Ly^>)MNKIK$erleyAD7w0dA_}{~^krG?4&3fTPlcJ65M897q^yMVq5u z5TN=P6?T0${%@j8asd?sCI)R&9S!LbH4(5ysUwn8A=Wb<vaR03TDebY7j}F8cjKQL zsnmJ-fH5bkR0Io4XChFR2G7w5q-+DotU=}e|4o$Ln{bvu6}f!yvO}$WfBOb#%)9BL zWCxza?AH7*qHHj%Fp{WCx6Rol1h~8tLp&eiAO2=LLN1?7G`I#G`i-}CJDOb1V_sX7 z_BN+W!li)5(CTMLV<`WJD4RPNA>qzd$c?4S(cMkrj{6^?>}Zu-e%`|+Rbi{vB~5nf z|1VK?yr1XzKSWus=Rtu-b=^Us&;Jl*V}ggpK`WkzCBX-Eho#|H$A>Q>iG_}E7<#Xx zvIM^Rqw*BFlcNf(w$O29wx!o`RlZwcH5l%H;#q@xCgfFHndaqHS6eCs0^rDb0M$Zz za}n9tAtoaXbPIt|IsF9ixay(ieGSy8kW3?`6iId?QVG}|Z8w!$&}{WI-66_&M}YP1 zBD6OcV{`@J&B!fdJz{SoG^(k<M6>Oylc5ABobKe6aCN^!FxA+r|Fkv7{`(jwEYWk5 zM0Pq%!ryp0LN5RLbQG>5a)zh9=X3U&Ho2dO=3<@2ZJd3S<vi~TbH|D9%efOTVz|mY zvY~%$=43|do#FRcxx<w2b4ovEzQ0j}P+ZKbGZ<YgX!A#0%#e{_i0Bs6SP#JT*2rNL zl_RzjNp0vqOw=49dPPKQM}b@;Ewjh26XeW3Nue=x9G-M)<?GZxCxOao(YW6Dck4ZP zp(0Li^(VqqO>HIYY6GS>bd7@Nv&pSJ{6-N;WNBbL|Bl`&4ZfUr-w~97CPeq_Jn~{^ zTXuah_=BjsSxHHK&_PT=-JU~GoVxah9^eyjA0dyTznCgoCbpjkI;dxivEVc^o?mO4 z#=_Ws3BiYTsv+@uND!qApyZM-4`XP~Bb1mB?Izg^-<Ya@@e0{(H<BzwSm$KXrmI8% zP^Y&-44QF+TUwq#>o6-Y14KIGT7({WM1mVfWMh_42#1Qu4~4{$16E>|T8kqvF{h!V zS`c6g49U$%@<C`FE$hu@h%V6Z|E!%5^4XDxfFmXfEqZJ20#-Lm5(O=EiBEwZ%njHy zG3ufmgWvs7@Qh#ewxl>g7OqPu0?B3r9K-Lka`3Qk%k4sW81$*jkd!F(s17RLZZzhY zi-;iFN}R@(;6uYuKI6(DsR+CW0OO^w#;LHB9H8iDum)B{ZaP9!eHXPy@;bJ7m)2Ds zLChA@yXIStB|75*6t2~FOMKu=0Gm}NzL1Z=F_GN!KJUVwI-{K1!>Zx}6w(T=P5@v! zZ4od|kX-9)U;UPR-ojdiJLAQU5dfM9>L(9(px;Y`TIUEyOpJ3nz2PJ>KghdSHNwwO zggz=les^Q&ZjgnQ015?&1_f-33GNZCg0*7B#SJ*1R4>c5IE~<~8#am>obb=^$dvRp zu(x-jSTe(_p;R}Y)UJj7?URP$Xg5g??GU-QQTB*yeIYtKTTkieozCssNZyW%DzQ{S zLwBLKg^L%}a<hWQPwU^7o?q0cQ3#>qg_g>xFKe}%JW20OnJ0P-KZJ*Pnbqho*V|my zTg}#6c26xghh8=~QZ!hN>#wvIUN(9dHQ2nHTIuS$Z1PWSushU$*SCJz96a0L@MG%T zt6!Hbkra)N5QEhb=Bw5Oqef?j>D4i%t2S(Eqbt9`+LX;zd%it2h4l1V;t>F4_}u6* z?KnsSMp2N{l2AMcq9?AkI<lLH_&`83&CMSi;&H;LZ-tcYs`iR_1)PM02O7z>H;kxe zOc2ccv@u@3K&Uq1%bJOcliIri^8rW+6-lgVc6o2wYi?f)7Krc>iXvd%m+f)JCK^L9 zka;--1!rQSXi*40D~!*Mvh@r(7|eGHptd8SrgoYCW#=%Ux=v$g(wu3xD8yX-rau_d zf*Fz-F=EJoBuM|e{w+G)1n6%PAe(Xc)_nkiII$*21X9D>5*U;ScE8-JtqHCty4B!p zc?zOoV~-Wk4AA?*{BtmR@LMXyxxL|uGj;g9mY`w4q|m+I)_I#i)E{+H`%@>HPGBe| zFU<9amtq?ZE0JMs0$HQ{c{A+)?9@?%3;@w+asWuyU=6CxJvVg*CgP#MJQjC_<hA** zFPbz-r}48RSHloKT@e65`puzz`u^8bEL7D69`>srnsaL6m67~6^MHk*<8#rz2%Ns# zYNA{sR+NWo|E|c>Weu@M1r)UjGz5r#E$B;R+D@W=OyOdIsLTT{4bpo(Tyq-F&bWe1 ze2f`>ty8<nqSR;X4VN<zd=p=Vup>_YD6L-;)Wr%E51yD!6w=;##Z&Xx$d88%Ka<@o z)9HHJsKl*BUAg^T;8Ya*&Sqs$gI>>KY0%RQVMiOhshMr@nUuxl_wGBn;A+>O-pUM> z-O`h<+v5M6O@+Q218)4aM5R>sQ82}k=Le%aPgIUz&wm}1K0C!qb8hKRYOr4oeMbrn z(^!&Yo|iwHqyTLvB4~<VDluq@N|?ldiQZi)cf91SnS<C(6!j{=!UQ+N^h(Jz*|LB2 zA~6ohHa($&H4;zUXUV<qq2JRl%Mne&BEB+s=hHUGNdYJJekK@amVM;!%Fh`m{*|k1 z&ALfgr~VVknCOXNE3il<6}dh6z^X}n2Y)o@cRN@0j~MZnUEj%pF&g}3QuN<kZi4fy z@Mzi!__qwLX?y!4XPV|n6l`4rquv@#SMpzY@yCZ`iJzh;z8en?m81r$!Z2s;Fv~9> zY~q(Zp4sw<&>Ma`RYGz+4l?>d118ZLb9+sCLd5Wz-^+=iP&#k<otjjCukG#f>*M8W zx4;@d#YbW)>p1G($cN>!9yR`9!}AbH0Eoqr-3IK&;N+9@&|V3sZ|k$H`4FRf{s5Nj zF)~7y-=E>ozS7aLvQ_;O4PVXkN?TOj`T=Jir>cek<4>$zv>)JxoDb!r`sSgJOvqH^ zNxws)<%S4j;p9ySS6j$~J~){egLk!mASJ)QuoY=dWcV-iEfW;|jv+EVnsROo9;O3N z$589JThFgV4kJjYaQ1+s6S&OZoZhYmM|Lt!_$m*ozC!B22X&%<+}joQwKKXG0=(aT z{__S4^OBGI7VS4aMk6ah(m5aJ9tSshM_K|We<%Td^$r@DA5;l{UX2bArY8?O1sRdJ z)}YC#?~&5gJk`j3Oz7_C|AZ8GO7UwbI9)f6Q^P+$J4p2+oIW5XM=RyUP*QmUCP5A^ zec(WT4gDSum7B+uY(E?ZTsC6^udn<gk75ttw+FbeJ2g+Ftn@~%f_}L93COuto+jRA zPhU8Owh6d_GlEou^>Api%2v#<e`vJ8qm#JD-x8h&FHtyNCk#)hHt{1r9Z7~k(jlCr zrLAEQNm5xWYYn+)v5thpKx)4S{A;ksByU0(BB=&R+FlD`>9TXr_lrBo1mKiTH;gd= zHtqOYUPtZ;bv3ap4no@FOeksVBu6q`p7Kz@wKOt}MdDFpLKv$ay!pVPf#G>6Ns<Pf zyhP$z1Tq1)P0HQnMPvd?8PD=s%lc&M7a;e9?SMoH4o0?-hBy&xI}+FKdxyf^*obWv ztH~rJqDqEHEehb=ad7BiO5ZkV6PoO?qhrmsy?A%b4xIA9k<z=jAcI6C=BnU@UIE*c z`z<BAzzb(`bZ6&>heYbs<XK-|#R&J>n~d9?=I21qpf3bSo=uQeA_6)AFA5!3!ku8M zg52WXtoJVkL@;sP*TwUmKCTC(y%Ho^XpwuT;&$_3yGZbw?EOuCo0S_YvQjum;~LsZ z@68aBoNN9hh3OGS!8H%>y9fXU1qFl|#VS7q%HyyLKVK|_cz?4X8$c63riJucKq3)v zEq{W?*<^*f)=>FpF`i`inV#}PsYn<|`<UXN^+bg`lGV7o1oKcF_*265;Kg+>rlA5Q zy%~)0zP}ReHtB4n9PLSLz|+nICT<yNyg|fg(D2oqyPl3Q+SGX%ObXN^98Uh?)Ly8I z;=TWiS!kGWXq70lz+r2;6-lAPuPOnZh^lR`*NY-v2tuz@2tk?C!0of|W4&8hs0Ll? zFiHBg%Twvve#DaMTqnIefsEMmiF^TUA5D3k2)F8cfeEbreWO6?NLn2o7x>#M8yrBu zk0VraBtYOGMW<22L&+h1Rt17_gl##<R)~g2&5Hs!+hl!j9&}Lx{18r#?y3nMQ?<5% zC)U?SjRao{#`V67Ne`|3<Qd(ChK%Mw^dbovae$d4SUb|57fo<<5Aq5}win_NOBYk{ zGvPKFkvjx}dnLpjR%m;`J!|2tN~EO{;230R5u%E~sj7FqK;&0>%<gl7fY3eClAqP^ zMmN$@fAWw30=7s(EjYvr2f5AcH7;Wc<{_$R0+nrOA2x<b-^!^Lmc~G?5n11(;LNmP zYjOx*u?kodpuhl>zpw=pYw(bl4U$C-AtS-JzkkZLZD=fg$(eg**?d*?X-sb`A>x$q zF)mNWoVbXHAbf~4cqzmePDp1<R^sT#%w*-1U+|BCa^e(J4X+7c2&Pwrve7?n;iKxV zA>)9<R!&KOMYfPRwfycacz*t<!Um=gMyj3bOL<mYcMWYmjYI-qf-+(Q2#}I(U!XvG ze=Q_z9`q1Fv6A2u{kq|ngx$izf{@Vn+le*Xq+R~8$_j8oD3Bl2N##VDd+W#hL*HOw zN7x8bszfQW?x*LE<ZNNTaIj9STZ!D0ez{=XEC1=&$-`)}BY9{kP)Y>y(T#)#PG!{0 zL)E8p-t)Uqo!o1!>0de}N_b1Lc!T!I&~arucDke72L+L8=}`g*l4v9>2M7Czrt0kH z_lBkrIlb!BhR0jEJZ2>4v?dW=A<grTR6YyW6B>MMMfOmFpu*kBP|#`@3(G}7&XJVo zI9Ty`&>h<_lLZIu+-C9x3g9&Py9Dg2m3RqG@lg3crJr!=jVy1^|B9G`0LPjh#^-PJ z;4mH6%19`z2ZRx<e9{KJj=4jCB3UIREkn9?leib$KFrTUSaJu$E=MkKuv<P+xu77J zk8)!OZrKP=tD!u>bspnjM+oqTQ_@NF?H2^Q+HRt1Yj{%rq)4&e9d8FcE1u>jebJNo z4FYrm54sR;&jcB&Z&>WC8M>YgIA=K$zAS`(i|xDT1N&D4n??}-+@`p|7I@{s`fXnb zaK=eqQ(QViqXAeBvK9{NPPE~_7uqd!k(QnC=!N3*<{?mdZIQ7Xwrm?ZcV+J<?>gu9 zh<p{=x!v~CCjTp6-Lu%<pW6^D4#w}(8x&5hG8ufaO#vWDqFc#ZSo-Om#{Ja$h1Wv~ zq6!4Z64!{mD^Jr)v8fXZ!5206JFJouR2VV}pBw#gTbBj<ZdY#9!<OcWyjbIU`e#Mj z(*7}wdq<MzZBKGjjZPl(9fdCta8Ak3jNgU$p8tS;Z%i!#g8Pu(!*H@s^dZ&Cwk8>Y zbA0Z@MDEa=cPZ^BIU82ZAw*#*@sz*N!&loBNrnB2dT`q$YSj|h^eNHScGuxhEe+>O z0;hgQ)Ba<DFb^K5YhqkJyn#?PhxOQ{&5?}m>CB-r>4-LIQ{-c-AO3*{ZMB6^oTFp- zWx|~w6t@jS)9`WehT<lMI2}>=_Xg_kNXlOTbjOgq)quKfhR?Djq5|vIvpU+XOFAn6 zu}{?TuO^F-@Wtlk6Suh#2DmP)l{MFr9qILkRCQW!4(?*JdPutu9V0}}=0gU_(@!U9 z^!__e;bR(X5Dy>CmU}BB`XZ`$Etl=-qP8z~99{+l9)u+i%0ej(JGp%BrQBP+!v;Cq zo{YFrrB!W$-2!mk^JM43{R2%4uIC#`UcDW5{wDFU`s<K4*HDWC(kIpdU)^32pXC#l z1t{`+p!i7p9HA^&GH+kf9_xGgwlMcr@+<$5i~0sa$yGs6*!%F+XRTx_NZ65oasS_` z!3e(N@P(2!3gznV0PP1+BAGh95Bt!N2FI1Jo4zIszAf6Duy<t|2*_dG`i=g*3oL92 zLA;BA{fnR5rbyX!gasm@EvL@~qQ<?BHx9z#)1LXlB?(s%q^uH9$q?@gerPA7Q=wJ+ zt)tm_xYBx?YXIK$p_7PEbq`+$@0`931b{s_49T!7sZ8UPKzY_maqDs7aj=UU`0jpV zaV`rVx7zY$eR0Y=igB!)D?O>=0Vz@<>II@EbiC4xF@g+48!qDfVkM^WG_fWkY@R&Q zPnPl*?%h#jT7>bkbjJHVM;NwshwUL{k};L}){%W+l|=t6%DuSSz;)K+HlB}VRdltB zC;KS;lv~n+|0$`WC0XwFkfZPbA!ksRv1P#kg&BfUZ|+E@p<HzM?bY^Mk5;mm0BjeC z`H#KZ!eQSoaKEd+Tuvkqa9k@EO{(%p#{PtsHEg^1oE(M0>wh?!d?xmV9}-Y`63~8i ziT(5w2@OKSwj^LZw%;_J=I<lP<DV@ZQG7mW;>ADwHbxm1Y#GpqBa6K`1#J*@5rn-d zv(0#@w66T2HsH#?F%sH01d7Fyl|0KQb~>{o3S0lX4Pf^=jbGMXQO@>Ke>R524Sr&6 zcIUr8POmy@+kT#~zH#RsEYy;;v-P<4OQ6}k#~~1^n)yeDkP2Zn+b%ST7@RC1^xmQf zcmsePV<~Bx;Za|xS8HIq@K62QT^wpHi2I+N(|LcCe#QQ~3?vKsHAI1%AY6=uHX<Xg zXCWocPsz5%na3B2c08T03Q7?a@bvZP&`STDvHqdHyLVyYUj2Tq*PrsQbGISgSc)%{ zk@j!k!)o2iA-owa<@kRiDdVql0dN3&&D>Q?I09<%xwguI+Ucg-4%I?-q4F@0^`2Ay zb@n##`8LJX_NSgc_yXd$L`FeA8L-qydWhI(G1?ILuxir&2LK^)D$zs~1XzA_nR?jO z{4pU{lO_MXYU9Mk&f2@JhUN7CtMadM$fQCym(`*^yVeX)S{B;lGLr;OXsKBX%npr9 zRU`g^naz*T<yxu4oq6AO3hiZK=N(UJJw`*m18C)!jSQ+mCLkFf1zLXfm<JGjts={& zH*K!d^x&UYo+H?Unc45T>1p-B1b0%Wg6e5r-0cL4g?g`C1jfn$8L?x*{35yceaj6D zmS=8rC92Pfo9JH-`kKuxRQ!-}=LIg+#h1b<OA!VwH;u=(!uRCgzZ;B*Ut*J2@WVQO z$(Zg=PE!e}1%*>v9X{YQtJVzpyxDVhX;z~f5g5x|taA9@><gV2Tj3i0-zSbMD*4$J zL!X2>Ox2XKD~35gsZ)=?1DsEaH+64D8>kXhF?)B%QZuLV6L3&F7lj@P!U20?>&o2B zdgVF+H3`lKJYN_;ea$kCPSi>b9-Aa@Byz88(`M1SU0|bbeUIXx^**Y~AZ+s8hVZ#b zUxnppS1Eo7M|N^!@v5}@ort5=D)wJ+^>aqmph+;0U0MHtDoUS9k2j~@r7p)2pAjz@ zu}G!+lJ6T{`fkVOw0olOZXKzv>NIEwrvLDa_y%~SutCAUd*OPnhk*xOER<~79;Ad8 z8W^#MZG{lAdRl=1<)~(sdfr$&P@-fuI`DOl&qatwf$Vu1M6Ly~-+Ax8tO0+CUoIm* z`x1CI5lzHVPE6q~w%}eo$80ozkGYObcd=B0Mu$W3E$Xl#;G&m@Ib!5k+YlH5<CMnC zO&j|%`$n}2ADvCPkADp8?7IKFK&H7YUVv(^2g9s>#jW+q27X`BybaIXpw|9Yz>DS| zLkBUNPmoa9X)GQVI`ES!G9dAo*XA89!D~r)I_X#z7EQ;SZPo?le^Glr?VjX&Zr!_^ z63@5Z9fy~Ur<MnT$Jt+Ms-I{0NEx==2!*vy9b|?)vGD$wmP|SODLL<=j&m;;6(fAe zPF<7fcP?049NssnjYAs><_Opa>XY{eno7spUV|6nSzBQ`tTHq6k~(SjpY<S42B@jR zvC6s0aq2te$FJFgWoXuS+xYJed|Hq^@C@*Kx)3iMdr{}=75ASPiF|*mS0c>f-fNaf zN5*H<ssXw1!;Yq2G1ZX$FfZN5oOr!>_Q}WPg=2qr&uFN<r8YhXE#=)LeoT(_^3aXA zxYP~}8~d_PAAw)H{9Wd?<HBib69NZ#D9WdbLU)sOew|=cPU%`B9qVr0^)})loLeZ@ z*_1SZYh*f`qz<Yb=l0monNK9TQLiY<2E~}xy`_lN|JpWAJ-0B_1VVD){XZy@tTNdu zxN)9gsjPY8nbZ}HIZj&BNn!=me;kd%RLWs%>LZ0~q6zVrr=wyCC~_Ogsjy0xa@_%j zk#e3Y+h{~_2W@nke)vPwA(9#xkt}W3tP=M4l%Y1WFf6jtcE3=toCD~n^17_&Jeh~c zR^N6kU1;6&pknFzT$?4TU&S72hif|m;R7so<?IWbRz32Xe5fipxnDwZkEjN<a;bg3 z<HqGMK>EQSlH|vvnQq!{n!3e=cXrMVxs4|E^dnAh&x7{D=8-hNwhv-UMjv?W3Bdgn zzVPLq^H}rc*8SD>%X@dTN5_5`K*`xCVRb%Dqk3SH?kmC>v+>A@(&%uSf6z1mVK=RE z4jQ*4SY*zr<qAE|(tGdUz#eGIAxBhLQ$Zod@iBONe*5rt8)?c>pfWWkux#K@z?<PB zeHXewO&=CyU@WP0#5)j`=2|*lvZl@m%uC*tVdb|AV)Zb5%dH@BrJMMae2;cMfJ`X2 zBTPTZ)TFs~B1!7V+Y@^5lf<OQ?(rx3K_F7$LJ%7>(vfGWPACo_^$VUnM$I;iYk*OS zie(@3o?Rp<fE*JQ@S~ZRR<s%jFOzciiI@^rA#J*trmTN>1q&v~8S?}k(U!WPiKMX~ z`6OJF9)kqeP2H%-?sK<TUa7RtEX$=i!XQdbEp{EO1fyQ*;^>do@qbgUXH3lp4lF9r z?TlL1!nB2?TpXt^`CLJA?>?O7J^|N_`+gtJ4$og`AE!tSkdPkdmf_b{&BzVV5H`5w z3@9#xwPeoA(oT4f8{5AmdcQWvTa&v&elVK$n3p69(Co6!UD9E`joS5|!$bmKT10+! zw%EIRC-A}$60WJuF>6j+_OuVJHix7L6BsFECY!7Ld{TLKK!?ITNcLH1pcnpGmb*vN zKyW{b<-?qZNajm}=H^P$38JO{#4X7zupe)+r1O_zGc+&E+u}ksKT_KXwxNG2?WCKp zPM{tnJNVs@)0)eXJ*zcAbQA_Ry$U^d`97~xO)4+R_|#hH%j7gwLE(G`+-1tJe7qV! z5W6mYq+V%_4}Y{~d_V5AT!;N6c2xP*8+fg)ha=mcb5wKPWUqFdT#E{rKkmVi%L9iv znV$oubdPW#rbj1BJ2Kx(?Hf_}vl4o{xD<EO(MLR=Rla3rj97;rRWNp+$5~7~NaZFv zrq+`)j)YdH`;kj5{^u4b6npw=F87D=3sxPqxVrQ!whOE_@6J1YRbMUo+nAN*%rn{n zasVgAvB22YaqYdBwf;17bR({UgTm*@-Q%gvfiLnF6m=8z)c3m9YFY+acHB)jKIqbS z*1dCPz1a);)y4QLj!V~2=6CcA%(mL=>Bjr7aXeuRfeAuxDNX#tOhO!QrVj7gHmpC- zD;}s_v2+JRJgUI&<bJX~&Dx4)R`?0^kbKdT*ZTmbXyvRXKg-B|%&8l3G%6>w+)Y;% z;hWW;d;I6$jDY>Di{Ev6&9{#hy=2Z^!-KFx#dt|0L6B;<NDDitx=odJ0gs@mYBq}h z?F}hi`QfU?b^-c9OmmO^(cTj4;1<v7qgM)H6Q1lW-{`WZ3$i^n%h?nDd2aH)aK}r( zVb7<UP*8rq0Ja=qIXD$8MZk)qYq^KKx3$!Igo2aqt3|CTsPAwcuI)u+vXfPT=eK-d zMU^-7`&kgRV5i^rTi_E4&mD;M+}Ye6EOyxfs#<fn8y*DCRImp8Rr>TmiFtOabS9n~ zi<B^D4m%>;a}GD^h`N8Cp`kkFm=P*D4@6$<v;7SzFZ82Oe-r`y`n>i|ttGnso|)<; zs83lxiNN}WdK3l~Qx+3i+hriNWA$HkSYKAdz)w;Y;kN#a1)Lz^5K9QD&{<qFOWtl) z51=U)9|bm?Mmm@b@Xp8A2lp;)G?3zlVY|F@Llt}5k^vKtjZ@ZBNs|8B_&|6(x32sQ znF`%S%fB5(3x)WnN7)QBStZi65!VWWF|AkA!#x|ry|xJfsF*$JJ`VwiG%45pW8s@g zK`vc5=C1-fKSqXrCZ4CT`#Gv=5iJ-f$-pu&EMBbg9hn-Ay)&mDcTYeJN=}XZEFV%! z8i3|itkhu4dS$K@<LlV@O@q~1iWR0@8}489K1qd~R&(-qO41JU;mbIki4<9L_DB7L zp+lL9dVTtK!=bpi)sM8om|?(H1@1jSYnVx<qQ$KY6OrygY_jX9bQKA(yz%NZ4&&g% zYweXMm1PY(e6HBnd-?E8!A~GQ5F|^Ytew^0=y!ByC5rR$?KD1+@jF>f%ezw+9s9+m z+gnAf0a+CDF^|(L-JH2Hr;p!Vdi+tPT*X<EV}Ps-ye)iyyG(-QJCrFRLG~s>Q|#X- z#Tdn2!om*f$~GXT%)>+p10LPmZS1p+BiH9(b;hR@^loU#caG>zQx~VIsBF|#Fse|B z^kaO22Nb0zpA)7gnP|t)h|M6z2+nEWgr>JqLjo96^BVO|cj!Zo6hk};Rd|^HO^^JT zAf`}i&1BVo{++_fCeAmKKDej)?^}o$E#&dhV0}tm(I!#Qs{Z|sT-9QNu!Q&^67?^c zIv&CXLFB2|MR)F1>Z@AoC!uhmm0XV_b^A7XXGki=fo#KRE}=;(=8E(HxL^rw$%y9b zd5IT|tFazH9v^Gr@FrCFWo8mj>+8xHe3X<I7Nv5Vp=~pqb?yug9=ef!q-@4B>lu~` zY!KZMh_jV|yc6M#hS$78us4*=uB#NQSH_9uqh=eqH%13XLJ~gL%Z`W`mw!$<P3D&1 zA`Y+;F*`53tN5ZVOXw4xuc{*sRj(GTSu7*WPyIIDrxt_bd2?<!QR^)v2?v|k8{<RB zjK9m&*`R-E4$Y9gq_0f>n>2sFK;|DDtgE0*jw%RbH71ZXd_7e0BNEIx5m$dCG#8#O zn=rHOWe6o=ng5wTfK&}upl@bno*{_zv5J1!09*B}PT(@R%F67N7-^*@&_Q?G+Eo^i zwPKI;nBUJ(u!&h9U|&Ue3tz^!u)_UnG4;#~+`OF<dnq-=1UHW&UywhTkM>XVJ&Hcq zmJ*)jQp<?3y*3b&t+EuRsA|ppECe|WH<Ff}<Jl+wHwt*w#w&dhnka<SwJY!Wn<=Yy z>9O>QD?s$tjh-LB2(P=P;@BPfF@88B4cR$kqC~Fp7?^k2l+-P9XK+^o;@x4sKg<nS z5lbTEo|!Bgbeb&PZZJJsLKK)rnWs-t%cgIoJ6p+yDv8OhIQf>|3|1unr%uVcG;-Ky zVf3A}Ke90t87F?K<G;UvGicbbEeS-X<@Ck6!%ZI8Te|vK?#A#UZDM3`|HV_2SPk%{ z5lBQJ!1|2wYo9Is=rTioMLRUDFkdDG)`}?})vAN%Z_ZfDLYgE7*2!l=h*_<O=e<|= z+oX=NO9R)5PgJbp?Jev#$6S~Mn5N?wz05-+<HLKDnEI?z9xJ7$w*3$wR>u)O!i~6x zEs4gykTQ%{G+bLWDQR;~!-}#An-D1_#6Q)=1<yltBrN)*v`e(w=Wr13)!0TPgnoIb z{BdD?D>x;2THoI0lgYhY?s&ou?uUu-;#PVM!3m9t(opj|Ez7*Gt?CSVa1LKuGGg(D z7TI;-8|7zn%LOQ78Qwe7tV+QgCBv+!99@!Qn-(pz-B112t;BMUYz#3LW|i?zaaA92 zS!097k7ZT*?0M9FMjLSRMxYG>Yz>D7xn8%D-4J;pB`1jIM#ybd?YH$21dVF%R9T0e zlKLap_atA`{iXH(CFh~H!t?R{5K(n)tM0w**#Ks^sis)wmt0;Pabb$XfmXT;6+}k& z!>IDTmmAr^0;Ae=3GqEdUjnsBH@7O*QvwQzoNMC`>oT8r;H&?XZ;tX@u@#a9bjGI2 zPQI^-8(Qy76<S)|kbG|^{^!FScDbe<f?6eX;9fr$C4t+<#qQHW<`}2#c0_+KkJcrH zP9!mPBn7ux3!Qw>{QZH6z2X}$g-qo9C0qGl8oo!84h&y&z{zp3O=<|SLaueHYHAYe zR5nn~JC0oYitSDvfgb6J_++r$kxX%0r}GWp3YsMM4pZs<)8RR3M&3)w_;i*wslVHE zRvZ!Ab*RxyGL)k(_u37QbD{Z1pFq_Jg*fpeJ?^iXEmn1HN|aIakc2^Nl`V%k#=L=P zDF@Z~x**qT%v*Dtab*?P4t@K<R&YRjo4he=>n~E2mm*VVydR@kaa9BC$$kc6*$-Kp z9=!;*Ea}{rEm3@+8r3*}jPX!#6jZBX@*cK&Nj7tK%kXciY^^r3)y1WVQwDBuizV>6 z?9r>asYHqFF;));9y}iwS!|773F&|zeDEGy4Yf~Z;MyLzt&Jt!7vV|>(#>w<+QJLD z^9?8e6DHPE5}WUBqN)Z@FyX?l<8E{u)nJR(s<{?^{-);4>{qlk&ziY)o0=6?8L(m= zoE2zHF3%%h6Th^56luIYXr#d`p1NOJqtm@kH_1=HVuvfAfeDc%hWPk0{y!)L5Eu=| z-hZxoOe!?&wEmVMOVXxYS1c?+KKb64*T?3p45(DrfK#URp9hEL9sd_o=lxIh8~^`v zj=jz~j?FoTV;+0Y&>4323fY8^%#5gWj;-vG>|>J(Ns-F2lCsH2a;y;VjH9CA<MX+F zfB60fuiJII#_M`s&&U04abnxfx?bOzE9%lYd!+bKx<Na|_vq!?r1<FE{8|7Z`6LEn zCPE(x6``my+v8HMM+QBs=aj<>Z2|!L&sq*|3H4k@q%eCSI|E?JMq_D3X1@e_&@0!q zGCy9`GcjcPRhZguw3}iIP8I*kC*-HyYWP@y$+&giRbhNt#I}&N)%=0e89i?xUEXWf z!HzGM*Wc$i42E3im#tRCFwS!Ar4GMD>Z>Oi*gw9F`e~|>?Tye82>L0<{JvnLSK&Wa zTc`eG6}IZcztBDXCB5z2_1nmSpWsZNL1Rpy4>SU|{&!v7iLnm(eV~(RT_IZ`h&iS) zb@4AMLz`*w=6BrRS9rth6z0(oJlF<zy%p~+LO*>L!hdU?;UhAXKZx0R(6ir}xj~dM zksAR?2|eP!AMX6Xgd6lMOnH^J`puN#UQ$KJW@yj9;y6s{@;~*5UDPpe=9ZAqUzSi^ z*_X7OS^ur%JsC8~CX5HZYm)3?{_Wss-<IIwzmYDtF#)45a`^o_^KAL^)ta2y)|Tpx zDW=M<oFMbf_<beEPvJQG%RPVjNw<}&|E0tgg91Z4via{fWEAbFb?VyX#Q%CXDI*G~ z#tC`UBFw6GXAUp?<oM^)73&$;wCt0DOFf~f-|F3=LA7XFALF26Va-ezZ31-Em^1A( z0_SB+-yFS_$D6E2a6Um`1A|FLvq$e6nZ6s*&_|s8S9$akwO-~}j%&X=ux(TeqYXrk zuUza&9#HhCKza3EdXgW44X3TBGPI={=gjJK$q&D}c!lZfZM_wK%l`tuu)A96*Cnep zx3VsAH>|N#r&e$MSAjWk%;8IYs@C0;(qh}j7-NTPd)cd^42?Y7@%?$W$qVTH^m5|n z#zBLeL5GT_oNJbJ_GP9M6=56JgP>jEIy0Zxuh_Z#W<^iLN%@PFYDN*X@q}sT=lmuu z)i;38^6}4~uUGuasec=<m7>c3H2F=`EhpQi_Ku;U36D!Mke898N^dSX3D-U6t$E2I z5FVSz`YLEiv2KFtfkP!(@jv4!Cil=`bck8g8<kstDWmdYkvwv)_>7JWZEVs_^QQpb zZ}gACH$_qSzlqbp%fEl$3^wV<wU?OxJ$V=J6O(<X$1UCB;zVB5rzi@Ocn7&K-#>N| zAl_*e*V+&D<*$8oP6T|L-NPrkG$HTf$o$$|bK<Ru$zFai`pTIxN5X1Q#pI1!)0t{( z7>)?1){ok^o{0R)@cVT?-yFm;%%gC5_d@)4q=<f#xA41PNZ|yh{4aZo<xL7pf9xAZ z$CgKzeg^<cfKwqZUakqcZC?yZA$xyEt#3_f&Qt7;;|MXEOy`I);Js<%miw<F=>9)M z8F!4ON5|#UnT2n~iXM7#{By-(nomUkAEL~*q9<$h(1OeetAGE0h_dY?|G~H&8V_C7 zxDcQWb6<sFF}F<rQt)BI^xWh!<`#pZ;dDc*^nCfLg7Y*J;2S2+dV9C}ewO?Ei}1BR z`v%K0eJm-<-SEQyA<85^UU>h$@%dSPBH#NxlkaY?RcCfzMKzAQ)WxsyD_S;wcbE%9 z@Qu|N@0sX_(N@Ak_Tof7#QDvw<1ati|8|ZjvobfHL2EDfUDioy&HxhzoQ$ui&0qSm zNi|pWOS<i_a=oYE&lcBPSDlzjr3+(6^;RYtkw@IAH@@qK=-ld=*b;kts&^Z(u$E3{ zT+zoP91b%*PP*vJMg7z}1a(f$+bnc;1+=IJTJKaL+9%97lZ0*SU#K*m?S8iFKa%H> z_C>=$fcqRrWUl&sr)W{bidWtiIF33x9`W1jK3}5MDwwAOPvr2ax`ixVzG(&tHp2Nm z3HDa;e>d=u5Oz2ElFK&w_7n1F0|7iDS82gVgBqtxn-XaV3OyImcs|mR7`*uIlkO>v zd87QE^79(~=9Yjdys?|Db>*mYP3~Pb>@&86W+1<Bb^q~fm3zEnx3oY1l)>orWAxy* zYu2Qgr7o_~t^|X1H~1i5A`zIaUsz!1k7s!2m9D>~WGvm(N10hs38HoTwZ0qK*yb~Q z#Mshqx$tz+{I+$qmCk`y?X16B!r*4nvQ9^d{&1R2Wzr;x$u9QmRj%>4ossuk5&WQu z-8+CWwxWa?^GR8g<e}p6=Qg$txdCf_{BISuieFqW|IIoSlHxB{Gp>7JD5w0E2b(;k zg4+IcU=_H%#w1=c>yxE@1{|sxmmlxwQBG4DaZ<t`@t-8?ttQPtJH+n?W;YZKa9Vle zWaTFVtf?;-r}W#*71S@y7+ZNb3vDo0o5wk(Yi_9x96EPv>_!whPr{F_loAFG;|_x( zhBQJF)@}5I6)oIDJ>X)HnYbf^y?1krOn?Qph27ajMqYXsZLJ1Ft3>0O^2aOpDB_EP zFM|uZmgBz&S-h?xEl<VG=w7?B==_RZkdpcGtMfg-N%OjjrQCeW)dr@U*X+ZGk21Gk zN8cmsdnCbM9LPVocUbsHvDQlCiBhb+1eT4PtOse9PB@Bq)inM<^%(hjVB_<*-Qg`e zZnFMNBvHX&ZJq96%NZ(#&CTHT^*KcQ(oepdv3Mk}-MDUtRIkOeZ)~+b%OGjo3pe0O z=%d3+xI>D>J8FZ-uS@eU(Eiy9)``gCyCP2LqHMP^Dq6|_)iBebn@fR8{4Eh)M26=E z`=%uRN1T*(;pKczKXU$0>&5zIy~%9?E8k)x0(&si%haiu!A?%qJOsW9W9AI_ao732 zWF)6?yx0xSCgV{46pZXpo!Hk#V~bTUBMlX(v}%$FV%F$c#2}lfkK9^PulUpDT{)!o zfCDo2P%_rl09t@Cj)W~VFt%IevFSKa)i!blPeQennhp5Hyer&}Su=`U-?h@(?%hdP zD~QhXy1c(NayI*mjj+NsyjE=k{<FIevlg%Jdc0{?uRDbF#|#y^Ykh#c3ypOs5I^ip z6Y{kA4x_&{u6;-;{DY;xd+O<=%lzy^Wen?8gy7fIVmhvH-!|vdm?FIl|G{ieV~rUo zUf-#%Gx=OgJDXk`*=xZ5PdlmN%w~hnDYCTX9k?7qEFCLqONtlYj0cxPgW!!KsjxAZ zc-9ieK?#JV<p9z;w_kx>p!e>kf%1%2;yK64s%TT{##lj<uH`#;?o3`3-wf=>p_kdv zR$`Far)zo>xy|u^3+m-_)Ac7-x>9tW>A8gkyi)PClwf$5`B^4aCq-;nK|$Pvu$Zrv z>N1<sdsYjlJbkOV+wS=1PcK~r&v4vos#OArP4)yJq{ChPu{D(K&ewnd6WV0*b*1CS z3S=Jj2`D7aX{POQQxXOc#*8^PgwaW7U}R)X?Hu02R<&GLPtPx=j{dD-+Y-82E+UQR z5y92{F^touOGB2w%X$uzU<~jHz3ps!*n>5E5s+^rFRIus;|sSfmzG%=Te$ziS5K8; zo}t`y?S;v=utu`vT6695it0p(ok`=v&Y^ogF~bhqYIZt581TpQfjq`sGxOe;l^C`M zF+j8Wy@Rw1#=$bTB=Rl?I-#^j%v)UtB%#u}zC3{a986B>u!zkb`*d7AM$jJd@AMt| zte9GFaHw1$QG2ZpT4WNO*PN~HD%Yaue$RPV2Z~Ut<&}dC8@)A^mlw<u73`S}l0kW< zPkiir@k-gu(;Jzc@#uy14;JNkksL0i0Y(5ngDhkCdk&95_`x^abzVW`zqi*oe-Pe& z|8v-`#Mx2h*I|6USJqwVd(o>9nYsKPpAFfI>Zl*gj0(KrAg({2sAv2P(y;5<%F~lo z8<V2qtqk6z-r%ZoSJnvksJl9N_9p_khhq~{UtiYq0-C3dwH+-23b+Hf0V2ub_HE2W z@&31fVTM{$;JI_r2UY#7x@q^o_PM7;5XYpS#tzV*vb82u>?V|I*ymlXe&yr(@tGvT zK36>ML-fas0?BAVC@TQo&rEmHEAEQTP<-;cx>n-QMq%Dz-2Q9p50mRPBGoSSUUk^c zRfU1mDc`Vy$%W0^%!hII*j0VF+=Jl(^u!*E+c_;N_2BRk5Sn4D6{WTXeJj}F1&*3o zyUZ|UroZJ1jwrT$&i+^P{jgvyBWM3KHa9Hh?Io!j`I^K}P*9!hYcA{JRqh5T!;C8V zu0Ft%3-Aj7h&)Iqg|~GT(F$bFh3}@1PK2^1LPM_n(921Zu}^3+)~9i<e@~k)dELx> z*jd9n$nLt${?1bWW?^>l#>{t&a<X)l0;|=GH;nF}{Sh$dKQB5@&VnfP(wWUMgKu$; zD1TRShw?AI2w%M5OwN#UMsA#I<Ll$5i$>d2lyL%~R?P3;ki^KZZP{~Q@TK9Q)MLFZ zzDv$`i!iBH9A64-t^a*?zLDH*(FP4l659^`!|ZN<{`F=9x0y6YjQea(z1Kl}<QH0} z$`$`;xB9r6Q~zq{=asxEy84s-Jei3wI?8HvK4EKO!*M3vJ*m9(f&@fX0l`UXG0qAf zga9VOw89eEShG9v#SS9;<pD!t!=E)x@XA{t1y@&e8cDVcCtrXYs`F$OMXqYQol^VG zBa|Ba^vdfTV|oK)+G#Nhc<m2m+O*0u%D~J_qE;2rVi*S8G(abv_2K>yF`nfgIg(`A z>7|1ai{-FGCmdHU-V1Y%BQRGq>6an&q1DRe;Z>|fB*DjI!FJEp^gii(IF=HU6oDjb zK!^G@6s~5!d_q~407GTIl)5_cZUZHXXA&jIW{oKP7Df($L9LT8_i&N`!rBH2ZNI8= zHPdgRpS_&^5%=)t94n1=64J9zT4V*LfSN%eL82n7(iP}ND$H+5ItC={iBmSgV?!$q zigUgLg<+CpThBCIlQJ!7Z#yTFgi!^CzTY*<ATjtH=3+b0>!t<A%f^!wOhCf)iBiS5 zp+}<HMPk}nKH7e+k~@7O>^LP~((i+62Q~0NmNQbnToP8g1~%ERot6kiueo}<$!k?f zKIU2S&DDM|5WPjWy#bO<1J$;ziOzrovPgn{a3Q~1qsLTOGZ{TY(hMx0{=BNNDF)!5 zxvpkn;ktq;_Jyu;yQU@TR@vuOCC&kTFZqh9fdK0)2Hnmd<L3J{oPd*1zDM?@3aub? zZMCc?Ty_R4{{pl+Tg~cN=inkS(}k1Xr^pnLr`5}Q4Dp)5_Kw?h5?fd;>6A+_A1Y7f zv$7??>bhuAU-t$`_<W)O2u~JDl39{y9ClyI#U1AH*Q1ymdl!{gKyE|i)$2>5?0qa| zb<)A&S3}lUw?V?@AW0c_whEl=`Wdc--Ss=FUx0rql0%rxvpfU9w0Ty!b|<Ogsui?+ z=p7vrViUFHfGUrSHQ{tJf-BS5^66ZVUr68Oj5Ty|O?Z*ms`9eW4o-U5dkENoUID59 z@myUQd~BW4`C>E3_I=_2-t~38SrSM#5_Fy*lwwY5RZg0IG@I2j!RwNU?*?^;Nro#> zWiT7?o4(R=QrhjPnT0;P^Dx!Ws$3C>RDqLhT=Eh$R5NkZ?tsVs^Kjf{2Jo+Hi~A(E z(-)sOfy_aMc_7*WQT&$^Xt7?;{tLGVUUMHbR9A%-X_U{vDRqcxiAotc)*DNrXP)5{ zHc3L=)d?=Xkrf~X`m;m_LaD?qV)B8I<-l8&DoS=_qgho=_jLq7jv%qsXPXBHu!CYL z_&)%wd@qW{Ofqx1K|c7ZlzF`l&Np1fzYOPw_S_WR!buK`uDaFcX5i2-aI)6Ie0iHq z>@_Ohjua?(%DKtPoFt#qhb~^h%zSe5GSRFe3en@GB0+ZDq{wA|G(lWA=9=uL6v3}d z`d+g*J4vDH8c7tXb1Ds&lzvpj4d|f@)L-JMPfT5>yF&k<rrKbL!+_&O;Q92y^vD1R z+mfr!`t$G{XS`fYA5#n{y#mBGB0AGVou2IzF&BTHCHuU+N_MwFA%`SXAwy#I53TUm zwgw@r&kBxnzuFboi46CnIAjfLMK(qOfcdZ82Uvxc2D`Qo5vFtsF*v1N3Uq6`J1@wQ zghMcIcbduFF2c$06T^@qB=EM74gy~BRhgNhK`;C!?_FSUKR3VOi0uFjY=Fl2B+AR; zMcm&_W@u^o^6d06ag#nKkV;0pvx`Uyx|=nVtIVLCshhHH%iE$fpq3x5(&+0w@OG1+ zrzCwpbQjnX`?Zy~Vtysr4gTr9N)p9V6oB!m7?QN0xM^}HPPc(%=SdRxFmmxAX?FSN z?V|l3iD@K|bgO8WsJmoNvx13VcKbIWKY3|2cP4s#M_tRhTIM;@P{bbE#k0JCI~y2m z^TC^d0BXXQw)v_pWTbQYK7z4AJz^l+&FO_cnSHFR*5|ArTalz4=`D(kuG?%oRW`7W zRDzR@#3{{V#3k{X_x!(t=?B$s;A^XjKmZ9quT;{5o>%@3xmL0r(rhJFQlS{RmX+qB znyKY$7vh>aEjOk*sUJ$V9z0g0wtM|oAtSqvL(O9pd_jsP_`SX6DK}6s0K5_0Z&1ki z755$g%ZV=j!4sCGA4UIVAp51@4bo)|^4xt)CUlbaO2h4*Wvd|JdDNPt{KFqu`-(uJ z+pR*)&EwuA=^T*k76?yz<mxhh8I!5sYUow`2!yZ3=qk})k<n>mUy?qPlNf4(hq%r) zD?T6F+1GGyDk1sWO3ciHBxkTnFUV6m^82J_H1`t)cB05kpVUl<^oJ^rPY*rT`)@9- zLllz~bdx^m2R+=vE47mLM$iTyNm7x$Qo4%?i`z0oO+zU`@~u^Objsy@>wk7WEUOSZ zxk*w8P|^w!>qg*@pTPm+i<g=Aqkz4pP9$Lw5BLQGdR`K<ngN<yR!7<RSs^K*TI3|e zN1mI+Hh`0zQDB?8As|`d|B(n(`J#}BlO^;`nmt08)w4pLR0^)t_EDJz`h3j-;k^Ba z;VN%Jssaa@z#j|@bhlducQNJ&KnoVZoFwklESt^iB5tXnaJEr0vV)ExskMeE#VF|| z?tazxQ`!PyzTxDza7yMNN`=S3)Di1@?*qm}A$DNHZIZlb)7fKo_}aP=50aA;BvH`+ zpLiA|-#;6Kk=-J#brA*U<t(-x^#>kJ^T^BNKTE~ql>W4QJW!z?HYI!niL4Xl;3O0r zWX*+xzvyEj?I*}|%!+RPbs=$hy6z0EqFYF3D)+U<U3$BMougEMxX<^smvJvjG3MV5 zx9MOFo|dx6&yMXJ_GF~hrmbC=ogYq(AEdgZ?*3IBCD%VFAR>OWEo4c1X138Z_9)LU zYTi3}41l?&L2v6j_&)9!M<8T9iX0P2<~OSYo}M)Tac)BkN6_FvhKEgEW5+t;IQIq( zRdLXTsxL~VYq(TpiPW1)kxJdDEq_5nPZ#NsmK2;hQ3A83kh&mEhv8sPDq=|jivR(> z1ko~S&t(z7JWe*C)A#h5tJt#Chfa|#oYcNb?xNJtalhM9zv3^txSw<v_xl6!i9z4d z+D0u0F5&#oNvxvoKULNpepmM6eAYRY^*=s5yV@t++lQ+Ha;YT=Vx&A->2;IvTGrz5 z6wPbXN9Cg5ga4`6UP9cGB3%T~iQ4xoiGY-HG*w^x92}%N*j`1;ZHUhkr0ib^Et2Gi zKi|eXgXl1t>`DD&o4AgM5tUWx-4guF85X_^U}iR0?9N*X`;Pf}xUZrBFN*x9@6wp@ z6P@!s^)j7|eWFrTpHjeyQk6%jcMH1A--1qF)?VrMYINrP1;czP-QB~FqhVTk#|tW= z0DDoiP;}e~05CvA0x)@VeazjkN6>!MI#JMxC^+$0zE}Ns`xC*8FjOxg`si@^BdFmU zDgAf9QcSEm0H6Nk$Hl5IWhG)Wb^i@@VTHD~Yi&1Jzy8!+{?+0jO55|L!_ntl+0J20 zLV6P5wQ7JFpvW%fDunAp8G%Xd0y6=_IDnN!AIiv}Yb_dtBleK={b*(tN%KCRA6PMQ zoR~--q?mx}=vOL;6TNpbNIvsHeff$Gt&xZhd|+2s`bo?CjijS5-CNKv16o`%Yg^cR zObzfBC;b7piZ(n30PDpH6ae{(&)YJOm<6L6B6J!mL1=T5xEx8Q6pIii@^BO1@nJc* zfub=OQ4tbKgv8T>zrar_syuz!(9Kf`lCbJy?)ain)a5U9?PtkCNOV9oi-EK~7314? zY(%dOdB_6jW%&iT&vO9)zXd&Okl2I5VlYU1lIRu|{s+KpavgsA)<ZA}IYSiS$G$7= z0do_1W(ZIK4h{vO<VfPdq=qM*7wz%t!+q*b#0vr18C)-#>10&i#N3Yq!9O;Y{R>c< zUth@RuP{o=);n_xQ>15vk}&+gadJK4SM$|Hi07<sQ2<G>ky5Q42j!-KdtbeKqA#)q z6t?eMz5!BL2SK>|F49HHo0O;D)smU$Q>Q0zw)O|Uyd}x}q%tsC)+y-TooIo_p|d&& zho2)0ym*AB0aoJ)(jMdlp%<LN=x8PhtHx>+-$rWnp{(@=`LM_>itzg1<*(-pM|b~w z+xe!AnMZTCa7o)fP{I0i<~WNQ?1Jb`q8{aHBt39Vhp7h^7}-=9nSQf2;cK*O&`Mz~ z4BtT8)rXosW$Ilv2b?3yX1enIttu}P8F_RH0&HrGb0r<R3$EEUSdmvhoMW((g|)F| zBDHL1fVYhvl$5<#g-T6v<e_~yx6~K}nn>EtyK?tGX&Xh46rGKc+4q)Rl9@BJ={$Y@ zjr<x({G4N5-W4k4?Slt(jdtac&WkI4O0q8notxJK_%1&$Q9s(?dRY<`G<QKeaNYT# z^_+PvAT91yY4nZS4CL_#dRB~NnIxbX^O)=Yjj!VoV;`8__GhciMHOqI-tpoJtIQl; z-+dmAb}SG0G=EN%edPA-&)|(tE$;_0#rnBVc1`DMk>45wH=br{$tY>qWNk|dmsSN$ zV83RatSbO4yPC3GBKyUQOJ9uaQ6Sj$J%!JJ(2aV-zzI44PDa3>(8WdDv<`YLeg~eA zcBcJ45uvAq%5rg~rYRN<OpkNFx9pSSN1ifo=3AMBZB(1<IEz=yzMn|tOLAXjdukfo z>)UEYPcz{zG-DYrP_qI`l!p2>Hw|fT8?ZjF3~aI+*DH);X|U1vGA!X>9EoVK{bjC( zzIB+snTrPi#j~)XZI>h_bq>>d=rlzc3Tz?;sx!?4mD6g>C8-QWvQLu4;O0tg@2ma= z7uOa6Mt##24_%uK%R)m`-og#jKR@kz{NF%QwxbcSuHT#dIU?8p>ifL{D<vO%UeHC# z_EZ4nReH;GH^uNiK-uA)`Gk?FCU>UJ$$EiC%)U6kqfygUZu6Mjq*>YA96uf_-Loc% zVwA!Dx{57h56$*a&PRej0pO&xbXT}Gqrt-3Wm^(I&d#uw8(TB-q10S^+XZhWDzFwl zl-^b9qrxd+k*TC^?O(1uDqf7!$M|rQj7*Pt9ra$U=U(btFj_U$U)j}7nUly-=~0t; zgp8vJeB5~Atg6sZ5VAu@a11%E(irca;@^G###VE^)R%5!z0@!1)_BQI)7!G^IPGw^ zuCSZ)`+cU^8_USk35jC+zv|Q+0JJrw_)47V5DXbOYxuPp!8@)H*u8y0hw<3*Z=+8% z?6;&9VBUvW>cYsC<4?cUHYBsA3<RDmzv_Esr0qW?RqQyQAU#?hZK*msqHy+Y{VPf* z$0yH6<Upi6UQ}nGNN2(Xm7)>ZG+1ll<}!Wq&`x2aAoN3Se*N@1-}3G1W(E;{<r}P$ zTpgcpUOaalMm2Sr>K&puTqD;5cU6|?6bJLf-$`&?-@<VAVmZ{8M8O45Q_js$`e#?0 zL&I;0(7aclop9zP8=%H4Tqvyb7S*`uKq^OAjI!6PIQ(rZ`vA^S9R;?;@WsOA`hfHd ztv~_JE(7IoYS(bmy-=JvmxpC8%e4Yab!}R8Xt<~zfO*wb@ckFQ$>Jd<7FprriMJY< z+}wk8iBO|<vDgr!DsxY7u4XNYFfS0yMPJ3dS#01t6K%Xvc>bmkcE%tbzwzvp>YEqH z?auo%N~0{aH?N$wo@iYIVfY7CgsN>w+Zkn81>;~wX^G+**n7Ic{et--h5?q>>hG8J zalg%B9F#eE_xoKv?m>*B{CTL{4f77)7rCk0UtJPvEv6E0IxXFH?Zsq_XjWiazYJq8 z#|?}(G=JrRhN=WIv#gKnlTs>>9DA{7#UL8sRHSkp0KgCCSN`?Q(C#DO<san?!mDj{ zFV^1G;z#l2@zV>RwzB+z+lv{s->v#U)ikXhtGw}2$dZ?u;mKUf`*~-})P|KiVyi}| zORMrWT5vjh3kNX@V33qlPPdHomSB2TBa5-Q8(chu>@#cHIcvU|@35Yf4~T(%%MzTu zJp!rPoF0B`o;&Kg*us5oZWGP`WH`PUFByv{HmXRy?-tv4{}kQKdKv9-&+W+eRX>aC zITUC9-KEC~dyRT7I~jJK8H!zj_Z<}-TCv<fu8(rEZio~I)UzgDDq;HCADv#;rCMm| z=&t`o(>I<B1<u>{9)=c_3r|z}V!s7lmglueGMyI<#d}{53S%pg^Ap8hFYr*pvOUk$ z7)zn3Kb8=f%?ys|Q`xqYA`+Opqi1nE>N!aY-QsWi$VG}Z?+g@b+osk!Cm0jS6ETzD z45J!r;MKcX=vEhX5kXV8h807OdY+0tSiwuuF}*Zt@{HpJNb{BWr(LNkBd8xwF@<4Q zG_V^jm%#soCypv{nkKH*pTWd;VFho>n$eW;-yqMqkXds@?ai0)4vP3E>+691$GqcO zQTe|1THR!}s*3dp`=k|}C?cEK43%HzrP53KAU?Yp@4H)RvY8J4Y~?x3BMwLb-6(Ge zoJowAdHWJ|N~Qut`N)1XhsZwTnPTCYb{U<1Pob6*EcHESkiJu;O`Mp{yrnMX-*Z%{ z=$Ks{BF6vBQ-SxY!Q6a~8B7I0WWwwRK$SG!#beVb)=SSyYwK^wGDg0T8DKJB=eqek z_)~+8o0L$^7?KN|s+OgkVXk#U(MUgCdDOaG<xGU4BLx5oy9%<}QWn~;tI0?>kFMGu zZSw<6{Dgl<2LpaxTbQlS&y@OObZub6@q>CAHZbL`NK6%boYGTd4uGUZPuGK=HP%|{ z-kElO>15BCvA0$J9g4W1-p6XJ(P_a)oU7(H0${slLqV8OApM=Rw`RvS*`=5msp?tH zHgmJoyEj~CHF7Jr1M;rJuka3133SXWE6kX6ET`|e18^63n6BD<_h>Vw0|PiO1+v;` z{_Kjdr2F9WGZRVMD%Ebx4>#7uaazW7>6hsqRI-iJ=>RZc4Hd_;PG!BYn@LQTD-6<} zSQg2BjN&c|T<zrgZH46aiTYmw&nJO1fU(CljmCa46S`GIgZ7UPUmx$j&}62!Nb9%o zwN5SHTHQ;G{$snv7xS7$M|iC@Rnwi!JStnw_q}TVgYXx@*x@xv8uX8~u60tmiHuYx z<nOmR<jJ(*Ye~(L&_GFeLq;X?N1MNo{=YG9p5uyN<JxZza_?lVJ~eV0eVdNl3H?<+ zBXauw`M+b+kAK238}yff7y&>I)8Lu`-;bexCzDoUUe|@COq?>99=GOGBZiN+pP&6L ze|ozdy(*hA2mS|C0^Gt|(x|+;y?-71|I%LqoIAy8Sfs#IStN&4xL2#e5Kvi(E}KMK zSA+ln^w3tc3=sk+LI4ydS{3Z9h*g5sn9gmV;VuX~BO(<LgtqjmbRyzENJ;H;FedCX zRf-Y_q0H$y>PfB4xk@aBp)3ztS<3fW&JksGp{z}<tdI6t+mzUzg|c<Evc1}8qbRWt zhO)nFWgp#VpH$+Q4dqy9<@mhMK~(~8go3wQ!F&7Q10~3DDCDFS@^>EsRE9EyL0Q_M z90yQNWlo+jPJuQ~!~rKt872`1lWv2R;$U*hT>XQ;0R%yUAs05xY83zmV2%%gNFzmV zhc>M4U8w?3A^XIij$ypzYpgxw#sFnLEIr#YkQRBsSGjgX2;)z0<Ig<c-w5mrA<^Zw z36viQkd+1N!UWHn+5{gR2(~E;Jqr`+Y7=^OAVg7y4~D_twZTUZ;FHRT*)YUH8{+c; zf~t(%2t!8u&~_)0K!Sjqr248Cd>M!&WwUNb@f0e)_ig(*LKS*VhRZR^{KqN$-R6ev z0m^Rjsw8Bvn=CYRUe~pTvxci1We0_VkboT2Q+edayZ>d7M5PadoDR=huUrE~#XbQA z|9K&H$U-B)r!7{uhbftxKtxQtbf7nF$_q)u@`RAY<rV+_vJn<VG4TV1R)G?;WND;| zu$YRd8>6JNt>iQI<t3`{JQ4Ac0$svR_f?DDSC$lLk=*n`?qI=xJcTx?QmHWM0IR(} zE9_@QK)@Jgbz+<lvJMIF<pZIh=XH-Zc4^5eS&1px15TH9rrS#>o^~SgH4zz-R~H~E zGY^|MWh5^4o~w?TtFgi}RFPCs@o6BSh{_&9g8zd7rcldHTpjjP(nCNQIx>=91?ops z4jNOI$fw~{U1Scmo~pRGJkorI6*{B}eV_`_h`bdjVYzS8BJJ8_IYfvZI0S|C!!b{w z6olHPJ5#(niOBQU{w*w61S>p6L^jK9j*wsJAIbWG;D=O>dsyLBqEI~*+)EY9_tr+K zYLgAI5Av~GgY7F+ge?^j$2B-cMg&mcD&d-U`mk^EhI+8V^hDSIRp@MH47QFD?gjF_ z@pjr#74D?64FGi)6kd_QJ5#DMt7Nzqk+YX5M!^b$P%!!qWiD>XXH)V#3<kn#!sI^W zDiyv<7SWrLa+DJrB?~;J3aL!BFQbG5h=^ql+1w+o$u#c)>|VtO>C?^3EC6Dirf>x0 z$N=i^aV_vB*Gz!{>%A}lz-bdD{KiwD^ZWc`TCIp2lIA4{BJz(Ab#v{de;vSIP{4U) zq{)+4_o(1Q;$KO1G%^A!Wv5*jX^QWVmVqpH1B+n}Xt{4HZ>R{lAW4^Jh!m{w3f18j z$YOFB84?k6=%xNCQhI9!B0@n9dm*>HZi!GJfL@_9#%E6H)y`ga8cYtWW#)#`jJV8i zcE=P!oCs{Q*W@8ghTTLso&w$>3Yk2Sp<uNbI=nNUs^e)A%8V*DJRYcVozGZaNpIz& zBk82Uqj{{rE>&oPC<d(3d2%GMyvLPKGmU6O4xxlIydXcSG&BE`wyoJZ=NX>gW-}gd z0X&5UF!0qWzDyjlr4UMwRj=m(oR394L6AoAolY|??Q7fx3jOmG96`C?LYYJyN!iv& zF3Li+h=#@xcWo*sslfg6q5b#Vn8RbNorB`D4<2V!!9}WYiPw5ep;S_`8JUb2qH_7S zJ3Ju^0PZ$wSO>jwAoP%t^8jYGBJkM?#VDH>J%bg#>BT|wf}7p&HC6NDxbO0lhTfyH zH<FR7D&k+boVQi2UNLK*OiM1l2ghSo-vfn~2{MnurB~904k;1YYQjcOUM+hH8Y$W* zuLfHA(2}mc(%HKal;m-&E**o0FA;f{P{P)`o>2~nl^yhLK7hhBLQXbXJ_x>aURoyO zqxht@cvE-0Zlw`J??>@XV1!>|H;cUu<~;dQ3~vYC<Xacn3y%)jix8N=AbEfKY?EzX zV}xsu?{?liFPIxA03qN=%pURD5z*_aCVHg_-U5V}XsWwBhwu0DYdmr%_L)9A{As^t zZc!*2v^pRE3{6rnFC-$)w!DP8sX{A6-bE^+WiEQnQTQ>I*Qr^^4{Ux!PIBIHC@-M9 z_49U;p+b`vi_@Ht(M-5vXK=)-#ZxMqXYQt1Hk?LfZbxm>PrH8#H@L*@bSf#n4Mfnq zIEt{V8F~IU8YHxfgJk&u!(7n#^GO5)&?x-70Qd{w{^L0UGK3dI#cTjc8x$P@6m;|1 z)r5KEcIuds)pA<0XzBRLk7sw1aeWF$h}XpR2`t_ie7O1%>BNt8kGah)u5(O9fWmKn zFZB4%R55VAgAh4no@^Q2U|EbnT6UpVZ9})KkVWcJQ`ig!B9umiZ&8aBoscdI5IL;n z^|_$=NWQbAwq#tftxuTX&I`i@E#ztxFJ_jM3L?qRo`Wi-&SDa^c_9CaQ^zA^wL>Ml zRb7AaBuUsMJ!^3&qzE|eaJ{9#tBB@QDaE^@j&@jhz;V0Z<5x>qu1JUSr+MBCjW?1G z*+L!dHmG`^2{0NKUcfIk<z+DL$tND|_bn?Z!;9n4%lUoh)`XW(5=N;s_LbHY?2l)0 zO$ecQTKbo=uqZKyf|BYx=6HcUf$^gO=K_ldWj;R%Ox%s1)sZPWQtq&vPwgRG8%SW6 zX!ea}hghp?pyfprk6D-F!x^|*2NIxi``?emQOZ#VS)hKJ@6Pi)D(a$Mrc|7k+8w8; zGo$Yc$3z%S<b0gOkGw)vbxM4mNKTQF?Ns&w6tY)UD#NnoK0$Dc?3e$u*rG^qOr%6u zK);EaV&q`j)sAK#MuPYt@hIUqL8)FK+`7~|Pa_-RB&>ykj!@h-ylj{XIQ_7g^2O4< zxN@K8ua+_-p$o{y5=&1NucvznV%l9%AoF8v>h+ja6&S#2KKbEqhhzq1_<ZFp&|4ao z_c1x;2`%;L^yVf-=+LWu4W)3hsXj;Gw?B%z?<8F0#R~h#Cw4`6!t-9kaZ}Xl{bMWy zO|H(ha9UCo{)pk(ny%mOv`=4+Y@>o(iIQ2FLTNLu3_Vg6?VS#{Xs41F&o;27VpPuf zm;IHWka4O4aVTLLSwhHJIRD(2wvH&H3Y;1tcn8X#pGvJXAeXURtS+}zY|l?u-ca+9 zgmHM!6|S=T*YzG(>|yb1sDi|8S!1DFU$vtE&S~QS<X8mqhf9XnkJ@)j_hL!6<DME! z63woSNgZPifdpUW`;9NR?(Y%7Xy9nm2>kYf)j|xMp5q)R9fZFy2|<j1a~1YPL8nm2 zkrPS&S^i~=@PEaDQayLoT%+!k(tar;TTuf4R*1J;?cX~)tpm?b4c-6|CJ?o6+W}iz zAmI;tmx|K&#Ues?RbS<!`zSi)K(E0#$$lzg85@J|LVqB?I;+46unK11;alLqzKou} z+~9m;{i{)dHuAMsE^(ITv^YL}sy0A*bD#JvxO%J6>zoJc|NW2Dh|_AP7c2Yk+`Hg6 zFFlJb#$OBBPyT!+pN-3=P$A33nZHMaT7i%}l$Apd$v9hRgaW=t9-vC|>;d6hK+NZi zF@0LjMP29%AUyC2qL=^C^ox(*mFJJCJOy4c->9DHmmfZNU0&lwv_3_4sy_aB)BNry z^rGYWt{!Y7*YlDpe6g#0&tZssY9E$rqjt*Nh}x8CZ@=;Yd=n*X(2dT5z0rJmKMYi{ z<z-NJJ80DnEuM9bw3WIyqCZ>Vhk|=NaF6u|Aq_MUXT4Np@>R2K6x6-UE5ENP9lJhG zokr!Mr1gh{kq#7!AfbD|i%5M%CiCeT1YFK~vxszc5<Da#e97>Exc?GCg9=CRYB#B# z-=09vux)LzFIe74*OrLY`4&~3haFxvZiO7rLn~h%8vD)m&wiG=Mk6>wRZ8MhtJ@E5 zvBaG0))X5kl0(ad(Q(rdG;wbf)qaEp-=w^op#0=?8!BH$m+277KO*r6q1$SRg6|GN z)iOt9J_F=G=b!sgC7g#uIl`xY=V%O2)cQ&M!K&90Lz=s8><M5v;un-Kkj^dZ(vzlK zW0Y~I6UWX6M(VokeTbTF_+GAmeUTP*<&1f9%?R)#aPh)BOJ}njzT+;T9~NKC?@_y7 zP1E)e<M*hC8#7GfWnE<DtCsLol`DE-$d@j4tQsxzt=s3}cLU?f=aJk&QxBi-T{4c^ z2}~*X=gkvNSf6*VHCFUcR{PO2$@a;nPRQ(ZV&N5f3<<atFP#1Ao_2(By8FiL!?#_s z18pbFn?3_3h!<ms_p!GUIox`tysim#<jZ;ZXJEw`rY<X04~;@tc1nL32|p)&*`gje zfXio6OI5E3e^PgyxUBOsS$6(W=}Y_X1vfwG**BZH?7G4@%nr+=-{W6C2r`zfh|Ltq zUQE0{ZZFg(2|w@YJj}j$U(FXBH>byZhB7*e$sZS(na|JiASa}ZaZV*@d`$Ww*JiGN z^Z{RKK-jJs5j^2fDb^)EYBTqdb~H#Aftm7nW$QW4IanYveIP_1Q}rt%W$RA`gH{NM zsmid=jW*W~%lb!!K5jXFHgFtC97W8_@j(iCc{GKj-h_#9YMuTvnz*b#rfuWDoOyZK zmimass!L^&ZZNW4SOd#{kDs=<k_Ut?YyaXYL_6&)Oq*Z&qD7AmgB>$jsGSsut%MH5 z+H;wWpw}$*7uD>nbf;qt{acDB@uLC<Y4~wnvZ+IneiC!v{S^GH8bt3?S(}Bflx0_A z2Cd8oA}GOnfy)zMEk+Mea-TVyyz<HS?l-UYtV^?v$k`epvmaG#0Ri@ti~!A*UdPS* zZecZ6BDrctF5N>b2fp{+VcZbSXmh+|5C4Pr7Wy}TtwP;k77<LEOT(&H@az9fb}VGC z*=5^OceQ3OG`*m+&21eMFSKeZvnw!E=Q*~#(1Z!BH{2+w$y3?OY*7gU3@n+eN=D^J z1h^AxvsIfK&)cw1T&LM}?l8(P4Y|l>j5&wQsDjOTj!%R1*0*FF=U!F;do>Sy>5H`h z@iwB1_RcRyVV<bz<e@8P36eplo>xa@oeBlEtUXBi>`0cNB_6F4gFa@g=@oky-P1;A zuohc7BW9D~Zmcr?_Fb7XEA5Z-L<?*s&%o&aa*w-v35h(ldLk5`@pl_Z)4>)pZ36*V z4X^7LEV?UaKByZ4-=KRcU-^Jd_sja_jItll@#vQHh=FMjZhoMtj+8}2tssCd)BZbK zK1X*>wzvw$*BX7t4&Hr1QV%NAYam#q6ceY1rYXB^9LfMs=bElGT4!E1d?69JWnEDX zAb{hx`eES{sapCGVxJxiLUI7T3rIV}%VI-ta}Lw9U(c0SXKK~lN{56ubLfH^`;|}M zyA(#M3e7-wFXc&R>SY}<M!2?^Yn+e`)ZV6<G;UshTf@AIPHlUBwN}<qrWiw5d*H|; z2g@F2(pBla$bS}+8&92hE9=CA^c(#EkBNIbk)fvlVZ+DI2$ingJ6W)GtwnOp+Tl`+ zKP1_~_ty1$jA~#8J<zBe{N@b(2*|W@4E{v&*e6vlO|2vJ1)bo>38qGP?a)7YRs%pU z@bZs&1GX_b0`AvP`yt;Y?ZqU8)#10?fk}_C3OmY26K@xFnTu-=Mud*55+%ZuJ8wEq z2*J9Nmu$P#SLGDUr_<&lb~&@l^)|!FblzG>3QNfFkbC`=VYPivj&Wt>YaXjcddo^2 zx{KnmD=PzHBSgKKS@5M8lN8)KurV^GAAF*Q&~9^X$WA--CC^;7ImG6L)w0Lx+b_ef z`+;*O{m;ry0#YSyMFmt5H>}!U4B3mOPk?r^^45O2pT3aj$hpU4V{*lPI)IuNN>Ipz z4qBQY=Vq!0*B}K8wsQ_qn20L8_cpmwzt(}0s}V#z#xM#B`aB}n`XEoz`W4K5pQoAC zBDc@A5Fb6WU+Z=>8ttWVs;63pVBYiHoM6)0C0>fYK4A6(ljX5DQn$Lb3149zkR$j| zC_9qwKg&{diqZ2@W&?b802u7@1~lOp2(pI$e6V=R=rgnK5Xlo@0W0LHkl#?PT$on( zCAX~%sAWD;e`{xu!YS4V5&Xix&>GU$b9sVJ{M%Z<<<`Euf_>(On`ZWx+@_}g0SMyM zGwjtMRWY8Pb-d!flKEkvcM&{!E%8{y|M7XBu<Di=f`%cN4cujPZ+ZCY3P%~^{Yi#f zt(V0rC*NvhLFX86&l!)-mX+*aB@=o@p%rXmHnN8j>uJ+BIl5LQL>>;WfZE^#%m&{k ziq%)+`;kq1-}@G&7hfw#wQm3bfi&PFQRx^8JeSFeMpca{1H0?0Jh+gw`Z=S~Sa^5R zxKW|c_?`~kOM4b8@)D|@+%9P&$Fg8M^Ofhn1vv@J3KQL`_cA-`X*#-{md5+u5G)3S zOo&z1{y?D&wT4SdscZ_kt3g0fS8*r5aLTkc{~b}9i(SB{<cmj8wctdgV(`;5KV8wn zh;_V2eF3v(AH_OqIPsaMa?TAMH=eqMes7uz!bwfjD>hF@O+D5lFj?hu?<=!#GY~jo z<e(l?EZK(m8*;hFt|EVs9bikG!;g_60UbW@Aj?DXx#_HMn!TR}OSZNz1$_O6(8$WY z)WUOd>PfGCzD$tV?PZ&6#mlv-wv>$V6i2LItpA5&B_?zEOaT!VDnh_q_G$OkBC%kf zH+)6R?qk)dFBn}W_JSVD{DDHcx}9v2xkYsPas%!e3_%K%n6w3vS_C#;>w6Kd4?Le= zvjiBI33;qntBr2+u#JkTr&uuHcQGPJG&C;C;hESWzb6|fvYOSRA9=Rv9K*7$b+eV< z+Xjpuu!I4|0fBHPqxQyDIzigQ_p=weU6dO{g*}YxqF1P3{LETCUs)P)ev&=57ms*R zP-_wJLoau;UB+W|S!s#VvaRx{E?7AFN4o&0y?26Wc2g=eFG}><&7{jjqeS(3moXvA zrJhSwi~#Vkjo4zM!XbKydnPX{Org08!7?Iv(<?h(N?s-ZT}+p!#MXzy?7Q^S#uB2y ztcZcc;~)HcUOp~AWlFR?E(PXI1xjUC(F76Ad<oYGX_**kO<(PQWF0_nx;B77@X*ov z;gFijb!q)K{d<^3D^YpY>fa68_q3abWOlnD*BVKlgs(mT>ofFu6t12wGQSqGDJHCE zc!ws%Nj(6^;G&N<eG2FSKP8D@H1BW)@EKuk5@DCPm@gRuFLvzfZea-j=8W9lqSqKB zpC^*ki#b&bAb<|Ga1l>aJY>6&H>#6!pwC>q9dk4hthvQ|HmE@>G-_^u1$(kwNQ(l} z1LnkeHPg<`zIQymnGQOj>YNZKl8`qorWypEUx{GX@^$SC%7sQXByvuBL2r0kopx|i zQheN;EN>RFJ4gw&@WnFpGq);*-DbAw`0BHt&uZ;OV)*4tC4&WK-R7l~;s<=E8DVy) z0L}w2U>IDf!u1#EySpOwz?P>=Rpm7F3bxSHz3mKb65;0Ylm9OYB5uPys(v{V7XO<G za2CN!5&^HTkQP<3>p76CYaD3X2yRaP_XNfh0yt+#kZ^eMn85f_$)n3JA|_GJJj&}E z9e}CmmX|tLW#iQ*gZOg@;7|@+)=}yJ0B-GN_7zQ7(m*^MO4%t;p5qe?AqhTOO|3hS znf7E_o)DiQ-qiVMaY%9^`bcc`a-=$Wp`D<AX-p>o`P~5@|2dA7b2ZS0%@rQxMlZNM zRC;9kwuV2kW1s!B)u!^7%j8F-&4F+CfLII(tv3)-^2;b<&Te`zBpn2iQUzbGxpPW} zXy-!Klmew`_adsZWbr(aD8%#VI1KD8wvWO)Lty-x6Pw6KQlC_Z+w<$p3ou>-hebFn zH70?)J*aiE2M&;w-0T8>u0fJK4twp*<-)4`s2QU8k19pLgt$i@<Y6L*zrA3K_^oTH z%EvL;3~fmRQsO5BxRq^@LVa9GL}2<miEe|GuT|ja9QL~DJOYldwMN1()#<Je$H8R? zxK3q=*AK-2Xqq@j@CB1K?RG-1Mi1Czgu{G_u09+-muzw0GEUXFA5x?y>@@9D%?YOM zhX@2Hs7@DPBx0tIU8wsZ`$~kn{PFk03~*Htud9+_J`h|L4<lb>;8RALj{^N_QFtrc zjuIsPr?)`3JPshZinBazJ!4E|1gz#|RUf2pc4=)uB@TKcIcJr|iOQw+5p_+FEpaQP zwi0ulS8!jjwsW4<Kx$otd%FD{Cb4QoNu7Cu(D6nf9bNGAA!t*l=jg1k@iy4QpJaPk z=1UHwWTF&_HMnx@f^K4Oe-<*w?6e<Yo2(Y|eBQ{O4z{X#t9?FXyB<<Bliy}=W7AV) zbj1`e?c3TR{n;AQ<jL{3)9)HTp8cA5FPalsD=LU~5&&V`FdW@e(B;cqfOV##oGKra z^4|2q{bL5C_^l2<2&928UODVO9wlzz|AMQSq#gfK0<wfrUS1)2q$!SbYKW+rHv|ei z&ArTUkleQI?5=ipyCtKZpD}gjYpFqcBq6H)1|2x{SF>z`ib=aR5d*2?B6+~LZ+fzG zz;uc}3Yf34k0>REHlqPBx38Y!Ty4G<ozcc$qyJ)ID%V{3+oXWMF5o1jc0USl^_CiP z-tFSzHgNIV@FkVn*0p0Uo-t}YXl^=}BfS=7_EY7C!?3saO-;EPPebWv2mvDtg`<XG z8o+b7wu(;~bsEa}-V@AT%UOhCQqF7I)RxIQU>^Rdae7}z*{||Ky)l4bu;JMvnC2u9 z>(kzxy$QJRL+YWlSxVYATQtFEqZVD7`c%0HQqNE?{a$-swWRn|^PlnEIg!UB;`Nr) zsFdcWzr-_}y_Lsfb#-@a@9IT~DK3C_tSd5%Isk{<Yb&=mRaA~cuU?{N{xCy#Ow?>G z-i7u(Nf$$L<5=QEAO>iebpYUhiE&VcVKk=`N<J+GNsn`U-`bd7%9(VN@ug=t*IXOd zdOKfq6I=K5$Pr~nlHR=>ON}d*H;yb1)}5U$JKgBbWtYx9j!v8OD&=>vIwe>cPUQ(H zvk^TZz+^kH4Y+}mrM8%}mzO1i;1h8{#8E(Y0c%=9u)Y){_V(!oDWA@XHS$Kj@cm)S zE>#i$qrRH*(seaNQ!J*$OayguMfF{in3npBDD_xV)u54QUniB@`wCwkv`$>$`hj73 znR6yP{$3W)%6{yeS%nQL7!p;0wW*;RAQvncN7x$9*=Bs20T_;x9CN!a$8O;HijwP_ zdPDy7giv$wZ5Y#vNHr=&F9yTz$(`()CrP#gX9v|D^GUYlDo-^O(dM<9O@jp~9Iv3v zaSiwJpPEi`T=<V-n!mOWg)*6w!r4pu*m><tj$TjHyihHM^gJlgD}1(n*DY^Oc{%K2 ziV}qC)tntI)daQOFV$@cfb0P{PzM+0=3GBtO?QVoi`T${N(a|SebwH4G!ZbaYB*In zOC>K9@rSa+=zq?NrA^$6<+d3$3<#=X<+5+nbM$#X5%2|?D`dmB5krqV==n2p)?TU; zwXdaRkIT*tW$DOQLy)y&L?X1yv|Ril7ZR=5CJEg#kfl_?jn=2}mpB`mTsTf-e$bS1 zc$^8gDTjm-Wm)Tmox4}$Aads?NLSZ#QQnZczK$Sx6QkZ5(`ZJ=IlKujA*lLx-L6KH zpVkM&+uJp@bMFNSrx31sq~6mavq#)}{5=2BQjZbrfCCr$Av!no6Cr@?$|(iIhC$_$ zbpyED8G8T_+HBi-)GBj`=goo-%cbymVE1EJdj#-$nWK+DTXBquq22a5v3a`h?e)AP zcqTECs|oVv6L~y#it-RLea{Z3A|!Fsd$255j+ILzp)z^b??MZ#C;co)eB?Tn2-Y}1 z5-;dKxhfo-ksnZo*p|#tIf<FOnQ<G&1v2E~jZs<MX{??sV2~eMmz*=+OsD_VvC~*K z{>ibRl`mR{`^=1~lAZq@m-|R@+i9q%=|`TfJjlyX#$y1OdsNQJi-i;l)-HO_3B-Wx z@5#P;o@m;k_)1aPf^)w;B}R#(o7#h#=Uk}*j{^aHzkALfApy9V5!DCxl-T$dIusp! zM!Lfc?kb;R*a1&1$E9`t(wKQ9E%Y{9T}`Fp>7!G;@7l#)UtKYVm0eJZxq8rQ^JB1( z5DwF)gZ!F)U<(vEAU+<Ih;Nza*x%1sp6rC6>Z3<*?m0wrx1HSuq90cW*~i0+!3W-F zbPhT=aIAB*XFf!}nm6o0dUhc1r5p|wl`yF#0R}&gCk<iQ#FigQ3`=Rw#1==&aPR+6 zbRPax{eK)kT-<xjYj3W-g^X)<xyH>Xl2G<0d(XPu%f0rs_uiCIlu+3#>KbJv-H<M+ zkVNV0=l36+&*O0(=X^e|&+Gks)+dAxR=CM+elmF6QT|7i@okCjxTNXD$XkHq8j(>U zqtDNWMNMu@0(yz>iODiPqajh(Z#c)9XY}7FWb~m~?FdtOXU_D5p1syv`hV~hk@}!5 zDZlAK6f4U|7v_Pf@R;tg4>FGHs|7{@<A|M1bM`lrMsICuQs-8qzwEIBq5)s3-*SI? zK56qI#eDNEbdaZp1*_%kmUBTN=05D?8urE&E)C`Un_hY<$}ZQ-N8o&l_kp!18o06K zreB;|&MSkSf7uF+td!j%H6?P=3!3Na{94Q&J$wH>SL?J|vhn5wDGI-C>3&&@y;S}7 zS1BdiDEtb%4*3)@wGWnRoMZAM-wh8KxXQAgGi}t|MtWC%5A45G&9qzX^(g&`p0SCP zCtO^XGuTY1sCT}!xWZ#V<?uW6e_p#Y^TG#YlaqEemwO*ByShN==3Neof(lrq7Ks5p z48E+2r85-FP=e~CuEa3Ib(iWj0{Uf?Xu5f(>)Sm$`60)!@Ss^`hE*f-pnW%}zWKXk zT|r!9AphF_Vb;o5SfV&Bi2pyz;;9Q`WHs|=n5qRB7<&bcwtUl67eO1A5=*cy^#Ttq zpTDl7il-3{_7CS!ResN_EWLl3@n|!TpC`?5wP)$xyAhe7%j_HqpQXV625M@027K9E z6?mm`KIS}n_HR!6w2X4rPbpiYaOGSvK|Z4w<~74GR_Evp`}8KeCi$waq&>JG*Ye`x zc5_{seD?L9YH|d5$s2THDbkOXJ-JJbuXGw76j>E0_SqfogUgA`?IX^!@%9E)0^FD3 zB$dB;f%B}tB>XAEP3ElVP`(0d*Sz1b58V<+4|UL@ERYuBlG8wo#QQ{AFYVvEHQ9eO zTv=Y)bWC_Mf3cK)*C{iAu(thBc5?01S0GnGBL9(XJGJz0xqt43-Tt#SchDf%lE?YZ zS1#s3eH@f!^)a{Nns&lo{*Ii~^-6;bUbR3&pSe1dILc_Mw)c<CsdV0*1`sfn{UZDb z;m6Sw1nt3c@hW=wbTmq69=w>kTrw{@o_$1lYxvmg;{Z<U8&z>r&{9b(;6aVhVi$Q9 ze@}c&?CHVgwV0!$0J+AF^*b$&&yCg69<>{%pB|2-Pbd&Oq9_|X4gKuE6XfXOtl$}e z9TOe)^ZU0~5U$?nLx`NJcc7A(@#n#Wa)y}w3XkQJZE?TrK{^TL)XAHLF<}PJxnAw0 zbD%%=u071j-8OXy^i7uLjeOi>QT9BlBJSEO;-AaYz&|&7_$PjfqVRuK=VI~a6*UL> z4`NbYDSqVxelC1-y>HT1p^4uW$NHaGR)r-DD}#a4?XPq~e>Y?%`*xdOwO8CcikX0K z$(nz!|GCF&A`Bdz&Wcl~F8Bxq?H+*GfN8Bux*do1?!4iYoHVHv(wsL_)1u6NZ#z%y zt8vFIVpBP5n}Jtq>_DR5%h$lZq_93D2QLt-wV89J_9zhqQ9UA<kH0fC{N9{r$8KE{ zzcn|(t-UMLGFZ8u_C+9YAKq9w#ip_ce;I$8A~&!bs~{9C8e=H@o(m<7Sf)-jtO`O3 zTow||`$Q*};*`$BlHj*sZnZX_Z&IQ5ZPL3uy}i2)akTiDWRs5W=@2@Prk7{Z4x<qz zAWsEUCU|c{+}fqHEJGoc7on7TO(1}=G{9&5+^ySNhDHttzgB?(sI{TOzRdUsO=UrA zHDiJ?0=Ey|(pzcSRQX8P)E8SH$Ujz%wp$I8ya4-nG9_GW;)nQtX}Xog?{<Y=N!c#J zmr5M6Mz`&3i<nfg{}S;Q^8KR1nww5pS(=ewm}_dGl8H$zuhoftt5|Gbe^*&8GiGy9 zM?2T#nt?*zT-%M$`fopH=<yx#8!N7SwXW3KOy>_=AM|>Z<xO8-M5mCXkV`UVza}z5 z*upK;*j%I-8_UmwpW)Z$a6)_0vH{NmH+&~xu1${#x(ObxCPU}0ZGpt+QR~WvD+vst z{Hy++>I~w*aH@}}zg6ok-Y`jjF3q3$A(Df^#<%)?`e){fEAPMe0ZqhDwlqoAUaF@T zRBi6UOFZ*_L~*O$Vl}CF5dHaTd3<BFq;O8E#U1Z}FD>8_Me$p^)wA;LUot!oL+ti5 zTW{0J753eDEfjkpY+_CrIFJ<7KSEbklAW%pZGQ&ong|<<%9vDSWxtx>YoSUD2Y1=) ziP~J5|J-<K`~;+-wcY)~&_WGM#TnZBDgDZfm<qHjSEtu1OT)ZQfMW~ddZf&x9gPxR zWfNX~y^T2i_K^QH__|)_V?GAfcD>)wi93z%LKeMZp_!YN=dTBU!lI?Ig8joBnDrX< zmVE`z@6vdu#syx2PaQ9v2hnzzJrgqK9sc(eee2MQ5u-UHbeAyxpVN}cgkZAJdsxzu z{Gt*r7=3;5Kt$_BXJ#zsYVc+mShx8g8DnwXo9opCZ)DB$7=ohZmFbBgk5GwQGM@Y< z03fb=R2yFp3UDuVo=Nk`3EKj(lvksnoWHJUH+zXa9RdM_(azeN2TbF3p8~XGWCL9` znU^tO=+zxl<c@n0@j$|u&L&Iyg!(dv1M5t&#<a3=m+sOefA6+RMGytcWfuR6KT1^S z_A*FlF6{%5K2j7^Jd!FH4lx{uRw?c(N`$AIz<!-8S7(PCE0{7`>iu3;4cij4cM}lX zaT!O8c!(ve7uUgdyPhkt&MF->gVjba#02tNMNY2h)1!lAcWF~urhXoY0YhdhuW-j# zcXGy#M8G!XsGKrond8bw_0Lu|6#&=->ro9lH*t&KvepnW8UkyU2j#Gj)azNqG%^H0 zSYAk*7}<5-*u~Td+~Fh(Da=>c6mFaLmD43YXx4eL3{oXyCYnk$xsf!NqPRZMA@)eO z-2HGDejAH`jk)@}>t9>l<J(YcIrO(9=(;%FAUVrjS;6^r<;SHphPwv}OE)|1gj%L_ zW<v}KuyDJm2#M(3#!TDgP5w-G2-i<m!*e`Ly7?D}H{O7IHO0&D5^f5N@)HG{4Q@qz zY{pBRk^7haJxY>rq#u{A>8c<^idA$i>o?cf;)1#56*Iv`m(?7c1GgWF_vKu4g*aNL zHU)qa?)v&oi><YA?rpRQx<z9xWfmm(-Yy9tF#bU*p+*73pl~-i-3el1*EwjOB4`X5 zF-lBBWv^CWzD|ol1}CA7&Mu@f>>JO?W5z`UoU5RKw7)rsWdT#8L$YGFqZw9ptl+BY zHD-Bn!ZN5kh1W6_E#MY@jG&H{f0z`v>isX{_9+pvi5?grqrZ1W{PQ*#U8tGu`YQG* z##pN?V(fzsiuVU>B1jHrlmI)=C-A&(G$FOI+=br|OnWqOI}4V3B4i?Sos&jlW=Lh% z!CukFF8Gjf1bsNn(Kg~L1E|n_%-C&uf%5hC^)rC#6YAt&nN5#5)OJa%EH;o>#Vb5D zOu6s<vW~A97i^Td>U6+4nq5N<;mI`x(AHP#7ny>nbFxoE#{~`vCc1~eGYwnR%+$I- zwgpA({J%tDYlsOtK^^Hp@l9rA7T$F-oGpAU8}%^Jz2XYnwJ*(KkD^qGi1${N!TSxB z$IHxd?R%e|CvSHBz)TEK!I*$SvCs&~uuifV=N_ew7i15+cd90QU`UwdpjUJ(1#@ZH z)yD7m6l?71gH5}$+|Pe&5k&u45`J{wsamie<GZOBgn#P}eNQmaa??^^wD?R^s^QtY z$iiiie)E?_y5Xwo0__hBg_iU1Be$=ygipHDzjxW6-x-!IDhc(<msyl>c<>>EGQx8^ zMyX16uSGo0LFf}rmtJmyWt{mYQ*DW}rNZG&T=Y+!151;vH{Yk5PB)nIm7l8p3Sn@g z)RoE$e^@`F%8VQY3GMR0`YG=;B8%%b252$bXaCfEe+0D5_KqVu7sPId3yA!hnTRxG zIS3p;@xGbF_sKi)g*_7!+Rc5AYFeC=kWUseyZztoQOoR1*Ix>EOQ^NB6Z_}h3JgF) z?DTNK%;6_zAGPAn&Ga5AC%+Hyj5dFMaH7mM4{z{9c+Z+7j49uIC_g4tU75S&oGEm7 zzGMjjjwVQg-T11hFd8S%v4bKwijoRnuG*)3x>UyJufQFlS8&m?+MN<ZWoglablRPC zy2Cx^8|gfMvA%X9)~&UFU2(`_tmb~kRNLdP(S#@xE=Zc79QrT{13NxZco9P9X^CG# z={gK^{zl;WsRcqdbODNvv?=%ba#koMMLHI8AxI#(ac@^AdsDJE`e7Bs;xbdkJrp5o z61;U-!8Ze`tIbWhk$i2QaCo3s$^P<Mo}g2So*x1AYqKD@G|7_$wwgnxcglz?)5Yv- zstoX4Iqy{rAAFg+D}Ak2*0$`**lkX#`i$5UkTXWR`xS)uF<meT!eI`9$TP_qfT3E0 zPlvBO|Ju62cVz@3<J{cvU7DG8I7Q>6`k?Nm%{>0W<%Yk?1A(3FlW;z!(fpJ_12yYH zvMeDg7>wd6n&ll%MGU9pmizb*PeNaieaG+S3Zz=%r*rUuO85f|Ua=dthXF4q;iFZC zra{nugp>=|$Q=EZxZw6^7`|Zv|I;101>@~JkX$+ysvTCH78T}Y#jo1y{UCPaC9-zp z3gcP9A~3YB2h#~PrlJm=+{qK?qDnY=SudIy_I@Nxt{~P&pobb0-kA|<*=u<fYIk02 z5ZsUT#TXgo<Utp~9dpR38~G7G3GI)RooDDex=h|J6aC!vJ2%soh~VcSymdF7&S1)e zyE-X%WPiiBR@~b|=E3D2EYZcaNqGj!)+XZfG(m)H@Kst$Z--2I+8zMho&@`MDST<h zU*WCTw<{MDpP1XAFH6hiXkmLApKcL4au-GTu9ag+KdQ|4WbiUdA4UU^RSnllVw+RZ z@qG??V8RJCkNp$#Ekexxi_=iUiqupp6kD6zRAFvzvE|fgD}!BsdO8_q%?id|W&nEg zp>>rh)KAgPG!c`1v&e?{V2(7hMQ+OovjCoXo@1pM56XYSG$mZ(an<6SDl?vB3h)@a z8_aAVL}Q4_aqi7{b4c_8UH8CH<eJXYn`K@x_^?hE(U|ntwE~g3!j*Ot9#*|1D$L?- zQToK`42moTQ6yL{vyzuqt_|`-r=x4La+A`C{F=^nS!I2+A&{zfXMNaCC@@JsqNJDr z^q?MJ>x@g^d_)t+qc*M6cNwY1@UO8&I$c_M_IRKoU4%v-^Mcs|(m=vrG0$NZ6!&86 zAM>lZIR#d?0xQK7nDsVTLffav48dd?W9i20CCvQFZ{~{4vzi~q#N{c?;@9ERGn0be z-ItxCLH&1Y$N)I-M9yoIZrug<94QY8u#Qs_e5#43AQZ6YjNH2vMui33N8-S%gI8;@ zX5APKfRr7Zi~lxBU&lL!)Fkn)W{HTxqMN}ME|*P`Ek{V{v90*W4ux3@T>Njr)hC%7 zwXAWSGDVipU<ZVan{)F#s%DRIGWri*pQvh(ihI#>8<yaR-Z>df$mpZA%ah<Bghh28 z|58ZHT}RdwG`^JpYU;IkPRVc>%W0y(ZLO^QMRQ5DH~N}IIZ$Bi?kIMDzF!;S_qpwg zUBBBSYqVg#K@5$D_Ch6325g}&rw^fF0~yg8T1KePAd#7!SvO?xApm!4Dx=#VC>Q}w zM~LV~REK^|70Q1Y55UUh-wCKdUQ!8e2iKaP2duo(f5mS={M%e+bEE@G#d`(Qohd=0 zG2A}Oh#vii=bhK(*HHYbs4JZ`rHm~J_IfWmn=@O+`isSsC$(nc3ob0es&<TLe{=G> zDsJ5^dKW$GiFluy*xI^Gt7VDLgeu0mn76`tvued^O^erfyLmWq?+#uTW)ysY8z)%e z8Fijo+PC_>XTp9agd(q<uR>xiYyKH#y&Z%X<|tZGft`=?ugxQed#kYfDKiO~JMsA- z97#o$PMgHKG07C&oaZrE(R4L~^|t*nBlEVU=xmz<+yZjkiSMdsi5q+vEZvU!j7s)- zo4#*++j620I$&aS6K~mkQwhJaQRa0XO&g!So=L)wmB2nwTf2Q@93M;k9jeOGkoC81 zb?}=_I#QmHQ>^O2-Dzj_B#(YUGbuG@WNz9yESN`&zPOm&-Zw^{7F)1WTp4hZ^mn1; zH9Xf7D0b^E;IaYxHP`)p%<UkS_j4DvI-978<XC_rOXt8kN^~(4hYkQ7H);EhryZ+Q zAYJb|)d|jfFENF>R11-8`NR<21LF~8i~+!5keY;u@p2w;aA)2e!Om}%k>fCBVI%DY zfu<ofLpT9F93#IF=TzufG%HOA;bGywZ6X@){xf-T-$i%sE|(}xx#s%vf5?wvA&{OU z0n*$`Aml{^y@2oMP0p+M!t=vigL%Sh9~pgEY6~K3sr&u6*$zhvY!GFQrK&fhpG{G& zCuq(+RFctJPW}v%mEf8!MI>!@6=f@FZm~gy4<)~s)?G23N_f;OG}X{`Nb8RodR(SM zOAU4gaAk|jbTw~urq_h7HS6?fZ|b^0IW`EK3m${m5%;1=G^+6c9*o%-j4fY7;^P6M z>d{+odY2`cWoq{q#J=|!z97avGVY~XE&RY3J&AwJDD@k|a>o-vb!zNO%8CRkbk_;7 z8)o1!=BF``WB8W1$}079n{1c*j2zUgpoItoYW3}N=^$$uPiaaizDY}ntWWscMW;GA z8cU~5%Y_X<Ur9fA@hCfKe=i`$ugUYAO**HA9Du=Z@#aY7fY9(hYf~t$2Q;?K_YpDp zz9EC*w$2Mef64OYN{Gzv=+)DjcORBpIsQuUzXDGbOZt676k?G25??4EQu*C!uEEB3 zFn+b8OhH6G3P(X>!g#!k?ou4d@RzHhk<$StC71_4VPJA*=acKopTr>Q8_ab(*aS7} z@jZbMZz(#QO7H?OVS{GFGleSr+!}YKpSNf=!#)-CUef3x=-&aciQ5JlC_W<CGPqvK z_n&(`=zE0+cPP8tN^^q^%7E^zC|+GNp02Erln8;g7+_OpdVO>2>SimzONH5z3UpeX zzW-sgD$X%XD{xaUc75ye3{HK!0QUit3g%vjx=ts!<rwnzSF%v6S5)f*i!SY>B*utn z^-1FMD{%Y+Ge`tHB_O>`)p+0q?5S^T+l<d$r`Gh~*yVx(dp&iVIF!Il%FQiK@Kbw} zjewhsCRwXVjH!RiriK<jhWa}_tIfzGs@)Xj4?Xx5?ew%H`(tU&(=!Nvh+^&VkHaoJ zyCzt6hyE<g_SU^gLwSa`jN;P+#nL5gx$f2pvd^-gnfLX8nf|?%Fv)tV1*z_>aPuF1 zgiuo}b*?OaF{u+O9$uh#F-07x9w4`JeJ5iUwlLhcYjx(?l!KptxV(W@zcp{}W(F1A zVIrO18VilXp(mBr+KJlL+e6b}I~SS-moM|^0qth|PNlHvidUd?Bbl7SpM~T28mw0+ z0H;ylUs`wf#os@{d%3I<0_>mIm#>E5BhuU$V&wi5i>C14Z)NiD4*GfP6e7Yb3mtv( zC*QV8q$eoI<b^<`XPuow<`qfB|9Ns756cj6t;UKSvOyx%sLoiVU+ve7zg@WR|5bdu zd)ty7A6W5;M*SJ=Lov67>RdN#RHn=vuZ`CNUO;YTN6$z^azGcmu5Sg_L8ruW2gp2W zV4d#QI=j@A=;}<UO4-11R(`LT>}S;(v(H;qp6VG=((&53%c8*)*sP|1DeK-l^`LXg z6CGhwaGyy9;owee1dDZgq+M;qMz8Xg2S7}=k4l*gSyVpL@$5~GC4n7fAc9cERqNW* z>N#W=A$AfRh6D@vjCPF?^dEyo$d?j^n1JG>u@lWjugOQj<ai|3U~RV8sa}c|XIjjr zM8$^TRpZ77gdyovo8=l{9q~xp@X7a?lWz?ez@dN~r>=J}U=)l5hefA<;Q7%cuJWiK z<i1bmHL|PpEq!!y8HX4HyyRW_K-M=QJqrtup8drw8~Oi&EJ)GO>qmY%HMenV=<~~b z+gs|ZH3T~w`*G8q;wbCmf{*txt76faDofi}z*AZMLgAseiy{Bj{7XL<E03H6l@yCc zpq=)rPCgI`RLYR!vyM<TVJ&i`gWOVhbZf=sC6%<;1jd$2_c<|>O|PAlf#b=B%ie+O zIw1zTsdYuKE1$=o0xmPnA!0x}$Ijg2rvX==haYWCp)L|ozJ!m`p&2p@)z4$r51~_B z*);~Sr_BnfQr8@Hi}^FR7oPr~F#0QPHP6?|_5WFB3kc6zuamH_2avt~AH>r4|9Mn* zQ6Vl-Ru~5XS*&6S6pzM>>{h|K_h9ft$@ncH<FtkKVi115*679MH=gFUS<=%Z<V9Ei zuf>f<lhN^s+W1EfnsJog=bvuzNw{X5GJj!z9~(9k{E7VhyzcWgN5tw2U%&X<h}|Ev z914XCO#-1S8-e^FOGwB1%loU{D{)P*zOYP={)n)mU4G2^hs%D(zSfljHV2b)VP`l0 zk5w(@GP;^A0B9A8k4LQ=pYBs*bk=83tf)hX2(#8s{m80+*;RDT4eL>NHd9%9QM~S^ zk0cym`*g&lbzpTfTkq9HsSy$AJ5EAV%A@CTB~z#z1KBx=CAZVbFlLQtn7i#Aw!*yZ zOF>&dMUx-4VD0S^XNGfh$S2g3I$kAVPVNW6VJ0g4Hk?=CfAUd0Mj~m560O70uwo6m zKVBThn-q7j4~62BW%`0#lkMhFvdOKU2+P~f96z_Z*t`Gec1P=yyJSRfoT`?}gsed) zTl9p7-SaD`({8i6|L9!E(EL#Rg*D_gFKwmXG(zlpkaXssG906(I0t$pgho*FkEJL< z^O}B-r{3MQq{ht77k(slA4~Qs0~JN(ECl1jXVMv(#-7<XOav}cC2RRQmYYsaxVgf6 zXtpIC`sdPkiAG(U-QZoOuVC>%KE2ZI?vD1a`4=*btny_NN1$S{tbVMfyIbsN@jnDf zmL@(MQ*X@|XNj4K<$qLIwBmNA`HVwC!rtPD_77Mpc4A&}d+@kQcIg&c<Xg1|_1xJm ziC<;+)HyAFc1wqSoSj>&XzOuzm`G&Z8@1N+q%V%$qM;vpmR^jB-PH&QD7qeYMf=$C z?d*UkOPk=uy#xN<GIsCjojI}B9PgX&WZxT^uCa}0s|4pFfa<PvJ?K5Vj|r2J3=h{1 zALO(@`(v)3srxIQX|S-6#45Zw@~F$q)F(*wO=lA9QE#UIf6J;G%gf3Z3mH@`T^is^ z30$s+;-@Lf+(WZVqsIa|{H~Zx`?H{s#04|>C0l{3OJgQ6S$bEo*sSqy^Y04v#s_M$ z^Q03mD!Jv=r<>C*bkym3H=^*l54yWAUwbzgvHtS>+?_^9WR74^Dkl1V0HyP>Gt*1` zxc-!aV$LUlH93;B1g_EuA_%XoS8rr{63+F7@IOmG9VMoCR=W#v)nvn^S(!r__jK6Y zYT(j@+@LLxW7RP05*x=LtFDpo|B0UF2K?<A^+FE5nO1a>+IBRxaV8@iA-y%(Z}P>2 zUZ9|rN8P2RQ-+s6BQw8gvGugB4ROcnuPk{K=JcOkcjwzN*Q4CX)~EV<b;Hz56FJHk zh}m>$_gyOLJOT&G&nAAXMI(+_TjB>s)VXQk5^^$dhQNo2gy}5FH7lW{#JT9h=xIk; z+iZnXW6?j=BZ@%y!&rD7L*SP4r^A$9M*t(hQB$MWy}<Wn*26`<9Il%$ZK#SEL)L_6 z+}n73(P;#U!~UegLQ_poo6!R2Cg@L(Nh77rgHV9L_x|^v{PMQ$A90jA!C{}B^7wd3 zzY?lJ)qQfNzRbKvfR)KNB8Q|u=E8YZM${tdm)4cY2$Rv`Cp@%32YHAOYXF6_cxB6c z|B5<AS85gQSP1T51;4sfn<)6s=Lt#Nrrl#}*-IR>?-~g>(tZ<?o0}<94bm$Kow;{J z1-&BR<0PN?`PSNwz>W5cBYX?qbgQ~IHNyzmON~Jse!?3Jm_&@GVfA2(J?06Zutgrv z>oWR~5F$2YS)h@Lmae@~Fh#YrW>P=um@bZS{F1_7l-}#axt|m)tM{r|D1gE1r=c&e z#$oR&C1v`qxz^nOe9k8@2g*w8x^9&hpP~2PAk>hL;`5jwiuz5fqoTr5EKoD4v6w?2 zNdXB-S11H{K3d2yPi`pt%%Ee?n&GrtSMzd*OLw4#<wCzJw69Dy*UM$5mMORs@e2QZ zZ&>qfV2a4A69enRS{D4)qcZC}OVcA)=oN@jTYoi57uG%Ub?ys<rN<=XYe<UYme|AY z5*FY#;nuPYi$da!#b9RH>{wF{32!R)$@wAU!Fk$vBGpYj$V|`NNrqVUzg4VYI$utg zWR;30gVyc=Sj{U%udYBoT%1lP`VTc)ky+S2Ft04Ky5))1dY5+C-=08#ELaMe(8kE4 z-pTtgjRAI;^Q?<cWB^L^%n_@<ZFR$I+TE_#-!%S39FBk!&)c;5poxQJbL7?u^&?Pv z1G{SZ8A@84z*QXzQ88~X(!!wpVsS&y@`oE@ci}AT7H_-5EvL}2o`&M%R<|#CdR*fA zH0t`M>wVouA#1rEuY~8TOcr*!yzU+Ah3#Pigq2P(ERi<-{o98}a}wz}?i_98xvZNw z_xn2QY903ln1d+WUT))$k|<R9efmC&N3&&mg)q<YvClZ8aObE#H5PZV%R-Lo6GfoN zo#MSTA+eUSU5W?<jr)D~%yGrymMU%B%v7_C4UxV<!7-~#^6J-DUD{^fI)kI%T*8!$ zmrLF`7f9zpDRAk@1M<55R5pL6Kj`y{btmN@-8MaP`=yIJL%@cQwv|4inS0IS?E8vQ ze#>teqxVD@BDebZKYmx6y?c#)zqpQfb}|AXl;tV#$2Cd9X~~PRh~=;9j_ufqf$hkd zS{dNN)M~fZdCye;z-eB<n1gzJGUt|vKT7DxvTcdt4pqOHM18LNqs05WX3!!w!nSFp z$g8NdKe+YI>B%^MrwCu`nUVQ&Z$+@irknp!1%FhoeMZ4)PuT0B_=hpYW11N%W5P^a z8RYS)PC51!39&~OSoRGnUQ|$JIjdDVTOl4hc(Zp?;EDaiHvxfh`Rm74-<5EBb`h*k z&+p?_-hR&JT`*P(-NJsm*c+>94Ga6deC*hou61dBlPUH@?j^Ysuc^Zl`0i-Y+0o)F zTXRl!*X5|*xuiVA3u0#bt~*mNu8!b4+!0?KacVLCjdv)AQ3swo^o$1)j1}a;>NPLC zUZzrKr0cJy*<f|a%0THwTYWn)dP+{y1JbI)jd-pK^!n0l({hP<%*}`AADq74qcQfe zH-bwqI+Ub&i3<Sv#*8VsxT9Ozj99a+xo@Y{vk?qNgD5?6w&syT9f`-3W==g`KmXgu zAP#nREwom%<^9PSwU|tcEf60EHgpL8GC%$OoY2cfldsVr^%>OZXAmkrGYRf|er<FF zc{587J@vFCO_z*$60wj?b5$^*(78*<V&L|#nd@2Q*6{ohO`<W&f8)MN)NT4K2%hSh z=&FF{^jce3vQ0AITa>0Hn;j)t&%r<(mog;7Z|svjHaRv2DKx_|u$5XZ<O``YW`JDb zHSt&-X^{5G%7cI8OY`OF&#`(ACb|PS+WAV^gJHf!kY+yWk0bm7xTz~Z^>LXd1TI$B zTcby)S}M8omBKMpj{nj8dM;5+Gk%2kqP~56U9;3CNMVGHqlmr)RT;o+T|%;}xvfAw z<s4n81*?2l{RZMT<Ff^7aGeRL03!^C#U|N}_Y0gI-{A65F3})YBFj0ruzaZ*u5c@P zgvRCHvt)yE(8Z=UIf7P*2ehvwN{$f#(Rr9>nA%f7dqb$-oP0{V;vHA<Vhu@su&f}5 zSE{Ctb7v(7Ay>5+UqRKx)@t;B^@xP%j9nin(;$v$mk*&nl^{$DbegZ}o|wf+R0(+4 z|LDwbSTroPPvRq_%aZi(<$SoOkK44ggoQf)&b)rQwNV>xW<ywW5jUAfl=IY@7$cdC zgF%xRkWM&H|H*qXoUx1jbz2vA^?4z|u?!*sdWXX~YLDR2c-6=i<i7Dbm}i<FMuz`0 zPex2HukpS4=Hb6Cq%*j#T|YDE@Lrveh}}x}^fJ7zpCr)Dd#-5-;v-F-V+{2SK??^a z>cN7=(8Zk04{7E4x*1sAa>u-*H$DDS>g9>o)|O;kYaB`|gwgAl3i2FVuu`S;CYH3i zA1>Z)(@;qE3`}yu1vg^n;I>XBaWB*9bXaf^drYSK%Rw?^Grl@Llc;>l_e|>ah!YXL zrb?kzy)ouH`o<ulu^`_1?le~30joDtIWXmwdMkGoRwsYt6oN);iNC$UnU&sp@vKWa z{!8*k66gn$+}%qydS5yaPPTlwae*OC2XDLpL^X1j=2l(Q3sh$POb??O)}LY1BTdWy zO^LsAHxDhDYEaCJ6(AG$2Si;(Q}rNk4rvT7QO3?wB2CY)vgkN?&vfRa>8xuCJQ8<} z912jLAr?-@1s9hQ+iJ6-%#*w!C>3#R$~$36Dtm1bbxzlGLa9$frO7*_Y+Et-Mi#_o ztZIXj+lc&>S0Ie)9F3ydu~oQ}^?*vH`8BLY_FZNXo7X~-@Aa-pY~B%z;I~BKJ!<|v z6Wwu(+uI|&mMGO^`^KYNGj=>CJWR!;v9s{e^SN4;lAYg^Mu#+&E~Cj6eMS~j8@SaG z4f2pGg{xr$;s6ZVz{>@zx4?Al>STRYnxe)Ktn)L|P6tC>2i#L*lj+k!Ge*X~+kQj$ z(v9|wWyy93M)QgA7EQy{8`VSV0MM!|dVc+)^&^kEA^v)!T<CTo@vH!~W@T_qjdg&| zH*L|c*W>jm>jQJlsCqXQvph&=v_YuBlUE3*f0Cig`039BsWP7AU>Dp_zSW4%Fy?#m z`)79UmSj^pCl#E>cVxP61gnoYR#4nche+4J#@rZfWRgK<sP*rohGqvR-5MCuc#z^w z!~I4N`g{vJ9QtwaPvg+WH}l?N1IEn=1pUA2Yk@LimtR8}E8P@Jxa~_xD&@Jkv5lIz z2OG;MhR=&!1rIg!iPjNDuh>4^f5KpBhtgTRnXfpiLjkGWl)~{O?;+ojdDogVjNvQH z#STUb<~c9vIUGeS;J~2ovc8Ir@cDNkzeXLSP#3FrPfGVU?y!GG89Nz@OD~#tQGRo@ zHYR}lrA=SF;I-Gu*BD%Xza4OL{3g43@?olUBTrTA+9=<Ck`51RsycVb$!JSEFRlH` zXUV#K`{AY&ZpKd?8X;4t6?~}2>+Q4abrftBjcrwit;tQ!<&y0mD}p|s7l2_qt`Lye z%&-CLbaaGSuK27zoq_Ho*O`_{zPQQlEv&cZvNP*mscOgV<~L*Hxw0EKRn}~}{oZ{D zq-&5KQF}1Wn)U<s_sxSvdg8<K<<vXu^CB!^xEs48tnn~DRY8dWC`81C<Y_OVLVrnj zgpaX8;<>*uk|?}prWMU%el~V44{MbP9A%<?R|2`ZA;NWW%j0-NCpDvAMolzo-cO~i z-b^FR7$!}Gcr8&l5obfHhSXviZS3y6Z3Ghy!(15qfyBbiyQ?7W$>Hj^S1lgUaB7Q8 z9y3S)`rKT3oc!<E_IPz@%+HZ9iQ+HUIc=SaDT)%`x!UrMqi?k(yqb!@dC}7yK_P|I zrY7~t>C!>Y4!A4E!vfJ*{<zsW9RqP>;ko4~Vi5(0-14%TH~Y5H>vo8UV&0po%$viX zQOzt-DC+r0mU2)&HHkAl5!Mxo$m;mpID#gDBuM&wA3|@=pmaRUGJ#4xonh~>`ga~_ z<47)zW{}n?t7w(NId250Ze{EoA|ORVZuwe$vIx_=8TM7Ll)#gz%L8IPF&MuZW?N{a z7oHn)c1bh+Qkl;PS}@Bbf>$e?YHT%hDZVk3LThz){rVP21vaN1{NdL2W!xf`lYo^N z)z@)w9-@N?_D<+5s~GpS<=buSj)OK_QJRp(R=wnlpFBc<5pCV=?h0b%K{?6)4C_um zpVb#LVS4h!RV#XAQa@C6nqKPndgFY!>w@w1Cm>)D^=79#oy~x0$M%cim<|11316Gf z^4J^CgRGmd2;?uJGlqDM2e(ec$^v?92NG?y>BzIRQsr2e4IgEYhux7Qf&!Iz-M!ul z()Ag0{u*%JAHOOvKqWPE?0_YsGzEYJ6GSgIkdiII9~u7BC}<R<po4<G6vZ2K@e~Ws zWgYli(Kvqr$yK~x`}_o{Pe74SLepUles3=q7#4pRvmudPqoCa?NjhtZ${CDzv?rWY z#Y_1{qJAc~-?(u@=cZ}Lk-@9R6LYd+>|u=A)1g)-z;N2-_x9mCLp_h<D9>If$h8i6 z0R1*3u{<Id6cjDyOzP5CUxXx9<p*0XDdyX$J6n0tN_<nh7@lL^uxfU?vTnmOA}p;A z(72t%8m7_~<@5Z`V$D)x#1>b6##x^dO0WUnMS*ba({9?w5qs=>dpEg2{M|$9Ysn9s ziqCBuR}}M+(D)I}dOu_s+AJD$^>wgTh~FQ`8|uibc@u_ix6S9*88s)c{-?)T(1@6u znIgR?abEiZ)E_@uSRGc=SQ>8#AeAkZlRVNw#bZ;GzNwEQSr#pnV`Ba9-srZ&nfhbn zy2qP-c+_TBAP7V1#aOn8t+q492mI)uS$*bsK3AVhw_l73&<wi-&~&`oZt*q@?n!@i zUW+47MHFZM7>ur;Xk1+cNnM|=3o;BTu~Z%%v)X=`Y=>g(rm`7(X8gu}&hlYuDER)` z5`l!OO>=VR%hqzis;P#28NH^tg%o>poa6qN<;mEp18T;|dkEF1IeJSE_fw<V{Jd&^ zA~KcK^P~9F#kgj^{DG^^c{Qs1vjXY?fp2s~dtk(YqcO~`^mK4zsoJoF2kA$xIr3&( ziLLHp8F{_S6YtNy>4S+M>@<lJ)!Cr?qaVjxpS;);56>qFk(YFuQ5Aol>eWcilJBId z=OHYan^&>k4_WCq#AVs&vSPpe9;CJB$7o1b<}7`xIgkI+3nK7EubF6-?YF7;V9hC5 zzC~D4@hpr#ITZHrgRmlhp|I`>6@qO2wuu8ZqU&wQG>;o>dfWBs_o}Fip_&gU@au<u z_x}(bH;rK>DlUeX)`pFBnE$MPG%jpzl;_{G&fUZIvh)>4Y=e|7{oylI=imERJ5$p_ zyPJ6bsm)S&;fYwOV}HuRnv$R9PgHDR4K5(R^A09v0x15*q!k_3@aBizO~_X<)xxlW zqA1w)K&+ZF>bzZMpm*`VKSgn#w`ferJ{8wB9skyTv(ZuylZc_h=_FE90ccy8t3fgY zuX^|iOw=HH_mHZSd+w7F@M~8@6|W?$pTPoV7KmZ<G%b*`e<Ch($yqOs&+%P%47>NW z3W#^w&F1!Moj3uT@ipI{<wMnn;jhhou6-O%-`3;88MbU%J=Ct#nz4<zYuDvIC0Two z!q>j%?n;_bTX3Uw`f>bWJ_E+jJS4!T7S;Q^Q8VVCQr286$jSCa`Z;&XLQ_u5yZ#Ir zTVt8vN1n4~npLVA9q{LAe}<_n*Pe;^;C4joIGDPt^<q0%Tj|K$5rH52V}2k1iwkok z@G0n;-|jro4&@J_mz@oE(AQkdD!fzNQ`5S6gsJk++>g@_{vcc_dH;pva?grSZPdr$ zY$jZP?J;0UJ^1hoZ6dth1d5?#-41NxxsfzFkX$^xtxJ9&Cyk?%Slbf>mOn9<CiQhS z!hiX<cGldtY$4R#1%kbYpP&brF}mwJvQ>(~q^7oG*kPj_EQp%1i<9Ay4lqNn84Yra zn8L)OIYL<hxV89?9Gpv7s^PU>dvuq8L3NE-ZKX%LcJjNObFca+zBy8J{_vd^0iV{> z$=QGThK3XQ9ywpCGKpt5YQpEK<V9kG0eEE)^Rze9IRLR13FWa!<>`g3dI^~b=86mL z0+ylH*PzxABwGNEg23mxb*d+KGGwD)<FtJ*?O7g<akB}~do;}(kn5|F?OW{2xcHkt zC0T_*0M8gnIi%s=24kc|w3f>?k%W{?Z+={%-0KEIYct5(B-0PCMPlKp<X*K*IiJO( zLw(kUJHhX}tF^2ydtE77q{S>HiFO4p$q65jREzWkJ6v#klT;N4h!ytLy7inCmxBKi z>3D!gG7wfE<*jK+8Y>&o)Z^T~sTwS%*OFPyA$o53A$*rASR8phm-B*&L~LHaZr|Mu zFXQE-7BNLHT2098iCEUe@IQJ}6JD+;H=8t^>9d;>A4$nf^8ZY?)Oi?z7QSZt-GVQf z9MQxZ34aIul3b}d6_D`XL6b00nFAgjpt3aiOxRRx7ApIcC?#xaszegX<rM9@Nf@|E zu_CBno3!2sP6D~F=;=0vJ?56x2Y|@Ag9Uo<{pOcH_TKlw-(w#BsnHar87vy)<cpJV zKAiivgxg5`=l`T{hrZ%LcJiF#0=(U1D$4MsVsOk1FMsPS?`ly^^ImG2dG_4O_1_y` zc?(<Ok!^VGknJf`;TR7oDWMo<YUDA&&*6Ob%6pITGXYMwG~?ZxtZ)fK^)7}?pKi&l zFpmq{Z!I{`MTI3zK21bD_U3=$TVgpPh8Ij0o~aDBf>0h*SWtgSbT2D&>*$EqXE~ue z<++>@=1}136xc+Tn=8hUSqJgB$dr7Lwc_uge#B$K;@wNkCZGgBGyum+LrxHK?$W^f z4+ep~un>xS=oh6l-7M?uElv*s%JL^CuZ^O}iaJNH9ijd}Y*tCJlw<>|2?CSE91`v! zV1Jqqil{S49+2>y1!e0@A5@1;g4BiOCMKSQUXe+aQz`Kk^_-?E3r0w0$*nngkmmTp zNX$~AzFQuHR?HTGhaul;Cbx77)3dLq?AtK0LcLOMWKa2o!oyv;^^cc`##%IZ#k^PU zq0cnq>RZ%0)*vR2L@jy@B}$l-J?Jj4a9*-Vp-Yqo|Gvd$kT&X3w1tzff1p_;n>A`I zk^zzZ!uFzku|aBx@iSu?^x?fgMU_`ABt7NBHxaSPxo-_7XnPK2V}&?sSqmsdkJPQw zoo-4{Q2`>SG_)Q70LTLX3lK<s(X4=+15^+JbZ7Mt7Q!y;Fxgo%f`^HjmZQ6B$I@B6 zc?=V~>L#+`s5F7AkLsuLq^(;WrVeY3lVlu-0yLP-K~|{Mr2o|8rZ-hcEWMy<ck^5_ zg0+-antD(<S({douQ-Ve7qX#3m&SItEp@nzqzRh6`^uDb`GkWbCxQ*bP2&okF@-fr z38@)Vx}h$+E3Cmi^!|PgkODc2X<4V4-mc9FqO}`9WWY3GBe<Aa*$-6oxv=NdMC+eq zW~ChKHmBLXp0Bm(y_E$tz>OgrYI{{R2;X2DC&Y2U<yWEm;tQ+~gFH26`s)``omrKh zVDGAa0x%$Ovn4wxF?5FJTvFPb&N)f{4|R1*0^EfBg^JX0?d6Mqe^2^reXNvP((8dE zV;H^s&4S@X04Tn5L;3;9fI)s#ikNh2<MSz*$E%r$p)!V)Gg!@%;f{*?MR)YUhj?mw zzAkcY&>+=*b&Be{3!~8QsV!<eWEMe6mlps7giBl=wK*(}!Qz0COCnE}rLoNCeB;dh zj|GT-Q8@(;ZZg(Ij?CR4z}3=syTqq4W}fMC=Z;rd@CzC5@&Gqna%uE-%a=-LM-fs* zJe@418pq{FsUb+VQff2QcPVv5W7(bh{9ArI4aHuqJB{U$yE{$QDYCoG^@V=BEzOOs zyR8qN?C!R8j-ShZebD{R@9V?f?bfgD1IN2xI|k|G_Buzo?(TI>O1AAino<9{_n2fX z_pN*JR+|V7n@d~3leNIF0Z+;I<N|xQvKXiUHV-q>Gio)`_kM<F4447>tNYE*foRun zFPwKQi7)9-<v@b~hztT$1lFY49QOHTxjeV8rXbltmIp}oIQ^6te{Pfq)j3hxXsemS zOq0VTvT13jtqgMx8>3RXy2iP$a2WH5FsRZ2+W7dNuia@Bj!1^w0Y`IasfS1N<{ICQ z7A#E^el1@65|_+n_p;pg)$O7Nqotxse^@`aCxBVu^&lbXU@m2feZlYLqSnIS1Vnv^ z{`fFzJ^sh}x2TVpbA@O!jwLYq6M^NLMu`(zUuC&)!)%V0TL7m|Q^e2>(3ZE2pMK$h z89p<p<G$I4%&)p8@rB(EPUOC4z?`f5h0LpE#I>gQ*NE%r8i~{4$GVlScW(TJ>d@R! zpRVB2sLtKzw(I>r0D<f?{c`7OZG)%x+ncy<5L?*T-fUA%aDk@8uGh~lM8$ocx_;>r zO)Izfvtx!iVG292e@VwMJJ?WyPK7yP8EXx4vG~$z0)rMmgipy4Xpf{|^lTo~uxK)L zyHHAsaVtbJ#QrgdNGlbh8es9Ma+lUfWEib+T*A`GbJgInhMjahuGL5vDyW;k8$6^l zlkpt#3j&-~vz<yq*^rb6zar9r2SdX86whRiRyR1SIGSnBGx4ihM@oB}OZ5N-NA+K} zs3(9N(X#=-y>jVUU4u}B7!eGR9ef>_fj&Fp5kx#(R)D~G&j<Iz^3wGyut~WzX`&h9 z7MJkUxCjwOch35X3s6dg!fwGF$<%perqxJtZ}H-<Kx!Zk$pdwx?PW4d1DbI(H%y4M z5E^bAALtaQhFl)MAx?>Ne6$fv%>o&vf!l31UGtgvrYsrG{$PlOpQzo=h%5DYFC;!= zoH(7(1a}{<L5epu8j6mxis=t8Wkt|C@YQowe&XP;;w}kv8qBigm;`}`&jkeO4hvYt z4R;P@q!TpRfD8}xCB>vio^x9q7q+$L)f3}Mfge?W#R-Be8?UsPJqm!6EIztVT1yJS zR$yIsL)%>$t6e1(UZMyPtBkzyPFaL#jy}Bc$HaSECZ5H<$+Rfdph~f^Y!X#TBOg3) z#c43&Y6X%a8m$Wq9^|j)A!#!Enp2q7ZvLFXSX6<`aA!a3?ao?n^X3ggi0oSVs5Vsh z#M_=#8~Mq{o(Ws4uovsUI$T>E9Pi|5-IlDshi}!N02t&X;rh_*OnDC}xs~Y~$BznU z<-Ii8R$hl5Kdxj_@G+5FozFe)ZnRMF6ZvY#s&d@JJw(mUD|%=7eD(NA@9e|Cs8{dT z{~SLZWNHt_o2_l|{qCK#Xb&xVwYIJG`xz;-J-o^6!|v_heao}$kxyTJ_#XSapUl*8 z;Z<8dEd4z|vFM0hdbNJs_xt$+D~9+l{khz&iE!G@DQR)jkG~=}*bSgY(tqx*TPO~5 zwZkESw~|r`-)%W+;hizpL(;4mizOtL8j;6$>8;Vl1GNYvob8RviHo8f4X}Ou)ZH}J zCPNnAdUt(Ot2EB{cA}RaxUxQh0D3fHl^V>UsA(dOd%BuYg=;c7dBy_^n*d$msbxuN zPEm-(u=FX>8kWs?0v-l%p?&>aDx!zuV(%-*ceDU<AInWWd=9z9L108G5ghz^XU&DW zlz$DD1l@{(_w-(_JSd+?#JG^K|GDZj>k?JMsprhsFX^+1!Gup-ia<3=_0I-erU4hu zHp+;sv9cRq+w$|Fv(JqMIxc|sZ8<y1WF&me^>-4|wM`O@_hbU@L`QQ}TmBTMe*W3I z>9<OZ3jjD#Ky36L0%eiPfL{W=ZFep66WBqVewRP6rLhEI9lNJ*#c&}^8k2ESi52tb zhm`|sP-wEuaUA`18W2#7X^Jx%`j+Vb2!2(E+$u8TYQ0>`5${6_jLv>MIxIp=(?sF8 z&FSf*qF**h|AzZfr7<%UkN5vmxqhuCaGGMk&30}PtbR1-2}v(!fqvf~n@ITK8fU;k z{W@mq?JfiX!OdNH7N&^Ifx0uqk`hR?(mvllCH8Kx$GaFM|GvA|^Isf%j0U5Poli>< z`?J{2g_eYy6TwSvFsxFT%mDMUwD8_8(jGTYE5BnK^=#xHR~%l%eBY{^nnUePvUGR+ zQHLVOOt3KIy-g@%j&?76J}^}J`+)O*(*t9*a9YXQ^^NIEPLUU7OHCR@7`poBT<DWH z(=$XQA68(UdgbtQi=vC8Pa{`-^IywZSLVbcAwa6b$kr#@`@@~aiG^d_q4#VQbDRNp zJde7x-b?LuhI)R0K>PZQe7-qCXjbb>+&RHSB=gsUTJ|CIOGR|enKjEgXIT)fVdka& zc=0)S^6#rJCSJJSFj*h>00XN}f{RIX>KH1uK`Io9PFD$90%Lr(4|O+*EV-b1H8E)X zzW-DrUQVB0o7=Z)3CshhzM#$L!59lkbh0N@!b&vBFvdP2w9+yL!<`@?Mc*N%y^Dek zbw(H@GAx3VsP*Zgg}yyR#`{Y26_|VDL`I%TjN*QhDYsjbCBuORMpIgcnj5EJ#lSX} zEd0(DE=A7@0Z?$*`DZSG7`I*otw7Q%^@4R_$wPokBaHq@QKa{F2zO!fB{7yKgLe&c z?rSuL`4q>g)Og*60L```*5^`gB}(*CQuxqnFHVz`2r_+pFujFsL?_s>+XVa78<b4; zthZ$ND1{N{rf0e3S_Nb5A%Oxc8I+5mPn4i`kztizQlYG|uV_=)xG=em3`ub6<Z6Zr zq`<k<y>OGD^N1kU;EW*Y_;gHK1UKfvEr)@VRO$n06()_94DBI7*^FG1q%m>$um@;A zYC=#S2C7a14|O^}u>{|K65M1QcMk%*Xuk8F;z=9gR(1^K1cQ>5vZ~;2u*j?eZ&>`7 zlnP`z5}^6&ogDANu-@d$+?Z;i0sGgBeM0NvZ$cn8y4CKd)i)EWG{Tw3(;rB?tv53S zD$zU}q<=;N=bpP{o*B9K7{hj55?;J@q0XTZk${CL8M-wkTBO{&91}!Y&I4KTGR?Vi z9H%9_fW8(nL=4hD8O&Oc3{y)<s9DPHZSY}Y1p|%w0KyH3EKo+n+|jV|X4v;A`YH@` zbQ07<WGEX13qWG%O<=pA+)fGl`<gJ*L0Sh(IwMP;bGi&+I@dQ7R1<{Ezb7z8uxm#z z7==uaC+6Kn)Azg!`bA{H`QGWKBeuEF@Qr(i4DxDKgSJ(P033p<_G&l2Pc2fweBe^@ zJ1q&BGhqq-D`j=S!Ay5_$L}gk51>vUG7x24>ns`a_NjV0BkM>xVAe=xkuZ*9OfspY z_q>=vNZn-~#(ZSSBD`bx)Tp3lFtPYu05Ir21jo)nodu86P@P~NimUF``)jALil&$$ zC7Qc%rmCs3=M!-rQ+I0jJ#`|@OGdAzfr0zbf}u(J8(*NpFor5vG2L8vL^XqNOBqzZ z;8|1}az81e)8*Kb<rk3OFOhP0A|M{{Gyu2}aL{iXn7R^8E|JkGC1efngq2}&zZwhd zLn&aIKp3MLn$SlSr0FXE)L8P@6O^t*Uo;phBooZ^$M(~2qF*5m7aXJ=O!v@(1_J;X zB|}v!NT4OPu2OBCWjKR(!$w5uCrm=U5>#NnD5V&N{hfW0*_X;hG!23#&y^V7Sh7%n zT-R7z!fJdSk!Z~aQYHt)lInnJx{xPjevJ%yBoGrKo2jH}*~bYk!}5p3^r5p#`l)ki zF{~IFF4+g`0J}aTF}+fvJ+*|c1mDk#y)$^6)u;tcu6CtSmNa}O)B}m{vxM-IKoyw8 zpWe-6&e+|NxFaOXpH3zdI8)SaR8JbrR3jh_oS_<-HZ2vu12F%oroTsI>QK6XNLO}z zF6)w_e*j~QBT-H8Fy^{kJ1>mplC@d~#{->UvHkchgj?HfC%7idRy9im5;_V3Vv1b+ zR`PgSVGLj6PF+|wU0CwT;4w=^ptCE3*0o?Y(`gd)w1naO+=f9g8RjJAJ7ftF+^^53 zvtmzoIs$-2CE8zb=A9jmCL*+YKk<J6fk1x0c9y5Psu1A-0QnH3=3uerAP1^&3-M47 zNBXi1_jed*18#tFpKzxfs0xxmP$rgpLQ8KE_6aAqfUxLyQ|nzvY7hDVZGJ!r0FVyx z;6&Y!4bs4y1R<3X_JI}3QUd{_M@kRrAP@0C2b3@iNt>_w`d1-_egXS}ONfe7ItcS9 zeA5YNU&e`dxQ-N-j0HLb1evy~s;Ao(dg-7KQ$P*es;|Fi5nHwm-O#(ct3G@Su18A@ z(V!3N06Ez(cyL*y`1gu(&;uv;jT!kv>qlzknhAeNVMKar5dU=w!QciP5De3os^gWU zk~^<*01xC)4gyiE6Oj$r*Rtw4mV!B$^gs^wpbBfS3zEA#&^r*k$dp4ckE9@LroeG^ zkPEIbZ+^FBwy<D+M-VZ)r06#UK-&oecwY114f${e%K!lLfUo%qrWK(N`f#-}>XG`Y zKHrKC@gN75@CuNsqz)r+Ao_R%A%2${403S5weXDth?BZ7ev9{+wZL!*Az}sE26c$H z=*wN|V}I&Xn$#c$kqV>oYY|m^e+IF;p%)MKKn+Jg4Ax)|>X4-SBBPBbasgO%20V`u z$ce!=2y#~n6$W86CTSAv3I!*O{6&xj3bYA1v{bx4_Wytm`XC6DU=Qg)5M5jm_9wr) zOAqgm5A>?BMf);9*<u>`y`ew~(tE((7{Tv3o)p%MyeM~zt8Sj>y-$p)xyQKKb)+Yo zyGTmBID8Qd+RF%W#Yu|}av%uAKo96pGN(xyv7nu&=D7zPiE?`itB`QEAa96V5Yu<4 z12$p>+6M?plD8}m-wFW5fClnF4lX+qlbpZufDSS&4r_1-+n~HD)1aOpdl2l6sK^1s z_Gl7?bI=Ex=lXi|H)^Rk5Hpv+qYw-q0J;JZvfahMeqb8_Ko85@5+KQYAFRoiTMrmL zm?>ip;y__AD{rRI3Ax}2DftO@)?&|x$45MM|Nl5(${}+5xRCo*3s=d#kr+|nE6&dq zdKRk>LXZvdU=&AMn%iIxe&7brKo6sr!veRl?zCSCYzi#>f@xc9wa}NRaE?`X(!i#8 zLwmtX*t0NT3axO+G<L4zT(rAD2k4-*Ax#u}YY*EX2Zyk7Yg{s9Ne%4?0IYz128oPP zS8MRc2eI(Ln&^51Ou)Qpr88%5ZqNoXICI?<dg4%<fJ+Vnk<mb*J{IfIl<=*|$uGN` z51p-WqHwL82~Vv+gfgcKb<hg7aMBWO5w&Ith3(MCxQ6srZAExp_V*3?a0Jwl+U=~- z@=%)M5D$U?)lv=2)>4{c7i`s8hw|6kXa84?m!XafQFm0DcL%|Drx2xuzyqG(jdRIe zsJ#tnuniy`7WVMY^03!^?WO#3r0P?(q|genU;`HVp`7@jwkMD0>wkIcbY!N8@fHeH z=)^uN4VZA?*cG-`O9^yP58e>TMbWB*`N8&J33Q+e?-0_>oh-X6qtejQe5}W(5Pw~H z3YSTj7Tlehrwc;>&i^H7oorq6pbsLf5A-k(q8$|eEf3>B4}!o3kDAOQZ4UMD4z<yl zp8yI9DGIJo3oW|DkUbH&$Z@)QW;@NHo}i)XTD92K(L%5d>tn)ftmH^4aDy4Hd_Al| zuDQ`7;^dGI%OD2fU<(Avi6Ul!)&D4O0&(LC5!oTybUkU9rC6WDp%1-FU8D^FbIsb{ z%FA8B%lj)2yI=*oP!AV--<vBfFdC_AunhW;4GTwd&$kFkS9!Y~5klR69fo>CAPBX9 zOJF?b&jq6b;mG0u+WctULUE+_S3qk(3B=I1`k>*{VzKog2!vn{-hi)m#=V<|3nWK; zJpsranhoJlvb>k%&2<jRO%22@79eTG;W`DcuyWS2yMMk6XP^&Cn-1o{ayEI}&{=uf z3K5Qe5D9E=Y~Tj^@D2H}ywb(XTr3V#K;L{$7BEZ>^56%0Q0n}f>d&(3`q1k7Fy#6` z?A?IJ`lis@SrMa#nFApWL;p|=_An12-NMg>ulhg<dXUt6J{F`s<lA7m#IVkNE)N~; z2ZW#x-f+UwP7JDW46L|tvv;2tF^1P#56fT$`alkytnSQp?b+`2D_#^ZDh~Ou3v18| z-hd9u&MX%@*ZiIi=@5F1{0)@=5Bku9898_mT<`~B%L+kq0ALQ^004eq2_>J@p$+oJ zRk8DsMB5<cjX~NVd<MIqvHYv*kUH|qkj^5Fq?Lf&@xbr8AYwLN3Ne1`>`cP;AOz<S z4@X}1zqRBgEDlTX4d~G6j{g-wuMgA^2fNS<texy&A1p)-!b-30$*#uw07?3A4(h|- z(^lLo0qZJU+K}J}rvE+<v|n5-CkTe$`(d$zv?C9Wd<(EHEq^ZeogLBzL=3%P58}X{ zND2VbU<=AeyC0#*00BTC0C`Kc(W7V2-av*89X^B@QQ}036)j%Gm{H?KjvYNh6sJ#+ zAbsTI$@`dc<4J|`>}^{U?U6os0#B;MnN#OZo+|6r3yEeKx^ySy#nWf4lD%;#Q4*9_ zFW<mSJWZK8<th{?h6)w_L?@D@H+x2Vo<*Bh?OL`LS(XJbWm~<rXcf*Qhi+G#WzNc> zs~cGG;Ir!Vsge_q+&r`2E_sV*R-i({66xuqv&<a1fj29E1|3?o$9&=R3E2jqo;h=) zSGvq6PM*+9@Bi|Zed=2GZngC0i4!7E9Kw_5^i{GZ@0{n#^78$p4D~KKeap_IBbU(S zLf+lIf48d+K(saT=z({;y`H{ZYXCfAieCQwiuPjL6GRCexp1w+5+g>r+#<?ns<ZM@ zN4$uB5~rLscF`vx+~}jQLJI{tPas0{nT)#&p*o2k&iqhinO+u}@Iw_{`)ZtgidiEb z;!e^hnoIIoPO`xitO%WamO(?FyarscNFxPf4FKv$+^<N_PMT+)mxMUy5ptqCGE2fl z%;$_{@}Z|5md1H3#n7;9$TND#LZg^?(jiDoIp@sDvvlZ5EuP^rH1aJU^Ml8ce8!2B zPD9U{C;y-JVnfItq$&YGpL09}&ntWI`tgi<7CW?4PcMQ}N+IAO3eF>2iYlLNra<Qw zVkG@ER*!ztXPYi$6q6}^h&iz-BEfr08~`2!)2Ux&MRv~UC{Ya^N{<XN9riR;<jQ2P zwFo<X{D8!s?1ZcF5?GI&&&OrfAPOCFv1PYNVF3^X04bq;>Z{oD5h|Kl23?4`cCQU} zn<eZ)2O(zxDAO#X);-fJ481`I4PNX)=wFL3Jc%{1M6v|1Lj9$1VN|7UubxYyq3hX; zWtA!<KPb_M(0sx|Zd?mJ!_>NbvI9Wnm4DXF-<Jrw^Q{#Zw#hu|ycFjWDIEqnR)q99 z#{a!2?FosPTVe(oWbaO5&>l1(q{r*1&mPS_dGt9#oG1?swK_5K=>?X0Chgg0v{j6b zo^<S4;>$b7sqqy_ox=DjqpDlOoOkrmac{{73o%kv{HQ4*L&3gJj$O`qC7PKhKa{%m z^x0F=O2|Uo$*8`;w-}=MB)#^vP*oD8ZUstm&bJUc=LmVSxkN(Svus(PFP70q-IHFi z=5U59j55=m=jrfx?RPSoEN<c9tSh}kmWQ<vM<fIQVhksI{O!AouAa+OStB2B<|#*? zS6&?lE_x9XhdmyonxvuWeFxk~lIDS#Wyr%+n=^`Unr9Gtgbqgtq)&9_fu}QU1OFcB zkXAIdmLsTSDM^Z2gFfD&E=yt1g&d&=HF^esisg+?Ujd3(>R}CW^~`K9bPa>HrJttg zBOCC!$@FfPs%?lt9O(E-(ttR{iG&I`Qvso;GG>k_1&>4Piy0N+N3qMS3LQ~;Ui3&< zLM_e18~K2QAM|m*ABs_o3L)Gs<RF|VLJ(CV0>EDEGYioz$Bw%Z(Y7E_66&06P<1pC z0L5XDJ|5DN50Qf<6r)6XC2wp=5tkt^37Sx4V+sT_j0kaLrqTg`5`sWS|JXQ6I|?g5 z;s{@?P_@9*>Ejvfb000wvM`rX0&7Wm1ORfx$s&o#R@;b>FvaK@A3aDP*#G;~!p^6U zGZZ62p@Wq))$$gFOl?*0sNO5GaW_cH$s3rlM24c%PH|4ohyy7bGe7hs^DM9!Xt<^~ zW^#^t-VQg3)B`2z@lHohN}ollo^|HPnC%o4fl=JX5lZqv2%e-sA<CgpY7!0h=_8mH z)rd#)5uzBLG9>yk8bj#$Apn|VYykM%Kn#e|$xZE_O2XE{$brJxm;-tj<Y`ZeGemtL z6LOKurUQS}IB^t6ib<VZ@1}AKad1>t3*%CoP~weBOy#6ltq*r3C@>{eFna1x*h80y zLxG9I96y;UT35!QNc}5X`uL|kyg`p!M57#f)d@n4sgILMij~Qt4*wwpK^Meo?~U9l zNwWAECfNw(O#rCGI`hHT%6247t3nD%9ShZDp+g*E*ar6cCD+nQZ5v<M25qynuqdtS ziG>SiZ8`FdA(|r^u!sllg1Vi{GE2CmqwHDX7D4I=f)M$DUFgc84(UEuAb4R99rkmG z+h|j_N4m@|B30GydRJ=HSORI;^*hSS#W(q=nR_d8zIs@JdC)7HNq^=y07wi$_1LL? zkp-oCAma<Do6&+5XC8WlWF-24oe0%IPz6tfWbV1eECA3y<+6)1(voN{I}EhHwO39G zVa*1`F$LmMXMbT_u}o1yF?)Q08rHZ)R7{%J=>jhwLKqH3t^b<iYw^_{MX?xfIb&T6 z=kF5h<S>&3qAkS4;}G;%DUoGGs9UOrvRc+G05oZmm9Z3ZM>q&|RGVcji^v{yu*5E+ zF%RdpS(~TTC=}6rEp@G78TIh0X8&AavDlBGuEMdF*F%jpXl+pDo8`~ow1#5Tqa2SN z^qiu2j4lYa#TVP6Zzd^@a5U-?YDDwnMna5uj6+Q4{S<ZnS(1E)x>K}@i;~jOyZJgN zA2EKTb=wMDyt%h`QL2>?D6v7-0u6xnK#gy*=j%hkcgs;LPz@<q;e5DiP#vDmw$6}^ ztNCwo>BvWZ6vu5Xy+wZdxP=_PTVh3{N{AOW$w{tkAph@1XS?FCfSX*D;InNoqs=pE z3+bIWhv)+hM6+SL_(_m3p<@XF^c!$xSzC!$cMa!&;;paxv*=)_z{NQ5wkJ+;fxJ`S zpN$%Clf5BZ6VBWte=Z24O<|-RFT6XW-OP_fmNlpX*PQ}sYsRgRa|~R+;5~yv7b9j9 zlTkIOLF3bv{+aIOqv;Mj+rs`GFO!7DMv)e-VJJ}plyAq~q$`ju^)q(YQ6`3H7>CFF z8o56L<>M4CM?PLHU%h(8N8Z4JF>^FevHNbq@IKu+)X{6cqsKEaZVdpI(FL@99ye}` z_lB}#pK(CS#iP7tJ*WYRB~X|kOXj+)%;!MPaR2%_(S3dA+v2r(G??^z+icl9?zTiF zo>%suvtFZQ2|7?hL{c&e!+&Np>PUhPbEF5ch2I^aE#yaEAf4KC2yi?eCwenPE5Y!+ zi!-b=O#aIKwLln;+n&)T<0qdDqJ|^DqND>FwVRobBO{b(J)pxX!+3^X(4%;G2a(~9 z{QDFvi4A$k4?+n(03-~sa3zumpbyj{qd+|>BZs1Jk>`s(adH??(g#DcKo=USMcES& zL=R${4FK2~f-Al4AP$c^i13RU_k%vP(g#Jz2VPi%dKia%!oZc`j47aopFl7Z)WNg> zo0NH<F03j+*n^#62@I<Q<3OnbL5f*;hW~o-5_zGhqSKyo8j(e!p)Ev@8WIS`lN^<@ z2YrZ#k25p*dp<&e!G*}0SI7tI!y3FwqH0UK0a2AN5EcW(L*57pYdW5{zzcX$y?i1Z z<VZqkQi!m~hFAE80%M+h(!S%Vq2*Brin_$^$dF?Q5*3@A-vKkg`3CvPKF4rCVX_ZJ zcq3JygIeRfmD`?;v4q4Jhsc=4?+C0fEFW`#9e`sErmzRCfxA&Mj$3$!L=gk#;S@-G z9|2S*8L`A@42|kQAeCy3K(wm_aS6g{tQWK+pCg7yDH(BaL_10cZvcQVC<YojGj=2; z^YFoeJRqG*y^@H-Il6>qyCmb_A^+?W3H=DTDLk8Wz@A;80})wAgdB{D`6*=#!Vbxz zg7}6RfxcbYnqZtF;~*Yd5tx*-6ghmMs#>1=(n6BNiOYzFDS*gUM78Y88yBI3JwP-T z(iL!`NGdu9#Y36Pf`qo(xEG2JVex~GQ8}Rej6}k-dYFeqOTX=q2Xy!bLDVKAdIiF< zBV7T<%}|vkU=+^d$g}y8F5pA3Bn*KR2p~Mmq=Ay5Qo*7)i584WDtbw!$cJ*UF#Sk} z$Uv36T$#JTCK;k3o%GAKaJm26#0fizm0W^eL@>`d4!EQuBf5mBSPwIT4&1QJv#G;q zn$6D4h+L|?SP>ckFo&3lH~*6OhApxWrEshlLJ<72hD)IiO3(wv2*1$d%!V{JS{X|4 zlQ`TI427gdKLmgo3yJbdOniHW&~qW<=!Nn;BeL+4OTiv<oT9KmgDac|@zc)Ucq4(3 z5e(X;cZ#ElVhNPc2S<>}<7v#L2q2OXuRXa<v;iP}XvQZ4z5C=s-s6yB_(^Q3OnHbB zaX5!1cnA5h6pIWc1ft2egpHtRpr>ij1FR@KiLc?H(7LD&^n0PVNX&Y8rTEAj0R_k4 z(w?bAj(mWJd%Feq@CJAbGs>f-rt6H|oY9By4E5^EIh4()kcU;t1`g4tNFmTFl^pbZ zmB?5V<v|8GOd?^5G5^l6gy%HNC}pyR2}o|*1+t7o<&Z&q+#ABN5ga)Q(^=36vnW+L z0&f{fIK>G?=_?@m9qdW5^T<BJu^>H-8sqSWOBl{`*chRRkm;1B8B{MsRg3eZqJ?1% z;<6@Zxze>!1lX}1)q$N!p^IA4sMWhtl$;_kgit@o9Viu5DN<B0eILrOhr>D@Lj(~L z71ou}N3P+}cj6YLYf;-lh;0x82>Vr?fD%&8!5cLSZSj&bqNtXLlu4Bw!YRaR?5+4J zm}EpL&X5CDP>gKt32VxbX^ko=6TLH-C=gjHM|h{bF^+F=1P&<+g@{aZKumlM!s*Bd z=bTr1-HGL~BmWCTRR|G0qp(QB*_)WTg#IC+*PMc`Vns?Z$~y`kA#qoUO^Md<)X)U0 zsgegnM3sfmpF)b7X7v>gU6O7onl81dDAI>a;*i~AS(Px)Qgw<ov4?OiOCMSoeRzaa zWI1&06@rK{7;PRw#nn*~q8$ymqfH6)D+gS}Af(~Y1xhg%)mY&AnSm7)r12J_Vo<b% zPez?E&JqHw;aah^2t5P<b-0oYJ<4DK)s(r?r^H!{!7xnKCLt0E)hN1?y`(FN*Ld(- z7~+#<5M0WIS@W2xaHy&<i`r}`D@u(ONj0pUjf%@~LWtB!hTR)Ca;4{l)QZYnh)|OZ zSspGbApgQ$F0k^3aPX3HxD&#Z2YAQ_)hbX=c}V~{H?SJ2H!Mq)LMxC00Cd<}IN74y zrHBU=J;aq=-qa>&TU+GyDChxFS+UfDoxC_nl+&qO9YZY7Nf%#@QUc?JntPhK#0~oh z3XByW8X;JuN*1Pg4D&*XkobZ#jf}{7S+4~Odw8Y&h$-)l2m&ie0Jxt~`lHYdAmoL< z<pm~LQQUGMs6TSu6xzDG4O-#YTYo&%+*K2f>R{;rUVzEIgBsrAts!l4k;OyZEYTGg zG%q{rCJrsxtSl&@p@UsG4{X9<%ixoP^xU%qD-`>J>*<iF{RTx?-y0&FXSjuOut3bb zt^d?;N&65?i_*E;Rg6=cVu&EHfw-S#eMh5U5StQU^o<ne{S<vLht+{TZOXfhJO|lu zVU#i$;Mlwwo?^fiCLHC^sWOMELa-iP93l3U<H&|pQW$fhv9KH81NsRU@f?MXVDGKt zC!FNReFt;sCPSr+wj2jA9%2<S4omBwBkoz1WexkRECz8UH}IAVo@0mDUk+}FE6&9~ zLoqb)7Ae*y<Crr#8RJ`6sZ|Y_DM(94wBE|9S*#JBLCj$a1uXu3WiXtLT_92&GYWfz zH7zlYLH>ry%o~J7WPkk16?@`*c$;K?h@4W58(!y1J{Q;OBl8+DFowS@VXSrX*Z-$5 zr!M%0tFhawYfe3Y2f!3)h~R~b6G&&)o+I`Kn<~iT_2U}3g@as?=hfzk#;41G1UWF& zRZc23VT?(N!j%>1^9U?~EM*<;5QXr_7XhfnxD63@k($Y6^swfZhFS|uBrgFIiW0w} z4ow#sAV|*Lko!-bp`{~cw6Osbc+S2+S?VG&sYh@qw0(*jOd)>8Kl}wEVs6HGAd7Rp zPkpdLEYxZpw!onRl19AOF5Q(Ad1~+Y!z-f;pdAR}5(;xjxxnVngT1YgAZbKhGOr$` z-(i!KHXeVq+5Gwt!s!KV?qxX)IVYUvTO$|CmK@3;3xNO(DNg3Q5Qr~`2LHa2?cg;J zY1y^=Ikt($Qyz*LzD|pm6rq&a;SQ;X$D!Ukb%@`V90g)L>lVHk8;C<|VxwS<2OS9! z*&<_c2{F~i3^ERTV8W?>iY5Cn)Oil0O%uC*A%wtOhUlHmzE9@p0&hYoO1_$pOSvZn zVymN&##ST9j%<t5jLNoe|78f<I09;jijRJXV~Fr)E=+xJP8H%4h7K2gkq=#YwaHMJ zzL6FuT&O$M?vgeNy^AFe;crCk?W8I^afk=|!fg<lA${ltV&GBmux4PI&Z<5%Qr>V0 zCzwF0pTuk9DGnd+<|(iuw^!Pf`W6{7`G)-d4rN^?!h16Is2{ps<p0`A66#n2YA}!& z@4WEY;3_X)0QiQsiI5OSY{zWgGl>)-X6UYPk;#T|U+bNE;1-~gISht#JoaF(Kt1R5 zmV-1e)aD=WFpgK7Ewj-UC%hh<el9FgTTPLduJv0Lt0XtpW1#rZgXmx5UYm2M1ghnY zB6n6$lb5AAv=(-AAbJ;qaOpYDCC{$d$IT%uH`{7Xin2o1(csfiVsM7|Frc^%<=XWF zLe^3IXtT{}ZGsbVXd4=$9rHr(Wfu+i<I<Of9id3e4V^iH+Jzti054BwIIpZN!W2p% zgbzwOppA!0Aa~F(4(Q2rO*b8W{gyM=uQH@GLaFwd`^+2HEB~+piimONV_z7HRCeXY z2<8@-)vh)Xal<cB^05oZrqv8>%UsXkZVp)nVV|Z6`zVz75j40<%DZ?Vf0e~P3tA6z z)8id;NUtXp2X)B8nD=zy!V>BOz8c5PSv@|)67V-#172_-0|Z)s*Z7P0!<u2}=pa_= zP<J08-6aoNfrvt#%6dHPajfDeuu%u3wjY;P;C#^Y_F{U52zYC_pqE96CX{AdWnylN zB7zgVWd3zI7vb0d)y&dl^MVI_%Xx>8xI$lzU@mG)aUaz!2iDDvoa9-PzaDBQdvOvE z_2Q$n$MEf;YJETkI)J8AH*Xq|+JAqD-)yR;Dv$!X{r}xJhur_YhS=C}aEU*6i1lcX z@5HN28#|O(2BPdm+@;rK0)RsRghOyIO6G3-AOw|V4sE(*m^{L5!~Ftz2XF9(Z}^5| zIEG*dhGP&1Zz%tFunm0}EkRCNnuHH-79UJ|976*Lbn5I8v?mV$LW1%RB5dgJA;gFh zCsM3v@gl~I8aF;n2f*GLYW4tl<Y@9F%9JWsvP7wGq8tFlUVa?e@+QulDi<y!ST7$s zdrP*}qnB_bPo4(#y^5yq9728i^68`ZPTH|xxVExt<;s+&Sgl%d?HcTuw0G}*jx=ZP z98;&~lJaaw&@DZB`goy{M~+@noq`7wF6<C5fd7}2?AkQ!_%Y<j4{3&>XjC%h%oXX% z^I1=vK1zb@k#o2Z09|wXvRzV_kE&Iyxp0*Nl}Xeo+^2T)K9%XVsNbMKZ9PUUT|Ir{ z;+89CFfc^7^T>f*rf=Rn=m<}1?(W^N+wbDXlSkd~3dA)J57sO19w+zhbnC%8cSM}M zyz7(d6PJ(JE%khp&1|iJ5}a<MD5zj44TiEHgu9LM+i$o8V~sx6ykbsgbWx;^KD(^( zSv~bA#L#;ws#w!Qja{}Pj4`g14*(!o6b=CNG$tdD8F5BWI{FlYMm~QLv|mp@y+TYa ztcW7YD5pSJN+}9bIVF`@Qu(BU5@v$SD*uXXBh^RowK$SJ;N-K$GUlk`VUKZ=x5h5! z$ayE85f$?TLMA+f0|1%iIcP*l6;u#tbm~)DO+DG;mOkNNwFw^zx^k&24r;n7r=5mE z<te7<(uX9u9Ft9%o$YuOkb9v)8epo*M<}f~B{dEJmiQ4*t-Zd-lRn4f(h#2xaR7iW z0DOWFjlRao9cS|Bvy2%1m3XK<>Xf)mF~8}uNFTvu0^x$5n(H8yrkDbXE__H*3n-tE zLd`cHIdo)0KW+2Hn0awFtFr-P#GQ!%Oo5`n2}jmmL#_Z23qp_pz{fGkI^+r|3ilXT zLDS_Uhbr-qGY>*;CD+X{tdO!BDF3y%Tgz>xJbCW93aa~LEtBw}izlW?*_Acn<g??6 z<me*^CE}3N6KZg3{PdX(F$y)+kcH|>Eu#bjKphqWP>3$AAT&zVD{@9qUO@@5O<rzM z6;3v-u(I2wqtrsFx;KlWCEtDft*$4hP<l!$xq&JQE5W?etV8;3vxGP$Mq5|eRdcs$ z<(adjAStBOb__zrIJE332-Tvwd#9;Nkbk0y<BdG%==051Ht!~LCf|nZ$&-6mNiOif zH>fTt?Y_I<lb5brj5IVg<gp)+_%+Xo@|lVH(=^fJ4FKU`|Gh<@xDp{kg8-lk05*Uh zBWLuXBL^?=kdu!z-HvkUZvRi-?((~tsJo@_{N^_WJ!w>u&_yZorY_rEDjP$y2|e;b zjWfgp9YxUxhZv%r^##md<3Iy7s)8^MlF%UvLdYpXF|3As005_07Uuw9K8BT0GMt%? zJ(h6>0DQw5@XF1T6sWFK)M6EUs11Z@)~PMsjSukR(kO&zim%{88u=*La=u`lra@<e zH4GRf`t!vxK4dqwSk^-__9SGH5i`-U$2UG^32Ce%iV#wu{zRd>U<B@jN^}qbMUgW; z<U(&YlVT~xf}y<ZWexdQ%jCS+Mp~f(0OFV=38hr72Av`aYS<dG&?pLJVbX?50f32? zaRiuIsT9M@8-z$v3;$Bp0!pKxk`kf#q+HaY6}AY4DHs%r-ibniQL5rRypfM3EF&M- zi6rGpd8dW^gc?(@M^Hv6P0dkhY!8_P#sC1JZ9c|P3z?2I+`xlibYgC%XwaqlX17)7 zA!`lNl0+JG!W7nG5R0hA_(pNh1j<YloYbT%VquMZh=v}KtH-~%s7-Rp2uSt-nLOY@ zLyBguK@&NnH#sVpvppvt*6@TafB?2njKZLyz!XfsQVLy2q7OWC=|DYoLI4C~5QE^O zEzgy%U}nM=(l`P=NXE45iF8oTYwGv5biRnJ5vqe(h{^O(zftI-5FfZ{@8Ves<*5q* zvgAV@HHi>>KL5l@wZH@)PVtps3Y2C~Vnru{F$72yDOUIbm{sK@j%}baA%WFg=@6p6 zT%hr=gjvY!Trrlss*{~_3*cA-`oCJ#^mN8-=_ntPJX_Sk7NY>gr3Na`x+*Afg|I<5 z!jYGP?8mWkqLC%)v9yWWR$!yZMH~PCC_%Zft-Vc&XS!iOR<N`dD%C|Na-&byMp0&- z2*%5bsV<KKKvTW*gf9HaGlXO+6yg-7FsCbuV054m$LNMU;^7v2G4;6b!IvQHTQ(?J ztc4cS?@1Q&n#pLTH^uX+E=(cL{}J?+Pde)+vZk)OO$azsWS38Mp}e88b*P;CM7xF% zj8#Y@ga5004uDs5Bzx>4F)7wqVjqIW7-#Io7Wr%UzR`+Y;6`1a$SV-`z|KxML{mcz z1!wyJPzB1Bcc22mTM3B}pQU$G1O&icTj7Za=pq)Z$VE6_LffX<7)Cb1T$%H<(-i_> z5+F5inl<9Ke1zkqrx>cdko*BRM;FW5CGVvWvfh^gV2YloMKCZiMVXy~6{WRBp<Qw3 zPr0&FV{54{Yyh^ofg&5>U>KU?>>ff0f^njzm3hSmfWT!eV|`e}e@}fTljWluxM(Sa zp7e=e>|qGWx>9v<NomfVf)8#Mg)1<@3w;D*6H*FAcwr5I)KXf2LnQ@>`{3(O6wVXx zE&q|M?>myxKtd2N3U`mV8`1_$!WN{!7%0(Ak)LQq(l8z6kAvX`5qE;64bjvIr^s0+ z%4-tE-~}wUF^Syyl#c=Z<1j@buPy6B;w%jX^Yp=6d21#e9;sJSS;X-e4YVN(Ku9Y( zSL2aKq(5W%%DpX~yAc%PjHLs3UCWw@V7yuvnV3W_77>7GNMjRlB}FS*S!GTkq;q=I zw9REU3KHwXM4@JRcZyVBtd~ch0N4Zo`Y>&W@Da;cCkWj72wGz9<`cEB#8=NN=rsmW z!O9xNAU5%HRoo%~0XS71J|S0P5<axV92>i|tqX30w$btCx_8{dz5G5E@-g}?0RMP! z3{Vge0DAakp+}zF&1<*t5AK96_6=QsJLE~-6lW$-(TGGO!Vv86djN>h>@}9c^oA$A z+b6+gPjqgGgv*6$EZ-fs1Zfv?h@J9f6xtn#lcx<K8_QSBt#JjCn4mfZD5NojHi(OC zRZX5Ne$x&sFr)p<NW|@NPmOF$0(qvN`*dA6gqnY%?oVn(EzH-LMW18%L^_NFVM)%$ z5ujw~oM<70BtRPEC5JTJTIu<oC}5i>*uW%=S0G{8rToS<BtrY`!#<=!{NbK86kYxh zUhDNvzS)2qu#-52)unXWr(GQb=EU{T2+8bVd5D510Kg(x075jDX>lDoxc`M#w3JwB z2~4p9E7Z~lSORo~3WJT$Z>&T6^#d><f-*P*?%`fGYy&1_0$VwR0)bes=>pj#U6$aF zCuD;;T#F6@;YuvTxdFh`;Nf@>SJR!sDwtJ3RTa9~gH$k^Eo9Bo0aM=S8n5{p7PgWW zW`Z)1AU_NPBG}#-;@&JYoA7K30I<s>d{yTFkxMPmCwLl;`C(xva~cbvk?^<QYo z+KOdJG!TO%EW#uJ5qIfL-L(Q`@mnVhQ|B1S7LuSaR0Aq-BJLr82Oz)?(8K06L|FmA z>q((2sMHxHohfuvIF<tVd72%{qGO=JGN{9Dq2qY00ZVm)6V=%3h5wsAT!IgnfC-#H z2IxQ??1na?kX((=gFMJ6V1oF~;3?>WF4O`;`dlVJL;LXqDs192_}vc#00NK$Iaq^7 z=E7wO(}R)1b=iQBb;8;;2o#;d9DbVBxg&h=mO8*Bj2NP*!38mx00@}C5A34{n7|;w z%dkZW5p`ZeHsl5tLMBMUAoM{U#DN(kK@j|a2Y5gu$bbnL!Yc%THDrU|y}}~I0Urzk zCZLgbLCLOZ8vyiMl;qkdMM+DZBTWv598}(1e#az`f_72ZslkOJc)%7M!XW@c93X)Q zm_aZQ(L+iJCSbxOFeM*6r4g7x5cFdaAVC=z0UW4-SpEa;3I78yJfk~2!z(;PMxFpS z48kNdW-OErupvZV?Ew$e0xcHKI2M}TT*^1#NcY&uU9tps*kz$C;BT75>8MXb{F5h? z!q}xDfGGrA0D=dU!6PU_9OywAcz_Y~Vju8<8JK|@SV0-+0C^TcW^!g6JVGG|K_BG8 zCIH~p=z=m#<S+n(A;`lum;fz^VE{-2FJQtDc9%h_BF_y$Enu63+!8_QjW1!)p%kZJ z7{$459fYz35CDJ~Bm<OPU+4*FoJFSxkbxpRf*R<+3G5>h6oGlF0cYv~A1s0-Y{Dvh z8KNEK26kX{`9>x*0}1YfFf;-H$U-6@f(Nt%0t7%2DF0mP_|EX0LTnl+D2zp@TnTPA z1mOgO#!+a6qJ$s7!(<5OmfnO606-9M4Ih9)ciCNE>VtGrrz7OSWqLpnsDg~ff-UGm zFfe2-)PgPK&u=t{+ui8mVc#<#!b8v=03^aM90CG7LOe`D;drPxrR5NGj^Me};rZDp zRZ(GyT$pkMI-m$OK!h~_z&mhHRD9}6fPe=;M63GS0%2d7`K1RS0U#Vg9K-<=9A;wj z#-9QcvR#U4xq_~Bf-QJL71AI8EW<AJ!#*@bA|xsR@Iy9`!!g{#B=}h%J*k3x!liP` zC{-0MbVE7RgZHQ^M=XTLx!A?18oIKC4%mo9fd7CVBv`C|s6Ir43H;;<oajytLN0^? z_le|Qx&p90Nhj2TC&U21eZp^0Lo~DlJ4AylSiv>$!Y!x*A-t%fsiY_jM}cD7%4lm{ zsT-D^!h1>5yPkx_4D8CDgdp7l0Av6lU;rINL>`>ZPKla4<U=onK~MH%5h%hakb=wr zkT6|ZD=8R)>Ovccn6jjwCs4>D?7$>=!Xzw$FJb~HV4o1`LN4qZZOTh^(Nz)|WNsWo zI2gpso&;fu7ShS;yH#J?QbdCQVnoD29TdU80TV7F#5Y7kG$ey6tO7s@==r&nrV`UW zbwX@zKp_N!%1}ryOo9%)iziGiCP>H;2LD4L@Bk2G&BzjL?+B=bxPmx@16G+sE7t8t zEejgCS?kH2>srJpEkZ@K>RK`9sVzh~yv9^yL(fzhLU5O-%nXF+f+h3-4}e!EOl>Y; zf(|GrDD;eVf!Ha?0ptdQzXcN0H3V)XPL?`N?N-FHSj^(J)q<2SMbyG2G(-)kheH&B zyh<w1c8ENjLpX?oE0~roy&lAoP1_~xDD1%o*i<m&!dvYCAv{s$dO|LU%OC)Oi0J|* z6qh*F3{j42xkeQGP6XNHRYc_92TMeZ0e}^Z>6ju!aP=*m-S2AvOA`jGutD5(?S|v( zf-Urb4eXyUB!e30K``v8E+j)TO#gx#Y(Na)XpS}_r{E7LsI6RTY5DHV$|1xM64~`( zpUIYRL!1Bz{J;tWz;yxu{T8pRO^!X(8ZPK1+0?KN->{SNg6A4=5A*;A$U!e6@f~x( z5P(-Mpk$Psmj=TV>eeAd5vLb-SLaB?I4$x-_z3{ifFH2%9{_;v^6vc#SUxyPI2;22 zj+M2IGT(&bgmgkK;AtW30UBU{4%EO0?B5>XspGQL$}w2qTw3@x4?H|5Btygs*%L+V zEF=R$-a!Ng=s`oMftA)(?~+u1*g`Al5(ZYY$C8UDBttOV!6yYno+blIvJ~08a5dke z3q^4^*x^A?aqa%rAi7ZL@c)_(h|9`-;4j18L!7`E1AsotTT;BnYs?q3&5b5`ih!ES z%m7jpd5azxLBCN*mlUrJ3)+=Rg)alvJvYP<Cd&|v%OXF5BRGT(;KC8Y5JEITL)0%n z13)gIX&OtEq1Xe;B<OSnk4@k7&A5yeV8Y61(oK`gr5UnsyqC6ka7Ign79Vv)kOBeu z3<NerCA8J}q_G-5iavx*Za8rqD|9CGQxUisO>cFR`ph<T!=cm#JO6U5xim3<aDv&A zm3B@rsE-?34B6auxW%-i{6q!jhD1xWSWg#{Ny1mtW<lHV>*YojY21lGiz45%*d5`e zd2y-C)nAK3D~L}aO#kh02&7FuGhGnGYlK5L4AGw*G@Kdl9|_VXOs~%c6=L@u_?<#G ztnG84^<&@jApaukL2@P}R+ZW0XOA37xrJ&-LrY_!MeGz%FYPJtLJbUpE+ptr+w@R( zgNaR!QfCB_nR5x_#z^jzN(N~3RrMO1LpRt0YE6;DJOluzww0CbDd0j75E2wAkwlly zu1N*{Ha5bfbqU8BLg1}#V;`^qTU!(NI-|ykNJTuzLpM-^pbVZlQ`k=*?0g$R9pr-H z{0{JFiSgaWx0!2pcM<s>HFP1wu?%6PZZ}nVH`Y0}f1_PENbZ6RtgQAeU@P=4eJ4<9 zb@v6wbz!$Yod30U0QfJ1)E2|Ii{l|QQBys1gET1YqS;-7&mH4}7H}B>&uEeh8scss znKXo%TR>Bjo5VQ3@R{$RUaJaK7z83pIk7r~b4v7Q{dO?afe{R`Kw+VRxn6I0LMvct zmcn^Km^efrdF|H0=|Dt|uel!<cXlJ9G*H7REa&e?Q8s#$g5=C1n1K!qf+VcWOO+Q2 zl|tr5@HVinszef*LApb@^h4Bw<DM|AM><SLi&RL%5PQOU7t|pUGu9A-4(Oy#o`4!) z!d&^x&A5UtNCRjT`IAS}tqWSlY`FDR`&~|ZXS{}#C+3v-j9k5wBdSZz$N&iRD^Kn# zV)72Qx&Kfw5IMKQiK73q*flzAKDxF8;k2I!RYb~^`^<3kOiVdDAEbL8<N>mm0SN2> zFYE@Mj`>uS`Mgv6t=~-P@Ig{HonG!cziUt=9ST5ObT^2DH&@*4Ja8`P0SNd&uF8NK z<N*lO09wFTB33;4*82yK_vzrSLpYts%i<f|c4#Bw&5MILm;<kSvosvM4(P!l_&~yg zfEL8jLOi%q5dE|V{p@l*Oqw{(JIWd-BH3R82q1wYID#U)DF|GFH-u`~(|c|=d3%qJ z*9-lV`!_V%!*blhKIQ=+1U?x|XWU!--A@DuY)#S~{>Pis&^rpnH@56#!x;RevH#>H z<p0B5IKG)TgwCINvH++Jc)};l4dcf+$UF9HV9RspeI)%vG{6B8`~dA=K_w)I*lYd2 zAo}Sygfsxa9*m8x_r8LgM&U;bT$q$cTEjRDO;2$9s}sLOK#W5Szx1P9eH}ktoP*I@ z^yWjqBz^vx6W3`K*QQ^;<!L`>e1FAT59Nq|laq}ecmfANjJwt&`aiSr8^8J=KR^Hw z2tb~^fdma6RJf2~Lx&F`MwB>_VnvG=F=iAMY@i=q14nrRAWBq5lP6K8RJoF6OP4QU z#ynVXW<i@bapu&y^JYz-GJysaIuvH8i6n_8Rl1aEQ>RZS(nQFUDo=qu6=H?DmH%tk zi=DiN6+4z}S*B9aCak(P;Z>UprJ9vH_bCVu3qu*DyO(cYzh~dRoyt})!M}$QD+S>L zz^KHJAxD-x5Nq75gehvByqUAWOr1f87CkhrWw?ZK)-2t2bnCJf2-Q(o>$7Xyw{cg@ z=@zwC)4744v}aG?xO^@B)QJPY#K79Yp+|SUn{sc1tldi2?y%r+@5EX90bpi(dGqH7 z7e>FH;qZd`1`>)R+oTSGMdIjTzn_19|F^pX4<<DL0pJ9IYH{qp1sQD6!LSNC=O8dx zS`Gl&ntM>g4LR)aCG`MsL?!wF(C>r{Jxo!>6<MqffP7vt;fIxG6vza|0RK<|fKyCq z(Z?Tw^bbCP6alIhS4L4V$R(L<(lr4O0%W-xFCwH8J_rFo20$R$1OQV+$qOkb$t=^% z$<%=3AXi+Os1{w`6etJ)f*GZhgT_2l&pr9<)6YKv4fLev1TECiLlI3>(M1_;)X_&F zja1S}DXrAfOEJw<(@i<;)YDHv4OP@pNiEgXQ&CM-)m2$-)zw#FjaAlJX|2`PTXD@* z*Ijw-)z@Ev4OZA;i7nRHW06f(*=3n+*4byFjaJ%esjb%9Yq8B%+ikh+*4uBv4OiT8 z$t~C1xfVHBT|=QbNSbxwEwmnahKtu;AZ;0lM1h#_1|7rh4H!s06#r>LAP=<o24I01 z_EAItK+pmJ;(lw`Vh71s=(vkH?$~2+^Y~a~4)ZB_V+lu2S>=^kZrSCRVUAhmnQ5-s z=9_WOS?8U3?%C&`feu>ep@}Zq=%bNNTIr>kZrbUmp^jSWsXeYY*mvN0$LeMSG{+nO z{=F*Jb8ISk*l+}@$7@zAUTHY5)j6n~R?Qhl?sC>9c4H7hP0PKqH_k|^;pS0@9#ywK zh#P_O_SKt#{<$QdaKcGE)Bx=f=Nok7;T$`RZZi8IO5zZQ)p!7aWe$Pn&<FL2p`0}? zv;nZDo|3iEhBC`RwFjMf^wDRYx!cZYp28VI=kON;*E2w%=Ktmd0B*WToe^$c_jMfr zhI}zl-d(asAA0AZXB$7*SSBBG?BP2jdeQ;F3II@shYm^(kKfOH#Qz$m&jA3Ae7wOJ z_K1h*9tFOkpsXA35J>YzC69CHBN{QFgeBTgjCznGZuE*BN=#R{?lI0B#RF17j-w8B zw67&wgN57xz==Qrpd8PG6mi;jjt>g%b0b8X|1<`{C5bN~6WpOm{&qZZ2%#S1n+F=y zH;;PM!)hkX&OoMkkjw#Kd3~}8c=WN2CXT~>7TH?%1`-c>VB-zkz(%DCqA-1Q<93Zh zNxguW#_Xj+AnM3tnbeUF_@IM@R;0)j<)IHh>;fI%@c)KBcCiM1h$D*#F$wYnLXL?k z1cyfql0D*9jz8Q15Wb)x0#$-KV{lO+i?ftG%pneaxZ@QQ><0flc@cO7t{d=3NI1;l z4gd)AOkT^!+|02^bFdG97$Mv|>_H77&_k0O)CU@hp$~dcv3<>yh$bDPk1u%7OsMn) zIU<n*;*?B*6ZxA!WGE2S83b*NAWaz;bdzrALmR1B$1tp64>G3Yod@yX;AC-)5jtr& z<jBV|gaCjxyh0!2=w>@9G7oa-gAjsP-}3Uoi#4ndn%%reLEtwKDCy66@+g^v7!e3- z_974zL*+#<YL4LjPcS>#kW}>X3T@D1mb7R`IRCoALY3&_8MJ_h!mL(30JMV^e{7OE z%At>JFj0_lumk|um&=Nz!+cAihw`?W4{_K7id@u8M(m+O?+m0ES`@2?%q9;v+F=@M ze32ar=+b-`G9rO9O+Es_iMf3!HJzc3+qzkheX>It<#1p)+@T42<in1_X~s2ZSI~2u zBNgtToRbQY4&cdw7pQY6HbH4pBnmVif}n)vq_R;<$Uz>agPl9UgUYb|c42P8=!0w+ z*L*O75%h>hJOn7ixDKaegmp+cUI;d#d=W~O@g`ktG7j;gOeI^>$1bNzJMLYh8RbCR zaoZ!?dKkhT@1UGv4WbWaumc_dI4zLAGylP~J#M4BID<Yksnm>2QI>1ig+2%=pn6aP z4V;_eO(`N^0K{XhvVGAw_q56>>SJTru!A+gArSaJ<hcV0$3oQ`*_EIp!l3z1KGYFB z9lv)aG*Or{l%Z1i=z|uFdn-jIs|@v8=4<VM#t+T0VhyPfZBw`kJ?J5he4Jq!@<@ku z8*)4VP{XW`Q?WhLp-F6NlOACH?K~3FU3oA#D`Y}P_guMQZgAoe<>>E8I-6qHb=GZJ z4PH6QVKN~iMuqms$2j!y4n@EL4zGBJKFZNa;Q*i;4ICyKZ%5g3d_x}|&WP^lXlfc7 zw1jH;Zi5KTMg9SAAn3>kH+2I`bN^^G9~~v>nE{XveL%tw^6*BRU#*a}VG;nCd}ra7 zz)<jzmy-Z6abI8O=7ZQ80C>=cp!*m%7^?KH2brQk_3;fr{6Uaey&__)W{#}7;~(pA zhdb8sk4}F_IQFO>d+T9e+9lE*skn6e3TlysauPhjl_wfkWVt^J1k3U0f;iAo$@guP z%lVkcmst}=0Boa++BP!)CXNuoaqod$ERz}$Xb(I{&n58bWTO=#A%0V&Uiz2@9(>`8 zHzb1|yIizihBL)Z7u+3l>_$17A&WUyZmt;#$EEk1k8TvC#R6$YGlpcth)5;i0B|7e zeiKw}xVpN@e&EK~DbR6v&Hrmsj!Z!aol;hoh!VyIolPXP3^d5&8#ctUIN~7$YS3dI zb-(M@(t!>xHyh+Pp~vIUzzcg|S=;;hPQ8Yk;%v(!#qm7gVBJpchB#hq05Byt+`Myc z=p(Vm<b)ltDisX(#nJoBU8IqUb#~~3>L{sP!QUZOOP1H)|CW07qO6tbW!ATy=cL_q z9LRES28H?fmnHmw4sVpqYsZtvF6glR(?kdWk*w%K4zCZ}uFr&3Y)d|<aRdOEF3#Q5 zC;%uy56}$2=Bh2;$b-zr=iZ<k^6VtKr<oG%Alhys+D;v;!49zDxfZ7vz@hshgL3qt z9a6#R=w+9viug`K_y3f^8P1`4_(v)fCKcMjmrhD80N@q=ESH9>_)cPi^x+Z?;gKQ` zI_#nFreGOJXl)Ls9)v&~n9U*z0@55zAE-?#<{=*<sUCa_r!J!=MhpOsARkWdN7g26 zM96>4CLUaA;Z6c|Vr?L9?IO|;00N;G=0zULK^@+pub3w?It?9Y;Tec893*S&zK+wB zFC!YrsD|X+ydxg?NgLSEA~fM0P{uMU<{hkx=lm@k*g+H4;h)-J9J)ar>H#<uOdQ6+ z<rIPvhN}i44T{i#+79A)^5F}p;nq&^B*Xy|<4hdZVDX0NgLViU>M$SXDfM`RAqY)j z=+NfW?;!NS7ys<Q99${UfUX=~$L_*nIQB^dfsg7s?Hs6z)6^?7+9Di8&>`wY1oPn= z-tZx&kA4Iq5h3EzOaiIu!5!#}sN4Y>q5;#QEE*q!*^chZc7YAlCgCQcaF*c=zDuLT z=@{m07lF$-24V{pB8x`I`XEDvyapa`EgmaE+!l)=^1&LW$FG872<d0{xP$cQkQ0z` zI1<el@BkU(4lyX_9qNG=hHvX^LZ|EtC{Yk2{wv7p;T#X5)8v7V{zWJ!!fP(=_j)n) zHnAdl(x~V`8oJ>d-a!+-p&NMcHo$4a9O7_<z#ME%+$;ik9ufc^r(*O+4&Z?to=_s1 zNDk1lBLBE?G7177bd1!1Eh(N$g@(co-c2G30vx~rur>_Q<UtMJ02^HCFS`N+sY)Km zQYyTriJa`eE`oC4fjHXXYwS-NKg+kcahG(5(<a6vfs53xK^ZDaAI#w!Jkd5U?Idl( zp@d)?AkLEJ0Ug$$7;r2aX=0=3U>BNaaEK!v>_HXQz#i~&tfVt-nyo=5Qy;A15Tc<R z;zt=<VmLoUASyF9FG3%ZA%M;y9uQ5>BH<FiAsz^_E2wOrUIFEt($zYx9Oz5n_(v;g zM-%2q^#-DPB*YN*1}n`W9!SfyAR^wbLF#a-`QSkW&7nV$Djrh78sGtMaKm)muecCm zdH;xQ5+h<B#;@b9Gn^>Q3EvWU(C_FNLJU+?G)e~1ATbbfz!&C#7$ymqn1Uo9A`-Z# z0UaU`h@n2s6D5yB4ePLm1j``6Arc<p6yw22yJF|2&*1Fq%)q15PVp7!!6}!oA==Iy z(1sY4;q1DvYf5Ni4u>Iw2mqqY#nQAPy1^X2E=Ox3s`g11*a4}+!9I~H1ZklYMFTpu zs5t${Y7Pe-RKXA8L6b;Q_q<OZ1aC-DFL4gf9=ZSt>A_ABltt?y4lLp5+U6`VvoG2X z9Hs#S!@(GRp&V>&V_wxE5GWz?A;qfnyDUS7j>8}(P$9s96WGl}<7*%!1P_Rgg#QYH z0r`qv3ezmUL$UyX9cUpR1g@Z*QUsAo#p<t{s)sn9VJSDst^|VApn)A$4R#dB8~?2t z##QVXVjSMV;P!1#@6;UMAwZoHJl<g(jEd8C)hsGTjCN7%4kvqr&0o{QgYGPn<g(Nl z^6&t_4=lktxzQjfVS`*mVj&^yJV-}%@wwQ@GIfX=f7Jse_90F(<rV@y-XI@fFIXue zAAk-%+OD14vLdDt0LB6KmM^P-P93&1E5$-|dQ!iJj}Q|gZ-~+yj1nF7lorm8A*3R! zD2r&lrfo2>8E{Y_ILB0BQy_@xA|{BkBCU$x0n)Sq>@<;SA%nV(LnYHDcK=W+%K!k1 z7!Q~3s$@*ZtHQ1!hJ&b<!OFzJ6eFUuh6H1GsEcfLGZF_9BOwsrBOc&^8<-Rs$+ICW zvLQ4O0D7T@`fx%8L|2)|Q5OQv$n$mVU~^AzS^*$)^Whv|(kwKys`d>$=#K7Q%x%9R zH6ubDQ=xJPO(0UC2(J|);9&)a<X_r`IJE4u>LEm#5+aIs7}^0h|3<PfD;2VrOCRHK zhGcmZ2o#-lToeBv$B*1bY@=(yMk68J;AkXAx1^HdNJ*tTHo6@ll1ev9NsELi0xHcw zR6sy5zWn(8efQ7Z<34wvd%s`r=acszpr$1BF){94CT?_DLLBK;JsR_KVlgV=JWP?- z{`O781(nGFB_ewR>frUzo(FzU9Xq(O()l9o@aJ>(Kmo{bz^Qs-`~2g5jc*FlbYhwk zuR<aOE7`6vvz3{8HxRX)+v+kO@e0>+Z#`E357(NX>BxT#9GfxqV=)1nl?ks<-1Pci z5B;T21fsfrqSkr;$^;y4qj0guDUzwjb0o9@bkhQ^LEm(EPGi_>oTL2Q6v{=o?+Bf& z#GWe*1v7S|Jn4A!Zn7N>=3#A&Y?)wr1smk9=ZAwVlp+t-M!32+XfZVRT9{ODQ(Q7b zoWIi!{3`F*g+8J0N%FW56cAuayeYu4$!_-I&O1Ew%0&W2Z0pHT0oRMm!wQWuasRo* zI?thfnc3u5lsR*hABBo+Ip_h480csg)6F>TpB2=tw;yxI-spQa!ZZASdwuAHUS<Kq z$rZDERsZgcu}$sR%iY!(sf6ohb#0lbp*1hamLChAvP4diWVTei61S%Pv7Qn7z>sN) zOCt#RBKgkQMjKAQKK&O`Xq;;;hM6xnj+@kJ=UvQsL;l;w`&b5%#$9D4BW{`s&drL& z=N&Q0jhx1<-`oR5Iw^DduUTNj-g6t^?=w7NTMrH>ifJ0T`bom*1ykhop%&^~&E2*x zAl~El;1Y<WvQ*H{u(y_nLe0iKx>(&U7ppJe;LKoI3Ga%A=Ljz8X6Br@7yf1C<`Q>~ z5n!=zl|#_(7~joVRq|LmXA*>hVEy<o$2Zi&DQF0z*!ST)W~KXIZ;&D+hiB@o(FeBl zS7I9VH(E*<jqWj>_0NqV4_~Bc_4qN!iDsU~3~%Id4#SWeJcv}N#fI6=SzHhdfTkm= ze?B+PR6wj^9lks5vhMe5N=UOT(zxEoB;6j@ZGIn$>aLLKu|du@tohyWOtM8;5anmV z2-X;e=)5{7UE9D9H<RfB_ap7dsn^fN5$-r63TvLjkBw{^Ympv%TE95c^?Sv5xYP`I zK93=2R^_OF1X9HYXu-MGH(p7Fi<@OFZ*Pcl$6~p>Ahi`$9TAt!hTNepu9>vb8wNq& zFZ_n8UU|cUKa3$GH=wn1^OzSXuq{$*ZYgxBlLU}-JE^&`SJGsQWNhQX=;E%l-&Gq? z#fI4lZ$20NwbY(HrOddZe20czhpw$enEL{p6}-l_vmf^D15zeNT9EDAf<J@f2Os*T zh*w?l+v!Lg)wnvNEU(DxzIR-R60YI%zys|ZGe&d!H_sc7sNN!9WqG`!_D+k(Co++; z&D4KvMeyW*3>d2Fy8Ym;%kwZDT3EVE<a1A1iF91ZNh<?(mGAvC>PQK#J-)u@0{^Y7 z93i7uhDXIxqq%TXF~i<y_(XEyL%(64^&!ME2|ECAb@ZSl418`C@qEVidrYn`biQoJ zyyx;Msc!1!owYvtJWltRBb|}QCljfsB(K7XHoBpJXbd!b+Mn*-T8KaGRX1qbni1HP zN`a(7-!I8^yRgGUM@Y*e=%+nQU)--Z@E3^XAEF&$R}7h8&oK&0Psv>iH;&6Vmzlel z1*<v&=LHO_W4}ys-D!Lx=Ko}<$`!}58LAtjN0V2s>q38kb{V*z-*`3KSP`s>VALV( z-{y{{;e7OKVkHb2S~|g73GumnpuhWvae?Eg^J(Ayk)J=?A!=6anWCk^c1dv6%=@ue z5&g4`q81N@s&w{O-)8^xOZ@k`e7Q&B;k63%bAC#LJ4TS6b*RqPOxDKDKfbTAPa@cn zS&Y*pGMP7=v;rYMzYsU<Ej6tcOm&~ZB8i)w>(MWizVySHSwG9z;H#E%hp)#8`#l>J zYG_eSAAN($kD7Q<^;j-7RLFD~TU*y@47~~!a3f`hyY`=sJb`u-4~>1Q#7p}I)!jqF zsRKKp;1RrO{;yM&*UzTBVM~A<4Ah|36djuxE9*a1exuKz;~`n3`5j^p>Q@n(<oWi^ zIqJ({(UD+oma*B?0Za5)0axca-}>=1+w%%CMwfqf*58H}f09IO3}t<ekUDkgDsNW; zvjAwretsID(uk)P0<9WGw&p<N$K@E|HvD(WnFZO#Hhf8jxuRppsduMA=qD|)G#pCg z@GL@q3Zo$NsFfd~KlI?8YS6^K=~yxp2HmDy&yb8bHY9Dn62uYEZlO~#Z5NWyX3JDu zh7a>iO5`Gb3@5~;{B-H^`@O=p&}C88pLDcFg8lXF=|GAEhk%g++;J$C>~TooGYBf$ zPlW_=NQGV<PXP%g`sjb<RH<^B{(X2ald~yOJIk+ZMXqJ@HMt{HM!xy;Y_It@+mkqB z2ji)&QzP3NlUA#4?w?|RDoqdrJ?3X(%2hu~-z8ypK57d7NWK^D5GC~=txAjH1du*3 zFUUM-olV0jU7d#cV*Et%l`-Nwlcc8aapBieus9o+uf2yz!Jf?%PNxNq;f#lV-cq?k zUq!h7Gj^&Ex!KZ|=w)Hq-tCrar>MG>?{q(b3{U|)v#;{3oM@Ab)eeOgKZo77&2>?w z$*x&K9}!2OGQT6^IIgFkS!b2&x^uEjkt@1eu6jnYFwOlLA#+2Z|Nq9eW%Df0kMo*Y zYVQdC#;Og+GNww~dgEzo`|(7aFF=TyRVF<<E4@#H59G>{Ex#=BjnN`SD>&<nX54%n zy+sK8{;}#_tn$WocF4yf#(91qx@uXgY+xfT#;qa=V=zj7eIfK8J1td&jL7iSp5;A^ zD&Mv{7z<$^&yCdn3^6=;(k6Mvk(_u@TVbWMBM-OGCVggn<NlEO+v{1+x_YydL*2ES zvHzH7>9<7B-PO+u72!p|96n3_%}LPR3P4o)YEE%ZE(mAigUm7M94{|nHH6YLZd7*A zZxgOlsCC!$qL`m!GAFUr23;vex%fVpmuVmcyZmZqc@*7>*#L3H(?kJ1u#m1|5d7gi zc8|zw;kzqaeRq`ReA_MY%UYrN=$A(_QtH1MBgze0y*7<U|EP^;iqdn0{2Woc8Z%I_ zex#hG)>mo@Q#5(5vZmr*Ih3aI0cwa-D1KdBh-CY3CO8Xla|6j8kQ)@M#b7H<R89ms z&VnTKa^4nSdV1q3|4DU<0*84uR*Iz(^w3Z5%E$+~FH0A(AFj-_Fw!4<??3x+;^}Lm zJW^WdX#ENN4mxupmGRV3w<l*x`HSzJE5~L<$q(Yjj-PhYrHDsQd*jVN?aW3Sd|GbX z+#lA*$+MMcnke0esqLdLFGy0<whPmCH21f=4G?t4V;7#J`*AupW@l>o-(KE|#5`Ox z4AiaWOSu8#dg;FHq%Q4hXB@!&X8F#biw+d6xDW#af?2^_?nCTA^KqhY?v}wLGdiW= zIFR3wFgLKh^7V5?O6WT`g};GdL*@%%z!!dxb|cH(om}NTZcato?!%PLZs$|t7JF+n zl|B7WXyD<qyIba^{~qO3m0n|^HC<<#8YL;hLfyFLP7<@S$<PtoaqKr!?!e}k%EBdL z8HDC@4PI8jbhI=$fBz(8&4Egru3o=TOx2jQ0El$P7Y2fB*TpSAS9D#Fw(3iwo|;+c z>#TJOt|Or&#qbX$PYdfg_lSuu?5&DJdgDT=F)4~GHA2kSbM{jc6TB=R1VZP>xD3KT zVk>m86ebB}o~b0M<%+BT3kjTRqb@vZ1Q!-s#brRyQQM^(?PQ#kb**Jq1ujK5kz4$2 zx!k}4iE7!JjwlBmgV?Rjrd!xpmyQa(%M%v_(Cwc=i+YD9p2KrwnnQxUOw^9LS@&m1 zuI<gq_a*o{<=^`u*-Rl6%ArQFfVPm9DLhw{lGRp4{DupClG>fRERE+_$xGy(U9?7; zM=01xrJYBKW+U@q`~FqJo{PS+Sw+?``8%!y__zXsoF$u{PjOy_A$UPO>wf75$1!?A z^esM1R#cPgC!9LDlrp+%$t{IDVi|jiDvOM-DY_-?giPMhnHs#S;Mz*2Fq6`s2!EEI zUI7C{!*Ll*+er&+T+2F7Iis*V@SS7}`<cW}DpTx}7=*FviT~73_Xj4-)F9Q;?5t0m zyC}{MVWgWY6#dzxHEm@pVaAkE<emr5C(QV>?UsTuI}Gw%;<NgxBy?en+>Y6nR`w+j zT}P4>Gh3fzBZRtk^^wT~cPE+vB*<W*s)lBRS)(x7;I+()x{t!yith;IoPcXb8f|UB z=|<XCdX+rvDn(D{9*Q%_kBTEyFEL<d*}m)8{J}k=@{?<u-<21$0qJQ1=gD!#XUv(+ zEiXFCFa9lO#~t!C^f*0TN}i-Q1%e+u$FxB7(1iibYRk0;>b(_j$DQ-tR-$#~%U`dJ z9R`a*y^}oq<nZC?yxgw`?@OLYLV5SemA5elJqv{vA{DaS#VzC<2YAiVQ|RqY+&FuP z3v7Gro$iaC_fs?P<PzUe0%e!O;)HOvAouBE8B)BzGff$Uv|e(?mdz@TcieE8O5iM) z-z1SNC%KTpg^?7^$9g>5Iher^m|Sn?z9O5l&l|Fdb=L+I@DFO^n41wB)|E6Z9fr&B zg_G&4uixXJZw&GZtz6{Yzp$%G4&LHalpd#z@PzFxxv}_oYI0<j!UBBf2#tuvet|x@ z2fI~zo6R7<Z!M1ckj2j5&GCpsl!5-Fh;Fo;ULhfYFA6gZyKP^I1f#P2C(ct7Nuybp zhOFeuwTz|84ON+>_ikkrB3b`@a;MMFiu@P&i8Lokt;QwEH@f>{%;!=Kx{)8L$s>8q zjIGV9+O`pjCpU^Eo;}*}FEA1A#t_sR6y=QC@B;lPoq1guGyJmopUkJ1$V5c4QWk+Z zj%x?mVEkMTCuaQ@r6={a>Civ^{!wb*gG3tD+7|Nt!nA1%kqMRLRb05Q8>El2W+35; z-0)GA&+AZh$@I>zPT%G~#<S|*W;kLqV&XYnEOzjUi$*^CtXp5<in@y5*Qw7;$9ip~ z_<2{gEK_ADw#yXL9g#dc8L)IQ??i0c_7Jh-s8o{Y0YkGEXq$yeC`+m6NZ91B^s{|U zu;xjk{7DNfYFUa?>&sj;$s>*^L=3xDWrqYwb9`Cjy;}DhQTEoNV14(*iOa(Cl<G`@ z?hBI#e)ni^jXZxb+Hc<9!R6E!Mw+Q?IKoS$9E^Oged*Jw$3PIvI{6jO2}Ck;9UwPq zoh(8l5-hc>ttsQ*R&(lmYbUPMZqx;e<=O5(;|%-5=J4MEX2{a6bA$HxIw%)@#SvJ* z@DmBu008SY{YDq@cStv;4Tp0ipK+z`(rbOv<G@;yz?B?cxpP&fJtbE<KS~Ot^X8yU z!0?-?g$AkD%Psn~Yi#3FIVzi2dVjfh)<KjSQ6h^hs{*b~Lw=-VtdG&Ky)nN_iR-aD zsPMAm=Bd2(un^q@d~fdYEjJXa885vX>>0UpZJRDT9pV9<<mDW64i4SPhd=4SmYjG< zsy}{#f%&3Bx&2Y8A7mXXpj=6myV2&@8opXODCZDwu0MalakL((rvzTi+?m#$7fzuE z&kNzksS5<a#ca%2$mUf^g5V4V3^;tusf6i>I?Vh!NR5-ZCVc|vD@Zs1>(hEj<`2?- z9Z3;GZ~1{a6ky)pfftU$`<AW9V`v{n(^eDXgBO|o13<u_eRUz+jKcD}Rz~_fhx4ia z366X6Oj$}x6RgeoP@Q+}HL}<lwrmae#AkS#>DM7u=*@2@&C~8+%?=1=x1{Neb6`Qv zkcMQ3;%C>l-{&Xt<|`%#vt=uDb3P^#o_F;2XLwlYg<%dU!>#s&bQE(ez<e`^avJAO zt`6(uhdH5XPvM5`jIi}1dE2whcqwb?P_D9;JF>%>Q<|~qgA(cf@NboZKSHFFH>jhL z8R-Fn^%ur@7)VK6?vSAO546%}xbyiukLM7wmY2>({>nh*7j)`~=G6lH1%Z}lDfE0O zv7Onau9>#TGK<-tnXHxNW0C*^%4Y&gd5VPYR%RcgX<eNSl>9{&Vxm13xTG}%t~pu_ zdhx<J?oYZX)p;exH6WI`3}YkS*MJ}rPss0RobN;NFTg|3afZbs%IY4a^C9rTx^@OB z^fCP5Csg`wg%y}L<MId`pydyW2mL<DUFWgfIikc%fD{R^bvWIiygof|UL976m9lt5 zD32^a>Gg7ClZIsSJST6PChDBy+cD~#;DxvcyOgy_L1_X6)6bARA^|qE6FilFpGnwZ zAU_F~&)P6VowF}xfTJ~AEX;Wt*2W4e487v=wgewH<I_-3A`)!pMu7T9?@H30I<q5f z0zXv49?wx1RkDs@K|jF2JW)D$gSWPbwUs1&PaEza3x6<3E7WWIvxn<UTA#qA6GsoV zmX#mw6gI5DkoxB{f*71fJ%0}>e2aBPbhFa%z}^sORooe^HlST?!tHasB*R{>D&^Wv z87yjOU!Yy0gqV9xvnhiOZO2&kJ}`5z1hdl-8chRNG1?zvrDiR-!+Xg4Q1;gt4zb#7 zC;y<;Xv%la{3QIa?F8ZI0#=s-ntm6P6X&=P=fqbiSSu>(&rjWCb(kAj@wMrpcQSrK z0sdYhDP>4^N21;@27c~LbBE#zdf-g!vK1~%s-sTz_yo}5%*kmTgoag>q84b6)_Fby zfpi5_6ckzBrlQ4^u<T!<^ZTK{qnYLSn$lt{$WzVVqS#ik<asUrLEfSbs9M>vu&1wU z8YK<iVaaEI@+siut#{)*h^kN$BP~Aimg}{36c#|BI>J4_MP@NYma9y{y$%Qaq3-O! z!EG2`a6J8>bO|5X^?7c=3@|Dekbf@&b&w##5N%|T0?HsVrA^r9HtfjRbP#3fseX61 z67o|o{b1)NW1^(}L1?EuTrgPWhybaPZc`y~FX(a}%Z3f)!nO~p8fsyHFivGdWe;r6 z=U#9YU9bQ)Jaf5%ZenU<*u0-EsN$Do8;N-L1t!TB9{@vBi&ANi=OU-`<>UAGf?|G* zG?t|Y4@8%~!OKz5B@CIuzL~=6Trs|}ifJg0Qn(ZK4W@NKZV|)v8|%T+<u02IThd1- z@ijfy)Gy&pT%YqNJBFS{Ypi%;$v{u(UY7#R++3}p*9}CTCFnO)<{Na@!<CxN6x(bP z12+TMbS}F{9m<>sa{c+Au!R3t!AujDPVP^xw1Kb9d!|SMfC^ES^vxdGy#Cm`MwWc% zgB`*}13#DzQd>kl;t<23yz3GTYa8l3jP>yWO*C}iueny_>N->EX8pVZ)FiMZQ@M?i z@@xJT@QVo*wNXBbk<bn?8AqwB>GM8akQ}?-Nysr7&N~y~*Jd*I-_k9Q)SUq=YGH_Z z%US<^fMz!bVr4#{Vu9wxx(jcdUapy(h9um>u3hGYa9tlZ2!(1O?c;b=9z}~^dGN&o z&w*`vHaq6;mO~5m%%5FGD?l&L2+(>823Zf-(DefhZ@gT;)q>KdJ`Mhg>b#q09Js|f zBRP^+Uy??z_`BJfVOp?xpH|qjTeM!aW0&^;&dn7BUBlejmSD14qGpqPrSAfJ!N<1a z5y5{5O~fWub?WV68B=E9^jmFJ_DB^U&%zn0#BIImEodMll4%Gj-j_9Q#z(Vo)iFL= zo!F|94~K0Y*-I}_(CYJ!nZphLMz;!qiSUY4b@v~_4)HSz3jvf%X1r254m!M`<Lhi{ z1&>*dg(r^v<)PfpR(%MLEQ%Q>W}Uh_$2JItn#rUNzw2zQW<GN+Ka&iJ_|way!7Ij= z5yH<T<N_MQ#hs4H6Zj`4(E^{Z^KQ&lv?O;9y~0U0dB_78gDyuWBmBvKiCCH{^#!&9 zSp7g|<*&SI9vWG`G3qp%)rAiF&P7U@6e;FXX#ghTV;qC|3E@Lp_#2I!9_m->5C&}? zX3u6Co?<DpE%u7qc5$(^c;w7*pTfwt=tK@v0H(-}PVpz9z_pncsJ|LE`D^*z9Ev{z zt;Ng^Lb!G*a%4Dii(^^GN#-L?X#H%MlhrF5sStE{Sjg%fK^NoJ%goy(79r`-V@yu~ zlhcJL4F2xUkP_T?L%7}9yQJ;CNqXW2A+a5k_B*;EtBKWDUDKNmI?D67BmhdY0Ns)B zMl8}y#4w16Ag0!7NJ&KZ^ynlcV`tiAuX_S#&3s)X!z*}m4eTPLGTg@*DJ;NdUco*@ z!c!s0*)T7|!$;m|&5gw)ti@a<pTT^wccb4_51HfNxOEEuqg#%F2A|d*OIim%l{44l zK1C0yfS_^$&R+c1F~AsA6GNCZtvf~Q+7YD~yKNW|PQ`Eq=0XX3OTN-z$k?9aELDa- zOoVIHK=1z<FQtc3Epcgq@S7=6b75F@pnra2TZ$^Qx}TX|*9G;N^^d>OC5h>$qsV+J zf8C+mTN2ftQm|VNuyMx*c^W_g$F7KvATEeXY+w}k-oH8yG<>!-{*@VJE57xIj+4at zNA`=Gv;%n(*+qqLJRE!$O}_`oJ+v5#JCUboU}cb}yRo8+{s-4y5N{o|<e;N#9t3a2 zKS}Wi{iF(Yj-xe~Y}r}N9za{e=Z%Ca=<PS?*Q2ci<Cgg;=w9Ba{_E3=HP!!rws!<d zIv+5n&db~Om`rjw)8h-Z5fAI8*wxu&>7ztXlB+2T&FzKVRPM43vxWA0459gNui8m6 zPS$jpK`S3E_EvgdE!*5GV~N)mW(6=e#dfL)F#I-vYyV_7wMR!)tbI{ENO08Mreioj z5{u~fkS8HOD-P}r90t6B@1Uawq<MRl;6HQa8Pq>i=yQwx8iM+R4mr{9p27ZQiz#{D zd>bRRAu71$(z+H6_vK0b<u^2;blZRmq4Myyb|-Xr5V}qH{?&tf)E|}okEf&tM)Y-| zU`*=J(8QozGiEmj`nJxx7Zss^bjA#xECo_gNGb`#CK{9~Fx5v@<!B-(>5VE|);vx; zzWhs?Zl;_#wofNvu^yqk*x^1!ssuS-;TZNuX^tsYC1jm7*gnnwz$7b79e@6cM|FP< z2@hm&vi=?ykjwu5@!3BPCwI3^!d}yNcr+R&%nDWslCIKwkW}^QKNr{+aSo*)<uBn* zC)2HzYVf(E=p{qmT$JP<7RuuBBXDLH|NBw?KiJheO)r%^tZkwTXLd6{!-i%Zw!wcF z6`-|8uWBT|yr^!y;G=<sHmGyH%F}Au`6*4wM$t_<3b4I3OQBSo@zNUA;S?Wgf_<Jl zKO=cAQU+U_{%WM{KBzri2o}iKLaYHL5m~IL)j0G6&Q0<XP4c6(g>y~{uJ>4U^2<wG zn`UwRXOVD$&BHstu@EX493a1f@+r)ftHxZOaFSa?vm}8NXt6X1$<>J-7<?_lO1H{^ z<<!n(3_V(xkC<Dwtrjxjx?RWzn@am2R;myvZp4%R@u&0ch|7t2v-}qh1L5Kk;+#Y& z2Zhk@H1mA|24DK}Zx&?-*&1^z-~GLwM-2+{8F~Uh584tbITwTW$x|nF9+aa~dG>cy zeQ?jz0M`?Uh5qw$ZoTt~vxGVmDBmFOINkdx8)v0*FUN&x-TNsj{`4-r79i&j>`|M< z`M^30_d5}bpWprTe!JuB7DCAoBxb@bsPem8yIrNZU}7VBs%*=qzlswWSvm<aK0yq9 zjlUH@{n7fFsz3SC(~hJozX-)u&u1jd-~O(fhyL*FF=v?#4sNINpmbbjf2^K*FsaL# zFq%D4KJg!i-mM5<*KuyomHiry)0tL7RE%$cZceLcV<t~HxyGT``x^`p;d3E6El&S~ z3O}R_Ks~PrUraI7`J5k}r1dhjWSk?4JjPuowb*BBwC!H_q{MJ^z3!8{b2yLE)fIaQ z?$q5LgXD04petT<;dYZA02-vq1G|Uf3L_O(gvEfPi9G~mgY<&d^?F`V+@~~q)*dru ziXlvrlkSyrkz5EoQFW^~M;f1gY?2MDX&K?zlxQbbqLYQ6nbtsykIF)5>O6+kb&G3x z&Y8pg=YEV;NL5~uf%snx`OSKbmjwz~ENK4N7B+Yp!qfLwHGa1RlyUcjB(N9nz~j+1 z(MyixG$dK(EALCSw<K^VQ)Th?t+)Hi#&^?5iro^$>tg=4I?zOG82qIK6h%n@&Ol{- z5pJbxgxg0?duj;G37GIBgbo%Z(D|)J9xEA>Rvd~NkvNkxi%?`kXVS&UWG$VKyUmck z<n_3^A2PJ@IpN^;*3Hy(J}^Q@+{@g(X=-Y(_#QyL_r_XmHAO1n<<}3MIgGAzUOGFF zq82w{4bNf7+2l;8-PPhQQ}}mBrQ13Er@mc5^``|sJ^AWJ<+pxLS>=Upvnv}G&{H^< zWX{p?a9ss${)TD$*Q_%GFEa@OPuK=J1Yd-K^zFF<PF>ts2r{Z6$Oj<}9xYBJGJ@ry z-9x)jUxj*eZ@<raJ&GU3=EtE<tg1>iZhb!)FcOO`Juh&Y;nn`x)F*FP6umNZxwp?Q zPxT73Yh<{cf~cFm#`G!^O|r;hC~RX-DxQ{U$a3_Ao-Ss2S?V|K{_cCz6@I{3N8FcK zI{HiCQ!fnBe-?mPu2KDD7iS0V%xfoRsQz5YR>;S4idl~H>&=hLWg@d4q79JK5{s9S zvA79HJQrhiBI_YOlm5(I7QiGRjJsc+63Lij<{Z@rE3yhYyu90fQaIP_BEE<1!(J+^ zUp-bp;ks(y$}UyWsGJOeb+*a)SyqhB4*XxmEW5Dp5Lx{PH_~ol$+#{cNop(jRBZp2 zFpIep$EOL#1Pq^PF6n#Q#(edMHbRdKZBf9=8MBhOHh0kS>w<ehEbg_hZ>INrLWf8e z#xd%{FFj4oR9G3Rk9=sSkLW7^P1-OU19d|lJqJoRiq}C6kME{|prv>F$%@iA%371H z9LO>wx8cAJ`t6oY9!`5xF!_CbMQk`7xalas<+TCk=D5&s5Fg&ELO)CLvxJ~R3l(NA zqCoYtM211O7V5ozg4#=$%*p}Nvab%S--Lp@+6G6srkuxFM=pn`xJWp+k#|h~y8;1v z7cl`pv9y9WrH!VAu3w2wH2mk6^r7Mu+N5;k0JC&vWUVW$#ys*-YB%Qp#jW?Lo_2E^ zg?GuJ0+D#yn{*m={2F^4zj0eHPt?=VShu3XQJ5UjACwH==A|;nyed^-{jcRXj;4ga zq<FE}eH|5?5pFH{Cp%xePK%rLfX8H@clHNHpi#y(Pp;iX;IFTaxY+h>q~+Og4AD(; zfqs&!Km(6Vr3PYag{;0q7#JzM9w(4Szf_P?9KTFb1<;A_A6aBct7I1&eH6JfcUc+d zoE$cEoVKzZL#tv_rQClw@q@C%@Www`fmOrQ@pr#w95ZL0`%D|C*gWmK3Y@?oXHb&^ zrCW@(aGw?@esSeb`XU!~%tB(5<7^}VEJ1un`C-dAJMmsuQ0lBfwf(RhyP$IHns;k* zgRm++Tal;IJ(hPV#2a{eE_Fsy;PZu<+9^|I7SECP?KK^>UW=@+7)@^C)bqQJ0cHl^ zTqo@YdZhq1NSN=o9;>$v@*avA_?yDpE&J`Up+)USC2#p&hNs61piD`94~4%F$=jRw z=`HxPp!7lt7opY>w3Y_<@wLwvOA#%dIATp9?uU1|TltW_NAMTh7lYmkWOyzd`_(K! zm!W!!1JB!Qh_6z#2%G!FXL^6)gjTj@Fei*g0J?o}Y`fh|9oBqBsqZA=k(O1>ABLSY zpxMb70vPJ{T8{bG*U5R?#~H9|D7H1Y(ea&Ot@v<Oz<p}mea@xHmo_zsw`U~W?(SY@ zcRYtPBd?2HYWe%M`w~-3$+&N*v^)TbaFh*bx<8QTw_U|{Ey~Kd-C6P|;I-C`dJxrD zx^me@mT-4%1BXFgjg#17zObSsh4^L;!!j4P^JM4x>|}Orp14`D%@xmf`pSan)*SY0 z%zg7Q{@nnpL8E@L>bniv4@P^IPmP@-s&#zEwnLElI?|Ij7*Y%kJkl53KEBG^+?QP0 z;+aQfYWTCJ48d#PaB_0HJox92E8%eX;Mo!DZfzPEFSu~kT~(^8MO6$o+afGH64_pf z(+DJPf$L4-PkTGa4`zs1nXD8U3ZBf!b_1?GWUuzaI2_M!5W+O$VbIVJt=IzJ3$8e^ z$#u(`%&~?CKq&d^rM-+U;6`whtKkHJ0iUD81BV0{+4Y-A?qvjv?0SNLUc9=~FU9S+ zn|^<UDrKWQhdF=o_WB_DCl@SiZ`R=BROVWWBekjwKMxvyJoT~dVH>Ud4HnAebFywi zxO1H@C&EwtGy6{4@b+wh;gzqk{=EkV<dBME#NT9Io%ow2eHTQT{*Ux5ChMxY0ji>R zGvrX)-zIgx_yK3N{8tgkvkASDv590UBgy`k<X3AUtW7Hb2_Q<!X0iymdUV=DDR=5S zXRvk)?qi5T6m=TzWHx8;lhCmA=3iapPmnMTQ0K=Uk=<Sg|7K5i{?nxDLM`L0#3C%8 zznD}_B@nYLlYwt8L%uwkYL1;lSaCq22)zvPkcA?=8Fl@d(m=E_C?cBTNIE;CiY9fv z0DYWsdm4mozV+H0a)5)beQkR*nPlOav=w_x@NfM`GHRNJ%-2YAeb%HUgTcJ|<SCc@ z>%oHqgS=0x6iS|m(Fy3w3H4V*mawD5Fr=n_J#UR<xiy3{&>oz+@+8Vuu0w&-SK(Hm zf5rm3+%Z)IxF#!mRk_&>b)aa127BGFkf2p*s;4)&{G7>+o9jE<vN^XB-`Dk)64{OL z8Ms<yN@@HvXKFh%!X{k9+TqzoPLk<-`~zY~1z!C#86YE+NK%4NKFCn87kM|xXgT#l zu^QBgOb$cSq)jzDZL+~#VCqQnL4ZbX0`wp>g`1~DD<w{HflR+Psc%_|dsT<qJnf92 z6%|28bGs&{n<ZW`^;m@K%k3u{z^hnvhrT;akQrYL_N6?s`HHn_H>Sy}d0_iSvhiwe z6yvjc*7U&$?Ud6S<35xg(VR<Wso^$>;)LoYWbYF_j$1b*OVQj^o7LeH%!DoU-@+s> zb(+_;;9KaVhl85CU#nu8NikRSh;<i6fRISq+jwkWzGfr)da872ozX-x_eg4dQ;)|u zG(O;H@PL&=PahmLn$^AzR#}ff$AD%BUuVv7q$|}V50&S574n*aLf2asIr1&Apux70 zltzQoeU|KztVi?{FKd(FA1P&)DFbZMg^_Ih>Z!Bv<ku64{Fo;}g&-ltIB^mhtoewg zQc5_S6u_1!xph3QU|BQ+D^0d6AFzJ_vz6_GOM(#DHhO6|%{^qt-Fn;~5%p@)f<V3N zj2}qn5Ntq_#6fyX{jv+~OItfh6&RQzX$J|cH0X<*-Nf^@==G~m^_3Uas%g%?T&9ee zGn6kTxN)RA+R%hw9T_jXvx8Pk7P=8*C|w<mWZViF!iF-)jJ<`C&Qc-i^H+2n{8hl| zByK_r+hT;<hNL2!u9c<k>u=kY;MF+6m7y_`CZoqi!!fn2z})EDuY-b9T38IZQ(=8# zBRz_-XTOjpe1)IC0z>pQU6BHX&Vj<GlKj@eV%2$NgT|g)BTb>y|2EQ(-R2()w=5Y* z9IYEbcxJoMN!pjUB0{q_O;sON#>){B`#i<I@<C`3V0{9aFCSMKE-8sn|9G0!NEGDn zDYCSZLPilSk4ZZ`N?>oD$x}`)>y6v<W_s3`2_mDZTAaFNBOhG2c({;4>&W$*EL9-L zRENLh*A)@ojN{>qYKS|Ura+;&zCm6p(3+BV|7v_kuL+k2`Z!e6-0;c5%ZV>m(M>WC z61Jo`n+)o|%s(WAvM-V~)dzIv%ch*kvq}amTN{hKQ)_#b>bHyfA=<;gD<#-@f8{>c znFk5opw)SoPNP~AIXL&-dA_3v9_9>cXomRRw+OJzHkBj~z*PAWTjFrkgBS{{rvp>9 zrQ*wpcQ0b&rp#JN-qwghbg7?iZ$ZXPdA`6wH-=P|qSAy3lo5Ir0!5T6+DXtYO|J}| z7@~}1fPs?O(kFK5_obOr=(aBK5R*koXkp^q6e!+w++rh9`9cZ8Va@2EVQa4#FkoAL zbvaIwF;PxrmcdY$24(u~lNOnCzXVrA)(Yi`aB(()^ylJ2LkH!uZE4Nuf(n@unoZZq zl5Pd(B39Wxw0~@91&I%*oi7Vh#AKY=tmeA(wVy4<AYZ4@=EtFX(MJ?V4M|ADCr_O7 zj@E5UX&v@hlR^jy4*&-jk>sa&=wNuRy=R<Uw}I1&TH;5(KnWcRy6i3jSx@Y27ltm* z(&%XGRXLooxX9l9Qb`X&9<I0e=QL%$z0l!4?|)va>XUZyp=3IRlnWot>*pcqzsFC) z9EX_JK8U2b`a?~=O}i~7sV<Yn6BdgjbO297K*FT{-*`B-c~K8O+c4dqEP%SY9x|ru zK)Lq(!FI_futY?QSLC8AhZlpA=RO}o{0b?_qS@+91)V19oZNDUoZ|&;-;r8?I`tAB zViY&UJ`cW0i%hn-N>Ay$B=!B<$`_>?zg}>7mbOG@_);<UcAe8eEh05G{a@s;=ssfc zqIBTm>6y{&R47EHDT%ipWb>)`i}qZn7>JO1=k3pC_iT`lUebT?jh)InhTAI^b;AGV z2Dx>(Z6^#U%Qt^9wmwXr_P41jPcGfzbihYe&En(!s>FthaiItxq(aiPn}vZ*TS6>t zvXI-->10HIcjDS;46$9pkUM3LeKV9dttbCEC!^}+)?<o3i$Nr+%2nrTOm?)6YVfGz zBE|CkpIDi1RkT)u;Wjk)tH=S&I)%WTLP=6!GpRoidmrs6sFhl(XL(hb%=$)BvGa{8 zdBKAzP!nVa-%Z|FLb)2|nytQiK&BZ>>`ief4h3iE+}T}FrHZoAC=Qs79YoLtEE}qA zCsYbWv1KzDGu@q+LjdUV#_2j?_n79w`@JJ!49Q*8^>PPJGN_yToGQzjRJ6g`reUr1 zxYy7yt9$p>^(}AR#V}5aAPw(Y*uF_b0e~wjYsf)Npp8RmaAoM>Bwulyp~cQ7F*CJA z<z(3QAE0SnXMkD4S)TSu74JNj`#hnSWoJl{FvRl;mv)|v5WJ$icd@!4-jc{=(*+L7 zEV*|#Xq~0ld;SR_=@3jcU__~$%sQP8QisGekhA37qsm&<r0w_8dE@OU{`{M1QbdJd zC_!D;aX(M4K*RR)gd%E|xM@9;2%RtwKA9d0!tWWrj{(>EQbwP#W-=gXd~IZ-jB1^V z$rPg?kLAAd{4vxfNe#2|t$Kt%TczyNc`k>b=>kSnpBpfSfe_8{y(E0Re%dVwvtf#H zpUgjnqEl}(wG^=5CtR2(A9zprRXI^5-7*FJ>e*eP?BPWudrW}Fd~%tMli?w+e@yU& z5hxQo_?)%#?M<`Cck8zQd-3G1zSBD8yp@Mhiw_^e2Jvd;{_^*42RKS3M`9bj%8A_9 zlsSf|i=@Xu-_xT{g8j5MpIA!o{8-Dmg>9)hN2kguFI5GVe(7}l2UWc7oaAzmloy(c ziTq9mbD+FT5lri_7Xm9Szl8sHf4lSP)2f`>OXI>`w+m%<4q^4MO~@!>|87I}OhDeT zG1%88{X4FFKNGtLkSDsl8X7wuq~%MsDbz$JD+ncC$2L<C?()Mg4e!s3QLxO=GvF^E zt8RS{Z!?t*?!2qI&ux-d|NW#SiaqLrp`yp4pmvPw#q>>0cqPdu(T|<A07U(0*7)u* z+&tChhJ0uW|M*9U)Z4oP1rFE!?D>++Cf*>O^X0=U8zsJ8(a-;N%f0=0*WT2wh)zE` zT}MoUe_VeGO~s4P{ng%x;b3!hp4-HHY79MP*0w3v^U!j-_Y=a`FMh}WBJt^`p!K?w zV*cc=<g_;-+P}rYzUb_L35Zr*aztmk>$7Bky(BwOuIQb$??eW&FH{ZsQd+N$tvxL6 z7w9?Y;0E}>;oT+^)zB+;=WE;XLGV0WGx>b^CO%Y&f+UzOB4AS0gj;^M372?tPdGe# z|NeDSEO8+C4@{m|$o8>LanJm*B3+Cpx{PV9GK?wT5hwrc*F2H>&KT={s$4tGMO&y; zp#V6YoAJRMG4z2A&Lf?dXb?4tJZ)KL*bUIW!h7joc*PXPb|F6rpEngIQ-0e|Lvw=J zC5rx3kk|)4$@>A0W`X>qyzbwYepL`D1OZ;Pvo#Mh{U`y?+Qh~WiT4<jb&|tzPQNfe z$u0#_pm0FDh55-<*5L)c=`dpeCOS5WC5q))+r@rZ#brrGZkItGdbSc#OOy8=)Ic?# z2!gAo_zxwV*9#66b{7o#z#gK>V+!lCxy7d(sa%MEp(Ke@&CCH{m4_F>g~aeSmbImc z-&G|uF@**6A~6GMX@4kzI}$Bb)Ax`@(f5&`v`)rDS=sb(Kl%kzw%%S29m%{F9pV%O z8=#}gr$m>|tYao(;H;3`A7Hoj_`@rf6!{A>vLtBuO_0}c;@5TJ1ThnbB#}b(dFu}N zdART2N;_zLY&rk$>*%F29XJ{ba$bM&V2hH+uohF%p8)07NEh<wd7aAmMoi_GA5tZa zejZ(2FlRrU$^6aK4ELjAGU*uG?p1U|4P<j!mT4}-qxG`XqE=RKU;o0#t1?uQ;bdI< zlU}B~awuKr#NrQj;ik`i7-d#M0!j7cn%B@+@FXc%9?q-L=uL9L-X-&8>Pg6t%{S9h zHwVJWKK#?9Ae4N5@@CG;{ezyfyq6r^OP`v#2OCrQB5iCovM9c0epvY5^P`D{gkT@i zW!9<;V+5db^U(I8{qPK2EcnWOF_%{ZdCDcYMvIr#3Q)dj(%!{3=*Q#5KWsI@Jm{aS z2+T+hLe`!n5hv)6Q{kd=z=PdfN4-#2wV;#F(^YAaYX5%YK>0e||EUd!aEQF*HIhG= z(fx@2)GQ6Rk-GfFtU<|hnh|$ysxWWLhH9s_i5SI@0*}P@biE<}3f2PnZM9ZIiHGX9 zgQ=OS-l300d3DX@XvjyksKeXn`G#-HPy|B4LO0Rd7D9Nnox}Ikj~LllXYJPsRS50S zx$7PCm|+*r7SNK~z#Un5Z0D~>reNf#2Rw`mZVwmn**{Qn&s2S|vdCz+6Fp+3`p~Qk zqhi#-2QOhLW|(~hzA7VT#R(oTWUBq%cB|G?R;(r7t9<>@OApSoou~TvK+{A`_h}qP z<>%jOV@KcMcz2C62Qb>Q?){>L$r-N5MDeEgJrQ6#IoDYAcXjVaFY1<Jkw?FA3?`OH zD^R^*Yj`-DJRmBPW&M;+FF#Km)qaRRDa^}Kvux5r0_oA_FvrWnoUB~PHIvbGU%1^? z{!_H3unKvvh*KwMk;PHt$FU4X6_!T+R_E&&ueqWp$)CAfBNN`cafI8}BDFu3HBFjO z^MS_3Cxk$#3OfqXmNL$NcI2~(<g3vn)|wj|SJmVkc+n>YN@{F&-~OZ?gr|;HpzQ!f zEB;>pi&N0PN+7FVRFdvB)l@LaFkXV1pJyoSBs0Qdz7Qz#9i()(C4qIK!>m3=q}teW zs&4Cf!=D>6#$%BEs#%2-S&P|}FV$1uG^20!NJLr<JBDffFnwOMrekg`b~i}U;d|Mp zwgoL9#jn+)GW~JnQX^GK)OWYD*h~7`3A?rlF@Id8FM!Zn_qOzFF<Us%%6sY3&hh)5 z?_TF~{E=FeC4Vb|-iuVrI+_~{U@ZO4KV=VnF6bAjm2^Yk=V{AK1cOVO{FFaJ65tT| zohKq$lUBRZ3j1U`nw;i=3_EMv0v9xy52+3d*7you?XumBp_yd+fRO6@YYD%(^>vMc zg(zGj%Qq+fQu$isZl;l3DiO?Zili0^9G;t}FsjcXK;GmIGxLZd0RVMLPT>v!z;#(0 z2HYpTj#GfI01_}lubD6u2WGh8FwtBwk_6|~FV$<Qe4Pe0WsQt!sT$8hYNjG?w^mQ) z2$|PAOt$jtv6R7ESvOj1-jpZ=9;{8aJ$w6vR*`a~djk9>mObW%<5YXy;xkN@n$eA; zd~`jnB}p{7GbO;tqs6*LGMM(R&2zEdak}%Hk+itd%k>FTbXkJk+QFykt`}ck89O@X z1$Ast#qb<3BZA=6>*F|HgK|ULip`jGMYBeOz`06w6>&1GLr?quVy*cvcRXpsU~ePS zb3I910yVRkCrryf48$siv7qKQ?(aTM64o+tn6IRuUiF8}B23BApSPCVe7?+<5z>gC zU){Q532pDY{7GEA$+=P4ul;MA!j7%!<;#D6F0?-vwp<^-`WL+OCHn7<$9fD{KyQJG z#k68Q4z44#5zlDlxskwnuXZC55klNZLM94rCiCTcZl(y;)NZDVb`m$!B*uic(q-Oz zZe=K36Nxib&WT%DXiDL2oEEd!HeOGlZadphZht!mqa(bNYhmTJlV@|UZYSR%WPhi? zIZ=4G&^_O4x5%@mZnxOCbAPu4J0`qW8uZ@lSqX~+cCTFfU~=z?vYo^bf$`!t2_bnl zv=$x4?5<vk8w;%^i0Mn>;_w1fsc2?BU=V4w<RANtK_!)kKGVI}%e208#gz;Yy;6eP zw$u<O_yG$I%+2Q~lT5%;Q7X@KQo7ZKQl%r(K{Bv9_OJ~xTt5e$+4W><_t%fu5?L-* zq*i|vyUJVhDI|<o4Vnz!V%X{Y`n~UHOyo!Z>3g3a0~fmuKVJSl|N7$<01`bKBxmtG z8UhP89u3pTA0Casbw!Uy8LfSfU$c5N9*-d&9v+V)lSEG@_zHYaCWW3go=k~$9iB`} zj5|09RZRSC6{=h=4KS=ObftQulygV|CcAXd7gm4LcuhG@m(pJlR;HDmjM@&EdM8v8 zdp0gW6QuFM-h(q_Jlcj11l&sJ3_#p26~l;oyU~CE9U2QAI>FHa{|{Q!SKA~2)_EcI zGc&IwZbMDNG?A|ZyiK*ivc)qecn!GI7pp1VY=4KlX-FjuM3bT=iU0|Hf!@gX7s9$* zYhgp^lIvOh=gH7P;qE8&sp4@ol?DQ`-2Z+L%fe0-fXY%HeUV6Kvoyg<#I63}Ue;Sv zdsWe{)IyQIv43`}y46&NWTlzIg_k{?rUinDCo(`w))VahbHvS5!H(MU+p{Mi!?q)G zuY|<|UFoX*SXjCU=ik&1ucGD~A1V51bFy3C0;k5_t5Bd2DgLGMpDfM^7DTZCCIif( zO_0VTwqo5~sSW<$<NnltSqBd*9+wR>5+=SN*;#I}ex~*?{zI;QRk@eSKsxAA0camY zf~Y8e<L>B)Xv3fGrQEQSWYAqK6~cz1#}toKPL+xmjU^#!L>`tQaH32sKHZtP8CLFG z#wfe2Vl4zq|C#zkFaV#X5L5}*B&s7<CE`_scrtpHpM3XjNj)byjtUK8*|VXe!5lf0 z$P$ORR+?`cpF5Llvc?L=4y78p$1*B86w~pBH7@Un3Y4#_!@?yXjzPn$y%IVSST7or z_6l15b#;M-!W7l;dkJPVPe8U|q8JBSK+;q5fEll6Znv0QqE{up(j22fy3SBNr_E`1 zF~cP#ZDwoXD&h-7yM%0tKVzV{kSj<rPUm6m@YICOV6Wbq_|AoGO7AKD2$Fe{vB~%Z zoQUL+=rMIB1(qVV=d<_Q?MC@Bejkotn1?_M8;4al5w&I2o&B1<F5pNRPQc0(PU9*O z=BA=82vtnsYA0bBQn)986;#77Oy+U_yJoOT#8>!!M;Zs#84P`ZIQj;XCEzHznN8FF zRlu_$le%h=#R4B79dHDzzF|2e`gVI;BDax<VVTuiXU0lU09;T+uR^i$yxkGi!S)7w zo?@3yN}15SBiMWcZi)~K(SJ=?d_);-{Emk;fo6=mQt+iERI8yrVE50$ic*{q_O62T z2AuROWcD^JjMPZ<jhtYr311Lc{%A(s=(y+Y6)FRHR-1%AbjdQryCzyUXm3F`A$bEw zI2Ej>gv2pqX8^;ZXfNhMQE6A~C0-GIIKmgO+xDBOnyWwK9TqZd2GmygdBc<0gCubK z#WNmGoWnm)Zr~17M?EOZJ_$KAq-g*{v}F?%LTXCg*lSA64lYRr`E)Re%ALW@=eZyc zJk3hxSF&9oPgD|7y`u)hXjC>zdC{!e>8H<40eMjAEywr*RRICkW78q7R;zXCucCvs z1#Q%=(vojB$?zs%#EwbSZBBy#qK?{>3pB8n)$F;1w!c4Je9RgJ5MCPxbLg}-6>5RY zAwMNjNPSMg`jwYVJD96h0AKQ~uQ<<bni~$RsSLMcVUMLBAWjLOm~C}RKw|5@krig; z{V-)hZGy@t5%`=D`72zFm_UAhv_?=BNB{lS*e9j6X3@h;-ZEq>g~0V(;2yd5L>#O) zKTV;gk!ixxPf!h|`s9-zGBaPV+9*caoEYkbUQSe7sIa%}m}Te%Q~rrQBB5Rf$b61S zz!Ge6(CsFuU;jFtu9dY}_b>xz^mBdc0DHB@qsQ0agGVeSil*y4tiK7A?4#<i0Ay<5 zxQ-ht6cfuOssTe{NS|zB$T<&-pi&b65biwYoEyT3dufxSDq=qIed8g=a|&+1Uo%{{ zs-r)>*^uj1&x}NBg1=m$L8`=x^;_S9v;6XQUh7(euHiaRZ=pD@DR@%(vnIH#SPWZ3 zuXRR8DYE^16!h}rTGoy25qRC<zLbBuUpz1O&m$eRzi2QJTD2UK{rp5@=11Dq^Ez4G z;g4(gSYoS>n^X%=|Lcux5&ZR@9hWC7GW;v(nJ(XifM}V_Fda0I=+>}_OG1$2VF9Q4 zi`bP0!@!C()ac;hlV-t#3v@eYv*Q4%ZM<0VffdLh@<&OI-zcMsKQKYYc_{&s#X37F z-;rPh`1JfCJeWA_Y%Z2MNlogLd*C(kV{b5q_f#F){Azy$M4_!ANN4m+E|~F^GQ}EA zwmcBT4Ya`ZuA+VB$vD;)uUUNeelU&MH+knFe#5m;+v*t$L+@sOO#jpPE|1$FBXm*K zIPasOM;I7uGtKcj?SQu6Gazs<UP(IG3Y4H+M4*&Ngm(cdHCuL7=3tINtu$swr)`P; zJm|ICeYKhV2mnqcl-?!4dvPwTT6Ddy?MZ}S{dZwAAfPXr>{?a6KNtIeR7UD4b<QB! zf{b|)Rs*!8oy`l+CNPniDwX_HMcpHdKr02ZP(56d7?p<|by0iZV4pDoWOyBrq=QMD zA?1eWlLY8<K@YiZX9Z7~k=27OG+5&ZsxBn>XUT~h>;In7yu_S3YEYqv3<!~Ncm^mb zUYT2WZP|pe(6|LhG_XY57Qj53X)@$tSTN9g7y1dQ%y6t`mE<bg?WK6}SiaWs3<ul9 zz<iLP--O^@34zsS^L`d8+<Ob>_a+H836*o&y*TxwpNbW2QDf#>@DDOI?*2m(Hu##y zpuo6(OW5yb8dm~rlK?%#29Z`knIuE|g5!cGymncmd-$OW7|68(dR<#UP7WTK;3$WK z=#IsIsPfMyP(KAMo~~0}^I1XouslJZxDHP`x6mWO$Hx-TtG#f*hVH{ez@9TazzV)E z6s@iRrEaD^1|D}^@Y_=WC1!91250BHR3eP#Y3DMI+t>>V3(|Q|+IrUKD_M9;po!)j z<$SX8R;NULcYshgIm=`~FqqzmGK|bWXkRaK8wtx@kK3F}ay)TwO0+Cup@|{@RnDeU zancL?RDWx!1*#3n)s;ui?9~>1ZjB@$L-aJ~K(Pt=P+pjGEi4}mI$fvziG&w2(aR^p zjeGE?N6;`K^0T=}gPv5|fS`}kIyLKQa_iRX<WV3BAaOaXV$iPZLjtg_U9Fe(HeM;A zn)=O-25+)NSWk-0uYy>%XgEI8?zR0<GFk3mWJqBgwI@Gr+>L+9=~rQxN{9A?6#a73 zbo63T`d9>)pz@hbSd_D=k^DWf5&KhI#;V=}4I%n<BAlbn`QQo%Ta6|eJ;KdC<8S&O z0G&W$zb6n&NSXL(LN^3y_Y(|@pivSvQM*_WnBWR*SP-osK*10JmS9T|ClJ&~FuWxW z@mC1(@D9DH6XB^~^=1#tfC1-le7p6aS`rT3kPGg4WFOU*URDcblnbrkT%(|REfosI zwFm;Sdp#6dr&9}H=2y<uUYpgQ`=W~QHwDxX4|4XMIPsLdWe(mD4}u^B^bm{bc_pei z5V-(ms3SySX`J^%qI{4G7Iau6IF>onXSky^2{BXsH3GHZTFT>62ih;;m7T?a2Jrxj zOA(%6NDp)X3C#DG8j2<QP;cR23m?FeolvEahCd~`J%)v!4Pjr~|MqmJ16e*fSjn`e z{-R)cDF~1N599!wJW-hGxN-_w1D240USg^CMhAjGiK*$9_hW=v%AWv4kPT604B=0Z zMVFm$qNdO~3JEZ#S`Su04FF(*>v<F3Nu<5yiOV1a+?ZQTDJ6jke||s--4F|D)@#ax zrM8d@YqfqD0eH{T0slFuZ&@(dsSmqA2j;+?bLx6=D4Ut+2WL<Zez~Vpf}QZE2bAD- z-Y`Z{)^1pu3z?Ht#bccYaW#B!Jq+<V_*0`PWU%{^Tj&sflpqfF7KhK86V@1K@<0#u z5D!~t3H9cGSHh6lI0g1VZ*NlyzV<i)iwln=JI#p@p9KKB|CbOx!wPaKYqf<{O?od{ zrC{Tr4@W=^_VBYxv9Tpc59N80<sgn#!dvBVg7QXh^U!kQU`ir{rMQ4Qbe3)tfeGz% zS_pAHqyP%R@BxKDi8q9d0+U-Phz8qGfC4d?J0Yaz$Xj4254)hGo0<=f=_I^45A%=@ zLa+@0Fb_z14*DPs)pS6Uz^z0yQDFNJ^VkrdvpfFPh?yxc;Z<^b*_ZP$hjS{M0eFW? zS`TMH2f7)!P+|{SCkT`Pi$!V<I0yjWa0>ib3(N^g5Ze$l3jhVBK|33blq08gE1URY zs`)?%yHF2=TdbuUo-3CR2@nkk7JE)+uSr6$`alSN|B$DRX?Ww=4TQj%byYLoIugkf zc)@^Zy1)t}_jue}FM3;YLXZviaC{l-6D=2jyjgGcPz(!j4)4IJQPO<!_6^~XTj^+c zw-61D1wJkX606B!pEHa#+F}vOFREC$>8cMZH@fxv6aRaIpo$K3a0bk$52)xQL`k&U z0KIW$gB%M0uMiF3007dkLTL(@6>JfhkZTHoGdc@dd>{^rYk0{UvGt&!mLLc6aIt3* zp1cJP^^kn8@WM|*4<|?nlwc0zkewVGfckI?!~g*3fQ{17PE^RHph*$~TTw?~4vL!( zT)Zy{Y7cC%3rjYhRlJeCHGuF?3_|d{RNN%+|F;ZNU=G{h#j$sT`jErrFb+6~#{$s` z1C~DD6TAoUoDYGxyRZiDc*FgIVCIkyM-YnuAiYo#o<S%M06+(RU=5yF!a`CH*|`mC zkPW(A#tO!`5nRb-oLd|k45qL@V#$l;dJ=<E4&aavU$6}IV1jn5FC|9_dJvNH(0cuA z!g(8KEC`E7a0}L;4^XQleJRbwpmOvuhw?DA#IVJdys`hsjqC}DDp3m~mzTQ`2l5bv z>3A>9tIZ)v53c+armMVp$qQew3mCd2-VlF+(5y%)wEAETTl}ud+hl=RRiN-RVu}(@ zc8e1$2o)Wb%6l(*i+oG44d-Bj-(0#J{~ds!8V__p3A5mdNiwzJunl4`!oWPV)_^Pe zFwg`6c^3>4)q`S3N4Vm!1nA(-8A;H1*?cHhmFch+5vpME;IZN`1;ua+`T&tf(wF+s z1;wBb;Lw5`OVpR3gXdt57+KXS!CNax5MXEzf<Oq&mku+HE$}?W^so#ptkr=%y*1sj z@TUrXunW=P)`1BmItYK1P|@O$y}Sk2ay^)KT@xDW(fQ!4=Wqn^pbq8W!V5Op^0JQl zaM|+k4SErts4EWfAO_3u2=hR)Lb7u9unk8L4qi-ny~Wx3FxRHr5Q*Ip#kai@tCxNd z(5)<_?s9bNXbyg02~+%}Y+=Rm|BSA3unm`>53g8~K!VmwK+VKvgK+J_7fIJY!Ibru z4`KiSoyeQ>qF}E$u{aRW@4OdXJ)wjk2;XoC^}xhIV%ZhF#@{Fpj9b+14a}d-6oi`( zyPyX4Fvi>+FYSlN*02TxvD{4&;PikF@qh-@@CwgR59NT%G(wcX4T|7pgBkq_hKJlp zJ>nhv#QJ~+u6NNB{w~rA3FnZ=-5sQYY!Banu4qsXuW-&C%p+*6ujt^H0m!(OaL(@y z-%r7t6FbVxx8d-@yZ}H5Q@quE5uu4&a%)fw_V5T3J(4^UhG>woD;La@91Zy}4iX;Z zPEil<pbuwY-vTW!tY^oC|9b{T8-yax6kW}c;t<vE5Dl<U59rY7D1x0WC=P2t4bYpR zXG{#oJ=lJpwDQno6)uL0d9|f}EJNvuib-#1KHEtClx1BHC`}K<01FS9$2Bst`g#t2 znGY>T$^X~qt-cgsoew^)a%KE3A3P7#a0c?A#H{WY;VBS=dk$-G3;=Km*05wa!dqcT z2l2q2Er-Tso$YHu<6!Q1NZu|jm$LaFyXC;7fI*}JxXANL4&XlOHu8!J+6BvyxOJQ7 z#JrJuQ4iz5>}&0@F5WBaSnn0>4au$+T^)qmkPmCH3;KW!j$q!ueu9$V2i%Oup}y`4 z-xe*+gJWpr7Y`}c|9#;4um;F5Y}8Hbo-Lm0aCO`81+pCtvtSPwStGBw4MK44iYpIi z{0u7Jlq=m9psI-g(5EVv^R1%a*eDLnnxReX7M^O3O_mN54GDgrRj(lGd=4Yw1-ld* z4{JQM&oJJ6uI4PifaPG}q^#0cAM=2s4&t~CQ=qbvLEGj4_zH>!emoCPj?OaT#b+!B zr=1TEZsT437Yy(4efo_Y4J~6|as%FYP>=18UZmOh1;?!q|6cSjGO}H8^8=XCaV^3p zjP-1R>LAR*^&0Vz5?%`E2awQs-T4@ge%1N_34*Y4(Xhp=?;`ML34VYMkuLi>c<Ev9 z7ZsWK%do$g|NbYIs&&9`4_2A)wZ4%OTMtLD4T>8Lx3K3f0=F?f)zl9FIG*F!513&7 z4cGiEmO2jrv2BSsboA)ivj;%oLWT_;K7<%i;zWuJ<z2*>v0goK`Y8F)_bp!~Yx>S5 zte8^eN|r5MzEnBSTRu9J@_D0Y?UFo`8GXuw8B}P+g!#tlLsLv&I(kE$K7|@p>Qt&i zFV3U4O^7~m2CIH$c~Rldi{{MDoA+(XHUI`MWwUn<>|DBa9g@?xiw@U(I_>o&3)Jr5 zhV$_1Rp)J<J;8(>KZYDx>eYDyIi^b|*>PZm>E`KMW<}pjagOroL#SEx>V+FSep!~U z?<IYJ{{yoI>pI_=*y%Fj1|D4a*Nfxw38FNvYt!LW17CElZ_O@qc%$7?*IfHt!}=`I z$wy9S?UT<NZy#z8FLH6;!~%GaUjBUT?>ow|6p!4+)bv}v=ggjs(9wsQHAE^WA7XAX z2_^p?ObH=+$k~k=c=Wj>8hyq=h_T<`ix0wyI`pufe6~3Pp^X4MPed1A{3<%+&>;uL zpaPUBA4vSDhn#fuA;}~ghh#`3KPdU@mS;Bf@FyZ$>dp^HXq+d+C$GdZCFtt0N1Q3B zp(maGvYf~#5If9A9DCL>$R2dw%7;u5H_|7YDFD#t7GgFuuSGc(BGI5Uml%hhD*gO3 z|4}kG0)Uz&6s@RF06JRciw)1wCz?z0kqc7va;&MISBR;noIVlt6aWfm6i2pHUmemc zI>kv5fXraENUXqeT!R<==24KrlW+x2y?mCTqaIa=iL=Suhy}o`zo<DPq<rd;)<I~u zZLS{UDiK5<AGsatIkb)yjhuPn(We&%$01iTggW}Nmpz9yFJ6PBE2h+Z#*8;$)yx85 zCOK4rr$&HrHP1u>k<+J~gyMm7Sb+!Y&JsPAAyuw?$wjEUUCt19v5QY$%^Q2<fMh9h z%|i$^!}1Y=EzeAPBpz*12FtK|&VXbY08DoFH!F!{N}PJ=*hQa1kLEe*ue{Oc|KNCT zefhbNDWpV?c)Y0x(*^aB`m1@5TO*n{Q7f7(ZV|eO9D4)_SLu4n#=EMJ>2Xw^<+weS zL~~Z&rJ%U<A*PqO@_tIzdi2rC5&*a?*G!D!?a#z*zA%UFav2BxMtQJulq;_ShS^Qf zreG3)qbkvm!_b8S^$bJjK?g*)d7dyILXuM#>e+`cbM&mX5{D^)FaOD`3H6~v75(Tz z$DVQEgqL`i$f*Yz+uLI9xu^}2CmSKcJ9J^~*Ka6p@BHZU^mqg8?6YOgsHaT=$EoC< zo!OtrQNDo#YuKY4jMCliPG*o+@y2QY17HLf(vj)VNO%l;&PME!rhHJs{|(^*fb|e} z3!_MIBIKZlIL<%^dMGAWPAZ#mcCiM1paX#>lpq7EW{J^VFjc9`NOzX7jdNfI0Af>| z>~P4C8rH)amaxJ$&|$;`ekgB0I)XUNp^of;Xo&z+6MppL!&h03EHk4-vRtSTAbI16 zUtEYf^kEHRSV9i*_{IiLg}3MZP90c*BLJI1pfxOmY-EHKi(m*Jvm8(kP0QXn^6`yJ zd?S!YtkWy3!G>(WgB}E{qM4$0kub@_GH7uSA}<**MwPBcs)W_42!xC;sE1$#%7$q= zwM2B};}P4Cl6vZ)NKxVqGvbg3Zw$pB53Q1Mf}%zjN+z{awGeu$|3Jq(4q^{@C}>Yg zG@(9T@r-ONAx)<<W9Sef#~JeFZq5wdM)Hx3YSoCEeL@RpY&R~29OV_!C`a}ph^blZ z2|o?$(6bnK6$-7P82O;bJK@Q={2`8p>bj?s<Y5-s*zhCvpjv7|atW&Kl6`sFlQk>_ z$c1PWmhnmlULYZddU(S(sG8`>sK&G~oe6@myj&GQlr7BYV+qvAhw?B<NlUUXAt(hF z9V{`Sh?*!LFnlSw+O&->j1E}l$f>{pmKv3<K@~|2;ZLDOOlC53W_p=s2#=zv*3B*< z<v{7<Ea3-uw5nO@^kUw&G!A(nM;+qeVphZYs+mOZYJugM|E@9uH+g6-ANVn#gN#Fr zZxRnvdP<W%zGSHWi0^ZGGYj|HX*cyP7H~kpORwyKwTwPTR{5X?>o}B<gdD{YDzg~g z5c1hQQLSrV+hzy>J3O;==Lp-7&E3@M+HG}Dnr#8yPdWsm39U>O=inzBDR~r=#t@|? ztH)9G(WbVANU_8!i#eVrC2`%9x?&Y3E#t(L)?Vy3@{kbq;PC}&M2sPr%0?yPls6HM z=ZGB?1V<Rvwp<O5l<BC)=EQ-@X5M$L7~vi*xuVqCh7uzP!HXr>5E4Koq?`77qtry0 zjZ1Ws9&?;RbrzFQ1+Fh?`Vhl14E3+~diY6K>7E!S|Ha-GM|O7^p@(tQE5EqdLr+4A z8m4q|l$b(qs#w|M`uanlUEEPk(={@rP)v_XO^S+mbK6g5rV2m&ieSCf$0JHo-hds2 z#uq{dTB3Q*ZGKF9{gH`0j!@tVrx{iVu_S%~U_*(P?PFWoMm(hIEp-fzY<Tj<E7XKC zKVRY~>X_upEWwo(nYPF$!wY>;=xB0{dKVzXseetI5K{7ub-m=RLNG;FfyV17)_BEH z#!=DS#?{a{Oh-O=u?CP<iPpr@;dDNo)`gx*9?xT$xSFD^c6}4gkV0^cYgiCq@g}KF zkrWOYn2#?YgS5H6c9xn#!KM)}Ul_qmn%02S|8Xzma90K=u`uNgQ!`0~c4YN1<88v| z*ijzehzGv&oh5#6+rkRu4~6X5C079|gaCL1ruh6SOesPna=}dXM!Vx@n{aQ`KtntV zvT;wvhZ-y8c6N;xRA$!0e_beWL=Ap88k38-4Qk7eb`&0Zcsr;jOoz(8pp>?}n&;?w zPd<wAg@u5!+u~zpOaY*ZJF4qnCwE;w+*MbWpLdt%ngU$dTXP)V%o1@BcYnYBq^1-D z4RQUrP%Xm1cpNFIxr4h1m9!yPJw3Qb`G`3XD{;P?P=^Fwrp5>FqJ0@2@%{$6IRfqL zV8dP57%Je($@FxA?yK2uH;1IW9<}KB|G^Sd9Ng&T#HeFf3Zv^|-iI(UApi)X61L*f zn9>c8RMDOx&x?a4&}SB)bbg7)lBPI>|0l1gf)1+MamnG_C(1f6h5A^uJq}WvW?8Q< zm7sj0o{m=%VMWA<Rfwwsu=WzY*^!Nq!5sp_F0&iI280Yl+o<aB4mp^V8v+!|`xDyJ z7LbyT!eK1}+&#w0m^e_6sw+ST+>Uv`ld+(!*<mZ98;hR$l53GJlY6jRh=%MCJO~k? zxl6b((T8GK1N5=FiQ=L<nF95g2ktvT6f72dP{Eec9{2LLp8C0xQ6EWC1oFC)8M}nY z>yUhUE`4aV?lYq%)E)-1hv`t2{}6OS)tHH-kcZ4*ro;=SatSc;I}&lRL1ELfR|vi* zISOy6gbU#_y!eQSYb#en!?NiQE^3v%l860h#5V*Eya0e=IJbMUhy-$oi@-3P6F)|= z7`b4V@dz##VY-G(MI9O<v^c|J3M;<pg7~pS8;L_-St5nvt{PE=Ayf?YISM5)hhh_v zQZtT*FpDnR5%g2O9-FA{=#_Y2j$0%>w%CSBM44ynHG(**9)XCW_^13k#?hz*@>-Z^ zLx#f}oMtjD*Fqz&@rEw4#s{g9T|k3P44r3V3<_C>!=p5as1pUlvIi-(cPPlRGY6_U zC}iR>?{lW=A+UOg!g_=d|Dn-G!FtD*8XY&1k|?XjhL9v=OUU`qvP(e7l>@?M5QEWJ z45EX^oa((o7$a@8$j8VFG`OT^(UpDK1~J&MB?PO<c_$HihF2iR`528$XcgJRzQR!# zcihOZl8}0+6w|p$`3RX~$;ZFJAzo~;!x%!P2}y?N93147jD(Eg(g#P#Ba7(|6!Qo{ zs6cv<4KrLM$XcZ_p@(xo1A@y+^gywEz(><bE(!V=glH}|`hsJSzp7FnUveYa0}c%g zI)#X+ju;|CxwFa<B`S2LkeLZ7S+KwyjvxYne~cgI*ui~d9z67rm864nI2{sUBRm-o zj}wlAyO)P>9;(@q|4F2|rOV5(3K4xchL)T)(;SYyxk|6x#f{8Nc{mapL5(K6z)V5P zRKyM5q&tVWF=SW+HJLEHj7irbA9@2!=41`ZVu*uM2RA$!Zu~ZTK#|(8K!%XK&Jqsm zlL)GrjxNz49;2*hye}P^5lVDV_6!b+WIz*&v-2P&gq*gT5)%lrzj5TV){GXj@X!x^ zP?fMe44p0eIRlWYy0j`#Sv)P{oI`tf&a!0C$5>E>K!c{K$Up+iw%`bPfDI_jmWK$5 zN65&|sSWy*jU<h($2rm<r3egk2*s2ydWeTEuo)91kwuhG6Ox-DvXu+n(ivq5fYC|p zN~<u<8W`%2|NY7f3bdPuI7yF_QV&H9eSj!$cn3TUhCK}iWZ=_a(1l~zhIe>})2I#J zGSs;A&V+jiL=*(Si4!WsDw_nL=HePXn8aJ*P%*8GTZ5+^UCerrk{(e9wHh|s04KA+ z&$P&fV8{hrfK^-o1yAsVOvnUUrPWMm1zUjCJ+%gLKq2+vrV%P3i7*HPshMkG5zn+D zT02&B5Q5n{OiqoA_e;&8{Gt~Wo}>W)-he{2%Fx(}7CTLoR(;i0@Ptqpg>}t@Q*hUJ zh1XGN*HgGvR_N7lAdm$^hznsj?tF;u_#N<yLVzjGG<y#Md8D?mhuou7YJ~}FZJHMR zO2LRp|A1>#d7!j~aS(B`26G69{Mm+MXoXg=)l3+LcO3;$P+3uM1y@*CcU@UgFa=Y9 zSy7NzR;UGPkOsSqm^wkpl5B`|0*$UBOEYBFtIN0Opaemn5!-ZF$FNpIV$BYVAZ;B$ z!8wc3goGZMTKyc>()br@I0jbu1eJ9KQ)t;!KwDRc*>w$tP*B;KZP}TnTbgx+Qy7I- zaD`)#29cmKgjCTe<t+e(q!3a+p<327%N$ce9{G7%$LNR~-8M8`o+lf?a0mycFo$mt z0*V~i4P3WOfrMlD1W-s>SFnXqaD`G}-PUDY(*=dMmECn^-F2ni)=gVcpw(kIhF7?; z|C5-m=K&XplF>^;TGtwr8sVv-q1?xvh^D~CFi}g?E7%W>w$;kdwAu)2poT#h1YH1y zw540OmEH0+-}6P^w_R6IsD)MFgJS3g0Qi^fdWg)-qV-DA7h+MKi^qhKSm&*aU%VR` zjn1RZ%b7_EB|N}|H3!WphIP#aK9~gXO<9{A1=q#k4A$WDU02<$1x(<BO*jQmu!i`> zmZ4NsMBIaVurF=d(TzJ+ap+to17N!d!oyq6iQ>DMlLsNVoe%wskR^qaW!YMg;94+U z+g0CDNZ%%wUDlmhl?{dV<%3Shg_LE5T*!uIF-!USkz$yFo6t*Uy+fWGuFKkm|8Hy2 z8h*fr9i^D0EDVD<zoL_GaD`S-SyCW{cHIO%sD%oiStzdCK_=uVmf5v!Sy9LYR{-Hv zs0B}W*-+pGX&}S?a2}5M%cUr|_DMbob>pi2wiE(@r3KbzWn(ezWSklu3Q1sf*@$Dn z1+`6NQ8)!r&;?2816}ZhQ*h#5mfe{pg*zsNS`LOfzyw=>+nEgocO`{vXqCqqO5>oL z(SVQAnz+I15Xeap0jac828+YHuNVGOH4y^On1^r>*|oi0S`GzW-~&m}1$AZOP%z|} zwP$;N+nHV0mTl)jScFHOTT@`&T4n`ZSV5xfk}ueXdWg@5K)X*~C7QT3|FrPt&4B3j zOFqE`FmR}cy+Vg@2nJjr1(s!73*Ki_h~P<hWKm#UUv}b^^#on;UR@{!QFvP^4u!P! zgky-`p_z#@Xc~2)NBuQrGe(K-paj5Mql*5D3dPQy^fs>rupGJ3U|<DSIN2p$XHT#N zTd0Frw%xE6>#-(lx0UHdh-a-1>slU#RR{($<QkAz4ktC<jRTmN69+;Wx9MeSmEZ-P z3`V}5!t-1RgE$9y_yA03g-&qSdbVk}wdq=r1V6Umd$w%Lj^wk}1zINGm}T8O{)B8O z2XsJ(EHV^{;K_^5R(V)9ZHrIU?(3d1y`|16@7suO$c8-_f?)6j|C~PG&-R317=%9H zZ3}j3c_!a}{@!-2;PkcKOyGrVFbCc^iwlJaasIlBlLL@y-WraN!UM(})nS)<4=Lq| zW8j5gaDyR`22A(_wIyVgtz9GDgj&c1K`!J$R@n~D1kIk;T0Ue#e%ZE`hL0dL^_j}i zdym1{9N?wez7`5~NRVl}388c?`r&3({e~>|1XAFELa2pLfZMX};8RHHTG($A59_u) zYa~|j6&D3kXa#x20dQC*j$F}#MM0IJZt;fjG1V5Y7`xH<5fv3|q0_DnO47eDk!~mk zcWnh-C<GhW><)hH^F0Mm_~1Gy?wECA{;mao)`hVC@{~OV|5oUPVE6z^=mv_GUwwT@ z!oD_u8A0Sih`WSs0PZP0$PXXcRK%oMvOoyT?VOM%=z?DFVCaNTNZGQ^W69<NUC0Fa zE`=AD*IL*FJpkX;wR9^_bKUM!rMmOdG_gE~qxbL(!UPXLKk^@^tZ|!yWq7B<bx|0) zmT<@hPoUeD{RC;SfjtNYlYQ)aw(?+D1md>U&&FqZHU%dBU_Mv{TR2-&xMxGY=@|cn zVCaJl2<cn^it7w4>=wTMFpfn-4O6dSvQmg*P>62+)Id*ih3JN300on+V0q1iA&>;y z&2N2HT_aZMNk8PcrCZk3au7b|ly%*jHRQS-*-@|o|CJtvUJr+B`9wJvzAX{I86hlm zXJa=4fMf7@jZAVAkp^6V@lW`KS}24MP;|yNX|i_LTrg()j(M>Lg;Qu`URG<ICi76x z<KP~GHc<4F<!N<@J_A19H$(_Bqqg1pai;+JXvnv~=p0>W1-9mQQ}_g30Ch;dU=4m* zP`Kq>HU&=rg|t_Db)Di);DckH^xJ(~*PZ*;C55i<gCWobmFHz#kcP?OWQ-rbusf=x zx|QyBUXYh{BTJn+X@y}vg_efwPe}7b?*y2?>^#<mMHmEkt%Xzg{8|wGQFwMo1_j5? ze3d<gPI%-9&;?U?cmi)=Yu52wjH!H}uc&_t|B%N_0$!{npCekP^tvTmEr)?ZQ1n0+ z`;!gsK9B@Vn1tw;{z(7@R(N|`;Owy1;MN7^VXg%m0P**(<x{|gU=R@6-(PE-nfswS z-4_bpclU5Uv4p6HdCz$(zvrCygoqyn(*+1o0tX5V6-r>ONkwFwXy{Nz5i_f5eHt~2 zAjXWMT6NN8qmZsnpH7()_^DR7aQ0T(ljrg!OaL-x(yVFoCeEBXck=A%^C!@tHCKwW zH-#Dic|w;mZR+$X)TmN%dYfwXDpss6SJtbytym_D7e!e#W!4m{PPQgR2*!#P$+IQN zj>;qomk|#jOz`b%!h;M+xjdCBB~UJ6|HPew?HQsA6e&_91-7#F&D=_vF<)lw?D=!& zZvX^QG8a!N=+vrLvtC*iK(yAfX9I<~RiCs~qfQkTJ4&uaPr4chBV71+@4BZXoiI_R zOdK_N)Wjik0tBF1VZ|cvetguYV10&=`XqUv!Bd{Hh3mS~Hfq}P=UaUbU>Oj7@96XI z@BimKuPsy0e+9C(l|1#>6AUhyWMbASznxW>SsVr9#t^}D0+%VsS(HgFi<oc%AZDnc zM;v;np+*rPsG*BkW_gF4SsfK(gD#?w(#m9XiLzcdUBTy)fkhf=6FEvzBhNfXI{744 znI$C;IRNAXKr#A2xn)yZ*`p7b|M~=DOD(2=Vi<Y{iDHmIpj?>Yb_Ip<VJ(m}lt&y! zoVX$&E#`5`DF(5rkwBw>a!M^9fHYE?7M+p_dtI4h&XAmOd1-2s0#KzNl+e?prkIL4 z>Q3}n`30$|=0v1E_C#~ZD}3;=NG5<<B&eW)Qnna|8nS}xZl~z72nZzB0f-u9sBvtI zFK%}$u7ZkkN++$<@=-{P667eP?bWjxk*bP|RX)osLC<Sbj=S!qRkHi8JpdeH0todM ztA-~Lie->1t`z3UoZwy9hAy=jtV_X}VB!fO4V6*E4nD{bM;v{E5JxWCMH?+ChhDqr zDQkujS!CQss$fgDy}R;K|MQTO4>f0;Gf$H&+kB*{H<NmfKDY4o0}?;{KrbKKWkQN8 zfYw50EeID}3nsb@F~lT&)Dee?4;S&nUOxDML=h(>QE{`i1UzFYW_@BUw$+l9oNtd( zQ%+X^q#TpZdE4Y=QE2R<4?W@PJviZoJH_)M9$ayVA}KQAff>OxtxJRoPf|4>SF2%! z6-AVBf(*~CnBuI86pLpZf9OyIiY;PH*T#i<+_tTw;93}EwS1$}-If|oxJ#y5;s-k8 zC?)vs$t$0{OZoufK^c!Ia&?PE$ZAG(Mifzm537rQq8@`(;)xtQxaD-yi!^jc9n`aK z@r$slIS{p^*wQvB|GRDM8!0GZX3wPHLlfjJk5ns})R(9+1;7!ofDUX59qyB}P(4sS z&V!yJ6afbr(CY+c2!gUmHwa0nViTBfh0_pLi%|rl4H<%(D8ix&8F&B*AT)x+%3y`- z{J|D<!5v+|Q!v^^Xk!5r2rGio5|*T_f`hBd8H#}p0HmXVPP`&c$^Za4h(RXlz~X!^ zNQOr^B05X}ff0DYipk|d7r9uWSR6E{v@oUvh0st~a1n>Uc%YAZ@#7A7;TzuwWHEcN zW43AsErVEOTDXvgIp`5U-+^&mnW+*b{7{c7S+SB=%tH+T00#h|VJKGeq-uCp2@m`r z53W?h4?GZu|6@4lM+N}}C<Zx5^JGF7ljs2-3f75Q0KgH+Dgzvl;6XJ2ViLOW7XT~* z0E1Md7G`LJgTfNBf#|X<rocrv%<-)up)ytBq8ZGrpbu}<tel>VgV$~%4gl0cOYZc{ zIr0$=B=oUfeLTS;auJHS_{Kxr308S@kqH}6Ef@|$UoZv{NQ2oT6#eohC`=(aAPiwQ zB|}U%Z*`0yp{$el6qS48wWPqs=cE-pK}~EBO_#1FAJ51G6RzNeEtKIBwIBsSj2Nwq zbYd}r;J_Y&k&H}u!a*Ubfh4q}OHYU*7`$l12JTqY+GPY-yXlss{->Fi(v(Xp@kTy6 zrH?7v|1Dl+Eg(#3@&N!4lN2&>>szN{k9?RTAKvgrHi}^jTexB@g|eMc=SLO*04fu~ z000j*u!me2qZXc6iw>e1Cr@~y78-KH2HN0EZ9*%kM(kgh04UbH8c-?A0DwM3BM&LD zR&QbXsZ16DfI%dKm^A5FZLx9=*oNa61Jz|>1?3xq06-L<_=IB%F@zFOjfK3Z!6GQ9 zLR|!75ug<<jLZ`<uP*Y4r(lIN^f4()p~j@aEs#sPA`UcA!=CRY+(nd@3jknD7XX-q zE9}bH`$~l+>WFQ>LS_-PG1x<ZDvxI;fmMbULI;1i+#(iH2+-O9ycBtmDHdD`nV^kZ z|GDT!s}P7+0$&QPbfCnQSe!Qp1;-P?s6!BV@!M(2#1=As3RlDgmmiiwmof>dE(HRB zO!y)f!6?KYHqej}e4qw3_<$P<(KM0NC5SUYvRF<5ifoYdJ(T>hk<yV4n4MvhZAJ6C zG76}HT(%DY*aQIP3g@fTBOl#p(6dI-V6@4o$iImuDLUcgV5or)g9!$A5w;0pjsgJ4 zvGkw|6R28rBOLiqE#CHApq0?f9@ID&Ip#rIQK!l*GWn5jWg^p2*tJan&~46G%@ZaT z7rDv(HFKl+p_7;>7p%zU(ZVc0V0-hC`Upp;bzLNS&_f*cpu;ZAQN<NYJ5{9s|Ai}B zVH0tags$BN%A}qhU<D%<*vUQeSU{nRJUx?sM-G^~mHX9`nfctKRxKt40RXo88&mx{ z_`z$Th9pQsCb<x>DF7hug6rgfn88iPGJ#86;z}m@_9~zNpbI@%VH7Jo1x+?K&0z0u zEa6FsncYkA)G$#>+rWW7#_{QyV=CC9sL7%jD~hD?Tql~!M>w+Kpa=mfP~Nc#+GsKm zT@WG&infbD3Ny{9V_NINe$+@)8ttOfhaCFw!!67)j$D)7NnXFn!)20*w&z4jDG3IT zmK_R@e>~-(=<FhjFo|4*jPF9#$yY@oj#l+<taP7^OVUx57svSVP;%6r|8Jrm%U9gb zxHxXRKdy3Ni=q~i$gD1?YIq~kM4G}j)G^Y_61>Tr^I4fkxz1ouvfAE2m6pj|aohWv zgsUsv=*H5IBNv)Hoxxw;1a@;oWbXh+LXA8{c+8=XN{xN^ph1T|#E=boe9`+xa;zBu zFzZ*>1m%{8Nj~x+4~!qyH?99Yn0-^LRTN<mMhj`M6-Hzz*^*_#Nae$Uu@{l3jQN3v zOPHNZ%u@pz$fN8R0N{YRc^~q42}=lBU5G_<{an{&S}Cx}DXc;e1XEL?&0!(jv;+z% z1jF`m-%NDh1Y*T&*#kPLgF4jS4St3Q*2M1x;lz<$xWETj*h4qa|56Zzp5HN-5nUf% z)Il!9P<aiCMMMUK=twPWgSW&S4gMf#Y=aQU13L7Z7|Mp%u>t_B0RVWy?}35_avu{( z11T&WZ<L^*tlq{XM_A;78JNL-X^fx%5yI_;Oi)9R&;uB9AMd51R8U(!$bl*VfI5s5 zB+|z3$;2eof*i^OA4JvTIb!qZL!X61H^9iDyjl<ffUAw5K_G{N<U*bd#&(Ptjf7aR zn1YQ-gZ!<R0+M1TV#OC}i67Y4FtUd0eS%CZfF<~sUHR7>IwCv(&^CBt{-B&$^a}wp z5@NYp{&*H21i@q7;)sQyKtu?v$>0o<q75b^R8SiL%u|f{{~$a*g*WAv1;|82^o#kq zBUkuY!{HLbxq>&wqM;?&DUiY-0D=|#K%;fy+=XE6$f0L}NxJopJKEzt`UE<l!xC%* z&2(gIWE3vQ01#-%Fv&!YSX$d{<V#rGfpvp4=mIawM4;?l2$ERZL|i8PLn1JPPzvQf zOoBEY+#Q}mFl>W5#Gm}Z<e8D=Q@DiA0RSaPpj3he?pziC%s?>M70U5JD@5Em79CW| z!z6V@pP559NX{F6;+zRYzc>goK*CV&Lm~tvGa!OHG!-V40-{JmH^kpcq{JkhWmZB3 zkzC0dAY)>JhJOVC0N|1|PUa{c&sloOY?-1oNCVU1|B|4U!dzwoHOPWc_Cqx^f+6e! zGb92#I7l!^gE%Z+J7%UMKBiDi3O$$|4)E2g;pS>&m+jdm66OP#<ij|$C8RNySvW{L z7=ln%12C8XD)2*VwnJy87I6wAa54oW$^kLx!zKP^cS6NPUH|~N!Y9(zdcNd#4#_#} zRhWdsH_WCu2&Oos!an#zHT(l27=m>sLOUFvI;d77zUMoZCr*6PidE4gDkxM8f{(G` zy5*!1A}A@w0~6`P@tp%LB*HnY!!Z2AKLqH2h7*R~CWHpX6p6t+wbP1DMFP-OtnrBZ zQQQKi=vj8CHZ(#zv_muef<LfkBe=uym4im=|7e27C~BygObCHEpwnu_s8dV=Da}M3 z=)%Og-pncKMiyo`oI^X%f;J#PG+3ulu7i<w!-0C~gHq|6%>-$L13kehR1nhwtbvu< zM6eZ{o7!eJxPwd}06Pc+Kl}q<VaA`5lbzl~eB{F}xFJ?H>QqEkz!aLFE~+D%nLSuT zHoQUr1ONiK!#ltO%*~#ra%6XU$)*6n5p08FQmRuN0{}?Eqf{EMj)kt}XsVK;K4gP6 z+(M{|sx@?jH=qN8^y-_!>2Og|ldM5B01hU`sjLQtoy|nV2^axNo3ai`{JBIvSc5l! z>aYTUJA8vT$it^4DTdbIvcf3^Z4rS~|Lau5K_4(<E_G?Q4#^UEs;~}g0GO*ecmuos zDZSoAI{Ydc%+qURgG}tl!Ro{x)dUCt09*)LpYH0uBH@<=Dl7nOsG8|Jd_#OHYsB7_ zTNMQk*aEHE0vn#JP;ieBBG$QWEE2ker;;nk{y;r^!#7l8!P+Lw=0uDQ!5-k`Zp6?{ z=tJc->O=y-3B*ASloG{yoLSl|f^_PqhHL<sfGJwTH@w3(j6={8r@9QSOmu@xJeEv& zf_d0gZ=hT&qAg8a%?^0LOHK*a&XzU21E?OtGlXh1^ui_F!ZTPy$tvkssj7mWL%40C zCq&##c*0J??9=K*#nRp0&X(5R{{kR@gEx3U0E9t2^g=XvYBee@-QI+_v28AF;_7Yd z$=1P@&O{t=UVGWBJ!C^Ppo=0zgCc~gK6vUooP)uxZpyLbO~?r=9&D`1#15Rm56FN_ z=m7v^u6w#`x7vd@L_;>*0{D6Z0t5gY46i;IZ>rL5AJjrAv_cVDY)u54{jDyF0Knan z*!yj-OMHVhJj3Y{gExdh0OY~&YUuGI@2fr6jxkopq3tNq1Rq4uv0N`*xx$4mZnwt6 zH~_29S_3fvD?FU8@o4Jm`k2V&k50TDz3M?FSg9oB#O>an=GyEzjKev^!#Q|^{}RJ1 zeDDanDe|6zEimIw>OvuG|9~{O?MyWA!G;9@6hTfD%VlovY`FwF@NYB_gZCD%$s%y2 z5t9vs9L&~$jxCuSK5bm#?M%QFF2L>-W9=0K);s*Ljv}xf`-CWzgiJi|Ob~)@JsisE z<Qwa5Je&rqdg&eGgb4#cCjiyT(d+9<$d|1R01Sa8m|LaIohx)m_UbJa12N;CY=qRr z%Vun&B8>&_WD&7KcscRPnX-F+@&PCEPJqPFBG$Hu#hTR41j;fZ)ACPTvP?*BwU(C1 zuw1nKpf9&;?gFzj)5I&v@RzwU?&dCLE;C|2Gq%#i#No)%kODE=F)R<?24b_&YBNqO z1^^U7#z+P_52HD||KmIJgn!wYdCc=aS~IW4^AUP7J~P%T@Ifl8pG<TD(f#u@wiG{O zCPLT5<*xGwuq`z=^bMLbMc;%e#M;wV=0!u|CwDYY48lwu*?@txGVAlcnzT(EhQ-!_ zfT^@ccdOpQG)`z*C`e=K*#K1$F-`YgCkfDYYQ_M)Ye!42^~yva_}57EbTYOpQ~N}$ zwSgQw^-250MpCs<_)-M$<BejqzT(6YT8iMnq`P`G+`XY$=dS>rEl<d^Kc_WLYybeT z?cBn3Ojn9f+ci%30Uzu2J>s=r=R{@B)zLIpV8bI(AGTaY?sIjuVn23PPBdgsHf2|~ zWnVUCXZBJE|ME<zv1WfZBq9N5k9Gs5hy|QM^{PR0h$3mX_RM(z7tpR1EC7GGwr!Ig z_5uI~%tRi<RbSsWaEsbh2RCsSw{ai$O_+cW)P(h#z)Uzca!2<`fdCWO#8FE(cE48~ z)WLFRw|Cc8cSG$D$OIH0^mm{4J!S4Cpj_dhw|iGmCGf!`@Im!f0w&l(BZ<s=?|1Sb zO2I%c`*AjZ4|oN=FM%I8f+u*j+JZ>qSxGB6gh#l9PdJ5>Hgs1whL4LH2wR4CxT;`6 zE!4G#kNB2|IEkM)il?}WuQ-dhxQo9yjK{c)&p3_OxQ*X9j_0_J?>LY5xR3uhkO#St z4>^$+|GAMLIg%&2k}o-vH@TBPIh04alutR8FOMXcc$KHP7Sx2=W;u*Eft5_Fmy>u5 z&x8_W1GkO&h!cVykO57+gE^dGnyWd5|G*;vKqbt?6?j9d(D{jLQBB0EpAR~rU-knR zdWwSyqAxn5H@c%gI;2Osq)$4fSGuKNI;Lm3rf)i@ce<y4I;e-bsE<0Sm%6E+I;y9- zs;@e$V^JtqtCXw+JOIEs7;jp~1Xj+uok~eMki$2W1InWFOU(N5X$E=1bhy0COvD4s zu9%kOL*4vXsm^+;kZ0ZK!#ex}O)yc!ma|i!;ijb3!zKmY;(;%K!#UK0I>;E$9N)89 z|J<monmGXbCD?>$&?`_oUQ}d8KJ3BK0stMr!#tE9y{f}306-)}LJojKK1|W8J5fsf zDv3VBv++*6bDKV}11&t8q93e^S_Q$A`#fCoItBY>b_NeJyD_{0IDkVv5JMn<1A*zL zK0K#3Xag-Y19FywIf#pT4Hq=D!@TqSJ7_|wp8RL*^ICTXfsjKz_<<xaJFw3%XC(Gd zFp+2k0w(}~%<F?4_=2F9Rm8i4(RXGzTthRIL#J8A!~4Xl>BBQ@{AJK-KA=6F%BnoK zy-n-^J$%Eb<U=-00RT`Nw_j~kPUZ2agEiOzHUL08FuY9U12`~yUKJ*r%0fH5|3jz2 zc`CF60I;d9Gey;NuHNGWI?zHp5S&bWLn^ofuzy<V&qTb81JG7dSTAX9p!78_eN#-) z5!9DG!7A>?UpW-N{LMuCIfZS&Lq0qLCvd|!6sSFLgB>IT1XjL1ghR&Df<3@F-DJEn zn8Q1$msW5txFbGnX}o>$yE3o?flU2WpxCpO(@V@|OO(GShatH%ZET$qKmZUpkYGWB z2N5PzxR7B(hYuCni)T+?#drYBL5yf`puA~su$2=i4<0y1m-1<3h>oQ_jw)fs)EF*Y zK6k0!b?YWjr@3a=!gUKL^Ps(a^2XJp2QME-c|-~71E7yqyK?|s3OuK;{~fe)-|WfD zD$}J<ebJz?%NK4eRJU(c%9B^IoH~8^#&LY<R&HOve*wdtD$ra;deo-qLnoMVW5+7( zq0{#*P@rV>(AiU`PA<{HE}uqXB(fv7X?Fm?+bh$YzIYWY+RgZwc2RrbzUh;7O`p)R z;oiA3M2{w8&Ea}i{MNLyOu6RRzDwnf=2+b4XgymSu6azCxs^d%_YV%d)cI1@R`1!I zy5;)(?9%s6>d2>10iTnH?i@P6_lc4!n|SD<r!acFSx><Q8H-0AYyik%jvNBfXPkV> zX$z*p6q2i)eC+V0KC(EHESo?8Ax9r|@~NjD1|R#aomBLJr#Otv|6yvFcJkTjExB@g zM;1e5aYrO`03=E$bbbm70KWj}MxSe%8IeSt^4aYhX}Hm59edv45XLbP0?i(8^x4IV zJ=%E1!g{*HudjOSy6Y}_pcE{g#Q;DLp*YD5l+4^1iG-V!0wD&R#az-5A~C@M2LNLX zB9svT_>2j?c;ey4jyZfGf*9BQ6!a~ZkYh)g`Kq(0FnIJ))xt(sV@R&C(97o?XtZ%h z8)(|mNu63{ipLOl-T|N{tnAq-xZ!kiOUia=87C)k;L*m-Z)P)fOqX&U2Y_PM5XU7s zEYXJ?F^TfaMadjNq6j_obMeVMi4x~tG4-Ja4SVMCR$%p-|C1-4a(uain{)KD#tv-! zLr<<!8FIAGWbELE({e}~DiVP*B-SB6^<jjQeDv|f4h!!R$l`%FqAA%_+6f9Yv6}71 zo@3v!S>%KYmPaRhXznc>c4*0GIV6*GsJT>E9Y`OXgL)^Qs_4=AXNL62F&~=ip$RyB zG;wDwn8%cBp2L=y%A0w_5kjAETx>e7zS1EF07(4EXB$eUkY}EGp2Alnd(J^)8O2=Q zYiqP2Cn~FW>iNSLZs3Ur9DM@egw*uf1)!csIKf=ma5$C=n>V=Oh9inKDra?U&e1%O zUPyyIa)xNq=NVdh)B4t&?P)Sv=bD|e%AC6Ksmh@r|5vE6WVO+z9<b6IYp3dUwNE9T zVwEN9Zd{a7)-b!>Jw|(SLsy=3@=lWub;zNIFTC|xW(s@i5eFSXC_xVug~e_Up+`LQ zWxs=D3IOR~p!y&Pk*9ow9v_m3K8*1OeSo8Y5ZTl@xbcR|6s~EEfQ3jpSf;&f<r0j* z2B)x*j61-|D4>g=ZGxg3cI2cc1T0H8o<*D<zU&}=sg64|VV={y;~lhc$Iu3%JD@$K zM)?5NIK<KvgA7FzQn8XobW)G1pd%=p3WqqPW46yk?}iU?37r67jl_(@90d|bKF+X< z1{%(3eW3_NzCaDd%)=Y?Sb`u61Sp8;jc)@H{}YGmfs8hqidKztPM;WYDXgUABDX7t zBIA-W0N5{6r2<DJ9-)}~fU+RD%Ev^e@h}duFCT%3#OEey8=a(aZsxezbM$dXnz;%p zQc{L9nx!m#Tm@;@8`kjRlE!e%W-s>%$4%ZLkHWB0h4tV{Dy~Nm+}OhztAbuG<pcl~ zQGyQoNKj!^BnUwSlZbsJq(1nT4|2?-9^=r5D&!!Keb!Tg1i6_V0YD8lq7yEabPGqo z@rEZAL?6~*or8$NF@dNI02&*N#00_#M$}Fo5=&u0T=E)~=|f`&%LgYabQOj&>y7m= zAMkp{79YCG9IsIo0KOp*^boXhzqyG#|9E&So1}ssxw@G{ey9&^$f7p`u~?RP(>QKg zwNXi_o<2w;m#V!(6U=kyOe?mU0;NQdqZCLz{Pu;+xQM7IeThrbK@V{(AsgtR$J+D? z4>3^VuWQ_@eX^q0gkB_I1xZJr1agrVF$=9Ea)~*_F^-AwZ?aN+h~|9p2W*(9E#Sa| zF;1G0n{g~2wLBRIOL~;Teew;)sAg(AA`fop0}q}%7yw|%I&M^!rp?MnGuQ!-ocd*` z7gQDE=(^B?Sgje_=*?5I(v9O*=`GE0hD^7{6<S<Grx0;TMTe2B;>ye%v|vYX>PlR$ zj%62Xm`ptgC_sJaffD&h5K&y@|IKB5!9rLO2s!dW2|r*~9h2=)lE4LkZ3y9k1X18f z<O>&lPy{v~+KeS*qMA(3V=*QjZs(q4Qldx{xF046743lGhnN%`+`z*$!ou24-3}ZM z^6U*|Ru7s5rEVnbi%#IdGofhlA+4cLRfN_Yp)k=9-f)sk;8E6|O*A27{l-oXTaak6 zgQ_}l(5-|f-WuH~!wr#(WB_O(D3L=RyP$(UNhFsG$zc~QdC5HTfs8doMs#5|$b~H7 z2kA;B9r11RLC$feN&sS1d7*5(V(AUiP;{l-!0kf7VT~I<<;RhTsiW<a4~&6BKbzsy zDO0JRA4d>%`S@LrgtyAV|6%DT!BYut^ij@a0_H+#0f0<lBHnnY7a>&}M^)m{4Y5E3 zd{q(Gy^MJ5>G1T?ZU%t4rm&67h^atH5rQ}dXXt|ru3ti^$3O?7-ziuF9Yr>;J@kgI ziy*{B<_K!Hp|V>d1i~1Bn8h-G<dHXk133oq2p+7lD43*lD#XA;IAm=@kXcFHo9YxE zM&;vIb_xK0(AcMUR~%U+7kd8@8dk{sWgmf2AIJRSNM59>r(m?n=E!FC*tgZ(RF5R- zTZmCp;SC-VurD@y#q+wsDOAgM7iUmsL4cGG0Aki&8c~~y_~y>WzL6gI^n=*dZ69*j z!w&}Tx<R%9067?V|LSeF7v(w!4sUkum9suNNAzK8sgyD$=qLvsdZBSQN@OaRh{Ow9 ztN5w-0uNjsSxP{Nhs*fKKFg`?)QDTg>CBBgN%9N0%uzI>FGMavK_aV$(n@`}V;F2n z`#@Bq40b51A+d_u>Q!qGrl=|&-|!D$Y(_2S0lfEqfP}gZqM}{Mfg^8!h}zI}hGm#z zpN*qOI{Jl%c%&QU0)d}BsIdgW5$>eu@*ea5u2MVXgVg}&G|yE+GJ$;2Pw3!ABv1m| z9wj5-0YbPzQWOFmB1#}CEFm@}Wme|oIzt}HA@E}A_PhmEd=E@$B2I`+ABM@77SDWE zC8rGPC9b9&|CkLTq{1G`syaSR6G-Cb65>^;q8)7HmvCmv$c8#*4*pmVAqoTla3CMh zp+)Y-E|%e6#G&h4qQT5%36SBhn9L#A4FHxvfEJ?BmQeD5&>&KZw|t?-<l!7*DdM1l zBZg}s!Xbo4E4E;w0N=nGGK3-SU>YosAs+Dl`r=6{Q1Gsep~_+dm&<O3XZVzXeFpH! z-m4A)B^<^9X<`o|IOZ&%AtxN-nxG*XFobE+>Oyv;Yo6*}H1HbMAslRE62DMw4&w~` zXK)VUfYu-yM90CdPb{Q@z`z0pF{B*8FVQ5+78^ou_-nGFC;h%~Av_Kok^v96Au|j{ zA9^7W|9T7#i2_3GiYGXS6WoFu=`XdwL8Mp$<>X?wI)_xIX14Ny@}|b`B1dL!@HXrX z+i<2Z;EElffyf#K40mcMz+^h!3QnwXm)rpWydjJ_OYw$>*Iof0f{Hm#sy=`Zhop^K zf<mVNqbvYGRdl6Ql93=33;?j`CAvdJ2tg1OXn5*M&+-9X?BPRXYb;d666~u9g)tj( z<gxUD4k*DE$AX9+3j-Odxuot9BB2_~(H!hx8p?rk1QNs+0@+^VK4_&JIp>xlukHpy z9XzV{kWC>Z#vWWJL_X&^kOYK4!gZ{%jjF~4eQ+LAttoOQje16F__3&1gcy_|+I|pR z|MJ1f!hse>!j%*$PR_yR{E>j9=NXit0d*<renKa54ck!VnsA~X)(8m4VlmcW8S=qE zW}`XcM-}`a9`>mUSr2FMYYikx6~|(5&>@iYVF;&)Rt6^@;$RsZ(_&QN9Fk=eKk{BO z4YtbBwO+}gv~u6L3d7hDCspVH3#A-jOT`L;8$v4`KFy@cp&4Ju8ViF{xWRJBA!6h* zg2W0r7;_vD^2Pq*hs<F&#wWgX1^}Fa2AKt}CNUq*L8CGeiF__GxoIfMk6ChvXM6@q zcCZ`ZK^e4TnzZtUZsptZ;RrT~o8mzT#vx#~3Af||e)4At{A(V@VtDRp3XZ`Z{}Ku1 z$_^Qhz#eSUDIg4B5KIsVK_Bu;DA8$Rj4);J0IbY%E><e22GnJwhHE||A6)0s9&8{w ziz2X2*F4V{HcSs?OV#Xv)gtdlJB1S-Ass}njZj5rc0*{$=PBuNA<1V(g2FBt0*E%z z3kgEwHq;?*;v15MO`8pf-oX&e>T!(9iI~T5Dl;FP0eH>{{_sj5EaA=`3nAb~U(R3( z5e(%DV;*Lb4%8H#g<sQO1BJiTHgX#!F<_&+qy?nA8w8}Jr8|C(+~{tkJ9Ho*2qK+= zBUDsWx<my81Vs1p{uB3e@44qZPjd&=#-G<lm3!4s4kfD3cUgN<Wr|c@d^FI0K2j)N z=d`g-RjI3rOk`3f=M8J^$v02xaUlfE8r!wrQV<L_IJhGXZh(1+#0ekF93ZL^u-7g{ zO`1D|MLmA^IxfpVRE?o7bi?wbI;uEXU02O}&3VZJVpTyIOJU9)g^?)oXZXoAe2QfM zH!BmLN=vHB-H@4mG<Dlqf^jzU*1zqCJ$mW~X%+0dqixPLqQY`N>q84Ag(1O{Q7E?R z8dK^KYa%4fDK5_s>Z~CIO-ubW7GMKuAq=h4<W?{I7?0i}LJT+ym=kMHCi3D^8mSuP zMZeu0=5?#%<2tQoHrvc=I`Mdt%(gh`GM}fMzs`~flB>+;J0#jOz=2*SN7rTShZwe@ zr^tLj#zZvMUB(Vl(pRUb1-$BgzXh{n2=j?^fYcZd1vfh_hUI|hPT;pYC(hJcqY?yi zm)m2*dMn$MhQ6V86iRY+4<vS0u1JmiC5*H)Sq+*5_-Gh`s(-L}m(w`99Tjee!yt(_ z=2}yyS0k0m{<&S+Ev2f~GWi95Ao-9iLZ`L_(U7-HkVdbrUWF>7NhWW8t6*t&vZ&SO zn0|<&<nxJmff+5f7;>LLMk%LlmM+!MqTiI3q)pe}zOn`LgBiy2sr2D9qG3eTC&Ro- zChUhg9EDEI2dWyHvZC9>hO2xRFA~1<tBRRO7b%(qJH^2%ev6gxa%fPy)L;X7rdWKa zxPw9;1Pd9RIzPI1APQFFHV|pAOFr3)O9+}Z<~N}tXL<-aZVj3dODM8hYq2Ac<eaSz zr#$IK{mZ~oy`OdrNMazC4R{(s?vi2W#`IdN(Y_h8ZPuSXVaH(+Ywr@!qe_+j^gdn9 z0v_$>F!mGj%=a(Awnt^_r73wB8q=P|K{<xVj9?vnV@ou~ewyK&bihB4;$W{1T0osx zP-(=h7x*#&j-IKB2dss(x(ZAvahudFm)pEk%#G&9jyC^n4me|0)Fq#58y92!M|XiL z-xs{EL+D=}<s=7AtXH`3w>dMtUN@mr6LcqO`|^{tRwFW1{c|}PlH@mO^dz&Js@IIr zb0hp&Ilr&l#e&<xp>M9wiU5yrSSo(gztJfWSI9A4%?=VSKJ;jH3S=e}R<VCcMp1C7 zQ!qYExGmgBv~e>S5rj3!=xD$EF7<DI2(khB%_Owp94a1<lA1X(38S{;?{pM|W#=z1 z*4`1uu@5fhOnNKWJ%OfSy`PYqc-08#jVqvAbyv*uA~`woQPOLwY>dP)ndAxpx~3iy zmb}B#l={2k6tkhqTIy{0Y(q?~hqbWQx5pKW+VdyUL7X<APS&~WBjq!G^VpFX;#HJw zG<v9N%zjl5UU}qeS-hu+XK5Q!?$#@FSHF+`;P9rHQxYQPv@CWntyYoRmMcC4?NjB| zR)||1pON)+5nvrKQ9mE0?r{Ft070zvK47%gey+>mvJZ?$h7-E1I4UwD+^m!S!+Ki4 z@~PGI%+{HUqwWzoX*ps7JH~eMlX5H7^b#L(y-qj&w&>*`f6z4MX<v#ZT7&eg^Rh`_ z1H95?@#cTG5uVTT!D<g*RWbQm#KA|*erv&^{PKI&E&k4=$ITMQO6Bc-{CA`xy!51- zLQ|(GUt1O;2p!4d7~$qGnw_zGzM-I>x0P@}^x#uzt23{`_jQJ@;is2VPvS=qP2752 zyw%oRNuP%qm%5Q=H$Sj4DEp^rJ%=}CliVTSK?1jGz50Gw{Iq1JspkmdzsaZT{xN*Z z=tB(GQ1K5db)E-OhVv?=nx{|MrV&59s3V9pZ^?L4>HQ(hI5#{T6;ARd<VqM_r~FiN zkKo?ftf{uL4amUE!usrb{nC_(#w%3c^?^B^Ve`RhOEl@KTLv=)j&n4*s{RAfPJ(%D z#Z8vntaj8y?_d0u&DKJ$v>E!$GuPCi+})IGG=ye%hOblf3NvPMN?ScQI4xFui00={ zP{l=ZY^U4VP8|uQqh{-ymoK1=<eY3f!y`(TV_vo)8$-0DEhsq+|Bp}N7-g96%@)T0 zLF)KfT*#oFSllCwu^ZKf604(n0;fjPS$n%CnQFSRDA)jMbHk0<dB&;yW2MM1wvAz& zk#|JI^ORLpwxAOArj3_DpXt2pCg?{h9mDM(sQo5rn58yow;1KbWZK4MK;%e2d7yFZ zo>Cp;Bbuk0!|vOGTWaVNRY<4vU-oo!BF67#t?U~#IlM}!Q%jiOdMuNbsM>dDgqx9< zd{@_dHZU>N%bsgUHHD=nbdM=#$rkyqiv0+R;vU^#-0`~g`)v#n?4oal%X4pnHC8G* z&h^`!Wfa2~$|nQaVV|6r)V?6&xfpOIwxyKpp~jxcWG&~MR>D~$eP^M4t{nTvf3r!g zy5hV{2cv`ORR&bQc`uJ$21dZrX;)PQ`B`v84cT2!AF>J=c|K_GA)+3V8|@o3ZDEI? zDU3+}T`xZME2$q4n%(Smek+$G9!iZ?C0-|FIfR(7_WFVum*dtyJ3hZLvNRB#vd6P7 z4^K_nxJgYWw!k~Qr>sqtU^4+<mHQ=>FE&414`0_1ze>&I4eIbh+3LMPm21ke%wEmY zv5z&eEvtS^{B$bYN%~jG<F9UR(Q~&4X?EsuB*F6glN*S_p^Md-%-{aZhiS(2`|d+; z=EYmP13OiER5_yTI9B{GFTp^zGe!PHxopktQy%ui@=NZCBZG!X&NtQHh@dg5L982U zf^R;(iMTuD%wow_N*m9746vd$1c4D6Aod(!QpDnsJ+fbBrt>_Gs#T-UPqs+_iB&dN zm;moJM6zxw2Q^oc=OI?mkKxs2&nH|QRS$-Zj>OV2&#&ILBkS)==NBs<j+t56rv$^R z$KrlSZU5Ro-qj8VoyFEMiI%?%>-zE_L*WE9?zatuBo$e<eC!4&dLB?pR>FXdz4kNr z?2nr1x=%l<H~Qbm-M$Q^)@d7;D@*ks%&E%<AprgOv5t0Y<F7qjS34gp^%uU#2X6qz ziD@6}H6wQq|E`aTI4Y(=yhzp>pisWn9_@)|3b2sDprOyHzFtSPT)^?#kH?<Z$nU|c zhupIsVmp%<#>xF>oBEHHwwh-#2-Y8;?->4k5n9_T<@*}5e%e>NEqecBqT1Pl_j|{C z3rXCCN}mtO-rV8U9M6@%?9C(SMJrd!prVh8xt3L3Lu<2Sp6XmM>XN-EG8X&}92G<g zKGDf>n5`lL6wFHUjT9~s9U00i<G*S3&iQ#EJnQ-6?{yBE%qyKP)0bFvzOMWl7rmOo zmU0wMd9LW3@2MMkobLU~w6uMKEq%ChokJymi`o62ZMsI#RxwAxW(M2Rk&e^-wShp7 z`<x$0vXpV8Bh<lF1$j`uxaD9P-7BU9OevY5bfqFTzA;O2E2o*$3gNg!rSL;ykFOqo zwrr@>g>#*6TDYt;7UU;>%Uw@K@zzN2YKX+bQ)!=TRvP49%%V7>m{6Epozs*dd=*mr z7OiRYtyytSE_mL0F-VVK=6OZmXcc316GX|ERd^UHYym2hqS)AEK7dgmj8yt+S>0QA z=QRl+>9S{D)Tu{=e$N7$b6*HXt_xr-k6GTi6lLRvwIqP-UnS+M-us2}R~IKBrOnr} z%Z`kH-Cwg_1&lf<AM=uC>K}t>$pe;%Ljx37S0xO6A+x_tYzHAynNK<XHh3znNqGp~ zXGF2+BK30z0=+AUVQq>}1_#95ev~Y|mR|3bUDVtS^D#CuB<dFUFe4XCZ&sgLoG%Z8 zr(`$&T-$vc{VD8mf$~BfaaOCPev*;<S9&Ys$V&((#Qxx*cE(ALPpUH992xvG{m;&` z*S7#JMlpAEbsWLqp8cal=Is1p_4xzxNbMBXS(B0E{BP`;cAl3^t{4RxulHP<bIifo z%EEu9?f??EN3aTa6P9xom!`g1wR0BK(g4B0P~8Y*uCQy!f%4(xa<D9c&T9X-{kt7k z^6kt!$;+-0Z@t!U(RajLjunJ+>xbQq#N1zfR^i{pXJ=Mz92;~d{Ho)p;^`DddAW*| zyJ`L2MqHXaUL|9~OPKo-oyf5jcdLb{p8ftt5@I7K^G)v<_b;1UEUDF5={MWHU-(JM zc@wBV-ZhbYIDIlZ4uokJL!IuKZLh^;c)cdkJ{Pa~%zHui6K}vVn)W`YI3Ys?w#j`$ z%b|wPfoc%~h=C06s(M-;Y0h?0c1j{``G35*!CRxZB7mVIHMK#N`~=pBYY5*_RhEnk zT-4SpRdLM}Nz6MI`xBjgr!)R>BERolpFk+?N!;C6aXbi^)LQBbzFcEzE)K_>vctmM z0`b3%mKuuX@Usq(0NGBG=j+K2YQ*A*m2{C4*yODql={8t+T_bBQnvUhvF@9E_ELpJ zYzwZAT}!z?oBjUBnj~~~tVwIH2Bp*!nCv@{fY@rn@NB3s0oOq}<nr2nVVl`rBHM1u z!z2<XsIpm}Em;r|_~|=ZlbhkSg1aIUP_rZ6eRP{6{D@2rFQK%jLJD2)+ce(F$?{qo zCa{#auq*9Ppu#*8*eN8nMN~Ih{r5;%4yPuQj5;-X@gB&kpjorMT4-3+RDRN7X|fva zERENuz!9oK-^I2jEZtQtEqzAnS0E@nM;+UuQzN^xU=e~Mr9RTp?$s+$NOzjomZma5 zY#hHWGOKI934N4Z_HudfBx1y&(~3Q)#28X47eD!2xs!FU-jpk%qGR_~lPVO)SP<Kq zqy1VgHD~6(F_|?dQejaA+0?E?JqnRGti7g9y}btP4LR@gW|~T0jtMi%3T>+Qb~Ji5 zk<?K?X!1QUU8sL>TF2dtk?eA2$Sd9|(DnMD?$$!R^(91LR2bT|T$@sM%HP~dh<c~L z&S@8X<J2R_>v?+jvvKegu+88xVYj?;L_()&gQ_NFrzEoc$2O^Edt0AQY{3Uz+#G%( zrfHjoN7FRS%>S6txgzKco1L^cmW$PtAu;2LYnssf0E4XMPSLwf@p`UN5U2<jY2@1b zkSkmw2Oh;t6kBw!U^`hXH=HK%uN1H097gsFnp*S61@fvmnGF}0QJzZ5wtD2N{KuP? zS#vJZp!QywhFg}}%VDPVq<MD-#;l-Kl;Ju4m{!Eocmb9e4m~z94SOK9JjTt@*D@(r zc<;H#l#n#-bhch6@$BhEBirs#8Ml%r%?F$|g33a&9&bK#;T$*u$f*$=b~-+Zl7pNy z+45}vlsb;}K0$Q+T8b$aNDQwckudWzB}+poq$hRjB(48Uy5!V7fyBc=x|412MJvmx zVfKrM<nkL5WYNyay``&^vboOSb?@_-cYvhV-JmB-qe-mg5sC6oUgB0S;?pq6?W%Ia z*bparZf7G9yN!(P$1xH_++Na~uHEggHVJZj#lrXa``810=bAl#F$4x}cLuFJd;@se zM^4mOSZ&A$7)oT5Mq6hGtn%HZ)GM<>p3-O$Uc`=ml(V~*RdqLuhY1=@svp|Vxln-% z08y;$DGJ<Aj4TmNNzK)8aq+f`V_6C5)76e=qDafc5Tt4DhZ6!jU^&+=*rdc%-CP<R zjS{<o@%xx{T^i20V)LGkV~!u6?|tHbWAs7wmLT<sUE&u|)K!yYV?@Y3V72-ME=gP2 zU6sE-O~*s_$M@zL-z=RqBG_~lxYu^;Sg*mQ<ukwRiz&u7h|2^Y@^^Esa}+(GVZFgz zSX4pHjhuZXr*W{?%U5=sI<n1ur?N4h&+9lnDu6akx(x&C96p;Aeun9nBXQ;|w{GoA z8ibi*Mg_*_xZfqQZ!?A}Z#j_z5Dt_`HCTF&lV&Tg9HUISp{UH38?{wC()Kw=5%%n# zXn^kZn38SqzctFP{w>zam6|m$1%Thw?zWZ$9s54YCb-#cD8{Ivi-Td0j$**any(fp z<0cv1wV|n}4?3M)HJqrH0>JOG?Jjy4j|*ge!iA4jWV(Kv>8}g9=0QueWh{qjx&U5g zD?eJetdBV~>>29cG1b*^fFFwf=!k>)B*FQ%Oc049BN%$PCfpw`*Rx=BmsGqm+3>s` zdfhF?Q%Jw@+?Tk9@e2kdPn*n9&D8A*O$v0pi}LOz4gKWdci!doWsU0}uj^n4{8N>w zu5-LIEq7t{e`40q)VSDxNf-<l>o)pP(#a!K9BZsaI5)SAm9weCGWr~#$rybw7aB5e z9@kuN9t&rsI)lxj_|r}JBlzKiN8qq2DbpN+IH0K=red~+f4FE4Pkzo=aiYtp4d=Fz zX$^Har_%$W=>5Y?1Zx7}o$0_Dd&?q?+C|tloaPcoS9(j&Fo*pkXZoBwJnR>;xr*j; zNwJ*-W4|c*FfcfdpT?sY#(Qiy5P=9AwVpK5gnPpGbjagXeA(UyUwUE-(b%49dmrgA z4PF{;G>yCF%_A4|w?OUy!*;&LJd1oZC8d$lD>1ijETN8;sOA3?4m&f+@aaeibD}Eg zbR&WQKY2_CHCQeI_WL1HlsVKS!{PZ6G-m)i<)q(L75^nbv!;@_d5$&2GMwj7oZu5g zlN>qf9Y0sGYp+nVyQ-81=)RvK<Z!5R4%6zD$<n=8)N=#V;)zk)cs(vYjwu@s7;y$2 ztp}?s^q>klCeHK|EvD!WWzeA3KH@4NrENQ>H5K64yG5O+5e+3`n(pC62*A%&s2z|t zlJpELI=n$R$}l=HX&2}+j`R%a<0oOALZlWx9(>Bp$l(f3k$SivDhY^F`@?8vm$<7@ z%tGY(JT?r)C9oT-^NurZ?t(Uomf=AUY-J7B^}ev}m~AjXThYu_+cvy+{n1ysP<0~J zBYad#qrsbc=p5R<Lx-V3gBL-og71vHG)b^RC2hlbd2^j_*t!c39Mg2s&vV%|oarsb z?*zZ)>6dvVYNNUQoB&#IqM5%%o5(C*xc=BfQ*5R%8@wK?FRrk|#oR{<@ZAW>B;*rS z$T!jVC%tl(6G1K6qRo9e62qmyZGpSaRKr9%bEXkH@Y}E?P2NB{f27zqI_R?xu(S__ zzHSWtfi#Pe@L%rK5oqduGMb$#{!k1}CBMfB(p-}WD*J%FfR;W)tFVHbQksmxK|tKX z3tBp44Mpi|ITvrMQUYj3UI|A+b+j3V#l(`{xI^c47wHF__fal=bUhRiMsv|!m01LZ z_lePsxtQaq-$Yp5ku518r_GH6&5BoZbmSRm(44D)^8=hu8)L6<LE;*`=NhoV57H+? zrSbJ@gK-3Et_S>_fl5h>Xr#mg-4a;;zPukT`F|FyKs{8B!dvCHL<EleJ};D>39=?G ziIgr|!zq?{D_hUd*xEUHXzE_X-QBMy--PkYb#u0yb7Z*Cb}rN0K<@TKk>5Yap5WMj z9#Jm@wT`<YcVJ#r7Si>XoYAJL(d+O*USCFmmOCCdf?*hIq#RtmC1i+)$y)s!32p(@ z(Jd&`&g$l2mws_yEimmFj@n$DCs`F+N>sds{_mx$@jEB#R|_m5qudBf8gspXNDY6S ziTk09KMsco(=(v#HX${$QT~($0FrC2Os|McC6*dKb!hL`K5Wood#4(Wu<<`rsd}eF zC_wJAf1@zxV}hDMfJK<a_s}56I~@48ROdJq*XH;F>!<hAIFZ(Jh!d(ABx<=u7@zxe z*9Ln9$cI0mrSO39#xdR4(bWK`VjT}<3GP&bJSrfxInYwRu~>bb+UF=XFbx*w%<u_c z)VyD0est?d2fKlU_JvqCR|lL+f#rezHIt$NEc2J+yt5gpmq*>lRoWLGnDS`YonWPJ zzhKV<6w9vYu*5*v4L32H4l*oc`U|n$KoeajY3c*Jf6BiAqG^=#j}xa11rLy$rYEaF zcbYh%L?U0%G`uxjypl3el=L*q^!>DQPlpf=cLuMAB>_B*>n5Flt@J_-;W?`dbh0Lz zUz_*IyW$Vo>gp4>Hcg<ak~|(<ia-G6XiwvJ`o4hr8c(_oA9PJbD9rX2lgFAX#{gq| zZ?L8X6s;q=0keuLWvcrqPBtq+#?ZP1(EMQR;`XFHKg|=h)Nu&A0Ts|HkptyJT|05q z;b`i=t-2&cN~5X`)bHh@<G9&8SmTDs5Ab8_CwFvac`pGbOqb-`F>K9=TAL9%(EWs! z6KcYwcjEK3?Tqz%33%p+KDp;rRIu<HNtj@cu;mi<5fB|q737!`6?li!T9+~)kHN%C zKmIloRw9VMn)e4&vUAd{kSYpOk4df^Cl?iJ@hu;OuDU~KkS!Cz;}S<1h~$zpkOixP zXK_t;-tqXUked@{spQb)Mv@jZ<L;vTSC2sNOrWdyM>!_$Z~NmCF=&5bhAvZBG;zoY z&SU~e+Zm?L!9U~d(DX;?>UY@h!dj=r<6D#N#n7goPMP@TLm%NO4SeExk6Ha`O-s&P zReRDL(>TGL3HB*H|LLTE{|Nmi{&a(A*iU2dB!GIJllq^2;j={n4JMi+C*4In^$$U> zlhL9d!$ME9hk8thsyk*Zt((YvdcW~07^R32sNi2MV3jg6=c(SCIPc~|EqV#(vOs4U z5s|OU-mgnwZ^mMG)=EAhK}8^r-U+KmmdQ<uMVx_>S4RY1Wp{>WwlwE$;^!W&a_$17 z=E3YlX2e>h%HySHN7OBReA_^?#<|Hk?D05D8}*3R@Sh3opnH9m?geKpoqLjdCNy!` zkH{@uuZH;essnteZpzpXcHA9)k|6i`>m}AD;)3AXrq5yu=?|)D>6D_<W5WL?JYhWL z@EWaueFG_95IkJ6YA9EKDCn&{WH%VkXI|A3P(8xiz^itn*sbp<Au9d#-1d7-tXnQL z!HIv$nrjEJsS$`dHtP%9&dy8nST&*fVehU$GT2{Z_k26`mw0^`HLYuHt_&Rma}W25 z07LWHJjjM^DPWxA*z5B>!Tq)Q7YD3E+mvwUc!k%5Fn18mmCEg`tuK$vV7IHuoob-$ z=3n<UCAZhu{Rcko_uHHgIlAsU+O4Mu5nCK)JG=p?iM5~p`BvCgM~jbG@_i<D>Xfvx zR`O^`<0{)G$MUt*vfQXWyFO8JjH>!C6>1L?7RCJb6?dBA9O%~ogDqKh>wGBKJ;%}; zCd~~kJTl;?^mQPvsbe&>KY)982DP$g&n9VAd#)GOho8n`NEQ)iGOZKW2%9-bj0eLf zADV$wnXfLeFD6k_aT}-wTOTQtZCI+NlF6D$ocs8_^G0ZOvFpo)*8?4PmUbMhgGJ;< zvi39kaTT(B#n3Js4StPgvq}VbX*F|3K{z5nckp@<yHgGAP@9=Y@F&H4Ox!XHc%D_G z8^&u*iNwUPn4%Hy*%9YkO}NUU_)nX!d)U}*Nr7cIpQ48_jPxyGQhMvN=84bJ#Z)%8 z;D#)}=G&5}dmwf&c*>wSjdM>KjEKgScifCTJm~KYV{)9PCMMh!CUm()PSnLif}aim zE8f!C9{TEh>>IxJcH$SSVj6X)L|WU7wrx))me>4q5^cp7t^(q>O%;x_WYA1JP3Z46 z_E%Qv@^n8`U=i*oAUJPrkzmif!Wml2O3k-F6GpFPm3}W5ei6|e7z~(Dg?{)2TFBaV zVW0OSKQ{3OOF##RV-zcY0@=QS9R%tJ5n^z;U+C%*2P_6nq)1W3c7)20L(@1bDo2f( zhTZIwiRSrG$`~FPds3jx<$mjNM5!n(;j`R-W>Cd@sm;f}VcBsRMrqR@UK){@e7puN zUeyo^Wo|#9_hR3>^KM_x*dVxpgP|Jw#S|HpB_n}iR?ig|JLuN8ef6MEf-#Y1gkIgn zWqF9vD5#_N*Nrsx4|88)LZDEZ<w5``?wcAdmxUfJZ}q8Q4}F*yxewBYqV#ge_*X$g z&fwM({RFe*+hmw8_NA|=hCvF**%-g{R^%5e5_`{_VntHoIEtoBG6hb#@U~La=z?@H zZ>+V|8TKgP{U+tZbYj@?3E?IkMI(U#G6qq%6>&#J-z6Y`1ZMpBMcg^y6zytQsTfHH zo>`LpZm8skWPRf6`Npv~;AFKvo_XF;2N1OVVc$gOHdU$m=!CmPyh*=kb3QJFxodB! zTy6Vvz97B#o96Qup=Fmp9D4o8LLH@3gW2U{^C2nv)|q@$aeENET)rocFXK=51iDDk z<@%ilImAaGrx^(#+Tn|I<Iky{m-0k+HTAkHUOM=kq};IR+0YJT1RCDfBR^Hu{L^}p zD)>-uO!Go@*{X@SQtYf$?b7VhwhC~?B*6*kwC{`9?OjJTh*jKVHnaPiiP~TLa^xc2 zmp%PIKF;{48n53&ICc-|%=;{ekd?VOO02ha(ND(M4{wrntm|sMQL^<v9Ztym24dl7 zkB#Y|LG)6^V9QjZruo<}DT2t`!ar7%wFR7XOd^84TTO(^TUZ2d(()ET!A3Lg1q~)+ zD&f}lL(_?p;1}eR<4G#zlVwp`COj2AUvj}3U8FZO(EcMm-=`1pXkT`C+Kf^4ALOw* zN6;eCv1kY)!S`ufRf|D=WDnfs_P9Oe+*4R<zA=aX7S5wQX>i(uTK}{<qboVaKzlA~ z#pPk+;Sl+5hS&UUlZuEL6fexLVwUC!>GvscPs~5pz2^ynBRB0%`WJhu_W^-j1cgJs z$4iwxdF?ua(Rbzo?c`q6R8cTaXud9HMt-I{xs&7!5epoVA)KqrOdjh{)#&ucZxCT} z^vi<-g(5wj8+oCD-PBEt_d>cgn8qChw2ZYwnzbG}5+U0fnjSCINA8*4W)I}#qTpT) z`LidA4t$oa5m<Yv#^JxSz-JUYSTZ8YPE?C2<&n|f#m5T=j#h-{h8~Ls0#zEYkbwnq z5qY)R4E~tiX-uZW-g<F;PTO}Lm@j)O4R>s3<V_w&r7+bSL!1(3MeoeZSmE>RukhVO zpx0F``mOXwWKNgg+uLh{j!zwGCKj~47$@(P4cVr&pW7KBw@o?1JtKF^#l0+L6-b~5 z_k0Mo<R|?<O^Eoe14aTrAG3u^T^f8VZiXjJmsxMjyT>NNcAw4K&+?UVQJgFy!oN3r zh&fUS3X64hZFPEGsu=i|@f@zVOGl4Qdr)|9?8l7F&e?*fBk_IuVzJ^qd~8u$_S0oC z*XTO-pzH2|C2=w5I<vUULX53qjPChS&`IQIartS(>xVY)?(r)JuoK5r=V*x9`#8r1 zXM8yR`L$Vf??TOd`wm2QXqaDHI+1lHDD%@3;@pWYbviiLr#{ETClppwe3J2OSu#vq zZM_hUE3~%Ys)X3C<sR$#5ed)h1@6T5F&-K9N%~Hd<U69FP@rj*<beg%0-zH11&1LZ zA;a|{ZrMC}@@dL-zhCSb5HVi`<dTt)qJ3druKQDS%qI)tJiN(i162tmPa7*$xNFVk zB`IX*8Oe7;COqArC5SCMPw<q&5pg!;3L}A-2Xn?!)$y4UU(iCsF}$=f7La((VQi2% zB;4eZ8K7#;3R+HMUF}t`eerzQaIo4!RI*H_>lhACTF@~|sqQlydqUTIB7pOK@GiB6 z4wlr$+;|A;)3U&QXd_}iEe2!FAgaMmnY2+@?IMkvV%of<P##>nv+!8%ZGBS7Te|d; z)i6dt@mSe>A&>rSy_EioB=;|1h_)#Q`m*k3fWWn*_+lD13=?LTv!OPXBoG66b(@(K zDVa*Afx4g$IO^SydTlzR)~Rr!=RFb?`G4YY+aA)a_|<71B9p9`7<aiG`uD7-5}6H1 z2xA=f{_iVLQINP`sg~fB>}gJF*ubXF&J@3P?A20d?__~e{e5M(MyUBgE$hBLht63w zZ*+)m7-2MJ?x4E9sna|Z$R^=FU1(sool3vLdFV_@JS#oMg<QltTK`E=^sZV*L^*qV z6@F;pc*{i-ivkzO=+&fc`MFq82!s;Dg@@6C>|Z)a<jgkOz=0dkOD6^a!)MZmXiT&U zb><5d%{I5kdK_uX+Sd_M)QUDFh^z$6O<pBX8LFq4L;oPvi8zZ8j;~?6!cH5=|GBr; zAd;X#-J;}v!-LIF2<cTz69j;)1Bq^#)2cbzhB{cRZi)_DVye*lBh!RpSN2~p4D7s9 z!v4c+_LiIJhRu?O9=@8Lnoj5mL=BU$`heA=YQnmGk}h|jOL|>r(u0?deyu!1?m_k2 z1Wt=AkP<0k@M2U^nCBC{Gl}t;`a@@|{xo^uvNZ3*H^1K{>we|*R)buT@NL|prO@0P z7benH9=Ww~>RHdqESYFlH1l~4bosn(%p<k=O7w}R3*vsq^!>_{8-bWA!_l6z>7uD2 zDkkBv)^;fq|LOfpG^xSmltHzNRVGgi2^;GloZ2DWED%9(o|93Z72Q*TLRmk^o&&oM zfAn%67@%BWRvxM$joitxO*WlmlOJM+Ka<!BsR_}r%E}$vpH1^AQw7e}Qzoug#)FN| zl_1_7#~I*2w+y)DZd~>m_`Zn-idWvKQ^qD+E9=z9ZT+2esdFZayzSKJzvjk|!o}@- zwao9=U{6kX`d*+*TDWJmXAi4sK3JNz?*{4K&*>0PO8?EO)<hXKezwfj#w&SQrQy+i zHQQqLp53KtVjp-Zo^Lj;gY>5Q4j^w49$;7z`ycq4$piud;^D2V<Z3^vCS-1t=H^)x zvXM?p-M`2}tc+O(oi4ciNa{4D_%7-OuQ~GC_wXdly^vN*R4;dUD)u4SQ(LJ=&9{7a zVCqQ5p|cG2)IX$2?TmOxQM`xQpYvB+=thxaNI33`Nf*BNn@q`q3hd=jGVML@MWvU0 zu#nb!6<2bjl2dy1)@GD4E+6uhxA2X3slyvLMf`ufcCg5%vd`~eSa4ZH&DgSm`5trE zR6IQ?mn9jZdEflaa<KX$J($t#z=ToOJt-s6DFM%*fY%r_Z(rkYl7ouSshtRgHYKWa zuq=Y}LjOgTYa_z%5Dyu|8%3Kbm`Zab;d01+73DovN8EV3-j5W7r9C78HmdLiuFvZJ z0Jh4N#|b>|6wi6wYWH-d6w%#mW73JdLe8Xw9L3t*w+A9uUoU$#xQB)Xt<uO)5#q^O zHVy%yIrDM=q!PyhEja1x(yAFq0T7XL;DG=M3KUdvk6D(krxPm$=p^64LP?o3W5nC_ zhf|C;xt{MSQ!apS1o7Cwl;(IPdV}E_&-5rf*wYhCYyfWz?pJ2cK+G0BERKJu!}tx= zO1LALf#ehzec`RvwQw=4D5$0f!z9WHg`cpS`9NajKpO&J-+Q7>7db0(HGx;;blhxx zPKi1Zil8!XI&&5sU2(DwY1jZotX!QC{8n`t38gBdJqdzh9Yj&q6vLDmb;0rjNqITk zjR~k5wG&BA6TipI;_C_X>J)fDa01hEDloKZ=-WezA<X8TeKPjg{)iTVVj;rb7;jYi zQ!~g0N*OAc_jaA^xoSdGLiuW7jhbhJ$g}u=#E4u|tXnhYfemrgUh52+;&dkYHWQ}l z9`++z8k*MB5y2%xHKcL_W6M@b0-#AwEQxE)MqA_y`Zw@Om<yn-8kMm340E2>eI-a; zAlIQY4Zb6u9D^N(<cnBtf*|EouwfCpt8CI28fXpGA#w146ZioV<*PoDw8nYv%{!jW zQ^a(qI~z0T0%<>Jrf#8@;s-@KRcuqTz0+Y#ve(Xr<mCy-#;zot3o?84r$#YDgbi-w zO$jJnFvj)?eJNEDA)7Kg|86QJje0KFD6syC?WjRiLCjjBd@qe^E-q0#IZK=u^12ph ziopmKkT&z*XV#TXOd^)b_<E^ZV<QZpYg5)hrt#pSToG+whM*ykOLJ>G8WUDU?zcaI zeyy*n))|f`y+LZSF~ddjB_lm`JJF=_PQ_#V5QN=0Hl)}An;_<MBeT9`EBxYwLf~0- zV%9OJd5mGGw`O}5b9*Hzis>m`Oe&zC@%Dmh_(;vEgr;Ss%KSJ}mLL2hFpZV2rWld) zmp>~W*LC+|^hZb4sV>&bggM@uF|!7P8A>)Xo1|xk95Q960$?8`!)5?Syq(0je)22W z?BkWxC_;9UKT(?Vvi=#>6Xy@9K{h?^uG*0iGJUBSnK+#cCu+y+gc<>bOxoK6RmmYf z#W7XMVm1|PDygoN<gwFCfoSRmF3#8`mH|9TbXD^0DzG|v?evN!03&^c<8h1R4rOBX zHWiL62AO>j2IMNsvFf2ExVz#a8YAT7e-a#<@=1qD02|ctYg`CgIv#6SBTP+dn*AOR z{+`oaDK8fSU~JJzQQ|mqHe(<HOveH)=EpAE8;kulE-$943rhT%mzAdbJa^sj+8}*S zp4b~Zc<GfB!w-@&c|3)Ol$6XoDlv|=%>zG>RqdsNdEM62c=|w&M4=<kpWiHlmTHlZ z(%S5~80RTcFVIeDNABZX)$C;&c}>pL4%6~{-MTPwX_}pFf+6aVZYRn#@nUdyzTtUU zs(;LnK_`7@9<!5dAgLaE48Y@<R4G#X#MrE=O4Eb!*;SNj6uPu}{Ol2~=95z(xpu9g zlIoY()?g&qzY4rxt+OvgEx|xr-369S;`6!AzcUR+s9>af8~mknpG|>LOyDmO&)aoN zJwJ3k*5~kx;NDfqz8V5WWP{~ti_UJi_LjFE2V|T;ru7UfS)`?Kx08uFC){)y@5s^k zp}S90URB}2wNXrd+!Qd0GM$0UU<GRz2iuxnEZ1=J!~jL(ELh4Wxn^@_fWS1jeDp?4 ze5frzAsTXbqzcRx#b!2I^hdm=NiscL(t!FZMZAL)m7VZVMNx^mI*Yck3{G`5YWJWn zb>As}Z7We*g(g8r=8fdzD0GH`8Q9;mDc&%LCX}`-vX+Ye-D37*ac5E^{G9>hEn|7Q zNVyCKdr`U;@T#lr_-FlSxy*0?ZFmg|<zEWycqed3EZVo!8awn%@b;?`4%j|*&Ltc` zYm$<cKWhT-mxuuY=7MG)s=P&ffadyMi$<dU{u9uTG%3G}%)*lu$;bi{+Lb&?(!S;e z!`cDE{*<AQtBR7W_WH>asUjap(#vpl>QQ~{p<fDg7z1&byTwU$1ggZv6P^}9YCmVN zEfc042`P85zhEo6o&r-hV_=u29W0b9$VB(=t<7drc+E7P;u^64Yi)ymd`7y0$O~Va zJWC~PgovG639)RNd4me9fr%13A}%Oz5sfP`Ubyok<<$%x%ku42Qh?EbubDeh6PSp9 z-(EXnG);R3qjb%p7Mh{jT{q7nfHlmS$QGw)#jKlHIyw~n(3i381##r9U&L-OU($|! z=b<AusOBm=#E*#bCvR6{2%lG()hKONlf}^K?}lbobQ`8{q<5#lK_+?I{dfA#5XEf< zVM__V?VVi-JT`wnj`Pz;eg;Jg!4q+B^**Es!f8$(7wi$Pkua)M7D`g1DeyrtN%T;r zf#7<#BwO^2t-!P6)}Lj>k}jfC;#gwHuth~;8G_K-OtvYvxX?e{a^z3mh=MQqWRunF z*_Y>tyu{LO{}C%U#KiO_p#b!4rjM$j+waSbYwyGx4Hv8FY6Y6&c`h7vsz|t_?ib!z zChg2K0ytkZAsEevJ~5DYO}|rbfq2-OlzBs<(9|;pZ>A$4(E#cF;smb<VN;Ox^977H zmh`Jb+lBrM>l=M#F^QJv&`N1#KN=GwJ{4hOVf|#=t|FbPI;pBZwRVQ8ZuEX<F*u|u zSq2990O+_ymd8kUHz$L;d%~42v?y_YAp7Y<!Y{Lt2MVl*Hd^>DwznA4%Y?Yuu0|2a zA}4?5P1}GnZZs7f40Q7^Pne}Rv&&~M%*46DRyOFlvB|b&YsfSjA209paB*;PMqbUu z_TuNH7=EE!5~`giP`$mUk^g-p>=Envp<W#|zo}x5#gphGd0og-o~eMpZDj0_d${(p z6#i0*Fp-Wzwws!Nh_R_#Yg*oI@-#?-_)QVH$~k6^WHSCD)B7-+izWT7XFK=b5R2*k zNIYDI-sb}^WiZ+^q0OmgrMNMdwsG!L<2*+5FQoE&!z<)#MoBx>mWK9cV4;=dPs~;Y zFemS|XSxdfdEUNUIh86$NmlTg|K>Y(39DF=(&SlKowIzSZQSQ%6O8`mz1WPE;kTIl zou;yTE?+iS&MLk;zszQ9-LU<S!qSFhptt1r-;wthuXhsJ6(EPh#QX4SnY%W$s1=al zk}EphkL@JkCC+-{bV12H#UM7ZyCj>J4KAPC9fFgixb%ZYiQ*i`_g1($BNB9mBm&_S zg0b(#DN_Q9$%8LaIhOoUk5X}XjJ@B+swh@^&Ba@bo8I<2&&RZqHb}xAttxR|{_@Ta zyD|;IELzUux1O(?YT5oLDJ}Axcy@RQvbXrkS4HCI^+c-9uOtLk+Fp8y1BB?D$LI{? zDYFNuh+)&ez#S);%RZ-1Tdq<O-u)jUA8C{Kr4Y)imL`Tvl&PwaBec&=f#1(f#2332 zEn}_ML1rCwSvtSO)gd;uxDb98#_*sjvy>B}gWA_2Ro+xSI%K??J1Y0>-2}hs94^%G zr{^7Wh`su<RFxd2negAn*;5{00J*8O_jMK*3Xe|df{_NJsdsT5sZstKR-fKQCCCRz zWG<Cn9CgJ9*z)uBfNVd>Mu)zXdQ;qW?g-Us0MKDfAb|h0@P;s!8S*kcJQkZQb3>kw z_;E=@Ria8F1H%k{9B}5b2b@R@pp&L?`njK$tV<GLcyRA&vvyS1mWtBF-_5Mfa8(v; zwuDZ!O|^Lab~K-r1i`S-ZwhQ1kQ`(3t^lGHizHRO;7pL?OGy2ICiRXlr3SD>;Em8a zsO%m*QO1v{DlDv=?j{T6e7X0TLIWHJ`Q0cB%bo-oxERzv;u#kXr#{WDv0j~K!Zs4j zNF-Q&(4g=YvoGbBCD2s+8L(jhCJG2Y9El3V8MMCX18Nf;E(CoDW4<_0eET=_*4zFl za9E8vo-!0rVcb<IdI?7WQ*nlN;Ze)cXem*<o3waeWJ&gKRWVJ6(>z!sgGbf+d3cI< z4X4_j>k4S*qQ{4RCQJl=nB;mZmAL9hS?aB)3s$H&Q_0JBH=KL4r;iHRly>uC+J7p) zU%WH<8bH9m(zWaNIltAs6?-1SxJ6{!<NKS!G1dLt%!CMDcJ)NaQkz0Pv%HRCSVWnP zj}kpq1RYWVR&e7aRYs2$BhL?su>66X<Ee~dF0Y#cxh6B&?-K8U&}<?eKY5i&n}c{} z3q|jbyuQFW_XhlY-C+(w+G_@SW^e0jzd@jrC9<CQHdzQPHW)c5OL=6nD}^wbE0gs} z)eHnJiN*=tg8RJdbbsTr49Y0%kNJA4TBpM(^7%#BJsEn>uBI_Z`uD=mv}t}gJR|0! z7>i;Oc!vq5RL}U7&90gjUG(E6w&dn6BmS#pNyzxr;7zu1?ZgEi=XwC_c4MZ<pVQHx z%L7xwYev(#&ZsW|WfdYZa>wcSM8IGZmIteEY9H<<IK)JK_S<;<`M<~I3cr7_vKBt0 zMmJ5(0H@@2yC#*t3yH~U?%VfNTcn&Xc7JV}-%!82-V~K7Qo7RFU5NfE?{4gJPQQ|G zLB11S>UFlJWugjqVRDY8%Sc%H4=5kCO=eCZ8B%nu@1jrgPy&(jFl6eO2D$MhE+m`6 zlXCTn9yZzsGhC7ZilW<71?rjO#VqN%lDZCP3Pz3f_$+AwxB`!0KD03OvFnE7p|ozj z*3vS+Y361VSD_7E`?MLBy7~6J?7F7KyzEzlF++_Now`Q7hovbFAxc&sEE1A91@Eb6 z5I(3^7h5XRe@wxCxZP}S5vPM!<STT|v`o43T#cmV(QY!&GV02HWVrBwxhdS?qNS}- zK9##EFARd_m@)y`s=aJk<N;pJE7+H?Nf6JQlW$9VcDyli6YTn;WFgcd8cAZ?6J<i` zuB{{&n&=T@BxL%8kvUskV{GioR!a&7*HykdFKgGoJrmWY#kYRXHwVZM05o?M7*?f# zqy9RL-!oHo=2yMyey>Q4>El&_)0%l!kAmA^_$oSYlojompH)c_Dy9A6YUr8wE1}1? z=f%EhXtZg3yiP0Z8WW(Sk$Ss!d1B5+_2-_|R>X7#@wHhU05H%n=irzO=im=~2`lEC z%bo^?)2$n!tfmkt6M6_>^>*{SsRn6~BoHh|1<0A_$>$6J*$G|IKgs8474J0iru%*W zn?Nxd`<&ZX4RiM_W30ri4yWmK&<|h8B@rh}FXXNYt3FxQNfg`R_ra%38|0h36|-$S z<l-RCo@bTE@dYVVYFX5Z!DIK%wLX_$uUBKEPmN@^;jhf*r#Tp))1H07rb-%(U-IV| z3{`)&?e6K0M7FX{nQ^a^s%dCy<eNup7HB7O=pQS33jL~bp|PDecmvHt(ne;MD#qK? z7!=$~MqEA5btq3%%Ey0dJEhI}OoU|r*gCcRqN5=Q$mDe0tXu(xAh$IMiSX|u4qc8L zo!1Y?5Q?TozVjU~Y~FHt!iPVrXwcG-43b6$Mzd4Mt7V3Z!$eN`b)F_mL7B#D{|ilB z)SHrM4lW<N-FLu1K08iLd7%D~On}x8B&nE6RcE*-;DB6ggf?$+DL1>UP*`@>u={PH zEUGCK10W^NDmVA+>U2sjx#8jgE;gQ2?UFCf+Hz(Z$-r8*?HA8V;bdb3a~<Tr(q~PA z6zzza4Nzg-NCk9TPng7I`XtCYKPI1x%|pXBL^NnB#lFd$K6mDpsZBctJV?Fc5_5+e z%(~iaf_(ToRdN29>o+Qhr*&YqMyFtyx_vK-JrHZ^n9>wy!7r*znWOV@!j;C$_7~S4 z8g4n?TN8Di6UgK>C9Gd!z&x#9)N!dLyG*VXJ(#EPzD8f<mu=Gonp`REs`l<1S{Q)3 zBqehLfdA7`p@1*35HSED07MXk4z6lA0YWEeKZUCv#lX1q%5^$w#?z=hm^9)#YA3Uh z>Zu6b&bsM5e)AUl>CWv*cqObRV7;?pu1qfYV0HRg<C{t<O+YR=5SB#`x(_(abTuzE zn$+qgwS*vr<8(Mqh;fi1YJe;MV4s3fC5O#vK&51+r~T9OfX$guTMrFw`2FuQx;CV< z1$}4|N_K-@ocRp|H21**?tn6r_)>?q7u%-Nm3-Uh%j>>pyNQ+zBzPuMQrEa_u!v-y zWmVxDoa=0bVgD|Kv5`E;Am<N~vLCRi@?21pQ(Yte<LG79-}h@5Uwg-GVS_V`VZ|CI zwlb1LDFig>5IBqn2QGh+-s_U-WdjUPk2Ys3-z<+~f8RQW#=Ig?VY&i9{A*~`TtGq` zguMwF@5r;a7DuYZzn(~+*)^_dW6`vpj0oFX#~_pWH?Z7=o*OCr4NV)V!aaK%Y2p+7 zo9R;TJU27scA7Rb70>rJvs6F=TiF_nURyajyv<v=1~U6wc_vx{+xZq&UfTsW?#<hU z_F?<mMNY{AJH>8=UOOe84b3~HzCHUpWdRccyX7J8ymlW)>@@FI#GLQ%R-!>OJY@8c zs5-@Db~n|Ube2dWGDeLT{J^b{%dz5st++9j^A$SJdSXpGSX0Iqn`y2rD();LEQ?(; zDf1Db*tz+pS!$wO0ZL6%p)&vgZtMNP;hJ07ESu1R^3&3iGdu;Fdrh9QPHvt13IJgA z7Nk$5lyeVxNI#$CNT*(_B-7dL-0<L#zINFnZF?KSwrjd3uARi|l#2{cR}OfPyi{9p z<OUGZ)GBFTVigjI#K1O`@K8Wc2%NEzTJ>JgB5_pxJl?t3;Vtpd_#$Ke_w2PFkvRSo zN9pXRWQN{bojjxatxwNcxSwTjygmH&Mg=T#ir2XH@N_|kul;n<K=%9Tl8Ls+*|LT8 z!?U+G9_?rE?8CpGy?4ThoUgbQJv{&5+1P&m(f9fH^G^YjBEMHd-aq{PIbyf{_m`O8 zgpB8}{sW7`A!vSL6=tpLwK$dTbk2)S$adUMD9KyZ?5S*U1ynT?AXcFzeVcu`N8zj{ zu^&IX<gLngZKuym8X6z<wU0eNg}(}+*#EWdqhG3ka6w1(N+a+ncN+kRE7(W#enhe< z12ApX30eQ=EI&ZLi7E<+vCgy5EXkQCq<`^I?1cnCjiaypMCl^X`Y!$y)UB)|`g1f( z78%G5#~hLDCy44ayy{0~A;HT@*A)D+uwoTz4C_=6)08Y!?g;r9i9BP}QSC_Lq$d?% zQq5i?i`&|8$<&_$-(8UjXTZ_*;uFSI)>BruMd>%56$=Fws~zXGJ0<%#{vZG_I$*%q zEf$hYTf{`=5TQoj8%#z|W|nG}KS%Oe{WE<AKgDr3CvV?TA|C*wvM1dPj%i9j9GHM_ zpQ4x_o4AOKO{sUV3DY3)al0V_*tq=K$R50=xQr==J%0!!(W^=uF_gevJe<wrsm{h- zJ@%<y+}HKA{9nuzgBQIEM21NXHP)1-Dc+G%GL^`hj3bh#zX3^4CGyGbORrE91H4t` zXR8=WE&36VjHfzp{6dOLry2v9fIA`~Cq>402$VFXDQQM7<Gtwb)PH+iK;f9&YX}K? z%FQe5qnc_wMG3sXG0Bse8SwlUM6yus&TF(FEkul_|FoFEOU6eS{QB3Az6!6&>w-@( z*sCedU?meU3Z$?uH$}=J#s#!Y)9jE^Oi6o0;2LIq81Y(VQF$r<gidxaMIwE4Ld``L zWLz$axHNi?R4ii3<k&Pgp~h)XKzSj>&PfX7ev~NcGGb=u_YfQR2T31iJwt8dLKg!7 zhcrPHu!?!?6a3oG!6r&CxnS6frg6TW71f5o-1^~wQ84c@KIBVYweWQloHF;Vpy=Dm zI&3Y!@(?H?ex&l1kk4YiU~15TOTqAzrsx$88*+uO<*?tkAmgMkx5&W}JA3lkps2eC za~U}1TAXq~D{_qSB#TTpeH`SV;0r5c<}({OnAYYUp#e{C%Qh~qbW9{gx=B}Awd<L6 zZfv$kOecdQ-2|znB3``f4jph4v0=1c$=nEk0wf6yD3DsvJogl080XU&zNe4qYAkL_ z5G@rNWOyN4V?IWz+TywVUun%_KQyld-=EKw%^~y^5G^ppu)*=Zn)Fh8o51RyuSXy0 zfTh2m9|^QNox5~_GsY7|73&q^LwaAuQ#^J4j08u<sy!dZdW!(8jw41ZRRG|_Zy@0; zYF6Ax{JBXAfYAg;*o3x{1Xe10TALP!k&yZQ5a*$D&R%@qS8pTWM>K>n9LPkz?G~ZG zEuqbNsEOnN1!X6#@{!+AgQp&Ah#0A+?o_xC7-AqvLaD#|53a-qs9t&n?Ebkq0*=!% zd`8(%O*4(+n5W!!=yV=UE;&&RQv)l$$3ZRPKo>DiIL0qun@BS`^VF93I5EKIPru+5 z9Z;67C68Rk#ALg&Kc)??`9tp*{Lic<bah81Xm<bSOW7JtUQH23BCA5$4;5Vo)v~9~ z<aet^5vNs?)gJAQN5pINYDo>Eyb7taPr}?-q^6#Zho?H96Fqiat-0u&@iX%sMf^I_ zQsh?!#}3$WEbo}xzha_NT~R6jLH9(3w{}hVR$@Km{%^hu97WvZSvVCBN9*BD`Xa^3 zwpXS7OzlQ3i0O)a<TuW5FHUX^$gY720-=@T)L+Xhi0Qj+lGvyAy-Y1kk$Kb@#Zw~x z$Y-S+zW|k1s&?L5mU3i=1B!nm>hyEm$ihSZqe<ul#oF7@ZLsM<_h-IkCQ1wX=8*CF zT?!z$Z3f{E9{N9|Ms{lx;UDi(_6hOf+u{lxUxfku0)~HV7BY8A6{CCm_;^qi-Wz-k z3}}c_ye3wGz9xOHf#Ca1A{Jjk`*2)MDXMjj$ccRmKlx@C9wPPjxZ?0TAKamuQdK4p z=02rD4T?)~stQ47u2wJuPVx^at^?b!T+me&gVgOTqzQd{#x3F%&Tlm|#cThg=q$LR zYP&Feh?$`#DCzDLlx~LZAtVHpZjf%2m|=z<q!Ex7DM3j=q)R|R8bmr26c7*)Up~G+ zaMn8O+2=WH?Y*!2k`j=}O^Yo4z<y2-Sq5>y0%v|20Fpj8Vun*#B(W-lXD{aJ6&|2u zR)w%5NJw@b<CmG<v^@2!=aUobp6kj^PA0Ovm`8*>uyO+fP;3~DBMdVqSgjU#ssh_P z3Rq?L22=tapF0EFriEf8Dt1KiW+WJP()uA<8(+etG9pPkLcTR3;5H*qi~%ta7Q5*d zQA|!^f#BtdX6{F<2f6spxh(J^&hYT7Zb3&da4H7h007qpiu2$o2P%su3C;KHq(S(n z5#8nnX5@rfq%Q&a8av|SKcSwts1SmPR|RZ&Zmbw8jr~K~(rw+?O*Uv@TXKZ*sfwgY zS0f101AvD>Gz>f?5T7fwTMXZ508bUemu@V0(HQTSVo!bWPyJ@XS2A^9a~p4;haUeS za_-gyCKZL;2oLT@NB)-Yp`%byiG0ChLCoP>5uHeDY*klG9>pFv%ZDiB#1I-s6%vLg zUZBt8V{Bp*Q|Ks~@fdG*?Z?9jTT;dqYf9~QvZA4ca>ZZ|cA_O*Y!HG%kWc37RcPhf zvpJA`)=vCzNF>5IH4jf7hleT5IVzb4pA9E{lZGV@<F1NfMSplcg91L$>twK_>~Ed0 z&eqYO;2{)*HJUgGP~9;l_Cr9F><DEVAc!5(ZOhQ0GP?{JV&i#lOD&6qZL%gA%IY0x z4gz*=2m62v{u7EQc7-pq6QA82c?`<%$h%vc(@;ED!GB&*`}swK+uh<<uF{t{#VJ#W zU$M+fC!!)e`3pQg;ETXngI}hGIsh0ngd*BV?7#J4>C&O=c-XDQJ_`@8c`NvBH;FD+ zXvvi{76|!X46}Hi1-2(MeN8@LhA*2Wl^RGeb;=BaXtWnYj)xQ=>jY72IxOrY(?EOy zue2hA`+Ig06;vc^LSUe|6TLC))DC`D4F8})apep9hD9K>VaMGb=U`9s*cc54t&B+m z;~errd^i<I1HJu7qf*qlO_4C2IGI7LU5xC#7_pj)@h-hIn>m`Ohe$ft>Z2=yJm@(~ z30xx-EgwRf5(>lJoY<4u!>^8@=WCG6XxN5tp5ci-%8bm&0wTU<Q8!5@x9v$eptkYF z1pvstzZIqCMyRSF>@?Jy*T4#Eqz<%X8nbyWaWN-$uq$?`6#KniUIe>_`FA&K*5l~c zui=Znq?^UTI#r0N7U;DM4BM8k%jrotMRpqqU~^7-VU>CR!ZXO#y4a39Lkv+zR8A0J z5*BYPrD9yFX-l~+<zQY4sF0q?JUHD7WfTkpCIjKBMM%i)@&xn^I}EpjIE~KU@CDDH z;1w1;b^a6?c0~QJUIc47UhTj5we5$HL*S3(VrEI-qe#Sj$)MpCLjC0`*|5v#Th(&X z(3%YQO_tS+S~lBN^p!S6D;_Q!URtXIziNPL6~ndmN{u+-o0HJzcDJo|eY7;0#IOd* ze6{syM7tQn^J21$5|T(f`IjKFQxJeW(~B1Lm}`+@ld1%Y$vgpIO9lRiA6k>8Y`#lY zlSt{19d+qTew&_8yk6AP=2e>wFUJZQ_X?I^DYWcRZ`FKmV~y&o?J8Xqj0YY*a&xbl zm6?zCl`$s~T_b}og~CQtz21>u@CJS)0cgqWuV=lvs9!5r$|YQoO##4Wam9At?I#_T zNK&usk8=yjxjG{A@}+Q~O*ww;&iz;QAXq#)+~+3DHdfGwEZdZd)~-uVE9T6`<L0;h za&ho+aaJo5k!5Ehn2zIO^rWgm99P00qbL@K-swyWv~j|&)*yim&?|OxIcJ6Ik(b~e z6QX0e0vao#9!N{E{8QdXk>6ikEs+L}N>y)0bu@s_<6$+WaNI^|4jztfqdM=d@W{*8 z-b3u;VS5cwm+y7O;oQBq?)PGNxvOn+R<o>=t$?~wF4tYn1cZL2Jeu}hlm}6?hfc_M zN%eVwPc2}83I3&p+MpUfm!Gd;jXOt0<-doTP8MD470FI#poB<%SjCL{Q?$NI{qeA+ z0R-%x%Y|eif>7k#)E3WzTgb!xndPJq{NA@~)ysG|6ShN|1MV3@K6O(Js}^w4NDA(; z^!s|{@m(xK6&aX7PP(@Sbr*!0G8)TWJtC$oHhGX~$>^9OX(c@1vXy22wW1}Sq0a7$ zz&;|d!xwyoih1*b+My*l@d)}vt1DL!(;-Ac(~*RX%{rSD=;$cgDwgYN6M{CY;UmJM zz+|tmi1F|7qAo4XV#I{~1_dr=4qxoI?BGT?*c&iy!d`_o?)756(6=klOfh`lF6NM_ zW0f&Hk-Wd*yp@Q<qchm+b48y?GomRlf^jLmpvmV`Se##ey}U5|6c3+?1}`#sqt-uM zsZhLG!@+Q`5x8vh3#eOSnlfSUUNO8g3AW^l12sZZHl56Gh@EYc14DFMoI(OdoD3<u zi*4lNNGS%;7cFq+A(d=g>k&n;SHItgz)~wkp&%?=fSZ!O8GqZBazj*ahSheX1R(`H z0#yR-k@oWUm_6S3Tarxak$Eynz0+^JvU^V;M612fICT`v%v)IkA&o`E7+w#3av}9n zfgg@EA^G4|i_oFym#xfXMw%@x2u&(Km#5kOm6I+6b6}8-LM_jTU76gsVz_BE#mdMX z|7&R4+UxRU1Z@X6+wO^~!|N*q)Kd&r<(a%gK9K0v96S_=kECo-K{SzQ)Y=(JDVTA# zezKr0yk(*WqQO_ie(=yX1@RvDOEO-@N(#zh!JB;OWid<`%0;j3cNtCLI*Bgl!>H>u zG4eqh(Pg!?RP3kqc@0w-j7blIU}u)}=kH!C$KE4zzgQKL#{D~sL+`5uiiivlz1mPD zBIa#gM`KOeTmyI+0bdaO<dYC=#Q^(y<PVw(V&(9K4*2_PJ&KYeHkbck^F`ov4SLx? zJhN8!J35$hWje&Bbd7vmCp7Qet|yb7gzm)`afhlIU+^*zND|XSSCv)lTSzG0LVv8( z()}31M^>|t_;J>T#R@U+B`H9*<e`vX@RfS2BRH*lXv3-~{yMCLk9ZmAKhfrre+}1a z=r{C8rth3~bDcN0LX<2cD6*z#;t^~&GcJ`41sD|hGg?bdMafx6b2iYrD)xThkOnT( zAEe(ZmWXiEszrA|_4bBD{c(iHUA8PatdVYCuAc9(7ZR61a>cML97>MmZ&SWc9N#0| z!kPT%A$eQt{y@X`qXh#3r^kmCykst9_FbtYz>*F8YGGN>0nU{S+b)K;5mtZsXHWB9 zRye?i8bnp$D}Em`xJtC_CqevF%#3>A@qdbv@wxE5%awaw)4u6Z=XP~Zb_-cW5tNp2 zJV3gEuN9}tz!t)5!Jpj25t4>YFWv<V&r@Rem&ge|zwah6{W=ezqAa>3s!icMwiLcK z=nxpqmM0v_R3vPOK4XV%+#Ia{>}~gvepg3}PgvS~+Z(n#5id6H&7a33j6+^?-`&+* zpaJiGlrVdn0pAy!GYE*<Lcuc;kn=U@IX|7sU_ktRKiHH&j6T#ey67%4@Lz7WPc2;3 zY7}I=xtWJ9jU2F8dPH)Kcor{97gxb-8<BR0Vu&3YKJm@0Os-cO(h*(xN#sY(y?z>k za4#*$8T-c-YtAWN7&5x(Q4wPBY3US7gktI=Y5D`YafJ6^xRe;_6#%np7qsj<{KQMV z$PQ1DrxRs?=B(i`N{Br?{HY!3F?-BEZ+MKtaA!T@_fy0g5CRt0?9ruUrG3yke^ABu z&I|uDHENa&4t%;%ft*Cc$l>(QzmL_EQ?~yH^5i=a_HSy)s}=S>Af-IfN=9&ze<wfo zrr;p6_NyA`?mq>#AH@B*nhZW!gWAV`*PA*^$h~Ly9pM}W*0T)%VaOq0m(~#tK0bo_ zg|)H0q0TLaoRse0=oqcz;RWA49{kESk2{OCJN~9mPw^rf&UV~+0X-8N_ABI6JD3aW zxIIS79a3OX#mJ~>f(&erD1ogoH)pE&`6o&4d&6ZKpc)surs=<@P(wJ*jDrXS)*Fsg zfu1)Uxj*Lktpbl=hN~+6B{p0#G}hq1bO%lS-G~Oaee3UdDY1>%q=<sm*wD-V62H+# z_=e#mZ!Q;C8GrJYrhQL<`5IknDpP(oqH=TnnT>$ZJ%*p9?5gGbEzu$kN5C5k7+$V4 z&f)U`0+k{K00d=i$`N}h6A??i&*b`RO+ArT<WYaF@up@fiy~pMmLVIr^40KEhMV7- zZnlte7y7ly<K7t1?5vvWuTS@)PA%`$GMMh6N;OhgHS*2&dtx|#T*f#(Up1*_vmX8O z%7{`ShIKdW(=L|kLzpQ6cWu78h>8DYmB<LzXH_BD;!V9`^<92c*xC1lFRglp3jTys z8yW?c#}0$y?xQb~3`u~%(?}|>&g`}BfUD9ERBeA8dc(F3yx%#bt#qQX_dgoGxXTtj zv3fI!`a<`s!80z{w)Y%&$*K6{q<BdWJ6$9jP#U9*Wwn*--QL-mqkd~pw7qZU>F}@i zmyK@9Q-WW}vd>JHKM(D*=d@f8JW{&8&eJ_@X?`5FoXu{L`sOc~yP>-TtgBrRDJ-zh zOqB9)q{#1-fIUBw`G7=8*(_m*DLgkqtpDAeY3y?>jZ<1{Hqx3@jZ);ffmAnfNq<4_ z*7~6aO9=C%LKO48*Tu|XoqK{&q5^vb*TN1HcLRW22Zjh6?rBBRvymN=h`ra4j~&&* zCagiHVV)d6kwo_mB<b{yv~>B^UB^=_-)gaG4UV|#{BtVfXNk(TibKklIf}M>Pb_HO z)CYFj_)RA0l9N+~88S{A>)k!$=lD1|rG*<6gHjKX60~WsD3WgkaBiH&e7`L%=UPLB z?c)BTCnv^Q+UHL_W@N>z-(f#``}`QOuuRjq11wVYo+QN*>bLMH=p4S~L}V3utNV@J zh9U<J>fL#R*FEKWnL%Ii+cIK<Oc?bg87loql1)#GyJ}KadbMU^#9ZOL;j0LbGJzzY zVb~YWSF9fB3(xxZk@9EL;hj^v6h*>G7j`K%Xfp)TOz)M6R-DIc!%1F;pAQqwziubv z$Ch%d=77oF7m`&8pWa~KT+x|phm>q?=ZB}ZyAkDmK~Ui(yM$h7EjWs<#f^Q^x=FR2 zOc-`6(Jr&>3O6@x=fvF)p1B7aXrosxZFcF9pWdT%O$ZSDd!!R(9gFR?ehXrE?!Y!t zurQy9yDl~_*Yk528eHqK^d6dzhzhD2;M)C{B;AV}D0d4`KXyj6NJ0h6$d`S?Sh1WR zgSN-tc5nF7E=>r?)v|^+C=db-rmze7A_2}9Lw&iXyXNAli&Q&{InN9ZLkTm~SOc%A z7)-x?m*D42FkxIRK#zfM-(2J5sml&rcj)u|su(`mKnvXu#lE~DrwuRnFY=rFKJPwz z9phAv;ORG}|0h<*Q`o4*(-{L}ZcJ5_BN|aSjfr=t8Wf&cemTdT3D><KxMAThExbgz z;$@~jo8({VDG67mg^NKR{fpy3`#Qnn0Ra}U&=P?Fnme)F!<o|x%sBQyt}p1P*k&m) zOSuE3-7ydH_(vjX9baX4Lka6XPV2~_ZJ-2Y#B90%R=iWu9JRm6z(7hrE9aJa1_;Gz z$m__yZ%8T19l(N|rb3D>o5I&fy`R3mLkCKr`46{Af>$+#>AApE37jJo-?7O~s$y+( z^}@!;=ZM4ZeFzVPhXyic%`t<U-c)Q#$EiE(Bb>AYlhcz!UfXJU{o%Xy_t;-s)9TEa z$^~LfJY7sVjK2Ggn%xQD8Y>x+KUKwHQKOMy;Y}Huk{milv`6d>fr>0@ptTg_g`_}2 z<W6q=cEktb1(Y*PX#>pZliIACB%?dYvY+GF>qJmfSfRzi`+~CCPUl4AjG>h9KYp;h z)3q7O-eJ9e6gpTW(k7>B3R94tQAAfrGSA7A7R%`E713#PiM&v3TjY{=GInjl3s6ZO zAVYHc%c!l8A3Y5H*zs}`Iv$C}W~+g$8;Cxs4g0+BU&low`iCjk!HTo&Fp+Z<uZ*hY zMDzFz`?zX>^Y?YOW!uUs1=_9URZh5H;Az&m-(>jS5L0;_mdXzW*LRevcMepQtmrV` zX3x<IJH21gK&C72SzgW%OIxNyi$%EQc5O$EFlGV3jfs|;T2yTepQYCe=MzfE6JrlU zk?A23H(slj?J{MpNiD;JM$^8NG@e@f0vX)ZyjzwR(luH5K~UCI3yP>Y>-C()?%CZc z!y^x}X%~IR#Nw{_;HGz*OZNl_^1`Z8n(J&=A0Kc)^z=Pi3x1Dh_)L+fMjCNvPpT=b za?FRO=+VX<gVjRjY^De?VNU5oy}W~r4h|tnM8}jVqodt}SDI{*Nv6j0JgK3zJ-1}p z;hSN{w6JSuU*UtTrFu+Rj0_zorQsbN+CZ?=R@wW1XTR?Jo3@Z(-%JGEirB==NCp38 z^akz|`iu$Q4L2LNHg$H;Ri|BY%_S<jCNid7zsXK>t;|i5`(%ReN@`1U`GI7<OjHu4 zga8~hLEckw>}!;dgAQg(i1H>yaFmO)9^x(rgj$MS2xwF$myu7f|1w~c_9b8aWg(Nb ze&mcQfbx37=k)oI_?=?4l(F*tS*)a}ssTN${L$4Kh=uoo-1<(t_jSo2&Gm{hjufOM z-{{n4!^iMxSeols@+nVIh;3bk5pzP_kd51+drJ)HC2^p4F?s1+%Gf=&$HidGgQyOf zgI?}>R;b-uzl2T!cl@tmNQw!0kL_={M~qp0B1g0bD)M_w?O7W$|CKt+YBQK(jd}6W zUUivMVBkxAaBByHa4Rl9hW}hDi(}LCM&~dzxHpy5uNs_S_Ke#D^@$7+<7X;#-kx-C zm$(Zyy#s0mi#;FIedQ`GdP!kiMDT>ky}BdbVdglpwDGfgKfzQ|s2`LE#-M*{{Nzr! z8sk6}MkH40^dWN`BlRd5aZT^8_gb`zjo=g4%5i~S*mDWauqR3zHBy;GjQ7aY>SVlz z26E}PD3=@fHC0-n9JvV}7)Qvm1MSICnY}b2(ir~JM~TMKgmgW_gHk`+Xq2rC*zV6C zYET4|*80+aF61JQ8;GX3zSHvKZ-KoPFBz~nn!55Kc3AV2Oh9*!fcwdlz@WiAsApR# zZ82~=&k+BMLL+~*Dr1Cnk4Y_<Z@8F*BQK22d0ytE%%o(Blh`>3567;%Pf<{wY~Fn) z(42)i#J&_+bW~`kd7$+*iMoH@<@pRLwvVw0_fKHvS%^i`H`>sljw_?a2n)+HrcD}I zMh#B-0)AVr!do+u9!pf5f{q*^nD7o^L6<56E(2gZP*bG;``mw&|EGQ0n+B|?C0HE! z!E-;&#tmcIrg-t<!=ezzWU`~<#fJ`RjJ_Sl<|3X~Plg>yv>YQfz?Ib{fR)PV+Ge0@ zBuSvQR_Q08IBsvddDtZ|!oTFsov?Y|uPsHS2Z#OJu8;pn+uyNFjiE+=6z!BZx{&|E zNES@UBBT=U`U5BP`VB5u<;IMvEPNQ;W(fr`BPCxa1Z~z=Qk6IE-;G#H9P!AowT$!A zV|F3MI=X>OWI&yL$crz%=W!pGJU>z^fQ)3~pSbm=PS*4;gBTfK33ygzc5_G($(X&B zjL21ZYxh=8g7No)s2+RrwS0}qkHlO5kMmVM=RF)Ah@P&=GpxqtkKD?dmG97iw4M5m zL;D@fdW`LqEo27G-7xgT8YkAY4=m&URS%+wqiqCmaQRmz2QT~9X!P(zj1R@b=oQSJ zRK_Nm1H@j8`nM>POXXcX*Cd2O7(VJAQ#K;7XKwstjab0~<&OK9C3)390hq-v@;XkM zrf%w{zRITjV0WPFhO4&w-NHu|QtW*JT*Ep%qPqlc-DRdrd!a%k_dCg~L@hXy5=GtI zi`Pi=*ZMo0&iF|iXi##{NsT7xF>UD8P#9j~8l^5*EHxW;ndvB(_`mhM#}u1MRi^w} z_3gr-2O9UhlVAKT<oTrBwwq2)B;`1nWB@4xqEF#3I|(F=*t$RQq^;1tC#7noNG%zI zG1D}b8KvePMTw1eI_bu*^qQz>eh`ZHK?wX4Qd_ZvYSrM{WJsihJHm7!q^0o>J@ox( z^tAS=T2<->)jy?Nl6EEH{lg&~J?VLSN`>uIr$BT7^>e#!5M@EXiOMi_|M<$SF+Fh5 z$!i$Zjl40I0hyD;2T|59H|F~~jC+@t3_I0p_Ed$lQ#Q&d+$`&(5*UM$<4+d~&5$xG zP2F)SoQiEi0mJbN5rZ8yig!CZzIqwOMH>Cd)OI-~{+oeokmXFj-5r&IOhz`3TpBvc zC8v}llJ|RlM5h1R&$q>?a9>jqC%k+V%0>AOLM`6-GHLkR!6#_*hvgbYk*!JejN)zC zKj1fHprJ}EAr_+QSo^M&gh&Iv>N+EdJol0&)KR19Bn_5v*2AyV$@Hd#M?&Oq1;FPw zVvw{ch)p+U(eon}dYV6LTA*UuICOfow%?H-a`S~Ioj+c3a)hZIH`6%4J*AuMUvfy2 zcf)-(%050tF!ELs1xj$6q$iUQ@h|(1(~{u7Rk#z2NT`0LnNj62Tj@05&(gMO7@pIn zC8QnxHCmJBoBo=;c0{4}5Mc4Rh;<cuCk@IH&LDz`%lz6><7m_v8U3PJ2eEF5(V4^; zq0|>^rmZSw1tl>iZWtRCNQZ2datTquu%vCHA%`ErQzq}Y!K`RHb3c;$@YqbfPepdS zO0G_8`Z_f>8X{y}^PRrPiv(=cK%h5?F{B4sZR>p$o(X(lv0|f(8jgQamEBIl(j&w_ z<i!ukYvEq+nF_oY>_OKWF_#`g5k6_gcyChgLlQ0qqPU)-c1mmwSXdkqo1lhof|@PA zc8&`vVo+7u*UMB<Yoa7HbE0`-u?^seni;9Ux1(EkJb-c{=)&K&*Wpz{6HK!XCZASw zNj%G7agz}DZp_15;XGjBcZgo88NcXUK#p5>nti;jsX{$i6pl!*P3XI2P8_|m^#PS> ziH4CHXPYj4Zpz|$u9eds;lyukbfL-^9v8Yt7U5iON1|%HM_lSX>&F9vZclcdEq{b! zmde$QhT~If8THmW?JIDFM1WTJK-7ap8m><Ug-LnB*6&y>zsYsJ;F*0J!LhoRW-bOg z3&50s=9Ls5uGY@Z)=hsL>*y<g*q`#Is1CQ)D-toI-+<)kJ|eOlYq<Hu^Lz-^wC8U8 zDXY7nf`s}l)`uT_X5C}jwv3~FsG%@O30nE_&svxnqmP<dO~Kw##J?H8Up@jk6<bgz ze8jqV2dLt<yD$83EEjUM$jdTz&IS51zN|d^$@oHV?(Ey@0kJJVF;i&91!sYPLK9b? ztu$@9Mgn%3{#BFSH#&QgW6I&l$aZw|UC&Fkv>MP9i~dE@s`=R$Bg_7C>(8BEdTCwO z@2o!l`wwl$kEZ7*cHaY2AlG=B=2jleWzy%M6tQQ$Yoy>*&cGH0Ysx(*GI9#+Z<?Ne zv}0XdOVEWl3)}vW3Kj?3D1Hsi4Q4yrNzkK);VvEhH35@K#N!(yE`iny!teJUaf&*G zmE$EU_@1x#{X)PK@rFC&X#HW-hqzUnBQz_X$aWZGXg4T4=K#YfyU&26f!K%i7^7i~ zogIufqK$q;UCMgx5r?(t73<*=X*&uhAGb-Epv6V=B}v!v@nTumFr-++>>CBh1OS<m zfTb^@bx7i^eFkqZ(=<{bqpB@dHzJ{HVoM&(6B0<eYV|e$Z2dBg$nQ8E`!&-?<Ui@N zF((pRK|`-cuy%H!X^f`v1u6grq8%f)%_U}9h_kB#p>Az#f%bQlTq%>+k=@ZqdJF&N zUKGDgzP;JJ<vZw4r{LNK)cu7|-8%&CiLd$N4N~6RNVj~En5c9OGZ2dUOk-w$VfqnZ z-Qws*`(?TIIDNJrFgVk9H6>ZITO(jPLL0MNSbbgXV}3QeFBFI9Gu*M~>yQg0nJp=u zi;suS3xI#ly!4#Af1$A%o7?nTe^BJ-xb<O&DM`E{e~c2aX@tO(D2y(Z?f#pUM^%B` z_u}AH8=(_=AAUP(oE3R+*RkBeN1HO0W$(S?{!Xx-TBfP?NN;1@SF2W##A6s;zcaq9 zpqjd~XS9d58%DG45hwwUrBItcn|q>}uC^rcI`o9OPal{7-n%06>oXXwha&uP<Mn$f z_gRpoNbGVOXT^kPxtNE<q}s=py;w`M#w6xO-%V51;B%*`at9BHA>K=AZTlf&$!V@* zF-{TX3mTumsO}L6N;#>EYVwI_zUo(ZF~-|xASC|tY&@m>`F6*s=&&i5?B3<r18|K~ z5V!jp(d}&)STyTOF|+uWcw7|C%1>~gpZNBu3FblDa|d?#czsJW`_V6CgNJ{i$Eulj z@r(&?K>CdN;cTjndAZf{&(2dHczrF}#s5hW;enLXodB75gEb-xOLgJQ&);@BRtr7^ z!N9g|aa7R<EZT%Rc(e}vEox4{)Ii|4v%Q)+yka(LjGBpz&YNM#uuW(zns`_9g8fmh zIpPUCaWR2Tt$n1nz>EIjogBpyh5eiR*lDANWBt82r0?w$f3v#%R+2ecJ$H0g_+813 zQ8G7+m3c5q@|i{R$w4e!mmM9jW+UQCoq!+(_~TW73E<kZ)rc`ckI+gNbC(6q_CJxL zoxL3($8p#h;XFp?=jI~yD7}_@JTu6A5)`+WY)tbD`bKSj5iBw#pluOYR!pxof2N4e zbv}&e%^H44PprfKkU@H1fz6ixY*Sy`Ww8EuDs?ym{DUg+gMAr7vE8w8<sDg(*5c|} z4(^NAOHaOzO=r+UngT`JsyL(Qh3|Fa8el{ItdBwmli!G^K7tOZYC*snCcLdcN<P`= z+gPXs<=JGC-!o{F8@X1i%8eggo1uA#%@OfB4aho|Sg8thwrtQ-{wFf$0cIuSz}v^! zW>+a1<85qUo9FNF{6a*I!ukbQsQTl0qvXmpW8udtIcvAD2xd`z$)pOTvljZFq_$n^ zw5P>Y8QSD6D_TPaELUB<5<Kz-M-$K!Hb6o)T?KJ!I6OR3c+x?Jh=JHvS>HLm{nrw$ ziXJT0?$Z9$i%R?ZUimU^2BS((Y-@?p7_Zr*ZpnpgXHH_vCa|$o*LAO8?^WQ@g<VHW z;6&P<KVF!Jdqhss2QI`b4gY<||FZ5H`}-lJXQKeu{mMVHj5SK7#ZNbK;8(aac`2sS zt)Q@^#NFYvzoVaZ;zn*S)KOu#{m*2imTO0=YpKFz%6LR89mYH~Na0?Te7&08{*W{W zHp4WsB2;V8C~e~1e{*j)C7kc+N(ZdcsHW^*d`16Vdlm6s`f{CaB2`J-@!Q`ib7i@Q zBVOxSbFR**rMe`<Bmp~HBSdyb?7e6*x_e%GM;!e)Dn651x8qWci1Qr+%X5vFGU2CU z&xPGjxOD+yQjeL1LwbJWO8qQBNspN^^Y`4xQ#{{i^i8ETMrh;`-KxrUbMARp2l5*m zOB;ldNx9+cQKcS5qnRQFnlVB{cl6!Qg_oMBchfUkovb_4J$9$-JpcSui)9WeArPRt zyVgxl$~e<z@>1f)re43@Kj^pk1nT{T{`9uH=eWuJ1f(GuaBuI$OSOzacU`l(2a(#6 zK2d@*jXq~547_@l&Q?9|LtZ#rr%`bP?vH-m@xGQhX$qGwB|w<?ob0{#{A`%~PJC<7 z#`AbF@VnnkRhed*7Jq)^{&AW#^|%>1^-IH4j+ZB9wbt#CS3?^UBL9@5AqnVI8RSd` zOz|4j#vV7^*hH!LNq>FiG4!F#f-a`n$w=vagMXr#mWJdP)T=cUEs?SULNgSKgO&`b zL+OkPl}x;inUijZu<^Dy-P>^I)y*(c6r6Qg#^`{}jTHA5xQ0Z}%N-5%bRULoTj`e) zMYCrvY?dqDSSIG>C@}4mrHR)0N+p^;Y?mfw6UdkP;(GUes3X!_w3z{@h(2LutC=xz zG*DjWOi?;hs47++NV%-iAQl%$Rmvpcgvm0hz881}H(naJcQ&@^_A1S%>a%n+{_Tc= z!B;bCfgWb{(fqrNfxBUd57l`Bc|i2Yo0jW-!O&L?RQkC|E|!AtXxz*9q>y`Yu#EAC z9Rd|@2c>YWd7sg8rN!ub-|F+6dGp_Zp^T+r+YIWvYCDFK)XCsF!f5`KaWiVOx*3Pt zy4%<h=^<~-g0pmNWlVH~ZW%_!%wTS~EIjG8vCPK%w=OR>d&s+aDMt8<I^aCbHT)m{ zdzi#`lk6So$S+;D_eO~*-C2AB7~3?c2=6!bn^5JVYgA(K)~TMHb|+JjSq^=hD<A`w zJnJx?_eTkUkF8JYZ1{+O&D<~apY*&hnQdlpkZ$rxT8eG|@pPdmRHf-0ClRs|_C@2A z?vvN+km%2IzfJT{zY8?;7ukFjbz0YHGFv)hb<&+j71na{KmM95v9_@DZm{LM@2c!R z_wfgcl?o=l3%w!*skbRdsnAi?=4k&!120`zv@5i3QSuP-k6U4E-7ibl@>BKdet8yI ztfBSmyUPF6sf6_Z`PKHFe*J;PzHJtXLQ`}vTs%LR48sdZNY=mqNJb{P#!MRhbm4J( zmEz4ZvvEK(u;#4{P(K%$0imP`?Wxx988e<Vkw30)dnh!FO<!f;wv7V-e(fH{s@s{< z9wmtXr(;^yfmS#uIkgNH9PhjrXJ01Iac*dVi0Pgbg^Xc?ko~Mo;%FN1K2eIDW_tc4 zzb&{uxr={DzOLLW0hKWB{hvi2m?fDiunH?(e1CxO#K2x<*}?W8hTbM{P=Irp#oSG+ zC*g<`NCLXSI$O;Z!@@LJvIXz&5KV9e7t7wlAVZgNi6SB1enzEFlSDQrJNcMjhhljM z!8tU@@1#kYm(GW9;Cu7HAT`+vBjIIUDJWp#Zco@PeG&uyC_eV=l`zj5iAl*#mm5j8 zK*>72YG%<;F&v;g$k#v-0k!3x9@$O>;ZJ)LQFC$e(09)M60xwT0|)4r=bREEn$>{| zade);5ZN93)VNNu7Zj8vTye)7V@<k7(8aH=9&a_{+dL6H!^Ef^wM^~zx*Et*Dmkqx zg@6r^`y~P?6*yN1rIhgL+)I+ybncBuatmKof!;J^6n!o@&WRcZjrlhtI61ed8J+a` zvT$QmEP8COg!wd%d+z`j1XQ4OH~r?k7lC`5C08VTQUTu)N!1=N_0U^NMqkv?cp8oz z0*w#hA=J?4oT1=L7;bHL22G!4Q8$dCj}tWO9&==!DJN1Ko*G?BzL~Xt%d8`gV3=sp zBm<h=Ksd4oH1C?@74vPX?@~I<q62w3@|-@;Ojnu!+~)URxnV>+c+KC>Vc0jThA6Aj zt42(+O+zB86r-<3CzQ5I8~5zyAAVsx6X6!P6>+g0HJ2ttJJ3{+z&(Yu@(UIS?aIGG zRr`B*bb)Bre}C(m|D&>qP^W1}Okv$6)u!{gr~Jrc$bR{kh#EUN6hR2GZJ%h3C^<tt zw`cR){k4>akvZ=s3=$+>w}T^+i7J16n0B29qIXtXIp}yW;(y3Ss@y9$?laUPM_m^j zk^P#vc~(wCi;v$U`tz=2i0+;AQ2sG&Q+-At@=U$}pOji7dE+L837+<>$I?%+Klk+m z$@?MbQ|37Yv*$zA*YCO}wu!C+-DI>&j@klr=^S?&6(&k3mv#Ph-gik1;^QQW)4ybI zyGRXT*|5u1ZDXct`GprUnTxa}tlOG&$gMlI;tJ90-vxlcGfE0;3bN<VnU5UC|7JvJ za8sKlk(f9mS+`iE#|4g|k`rRE@TSE{-Kz$h-JbQvBBBTVZT&nKDh!d+-1qUHC_HjP z+m~3-6l4NKi=!Fa=oOg|ZWhd&_x1=@`77?%2QOq3%{+O|C;@h#z-Pu;5bDrwB6gq$ z1eBCA*11_$*v%%eF=S?{ZV;2aR%3z1dc<X3cpXXHJgKn|R`tkqoOd(EDhYF7LnFCZ zsU=%|NJ?Qr1)I!K2m6c-{D!38TBlQwqDk?$3GdecG4Cy^0rna>iYBbqZT!ipVuzQr z<bVMSEvhrcNyb&?pR8Sm?S#gjgqk`jUlk8B4zBBJrYp!^6=RjMg_dAHh+wSIahx=i zSQ+*nq9BrZ0S}JTk{`%Djl1us((02c?%UG!pftb$9s*d}K*5a{$?~fYf7QL;7C4Sq zFz1KcMcB%@oVmF1C@%e(yWUBg3}en+Be>t>K$V+Iy!u-yK|^>$Fp6HC?W)*a$&P8+ z1sBIKh5}Oq-4MCS9ym>@Uux@4viH5=?HjSzC6KJIoXm|IM)GXMYBQT9Koz~(H*3U; zzV$=r+_$7pQRv0btH(;doiMj27|zU?Kj!>u3^R71nwpXeUomZJmzREu?CNyKWPbv0 z`RX?k-@ld`;WP&e+=4PC&*taHN$H;@wT*I>W=!mVCjhXz3L6_rKnx?hI7ydY>3`Mu zeqO0YvVT9G(bir(6TQ$A*+PoW#C}m_xrGN>2x2Md3D}v{Sv%vm!;F&qlM_QhfY``o z)VK1g>6X2vKN?uJs@~7c{a~sY*{!}A4pr7I)nh9rHsZd?sl3TTWa3P(KwEF(0Xv*( zAhC09mIV#VRBh3r3iq4M=CP*^x*4#bc}ODHA19W~b3qV;9vD{Sux(;P4)>sG5=xUz zJ`w=p1uBg!OeCQIm40l4UA!ZjFsY5uQD8Rv__?aK4Fj<%LqRl*9nC2`k>U5XRdxy_ zWq;q6<BljXmoX7ykH{~2or7@jc&dkv9_<G*dp4q`bV|sKCtzSFpstD$T!1Cz_9hZ9 z_0A5X^a~&|Xu+}UDuN9Yv*NK(4H+@gI>l1t@N`<Cs(7-k&^qU%;{2x=ioodN09rKt zew?%uk!UTF;1Sp}ArpxnoWmnU5wWV>sthZu#{)gQYj&5XFyY`a_BjU*!p#8VShkry zx)Ltiy=cCCtmH7GV(rb>C(Zq`!$g6zy^&jMzwmUX&fu`G3ogmMvo;2zRXv|=X_JaA z+{6%W66&%Z#ftCCRNY?EiqS1vIq8ZOA)R8A8PIb2x%SEUg7seI;IC{*E92oW?wN$5 z^r|eDVCGBwWiprP@P>L3mliKtdzeVBm_Twku0F=fNLRh*Qsp;+%KNQ8?MJ;)q?z<Q z@#e`|rZWBO{nUvfg96-6EL+H{J=nZ`k;!C6VkjZUYN>{Y?&W?Q8)812WX9N`|H~dy zc!iA{063WAelwuq?XejjEWYy$y5lQ!8C}d|HK?|c8z3Ty_i2{-Q@Vov!v%v<xtpYk ztKL;{irP4(&KsgEryZL|wA(i0;(!XvTC6G!GJi!kKV{0hnOdjZVkZHK%#U%5Cpk@c zk+Kalz92{9cK#%wWk{UKd2nYbJ3%S2;7ih3232HauiFAG(21NPamh_iXNq^$!3{cI zlQ`!0h+hwD>Nu(ok2#*1yOHglP4%Ts5%6rq`9JFC!+&}Ur3R{ERrPxX7P!F-#CL)2 z7qWD6lFxm}oHW$gC|L#;Br5qDv}<hDT~u=88+QL}6WuEyxTE+bvgp;%T3qn@E~J6? zFgXQoix+=eC{Y`m$i8F64Ra*y7FTdF*X)1w&qYK(0~5bSLh7t^D>Dh+Lta+~GNPdX zV5xiKI=a^jN@of-hcNgV36~Ct=f(^cYRYGA+wY8+DuA7=O7W~{>8&_sOC+tiQ!X#@ zA3HjLJBE?C4+5w>W(5H>?$6xeVVXPHy2K%%xU41TQT0lV(=Sgr_1q?2#a0zm0MQxc z`|4h_zX_tD`my{A+<)vI@lv|gLk-1MG||t|Ze|+H^f8W%8mBtyHH|c-_~&>JU8TJ= zh2*}}bEjVyWM)Mc34)epOML{;R0(0t?Cc613XKOdF_dF&xP$$<Datre)B0JH-041f zAey-fSzDS{cFr43sKUXlPV8s$Y;i-XHgO%dq=Tptr5AcTTA9MjTT(>Gzr9rZ=;pDU z6B+k~YD=~{6-h4wnBu!ON%PhooZ&-dlDB~>u~Zsj^q!*qmEIh};fFiz(O7<Fvh=EL zH!@-^oLW=)tmaOQ+7{u4PA`~PjW3e0O)h5*ttPXQC91(~Us3xjG*+a_vnYR?utdwv z*TO54$cSv;I)NxpGhr#lD{eN4k|GwGdw}Ie!#L-s-N^FSXkE00HB<(A8GEuCKWXb6 zq>Lo<ts$jtYB?resU*AS;NpB|<Nh#+SP(>W6UQ(E1VA96kTyc6h{||9EAzdn2EudB zN2J4?-SE*wVt>3ycAY;}yrP-u6uooH1ceZN4+BMv=z{mi!hY0OlvwnQ^S8MwbwHGj zST*w}*}Cq|dbGFKBzSPbIaek_LBB_8K`rsUH_^VO$Yc*p_;BRENzT)4G--bx_uwbw z<NoY<bJ;E9$%DO(-s)V@ny|XWm_v&u@BC2=D+-BcJdEkN0{}52EyytT0vs*>F|X&k z;cK&mVJBjOyH(l^mA|%aQiYsSWhdhgPiF2-5}YoGs$Wbd#XRA|BS(Nc!46}grFRXV z^W63vosxeF0yRaCcnn9A|4k2e#@qGh#v#hHZhTk@GvRP{qS5R$#}mUN9}gL?&xQQ< z)EXK*_VK;vJ+LEWPa=+dw}Il1tH@C`b?}}LB_F`8Pp;~dJAI==-2;IA3i$S7M7p($ z>|JG0eTT%Buop%MO1Q<s4*QH4YA*}cA!eaq{@6wA&hxn61^W={G`9moUZ>bvyCTG4 z^;5K(bZD<T2y}pMjH69-3OwfBvm^iAn36eMa^dA$y6;A%skryKN#zIQJAu}UB<_af z`gl)838?Z<1P5QqBk_G0+5s2nPsMnGpQ)d^H^xXql<r%#Jdp&l0xq49kChq;p8S*< zu@aKVK1Due+3)2<`yZd*s;xD6Pir}`uQikVgLc%^n|)ez4UnkbunUxZVs7Pvnge&% zwH(L-jT9k%C)oXqIOM*?f|hiy-{R{Pq;H1cu<E^z8xhL%SP?*l2yZl^K3zENqZFtn z+9_THYEpp=c%lQKk(&h+O-Lqc5k~Y=%O^%x5cv#hWbzi{UG>)Qbj6WcCV71BEO@z2 zG~u?kY?>p>Y%KSI3Xh|vbgNF3Q(sW^{gEE%bmp>#a-J&i3(hjd8X;j@CoBmxnKTFH z)RXAWcgsBU(JOmpcpEI;g+vxNR-pR~_|V`Kau`kpd6D<&Lc;m1nnk(FAw^RB)x76I zFZW)zZcb2m5PkvgH_q+fV&3akp{9uHqv=1>*d-G%8=zG0X6qLRLXmTBwEh1D>J<~o zm5&S#Q(A8>Bo+rjYXjRA&O2*|OZuG^(rzjvIn}2C1M%XwQ@Zzsl4ENZRG697yrNQ= z?Op%voj4#c?Zd%VYM_TTK_dK<eQ(dUy}+IIg1K^n)ssfwCwqccB?^mARWG6$Ra{w) zVi@iHRt>l3y0q)?Ck>rg*!53-$B<A7Fs^?vobfPP6fKD2Kw8G-vbL7#vIF{yf~?CD z4)@>eJXF>a;QOe3r76Wb1M~_sTnn0SFvrOv1M(j>sTQayu&ayq_kLY%f~Xf!<VH7N z0#xcxuxH=(@DA|j`k=oVB6hvO)|%IMM1wwzIh&Lp2A`|$F*3CgXw?a*Dg2DA9AgUO z2E0@egx!KLskjdoDtT%$fCl!-&A4cm<_5a$S=>yz^yQE4vl8<&DQ<N!F+MHZtf^A4 z87ulJhdQP9irr()v=6~z2mWRVa)C5`kp?8C-GHZ9dI*!h7;~#Wn}bMX?@O9kXcZ1T zrLE>flw{4_x$^d@)iQqdBx7Szu2D<6%oX>mn|&+RWOFOu?i@c8QrNM{ZFy<1%QIWj zL#|(_s<8GLBzy>)NcIm3Ex#N7p74d1T=c8Ep=<$i@2YPMFI|(z<G6@%fN7UtF6n6z zh<`iPGsWVYqn?xg7{7T!K;fhIUcLi><3jyi8doUSXP0GBfyh|V)0pk}@=N9jtP7B; zS2*ymC&#g<1cQ;;T1yPQv6lWAA!Mm)v}IVPT>BBFTWMV$L9dQ0N}F<EX0Zb}`c+x_ zRm<g;rUCuDkMc7OXVx7^Az}iK1w)A9`MbQ~f{y7f3rRV`UUqcyQ${qy48Wqoo+EgD z`4Cp{<LF&$EahH|Xj`ud!rwblgfl`xjku3h*gNUN+c(5LsuU5Q##0n)8xkc3tLa3I zwIjz|2R?jC=4bce2v!i2`-T8Y-V&C<s$2?nUBkp;w6f(lw+UnOu4<k8obiG3vhB+0 zgkzr+2s#wqPFwhFc>nvZpdS5UEOloE8~cp0e}qVd2i<x1HMV_Z5!*mg^YMel4w7j! zL+8Gm&{$aJj}OSbn^Qg;f9!X{Y=46=eL}76mT(!(d=Y5oDtekuqgfhc+z`*$-!r&g zo=AyV*iqb}&PGN@<RepjQVfWrAg1@W(q2AQLdQw0Omx=j{7|;3m_r`8VxAIlJ|?J? zK=-|{Qq=nH!RPy5WbADQMZfcy->!jaex}0$eONg60Fj1r9U8YRWZos@^OH}#btgRk zzy2Se{|P)|Q(2(qN4;#aDN)ZeX+xQ*8JDnYW-d%V5Rvo?O!weVcN{{MY39id2<9q< z0suu5_PMiO&RzS#OxX+<gBQ|%J2UMWd=tisF<@G`Ot+~b_7vU+?=xQ;#_Wt$P=rv- z2;j*Z^9il0Z)mjNl(9drcGfh|Y_R!Qd6pPF^ICuC{cO#ArjKn$NLHc)L#?R@z#JRq z0b1jG)Q6?yGw;mxGph1GOQ?~oUKgnG=m}4@6f(3*flFeQw%x7UB88Y<nSXf5Cy<@w z5p~s{AMCx{>c<vOR=ieiTH57vt-WY}obq1o2cdI8yC1&Puz9-Tb3ymYd?OPqe)`ud z)5RVvopM*BZp_!ztoJKoo)M-tOwW;zg4_A)e}2m`Avuv2b-$ch6ycc}7MfJa*6i8h zu?6h5X-r|ss9sWmNSzAb-q)DSPsn>bO}LF0ce&P;t`liYbTevtX}OwWdKN8{jRzS# znW~CybZ;mJXf0+obW3;D)9=E#ViQQpskBD8sc%jbu!DS_Tou%r3Nh28LXDlDiX!`E zF*N_FzddN(N&TU(b}w&pw9c{Did68&+vG0|zidiPC*+UE-c<znczF(uvPxjaOafo` z;cRR!4LI)6rPP;K0ihWxiUMEVjRCQBqCs8RLz>Z{JyO0G`YM~hXmDsDQ5xG*{=VvO zc$@q6?VK1g6C=MY(g#M@9`00fhhq;G?0arU9(E5KDYU65{oNiYCRYt)rMA8Q_2E;? z6l5augkx?w=alf)GSYQDw-UgV(ZuAT{b96keZgdJk=={K=c94;VYP^HZXl^);P|#0 zEtud&biuBVIQGEOJUCM9!Df+UX_k74e6tls_%Am-#f{>^%A?i*Ks8NAG>^|`{2gC` zw+8`88KX;}A%_gMtH{z&wH~J3TYLM8RmVWdqNg}PG@m!7&0ByiYK~`C@LYefG4r9v z6b7CUM0p>Te3_-mmTjiX2sEbb%zyzBSj$24V*F@vb#3oO=0k3s0fah2rw^geD_>!+ z)z_Zo?O?QDHrhkU_mC%(JB7l^#M@6pCz#59@MJVkb&J919!Eu%zF|q_i%7RanPXkg z^*EkbqbG$<1Qkn~IoYbl(`=ve+=&BR;*IZ7+m?^C$o;n2J<WU|whcsECO+wM3P`@8 z)yiK~T*T%*zHaYe{Dhg($eB)V_BGl4r2sZPnYwFP5q^+Rl>fN?4<D5JI_7b1=z9Td z)J(J?n~|~qx-vn&rysv8R&mW<@#!@Y<75@v{i~@I9~n}fN+!DkO~UB=xdc47ygaKY zJ<>=O#CpD_b)C7M`pnmet#bd)!XO`#Kc<w2*N&9LvXq12r<mRfQcLm5zCEgZoh8!| zEHO9*4JzP`S7>?;0iub4g-M9;aWo8AW90Mk)7;%3lw2E1R=3%N9I9x@_fDl`TjG<9 zs^ciKqp4K-V|dKnH(7WBOME-aSpHkn5?r8+rmos#`i6r{=W0tSyd}W`xEnPD3W;UX zbx6-DN65^Sq=j_G(G!qFLq8lt^&XAfk}dNL0D#m=z2z8nA1bIjrx=D$6JL?=fUIT9 z<oZ>E+=jRB!p-2G!_yf}Gg?xsQ|flQRV4Q;ckcTU@%?s+%N@8b7lD$FlNPQ)ES*T% zZKy=OQ!~WRi+6<U+zBISsB*Sw(jfIm&;1I!3(sb#JjOOtJRbhe_@z>*2yN1PVwhe8 zNbcEA`WbqLuQ7aR8<3d`>yC@vg^1brs*5jW+6SLNT93A*OQ*;k)cY8z#`!~waa7tD zAOXH00aR5OdC(FO0YP+}<RkIvXI(Q==qh41l4HnibA{@~FsAqh#ba0`n#H?{8<bh| zOK<}?0g?ty3FIZLa=OyPc3@zb?A?RL32xTKP>;Kh{K!2+O(=KJLpp=`Od^9>^>?OS zC2$;i5t$r-@-S8sW@XU>JC{3`84^opfDR}*FwZbU>>rpWDFHwjfD&{XU`+GtbY$K= z(tPy6FX>TcQ(>;;p*v+Z72sx`-8%e3zCY&S;zYLSru>j}ZF&l-D6S>JPvZ$GQ(EgF zS3|dkKGoYQsZG(Gc9l!@(tIY{{S)=}FU>!L8eiBR`s8$cJ^LBb!}RDlHK%i1@>kf@ zi$`bmIUf##enqS^J-(dC={jrv6?OdL@xPxrA8%JhpAj(M*b%^UyFpS%F_Z;%pu4#} z(BPvu4rco}k<#~6Ek{|!YtMaca{K%R34!k%aH-(jeh8z5UhWz+Ff(^RXgZElf8_a- z1vOSlpW_sAG_eM-MkzcMYwpLqMJ8@MtRZ!ho|FUOzRRGH=yZ}%!t5+ylsEdI<s_@I zz**!;-Y47hlbjxA7xA>bF=wgYdAIQll5g_Hy@P+hSZ8*X{hT)u)bcJ%vsNi$VU+n- z^w2G7*haKS4@gQiDUh+OrViWz_AEzA!V>o)Gt2O=R7p!7yHZ7Hi=`kiEEt%#qkh~x z>t61V!uw_>XG011$3)R`ZeDwFbx)YxuZNW5ds2OGu3g#J8O|!ySPmXr=S;4YYAKyh z63OBmS+|C<vhm)N{+V2?S7KmRe=#iYtjuS=G6@;oj?&*~HCC)8R%+oGZndYD3F2&O zSWj^)3#?rR*A2;>5cE2uN};b>PIX>VWd)3JP^IS*0o@{SzTd>@v#@W~(9^q7Dse0Y zU_fH7r)gcaK&mXYwU%7uNojGP<t0Cd>ESxmiJXvis~Ez)ck9a>BbtV6XDdt?rz-m* z*;aaq_)aL(UL-N|_m4xwR}naW-vR|foie5R#-C5{)@-}Q8WIoN?1`cj7SxQJWm4T! zd~&xiqID3(Q%b08LEPcSFqSzuCN)64<ECh(y5;T>9`2Lbw-h|7CEGTBnnzN;RKPCN z)4pCF?x@A%;iV<m)#3^ye_&}E){<`e=@}MayP&#mF4I+#=GxtZh^83&?+$!Ctcn@E z%Rcn_Of}{1p5p+=tH1jP;)nj3w)`xc@~n}5Fkkk3rkK6krHi7p<z-^#l~5w7N*0_p zvEo^447J%{3Ea7%kDIApyvx1kpA=~k-=}Y+ySLY%NJ=5gD8H7>igAjozS8fr1A4`2 zf@mHuF4ogx2+*m@Rtfx=A((T3MxAo}P1aa{G<@w_%3Rw6Ylvy{NM@>Bhf%?thmG9d zgIG>tC}m=pj>hQ^*x9-Xc<%Tp+=!{Ot=vkTRbydwtS2QWC+jR#jshN{0+V-VVhK;x zjTo8)nSeDGw;q<&CzdKc$YE7BepSSVDzgX0&1nyn!^AeTuXk~*kqiNxK8DHd;0rU+ z(yc@OR(9Vl!Wyi`deBWj6GQL@5np+TuUv=br?qu+Ang7}(Rl_n(Y0YX)KJstBm@$A z@4cANdzY@#t8}EJga83)p?9T;peR*DK_t>qkS-u1p(r3CT|j;L`2OvWo!Ob4-JP?~ zx$o=3ErI-~Livw9v7c1DU+h1IZ{gUND3AgTBD&9hq^+$dW&yv3WZBlkS5R!rSfq>q z;+T8@03fX`%|XlzZ-rn1b+gA5dy}N8UDD-p5JLkF`3*NTJ#6HSTV;|uPzVu$1cH8> z&-bBt>nxBOmgi}ELe%f5R8f#))WI5w@)zHM81)g-BLA}I<D`r(Qp|!!#sa#Y1)uqN z8cih68~qt*9{PYfE+BEWWm{8%<+j}R3=jU^{wQM3%+rab+aaI$n@aUffF<16)^qju z{Y0sgEYK8y>FRS8GI)!kMoU&WS&HjD4i3utWw`$fBFSf!1V5%YYcLxaqX6voaU_{* z`%4@z1=G=Nh%P)sDv)^Y4#CweL=d@x{?nYlnPQtrG{bK9rVWu-cA7a~%$n{jV8DTo zVs{$LAGii5pm~ZQu)i4IW2=E(in&M%=B|OuC&Bu=6ApR7qGi9%H%LauZp=SX=akmB z4W+nF$kfhgWD6Nok3(ln2@TXET1Z#Nl$V=i4t^}xy4xUwh=$C-M{A0#*Ay$aE#V#2 zDY0u`BKM_&DOX~d#exofX|<CMQ9DA-@QR?EUAI4c;kTnd8Z(U}D+0NaUBT{&oG{`@ zW(~Zw?dtPKzwOF#NIs#i89Mxhm`vn8#EF9~&6{eMV%^xarxo7p*<maT)+i8H2%RHx z;u(=jT!we0k25V`X;(^(iwsN3rU+jv9K&%^QXp2XkdZlRb68lv&TZWscBOGa|4ipq zEbr1s#1;u*ZX+CN$)O|3I7Klf6D|}$X)e$J`$9(CofdlpJ)8`QZb_cpLFKoR>AZJY zB`E+SSau)zfBxZ^t!iW^neOrf#n&{b;4})bxypX=>rzBe@&xtyn=7axa4D723jlzx z@WD;_B{!!*O>So!&&18zCElaB_FX9hnZ$O9ESzM1!k*CX9-@l^oQC5JHkbOE2p0(h zGwWvk2YEhVkaSFfER$)lM{2yXnD^3G^g5O-K_y@^G_(zQY{Laug>S5Bi%h}VK}KfQ zNLLGxEeh%V966Z?_-!C0FE89H&09u1wM`cMYr%V;f|*s3{YwYtxwKeWC_AScq7Ma= zLJ7RwxEA%!Xn#*Ku!&2R3>_nxM%9>{;5hd&Jd<wP&hEcgs-*2tn4NzvjgX|?=EFHD z*!!w6BpGGa2)av}6AW%VW4D^?IqtvLG)BTK8-}v`OTr<5J}yrZR}=2bF={`|^6G&} z;4@}f!l{7*m4_y{3UGd@d6xVW$hMELdA>~zTi!?<XqJ4!H#Z5IMbIz{>weG^#hu35 ztjOKr>NuQ5vzyqi5i`lmVILU{+KgiNP>Xk*E2+<9<oHhx&!gWfy|+0}-h*mSZl$#j zMM^`W%_T)`gf_6e@uXk7Fyq?%;V1bTgZ)FtGlv~d{!3&wqex^IXfP9e;rvF?$HN`E z>9!jb$nzgcR#jeDKF{AH$)bsZdzs9=X{L9&#iKxiKan-hw&Lwg<c{}7ZjmfLx^f-j zzV&s=UE%{ZpG5{Q-a*V`g04ds9AtSXT{(_PHb(;ab<(^{={^UpT#ia|amOIB20@i+ z{{C^}8}sKa6ie(@eA?17<#omfa$CnZD4N1<lfw5Eit9fB-0p{CGk&rR$Kxxwfj*t| zXTHgw^H<kat`a7UwoBSV@s!ev*pT4<de-x7T0m;r+HAiONqXfE2t)a)2f8<y@6b2O z@K$gL7KL!k^T{0-MsH%J_RK8)DePb2!aTHdU8j(Hxk&GzS%+Mm6BN(d%Z#&OL|O*C z4<`{|iil^0BgHprl>E->n5uJc*V}OYOWEGDxpOc<P0wuJM?#|Aj6YTbcx2pF!vrpi zrQ9ytkexGgBkM9h$$~Rm)?Zo0CMRSUfBsbi|EuX#{z;;J2?k)B<;$^%S>LUimr0dD z5fTSHl&wz9kro7qj^)vvakrC0a?nu`5+-yx4^Wyz4FF#HGiN#PGxN~3B-o<&VXTT< zs4LSDZ=m(cNHwwu%Y<IP)K^faoB&P9A6$J(i{}vL+Mc)8lI#Oi$uJs|FwhSQN5?{; zC*u)5AH-<14c@TAdmzH8AVd=dxSnFklG7mz>kQfee#B<!OSmb8a>DkVQLTdaU*hEb zgvqGmCE??D!Jpq92r0B4_Tti;i??iP|8tR<Y@rtWR*h^RGYw%8e{=LMWAG4aoRG4` zK;Ir)Y!!1srb<qi(7rwIRw67i9O=GxSwv>+%tIb>YBW(HcPOY!t@!%fq#jpG&~pi8 z&lo`WK9x<Kl_iVZasM?>?D{sPkRBi<tBQOo$+e5o4DHN2Aw>+kRf0YGciF7zxP|<i z;NGTYxK|hMTnMVeNr4e0Qz)W-Poc_(d(JUJ@2AjV`#=A4_giShDmLcxPva&X-oLFD z&S;)#(%oV{-o{1c$CjWK3LX(G$k$Zrb*a$bUx*1z(6*9LnI!LgA_v5*GHxs7n+y-& z<7Cf1D4ra!_llTe6()NqSTl2GoaelWgLi~;@1T&qN>b&ruuCx<l7Y2u(Z;?sbc;_- z=4rS_Q!RWF#nwat`0#&kne&XVNB~+s?)USk=$Q}XgHyx%TyYUsTduDA0pUuk^*=8= zExZ^M=$*BBcd!5O<xV6`u(8oMcrY^W7lp2~vU>zKlxHDraUiDamDm3W9kX)1PW+;K zd%?+;cM|h-2HW*)!@^I2YmQ_HJfm_}MtVjIU+wJF7sPQnkkLf=1nGJIf>3R~Q7Z*f zsAGW$M)Z`Q0%G@lnUHM?T+?At9D6m7szzNd``_Db&Fl&kd~9fS{{w~Whp|Ge^MqHy zLzX&8tJR0-?lzyKj~WMp#ok?x=s?NP{^L6uhhV^ELx_}Thv2>$gc>C$rtDwNTp>wu zZ<IuYebV7@5t2*it_LI(Za)#lK{l>L<Qw9Teo6jOlRT>S8T@VIxRzpWGuu~<*ze;U z%X5Cp%s$=Ta|`X5Kn53uL8V=oNF-1Vj#J$`@fRS!G+tKVvz?ziwtOCLyp*&a=ogzG z1uYQzko&8Kf}5ey?8-~gOG1P#mZ-YGrV4mG$%jejQu5MlLKcwrWY{sr%A!ZmG~)Dw zTU3;Gp%)l1hT_>l@f^ExP5dVGMJHSF|5@&X(S~<BCy6(b=>|AnSL@#H!aX2!EN#HR zO>U~;Nm*e<{24B$T<oe;I4)6}fnK-gm!BbbJSgQ)+_?Aq;P1GnRy`9bsyO8KbJfjP zZg+_?|K$0AlKoOak~|`I3<gIzE<b$Eb(2g}*lBS>k~NdU1TAL(0M6L%sax7oV<bdJ zHJ8F@q=zRxg)7%Fx%5U-r&Wj91pL{-IPVk|;j043afQ489J;l})1tO#T`qSS0iSn; zyXMw}uVcdhnRs=Yyt>-2an3^J33gFDv!ayY!scqel=wZ(ZD(7%Xv3Ry{k)1ts47BD z_!Hb$!nRfcVwd4t&XhV#tEe%-yovfVPv#DTS+D9QNJsM>hJWgz%@lW*`(B(ry@e=J z$+|tWt>DMmhNb-%?)}U9_OuA{QX{tC++$WMlBJqd|MbpyaP5#wP^k^{QoFFiCLIPi zec`1oC|AfG-F@vm|0-SpS#s#=&YDbAJ00NDXQ|-*i3Pd*(*aU$+N^&_0X>Mjg1PQ# z<X65?+-C?C6%gG@QVaq0lMH`xdG!>)pY#vaiOxrU?EX=W30>P0`Xt3DV$6%;MLcVv z8>s(+V|S%naCKafk#Bc=^@U+;9a)R4tA;PRabA#kV>4U9<7o!vJIzW6v1Y={Tve{m z;AT?nOxND6t+&ebM}T(^G-D0{oYZ_ozQmyK3a@53q!56Z^FyAVG}+prEQEUOv4|xC zV0?En-6n1F0XBA<VNCQgZJ%!}i;aGw{ILZaPr}BxQh9@%2VKG1178Fj^7%ewDW6!e zSU3B;dj!PapLywB+!JFcdG{}aQquyS^8Hdql=)YF^X0X{rzHxv<kXiZNEK>!{A1C8 z`ZuD4pKGRBZ0p<WtRlBwJ*Q+Ak}Q_CUJK`;5!x&Q=QQK4jhjmXC$eP|<Ql(e{(BLs z4481Q|0^Qn@-nJpY4ivC^VXY>sIPzTwj2MV9<@{^xvOcpZLqO_=r>dJ>$3&^wO4<D zfys@RK{h~}m%mva^sb!`p{@*So9g(BvFf{E-lo3TlgVus-BA~{2rub+`7{s!J%z7` zKb_Pu*YMfR`)Ee#_~`N~FFD&^sPQ^sc2+84V}>P|3#yx=)!mc}Ry*!tzja^Cy@04S zGf87^&t^8jtXY<;<l#`C5JlEK2w^dl&Y&QA7^H0Tmuh_#c*&35Mz9-dvTm+_!747| z7vV!AEEYZw%oMV<obo!|OW`Rx&g$O^Jj@G|L|;^DHFoe%L~8bq!m(dUX3WLbdib*x zHhuXsv_22oScVk}a@^Dk_pbXK`Ku@YzIvpbQDG1z*J(vH`%27Y1c2yA)b)N)#(_P) zk<zbpK6_MY;F6+PsA*npwTg9fI?PkqF>I_b*p8;^OJbg&dV;++P6bdj+2WtL7gS>$ zXmD+`Hb*vCSNYPi>Cn}iAbsAmdHv>2JPioYzSUpskSfTv{+Mfy8lW6yN(H*5=U%|7 zvb-Q`rg@{R79PBrrt0+K@$*ik_C?1l{<>3L)@=E<h45|t7^jA8t@+6{kQ(`~ZI0Gh z$C0@T+#-Nz?dM1}t_;1y>Mg&tMP(7C&cOOW3uMO8WU%n!X~+~JrqM#l_qNW%p~FlM zBCnX@vs#VQ1Ap)==eW*CrCVt%-~@?crQ2Ge4)5GjctU@^P!Zy0jxsR&vCfG6$u{7e zk+zvH<)7Iw^KyWNg2;qiHth&DSWU(cHypZ{T(=K$3kNDK_vt(zP~@67;ajc9f2Gf3 z@Qw~pFvxs)OZlRumT3a8Q4cd@iJ}4n8b^k1+~W*H2utpcc<(s>WTJwqJq)UVZnQ1V zn9BFvn)OgVcl7~lKx0O7wN`AotzJTJ3FKBh63mD#z4k~41R$PS<tT3xe{mnTN*fcE zFREHIv?$z@t26>wshV1E)OpUHX%`QiYT`ch!_WV3RLccXCN#&-)_hcz>re0I2{ukW zNZ~o0DiYnKvHPPl<uh`S>Nk+XZ@;FmvXYqfyk*xQ(vVhl0{tYzwhoaY%OuMLd|g*E z$hSw<U7w)1#;`ZU*Tir3``gRzZUJHBT0@rmz8q8(?W33=XE5gKlN~&QXa88jxf@L@ z`}mTas<fvv%(7`fOzYBNag1AlI3~BwDSSk9p%yyU(u4rB-iR+FaMr>zWI>u3Z&ISJ zt@U&*!uq=zZ;i2KMObPywVv{|YM^-p3>-Y^p>}_1oK%FPjc78sX=Tet^{I*>PPfI2 zCE3$aY^_uWJ#BmrF?6DY(hpV*BaKM3$R?;XKPiQ8mCmdW=>y79k-vgsqg@(~CC3Jd zE}D5R8htoUsTWTTK5f8=X;#&BlZWWM#^LQq(eAXKe&mZr;I3Af87^MOe7CPufQO1h zp|{`jUlXCYGrZDvzm@pV7=a9(5eC#rL=|QlYIu@BTJQGC4l``zD?&lb4YijAus=q_ z3si~s-pOnEQUg>EQPeY!*00@a)t3}30#!(O(Err2+r`Ynu8*LQ)+iyD%(@&eQwpaO zl_&ZUwcwkRSBW!~DTf|`zCt+`IG`4$I(!EdvWnx}eZ7rcewWpU$oBnv$e?meqSN16 zuSAlqwOmPQodfvzlyj&sG8f#fVk>jdN6SQYHXHON4Zb|GV=M^k&KwOA^Yg2TZg4b8 zD&a>U;rfQ67itRI{ZSAuI(G5%d>rMfH`QR1z9)Z9fJ(6X_tDwimFjdO&8gN4U!Vfz zD{J}c1EJ3jlv{{8li{!p?8YR47pao-8#^U-;6SOkgZd%>6EHoylpXa`oVJa-y-sKQ z$N;wK!=6AC>k1U4Q?3ss#Q&Ttv(+9Zr^!C=`LG%GUY1VgD8M9rbUmqM-v!dDDt$Yt zpF6sQ)@ORbF0KL(4{p&{rL8f)S#w1$G1T|a8(GQPTIU+`T?lh%ELf?p(VUVfv952^ z$h2;H)ciwIVGK27k-!m8P6TTB_Zt)@8uN7>q$)GX=9n<6=Ij{`Dhs_{pLX#?Gy)Ri z+M-t=(z1e<waI)tDA2_+RO0#}QT5xww7kT+Lzx=Ua_=RRMg8|UHhPx-j;q%<-X&|9 zJ0@v9VR)ri>P4WQxsfKFpLzEB5#Jy8Z!Q~8O?iqY_<laIzSIU-Dgy=>i;uq`l>S>~ zyu&Bf|0807)S>$*y)P#yx?#8;S~1A=Z|f#uMlROFCwD&GtAxBD%r$N(qmkgR9<DpX z^7M$=;04}&A-qgi(Mp}QQWQ~OMSB%RYGAf&SN$kUxWQL6H~069tGQj##6uVqZuyS+ zUeQB?8s_qih}#^#0QtFylAMr@eprC3*j2UoZPQlHOc;xU)_e;S;A|E{r%FiBbq`8h zVw+vT49DmGW)D~(MO24#J8c}$nRz&uy2v%Xz0yxV>>89lcF1(3Z~G|g*ZnMY(V5O? zgjql29sG7ybmK~Orq6;r;``2sYnp^+<_c{`>g@tAlS@v~xl#5gky5+nlh7>fKw&%2 zgUn;K6Ogo#^@H_Sj;O4Q;YSht$X%iy*0j*8cB=5hSYwXX2JxB%{6gI8ZmZ_5Jo-WO zw)!={y)<gp0`DVf-OnohO1lTYB%8-x6`X}v6$jY*(mdig9x)hpfiIWUZGtO^!S<2g zr8PJ`rkVy`YVW$4dP=2uohAmqf1Ukng7uVnIYhPb<iC78Mg9%^FE#L2cin{9*RyzX zsx%;1`XT<lR<ZI0?Xwx-WiLA<wDHEHvDVX2{Z9D0F9F5$sIAJ&f@>ng-A?uMz`T3& zqy3PPR->I<=w+nhD{X;}LkdZflJ<!kSep-QmvR}ikA>LdXy5aJ_3Xu4@!l8vG_$KQ zJ2FZvU5q}HHjXdEP7`@;AGy%EMf>*A-oAnWV!$Ud-rW&`tw29VT@!|Ca5NFS_B}}M zitdFr-6@6!QGnExL7K%H-zKq<`KBcX5MX}%sGXG6u^o<xWsp@O905-fRq<@@PiNHj zL%goD7_?IWQi)(^4!yEX<P?$NB@`4i#jl}YIiKniy^a^f!ObE;qAcu(1<oaMrq^=8 z1#2Mal!;S`rU;w+_$KoJgmsW3nC*bYriB?x!7j)e+|glS)528GrmmT!#mad#2E+!` z+W7RLB;D*P^qFm3!EUtTjZmSfzDwE>S5OfK_<5CYx?Y#sKsi{(K0*a=QVq5qk#es$ zkyzurb)^nn<qs6Rc2ETh-Soe2ZxlRdzMqKUpio_Q1&Kzmzy0q1%L}+LDXHZHc}nu= zre!(w1c%YZc1GOcd|~;T<kw0P9?17dOfyTRwqj7UauJrb|HRbnYVr3#u(?)koC^Be zmcWIwIF~W}5)!;wiy5b(w@IY+B{ECV5RoL<MT?d=S%E`ah&?x&&(6QNgV}^ChUXQ` zq6S6he)FuDm9Y-YSOa#MNjmd}3<y$BQUVn8SZ-oLCy7kA0EsmN!5F`wg&N5VSLEGd zw;dw*jt5xQ-B$IC<rH_B=4J(|Y`2RlFbRg*SB2Vm=d#~f_y3ARd@cdkgvLfE>#y$@ zRnrD&PA8={ptH~f+LP=<6nGj%*yl5{naaVP>FchsT|*i0dFcNuhJAhnR;mTxqGoTa z1~<2Wy6}3293U#k)E1qr=#7XmOHjmla)<}}bv^pH7UqK%#@j^Z(|vJ|P@OBD-cMR~ z?N=~5PCZS(Xv7xthj-B8ItE_=px@8070-8G<*n*>eM6oNYU^^&2NH&P(N5Xgqe8yQ z;Ful21tT{p-FS`MIqq`ccp`v&)TLY$p)qdY$4bm4M>lMyOlzvaC2i2FD)Gsr+rldQ zVSCnQm0)DyWtn50V}Nz>d85m4npi-x^H+?s_aHQ<)?F+O^n4IL?&c`^0(#uabIzB; zqNc)q0J=608arb<ob_C3(Rh>`VOH;4<7dYKGZXiAH%`8B-p6Qzv7M0tzvrVpm#K&e zje3H)?w+f4om^h1fcw$UGH_m9X~66o0y4lUo923h(jK|uyifOCu;*;5g|<F@ELbSI z8v@jwtLqkkxVhuG6*%Lp;-V9oRqKn3&e({YX4^^3s<qbThy1BDRU2|jN&eC^lMeUk z4G#7TaaH!QjgXr-pC5$|bYu@%a+N3=4v+z*u7dX6*em9QElc@(4v2L$PH-H2(}1y} z@$w-jmb<J<;G&4z`}oQ=Prni(+OK=Ntjf4suNpWN&_S*ibkf4M=6#j{ZD2rO0RR{! zHuklWHj4V0VH8~r*hZ$D<rVZFKlNe@oArGII~3TYg^5+JjP^j_y=(oa#rl9F>yLsa zwIk4n4Zs2n*HMeu;XcjCs*zZVp&#_Ij@;vil*zajsoK-zs13G-su~?X!7^E?i-s)y zGk#XPhPTB~jpRVgG~;=jypJ1a`>JXXskNI5kX8+{jj1}DNA3(t#g?MG^o_2wz@O;o zGd9XYtHE-y_gpyOzUZ{_!SqLVK>|vk`kD-FM&wO}Qsr8?*HqzN-}NkX+wV7C3e(97 zllz2zI%4NX4dXC%K2t6Y8#l_!VDII?-}$J&LnIrv6y&l0C%|1b>&6?shtVnkSL}or z{Xx2>h!r&PQ?N-G@nxsP5d%G9t^DzYXjT{XVwI76jA9r7FlrZ(R=|q%c-(JmW_HBy z@#tFTfDtF0^F%ut%C0^+M)zUij(2rfFwQ=gA)riN>e^xaabnv|(!&a>Mke)wF*0_i zg*Q{ISoQ~FungmRUg4~^S+mHKnB+U-EfJ)JM!8hDQJuv%*T6Y`vFq-j4v1K26yyoZ zy-&5Qo(83_+Mjnt^|nt%!blyV{XT<t_$26Jrdw%yh;Nq!!4}%EG>*$=ZW8PiKp$4s z$q|a?MuYe7qt08HZdJvc#<q6Kp{Hb<fU>wN45b9L613!Uv#9g7Gv<w7ulKb5L==#6 zCiLftS#AjZD&|>rQmeQ-v^=g=#JT8=y3+7>dmNuRj4HY6)J-%4y3<D=E@SUha&w+Y z)hh$cm9cNYXFqP$YbS$JG2pH#lO8M2LU;YfP?@H1kQ=32D?0V3Yh#;@SVz7yiZW=@ z7JR#|_t)o_00^`0p&CCYuWu3f<DGh?18Z&WN80tBYkh`EeJppIz=Ig{hj;dZHDHr% zX4fCQ=%flaA*_K9_>Tavs0z%Va*t=K?O8N+p?HgEC|fntC4iP5eTt_Y<O8obX>}b- z?hCd#l_;+ObbdJ|2erO>`uQch8x#EZ{oGlh)KL0NzFUsn?<)3zxRZC~>l`arH0cg) z?ir3qSLSd!u`Y#JZOU7jn|WR};EN3I2IG!p7LcuuC&vY7&GPLZKYclWO$8@G>41-O zI3Y}Z@0j~l$Hw_iUS+yoPPJN^nuEe~YJgn}^F9NbniAknWG?TB+N1B9QDa|o1<wmk zcEz#Xq%CwM8yzOn&aQet_*?&3P0T`^{dXKSL;zbA#v(+)#shn0;Z7gAYE8qWTy6sj zaO)2Lqrx4fBI4J7jgwt90$7lWcVYx%9b(`8fEMRoHbm=(ICaM@B;t%KU43)GQLBux zFUCwc>5R4KzE(;9tw8U88-7%8aqb#;jNw|W0AFhrn5PBYbody3Jaoaw_{mk|X)I)N ziRqK2)ZNU|=1H|TV+j=}3`-E}ZH`Y#Sf^NfNt**}P<$nw7?^1TSg;ywKBKTc$ddSv z%>cvv{V$KbEX^!&;^r9U3OFpLk`K?l9Ys6yQZ1%h<Jq0Fbju|cI)ARkeVVNhmfg*U zvd~c~9W9eHY0xQDw>|z=>)88E4vjhyLK(syDs?mEUVN*AY@W5BgcmSZ3RzV3HJ9Jf zooT@iG!M`T%u*9=iVE#edpnpUijBPS-cmjNvWG5($7`$iSyWYQjKP=hAikp-u~we% zeRsF)?<hVoiBIr48xN61!RQE}248l+rQofqVlyw$MF{o7O1%9~uji>EWwipIUo&m@ zjCsrA!m1b!AlM^d%xT0mv4j;_X7Asmk!LA3r}@oRR;VYG-XfLPv<`|NSKr)A(!Dpy z7zo`+CbKQeWZIf0D?~y*Ny>T*aWII#p-6=swtV4G67<Mt<w*9ondbkMH@^x12R^_1 zn#8dR5pa+aD<ZRPTB@XsG4EhnC*SnFjAfsk1Sw~5`*vu`t94wgGUX&#h%ZgxeHUg? zX|SoP)*~WFwp!Ns>8*&#d4l1QmE32UOPby!ha)U_i!XgU{#)>2t|j-hS%$$#9to0Z za55=NH06GAv!c?TiM6SMRD)4z#pyC^ep8P@8G_!c+H8f;ewusarzKWo33KYVuGis8 zzYCR;%YM;0CIU@Srek+V<4&*v?MDhP9%8qB_)Hw|y&-O2^}b*5wJj#tovbnbi1{>2 zy|qvedcl|sfY|S@EqR0v8rCO@v*g@Q5RIIEaT8r>*<mqH3x1|&{t?3%log|+Zke7X z%MLS`(doUFJdA)=#jm|oby84re0lpm0-Ur__;^Nt4M^Ks_n0J3V^yA5sa1dh{>)$b zdLeKH0X|*T8mSHW5OlvkM$!#?d9}U3^zU@e{BsP8hCROMlaD@lmXG#Xbl$$7_;+-> zA$6bb8g>(kEA)f}r*Q60dtdhv6tnK9L?Qc*M@uRkgnI|xHe@Jr2yRak5eL9+OZ9u% zk=Lx<!n^E;GX+J8(aR`jE~z~>2H_4okI7?Uaw5;V>rQ#_)hi?V0&iw$VDXU{Om@}a z?uEE4d}8Hynm+{r?=F_r=q4^FI=eNSCrLEuqBeGdYRu>wpJfANPEF)LC&|ByCDsY? zpc`0E9%$e?OO*bT`n>@GX;*=GA2^IFE?wX;@eCs^x--8}o)?phiTmU0Eq%sTg}khV z9y4vJtzQiOCR0;Dwg8uaG~1w6Y%)FDkj(-FpplTtx%tQ2VnvU@AiJ}kZ1D9}1}B9} zX0bFxIAL3R?ES)icJEb&l)1x4`c`ko!mfk3kJW=-zo@>@?&x-}_hslK=Hyb#jVU}j zAeHg=UZqel`SoDNZ?lJTk*6zGJiZFmi)A+BuV(7NE8~v=D-^!U;Q}TAMV_53F^eD9 zpGNZb)?Qb3(RxU=j($O~y!9lKTxG5mE6ejH&}65&*1)39EB5;;eYHV0(l*AoVev;3 zr}QntanE*nSkujb$A{l?-@g=a?uigP=-iEejx4)z@on(gEA_9XUgzJ&^Ixf~55|<F zY_I?^D(^DZ4@X-)FD+c0;^e%F=7kN|dfpeXtz<q9o<Q7E4cb(Xf<%4|KRlqxi63hP zRhMm1xt1vd_>7V5zHN`M0W9+@Q1}ux##VZ>`?|bTo9DsO567l_Fc8O!9C*k|-?y3} zPy}5$&5v!y>I)V6x(eWCI<NxcJtd5!D}D`mQlEW$tG?WSN1r#aW6I}w&_<|mVbtqJ zxjM$iSYVm&PBnv4_>z&Aaap$MSaZ;--#4~|Ui#syKBk+=gP?atL?gk<-Be_xXRfK7 zpzzbi2eAWF1lYA>6mVz=#9&?#yJZ;kiu|`-xH~X8?f5wqKAnL8WLF9CE<=`Q%j1*J z0@WHoX0{J6rHdAiua#Ed&0oiy)=Ai}Y^@4Dh?&l9d396%DFI<R{+iw@p{Dd5GB{Im z*5D43JWv(9A~R$_&-TO*ac6g*rXp5uJWVSuY3&>Kx)*F%CqehGZEx6Yj0g9f8|$>? z>Mdkro;wAZ-w`2uhO{faUGzS;;*8}E4GU(mV1sPRE0uB{1Qa%Mm+_61=eb>(ScNzl zCtMMH7^=^e(7{wF`|QxKzO<zK6=$LdiNEw)$Z-rU_p{fsJ}bosvope6qVI>xIt5&e zJVSqCSu0PaHm6@?c(dq25++Pc=5`yP{Jaz9?|<Bcfnjwpz>t;t^N4TTlJJP6+9r8D zQK$g#W!RH`M)j46D*cx+7cSR%v2?ivL;$pG0_m?%KH>S$yxW)AbH~V~x6E_xJ~kwE zOc<uWi}m>)LQ%qz6RuMrjSNcqKtK^h4s-kg=9GZnZ6R&nzbbc;8J<5>-gtsY;q`<G z$2jzOl%?@UaDxFM+H^5Nhpqi3o6MO&xH*!3Dt2Y2InxYK_DUb&_s);N{&dLmPebGD zm|-5B!>L2Gv}QdIV8MDuF03tTgP&~=0KERB4I`W4;s5C!qXr#I>5InZJ5;aAG(!M6 z6Y<`HhlT{LNE9%kipq+?5e4`QNE8Sp$_--h8a=2dhK|~x8@Zz?->h=HD$Ed-=N6X< zk*%}|nf-|ZVcEQV2P!X60z4a&Kpqj&Q~I09!50pAL4;u2g)SO$0T|x856teQ;KO{Q zG;k_Xf#r;^MOrojQy8vir!UIJP5!a(%LZyb{_<R4=1AY;fiSp<godnQ2m=h88A*W_ z#N~!zo?gM6u;d1W<U3l8(*~?%wuHqxC(tg5mc4c1m-cxaL5sm7N771<mr8?B6iw)h zPaM1#E;m!qAcsAfqD<vt^3vwh&gAhPR&z21s)ZzWvK!M`-9Mxf>}_bg{sbL&)=mxI zIbaqX*WrC%qP>vD*;wXkMmUHDs^xvk+b)p-^`)<2jq|~34oS%3AD<LXF5T#{3wYbA zjDq8O9Lw_%epqqIdVG<#`mMjD=+it4#0(9a0%cBAY_drLCy72-0hVA;{V|7=f^prb zsrDj~hTmFkdUT=MUu(=jnlg9VG&|Wq3Pxu-!(qhiF6FyxnX2v?%IpC1_x^FjVD*zC zr!jhyZ7I<}IZd=JzjaXZ+3cpB{zx~VO$Q#0o`&1M5*1UEMSkEW({1NwAMB%fPg>G* zJ@w22Xw79ftmzdeL$YI&#xySW@q!z&Ag;VExzCt>C5LscxJNU|0WHJIAIiFW5N_~B zHABtgt03Nnhu`~IX3d6H9%CAIu`LloHm9Rqh(m4kJr_FNUwscRqajR+0-``Amkpz2 zTOewgGd)i#$$)k7sYp@>q4TC%>u5m%ytnJ8s_lKtqP?`vRCni8cXtr)wg-Dght#1H zdm7kiw~ZN9@C1{tDp`u>`Og6e5IZ#gyV!41mPpX>tYM4B=<|9SJ<NBi&vafeM5f3R z9`qV3W_mWf87y#FD{9H=@RAj1n*yS!t;%kGvEcn&qP>E)7txzD=AqIXnLDm_q)TZh z23V$OXqPmG%Vfj8HPFpf31;&{7~ANqhJA7%ojt@Nn*ay1cqv=h_pnX$7yK8Ze%Ykw zG7jld{lR#Qob~lvs^Cr+6=1BvYHW*!#}`4jZ(IgWFSzvR#+mx+evBW9F5n-_mRQ6_ zeD|rS(h=5Zr8{&@Tgf>qkaIeaPf@(HT)w3<{S_d6x4MQcuFFE)sdTe+NY1Tk=cSpw zn1E!3tSkKrO$j>x;bWGkSdTmR)&JZ!`f^;&pt}DAMe}(m*P^LzX3K+qwk21eHbCs@ zs0!~b5!!(1lQQ}@CEOR$og*$isavl1M=p=4(4Xp{Us{Yo#E=62&q}?tFJuLl)9Cn{ zn7$~@WV2*0w8a|D&xeHc>yhNYS;u3SwNFC$2H!JQB~WKy`x`egr6-~iPeG^3(OAo5 z4IGwu)9XQh!MwOdulGL57guK?cdoMYZ<dhT`9R0~(nM4I`cUX238NvTl{O22dbk@o zk;gviK#&$ZTg?}z!rGfXy!NjMEST3M>&&XH+P2OOitYR)Go>`g@J9tY#y>pofLFmp z&wr80h8WciKak3E_uSIqd0L-2^##z?)zOsU_9s%itRHTyviC`{`eQm>L~rg^KWFeH zu+Pi-cZ9;PsHT3m(4V2OU!Y{ygJ_eK%*XY|iBWv?!Sy7XOWH5bl%pMnsI1O3AYW@3 ztu2uC(%SdcyXaOxkDP<<P~QV0Z|JU~@$~B6HSLz#{$|xrJ4`3t!w@?u=x@HM1w#kf zfNq_l(tC>OA=jY+ee|+~sP*}f=b1Jy&5u_jFIy2(dUcl=f9rEhzZ_uy)x6>((f7=r zX6Egg(#d8#Cy=hzV+#6f4Zz?k;9f@I@I{kgNI}GYp-OdD2mk9Yuf>Nb%A;JlCD&@a z3{kqdP~BF7IaDNkhV^*AA-zQcdR}=zPwg&Ji*D>rHlh`~sOxrR3Yi2R-!EAuGkT05 zm7eydE@%SI@Tp6+Wv)a@Qd+CyL&XDz@NN2A*q6aAD!Et{KvgcD*dfEspY2#Klna~= zMMmf6RB=^B?Kc~TcXV>U{TmCbnN~|kgkMgT3NXE>Ymne9%Qv>sX&51#S3`=#3wT+Q z!sPi3JqlXV>v1Jnq1{4HxEd5O491sLc&|nEhOJCrQQ_c**U?KfM#%_GYQVj=<e)g# zo`uJuPD$|%>{J)Ba}9)F4jfvPK=oCQo~oSiEB_B)DymhryMg}sBtc!JIKw23TetaZ zXja`;Q}~$<0iqI8qMR!7REdT7mW58Shpx#_duvQv&b@n-u1Rq;muEW{?M6>4O8~kJ zWiC7oZBSP@)@NSpxN_8occpqaFj(5~`d9&@tDf%t(Is46A~*k$r2$oPkuRnO&Yzo6 zRnx4hdryPTE)=c5QR#)DN{}Ilyi4mqE04Hoz*=>OmYN{%*+ScrRa&YcESkM^N~n;g zgm<9OCkRORaPt0R|2Bg6r5xc=QU;k^cTM|2tYPZ(dfSUdI@U#PylI-@R+GDp)~yAh zTqsXW95s6Z5kR6cSJC!0X@`vxl&_XPGK{e066O1h%dPU!n77H+1hI^!*H_B~DxF-c zM4&4{PC>!ov&qBJ2O3kf_lS&=p^x2R)rz>`W2{8|Bnw?#RZNMY;pAv6Lt)nb)44^= zeKlrT2!Y7LCF#xv@Ks7_QADW#Cmi~QGMQsnO%EX=hNao@3n}t|iYF|k+ZZ4!5g3tJ z_`4RZS(WTX-&!Q2)`A*TsA+TzY5b`s70^P3O9%F<NM)Dc1*T2ZYQ$p<H8XUO4Cjz4 zHCSy6FvQ`$-=#yh;;5|dpI7fMa?mr-Iu`mgNUe%nnQ%Xkx@&9qDs4jbgXpeTUme@? z#ekacdT@!fAWH3C)5#ar43Wm@XMmAW!~Uz=-C~(*sa<qnNfWyyX%b)0`3^J#8$dB& zsi*<gjfI~};PCaV;&=&HXR{aw{EY?H+>q=Z9bjjfWlEx1f2-_GQ^KMO{>FZVeFUAP zHNjj~7^azatA|>@OCFO)a6e87!w`hr%2-<Qlvavr0maHAZ_r$62ysR_MtX}wc7&%j z{4a#66#Jo_Adz69sHc#@qM2DGg|*J)ouc27?N62wjnZkCq9=rh0G)`v{TMA88o{-r ze2vR=^IzgKb2iVP;Ve^19!6DUo97ZxVqJ4T7~gM=gz121x(xT|vLCUcSORmLN0`kt z@xc(_imig#VvT<o>v0Ik9>q?MFzuPazhG!>!Gkup*p#mqeybwfhERTb#l&?mctD~G zSTN@=m5ZAkLyb1#ON#SX!Oh2oxR41X{&o74721>uuwRq}r(YtcI(E?QIU8@tLT^n@ z7vUaEhe9vJSre(|E-dThk3N2F<Uv7g&s)SS<fvm?1S4+P67JZT{FF0*=QdCz#{Zq~ z7!hbvRg0>bEk&bN02tgw1$&-VdAD^lYx+y>$L)<ptJ^uvWRQ~}h}w3#`zgWgQiqLA z^C@m2E7rHd^$o@oLiI0BiA&ZfE+ofr(f+OumUgjjGZxu&kb>bPM3`n29kBltEtOFe zO{IMPg2WBjr%3<^>{pberBR0yOOhEFLRy|vZb%(>rN;_#eu(Et(9{(CTQIbr61wHE z(bJgHO&7v9c2|=1=~zdA4Be{E2SS3&$n}SpB^f@DXUDRP_t0QO$}BNi91y{J7G8NO zBk^}vuB(ZVRE+|R==N@b-pT^4{T$9mva2f<DHRCAO+fLI&QaBQ{sTv2fZYsng5MZT zazu}~u)jD57yRqtcY(LJ6G$1zFYSzYnc}tklZKnAIZh@ga_ycaZ+0)|_;Mh?sdVJm zSgE4FtjRc@8JCyrWRCRK(cTD~<wj1;L0UG?I`-XO^k<H6GrE%K)F+g^Bbu(%-%L~~ zt_>zzI;wID9U<<_X3Vj6-UcMLWw7eWzWp+wN?N5+*kZf~qc(;B!?r$z$Vt|imHTiB z3)B>3sHp;?M?Z6NNEw5+3U18J65Ok(CRF$y_HiHA&|NI^^G@AzPi%tD5`ML&F~%?~ z(NjC5acc2PVMat&a?Q_m2|H)GMX}FHQwG<Ky1pOhhP5<)x6Uiy0xxXSC-YT??SE8U z6adt7lR|)R9m=RzJhZ;?NKOHNw~8@OGaCI+M2xS>C>6y(lY%eP9*ftd_PE~A)4Y$Y zdAe7Xnh?9n@mb=gEzFfG$C=aWN?4{05s6}0_ij>Xnv!@5&0Qo~g*))<;0I$dOg_f+ zUjuny$xEiKdVIP3=qVdOOCwQ?wTqLke-J9leT$AoL*7H4w~=sdH92CHfm*O(lYYp+ z?NcOvni2Z|oo{jUj3sM5Rq5aC`dS@D!Wxb<HRGp8boTe!eb|4hSy88BI0r}LzE$#I zb4E#he3#mwZb5tlf`$3U;DIo}5cJq(b9~J8^G23lPiC1VD^DJfrRPycUzuo0Co7Mv z!U*lWib>3*WM~PcIjB%kv{LLxbFD;P@&zY4SIYbhFL}vmlWC&}Ya^&V=+U4`Ora1= z9f8y&@~f;<2RWGh5NN>vS<4<QGYKJHd);KANk^n>t~=J(P)kQS8YgpF;xZg!kUy}` zpSDF4Xlm}u6nyR&`I3HD?*}F)^@@T9Bm8r&_Qg;w&~y}>%;3)`nO20}sB8y{bZYy7 z?5br)1<XSY)f)I48h*gBzPr&*wBrp$nen$n_&N1Z<Pb~KAGuPAM*dgm%Hucq_wNOy zYM-;pE##)(uUzAZo3sP;;jifVTWhJ?qW;j*)Jnd>{{|hl$K=>`>vr9-wpR>`mQRnO z8TC2&$$b^LzFL+1A#EIOWR+6eO3>ba;1+;$^JP%lE(AEY4@#R~+1!VRw*2_aR~Rpr zb!-Lh-iLpBmG1h-WoG{a+YMH2m5uxLSv~s(in`!?OZc}aAe`&5yk#G``{Cu*?pgtA zZ|ddu+4qHpdK|4%OIo7;ZC091+dS+9VmRqquJi6~Cd)DOklq6`N;fns1a{U8^7?2e z)V)C4KOQ+8gj@ccnbO|f<!C0ReWw4F90DZqh3%P#^$u{?9IEnqX0{!$n)iAeg=I}( zfCb-1hYWX}(@=w`-d%@ODZ27z@w%Z#Lrl}=%{YXqRYA5s+x5V2UJg_pQ-vm^0{Y0c z50icV@?E^!G>!A03-?mR-b+?31)elw(=P#B9QF^(>{=djYCy1IM(^a*8(#Lvyvv>m ze)hETrbGADpdquV`;wUEP=8pvUuWCpBN%+5`5<GDk8kA_{T+W+&b<Je0SY}ohV*$$ zV-4|L&c}b_=-}sbFVuduC$amN6j89|hE`?GZG|(xM%l-_rO?3dzCw`v=}TFG7K`II zQ<!tKcSxIgih-F)ZfP76{wL}31WVHs@_iqLhx$n<BVPL_<Oi{dJkNgoRIYmCGSQ4= z@HY3A?@5@rOw3Bp^%BGp-jy)g=bUL3WilQzme-a|EYM0FqQe}<6dfIZ^P!xm0J09R zDKl8RL*FK2LQF)NJ%vSdRZHwl3DlRr#rwG1@}ods9mD|+sWiM+PiP%mZ7_{hy%*8R zhAPXwp7gQXA3YFhe$nP9TvuiApD*mz31Ti9(Yal%SaVAPBz*zVKMz6i6w*ZxHGss; zx(HR3XD7J<Mf6EAPX2Eo-6EmsAO8&NJ;sgXB^{l8s0KEXI)8^RcViw*j1ZhLHKr2f z{3>(B^S@dc%}Vww<^-}jpbMi!`ieU0N|(9SETB=g1Ds}lQRHT@Yqrrmqn+x}^uOn( zV9r$0*f05-?F0TARV)43toX^?AnL>smYk>dEC*-)34M0se+Cp|A{QtKVTp98uiA>N zQX#~&zzIT;aU<<px`*bsUSEFj8=Z+exVBoIml6x{<UNw`S81bQ3YM%v=f0_Sy2h<r zF;-etqqs@~Sh%*pN}0$>kh-B3cM9M$Z3uDG#$WlDsQ8Ahdm@fUHfwc-d0#~wZpbo; zwpG80+1T;>@Llp@#f{TR++UTjYEtr(jSUlEm5@%t%*w3z?_6PR{Q2Qv{_l3g%jko# z#j9y6uUY~vc!DYBnE$2nLKo_9(Vg7|<)PzI^~chd0twpJk_5!3tDH0{jvJ|3l&pJ$ zPglnZ-a|f@*B>0pQd&+llKSX!)C4~;OC;8MT$`t=3gk%)Nu<GpBx4n}r|b2C66i7c z-64erpG=D_u5V^P`mTEUQ#)`)BiZ+6xxCMkYY2dIYCq2a+;`~Zdw4Z&{TS+dXJ=r$ zoHJ*6Ff+C@E>nFOsk!)mtKrBSJT8?0&~lnsa#*n{(H@W-F57P)Jv?7IRN&RlCA%@J z@HXayh3T?9*sPKQ1#>(L(hDtJz)3?kssW+y*&3S;c%ahv5f;Rqx~n9nbo7RN_RaK7 zDv)VnWl5n&!8R2mf2!kS%Misu8j!<5=E<te&)Iy7tjDs8b@>+Br4WtN$!T*f@|N(D z#?G_q`*Dwq2$hg-iv29DfR0ZBq2CG~f0POxSRdDb(rc%yY{>XoUZ2?J2L+#3v}S4@ zC4aBOer*V+R#d-Cz+MqeCq-`B%`b+3lT&r0>vPMLfq9tbiLrv!R%OEIt#x-;j2`dv zbqM&TT-8~O93RxLB5XtD$9Yy&ywDA`qqW(x!5a|{d=-B=8hy<vh##Kox`z)dEXUir z7=BpF&8#PE;+?c;3vJ9bk8S<tnyqTepTD-!I?MK6nw`nIs&;!#YMfZ&Qyboo4zhSd zyk45Tyx0)82ws17PSlz*b<3$(+u%>*yCAObm>w;ve^fHrSpRNhlF4EbbL6NoZF#DZ z%p;hzL6y#XLX^+3`qCS<r!D%U{jicxFKtrwyk*nw#k*YA=QgX<av55>Ngg?lzu5GC znc`FjnfY5T3*?JuA!4EyDi<MPKU7yCEOgCE#YH*N1MjG^J&n%AT*t#gYiE)G5|1WE zDZJ^;rCa#Cs>gL(`At%OpdWOtncij1(fT=QoufJL9SzZZpN7g&QOjjVsGd5Y4Kx;H znG!23je&h~x3-RC0CyeG7HV4+-qM=0A@Rad+P7K2!4DO=vQ@h)sz1Ws&mO6}6bcKZ zh5lFM3sS?p++1unaAXIoRLGzqA0s)BZq`@(@s9E<{4#KVaIbJHpJ#El_9JgEC;Qjv zLM{)W=1B;Pq|%#M-<TxSSn*+X&fkBJufOFUt7R&w0eJ6t(w)NquTfotZZdf8%rfn( zxL|PCrMQ9yilF6604<H1B@2e;Z?%N8tg}8bn%-vT{@cM4ilE>@nWByWu6er+?~t<Z zhqwlymD^Q;3hzgOJPVWf*hx@&82twW-(u+q7cXx*O5oWst~X`UQ1&poU%^wm{X?d- zf}O`eu}E#c0K1WY)TEu}e|_mOeRV#jYMDGUB<7H48stHX9rp`;4uA|A26xZUe8)m6 zDXB&56Vsozal#l6L-1wG8~GwYK&V1Lm##Hhv!x%I9dDA9M4xT65lS6UvTm}0<>;IA z1eKEa)2=NoIXJw6UBlEMzmBBw4Um~vt3{-EtAWVDR>BP#o5JE!4!gS|$;5+ivX?jB z&++X1)}s+?L9FcGuRqRZg35jqt5aP{0x4q~G)1LwTQr*W6lu+U-^*(k$5eM@ErKR> z43;4Rs2Hw1MI&S0iu+dMHN%k7mS#_lbY4zXzp0G+_sEnP1LYP^%Tz-H-v3W1OB_dX zKYT~~h^10ow+BxsipnftXR6#|sQ>P6)E<h`>nApXTd#tFhYg$v+#q6f+~cMm&-*v= z{^eu0j{=vcm*V=cn!j)VivM0B*5clVYEMj-TTOhNufNTRne_-v5asf1GY~Vc*nn2Z zWD4u)u)1$j#qW$b3Gs64Phn_klX!0XQr146>!@$`oFa(LSLHE+hzaZNml8aaSdD}S z-)_a?zF3}+<(euwieLV%;G;XRNtmVQ*(jN^)?uj#cKBrzshOr6cFGgHOYmMcOy!9l zy#5wF@T6i*9Pl5J3$QEKA)q>?z@Ef>_1i8ET}zezPbNoK%ul@Z(Z|NF?W|aVLpVSn zD{&2%g*nr<k5Dw=#&O(8MijRkR{mlYe8d##GMX1glH|TGYZ8)Yjr<JhS0$oS&$#a= z{H_^->N;r~hUm5y#u*N0^X1U;xWU0zL4E~=ABOqXna0S)+J`86KowD<-_t~Ef|M1L zt%%eV+fCU;Nj(&$hHLyN^E-^;lv^WlnB{vfb#6ChkGv3F{ulD{asmf2*G0qDOX~jl z7eA74GkSOYMNas)cTUt6o@cBp&pI$t&MvRz?ZpD`s8fJZ+Q>T7Y=g~k-O<g0n_i_S z7}_75IH#F4zXXQQ`uIUP8s_icClu_w?R}IqS2n4vLqm;KDJdAaN;9V%opa+}Cw;UE zvy{=vH=6_`X5IF(o^q|L&)A31qiw$-E)>Tj=KioGFqQT@ksfF`&?I6$kf)6r+tzHy zH$9rgGuYz^sK{ud!gG4SiNlSDhb&X`)>bc$9P}wgu(E&#{2R4O?yL_pDOz*uOd}!S zbc=SkP}8fXHi@K!eimRp^jN6j#Q?^d3GkvKy3ASj7d*M(vY0}YR&2)>rHzKBNz>FI z))ODJ(!4CBnjmq`uI;_ift7?j>VH_#_2MM$*}ITYHJC!*i8*Hapf#c&K@4YZ3(#8N zp3~u)z@+u$Ma#kFM-fnH#gp$x>guKZMr<7EVuLtZ|5*>XwxJ<*sIsttg73uuq%vZo zbMxG_5_a2{$Lzt=P@MQEGWkGX^$8<8arTaahgn)&&`C*g970N|^NI6X`*BZBEfQ<) zsp<aN>8+Z8(dq*6&Y8!Z!zGQwWM<P6FDS?~PtX*wMJX4b_TjnMoXb5Q|G>@t`xXq< z1&smLW4mOaaYa8k(R_yt{88rBggus1U4`$GIVdh;fA~HcBlMr3o=)Wqa74;zz4lcA z!4e*XzA-O+f^M~6LfyjgiW+Fe7bfJ+dT`P~C)Ndn|BEQ4nyq}*u64h<7!%APlW@Pc z%(py8ahVd(U8VElb0BxcIcdQ1UDWF6Z$F6UY!Sp$ho3Zy?ZG-%GBmbKB^C64bhYzL z!TXea;&JU?{^xw8H}-gTMd6=bhlXnxV&HcQ-+m+Gc;VM`((3CpJs6kn&VG_drMW3- zP>O5yiRKVs2p_pM!01h*xzRr~Nd@0e`ZdA?WngE)vPAJw{|wRQ!?-$J=a}TnxX>J> z*P@+jcz;VT{SL-NAi3{SW6&8hS~kE_pn|{DaF}dYbz_=F`BDQlW_8q=@LJKff(NXC zhQ%F<65oo_t`k?oNxUH$LvP0PS2H~#UT25g*E>nILSLliKv}U`gvDguNV{Tn%ovoU zI}&pRrw86a^?{U$(p>~mbE`H@xXNEv6~pY?nnvZX-0kWX=;qy|vr_{$@DeTffXRya z4|pvV!Z$unrm=n<K%yc5r_n@`(*?ecFaW&9HHd(jv<7+<jO(mGZE0opg;c7QG>V!= z8a)ouS1)MCGAbxf?Vnz9pT}AvIgY7PdS`u&Q=7tTP<Gx(m(HC@%|n;3A7=SMPKiF) zw4BoNo#ous3A%VwlC~)r&_Q!)MEslxU}pYs{R$>-TA=ekiq89=s{euGhkJ32>t3?w zwYMmHUe~qPHIl5Zy|YWD;tsCawP(6yuMo1cHzA2oc8D^Xs*kVlpK#6(@AG)P&+GYo zvj68eig>5}!<|Fj!}yj>G)Zvh(8Ii%k%om+I6M6q=_1xtDsF9)yNF+W(AOcFptcBN z#^6mFVf<&ys?lJz-NaOj)V8!`%oa!me(@@eEz8Uz--6Pb-IyG0Y=$XXr8v#eMDvnu zgEIX;>h_brgq>$Vx%4>cz<B%NH<r<OWeQ%ynCG%Po0S^fA(r^!*TQvFPE;x68Ycbb z*_u)E03RCHd{@kLp*Y^4NCzuUvqxiB=H+8Jru^5=IvM>)Dt^l@(R+dKW8k8m=<3UZ zQWuV)u6bc^9<X=*)1Z5J^_f`d7{YTZr0uSOx6QTlkZCjOV($!WdGdBI?=R~4#d32U ziJ%_w4X~k38%PeBa`oQM?P+^e2aG0He^zfPif>bXtEkz;@iMicb~2vD#>Y`s{A!|6 zFdR12rLV3)EfIr1OZL!L6fc@x<(ugZPZ9JA^O>SIl2(Whh}e82P-*^Q{b3uzo{*r^ zKo^cl!{6pk`8$L#Opx1uRtetLq>2eHCT&C{QLWimYFBQ};xu~);zU<Nx80NG+_Kt7 zgxCatLNASZdqoP>(2Q$A-cz>(v5#sdTtek>-sGJ2(Qzh%;#!|7A4%UU|A*A23~vL7 zIqeE}Wy-BQO(aKd`d%1uLvL$9_b*;kZt(nyLVR|XU*Q=7Pa2pPLu-$|Z(*?y-2$o3 zd!onpG9vVUzV)T#3#N+?GOtq0PNMZ@-Qv6@Gm+KVw=g<VgP|vHYyWLuQ%K6=*{{Iu zV~?TE6i_7<ZV!RxV;jJT@jzXdBJ9fns(tbHq=(MfN7H-%w&rW&{GXrs!^S?Am17gx z&{w5J^|4H~(w4=-pKErODWhAHxrO!93u8*VlL|6LZm;Y9^M9G`*CdUOFX5W?^?4=v zxdY>GJZRI_WEHv#7DM)j7TwIA`6weknB&T15000(!K8?A_M0#LSyuCsRhG#+O=9nQ z<i4${I2y-=RxB6Kq!<{NI<OH}&UFlz>#ywG$gcFu9O&sVR)d$_PsWc*53X3pRgFEl z$#Ri;IG9KT)9{Og%`(6IQibu3OR8N8Q-b#3#O%@4zI=sUiE(Z_3*jY<CH;YI=?0Ut zoJ!500{KHF;&9GEzxmcPaeh8PHt}51WTE*&eG#i1BdE_;^ZWOBGcK{KdVtT@)SNgh zR(jwvJk=gotpotKQ-x^n&Mx7qrL)X0NOIH~5|s%6-v9u4@k<*(scmd%<p`3{8yme> z)bfm(ZawohFo+vW{NWxwnd?jdpbB8lR3f`Lnz>D6@Cq8T1xN&vHV)?I6KTa;@Le7F zD_mL5TDN=;W-fPu&PV3zGlAa4VtX%=URN>sz9fK(hyi2?^Cd~S>H5@m!zB?H^8Q;^ zkl`Ce+j`Bh=XdqPA5>HQ-RV%Ej@2pT-$EvK=`q6(%kEL8%D?QI!k&NGRO`Yk`~{%` zgHW{~^A5%j>AR?zl8+_xsJ~y$zu{4TK?)7y3QYRZv0&*o5EZCbGb+fQf)dkd2p-<k zjOZ0898i_DM%9A#`RYvwagO9TRk$w-d%<LaAeX^nUBi|!aY@ZoTD=2nU*M0$31Yh< zPTWXlS+x6sQKo3@xHv&`Cq%t;kyQ9q8aE^;gtkcaXua*N4L<gZ`r?N`LHv%53HV@? zzH&759IzYER>6mgqD9&UsB2{O8|n)e^w(L(#Ck8yiThg<_?Ts;)d-=+zZ#5ZK%(g0 zZJa5q`qE<1b7KsS8WF<JqpyacRo$XlGNh+RfK{WeIDm0c&2lVTLx1E`P|o$O5eKN1 zM*jN<28)2ce!SAJ1M@CCR0b^)SiZ5_gpz%x@|XISiM}eS3e}7MB25Ue11WtA_W9+% zng0a^^u0>a*MT4V$zGJM$<Q~FD9=N<0+?46EEZwLTZn)Dpwal3lR0y(v*#2@9?eYA zU+8_0a+Y73rV>z~50G0r@+Ll~zbyax%jG13W(0^9AE&2ls40q8Q~OqcTSm!_oNIi; z>jE)X6$AlnvwN~c?)w3i%y3KJop?#G`cFeK#yHa?G<1{ejrgGauh<{sN;P&@fe?9s z?-nZXa+(9R78aefA?eGu`4C47z4!`^CjK_`4pHX&%xaP-iPq#ilsn(wN`7h#dEG4_ zaX3?`9x-5wdZ9<eKvti<`(=#sObO^6TyAQ7h^*CSss<&1Yi68%b(AWz!BboM!bKYa zq8nP#jIX}Q8}kPQ2P&)*8H%)c(;65UyvFi{2Ky#w!jf6-+vqC2XzzUE(T=k5?wwT{ z!K#Mnt3^+ETV9>o+A}7ZqLSIU{u}92>{oPqtnN%d*vh8Xz?m_5@?3y;9{DZ5*1|Nw z%TN^0_6nnXV@6TGVO$eVuYoCtTG_Ox52=@4O$_>)8SU>}NNy~`phv+PTrB39jr@-p zqmm}W;MdU(k<5Q4gIS>7^mmMN589)hoRO0`bJOaS0sTSHqYpbMQdU5(J;y1#F_;(< zouskL=HD^A&|q3tIiP%p(HP7TIho{)fq&b3vie12t;ECFw_;ZKGX@g(PKOlbV9*vF zK{M;@+C~>Qz%m|f?LM-H@$}1+nz?x(Gb<g$@!X^>H^6IB<ZSS#F+}~RFu~YqbY*eC zn#)_-B;I$q@IHZ&X6dzGIOd@iZJ5iGfTquSX^U6(JiSV5dgtnu%ZFJwRS%?FRFMO5 z4#O;OQ>6+QCi-XFjdMq{Zg3aA_UqYR()`o@dlr-hJ1Z8sS8_i9d7&Hs4W{t~06>-+ zU<CrHC8+_(IY0&BGj5>t;USl#oktsr2jbx(riI3hB|}M<ZqBEPV!(imL8Y@FuCa71 zL(;a|d90~yB1gevywK#u&Nx3daDQd&MaAo<NIV0-sh#&z1Aqg%p{C$DTY-6I`oy%Q z`fUxXH3evJN7&S22NL<sT5E5-kn9j%xz}2^{4!*7{E6Ai`qj>;)BU=oer(b!sUHji z=4}n@1Efnbu9Izzn<Hcqvm*2MrtOK`s{tP-+h2ToP0>#hu;^&sdsAs!<2u#R^7&nZ z$3&4uXY1i|TlnV>Q=Kore(c3F3R-rx9dC|i$lRRnYCrun^UUn2Wp~H-&x<btK2CRc z{`|T&kaR9+)zkI+boWio&DTBMe|{cqPCT`G)${MquhY*TU%z^FelazdT#Eq<=e$;@ z5#N2H%`hI1#={Nc!K`jTjKTdxbX(yi9`SF+@p~-cGwjyQ*M&&icVjmaC#@Tc<bYf( z4kp|B6VLI|Gip65v=HNQ&yh)K{cgqD$!40dc-0cSsmk6~2F6foJJZhIZ#&DuyJ|bz z`S#v+4mM6|C)YFEZzs>UylN*uuyt>zAY@qTQ(?q{-=`;0J5`^GqJQjtdKyD3y-Oi* z`0o~z#H)8pl2!J1pOFov_ewME{rAdpy{q@i3vci5RZ!xj_bW@Y{r9UX%d7XRYg_mC zYr3DD<I*HcAZ(_R4Polzk_^9*!^qOy4SGpRl>0#gXx22KNSBF#Eo+AiGRQ>cmY69l zdMDM%mq2(ErJ^4Gax2S&*u~3N6ryUB(iN_dxFdUIo^wa<_A|ET&2-ch8gCsNmA<6? zTPIb2AvTu-oNG*Z^&vBOZj&P{EeyzYGlYp{Du4xhoC^{pI^_$>B`o%+jPy1YAbXM( zSYeDpbaP`LoH%b|EI#Mk86=+97OOb*1bk{DUP_+Z0bTLD$50;~IA_YF-F9rE&=Ju@ zFPL#us|-Aeu!t0A3T`lxA3N#_&d>6sR7n=`y%>cnvV{dn=szx*cnkP;fBxWn=R7P( zNS{=fbXl;|4@XC{2SVy3%hxbUvV5a3zI%Ff5d@<4a{v9|S;W6PYeaCyghW%epXr{n z(s8^1z%(~jQa0$yP*(;~f&f8a+X;#GqkMU(7A`rm{Pw~_hEJX88+R0l-+J*9*WURv zwD~T$Klo7B>#$pQ_9du+m(P68NWK=XWGcD0ph5mYCGzO6#1n_h;es6p_40aU;R#2` zViK$7GoJv1nH2@_ZTdm>H&;h{m{iCw=n3J?B~A*?Zg?SV2}dp_N0LL5>=T;6w(m4w zH|?zuXB~vd%l)u)E2}*gE#pGXyDsUQRbOv102PF|NKA`sT{aQsL}&`upQm4|e9`w9 z@$izdoDD?Yl?vgxKj18P7Oy2S9>SIfc`qp~+3^l4da-DW*J{mVye=w3pdPzP`Ok<9 z+d2#brM;D8g~aR)rP?!1t}MCxjMyCQM;wI{<=@ZXt+XstoSJY*txzo?Y5(ixT*3@4 zx$=Yt7NFv&<kDq&K;`V1tsHA0Q92tBAxwKEd938j51F7EF^H$|QBiE(D;tE3P>sS< zk>BrntlQk#Y+n$ev@A@w2m^dOGweLP5)AkygxjtNNq*+1sS}Ot?N=hC9m211u8Rxl zipnAQBAod_<ud{5#`y8G7n2#$I5vl7Z)Ljg;|>g-kUk`Y$;0>D0>2fW#=GLBs!ugE zKI9Gys~pkVDV_$V$YPWb_YyU_39G0LP)jBIgs~wxMh8<uUxmM*7B%Tq$l-a$aoVy% zbhK6aS^tVz%)-))470wmQ6PrQk#31(=pdV6K&i>4jX_3M&muu$sZ`G~^F=d(`NY9D zw(@$qGuvhB=u%f1CKDvkP{Q7`EZE=iZX7Rbfp~C{Z9=E@+&;@>@0*F&{vZU)X7J=w zsIwA-y3@vD*hLVLb~5tgZ&IldIe_nwPMW`cA+u+~@6DpK+mVUpTW|P&Q0UYTj_vNw z<N1E~9%yWaxAroC!>cyl&c~5E!}?BBeszlJ`zyC|oHN^1{RDaFd@F_p&qqQ>06={| z?eT2?NNm>?M;Y+kJI7oO;X|#=QTM7O6jNy!=!QI?k|r;SBBVl<M)|u<;dc??0t2f< z@Y}^V?s2`-ZQ2&A$gE&w89j^z|NdmeT?0=mOS`_BxCOt<E;pMv+w~g}ueH%g>%I$m ze!}Guy(4v{l|j^x4%FKS7H)FMnutEWmMQd8fuO`QShTvjjqW)?Uq>`l01El)TOCf3 z<NC?@Z%0%J$j3xs+b2+$$Ew8+3>Yp}r!Eqn`CE*F3xzRbfw4kQ;kv!P$!&kW$~;30 z$LHeJT*Cg&B}o+$iLiK)<{eUq2COhO`k>^zY)8#UyZ@K#F~q#6O*lKFQ7l1+O}LJF zi3(s)gjfOZnGAs#9!Pr9+!)!q4oj2=Q-Nb6s59x+X?Xj1)1oci^COiEWSdnt5irsI zlhI?_!&uidcn!z9d^Ep5&~i~S_5k(84ESTIVx!hVz+(eUE(aeC9`ut%D!Eq$G|2DY zQzs7nCoc~Dk&s+eAHA+tzF{f1&i!$b_qd@(XIJl&a)wb8_1#DX4i-A6pUCKU{n<*8 z5?c9~Ua<WP72p{|$QT+0@BH~(5}~)z#s3_k&Q6k3s;o^KHHFnT__z0`O%o_QK>oHY zzk>zy1JM^+?Dbg^{(V{knG|T!d0Tcy3&(^Nn;Ak6=`3)O?cxIfI$bR4Mc*~Adq1q$ z92UZ68K}Fjeo1`w#J+@c$N_G5lMi4iI#%spwYfjZt^EflaB4Vn(cMgmy0`hZCo1cW z2EaFPuM*F6g@X4!7K(apF<&YJ1?IRtAMvHi8|2?0tA7#^w7h(|`fb8wMASf41Q4Uj z<@o8)dG1m>wg}qspYjV6C6_m56p3advKo`<EO#5f2+dr$9=!tBSiOOSL+l=ABK_OY zj*>xYA02Hm{^bgXmR^$u>|UV0fbXI~aFUsTElJond#&SLf-1wO{LEBwnpl`aMKB<# zhd8U(6D&=mzcJ>DNilag?|bP-e$`rXU;IYBdJ`28%Jy#0zg4aJe(+=3&zro1Q#Fx0 zT3;nB3%0x!z!N$2Z#j%|bMEG;+Fi+_J5vb<La4>pXpz03R?5AP6%x8Cj@u_1)DR~~ zA6;wu9q~r!DiQ`(WcFZtL|u%--0`4m#r&YaA`sCZV$2s<Ji9rK%E`7F7`<$R7%MyZ zEP~<qoF&Ot5u#_#gs1ONxEJapAsgjVA7Tw&)TfWV^DlyB9RoW7U=oXP7Fy5!OxPaW zFaX2!9m9+?<R|zrU(Zo3LHOOmg2F($TRDdNm%?_h!~Gk4BPqThD(cI&5dO7D%~HLG ztez(nwLWF=t#h)~^Okt<y1TrJ9UBX?s`v$60%T#KC*&(ImN>3=p%Wpr3^a~{M*J+< z_~jY;b_%0@FDQ?~m}P4)iiZnbVrY3Q3l{RFu?}i5)_pD_V{9a0dB^pX3^SwzcE2%c zIYlFsHJeV8C57C8H9aO4&waG>761fuz_^THDh~XQe3(DNnKCfc6Lcvf16K5*GJ_lp z?Y(TYR3QK*xCLM^1SPqu-o9^}9NdrFUrPzYrsRCG{(I@6;%wAO#l;xZsTx7opT%6x z!5^gNoDG0P-YH*<KW;?X6^9s=U>HRQXy_Xu?K8R+y$o+Tk{l!@KTu!+4UF4h;2bTx zeje%ghmF0`(0RERn@xs&Kt{h&^kB?_JyZZUB9KQBIzpe|EBf#@3WKE>z1<icfx_52 z!(dT$x$P=gzCs?LmrzkL6mNsNH$cVPf>dre0SJ>6+LU`fte+@qugQt+ci?Ui&wWbV zkNE44uBVM3-}#MU?%Jl!L@+m3sx#36v$x^RC%*3^6e^AaoilE=r6XnNfjI?m7@TQf zH#b~eLc1K+iKK(k1Dg<Fy#bmFw$WFOPza^Jv>s6>j-S9X7kI&H+W9<`oad2rWD0Bz z3(aCnFH^|YeQSGFl;PHxv4Oq4U6z*qz+=>aOqr_0DLlicf$=xu+JksY>T^BFnHM|$ zUFduWcsGW5o0K!E7`F)kvkEkwG0glq3Wj(xtKPK^av?(+BZqkY9IF`;k$l@HAp+%m zf%k2YZ-{f@6Q4bLj)8sIV~zAq!S3R?In#b1na4)SgKjYW8;Jm-<TT`d6o~@0cKYqf zuyn)d!*^={5kncff{}D%X-(*CpiQi}?@jfnG7guyMt6c>E-K?2&4hg<!-g7YKapWE zQbovb1XwX+BRqX*2Z>PAq!PR0YDc*yax>f}o2{L8qM^uZkHhkMwowA@5EkYoncJrq zHE=yq(U|!g-0iypc@-OdzpRAeSk5EQo?DFJd9&(UllVcr#OQe@{(|{V7AXp2c|^QZ z@&idXG2=mfd}olw?P6&@*g*TzD9v5XG0V7&>$s50z&g*)g*Qh2-?KvB63f#DH5@>{ zAyt9t%VuJEgf~i?M}W^}D2Qram4#=b?~6|x%7=#v-$=U7|AIdUYlSw;you5%#TpX< z5WDZ4QqH<tO;5gKY3AYAl2xnJG#*igiUoK|ejHU5-@CsJl!A{#p)cX--(2iyaKFdh zQnu*RjgrE)(BduEJ)3gGCE?!@%<2#h_UfDk$fHd-OkblGtHdXq54&9riyFu2i5Inz zFT)9jLL8N&QZ>#41mqDZ!nUdMy_oubik2yJK_zGFIlbe}1}6IKhMqpe4+ZA4nbKoq z+^&M**OoW{38f9M9<rAyh++BG25&)KohHg$evk9SUB5~XD9dow<T8&$(9TmZ9f`c$ z1+@Z+=CZprCve9EqDemO18#43&M0^efp`((d}s^d!!m;P83NgY1h2O`%wc@!fmapG z{z=8RkMFQ7glcNkewr_6E%rw8LQBrD9!fre0r0^xq<hYD#yc!A9B6t)q!y6>{JW{} zGc`hi*nTGSDK_5+k-71!A#yzeRs|!k(eX{ZXxFRR81;DdCjzb+mAJ`Jj5W+JM>G61 zqJ9S-cQ>4YbO<V^E4{cmTBQy-?yzsdbe(_hT;(EOKV|?ZYRR3rJ;q2CZ`cL}rp^fL zVQ;;pGF06CKY{$USM7r)ye5J1_o*AudzVwlqy^qxtfE~<))vIlw_GDUkPttXs7E28 zAKPm`o3SS?Ccs+ZvF~u(l^y|DC~#!ccHA~5Nk>*lGmme<a^XL&<wkCya+PFCVjSy% zdip>HCoe`~FQ~qu_iCp6^$9VS?Bt52htNNL_Qj8wLz8!6T$>B9r{vhC;tDrHW;PsF zu#MX{dk(VBmTi;iJBq)O%+lzgfQT9fQ$2VFG*C-6RJ;){@TJ$f7Zt<;mD%k-;f%~3 zYCJ>I<FJj!GQ8?LbmZQlFXxfitr|G~-NWDd>4NGkD|m(IHM5z-m_|EBs4U!G5}w2; zUUY^%L(p|%Vf*BA&%T<W_Ysw?PkuLmH40kW0(jWzn{P)yQe7B@Sx;QyxkPg<NViKf z%R^yoe%uLFysJR7jHuF;hQDl3!*C`(cOF_swB~E@>ej$=WtczH56d3svL2_?vIO<b z#O7gixJIfxSUr>V>7KTX28AM868x{yHg_J;oP{v|li?ZBa2^ezeW?oD3kmIFVwuG- zgIKIDC$TE>7z--Uw~!fE0pR;us2_^{-b`^y@x^4F9yjCByUcS;fh{S}h&{Pd62-dK zP^C>}KyBwz^~YxaoYK~%Ax>!l&&N!@W@7QEEd72&(;uHwOVtyBq<>26;|^qT-+BRH zMKy#9s2gdC6d2Yl)VCjFc9gNF@G6ojaX#5!I1u`0h3D&84-QEW96^)2=EXzbTybjv z2|@d%nYS^_Xg~4W>`$Zg<^>LLHeF08@_cpZpuP!xC>)kl;XUlcnz$Imu6^l`J3~Gm zy4qk9I^&d-;qA&N4wW9=Jz@^~&V{F&&upOk*2Pn5Ot%rjtT6gU+`3sQP5zk#RGfsk ziK+L8EZc63yi}#pd{Wcp!oEmCn6HdjD`&3e&HpRpuB?SEG|=kO!`u%RJVF`f|5#NS z!oE(}B%aG%r-OEWseu_``)&)l3FF`ajE}@RFef2X{x@nWgoaRL=&=IquK#LCF)TR% z=G(yZoy;uKE#`GMGB;p$T8lG?mj!vxBg%mO78Vxh0-rkMD)fiFjDPisG8g2_DSef! z=sWwV6KaHgE9N+QlXdhSWs%<UJ<mS$2NHtAc9tHKjq^tNmlq?_U}56$D3>?X>vWk2 zn8NhPjsEHWYcSGeV`&Gc7JpQpGVE(7_~80bk2yC~tmN#d^2_r5Ztf30#p5atu;mN5 zo}zXF-LX39E0AG6G2@<0Wd4qX`t~k7?B*uYuLfXC<w-+P#p9}<QxYCTg**{6(sD+f zA3=A4qI-G;tg~?q=JXMW%#%ZIqZ=RjJ4T1gc5Yc`Zw<HHjA7brt+EUhgJ!|9k)?m5 zv3Fw;JG=|YL9jIp%rA&}P&zJG(Z{!L;VaoY(}_!OXQ#85Hoqmu`6Lb}%gkWUC1|rd z@^5I_;=?lK$}3CmcqaOB|AUmYivw(5e00yEDSzka<L>g(0}J>kWY3ma`5py!k*a)^ zG@F&SJ<!5rrcg^gy>phrxx4M1u$sbNBsz+AeklQVu;6+&^on-2U5?A`a?9r(uG|3^ zE@B>R_AtMM<_m82{)ZJBz_sSmYvKD#7{>7iv3p!Q6Nu!Rulr6>ig)Mfciv{7&wgE% zayAY6lG2Eo2dZv;5DQ2cEy(?d>qA8P!BTampig_eZbSveWp4mQ#vizl<)vrj1>NO^ zKVP<niKF7xCpXSTpvsvSBAA=HoIhd^AJ!muhfY>nQ+^-yj4IG<ihrd#|CFbk*}d$V zRCA11^wGHebsKJI=qkn^U$w39DjLQqFi4!K?_oS2S8U&ka{PIJy?FkJ=I><t0YCRX z+tZeZ8<~%V<38szCWWRx=PG!#0-0Dn!}NLbp4?fl+V7n_%o&Fk)u*m!{FMI`k^M_1 zZ0~sKeh-Y3EB}jB)Y)W5%5Euaw1M^;GPhWe(;YHF3S>@7IVH~)X^(%eIJXkpFP#aF zTmP=G7FVpc6oT06_z<u|=J%m5kNTHfe8CxvK81YHDEgMF_h`8R{2TEX5Q6n0aWqf? zbS`Ec6$j<lA#ho5pcC2UP_@@#F*-ozVA_j2)?3EuG$YVxBBltLC9|D(^-g^e!t7)) zYcMZExI5yk(n4J|xJdiH%%u*`D%-s|q6Cfg6(dWEb@{bA*P;AtHEQ8F@E)k@TCKr- zi3G*c#7xP_yIUvx#k2^1?GleeRH0Gua$eAn9btZB<&e2fqR9KxC9#hdKqOQ*j_*d( z;N|70eMa@WO}%C`6|4eU<lXTI?VKT&pQ%MVBR{YY->7=!O+_1=r!}!n-jki3q~!-8 z=z3wL<kJX2qoP7T!&KgFcYAqt!NIJq!-NbUzm)Df-Op~88CeR7>aBmG`tRY-(x1d1 ztqH#kgCp;qegEwA8Un1cgw}*Fb0%pM4Kv~^BL+|P*(2;~puL6Pj>Vt4%(PiPxi@pl zq?*IWx2H<rI~^`kzC9Z+My-xk9BQ<8v=Bsr$0XEt?FLOnfd51!>!=T<D)=I{(kuiw zeY+}UA2i*-^E~JulT>9&U^6M=X2*^3J&;Y)7a)TPO=g#2n_(2LiM%fp)zgj8W?mOz zg{RRovp#vs`*~K)3R8iTMO{Bi#D|Mdv>--WLJV&db5E>|&YxZ`nUxTM(Gitw@S{~e zYI5%~?PU1rl`Q+O?jC!Onm>5)sUZ3<1zi-JsG(@2Y$R7D_uzK%KoLeCuY8@|s?dn9 zXQs;bT~d?O8-zq~xNV`W-0UY&mjs4jEnP$*9Y0dh#TMiCAlz8T_O*lI(+Jx85l-Q6 z-b|?fo}SuQx%+<HDA{XYNMg}?wPXhpF*8<a60~$}_brZ(@fN4bZl5JKhBNixr7KbL z$IUo;jZc!$6a&+RH`7uUQlH;<+KR#gCO+{hWrAA;R3j%tHe#iVEsO3ASNY7c-pyF_ zdh*=SM9Z}N@NrS0i@l2QovZz~P)-%1^yLqpK72p@w+Z*|oWZkKBY5D+<3u0f8-79Z zg5j;=e-zdI)2jpHPz=X>b#nEVuX(pIVnz4NG?WA%{Mfl4tg1U~DsV;W_kKZC$V1*u zB26uq+)C?>lA=&Io6eKk!P!qz5x5u5V!&`H+VuK*5rdEV?c*B#?#IpLk?&ky(^@|G zkNIvXsEj5_AeSLi?d5R7#jL*HUzM~|fwD1rGM#g?T2g6;KWz6x)xov74{+I#LJ52? zOS(sj#kp<K$EDGy+GB)F$J(*-qV5`2lEBkcg?O28h}Mtd;hdKePoHKN@|=Pl(w};k zJA;(o2NBXQxanBS(_$CY!>gLXd?3zeM}v||Q4GwtG3WT=BZ6ci3sW#a(E~!*jyak% z)t-o$93w}@Z*56`+Zw(hj$R{wLniEK(Z}jWkE)~sgK>6`<F3@iH~k;N?(ztXF@u<= zMkHUmNM`f#8Avv_4axb>uvLT*B@B0UG_wc-r!#bI2YRV@52i^09uAE>!fbaj9`wCJ z?gE1SeE!j~2s*YkRRCEVk08pil<2Q^>E)37&|Y)B2I5z&6K#BF(sP<iCDCq)$1by% zMq*MJgqpPb`#kt$%=jE{sgXlTVeVz^W87rx$F+O2*@=wPA%l^1T18v@V$vI_XV+j6 zBof*w9bujA3AG__u;sH6IW6=|OvBRC^Ut?LC7vxY*myp({!S@0D50U(U9`Bfb5#5t z9L5^3(j?)K7_UYhW#;ssA@j=y4((7$mQsYA<;@v7?US*I;XqNrb}S8DO`b)Z%6#z~ z*&(Sbv5fu%k*n*`B#%}fdfh^OzF%f#8o`UoFaMDxBhp8BO5B(kr);0zO(vIh7`=8^ zues;nNLT629v^j7nhb<^>a?aYSrzu@&!hcqvK$%YT(7cmfxUEAu9w9XHVeF)HPR}l zl!kGMl`^<V06*f9BQu-)KopBW=yw}oQ!nVyqL|agpjcJF+DmYi$hVP}8vB0Fc$@d* z)navrepW(5epk7;Q6Ga#B~v1Ep3ymLAN#Y2X8$@!m4nKl^g@RtGylBW0MDtYc6;?< zY8n3`YDGCeHj~U6+VD2oG9PB_dW?4-tmB|dclx07Juy$xP_6WAG4}g&^IMMkZPV7g z69Oy>DV>8R!={5-y|mZ(#vtZEf@8~4S|{i(+8A;wdMEElyuvA8y`LpjY@3?11mhdL zt$Fif|4a6c7~2mDiSQ>yZk%tpP4hKm#1$>>1k^EkYwRDt;u=5hoN!9v=XZX;wl4js z>w<4oVR?*sTh2Q|BFfxKGBM{M41$CjX_fCXU_1v(q_<LaAb0rf(r+VP1uVo6Rnt0> z8KDdCLXFlx*ql1i%gr6r9RlaI<sL#}g4>WWQoaG~{Rs+RA424SX)fXdmnLTUhJJ+z zK_`7x%_-v}ucveCo{M{SXz09?<`x#XHbXUyE?OjkjXZ6+)%0t&)2zy|%)h-hFO{v8 zCcc{V8j$D7PrPLy)8xjy6ILbb_XDrJvHqMV^?Ja=?9cvZj%->vDF$*p5TiiZ-bDJj z5Dv@2NC(j(m!oE0`{7dYz0QE&;<qPr?;cz@5Il4X6?^?U4zSKw>|fU1yQ{J{+Weny zflcRRHAvmbduv_1^+)+tiR1kmCO_uVC6VWSZEI5URi7~j_B~&AA|F_V-W+5@cP6F5 zFC_9SZ_CCMN2D1lWjI;S)nSrXzoQI2+#&Og*9ro2^`F~)S!w?ul{yvJ7pEmj1#;Qi zxa81NcMIA-gc~eKlKxLLqdq@R!b7~hT7E{gV7bZW+)yim0`B(SKdSo<zfbMP<9`}k zj=eaSzLSR)8Qk!xIXHyyojYR|ADq}bH{NwMvX;##-T)v$Mpsp{wZYS?M*wBIJ5=m- zWaRq@wLeSX*?5HN+=2L`ozFiY!_v4$I)U91_NS0=+b7fHG7g<8*TR?bYi_;aO49AW zTA2eb-zM`~8g=<`BAWl6()iDWZuoy?eW<kI(q0P|@c-J}JqDc)ivG*i=g=W<tjJ(3 zt0Yt?3;9CdKeJMB?v6<CYE)KpuX!*rXC)K5SuK(LzHN2O$HSI;m$NlJc}s+c&HY)H z<@uXA*3FdAiP3nyPzL)5>K}X(LlTx$fQ39^3y69(AKuw#%l3@-x7xOrYifI#=%bS{ zdre$%JRu{Vt3+kbBgeNG?;=T8<e@^;(?LzpMRW?wo)WrwagM(Ta2p0Fs?nT>sCWrx z2H-;IvsU}E<9#a<rPOxrCp5OJn=HzJBl6tUHNIr@SYGOM_NDQYe%1Y1(`6UzGuNF& zDg9_B9qB>5HcDsgix2w6H%Ths?&ru>q@Q`l_uHDN48*VsEAx2fM6aPHJIjV;gob}z zh5nXd=@dN&M!}1pV^E_+OD<h&EQ8#5iPfT}9)#|mWPD8r)a%mA*wMJ@QN6nkocG}% ze>IVppaFTQOINze4uwd#@SIzcw6Y8@E^832b_tHTU|vZAc9)=V+FQ0uaIU0LU5nMx zQlYvusOwRY31QmP&-cAb*O5MGRLb(w0d$QVAIg2D-BGMWACgrZ$4LDG-6?EqJmkoQ z6AB@!gMp8i=uOkb0f5G)IaUZl``5Ai#QmytSK1_X%;9}B0VIiS<aFg@zqc#$&)2Bv zK5clzAhkN3lP}G61scDSQd<P^Rd|QWZmi`D&3DbAM64von*r^$7!(k560S%#)qh=? zd(NuS-DumnPG&R=Gjh2>t0-CT<|%_-s!c3TY#EI^euFR_m$NwQL-od3{{>?j^wVZU z@$)pQT-0W8RDwoa2&tf0k-<QLJ*-rZcb%wAj%R)U{Bd&TJ!G6b7fD0NWS*yHf0WKV zvoyQ5lnoSP8#V0Pg|z2-73=US{+E%@BoVudXZ8iTs2Q{KUaiXSXHz15j2*9k79T~9 zm&Xp?b?E6{$pTF#MXy7|lDb?D%3^2aAH<ZJ16OZv$^l1%wv|K`5|uzDjSy2YK?!0w zG3E$~Gue$5$OQ`>5STS+oFTN2Jj{8Tr6+%L-}My(C0g`*Lg#X`WYa3LI!(`8@4Xmd zqO~WBYMCnrb_t(cePxXp)tMn;5j4ON0TWXxQac>TAap7-CA1i$4T)1n8^14j>5R<y z@Vm?3gAw>8s5Eb3tVpMXEcRox{KBd^&Q14#jc86TH#qIJ-UXk^5QKICfg{4Mmhrxp zpw-N9&^*y`7ccP3a&86OyG(f>PP9D&2Vm4MkZD!Wz$1@@2uUHJw<0uj@MkG(BB{#= z+!`_(XM@$xDZT9CWQngOn)~8eu~h22_-Up%1pC}H0V5z8E3gP+kTW>bx1=1<=8R9^ zW=8czN$!gz0~>2$Dn3b3$n=fLvqCg3H}!!gtq+5G#xla>p7!}oNy3|z7)~-sbrGa~ z2x5X$u^?^mqC-}r1jn{gj9R}nxm2;>wY1%(4n}Kv7Rd-T?i7U=vcy5V)47%Avc_sU z^LdK*S+A{mBijpo6aNY9A_0XMeRB}2B1y1VBm_qc)U(aYP``*2d4+`(9p>98WIjG^ z0vju5h_Vj2_^S0s(~fpg%sa+@c<35=DCuomT|83omeuv|$Vf)w05$Ob64AMVc*-;w zyGzvFcw3F8RpOcqF-QwSf+k{2w`SvwNbwud;(l}8!jseS{*o5a*SsUIE$~6^YfD?s zVb*PvyvJBfx7(wUcy~C2SMfS92Gy0eUX3O?`qG>ajSGKF*Ueb23uq~|FnE*X(rB(0 zcPnJ_kKZBz!fZN&$A0U`Sk0;jy%GDI@4JR~Y#3PXw-i<CdSW1Lwy{*k+GX@dnNr=r zL73lSX;x-s&#_2z3N<o%uj;o3G67<icxia#NKfCsuiL(15I(hDGWdEdp4#obJ9Uf; zGCm^8wESA?UrAbqrHQ3}v<nbpQb{A@NK)Bav^bpaIkfAcSy`B;dDm9Vd&QxpfVmnR zL+iPGMt&M?ZS7u1V-CdF$LN;MEtQTt*Ke=%O{`dBb*&cTLL?!7&1Q`X=_Kva?*^`H zuF>DGBs|B8^o!bK6d(pkkVkJ_9=VX7xhtMeNf*C(|MX2+Uo;tHT-mT-z})u>cXw%G ze}>M*xH6XVK6X*`V!<4s1zA~M{c?Eya8>)@Uy0RR?OW{1!qj75tT3P5hbcH@dYw4% zRw9S=!G4Vry9@f9^)Akz^rhw9f8En0Y8rn8cy_n=+t$!l(8sT2t4bz`@WnW9$5+kC z#;OF}6&%T>6PuQ#OMthV&(P!wscH(jR+<;&x?mfT*w!!+NKv=d6k)k+QZA7cbsr)( zK4a_qQjd%92UHO!<2LV+@NAh@Xol{mx!V*uix9aM_ea5Ei}L46V^TL{hA#m_S=J+) zQH14Nq0Aa<L~e8URW21^jix;ceLl+=?=ea-Go8@mf?yh^kK4!M;8PmIV_dW`29+z0 zkoZ4(d^y`}FEKYdg(?+$7@xr}bWk5ET(s-IEs^%oz#4v4!}e#5dHRg#^6F;izg5Ha zlpik8P$XTN-4%3EvddzHQF5=5jp2$I<YF}ax!cv#OUd!e6|IM)zPT$d-nz^uVE3_l ztk-+n)8tt_uK_Ftw=vX$P<?;TOFDJa83B>$Z{prryS<DJiqjyDdM5>mV<=8Ktu7TH znm;mRqabHrMG~8-w^tE-l?}4@b}+EW5_d!h;2{3)a1Wx@33VmtKxnPVTfRI?o#yLt z`tf&tJJ}z8N_6o4{Z{1s!YGk-+!;l)I+MJvLval1!FK=aEkrKF{sP+=*ZQ6*$H$H5 z;=oVt`$ol$w<Tyk7~HM(s;;1p`O9vXMB|6s-Q)S;OUqBX=AbLvxdRt{!D+rxBuOj3 zRhYxUIKB>P+cv0Fj?eNOxFxVRgfjCSx^j<y&vVtwx5TShfYixPL!R&*A;h;tE<wiQ zr50%;9iZ-U`_+iVE(h8e1|GJeo1z-5w>tbD-)go2h|Xlf-|zm<rgxZo+=4z>;T$YX z#=#bzy2B^%SC$@MXZR}S4?3qSC!-R>Fxg>|Z3q6^0KAcav<w~gd8V?T92po~zwn@Z z?M1e^q0=k-N}6*Db??jJS2yx5&GaP6JH&Og2DC6%gpiV!i#Gb)8!uXq{wg%G&t?m0 zfCKNKk0{Flc@m#?V}llrlP?p}(ru)H#nI7mqbKp)F?bK}Xnwf3JY=7w4B?KXIhdBy z?D;TwvU`oPV^k1q(L{6osQmSU#Y;)j6OZ5`b<b^AZ9t9o$AB}TGUREw*WvVZ*Oag9 ziw`EkBuC%PzPav4OgnTw%OT?uy!0Ei!KBlF#&b|Js4mI2)M;rL8^0#H_^_P!lSAn~ z_Iijp_>t?fEMy@vv=E6u7dD^cf5mtmqNx;++U?Nr!>h_eQdT6;CWOZ4#LL@L7vsKj z+8Q70-+SI;8djE@(p_3--W5hrGq4<|(a9w+#;Nj@2RYu-)#7M${SZ9BK=X&!+s@x* zmnKH@;;6Ga#UaDNTTpjpY03h^2@&j73z?bs)~P>yr3|4c6${!&fCpKM5hn&CwLiB; z$kW&}=79eU6)od78@lA2Z#7rcm|?E_-PwX@@8<th`JU!L8-DcND1!L@)H$AV+?@q+ z;f1KR3I`r~6OGNnF3l2jzGYyKZa#+)tl3!IPO%U(QX=WcpAqL&2yA{+kIVPizS6@A z^2?p(AF>eh2rYlm@p0itd@mo6D|W}3@qQ(7FXD^W(_1*Qc^ZVK<v%}S$dqH2FSyI# z+zbo47y3Cmp0w6y(=~_!jyemnyb}}xT!8TS27P~5uuFr!(5ut9H7mu&v_#l-pa1Uo zBSDi@(DN5jiBbLvT}9(9!HF}a_jf=YE$(VJKWmJBp?nHck-bM~GkH~drxMI5G<G+Q z>sEi)uC3Z$KWo6Vmus;z#M=Xwo^MOgoi3^W{54v=v^dmZ&BR#gNLRZprK`mls?O@0 zq^tI8@Dx`(<@$%^qd)RA7B;^v$d$2H_R#0ZEF=4S5AIlFo_@dg>1q?*3=drq>E4e8 zI++KrYw4zrc0y)`i1iOod0s6NgCWde#19X5lhw*Tt>;Wi+`8{z8W(BQBu0}oG=2WW z0`g3r$jf=x3ZSucCB1eIAgK*eer|3VdL>lk7>?YJ%iZs;&}(YBStqFF<wBy2gaDN^ zgLE;LqqjzKAVIjlj@XA+;xG9-fI<RZ?CL_MAGzK?>NI=*;Lc-`lojb37s(lbSOc`I zvc5-aeb&!_Mbz$*&>)Fb!lu^uSa>*@c8}k@;#g#qENql6n=mWzT=~0sQ{bM>mOAjs zy;Zm@q*%{d<Bt6|&m%g3TjFBTeoZFBGTkH~;r@-VmA2rIYwC6WZz<aMfl>BvDqp1+ z8{9`6=Z${II;OP%E24Q)mxdgR*wQ1m_t{pO*$y8}*ncfhjX3_s`rofF0qf_3iJVt& z9Yn3Q`Mh-fz9-^`n2s$|$qD0<X8SZvdkre9A9{84wT9JiCRK&c9swUp3|?^lQv4Ds zb93{{;U8)3)K~Et^BQn4DOO^?p}QSp=ldksBCp9z+b_H=DSgEHG^7r-U#V+DN0xF@ z{rIEy35d|kkBt~kxH_HlSm(dLtUluz73aE!kD0!KFf=LYV^Y-#8wnDW7#oc5e8Tl{ zr$D_c^GH3WEq?1drHVH`JVc-ISeiT!%SXvW9#fj};Fw;`%@ta#!;Pss<OfRo5X5C* zcM}RoeQA5<2NCj}aRh3wCCP){rhBG?>%>gLV&I;GNPE_ZH$D+wrDV%<Mr+&DV3~)T z8%bMT8B;0xt(jRNpyCWmjfVES6~Qv>c-o=|SFWSO7`MG<L;*JHUc>_?YNR0eSP{eT zJy`4<2KtShM}}^tC!mDl&@KtUyseczO5S@akE${eP`^_0=98IopN7l>M<H+Ny2q<O z-_Q&E!fYWm5XB%M=d2eD7>GI<vXpaM$FYR4*~QTV2u9>3h(VsCB<QXq`AKqJPIdL= zVTfnFJpDVt`n`_N^Ypq=z!&6U&u0gLRJiEn5)!IuR2Xnp!4ww&G4#NbS{%Jh?P7XT zys3Z@Ss-*5Gh9mZB<!pHX2}hC>TiXY918e6z6~MwbGyRK&f_y_0mS|Hj?W*-a(Z*1 zPN~UB8K5UNX5PA&w#N0?neF8C?0Jrj^sFBi%tp18oGFgZc3sVyVp+-)(c2+0Alq&v zS)>Vrv@cTM{^(O;&}pXQ=^`OE<{L7-HZoDBwJ<C({Qgs6hRSD|pHBUkbxPyq%cGX% zCIoUi{Q<wfzoxLEx`SVkw!m82_7k5iI?;lRy>{1^Km!e{Zj9TYT*U9X8&V7$-?$G~ z&$?A#M+n*tiW{Y|DL<%`rdH=V-O5N&UG93rwg)Cc0iLeK49mhPC)f)n+V7QD7T>*t z#5@>1o%<ts|8kGoQPR8AytTxP6I;EET^yT<tEo0K;+)F3yjuCCUD(9cCdJhB6br$i z6GNTd2F5RUpT~mT@X*Z6<nn{z*vrROQ_UqwaY~>3rcFrUA*|(-T+BedFKh0i&x`M# zo9tOfhAMD)jMhbne3qP|28rtSlGRhwXr}yp2pJ@QGm_a>Fp|@uiUH4BifR<6N}%;# z#RgWZ1Mn1Ml~bkf4g)+uL!59)+N+-we?G-fti7Sv<5k}wSAEYV`Uq9B-ueN1a4mz( zho+&&$#8QuMSX=5HMJb3YSka3hMYI`nA{!ouf@+8sdRio*2h{gXLB)$ef=eG`4-2P zuE13i#=?Y)F5zH4Njoj7FiDyBxbE8Y(a2Su;rt*fE|lju6LrKo7F#%~c$5nbs?}ox zw1j}?Gx5sObc3~pAfF3=e&Sl|xbsw4f+i@YoZ*DNh+9-}y3qR{B)#V`8Y=G%^eQ@@ z<V|gzXsvUx-`Y@QM!U-KyoQXZ_k<2aL1x1ns<1lMbe4|Y20~0c#;hT3WUE3P+gA`E zJ7e7!n^>A}ndbf;fE(vDyok=@x}+5fdK}d&BEA%5sC4f*(bsd6|DPzoyX2WXCf7Y! z^B671LlYy;USdKgWI-;KdXu2_oGi}*VYi^-mrVtmyN%OM-}_w<>L9|S@@-gk8Z!7F zB%Wt2<1NN5l0TM!!&ANJ6V{*ynpn?81?%Z$jDOwEvaZ(SH1<l!A(g|PZ__E*sK;OV zsP_2z#YOdZgpv6=Lk%VdhX<|4r1MF`ZMGs1Yf)A1e%`Pbwf$Pnfe8|ZRn}I42bCou z267+rpGE<<^PS6#Y}qPd_u3R+{Ay&pb$Ft~Y@ontDjPJ|>-G4(w~E2f^*n1mO}I#4 zvvlQlO%T-Y@uf77&kwkf@v|BctEDgm@u-g7>~kU={k2Y*dYr^b)5x>@L0evZIgK7a z*HD@&0q?$8oo0=jKv0}SmcnZ~aVmjUu0aVM>EMXvNG1&8`wRIo8e6j~MfSTWfgQ~D z!|(1QwVuB$pD8Sg#vvds(IwI6cMM2R6!`2lBSoIrM<n`&&$?uXm=>QLhPbIP_25F7 zN0i15;AagaDEQf>+6$8tU%~3{B44}Ti?ouzR1!l|2YZ2DqO(}?kZlA<ht9$T_aQnf zHrin5rZ<y3BPszRUfb-Xah!KIFGW(OUb<suAgjCigF_KD=iE_P;p?WQ+L^r$pG8CM zU7@!~UGWeQ%ONsagKWvPRqWGh#q*hkS<)#}Z1dY3qF{Vm_p0N-^G2gcMjO42Y{$#= z!X&{!1yeEc_P0Ogh!*91>*>2V7!Pjyt7$P@_Y>$v-NQE#-8<W2f|`nsOf-=WdVW_& zd4OyI;}Gs3!SG#u&bq~OuB<1ErTo~PXtBP^%G+-bcz%Bx=2ZF7F~S-ITcse-NiQFt z6sJZ<ElZaiNnO73hE<B=;+C&+q~!QP7O%{TqK36FAd4Kw8F$RLjWadqH!05kkZ*s< zM9leM6QbPTxz52tR-)5{XNfLsCB(L=tajbHy{FIPklk+bUtA?W*m;e8Dp@l1csik@ zQ1pcO200wPU-E3I4**aK3TX+f?>lsrM}}kv<XBx~{V#35IWvf8;$Apl1?YV=OvXD4 zqGQ+({f=2-sn$Y-gz(khzKVYenOUV&67K9M(vwh)h|2VpL$_m|7totouQ8v3pRMR2 z9+cR&?(&aFjGHE%b05r)dz3a)*%DE`x6)YBSNVn>7Hl}7D)0>&-yLaVvaYW)#A@vi zjabeq{>To!6;#WSR2j>Dr!K7#L}72apa`UJ*wHP0=E0fx@yWu!vJ6f_FotnaXBJ0^ zL!Idxvviqxiw|_fO;}IE$D|zHlDbVFo$(x#LMPLiw>ou2L?SA!=t3DV5v^?XT*S4$ z8-?HF)k*l@05a#-$_M&n=7>U*7?Y<aAPw1@|D*(gzd8E9^sv_`6<Pg}x&4l!fRl5< zBK^(6(1MpwP?3{GK-{30^RNxgGHV@9iEkz0n~}J(;UB75ZWroc_#ifL09naPw*a$D zrj}A7fZ^w8iFrMS{SQTl@0J7Y6{4N|>RuZ!_KU)k+W!?=!kx5dZnDfVa`S*GDaAG< zYANTZ5ZB=nXX}dj>Es7X-b;MjCV3`X{T%O8vWRGE(^<s`{q<ru1LKT`Py#PpNT?Mp z*W1g;1(r-E?M`tf$t}vty(JtxiKP-eNP!q88ySg_X4rYBWH$^}AliYT<=m2MyRl01 zMfCp!EeZLLmGjEwax;lV^zLXmERGpGX`DRbAB9rsx+Eju;qfg8*^Cl8PWF&Xlabua z^BUS-(pU4upC3=XF)z{QLjZt?v6ho0>oc9?@g*UV#FPP8iO3rLpd=fEwJ*uLw@3<o z?iRPSQJ#il5XJ(`;7`}UN7t-vr)<s?X$BfaP?aL6{OpS$NLW<Nw6A$h*&^jFN*3bE z=U!}BYrrC#NbQcMu4gAUK24PqMQ0Y8*bkNgKpY|#hK2N$k#y|VhdoRAaA+tKN<Mna zfZ+L*22WL1iXMGe-=@cFH~4^3`iGz1j2X<2=tHjMjg6H~T_AR8HznApgm$T|+y^7k zSasSmjPRfkPXg-=$LqpdQN1X=Ba?Ckx}K%ckR|<ViMWabG^0Iu_5cvdHFC5Zyd;$+ zxrXbL+D4^vSFkZS_wu0-Z&fjC!otS8aDo#xl7Fy|8NJo<eNHYt+hy>4-M9e-4=fwG z29|HJLWqBGuo<K^?(eQEN5_Z&^T^>`=l(o>m8f#rYVyA-H;IE@K>$h}mSh_=Fmt%( z-}4@M(1)Di4@3=mF%2<$0stGN$j|$Qwa81MH1>x(Vz^Sd797hOH!xjnP&xeHTWS+w zi9m1Ox7t2>3M2G(iA=q*JPLFO&mArAPZ4=T=1tVDse)MHw^7u9<e~`rZ?R-8N`a3r z+7&IR<BRSU6`Z-~IqN;VhZHF6muIFtn%SN*agRq4EDt!GZ_&!x6RzNj39Xf8g|S|& zLuK>V2$rQO%?^556$iQEn~UH{z9C%=^qM-GE7)Bf{v^r%obZ^z*ED?@=?v)gdWx+P z?r!8dGY?iedt|1N4PC)fZ8#otQ$JHe#UhPs3|oJ<Q+leaYyDo#Jk<jGYQj8@{dQ*T zUokyd8kK*mInEoGi2bSref7!#^^1_6IZD4S%f-G5W9Se>9V6X<b5!)Fl+BtyERc*5 zH?B3{o3wg~sMP!GroY$kN}p3KOz?2)Pv7t}?Rm`0)-Oplh02`E%yX7887N0&@u{S_ z+OOOl7XoikV~VQL&dX0a{3HO21peYe*Tq$Syrl6`{cS09CQiQaQtWrpL&-s>U))+* zqK!Nx6*+K5y|?79K+XGIq_YUlq3oI|n6!(!<9S|V;NX>Z8*k6#-lhYV*)1%_`8zXn zcFst3Sjs#Xuk5Psvj$}K=BF<`!Kv-y2Q~79;{xbg_Ify6Sl+Hk|4otYt~n%DcS-+` zr1OkwqKnpWLQ5zq1f+&Q0)*asl_c~IDuRMi6_65&bTpxZl+ckHIx0vN0a58qK)Qe} zQ~^P07EnJf_uhZAX8z2YnKS3CefIl2%z%V?!pO|0COYe7@Zc?J{36NeWyUJ8@=ac$ zOuK#C=0fY9q&^9s?L6v4bJVA8aPuJ_k?u@jeHm{p*Pspj(sC~z>g%5`5|a#5Q2Msg z^Z(h<s~h{2OEy3_>D(k`W<3U@<IX_<>nt<7yY@Bg>wR~02jV`INm0%RSM0k}aAfHY zNRMwx@>5-#eZ+<x%|`$E7Wu-|9sM~=*?;R1e4C#QWnX!CsS3s87a2qLefnb@M_11r zWGQ&cp&K2vX!_gUt9w0qIR)z#AM19nh;4uP4ENpI!NK(k)O6!^|AVL?#n!PB*&Sql zWs|L^-<q91esX>~w_1I^JS_F#|Hd+4yFK7UMI7+y4^W?y?Hb=)aoaRma&lRj4P!ww z0Hp?eWhCmxb_nV|c|Y6zcRUI;d}3KJjlGkW9P@POT~dF2?ms>sSu$SeaE8}ZRuK8H ze4mZb+1R&~bYSY>somtcC;?b+><@k*iwECM1&hzoJ!ed&Q##-51j2srfg1V$ZekPj zVs;H12&vyCmGxQNjA*&E&%Yl!a9)R+`VHdpg7W0==cO3BJdT@tNLd!G;5-9jx6)Wl z!8q|r%O(zS&NYp#g6#w;Y)>T&RR4)i??LX{O$qNgCX^+P4)LC@^VG|Bz@;s{N|#34 z-XL-fD^y+)e$MVwvs2fbKxYZ*gC1M9eUsi}@Wk>+JR(765Z|v2#31E}Ez<<u%hfrM z19<4=^ZVvyUF=LZX0E8^^d&^>&cC>F@QP(APr8M<F|)>(zIGkMaH-|{g<g?$x~>F6 zx>W-y<Nnja7Ac-oF{&(kQQ#x5FAb}7G2`;nGwI*=NFV>E#iZsY&(q01&vHyTe8nOo zU)G{A=HI5sej|j_Qie|YON;{S;ANqKifjw;W>CM=r`8(o&p9+p_cJ=nM|j90Bvyx? zVU=@vxqsUxXkwwSja^@0AL#hFHI0ulfd+r3ZhhXjz#8Lq-qC#yt7lo}RH5DZ-tHf$ zzi!EQ%$z6O=Sz?&&XbnZmobmwo9i*VVJ;{FP2RP@HpM7!5o~WMFJVE}J?jCErd<)o z)}tQT+k^)zjJ4Ja*ew!>L;@86^v8OH3J`83F|t0f+a;w|*EcIs6U@?mCr;18EtD>P zPZ<b_RaQS1htq+J0mz<S<{Tg*jKqgb5|1aS#Z?1;)M|cBMS;l!^EJ#PHCM|Vv<C=M zcL{0?1o;6VcuNmCKxV5W^M&cLGsH5)9M7BtR}YYRrO!x$4666J^oeojJQF%FXD=EM z!?q4YhLOB@ru0vO{w$Es13~Q(Kbx0ElT%}L#bZEWy~5&s=wis7FWm6=AvofShiY0t zq`3Q5zi=1;fsDb3_X*dlBG>6(B$XqJNH9IoLFv$L6%K_067ydGq6&IR3V*Np4KZ95 z>}ZBF77YUxQk*H6V-|f`6=Ybfb}=D@P=mX<Rn2)E^*KaWzhA1mPt=i4Au6`#zvm&h zn_++TeiB2;Yei}%^#hZlaYnx}Qa|DopY!74@3)4shj+kO!Q=H+7Zbwf@BY3o_gq#! z8TeMcy6gA7-mpaeUj?h`mD}oZe>y0$Y81D#Ns8b}{)Ns=VU6s!+)Rw~>1v%hVg)$; zlboBK*~992{u=qAo%#1Q3KBaDGBh6McRnoBD6H))Y}6=v-dXfoqj<Qp_^n3CyUvo& z8l_)4OTTNB{pu_`)1ZR7s4&g)bDz1OW`$T+g`8%kT36*o%_^g=Dl5(Et6kMMHEV8n z)%a`HR+hXXv64c&sM$a~wWF>~^Kot0<3`OV&%2(y)~p}ys(-85@UE-jv*yz;T~EJj zHvZ~rJkx9fy=a1IHFLjc7Sw7Hd(k4N)vETQ6~^pyF)|>&i}BeTEdb!+QgF!&_Ghga zpB{*MR9(BEzD`}g8i^jeWHh*w6g@&eS#<`=lI_xFunTFtr5;EBAt&}qeq3}<Y(i{W zSEE*1+vr8dSeNYNN1r<-r~9?#;dt*_f_@}!ao9PQAh+IwM2eJ(f7BDl>#$8pE-^n9 z`Fq@JqABmlQz-J}Ws1o_tS+$+`MVFPPp8IK-m_-p%lknSuK)5*mX3Ipl1Wq}EJ61J zS&mrbpdT}IJ+6cptGh^6s3Pbv;6-u>+I6x0UqL&M7W9JYwMUYYQ(wHGQO}<rj*T+) zqC_)wl8+%z&^|_2Tm=6U^iZEpc#EJxqR*-b>lle01mQJO3A#M70*mzOVf*QeZ(i0W z26z^tVeFgn{aPb2XzGN@fX-^=*;;ZH;jRR{f0kZj;Kd-YN3B4g-78*au3G@PXjuG8 zJU@1Rm|k^}tU`UU`yQv5Ll1;D`S%38+n?7OiB<LN|JWO=U8PeG4$}EcuN8Ms3qaDM znP22s-Bw%57QpGUSx?kmC(eaFhh5Q4g|@%e*A<~h?I$Syu(x*6zu%!P#?Ti%{^xVX z#o@VFttz_FAhu23VrfTuz4dHt0}2oe=n}ZxL2)4@!qA2}>Y1(v54dHPTW_Bu8T>&% z%ITXjQ2^73RhP@1SsrGYGU&0^d_`L!z#?GaO+E}uDgm7xud3R*>6GfajAaj72%>Io ztUkJQRrWK#o9X?ZbA<tCZfd3Pj(Ky8a@O!^*QaZo9yS)e3IX)Jq<8*yUDx+(A8_in zrSHwxY{QcOw0={&qM|Z<W}hDjX$~Pz5P2VFN?!$>9w$fE|MW=L2m+Akg|5h(Jp%0^ z+kRaV6gE7qcsy6vhE&y>T^+o1P0d<l(LwCb9`>D+ec6d}$k!otf8rM}t%X<+^`m;r zDs(3LRY`?y@RwIXMv->kTa<=)$EKfHM*T^+xU$`POQveML@pzrRryKr%#73<2_rec zK3J-HY+U1Ub=i3eCtt5;8UhHP1d=$47=o>yY;t-}zD`>wCkRBV&rRtk<~*nsAS{}W zP>GTZLPJYKngLpoLuV@zWlbYXN!t9PGfAZx$5eNv-W`Wc*5m)^XEcJ3SJt80Q4el6 z3%c;_l=EG;ecY#~9zFuS6QP;Nua)%(^du^0bra&#G3r~3Epgv6VoaVfu1u$mCJJ}} z>Yi9W_<Q94WQLX*FObMm_{KmJG{18(T(%Mm6`T_vDh-}nSG0{cHA^h@J!ij`gmV>& zm3bWFYfCMg{{~Aj^{%XEMx~-LynYLgtQu*PUUNk`6h1F}_~tQZMaezwpu#50A~--M zG7H47T_JJ1vLtYgDZ^b~3p!(U7If|<I<!scPFGdD`aCEn_kuhDk~>j4)2HyIp@U8H ziBR-^<3>;2HqQ3UgvH&c`o&I*0Kj~Ns?=}$$84uiv&+EW6+Fixc29&~riQyU2KI#0 ztCj3KnxLX<n){0a)o;{I<sPH4lyd8ZJJQ~3&x{3c?v5BKe_S_VE;dGyAxk-0H^ddK zzdlRMdtS)2yNJL2%GheC=F+X{xNjSW{PP1lo!+@4z#bUyESFJI)SQH;qr)r?rZvC& zP|Vlt7@#-T`8LnkX=r>JG#)j!f)#w{{GO#G%Dd36e(L9&MEin6GGkxP+`N&5<r}|k zeEFZ3YRZ;8Cka8Vpc1WOV!P_rm8GRjgC4&{`oH@1xHz?tT&DX1sBqhWM4dy*eFOfV z&>5Zm1k*E)FLituF>#2mB6ns^5{?=4A^;)m%pI|Z61PS(bno5xI=|RGYT*;e|HQ+u zXXz9Aa8e;X{BRU0>6+VgfDIcRK*hV6Yt&<8TJ+s5fAXYU`o^eM9Xx>i*~D_IG*NV| zz>U}<W$gF?Nb+$PCvr$Ts#6Sv|E$Ppe54rdy(%xBVXood_XNpI0^83XHDW>|r=P4g zr-`Q0yWMvwG2K*vMgD&Uj(q}?u3}w@+O|i-_z^JTvFo*ij;q=US!}z$8xV~HPIdjD zT;WgO6%IWgs<c%XHjTteJ{=tnmYu1ITI}WKz+0Brxq{rnp2jl1zmYvccwnGoVHaC; zCNvJ%XB+295O;VmI>VU-b8zezdgC&lq1sB2E)?|v+2rod<muw9@gh|YYx+%gjrIx9 zh*Es6ZXG%ys;VKFWyw%?s);pm&^zZDL#`E1Z!)-g!1QGgz4{dUg}Z;BVt${D;1gzw z!d=$!J5z|m-Gj6yhCancObz}XCoD)rSb3{w9p}u|$>Y*2;G%K+=x-HUsbi+rP9a67 z4=8_4Z%y#H95i6+kU1lwFZ(WvGoPn2?UsB)fsZz;hAAB>X1r4Pcw|_$h6D{#HnnY5 zmXMKq#GX3ci#XQ1khg_{1#HD4V$NgjzeoF3KHlN;mrrazW`MpoC*-i72&kW(+p~RW z0kTL2k^)m4*A0Q;*nIvmDSkw{`y!eD%g96gF}sFbNTb_WbE1~#O8Pq+&Jw2bK`qw> z<8W~?!3mO~)~5hMXik5;y)U>7uwNS#wN@J81yVM>Je@cN2Jrfh7;T-Wf*f0`)E|#8 zN+%DvX11Xp<A>N+AKNDn+zu8$hN<nYa6)U|Vgy@<mHEtI(xWigLY-i*d{%~*v6NJ# zYZWe#klC8Fj>t^Pt~Fg_)n1Q#c16k3-kd)(uBt-dz#4j6I2ZY<3NQG5%TV2K3&O(4 zBrNzQ@!jS~mwzgO<GXdOCvQPUIGr={%;tjJ7W`V?$hzX;s8Mvli!;RKv}qR@?*+bg z;LQgEwQ35jGx2$t@*n7Ic9zrWC>Of)kB`?%C<?|MRQ&vJI)K3K7N%XWC;XPz0d$sj zCFO}~UWkY)X20&^e^XhrGNZ9_hbCXG`ls_QJQMF|I<^WvE@uwi-^d+%V&lic`dL{2 zhmh<<GQ2NSRe)fDnkh1XMG(Q!>y?*u%7@qw(a>GVI8^s|a!meUO||nHbf2(PeC)!e z9Y&9|Nlyw03)El=IJZ4f(zS1eW=4&#-paotOGuGsX95bTcwaNNOQ3uIMkS44{tPUm zS;N^S+0Ppk@1(m^0rA~(BS~@Iz5W!<8Xcu(taj{2TJeDopK-lG-=p{({nc#j+QUPa zD2YN0nXs!3OBjuoIKf@AOTsw4j^Ct;X8%wcU}$@i%w<s+15xo)mx?her)tcsq^WJ+ zin_3Z0VITeOVsxy2efAe{wS}Waj&+^s7w64cug$*LM}R<KT)GDvOtFZy1WXD+OOS% zk0Dik$gRLk+&JUa(9<P!G25F#kD=-)PmFSho%}Ea4~^F57tm!W)t<ra`GQvjA}WnC zhsZYf@-~I<EXL~?JoJ32eK7rQa+Hhz<6f-1D_2@8xHZQ>S~~s#$Dd=V@WTVJB`t24 z)7`kN?D6McTVT(VB#x#N-zUK|BiGDVhD}<5yjQfM&tBUT%vNYSD#%>fk&_NXrI=ll zT+X+v`J7^awt(SxyaF41)#uKxCT_*&BFU#o{cm4RtD@_KlNmCS)Xu$iW&i=qX%Z8k zw(a*jXCn8VS@Ornny(Nq*L~y|MG6mDqU1NetuTet|5L^ICm=lvIZsAcCAH_H1wF)5 z_uGQvpVV$GRtoetnRmjxX6g@u?r7nPqio6WMFm5R@5Ds(j*DH(HRV-Wb^P6)cKe~f zk5J!ftZomOEyYhMB-2rGG*%?{-ko7n&@E{kbajQ_b!>@Y<#ScV0nh4r3H?Z4qVl-+ zOP{M;gh_Lom~xh>As-#G9tcZ%{EG{(OnI|%b`R@WXCT@_Mv?qZ^!kLxR*(e-Iawa! z2v4sC2FloqsybUWY5iitnvm?bQl>A`RPqAJg6Qgn94eo;onk)m!y8Yid%BDHz+di^ z3oEj||2-gE2sC;H_ordjkW%G_+of9-TQj%~FnUSb{D)A5u-@A*yS)mkF~}Vpm~-t) z79$<dnK@(+t!^gL-PE7*$a=rNb{AN<8ZS{yCz(}^x$(wh2Q)N}AG~HQdYY<Wx>h{5 zd$rvQZM&wnF3nkKAvjj&wWYtiZzz$v#@~njJB}U!ZxF;8l#YQYg!jsr6~_S3Y3TdK z!<8oIDg?7N+OC0LHEqRPM2?0VJ)^}8Nj_%d2td!cBu`SC)l*{s?gZ^5@J;F=T}|a_ z`w=rtXIPAHiik0kMazy^AY$MsCHeXxu5)>qO${$-+aFkA&@obb^VL40nf%EfuMGb7 zLt4yOwE~v~giXpiY>5bB4|q2=R*eVv1S>Q+<AqC_Ui+=U($W9gvGO+_nb3Bu@R;Zr zBg2}69%O}bpY^EUfp^ljG-CDpA>BG>y>iX&&7NlTF%J9+n36g!wAssl*b5WF36>fg zyWiQg^g!7eSEm|O#^?)bvjC>*o44Svaxg~wB#z_qi&K+<6$4nsX$+O&v)@;=D+8CY zxhM}B5k{xKuw|jijyVfn#dVW^u8*VDT{_)u?MxX0jKwiGCKA|s)g67MW&8Qvaa;>P zK6fCx3tgy6!Sumj7B{1F2!e$;IrlouF`A!R&ev*->099iI6DW*w3fo&`w(-DzhkoM zP?ID+EZj}sqh`vP*YWX|5GENwW3#Wu?2wZcg#}X6qxfu#hGa!ahJlwW)Xp`69gL|g zz7a7E?nx=pB6u^}?O}%VCQg@5`9L(oI-VudalKrBN>rlARIbKwDUOJ>fHbIkiM8Q) z>}8zHpXP;B5Q7P$hpSinYT`ew2(Xb+b1;l@#rHzof@2)*8^e39Z<j)RHCK;jyiN7O zGFZ|)c+a|eB3BIuXM8r`))NJgRkoNb$LL<3AnD6~kd$7w6={dK9o26J!b3*bn(}tP zCkILK91L-0?()hBF<+(W_!;8rmV?kq9-TMpe@1v*qa*WRL>SYWGo)*OiVUd}{D=c4 z`VrIS0?Ft4q~h*d$nLK%yl*d5eDzK@76UR7?u^RQ%288h>}DXdPv{03S}saIM>QvY z&N|vV1MX}iJcARU03nj}?-xBSsz7SxLF7#`s?G({-itDg5kRMh*U&5^E<-kG5@nW? zBg)eLaSB}?eBYcOE*e0dfdNV6Z@cdQ*f69?B|8XSU=DImula`cW1P?CL>#36<zjM{ z+pOfjYLV_~IkaM)<-*T6PeFaF9bd6>kF!6(jvS*G0M7icq-1Hhidz;~%@{}S3h>9? zIi70Nt6t>hQ{Cr@FT2ZipNrBYB{cn;dbS?yq3|0-J?xDiLB}rYZxNS9(SnG66u`#$ zLX1v`3#4uyou??su!2xEu-j;~V4T+I=;i*8#7`^7k;Y6r(eO_e<*TB46>R2#7`<X6 zkv<W}^?4!83TB)EKofUPd>d$QK3kE^{{Hsrx{D9#!uxCBh7Uk$A5i05%(oLH(q0>n z{bn$ffmXH_{D9-I_myjz_8P|t01SB*ryfaSkpH;@xNRJyur-S#{&PcD&b+v!^Ktp& zPx9NRCCU{m?ZEW^Bx}O(VCT$>UQI~VNz{9K)Bi{uns=`a(jna&RsSK7&cI)f=PWt# zxAzwMySETLE4xvm*n2g4t1Urq69{1GF_vn4KiNAu^Wv{KsUN_Xw4JMl*<$mJY!@)! zc6Rn?<w%}wkuMxbnv1t&+)(@GU7G3qqN}QSjQ(<;(5)()vf)4Ltin_d1Ql`#Z7FZ< z!M#OA>BdwXlDQZ31gCC`qn|29Jazr4WVO4ZT<^ltC*vSbC|0cWv9yzsl@^qIm$E3< zdPp{>w%wCy7ZQKI?j2W<Lx;Rp*=LPy#m3JJrQOxr_GC}ClNrFC?aas#2p+TO;E$Ci ze7~|ZM-3Kxk>lROH;i->T#%NRB<ezuDYxZXG9n`L1vX7FUAW>K<-8(o{Bh7l-CIc} zRirf_Uq!i%Ca26KZn=xFK4*B(DeLYCw`7`mb-^K9h)X_2v0b^6wQfZ6rbLbRG3&i# zR8lCKsz1n*bMZ_{u)>9F2Pe2_7uZP<aL@BFsLwwyzjYg=iKJP4E8w^`6*C;;0U)^_ zh9-FHTT8~cR%MgH3_5>PIsOyU-x$2)`Oa^mmlq&c4KOWM^%9O(mK)rb{WSMHc$ie9 z5T|!26f^$UwwM2$5&XP{NU45#!$@weU4!c=rIW6N%Aj<HbnCOHGtCp?AOCgLOIWZD z2symq&yA^RT4PPRbY<7ZzsIOjUh@8T2{q9Qp<AZVS0u<H4W^)~eotSpeQY;k%I{$x zzK<@bl_F-p2}OJ<YzUVAL{(iDXXFRBGgQ@$(A%2N8$oJ!rff0ZqHyuJ_`z69>)s&E zkl`%)xT&}3T({LOR_^nLs!uEV&qFYU^iFq^(js{AA6@XRlGIWhuWMC$xgpxqWwzj< z=*}i@L@)o`%Kl}H9FbJ{M7r`XMe4UJ_mti}VMB=<jHb{jlyfk~nvs|90dl6-e5qap z{}#c}Id=Ie4@pmKE|lMOvNo3BMBIR^Kl!=5Cvj#N+ixqM2k9&Se#sC<$KS;nI6Q`K z=~E&4@N%!xw(<=iG55@GVMl(%Y^T;~GV#7>66NB2+1H*YOW=Kq7TiMnULQfmy%RG@ zPKbENdn?Vom+NWa%AR97I;NBN#>xVQTUZZ5y&RymgEj*9vdmG{o{W^V7oc`(c($C~ zW%^*!K!$u9;d-}RcXvN*h+A1UW(J#@IEs4dzVVl~@_R~KxsQLR7qQB1n0U?OZzUc> zW~a-_aR&ib-y?NxLW5WFJ1al1bVwdCG0gHM`%3K2lFqs0fb07Vr-*baI{0A-Qnim; zsOIG#x(wI3^O;WSlo9ocM|~A9SobFOjK%KnVTys}QD{4M8V`=t7P&D~D`RgfYc6$% z$CS4ehnEoki_&aRsO`N1T{<pDwE!V?WGRy+H!(Xnz}lbjx_o+t&??i}JtK+Bek^&w zD#2BVQbNkizOnN-Dz8Va%u`gc*x;X4jqLuHbj0zLvs-s3X|_-EcO8-_&HO9Be;4h3 zXhFVrs_xSyeZk#WCEywlkgFhZDw-3}qyI*<Q2U>w-i#PE!;c}KMfhQ!DxgR5o92by zHbZ!=4%d5x1;_y_>rq(sJq*!`l;tBtd2jW$ncpQ^7OpbcV*CySl*>I7uA;}dkkYb> zchlUYKcN4?pxG1rHDuI(3(03W;O^lV2?$17Q^lXZuNVyVe-7;3!L{p;7QYtabA50P zbX$UTHT8{l#wEt&%ahvcp{O04+cpX1erfU<o|So^qLXdzf{02>tRL_raUW3#4aYuf zn7sEQyVm3VqJ?v${5mxOrwGDtCKpKB(1xFtvfuWw4zPQ%F5Z{yH=O#^bA|WNrT2>{ zbrIP73Ku$*rF?bbKfo*WE1&=|Qu<q)k8@3kvFYN?H~~Ei0@O6=zpphrG0+g4z~h&R zdCr&fbup!{k_GWsLRQ!g(L{dCrk!8(;57`?+sAOeNFY#jnGHa>(W&wnHD_M@6`iJ~ znaMc7WBvtACnA;*!*eE`NRwT}{29?@1p!Q_R+rp``$QKv2MUW-veQ?4c<FA9J$<ET zFH!H#cMcBzZ**7=|E^g#qk|#d^uP6sT34-3|0Nxi(xrGeaAD3(I5pUjs1H&%fO1HD z(#xS2B=&CCOPeLJ+Oh;V3mP?p3%}yQJJsVlbDC2yyf@!|iNkID_#T~6#ZIUf?-7}2 zfwn{c9$gaw*~N96{%XXmb&6NKe-50WRKFLr5>(}yPjQ;2sCod&sBTHSyQ+q_LT+?r z^JlHteYxoj>?_p)F!a8Bh_$-$DvFsI;V2FRbhw9gZv-VNRQAU+em7sMIY1KtClNpZ zucC)WOxSVBowI_O@|R&jn3pS6Zym==v=w%Qd7jo<13rRp+_7uC{ygG`e4*0+iO_$1 zif7HY7BY`9ofvgZw3Hx`(PebRT9cbLG1mp!Ay?;|9*3HO`npe{J(r&`w`P5muomh) z$D%@Yy0cL_(eKj-F6GPJei?AGu>aVo@doX+-=DlU&)Fsn21)c<Rjm({-zO=KPWF#H zq}nYU&ukMChCX$N7pY*iLC#D0^8-phb89o24ug3aL$S3PSwhiU1=tT3kTmt+$Lx{Z zW4_A*fd|Hl?j=ODQEfdCX>}j9&fi|`5<?FcM*wKwJ`+Snj77qq<=I{b5D$&5_kI`& zs)vfio>^Gk%RS;ioea3Wi<umy{~%aAr!>L;lSuzLREM`FJ$cB0b5iRY4<3fw^ij1| z-`~nM)gtEB%&G59(Op%W^y19XZE?)baUrZQ0%Z0UIVLFp?cBFog*~%rS@_=dVx0+f zdMj(qM@a>GM-+OJAZ3eSnF`otD&#q#9PwG1Cud_tSHj%h#^`KUj`79ihTPIMv#z{e zA|ZiI*L9L6ywyITh<e~PO>VzcH;0H?S3y<g9~zpM)02=d7W>Pbxyo(WaMUd3Cy|H= zgmLOUu8}mk`vB`t5j_7u=}(($!ZHodwu6%Olm3B7Pc1%Pv(#XBIZ7~iVzT{SZFbS+ zEKQfmFSuOy70o6?ZIQ+fsaqW4o4F>54ZZ;QKD7$9Y3{AgP#W7hf>_b5h~{fuwdl&e zJUP-<txb2gGDCGa^(fu4$f?>&>(40H^*$bm(q`ALw>uXO?;~uLS~3%xu72CP(q8}b zEoD#5syyao!E?WivoW2*b5?;LNwbFyPycg#EDD%f3%I|!t~99V7ND7@vv4r{;f;Sq zcN+Z16!WYfU>9Met$yFUM*CnrC{b=aS8R^zlXzUF^J2zL#ZbOsz(fd8pVMm0s6fZM z<dMdUR{g#=Fs-ps6<rqI^h4sU`YCP2Ok<7V4@if{PqO3EK^)r?z0Y+@^IH2ON@r^~ z@iT|1y4RqSSNfO#R;6n=2HJfmG5;Bq*ZO0qjlIeywPtQ_&nz$-AR%he9yIksd&}q3 z)*49kG|5fikZ*~Q{*y7~Xi)WCAQQ)<7xh3uS<Rrbl}?}2>)A`;<;|>sEqOW4!a<iD zXs`-wS+HhZSZg&56r}k}Ab5QZ_KKQeZKo*sU(X)q%gC^>W#5zX-`=_!N)(;cgM_F$ zVZx{6sT6rGSoFG#VA_+S>#OXQ?#IJdc~_X!cI6>n(UqtiDG=MoISpTcp5Q*bSfkIT z+2yakSU2l%#;VJO(%+(rd&UOqdij~e_5RSPqx7Kq<MasaK{<Ug=)iGUw&bi^(p%O& zUvH`$rYubmJPJz*nk&yZcWt=x_S**y-F|lWWlb7@0tF0BbM$VxaeI<(nisgHmkB*a z#pS@OPm>B&O3jgnR6&573VcKei@I=pK63?@mXO>6b0e?cR<D2^=+|YX6WH$99-9nU zuw3DFu<}1<Pu62gp|G162}J<YF;8zx5k;6#9YCbtmhi>XF!Pj(pUqL=fQvokq+cvm zP2?zoYz^zft>Zpuxc$c631+q%In!N%3|8X5TQBb<(UER-$J}HIG*+LQsi2PE5@(X+ z0<aOxE-1t+T%x7l5_$)ZNOEI&PvH}N`HOqgrzY#vzF%=FGo8{~b%s9a;egi#uq*cY zp;q<iO)c`8KT0361r-|MRq)IK6gMjGsJYvCvvQ=gyYXq$IaxjVb*a8$e0Rl)C8bry zj|ZBo15Cu-zNPk9mGvCH^!E9uSyZqyeIhNa=<q`&%x#ez|0mMf`0@_FL`9;|tB(HG zyrt4Z?HCTBOpyARf-D9l_K3g>l3B!9_5IYBI8o2i8Ca!+(u|Gnm@MDwI)DTzuko!C z^9@D5iWDGnR7^+n6+f&O*QuMEs0|jlvWE!-uE!!Gl0YT;k{SPP6JR+V4=a`*u`8bp z#xrL&Ob0F%XDRxoAJ0u3znYR9yu4%Q>)k;3YYlEq;1GUr#tgZuI!6hga^t_$1PUd2 zRy^Di=50zcXMv=2Fm1XaZ*Q3B?mK^WCCdvs{Y}4D$03=RlUPXGax*O+<GRUIla%Tl zhfCh3TpSlhUGrsC`{bPFWUH<(j9}*ST|%{e5JOso?^)*9W(bxWp*UyrHH7Y{6u5gK z<xFj(6O*{;FFw<`GaaY3(6`EE5-;#`CLkygOuF2|O-AEpdGpX2;Ygy?cGIxpmb{V{ z--*{JuQz#L$-}N-Nu}gDNZ~p)<wHfNv1d!%+qgdyIq)GATGZ@%%@-z904Y0~SG;V2 z%A#3&wQeP4014fL49bLy`P1GRuW3L1r_Cqa<F$YGX%(3@<S~`u$ap~*Y@06g#}FlT zFnDdH8RZ|?F9g<jUlADy%D-%n+UeQo7zd{FK7{a-g_t5-7_*~BzfwzB$Fx3WrbJ|R zNPJW`YI$H_))6;tViJDblO89E#z7U#m!)rx*ybXeIqc4~-!wiP|L7~-+x-P=tT}*& zqNm(^w8&6^kir(a^lfJ4Juo0@Gwt(F5y6J8hb8rT5Y3+xT1QBv$GWq!ZX*`0Fq4Sf zZ@BoKD1s{JXHusNpoDcqh<%wdBDw$2^U5@sl>kCf#KWC(p^-%Nqq~fIw<_KuJM5q6 zj+n#QEPaS;uvx0ejj}AfWm}xSlE(0`%USbKXr^i_kH!uEuJOY7?MmL(>|Hk?O{*_h z+RfJ`#rye*i^!Ac)sYt^3(;4F6ECNV7_i?xq_naFw1qcIUR(-hD8JMZ!WUU*qpqr= z_(?P;N8?ne?AIxXv|``p+?ER}<h#fj-8P0gp4@Q;kl13Td|wzD{#^@k%c!5v+50&) zTvK<z_)UQ5@P#?^iV-)sxMSHnsg1C~xhk_Rqa--g(Qgo(I`X#;95}LPt}iZDbX4$L zkKBZ`DqG0$`dj?HggvPy%Ku8PZv5rWcScV~`yhryx=aSlB^#R7x0dFx2V;O-3Xob^ z_tGxYb2`y|Vnu4gDDq|%^LLV|6YfmgNLe)IlK!1Uzpnuo?^s_%Gm-`sFP{(G7$I=v zkcOp#6?eH!h??k84&-o(40Yl13=}`1KwIB&Jg{L)i^E>Fm3~YIFcVTYVgzi{uwSQR zPW2$Jq?livDk%zjH=V;i+1xSV2A}jmco6m?6<3I{H#d8udD&rKve-Q4&31a_!kpPe zT%5ecyrUU|70~d^D!W+@1k#Az_P2o9taRCVc?b(TRDf(YMT)LL{7Ddq_<i0?uC1R^ z_1Q2749R2D>N@~3O@Vb7AYO6Y|2z%Zr&^uLL**7A-}K~M4iyNta&e2%gBXTQ3UBiY za+?BsAq3jYMF=K{eH1&3VE{7kZNiV_RmC?{{!<JG2$6%270<z8-7#0(>2B^Z2?SGb zd$!oH&WOWnVVp@k?y44oeNqQKke7CLSf0Bj?TC;jwRgwYHUR37+bHH<$f)yGOlZRU zBkt3ECYLZN&IBCxSQZhSW?ukn>H)7?rzRb6sFO2z6xhQ^kmx@4st}h&61rz0q@n<J zF-CNT0@F3*aVv0Wq(a;h+1vEon-M;50T7&`K9?J;i{8|o9kx5{&eXy)AOt$-L3)Wr z6bdseuOazIjMjp9x_dk-4WZwHnC8$o2mxXz`;6y^P}O;E9-O41DC{4dR7pOfF%uTh z#JW!jux&Y$_({ARY?#e4AjRPV`T&6OU{pq}^S;Oj()y%213{z8@!IIXK#(PXnzv0e zt$rR7X#(E|KwrYa;=pqoCflvf{M*9LSOh!y0>`OP!PH#dHX&(3-Y0G`;v>~!jL4q% z$jKeU{h1;<351Pc<yV@r?Z3cxD8dE@(4X=bKq}F1j?%~U5EaJo+gVs1HP}IxcAy^H z>HZyNn>(xpP7MJu_YcE0-C$`LfvUr6p|-{`@?vU+@IRZ70xl_fWyS;IMWzseA0##> zqRxi%gMT5ajXmJeIj?ORB*d9*KKL%ffojOS#nmKs2lXKB%>0<Od;rOtQGtTRYe;`N zL;ltvLKUbR<*-N({MTmFx#P0L<_kXokc&%Mhg8mQP0)T~xld5^gsATpO+>5j0)Qgz zr<hPOt<^5!u&!KKHo_Yj5VkdBYt{t$pb(R>2G=qG^Yak17c}%ZAK1Au$E-r!IB&0X zvbjzb7t?cuVZad!H+K<tOYrcG3lEC(*pEn1Spy?k<03j$yG0?HdbEYyFO#o_pxOZm zdY~vy0TMaNzGV#^p3~vbtbwwdTRd~GoprwAjUn@bcWC*CaLkfCmxUKb_CSi84lqZD zfM0=|Z#wuIsQ!%ep5ABslgS~(d%;mz=-VokWUTtpxzJdjb&_PboXq2vb(RD^R(iq1 z;n~L;*u&SJ&GW^?+6PUv5w6Yy*zzoMwEWP$UdV2y#K>F=eagpCMW?)%!wvsZf_Gu( z=6>R23`gUk<q4)E>|VB8NOU%o%{@<R?7@GAWy@n%Uf>J(LQ(OtfxN);^BK)_VCXv6 z+~L)QQI2;E>0jiZYTBUuDUf$_TvD8{m>mHJMQYPC*8*d>G_R(+f?PUSF8p2AMLK}d z%Ka8{QN>p1CBCrFA~pv?47=R?Vg&*2uI}^-O7ExA2sqeMGvs1`U)UjI`ImZHFoRx@ zpE{udG0br>fVE%qngpjg_p}t{T9oA?SC1<w(d%(yZxe3-RH5&TSyknMpF_rxWT=q) zz5h~phSaF_2as~6M*mSg#}2qzHQoXYl|5?6JY}K@#qW)97?dN?chtV@BT~<e2-9p6 zJ#sr^mCbmUnJLIF4fa)!`=dO*;8AEzSA`a?<<w0@#uyQJ8P=VtP)t^KGV^+{ot_rR zkYsE2hR*XRK>yyf+?$9_UWMv@$u9b4wx^5to-|uG4P#v;IT`ZGzVtxCC~Sp6>7NUq zP4wk_Qs(^ZOn$0txax}Du!cR#k!S5yy=RQckdSGPfvjdCe6riCq@10UDOD|aD|G_5 zD-5j|8Sx@&lhrcg)@v!l<T_2cy(!_BbAs-F>^>L5FOtvnPpw6-qN|!V!VkY7H!{1P zWpapO9wg~A-y`an_i9&0UXt%MzK@1;g8}CRNyW&QGh*HyU_gDvt!vmzI;|>_%dHY< zC7Ywz5o*{c`G})Vq7migK{I7v&+{zvUVf7&+y%C%7o4CJquI?jc_&|DS`R>Jzb*Ni zW{dg&XU-*Bgb;Xs^aRGui5A~h`&!=CcMLiHdj2-p<$Kvr;6jZ*RYiX)1lqv%iO=r+ zQDE-P+SrFqwfETOUjW5BunxP&DL}C)dJ>phpMU~<NyGj#swxDmxHLFd@Am5iY($>! z>&F<r-zIkzQ;+q;2x#aHFJ_-Z0pz-OD-b$&ct#De4>WzpSv7NQ{~Y$&e{(@}fB}fS zcEu}opF`mTU&QH~6QSJCHYghP-tG&OPHl9MMBo=!h<mGhTH;W~2afOZY~9wJe_Ghz zMd8mP)zQ~O<9sky3jQZlETAX#J=df{3*;ui2(17+)dLNZ+HR~*LKT#*-iEb_s@|Qs zHrK@9L)X9iS4G)Cb@ds<iI#Fqi2?LnSK>!}RM1~{PG7qY{p*?cJPWqagQH9BI1y_4 zlbR66#Xfiy`hi3_-(n7UBUdHW3)sKeeb{>xFUUF)LMZphqE9c!iuQ8OCZa{R>xL}e z!#9ZVgq?x=^y3jb0_U6#TIz%Xx#tJ%4939z;Dl%sr~aZi>+$oGd7cA4&k!j)VJAGP zo(G+3Bm}!NLFE0&8-M6NEiTnI$61)q?^{s?mKpU^hPQ|gYN<y?1v0&$z+y!@c*&E! zWTr?i<;r%{NQLSAZw{7rcugKg?OEJ`JcOZ_a&J3QGvB}SN2%4NMBaemP&Mllsvw_& z^Qpq~)FqV7^QM?l$`i9PahE!B67|YI1tJ6NhpqlK{rR4cPag8IuZc2Dj6Tt9Wts*6 zcBax+`(>~9N_HOeUBtN*zpp!xh8EYu)LCGkCS(unVE?35^pcp?rXJ`tKM(?UXJo@? zNuUL5j|USo-eaorI9~75CNZ6}mrn!J9^Ji(K)*9|fH?)DqS04SE2t}uuR}EWbrK<4 zdJ&Rz;B9%zDS(v>fchjmFD>5K#W#;Yn&IrU)<+7P=Bnna@&*gq9|*AWX-*k+$LBHC zzcxW9aH3*Mj@53<`KNzL=%Z1k$F3txc+IrIW2~#Z3e*;}327u$VAYE*gex<qZ|aOG z!QKloT~Hyi9lY`f+!`!@Irn0y>dWlVRK0~j&&i4Et`y?PQA0)CyESuNk*pcf(GYt6 z$62H;FNubDL8IIVLQ;3ja2ol(<W>@{YY(-f$NuXvMmMlX{M&q6`-?(oRy0|E48k#^ z(MBx2V!!-cOF^ma_)PJv|6OluO5i@nl2RJN19qIfc<+{V8=us4IjF)2E)l5fc&&ae zHo&J%XrGMq7RB?>bKLHCp;Zh6<d@&2W-MQj4md#wnPbz^UuUJP)W}}toknc!yOaqy zBVtTNLxn!gj1Lt-S+Wsf!SKFa4!xD_lc(Q>64=*sxbsu)e$8q~0vVZ6APR`Q-5G(r z#HS3+<muUG%s8~6iZZKBV1$U_sEI0Pk}+Zng<Tkl1L*kz1$#0Dn-6v!7Vks_k?YwL z1nF6&nuR(KK@m&aSlj3e18~+i%w-9I(&+{RqzgP`NGJ)?=<2k4RYUVT3XO+(M^XoE zq0%6!!I-nGKj}Xl$`EX=4h~tv^}Res@U*udd5eo+_<hKY{xoR7*pWp!Ua5=WAm^Um zo2Em)6ftOPqF4@%X;*t81t)nPcxAx(Z|-L(pl!wPxbNGbAT`id0fZ$8&}41#CG34{ zc-edA_AoEd25AL6aO}2%wsHNg4w58>2}2BjxZ^Dj^_$pZl%nZwG&THq=KrVUQY>Jf z#pK{e5dzYAAmE>a%@cyLFx+H>EH<iR**jRLM^<CdrA~mDXYQA!9JH=9q8{q<Jz#&U z_&)Z-bKbwJ3re2ppBSJt+8!!4jnrEBaspDk50VAWH@A$xv+zFYVGgpk_!>~#1c1{3 z=lrXDe;O{1nSHtSsx_)BI1E5~paw^g%rZIs*43w6bZ>?n=2q6qmg?RNJFa%KZ*uO7 zBCBsdS)AUqDAu_9ZGCC>ixrih7c+NRb_*AN2+g9`OSIJ~GkJLJ{K!$K&PWYA=;crC zAUj3|RvR@u&<!{S^D)qdvveW|v4u*tmIC<LqfMZFNJ8oJms-sgtzx(HbpgS?f&D)d zu6Kt)b1|2f3-~nw8>yDZD*KKTR3Dwq$U4>fg{s4`fL1pPT2I&xUGGAQ^+&;*pJ`XL zK>$1IJH4A2>BL+iVMA{zsF67Q#A)+cwN>qnkD70*0xv|Q6-G#`UZ-CR{33q#Qz&%6 zL96h!gk2;)2sOB^6<GS$D*B4tQ%2|SBdTlG*~7A{@a2uvsF8<>FN?bo`hqn8XY0OE zKu--mVR3f2NUaGijW%=+ukS1CVTMYax6^qP$A4pGDT;-^s6_dV6is29u}6&XWofp! zf({C1TI{a<crDiOuzX8sl!*?c5cB(wS3$_n7vD^!TjvzZZnfdeAMyK-5f!}$n#3AP zT3W>f0(T!`_#@|@_>FV!(F+LxQXDE#+WqTE=!DI4u&Rn5F9JOq#TO*>LcVeUGO*>c zlj_ko{h);~C^=H+wB7^~sP{`v%`^@!@)=+0kpRJN!h<|3v}#s{OwXt>twzr#ROyFx zxMz`D>F&3jppUjlijAldKb6h2h^^`2VuK*loq4bQrp@NC)E2kGsGR^C3!;AZVQmO? z?$9xK)_1Cu*cT20__hJ5MSy>fRwzcGJzYZ+bdVFRx=pWF=E}HxwHz?PC^TJ4_k#(b zaakh~6|v=dK&}5YYa-h<m;C(+nfh26&k|7Vg9<!krz>rvTQe>*!njDzvix8cK{QsF z8RB;iHEO9TnzM;TWM!y#`=<)dtS$kywQ!f)1UIv?i|W03{C?jk@~U@JEyWcB<}XD0 zw8Vc^6%4gKFm0x0x!OR@P<>DFHCxsO=bg6|Mo8s4n??Jx@C3v!SpbSF4lceY1M}DZ z^Ego=VrCkIxVVeH-CfCJn_65yWkY;8Fyp#-qqE&%bv5hKFEGit$3zpoS2H=jO>QFl zXx_bXby~AJ=|5q?fOTFmY}%O3*w@k?asXen@oxK7uZ;lDRlNuk@rCQGve(MIJ{8n? zZfT9N{AhWjcGl$wAR1){d@{NCx1{Is;}>z49o+iK#}1p)+XJgnl{gz&sg(CA+Tt}C zK1d+`SdSMVUY-~x4i4vU1-)ky?{um!Cwf;<sfQ~d<GAmlKMRHgk`l55w_-V36-sR{ z^MLu-_s=~MskmKvc)LI~<^yd&cn+B7e=h1fH7-2+*%pXcPh}v=B`020Z?1|W#;||t zG4I_)z=C_gcb?Oay_o!EAm8q*cw(KPr2Dg3*@8*xlsd${s{k7}@E6~vfHwAX>!N?i z5%-Hgnt4qSaf|&MpsEBqxkR|8_ET5S56O<o!^YSK7jA&@we-JtDHEb`E|t8CErxV; zf6TucA2y}#DbfQh$H_@=4^4XexR?z+YYcqX67)hsC`BcKju%~$zQJQ!1H%||w8N9N zJ2Kg{No$zHj&nR(6}F3La0fth<!K1FxT`@AXwx*+tyf@tBM^_;q8M@4HIHh9Z@73; ztSbhZ8S1Rf6POiXIq+DqXp+2b%&sXT`i$2q1fd`<tx%#l)yXa@W107X*=Q8bkrbFj ze@~liL;mE<X6aombaarUGv)%(3IpeG3?{!94?-Hwt?85K^_bcFm;uF2&MozmYE9vn zie1N$r<80S)>@d3wy6Kd^2Mk)BD_de)JHGVObBQVdpY9faWKVt(FG*Fw%8BLA<bwX zqvHaSCLe2>B)(at<MP)2;k>sb9C~OY`0VG-?UCNO0v?Q6FtIX1(98vK->}eZwW<&_ zZRZM5d3%m?!+ww-N)>X`FWa(2t|X0`r@j-+3Rw>sZR)?%#4g36l8g@%08jg=*p<7h z);_s#9r{Np|MxLFWSW}p!iJeXtJn^}=kudP|B|>;l7sx?!{2D{S2g<Z5K(n9k8F1W zE(4IpnNR0Oon7@|KRK(^)Mi0@oP7i2o<8xzrfq{FBd4zepcWmM2l^2~X3Py&#T<d7 zJ%`@BBh*koE^i6fuB%zk{6rebaJf5>C>nK9yy@x%R>hx;dCDoak|#|A|Ae|HmiHym zn|L<So|&xbLUY-p@_|@5CeF7z0Cl<{`hw~3y}J2~hn?uhhM&JbzN<5lohA>e>O9Wi zkBE0p8r(I!Q3-P|w0)&j{!wd=9aAwMHzI&b6`0Gs3NUZQPOmaMO_F)is0=VkfwVZW zY)(J(ew8_fGUvt=XZ7r}G}-lXkXqzwy=Azl-p7L-kzB+oo18ry#y1>O2_l92(08#` zn(FAQ31~vxA%C<k5i?w&X1{>~cM-NMHjm8W?GgMVRl<N*<*@G!kSskM^jJ^0q^w$B z@WwiW07RhhH?cp`iXIt#1R@nZI-UnlfHdJ8Fl9@P$v1ZSExxvwgQzatC-zfmvmKpL z=4d|a3WCs;$i}o?Bh=~E`-3P+l(#f6Y;DRYd1D1)V>$ecWxq*Ha>UWRklw@gUxK>q zUHC}V34{~KZ&cvMHzLFfYt2Hu3Tl}tBU<CXjF@WHxRkRx4KG&DgQR&5c>cgOR1U#~ zrhxroq@23o*-pogu7ZDuQXfb1b$Z9E*nLM&EDdE&3+V7E(}!A543y26nBFphkN3jj z|JQD>8u#Ub8YOX%lVQVhcDi2bYwVju)QI+B0F!r^sK8u2dnyT<PF(Eexv{b$JQl$I zLj66~c5Wi?bxH7YH&y`sXn1g4mKH_3<(xtC(zf(i>ohPD-06u`*a=u_IAh(+PHfeE zTHZ$GTw{gXI`KUd1{-<mSe>fZ*+nd4<L1`<ap8+QhiI@Vbxq(PAj~`9w{&np|6(wC z;o}8-dI({PzevQ&z=BJ7U40K$d+^PwYXRvT5W8;Q)z8{s`=^N7FOC@lJ*pEIXwQZ7 z=PjL0WJ%n=SNyHx`sU6*t1tz4*0jG%nB)-eu^1D8^Pl6E=f9q(uTB$eYX6cL0M40b zlv+%7`Y-3A<+YanUbcKPgh;92Xkp%K;!XRFGNdF1QBXaFViq=8@Yv^H>yk>!L3R>} zQ9ZiE_q;@TP@gbgl@zu7w_;y*MH5^`8jU>u+Pl18=m+4SzGrQu#rHo+JNaGd<SeGe z4o|R#yBE*}0DGwLoG2D_QDICQ3oDmC_vZfNHrLEGO$fkVSG6^H#kkxU%pjh8Vf#q0 z)djJ<nCfs)E8CV4V9lC3mip<BR*`t(x9LRxeHIUXiAJ7WmGwB{zK)=e{t+)n;Tg+A zoFgC8i{_S&SMi-~zj<n-7U^+%^a0{eTmt(T6(7U`%Im542E9bqN{ZG8L{Cf#Yb;CW zZzaQ~LYF_X`Nk<jfW&KbGX2@z_p%;L(Bh)3J2(z&w*iGwNer0%c=qXD;W2|)INqSS zxm+GgEQp0unO*SOMr^}H6|D81;=k!hMB}m&V_pEIZ-<ijk|$BPDXtHllmJkEOwXyV z3D%=4XK02-TPsHwATLrlcVh_jW+^&rNj?s`<c_K^)&~!iSSl1=Jmcvs&VF!-ACk7n zA6TelC{2x7ga;xF8}=2&4;YhJY9=eG_e|2F3KGNu2Px~xn;b^Pf3t6#tw5{gjgF?9 z1Ne<6oJX%#4Set7AVrBaQHx(wO&0nzVu`V(J0h9R8sE3TgGr#5JB-oxgvj4g7rT>b zyuwlLjly220>|D$k@hkmz^x$d+gNeG_mdu*ijg-a-2*ifbuS;WvDELg^c86AEGpau z_RK_@b~5uuh$sEBHi#c7Hx6S6YHqCz%i?h;kD#@E9ijZ=2iuyYzB|Qfb?4%Xdb_nJ zg2|w1`)BDqgvhPep~@4Lbu1GD2vh4s(cer#>f`i5yxw5`$ivYxuu_=#SXCYKcL|Wz z7TcX7?Fpey4>X;R!o|7zNmMFd>O=9TJskM`rr(v&)NVvV5;FQMiAl(s<!KAFz96H) zG*LiYGd#=UXtW%Z0_x!bbB&6w<Z#_JPE;#kdUgl(!KL%&L#80>7flSp?Ix`mv7orr ziTyT9W&`=7slI2*55WTFKF29O1$0eRhQns4H#J9v0s?1u(7P2yQRDPoSsnn}*>+pH z<iS22=$V4_cm}}T^NaTBE!y(=))-us<q2yOvyScEPNrdH+tdS`H$cqmx-E5)HG*;; z!i$A47a!e8IwP?(@S_$oZDafCZx=J2tb^%z!5{2P*MK=k{2E--Ge=7KaDy4)YR0?D z55Moe$<G#7wa1rg&stw%saa%1E;2q7H$CcQ>loE9J#)$B_Z>}_Z#NzR-T?rDM+TSG zGgF#gsK$0?zOhyhYDhS>(SjH`9FA7?C7;6Q?kGZI0d(j(k*kB85tKn4QX=6H_c%;t z(lqfc#Sn=G*J5mojoA(18A`!btU6`Z4f97!8KI-Iml`Z9O{P5PIr};oU1>c}7_7oc zi4pRN7kmcTW)c~BlOFWXIn5-8QO9?}3N&a85x-Nd8W!Xf3#07M?Fd)9wH4!dj2C;g z3Z#<o*R>Pi_6<BEzd8#3SkDFXve4ehL;yfH<@-Y}WY34U?g-KOP<p407w<uYZ>i|3 z^FyPXm^{@*Z~eI1T@3d&;F+54B>o)>AaHx0>696rJ`+cSg6&@g^VG{{br^%m57sbA zcbCS2fNKE2uK?5PhRH{~`ow{%opA>(kHHTq$px#=iZR7z2Fth7mbb;Zivlm1h`ukb zO7!1K_~cB9B3X=GdTrDF=1vsM?Im{Is}2zXX?mov@8$3bsBbTy$(3yUOn`sZczNI% z*37lK9-Mf^jQt1C^=BK<Hv&af#)%5<tg|By<MYDiqVIM+KNR)Z&E9oHgu~7^&~AWX z5fL&fxR3G(^P0X7nchn8CnT~hlGKtIv>zE<{pfUZsp1JA^nVC@&!{Haw_kfwNTm!& z2O%IJy{IVt4!vU#REl6gnu;2*(ew^Ap@$;9gx(<_(p9Py5d)$W6$7Gxhyo%4qP+P( zd#`st>n(e)m5;L~vnFdM*L9x9`8%H3x_!zgSSwQR%$NIHpl(zm>xbT<y+<jJ=G2Vx z|H*Q9crRRmIU#r8=Dw-&A-~)G>kH1Cw_+oMkp04ODc&tzpL7<lp(LWTu_4vp^QF37 zv{ln}w{D}shpu0M;YH1haPA{h9m2h6vr1bQ=#|{`#W2)KF5)NJ_PrX$BN^Q!!I>N1 zVe}R*;UNhhPD$gOH?>_;IUnt3T3X8DGI)qwL%(ky&R^~>ZHvFb<ZO_q+;Dnb|EXbO zFZOc@)<f1qrl89&_*~wOU6wI&Zj=#46UUqs;<CnXkEo3IqdT)M=F=5sZ9O$4T+Wvb zMpE(qMu-y`+_`};z%Oz+@qHvMij!?-zg&ZTfAQ`b+Kk*bTZuX@cFBBF?*2LwF8Dfs z83M>dOb<RgT(-~T1IS0FIn1BLUfZ#6b3w_LA8lGh!-m4csfchKRA1uFRig`r-(v4N z%>=hQGL<DyL`*pv41}*h#X;tj6**i!9M)a_@yrVe?YJq+^d0>Pkk#N!j?-pRh4tg` zmG~O{516itxml5?-ymNre{zmNUmN37szR9r&0c#Jep2huPpt@BM=H0IaQmM_z;xss zbFQw9&&7G^RsX5t>_la$h<~(-oTQbH2IpT6dStOK639aEk>nn3EnM@dd;X)?IflYL z9eKAZiYaqG+9F5iobPD-LIGLbt35RcxAcBJA!ZJBQR{QK*5@q`xRQ1~X*fLmcTV^+ z=ivi=)Poj}sO6Z;5+BkEx^(oZ*J+6MdlVlFqB!bB5*2bK$0<?2Z*@9(YG%2B5fx8_ zsiu18oiJ$JC=e%-W4os#hal46v^Xh+vz+4AM}%c86{_a?GSJsUD5M>v@yYigWIyX= zU7?wwa1aiVJfodrY~I64qBNs|G!54v5UQ6|CAeUEwuIo6wEi&?-x=PfoX;{71$n+J zBC}=_yaeJ((y4_+zgKGr`I!@Wz`|x#_K)>gPlGeCYV^-6N<l<iuohCSLnn)zvt#{g zWr+V6JWkD+(mcyCcVCg2b#0`xDC$4$x-q%;L{f=N2>}@pYguzP!Pi4(?Zp`9h=j2C zLaeyJV$l$$vyzx3OrhUj&AT!{0^&*PNjH~Im9?PF;?lmzH*>x6jAA~n$6bpW(x>&X z7r~Sp4F3pWWQjbbp4Z`kn-n8cTUw1=UKa{oK0hvxyxAS+*Xz>sf}8iB%v(|45i5e) zD;b~TGJc#C^oZjHzQ=Y>8_f=xVSCx-gMcgt3Tgb}he(X3^o?~+n)ttpYiEZ7yluDc ztR_}^@lP?kxg@&>l%JU{$`-fSC<n;gDP3`|h9w1RNd9n;yLntPm;B!h=NxR!`E95U z^nY(S7v@!*849@6n<V~E#8wbVW;j(&v)oZTRn{U!&FxN<wu6sFu9e>#6OlCE(~(N| zzA5`1J8D-VlBVc3(p>e5Z8+ynH+ppCwY<|qm-mXYHRtNjKlbDRT56nXy{igjv4Y(* z%|0Jm^u;*p-!<Ls`TWVM_4@2%SBR^C_&H_QC%4u_Raei|E<8H(UxxEzM#}%oaBk@O z|7SRFE?SN`Cis6F&UZ{|9V-cS`S05Phv8fz_-mF5z_>B<zYOQe`5pgdI9E#w{-1_( zp2lI6kg8cT{eKwFM_Mjoe{=Y;!clUSEE8K!6IKLhCO;qbCjbJ33!kZ+j}gDKlPd_E zn1=$&3;@7LlvggqDW5Zo#tRGj(GpbN_<c;&l8})$ieFs*n2fJ>GQrA~17!Ilsg;Xf z@`77NG`8W~`wA{*x)%c^kopoZ`j+;|?wCcRqo_vp-gLI%yxhT*LH16K+>)oIaO#UB z82NI;hw)B)UM2<c7EPbohI7&Jc&=@9H`W8nFp@+hs-uC3lL|}~sIv|&rA~MQicxJt zlNDhvSWt{KN@gkB^eYe}NDw|yT&<1FXuFsSP}L(<0b(F18IU6dmI{|v)8sikL<aFk z-lUY_Be)&mg3afys-(w$6Eew*<di0Wz?MAQ#|0%R0%;+k()qH|CyWcFv)HAaFMNw% z9_@S%z0?U;S*XjT-NLFG{)ll#Vr~hZfB~UN)?ms@?*6{sy>tGJao5Xfy<NErI!6tq z6Dn8o#L}kg2R~!@)v!B;dLTypqVkVXj9`j<Ax{M(qD%bJ@b_r>XL^KKz2xQI$o+-$ zwAdrfm>8iG<|>-^t~IT*QspJ10<mVVf~2OLeQnhZ&jEx_lYSNY`GUU3uU;>J^&H;F zzV(mmulIMbQFq_(emW3pZ2ncPvcnqF?BN(dydXs`P<{J%7HG%6sTy88bba?zv*umb zU^UNgyGxDs&+mK!oP=jrDl6*uzSOpU+goJ}s{a035ow{a+-3|P5a_y?BL3F>0`LBM zuh8lJjb}%b_cupQNrnY7&DH*FO`gB;=jXI<!=LSUcfbGn#k$ns`fc%edfxSu6(6GZ zzBYWn|9kzZ+Q0i-FK_(&XXiu1zkm0?fB*LY*e?WN7Tu694ThbuXLkjiXwv*r|G+1l zuxHdGFlR_`p;0==DXJm&6-Fd(pN`VE=mj&@BX%r{Fz1JQ1v}QGcSVZOzVdyd1?w>< z`ir=34)q;QT8}t2-6L>dG#RzH6%)RA6BlmP93cWKm=O|+`71026kRsr?3*8C%MT53 z-`R+F=R6`j=x3Pd%oXovQzAMw^z5W(qsh)p4_8Zxw#+f6k1Ep%<LRYzYHuU?{DmHj zB8m)gEC;wruS6ib=K9ArQ)tTe9FalMDkq8z?~LYuPPdQ|T;52dbC$`QTaKK`*-WQ< z6=$0fhajAE0In|M$mvWLnZ`V58<mwu!>iF>HZ!|9%f}GeP%9U{v~1-MdvZ?F9y&j= zpUN=D6#XoqgmOR>-!m45enC{Vhu^D=M47RMujjnVPMw_KcAqTp%4k4cnEv=ICwMHR z;AW1ve79Ha?!k!v6SBp2zpTD9F2e9uBvOqbst+3>*jqJa8NKV>dAHkc%e~@98?7|U zY_ke?I<D9N2c)rJlmVwFhss-d!Ba8eRx-vy0jO*%Un^6~j_$0?Qa@8&%AnoJt%~uk z3B?*`3uh}+SQzb@%yp6^J!gVLm|)5a;(4ML2CMAuRcaWQzIvyvUUq`(s^~_VU9pvE zAq<@^lND#*Xr>WuuVM_?Fu9H=JgmE(zjE)o`rzg*fxFMQ6wV=atuAw?J^*&)9Wlg7 zqjy9wb;noYxuui7(OJI0{8ht?w26_q9}Gh{uMmw8`_#pbZIZ6g(|_)Q#yrT0%})@+ zK*%x&TONGnBbTnuQ^Q?_*<yvV8n>SxpQBm?vsO;X35F3}p4&Rc2EC}cRb+AQcmVwv zFE}KpBgJ)jxhV5h+4UR8#ooOzJJoeRszgWWa?xi`J8Y1iTF4I<H=}2Qif?4P%_-|h zOI9x@f1X;5s`cFFtUxXF&ZYYi7946P!qKqUh|qB#d-&1mIxqcNXWz?{&`Gv_cz_jM zR2>I}O~EGd@>8m#W<Ny_VTSV7S>kOLf|s-$MeY3W->&^2u_`3RF1Z>K6+r(nG7?o6 z5R{BK`vEG{hQi|ke)}of@YJ)j7f2>I6)*J$Y_`>UdnPp~Oo-3{AD>cXk6_mYz(o51 zAZ1ZB3wXIaWwLXL&pu@zZHK8`2!HM-D1NIk?9!>3yC;0MOH;?KJrBdX#ezvcj;oR& zB9ml$CAnsSYofE45Te(d$WW@^S2@F+y~#?uN7d(Fd^y*-_qy6=24$cQ<tDLUEzf?| z-L1Ro_C05+`|l%$w))r^?8G#~?oN{{Io$ePgm42DLAp3j@r-3T%sRHTv_AeS*p+pP z@9&9O|8qToxxe2n+uh~(UH<J(=kNFHcTSB`?<f}YUYk=UJ3n5#_x(Oa@q_a7(_Kir z^;?~IcofR~FxZXNgm=SwDh+#%+66>>tcZwv+bf(0UJ9^YOV#yzFl21EnUdSJD1Y!z z`-sEX=7Y|zPwJA|!@hHh>3w;hPi6+cxH$GB>-U8v-RW>ni6Saz9-gZosF&F!MACol zul$p&GkJ9^S{eYb=381X=yy5PNfmdAJe||QLJ|!ZeRYAhUg2(1e#_PUwd={c@0L`5 zb-cQ_2CVN1b^|e8mny!yuJ_LMq}}cL$5wY{{P&%$vAZ3*bKhwH>b-kB_DjRdm(v2@ z%X9KZgkKN<dAU5mvs1tGFl}k8^7P}o!1tfcmx`1U$2%q~7vKsPHn-beKK^$1<?pwB zpMG`o7@Sv+)K|uzK0e+DeVbaiKZQNmWj0tvs>7m3k9c4mwG1VO<`d7SL(s->`~h_E z^xw_ggZ<^xPp^~I{?<Of@8is#fS@DD8q)`VcV0gI`#l*vM(e@3<Nr0}BLl+Z@XW&& z0Lp?0Em`9D`-=<;hx2KL^E-tL`h{~8v9rH{+gtYq(!?*2`M=$U;sEGTqPPV;%zZvw z;NyJ&2LbUQs2+L3DN<7&#HzD>2>=h1o$Ld^r66irQASQtCP7hVSy2{kQC8DYHak&v z!qEh+=rc~yj_e2`-biRsw9&Gd3kuK#^;-KP><|4%cH-v;@zsI|cE?<2+by&pfI5Vq z1oDz0ceC6;9OSANL<k4@SC~rHqDDATqk^b0SyXBpHO`NE=wO{n+o70LQqzK{YVy<v z)6|5v*d*atApl56#HF8%D|L!14~nbIimPsmgZFUQtJ`~7h;GuQe1l@thA3@W@g3B7 zZV$(0drIIAD8!<;$%9400%1Y%v}H=obi&w90y8K92GMT}(#VGaf_TVnlz^^q0zgk> z2`4RRB`rE7eGW=mmQR9)#~?kDo>3D8$>8jAB0ME&J1F_>j#wcI@W6949*a4%0e`(L z<vWyQwQ<Qb1M*u-yvL7yHz6Bs(J<Z=F2m$iCr}VARp<oEKmuS4+;#(Ik5`!&j8Ddc z9~n~o+5Gz_KyDyPBvvfhB87K_1`y%i2S>nNC-4{(d>h0*Q5xSw@{nWdnSjKmB@}Ff zYmY8<*)IWW$r~qoW~nH~3;?ngl<jvDq2p<DO{s_?L{_hqn=k@ily0$(+NSY7CW97L zx6d5~z3AME!~Af(7mNkGG^D^ABRNYD91tp^2RWb)&QifB0N^4di1wzqtiv+b`F*r$ z91tX|k?S*FiWtj#xBU_aBhqMBj9iK2FoeX@*gIr4C=5=tN#W2yCOsW$?*bjq;FqF# zWnlq)1Z*Sc@MgNQGsw-z=^f9Z`+>ToJlF=c7EK+*gSjG7NxLv;04hZRoT}ny{lZwW z=W`G!IRGkmfCF(%crE~B<E4^^vV=FRB%{x{?uyM-!n(R63)_xjdh&h>C%}wBO(H}` zJ>~F1E}{q}q!IHEIoIVVrj7(wkT4RSd23af_b-d%<s;b<<+_9-q&*sMkrGCN8U;a@ zs-!iEC*dA+E{zOp2oh(>2~9!v;}K_=7r-x4d%-m6pMVgU(;JS(i~~Yfz|hpZaD^x# z0DXlaOIwdE%qlV1#PE5fqwLX>3fE7~N>OI`)kM;s20$a#u`u4kn^Z8%GdCO^ciSTO z`AQkOmt#(W_eL=9eN7N!m3`1yCNv-K=Pj--pCUY*N!CdjuFQis(oS3D83tCIK1e}A zH7bH~jsy=!8th5*4dr>c<Vf(vG(zsDd^zIa?8QT`D0C4&qmx?Zazr}_6rn+?M0rJK z!pq0q8%CtF_mUoAcy)+UO*u83QE)4uwpX;aU#Iq&OYKld?MP1TXh-eXY%O!Ic0#mn zQm5{XOWkxx-E2->&j`HRrR0fd{en*YqD%efkox7E`Y#>zUuWyT?bWY~Hf-uNY`HXS zhcxWuH0*UW?9Vp*-D?2E7*JgX+?9a{WuS5ym`(=gTL$-U1}N6Zr`yQy+9(*>D4g3U z+SyndkShMWaohtMOi#Z;Ky;x29!!(sZ!t2fQC|Tp)dstonog{WUOmtT6<r?cbUxIJ zKeA1Fs4v$1P$S;RwYfoxXNlNsC5F@JY_@Y1HJ~G(7bA7Z@UhKiCnbTSS#Y=PNA6+* zM@eO!XyEzgBcGal4qjyGOd8D-<NLdXrzlr~1-ngXL1>`bX=S9&R%A*6+%V_Q<yQ0F z)~I+ejFIaN0A%O3gtuT8kjf6DUAPQpG3kkK+X~b{X%t|AuPGp4F0SU9gtn)5Viuu5 zK9gS0dW0A$FO3K3c(6nrBmeu64uB%BcL>ZQ^a)T|VsoPs*xK0!v*)(0>g1kpwZ=jr zaa{uT*webGl+`Z5`PQ*xomQ)mkCxyr0N|}3!wwAP<gGh9KoxjV*H^_{qJ?7fRgp60 zll4+$I~M&3`UJUwR=@(yztP8a!8NglQ6;d1tXx@yMbthmCAM!XfxFgV#ro6DY82TS zF2_s@aTN){VzL2DPiHqo_c6=^Dn}~b!}gSnW8}W}z@A@#&O@LZ=!!;E2Y@L8G1I!B zP;Kw8k>dIQ&XLeQm|?e$O~WRRXPeaZa7CpY3j}xf?pce#($K{Oj3Z}<aczUCGC1gp zeblW~^IY_yYv1|WhJTd6c>tiZFpVG<<}px~f?n2rw(If?D}@;{!e}cCWD&4ul)GWd z{ed<Nh1@}cA^WR`_N@k?2U1+twW4jbUg~IriS<y4J+>J;oRZM6%)(sk5>3w=ri+h& z@x#TVjh+`q$~^`V0h|-e$2*FcY*(;a4}3%#s_f!#ygK;M|JgwZhN%mN(P8>VBdvM- z0bd);h=?mVWu)QgfHH5M_=~3rjBIB2OB>!h`vbK&&?qnaz^WIZwLt?SrfT_LjWXs| zo_*@#Usmrxh_$z~MpyM-Ze6H109)WLFYP)z3h85edX4955M}^-WnX#z_e-1@(wo5k zod9GaQ#=&9psf4{J+6;UEmg-9;$8~=VR&NEVeiI;uRe(|%DG^Jk-pa$vWn?oya31( z3Wr}E(|>j1!0pw^d#|+eU+Fx4rT6}o!Jk+7!;?n(lO}GHX7?s7@+Yn8`Y>ISc7G;M zL5t?;+&_WWdskop>8MvRkJ<j?bNUTl#~xO!=Y3j#z2AZK@#o%Ujrd$^sHdSP)ZrNb zut?;dd-rA=Q#zv#ZsB<>5~hBRykSpFk=e&|Wem~TuJ)<u_tQy#rfG*~QuSxj-DWcG z&1B`z<UF3qdp}d~XNG=wwpf3*)NQu>-fU(5Z1v;W+V`{de`Xnn-!|#LZFYOxa_?<h z{@aenZ@b>Vee&mR_u+TF`tSPP-aWhbZs>5;o&0yhUQ>7f43E~GH0gZj_qAnwO?w;1 z{#)Uy0bWfV*lIa<Wtgu|m9jA6f8IyH-Y?gk^v7|jaRKGT_p8^m=kPoVuQ0XrxgWO2 zw-0lMs>7k<!@u>l_DGxySfHJrOSc|?8E7def8a9E`Xe@<d2@{a{=9I(yy%m8@ws`4 zzw<bW1!;o?8TSRb`wQ{~3yMz`l;;*y|1PLYd^~3G@r3)wllMPr6@1ir@=<T@qru;g zc!@<LgGCefMYH>h76pq|PZn+F7VZ8n5+pvIG5F-@{^{KPPfi7&T%LTg4Zt{jeQ70y zPV4>DvO%x-%C8oRGwu4U@OSFnDC=_5=fH1c3I?Aek1aWWU6`xmua5)QH0RgDmja(G zsOq5v@AJ+aRDtcJ(N(Es|M~^b&^gW?rF#b8f^u6zy+qRAWx4tmfYnR6&nvCm0_|Y} zO)J6N3$eLKZLtDd2vW{(1uE6HAO5B4TbJc?a1YP@5Q?l{<xgci=H>znNDsK`5FNn$ zcaPObyT{ElOvL=>s52F*&-ot#=%dS(up-16rH5NRU-Rrbt`5JEa7AaJfoO%btI}U# z8?ZEbt{pGjn*cx7ePKbI^#k&4-marwyaHB)S)!#z2X;*jwqL=aJJ3S{Qkd*-z0gKj z>6z8Nq^@Ok0WT$Ri5pnT=J`q3h$`m!Hy`_`c3p7(W&GPNQJ%-y1rmEtz9%ZJ+3okf zIbd>qF_6#mfBrxN^Ll?x<@8dfHK)dDP>X;fKY8eXeYN5D!zCim-BeIq9i91ZNC*23 zVEu@~HWvUx`hjf#1Cma_ir8X8lT4Ie{<!J>)AxH%Mr|9Em(z*s`?s^(-^Mo;IWg@7 zq**t%V;uqzw!X<Ix8pZ=?{6j5_maPEqqzIr%5txOoQ<`gBa((B@muP(ALu{we1Ko5 zh^3VMZGilgzpSgHdmX*78MqHgBVjHboDcjy`!61R>i?qr_UEQG6?K~}d3{Vqp>AsZ zY$>^%wmFx4`t!FQ%y~;Rx6S_dqMuOvrz77bFb%I?KHY~(!7oVmzxqe=LGGXL2SvMY zU;bGQSSE7+ofz+Var*Ca<8z=JHnhIG{9VGDxmEP{Z(rl{H;-jGH2Su_i{Ifa0*bHz zaDlGJ_5U)QyZ2|=e>6)vtbZRaa)xa<m$fZ`2P-<N141YBq4cXv>2UdLbN$&4OLhhN z_x{2~9py*tOZ*{Z{AI`T@RAsVXwkD@9IO9hIN!4;MwUB2zR&U8p`eT5{i48B7j#qs z&=XIh#m;}b&~ZE36MyOaclRgv{`}Rn#!yfeWG+dwJg1F?c;OxK)rVA-OCt|dE<Ve9 zjR2$4j{l1|?6T!IQD$3cmhbZO%9}d3r!j|JxBX`&4#xef@?C#jpA(#7?;7ZKd50xJ z{$n`5Bd%|Xm#0X$b$sgOjz2wE;MVy;^r+W~TaVoKgEpOy!zC-_PKyIC3NtB^7yq8t z>W0v(=8uk%qORPEE>y!qken-UV6+>b9KESEpa7MOQa6h05?k&JM^#xGah;m9OEDKz z{8ID_p<`&secEKhP)GFwoP5EhDmtCtx71#@A|}fV=Qh1pDt}(QR>MNdwFE7F?p8RO zY-1qOWO>vTD=U54g!hxBQbYeSYn9eTw&DCK{P<|0i!(J{alqvGi}rK&7G^-D<8eFf zhhN~pDFJApo&K*<MWN`_#p49S&}xoDF;0+M2Lw|g*_Cve-^3GVEN^&nkgX1N+&p7@ z>XCe3xSsa1t)02-BPoZZiN4do9!O2svyOh`Xuwv4b7|`(YEIef!*EdGi;d%X4^6Jy zPM4BRPde+n&G+$p7rHs}MP)&|`F)Exe%SaQ#ss`Y)!iNt@Re2YOubNPin6nZpah-m zokkjYBr0krTy7lUY~=@J#vy=fL|Kz-)YtLBg7B{zPSf&Id^_&DM(6<-2i%?Lcc&qM z_xu?vg*Z!~clhXhBWQQW)Nocz-W+hht!1E?fBQs{%Q5s_+&ycEH$Ci&MuqRqmV0Ab zQR;Bw#|+tYLoVQowrP5fvD6_T^5=NPf$zPpKair@+gYW8*OHT7R*3>&PJh;%a*Nn) zK-hXI%;k+S7fg0u;Oh?mFsrDf1HxJ>FgMd8rBXPG(A$WGzU$nO%kp_7?v{!*Ls<$^ znyPkDONu8BAO}P<`_2Yz@@tHl0O>IwmqLJL5s%@YCR&AIVX76yiHU;x7RQ7`TpbES z%`ABSN+>G+h+#WKx*y(@B&3|VZ0^^eV7F8B;XQIBa+mAy$~|0@;9C2gC|ac-GFq># z_=gVYaxrvwOk@bY!n@}_v5pLRxf_#y4wY)_=w|Vh{}yzstwHZRtXmdXkBgG=ci3wi zxXEAil;YoO`-mt4c+oUJLGTCYuN@f>jzzrfV-+n5!2($l1ByJlD)n-s2k+>q$Lq5s z{t*E7alan#DOBG-GGV-pUysz$ls!~}GkqoFDJ7B=VFlI{g;_W$YOUYEwV(#FffL~Q z<{H5Q41(_vbU;4CURT@Nf^QV$B!~|Pc%8T;K2TD9p}XHbu)idbMFq0~maNF=C0tsG z%Gnb(G>TqQ2SC$0Dm{^s9OWf*NLpR9jgXpo!PdSx8g1=4kyf`md(>3h>P*H&dWDI% z;@Nhqb1f4O8lt?Fy|t}f-b`e)_Is<|Znt*dp2&O(_fe15w(%5vl{IMMbL>I8jnBzf z*)OAfPLyfCShI-FnL4;d734GG^1t&+YL`5?+BIwgNN`KpPCt8Fu4U)TXT&oF>k;Vc z(YfRPkPo(j7k*-x(ewIMwzm@s`bV1(Vers^<FVZ9${50b4Cg%2ekQUy_HpMXi-iXK z%rraflkQBGNOD}ZFx5GenlV{=)bz5|*^V<AEt6$x(U)z!bsTcuOqQP-xNLX3!=Ye% zvf>|(D}-nr$6~?PmFA{w!+D2ex!uE1Tdu`_5Sv<+85?3}HIHaDcATxh^Sb6D$5p2R zopVhYuWNlxue!YMIM>qhy6#5w)eE0=&Ud_dU4M7rs{7B5^G~*4H~h=tPvp>b>J@y$ zpqTo53UoR>JNc$DIokigOIFu;<lLL4%mIHN%}(dBJ8vEqa$I9qa9t+k7P-svdDj7a zGJY#UYy)SlN9dHA;a=o<M|3qxHB6Ei+cx}!AN*Ag0RqKGTfvS<17;EJmc?2dPjB7L zLrps220}(lLDjdBGD+X6j46Oq?j70Y3;CbUbuHz8zT0W9y=8?GTN6ms;@wRAHc--X zs$DHi?MP=-l#sYK#Qe_BT#>)3i%(JZDwdzMiBq*{J+s3%j7Fp`rcl54K&mMkUzu;Q zp##Dd`tghM{yf;bT1wlje(`Eo!5M)dTprN<TFc+Fx=RI=RkdCfxB1AZ-08d=tDao9 z`B<0puBxhF;JKj#rS~%CM|-&Pu<Kj)$*m7c3T?Tq^v`8xiCmg_ei3mqYe3KESmw;A zui4F<*Ihm*AEw_R<{*8RrC8VR>^gN?SOgr}bh8FnhX>vVn!^pxLLRrOD)|gWE&X_y z?{#Sq(~bc4#*>%R0YIOz<)D2W3?V=PE&rjCBgMY?EGOwZ<?+#%X_4W=voeC*J$NwR zC9w+zd<8VkgjIN5Pe(Ct8E`QK0-M6}AgFcR_u9enPWMm~aai`C9`rHo8s}oQzVo`r zm<L&$4P+q58%DiisXSa!yu0h$sirSFh0IS$L0=f6{MJvZG{lUbvO!TEHD0B5mGHvm zpLHDRJ$2x48ZK}?(o7R&E9lr}EGnE5tyk)j?EF^t@Ji6Okq(1$Gb~a9)zkC(oVjmc zn7FjpW!P=wMB25{l0|NIocz0pFKMnOl&`lf@+z$ViT)}*b>32#3s^@0Z5`6z5O`D= zBn6L?0rzkrMib#bV)`S+eo!CnXobIhE1G@k#7k;-fTudqu~nr1G3xB=6q3>LatSTJ zNPmGL5BRf^S(uc$!5(LdFo0ve`kVMcXyRS<k;TEo*#XFD9Mi{lQPA4w#>a|4B0!2f zG~9-&PBer@v$lCVeYT7s_@G#lffRC#QnN;b-P+GQByjhIcE^TKoW*V2<G<#;+M6VX z>w(uSCdKU3yCN`1-dO4eEN1QaB^Uq~k-A2V3|O6Cp=60mh%^j+w@d_=9ApsV=Z8SP z&5e^?CBNQLEO;bRlVpFxS0q;M8#(DCVPUl^m|$b>F}2$_tevD8ncV*hBcl8$$uzw< z5(0pep|_|3ADh2~AcAOmx8=3kcOHkg>jLzs)|I;18QmzRHf5UQ9+{FRLJh&j&c-3D zBdOlB$W{*nV7fV69s&W#ZVXK;T#<hXYHV5RC$<S(ME^Bvil$dP1LW<Ghjsd3(SAno zz9-=T#bQS|YDiVqggV;@L*K;P`E`af)Mn|5jSeW0hZGVXcR!LEQki#fm)J1Bn!BQ? z5zLOheMJcb+rtg1Y6(=8(1&4oB+Zgj(E$~jMVVWX2vOJeJKi3Yg$&)vZbkRhXq!lt zQa-$G1Z^mne;1fus1G4fb}p#~Gby*Sknk`0K_KO3<w<KY#qT&J!L?=MhlIRqzbPD$ zYL5GR^+_OroQ>Czi=<YkXey^8pBm!e#}Gge{9Q**ApMk1i5@&x@r^w)gn%Rgl-U$Y zP-Q+Qic2tonlFOdNjcm^rt}>_2NTSzvWsEOs36+lp;}}Jvk2>$ux(8Fl%w8+rzEUC zZdo<EEqrQ|4|$KI@s;l+KsEBXKt1b)y4lw9r3M+PO*!}`CLTcT9TB0Z)TmI?;{<dW z>=tn91&e55Y^w6$rOE6-5<b(53QI$V68fvNrBg*H2RXyx7D!SMMf*AB2GcA#SB*q4 zenUIVFHSvr6;<QW{3s>=%?#>aQeO<-aJs3NvWzguLj{b~U*n{dG$*{~tr)VmY?)V| z%C<~dk%}5`YI@h0f2)3I_(_~hA0jTVIYB%WmF*HGUNhOG(s?Yut*<5kzkY@?J&)>0 z7X|WQ!44YtYb+bRP=k$@Z+1m)qHGjb2j3H|62QEkTPWm$7>9Vg^euDZBC6XGHQCI` zD~9DRVMLQ(%y7mvndk;3P?a9qHWO6FYf++8dXKM-BJa@|b6zNx-jg)WRFbr;a#Z<$ z$0gXb1P}t%{y*UoVmkj%T!J^}mULk0NV=L~OS;Izk2blQ#-Ar+Q+-YsB0T=~i#Yn( zXZ|-_LT=IMk)n{Y)59x|uAE&xSMT^AT;gP{ld^Y10S7rlNwCHDRlzl^VEy^_fahZa zap(O%bcXzhcyB#bN9=PSMr?O#1<W(<KzQ7h9yNV>o^||GLT~%SrI&Q$cnRB_=FhJx z9ctWPbUa#}VqAJ&VB6WU_O|Wj>fDRB^z;vBDhVsLU2Pj5htiZTa&O#CTe1yI_O^T6 z@pE<hq46Is;&TDuLj(0d^7NCg|H35>>L33XE^%~8_34v8zjuDD-f-$4pz;IXj<U#b zK|kU(RiGP+MV?${MS^Bp_Pj6^`T1yJpUNUKe+PpeEfyocK$Y1(DK2ybAVV=gDPbXA z{h9nF9~V@=5e6sP&q~nSX5$ivxS)$P6G4$9SS5f~d{kFX3+8iLu)jFP@!Vzat9@Mk zo)~-X6TL~O_l!wYAuh@&;(U44=Nv*Ad&2><lxC(QH)u?0fIbYW!8cgaKq_naKe&Wd z3RVS`4$VhDW+$d$|Ez$8(D&=*C1i{Y6gbCkI3O@CqWGmUvW2#6*m5ErCn=a+<QErM zc_2@tL)QRARomw)-dKeo3$UOWW5Q*a#@T#151_K)3ZlehEj|Pa*5V7kTv>ahe`i`L z->3sHHZ<dOMDo}ltM)fhBM()Iq<XG?>l8DBa2R%}3fD!T%cw?iFBPY67&+vOKueCO zW4`yGtSzLHU=Qg_NtUXM5m?o^=U}9giT@SD*be4O1)8F~Nrry+`|^zA5w^QZ;MnrI zv9cup@#q_g{y$#)+|Bf5<3-udaRx%o#=IUZ|E=+}bLx>3Hfo7muLwMGriu3Ful;=O z<XiXi&4s&bKc|Qkx8mG`$CleOJ{4};vwjcjPR^>7FZ;Z^_3~QlyP&E3U++|G4!-{S zKt`(Wu%do1E&OXGQ6IFBaOB(0Lh@0Ghtug(tsBExzV*AG^X?YxdT$r6eO~rXyB@Mq zS!mZWqj>(?UUI>IaEZe685&4&PJH*bu3z7NfA2<q4~2*-@9k~qK`Zw+M^Am<|G_ku zd{EW;Fa0;b0jhWZPh2AOB7PgLMd;={kZ$-JGv50B?{8pp){{)Ie+vD^v0U))&i=21 zKRcZ_$q3GtC(szweUu3<mB3WG_=&18nF~SIws!v6{T{J@1lYx}$Q-;(GA;pJGt)AP zdqL-EWA$O|w$o!(EMVdc*7l~kG3P8T3<k2|jE0QSvg?%Zt8Z}!2oHpW7N_@V!wHl$ z3$b>Y9YCL6#I=jWf7K>Z^hZ4-ErtfBZNGBdqrrI+h9U&h8>7)y5TrB>?UtYxs+qpP z-$OAze4h{>)XxL{8tUTsS%<hsLudp-$O2*V_e6%L`A+dBSeg*;PS?zf|E3soA5%)s zddDMqs!H#G9B?S0vQK&s7a_<$deKsQ5u-^CzktJ`dsqdCqrp9jv*Tve(NfjAR|D?X zuX~a&M4=)SA};vAEycUZs%-zLvDZS1K&kh^iAsIzxq!^+t|YbA;A5w^i@@VqhEjVt zxhmmf+0Qxgz!%W^kG_2lE3$N#nfW55g_8Sji-`?l9H89SJ$V;(930)L;V$Y9`Q#wE z?~AC@UpYwRspblk<jB)uO~gW<%1EqFxAZ0V#XB7Ol{zyDPwt+)RRsQAHaVXoX15t& zIMSJdn!A-PP~=eh<(AwD&7Efjds`Lw=#P5Gx1};fA7}~GRsOqA?U!l7Wh2g3I8N=N zk7B-8pO=-uNZ*;P7d(22$W`MsX!WKkN3#|_U+s{k3FQ=rRX~Vx8pkxC?*i!cl36Ub zpE>8dzPxS-{X|BYbVEWyeg<tyGjj!>Pe0SyZlvA&dietDoR7o_(I4w(Cz=|mLba8| zQJ0LkxDM&i#^q+E;xwxVMh+4FQjV0wwWt_&zVQJw1K09mjd>jly#L&Sd-~c2^dfS> zarDD-sBRwWeE6Y#0IfT{c0IH+GTi2F$D^jY+xI$MzlF4Rvi_*vts2Ns9?l@-i44^( zK8)6A76QH{s)c>fMeNMBKG`X|5&BE%;{I6clQWP$!H%08DtRmsQjnRNYSGxW^m#ZG z(kIY@W2rbzW1$;R;V$|-7mrCF05npK!#?o+{?#vMrxEwD(;e_Lbnn$}s4R$-WKHip z(;90`3P{MQ70;3&t>Xh=G>UT`z-bc%70COMC#q?PwIMeN7KndRbkKG@ACr{PI{Ha9 zwEa2U19}L>cS(c?(`WyY6!RD#Be^Agz$2$_C<_$X-AI_n_{&8W40bOW<hH#eb2rnG zw#!ChqD(kCl2l24u$AL%dj@Ybh0B8gcrDRqKM^<_Cm<5!f_ScA<SA+UWgibfxq`Z3 zgharotxxm;%@76<A!wlc4WOk74}7ue_PgW1aEVCUuO4EZ(_M&eC_s;#XSPjV&B4d2 z;viRE`9S%z$StzOaO4n<8;8fkM9EjL<+{$c*!`-Ts{3~5;qUj~l1_CksoX%*b8$|j z6U}OYN%sydLSaSSSLI0I5lcF+7p`|#UDJnP33w=&+}3~8ZX?che?j=AR=)}{Jbamq zC2h10DV-sa#r98f98h+ugaAkc4F48hL>~3E`;qf@|FhQ1_OYAyL4vp0#F4?z96oM= z!06t|V?xx&jfsa3^Q$OY;El$woI7m_mWulz+PWcsH?5FTr%dnigq}FW;cwuHTNtAF zr(LI^!ww6=R<v^4R0TY7rC&QIdxlCpwwxc#FGCy2%`=O)s^~M7-om@%pS-|u>qU4C zH4>k3PvytAV`l?YQK$%Rzyj>YtQHKRQI;U(M&)|uZn)rekK5J08r(<M0hEn8%`<#q zTyxswL)k$3mnZR80BVQo>2PeMf3aYF&=!odIIh$&SE#9l{LM6K&kEJgTRq&z!**bV z%j_r)9pXCx>{9m62wlQ)5e3XL?nM|17j?uhx4k>=2;;nQQSs90p(A7i(8&Vwef1J1 zkHR}E7X*;d>JdH^br1*=z2tirhB8W`TosTaaUZ=lvn}m#T&+5sWA`XnFBC34jjKE_ z#%9{&{cw@KVp3TVs#%h^2FYAI5ht`19i}2Qvm$lcBK4*t4R#{&!cj(AQ6^4NW<gOF zSy5JPQ8v?2b~{l7;pj73(T+~h=Ypc0vZ7tuqAyHGyYEC3g=0LmV!WJUe1c;9vSO~Z z#rRLhT;GWyQNd{;%B^L79Dq7^9$~f)lfZ$G)G?Lw=-Wfl!Nhw2i5-}Tgxh1!q$t7; zq^K|{OaTs)8ia|Qj=FLRyg4MQ%fOV-&~yM(z(N;-oaL3+EL?1fFs6tUTfakvr(ns# zoE?Pt4kq$C3z0^QZ$@FV@nG#voW4BIrn(q-4w;5S>9H=$GGSv{Y}+MF7>A6;$M>jX z=)~CGoyhHV(dJX3BXV$k1~N?@ollHwmPcpN(ANl1X#(;d3*Dg}SIkJ%_v0B@7G+B& zvysq*QtY)Ybcs6c5eZWQay}!V)|{YUOR<GC^iRL!%azoCbtF3o%U2x?BVe-uYQ;L` zUldT7h0Z3%WwQ|C>ZoQ^EZ^lA3&MYPAcjQ9IXaTVBUbC6DiOfPBC^r>>*x*wYHS)g zg`!GdPFHD<_Qp$1dLp#QFt+cV%)AVABRg0aXch?9#^6QL^_hr#Cj0Cduk3VJCmO8r z9*zVx0DvoWDpX3wdj_mvq4NpY4kkiO9o@r31GEP|meF3$m^#0791C`emI9LsrtV~x z5ir~yw54VANgT3=fGwn_g=<H{&_EqqCPGdjp;7dTlnxM6yq?w52A1P6g-mn>4Q)(> zb)qok%<SCVsPwj+9%33mM+VT5WzJwbKJ}($CL3ay5$3!{guPzQgoWp}&qS31m=>li zKtO2Xz*zH8Ks~w2GOO?)7EG6Ce=yku_I=9Zw!~C`DF_dqZ5q!mKH=3$WV!{Wo`voK z;MZwE9OD!OZ^0tEut2*2SkGy6hF+s%^VKmq3ZPS~_3k?NuVK+z3k-e+X-vnq(%^^< zm^%^PO3SNfVPM(C6II3C!U@B>X+2DY9>^)WS1_UgF5?q6@r6=e+@I+@p9wraap2P- zQR?)Kw^}r|3cQ_&<z=DEX<;?p7-$d10}VL3VA<W!qV+8Iy)vRAm~07pSz<~FsqM@3 zVKh*nuKW{M_#S1nMB?7gj{SG0I6L5uZ)>*C7jy*xk0xhdaKUD=a?Pu-@#-k?U`+CX zWvth3C2g+~v5_^ri!NJ69N$B`?!~_+By7$Y@6nQduEbWy(jSDwgV&L48C;n>(wLc9 z%P6m7Yx26&5~{JraN2k0>e}g=Cwnz;DNF^u%5Se4ssPTDledSB=fM1rcXLY!1!sCv zP3cGy0sIJ7yp_k~gXxkWXQ>6|qc3(K72A7-mOg|DBcmVTYU^ov|G_0N4XBNr9&%Mr zH>Na`XJppcV;x1u)k|NdSp<vBwNw`~D|*!7p>(W-2!`IBmrB4E(TY<m%aQ{zOdVS1 zZjD4|&XOf#K$IN_9J{$*<pQVCh2x5~;tIN(2=?d)F^r5ab@vXmYlcNIqwT1Fvx>bG zFbNjm1)Ty#muBS<Iy5D(j#TA?<6^gYM{<%8=}0o3LxKSdE5<fE#k*cje8g&M{lzbb zqr-}LWLM+TE2|y>m01d@<?96sQE2$p^drNe3BoBHq3LF!%~IAF@!*E*>;^I+;W@^L zLPz9haJF|N?=joL2<(>yBDxzH#z6JZ+hla(pp7|v8|(%phwVD@q&AA#o@gyv(lDFy z%`&5cfw@h`mf~ZRwQ1U};1f)FTW+VP3+D1$^aKGF0`h!WFQ4r&hy(IS-GCMV*HDM6 zF<_@iFeN5Zj|m-r4U=UigprblyHf~?`GN=bSa#Ppn~6!%qV9@xR;)wPgj143Ftr5a zBPOP<z1^ZFyNI49+4=Ozl>&G?=Mo+rLFZWnO66U(v!^qX@ls$6WU=zmvR~qI7CKrT z9nFB8Tz`<UN&|-*5gnjmXFI&3u0FV`K{TW0DyE2ljTP;MDN;-6$cH(t9F47^N?@TM z7mLW_N5^dAxo?P`L?&<pc+Tbuq$aKZC;-(VaB^FvuAm19qoq$+or1NQVqn`nbV}~k zYEIrxzTg5`8;m3wUCwAe8B%gzxX9d@{Rm?^2oKmeMxHLX|GOsX3Wg@a4G?)27>G$6 z`{FAGo@;Ji=KetB89%^>iVz{1^t&)Nz1m)uA6o$1rOE83<r6t8=(NKuM45a>F{_75 z3f;~^!<+{tM`Li$>ng=K52K5gf<tSIu{8;OAZ8G%G3cJ~e0(O`R0$lY;F-sB?=raj z@LYR%9%Ipyd+S_Vbe?nuoW#s%HgD1V3T89V?I33sJ(K<}Q+H<IwoTrr)-=h{XZ{u$ z;+;<lXkm(08TBmcnoiZiZe|%Oo<pM?pmmn9dSn#9E1BHSY`BaFJd5f)o*%ik$fKd^ z$^ZfVW+~Xw1#IC2pt|>6FE@L{#$8(<E@fu6w1Z_U6;<qz-O5s5|6Ya;hG`YsLPme> zPsJP<rV9M2M{AT5N8*M>nC}TZU(~x6h&)gmo=DCL*GoL7b9the2sZfe6VEe8PfT#i z{4lI=-wzxPuD@wL?16qBaydI{FOwAyc4D$KmwPUVaOyD`_p|dP@)SczPq0N}pM#$x zzceD+xpvjNpoYv{94ZRm{USlLFob)T&J)T&z6E&}@!T*7hCSjtywv+S7(A&*JG_Rz z#)O5%qO)VC#;;^tcEv^$VL*1VfLI*@lkM#WPFxv$k_XmKkJS>fK1w`GxWX+3?mY$~ zgUB<7A96Bg52mx{$50zIXM%NUqj=p_m(o*~eJRvd*APrDvo4eYxrUEFd|+7$vzPm5 zJ|@2wldeVEA7*gZyeY}&7r0v9U<)3#%4oxJ;X7(Kv$?tQNB8I-&cQ0Sx+mEIKHDVj zFWn7Bot<Sa$x{CCcz{OMrY}_$FAXI%&t#e@py_5$)~+RA{*5kw0lA0HExEu5(Bnlb zfi>!_4Qn+=6=Mep+(uSyo2-&88uuP~bdtbEN4ig6;`vDDiNK>TpW@zk>AI88i<(X8 zVIcK!$SQqsK;b=~Wkww-$&ZC#R5!A$%j%|c_H8l;rqC@Q)BN(w5-ZGGkoyZc86dRv z=JRB*BNJ(N`hTDJLFm2@pqE)(E3A^j*~D7%6t?G~<&#d!gHX)jeDuYtM^Fv)z;KzR zWkxNq;QbZ-puX|amGptY1zxFGXpdrq@Jq$6S)aH!6GZM<w?ZAOgiU82!H%V$-Aw5G zN96JTCEQ{<Yx=W#k$fnol=c+E`xa&oOQno)8g@PcO2pZCE4?}!`0%gDeB^QuK6v(r zMQ1T#keNNslTru^$hmuE@Ui0BAOIZuR#MMh(I512n>_j!&+~)0ih?cgsq>6?Ep4#4 zFm51z_9gW`SQGn(mkZD(J{WPHTehJs)?h=K5JM8@YGvcL#Rz+3r-MFM{k}%JY8{lq z$SAS#viH8+m=AOwia+<}%$It*?p-{W0{|=^;7U>4YW-Y*PYuru3EpYI{m5=;kH+(f zfW2<R_>|CWsg#NqJ=$Wk=5sB!L>;9Gz+TJGE!l3~@+-T|4*FB1y-mtlR%WDir|@eG zL+$0hJ1^Y*^B&4u+W&l0XExF78c&4nwAOJRj0${`$g}4*bnSpEVfHES{7R73w^ItB zW;e2p2s@5RiAZjdt;Jp^^}7E%F>e4SSgrFkmdB|+wfGl&kNbG7Ve|TvO`Va^WjaqF z9=*rn(o{QE_0Qt=Iv4a>)24c9m~!fQHC`oUkXE}@GxIdVsnnZ+k$R7)y1GHT(Vz!b z{v%SC+^}G!fzng@u#`}1G@BUp`!ngFp=9R?*F^@`a~mG%w5478_h;`1QHG;Jk{^)c zjkOk8B?N3W9dV3+T);Gbh|S1RxDOPqzN#QzkAbglt)y4lmzcytLHh-hI02Ra4_qQ) zhvrykBo-KaMcB%xl3HPB8|8P*cOV9PB%{Xn<(x_IrnI1GT)Ml?y~%!h?x`E{R{y~z z4qyK6YG4%sBpmm(t285M7;BDd{qXOzFEh%oHnl*KO&?wHSb%lg@E!4)6plS&oLqkf zM1K=0wob30aGHBWi#u<6v2h6pgJ^|mnm!<&3r!rKJZsY;8gX57{K9y=W!gl^QM*E% z)t7@Iw`cict!%Alt*th)n;oSu`T`=atJv(vd|{ZW7^e72-Ysi#r}DU^Eh1I|Ak%~? z{D4D+#cjnP#-W<rj`vU5xWxT^`%-@!mubd^w~c0*Z=8kXEdaExtV%jIqFEG|GngBa zq=g{gS{Au#fK_Xz=7m*iUlId`vVD)-lZJjuACw6}RXjU)fmerltV%Z1FlW674rH;U z2c_kj>@zoP^prJP)Mc71jwDCjpu5QJ;)HGZXKzTKmZ|nWS}PbYpT|ggHKbWOkzJv1 zVl14?^7!qC=7&GLp~tksj*IdFXP6ySQ{6Q<m-K}MsysLFg=(Cvb!%Fqm{_j-{h(_L zJc9ysUPiHTiKDVF)5C9RpvX}YX)E>#dit>f(3imvt<^q-+vbJ&!MbzLC`3Py3F#Uh zjPu@-q7)?c#-SX|XP_sYbWW!a9ddh;i((%0YU3sw>RoLp!U=?0lsh#HoP0Zizr>+0 zgsJj=?2ysv*Htsh(cPzltz{HDd=jy$bY9Ia7QQDpdGcZc^-y(d{kyQ+(nY<BzQqCN z@k83tLU)pi34yUFbnK>j$xBK6a-@2!zYdSXPlEu{iz()EGbIn?R`8iC=|_ZgfZ4P| zN`SY`Qso_6Qw(`(d4`mDtyoce`R3NJPh8N}@Y3gmwsiRuF@@K;OD=5DEe>K1{e`m@ z3<Dd{9R+siV_6R(<vPDQJ#e=X>hHfZ&Yvl(=q*j~YEm#w|FVG~lj6?g98v3&HZOF0 z!Zgnd`7;0d>(y69ug~54Ts1Qp+rci4m>1pGDan_~Sf-3=yzx$VxKOL`&Q$j@htI%y z-}gpE+?hiH5&rTf-hXPFhc;ttRTT09EIe&}r+RbDjSW@X&riMa_<5J--V=NC!!VfO zlj243jvr&mVbsb5tu7=^9o%6Kl)p7ad(&+qcIjZ0<3)q}y9y3DVs03bo(b)>znZ^( z9PW$LTWC(XyYWJTF-*})!g14Ie79La<;jlGcmmbS@FE)Y^oR$K<%9bVbOH4UiOLLk zwW-XdBGPEw=y|Ney9&Vqav{uH%Q#I&R&kzcn)c=+%`P$G?x6rw{?1*2FY}xV{R$X| zJK-_#-lP~Iz7f6UMy?b7M<j3<bFDkx+|%C1D%}wYg?9+N{FvwJm<{;at?}4s$9TEZ zQJ2J3_%bjrtR(N#O->;KG3Vd)UpEfRb_R9}SizSKH|5<8_JP>NVP1oVn!!^(#^_sA zW3AY?D4CxgNiONdQq1r%n|jY9zy%fQmZ10&oln`6JSab~-jDPgFEG@Z$Vf`C(w`*N zT=zO6ePjO<s2|R7=Z&|pta8r=81Mk*5tG(YTYgw;{PE>JG5!O^VpC47JR(c_P!g}K zmxT!LKwGcCm0;?9U_I6@D8b(FgxrZw+QynHk)*ek6rC%4DQ#<MdHth__C^b3eN|Rq z1jENbRqOP~Vj%ij4pZ)*RQ}LqW6`f3D5a{VSZbvaUo{maHH5UbSN1hM7EYD#7Ub-& z95s0gmoxV6&?%xDOJ>ku^<Sl!RErWp`QnLZXQZ<i03umpgOAVt>_g3UX~~t!L7P~u z$M8T?@F!^A)nv(E8uf|vekfW2$M-S~4_7_e{#<P^x>z9prCyFmgjn8WrKHvCdf7v9 zGUE)+TR2m9`$zJ?l_FhSjLjK@7gKMukyFRtIQy=?<v}#JdGisL;$hcM)$5D%uS24a zh{=}4+RVi~AX>or%hZ>Q@#vAtl!Zf&grh}ui^OrF4rgft*GkKU+BDa17afvHGEsy8 zR}!EtUiqA-O&3IOoA3chTfgg7M#<eOeCJ12b36IHa4HbG`U8b%mA|F&3fZr&_F@DR zj%`4MdmTHzKYnv&%bv5>%|TN4wR4wzU~KUhE?^?d@yw5awjjrIlF88x7R9NFvNGz2 zGxIB@=6@C#nDig|{I$p=Oe>9Yt2iHFh%!5*w{Tqcq+}-@HdmniIEnbi0`2l8EIUhy zFSH-uH9qM6lQ(JERHkiKnP}hJn{&x4f|06GtKxDHpevAnOAZd%n3k8G6Fu*I>SXC_ zkqmoo&>NJ2ML0_RacK)1@(^0aArHId5rZ`b_!JN+IU2%VK{K$lOo*Jvbg`fT<tDB% z-$Z4bs;eZlcZ}kANRzpq2=jb+n_plof++<LpnoLIs5GBgkwQ=>js*O3ohx4j${b0j z9$h|Lb@eo__37q_#Hf?EYE>@1`o92uK!U$rtihW2ou6Orkw{ADAs*g{oUA8uxO3zK zr}oGy;+O_x&3fr1zWPXNG+dF@uJ$yp3`QFck{n@on|^i{oUIw1Gm!)*Ryz|1Jm|0s zovs<aWzt7)>+#GxYxi9m5r<7W^2(4@D<Xp!?5T^{L;r{<3dEflk62;tZHAXbRlN<z zPL-SMFWJMMg>#~z>lipXP@*0*CeX5hd@8CeoFk`+NF6@$GKcZ`e+_}reNMri(eS(B zH!q1jeg}kQ03aytwg}LViIfKAW8KbtX1As26bCC0gUxnL^)_O1<N#n2COK9{s?Azc z=!YduvN=UCjdQY7q#pFp2QL8dR0z`$-T4s0HxMlA-ry1AQ6*rIK_ZH{@s1{02SCV1 ztC6~PL}8U;=c4vFnm7fo?2ord@c=+g6%TOiK?~mWirp1)xJu|Vl^5EnF@?uT#l<9- zdcVzTrCd;5BmE?NpV#6j0O;ZamJoDiA;0^G9RE`CknjVpgfnpm8qge-TthMH0hD@^ zn7aDt_{U8@=X-;MO9)#|*2CIAll=4|!`gEwNI?ow)WQ-?I<iC@&wI#|!yZD&Mm$1v z`PH$8=z&|t1asAV_!4g()c67iO9%c_KT*>OiGY}@$O~Aq2=rnL&|oJ_aRcuw81}P3 ziGYo75QA+%hq;>}#L|j<SOa!T2QZ7Y5etj0@B>ST2gAWTOe-L&fIVEGJ(Qp_@3M%k zv$n?=g-ozLOW+1`NSX^|znZ!!HozM%b30v=xFy&Ir0K8snjY9_iYc%M5Q!>Kqlg$> zzmYI9T_~X`p$eL)u#3<^t{XoXu>=l4Hvgm{!V9#AU5JQrpugqul0*W&e7L3>YcqXN z1v<FG%gQFbJBe@DiI?I&lQ1m9q6h~B76?QSL13f_slzwaIAoKE1DhwIcrbC02Rc{= z>iWDmVle<H9($MqYG|~Z5i@5aKCCD_$&kIZK#RvPha;edvpXtFWH`;!2VB&LpM$2P zNQcEDJxi)GH<JSZXeOr{xv0a9ScFB{(~p@Gjw;lLau`Bh#JR&Uha97Z0VBXA<ixyL zH+6`LN|dKm(T6WU250KMH?hC!vx;XJAQ*}%lz^C3h#>%&MYgb<s8FOyY&&i&yLbQq zXB<XEQmkcIf)7#1+@iu_U?Oiwy8lpfHl48wEix+0$Va%TwuK-CUC@VM)W}q{2VpeG zhP$aa_%(*2D4nw^o$Ehycs@O#1YEgDdxJ*EfS2MJ5oxQ6onXWU1eQ?92Fl5YERqeJ ziidZQvy~J!4OurZaWt8#vv`<-Y%mb`TDmF72TPNlXY9$!;7F@D1zlK#j35^P5S1O1 zI7A``d5{BDI0ulEN?9u&eSkmtn}>0XBL>kB;IjvdlrF%zqnvEUc;u>#jEu~iio&^y zl|v;$OA%2hk!;W+J6jETfS?Vr0)_<4yv!}Z%!eh2zjPc$J46+FIEQ#Z&3Th9T?D`@ zlnRU>#6#Of%78hD=msttivOfghkTGE+Mr3&EHo#w1V2EBcR&!SDhh4v3Uv4e-0DN% zYn8tgIjAekeEF$5@V-j<C4Q@@>4CHcv4@A+HSI)B5<47pum?(D18XuttgJITq615y zuAQ8z=i4iK$ha*;y^_&|GK`2;Ko^Y+jvz}UOK?fUY|r=FrZyA=7W|zP1U(5UMr1ex z6|0agbR>BRw<c1_d2~f`Bbk@j!T}2k?nEYyTtVK5Q1`3{o1!$>P)9jR!FpH&ODLQi zeInzb1anwS0d>sy$p?KBiY&S}qZo=RJRruLQM)P%;wY$J3`e}ft)k$WZCHbB&<A*^ zvrRmpVsr{~pv0*#(f{039DRz20F6l@Gl!zHE__+LD4bG;(j;qG0|0=Bh=fj5nM>gN zI6%Fn=OauAZA@|#vy#c8h<Jx>l!(507ogz~q|4L0Dn)%D)C$_toS6qzc_>3Y)WG>q z52UkKESV8e)mC(k_XGf^q(cnN)R`(CdFZuY<4>s)3gXzj;Pbh9cu`xLCR<aLq*2o* zRaLUtO#wxaq#z#m)3SW<z*>bSX}TjwkOxnFFHG9XNnOp=p%vpS(r1N65Dl6*(T8(D zS0nAJIn@vplRj&O$<2b-NrQ(D3^vFzAnF1DN}z-6Y*!kZET=dy3R%?dtiLV9$O0;; zdT_@i1yXu_H2-@oo_Y|1ZD2??JDjbM10RJ?iL<5WBZR905rs0>BQ3tX%Sbn41LBla zij|`(&4+O~F*%S2OVd&bMWlQ{1~jOo0h6OTVhS{{mvjJ!e5gQrOuhJ7R(B=Fz<DTY zB~_V~pF_G*=(-J_MUdyC168;p<r&!J`K!?rkR(;A0kzMRturt=F*+!{owZtWY{RZF zhpnwKFoDvOO;#EL9IGPI!%5XRGB=ie)vCfH;+$I@<)Rv$4TN&PaCM}DvWJhwszZXK zf-;A_LI>$dR+XJ8LWB*oHMfafTzx?_b@;|90M{BTirX+-RT0*wrKw#DoIgY}_H<F& zbtG4XR{xuPhirYSsy*G-5!_!yM$=tLdI;V+rH5g4APCY2ocxe^AjGk4okw_w`XtNY znNz9Qh9$5~$t_-OF%Wc^0>^4v_~O#o$Ol{$Nb=2>R1t!6=s>Z}85D)1X2ng1y<EGi z!1ARyk`)B%BHrA(Qk=p#k)0v5+l6IJ-ndj)>B`8j6p#QFVAe5B03Za*va$-<%dJew z*~Q+n2^=?2%tHcQ_B|E(TBPAs-VBBn1{qgE2t-5UQl`k&Tq$9)sfT>HFJ>B$6Xjhv z(%%AP+xFFm@Qqs;uGmEK1F+>*LxYXgNJV(;;gX38!2!fBQ(J~wP{Tzxd%&Z50EZZM zV*fLV$*9-{A;78!!(n+y;ALbq1Ic1+nVzESI0~}fFRoYWb2j3k2eU;7e(B0I#;f%d z2O$s;I2N{xO<$e8<9rD{ap({-d0s!BCsLtZSBwaCV2VY84V6S>Z4t95QY;~`2XuHa zG`^*c(+5h3gTln74=rL?F=Pi`gPNsT6<*(YYE^+s3Z?SDB^KZKEoIE}%vcV-a*Z|E z(FZf*ji{_$Z-{0VbisN2W!G)t*dXJaB!>ZU<z$wR;DKh^KnKs0wSk$_4XLbVgiNxT zp2GP8E0Tw_onV;s8`t<T3)We3CYh{-+?%r_Ik*K@&g4msl`TfGbFfIJy{p0vHUGAa zi050RkCR(~p5Z!!<`raRahBhCqCx;HJ(^veSur~O1Q8WJ;+eVxkZ{EZTjDM-#oN^A ze3>i-V&z?ZW~{nqdq{^B7MTgzhBHXbK2~T_l<1Cl7j_hbWuTz#yy;2Nq-{6?G(BJ| zTe>bN92{j}A0E+ffM|WDhzrd-r~_hhsE1>d-KoBoqWIy$IRb>fxhS$`gGOlREt$Kv z1ONzGWV+>{B?_i~7oZN4FF1w~cI$JK<9Z+((z8>77Cq84MW|!eZ$N`K(PUwJm#}y~ zRgeRC0FlLp6}ukDE6nODE2uKFgezPZSJf7o&Obdw>cB3vrgqJE5Cde$2mhWX?ISVG zMMCYz+iGNkji}RWSkYtsjEdxjFaBjVXbh7FW=0JDZQw>ET3MuRO>M1qmAbskgwAJ5 zk)onL>ZG=^>O;>X*an;I?(2RJX*%s(8E43nFKXxl)E?_t8JZ=M2eJNY$SZ8y72a`p zZ}`Ry8=8mkt+Z<Ow$=XF!enWlLT^GEQvfhCbSQ@kPw)JFjWA(i2S@O7Cb|V@WM?M3 z^3LoL5${Hg6a}F}G?2p!-@Q~#m2Vcl)*W#RNi3^QAQ2Zf)0XAy+UzsoM5f@-s5)?O z>ufZw2Su}A>)vq^XJa7{z};&u+4us8Ladg??%>%=N+1Mr@M2z^Q2*kwW}|Ji(VX(i zfNP(ojdBQT8gDpAYDzh{!c7{oR}Bh;WCgK05;U)eC4g$xWH@#uY%ifg&=zgetM4{1 zi7WkBG<$T&+BkdQw1Y)%ImXj3uc&1}1HbOEbsne_g^kzTa(IMv3%OFe!&}J1RtGK2 z+LlwtmIhoX3}}lF13H>ogITGTwWaP~51&J0lY<rn@>Nf+#+D7*2!~hSJpj!rPK(lJ zlT<_$&&s$j4D!W~Ra%MS#(UefK^B8mPIhIF3_CZ6kInJNlPsUcscqFNAP%l#n2y}g zHzXENtOdsr0ryI0VHmqZ4S8VzWpi|=iduK<Y^baXI`~*i9RKFkhfMcsI+BNDxd~mz ziheZDchy^Jg2+wcaI6FXVV`L3^lY?Ca{3NwgwMOGZg@c~LfbVqI@r&M2#atyh7!pz zjgrNWTvYk4OTSbzfahB7grq`7gLkxPm$!^Jf9!27NcMw`Le6w$`(XgU1)DG@jlYaj zF>S|*iaj^TAS;KP!t-Qv`lsjgB|d^1CPJZ56-#*8z{xLNFbzI(g`))es~{G15R2Wd zr#=l<soZoh*AQxt?6tp&-<4i5C-djEz{IHso8>gB9T8F(7xW2*sA)^en38ZPjy*S^ za5zFev@_Cdayo^C%3pHE2MN38QB{D4388S?wz6nlYyUV)I&hlBzPAeg;Y<Z#v?)M_ zZO=>CRtgH?kh4=Z*bksOOC&j9B)sIkI*JW?cqpHvhE;F{PuehHxeUt*hG2Z{rP>fQ zIJ>Jfe6Szkhuej_g?^uuep)f;$RGI+mPxv|rk?@`R{%y4998Nd!h`@8GHmGZA;g9R zMTKfbYFj>a_VVSk2Vfq#e3s(G^ENLc%9JWsvTW({CCr!*<<YEZ6M#K&`Yg%OC$3&S znL>vWEo$^A(xgRg&hwT}4kUf#=qasg^(s<z<MfH41^^T(QKA?YEL#>UL07IaWjfXk zs5x`;K8ExYb*ep&SoiYn>(b^;y7{`=o0rZn;{U{o7cXWy&mNj(_0mygZ22-wkRs_w z!_*3Zsf7tgkG5*c)WlJ^q~)s@H?C$O@5IeJiTO6}mw;;mkk?e7-Fj1V6EAK&G0l1O zs4dASj$Y;C(iKBL2SAP>U7b#yB1oDvfKo_Fr)C8}pFWxk)9sX#6Z-V{xp&iqu8-Oo z;nC&u@9&>sa?35@6MX*}NK{_yiS&UkV>xu%LE(KT-cS>sM$jpsSYu959O+~U8~J#% zP=W`Vs1$wj042_Kme@m1TqT}3BaM9Jr5tkv(xYCDJ;p=gLN_H73=r9U(#j~Pjj~WE zO*;8xlSV=5<U|X-RZlqKj04#+`qU$1kN;unb`wW=edq@O;gqSDm~FcG(v9<MBZQ7` z(l{4GVAcY_2ew#r+Cyduy5vAE4Js%A4l<Mud(?bkPl0wy>JVVP)#Ooa;t28Hev^7C zCXYeNLytbYtl^V7_3ZX(fBNWEPd*D_63h^L=t7D?1UWP%uTetuB$K^TIf^Kwn5U0m zl;}~CZD6t*W{SNnL=QRFsS?j{II;OGw=+Vg(;B--m5*F_b}QdG_RyrxLb!}l%Oo7w zVoR_G={nF^hz`2Yq5Tq?C@HplqmO2SKmtIv=f0U@T=p?X4`m8Vd>~CL>LZ6G1P3;; zba~06k2wIi@<}H|X4eTTqnz@PSpO}%{IXbyzAQ7$HOCy@D4;9^QawU^a}LBD&loCz zfaL`gI`vFJ&15ldD>T%%)klv`7)!Nr)VRT84_pj=@<}b8d{9d(NGi%ul)|dLHm~<K zG*78?aEj76S^Jlw#g_PCPdRbf{kLK^#bvS8aF>fU;Fpym3U{;Cs!Kr;{>nDx!UEtc z<0R@M2qox{lb5RxZJ9W3M5nkWNbv|!&vWVI<t*v3BQ>=+_F#-K(X!{3RxOsu8`|Ze zthA)RhvG{p@&7u63jq1(bHp~0imtnKtIBg@U8<Zz&SBJhKl`YpZi5Cj^qlnc_l${h z8p*-%U~4Daxnwi_^rys1F8}Ck^Tl(ds+)d)QluG5&><h(LmvPWxRQ$1<30oOhU*Zh zKorG_U5NsXDOm9dTTG%)M_Q8PR&tsVlCXp%T*=K?(TQ&;3tKxf7o{XPLB7yOTM5d? z5uWp<8S*eCM}rkLx*(MZ_OL3jYlv7tK`UEj!fh{6n@gG`Ig%k`4a+bGW#nO<Y+T|U zMZ`=E*HpEPRZCl6{2~MMk)z?r@Qg>v1X)Hw3V3xO7)?wP@MMCJm>i@@+#y*lK0q~y zp@Sh_grOUeQ$qltLm$XMgFU*J$RbWnja@LHZ6;Zi5_RK2Bh;WS+%SY-pzIWRybSwv zQ3xRDBOd7}BLLo^kN<NZQj;`Hk#9n>1ZqT5lD14>UZ9hYY#iZ5nf#?pa@Pk*0KgOL zGes*taf)Dkz!J6C&M6mj5K@rB6HClT-2lKvF9r#jirkH6AmN94n8ch3tk_mAAqaVp z<1uY?CrfexfI94{J9q?zF7`0WOoT#ti#ZK9Ph$g2WFuq?k)?I;*_RYy&mPOjPi-Xn zJ=iz}4XV%wWsay(l)#E*XUmW-HZTcW6f}g4A&4nF(E;<ssuJO><w&c7H`d{h8eYn& z?vfJ{Ib17ZKy67$8?uOpL^BwI00JqcDIv?KFc_i?Mlu#Mj*b8zqDQq#v>2%mN(ds7 zh5RbuZsZMptp7n3@-Qk|Um~7C0DwEDESo2EQO#?v3^S}?MJ<3(h)*1&64}THPUCu% zuqp=~LJ$W!7^PUK(L}9m{U}@~i$dX{?G$49L@)%Zi%f9Svy1ucCp-~>T<mER;LM$7 zmqH(o>Vpous7FR)E3wKJ#wl{RMP%tAQr#|OEV<YOLmUK1mDa+Eeh~{dMPb!81fvg& z;6_7+OWZM`6K*46mfyD9EurRP4aERyr^MTkCV^s4#XU_lYk`SAm69Ty^$Rz>Su18f z1h(qsuF>*xjwxW|OZWV5jd(kcdMrbT{nM^u;ph-J_JK*o%GnY}>)gI@Gf_6!0|0XI z2>|E>!T&<x(QY`RRkn%?C_yo!iQjaidLTm#bwcnlJb^YRk-{OLh1Ujb;fb>#h9K}# z048$LiCVzXp)o#jfEUt8Q|V(w&5PBO+e8!C(AdGyfpA=Vyx#lPp&_JDA`sjV)xPfK zX6+k+9HI&UIEEw3V-l53I5M?uh+!N0fR5Ab+#`?qrpr1Cub>lEi%s-_6s~|K*fO!u zQFKCO#XXypLLrvZn5Pg5V9O_P)s{rZgrbEBiEVLfPcW0ZdNo-vGQMzQK{siA?PUlk z4&u!{*uah(&NRQ4<OzMcfd{(qL^MZ{iDI<6)b!EJF7jg%RyTV(0iwnce3Dr~pT@L& znEymB#zL}`PNEiIxg1uSB;iFo?v4hnHcNJDj%}P_8vqdQf#GeOAL@j2;iz4{<C@Kd zkdR({sH-SQ0a`&AyAz}^?NvgdGXV4f6E-M>c1$T@eYYg6-zcxR&dPBE1(Ry}K*KH! zNTPtNmpjZ`88<VbS8K`-DZX0B#G8qUI(A~jrD&pgq&4#X(&u&cnDVK-5$K`Ir#>WR zF~Oefig)kWA-Pb?DSEeo=KfkH_hK^uHeuCKIvg}?`3%!%g3J2UgWlVKRC?2H9NIzM zo+fq$*jW+`0917dYVJA2jp9U<1;Yk|&_$?0b2GWCU4UyngShI+`1sI0Tm(b((Ekr! z3vTAZ;+{ZRlCY8sR){TZUklGz&_4Nwti3j+I)jLgxq9MMUR<&td0!_1fNq8ss&}+X zCl(UgAsqYC3vmU7W?!`3*k^p(s7KtD&lui*tM1fB@Xa#8W>Jir1CwwCH(e?eu!kiR z)zl6MlP`Td7u_Bm4f*xgf0f!to#}qucr8L5S{JMt(?wBBEfj(cXvZfIi~OO)Zsf&Q zaE?BR+yP$3)ZB-xN#4l0)P0TCDd<AGbzMv77(<u>DU{6n5MbUtprtI5BTa!mgp&zc zMkN&kB(;;=oyN@pKqnmA2gKCZP+d&0&nLu!4NO9J;7SV;-EKhN$wkATz5iGdDw2J` zAU)aL<h6o(0l+7y5)6=1E0|JINEj=q(gy@X!foNenP39;mOc;yC5%Ho#a|N+MFbYZ z1kMBIt)4D`f+y6%<AB1-)Zi0I2xvXdDU{Y5E+1gH9x_-#mEB$;&R_WGLo}d46h2uQ zvcxHHRv!cdCWK86a-TH$-%D^4yx71g{8i{R;t2vq^+g75q2fe6;xgD+8?v080gA}% z$t384<HVW6l^{!OTr`Ce*=->zt{qK;1m`f4in*dA3KI-Ug%rwPE_l<$X~zYrL|-ie zlM!47ePIv|;=_Sr3$C3#+{YB4!<M`bGbY8BnS;X&NIflG+BsJ)WdA|{+CcufOiJtt zU0ox51=J{c0$2pzIO38zHjty(1BbYVlda=ojY>%90VP0V3-&?h(F!kqqDtt2$ee~+ z;1xAt+;)iL8=hfP<U<^g5hFSzg7j8Ce8G81592+F6Up2V6v8P;)k=7lS|HRMS%M81 zO98TED%wOkoWw5B0Ywre_<#gk@dDf_-)U@`DexfxU;_TAmMxq@+4$l^_=>{05BwA$ zNj71MKu0}f!|KQ&QyPU(om?@5PZ55`Dgag?@IWkl4MC>FkHw2Ega#@2VKD}n`Je+l zoWU~W!%DU#OeDuzp+Q{Aq}&lilaxgj>KAo&LMC{i2$@33JpT>|iWy6q+Q)GYI-r9a zGA5<?#$!fi^f8{J;YuDZ1SzzF24>>BT%$xN&)4XJC5%nk@Zeys3IHJFIRcz&!XazI zrCgd=SqjD3=-!7-0)GVxp}^M_j$kQOqATu{IIMvZYD8)#r(-gwWGdg{Erbs&gbaXy z3^0TlFi-FV%R-clK>6Az2#;Vk;@Z)}TG0U|2uC?2CzSmL8t_6qoag#c-3fTW39LkX z31B9C0xNKb_&MZm#KkM+gCy(?1rlgu`UcgI&!4@f^zj!LG{hOmfDilt0K~x^HUxGC zLj>d@OpOo+7NP*n13GAm`79=gBA{=S3K}?vg36x>EdN9tC@BC~feh5ZLe#<tEre&a zLWT_)9)W0zj6*&6fhEKPat7&2oWnVwgE`DYJ}iT*Js2&HTrEICl0t+Yye9wzLri%B zp3YG%@W9_mmBj5QGlms8Y>puK1W=48V-D#q6lwqb*C7A^ARy6E=)&Hi1Rz*J2FL&( z<U%lXYB1D-B$R-fX&<p%7<uxBDgppCKvL2$p_r<KHH=D{uIZ7+RV6G$9UuV+hzwGg zK|`!30MO}+0)PjUK@XI`5Xb=!)IkZ9fXtB=vE=Az(g!`XT``?QM<6OwKIot>>a6J& z96SO;G^kaSfeFNEM8ts|)qxq*0T0OBHK~lWV*hCSy;5yi0<}b=n6jWlfB*<w0zIhd zw@Twes6qxX1V=6eAS~%ZC>f=8D#;YYtFj(_*sD4%<;1Q890V+_(nB38))P2{2UNu< zECRYR>^?<ml(GfO7KB$ODxTN`p;3l7n8WJS#>XZnvP48406-bggSWD&Zat_&Ab})Q zVO1DG5R}0Q=l}o|!9x52ldTM*WbA5QPhrdhWSs#u)CN~sEku+70KmaK2yFCFMPdOJ zmTdtN000;m!7VJw%f3W+ump0&(Y(Se`!P_z73xp4X?J2-6aYXTIPF3dK{6D=sWd8a zEn}3b%-q6+Kr{p#0Dunw>s3-I*gC}j82_S83@TX}s;i1=tc)xGn1K)I0Mr_RG+dlC z6sN}ysCwB#-Wr7wa3q`E%Y|<4S(ZaM96>mkLu*WIf)s;`I)n-Ifi!GDA;{;>G9{oC zM0)aWfYAh_h{F_QgO`kMkRHQA>;M4#0J>5m#*qT^=*1<hBjc!rK5p)6?kz;>gF5L4 z*k(d5e1;@Qf)5Nrjul=Z<ew|(jFY`a3pxmlKBxP7F4j^D09@>czA7B`)t(pu02~7* z=)%SE71(L(&;<i$CU8om$n|PU)^e~z7DFZk0|$uYK%m_%l!FB|B6ouD)z$>zq?~we zE?Y3fCZupRZb#mYL(VFngqguHX#XD#FA#k=1tqwFa{z_aPUUPyssCP6T`j~?9UT<6 z;NGc$E?jXEhj7J~ihH!`<|><*@c}8QFvb<i<Ss-xaPRtgpb_jH0@LtW4(ekyj~p{5 z*f~)x_^&lC#E3COtnk(YqU;^J@7f(@Z50DL)M|2`hR$&0C{*!KvYD7+nJext9?u2y zxeg?_$Fu=%BR+|a9n2)KamL9C0MM?4eQg*MWzpRmd#Dp8nQ#-P267ET>tY;PesOWV zucauTFc-=!M+7dx2cJa`kcufTBmn?Sf(^hClH{EzsGcrA*&-)#%o3)_3BfiT<u*T{ z+boH%_G8bTB9-1(GSl)hKmQ%)uwgkLphDO$0GvUEEkw|*LPNaqJJT}z5!#^g1ekuA zDWjq&NLUb{NkecYZ3gtIp5bAvDvKOyLKk7JwM;_*fent>F-x>+ezSTkupZkRMo(<5 zt&Hl~pzs}>NNXu!vWFm4!U~#bayAJm=t3VX07DRAl)7_FyW*{SRZ)%#d#FOvJu`vA z(NYnzXbv?|ax(nZM@6FnZRo2?GXzv6o>Yq|^O@WdAVVv<FU0YH_by2xf3-~0-4`H( z`E2e%FwPh605a?_T_G)7w<S8YM^0?<#2y4&RO&#;+&&BSUN@mpQ!G=I%Hm2gQQoL1 zc!Dh~f(0x@3RhSyApdq^cW1>8>K8B#U<YZF*y2Jo0KXg`OW9XvH)8rSc1_spF1gsm zLWp>X0`lzujDp<>wRR!CLRW$ErFg`k+674UF=IXnbm@W~1i`}r03S?lvG{hN8Y0B# zgB&iR)uM7O41x||0z=d-br)hpr7sKGgncM=>{)F>*rO`cz*A$kX^(dkK0<mNHFSIo z`9MlwFV2Or1uhgp9S}BYfur%!xBNY?rQ}7!h_z(QLp#><>=8t1QED6*ag;Iy_|-0g zr(K4=#=z)JPH==i^i4xDrC1aMsMbLpl!4*mnk|5WaCZ3mSqFogLpgrLE*!zUd4o5+ zLr`S2{6z?7g8zUAc)+f*42`2=TyVrTcyBHUU@pW00PsT4y{bQhzz-mS4w%3X_&^f? z0J_fSk~d*c9K)H#kN?&qL2Mj|R-qc`0U!WtnE^nOm-!pkLnm1TcU08}0JCTc8)LS4 z1204##6g)oD54j^o#VOub*?qUgDbScrVZj1x`7-Zo=$2m09YAQ*1}UCdY$i690Y;s zI=cL6(S%{h5bDAtI6zbx;H$p&KGlI5Gz6og`uc@RHsCFEfsK>{-boSYQ*%KP=)egG ztF9NJKJklK=yW$>ut@G@avofg`#=%Eff|$<And@%9-DXo>ar(V?)258ZFGM5?<kB| zH#_8mvi~@XBYGU<dNXnOxRaVFTxQEy1o`rnl89+_#(}^$1QK{a9E4l2-MhYl$;!wV zm7apV5Q{2pfE^vUYHHX+{6Mmwzz>|dGnuNww_08-qd=749f`#a7D5<$f?l?J3%dD3 zjQOrONyxX_5Rb(w=s|a^^e5y3P{L8-xqJ)mNs9MXB@99(5CQ-o{U*#&CbW#b*SumK z5#%m3Lu~dlwT}(-0pj6`&>tY1aYtRLOmpdi*}K=0xJ=YbJ#m@GlHkfHj0`_<2m6#v z28SB8CwD;=#112$co0g8&p6xb7LPa-*opl^f7WMadZ@|z#Fm9xsKww{n}4N*f1eq= zaQ^@S>L%E#g(puw$NAAofnxxM;W~f4Lq<M8gMPJb7~%tfE|>y1wpTTd*bK8i?z>So zaYwp84!h?*@FSBzxHDMr-VY0Y@F)NGNItKI!YTN(T0|E>BHohBxAI><4=GV+;ZFx0 zTgziV`125M2jAE)naX?c_lLjwPf$OK!VPvm%WwMn&;R%Mv-8If02GO)M=t&MKR^Hw zIFMjLg9i~NRJf4g!BVA8g{md6)~8OvhV;?(iPR`j4MBz!Ig(^alP6K8RJoF6OP4QU z#*{geW=)$hMNQ<RtJB3HZi0Op<?&`wqeqb@Rl1aEQ>Ra%MqNls;HFcgYE9y>vH#U6 zQ&Pc(6+4z}S+i%+rWN?`BLIzEF?GoG>C-8-ck$-cyO(cYzbhXK)CFKtEmxC11jE$o zZ)3-gAxD-xnWd<<J4bo4VF^H80HH!r7CoADY15~hVg<0t6UH_{N7+R^n|5v6w^0ur zICxPljC(eoI;9(TapT94CyzQ*_^LXme(Pcmnz(Z7*Rf~U-Y`?9V**|C9QE0wDA3!{ zr_Z~n2!LE|)yHS}a8#yRr1%8OlvuDp%je|_P{5{20brsU22AiEQ%ngB6adtSqYn)F z@IxR;02oif4LLkYm*HgVFg*qb%7h>f4l)ct5m{`JC0*ciQM(WclHr6C0sp{6#vOS? z=)r^_sU?%pdc4lWfdEnCj2h_BBaS=(FrmmPsXPdTfhMZ*y7uZ=(g-~cqEX8+6Ks!6 z(&(|Lq$3B4qYev<0H6*4ZZy!7Gx21x41My{%N%p^$p-*)OzN(nIQRfyiG)_{)6w|& zd{nt2+>BDvOEJx~C=^3t6CoMk03eRtG%eNCQ;jMEfF=N70wF04^c2-uC6h-@TJ?gp zBvuX@wV*|C4OZAk?YR{I50E&-k%lxJOhXWK9q0#vSan6XVX@72%qtZsC|ZL;iOm%N z7&FKNDRmIYl<Kr?*IgFB6$l9(6^bPmA_XFZ5CHxth(XXSdspCrwf`K?6<Z1#tRPon zAt+#iA&z*;>Tn^bKn*3%SYsIj13+N_T#0exkxAarJhuSgrM{9`Zh1pVgmhWvnXzMV zTr)Gdljfayw$0{R)DY;$o{27cG*^%oD2ZA?5!vXcq2>$euL#+plUDGJTI;R%!ca`E z!44a&Ym4Xu08^Y6TkW-x60TzRzGhqQxo0}%BQw;1aUc@u?%QveT#@zf!3j4>mDonf zy70vrFGv(msA^pD$ql-8JUw)Yobt^jSL42~I1hbsR%`)X^wZ@Qd0f<45Bt2;TaUf( zP|}v&_MPnx2Jeq=@15v7!Az)Q--*{4?c$N|*%X8+Ix^{l%>M}|`RU!&+!F?e2Ova2 z|CC1_>cI~-=z-F%J^b@A%^rXtSke45B0mvGdi3c(wZK6L8dCB4`7ibP-D;sBQ@BEB z{WIXDOveyHdGCM?91~~~$f**^Zy?1gmIE<3rYF#83j@hTHo74Y24;|iEc)Kr%m)Bf zu}UBE_)`gCxS<OcBp9|(m=6x}jd%dygfaA?f^1a~NC*T>UI4%yJb;CFm;)U@bYg;D z2mp1cgCLIpfE57%0xAF?ALbb06Tv7WL4}cwWi+D!p>#$yDkxBaTH_nx7)LqIk&bn= z;~nvsM?LP5kA3vx9|0LiK@O6Tg*4<L5t&FuE|QUrbpPZdAsI<YPLh(9wB#i*$)hi3 zl9M9w-X}r%J$Srhl=Zls1&x)G3!+0D;;2VGW+;<S^00@FDponZQI2xNawQ`KB`s^o zl28IOn5ALhC;wy*eSAY7-RMR*x}lCP66$p4h}28$F^_!AV;-i|M=D=3Oibw#0Q%q) zIm7wAP;OEs>m+6|C$mma7AqXgw1z+a0S$LJQymse3p~s@4phA|AJ3o%Jp{r_lh7j_ z`rt(m_TUb1oCBOGX`(*RaSnO1b4*i=hdqp8hdKB{AMu!CJ3sl2Z)}vKBw^`o)``k) z=%XF9V23u?@sD!UBbgPA$_&Gyk7QV5nF;mjN&i}^omZkmAA*<ym=21PV*QDm+rYst zC{Y7y0012dHOV>ZL62t$YNL*FV?1&YiAc-=8}@LcD(zuSbH=q;vrMWdUrI~btTP<p zkcT@`;SOm8!yL|_MKinMRj~9`AD1vhDtciLW-7Lq?!0Sl=-~~0=%Eb&u!M!up^~ry zz#ei~hBxN1i#6y&9QiP%O01~|E9k+bsQl%b&I%4jz#<&rNQNCI%Ed97L>>V3#vIrh zS9zkumn^+(W1728XA;U80C46z0MLwUG?TJVQBzR0p^b2uLmBL7<||?1+~>}Q9QxP= z9RMH>0Qi9r`bY;tPr^-oP(uir^#(oAQ2z}3;`b!>(5xT!01ryY0087jlQ_u~sE<zL z4ZYPY9yn3bw~|D{0Kmo{kQ)eW<U<~T>TW}P`A&C|Cc2>vYEA9&4vfweu%tw%SQzUJ zWrRZ--EfB{^dVzv3RAu6gy(FE#Z)vbLm%WY$2OLL4sJ$~B=cym9w<={ayS?ge$WSM zPppu7sKcRhsK++!AqYyyBOP^x@RZ(K4t+2p63Z+{K74_PWvXezBcaEfBf*Vw<ay7t zB&JJ?e8TnWrNwS8Cp_{|UVC)omEGWmK4{U7cQ`Z5MltcEyD^TyZdw}oki~X6eN?<A z`pu@9p?;~cgv`!E9QyDBCDb8M(*LTuf~lm(nT1e~b6EMzOV9^5Q8Ev2<l_vxu*a6O zF$DmGBOmHmF_mV>4FJ4h8sz{$JkG%lJS1ZrJM6Sk-%5|)V&fd=z{a@2feu?)aM1~| z>@e%imzdgvu{C|iH|7V;bFf1e<#480=&28akMg>J1^E0>%4+0Td9zubM>^&~k8Mn$ ziLO0~d*#sJU)Orc`XKN~y!Y#EoM9Z_P&PgM00}ME<J!kLGF$-w>15ym8}aZSJal^r zaO{vI-HQi37{Lg7#3LTu@C6{$A@92C73GRnuLy7cmyH(7nfhqPE9e1mdII1b;YdY0 z^Z{|Hm?Oyg7)Cpw>DF(UqyHJ&C@GbZ%4$R7M&+^=$3g2cj(h~z<R@pyTghRMH8{Jg z&&~%W1W}H^8-5`(l(CxYiELG@As=8~E=+5_k}1j~9=eUhJJ8{Cw|e6ZJ&#A94^Luy zOv4VkY+*ULVTWmuzS_6NE7osYR?2K0)bAKIG`+`luiM?*Vd<+qYTQ?I6e}O?7{;D? z4HCWY{WjLz1sm#-jwaHhy<Il&JkGuASL!1hXgCMa0YHy@P~!{VMDIuf#nd${BOK^B zD9M)r0NTtRe6Kc+snvuD9kAgIvf;tJ2ORVv5HjrbhN~eYEFU5v5bS{)d=4D)A?ftt z90DcZ3gQ5LFZ6~ll>ZX09a164p3j1)4X|FRr@RZ)^g$agVbj8ap2FcBXu%!Ifd)%r z`%us{yvG{=VDapsiR|H^@?jgq;P2)EBv1*~`U|!4p$XfI@S-Xtip2`+0So!$@%+FZ z#DR*6@HC1{CF*MS?0_5m>XR-_0_%YSVecSDP#)wA4}75>JWx>dfx`5G8@%VONYDhE z3-}PwFPy8dWUTJE3za|(0Bj1e(vK#%t{dp#?CRl}G7$hyEgn)0(G*eQZX;0i!5Y?J z8$jv*>_G^&LBITIA*iaoV(!?`PYd;-%K!ki1mX?};?>%V5O9qg=7H@R>a*g(m0*bg z4UGi#?dqtGxc^ElAL2nDGB6)F@RK}{&>9aI58`{cAs@J{4s~h5-jEPWjEANX#jMV* zJ`WnxVxzhT)6h<Oobh|0$sA4%v3_dO!U3>cFdSg%nZ|(yp(%u_jv$DT`%pu_kU`c^ z>rV~}9r8iV$PXmmO4*og7jRJ^$WI?sA>@ovB#MQh?BNWU?BY@`v~Zx-sE@=P(wK}) z8dJi1u#pk+0UQd^8fWhf>H!<R4IBw#1Wjt^xB(vG;T*#)5PHEHs}bu~4c|)f0OLuX zo)56-!4sYFg2G`O04pI=qTN>FPu?LP!YdyXGEkoB9efb(6mlw^t11i72<3s|h*8UO z(R;|D9{(so4p^%T8R84+ff~->9MB;hLM#60K^)=%7U^LMM}o|j0S(Y$rDmz21mO|{ zupH9xDz^`%xPczH%^pljnn)}juptnLVd#V__DGK&E`bq-ZYj%w>9D~U{vaKCQYu3N z5v@+eQgGj<>+AfG+VW8z9PusVZWbHDE6wQ}RKhHmFYVMMnE-&9puxO&YRIatCZEwJ zX)?1qa+}h`8M}!Z)}Yp2DgEj}AC_SXifSPKPanR3$?z-v$P5{#z#Lr39w>4icF_;e z!55QL9`WLrmg|#>g-<k!mrkrFy@wleZyNYaP^|GBz#$M|;oG8eAxum)-@qHltQx(i z9RFAk8@g%)4{afU)5z#@CK*wlGST?jAs_lGrsRQ{$_pOg!6bsp9-QGB%xU`YZ;bA& z9`ZpG{w=7kDIbE69h5;I#sTjb!m^ky5ml@%hf^L7$}qpd|IRbz+6xx-;r>8E@YD>W zjH+1L%M#?k3<b0D>|q?5iW1PFt6E4N!fL<VkDESIG!_(;uF;(2Ed3<(^=2Uuwy}*; z)9L;Izld@m@{qzj(0if?9LgaOd|@bMQXcWGmLLp4rDBtkkKW{=8_a<PU9cNYwI^RJ z73|?hh0CjW>6QBGA9VE}dQ2T&tJ7x49GFSR;^75*5>Qz69n>WKrs_}9&YS>X9RF@5 zCf5)$M##2savAE+8`g=Tn(7h;Y*K%*^Yj4?JhF)jqP-}=4b0G22h)PSVeoc=hurM{ z000(c(apFtGG0`j@=zb1;Sz*$r(O#onrj3t5*8SN9ONwzPxKqOZHK@Sm8OWPGEg6e zZr&yo00N=TvJ_htLP0~7AwLhgSjrLgp+_l==4x^UTM!=5G$DYh2bIAY&h#2+!I=^( z`wAixz3v*EX$MiY>tul)tV?J)OwO#~8KNNzdvi-=)G_ACf~-l+06?QcDI_<q^Nw-) zc-Bt$FHa@W9vVtLKPqM!g8kNDtLE(_8#5pLz!Kzv90HYJ`&AFEF#?e*2mi3)wI&sm z@^AsYfhXrJ4^foco)#fu(qaPvV|^|UJ&+Ru0Ylr!H$(Ov-)t_W7At!&W!a$<cW7#D z#hLP<5=XHiWGuYYL8Zc>8Q1|HzTpyg&6(oi>%L3666@3^vFfBD9IVeD{J{`#6ltNB zRMDcv%4x|ms#_6?8vax=8A897;SBV0m@>;Aj({3mt6&#`oAO~9B$77`?M>xi8GW^G zH@D_UPpI$!9KeAS9>E%a(?mto8+K5yxDn7yQ(Omyi6St=ylvj<k;2SD9rZQqr1IWK z7JU<xbMpbP+~N5KLItHqADp2X&f#<!0v_l=6C${R-C-Ew6-Waz75~nm?BWoV+L8s$ z;owMu%&Z}>xJVi7PFhn*_yjeSz}6$NwiO#wQK%s@K|*@ZVAiHKB&R@o(KaC{4iX?i z9LPa@M@T^7G``N)Drs`XSacfjfE&O;vpQD8D$rop@fr!uGvx^!I5rYI6(qR999mC8 z_3$=l?+z&RRojt_g|o$i4}s?q9zTh(YV4U7c$Rw59SmVBcUB>M_8OX@ub>IwGHui1 z@;N~bu*RY6Ts4#o5|Pz%kwe0n<e_NIp~uQWyTo$WLUmuY?vs#hdh@{;nYY%uAc%7@ zddtttWI1aas>_-Tdb`&f>|qI(VVmaRw$gzd0ALEX0RUc!f&cr0k3Z>^UXK&Xi5r^8 z816tDwXYhPiV+&uHBAr#C0C3YSxriB=Uguj1%m0gArNMvq&_M+uk?G&DGMv=rHnT$ zh;ycD_Gk;4fqIZRL0NGxITf-2g`H{OWTAyCS%J(Ub?pu_!P9%}w7m2I9;`GW{sf?; zRI;q=9lXI1G<k+_xJ&hG7tVldtCD<KYl#iQ%7%HX0QCU96%qi`7aKy^>Y>>Hpr%h1 ziK*e0SQbV{Lz+)@9Qm+?zU|$tL5)Kq|FAKfLzh8KQyvzOLf@6?8jCiWj-9`)^f(kM z;W2IHEFP@E+zdjW{rGrUigat1-_&lSVz)=7)jJJ>I{(9KKG}}U&hDB(0%ajFcE!ni zc$6KAOC9j~Aet2(>|q$(VH||kPTAqGbS*}67?dcE4tBwqtCEV#ck-fl*_y2$fclfX zbs6YD9FT3N!|n{S;VzHa&~DlfVtKZqnb9iRmyQy+K1v=mltW8u*YwyKy;%2nsLv!! z9xRm`F4Q1UiK`Ws11WHX+!=nMa_TNi!t}uy-XI5ZfL?F7toAu7?k!bI*e&}ipg(D* z*kK*Q0Um--Av!wJ%nOujZLf*DAy5{hcec6cNgnoEqZb>xK`kGyK^6egXERN*EBT}! zW1TosCDoy|B^&^jVYS3GdgtLAU|Y7kwI0O59RHR88S;Vh5CWi7OR{>8wi{||Q47MY zb+-wX9*CiR=h+_A!5ZGM<HmS`O;jGVt@T>SVar%G;Z0(Hd|YwU4y<99g8YK)!F>@o z$dhV@z~SADVMF5?{$kXqqj74BrP6#i6(V}QfqZJE=g0Cv$c(B@`EB~%fl2!cpZU!C zu#bNQIThf6D{m{|eyr_ek|C}uup~PUi}M<wiQ0-cY8!aps_G21mz&%SmC`}8rXU*5 zlzR=<y*N)C-0ai1sn)Vrh-qnt#@72dFLvE((BrSYHt);!GOr@MqES8E@E{tX+*Z^W z4~$`1Q^}-*e8{Jv$lE9;-I)<CAs^tOZU2KEK)r~$-@x{w{8n(U^;Yy#4Gon{%$gn{ z63juf?0}?Blb1#|nrT$7AMtf}X<83--p0!vpn<4-{H<harV`u|VK5x%A=8fb!~*3{ z+MG$B$<D8p-}FJ=iE2`3$eC)Y97?+Q5Sfy{+|lo1-vWiqR7=FE2<xh_y|Q=H-@Iql z#J$jfO26sg6|=SEU>CH^Y3B{ji^ZB+Uf$#wBpWjxzJR6=SW9bNI7KKB?EnCFUC1La z5=_(F+#TzTG9MPT8@?K!1>#SbPPaG#+~nb;UUS!sZUHq_j<NiI^T8tVxc~#+984*s zwDB6t8LEx^+-H=pI@ffwkiCQT)c+jXR*O#=o}nI|uf3m1cQrU6py_899p(={JHz4B zKKaBt`UbTjA8fc;?Nq-Fk=AG2dzebK+T2(qyuIW=72=Q6N#0ItzMo>AmRw8lIG-5} z+O4E@3Ib5u38FriV5nz3w=X{Q*j~@J@sqlHo3+i}=(n*Vp&Q;$xvg=Buv_(xit49Y zAJCYin5kon>(i2oyDyfyvBAlA3CJ-U-8U*Lf3VK;+1Uj`9~?RFD=HIztOt>A-kwPw z5OVMhyz6Rq(Wj52Ldetrf?YWP1PdB87%tqqe5u+ctXGeqJ$vEwwM%91n?ZRTJ9<0_ zGNj0nBuknkIdS4SeR6i8Q~x)Sphu4M(&^)c#-6u%=FEwlI8NV`W%^Ril-HA-K1*`q ziK9pFr#*u7@~uIp@2EVg^u)2;RgauKtsGC9J&QK&!J`E8<%_2;5~F<FIF=h258E4h z+~UQHxfZE8dGP?i3Iq;aJhw9Cx#h?W+#76zQ%)^t8J#{xbHT;idf6bjxPkO7&est@ z*@8U@a?^*$SJAQgdIjnWfN?>xYJ2-WOSY#zcbe>V3kP`POaKbK8G6^Po5-H;^l8%u z;9O6RfZw@G^(}hxkQ1YiQ}zsA!qgzc0jSrG*0{zb&6U$<jn=zw$j5GF-VHpov{TP< ze)0BOf(o9*oju~%Gyjx6`6%ZRQ~;>5Mm{^4^o>4WEHlwot9dj}KFh3O4>}f(l+HZ* zsDg%u^n7%XI{EB^hCbq`quO!{{s<(6KDwsQ8^+K!;e_#U6G$&Sjx<wVcvw?TXpMPP z&NpvN^A|~O!4*g(`hY`YTlq|-7dT{UWsq*%U~>mHpK+8=GInrtPHq$KHe`@~qUDig z(dpC7HQ^jL-cjXs;~g#Th-c+Q300>IJNk4JVn@`OLyM*8m{guQ7n$=;LT8pqkbCZ! zwP-%gG;?Wx4IWD9HR41^7OH>lT2i26Wt2~ZDG6DVJ;h{5&O9d7qYoO?$m3sw4bI~Y zI#V1Y4^-nBH2;rMyPQ$aPN+^qPCiTl@YIZK^2)ABBYyOlJlt?&$29Pq_GLWaFak?C zg}IfeVD`i_%^P=F*<)kn<YR|1S?Oj_rr>Zh8Ir4+Sy-CbAW2_AjKOu7XB~k<Pi*?= zDWtCL?)omBXByW{KD0bjPeSG(+@nW>E!2!Q`i$ci!~pbU&pVnxCu>KN=2IyE@w9f3 zWdub>9I2-I7qM{)edi6NY!wvUJC4R<Gu8kcH;y}o6ewNJxvmVi+YPp8;u-p+Lr=gH zK_yN;T`W`2JeG~u;)^+wlXtY5n$xXN)YPLb&J#6Gi5~GJJKjV+%|p*NXl!Fo<kJ2} zQp<104gY1XE)%AYZQlGF^j6>`g9kQdzN`6Q`WR!!U8*S;Z-<<zbJ}?E&O4c3@wWMv zJaA%Dmt&|U48TN><@HB0>4XTtYhjuuwA><+jyjM*pC5F2;ke@{Jqc~A=lL8-cO3xl zK#fp0`drh@q5T1DkGq(|BB`jyIDAJQd-Mbz*6~?A04TKFRi_yQImh`xvZ#wF<Ty72 zU{B^Vpn5C}eIyKD`Tlgi$$9Gx8sdph;`cJX>Emwz*q-F<(YSAgMR4}e4FJ1k6=LXv z9uY|(weoR>W#nTXJk*V4sO6zz3^8#eL`w;ScEXcf@p}3=3^#69mU7f%OBXxH`830s zeE%edd|(vbT>gSHnb;#TlX00y;(?BRF~T&CL0L!$Q!sMe$0+*ng&p+K7xG;(i+&;t zV8W4)i{ztJ{Q*f?QX`LWn1eX_fJZ)VW+hzBEFXwcoLdHX5q<OreyLK3J}PyoOqEek z0H{<w?nga?P=`=Hd&kf&X%PKgCm-}c$6!v!$aYOjDV4h%53ke_8KMC!$}*x-EJ24I zW(t}$(Z{#+;SC#NFm&XoM-rFF!&%}`DO0dUXi(E9cYUOc$+YD7hP0$Oabqg++DbXV z(Xf*VtwBA3%kaQq&&GfwACV}{X+Uzla@eLXrzvB;_SLV?JSLYYvq!<ep^k@5$p0SL zm=Z!Uqquj~Q$b|W&2i#$%R|9WQJ48nbx!%hsjW{F`k<sNp+%7nDZ?46tRzY$r4V~m z3Lcp1Av`-)5Ph&i8J$$eF=;d@rm=&R)!U6kC=$s6enWo9Tq#RuvN><)V+qvAM>^7h zzaCjHADY3Dj?_^PsSS;B<vhdVIJceuG^i%|;6;XZ5?6w3u3UbV2NMHpnVzIWDUk4k zJ`hJVqp<Ohf?XFq89C2+N@PiI$VOhPXA}UqQ6Cn3YQm%krbqx_O~88@NAwaIGck{K zjEKZHl;>KEEr}7A@R#()_f@xevY}&w)?>~A4m=R!ErD6iXUz(nTusUzo&VBDJrc{O z21yD4wTg~W%L9N^mMSod;#51v0V$Cr1Ri2*hdG*h-GU^9lkh0VRmn#*qxsZq2vNv@ z&K3^UVOKc`ItmckO3bLB7Mh!@$1XCIE|4s?9&B~&JU&a4bmRj=;i{%cLVDqPhyx<( zoXA^^l@rANS1k%&Fn!hq7hm8(jb8=KXgE_2W9GC+@lw-d)WIHzz9lb{`Jx|h2bWhc zA~6p&<DQU*jn#4VOZnhTJ=XLXcz|OTjNk@5^z^p;+PHLVLFz&VM31JLkfsFD$19o< zkNEBtXtuoH3oqH;YsezcP0boohr`oSE-x_5`A!d^MkC>PBNh9B<o^w$lMh*3gOuIi zQH{%2#&u=aS3vY@;GW4RoQgQb>C)?l&+r~5Zd0zIqlZ2`w+(urnt7UG%H?|E#FX@; z95x~GPOLgQd8$s$Ck$<pokkjcXhctzk%vB}ai?^cDO34+Q=EXyU^F}L4dmFT^mdz< zKqP}48V#<vZA3<=M%pL#F!D5_m7D76BOA%9vUQ)mW(Lh9Qwbp;J;DQ+fceTj-l24K zzB=Ff9_q7;@{S?mT<DOP${G&G?`G-Kp+X%e!Q_)vhcvCVqKuPP&QQjEJ^nT9A_!13 z0U9=S1d)^ph92emf)rPjwW{ob4(Lc1a{0tJdwd8TyGChU*Z&}ocf=gEP`UNzWUX16 z0E<9$zkhnoWVs7mnCs+t<tt4T?dNgjMKL*58JgV=1TjP=w8z-P7;mV@Ihak5g>7jt zX8)>d^dcweZKvMWumd(ewdk1#T;OD}8OJfs%J2g9Q12LrAs*G#+#xzv4T9#R>Z?kT z%nwttV8?w)p5K_n4CQ+M>Y#>NRIIH=eeZaOA;{r1QFAnI%T9|&AmWvCc|-I{TW7PR zh_}o+XemwcMySar!y_z1*Jo0)W&}YA0E{Eq2TA%g_3>d$;$8Avm${GJve0_ji0!CZ zlG{DwN9#FFU%vQ*+D$lDzknkWk7!=p;h84oFne*NTARTL=79eWeTOn<b_r$HZc4LI zfxroG0cpCoc#Jo2L6r~u<3EvSI$3ocKT}5g(?9%iGjWv?q@+~r01q=VWG;m%v_Mqv zLts%u5&F||=%8nUvOcLW4wQ5%o0V0Ck`LdoZ1MCbrgMbyWEsH6e5wT)zLF`8g9blW z74W1RPnQutr5sL(eLB)HmeDsyKn>pYQv;ZELqUE1!G(+_J~cLe?9x(uf(`kwCHKM@ z(vvUWz<;LUM|7eZfAI*B;2CS@HrKO%l~51u1`><G34x#vWP)1815a)gWM*eaaKQ-< zh%cxyM*#3WhNyUK7Kd=-NH9|lsSph{V^j%sCFRjTG1dPc(xDGCqe=_)NuVT4@gP*} z01+s78JGrpWs`aop%CYAc{`XA$H7UZl5yh{Ga=|_qiBkqb%dqZgeul7M3Fe*<`I+S zO>qzp-q4McXb&raede%z0OvM{vkYILBTzAb6X6wKfE9VAI9cO`l%Nmjz+x6yUDpUz zpe1VhVkfo}59)wqsj+1HatY=DJB^Vq`p|%7w<oowf1JTbCbSaYb5ii*V_n7w1F>ky zu_S-s3$G(RnX)iCHYSA;g#ejQNSH+k!i<i>ilbINszPb3SQb4Pbv<@Nkd#XBU{%l< z4)GCn>+x|1aU2cTHP2WOV^t_cLo`h(DfZ9~!_fappHzORbB)#}A!jlh#K#@d7A(~8 z9&9!dkfRU90FN7DgJW2RyB8QPa$)(9VIeVAQ*e(e!!7jij`652fEkcW$aV0dB>4af zWu_QrHzAPmJp6Q#`9>H_;tRj^WL5?l+z==AaBc^|K)n@-f5B`$^iePYR5=q9*Y*bK zP$gMcXLP3z8}o-Wxe?H$QUqy}Qbh|rl@Q7%B7k92%+ezZGgT)OSW;mQVP%y==6VFw zQ_OLi#yCOOu!UwbDX+v1@{n;9XPpC5R9`8F*4TRwax%jbkb7fm)bKfwW0pWwbvU6D zCWca8;g{Z3op_ledub3=haqmIE+)aBggO6p@p(@&*=(niB8+((;KmmBVI-945pq{B z<1h{c*dv2yK}I4{2BDCP5eRz(4)_)lV;3h`c3ebuCize>u$fW>Q5e%uJJY5c2g+I0 z2x_O(4Wg0?!08^G1x=RW9<K5V^}rw7MGNGWc{P|^7BLL=QJGGels~#&)j2f{G$FyM zUy$@2?r=5XMx^?qX>6mL>`{shwrrYnS>Wdlkdr5KCK!~X2k;=5LIOYvsSoZc4opNL z+9wo$Nj}d9j%WZl@<=|7V+nB}58~2UBEg^N0y$F$VxFa-yl0*!>6z1@qGy_Sc6e{% zHdoL>cL4At_7s!lpbqf{KwtGw^<w{9v&K9Gfm`ObQ7+?2oIww3l4S7!U4bwQeu#;H z>1<z<raw|+d}b+r#%4omjQa2l$^acbIzX$kA9m?^;Q$Zlk&}TDa=v(_O$ibmlAQ3c zoXk-X-$7`yYJ)7-4CnB0Z^(`;bB!+MB9LGORsaa0Q$#ukM2k9(_KB*s_8{LUu<v1O zh9#hp_f_ejR#g~b9Rox|$8&`#t^mM9+ZYiR%WPpOe#Z(VmxNCQ^9J8gCDgMV_t9JB z&{~&dp>JTSpyD436B_`KfO~R0)9`I@;cl}kCF`bTF4K{bkPiaL9@oPpy+B<MgPUh+ ztQSkKjh9pnQ4Uf`iXFjl@Sy(*m}d?_IyJq5wPbn?mm-x)YAN`27L%e0=kPSg)JpoG zX?d13QZXs#pb1fVhD{qJY@#Un5EOf`2h;!$lwet6ahQ%(E`mS^m!)l~Q$5nO3wHw& zOq36lkWH9#u{5C+RX9bH%UH``4v5NZP*jBgU?F;|csdG}3CbP=gIfc^USk0O_rY8( zD<WSK7mT0|uq#gsQ@cL2WN*@Mi>74y#|e+Hh<#L{Z()G{)Vcrz0N7A}hPymI@_bHv zsmi1k1s5OF%CLvKorNMoUTYQ~(W8ZOD{a#lSp`d0TN3-lQ|79RF!M??NOCA)o#P;$ zK}w!`E07qg6x6T;JU9Oh^x$)MBVlK%EcGA+Y+Dn}nk`-7A%Md}fRVAgAdci{m<6E} z03bz>suV(y4e`K48;r5ukPiney7NkY&!)PVDn13FiGjdlhdH|dzzC&rv%vHg`4A>I z47ME6A<T7V9@CJt<9vo#y!yg_OSVyfkq_$7Fbdcv-jF=vCN~3_GV+>CG*xiVKntAq zz1XWhQ>6~RL=dS!I#cnzXk&ZRT1M-^K9AChB_SyR(hSa!B_yXl?BflT#B7-*Oxp0A z{Ts5qR}jTw1=}zV<WNq<a5#d~!VlI~eww2l0TI0>2R%h^mjOhIYY)jHPlba`VG$CP zj83~bxh}G(m&O0FBGNH%Sgaw7t(WX8GTOW+g*z!R5XOK92eT2l8z%MUcL~H1qrqH- zVZ_Sw2%KP%Ueb^n30&jB4LXaE7vx71qkdS-7T4>sTFfh_Sa2;zwtB^ugL5eL&=C8E z8E!bMXG0LgaVTvw9?~ftM<*3`oDX-#HZh?!?Z8vMRLA2)5adc#1NOpag}ruEL;6q% zf^ZJ$@*sjB2&T*@)k6~iunlLh4G}z3#YZmnFqnI}SoyF7*`OjeRH<!gYtayw;ip)P z^QI7nb?j;xRTm9tfDV|GQk&(mh)iSIdt<k3v!tO$%A9KHLt5BiI~3AGQw+P27g!zg zh()^^`O^Poz6EY0;U?2ye}ut327zTxgUzDh!(viVtc%aD^>3&Gvc173ivka+;123Q zgXKGLQ3b~N08U4vzRe0C3sHI}BNF(L3QYAota5|z(7m|Q5yFI>0$rVc5f0x#9QGhW zuxrT3nk$(h4`iqh$K;Ovxgx)(jg%k=;@}NqyrGO^BJkL1{(;K623}nl6_8w?ldBKQ zKnLYubdMSmRR@>g6n<{qS$S(uII4BoE3(C>T(BV<yeoOzkr#I`4HN}N!V3;~IHfi? z5q^<&DtbPCVGn~?h$fUZc?SR<x{{aS7wOQL_m?D~aT(r&*46uO48|KYV#0^4C})Ey z4Uzv4mbTnmkyY2A4eTQj%u&oJQH1Isjli57(K;WsEMJUb4_gZ<+u2>x;iL&PDRi9= zT$<4SEwUC&S%vFD^q^L2Pz(`v6i#RfY)}vB@F`4)L-l|RF`^=g!x2X$!X(^u_GBT; z5F<QI5Kc%5ZlDwFDiVBy4$gwH$bAq*vyj)z#lH8yLCnzeva<u#5g)@1$4fjgB$;pU z%p*~4`E=bb6H(0!cRd>tdN&QAnRuVlTkQ5w#g})5ga?Gp)}f`}-OS%m>%U~7Kk*R{ z>OsDE%^g5x9@_8^*B}oo0iAX%ZR*f8%!*orVv9_P7IjP4<<KARBQ{{#4gHN;v~vGv zFoV6AI(6W92D`9Cs0BGAwg$u<<Mn_J_JG><P~lfQIVg+<yijX^@mA%q1RecWXwf$S z5V>M;8JWy{^01EMCqruxxy6lyW1$iCpqdEE!Vrv@2<k`NP!3x{)_c<2-PXjwm9uw{ z=J`A@Og1k_@)*1G23Bq82C*;=V=?D;4)(wq=M7J*fj}SC)LZ;~gl@h4&e=4jKkV?E zl+@s<6DZJ<71dJ@o|K{7A#nCU*i!|c-8~i0uqWoM=D`??oW6OvXBLM70Q>{sQ&Hk) z^|VR8+Zpl=gC~#M@CCV6O{Q&3WS9^A%H@r-2E5RM5=QMzaaka57G9z4fS&*4ysi(Z zz0-yM<Xw>u-$xFqYr4#m4I&RT4KLI}Dz7Gdeoj*k#PFcv*4(*47~rspnkhem=*-i6 zL&C)k{1WF;MVm&e%5%<8H0()OcxBmx4czT3U*b`3fJhW-sSB;vZnH8Mgg#l?4D4VJ zjLzE3lO*U<>FNM9{!!Z`;kERze!(Ol_9fkC0gKmhOFdyKub>S~C1>5ea*Seom}e%7 z#4B6G?((1!a$pJQFz_kieY-H_P6a^t*;e=n%{X;LK4-d#1AM-o+Utnk-G?p{LhI!4 zRZchsYDq;{lt41n5=<8pB@`1u;SE-B2D7dqMFG5wQ9@R<`C9}K00jRI6qwH-0E77k z%8RFuQKWD2;t?#E(4ag3<?Owg1^^?%d<^q3;>1lNMU(>#O611rkG^;x2ilwVCSN(3 zDJja6_f21<K>FZWyr|FE8+zb)@;pdUBDO%pz{Mn}FkwofS3zdg+12aUrD2zb3->Oc zCU@n!*|YaGrC7Le-3sJ6(40F>LfZ;FsjposeKYsY1;DnOUt0CxnKKveTRvLP?2!%Y zmMz(L@KU)8*Ntx6x`ai4mdn;&y?W))P-9rv9?x|8cCFDTjvl?R_VU@&H)UHr+&NL^ zwl|NQK1zhnrK2a1tvG#_XnSMpR$t)e1k*8QiyB>TYWeC_o=g9(-m)*XZ!h(ja~{2I zXO?Z-wuYF#aUpYp4(*md==KQu@1lla38Wl}n&K}becmueAKem?=Nx+;iDaq>y<#dK ziNN9H5qe^(4uJ1C3FId7+$tv@plZ8F9)sAbsUD@|0x6zzz+vPP4nZP~y@fs!E5P>P z8tup+jg$v7eNt(svk{T}FU8RU1K=HKqS2=ubHeH-pTDjoE6TYp>*gI)aN;SPyJ&Hz z9?FFK$}oMj(MFwj82b-N!v16HHhq>6qaJVOscWhCs6k^Jdzj;it$6@IPLFuV3C_Qz z0Hx*#eaM-|G<%@)!xDSOA+syqiUR<>+SIAXxlr{vf*SvQUX@cPNb5l+J==oAD71R= zc?^wR?4gG@`SLMzzXj(ybjl%vED}h*!1==$Y!Xyx+9Au)#|~p&Gl(&kuH~k%rgYkn zA#fsjghP4MQAeP2@(Co8EvfWsMPKmHM;^8|Y{*0!0le`XZWw_@os$Hl651bsy_HW) z;UY_)XK2x<o3#cz659UwM5mc%0`siBZp`^hpLgOM&CGX{c_tsS08lxvmWd?nGQ@yG zr^{w3){s9)y~&3TO7iiPTY8M{Vwu}~l_%1CD52ESJ~O2!pJ>usnxZ2ZeN{Br@?ljR zSDjNwpJ>)V2epvhn&-SO)RQ{2dA!jF5<fbf=N<pqXcI@g;cO&(NQk-Bw<deQDcnc~ zTZE^(@r-(d#<otyio<xg@#PPb;u#Sgd+}8>?#(-V0~>B0jc}rS^EG@RLOH4^$&eE_ zSZHVYBP$<gl-amr-V>+T99gc}n4q%kp@khQh3-tBYh=l%o6hpNMw?f|@rX~y-qGY8 z-hken_noGMl%8+S$R?h7=Ft=2;*Jxf5`7#+6d|iCJ=SA&{R&XUNKc{IA}@hVAw2&h z3}a#gfb?wRHUcruq~hU?bf6Ab#hJ%8(2xxPtS4IWiw~oiQ;+=EXG>f%hr=K@G~6)@ za-oq+jN*ZfH-MuYg;N}Z2sV`6yvA}F$=d&C^5dX?QA8iHo0eNv(z!cKqjfM!$T<KI zyVGfqE#&|QM;i7lYAG&^Vw@QI(gznaX(lZ-L*JhGWF~z$qZ#Ai*k#J14_dSX9w(z1 zS;El{TD*f}<a1Izx}m|jbS7pqV^hS&XvP?Zu^#%^RHy*P9-iDL9|Y7#q2`y4dE{dW zw7QMv9v4D-=);2&{M2d2HmiIzr;I6i&ni7;oT||Q0OZKvEK!oTe5^qg@hHdLKC-r5 zpg|ws09gFYAr2wbgO~a+$B51cLnTQJNHpZnO7zh$eK;<C5d*+C000yK<VPWuJIXQv z2tx*et1a^42{*8Dhip+1kyYUw4!Qp^MT?wciKf#RMY!liACd7hJ#=BTAlVfF>7z5} zK#N4Z2gw&wY%*mLpEv5*mgYTgW2Q`GS<HbJj@=~{g6x<tbuzu+nS*1FENJm&Cy;SO zM-b;Q)oa9Z8|a{68Oq`bW8!BIA)Esp^oUgNGFcDkticlcXsW#QVU0CVgrq2GS};}7 zsDa?Jf8M~2Xn4~!eW0Nj@hGKFL-Uw5>_Q*v;K@AFF*y0uV;)>;XiXuS&5SP8M)4?J zIETg_Z-JAFY!N6H-}zUbtcW8T`3yIvafi^Q>njK8Tp)Te6&QWbp7_+(BliN1f$D>F z`stw?1xucNwy{}<VTbTqcG3Tb#&%~LD~me}F^`Xu1s?CnBLMjLMtk_gPG!l*E3^R* z=Nt)CV|s=%SW44J+BC2LpboKA8?c|!13F(=hB=m1S90V-2oYiGRuu<SeZ-ZjMm-KB z<Upu-P?KW3fJZvQdK^DMVwbHPO$7x(i2O+nQu#&38Kl`u)Wl{s`54^Tu&Y~zl2Kx> z4P!$X!HApiu!$jw2RQDKjC0X1r-9&vIw+g9$S#o+sx1eCI(OO3Zp(?B^UzCTau9h~ z7PAw1(S{3SCDeXcANA4?$X;kL3{%XFv{i;VZtLEMjwUoKY6d�S|dJCL9=}g*|5a z*g2WzFztXwSpeW9D}n!aXQsi7J<!q_a{5(D>T6VNsBs1kI`U6}vm0ulV+lXtsECCz zmU!bUS8~wT9{rnUgrba)FAxM$#}NWNmYNPZqslazT0*Dj!5!07kZ($B<)4nThGGCG zJ4FuKI5n(IOd^gv-ej?1Z5@^;as!{-culZ|axY=M22=t3%!)WMhZU+x$R^RJOP}Z= zM!+K`^t6XP-*7I%N{C2JNpd90vD)fH%Z<9ub(Y@}7dqLAWo&f!Lk*J;JLLm#V)jca z%<LI7TV^ubD2FDp0Va*zR-=<S6CT?^#|yhu%d@K>rJD*G^PH`%;;@Gx1kouhpHUtX zUIT?uGZ0G9LC62-BS%<6xdapTax}o9q}R?%KVXiMgJGdZef=QKreYUUKjPMB0tSG3 zsN)-KGT%~~^3QJ*dF2fawr4?G&wFB{Et<uqw_0=#xWz*qB=H71!cCZKf2bVikVn|T z@i}g2`$alANIr~#*>gqG$hsD~&g%UiCfzw4K@51k&3f-<XoF?cB#Sw2p$vI^RHHNt zhdqM#4nsf>9k6<tX$0bv+FogXxxRG8_`{g4$_E|JtfpJ(*YmV4L)Onhjv&y{^4`I! zuJqVcZB8D_Gaw^>{x#!v%xg3uWMkx@_9<aB8I38JTF&+m=rYidkGGA7e(BiGHkPpZ zP&VDQ;{^Y#kd}g)R9=Toa5+e~xv@HJHMB^<?nNLn$CArV<?M&^`iZPq7}EIzPDqFN zn~Pxk91K~Ci4Z_=0J9?VyC?FeDT=thTaeP@6D3h3cW@KQGdxJT3@`x<M&p=#*bI1} zH=&^ucJPO5prgSnJb|M!p>P@3yFk-3G718|WuU57LZkZ02Q=V?SfU4c`3|9qrHKoR zxj}}yL7P{}ul2GG-sze+<DhIf191?C__@H__zwB%LHhX)N)QBdh_u!Vjhqq$N(cvW zIJsNHrt<+6d4LCfAcj|XpNU|!4G{=#NCrH}mi_B1eFA_U3k-(1u^|gYu=t4nQ-{Uq zlDGc}gjvu(t`jvrlm{dVi+HGqM<@vZ2scDp2>`$$aL7AB1fv-O5F7lMxPU2T=nUfV zz=y&NO@Ie5i@Yy!5<i;7Z-57Zf-Xpsmzk=lIH`<ZakukXo3n94(4dFdPz5<qn*aF@ zA?TGo+dV}QhY)%~QDPMIIfm%-hJk>NF&qbRxFm@i2>6l%QXvQ8_y&8J0^w7K(ZjiX zm<`{vunc3iqI(>9$SId#gg1x;KzxzvAe~M$iG(6Lr`s0K`GaLS3Alr<O7x10pb0x* zoq-UjglrfjSsQTqm!+r|7RxalR0)OXtXb%hQ^YlOQ^j<=MzH`XHgPU>_^6PRMX&#` zBfR*R*AR$z*bFht$&_FV?zo<A_=Xlj$%PxFETO!5)H7B*A5kF{P{SQi0Tk%#B>6Fi zt6BpIVxZmu6=0GBRp6;v0{{@>otj%cMiU2f7(;QOjvAb$KM^l`h^sP`!+22*YG5=_ z@hR8~8+{-gy_+Relp%fU9G5_idT<b&xConRA;S7F0#roMkW9w`7oLy^dk{c(R74SD zi)%ZvDUt_$m<BuGh8mf(5s|D1v9#2*18=Ai$)pm_Y8OWMM3FN_C^Nry`@3eLMQ>=C z*3(Jep|it~1$OWw+Df=Ffx*M$JoK?6b8rTY!5;7eFR8r2r3g%WU<|zhf@S}(83mci zMl(WcfS+^#Fa)y{qI8|2iLYT|j_;rgz?9B~5{USks`lVGN^paJ<j!=2FFz=RN+~LH z02EcA1OMTTka0$R2(V6JKI0)j*vbioU<ho;NN*6RXM>5k`$WR(NYR`Y@SGP1Au*Di zg&dnR0^tTbm<H;=2)lcOB|Axr)Q=T;h<ez>df<(A8VBE$lVIBsm;ed6NK7#zI={=U z;S2|NSgFZeHsq8pHS>vAXoi0qvz56r{k+l*x|r&^uKXlW?GlToU<>Zchd(<93Dpk* zy-QJ{1iz6KL4X9MVLsC%OT7`Mk;@Jdb3X9`0CuD*p76qDSSmD4v+n<(Bu;6=dXTiS z>cNESxqRRS+VB(ty{5z5&(H7)plB3;;RZZN1~oy5nWzbM$h%7PL5$cTJn#i|;2d=@ zmjV>H(xlO!ywQAVqRrZkjK~L0@E3JL&34M7g33)l#D<Ch4Yv3O9cnU$%230bGJUA6 zc{@%qMH1z#hihmCnVPBE(l-?BR`6+_JL?9xxhbJ>qYAPFI_SAi(L(^)jkAfLZ-}O) z64b*%uL*^O1QUoc<Q@2uFL#uO@4$gxAxcdv4&Ey@aqzFYLcYJ;!f0VCjuV1yII1Rc zsCV10LqQ06l86#hJ8fZ%!e}SK@W*b^hhoJKWW56#xgF7nQHB2jElB|<oOn`8^dbLy z)P6w`cO{5P;)tzlGO?hL>%foOloP(Ix2&)TNm&bd%aiCq*DA52clZWP@ThKpE;yqf zht*nG=@L5BhHFra4W%Nk5SpnailPC4ym}APq*{wuA8Ozg<Dds27zcFVKBA=BMx&%9 z06OUKxLxvAV}Ys(wS?PKw%+)S|EWk(OO!4EfL=j8vsr^lMGfAt2-o=zHMAtRjoYb1 z$+&eGwz#T{oSfGH2W!YkfEkx+l82heh}g;sHvNeMVcMer0J_Sqt~kIy2$6r(2RxWD zjo=Md?7w;dI}}o0P9R#U{i_=DB9Bps8spD$$blT_1(^Rh(W|&#os1U7pu>u4UbF2y z!{Df|<rs0)#aL`#EPYOM4TtfQGKw>gx+O4sJ(Rf(LL1!$IZ!P(Ov1K%6>Eq-PuV=* zpw7-iO=K7dR}rYNk%#7JzQZfav$Pb0I5ajOl#F7F^ukAR7>DfGUm`i5rGN);u)2we zF=QiKdl;CY*dazcEPYB%JoqO%Y!Tu^63zku6FG?$tKQ-L$>}tTI{=3oNn#iCRDu8p zd#PSf{1rXX2dIbyW0->+z>l`zroKZ)BY~NqbO)RaQ~PaQmN5rqXij+CK+foxvNhZ3 zlF~rBE!WvD1tt!HNTp<gs<vt<@PfVmfk%%6xeWgqOVdCNNaf0<l$L+Rh={F?_yK@j z&?V-urgSWte2@cy?c`9g2Sh^$BBdYK(T?Mof^29s3jDQg>M#JPiE=nidGMBE%?GwK zjfTJ?38rN5x`=a7hZ7@*{8(On2o9no6AyWWwM(ZfE{Az3jC7=0VlqvMNapIzB2Z<@ za$=F7V6tcJwtBDwUjT=5z=q}3;Snw4EQ3~tqn>7fMJu&mUA>-s&{n_+9#||4e7@go zs0Xwthhjt={_Q)q_znZ+F6xwL$J~ZU4dq=>mOX<N(9O#Vo`=B+n+;~;Cejr#sEu8s zhXb<*tl?mR17%?X0Ol|Vbco0G)IP{@wSfPXzPc=^#Kbl5(&eB4hm1xDW59!!lZjuB zgk<|GSaD-^;fN2-hdJPcdg!G)rVH8q!yugqW!?>d!BUopB5M2P7E{(oA~%O%1O$1J zYnz2Y0EclPCK;P6mjziU1!Mr|jBwaeq^xTDH3-kR+Bi~%bLhZ;p0he?hHJoU7M4l7 z&JXfxq>v4-sFEvhzyVXc==LyBJIy#Wm}=yzi+Z4jCL{+-u^M@>6fzbK*pq~x<E0o= zpwrkcXUx=+D-;M};hiRu5#a{vg$V?r9RTo!AVIBJRjsTs%JEGYSO5p+z=H=_ERYTh z$?^pbDTmq3me6HmP+<v<2p!qYNGtz(z@4PNd>C4B3X;yT18b-e!fGeb3N<Qz*Wo;q zuLaY>KD;q2SHQ`mbcoLTp0mb_hEzbxJ}%lyE|Nd-vqb@p$I`XxKn_312R)#K<v6uT zu4F^A2X<@@K`oSp%Ns)-ChnRCO0)1)JUNLjX%xx_zJV^9ek7o>hf#{3d=Njn4v<=7 z3U62)2h@s|cm#D|yL!q$v$I^P;~dWc1a-iMWVnM6InklZ<pwbZ4(UTXV3;f(joi#x zmbg1`C~|7uQ2;=g)iFhoSQ`^5hhr6o82&7&<EHp#>}VkiywDAm{cp5mIC#*6Z&<oi zu!ivDRy-eX%%}(Yjb%9}jtc+Ug)_(p507j`PcJ!WgFQG0(E;g(ig9+NAniDw;|pa0 z^M;nAgJD8#;`Ith?me>N&#~&I)D{Rsdt4l$wTvoK$l<JVs6WsW-4eSjt!t0bD#+CJ zM}%OAKKz4ez_zJa$V&DWbcTs(`!UwK*_2H3Cy(|l57wvnHZ!j=Zk8Q}u<k#UyKTA9 zG=-cm;b&AE^k5|mbkK%NfQKo42YT>tcK-^-0GuxSvS8`d8~4sgziD22=yn4y?n8%d z@B=u-y{eYa@LZKIaP*ENgk2)OvXwNmv?5Cp0(r0v3yn$I2~u=ejeOufNfCp;Y%A0O z74t|YySdPv29lLP7(D;D4|ITTgP@Q%pl%W?2a@0hFy}`=E|qf@Zb0ybxD&e|nmB=Q zwm>ikbN~lfV1yhi+h8*hZDY)~26NIgQY4RxWhaPR&dA6N346c>a{w2Kpr={(WBEpR z0LZsIx$t{W2?%jTbGU|ARJgjI3+!nJoQcjjUqpEZCM%$oOb%JaG2sv)hs_IS7(<i} zIsyvI2lsL5A;wY<eh1PXhb0h)ehsymb6h{51eY!dj)jMhj;;2zhc5_^b{#(^C6XFz z2-PgbJ#3H0s@_D^2L=p!r3O}kFcEOT18Y!7BVWW<3DKM~7jnPAtN#ODrjTn9$86tG zmQcILCs6><b(R0%3Dh!?CA;(AG-LAc%AtU>K<|4|(?COjjCN2AgNFQjACb!_2S9oU zKCZPtjuwDOr*D^>dgAEOv!~D=fQA6%L5wJIp*(T&6gtePabrV?5Eag&M{S8dapwTg zJDBbv$CeHurb}mU*%^A?0L&9I4qZ%z5M6RqSkIt7IhFvBqo>c3pOgqcG7M^u9yxt} zAn8j-&m&iP9lQQ~dC?v^eVhX612@qg#InBZlpAL+o<2sLxW$W?FCS2_3jw_K^`_oA zj6e@JR0n|5902F&{ozE;E8>=W8*(FOXIi{-^&*4IyEkmujeGNQW5h@wIsoR(dCeD@ zTf@Dl<4ym2!!2AxpI{$SuI!Su$A;m$!D~nBT(@q9g+q@n-5ff2`TqT*<*xa2>E6Ff zZJsaHGkxL0`R3{!Y*>Y5Ey+Pg?sZG{#ldrwIIpUlTl(x-u}wTN;RnD_`ebv2J~ttA z25Un}<lRtZErW(W@t~6rC2r*7&1>p$git=kSm@0>UxAp>Zya%>4<5cKHrh`S<>Lz; z<%DL>G<RS_8vvILM_Ggb*i#NRjJ%PIVg+U-5CDxC7};d;6sXWS`q<%1KIh2BNoacI zGo)pF#RHBnf6V8aIRNN0jUC)z1CecHauY}|7ZS;qeZhUVCuPU!Bg-}QaQ7FJhav`K zbMF7F)6P4EE)*4_lR9LWLdU(sjx6SUgWgyX@`)I6T<v9#KHuoG#xDA(!%%ml?pfek zAbDdIB=u0@M?T`zlh9Za)}zlz9p)nlCE`pbkBre7HqSiU2vO2F`WTxPIuza4+f?*q z_ysle%mdYm_Nf?=k(<>vr){F$;Y*IjypfMwKk}6ydl<2$50ItdXHP!Z*kMhZcFYqe zW!)uOFREGoHw{wU$Qfp~l}7cNTyGeo&r4<nqE0!b`dcpm*5HASXcD8?m8|R;*UdZH zd2<}Xl+v8hYvriZjX5$?T(i#<pQn#IskkGvt0_VU7LW&S^98T<NLpV+z)gIpezpI~ z0f|E$9y(M$O>YydAcE*aj&I<BB+?SQDs@EI_57qKP(z7hl_f={jC9_iHWW`ey#(^5 zj0(M$7dVW}f|ouv>Qj!kefbHGWBh`5+BxOikqkL+HGVdJsA9~QF9xb3qnIwe22MV2 zOvBJ#SK`4*;~y#;raj!`!?53uQ(ZNF<N|P>JDSup4v;@1U#U6uypz218lCq}KD0R6 z&EBU&zG6fB=|c$}Hk}xxpOpU|k+b>Gl#d^l)I$zBzd~miLUsE=i9X#6B9Hq*@-5tc z`N%;PY}y7Iwt<lJOid%rqQ^3(P?7`6ZG5D%4FJ%=4Ln4n9Inz6L}<qiU)=w}G3JO} zK6v*ydyNk`RgzSh05A=27~>B4_(neTG&7(WrX2c+1X}U|uT!xFf#ge9Lv;9}e4t|} zM)bvh#6=l!?2r-W;8G2vGQ{%vB`V?22RoFZ59yikd14&n&n^{?cW_Y|Gt`#$Dw9Q8 z<%15psE4y|*gKVBuY9k8kUpjW03j4_E42g9{EA|Ui>zT8`B;e+`*#>xS)~$e5(FXQ zL5_L6#&a8q)PBT)25RI3A=kT4aUyn_fpNn}%L*ApdW45$<U=2UkR9*rILe5eqm9h6 zA^^C-iAUsPmH^OTRBXu+AnDLXdpV0b)KSU=nx<Yl<l&YulZ-pm10DZhlE^7-WDjr< z@n^upmonI)4|o`pjOtvcbQIE!a10Fq?>G<egww{5Y-0)B5~cWJMJb6)$R3u!fgtLk z6}A+pkVdhGH;%v)L3-tiKzWU`^sx*zDC;Wn(8@*hrjdDIO%?Fa$|%2b#~~?1FSAq! zI8WL^bBH5%?%EMJ&JmBHq*E+2;vkVEDjj}hDIZHZ)W<l1hx^5@i7Kni$9Sj@o0iEg zc#%glq0+Z_aKjGCh??_O6uoz7;v3vyCt1t-9d|m17SG5BJz17C_Rwu9asYrga_T3V zt%V%qc!vV0fs~{;QaBSD2ms<C54Syqf8N<kIm!W3A(%=C?-2h-Pa27sUXADr45h~{ zr^X&2aibh|Fory~*_F{mu^eZ@%P_;3J<krwr_uSz=o~T*dgXLX8DgA^d{K^1%_y)M z(cxL-)fscN>q|IAs6((CiA&@|atb+K&AjRyXDGuQg)%F5yXz9P!b4L#3kOurCfss8 zvmpUx!!AN8DhZzVt@?S^swj&n`aBDexiV-%5Gq@j3^tL=pu;&R%US6h5FMYSW28V7 zT#rO5G0Aw-$?UTiY`mcyprI0Vr3PPU;^#E-$kJw<d8pgaqg^hdB}V?cwS1t4b$G$* zAKVqOsTsx`6E;~qGRajY-8FdO7>6O;@hInL%)3hNZlwRt(;-d3qd9BIW4Su3UZ}z2 z2see=k2|Z&pYm@lu`Jz3;)|G-P{RuHpk&$ltI7D;Bd&W8gd5sBkN?CnItsOfB^%7L zr8d_dm52m4;K8Q}mKFfLc*7ie6iyG{D}hu7k3Qy*gIREvN_narjBk2}X<(ydRg_z0 zrrT+5e3~|kvx7Pc!$Ge^twpm;GH$!vCx33S9jS<}YnJS5?gA-#_9!P?%lqm{2bp_p zP6~a3<YhDWQ$`@O$2hFYq}OOApX%5HA?!hpJiS>sgfqwa{D6aPTr#&Bp(q2t@WB4! zF`~sWHC>DW7quMPBS7lW9DGYJdrGi(Cx)>)B0>KHI8Ev@H-!ZwVmP^FLFYE8PDY{g z!5DqW1zR>VhhCJaN|F6@Pg^XfJ>cQvU!$D6@6>fZ=1E>y%NyWX1Zh5mu#Iim^}(Qm zwzwBE?N_fb9o~qeB?M6no@`o$XI)51vXPLa_k4S`LIW@CLDG|&^gfZI3o}`JnR`X$ zW2FNR@Fu;Uau|b_DdV)^Y~*mmLR>f!|7AL0=PncXlt$}vp&hXC4cCEuQY(7rJKSLi zdTcl4ieD#M-$Ar`9H*ZBJRLdE=b(ce_`SXhd5{m4j;icp4M2#8fn5w8ZRW!q>TU`5 zD4_>S!u!uv<3>GnM?1-n<27r#^_OXOKXCsKydmHqMj-l~jtZNeUZ^<>0H&2C4bCW< zjsb_AcE5W0-lsYGz^*<LzxeMz53K;u)Nx+!QAiI7A!SjOwH6<6MEQ$IZHU2S6Z?I7 zWYZqr0+$e<3E~Ro1Mw9ay}TdU1;=kBpLd)D^5g>z(7-v2gJYfFF`e2k<pVcNSZMs) zVU)v!aYJEr7?8PDa{xe*9ohAPUkZLl^q4~`w1d&~o<_WpshGnNm;?TOU%W*hqI?88 zY(q5Yi`jWsTp5KWeOOpr208#tGCZA0xs=ka%o9SP3T6bV(7+rt7MTT?cYMrfrGqa3 zf;ymH;Bf>vc*AD!MF?6=gcwFlby5GzH5(PmVa-HO8g-wc#UOfl1VvSz>$TYlDH*Kf z;aTa0J`4rbIH8gmMmp5PGPoP&_1}t|(pk`hk3{0mtxT*Wpdv2BHxLs7fycDmfib{C zjbX#1DNt0jh*N=y&u|64)XgxogT|=g9NHq<*aN0KURzC|9wH)6ki$7F!Oihg4!RXy zK}0TjRtnPG8mNNR9asV0j!e-a89ErxO&%%zp9(4jp1cH;)PuzZ0z706kJTa(>4UxX zk}H-HT5X>)lphM-;yiAWJv4_pkYA@<;%foau22ivd_x?%-!XC?pe-Ik2ul}~4I^@y zdPIoA1z;e|SO`j<0lL&R(&PW66jdO&2@Y0<#J$ouP>DQlgncl?am0fOLW-?rWJ^kg zIegK0yr6T81t_A>G7^b8=tDHDflBCu^|2&(RU{7*q~g(yJs3sVu#u!`T|6vdJ)oja z!PXjHq&B)_h}8==6ki}f<vG4sVd>bLT#HxA9E7<Jst_9*Rnb+lC3NV_@O;sE<eg8g z2+g6v(UC(s2&CfSQCA5e%B4d-jD$U4-Zc&h*UiC#1m!Oxk3Y2~cr;UIU;`1%0cW)0 zcSQ|2a0Bb4AsKo{q(sVI97jH2*OA3WEYaFyw&nf&9so4QIb1_CghQwN$Nhk2)Z8XR z+>cjm0|1Q8g6K<Ywx<8DSqf+ZV!v>ep^)Slv8F!kM?44uBv1uCfQ)T|W~s;nZRiea zvSx&VTQMzWspaN)9;a%yM04(@Jb;5WG?vCR=XvT2Uu0)pFai>h<zY-&?F<E~bkVq( z=YP5c3o64k+#zsX(ay;O#_eQJBBbhtr?2fGfHKJe)f_09&G^hkJ}{ig6p3r8QvpgS zoaseF=u6LChK{@eIJDGqW|3IEqd1Tt)P*R3#>1j$$Ekcn8-c}Z)Cx_Mg;t#0j0!31 ziNqRgLx&ujz9CVYyg@j8Tz7TekP3(7z}c0>nL1?P7%Jd7aA}uvsXR2#PiliQTq#s0 z-F-^w;uWXNxI_OntOKUNLtJ=iMvOz9+G(ANL*4MCI21_@>E7<4>4%1yL1tpUQK9@$ zCp8q1Ja_{-h(n!1L^E~iZCwy7^_cGM%b+Hr2<n`sPT`Om2FPejPK9Q@fP*~*LL@v@ zV^JD<-cL6KgEPoNGaOkynCWt+sp2sm;c3G#u!A({40>*atLl~aY(txQXRZQSM|>Z? zR0TDxfqyioskrJi5W!uH;a>IyvvMA{D(e`{31-*{jIqh?3CAtm!YiQbETHQv^uj;* zgDkW|J&56Vnp$~&YYMI@Z|FliD1$$&!!5u<ySD2$0Kg?6Y{Fi`E3`om&;dMT1(Ez5 zkl^ZvhTQ+&WSy>p=N>f=HM9X6K*B9l!Yk;5HS_{8pe!dKi7#-&-_@GBVWS%{B}V3} zy@DrDP#2J>&KzK2O9kp704*Q{ZP2nq^W?)jjcQO<?Am>5%^pgVb;JF*13TowAqcJ2 z9zsUs!PatZ9#}${7Nfv9Et3=mG7g-nFk(C`LmtFI9smM8JcA-s!rVRrBlJjX)FSN! zg}2ho(vEF((1$)?!!+Q?Poki!c3(H-X>a^T$RNg_X2dxbPbx;PXZ~&ZoX0jqt$U{C zkGLnB*y?`38<5ONai)vkwk7I{=gP1JIY5oAre1TRCPe(?Mbu+UXlwAv=;c07CY6?+ z{AB-h)M@kGX`L=tGqEak48<Wz$58RE^U#MmL|5@PM75p7IDA9)egmFjs>Cqw?dHiQ z(#%P$L`$%wtxcOlbZ$mS3O$ssBv7eClrJvgYk_R<_R7Oa#0B;?)^B-5YrKS}m1O@s z=<}jnca*N7yw}Fr!#RM12EoJoG}b%3!*l!sA~cVBHADs@hB%O@LpZMi*GzZZo}mJV zcmCw!?rz1%AOI_w2NOv{xNtq%nmw2+n+QkP0>uJChcd=21yU?86=$aU2uozd{g{K} zsKYocu^3sd2qR~tG+Vf~lcd<ALs$<`j6*YIL<kp%heGl5T#;`GMLvX21$mnSEnfdD z1zru|5KGQ5t8m0^4QpkXsYc8&N@xT`DVE@&RMeCTvxIRN8wQn{=?k{R9UI3W^F~8x zLjkK`X=KAARR#=~6&>TpGB|`H<FIt70uMJt58!}H)XNb7Mdmf8z2vS7RmK~1a$9QP zAU{txU~)?|GITJ5KQKu(xWoE#gfjpDKj?DJ_ybh_gG0!IFaIYeF9QJgKnY}oDQCn@ zhzh0LgdP+~4;)6|VMRvxk#GnwP*4Ir6v9TFu{hZaV&nh~v;;BmMGh$Q&xDCAFCGUs zgfpz~nnXo!9tJA6gfaj_3>OGH+%oDoMEueWZzMuP^g}}c>kVh5JuJx{xP<>7u!$JR zQ#{iZt(~ItI1FDIh;1E)+3+oN#4khafj$42VX25qe6nSvTnNxW4gdfHM8Zb&LOIOA z8*l=p{6R|%695naP-`?ja~B0?1ScDZG$?h5snakFL;O++24^voKtna$GCwr*x3Og$ zTC_&sKpPOInWBM1a8^A~G)GWELs0W30l*%d1SD(3JG8ac^oDe38V64S8InU?yMzLK z?M86c6F(0a8*B(P1Wgw)414imkN{%XZKX7Z$bhj%oC7&<!(#(=Mi_%p7YKDVbwijd zZy<DKTmvbSk;YWR4WG6>ONR+5b!D^VBnNiibU;c2fFwnQ$nb>%6qx_~Is{j@L<jtc z+;PM=bTm*<DLhPuON283NOeoJfj>9I7Z5f8AVYqDvQ(HAa}|+~U;{nCf;Gq>llTH+ zbA$<%!yC{v0I>H{2?u&Z^g42cFVwPUdq+G-LqXH2bfCiG-FHTGgEaW{J8*GQJH$HV z>l(Ddwq^t&Xp9Z8L4z08j~oRK^^F)Ux6iOaUNi&`0|9k^_}(@Ig||d=bC*;0w@b8! z!7_;}=Kuo$05}l=N5sRDKpQ={@?w=Xelv+X97aDt!!168a%Y4&QAR_DG(#7WkRDiX zLURv9gFHFJ*UCiXR@*LUL{b1nGl#S4as&@UjrwlHF8Bc_i^KnOYlHv`_c`yeH&?hr zKr>hUaLtqhU8H8Hv=k>;k33*<^463~K#4;PI!Z(ZVg~{lcCMP&1_0oJ%_wp&6tRzg z2X#TT#^4N4@CHnZF>fphn$j91YfP6pN510V8B>X-p)w~!<zBtRPlz}|d|R3WKr>B> zJ!={!Z%|9%U*NIifq8gg%tJVCL}*LSfeANGxWsUhl^r<5Iq=42XN2RJYrVMIM$Gr+ z)H-js6eFmGXlo3oZ-j@M2Z=_-fq|1;Q#!>oR<EdtP4&i4C<Z)yZ%g#J&&W#-Q#q5o z15|QWozla-3#kj=a1uL?2cv`URth)~_6^6G4u4J(v9HWdIRtgIggCgkOS}VTX^am8 zfF<K`4aoyM%;q<21v>C>sKhm?u@g(GsKM6DnjjOKXiQ_zF`wifi`;cNq{G<BpjUhY zBWZMB4;46kLoU_tx;Je-@=M$daPXE9FA2wStf8%M8aT}N^Ik-~+v<CH4w#1upzdz@ zBu$**)YyAwy^|G7@df@}2;lL{aMHsnBgV|Ea|jUH48I1%uSY~cz0!l3F@;-Mf%zl- zSmA@JTo-5IBfjA;@Xx2I_#Osps%QvaU(?q)eg^~qA^8LaWB>pFEFl060AB(u0ssjA z009UbNU)&6g9sBUT*$DY!-o(fN}NbhqKg(4Giuz(v7^V2AVZ2ANwTELlPFWFT*<Pf z%a<@?%A85Frp=ood58dju_OzeK!XY$O0=laqd*r4OyL56(t&aSn1R@|AdeS4k!sz_ zwX4^!U{&4_C<(v}J^&yQtm<^<!&p3Syg&gUMcBJ|^XlEpS11M^xd3<?h-sjnrvyb{ zP-q4d+Z8|iN}f!)vgOMHXA~SnmY`h#g$2?ryGZE>6e&Ifa9dWO3mBMV%brcU_Dju! z1}VLoP>z|%139BU7=+;p+sKnEU(OsM-GU=nv}h`#>2ZUqU5`-syt()9;KP6ag**@= zi^y4LM7E2OZC!#b;=315zrOwZF@Y<L-*Gxa7XacX;D7`cI1m(G5Hx}dBWyQNQxGob z+JgW<SmA{hW{Ba2RcXkefgpw`;&MeaF&0BN%#h-WDz?bti!R0p<B12QNDvlUjHu&| zJc1QP6gORgkdQqVY2=YdQ2{^{Qb=J?696<J<&;!bY2}qzW|<`vP*CCJmtck|=9pxb zY37+|rm5zdY_{p<n`kbH<ear(;l-VJ-WdiKd-loapMC}k=%9iYO6Z}6CW`2yiZ;sV zqmD)j>7<fYO6jGR`bp=enEfb)6G-@g#Hgf}YU-(|rmE_ythVavtFXrZD(kGY)@tjm ztu7gbmz?%0Sra};aKQu;6l?6U$R?}ovdlK??6c5DEA6z@R(mW2*k-Hkw%m5>Ew|Q& zt84}}B>3Zxy!xsxSX}rp0R<CGaKQx>P%!Vk_~xtczWnyfZ@u%@EAYSs7i{ps2q&!Y z!VEWjumlz?ut3BUOHA>_7H3@X#u#&)@x2a*d@!*VWT1l=TKu@~%3-w&alP@1Ec47X z*KG66ILBLT1{W+40Rb#I5CH`77LD`5!kX;G73s3<v{5Pp&@KcP9BuX0SX)hR)&>&` zug^dOJwQrB7acR#1VgMe(@H+=_EGIlP&L|g*IhTg@7fLXyAy!_4fIK415iNO^6D+H z+9&J!_TofMJ-6YIM=ml1_6BTsyctM<!OtiaAkY9pLm<J~h9kao(~PGsQ`B)kF8S-Q z6KsL7aqtpH1H<Ocwbu~%O@QYBj4k{}p8q~H(YotxI@_u@9~0|7P#yd9vD0gT9(B|p zL$Q~?+dBY%13!G=#D|W2<fE?*K-<o@|5EGJ#}7Hg510Xo4ij78I@ddE4n6^58^HL8 z2fo1(ZFE~xUdc{IB=<S6C61Gy1nWk>I#}ZtwzI&zl7}_kE#QB@6JYR$*O37LFLVnq zTj>^<pfLF05)X_aNphs5srl=MILx6AcgVvY`tSn!dq5ojBvAw_5W)-(0OAjGs6Prw zz;^@q-3UoCxCRhygG=P$?3AX3F#JG<U<^sRY&gL(W=&WR(1RWxfB-(M5ngn|oaTN8 zzz_;hgdPDN0YW!AqbctKTns}P2Pww5W$}=ROr#=ls6ip}VP1Tw0|FMX$bB`jcXa%n z6h}xtjug*;DU??w{bhj(a1jenI1nLMDG}(&&5W=-+Plc5hg;l24>hpY{;n3YzGboi zcMN7HGXgvSXyAB${G-XjkTNW=@|hViWGttNvj)gu2Ro1f<?Pl!-xa`)1;HaR2ZGFD z&CirNU}lq`$xey1Zj|thr#$@yF9<ZiiV~>YJe%nMO8^$&p8ySLF+CE22BdJFmXrV& zqt?!bG9+$hi>O2=O3{j1^r9Hes75!+(W2$9qaekc1vXd5lGYJ?A}PQFkcYRBYP4SI zJ6Xzr<j|THL<_t!Btmz})1D$!gS}h8<}g6i2oQCsMLnuflgd=2I(4Z=l^6njIxh__ zbXV-NsYAyYJqc_}Two2WSjS4%vU*hl_e|>p)XLU-uGOt=ZNOXQ8docd&aBdU00U8{ z)xKhZ2{H(*4+KkC84T92g*~id6U$h{I(D&-Z7gIbE7{6M_Og`4tYtIH+07Ofu>c6H zXh%!h(wg?Pr`3UHHOt!0%HRh&7=sqL)Ysbo0>GJCAOji3fG6FOAq=_&?r(!j+~FEm zxX3MTa*wOr<}&xW%Z;vcr3>BZTDQ8`rLJ~;D_q}t_q*T?uXx8x1}|K9yV<>Nd2frZ ztlGArUW&qBnLyu?Xz9NA&98p<%isR`_rF;hh?Js4B?1?CzzBv?Or+E#hQ7C<TF}B4 zCcK3!T!F$E&aj3z%;64u_`@I$v4}@Z;u4$q#3)X&ib34o2WwSI*o?7^XH4T7+xW&f z&asYn%;O&W_{TsFvXF;NWF8j*0P1v-i)&hhA~fj94Fb@D7$oH?Q~Am+IFFXK93Loq z`O9DqvzW(B<}#c4%xF%tn%B(cHn*AoK@C#Tgx9%bXr`+~7l8~4_MC$Aw7}1RmJXm- zumT2g-~${ubfOha=si37(U6X`q$f@3N?ZEUn0|DlGwtY2bNbVu4z;L7P3Q*QU<Vc+ zaGe|4<ck0(KCq6ptYZzJQhxv;CVcg*cg^cw`})_w-gRoGGi+L4B-mQsGYfPr9{{-^ z1;LKCw5Lt&YERqLH>j|xSItT&<fsT-h)-(HlbUjy``pDYH3x)u$KVM>I_QqKyys2t zdfR*6em?fNr}O7Vo7>N@-ZH>h02%27oCWtzxWX6C@P^;J)G0Xig}Kd6Zvz0&EpRxr zTVU&fknr7qM!3dDPV#fZ+6Acpxkw5|AcB?)+T;k&cy;*QauK{h1R+m>%S+Dlp8K5M zdmcf=cR+;(-j?Dqk%xU~d+{PzTh@>n!MaBXz_lFv=~&PDuJg<T7tDY`GvGlT>M(*8 zWL(xvL4gZ+u<R9xy$-%%d#&rh10J9N;9AeS-uEu+^DO8F+4cex2I5SlgAob<&;p*X zPVHK=ph2G#NZ3Hm_sUn>1%n8N8D8-0I!uBWs_4Vl84sWr@L(02xV!09u?bZqqZT`8 z5Faox2_r1q^0?1^wf~;&f#~BA0Qf;A@?rRugrOb-YI5Eo!vVJlPKr`AxbCM<>lDnO z54=DI57e`QRn*}HGx&u685RU^l$#;*s(1mRAu|Ib^kEPw>O&ulP#pkCpZfTp{&^TA zaW5dD62&JI;t&q_v3O5cYcn8q?6ye&-~i8-f7JJE*QW=#U<Rt^eLT<@X22A*CIWTP z2Yj#z>bHL$2p8aY3Vl!qZZLZH2Z1iQcl$R25(fZ2AP}!W5HKVVw-A6Kp#uQm0r-Ih z7T0PS=Wy}SaRT8vV*@k=0B=7>a^iMx<kn}?;R0r03)`1*n@|Uvzz361e7#pxQ*GF; zJ4r$+kkC7X-Zg+A-B6?>0ThuYAPCX~M5Suz9YT>_LXqBkm)^yINEHP^q^W?Qg8H%e z*WPO%t+9{i*_>m%^BMQ`yw?qrW%YrNf-d9W6}Me#M=sDj=&~K8pFq<?K|CfuH2WR? z#4idd;!A9!zDI<>sE8_}40sn%m<|@|;*nTJ{MH(s_A9jayw&?%tGk$2M9wew4_D#& z&LN_(n74eOFf2k67jPL1%d>;fI6xZgpt2M;?|%2h-?7H5VY0ukgOkHR>+lc-hHe}( z(gN~$%<GGZD;<M^fdxPp9mNsl^Y$?ANIpW+8Cv7TEP4RS1R`bokapYdoAWUR3aoYu zuoMzezz$MMX4J+ce29+UZBINbjnc}%wz^;(y)ZqbIL1S!ZkK2yvXAzdw?rS+V6;xi zM)-d8!%1P#eH?<nF9h++-E9=sPl0Xx0>xpIeQ*dCQBYhTOyQS1yC|X^3$uv=JtiW& zXRzuA5%<?3WO3l@79^a1)U&I;8m3_w`Xr(AL!|YZEv*ppm$&ovwb-}jZW82Z(D7Bn z#n5_DUVbuk9gASId)^<JQlLZAT^}iC2Z;j$mPA2fi^=>LSPg+@s1F%L1o5=PrN)`; z%aGl~<olyB28tOATcAKuOe~&Wk)L4(i-~Ya8Vm8}cp85FlxhHM2w5jyW=}ob0vY+! zRC=NKG2E8I4@Isz(J6A9J>i)A>0YKDA>M{H<nt9Ec|UD?F4^ZCH=bF2$49m!%8CLp z#GBFdr*icZynxKtg+WynUg2Vo^`kRGHxwaD*;`wgnoPh9?&3-^J-_qAAahR#7tfi~ zhi??!rxe^rI`V{I-VCfc$oq`9&)4ia^*D{ze0#FIUMa?d`L2(S<&7?-bz=Z3AdBBC zdtp4$3R>{@^if?0*wTwS;x?nQE_LY5{E%^Kin)&z*4IZd@1I_%Ydzw)B6sS+a}rhR zpRD|UONEFpd0L|?at#^qY_5qm@*R<k>Cyy!L|oznXeFWWL@ev&9e0d{XS_~^Qsv`P zmZBB&qStQ)0r?Uw%M!CAus;PQQ<>X#0M<S$A#l7jReDJUEs=qUSY*Gn+!eBg!1Oyy zSdYQ<tuGxdOYaAix^M`acb3Y8P+tRJL-i%cr^t*0u<@E9c%n3*vkbOg>hFb;i3Q+m zRM!aTIwIsIsVu0oJm`G4)JwnM8s_2w-3*?l2T$X_78T!F5r`DjJws0H&^|)KE+RN# zBE;D1lFvXzwPk*yWkm*_COH5!V+XRsi9cPg?2ILQT0+mf5Ig{k$N|g)uxsS<uI%cN z?eYvekcb^<o(NFkpp5~(69F|U(bUC9;A;R>_y8V71d`V142cj6V)bHn?WHHR#r%T0 z2jFjbx;6r|yt4MEt6#SU^}`7W_5iHgcSSc+43r}VwyK8&)<bjZ;a&B}m3o>Sv0uwv z*X%&T2VfC=9DN|Wmsc3O0jEC#;9Y6R2%$T}Hn!NKh27ZC$mpM5bYg!Rahy#u%1u|S zn&i&|n-p@Il)9Q!R+`lQG~qd$HI$pRteUk0n{{)V^}Cu4SDJ79X(n*Cm@2p2v}!RA zY_YI13m~;v8*rLaTI?oSg#o~v46V1vgpp7$F|F>C%yOb&H497-8C6SZeImh><wf%t zi@Dr~QS)yjS}|r3Fjj657(GoGeS54GBNmH!jDf)mQRIWRJIcsnEHX2vBeSdh%3+JE zmm@40QATO0C3Kcrb-t``&7EuqDD4R-AP;CQ#2`WT$kxEFR^_g$6^0fv(zTu%s$S%- z+?5^I(b?4{MUN`5!&Cu46^3n$v*%KB5=gppHn8W4ea~W7&-<004}W^r&N+KODfez# z^=<|BZs+vwc9jct^?vKZ*x>8FE5Cw!Bf^QP$9ugkWYnqhs~;3v&^n@Z<<(x5FQlOZ zq~0ZTh$zDKf$6&-?!6HtObNM%o~D;E2-EJ>|Gf**0svX~9<KL2-SB?MVSl>vz<MB( z*AUZB=o07Zg>wz=?S(bq2l?0gZgWDqFV<7*VQPjQ3WoGyR-J@D{Zc9z87v|s1o2mS zh}WdE7}sv(2GzEMx{{&Zs9|1dL}z`g?B8bm@6H-Kq;)QRYanuxvnxv(1Bq@%nnRrM zVboMe=W2Qu70jv~oq-k1N&+J<hUu^yc^cH?O@<98!(`40W2>AnS367xX*AxD{upTa z9*faX8IP-i7V@_N*zs)lHmg5l&>0wj9VpDD|3Ylk=Y%~60N4695LNQc+=)14=6d(Z zl|WGE`^nziCZ|GV3U;dUU^3TgvX(F~(mgfxero#f6ou>ctjg;->(}!^uNQM)FL%Fw z|NixdzpvN0ra!4nZ(2`p1x;_~PVaV4@4uh^_ILV#>&=nMn`7%YKZD-<&V6&%{pRoc zH~;;818`G7suYL~1sY6&=TVS76q;2E-9HM3dxk-EhRJ4zC3uD{Z-%31hHG_(=idyL zdzN2yR?ucvICxexZ&ti#R&sUr(!W_8_gfj&w^z<>-pU8RRmgj*)bmzl^{v{!w|MS3 z4b?d<n>p>^Io-TDKJ_5|)wvrzZ^?h>D(<07Ym}ODMnE&YxBkgjpnxnI0NVZTA>+Km zzbng=6Hfo+YXIOAY2NeSychR^kLrT2&BBx51;4z7fS!e*)rDvO7Kq%7p{k4FHj9zL zi_v+Du|13NtBZ;M7D?PoDXL3pHcRQjOPP5~**#0St4kLL>6zg?S#`N&wdI~Nrrdh@ zMFYH|X4yYE!y7YJyUN=4W%N1_PL@Wr{CzvNpwgj;`QZXeKy`u(!HueKS=<_g*Qk>E z<|;Pc!wOk$P+i!+SaPtK*C>wqs@ZG~P0G0urY>iwz#3KDH*o6G(arWwfVLY%6$Id+ zJyM$2a0rS425E@d^_Y#wfIX+t{$2?++<zy0*a`MV)&x^5X#ryW*fVzR4g#w1;2n0o z4zPm|afkx08OXP=burA+MO7vNRqKWP<-rhWg=!&vq<K9FQK#hs0Lq`$reLQ2`hJji z1LOwAO?5+;{$p7+s+usBQ9lfsL5NRp;QQm$6g!P2*>rnZV+=5DKR5mR*~<(+`<r~C zK15{1efE?7Y|FFt_0dP2OIz9v@F6M8q}!HGVOI%Zs#FrgYrW<Ej4_h4uLh3<*?!TM zZYSmRXOh1J^)f%D<4{)H);Ra>2AOP!ByL|X+y?BxAinLy8%+MTn1BzPFX)(_SYv9| zke9o6)a^&#(f0dZ+PyT>twP+@Rv!b1G}SzNjcR+%wtKD5_S*CJI(zrJKkRjsgP-|< zN<aWR8Qy|j@BKjkjur?YR|EhZJY?wI+<h_WB+$&qIW@-0oUh!{?X$1HUbY84`fDjk z_f44ZJ@{~J(eoRh3H0-g_G@F`uqIRNUKoG;=20(w7^?Gb^VnTqP-%AG=_UG4Qg+B> zR0(k({0dV{8Bn`uM8m^h;NXnc4l4<$60bGXL(JWqsM^G3fH*|^>J@eGA=>04vOn&z z+Yv*<isbnbj`xSm`L!Qc?*5Q}{zIYQhtjJbDj$ESo&Uh|9&21X*1CJF{rp(>73F8& z#0GW)V&9Ru@=pFT`l$ZcJZYZRzN5@*_vpsS&ANBt7+7O2CJQs5V0>bL27bFyvMb?; z>GGT38^Kgi*fM6g0pkjEe4qY$vyP5BBo3Yoftnx+8!-2*ST4Q!`mYksmxJlX57QR> z2HS(=;Gkz?C+*Lc5e-}Auj4q-z+}&X#Wf5O=txWYXy)F*`w`RWH7HpJeI<o?X)w0D zhit*1B<e6X^NvH^A>L$^_4FTr?0=t#YR(zJC;bJ}f6l>mW+wf}$FTi=c0Be99FD~x zFaPbXgF?^$JH_8c8rh;uYX5bT{%Ku<kJkQ!RsYAF*uH=MAE*$#KnqwtJC*}BP97eI z+8%U2gaCz;FC+kJS{|)T!umxUB)3{Po5?4wSY|2Pp-htv?L=<XXApMNP2ChBRt_<X ziB0`<DVyGKcC#(RY&nk)Ls@2DZse;5{|Di?xlJg#p1^ZG`{s^msZpL<1jnu2o0Yd} zY=^UN?U~ow^gN^HG~c&qbb6hCJ;(g3Wvj<(Zv^M<Z`PfUzkV3bx&7U?H~8Ow)La$^ zb^{T#yxO@IhYlkN+}9$x?i@KzypX#3*S;Q349ZY_4$U*scbR=@#QArS8qb5V>K<3- zwvzv>PkpXxM@4?~!Tm!I@7@n?>-KfV+$dh1Z*7l!wqEC5i{i04^WA+{b9Xe~=FgLF zt3A(QytaS+jy}IG&?&I}7x44z>Z>T;yZ;59oqYW`T5$LL*?<53ox^Z=DwtqB9*ow) zsZ+B$)~myK!*Lo2k&=21)a4<ZChgVDdQJ4T3uW4c1fxNV(O66RI`eJEhU=_%!=<&^ zol6?DIUf#5>u^8aY|!C-4w2F2ixO<q6-d&O(G$vWY}6Ae2$#_pD=TT#m#7<(F_3E8 zY&5w13L<MLJu28_DEmfB)<|x_vB~J_$8gyjieE~aZYX~rk~LQSwb^8R?HqE2pbisi zCTOCsUpY6q&g#@`qQe_;#Z*t^WwWWl<>4!4Mmbis<N$da4A%x*MOiMW>y&9OwA~-p z9%^{&U7s?|tO!Z>I7H4I+)=1A_rUbxl`i@^#qfOFT`wj3M;m$F3Hv05S+sa3HkPxh z#7yG8vqptoIN0)*7r0F;BQNh2$vw{LJ0WrVTHt=6i1o*jao9>s_~U3!mo8anRqvs~ zvek1C75?sh6h|95Kmy6ecYDF+sq*90EV-qyN3!s{iR~wzcY*Zb;--kp+HL%g&YZ^X zee0#_qw}BcSzLT<T)S-(wtol)eD!&Zmkr;rU*)~$Kcbs2hwEii$!0#vDqbD<lg7A~ zePj9jnhN08=?bctKNAS-f|6Y7|4atB18=02Jz5s-cX_mZj8yjQ_)^;C+4X%y`C-qm zt*(c!&Y^$HyaN7a*EBZlkB}cjGo}*4{rRH^&l~CgynIHi8X@0j({YOlbr%&qx~N)= zVF(%J(BX^I)5w5EFp7UUT%^ovKZy}{-sV`b-~E*l8ZK7O`2cxMpQl+wsmz^PcjD}K zDBV++rwKQ%>iX^s7R?Kous0}Rg7?R$oZ>YOs5!&gV%Ug^G-Fil$$xxc$)SCGw)_u( zv1dio#C0}7r-2YCux+38{NN4t-x>_~K>s4rB%JF+B3k@Hmy<v?;MxQ-yczgo{IK`V z{jI~`Z_=eDE5`+(9-^!m0MH2Y)pw#U<RL8nN)d#Fa*hCiz=S=l<f2(~Ixbp{?g;)v zN)Yn_IaOxMmwF#NBk<`DO#G-{F|58`;*2sX<;j;AvF{eb5L2iz00*$0n|}YS)-{h! z;={^|o>y>e7%7NU-k~_sX_4>JeE<?!^}}PS)koi5gaQ?(LPYBIMWz25l7|#$_$JzU zbk1(kx=7ASxZ4eC{Uuz}*9~`~FN93)pA3hQ8~Dk}W1cb<B>R(xND3Gb`k>w)dQ8T) zGa@hDO#$=U9s0Ab4`JVAus!uH$z<`56qB7zd`h0;1-v5FOkqT4sIkP{IY5*$z-mQ% z(S}wtah_CLko>%=<1rzlm*^T3$`E8o!}|oGpDl6J+A;~uF;Ux3d=%_!rv;UQY}Ef# zpcg#T$c$)!DRuU@8*2#iP?SblUy1gH(M)E*#z&_^<$4l8MDH`U3mNj!@IxL!Zm2hp zs{RDVX@F$C_=!V>YaDY=ju3{|gvmdppYdca$!fJ)U=vuFEhG!vo(vJvGS4RA%LUv- zi$%4jlF^UmG`T<HZe6t#NSfaKe)*&s);uC@l-fMURkmTy#oLJY>(k`fR)DGaS+Xu> z>X)$4kIu62C;F+#RbuXBC_u9ttUfjJs8x+>zUjYSCojac#g>t2YX!=E=zBjG%C4h0 z5^~-8g#h;^-a+xd$_!)fR$Gpyv1{)O=feeW2~N_R_YtaCa`*(f!d{NKOH>+Ic9_Q> zw{Q3ONuaOnvhcN>%sJT%G>z1TLv{9}RqZwmR=X$Li1g-9`~wZb>J2;AhNQGVuvUK^ zpzhFDeCVuu^+UGJf@q6etuCc7@nvgU%eOol)id3qBU3T##oq7#fpwq@SoiGz7uGct zT@Mqpw*J4uI-x=KOaBMfDLmSJkC+*bj#v3VuueC%(f1-*>Q`dW!B|83#^6j<P}5ug z53C!E^*Gg7n^%it>1Pmi7!nK#<I$&f+N4HSNFaMDq65|VitA5^hajiw^}%RH30ujg z5xgPzW06b0$R#Z%ZJ9&1=uol^3qX$DwyuY>jFg*I*}l&9CWWN`1CgNkaP5#Aoch%G zcRsej6Iwcb1A^Dy#{a-No+jC4^<aP`uTV^v^d8;D56LT9^W0h+j63HwR@+r)G1W7^ zy{KUy`w{5ODEJ>(H=jyHyiXNC9+{T-JO5GR@1e*l@t08fS}0BAa9RkMd5k`Mzl9PS zM0>w{J(4T?N~kebpPC=wOaHwdBYZZu9xK_p&98fP3bPS^dER9sL1F8EVBOE{jU+r& zY?Gw*Kd??$xMDNKP=04Km7p#5|G~P7&*|1rcK+|M&TB;MORn$ygD-i0TNPjOgMRLO zDIh|{x5?owuG@vt!j;=a@$$Rd#UyR<osu+j*PWM{_dBs{wB7;2%mCgbv$W)F2~z&D z@{}*Sx>mnP+py<c+^xEKz;&;>ZGM6sMO90{K5r-$-;a}Q?ki{*=BaXToZ{cxZ+s(< zl4@RkNg051IZpP&mVGGZPkSOIzO`?ruT<f;vg15E_gnYAbsdcSseKOi2pN7b82VuS ze_-8r{bpA}9{|A^_Vq&)$W%!3YC0+6jG2=!6!Fq)zt`~2Z@Y%CR21njx-SOzFQj|! zN8>_uLw9ZI6mWf$INqrc=#$U4G2yI%k{FlX6qo$~$ndf)kq7)IAK#WNc{D3uxZnI% z;#B;g567s2hg^~Ud+7hK5E}~TR({VO3A$rtb+`B;k@L8m_MR1q!|yvVf%!r%zrA%< z^{ZE^=A0M`y)>v&KXv5~hm6M8EPL)*Ad@c&pT}2DkA8gf5)2(kh1K~?x_T*!-LRwn zabz(F{|j%tX7u?(b=PJan3}*HNCms63LcDNEulvRyAPm*gD@q?4QLDoCR|z05HCp0 zEUO>ib8f5ijY|mxFeEJ&pS`I5v!{gO(DFI}ni!ucpTKAb25Gh1L;ZR06X*50J$CjR z8f2&X2Kj@cNw1s%0`H$2A&Ly%W3Y_H{PfPYw%(A-PpBn$sp=y`*&!%zj+_v#-}P|T z`aThyzrkI&sbpz48J)V=e;4uz0lc?^@PYtKz)t;m)tN>Y=o3Ji#)KSegxm<o#+;9* zr*s3;t`H)Y>Plb8ik>0gKj{HMb7|Fr3o~FUZqRYltdS*p8cyk_dpLa+B<AT5ameQo z+PxMQCWwh9IFNq<TcOM)z>_euPw%b}u*VV8VeQ~Paa<cn)=@fAl2A+|Lf@#=jB^N? z(!bc3)(q_q#l{lvVWOgC(k;p@h!Tq!<e|(D>39e5OlE}N8i>C6q3nIpaCYr`(!aN1 zfW+byHd<Sr$s+CrsDYaH#YmAMiy#fGBSJW4NUywNGgS(+IH`@Ly^8m`fBE3uw&_v> zd$*HpDiI;vIsoQ5hKbjAQXwB=s^}Sp;Gm`4=dB%NUaifPNv;&GKP~5JE6vq*DwJVC z7Ij?p%t0v3KK8$x{V2Umb)~pIYQS#>Ar~}C6i~3|^(0HrUXd&YEe){?{NxwILvEe! zo5(81q{QhZxZdB^1XApcXql#;LD!9+#-Fg>)!(<^*-UIOU7O51i*>wKk-p8=2D%It zdo0F0t8e^-0ZCipba|s+5QHJxNrr}A#(#c|e^i*4o>1;6Agn&OD}BngeJ?h?(ppI7 zU0TbKhM5G>yaP$JV*-H%)^1p{&PoTEPt`s$+SiR18_HU|4q=N96a2k=Tdz6dcC=K? z_^0B<=}<>s+M9^+Oos+@{q#nlFH#Wa#o1A~c{e{n%Iz5`>drZt1z2hyMrUJJJ{;+y zY{_4xJW)ieo1b7-0H7Z{Y0VlD(ppEB1gWfrNN;Wg{3=@6$(~%LwO4Pa%De=q;1gXi z8!SCzV1}Z;58pa(Yrc6sC<MaLx&c_AO*9OKw*v{ft0N|Z>xg@UAAV=wrXRwo1J5wD zj6^ELp40aS!YXUXj4vHtV^IPaQq(rIkJHQIJLBStEh;Bd<>Tuxe!~MWqXn3XN;J%~ z4)=+1g>4uE?L#X(M&Pl1?DO~m<`QDW*AKtPCj2$%3P?(VejD5wSTI9AVUt1NbfUV0 zm06pMTJZ119}nn9KO;Cv-W?jduNKQv>ukKKp?;3?vVD~M#qf*L%IUP<bW{GXsV{1O zPTvsen#nMuZ4FKi%7bqcnUD9wwA-X-xRNiIBsi!7Hv?ul>7#z)Y?y+*&iH?lqROus z?V9GC&6VG1xj=2Z=3Qs+{s-1M8|_)HSQ@+>YpH$sdM`OX6k7<7z+0=k-#$KDWUZjC z58;lrW?fkvOO(GJ+81Z$=fG499~Nuv`RW`80`d<aqImj!FO=2tHWUzrhoYQPl^2RI z5luEGNJ29|TW8->+|L@64GF|l3U3#imGWS}LdV#`M%`e{7fVc1{+PcV#)*^$)9ZGl z0~eo4sjVYi82`>=0U|;LcO>KJuu^=E8y3^`jtxdTz=XC#rhefNS(DZf%hg|<M#+0g z3!O9o5lk_zj}E`b$<+BfoJ)%mreWvs@ptWY+!;r_-o8CpdQG!ec0K0dAC>t4Ae`Bk z92IiR$6AV^miXHlBG1In+Ch*9w388l<EL+AQl|ux?}yTM5zFKAvnne3D5Y%xLEzIB z@ijpzrr9z47N%~c>iaq|y24m9_VjgNJ;KJ_3Y&U4T5*ccPxgoWW}UPq7jThdFERq{ z6l!683N*;sfvJp50q}kO$9m&GraZQYE68=C>UJoz7;CiX4L;IdV(;+-Xg}f^HjFnH zk9FeJ#i<-p8AFO0^M3z5SFbmEc2wZNlsOh56@Ux3+%96Qwfj#j)&yg+a_?<4hurbQ zl)Yw@<L&|@tV#sqPx9lz!Sn3Eso22xP@q2&17Zy!AGl?$-R8!@`wtLPS25E%0SON1 z{MP3RGmnxssniItstgFk8zfAD;p`CK%R)+t9%w&IPnjE)4l)x<kSD+!qXJ*UfH!TT z`K9QMixNIN)P_9LMkG{{-u+M*(?PfZ27osy7<x#BgCjXDFme`{LzYN~_Mo`iDAml6 z0z5`@Ta?`AlXf+do-L~LOE_P@R|f@l3w|H!4Z>m({X~RhS)hXpMvl!rk`3vgfZQuZ zY2qMy=NTxlbU;x$df`Om>^9~OpL-D|Ad1cXDqDo_B7HxL7mYJ2r_T!6e-Q;CO9;`0 zm;fkM?8Mc`!+Asj8AXqU_xGVRMA0Do=f7D+Pw;dQ`hY|8FtTo37+Wl>dRUzT($*QO zcm;E<4<bweU&KhBY;m?xn9ZwCDGHIX+sJ+#BoNQJ4gjACbQy~xzgS(<-~nsf@plz4 zpPweZ8i{A=5A2WhDDnyftHVKsD9<%$C*J??>9db;;1C*z@D4jDeG&(Qq}b7Yz@q^y z`fyR?42DL~d!4Z{Qe{Lhm3rh8VEqJCDut>Ah?#&TV#i6V?HC`06eI%ZJSRfa$>>cW zK71D0ib2Y<B{I!C;?twgi;gbB#e&;BJBSD*9LU3Cq)NPw&5@I17(I6Pm3c%phR&xC zb%>`s_Ige{qRklz>Ua{}v`r$nk?#1XF_`%KDn9jjO0&gA)AkfeYA4z(M6mRG&>{j$ z+Mr#1sr`#0)@$$%3KC?3OoL@^>L4GmdZvpZjkbx=q8SVgFCyWI3ga5wn6Q^@rfI)2 zN$m7`>|TponLlvovwDbbCY@7OW{@dr^GP%<0-33o*iS<Bl4$y}9`^Tzf07S59m}E% zNt#x8YBB~(1;7#Y-W-bwLF5EOu{c`#fX{6~ZZKezgzh@W!%p$&A0%|^0}&z#W)Fa_ zlbCaKpJnbKI)RwnK9~mqbk<SeL4c)TbImdkvK6_g{@m27UW+5hFaoI)<3|&fbqV1q z;~)Q}HTPG0P&<a^7?1u$Mt5OhKS^}k0B}D>B-X3Qt`wZ(h0N-U&D?o5PAm|rr^2s6 zQwi{VJ4EUl!h=kO$2_t~3jv8^-1W%RRLKeoPXP+@z8$!gf~X<+^j<}l;4m!|FOUdE zdK{x2<FOKnS|#THSff2%gN2jPtQ{gr0Q`buV2KI7&K_<H8k}}ukNV=@=`?0LsI?55 zSrQ_G0N3oJ!s81%@W{g*(n)zz{<$9JP#al*p<%0sbsQihzdTM|NN6Etv8=x&d(o^D z^G^uqZ8F-&D|3^S@5vBaR|W<8ti<)7nq?t0>#2&vQ`Z&{Pk$lWqCBzy_Mq&P+gJ6g z2^EKWh42Q?8!qHkF=QSI6@j4|wL{iWkTe;XN_eJjg$J2LyN;{eBBOuc(Pv)JNiw?m zPLZom%$JMxYzRQa`)OamH>_>}4%y!amZm_ZMv-gIzCE!?Pp%@@em%YYiz?zEc)=1= zjD2cQS#$SGmR^iU9+p;~<jwsB88<<~ddEY&pPvzv&+2KM`%=GDRNm)zJ)+dk+Zn$V z0VfG#))t^1gpjrKUkD;=7WAyVO1Hj^jV7G}Ug+>%*2B<Q1-u{6y^N^n#MGn`P}M+# zaAB-q!1Hyb%1?H5=|ItDeWY7aV^Jx($Ie(#2jfHlv#mitMm3SyBWd>HU!NhA;edP} zIG>nv%Qeh5x}=-+;eW0uUOcP;|FX+Dt;vGngwTQ&b^U?KcOlU5#U^`zTDNdT0D!m% zoIy*7Q%kTi_Rf#!?0=(=6m&c3w_o;+cFed2jXiy4ZUHHwAjzccm!oZZ6B_;XFnJuj z73<$I%24QvPTP(vN~hyT0vcX)buo?hpw^><AZ$A=u=ebxb7C_+<T|-z>3-MyxX!pT z)aP?Y)VLzXUzyA+(vUY6`*bBNh(Hrk#$X_Z5fVoi3Zps2=}zqs&+O1ce!|6D-Njcc zcPx;l^?ngv4bOkO#a!(vB<4;<_Wp|wT--wBcEL2g+Q7-E$6wMzqk0d2B9eEZng=W$ zxL(oqOpVOs6x~<f7u!#<@bC+LKZ(u-)cQ-rwOAZe1|Xlk^QG+!qP1dH!uu0NTC(*@ ztag$<mUhw;-~bu?;CK3;Fa5S(>Wb~anG{$G8O6NJaCN_1!LagYJ@kwI;62cYygT}Y z5Ce4ww=E(vCW@fm%`o-h4^{5?KF*edcq?(gDa#b9QKZoys#y%T5*Oo-$${hZD)e9F zMi)DDc6vKdpKSA~`)+q+&f0BxO1&8((}s(F!zyL5)CXJ$Wdjgq3+|kMyq~{+UWTdI zvOonNAm&|%1nucwxL|&kp||j88`R*@8tn-#z_v=rrMmHG?*YXX+*0qIRu<Sl68lzy zUaxBCKhdZ8I7l$b_wZ^|XjI9aiCFOtstz)eu<i{|M)~P!&Iok7N*FaU^e&n1jD&XN zY8=`RG53iX-H%IVqsv(iuE9LJ<C?UX-gc3tqhCzZdWS8VqoxL7yD$hlYtYXA>mBXk z{-224N$|*3Q~mLNfkL{Is44cH?)8p~h6MB{0(uu0@Lf{qpZhH2oQiIZR5t>9Nr}ev zmJN~)T9Mw-|M?-??I5m16m}|lC8+K?rw7J8`k569mYZuGKQ@pvd9dHzTa8X5Us&>| zmNmzXL9MU+W*viPU%8;yNa(Faa@8W~l&xPiBlji>$N~Hc_7f-;s30;p)vMh1Hj3$A zu(Fij1X~1eZkHx01?W=|%3`$ZF5L2>`;|*KY%O%Y*G;XC{y;_tkXu{f3H-q`9m21n zA=4<6!hp4hE9rB~xxRS6UWPv&=>ctA2Tz6-mL+Bq)7<F9dS<0;(9)_xc7Nj}4U0B$ zjd#6}wOIcsx3CKKfT;|Wg<rO|`@nQD32Rt@$K|b`JNJ%l^#i22U_0=~t1l|s)BJ-O z?IxGbh|um#x|HrWF1g8&WV-qo8W${GM<245ID;vy2AO~Zh)o+3&tZiquYdh-yQtzw zzSi&$-P*%k32#pjfCXE>^2~=#aXPbl+AV*f?3$%pUGFXmH%=+Y$367LcB*wIm<#Nz zX9un2fI*{jXex$C;_s$ZD5$EHCi7J3n5OhTs?Ie8z4*F9|2nrmB9u(`1OL&{=<U(U z(lb2bqFj9AwO6DB{l}lZG$s+MoDT(JUM7o|Gq?}T$VbYEVUk_@SDasJ7CyIAE<Ghe z2Q_nU%6$6I5OYkTJ0sFathP^adsY3VcRDBaC^GpNuRNwdEjM0>o+ToF#d<~=t(2@G z%KE6%@%7d-ABa4(E<k<?O6Z>o#@vnW2LU~IKz-OZ`T5|Z_XB#n#9)-l&_dbc0hVOW ze+b=$)$bz1-O#p8SVWay+~=NFAezZ8uI0=wQ$_66l!4%=<k#~2_s{GQhgiBZornA; zs~{8D5-02@6Sr`DXS!=-*umf!hnt0Jr=0)(np=>`)c$`o@f)4Acd<R36N0ie&xMxT z&j5rEcJO#DZkEIxu}AN}fC<8Uk@H8^c*R8=P>r&-kRP}?@_aW4h+B0=maNr-Jej_( zF4?H2w=4;k^)8*^Y2Cc&4(kiu&beq9m<xoxgAH*+;NXBW*M~kcu+(cyp1f9@b69i# zIi$e@^o8W++>gx9?I61il};<od^o|<9pb3x>bu47ek}U3az^^Pl8@fSc9Y9CIS*a@ zaYNMJPX?aNfXc%9?ZCmLkYdVbosVBY^e>TOku5bScwmtF-%Ly78t1p}FM6~#!1%vj z!Sio#tY|NW^ue9A)F;l9oFRSy2|~nUeln?CSB}I=BJXd9t?Rgb-+r)4%vs(_+NcRh zwF6UIf0w*+Le0%&_rCon7FJ0-(m(n=``?#_ELwmxi16O#q=KW|p9oox>Yw%-O;W8~ z4QYbDy=b1lXz`luD{4Py^<w0u@u^?D7$T}D5kuxozL(y727rsIg5)^CzH8&#<Edv@ zcp8yz8&{cr_gJj(2XHaD;6saP5*dVIZ<g74Mnd+6cGE;d|1Yr4C?E2`_@!#7#L44g z^GQacS&h<8qx8<4C;_4wBhK8MCT1p@a6e7Ncx@u+%O;}8@r{*Qy3Pfx3y|3{uhnm3 zsJ?B?+amOHd&Vs5rVtPeSW~|an1K*GKyG(vUfg~-U|gd64rE$xUKRu0;Q4=Ho!PQM zwlP*Nq`>FSC%ehCk7i(l$4`P@NT@dGwC*T#TAu7C*w{$a=qBa%Dx{z9C+9qEka|6Q z4aY#6P5AyHyhv?F{Fu)|m{7vd82P_poxr=!_rdS&akp#KXldll)_&~r)V;~k*E3e} zIi7fR`|p|C@KXBUAx73#r&~Zf&E2nISUrG^fY$g{1h0)91C!g0*?hq8XkB%<+W&@i z$(xfpGJ%3%GACBD14T51HeSb4{N8$z_ok#pBz^bqIB){HcVb_$JZ;wPtp#+&b!I74 zYjD@yEN7`WL1p1oW~woikj;MMaJpG(34+f=+uKJy7QjW<8EaEjV{DYvMfG|92iCo_ z-XoCxx00Q6#0JKNbIv)KCSHh89Y_pfsVv5MypIcq&S`_Yy_-z1_CLI_LSOhqcy%Ea zu&Y9sQ$~zKe(vk4o8{9`UzU8JBy@`!!Jsc%q@jL8QKZGU+1%<O_4sIw<J%~VI?yM@ z1vGkxlNmUT+^Pa5sPKta`+B3Q)(dIIWOZr=RF=^8xUpsY@e-|sv3A4Q3u|C)@I^s1 zh*?0IGoYN&R5-iUHgGTDSTcCqqBMUF5)dI3(n&>Z6jEpMUGPPI(<pHH?jb$<@BY1e ztdH)`HSqsuDK=4J37Wf}c1_~bz3%R1>L27(okB0BT!_HFL9}zJ;->{W6%;oY5G_&@ zI}i#3!cS7K+(X?$8gK<J)@$+l_*CCfvVj>P&qwM<7&N(OH6%LJZyDG#?=#r=8!#1J z;lDg(DSV1&HU6ul?Aq}qaavAjXU3UT5x_Ex&5L(>j=q>1kIKGuv@`G0$(|FSrdU=q z$PlpQD0XAyzCPRuPn|N9ZlXORYG|Tl?*hLn>`qemm$&JDyigN1H>&@SJe2#_Ykzy0 z`?*%#g$gESH0QnT(`s)wdkGO<$LY17lJi$5gjiDbV}w|sSC6!|5{?)imC{Qp{zyxV z5qb5Ow(2B9>TQ0Rf3t7B_LsXq7-jP*m7=YJy!XGN5yy#mY3d~zol9{L-1Ut^T>=dQ z69IA$jUErbE2G|bdW#YYiJ8ki(vAvRi#&Jc3NfmgD@uB}J;>lb1}pykRJ{taqmu-R zvnc0_42l=v#aS9vjui`s9z$&S7~yD%Bi<R+Z6<k~nU?9WhVZnpnz)|M%TIVj*=J!M zUn>M@+8!<KsL5mHR-{+{Gkb$R+_X3KeXf@R12QyRW#NaOs6G|a=75Uv6X(b4k%Oum zL7y&pxLudncDlA2F+-C5F>|NY8|s}az>V6=(bjO0ctH^7O(SbEqhnHBZ3MX|?&T|N zW~7AtP7=s&8WVGEfQM{)3)CFNiG)grtKx^WW{K;<kNxX(-wE)pD1d;8Lb}J@m&BYE z=NJ;hS%$wdggZ)R>yH$o6|Wds?w{{PD{ySYrm_hV^T+h0bZ3y>;b56*tupxC)aoU; z2IdR{lYX<K#I{6X@Fc+$r;>+#`JG$|UCA`VWHcwJ`F@ZibvREW!cDHJ03Gp$ts}HK zfE<?HMf}2HwZL5F+aH%6R(?(Sfws?YI=^h!xi5GhOqih{o30A$tu1!bY)jqSX)BQ! z$5g>j%(14?6D2S=Wc%|GZGQ*c+$;QY5uh$6h~$b8@jb*_C*H#vaJ!oC&A-r}*5sWe zYbu5-jdye$B!3!<l6jjknZ3K~7jdSoR`~#3CBJJeh)5J=sEk8nHF<xKb=I1d7T@_Y zsGgF+LP`oMjh%Fsr}gM_rI8RLU-@Z?`oe9CUi^Z_t%%0CaRcK{d4?jt(U83dXeBNk zi}_1ir7wyGFOjZvcUlf|B}PmsQlul?7sFgUq$=5aLPqjjeRW`BCY;wCNQRCe*3*M9 zp+&Q?dGlYmJSKx12uo3#ONkQKhBu2Me-UcA9+rT!bX3df^#e*an!fA7m#o!ecV6%l z*2yFE$I0ER-3y)Pw0aw*dNEHO;;~6srqkKv0$D<FPngtq*GD%8I@CNOq+;tNv`xeT z8jybJ`!V}}0HRE4e*n;y)+-fecC`$BSRHu1y}OG!u(Ob7gY2oKT%jCTuE{%t2P^fN zOj*(oGq;v&im08xe4jKH#$gTscAPm5;stNyKz!>Q<^49O%3-m)+cnRx`hVcMW2)Le znV>1>h^e647CfQc_nkSUdsKbn^{tT~*Ecm4UAJ%gIe6MIolqgJIl6ZL^WD2H*%9tO zbnnJn@fSQ6LymFBS{777405G*XfHvDHwDwHZqM|$UkQud(-QueOR1b1r((@!R%8l! zqfUo!E5GT<5~JoRfq7UTK4b!YTz`GyRv=l2*O~OS7`=aWA>lAJ`CsI}Z&L$WRyTxL z@<4J&Azgv*_*iR)q7&vqx@yf|O8Moq)>m~qd&(*BPVhtvbW49`U+`+Ptv;a^GEXkB z45d59<a@6UnVu)7h4G9y>E%j=B>HNZuI`R}vpD{ffTkbfs3ZUSbaSBU0QoM<QS$Pu zGMP^dd!{`1mV6cM(l(;Z6iweYhhqh;=-G2F>;7QVQMI5oktx32V}R%C&M6mkO<5d} zf;}#J#fQGKKftpU&FCJ@cSU3Zto?;p&Fdb8ONHHbIjwh*Lv$A4j+T%w<wa+0z7^MB z_?YBa$AqeH^_RR~<mooLdf}tI633&SRyyxA3*fsNnr?js=5Hx=SJnjlRs7CLyY7xd zRQKKQ-i;9!D<bUKzEM+i4cjHD5)wJs`b9rRiPR;XB`hCC9&qO;ao9cjur{9eAv2H_ z9?xP#+gx`3NIvFuS{vb^jg3c8``EKzg<XN_LU%Oi4&FamsI#Vb;6X08et*!=lbzt< zkC92|RWlO!yQ(k8W)VfVpm<TJ;WHN2c7)~nxfAIR+<Z0Mr~ij<aF#X@!!x>uzINEv z*!idOGO^72kHSlf%*3j0&0WP86qwsZ;Hlp1cOY%FQWvmR1_)Niob}Qv!WfUhk&oJA z39pd)EPb&O(q6d2ke<fM3tHSv&lvR+E=GI{OA&xEZs6w|IpLCpm-|HHy&zmveF>%r z4<9uEFX8#N>qd5(K0WwVHf%ajR82W-DWIRnw~u!z_LsME@M6(@rG8u`Q@5sEXI$P7 zB<j5Uk(#DSlvHj($<8%#4$aezflArBT9?bgYt&b^vFoz^0)qL}X;-voV2YbBi;6_! z&OopxoKXK@0tg5Y&BewIKFS_aX;w7(QR$?hyxt#ON*Kyk7xrK5$m&#ik1B`1Z%&!5 ze5xRC8x2El4v_+i9CB!vvvU1$wYHdOsb#@9AGKgY4Wj_>86(^_Cif@9&@+c?T8CkI zrcp`)LsoNxI^GF`jiGIfO09m7GTnO3vkLpenj$^zx;=4k1&{*gOA<2fvT141Manra z0`V=Zl!h6UK(8p!ei_e{5FhUF&z4nIlKYF?HI2bYj;xGVmXxD|&R%(UkJ?OJKaX3E zkh5S?4Gfpi5P6p!svk7aqbVHhr?uoF^~*uM$!{b!t+%GVwR>jF<&mCzOuY;TJh&l} zbPT=EQ7t+FyG06HA*Z@kj~|6F4qaHqEug-OE&VApoHJL=9kquWuh*E$c~iuUPJ4^F znilE{#r%}BVy^?gxq-EQ-(0mgpxVO%<QFhns3E*vRCF$@U+3Ohd%$|lIxMJtqA-AW z!i(d+Kz=?WoVN)rtksuxvrY^*!fCJAt)=gflNz)bA<1-ozA?&`p>(DARl){Kumw0i zJArntGJtg5*}i=Or8vGn<dI8jI!GH*B^H1&^l%-2v(gsQp6&h{<o#Rwye5=?T;hsR zGH&7KWSywIHhri^`LHkfb@sC1nm<e+_gV}>(RL=RyuQCKP*+(w?om06r8>&j#c0!d zxJ02^$Rcv{UQLrI*XZWNSTn0rd}G;otG;8Ykt6?$^0cweyh)8W<L^gkHFDdBhA)3g zf9=~4<D1;|K99}4+L?306VVegr~I5A#)TX4Yi^=4n%=`|E5h^7L6S5~FT1TLb7@|e zYBIctyHT^NnZg+bg_yh%lyAl20JbRCO=ICAIYk1sA0Tkn{9>eovwJD><4yUugM=;F zxIV7()9#r8!B)+2`CzYs-Pkt{lSW!a6HmvYz6wt8s+OdrfyG^~oeR{=o>`Z1bSl4^ z?Gte-EUAD^ySHyx5B(4n3-r_axI8;=8MguuBe|~1dzb~y81TkH6KGIM@4ED_<UY!2 zV73_vvWUEl=L)Nmamh;1dEXj<pVJy<UW8OKotaiUGVuw`-n?~Fl{xxJEYe#v$_Mw> zh~diJ2i--2w>lbf{&Wk@`P`~GlOEmIGY-ql-y38{Mww5_(pu(=bG);?C30j?CG}|j zJcZuhPwRQsyu8W$FB9s7DMJ-avlWVnTgiO(dR_`csC#sQeN9D4vUb_2d5+_-@3!0( zQK%H{P4Ox;!^?L8;grYkNH=25O;T=W?}`K4pbrL<jz+oz$BO65CfOe=WpWFn`~cbX z?%QDr1p4btS;gb$rVQ%Jvg@ad;SDzdBK;jXrg*u9Uwl_8L?^7Mmv#>NEFOU?aJK_8 zlO^-aVz^(iX-EhhvZnVf+3XG){*&Mw9?yNugl-ls)uL4?UKrbzdz)*i9d8;e8Yzdn zBJ!`fqq>yttT*(9<t|%s3!of`ODOrgJU_thgNHe3&_1}c^h@FL&nDPiy~6c7%a?}O zv$S%(HRoF%GooqYyeLubU|p3a!RM*8Kf-VER1_qb)rDw8>D=OK=d9Mtg8BXq^&r8} zpUs9_*lR7=7>mLTr5pNR6BH(4N6iBdb~?_v)V+yO&x0e+%e16zlZ|X|t!l3$SG$ta zKC3J_6;%(H`J1gAk*_&6!b;-{*dHhcD?-6T33E~(!Xm~U7_;fS65Jd<Y{|Xhh$*nD zC~(T9wY32IQJ5$%E%rc0-lQm34F-*+mG86(dj!O4F(V%l7HRe2hZL`)T+@l@?G2m3 zAQhga-&XnxQADt9NTwvy#wB0TsBU$z@bUZqPVO!s@2)<&%~{B$%iZ}x7x`Ee_Ojn9 z^y{*9iKy*^>FMDdB}VyzY?!yGO;W-K`ukiCO?*8KQPbSZOkISKdNodi+mJ-m<Z`Tk zy<x&ljskV1dsbmqV=I%)pLW~n0v?z3Pss{3aB$u0Kkv@7=PfMPY*_w>a2S})_*|&+ z{okiuU6uf$dM^cC+If1$X_z`Te5L+<$N|&Mln;+9V-?k5ZSgYV^QE6rttpNZ;|-(A zHynf0=x2t?S6<3os=8&U3J%RSdqiQpsqUEfB6FSV$~8=#E(_aZ38pxHoWdZz=!m04 zQ<IKdlmI-+rQZo9&cwyf7hKNvh}@!ZshYXQYN%*fhXa0Mc7JD1&D+l+%Kr6(X{Q^= zkAicsw|EK@YHe14%aN^IcSPugKKpM%%FYYDVJ;RPYNCw0;=M;K)U;b3@<|6@2OaQW z_w>(YvM_@)ZXJOr@F!e)M5#svQ@M*H(B2LNm7Lcpfp3162{v~+*>9oGX^Eh<?atzB zsE4-o-QKT+jmptBgSh6DQ7c)Y9+{~IBQD$Ul+SZ8b?qqbn_czf_Sobo2Y@=3e5H5w zb%7=Hif(}cwr%~#mgO{hFz3O1{e08hgA#E6z$xfKG&S<U3)BPWl%N7xi%1`~2TA`m z*Ycx=`~~R~T|Ld;Ty!q9BwE<N?XfKet1F~_$5B(?VcyZz@(3zaN1*JGQOWsx2OBTs z)~MY*ms+*sJxUxd6z|@|`vm2FJ=5+w*PLE9YBRRPU%0a7Rps$N%sN06Pj`+!-<4O^ znXEqU484iQO0M;B?~RL{Ll>bB$U-(`%(<Da(~gDWg6FU;UE#lVjk_Ey{~G&igT9`t z+9-5A(C@oeVs;%Ei_lmj+F>FH6b8P~#Ob~WSYB`2f0c{75dn)LbcVB<?5|&Gn74X< zn<ua=b8o1z$a679lc|VCa45E1XqKKgG$+x#y~>fEaGZ@)#fJ&3R|G|hO8>{)HMjLU z{d;HFw{8A=C1$U}C#lUT)UD%tF+_oPy6|>P62?|)qJnCCsh{n7j}K#*2QI3G#S_Vz za0&(Nd^nm)W$X({hM6x_DG@j-#vKcG#{TreulF?`gVjk<?WXoj%94u2aHXFPoR?!9 z8#u=Cuvc*`tT0?uc1HRcQJJ6hd|lV&9f7pP5bc5bMlsNO84cxIq^=*V<Y8LtjsgEv zP<R~SD!G7kqIzKTZ*p*t#@vqDFC;qi)MJDUH@Ap2s7<pWLX_;#eO<#EGq7JPkxljY z@MzzJ+9>)x^5CV7%4n!(RgCdLxaDu6UU`JEC>_c>Hil#Ljz#3xxspK1G)=y4|7h4} z$O&g%NpjWEH?7V90)%@h1{y%NyU=oQAidmZs1>P=>m!Y#^rXXG0AiG^OEXjLn9+QW zA3iRq{m34TQ)ZMd{xKe<+;2dkHWx)wyi(|hkHZc;M=4L~lp_okB0VWOogm<0IV1p! z8}Hm!>82>gMA^ywI)57V@bUSjcBoQ>YPT+uom*e@dJ-I1bgMT>=pL(*>Zg97tMy2< zJG9O=J{FeMqq9W3q>J5*x&8DoJ*u_)x0kk3eFZ{&mYN<*KLGdN!Ejq&eDj7V8LnC< zHmBO-iGt+_)w%)WSEs?Xel;oto-!G=ObGK1jdK*1>Mm`%{tI(TMA^Nw6xWe8-*JJ+ z6_0~?-&beOp<@A*oEr2iOAG2y_yHo|#B%Lh`<(>yLt&FesJ%&{Y-6Yg9@h4BT+@5| z{E=7u7P7ypG$`P36`N7_o#yZ~-1xvR28(ocrg?J8WvoE!Mp6bu`9O@Y*f<}8W|hxX zxty}!Uw%G5ms|ZCf=LQl!x1PRd<EobsQ+8zcrrHD?HZKRzrgP-GDA3JqV3WW3C7oV z*LXBo^3`9|WysGp4bMiDv1qKzWe6uF;?ws%ipvW#fZ7!cd01Z5&F=INcM^MLJpcpI zC9V!p!vPSCLDJ;_I}na!m2uxb;2Vl&5HWQZ{a(}^aB}RC!=Gr|8OyJeBKbguPZ%fy zf_9nWVSr7ZS{?(l_}qBp)rW~3FZ8gNAAQ;Kf2-qsyT|_rWVtEhhuB=XDgA75#={kQ z|69@%IlCtki}emt6K<6zcUuL{#$LKD`%1oV7qOvIIN33)(c^V&tVCouzcDM**a6|n zSMcY-lf9dazsxUfj+x5kziqppr5Ip+S^wMqsjPL=sX}EQE5nuDIgskfaml0+r%hG> zh-D>}slv1qD#ic%^-=BA=~2ZcPp-au-e;m6ce*<E4!38M9_8uK5wRL)voks0g7;S~ zd4=DB<aUMMo4$m6Ph8R`D|(%k65cw0Q!^|3_$x3tx0XlFc`WS4EhBGeU&vpv_BAtB zIVT%cp9{O!QyNPPQ;C9Zc`cmmyKq~Js~sa&{$)fEF^Kd#IqB+&_3ux5o=f*^)SM;3 zc%>g)nb>&MvrJN$Y(Q!f7s-8LHA#=BBntmDrf3qDJ~ularC>zOAK1M!%LwFK$R;VA zJI~!FTj^(KQM`;^YEJtE3~kV=LOq`d=h5)^6+8xXMU5kXwcB6f6pRLR{7W(&;)J-i zKgHZFhC_<<ilTiu#S~~|qA!)?%1o3FZ#PYHoJ5Dw`J7P&xK>=T)X*_Ke*cTBvLWCX zR&`F&{*8|AL?zavkYu{(THQVr#>wrfv?H3L-I<~<5n^h=+aIK%Z=8B27A166p8B!2 z%v|V(nudF^iP}%EcT%0hGp<!?9i@|Qjn_{2VlKU%{}e-;-#k}-Geu?+CRQ`&7%Nr+ z*cnJV&zap&EmiyJnUs{5nuJZ;mYud@Q}6b+wpLYmBd^hH#XMS(=R*omp`yTm^A^%4 zJzO9SUrvd&wot4H=&)g;R5fcL#Q=Z6V4V0qeZN?H;_HC6X`RN?D|2T4?r5b+gsHIt zhxCc>T&2;3{v-fbp78rD6qwQo{w#?R{`E87YBB;yHdZ;ylz8K1WA&R&bu+w+7C3Q{ zFZ&RY>O0fcm-Q%bo%A`Kund0Z!wN+7;XaFqFG(^)Pa(COgq7E?AgAz5q0<k{u1@pj zyPw$$Dk`~lD}80KNo!VHti7ddT|yZqy^wZF(Zgvr(@(iO=P*r-gIlEZ-=wr^=u1Vc zVGI@5F~_*?A7<Jo*-wX_dH(t=5w4(`Xdg$nu@$!EZ<x2~q$yms2Hi0`Z*k<`F@m5t zX)r}j96TMDm5ff!)zV3{fi#JM)RNdU%0+%5DIkW{di~uY6k)U9Pd(eGb@$oNv|DgU zK$tpOv~o1WZc~yM(oJ^dkxdM^Nds(Pd1)qDOPUCpQXgF6Dtts)LSNLgfDdCXMb<~z z5sR2=`*^SGt7DAIbxe1ufSuSjSeCA4poYryy-&$#!p<OP{TcsvN(S21S3Rgqz1W(| zY3TQk0|Qt6_5SjAj5;q$M8r@LCAuLQ8bNr=EELRp&5x^}ii}#JOsp|wjl|Ch@Xlur zSf=yqwdYRRflsxjRH6|fF`?0n7uTtSo=S%5?LIG^r2gEvRdjAtI-+!T02WH&SGKIB z^LC#N8(thRXef7P5@FE2^sGp0lS;-TCocMb0ct>%zbnqu%$q=Okb7ZGCXNAs?#OAF zW8oe>=1~vu0l*uwd!aWsb`hf3V-2dv2g%YY7FXl~0I<B*2V&uhyZBLx6tU7CM?o-7 znW7dQ07WZU;izH+PM(mF5l9q6hjWmrn-1OBgZxGZRS->A7oEy6TZRc+Sk4x>S;;dY zlCxe>b0wgZ1Ba%?sgHu@8~K>RjR;56cdc_s?(FDJ83I3v6b4f;GoG}PmC}gtubGnS zL?@ucs8+OsOTn;PP~}oJOZWjDH!MpKvns1~)(Q>hfTUQX63ym`{|#D&dCyRpT1r!> z#}ub<i5uLoD5~-i0Q#6^TBG7Xdn^MDRMXn*0$V2;k)s~V5JS7T^C!hVWfQKrR|j&D zi@r2u6h#FV76Y0rmsYQkqZCX}z(yPgQuZlCN#HW_p%gixv$YmVlRfZM4`h5HvaT{m zLG)o;h+L5%EF6d~1lEvx0swhO9K|17iI)#}B9EpV?pN?Mk9<%<5B7*1aEDV{>{^Jd zJseq_O!Wxzii8g`sT>RdFv`9zgubFp)?HttS5M&Px}{<-RA{t}CDg;5I0W#ExWcB2 z;i@WsiU)!p5*W4~7XVA_#6wKc6IZx`mHv8<E(qD7s?ODv|G<s#NFJjUbeuy>^+-pM zP~4-$p<x&Ln8$rsE8~QC__6?)L@rjL3m^zWCe&I8hY8|gg0&(Sn8=qX?sBpTzXu&B z-Z4qoge`l-!)aK)P~z5LV;q}9$6r>+DRQ9)Ol&HN7p@;d1_QUyiVin0vq2$b61irz z!WL&Pi98g8$!{F^&)*62m~$LfLmMQ?A)TCt0w|NriI5<m$fH2iQ`dsM)D3t2M2Cwj zkSYt8(GeL=!?v*oYy7nyg*LTuNVW|$Py+yDHZ!bK$zj5*Y)iFpb1>?{)`5t+S^g3Q zUOALXPZC5hea`hm{8N-O>>?lBc{Q|A!^mP7)|~7e|8`U)@na4MA`{}q@WC8a++qrp z)4_nLw5U~SV*69L<IOffXr!XG3=Z4)mJG=jBR);G_8ei60RT?m0~vq-;REr@K+<;X zWC!CmeXY$vw0G}++j<`QuvOpA$u*9DrYia1wmrP9*hP!Q1TH5CDdI{nQ-lI9(jZoc zKEWxrnvzQ)WjV<SGD9)z107D;c+khv9etoYc1dSQ83>|=I27Ro0MJ9lKVcp|8q*WC z2*x68P^{U|<P-yiu0IFzlm9+_ATmk^cLgC_i?+QpTIT2*TMGi1Pelz<S3?mpAOk(< zA{fDdp0Jy{h#vHy5ShRWL1&(jwc$GH8#yny|6G{Zx`%}`P8kv!iZOD|AH)g-0Yni1 zPzJ^ufe)RK#3o{Y2gYwvHr0Y3hyZg6$^)I_c?;ZC){u>I-Ob;mp9-4*AbJG<;D}PG z0|1O55UPV94$_!}8-`GV?Uw)mZD5&fW>Z3cAtW%K$VNCS&v7+*!ya_VrPJ?r{INts zxJ5w&FGf$<H~;_%dnd&tWWpqvgw-{l5BR|J0RjMkfEvt(F4&&_2!u=wk3ig)LFk?* zP(wMC%lrw1Qsl!j&_OxGpYe5IPM8yMR8VV09RN6j>Lr{9ydXg!fexHR>Hz@sNzN$f z98~q71ZF}l>`_7#*HZmn-F?g&Sphnj{}XNLp9zk{2{d0p>;f8G1!a{QLJWdHK*A#Q z#z1Vs00O`!e2#o6#NG`AAUGUBY)L=`Vap7U5Q>Bma$ZwZjhF#|1a00ElEiv}!67K1 zK^WFR=;1|SVL`;8JrP7LoI((e!W=E)$z+g1@E;B$AVI`IJq1)<gw{+s1QZR#@2Q`u z{mFt+0sv%Q3GSgolo}Q&f<ROPC>jLP?GzF`N<q+92~7kG8iXyd1^|f8C(2<Wi6XRJ zo?3v5Tg;*=DnzM`0UE-=3nD`o$e0&`TSZu-Kp>((r~&}2o#^}%DiOpSlAb+q#1{Yn zJZXfhIpH#jMAQ|5G`N8v;D|aT|I)YR#Js7V-yz`Cjp5pT#W=Rz0g;3INkTl3L%*?O zJ3@pJP@+J<#0LO?HONQrJ)tYeM&bdaJ#wCQeF`0X*F4bOLW+b55Ck6tgAELXH(c2s z{)FGnk<ZZFPH;{r6q`VVVnxE*?}gJje1i~#oJfx3Luk_?+#mpyBml$$L4b`wxX3H0 zq7l?VJs}Ih1mj5rWZflAJzPdTU`&|^WkZ-s=+r_hNP;T##z_i9M6!e{DCI_Wpi7!T zg@qPa;3VnY$B+nu+@XU;C?i;wUoQ9^0DwZyOu{LEO*sB#N!VmTU?t~OQb!!tI{Kwz zme4T;K}__44dfhj4FoKZ|4L<gg=5woJ=8--NKg}orbMtzOcX+Mfl!hq##t$(YAQr= z#U{DDB^@$QTf7dABxG%N7AP=RbFoY?V1g$Zj27lY`sHMBF2s9mk8=iH-{=D&%;WeF z;&T?nPz6IFtWYN~<#y&opIsR-l3Y5ZgE?%27?gujbOmKrCL97l5;Rx#jTkNp1Qy0; zZ91DRVBvXkoKlR65Y$8L6yJCbVJWP{A2io^*n)Y~3?G%k+9W7L*rY80mqrBWzabDV zt%cL@=U=YGAm~6W;8`xf&Cd*AF2t3ELd2EX<!%ZDn{X96po2Q7Ln_v0V9b#v*uW(0 zpuw0zu)U~Ah$n9C|KS0p13KV<-Sj1GjwiG1Kp~*0!C<42E`(JkDcg}F1H}ogy;ypQ zsA3*N61V{l<XPrmX_h7gh|C6(65ldb=XDw=nUSebveg&BK#+QpB(~{7n9@*jDThK^ zb*jj~$q1e<Bp+eG7a)(pxG111#O)14CCO=*9$!^djSzgpY!zRWR%ZW{f@ak~7a$L9 z)Pf}RL8eS<L;Ryt5bAVxX!_)X7*Invb%mE1DVMB7Ef|3j=mN3`1Z%qLL~yB+ewWph zgE&B`s|FGd?tm@0f~07O1XifAB7~%9)3zARGOFh?tbq$TYn#@_ZpZ+6B+s8_E03K> zH^@n$l3aBP|ABJk!(@hPXkJk*EP@0`!eCgVq#Enylp3<C;+ovjEtrEktYfx1q9rsy zAD9B8oI*;pC;;Rmy8=M5HATVh;i1YwIqg!LR#B9_1_sc9EjS8jC1%DNgco(}6Gl`B zqJvT($D%Idw7?7wxWNwaf<OcVA3R*k4g~%@hKwxax7dTY<f?W)CzG`TqqspK=m0GI zqd<T{C@j^`nnO4QNxX7g;>f`+$OAd-sA^6a6V-rwu~jsU*3cHjRk__)E@V3BgC)p8 zJTxnU;Op6rLMzmQU~*@`vMVkW#Mfq<jM&Xm>;m5M<vJd&P=>-BF;^V`i(tI1LL99s zHidoU|A^9VgX7-pNQP8Q2!zXEu0kjp<ieVMI7LLQ0WZK)dbuhQ8O#o7;XrI1>aK=C zXs!u9hJ8eoD$v23MAD>k*yczBANZ>$AaA=d=Fn>H>Yf=`5l4X(!x{hpc%9gAj3!t@ z%83|}86+Y>ILhx>WyYGtEKM(#;a0hDhd9JT7a#*X>4W_WmpL4W_kv}9PG2A3MJQnG z?)vT%HjHq=F90k7u3AGjhywt;Lt>PJk;;HJ@|cG8Z_7&Wtm4~!2$x1kLpJ2qapD5l z;6mXV#Qu(?Hl6@dA|MD5-ppz3?k;0jBoZrdP)a6GH{#3*qvLpb;q+|*8ZO`rKc_ta z{|*4`)1u@{9$k@7ILmgr=q~195i4dsNU(lph_kuG2jm%U)P#$EgR2(78M15@KOtx~ zoBe=NUcnMg*n}CYX3ku~8NVoTAaP&yL@sD%hp<9ZmG5)T5kdHX)d_?Go?$7VZyg`s z3F`tV2nKG<kG|*}90RHeoIouCKpw<F9Z((7#_=L^-Zt>udf3IwpkyITj!G!<cmg5- z#6g1+Z746}F@QoQfR<h5Y%p}OObApzjieMZgt!&*EQh8xCCfhXL3H+4h;3%_{BeSg z0x#@<K&T-ASaUJ&VK+F6=YU@`-Eft%kW5uFk2ae_C|5SmUorU6K;S|h7*Q*+|3WR` zS-r#@N^PebVi5q45G)!*E?{svx1I9*Y{ZF;OW4376iStZrq$_!HJ;3-6a;Ywv<Y6E zuK<8DOOHJ70S_3N6{VeGf>wP|bUU(XlW2&DtwIQ~vMPcyNslD9YHZpCEht3tB-lVK zutHV+3_!oMPqUZSqLQ7VWK2*pOaC-dD;BdQ1QTTuJ%^CSCbd-mS;3UAYsgH!@XJ(h zwT!uf)wY$0>B~}cHCeNlD>RQD)PgD8MJNF2DNIjU$MtaCL~J4#RG}oRj`LB=HD7Pi zFJCPm#6n9HPai<qLiaUd%abM+1o#co3eDG^CAMVy^(b(de~sGTPC^HC{|J>t_GEwd z7X?&R0+MT}9lnr9XYVy=uXX_m26N@YQEib?yEJRpcKQ5Kbao>u%Y@lMuWkSK1MyMN zs?c#A8E_wW0bRBP>IDnEhe;zhbT`iC1jCPdLX=@qGex&{cMnc5N%6>mwA97mZZ~;D z%(`K8b4i*^NnUxkH`EjthIuD=(u4^4wtL?<s#Fm{U_xev=TLbzeg`<9Fv}<O0VWjE zBMQXH0JwlR_?cwR_~L*Z@If6g36O=3gJ*cRfItOHU{7l}h+jwyBH#(gKqeCeI)}K5 zCrKRafE9EyAPD9nEXs=4_>TyI1^5B<<pChuxQ~Cufy9YP(81Nc|MHI?d4J@VISj|2 zNW;291d|ji^dTjZS9wm{2bKc>F<f0ImjpHQA2D0Gn2!XOV{t<4;6$82;F|83uZ|Qt zf^LrIeVBRwVZll0Kp8Meo9}r=%y~f&LPD%LLe$_v5c7ERIim0FKy)}k7$pGoM&=lV z37p{%AY2pzfCr==T^xF%^Eq_v-65=3LBQUx2!!}G1PD<1FRFH@TX~e;a3h}jLhwN) zD4;_Q#vir1t{22J5Cj~oxuHaa8)7CFf%L8)J5v}UNjM5FJ~^^KyFrk`S4V^q<ic4) zJGLi;aZiL6^1^IzdbW4^hcAQ?)qv23JGz%d5e$MLr@OmX|Ah3V(!0-lMexyc(>uQZ zP7$QUwBx(KBg7<}HMsvfx{Dt**VDZde7akU1S-74N8C?1B)vVnzgz7<Q~bY|yCk$b z#^ZZI0YD8pa>tK6$(OvzyL%9jkN}@N%eQ=+C%ntYyv)x$&DXrmCv^ngJhGDz@9O-n zN0ZM7z0eOm(a*9Z=62C{dd0zf(l@=+C-ovQ{nIyiCVN342ZJ<h)6^q50z%_Jz{A#$ zc@u2I28TU<>j4=I#1)u*m5aLDffd`wz1$aZNh<r?*SOu^z25IV-}k-W|2^ObzTgi& z;TOK)A3owIzTz)F<2SzJKR)C~zT{6n<yXGtUq0q%|GwsLKIaQ1JiNm>#6#0&>~M&~ zsO+ui3Iu072jAuz$L7O*fP)yre*U&Tw24<dAVxQILpYoRsM`K`R+3Wa1Cp@sAkInZ z%a~gf-Tmr=7-`=8sqgN)gEIWXKWs!f)V|q%#`ZhZ0ntOdv_TJ013X+uP)-Evk3RaN z{&3-ka#%wS<iIS@Lp(fx@~b}Z%M;h?gEgQ6K(J%CPS!hf=Iq&%w@@AchYuk}lsJ)M zMT-CyI%LRDW5bIdL537Ll4MDf3F*}nN5|5xHOuq?NNDomMw=Wt(u8<ZXHTC$fd<W& z4}iXDe<DSiQ?%UBpbHbuROm5iRjXHnChXSj{~fJ%>7;ejwys<^cs8+Gy~#6eTeoi~ zlGDe=(z|)trl31F(`QC``t+TXckp1wpKCY5RlGQ>J%``)1&YKC+_X0Uz(Ji#vtGS~ z3lBP`%9wQNllH{r)7DJiyUy=Yxg(s|bjXJCrXsGroA*R|^z>Ql0$|)bbbcV^OGnQz z&4rz<S<?r6_GpucY4_I7+c7w6cCf{Z2aXXeaPe?&7RmQ_XTaUU<(rv(dws<Ri4SwP zbt`~tvH;lXGwbYgD5}5e`D?)D3TzOogytb9AC~ALha7sgSt1{D=E=>uhT^b72}1Po zCLMipBhWVNFk;Zb7l9f|o_NYB@4WH2|FL758D;EAxqRd?XfShfg3-vJ!s$kzS6KTd zoG0IbC$=Y3RB^YP%F!pAaP;X$Gy0AU^CG?$T27oZsM&CyaO^<?CgwbHaUup!6oe9S z^jU%$deTvduMe>+Qp`a^aw;Bd-T+5FdAP9$4`1quXDAu1lxU-a^cm-mI~WO1Qu$IO zRMd*J>c*W^-g)QAg}yQ8nsvbW22A@v<MI_lXo;pCDg_<YSBmsm<_iG4S;(7w1QA3Z zaXORpBlog7!X9tvp=OF@qjF3qhR~4*9dW9x^jA@bl9ZD`>d8!=EYGb6o*qX^$SHfU z`NJ1%=9ojDc+>&1#c=_Ch|6|T|H((ya2SFIHgDo7OkC~)^sgCj*ny^<0LwY>;eZ{K z>K%RLu*9Bj8_I_oG`s~>+Z7|s#}7&>q*jhw&>06#XDiao9O9;{C#D5)=6KL71L35e za*&S4C_5-yh|+ii)5i{9(vb%oJFHQ+#f^n-5XyX@VJFFKx5`HrcF+-UWd|X1h8BIo zaz~SQ0B|_yu3zk|s4u9|Cqa4mw1@9}ej9M4->9)-Sqtfb#1DNqob@Alvy8@yGj4&L z9-#3a)F}Wcdjp#plRk$VJct1RJ;Onw6dZ2em_|HqIC-QT^q%f~&?ocpMiYDB(=2#` zlkA4`2BmZdo&a5yrAy;O|JD7-2=&?JjC#D8N2YY-B18~1{{(5Faq_W54tY3KT^}*1 zsb?O^a~_hMdXPCI8)|IW1$)onm%ctqxq*#4$gW{K0{}LB@rQii4oJPSNIcTP2u^_G z9OD7N)b{ncyZO&Fe0kE6wDFGMc?3SGqJ=xC6g}-^L?7%>hB@fQ71*E<di~?zZXh%d zeW-#Ckn4~=_@ocV`OsmXvq(bFp$|6&##qP_1OS-zw~kmuGxk`P5|=TLYN3IA%|go! zdy*~3SkWg+y96V^0T1+K#2nw@hF~bQ!H3x6P;c<Yd90R?qAgH^TmvI%wgL}YJOcnJ zgbDzhl!|to#fB33|I<0nQI&(hLm!Gv(u`UaHhmz>fq&f2JiK9#B`hN!^LQWN=z%98 zjKh@j2}urvb-nBzgdX`o#u|#!neZKPDxh>3B+x+)Y7H@RU-V>264Dt;ngbp9A&HD= zBtdVWBOU-C3TDdjs0<RNlM#86(tLpjeSiZY;IxB2xbY=F9@8ya35VQTV@P?(NFQSf zM>!f95ll4`FbK1UGm&YJaI{Ss`f!qH^wADl<O3cKV`qWpVaqcB03GS58Y)x6zIxou zkEX019qPd$T5e7V|ICLJNwS;_8HYoVVIMto_^*eSWGM9*M{odRj+i_XNb#`DH}Gi_ zZs-FKoY>}V|HPG$gP<cHj9>&&k|vL7;2~>HYv4?4LpIfD0{{oR6s8EKkA@;dg%R<f zIk=>cJXGQx0u3YZx?v7wIHOAd_)XaqIS%-+ZX|NVDyg)UM3<B(TMm&BB?O_4DDrh8 z5b_29CaMlojud3Ku!qfdIVObwV6fgWhdLybEGT->uUH*QLX;MWH!wmv8tEfNvV|LC z*Z~~ikXHl2p^tNA(3)4Bhz98ej@T&#X)^*xAYc*H-2Ig?2?+-b^Fa%CbZJqe*@`~A zqF3lmPFwiVN7&Z!k8A*Gvwcm^R^%3rLbhltu4+c{^7)a{GFK)e(}(#kdlR{cHj1T< zP(98-|4NHGq(VaU1Nu%`+J<~1A8Xh}Ob&9QWvn3|OhqYud1+s#9ybS|i*Ik0=2UfL zX0wh_nq|<bPWg_97=hqMJnTWKe0(Q7^Ykr-;j)k?Da<RE6x3G2;S~|8S6lEal{^Ni zk9;U}KlNoSFO|fOW|V_&0_(;(+F^+2Nkzfwv1%NRiR0eh^b5<dhdK-cp?plZZlom; zUlMYT>QVR`<^2scm#__(hGuP4{7W_fu#F*^BZxBtKsnGHW-<4+D8_ihH~|odUhFG9 zymUyp0KkYqjB||;(T6ea@H(r?X+ScP^SR0)nBuOB#tcO2d>6eQfetJc0b-MSj!ZnY z|CKhbE`(vLT(~RTz#2;WPzF010yHiu(jMmkvw3mDV1pV4*6d7Tnf(T5Aj(AucseOt zAd<{_$a%1J_Q;*{u}V{lW@9<bhxK}=J-f=qant%?tbe<}$QTVA;h=H1mfP5<DD6@C z&{}VeD``px93pWX&m-<dP1oh4sQa?!lkp9dQW@JBh2*4l;4=<gdr8sy6l*@__M{|9 zsU7kd;YdRBj+EaTA~)5BHpKd2i5zXlAJfOMtNllh?t%^#IweHXp~IQ!Lmd~s2xQPe z(fT^XqD+;;E&!0=b&><J%P>d!?AoVdP`H>uXQy|-BOY=->UKs1tV6f~J5Tkf|6Jz) z2kKN;a)=ZL9f;ya#^RL6Jyz3zX3sd3<2uNE@JdDFFo$$03hs%R12WH0#ygx8AbtF& zOEecrVNT^$>m+m-;TVU`=Lpwz3<Dap2xK?uOFiq+BYSkBw;zagbdW%1Sbn2ZJ}7bE z{;u<}0d|bMe*-Qd=vjNP$8j}b5eN!aQy-Do^r!B|mjK=Y8xp@}x#B@PM$Aa>4=I;E z!l{pPbmaV?&PO@}e|W2CC84zzJw+g+NiREJK#JUCfVe`TzF{jggS)P)8Lk07ILWNs zffkBI@<L)9nxPp?<v*H?OxEd!s0TS9=b|8@z#J#{Y)JO#0JL<^AtGuQ|KuPZ&;jEd zNg?JeAI2ek<N~o!!;22jP;$f?0Pim><Nf5wDU#@nUJUypq8#MT)x>2en98ZjL0zm0 zJwUA<;1Bg`!V0kpJ_x3(c!eUeM4_4u0#h%_lp!1rrZeav9Fze7;9&;)>>>nYu2fDU z!XX>#A+JWr@XWz@@_`*_K_1M_@T7-&mLMDC!IT&zaK;V*%1&HlPnJ$_-t6HBwjmyH zP_xKw4W?~0-UqSHK^)XUrtr-vJ`E3^a3SKsbWmr3+RZVNXv4$<Ud)fi&cf{|f(iGH zn-~K8rU7f9@H*B){shJhjcvM&M-(GsDB58dmPHI5LLXqL80|q;|Axdd{BRnR?G0bB z8vx)`zTsf#P)QI_yIe4506-Jk0UDDe9uV+(P-M{{WPSpylp-<t>_G_jMC&YqdWfkW z(;*%x(QiCM8_nvn^ufWHE)g+g3bsKY1<`-b&-&~E{#1t>BH<F0>&B9?r^*51y04lv z5*#9p6Zptq<OG0{Fvc3F?&={BW`WX>YDI$aAvvhnq^nCXu2k$n$ac+2o=YB*ClBRe z<-7tO;Nz8mryDf^hMoi?3<P)(Cd=}nCrP3ioB<xxtAyOa5a>Z|@J+CA30%~Jz)~qs zwgC~H50vBqAL%g>Z_kJ1C?OaO+i(qtbSNM%aTN895h7un{{{pc{7wmP5lD>U4NlQ7 zMnfbe<EW7F(i$l4xUYg_Y=Oe>B3ZE<cOvkD5#Ky0J{nMjYRD$CB}pDnY^btDI#VAk z?;Hj&DgZDaYE7@=qcNRq*4`l>5O635glxE?0rw*`EzKdq;bL0jDQ~J7a8Aw~<C<nF zTRH<QGiB5~VkpSR1{Z5>3M=d6k(5j++_ufY>}@y4@*zBG8P1>sI|3!%GJC`m$9m-N zVh2S&12ay?7!<-5W$Lu-!7|jL2W4s@6q6(+rM~C`n(BcQ7@-I!6F`&D#&G5)^mAvb zsI2JAx#A-lh5-OsXF`(%%V?o^=950kh8CP*))2xW|H_8*PSZOr^ka?<co^#-Zt5n7 z1ZODaAU@{imc=t1LZ{qe7|dZMne(BXbKLB~PQ>B#a3d}N0KdecaEi<$vc=hm4qJAK zPx65maEU|2Q%)W+-oz6G{UAK2BC}@7P|BefTr3v-g&Rf^pY)U3rc>Y2FR19_FVYYG z^mB?34#u2{G8c57tU+|p!<yh{BL<`?R!vUf5w7fEt~?GQ=)<|pLMnTbK}rQ4l;IgR z>AA*eE8d|22M{<bA~bxH$i`D9AVVA2!8LSogWl1SW>d$y0XGwHuL#nU#7)kQpl>|m zXUwVw$8`7xGl?ug6CW@p?JAYzK~G=`GqqD6|L8z}v`8X;Lmsw449@b0Xi{hlMIWN? zM&>iO{uCrF0@Ebp&?FDWey~vxQzD?LBRS#4)@A*s4m0-csGM&j@?rgyM*SKn1OKR0 zqKi{k#ev)@R8QzqN265a28IfWFL2ZxYOSG+Y}WKaZl;n{AtFB7K@&2?ZmeYEIPV*3 z6I8d799EP_?V&U9WD1bM_XH&&(xD!<0S&gHW&eiMnoS=ND^u9*15+v8w$(!_!k4Td zX4h?Pl20F&4=n|jgTD0=CPO?%tuT>LI^i`R<V-T`!A^6cT%-y-TIAWx&tEJ92{)qv zF+-2~68pr(Fp{SFazLAmuv@zZRK228|KVq1Z&ENE2uJG)=R|WVAmc@MR$M;l8K6PC zY&4;uK}oXHA_8fy>dG(#_iwRKcfJ7)d=+Q7M<03>RBSXKQez6Jp=ELArtG8~i1lcp z2u<{%JI#t`ko0xklPKy4GsaSBK#d+oX9@LfkAAV?boaPmffaFPK+<+mC?Y^hQoiCO ziF#oUrok78K+ZZ1Z-qulwop~JMqHFcN8v#oh(u6|?bx~mGz{p{NYC`lbPSDWkap$P zFcq#IkFE|@j?ycJGP5XLh@tX<tmrFrDWQi<gg$gCbn$W^Vas&&0cQQiDX-A5?(2Mp z4`<Zjg5v=c>%oy2@xC<CgSi)A|LAG9zya_+XLbUC7&4MJ_yREBfE!v+79CUVTv8tZ zP9tx)`Zmp8jTg1hPn>@7K^=5I-(bY@p~YzUT``Po%E5)=>EpyDNa5*Y$STcd%^ptG z^OOo20YIU4MJDtU15wm0Hg)kl6?4hzy3R%&R`y1tQOY`_DaJ@!0OLnJRV63ae<ao% z{>u{L0KqnNFs9=~2!Rsd;X*{#F&Cm=JlAg=sy2ny96*sk8#b`!Y+4FACUi&zZ*U+P z^`RzZFP{n=NX8>l@wi@63Hbtm{H}(HVr{^W8_L5Rl+Z9fr)&EX@UoLqEJM_6j3SzY zQHaVH_JtcL&ZuYvh-p(-|Nki(nT@GH1wT7tXO@xj-f>bomP_Qu<?3rs3#l9Gfff!8 zS1GstrueqJGvv0iE4NGFzUD>AnMXTfps?#1>H(dxDjtE45Q6E4+)k&0NEL8tmfAP< zLRS*#z#bSmNQd+w=Aj-=MjX&Vmk1IULq`3q%F_UVfzt$|tr@G7#`-X$qa9*Ak^v9s zb)**}fJA3Wxj7;jbcVa7w}uoVLW~hctk3v@T^~(PbDEg9&r@`2w#EsiE7UeCsU60K zLcPfhy<#Zsmmw&1^WN)8Bvne?@odV18);K3lyZt+FkwfIu{yIJWbR=6L|Zn_8I%Dk z`xu)4O9-+d9-cK-|HIB697i75^9|!s9xS2gxKytTY;@g>B3`y{5{*Gnq`=l78a^v= z>FaZHOPjoG>b{m7Vn;B~*0^9HK^f>=zae(C_Oq?#?u-FFCfOm9=1^Mrg&#&zs5U%Q zC;TLh6<@2LG4>hWhGAg~uFU2d9Ca%6vqO_Cg&Z@+KvmanjnDQj8p+q0v{<Rkp&lNu z9gc>v<aowV<zSzZQbW}cKog_mw`>0Rzx0G2CmAZH12|4*TN}A<0J#SBARa{Oe4jGH z<f4JOo4goo3SdH%11}~5XRt#m9YnT-!{l>9r^e{6fy%)f2vsH7R&SCBx#;!cXj#H3 zJUmpAPhr`P|8|&dp@}>$fuV+ZPNX#aM8{1Tf*X9{4!AbNpZS;;7aBlRuiLp+W#Jk+ z?|2604@FOlw}KwB?0JBW4vFz5Id&orw^f-#zY8)+Y*oEvDqGBf%JM;dl{EGyI?oPK z_Y^WUoK@?>r)Aa~Eh(bFIFKAX&^Jy58PEV8u2n@)DIacO1#8dwz{tV5VSr}DnmPhN zkGUingzxNuFQ@5KEaI|#A$s%kF=2-rYEdI=*(EE?K_6y_^&uT71!?fWJ~@4<#|8nD zq^g$}D#zhe!~s{W%ALZBt=&2*prk9(F=J}|o{3R?J+HbQgYvqZ9qe2ez4MHHvn#XQ z#sRpX|K8<9&s%7;tvZMGgA3V;n)b|(2PKZhuH#{8f&Dk~!JtcoTQj+p1UVk4rIVL+ zhmdt1+B<4ZSa$&+v=wwn0ko+YVVj<E)ad08l0h!`xWf%y#O`)ZjZ01M-Nbte91_UV zSKLx;j9(;!3Oiz`9%UT(rLpC`d(A=<P-uVSuOPM35cZi=Cu#GvfuYJFp(P^!rmG$p z&f^k_7Gx7zY0Vz6IDGg5y)?lL`Ly2+8J^<fnxegPh5}D4feki9a)2lu@I(xdVci@^ z&F`Ac<(#km03Q0>OAm_<HY6QjYgwZn8QjMi|Hx4CAzay%PZcu~Doh<X{<i+Y(deNE z|HZ{*B}0HsGCiP4k6_{6E#e%;!L&=gBETUOr=hwQB1<BHr|p%&2_;iwV;n^OBcOyH z_Ey!Yx~-htjE~S9$akba$Qp*>tLNI}2&UQMbTnkNg^I!;h=j$*X09A#0gp*P!3D8` ziGnG@WiJ>THKyjuM-EitH!LEEPUak-mO!WnO@N3Vg8m`0Js-=fvUQgmTKJ-JI!km4 z#fli=Kkd=LR!$23sRmS8>u%A}sO@QU!U^^8=cK6B=!OBn(I!%<c{|G927Cd+o;`W; z02n-o(40Ae-SR182M=Dkg#zt`3m5Mlt#;u6<QqsZBte7b^tIEZZ(P2W`9=Z|{}`^D zylc%ah7;%#p+T76^eJ;@@7qm~2rs_#$xfe4dG=m5J;<<|K3Uh|b?YWjr`D}pyL$Z! z7VJub_3DY!H-%a~dIDE^C6~{V9C_mC(Gw}KthjuX+~o5{(5+5^cDLDEvaH@boCS5x z^OkQ3wS4pD?R<J!uRcGP<c+I%FlX4&q)VIDI@aE_H|5HKWcsumfOztz-Qk8UUc9l5 z$LcfoMqfFRq6M1+usR>Oz%60(#`eb-J=(lo@&=a=k1u_@n|sX%%OE_h=m6j$#vOLn z)9l;3-^x%QJ7xLaU1U5uoP1^a;3*^slYZ@_q7+uI5hqYd?F^&OHwFoY|Ik(Dq!LX% z;ZP)+RxwR=O@a6UK+t{er1DNT;oyatQzpJMqBvKr_g;*q*&~iPDRRY_W=CwZR)$-V zqmNv4*@dD(X9@WYK?-R_7(HhRK@C0gd?Xq{^N>@I71ZccnUB0pxeFTl)Wz0~GM<Sh zS8m0#8UVw==2BU-waE>0*5z}KK7mByCUK1+w9=e!08pnqygk^`Z*Sx?4uC`*be%qo zFp^JqRT`SlgOido8=|^#6G$)V735=@rk*JfJo;=@)_;G7rI0%)`Dc!!7n$QsGxC_o zm}orJL(4Py+?Qfh`2=g>iLY{XRX#MK^WvihU8IjSBwiI#S4PRR|Ix6eo+_h2`j`V3 z0P~<j)UsPSnATbYfi+J(%dC+PIz+xI&{={|BHXtIX~vm81xb4lJ^Ji27n$%LyvCSi z`3r8urv<8yFL>w!jy=t}R8C9raKi{J^$vVzo_qE?l9!d%_69gFVR|Q1$-N0NIC@4> zsX8rz_^Mm-U~>mH+`xlrpdb4J2sr1!tgggPhZW#E0Hnf^fe<4ElS!!z#8_1FP?+qu zQLUO(v{>77l{>V!1J6YeGZfA{?`ZPPRWCP|RZmpqW8&2SNTrQ7^)2}{s`ijGr5}RW zwOG?S(UXookochvIqAG@4?U1g5sf|%<4dDHJGyJ8R&a$m|7JROy{efdY~(`@=2z<T z#boyuj=O2<s3Q&ldz!OcMR$J6$R+fk!}Mk2olJ9AMq`6VGT>0>okx}G!$~0OH1Ab8 z*aw2LL6<W1uR2;0R1P?H7$fkZxxbIvM;3(xkJ|3U^kIG{{-lrFuyq3f`?XD3-@1xE znsJSCyohI)k;;JT<3AV;25oV3hau__Efm>}f8qljLX?z`0qFw(go7V@R${O=6k-oR zum;y0caSUbMGx`tM&rCfkaPg4U3OVdTk3@twUmiTPZ7vGf+PnT-R>ZIv4@ZV1H%{s z=?lfs#}ZA5MX1<AA?T14Bhu%R;eCt|oTvx#c$1Y%|M@Nw;d5T5;sK80t;~HZF&P`1 zr!s<I;|<&>6mJAWkS_A69$O&@H*Urq_hr$90n&#v_>;jXYN#Q5!`A-*FrcPf#4B(c zhXv_jHZ69e93r%jvN$=vcQ_;|1jHNK0+<STm=a<mF^8=3Q4d!wk~BKhha6sku5BDa z9*7g0J+4#_O3<MmmXqBMt>L+P_{tu6I)V^I;*}#>VhsQwlV~)vFLX32ibmX_S_tX4 zT}n(L`UwOlP_`_=V8b?kl%Gz#VTWnxqk3wp6dcJo4%&D`H0Q_%^RT&<)T{;^h05PS z;_(!DOiw3<)YCgHB}sLfs*%s2g@*`+ql#>Z|0e2)WH|CMAAQ*8D^YpJfMQ}bSH9#S zDmBL`!y=W306-$OdKCZ%WR8`lbEnO4hCGBa)Llky7Y*~qHss+4N-!#0M3kW)AfXR( zlu3eGNyiZ>p$B5F4k32Yhboe&I-Go^GU%wC702on9q~w-8TG0@z$(_HYV=Hk!3`g& z#}$I8qaJUVhBW`^Pj1*|dfoYsKjV0b*(47kh@_e00>v^y4TO%(8R7c$VZINdFCP}u zM|nWHSBb#{E3zotQ1rSYZy2IP1~Q60sAi6(a8-*&IaWK`CPCX$O@R*eN*4o{4_YC# zCkV8M)WR|n)?Nc1SJBOGQ(Kk>4O1bU|DwheO#8XB8Kg4$5CS~x1y`?>l^67~p`VZm z)_7>uQQ7nc?T#UjD_U<HL9_>5!LnX7*u%XUO)Z-G%8fVVCLSK?9ykh1J?0ohv9}Ru zrrbE;#o7r@hWbW6Kf<%idJJSDi*Ro)>{o8+213@`4RG{PC#M+LX%#_RH^!j}Z^VOG zLyg)yQsIu{M2%bR=$~34rXOe|<u1o@ifuQN+u}};B>Iq5f7H>_s2!_pHO8SlVp5NG z&|(~xyskP41Ei}SZXWbF%2n%;4!V-+Rh7wy5T4p4a%L`as%Y<G-Zfq<DHC>OGUn{2 zU=8$svmW}`#us=r#I6t~a?3yi|Lo@B5;M<OM!exhGVn08#_EJO<xt0GVfIis`r;3v z2Bf+K)3L&CwmF@q=Zg6`>ckdL9VX7ur@c|04(jA%fgr|kHvP03I}jRi<1tl3x}Jsv zuBJBCPe*qplhSF?ApD&+Jh1E%YIT%v1_F^|l~m<ffjcA@froEPv>qR=Cniz@aygX6 zVvQ!q98${18J3X`)s=M{OOQvMBg!;-)MFcBhzEK#?G(rXpcwQ*oU0TfLqR}-ndy+A z$L-O}HSi)HX|3@wffQeFbo@YEvCB8|fre$6V;-)8II`O_mUu`i668P!gLf7)iF(nD zERM%H0PqJ+%tJQ~W}s7k|A@W^V?#+4sda@hN<^c9j1%WD@v!sp2u^TAv<NY}?`Dyn zo6{I=@|cf2X8CNER-`A${r0dr^2ijWGlW}HE^MeJLbK_aBym&5Gt?2m`K6nJesdJy zv{8?Dlu+#qOG#epaSnT&0U2;UP-DO;h^!(sq;}cM7ZUSlmmpIJ->A#VjTztprye#k zjIUO04uI0<qYJ3lt6q^k7IamD5sb~ZPHZ-*dbw}KVNb`cX(`cqoSMZ10Y@_IP<&hi z>ame{gk-DJ7<r&0AB=Dl*;^bBY^?fn1y(zI*a?8Z?Q|leC(VVd43DVXmLnahKUV~V z660_;1#v5nlw0Kn|1}n&H`?$~*6|F=KxXVAZGuBI=3smpMG*G22D@Mn<0n5T=LhB> z4uiF5XF&;qa5!oOU`|3iy+<4}v;^A#5BCBwkfRUmRS!1wL*>L5%S2!+corL|5A4@? zap!(+q#JR>3DYxKTH!L006yacNCg!Lv!G&Fmrxgme2l<r)OQZ`P=!~hNK*y?T~t^b zHW=LS2h)HJ=0;Jy;SCBl9v66o?y(~J0A%=sTKY30??6{qp%Lx?0GpJ6t?>@fP$3uM zc-;^WsbCEQq*vk46EvX|H)TM<qDkx#H<~aWlQ(1Hk_~9^R3Ska^*{}1&_(*yM3mqM z=ny;YS9<!;{{@_fX)lN+LXZvekPhqzU>(<IIXHXeqz`nk3yNVGq%kFxmJbR8T_N^+ zsijcC!9Yd`0K20bdqgM_1|soL4$%QcV|YG7Hz{4XGvX5u>X3BVHyW)WYfWenic$~X z@EYM54&0DWXjq3b(p#Fqe^e5FgXd&YK^42QA?!d4&gC{v=M^!L50zvftCbH_V-tQt zM3-R{?=V}uQV~}H4;wL&?Uxnd(1(79d$=QvyKn{oKwxNgU-<=Bm)Au?$cteSi!p}| z?6)4LLkDAG7ajC1M6wN{C?%pXJ3`<Mu2&jIggVUl6(KPW<FGW(xJxY2687+7c=T%i zv`2l!{~Q&eD0tE<)aVi}lYEvE8hJuS>Ifg8K|<yLVNKB-F!CFAkPmMXj@2g*doml~ zn2$4}cw%-AcB3&YQ5rm<4>WOr`q2y!VM@4XEDot`;UH%3FhD;97Cx4TC$*90P)dY& z8VA%2BXn~{WM5~n3+6&|3c+uYGdaYRnu1Xl03bRyStfLNHcH7&WO8}>5_;rdnUa<{ zEO>h5;G2UPX!USs26v330T-3Vll0(NvZ)UGK%JmvJr~xOp`jXsvK*M=71!7@h0=8P zpeXu~dB)k45(NN}z=Z`xm>^;g(2)#N=bh=<G47N|*m)2~$2^D<jy7{LqL!WSu_2EH z|5H+SnHJFv@8At|1Bm*d3GP5#+D1es;z_AcHy!a5QeluP<v%@!Hu~Ug6TuLCr&4z4 zNX-B(?#E`^a0Z4^8SuGhW+ewTG<*MIMxwI~`UPP5z*Nh4FPd?J<l=u@5sSR17$4Fl zF$i+$FdC$(4`@(DyC`pi$tVJ&2wZRr`5+vg=zcY(bJ<gu6q#$EQfy2JNaZ<BMY?^u zu^L=iG>PI1Z%_}e(SBut9Z=XG;kBPPQ<ouCefc1!9w?Oq8X)G-T7el;?O_z=un~2m z4-ZINC8;6{YC#yJTOrz+t@NZpaX<`s6xH?)+`?rPx|SE2W1%!-^1v_v@D23<{}N3i z4)JhjLrGQHg$_sHO&|$!3<IRAQx;t$2))UskHdm7XK*4Rq=FC*J;$q$5v9cda_Kce zh!d21uncUl2grjw*$JkIB#*=qKS|hqBa^1SK$qhbVvco<K~qn@ag~5J8a**7<$#5t zp&i2E6}$5i3sp}8${wpVH=}A(#X1^*(+rW956<9Gsw#K%rV;IsTP^`W(*}2iX%YL; zAB6J`_OKCwNvReYH;7uQ$kr1=s16?zi<}`}C{lZb;EFRj8cUU%L7Jme0BHv67(Plb zyBe%_B?#hBoJk2JXuu1>`7LFkaJ6G7_P~l#Qj6Y7O>1Nh4iZILHz{RU|DPtq2_%>@ zSF4qS@~(*zukEK0HlwEy^%Sl`VJe26<Ek3BF?Im!9#I2i)Y(&o8X)d43@4>Fl<AqJ zaa2CRfc|lJM<J02h_ObY3HG2WHYJ+_LS2e$8d#wXx*~Zurw`sBihkk}K(bBU<hA8g z4}w4lhqF3<gJv+d40b_RKf5C|*nX!YCO(^^eerhPN*ZNV3}SM7+C~pRGC3-l4&G1? zQH2gRvWK|?aW%%O`D&L)_%V@i31(EEDuD;@^j~4|JbW~^b|f6~`W4UPuJpw-DF#?s zXr^cfBDP7lTu~MPlv0w{Q}3}_`tS<;p$yYyO6|d1pgJx_frnKS|FXOlH;7o5)fTA@ zD`S4ip|UA89bsVPg_3_!i!27ZNi>3TW^h<yx>-ep?FX$=nh%2olRDZX?KfTwV-_~6 zFP1=Zx;q-YD_}pk6>Mb%+h8xMvv5;@JiCLSdqp@Yc1HT?74g`PO_wLx3tH5uzW;Oy zbA(G~ksa@JY<{B<;MqskwMFKTguOs0={v6f1Pdbgz5&a2ffISU6eC7)4(k97w9vop zQ4l8jZ3_H=WVWcLA&K~_D<;wr$098La~koc36z-+^}AOxG`z(`RZU_KwUc{rRT<~N zq*VH>aM1<$RS$8Qv7-}dexsDNYqQ9M1Lwe_UqQq2KwzZ;|Fk056u~PGdO!)xq>#+J z9{SLMO(8*jWg83Tz6cR()1VGpYf&Za#A6H&?Ad`#a~AHD4+gWmZJK^!D-UX$#k*03 z;2^_UI2)h>3#KIx3Q@oSyDf<u#HFDSIx`NhAT?e}8X0S4p(<{)fT`(xsweVDlRJp^ z(?1d{xPP*s(C`fXqsUpb9xyl=mGL185xhZE7IbAqP9g-U^LiP@l7esv(`qFsM?>?K z%$Fe$y%ck60jxw9yM>0)!5NdwU~m$otoe`@`(zM3L~!L0qoyh`E753q(lPNfVOz;` zM%)#$QCP+7%R%#e+{=BHFf#i#eoUOQY{{-46Fv5d|IJ=Z8(}9t(dj1GaE~f{##$Dk zCekWR)*dzX5hY<{Pp8upbP;M}4b5>8`S1$bFu7SF)&dIvIVKJrAs@6*A7>&J1`0s> zRuS$tFJ;KfkJ2QP;|G^kV-Ia!H@R|Ntq|pq4*9SQU7(Vy^BARjx|S1`(3Uy&MZ!Jg zUpcxX@&K#TY^-}Bgny=KqM0qPx-Yy_7Wm9*ETMCAKm$2o3|%N2kn%<VKt^In)Z1qe zMm-Hb^eM@32h;I$bM`Gp16jPrG`L|0%8h&2%?Xd-PrSi&(b0xQgx*+Fm*4P~XUxal zP(N}UNv9%!XM#Tnl%X*J4-q;)DRUb1HVzx{|2G_(u-j%DnI@?K#Klv2JxryNMQVe6 zX2Fi4Rh4EIm|Plmkq^BK0FL|^`S8KbB-XujdM4e`clFUSOOs9lbGraLAO;^~$Y$9v z1>)Cbg|jB0!U_2>4R~M;N>iUXrw{4)d>Lgh$#)K|Q4pSH2h`1%73mT9^xX1bjUOZ3 z+2=P}*L~c9bzjNNA<Z-3P!4!t4EX5YM5KSO&<uIaa+}r^%|aDcVInf&h;4%*d;JvM zmayZXN>no}<*XAcQV$Ut6NQQ<`JxXf8<vhDakLX9uepr+urKDoUsNr3G%R}<2N`%J z;+TVRX$A?=Ob?$9;-h`h33?EfCk}kt|J6I;Ch|iNvP{byht^MHjTK`Dn=2_%j68%B ze3HTm-%#ZJRMYDj2=&q$-+X=P;BzbS-Ob@WZ(t1X(i{|qrrP(!%ghMZ3{fOBLSK2s zB36A~WUo(t=0(vB^^mCZJ(>zS4q~Rq`Y|8kaIt7?A`f&FlleDqy_S6asOe5fw`@Wx zF$K%uIb>SXEVu-;xSJr}oA9j4215;Bz$JfH8TD`m)X=1Qm0inl2AgZ~Z~<0_qvEJE zUI2g$V(^?rSkpiv;g0+?g7I?s>e^t94TNJSaAe-YuFCqLr|zj6<q$GhzS7N|5ABHE zy$}dQFBXXv-p<z@0-<xIWm#T^{~dc$Ddv9e)3S+t-hW`OQ5QK|7r~((B~)UqA>lv| zj%X;s!Z!e2xAwqa^RdRYo<(-G40M3gA*>a#C<nz@i=dZP-8{oiVh?Dr3tUnVl_3s7 z&`lV=y9PsXmu4l#YkN+L_U6LbUGSWu1td(=Rp}rO@(^>jnmald4S29%FNgK$P;&#J zDE82ua|RYpnmy9QujtT?zVMCMe#8J!Skff*Ul<)K=8j;29fj2rgtHe+T=iWs?tGG; zhW@1rI<Q?_+HOukasy-!N>f9@+xaXXhtOu4Kn??R88Xs`(AmI@baFv*2Eh0qPRAHJ z6DFej+N`<;YQcWN3=jYW|Jt)hkDfSvXm$Z0r_bEHdE$haLzgZcL3#27ZsfSpoH>K~ ziha@NZQjRu<no<arf*)ljxjqD6qqvMvU=(0afGOE*%_DVK61>LZ(Ke~e)Ne`C)4Ru zr~rxrh{p|2GH&wh#mhI%4!5iuG3qn+W@*Nv8J!lzC=c5kY~V7+iwEvcFK%?xYK*$K z9DqQP^qrep_YWs<dh@C6yI5X1eQ%8ElgHNHIlzMd0$?0-Dgb+K-+&9-IqGTDsa3}$ zNHAPJcFOe8``C8%ZQNo3e0-O$nKpgj-r3XSu3NXZrdNjxH{9PpW$oUD%h=jp?v35P zjnm{!Ubu~Wv8SfV|5=_*I=kqRqYXMVU+WEbt;r|OU`Bo0j>t3kQTbDX3_=KvWy}%k zA(ezUM;?nZ`j54O=+OrmH1dH6rFj4lqCShrYYioD^jSj{2I;XbC8YF_$0X1M$_OQT zs6hiAkaijms-lXDhb*(Q+A5y6u;J!CzU0wonl}LW#=7#>%7-p)?wBU4jLxYi5X2OF zup__pi6oGG2wUu&ast6ivDEegC$eb>%JIp3@bCqk%~X>INpP^a?nXZQl*zho^wCC} zeBP;zNWT2^ld*90X$P8c=y~TITHN^tIYe<I=%ae*splGJ^yvmXvGyFV8vvTQ#vGy? z+fvaNADYJ=|0}jRZ`Su*)T%X|wn1YXbncVK9DR<kk2Z5&ohd?u<gkPxhtSc-5<k!p zr=EIN3-F+P6mkheahCW-oDOdTvD;$c(dkeCys2jiYV667qgVyf=Zk0nP^X^H6cy+* zaO`1(5q*wYtSUxeDF>~5KEf;#M%0n3GRJUy639D*bdW4Nz?s;x)4Kd}u(S;GB`>b> zNz<`%@(E0zlrsXyny=uYIJI~H;Kt0v{Pp=p*P4@umUil)&Ov2=UM<mZ+|eYTZ}f3S z8F7xYjnAUG$wyS{e3n|7aI$evY1O8c!=7vF!N@$02udf!DT>htTYA#bCn<wWG*va4 zeEI@_|6>snL=b(*X%e+<2izqea!^X}8vr0mdf9a5(MJ_J3O{fo_Rf&XDVprwg$~B) zNz~`^NVB8Olyl~WlSj&lXIOIxA`A~s^jUZ#Wp%`O%Grta#SWu}Vq3Mp7zqUCwDcKX zA1eDrO=d5_#Oz{jjJYGRltaE4oJbyld9|F$M%|uKC+*H^d!#piJe39NrXE?Iu~`;p zz6(d4_H(?kI(VF8PhH~^bK>ESN{tFM?t9-yJ|Znj2m&4C(8`-2WRo@UA|L#lhd1)! z2T0U|J#LDhhuE`>zmY2);>d>}C?Sr<nS+5&`G|lLvI~9KEj0Srg&dXwfNYtoM)IJ> z{}Bp@D}wyR5^?~XZp1R1h}1&}+ki;J&W9~G5d#l-p;$(^0gg9JgEFQ%hdy3b4twb1 za8RKOIAEua*;QtE>iEl>N;o~T;GrB;O5+^IQJy<SB_k~xnV6t7jXR)hhBARt!v1nP zsLY}q=z!$=Zp0j^$>JUCo17(~(iyE?LmB3HhbGPe5C1r*PXs(4bKW73RJ5ZUnDV4d zK7x=bAcHbUV+>;gB)T({&L$ufq3J4_nt9{{g@Ch&;9h9BTp^BG`jEpe<dqS@5zZUt zIp$MpNRNC(V+tjiM|JFh4gf?Dh5*8*KKww5f$U9DQ#lIHD47-jK*kQns8~_p|6#`5 z1#C~f!yYFX0gu_W&lhI-Mkl%SJt<MiNW&|~!isd8H5Ia=Z8Ru2&e6TbPz3<V*y5JT zhdY5pf+~xw<!M}_HCX_Med1{;b`<yyL-<A(0GLiVlG9C>GKqxoT%!>G85>p|%AwdH z;YT1d1!~OAoVp@vgz`a*HI$@o4FO@{Y~;}LsALxvQsGjLu#Nr{orgcv{{zQA+;PLW zGqT6oBMQluv(G*wE1L>Q;%o|sv)v(C>5ObTq!6;VY!S-Jt}jv{<=5|D_<Y`v_k2B{ zFUoERww_TXE0H!7Y|4+n%wwxzRT5B4#rdQ2iB&1h%}_AO$$pZ6-pIUJ2Ay+OX&~4% zQ|11Jf#u?OlGN_}d_q%yx%6h}`u@zSh~5S$wKjJtf5ZGqior~1@2w0yEj-tVXD@rm z;6N|f0&#&Z@ClN-&A=t{{bP>poFqVosBOE7`o5|tYkBxW>f=MkgL7O<%juvJKxXhn z<9Sc_xv=H=T#=|ByoawgR(FGxl?UBpLA4vNkG@y8O}cX%*(PZwdCSI(YInSoBQEzo z1h;*g(!O2<fj^~Yx*HG5%e*|Un137gL-1?kh1(w1#orn==U!<pAYfCdSo-&Nudnkk z;a2_Al(fk{4T`kq{<c4>>PhkK_G91bZDwJ~<txE#G$yI{9iAps#mNxNJy0bUX@0Q} zgUmv~Vw<Zffw7Z3s6SV{bJiKHfEAv~CBG*_i>Zft_pRo38lKWn7Y3Ae^PZt*gDo>m z)q5{`xOZ|27}{w_3D6?GOVL9iD)Z7e2kAsF7_wy_W-|G4+48VY4X{pldv-MGp?}); ztXWwg-)eRvcAF-jr)-&GHjq;{e#fh9SfyS6QX&1|u)miv7n6VZ`leILlswxt#>hbl z7kNj{tPllNhduk$B`cF53dtU_0OAgz#5?$AG99=ihMsy_xPL~cZ_LpE1<=@xI?FrX z?I3dXlMpq@B>8JEH?h%hNLlm#I&Pqp`v`j}B!X+~XxK>PAcnA!q2NXR1RtYz?D}!I z;B&kOMaL+Yx@8#lkG(L-mDo2>N<&Jx`<@8tMw3yyct53)P$zQ({Tm^g&+mUyRJ?dj zHL`1(Jf4o0D8?yEE8XdW`s}}UtE#W_sBqL<N@QE^`^zWx_g@#77Hx1V_t~)Nt-b9p z?jd@sO{g!2sSznscOoP{^Wemgt*D)PE-J-^x!Uy4+dbH!n2@%>S+0C9-OEcpZx_G* zptm0c-MpENjQc57Gwotz|6O(%zpmNU`o_eGPe)sJhFef8q<{xk_cm}&sMu{D&y%f9 zs0Xg<(BEE%{@9TRR%oJb==Y&4qS<w#_O9Z*>j$|KmG3%6d=%Kr9v*bhREbR{cy-qA zep=twybC#2K7CXx70<k1D2(tjSuSQA!_3es42=)g@cic4xU+PU5GJ+o&3*AARe6Pk zxJ_}FX)|tn>K^xMqAmQK=QSi?BN`q2>bG}xFPoP5DsA`y<4yaHs;R5GERb+N0sj^f z*P0||LhS(=f}BztzNZ4z6S$7ZOb=lrvXJp<ZrVi_NEj5br9Csu56u-!4N<Dt)(CC@ z<7|mP1DK^R6Eu`K<BQrQ8r2taljWjmzSX0-M#ZASGB#TAUGuHTW8Q;Ma8&}qA6;Lt z_~g$$`n1;eM8U#`$ZidR4551b193>xN2o6*UX=`KU3qrZpQ%!&A;gHkpqQ|}(tS!- z=NSD?wLtS~0E0yg!L~I^lKxFV-esc%f;12MwPZqUCO2EvE1u%2rHf9sNOHUc6rBkO zm@dkUSi<78nM}S{p-VM54xji`K*N-hM5+*&SokR#e<s<^E%EQt2XxPmJ~H8XQAM%` zG*%+^27r>2u6&!l3VvA)cRm66H<v%V#aWfmEgi$`jMjR#C?mS@Iv@k$(32rk)H97% z_#{BDw-UP%mZCxhBuGH;x$mCF5Q4}wArvm^8f{e%ji0x4L!~a+z^~qxffFiT%vGdE zbW%Nxf-scmLx-;RuhT?MKqjZvJj`3BWfCI9Y2_;*51Mr_N|2wnvP&n8^hty)Vke}a z?Vm`DDFTYfz+>~(*pkRFINxhLF?Eo5b&xi^GdnaaWA?&=P?21o!a)c-P(DWsPYr6i zj<$Z0?N^0rsHc=`oJqUu^t(8udPl_GS4*-Cpijt3OzEuO%YnaX#(OkFKi0pSogzdf z4oC_?t4VS9ke7@lRIiojJGJW1dJY)W>wkyAIF%u;4=YCYB*RbQg(#3`+bjk=uw-F~ zKN93}s<uQXczldgQd0Zbsq<6(Z2$>$Gl9_4mbmb*DZ~@{{@B=dBXc|^=VR4Cs%Nfc zWA5xQBt$%&Azy0mp^zR1a=VRbkeE`QtS7&uQkBB*tE3>C0U<BS`o_Y2F*${&^v-~w zyc{AA4e=vNr4p~3H89#(G(MboXIwv$MwV^8aCm=skIrg{V3j~y!kG}E&19I+sC<k2 zwgA+CwLC6G4eP^Tl1Tg&26=!Y_#k6!O3e})$HQ`ZC2X03$^SPa{&{sd`Xph}7!AFR zcnCx_c4rTn)4i4WS6B!8G^w3Of%py*J{NQ3aS2DRfYrn~ge2&S_5}HV(+}oI|Ff9- zBaM8~;$M&HvlHpv(WYTg{cnlV35&^c%!YmmEY2JXN54z2RMFkj5sU6j>BQzv5cwie zw7@}yg>2)IXO=#Upe=9qR%)E-l3CphRK^`*_is(moId>5JF5)xJ{W~tF?6Wm?@vHf zpiMm+EL2ochVG-Mg6-1|42e1dOcx*3)W!scd(y@$Ab%#*o?zn|IcHR~wE;B9n`ms^ znmV%@KYQ5TPL>@+^>>|!`IZQAx%USoFyB*}<fbPnY?uh>zQ;A=ubODjuuj#k#Cx`J zEQ#lCwt*KOrjI4Or?R3;ZGOKpGJA+GIL1S)xU?0TR9e)=)h8jrm^hQL)L#+^R;HMT z&}@Sj8qqQd8aJW9fo0p8nZ>g*LnD~~Jkfp9XofiGz8%wdOiO*UsFq&s(L(%HaxpZ; zOt~@B(N*BCX1mp{SqhO&TE#;8SryF@{DBO?#q#~Mg!Dd%*}t<k^ORlDhn|f$r;9?j zT%41Um3W23q9m#PZ;Y>Av@!VR{HwI0EfttkZO&<TQSKb%z5K_#K_dOJ;XD87n){LV z4T&!T=HJ?TCx}q<{O*2pg%uizC43-fM<A*1gkeIp7$7Vp$BCEFDgwQ<hKWaZgf0HI z%jg3R+Z>s~zqqd8DM=s-9D;7oS$-FWedX^7KT+n$caP;uty!OBl4CNG9=T5ZVgo(o z^$h_%0FtY7E_w5svfaLUxds1ptV5W=f<2Bizm|}$Wq%}iC7eh<Oosa@>G@GO`vOSn z1`GeW8Oa1dw23{T+By}ypNza2BUzucg!8lG1jdAz14oMDx2bu^;7D=#UXNSB#ZJKd zt=_jx-2T~F9FWKh-S)jmnXm-3KnQ_8E)mq8mH^B~%qPbD5Vh7MyrIwzo~3vDE%1$9 zceYKjl3rGDi!~yus8%@5MZy<jId!P%;wNWq)FFN{Q#4eZ=2q3?aG{T*(!jyw$&Sb< zS?0~UV`Ovuok7S?^DAqPt6|FtWs~5hdyX%d+9Kw$O_gf&^2pN!TJu{k=0afJ<d^$n z0xjI>1_5kCrL?jqMdJ5eONEroir7+Z)xC-*kR<#qC|i@nt^W*Oc)2M2h1E|>(7VyZ zMu_)Zvr0MrQ@`*Bj|(Z(SX*1Poke2_5q^_rSV{Hs<g4a{fxe`7y7qf36QfbN<!|A> z6O`4xgrf`dk*_uHe6f&XPJ-;TJzIyzERY_8jmL7<_@*X)Z>14s&c4oQ+2erOJ9>Iv zML;<XcDW{41SS1#gv5!%H36O;FT?Z@=;>5rONLroJ36g1JAzD`5du@8nc`J;yfI}j zr=apov(zJn@LK%#$QOkWO2156AIT(sA#zfB-@z+MY*2<)jf1fCJ-#UHb#-;27!#kW zcwN<R`bY|GG`Y0y&qmlXtA6xq$>1gBevfFU>C}oXD-7$;U6v6J6D-Sh@zgI=TIGAt zZH#tem%8RjdqU#-MfH3(4Nraz@z|bg!+&dFJqGDv#Knai&!jrZ`id_-G^$ZrMsnQi zCl_6`J|}pu1cKi&ts!$2`H0sCT^gEDANR`T{tka`e*D60w=M78H#80P;HVTYrc$;$ z-^uGT538rub<ju8Qxjx|@@_ctnZ_h=1=&Kb1%8b7-NVaY((r*ClrAj|UL9eIX_h2_ zCT-t>*s-(eQ$>3^qc1t^Vrn^g`px^_Ji`*9Bv?U$CPP(-e^=AjPmA+(zT53tu)gAx zcyh$lk{0J4^iJlvz5`teN6G8zpU9C*BZ8^1GOktXLw9HL;vaGphMmy9=G*7FLtnT| zvb;RFcs+eIo`VEOEdSv|b3v|8%lx8vyh;0JBJg6J!KsT)aAZf|ReeHYt#<4vMCAe- z_kINOEa6Le4#b)bR7JdXWP0bU>FI;*Xa!>aU_YbvjV|3Ee7ORZULh@gwjD=N^m+-g zVa+#N#nUaWOpa%;tlauK($A-gp$!YcZ=c_Kc;{;$#Z=;yR*BYob_LVCLW^qvRf=a! zYfd0%3$Ka3&G(Y{bbG*xIK48vwQXvd8nVjad+qV$tzBI;E-~)>mC*p1;<FAWkOMU^ zPfINV;rq_Q^@)au3o_-T{9f4EZyj#C{d(3>uiTGsB^)&SbuQ;SGgk=M%*5sPW(_)l zFq5YGy|Aej!vS*AST#uvV1ZuKY;rFkNT<Vblq8Rnc)h|a%-J+Q)=L}e4$CiQA*Oe( zHFU8hc{aaWvW}S`czWX1D`G<qSamgJu)O{~Jl8c^QsP+2ijdnR=%jLqp7-wn`x;)) z+WH6?TB)L1|K7B^WzyBx_=3fD_r5}>6MPuvtMuj_@f{j93V|cQ=|;<Y4RI-F0Nk-a zig4AwDwG|Bp$Q+f{$-7ernM=wAV07Cw>7Hz6Y<gTO+4Q`-fjN){M%rbRa^j)x~DBr zS6K`v^ThIj4GW17Tbu9vnY3U(R+^hMAVTfl{65L8)Ag<H_@`fl3`gH<w2FVl<N6ET zd4im`f2LKm|5shhJ(@g=sl)vqT34Ue`4v=QqOsH-99qvqo#@=&@~!D&pFch&ny(_= zG&-d4fP8FAt2|+O`O<g_*+;|k=?C|YT}`9I#f&2tj88>Xc1Ndc$sN(v%{%*X=$zX7 z>4dtQtmA32YB?z?1n+175{NnsJGlAHjv>qc-G4xos~=(K@53i=Mto%mLD0#=qo?LG zHiN8YK1?WOGPsB5>_#Yeqzg>bc4!9wv9+EcG9OQWOG`;ksLSuQ>6u|pZdivG_oYo1 z<~;mWPC|iZK(2KCU_vZ=d*OyDLo6|6Aum7YOF}{JpXIoXf4{W3=FeLjoZdKpReJ~+ zCxAnT;vS^l_q_GI9%e|6HU6O16m1`C#FQ$I>3Af5m0C!>X!7&Ln|l8QFsL(W`f=pu z2tgV3XG{L^3?S{h7ZDbi6t@NC*8KBVjj_O=V3IV_aPcS#K>4A%VrUV9#ua|6oqnqu z?Ikp5XC>h0hHKWq1X(?NcXx+H@iupRD6cGBr{$r@Nb2eP1(tc)J0p1By;%^kRzKhE zV0&`UHbC4Qe+=H;)2iiDf1*VfH2T!csV$<N`eCw7U{!yy)4SJMa5V30^fU#=N@wk@ z7TG~Byq>M_*(T-7(P_8)U9RO^dCsYJ5WqK|ch<2}(r5Zv71)#ul9mdU`!ei2mK%OI z{h1uFY^o<}m|k#0gE&e8K^Elp=D^W%Hz;&`%B^*F>ldu$=^3biPgf)(44>rl-mAL) zx4pJtbsDEMd-Kk%E6k~l0q?ReLr{fiwWaq|gLTODY5$#lTZbEp4vLZc9y@z;PW+K) zX0z+#@6J2g{63FLtfwf;*=6x)|6I6+P+#MTW>i5h+mIh|PZF|j0A#DraXMb&bILP= zneWY6?klZgd3j%qbG_NV#)$c$ep4XvXv2M!`!s5LGVW1svjf30l_fVt*9!`y9eD(= z5}g->Y?PGa?;vBeKb933as;xxSBh`ePLGiM!BLh|JG9Oy{cQvM5!>?QjzKapTDh!% zde+@ceS<^kuF=kRBLmmsD1KGTqN~IVMcNK<C<wb~Wm~;}sMI=V1!im}S)ReJGe*98 zWr<MBdBG}DQj%dv)MGERuvP!GT{6sd6mktwP@JtIpwjd@meXrcij=PYULcn9=8CO5 zMB#8^@KW7KL#*Y!l@|j<L$`%%g22`U+&bu>bJ|JgYnza>)v#NRbmNx2-X~qINbRR? zfahtN(#QM4X-cKi0rBeFrI~51HhD&puWEHUBpP|gv>Abz?dS<*#9j7r<uf&A18coA z6_!@9sos)U@M7-tfHaj9i-}0pZKC}y`YuvM!cz3J>PxGhw8v0;olpI$TLfmu&F1M` z8`j1{(;GVu!akj9x3a~iK?Z?LB6n>YnS@d<Hmr`ORk_vdKF~$0Oh}zA!N1#3q`Dd9 z|JL+uDXz}<%+?h7I=->lWjr=nl4{o?N)nGL1FC0jw&c0wkB&2)pzl%zYTrXF#}(9% z{pf@vZ6vV5K{9fw))r&Wnzyx;pDcZ#@e=t^bm|kQWd7K1*EGV;UvXlp?!(66PRR#e z2x_MDTDk$(_xBZQB8IPj>+v!SN@}IivnE`{Njs_;x!&Su`>}FtA+|mHGRsW&VCtUv z%-KAr!&0vM10*hYpfcj;+3lUFU&rV11vj4LwOv1YGSuUxE_cg3MiD{cgt@aP!b(S@ zJ1)l3wQ`ePzLjd#4Yh&zq<V(Dk#dZ9@r(OH=OBPuqFD+Doxp$gGj5RqaivQe@c>X( zt<fj7`yL)BAt{W<l%_W3eB55=p><2r8hcrVJAwMtC8U{J@*r16&D_CYr<<j<_?(XK z2Vh}1p~(@VBg$0aH-Ls-%U)uLO|;x_yc7!UvsgC70z_AahhphUWpR?A1zIrG#LFiY z4@GuSe3>eGEKSXRj`P*Lz{HW>r)c-oDds16-$W7Y7Nr8ToX^oKMGVmxe5{k~1X$$s z)nghg|C~Q+T4hR(_q~ijbLKkzqz&?(2{sWTAtJqFh1{AMBBnBv^+azEyUSJc;v)3; zVN)Dl@|gn56C!fSZx{+;F_{-Mp(22x1&as0PQs)l21c`%%485jqLzq8GB*gI#D#gA z4T~g3G{?O^#fy$jY@$nD^X~<LfJ!b*xP3$VBVokz6iH3`k1h=1`(3o41>I}uC}hZ{ z7&llmnZJV>M6u0E;x_M77I#I)naE~bmT-m=i?Nmp?x+e1r<Tt;0}#s$I0`1|Fx$TI zG@TTJF)ejRs3^q<lTqT=w`_(bkp3uQ$_A$DzLab+nWvZgHI-x>FcDv}^eR4g{f=f$ z5-~haoajs%F|;bT(93dX)WKHTU^-#1^<L^IL#Y_HH)ft1#@B$D_Ek2t2Pj(i#T{ry zoF#<l!q4%s$xRoZ__-A(qkGp2Xq3emnA~7M8%SD8fL7bW!*r55s&oe9&1t8_5(qC1 znzL9}R-r(ynNl%$M@mvNapZyb-QL7%R^JPOWxqTX6wnC)E0j@1q37Kh;~su9+?28F zob$+r!M6LiU!?54j%5?EfXG*MnOQmo$bdL=)UOC2<zHRnZv=|b+b34*S4!)zTuM-T znqV6{Q4(|*0=XXUwel6(%gp79zu~P&k&yA={C8B)^!+!b=GDuB1zg6x^<xqzW-l*w zRih)iU;qb5AcbRI=@SujAgS}>JQEVOww=7}W~02kR=1reV7deV92d3(^f19u;T07G zA^=XgU~&7Lnj++X*%j2_wwNKn0Un|8>QQ#7Mq<c#F3{<=4(${^WKGt1LNG@6K>PzM zOI)uAABGV)papgAp|1Qq!U{$sHMW}dKQ_l}l?pWQKON>Yxj~9&f=9int*<XypaFua zbH}O4CH14vrVEmsW9X&$?(E<3ICx8+q7{M?K>|Qf(ds>_PUeG&T}vD4@ri<kk!N2? zr0_`#ys-8Q3Tl|Af-b5JSN>A>pL*TL-Q(pxg&mLyBF|2fqI|_Oy=152;04daI2L$V z9B_|ly4PcBkh!;np$lpDNSZ)v&H7RS3cWV!FSEx7h`<1qfixnl?Z_&#cG;OP=)%NK z%$RrWWJu{qlaZaF*Xx<IfqG}-J)K`>##7H|aqo?UldNK&EK)%fwS19!A?u`XDMRLh zFvjlLZws?`7)CZUb37cueE&5Y+51}{vKQQET&E!G*`Rd7*wU~+JwZuwiit4FbZ6~A z!Dv4pk=?YxeZfakH`E!7li}44Z6&I?$1t+1K)u&kFiPZr)q>^<-4v--`iFw=7AMFr zmr%YZW!=GesJayOzdiLQO++QKkmnQX^6QLGTsfq>+DZa$9#QUsf@~YpPQQQ48hMPQ z7>M%=CK~{BC090G`+0IS2H751l>f<a`T|L0X5!th_(Ao>3L?S(1vGfNZN|#U(;@kX zQ>5u#c5J7c%R|>Nt?dw&_Jh5m*0)bQ(slRvS>$MbtI$8_ab0xPPy%ed_l@-bY#|tU z1Zc?>9qE66^=SM(HE2BFd+<0K3<d;F!89HK07%gS2mnVdNew_R04gXChC=SbLs=vp z1}Q~71f-B*0jA!qo0CnXZg8-^WFQ@-oy23%P&$+;Zdv6p)F9HU31EG2290H7`APx1 zOGAz2;|UqS0mna7T#E@vW1#;SL#B(BfO7pYXsVj6wr%uYHf-|hx)c%f@4L8NiZTG4 zkg-h@Ea_ZA*k-i(0j+rx5JQdjegS=Q*`yiHXWUF#?MX0m<Jk6EDQmy7E5&6+@a(Bb zW%>l5txSzeX@a8+j9XvrOjlU07s!TA3P$JSwU`rPDi+wK(Ci)petpI<FQ+97YHY~P zvxAwJo!>{a*xvwR#^=>8z2><V0=bfL4PV#2E4$-+acug!<@EdZboJKG6BoJ>YD@XZ zVNT$`7;#%2ldg-EKRIC1n@>?-HqVu4uKELK<I64{`~bJ>jFuIs=@-iGh$?{;0}a|< zC7|L%1maj*R;USrWff~lQi6)zmRFfCmC#+A!>p&uQb(<)6?{E$OGeX5Y!JnlS6uY; zM3t8_;P>^Amvr<bzGPV?;dHfbp|ZX_q1Lqf^3)|>Vl&4h+iNq|v#fG6&*$~dX1-s) z#8v@r&TH#g$Y$kMVZ_g!t>;m+lH251Ht+4C1ktMP;uMA5?GmD%<W6apwfD}8oI6!J zWd%XIJLTkf$=!<5Z13I5in6NRs+!lkyVaEb3(372Q3EUz{A#o6o~DDi0FhDd-v9w_ z46gK``}i(n8wR-+YZ`i0-qyUD)Ee1;HD?iiziB)ux%SP{qszX{8@~7IUT@zC_o)Z( zQ1;#mYex5>JvdnPIDn=6s~u-QNB(>Fn|A+YCxGzr>w>b>9CXo%jUMzc>M!~AxX!2| zJ0wG+ADWu$P(3KLbrGOpH_38{MLS^fjzUGWsdNYU_jdX&xy<+kjCrlpT;ovw-WD*9 zzL0t~t^;vAp3oCZef1s?kCdM@(yqn5xBBhyW7hg^>W?}5;ISVcoCpj*=iTl`28;n1 z0o~CEHrbv<zjw78OGZ=ogO@`-*9L!z`0wIt@aL${yeBJ<*-cMY<HgcW*5WRo{$y13 zq(Tq+Oz#|B%J`4mwOJ7S?R1MwxN^2#`qcMqr=q;>Y`5mkx3j$$ENCIXCCef7Sq=yb z-f#Q$P4zz-Ph`Xa_}usWaInYJeN4o1^~+bkO<&!knYWCc+aJDv1E`jQ|BL*wLNNQ2 zUZQEXb;)V_%HOk>cM;)K%j|&0udc=i7k{eWHS3;kj)e9-dE4_GSca%jx7Gn5j0^Ra zn8vvBN&o^!2E;<t{v5tUnH|_(ObDyPKaEEff&_NsDJ=pySdjL?Ct$aniqW%^L2QW! z;)2n7&p;K=H@dp_=oJlvX&TDmBRTh?jo1O~$`AzQ9r<yZ-MSub%sCS@h_w%Bh66J4 z*@3P=2&LtQM=?u=U(e>!M4~A`M(7(0?LLyHjow&i0!}nVjs$wIIi?wTgPoZb-{?<{ zQCPYvT>pp`MSrU$2Kb^&XwR@v);n%sA-^7BJu;P+y(~-UXzBK`BCW7hahgwS!A4oR z!N!mJ^dff;UOCxVCf1i3+By7G)`Q)$KdDl+JB1NT2ZQga$fOtao14e%`apyQ>SaZ* z2(26&HeMp3TmBQD`DqKMLIxyf$>Fe0%!qo%0u(U_mI>JDyJ72}lDXn0Z#1MQtQ24p zZ1q{CPk-#aYa>G2wpj3b=Y`>almF!>zw!`$FK+N&*1xbTc7x-JEmBx%?U~!KqdJpe zt7X}H8t463+0w}oL-+$|T#hr?XkJ&#Ei<5<r(0PfPyf%0Xq2B1<|<01bcvJnqNcH8 zx7m|cG!4j?SSpY|TcK6-dzqYS<;4$=GT~clAPEiX@CVsx7wjT4et+*0$=*TMP03@J zo4k)i&y@KJ0+{>g3T0i2=xjPHK!EuA4Jsn6lJQ!JGwa^X=iL(tm~YjW8!DY_6iph^ zt~}z3(gg~k8dFp_idXE0CuK#BpoXAaW`2Q2{Z{Sa%LbSxqOMXS0k_z!Mz<&X2w5Z1 zEiX+vG3~EAY9lJW7tHuqR1<N+4&t|x3>A!O?tgVonO-zba)Flg-Is$4#H_uaj>!T= zeUG^%vK2VdLi(b4)z8S@(Ri(XK6M|;#^t!1WB@mvaAC48E68a1)&4CIGu%vUkc0Mi z+$MJM`gS=^*_W^nbYEo|MuV>)o9V#{GE7NP&cOVKE|BZXXbbDuA7x{0-eF(;3kFsh z!*hCIp|uH3onX<B=w8vkntUgVp8<!pOB(akESMUa(e@M=r|?5o&y+Qmaob)^dF<eD z^6GHl{vgKmh{S&6`XOGkPfAppT5W|&cm~9V=`3Koat|rl_H$rbx*=!0WJB(1uAnXU zFbH&j2T)NLJd>#Y%Lyci@MyJwD_>*bnEU39-$+5P_dS=Xi3|^jKQH;AqhQ8Sv10qD zlYCqarD7&t!^;Z-e7~u9Y7Xi3kBi5|68aHtDPZwGoKqD}>Cc}=>?WvjG9FdLLRLE6 z?sW=`q?tC=!CrX_-x414s{lhyU8wJ&P=H5sAL4K8-ktLD4;^(-W}=L@OwI}u0o{4I zP4=si>hHzT=%8w$qgXHJRai+7MBT|e-WUISc{uTPuBuj?gR|ze2GCW}Qj-yS^XxN# zXzqlV9>j2;uRzV3yV*MqhC;bNz2K}*(AA>xeh$!MFwPt&42NmY`ynVoHb&3UIGtq! zB6?xgGHmnyDEsaC7n$^y(YvPK^A^uHmBw4%2fzPb`1^cIgDGx8R})zT`m=2<8#krB z3Nuex+bKb+%#@hoN^kuU)s12l*KtiU`=@em1^UD>n(!h5^{%1K+3bf;8C(F0-I)+B zu!My=ZWpsPorKA#6ya=gy0?80=LTokST}G9(to83;xiG?CxwP^L>UR<ndmKmmH)~I z&n3X)p(J6=OX?i|`UWU4^d>b+E>TAeK8fe+?WE5IRK>N-lPqEdS+!q=Z3QDpT+NnX zSX7rpX;HGnOmSUqMc;G)72xPm%peldh1&m%Yy5nJwQc;b7J7w>B_s-kLSimN^<@86 zYDAvbJ4Yh)u)pjR{+!Lf>-f3ljJ!NZhH8XR&^S^kkg~SF8643>q$9A0IemaNLmt1; ze|$Uu(Tf84kROAJ=%~%Zy`BaY`@u^9;Q0is2}z&&MyKfjW_UNctTSriSEL>V6n1b~ z+7@T32xnKqgC?W9h%k`}+B;zQwTd7B8!kQ=B>L|RfQF1%AR~!%7K-qu53w&?khwN` zsAj6b53o`fxG6MNb1)!EA6X-V#Q0G|NwG#sfzaqUzz-g^0TV$%S|?yNe(*AvN8HVE z%D-?T36a!Hkk4XBKNlp57+a3SYX!&Lz#y9xgKAcyy8!L*3o!zFMO;vGfZ<kPHU$tP zgB}7vpbHp4f~iRl@I<=6AGkMLv9zS1yt{bcPSBJe{5gt{$Pt*C6QK1AR<8s{%Ya1> zKw(Hopr4#KnKlrG^r(mqgyLaE(WS`n@J^}>GF@R*%IuraCeHw^5Aa$SxPlBU4gf^S zw7^PYKUJD21=`dZXb*i%OA6O|8d^F5Yn^~7V4>j<pcos@nLr0|Mf~(jl?)Eog8ZYz z88SP4w8fF1wp^a0;dLu;ZgHY^Ig(BsSpr~kvFTk=uo4u(bRhloApKPa;y-|>DF!b+ zfHh&E3S_$HM0Rha2WpGvHZqkA;EgV}kro8lKso8z3aNz5`UQ*lyPaMsh&Xa#+>}9{ zxn!uBlMLC@yIep<Sujau<U};xGYb6q1RPj_Q=12}pWxuD_>hYDrWM$-QcS5IJQu~V z;)3{rLI6=&)x}w$hxCeGNROSz*t?{m?JRx)ToZd-D+QwMhZlmv$t#bfZ6D>5ZyCj= z6Hf4E^GN%g40W&cJ6W(fB%`huBB)aG$d3^qGL%lhxx|r%AL3{P5^2nHW0aY+^n;4A zbo?@@n~KQSNcf*OPuD)=X%D0^n5XhpWdDQ$r4)uuWX35GQIae9X(H>dA}(bIRtUfc zIkH(2(~GgBUgdn&3r$=tfccR_=a`rdkO>dAU}b*rW-++aP$t<gmva^O9Q}xE2#&Kt z{2*uHh9uKn;Por8F#S+xvDC*OaCsldd16R}WZ@-QVrypxD+bPO3qRnbpA<-y&50LM zLRzsGGLfQ>DzZH_5yw$k7YSLDiIR`~=)2IIkyyxeNzSenI<R<ZAvW@JWt6aFkxF7l z=?cu!F1S<T5g-HIR)W|0g%fNc=VHh=AD%MH5|0KQJ`)+glM%%`#a9g_qX61}jxbp) zwK@{4xk9am1nW(JM3CiyF6pf@aCJk1ht~@&mC|P0B54@G>jd{_0Fncc0z<-m?dX29 zSG>KjE7tKQ>%KsINBvWP76)>Yi;tjDWLh~FDkT?Kpnhm^7(R0)RoexmO@XNFM%+#) zkE$#WH$)oR6zb>ES!0rSTi_N|dF9yfOJ2`g$%J>_&*>gUFU-THu+T6hV&mZXCQ$ZV zFauNs^}~X$`_Zx;fZ7k@pA#bnKfqd6=%TEOxF^Drk@O`8FbA6$yZO5MFyx!<^7s1L zz&5UyQaz{tqWNwrbr+suUtCVi7(_9~prF7CL-A=r_O8S>0JO{aSpR!<M}f{uDnjg& zezVhOQXpT>VB3;G*t?N)?4?@v`MP1HU53aqTe=JxXj4?tV>=w+_Yy>v&wQboUFgCv zAwfGsM2x}9CaNTU$}pZCKzsBcu`4cOD^$M05g}ZSxEJP^Td3}%qX6<V?O(6{gX1H; zi~N)lLOkK6WI9(;+C@@i_yXkG<$RXI*yRa^GZdpIn&C(W@fZ3k$6I1tg7FN1StFBZ zsi4O#fg13rM|Od^NZmpiuvKz!Ay7(u+w^Ind}}BgZ~J1Wiq1GG{emmI{w`}>F4N{j z%_53+k&KW`dXwXZ_>M-Lu0V)>jP8e#%VNk_ELe4=Vc<jcPtHa?2)q_aUpPT4=u&Ep zNquyRQ@C9E#I}?lNhdr1)J#7pf&$CcuL0FZ9ogYVE;HeD5T7oH2;vF^qFRX#m(Z?8 zoM9<vGK|LnFoH9#A=A|$AvauT^Zg<iVfl>}L4_;zQaiL=QOQp~)ZLIodLzNkO8JHm z%>5PGR&;3xJgO-Q7Km!&hrj%9Fu%1NSrm@^E5Qh0DL>GRCU%vf+!8<0|9}eyEdX|e zX8exUrzQnAtz?&UM%-SxlD!3+r^{itEu2yU-}eh{9f~!vjil*{XtawgA?6!?c$#yo z>%oUEn!_|a2H8FG66P9DCyTh&2A&}!HYmk(suDZ*7y=eMz>{!yo1lObToa|UkF&vh z5FTyS7GD1BFQJ9Aq9G<U8JwGQ8`p9Gf#=ZyiWhB2{{6@Fhs0;9$iEoG4jHi+MZ4gF zI0ndf=_P94GTfywe7To}Gz_|C3wMDru`H1I?!mZMAXjz<nK|J}VREiJS#P%MWw1~o zj$}cu!1@75CNYgpfK<nsW208EzmP7-*^%8zdx~O|{y3B_$av}p9_;MTGJIwZdF*72 zBoCI0eFWY2OCLN5Zlyp~WRmtcpEuc(QthDJsJ3~<z&J0m++yDaJG@a6siutOT}}US z!1xmli^U>#WS(w?S0=8df0ubip#$WMhr6Qa%oUT<mYB?;7=NJa8S%N-uS9PmUGA^3 z%=ymfR}iN2s-QM_1ORvO>VwsHIbS5e1d573M=|Q783Y#!CR!#4Yw0?dp;;)#O;jz_ zZvW)oQ$eO&Uu-XMAI@qEswUEzatzUnSCmhrilp{7hQOOBum~)jlU<|6e(ZnZ(|ko) z&r@g@T@YU=L*ww7Sh*oldRPn^aoc$KdUf=-k4%Q;(Y%8?)aR3*njXh{M`wExV%jqJ zDZ#!4?LbcG9ofcQ8xl0SMObtA_<->g&7d`r^}TZ_*l6t0TKXos|164LA30Ve@o#Nn z^!Qqmv&>Y>6|Vaw!g#a-tKaZlY_O{nB$=8VpVG2_+MrQX9APxGi$dyFQs^1Pi+0k_ zhz$2+`hk__@1G&+9qH;WTq4VwNBKyh_(<)p0|=<-ndR2vF(J9^fGTqZ-YdP(WDxC1 z>QdGm{ytHoT8r3m>DRm^zLJl?p<yCw2ypbr&wlXFe@ar9n5GsJd?}y@ip3wc(r$$$ zqjGXkbfpJ_?HV=6Kf%nBAG?iEmB-kRRD9x>YY<r|=$8YAsj95MoQw<PPuX^hsG?c! z3c9OUPzyT9Uuon6VfL9APR~A_iRaUS819Gxc;a|z_&!3%vD=wzIW7b7$#3~Aim{Zw zY}ql$n}IomJtyK{_zl%*{wyfRC`jeeMlpJ+5J~mmBvUq_CAYjHg0g6RIPt>|JU~QT zw68@|cbxgrzP%tb%1I$zl0JS}d1Q35Dd<Z35C@6gi05A>8RdjqNPUX=0C(C-a8^b3 zhviduZCRKi&d>}v3d6BWhbvrsort)a#yFKSBjt_QL^2|jH^oR)*SIlX3Z8#j!27%n zS7;t-FGz{4EZX;?yXD%QO`)CKe?EOKR$74gOzA&x`RdG-_tuH->FJ8#Ln&>JRKNvf z-iz<vN!#EHIrISy*pOO+$772=?A?NW&0o{y6#pH${dT1h`lvG17jcGUL>jVm9R)SX zz*_9+g5K{~4Ln;=gdgR>5U`=mVEBm?he*didnAJk&#U@JVzlY>o-T+vdO#2MD#DQ^ z6a^B!09Z&~u-z*QX7{G<*(6GQjX<=7st@+r9)6LnLA)g%t*t!A*&T^$JiAAsdtJB} zQk^wc%W@_6Mf#tne!i)JG+d-U+%WC1QmP<M;@F}7^C=4YbmcSP`!O(sQPdbVqJr2# zBQ4)$Nw0#$%RzmfDZ(Z;tp}ZogX1+``*DwPA$E9@9n|i>ezB0y$6|2AP+==}?w00| z=p#lUv&!NjF_!{_HEKB7^x(?XTJhC?_Ybrc?-J!!sAM#8$(VU!d#LC<-umf@phS9% z40vfbm>v3}Y-PuxC`&Zrc(S0?_o~?66NW2Sps)E5py)SOpEC~^)8-E*LZXvPv2=YG zmp>m8BEO~Kt~w)5v5X5S2Eope8YJPGILTmlFVeT0V$|<HcKq<DpiY(Mfk~FQPbDB= z#s|dEF!1T*U|qGYKl}?|ith?U*=PHBPzP4IRA7tM9u;s{Y+y1(ObT^!Exs6LOFMSF zVxKNl4mdtqpf08ZD(#C5Tl{bCmS46k3!$F38ksgK6WN=c7V}MP4m<9SD_OAGv#xX4 zAx%Su(r@_hfD3iQU*8)PgqiRh&sSyEX$i&zdS8bF1Ll!`emZj79=LSJF$C-8Uv;*Q z94XsYrA4uHS?XM7xpY$|r`$3M@wQaotl)-bR&VrmNM~W^c&+2}6y*m_Z6b>o`$M8R z3blJI56r|zjs0dM%v$63Cx281IH!$0BZTofp5b<95yP*7O`r1{9qm&QUmurOSiV4~ zQr{d=G0OYVpZnWF%2_4M^TTHip6~fL4Bh*_{AL7}ZS&v9^1~(9vR9F38<{S8^Xqk{ z@<-b(n+H8I+6;<TP}K*=xo(`eQP@F_rQBgJiw%IhEy1Xpl!ywO@=9TRsMYwNF0Wk@ ztV-gwIe{<6jmr<UV@2h{gqJt0=&~1W+0KO7omUL61og@pNxv=j(u=H6UhhBKm?V(z z$H4A1u)Zk}e_pZ6q=Rg*wv<v7TIg*gzwACL;q&jeGE&?zt<+TqWMEzw&1>*eR89)8 zJz|(%G1_Qhbd~o=ffA&Q=X<c(RmZ0|M$*f(*Qt+dFdCaIFGPG0FRPN3ZDM^R(x9oY zAeh|N*kn%Tu6$W+yCa+<u+&_ADK*wD+b+#BPQjkh{o^zOGgu6H`xBTD>-3~C6nhqt z#00u!4$BJC5APo;f2a7p-V!UV?u}%1ypdCyEpd7_@)CDJW7|64RymM#`*`wZt?%s^ zh?D2nN&WiCrFj}Ye`{^U6?%7_t$~S-^`;NJ>Vk2s<_;3Qw2pkUbW@LR%_-f<%}+AF z9=?6b%<ynD)Y~T1t9E)bU_)6yA!H&nsWav7qf~n?ks=WAV07)$#rRz+)SRt{s`-^` z2D*nSUiAYv5=C*x^|1^#G^19EA!G&>1^*Rc9sURXR>mF;-=}BzRDw>u`G9ICd;RpY zqh8w$xzpM1yRM&9{fDl-Fi@3e{At}uHE{aWK5SxW>p_EmLEH7fBfHJyu!<_NPgIwG zRAf3>JZcFVG#YrekI<HyHXWPYjVPM|Faw2-bAynbF!*?6ZMj~iJ3BBai*eelmogl7 zSz1}WVr?p`ThY<`?q9(y6{Gal{VM<E8|~B22n7*f0gte%NDb%9_rEG@6$I}dF6>G5 zF<Bscm6-BIowN=c48Dv<PiC0hQ2J688cPps5p#WH#A6>$xL@$ew|oNGt%=mTRNtp= zv)aeWCNj)xv5Kr?;@B$KT@okaLzDQQ56Y$gtfaxqH4>VG1R$a3cSCdEt{QHXrGH$C zC%ju^c$G8-hkPvxe~!{M&!geM3Qs26C-JMqQW$_0+N5{fi)wA8^#2$9ZB(ERIubI5 zcR-w9v><6<4lOBI9I6(jEBfs=%n?Tol)0Gdo9ZRqKlV*a?<I2W)q}mW4inqXiu%E8 zFK!oT@*l%c!rII%c^G4Ue@btGj407@^=h08cbvF4NzU<nmza?9MZ#8A*!*XPifqy3 zm2DS<EDaGyRh{eI-^H())58rKO1jF<Ja#M%V)$_Z{Scfoq_5D2Wv%Iqo%^N*Kll;% zuzJN>vsl6;h;dWmZeuLZ+G;9`9?9njO;9?6v_|+fJ}s5kKi_qg)_@J&sp-nOEGxo_ zjuGVGN0kbgP-U5W2+9G&i@!g%n3wf#_+$}Tw#Ydp#?<DP5yfPU1x`&_?79N&pM`fx z7IJoMZqO2}skz@NLw+>2gono4(EBIDU-OciKfq1~c$>zF1Z^Iit)4PEPA5(7QlN7} z65s7&<?~7_eU<CFb5T(>W*fIzYoPHrMvJnoX=iJtc5;<E(EUEOQ-$Efc%j?Yj5F%} z2~Lq4-!a-S9QHwJu!)UCP<N)WUnko$m$(Zj|H;(SKgYFCMTVFqGzk$)wS<9E?}HhR zR>v7_o1#Bk)?cYwuUg6Rs{35-#ONih?Yly|I(w5Er~shp5+$d7pIMrT5ZdvR!dVRl z?C(xNgN`mMXiBRt_lSjOy}-bqd{x{!iq_hues=ng-|;AxAEExx29OQTF?(Hzy6ae@ zfcg0oxJ7_eK(*%0mpoQXh%;7+T-g#Eu{%Q`m)gM6E!_i*zj$o$22+`M@3R|ks8DsZ z*X0+H)UrK+%SVRQ9*L@^N}ZaehYg!=V6?lQaZ%Nw*srb4Bd(9<!`HZD`W)S+#vbS1 zft&k%<<OUbqzR<B2|i^CENq*!a=u7W4L^Ut@b+H@8z*Jbb)%*A`PYMYdeL;pjO@3J zt{jEde>c}mSkL`be>rvf=Cwe1T83Wv`n+79^zsN;^<(O53woqf--54ngEF;d?p$|P z!m>1cQFPhgpE6R;$IKosZF|=KFhDcd`Dk&OsFlCrFk<0qzMCIo{xttC2c0jc(ZNhj zDQA9Y0*K)X&F#EK9+~Kk1OItei*ofpbCW!-k%$|2{?5}_M5gqplFA_0)6mB1j4J+t zb7F_PyZeqdKU6;^{?k-bSM+SYRNvjURbZo)b?ygCWgm<W?Ay27mG9w7BuoNrO7eJy zT0SB?<h`Kg%U+Phh<tFetqR@Fg_AYs@RhkApEflS^kOd;{M!_<U*@j7|7$RjaKF%} zS0MdXDDlbUCD*gpvNQpmhigB4fAvt8IvH+9e-;}E>3wJ0$YaVi4tu_o^U~huu~@z2 zS#umW-=D)mvu_fs6Z-6o);q-`ZBJW=DR_hXH@vTN`O#gR2&q3o$g>LZAs(DH+LWiS zlWs4~1gQwms`lqgD8E;zX{sETIiPGkSe-eE@#cH~8veBI&I$nGeoEz3R<8C{FpD84 zZS!HlR^4#+;K08iRc{Le6R<Y#H+t<#vm^4C+2X5Tt9{muIp<=g=3Qx<{I&>h&qcl@ zs?*cLy9jx7%fCslnIYdh{i@VO&nq_8NS6UqAAh9!vB!5-Lk<4ln~CRiYZ#7Eeh%*V zWY?ymqBpzv#~pkO??&UFg?;zD!WBM4tJq`YcIGPp!9_@(KXN|hs=eum<^6E5_<2$F z$Ki%qvB+yDDfPb`$qy@Pc32A4mGQSL61(@ReuHwpO%v|hQh%{8RQE@p=jWCK0M1r{ zf^QafW5DLd_>ddtTszu}604>Ob<+fYmrm{^(mpCxE2sQ^H=09A^XoxV)%+7|UWvL_ zOQ`qD^-Q)UI`J^fvkGxY;K4f<pN=qMXT<#LUvImHb~0SJ%KmCKwyt+D(?dcN_;4oz z&*h%~<aj$p?4J3JhQPTl4D#NYDN{PCyO&7$(J`?xyIq0bi_@=NuW@@e)YwgPo-Tr> z?bm*Lepmo?pf02$$I3Aa7HC7ykY`<N{H!lHyk7m8>V_CTcl*cRHRu5J#M{hZE~y*$ z*Sax0>Lx|p4QM4yN&zkhqS|^5+k#H5%)VD&r-auni_W>P6thuTV`bHs>)PaR8}opu z@)fTdij=Y%COias{}Gr%<oNOmwA(AyQ#?4FEG8+XS3jvF;Md%}*LU+g^R_L1b_xx# zZ@!Pl>v8p8KQEpbgusLod`buWgt@IpAOcv(Xn5Z(dH!85<&Y3aU{3#|nk%pD@HKf) zBF_aW;;CoU`WKHPIsqp3dr1w2lRf@#a~<fe_v1D8Ia04<(O>GjVv;+Bws|Af^ixKe zyChS)sc$$l*Zd>S+=VdqRAo309d8+(!~!7$JUG<vop#nxRA}KTDHDe#L=&$EC8+`@ zOrf1j%Ex`cVTK!;Ps!~CJb5VRupr!lS_sznLS7;-D|79hnt1`=-wAwZRp$~(HxdQb z6c?|vFyu~349?-_;vs~D7&X1h$_s^Chc;Eobky_Y=V?L!iXOrqQ#SO5$>&mzhaOW# zVz$-gFAar-^2Usn*IaaR*uj!rT*auW(cBhF$mnRYvEcP?Bh8Q!rK$eOUKS`%OI}VD z$Aa<2J666*s;G)YWBkYbJY_|}v-C&Qg-Z_d6<O%%?y;4bF*O6@$nEF0`1i_F)tikF zHx|MZu;gjwP(aSWUJB>0K?3txo9|nx$<imwEYw9C0(<l|;W&f4KE2<p#(8CjukMXp zWTn+bU>3I7F4_b>&VURlIZ9_5)Gsc5e5E|2BeR}VpdJlYrsVHhVI#t&VQP>C4lJxM zBYJ@mqeRI6jlDVyxt(7)RIjf-AJ?tb{QV4Rl?0jdGH2;SfZMN2?@w~85Q6GWdOqgA z1OOfmh{SKqXfY{7vN#lH%>O4Pm^Ehh5WSN0Hi9f{xX8_AKCoB)>U$L-*tV<9V(@~w z$%3J%L%faY1XrDsG`V`zzb3$)l*Pg)Vi;th=_(1K^o}cxA*G&lxA)YfFScW+AsYp` zew+-lgYloat<2%64=M=Y0zUp43#~8kfNF?q%%H%JmU`_sKUs)#ZLFAChyX^eczQTU zusu-VEkV8*`eTMSwEr8iUyP>iibTiNS)ts?iTWs^Bl;?=>(lEA@glK94ztW%M<7E~ zGHb!`n~#_Hh9RoD7B_FRTpAsTZnWNqOS*i?T+A}@e8!kpYW>E;(s?&yc2&Jd$HJqP zlj2z$LAE$;EAmVHM@8ZNP*7yj&A>6@mMp=GCRaK_=h5}f55@5!Q5d(Tk_$5{K8t51 ze{$wfMrQa(QaY*neh#UBe>#YIE@I;4rO4tGo$2ZIY12S`ap9I^X}fesn~K4Bp#*}X zjxym=kwWsknSEVKDaL5tTt}n<cMu=@Rj<a~Hh-2lg&S(X_JnlRU^!L4&D+hQpN}U( zN~lESzgufONt__sZF6T<#eH;UE>szbm#C=2QLIzO_^G=X1rp~+jQG74O6|az-TrT9 zu~k}hL;n)EV@1<3j<-G#Kkn=(wg!>`uG*})lIw3jd@SHY@H)ues<k)aTfgOSKB#Dj zitU!PWF6rMT&Yfod#Y#r^d*HrJLW*W;P9STT7Iy)7x!|a9bu3Gx^Prm{yxmn=W=QK zo=xP5sWFT}Hltg_LxglBf0d~$!q5I_ZF!r>9ZtmGl39LbJmX~0b-STo?^4G7?P5c! z3h^Hxx8eN2h3n%?kU&a*?BS<9>6B<qyOl^AFZ;Zx41OarUjMtnDoLYz&3t?L`k(wc z#Yz3&eV;N77lOCn$OsXuJteQcpgn-oI*5~vCOiMAas;|O`6w-C&D|1lgc%H6A(1;0 z9NSiwn}!#x6)5=*ez`^h=Ja$t65uGGX7H!5&*8cRxbEB~(UiBDwgUJCVL|4vo|X4I z1x4$#A}r%7B$68i5`u{>rsut-ubhNLQ`k)1N*UaKP`h|_#$FV3uOf;-h9N?fd1?J0 z@+Y$djgnDAn)U4Fw^x*A&ae)GAoehE3uWZLTtFJdl?4HR=7vg+n3o23DE_&uT6Hk1 z#zrs2JDYd?r6cK<(Fx#KLGLdYXIKyO&Y=#SM})0OOj^E-5OFtROHtr1mbm{9j1UMB zCwM^P>syn}5?&ZCq)&+p0wLgHct=FOyuc4TThoN)aJf)F8#P+V*xh)yiVCwUx!P4( z2v@w7zcBNs>)|}gp-R%1?%c^=xLGsWy3!M8jOB4em2;<AS40iywbHmv5Q>!BzOg_6 zTNlx+%>cH<G8GY{W`=-%gBX`MW2HC)KPiVP!M<+h3-AkC0W!g6JC2SkLBv{B__)XQ z(smtYYnQeCA%#Zr4D5&mqlid}_ZbmFU_;yZ6us@6bj5ZK#@`$^iN2D+#H1%<hlLUi z8Xl)v6=&u`lB&F}@Goj4omsCd>!PAKj$bAE!mg!swiFxh`*njYYb=#$2o2JXE(J%S zB)=g7*L>VVnU>XP@9r;SmZIjN93M1Z?~*Y5mU_e7%N>}ZSo@Wz2s?810+U5SOlZ|k zY8YQ=j`f;>kL_#ydr`O8mUmKBXv~SsPhLkm%|W~Sk+^zV9&u^0XFc;3gxlLO#vLqa zo69QKZsTS>v{>S-U1-cFX!yiqOZaFU!k8{dt#Kcd8+!XRtTPF7)Igy7eaNFEc9Z*> zk$ZxmJ#%b2;{;4+ju=3O+{4D17Nh)^w=%h|cs^Phe!u?Z{Q_^8PtY(QWR+?oO6p(| z8PJJ(Pyr6vE?tc9HOsV*t$erf`ZH%e1T!(REAn7Ofkx6I2@0jPKKNq3Nz`AdRX9Su zy`koH-JaZW?`gB6Q|JFEI?Jf2x;6|C3>`B=*Dx^T(A^;ubf>g*OM{?*z|hhS0@5KU z9U>?&bPl0{DAEEV(gNzs$M^62J!_q{_u0?B@9Ua;Y4CP^`JrhG)2dDmd(rcU@<3W! zoq%LZH`7ik_vCqNp!uG^t%|avL`rT~jJ7<n3E2r%15v1F>ey9+vyg_xv&8)DF0q7@ z9A*(k{BUnE&N%&9E@RxxE^EOqq)f<vdJ-;Hb;x%=8Co0=zC3*E<l>Kvt>3m}Ozr|5 zAQS%qd^-<WKz}7En1bTe=2^g%Oc|K|`bs!HdG?t5Z+V$3XVT*xP0GaGe-8uy#s~g) zdd9Z&3_wW&TV{RmF8gA=!oY;|aa#bDUUNhbH`DK5oewv}2Kcwrf7<<^<Uff6hc%I} z1RnszWY?OVe|lMvFz5(YY0m`_H<G&S5%v>bD)b$0dSF+bN(f(8?30nEDPgH(t7@d3 zRay$2!J#Sz$#3AH&U3%)fW+zxWz>a4_oFM^{ix9^86Q`Or2*08L4~ILtKS8RRhz#( zyq6Tte7VFZnQD6{$cjOoo><GJBJt!QPI;#BE>VZ?+5>>M*irvTL$bs5M^1_3{>@!I z9>g-gM6G}Od>T*iUuK`K_+3s|z|^VAdlXpTdDTex8=!D)&q`d*2{zn|wsr7u@GKuR z%06?=a@k7|Q^0a&+t99D{7Qduij{d+8|M37sbE<7VKd5Tyv%>-JfQb*&Y>jMGNl5H zlJA?Huf)96udmZ23zZ?|FTD;;p)|3~V*ga|N-Wi)oT_4+%081MM4b7*%Oj@}nmi_a z7r$BT>wY=blKioz_gW<?%ZEf1*8@pMw${X+<q3vVq?xdpka>ITuJ(|hY3%O%Z@J<A zqxV`qmJPfnHriXSgrw?SC27sq_{y6<?lq8_mgeG0yzSL^f`vpPo(q1hE-<W50w)n$ zT*1~rsVIK3jQWVReUY^Ha?z7xd@8X)YQ;Xr5%vA+^9BEPC}pJ3)=lkQzlx6BNaCH| zO-9`j4o&CIi=S(Kx>&oHbVM43|IJ%4OPt{lZwnwZlvPgVQWrEs04SIwefEyw!^TyZ z<bx%FWth}W-%R`WdDw6!mu9xG=PA!*uHgM*DNV6bRTua3nks(7vZ3cfk4_Kw&-n4> zD7J+ve$j8mb~n5G(1UY<rFyugNK?pxDZgF3supf(KNrzJ*<j-GfqVd>rK=Q0|Kn1` z_QlQU{&UofeSdAh@6(?@3aZB{HFJuc8-I&!-VUP;wa=@)$6<CwJUaB=2W<_8ox+jJ zyV>@-BbAze&Mlko2u!&|6=$J^(ud1!>WrQIVCv|{dI7UXKW!XeO*P$tG1mp81OSc| zT$p8Mwde2~K*`p>KfQioH~EqCkEEMJ4mZc1iM(vKe3afi(Vk(WYu5M-y}fsX@p4+) zt<WeXteMh)Q|tguo)F*2WXRp%TXhw-58XK9Xext0hkNX8tv{yqDqL`-{;)tHP(}nS z7kwZShc_ZK#!T|p>9xg(i~us{5@b|m=9F(NX*HD(;@!D3NlYxMST8ek3=)unEG8m= z^`T{fPI@P_>kPFyi+OD!Ln@mxQ9C5&7AB(LrX8EyJ}le061te-(yQ<}^Q+_X?(+~r z&XxQ#;>8JmKp`!?`i*hiho|v-LzI9UhzEZaAc=fH{(8KXQt<%4f~bA+0X-KQs9L!H z{Mk7T6~clTSS0E~%v+Bji>#c2*}D-&OYh>zUY5cts<v3!Wb$}k51yXyd0t~otFaa2 zjV>sFBsXX<H;P*EqDSz>LjiH>uf#z%g@hOq9gKF1FCEYs><5Npd;@3RGcF>?<W z#mRSU+dQ2Sl~!=^!xak4d&aWH$m)_!a?;l6$9|<`yY1z^Z#$>NN5DmorkTz^+XOs8 zNb;;8ij*&Z3aGXA*06aHolOkg0`RziG}uProTU3U)>+rbo<eF`YzH^RdJTOeF$cLc z*5zwzG0`Pz?P>EHP^MP)=m2p2(-!UhVjY}DZV;1NnGvYcRdvbf0cIUpMjNVNa?;q< zdxblibCrir$%XD2cRaFeIn5MIqR{^x8ng2`=d)MPO8(+(T!s=@;ig&yyqezq`#Y+) zgR7Da9ZYPI$R8iI(pBBVr6bP9d_!(dQREyRw`vuZUPXt43CCuiwS}s5v+a=sg28aD zWD!yKg#lV)>6E9DRK|Y=c>nl19Jx;?ZJk5EtA_8av=?|GUhmPy@V~w)TIkv@;Ig&g zVE#-ou*O6deuth9*r>Zby>~<n$oXD-8=^eV1F#%n97GU74B&Fp6>)x*@+0b(fH;RR z!YBZAPT$`JT!eQvV6tV5y}3^{*?)*tWht~2ZzW~2bfOJoOTJlpRJ85F#S9JmCLr#N zI!Ud9Y2Q&&zI36L;vv*;g(e~4fiEVN)k!H7Vn7D|gz>|0Ki&Wbr2S4GZB{Io_Her5 zdFwNo<t?^7k1tGl9sM+15@~`JsSmsel#?84(+}I@KWNe1lbhw^04|Kl;xp4CmYj_v zpgGgya1<@<lqVZP$pq!XQUL&vd1ogoDJu$Wk_VZuC5vU@vet4nPR4zCq}C^P)L0|w zsYW$a$Z$dNwtjdJt{A2UJ*v{yw-~*LWgZf+98@&Ud`;g<Po3T+Md!!qnK#BW_hT1+ zca!hzKSxDQwnj^outxxZ8Qqm<16hQfj6Hk(A4DE)@srpGiE&6gm+lToke)%qoxJ(u zxVoQV^yyxJkwYl!-CXN@Bs?52K<t7iwQJeSuEJ+TQ8}eJ031X9I*xb!y)N+M9HG5Y zOVsqKGyaB8eZg&~#lC4o6hAGA-~&X10qdB=;R;d}4_YJ-;k*%*PJ}WuN?d%9qUHE! zb-+m#O1_g)p&Si`htwK7=VU}a9(&<$G|r7Vn*pYmLmm(kyDc#(6B7<ngZuXs(M%t@ zb8jg#O|LZI6}=yaOV&wYVFKuz{W)d%O_AJc0nV3|3~a~cj1Rby_-TKTTM%v0Gl<OJ zua>+29?y*oHX>FWHy)a}+=WnA7(Zg<8rHazGm;Xk$r(>UBKNtN=Oxhmfi$TfNw}Gd zGSQ?|AIRwm2b@b7o=pdKP%65F!m9p>cuwNq#-AT?e>|__S>w**8t1IFs82ztog_O5 z57qKAqu3Ab;<G;G)J5Y&FQ5nN+r2fsXJIR{`N!1I{nY*xav%c>3VZ}8e-Ws^1s-sS zv*|E%fK2Rq5kOS*IxhPjYQ@ro4FI#OFkHqq&5<L4#Z}{jw5LgCs+eNOdRqd(Z8#nY zSt`$Tu_Pq>_i#(QrpBS7Faz!tjiu6g3t8voabcX$dFVZ*KIsrP>^o7;T=bY8&H6^n zOB}8D3_!>Y^#`tMnJO|S8b<C7F;>z)O9`3hY3ZpPeW2=hJWCp#D$61&XS^g^8=W2z z+&tr}FcZThS>sU1#dfe<TzVhHz<rmHq$(;#WEb?Q{n=rs$i^rG@Om2e;`J9Nh<TU^ z3E2^w=B9+v{E(WATa#kAb`n;!_%2>3*1O~%Zl)MGOsOyobl-)vHfpxn<`Z%%P@i;A zBbHNCRpdVLN?_3u-aaGiTF_MpiuA1eu%5XB1Q^$W%c~)=dN#ackXw&#^&r;ZB_Q=w z`I!n%B-eR(knGK}D1ZX~m9X&%&sbx(2Q3eo&fOF~Z1lIOSxj%(ry&d#f%Llq;H&~6 zR6=orRHoJ;BcQK+<6i3s%0>6M-4e<*28d<}9Gp%6!^{3p>5;zHe>oP2YK8|3uUyPQ z0RO4KV%y_)4JUX<u@DVFP<159V(hHq86W$;8mUYZDPLv5wq&{5Lr9mm3|6ZDpcpka zv7hQ))*em+D8%3|%$*x^*hQ})ah!c;zuM5%oX-IRTs{atA<#cv3S*hoD#8HiVeFEH zTr9L2$z_3myG1qk*2XCf1l_|y`&V!9LG!+YQ_n+^-v2ea)dK<U)w@E^wSMntp46~$ zZY2<pDIe%MgJ&91AR<)QnoxTS>*0`B{#e*S&{NtBW;<wBZRt@rL%&6f6X`R~dEb!c zzol1$w5TTsJ1b3@QpbarQ}3g+K~nl5!W_2lob&u;>HkiixhOI|wmaYrWcgJ^XS@CM z9_Fwubg6k<UBf7v_naZ<>isP*U_9KlHU8*LtVkh}aGSE{m_YQH<8RRyNqmg_65XCv zseBRP*)ocq2f!!JNy?WeUx<ac;N0dPRHns>QV|ka4w(bgID$EEwI@ZH$qyRl&>x0) zEY*VFa9*qAaap07ldy`1tgEjIFfHS#t71?#M|$}!x>uZK(~bm{GzWqhZSXp-b!sbO zW@(Iohco4(OW6#fFP59A^_Ic^ZLb9Z)M%pZm=DU7lV+xbfxh^HZy~lC#_H5zc5Eqd z17>v<VFH;Y?CuT>q5KuJ7xR@M`sycq)qITYRKrV8M+K36I-xHT3FWq5Q~7{a&Bdx* zl|SPAa5|yJcK}N(#F^l63K0Y{K3JIuoYJu&)8v<eJg)0&V_6=obVM}II_v;GiJH!3 z{aksZJ{8vgd}klVnaju-oI|=D1Et|!mCz7BN48jDKs#TX_TcC~GaYU2-Tf>fvb*fI zE(7h?{)R!hY$s?nqkLQGb)1%XIo;TYTc;1M#mW6ur^$2$9mto6xqb<|=~uaQ|Dsj7 zU{*<lLR5^zE2L4mrAnWf0UcXN(4B^Kh=(dpfEkkohcOeXu@hOSXS4rF9Y?Kb%F33c zr^N{Z0I?F}YiZS!uQ=Y@ZgsZU@vX<^io_ua2k0kUR#@V4BL>QPUW};RF<Hke@`yy2 zxs5_gkXNKvBinf6co(aAPBWB++fMuOXVZ^Reqy`G66dirD4-*~Lpu2j6+ShxW>Ou@ zpO)%^z-Y>r@Gx6zyTs=8@G4rwSwLJB)-=_up))702kIGaE<6$e+jlc?=bIb>1P@=K zi=xW5vwiJ78cbP4HoBPCE$Y@yIEGMQnUj<g_yR%dQM)Taz3O32m<JdzYN+)|UqCQp zs0jwUJ9d1IcA0)YONxHsds^#%0PY#yfho^f9ewi`b-!FfA^IrzBBDi!_^c%BLITrZ zoVy4gb@bYHNEH7eVx|E~y(G;SR>qH8hq<JYoyb>*SMo=^o8s9XQV*V;{F3NCS{K!; zE5w-=EE(7Kvo1Q8!hScFI#kUVR3F<rg$gloL0C2#?Zg`F74jr@et^8>;g9$ADCHUB zgk*LvCB|xVB<3SBQ-=g0nYkV|4@2kgdZ($3TH;hgTo6s7<sql|2T`MljFd6-8<fy7 zK>(!2dcidV<{6`WTbgoBKyn_#VQCYrjmS0-2<_v^v)>PM$wA%>kY`q+qSf@w`Sa5o z9t_8@;t2qjNQ@xHF}vaUrMgZLl3JL6VdKMezrbrUZc<g9>MIPLFcFC*0S6CTnOjQU zyB8Z~Pyi9o<_N=nOh963DDtoR3%yru7?M==L$EULb|j|rWLS@3u<mn1jpU>-*8y8B zhBq$GqmoFCVaYsFuYp9@QvlVvv!)Mtfr=)my@`WGY}eiOM`vG_mPC{Kb3T{Gn5bfC zGclgTLam!AbdnCLeM7qJLv1A7Xcue8*a6*(>RN)OCkXeB&3y&S94?ne)E7cN4-(z1 zA82SJY13`)3whT!+4~)`M0}Pbyq%tC2qAnRS1YANpnm+>+K)U9Y}&|6RIZiIUhJ1U zC&DO7nDek7wWc+lqQ;Us5_*VU{$Vzq&7zz<mVa0QhwDu1Q2G+~75j9+4z-wzK|Zmk zJxw!5!=Pj2%P+!nwQ(t>ywjIWc#z2a5ClN=GK=xmf?}MQsK`9YtHm{+>7O1;r-$9< z50|=xKYnf!G>R|u6<JPr*zgf48u4m5zmau`P{8QtiggpNOXSPwt1q)6Uq8P3x+b!= z`)ch-<lE(|Z~uv`le}IBiEc2y-hhd2g0gt7yf;nu7|(g^Wkpl7osa?;xPJMz0fLT- z_Qv)0b@F3C?QY|DQ3RRCAj;uz&;ENut>}-g*FWBg9*({~oE81~@%7I&(WBkhM@OQ+ zE?@upPxP3i`4}X2!q|KQ6FcQ=J{1)^lWjgz6+8DO+tu(h7yyP~te<oc2@c_uN`RLd zAM~&0tMtTl&u!$TVb{CGvvGb35kUEKyYA#<<zZmV9$Ic3y_~A4y9`tgM$0XWY1RBf z#4i~~tiSr;i0&9szM5B#!zz&ZH|(c!I5w;90sp1E&f3>gKKGMD5J~r7Z(jmQG7=E~ z{ZhQbN=Ez3sU0)17?A7$HNz@5&f_%Y$K_iH*bY&o4LD$icul-t(g;w_9|hW0BYtr^ zZ?uh*i$E*1EGWg}u4@MsTd=ZCIHhsie>dVzVMO#l&`MW8r54;h9vy}AW10O_w-q3} znufB!&dT|)XBdXfXh^gJDZPg-rPj4+`k-HrRUF2u`VX;ThM+`*veSM>^=P{LEvmV= zSG8H1f14#+&~#Hcneid{t6yOyeoFY*+s|le{E$)vn)J_N&pwdNl2GO_1~!al^$yV5 z2C=&ot9(J>{fUGNhK-d^CH_(T7X^gr0R<%qxe*e8>H~vZv;v?_VttUa0Q<UkUO)Im zMjEZ)aVoFZ_AkoMue`EKKaiy#t*Upbl%%WVil6y8u8;{-j+p8FOSH;!`*ovwl&Qpq z4tRGmz(`Y#YhBO(jRkW156PL0N%s-RMFU4=<0YqX3flnqcYwU*F<d=Rt`E!ChgL|$ z-G-jZ_hA*nD*b{3l&WJ@)Fje^PZdglig7?nVCF{OFoy|NISgm^Z~botMi(>tE_`f8 zBv1Kjb>}GV^&XbPGKK*XtBMH{o5J231IqTr$o&majz;s?63UlkUG1K-8Om@^qqq%m z91g&=q)pKNwA>z6RvN3?2UIM?YOJCKJMOm3Q&<LxIxt#N8Lbil1O&IJ;A3qcVHLX1 ze?mv~m$2zqNaa4X3MS>v8$I&Y7EjJlS?Hjq@$5YNASvxFtqwwPdk+ZjAow>KV_p44 zia>%h2*tUL`!kAFu*4#(fO1vCM5}1zBQCjdAk06O*!=?3NkqTpC)k62FossXYUZ7a z{r9@X;ytmtjkGYT^|lhIgy?qQSXAQGGFb*H;=usLaRY}8Ui{!}f1HZ{T09xt;5k}f z*+x~_KjPI0OM5c66pCjVt?-3N-XF`ZhpW#Dxon+yvGRytqeE<c(6-vxBN*K&i&ee~ z(SAm0`xYnP5*+kaoo5v-GlkYbw`z`cs#0CX;|$(xleiiZptrRazNU5*VO&38SrNo{ z@V*}`$$+D^V#LC`37~>}9)}T1wHoImmwj*b7ARYfW7ESGF9YS4alX3eYz3GsXS4#( z^<PQpr~GJDs%zrXgxhymNqO`g`;R4j*vha?+5ekQSdVISkX%VZLAQd^681tvfy31( zJynis4wtZlRyjM>`hrnBpJl<Y(z3)WlMP0ESky7nDlt#Y!lQ>Hm-Ka|Oi2S&Ay_zD zH;2M$%p7s_3yg9uRxD0N`3sRUKw7x(SIsYo`dcht99qM>g$ayRjQ}3#sO!=%s6Ru? z-_^MY)Rd^O3dfzLZ;c)B=K`%^)Qu$GfKF}ccom;9dOb}W%Fz|$SWYK9_vdM<^D&D4 z7!`Te?>j(ey3k9&$=`gm8W#Io@HXh1K91cV?du%yy$nMqMW}+Yz8aF1^}ji|nbrU6 zC(|rLznY`6jaBRcia>rpS-sGV!&$wLmF>ei{7Aj~)NwXg<y?v0Zw3~Nz~NE?FXqzn zr<EMiAKoV~%LAf0EeSt{V|4M-yjO!8!vS`Qapm8>u#}ffxmf);xk|%L-@v5qjv31I z(zY>}JEgWf5lYM_ys?U?`za2{rXrsUgk2E=hSBwgb5$*GWDDAMK4NcovBI`!RlH1} zrRHn?7L}4nsXo-L^_ATsp;94m)lmA;k0hvn7`U0*W()A&rm}Wn=L;cq0Oey9BOL2t z$_A;T-})~}vp;f4$;QLCSV$`H(tqZLF;WN6szN4V#vNR&D<ii~Afff|6B;wS+{NyX zo&QE8w};Dl+r{!@PQQG!#~XD!)bD`9X?aVpycqtD!(Q+S8D5Fu-l7#af>!jprKEu; z?F;(;^sETgp+}jjWGG(zFc~4qZz~+D53r?Ko0K3LQcdDshha{ew;g_Fyp78M0(co` zzJI#E_n`MvqpVsX(0$JSUBt;|z}ZD&nR58<G(o0(RwX8pc8eg1UW+3-jA?LxiyrY! zA(2R^*6dBTt8Rgq<7jTtLIutr{=k#%6E#2wAp5reiDsi+k1vxQ7q4YdiE7>6;Y`UM zom$VM;&=U&pK@-?`+YaoJEd})ZRB2>@Rq5+&3|aqrSr35G10B)-DCRwtSM6Mbk)GK z>e<C^A958xTk-|nx;b!l#MYijUR~%*m2kkj9h-JafFc$$vER-!Rwn;AtE$($zxZOf zxS8L^;919xH#Si2;Lk3;e8$JGr}SB!f!)t36_o?$VFX9d#PHVsoko*GZi>Xl{nNWr zx5Kte50yqHUvJmgZ`1Qmbz-pL0xhx0sk-LUcE8JaA=|yO9B<vmgrsy3m8sUR8kc%> zjgWcJV*U=h+41kq9fuRT99n<zV{8M}PE@p!@_)5qloE07xS~qhx+>Qp1<kf#A|)rb zw@21^4PwXJXFp{+!j!Z)lp{PvWu~?X#-N-lxLIDT<R(dpTx}LVH=r<;lubEXpl*!q z&0$~-@O>aZ!;=odIj+^^d6Kdqg!GZ#lco9Z;HQ5p>U(l}Z?d&c*9g>D9-b?BX>m!J z-X&%}OMM?G%<XV5(Oms9H>J%oQ#XhQ$XAt7M=I*S=IyF*hb1AZsH4OC8osBx@@(Vb zwEtSZH;Y*H(nq__BHYo5oI3m+V)YeS3yz<LOxrZ6v#0exZ3moE`{0x7x~Ec>_%pT6 zW8C@TdNy{`5j8U73qb?q)dkq?sl??Fy5V-VpwHUsFC-%$>(7Tu&$~kb-<}{=BRY&n z8^V-s7n+x+J`2=U0%s}=?ZYMoG$)FdMC#VlAujiw^P%VX=J4Da&60@xat*Ud#Lyzr z+^RGYH@tV9%UW<Yam9<BaI|QpbXE!2dhxb#qAaK+kfO}<PifbxUsdsyq_;wYac$~( z3@^mLw)(U@?(UZJM{o@2kAv!k#8RWlzmP=6N7D@oeD)&gB*mrG6Lm%2U7HgkvMlG_ zrH(@^W3Q6Vjfp^NeJr2dT0cF+vqk26C}3Wr+J`g3h8r}!^2t!7(RLrhsNT`2f7DER zXlwt47mE%azhAa<QgqVd&Gng0O|*5H$Mk-zn4%@~21%KJxC}q+No^}PyRXx!0EYqd z?V#cpsl}6BtKfk$yC+-YSoiu+u0Wfbwr%4%ME@TVA&$z)jS03#R28JrRafx>(8v<w z1pRiOe12%q(r&tcJvu}?YivF@AT6}T`Jo1K<<fVF^Rdeo)oN1WlnGx(_&Am}>Ml3A z)cPhr%$McCfS!&4TKb+P%EDy+8D^S>E2)G}v79#V3ForB-~^gu@e0V#bwc7y-{QxZ zmH(kjR)i1!i~8E3Ob;rVCKrY_o(|MfXgO(0)e}y%>#H33lGW^2?icZ^S3_#{lX7!# z9OLO;4(5EGO6{vA#>6;5im)cTK65U@6>03H7%LYPSH<2DmZ%!`NuBLPhogM)Hmyq% zQRv!)<k-X8z8`f2BaH~zV;hsuf|}Zp6bK&)PIq62Pf*>2!Vt8PpnACeEHIi|E}zHs z5m_w6Upba;SuH7>ldDF^YRlUXt;r~rGdLB;2Pr|!^4@P4_uuA!dVK6m@Lm#h^#PYb z5;v~2?O6XP2?xIzPgDXhW!((&aFt#s!1@=cBTE9JT=Y2L)Dq3UT4)X`VanS|&#GCO z?Ci4Xa>w%kBCl;=@#w@H{Q*kHC}k8|^p;mQUm|{uz(FD(XNv}=aC=Pv*$=cxU}c5s zKGDEzl9GIScY){0;>or#(eWy(v^l9)gy35GEHo-m<npe_1}|kt-d-VKrybiuzsSmg z$%x9^K{Q8$|Crnm5>i#)$o~B*r5C?BQ59hVbDgh+_jvLZ>~3Wy3{6KI(xkh!Y_b2b zt}`~r)@41^;2427#@9L^GcOHbzpsZR%NN)m_iaIAI>#KWhWK<2D_|7dLJEfx#Tg&B zV!}dnGpdKFl`!1wrA2q;5~0e1cY|7zd0KgsGL)CY2`zdiAntSH=@*Ow9B+!&tc|ky z=U$T_yu1@t^FMb_NUN*l55XO0XyiO1fQ_mWV=^ukqEC7;uU<PcnqW_texkY^KWdFA zg*g=^R7l-RhQ79$tpX=~R&T8s%uL|ZwES8Qw|w@*+=G7d7XQp-JNr~!1Fzwdp?!d> z{Ph*&aW=TP%jwRA)3sLh$I(ogxL6;wB(O&m^&c(E%JquCkkw=$-*s)lbT4L0_SAe& z_y<QH-Z>z3HpfE%1?&JJ*p6_a4}<JLx8G>34=?ezGea6S91<m)2+e!css$3P=^7}K z=&Sb7jE9I!Ol?t_yQNg)P@06EkEzs?!|wOOyD9NzNbMD?tghIY%!KVRhCBj!Hfa=V z=9A5WH=Gv3eo-Z;9|5ecrPmIdidw47G~^-5SvoUNFZK-qnwO%Qa%5aueuolMKNyOU z25snE!83K3&OG#^_9q~C8xpAyuTK)=<~3*A+;*#I<>2~Q#PR_;Ghsu>M%5tMr5LIK zxGJtcd+DY0xKB6*PY4*F;f&w(?t1LNQebzj1D~p3=+9GUKg=YSBbeOlCZB<c(owU^ ze#k_9AAvEqjg{QrERRsDH>Vd|^9;LeRW}`0iMG<{{BHdD*XOMe)A3Q~8PA5dFQ2@6 zy_5){nW!e)8iWb)g{b=mty<Zya_y{-UZgX9coF==>Rz&$AAXQJ$Wy@1c3a$%o3T`D zJ%&WV0gPd-Ib~iQh9;VUN4?B*95W`I?x}X&CtJ}7u;E$yXEutr-^}T1!wPF>c&mOU zNE=Wo;3diWmVOaWpH!HGIQCZ@`J<khhrHwe&{e)tH$X3l#d(?e6;QoAM<&`WIm7A| z_MA3Lz!3$dN6&8k2Kb47V?}sjJC;deHRkDC+O1okVgkMm5P+1JtGI0=^o<m<s^@;p zTP^qKwI$_Fh2>H*Zj_trM$kUyx{75B+KX46JPDm>j5A#K9QzAPs(ViLrcv(l7doX3 zEVO!|f6kKNYjh53%yz$E>AU~#v2cW2$gh<LQTp;XXv#>MkgEW{ZhNAq#mXG?c}swS zzkh0fWz(p>=Q0VFK<tZU`xTwX(4MQo0ySD8V!`t2d!I9`9&d$-!fD0DoD|W!Nsa^K zDQs;?Y*G7X`Gf$JlLBayH;Oz=ajW|_CD8`3PV4h)3$eK<Obo+Jv6hhKC)Dru{vx<r zj>}>g$GN_e=|;M2uoAlVRZ|Fe{Cc^d-#D=GWVi0EJb$VpilX0;BbzFVFMVBjlr@0> z*8A)}08o1LoxmOSttpz7*<iz{J~+<7O^t8gs0P*qU{R~S<=K=T9)#)anvEOqj^7D} zqlY{;|63S@0b0II`+t3m)h{E43OZd9BD>l~<*l1NRmD^VMQA}N_RvhON@s;hxV6s_ z{~>auZ0B-vRx@G{6sRkzu}Lo!K$8QZG#xCyBK>&j0i|eYiffUq)aBTAOSQ-I_d2qj z!Wq(kDYZ>MJ<{|IB_z)iyLWrUN5Qh=`wsQ$V-wqH6&Y}c*psHrDBdL#&LN)EL^kAv zKth<Q+G;mN`5L6YocyO#M+s{BW$grdRW3R!;ksuG-Gm2{i9y8<xwFUEcxJiq1W<!X zpsDY$aLsA-7+fEG6P8pLIMr{<ttbi)gA9F3$I3O4T2pM&J*BQ+g6E$j<(q~<KF6OJ zvt)Y-*pF(JO>`TFgra%{Oa_EFQp8`|L#8GPpXLri3j;LGoFW11l?KAE*GAZiXjVZy zW%&@QDWJgkcb43WvbY(j^y&0^Ea#?6w)mY6j#$DazMT0`x@S*qdx&<~!Su`FHyzCi zGXdFI6R!0v9oEC<+k*ucz}68NEuItgU7pZeunM|IpmW4y7sx}H$4&cg187>Qqln*f z_@y`NQdolaruEF%m~-&g=W2=ZgbqnP-tY?4F-ZVlP7Xm$;H;xK3Z?|XkzuyVHrbhj z^voYmbxgRzHra<!Zyiu&VePyQbBM4k#?(`$r>`c++zte*8hnGIrWXiUW<DNli0p8} zKv<d11WrLs(DvZnyMzy`i>mQ+961N@IJ?L;K!*tuqEb1_wcBaOR65<Dr;hAG`--Gz z`&xHLu`PL{A?ubMc#b63MFn?_JFi;W2j$nYg<5v8`|`O&^$>c%6$xJyKV*Rbmit<| zBAzo(?BF(T=-PfrWpdYuDy3;0OR>)@lcE`vgyI;^;7YBGC_~;W0f}A_MeS`gN|G3I z)e0Qd!s;i5(6l#eaIWRSPQqMNIbrZIntLZ5R!>0fMpT{oO8OiL60T@&>G;Y@PW_Sg zmdr=#p8H)9MqNrvnOu-#I!H%~YzalEL(eDprOG-^2l>lvQ{I%}DK)$W4oO0unHYS^ zR)?81sl6~jH;+ISmv}2tyJayo2U@Ub%-PVq9hm@wPt$ZNb`%eC`rL3Q(^>V1(R(M{ z1Le9`?x^x5U0aj10l;aWFY>0((70rw!Gu8WxxXN{+mFcuy>(PsnXpZ?D0~$x(2?VD z`(=RkG-g+lZk39gqjsHnn?P-*O8OL8ap)w<ZVFROQT{<M@-s+D9SvH`?b~xSm<f_j z1a}mxchn-;H#a_RqBz9c)arO=_<*&OF<KwVyX1dz&$ek+I`h0VCkg-Vi3!j#@pfpa zhRW-5ZB`GHnV-HRcL3~U2IkI^AnZ>oESy_}x{h4l=wtGSp!pZj|NIrvoqJ(<yzd0k z0mKGEv1Xe{x;4jCwFP^C7G08{7`aK12H${uBa6~5SzCpT_wWoEN<F&9=7LAJI~Z)} z%qv|dP#ewKa;a<k{eF4{YDroR`6G#N5I(<XWJM_@H7`+wa1zE!LKqpBkeJ(KZlfJk zy$5K};wQD+#LT2GH|Chzhq6{V-CpI#_!^w$8Ol#kR`!TL6$aFt3l!=S&FJ8BUFEYs zaD0@Rt(vjR+7YAY#%TRvT9~Q^RwivO<tB7o$D*7#8{t%}IK)zJAoYR)&HEa5PGG4x zWT`A7fvS@DJ9O-(vnkBy!!c#1!Ef{S&K_OiJ#QlR1F2p+04kD{wf|1pV?N(Pca);3 zbLz<WnGx>qkzBh0Dj|CEAJtIp9ToHu((0JDt5#@km@_G1F|^9oZ<cd|iLJWhPzxf# zX1p6^=s5MM-e*YgJO;5esPIRlu_+coqD}EceBxatFW08uTJBTxP4?SEIKxLE`P;3i zGAcm2o3Hb6`tDimRx;u)y5k&(fn<POcpttZTMr}9XA%Q5`G=dzV(sfFmmqDm>Q3ba z0{_IM@dJ-rKN*+{aj{%^e}3dW5JThONZ-ysgQDpc7Rt&cVN>&w;l(<h5%{<An^4HW zs_ShO^JOOoL5~T;s6W^yOa`0?#ztl``p*YEX(OBesis;*c^BX0s3*m7bNI^gD*h&Z zFG=12aSf3|Bn`1-6bcm|uy2xH!@_#(aY*?j5PeolDBnrKm6`Yy?WUTA{pd8N+W8$P z>+9c@^gsaZue9}j^UV;ZJx;M>Jcj+O(DGUIRgI3z-AY@>b^EV7t<@EmJxf=CVR(SP zZ_>)gnft822dY;|?+OMKy0f~?=Vfnz_9{$fT1a0Y4|^K|2b<U;7RcUeUr$#~RYE*t zOv`$GGD%&za*s8HfWM<n^g!cb0@cDph{-*7-m7X@5@Gf|2C;93(whTH$ldExar^KX z0=XOAi?nZj8xW~o-A5XQXR+ZzT<#7Ep?ycK%GOD8TH<LeySvM6xfr`@BB%)+bgi(- zN0%OMY{J;3RYt^S?Zqn(kr!_AgD`f}GZDRw_2T35HbTMN$iWHYQr+UCU8#sL*&ml= zFy+FhU*gMfKm<p9!)A>Fypfb#!()E>>2xKZIlag&o10b9tJQ7tpH9Cs-V{w75^$aC zhjSYmo*Tj50a(ZkKk*D94+&c3dRLdTnYWwTD2sK39Sgz0hl+|Eu~*J+U3WHX@g1fn zHT|%PxRz)^j_6^YEOVl#!%U*DmbA{fD~g}l_;-D7d--IOcKnUfOKPx5^J)D`M5F}N zi7wkSr=ba@m9e0-u5N$Rn;N$WIUuhFtn}e2mC3!Qq9o-6oPI!!8V8OXb!?u*>d*b% zY2>eTj$4P~k$JW#aALP>FZ!E7VsNT+9<o^S{Gs`DYoUNk>;BNYSA~uj6~nVd)|i=+ zr$X4CjYxr0x;F~<m}9tYF(K8i3VSh<OdWN%k&cn~M0)^$3_FljXYb%dPqy|OKIX>{ z-GW30P?Z@|a!46P?l)Y$?uai)c8_+_xq3B0rp!46E1XR@buJOE2(32)x+jj1jY~qv z7s+&Qms&WU)&J+a_p?Kp<7FXlsGIH_GHQ0H<-&=)4Gvp?vwvhO)ZA_PJd+_H`g~RX z;;3LmQ=HcSr6g}U@Yg_r>ist_<B3+nxi4Z0L`zTvCQ0Hn`1=uwYDb(0T>+XbvG2^R zK4h$D(CM9Tm|=g(m<=1X)j-Rh3sJ<guRE?rbaHKz11gbSi62?UHr(T7K9++iWeAvb zKM3F^Sf&XY9sauKS04O_dT^AlrFd<Adl17q%V|CO#k;#eLfBDWV=RCuprR*Ye)|gy zB$U9VKC=&}UKOdPBzq73(JJ+I@Gx(Ote@+S2T)k0(pOxk^ctvM(!-lilS;~yMz$co zF{Dc)fNI`JG0PwTaC^7Q0m`H7UeV7{acvWZ{3OV6=dyT}ZdH`)lRg`3Woz+f_QRNa z><BQO`d<!p3^Z_&@1?%bzm%r$V+m8J?jW+l_<4$jV+rY&l9!R}^BYQOz}y2zCVaW{ zC^T0!5wvj5yVURMzlYkdfOTz90s=oz=mhly{cBq8xA`S1Xu>5t>gbssGB3B#7eg=6 z$G3}PJ}kGU)7Ie%lH~7`eagjin^}FdpW|Ua)!{4J0WoJ+wD_uLN%vYuFmM<;3{PEZ zEafDmY@puBYiL2S8)?BlO39Da#2T(|`1a1aEwN^}amgcD`qjz;C{XHTNV4sAlBi9k z`C6}485m(tHXFu%%=S`XklLjt+fhTk*MVjE>mwES-;TYnCt_ea_4^+_O4PVA#=3{; z%uB|geLscHlSX}uSL8CE+#2_l)LM$BRPhk68dPv<_``$)aK^aPbn(r1dq(!~ShA#@ zij){@)a{%QsM&`u;0cCGR38<e51P7zqEUd$!;r;KqIvHgZ48O@B^f)SpPcrtEY^yA zQwrK;6+Ha-v$W0qMzYuC*28e)?W2y*`;`1*b$tcOPj3E(w{G->-{gx-d{48Lm0miZ zuX0~-H3+^WGNvs6vExfH{})jn?T?gfo?B&eiwQ-SsJy6@`a$}&r=DqqpoRVs6yJH; z8%3?_*StO$N9jJjVq~uzS->3dj7jXlyVPvB^IL41jlsn8vk7!ThB1#{Chwx%vI2jX z+!yI7-M__Es?L7r`xg@yYjTmP%nglWj28xg>&X>~+PSmi*3*{j8z2aFGLg_|Gp5qV zg|Yr+#HisTX4@S$Q&REALNY==sBJk79j@r17k~ZPlTcg~e)#yJH}9FevHFQ4y)F9N zHZEO~B+nTX_BD>~HcNrtipUK8bsK1+!p$3OmnatVJ6GN!2?$nL!&gn-Uz<K#(75ai z8J7L~FPBamU5YbPHB|qAx3O@HpA9q_ku_9#TTYN~NhxEN&+EOnMV*G3<u**;SCe^> zXzi=O<DM0;xvY?7TxaB--%pV4T{1$#BLDPiQ$I8N!pur}dEIfw`J`vONM*6l*w$ZV zr^Ci?XLzwlw^4;8TJb<Deu-_l1m{}wfw-<zYO-*v)S+R5Zq~QW1GgV`QeJH+C~Qu& z=C~4HwIFqEG=3kw!CAi^2b8Qc4*Lcf=Fsj>XfM@bxcHnC-($ejRP!mOU{UGj5T5i9 zolKX(Jhhi|YtSCCYig(}ZUXeJL}z2b3fJYvsiu}g79VMrrV-WUL)UpcDy0|obF6Ro z&JdxpkE_6}eamO`+Lww`;*Ku@fk_fy2c-CdLIQyR;cL#`-IDfx_?-OTBH0%PiXX@g zcrx~|9_@KMTa>Vy-1ZiK*GcXo2}!vmsUp|d94eS=R8Njvs2<J{r*oUz5PR(UCeNU$ z3&*aL8R883@CzR#Y;-&ksIO{B$}a-=nY*>`-<5#QL|z{Y=O}lyRAp$g{bUeCLPhNC z%$oO|=jb<=l0XVKhq3wcQlb-C%70h>ADlfT>ulU({cl9#)F|rA#x%3BIWzycl%eWW zdBrVQF&9f(m3ndLTGjgivvu@3;@i<d@zeY&gGT0xroaQ0=fZPiQlCuU=nhB`0$f_O zL(^4bFp@!;_hg7z<g#Dxx1(;9hsZ}o2T2T67u!>x+=vt4XA~NGg6Lkw6%jQmCuCx2 zpMnWE=i@#p1y{J)R+-ghef(lA$$V_)0-f~N_$z86+sjhR^(*X!Dy@ms#fb~-;1tLM zPy-1*G_aOf82cef`!>P|1wOIN`nio8j5^_h-R~uPsw~&sF@tqD{A{~7K-WK4<S%9` zQNnAfl|JC%pUikR?Q;l75AG25q(riCi?&K^obMZ6lo#!hNtYZF0G<V!%v#Snsvg{i zpYZc2n0o6h_ID@o>749oU(epx<P&`O@TkS%)9bVJ#|W&i{C<*3@!kJg2@bju27dq} z0z6`lg*gKmn$C^s3=|g3H|NKMIs(!S*o9bW!&x0g&nJvR(HYCh8!Y*b>5w*FcJl@z zz=DM86aN;NP%5c{KTBubb``Tn=2(hPl5&9FV94|BDG;T_U9L!ie-Je$`J-aEpG=C? zG<rd~_)TVzQA*z2!HU!4oQ&Xl?(p*pkX-5sDWD`%Ozatk(=C7STllEK1R16zp_?uo z^DDypoc!`IIMH*@(|{>iQ)OTbk>FMh70+2ITh^XE$V{~)r^x(Uy#$F@z}#|hN-#E^ zW~GGojj2zhXv>cxAss8JmUHDJ4To+@Pj)cMr#%`{cmi#J84pKfpMbpBLRy(@6*O;p zZ>GKh?4<{H3BFSnnp9^%E+<{yRui!woJ{pgZwuUT)~dK@^WZKdbtD2@3>ISEgbI*z zd(ZG0jeC7WBws);@QJGLVvOr(XY?u@F?Wx`qx-|Kpm1Q|`I|yD|H^0N9i;LH8<vrP zV3A9CQdp{E#@fXpFV(}GNm*Iz)W6zga#gAB>#a&h<d=#(PqbpUD;ft*U8*248uHcH z9M#?`(=gzG(hYNszwj*A>i)POal5f)<W?k_;lNi_d*VASiN&v5e4LV7<6J^2IzBcU zIss4v2P`|2FOgBLJ7}dp##b=!6_SdCJfZ2UyqnQ+X`|O)q8Q7@vv_n1sA^bDKn-^S zb+Sf>GA?j{cn$1p<)-d=Tbhj}ko|qQSXc~Uzceh=PkDm;*P1x>Cyj*i>%Q?~M9O9- zB#CXY2V3Ug4qB8%!H%!EW<AbwCa)$&Utjwt3NO+2UeAeB{M8`-S^<mn(D4ZcdWM}# zXx#-_*`W&t`aeFVjZkYS|6)$$>&;mzjbi}_w}P7RC#n^!*KRk<qmnX|Z09N598u*M z3(AhHib6EmcYvOhJ}RTFQZ%k*V?B0%gW5rd{5j6{{8p~LTC_QqLD!^GQ)O~fEONTa zN`!U{^yH4md5FxvDt%bFInO#h5YTd3Uhgsz(hi}^O;U_Gk>2D6v#y4HRNbIbH0hGW zywTzZh$pZE0H8{{RGJofGq3MHg^#vzZ#jP2gejj+q-z0l8V_V&O=Y`Ez|DPsuH%jU zG?2pWSW|`YOeK#EkS?FN?7BFq)?_Q38_dh`Rvs(&;&TB`MLXauF1aecB`s{4K?yFn zEIElxx2G-vy_9dPZpG@W%Uvy?BuY5UHl{MblZj6>aPKu9ZanEfqFP#J<@pP+V02_l z_4Z1uPWma>wT&z5dHq2{l@d^-Gcmlog<%}K9ZFLti0o#=-rWmjZ9QAlQ(UAxReeK4 zX1RnG5?OoG80Q6kN!>m9(TYvEe)OI1`3d{+6?bUp%Z%0C0JyfkK>XTF!Q-3`7CNM4 zbpEtAZZUSOy6mUaehcMes(1yG{|MhOj+rmQCzcd%AB@<E9z3U3=ZGVjc0kQi@~|%! z)zA&e>D{iMU;fy+M_z#1JfRLethPRQ*s~%Q%HpF}s-VZ;Yf+oi&x%Fs(TcPhfH3C) zqCBwm!g%L|d)1$!xuKdrz82F<8p-6_Nqp&1l)v=7G<|Hs5<nVZxaJ7{rNa&7EYeb7 zUGa*~jN>7)(t12h2bM9Wx$5@oTCmwYzEu=}gRx7ruAjKxE!YL~yK~5b&s(V7GpS1o zXh>v<#{i<tgB*9p!4I3%Y2AU3EyQmL^-#u&x|!5_nIOS2I_g1=kOY!d0Dz}XSEP_y zng=U%U$HJnj5ERhTpYC5Leg=@#v&87OAkKaWc@Y}@s%4o^2l)Pk<?I^kr{JvZw2@= zPPLv!<>>(V_xlo3Jv4d+R*S~m3VbS?ztwGA!8=AE1Y_d9W=LtZfWvN-g9|5C4$?57 z`Xfh{asFv)yG|lM=QTgHYtzM@kA3t)QSbxYWz_9pfO9>M?!aHZ{){?=$ipRs(xbvW z^^EZjJJuQ(|AZ!1pb*SuhPeRT2JCW%*ZuYsKzLCsGMx|y(0&RxHszVZ6W;)y+>;33 z_m?M0v~Vk6eRe{Y<&ZE_=R}srGMGj8C6nqAgx$R-Fm8zLx3qzMHh8@~;>%tHUo99h zO2ZSBHrP$aXBppFtFqjZ5|+eHf39k~9C|<_<lt<UnndG+ru?X8)x`zAi_}e{qR(&{ z_yO8EnMbwT;z~&2Pn?vq9};J|>~A<p-#UOdHl^B$00M-7#!m)ydn8uo8DD!8C`cIx zX?4$|sYvcWcz;F5z~m)fK&OqNc856T)S)k0s2-@L(%olTny0;n(4G5pdbCjG5M<g6 z`NS|8T}Uc_cd=al?qoi8OHFR>;!VJsIzS%al-^+hx`9YJdiYcflE1LbU%Bsn9ZmY~ z7%{`|Gn5$Re&72-yg=Ji<MJw+KG-cX4+d+KO}+&G5T}W9WrxjE#U;|lCT7Bj!}R%F zpU2W(A8Q}0+0qG^Z5&fgM!T^z@J4HZE&-1Ta6&0A;QRvYABoUihw$a?Xy$pyfn@IR zm3(FunA?M`FP{#c4SoR7Wf<kTiB9P;e=cVl_>Wd!W}9}8fM^PjxJisA;wL?c207KL z4ol_fS2J%Mlf8>BSRk_s9b)}b#eAujFkhdczhre*Up9EjXVViL;Awaft)UuJFcTDu zA7x850@+#=MmOAArkjGHc|y;6N_qyF0RD8vArG+ua0j3p4_t&w3;t|Tk7C&F*CO>o zw8_tPDNSAk|HwmnE&3^c67Ek1EEV>;(NrrK{R>Wrrcr9#xR5xUz80NJ^(kedD8RTK z(&o<4x+J{m0IElT(4Q+##l^2%NZ3hBV~4neAEU@M!26tFc~+K1WbuHua*LxF^&rbl zi_$uTM`0)K%Q2sqwYM}Ki_3To-Ay#pR$han@^|;T*+=;f%;{wTpdHS9uVT%Q9(n7> z3A_FgyPoA4xsNEld|`xwTNS*=c+H*;ofapMz=&$~8&e8Px-WQYe|M>mC!hl(I*%Op z$HNR5<Sls|zFIb!m6nug55U}11(tBi9oVZ<Pv)&dkm=vBKbK<B1vLFdk^A~vjP#;S zCMl2od869tywu6!&&v1Ib>q~?zqh1D07W|UgTD><B=xHMMJMxU@SBr@N{&gd{XsZ7 z6-Z5<^8Jv;ES5}U;s}}zuvpG_Ru_{A4r-;ztN^<#EBn34`};EOHBIg78^PcL6FEoG zWew!ly9r0lLxB;20$R2d3DBK2FYCY<_5<NQ0m3`j9v7<i_Mp!lh*u@)>l`In9`R&i z^=HTdk2%4hQSVluekbm^MSz7N1?+@3E<v^<iqAQjiOyn#GT2DIfba2|5m-XVOY!&Z zgPsm*U89^|Rswud{2|g(l5VfdjE!Rg6W@%!b|7TIonh8n3?hqZ+$Qt<QV@T<l%qSl z&?smLge*jXg?uA*!?Zc{heq2)eQH(f&AMI24d<AQHYHNnpFeAj5wxQQIW_{Xg*>J1 zt(sggCeSpXMhZ-|kO0&em|eNgI33Heyl;sBahc}#JdAp`sqqwG!xQ<p#Z^ur7Vlqn zyxQ{oQwxznn7h|>rkx?`|H!6uacpsdH7EVSe_rIYG6$&vgCOL<yTJDXi$}1k|3SzK zoicO_^Y62B<SOPNVGlrD9*@nJG&M4DVjb*K*=uC>MV0xxDCNPyPqX<L-rn{w2l#or z_eY><k2AqkmXCfIo0?s=Fw(jmu7hs@6*-DX@P-{(u5tDWqy69mH7#+was|joCW|LQ z&v%;+oWyApdF2!pLPxwAw5Tx+ii5q4k|<oPgyh&=$(o-dG$ti*L$C%be=^|T?W~?9 zPTet2IV_*I@h8Fcx$KUE^n1oSc_1KEyrq09Vd+r_kd<vKp0p&|@bF2QU4zkM9ky%8 zL&cZM4@d$1>+0#nQFRqXGit8M@ej2uOy~pPPnL^Dyo5T)Xnq=j-)1Fv33D(x()<EY z&-<go`lL&Z83P^2|2uH@9Leflr>7i5UaliMy(=-<Z&l1dWqhJaO}9LTg7j~cYK~|{ zhgWe;%%XBlid-(Gq>{v|fpTW#_b-i54mQOE<_N+Y#xK#Ni|Z`C9()U1!Rz=qDuy=i zJ;YyYHv98x1hD5a8j()h)@|{=`v>pooAk1IpJ=Xb9hPaO&wTwcs`*rf>EYD>D(sZ% z)ZEaNmjgv#%R#@SK+h}<BnGv>sFpO~D2p-8?m89uiU3icwD(Z*R7Y=GdzFnfy;C$j zgGJ0YP9p8V2L_GvFF8rw85Hk8o)5}941Rcc4^Vo>@Cv4pjD}1_QPRDtpO~5#R*xaM zFp6>Y0!!3`YYyA<QMIQ4(0a5JHDM$n8+eVDPDdm}1wAJRymihP;rLEZPN6?1ib`B@ zj>;V5APpS#n(|&8CEtohP)M{%0LQ4{%q<!Z4>Ajgn;@~tmZ87LtcGNXPv%NlsoUE! zM-ED@M@?1^+>X`gj-oB~h}e3n!2&}M&H)*N8}=i|4DhAiJx-!s{DLtWd&6a}@`pYl zD2Uo^MM6{BSaIsTqk~*sUsS|fxD)ul1*TW=!|q04W3Hw1LCS_H596YbWig-~2zhEb z_&bDdA*;;vU+W-aL?%JMN79EI2hw+V+S*32dx_$!&nDg`suFzQ^fu<8H_ho(bWB^X zr@l(LrH<|laQAl7sbNW%2j1~rE*CSiG0bZoJAnUFzx~3JN3n1UG25Dpc*xF|vy_K= zRE!6)_DPe=w)daEdVLx$=FZI+M$amrwHimVJc+bMzSWF;G4~nWY|Iy{Muz&k(e|A* zfBn_V@V-nY<`OrleOE9<uAM4}6+KElUdS7RrxdEk59U*aLX1cC@(6TO*|cZZMw5#e zjMUD2vb31LM}&lal>&~C7g|1l7Lt$9*h*bR=*T6uck*?cm{3iBcGDEj5P)s?+q~I< zXUBYB%K8pl;9RJr{!IlYEK@Z;X*&GC)cBRL?Gy17U`gkV`#Y<C;D3s)>bd;1Xr&(k zn&u7(+~iRZ$-1->t>8rw*IMHcqF&FcYUfT1{4IT~n<Lu>cP>C7Ir96FEsKXI=}k1X zF#+h~{}?*&c&Pt4j(^=9cMj(c$#zDZLWjuih@4f2LPkF%D|?h#hvUvZBU_!lXUIxs zR%AyidyhzomY@H>e|;aH$LI5Yyx-6F>uCc$R^x{+6Cy0CtCm)rAON#!+GN`(Hn+rZ z`1}k^yH~xh=m%`y;>&&}tIz)GyOD>h9g`EZrPv81M*~+P0AyoXBuzeZ)AxTQ)CH&t zzVl<;muC5lZGn6i5?hu;Bt2$yUjKae3xFogMX7Sp3p@yoJ`oNx^U4HQAyvW<O5XYh zs~QroJmfF3PI_+Xrbt(tEZvYUQi!c+cBvS7xG#nmg`~A;&wQnOaK|U3s@4mYpji|I zQZFm7u}NW%<_S@IvGR#_?%C|a88_yV+z7v(y4$bbOnc75S%7yHy=`Lm4S$~ca@+F$ z8fEeUfKc=mq=$s-f#v>a=kK(RSNBoNIQbvgd+bbnSKcgqQR<y{=He8l`u1J)jhW=N zJ?}WC`Ka8ayEeH<j{XFzR5h2C0))4VTtHn8dRQ}{q{zBa1DOZHMGOnH(^<y|2HfYv zzY$K-ZvDV^p8Jktv8G;59{YLAIBX3acSvWZqN;WI4fpiEPhS2y2}4+h#Z6Ws%nTis z!F#jGaeF6I(sd|D#-=s2SWW86-P*%u@UyX(k?_#Cj~g$%t?X{`M_v^{#?Un_c&7Hw z*H_pJ$tJ?*kr`W3=JpJ%kqd~ZBlWHKISjv8==c{m+4&x_Z8y>(zpb3oq0L8WxX{fF zx9cy5zqI-O>fx7g8p+m(<)(v);#rA`A>NO2!B~&yib5Mb8ugC1@^8cgs#})R7hYTq zR2pVXBuiVjq+Vu4e8N<(s(PQSltk;q-_!R3Aa|p$j^t^FX~eaNLOWPRftwNW=Xgx+ zwRvZAg<jW5p|u6K@0WndNFfE)>89TBtOQA7>dCj>>p_k@3SFO)W_5MU_vb5)c2Xz$ zB&bSV2OED6R(Gx1`lw{%C-)8hGjgBUYdhzL%x=ereovH~NfJ?1eY-`spL!Wt9J~r) zaI+4U>~lZ5C;#$;RI~o_SmAwFZs||0!NWkhPf<no;pSrR`Q66T#GDGx)u;sVx$)Pp zJ&xiDL$6vDzQ=;r1189kW~u-&vqa>;n@vaH%A+xI_KQ)Ju)vFP#;+1yqqHJ{i02kd zS+JOw`q%!g5bZSrA-}`~`5NhV%VHvhFACn9UT}N<V+M??dD&De!aX3m9fS2evw6$3 zL&p2kuYObN>lR#Id|UH68?q1|cnmkJAFxR_%=RA{SZBT2;q|V1S}{pHZ~VKLu0XFT z7~Ar)rgk~2<r9cl<NZX0EE+W0xyIr;Svzq<GD?qC;BJ-ko{}c-xw1m{@6P1ZK(?vk zEKj~E-wMy~0g<VpE!>DVhBA5L!Y-qV#R3U{i2RvA(;__WRBkiTDLRQ5cuqESs}w4# z2N`fIOcoGL)eU849$*XVm(k5;8IxhWNjiGDeknw@UVh5Qw?z*V*i-As=(1)z{I-KZ z<y(AklkRz)Fwo|O{`QqI$4t>}NraAg?vAnGNYlxV-aS;_yE^ZY#Pw{|pxNykvP_># z_~wZwiq8W<84s%4wb)~^u6rGkyrGbn!va(NLK!0NiUFd6>W`%wXz3L}eMk?Wrs{15 zW91&N)`t^u+YpPL=Jm(lbqjM0L{vVa3%=)SCHS{xKrhuL#W`ijeG?Lw&?KGHZ!r?e zJ7a%Nn2yZ;OXSB`1x?Qs-nIElEpc1kQJxZT8Bv@<pXzOt^to{U=VEy#q#kqB%_s~q zcphkTUsTYOB66J2OGnV*A4OKl6}?f9hw`NjZGIaX8Ksk2lKooO%_DQN6pIf#<@vFo z^qqTMax%Zd8uR43fRb3}XsP7m=)ZO^&k$mzZRc3KvYUdBQZ|!m^SPJfo3^?_#b4OY z(Ai{9)L;Jb+hHcxQP(Ut;f|n8>R4aF&wJ4WW<hxwnt~qLY$PhZF2xm=tD{C0Vu+&X zBg4#*4Pk83A^p2omio!)BLb^;?BF9U?q@-DUL@C?L8}=%!s16Wj!@AD=bfndoBm<~ z3Y*=C_R+p9O1EtHaj)4*H(30;5kf3V8Xu|{bDGw%qB6}-4tL!AV7pXX<y#>c#1oKU zgW#kr03DQUTwdRwCD9vJVLn^|ECNYJ36;nd`8OHEraV{W@SFMEAI<rc-yLWk8usDC zHs31k7`3a`Io?im(Yd&D5TEnf$OJz?M)Jv4h7CYOy|2U7R`vxW7ErP}G7D^MC1<dy zCSTkDuVyg4BtsWiG?!V20eYwAo_0Ks33}qmcOlYa>Wa%e=)BT*nFv?hh<aRIn*0ut zB}vNw%_$V;Y(>u+0ug4rHi@<;nJZIQwWD==jP3TQv9D*k&p#@G{w}$I{3LY~?LWpu zEONRAP~%Z*V|?pNp>g(~G&IX!_TyqtZOQ(ru~~A<_@ZyQ%#Sv}an;PCK?_E#+6wgq z#U!1p?FR^p`fk4I0UfQr`)QP&FoaZawDA2rNxh_HUQNP-o7oQ8`I0M4bEAD%aRVJy zq;<@p;#^HqBd$7BI!QZpu#Qu7NDlcnA}&T(xg|_0LUBuSl}InLSAcSGk?{FOV-|42 z-%hZ*Ea*r_zWk4v-ZZ1Z|AhIHA8mQqdFMjq4<zFH+_FeO`t_SLGZgi=O6{*^eq4x( z>Jf1<=e;Zw#!d;Hxj)hwch$VxiH*KP<&!PN)X4N@)@QWFQew0dRW~_a`2yx#+QicF zpnt1*xQ&(z!gs+i;oD4tv3qFzsn7Ry&E=>~N%DisOe{W)h0nluym=&jX`Hg{gE}&! zHmv1wjq;qEN%2W^{b_t2UQq+Z>B^>hm!I9hE;Gjye#)DQ(}!_+U--HQu}l@r1@q0X zFsK69o9LVChFw0oO2mG#k(83!|6I96VEMCn>wNAXn1leO-wU{p5$NftzJT%MzF@qT zpdyl7UDn(gFdELI4**LTTZFfbVatik;Gd*A4wzw&xL~1_8r3!#Y`9_o4!&g+UZ~PR z=wkWi4}Egw1m{IZ<jJs>3H}{b*A_c<^V3k@l^tr_XGL9k)|dEX`in@vjq7b*y2jSU zBFgUHg^{bVYge|n7HSJlnW`vC#z}95rrYEXui$*6E`Pzc&xeKwj4-<jv>L^0t%6mN z4p$t*$0Z&YfD&T^GpoOMQr&7?g4CmVcv6j6n{&;3-Q@8VOGVMogTsZxDh?Fd(FmXK z_V6W7Xa60$BsZ9?x$V91KYNF1CLmhV5eB8{Fqb4AZz4E%1?I;DzKPC|*E19t?D@WU zC;ILU{#9DzjnQ{e*CxA*<T!4>lIyA#@14>gzr7xG*L8Qzx<^>Q&Vci&A=T*@Rbg%W zi;D4L{9~KJPjO<$MK#xBNMe1#N?8_DH%qj_%vZ#VbGsFK2#8e#_HKJms$oJ+T$=1A z=5=DXR8Qhu!iQh)PK^-<6taB$4R?{3y%{=csiBuF(o!rEEMKt>8@#Nf$|Kv6Gmagi zViY%?oM)Zk>fbcnCB6n@Z-O4H`)@GOabBR9T;9Lxy*)M9$=wdgWfl=m#CGnVwf5@_ zU++C6Kk}na7RD+9aHaOf^HyI|D(@LGRZ1*jzcGK4W1L1KWMXFOS!6Jgs;aX4x%EBc zf|F!*X(1TLoO1PAiQ9n2H@Jq4)q4E>lbAaPeU|+~q_NySUC9*IXWdlZ6HJ`imlQSe zA4{y?H<Hw@O!wwW^V^<m2+4nDNe+y=`B8T}H_0K!;dAxZkLu@J|57wFW-tT7zxo*j zifW5!t=a;nZ%^Om2;RHcnhneSN+d7-{P!<k<09YQsMZ5^-BAmp>&)HJA-R&mRn{{U z1bfx&MRbU#Qcoz!VL*A4t2x*_+_I#tx<iqd4prC$3367<wqg4Mi$Wz*w?tz4N}&(; z)kArh+_9I0>7XO~3<Lh+E0?(6xU{hSY5$s8xi8BQRHBhaYzsS95N=U^)8ASlqW}PT zGo$>W1ZI_m*N2A{{z>QEUqZR;<zqHV3dhJ_qm+-gHA`g`e)ur#DD&JNY-|3F%ts5J zfqj&`TKn153zY0?bDUsoY{^M9^KW>74e~7RC7BkbNQ4G)seaTuyNls#de6w|<m+1P zeH~opr!YvPKRc&>YoI^)zkcksm&%L}`T4lX-c8{9`w=RH;){}9UWXCh*m7U4^w2sn z3Ere@>5;zs^f;$j|B@HN%#wZp@o63xKnLw@Vb^<?@TU{(-o)Oi*gM;m;+39aAi;V$ z`>mk_CZvYpx;J8WoMTFseD9F)XL9-?A*%UO*Jms_m=<o`54{GUi}yPlvsBrx^F6-O zv&_rXNsvk*LKBtAMm%cUG0flrG9=^0W|PphC`s89{?IxJ*K)aK-loglTt*eI8g1Tk zr9iV>o^#lzf%8>r^0>}6Bzh@1&%kW)zOgFk7MTD>PyAcw1wQNV+=3Z3?)_w~yBxx& z1vj3%c4Ssa`uCR<HTM~MvxarNa7zc}!E_`~TH`P}oXKqoSf~;qTaFfKflBD0USN9( zRi?f$2pfE3A{Af`wucqIyQH`2#TZfpxyD7g5&SBS0{!MwJuigt8I=yPAq|{V8_P+M zuo?aYs8Kf9Q(1#*rQH6#{2Er58k~LGs`na&4MF1a2x|;NCD|J&S6-r^qga3$&Dd;& z!NFCcWxeu_?(<m2icu)3j9ipEklGRb<@kj|Msw4oz`z_!2tfzRnDzocoWC*{+%LZX z>7R~@9k*Z*GVksP(^#@qLLC-l#~_rzz)dIRc%gLOr7~_wnHtNIeyViqDM4VhJ6vf$ z!lNe1Otr0$S3JOcfSk)&Jcj4~MjvFZ+h?!W+$MH|NWO3&_gRQ5R8!%<`tS$k3U)2( zA)^e+gOvluhKz1;jqEUkW)&?sbdfKn;CS%WEaA^3saJm@FVM)I<`=g~h%cWaFJNv8 z0XMBTyOVO6AJ#BX1`MBXvYhs(()~&go**mR_6I7FPn1Qf^Pn1x*S!941yM+AoeVvy z;#Gs>ok{55+c~qc$>Gi|oVWR-m8)%hGk(wkFE5er`Ib{+<i%%Ezh?&ETCgllMJc{v z#>$B|2CN@At~*b1{56LO9Y6awq4IY@;tGwV=7i=|x)6ks4y0W7J%vq5TBlE72M?$` zYBSy9JxR0WYUXXpfmoIMP2h>yc$gc1I34-JaWg)S@4@!?REE^UWF~Jcv+zM@LR4`X zFEl7!$el@p8b#7aCx5Ci@F(6Vt~as&jIN;6M{i}^$%DL@xq8ey>4t<T&`1tKDUAUg z4~}d9{L;K)&$^ru#w3$Q2O_hP#?9yjR_UNh8M!~K%p@9^uJM@a@Rj?d-}x^cJmahz zmt{P3EMA^$^tB#*p9=NpkDGvXCe<3b)?8M!;K;Uz`gkIchSSd{@3dN)=f%ox&@`7% z6hYahAHOjW^Z~CL9?b#9<y?|Yr|IFciO9~o4T4mVr@q1I1>RALmQ<42${d9)E1VAp zmAeB~_Cs+Pr^iQJ9vdL5z(`6|q_3!XkPJh0SZn&<4{Q&g{|1q~XZXj`)vA>zp3~)N z)<OMgJu$sAud{|ZO9gal`OwiQfrbyT!|TZp!Xb*#a_3uOoed&3;clL(4Z9gv`DB9n zm4bE|`D+>6m*2gibp=ycGp8)BSXpo$UhYbd#M46g%x6^Ch6J^$C($6uZ?l`U*!g}k z-iGAu#1t%=j9%1#gPt?Yjcr#!zI!ldzZ>}&03M^^V{rm~`q7=dUn2EV1N+IY6b8Kq z^2sy?J^%#Bn7P=Ca>bNQqb)-t*gI;@=i{!?PD4!caZ^02=B9Gd>`{=<$GQhV-p;#Q zo_cd8zKq|lw_L73_;4{iwvm3bY7G=+9Ac)_nPsLylNlm+Ly2M`HP%OzX8{DDmoX;s z-0l9_XAf}b<_aypvk1Q98h}ALc|fXoSu?DGyb?O}IfU^)7{o7K`{RLS9|#(7GQW?- z+@;MRzbw9}l>A^%UV}9oe`KLzr0W6O<2k(~+>&whv%ne%KuuMa_>@tb5XhzA-N6b4 z^9L<NdZ!D8m@hKQv*&Zg560cjUtrp2Pe>3Nze)?eYW@PFhCqW#TvjMABgh`Bw(8RG zZBMAh#(tcI5ulx7(4Tg%25X;!B@?8Vyyqy^q93v3*(&324lsw7%z|7*P|nqoe# z-Fo3mWJH8BCTY2w=W%Car?1UsNn3n0pOX``sX1YA&R(T*m8~@eUyB7ODKe6SgZa?^ zgtZvntu}@{qs@%|ELmkL(tLGx-pf^e2FQ^?<fJmx&}NCe-=}`!8gj2T<F>=k5>;<g z_MBfc*UEC^>&VjK2oHBgt4GQ~MhcI09gkpS*RyMHD8+LFW4U+V$N%h{kIrOEd6$sS zExm#KTW86<%Xo(Z&PWh?cRRelcTf9^4Ck`(_{NJLeX`Q=!viQe@2>nQib1KsS%RnY zgAI>IQTVY)ee;doW;tIPZ11$wNnp+C#>3{w1;HZW=vj8{90%uN_W7r~y()@~#w@H_ z!mzueh#esp?RG?vCn3z{O@&+B7kjwlW^rz6Ni_mbJM3zFNik8vT|rZ-%s2ChVn7q5 z+|KDGwu>O0((KUCVWGb*$Nk5K|1>k+6AN`F(mRbt_M>8T=|!_sU0^=W0i%%zO(X$D zDIo_}?I*JT<uSni#Q4BSyrq=UhMnTlhf%Z29caqEe*1$G2Eacu7zTy2?IMdXF~pez zm>5IAvr&xmte9eM9gKOYUBL#7Z;H^v$i%`(S1FJ{|4&~UCz|(qq&V+wASvjKaHSG5 zy1_P%IJ^tnUOzRpF9yEuKfjUhPmYkGsCHE8P)N?B{8yzsN;zSGZk+eb-sGzLNvd0Z z9P^hi9(4}uZC9Yl!@bPlf_R?TPiNZ`jyr0Dz5DX<9>)x~Di;`@?v<EtF@3$?TEpV} zj5++6Av)j-%c~tfX)lfs65nnfgl+fiiMnyV-{{yH;i~rHP20^7W%}2404N9voO*5K zLZoERXQU#oj(VWyJw<PM14of|_TIZfGC)menE%pXCO0+fZExz9+DK*?Ewm)k8~wgX z^`kdlp*VV)a#=Bq`8@@JB+A#b!at;#pd?)YqBWBCl~Gjo%>h~_emI3irJoMO87KFH zzCABK>@*z=?x#~_Kjbxw^dvH5U=O94Z)2um+^A?a3?opp|7IcLP0g2BDg-bBhC{oG zLucmy#=MJ87k>pIyl|WCh238u)utPSd0MMDB;b#I@Q#~dUpVe^6?q>+Z<~9oKk*JT z_mP!R3R5JT7FPx$y_eIQ>;Ji$oG|I5qwgjlj?Q9B#X0U^#q%)U0t}DBxO#sN!kp`O zebd3hgr6Jz)wbfWfUl9m%#Q>bcQXc3T!@iR)3K5Fz-Xs%#ctTOeI`CECGhyO0XbHQ z%&gHtJF*Y20Ei05v4**j2Ocb>^U=(MoBo3oJce>@h>n3$eC=2+yq`|^cs1Yl(Ua3x z6OQ|jdAT2<!N5~=tJ<n<0y;`z<GX<8msosem<^4MsiXYgXAg0T8rQ>q+|Ot+c>H{d zm)Z74$1}T~@79|>v6YE9Y-AXg;XMOU2^JdW<Q|3v07VrmagN*au>blawbFiNe$_ln zVrBZRp?<+XEZslH);W*}bu6to9j@?2vpeWiit<3SJy3JcmCC+SK3-r}yLXVUI(T(J zpDZ|kv5#U039@83c+f^kx8d^K&`yKJUj!3%Jkt_>8q{hoey6?-CX(;juePlZ1om$| z51nM0f9v)srQ_fBQU})t#+Uc*b^;PUHJ&%q!X9zA`;XlVFPm+3_o(4g)%@b&%Ng@2 z-?+(M$nygjvWXB``ZAew_TY<$t4Mj=Mb4_?v|ZVIAKkloUuplldiJ_g#os?y^H~GX z1|^<C-H`~?+K}UD?(5*A6`|NPtgv>__YI*6v#&w}Nn*G1Buj72cTi6>;|(NCa`CYz zlNl3NWfn&=)SrS_F8X4OXb?tDsi-Rw6Gb;o;K9+JrIWd!{EH1{ewRK(+!l0M{pIH} zQ|0hpmKg>Joj~aAfipEb2*3gXAUFs(+ufss@!@M|o#8O{i&p(Lx!q)>h+a0nHm^5^ zOU~s}|ClX=84w0K&`Aq@R1tlIszj1~7d=G6H(U2*(QuZc&(^1b2{BR_TOgcY@B8|D zC`j-uLbsmII7}}C<Y|F*nJ5O={u3Q+DF0Ax(;eL#6%mEwRtIQzwy(d%)w{oM3{f$2 zw`zR6I6iE7{_B@FkLZ5082H!NzK%c%?v*#mEH^)-+aRc%ZCDO~FFzc4H~VeoJ?(mo zfMKTiIVtdKF45}@z{3xf{|&_(@;2_yzIwR)rLy($-h5l=Z^X^uCa=Y=0TQZ-59hNE zexaXmGbg|=tXlu!{K)IppH;U@v`!_43felv<|lq?RX?{o5i=~nJKuWK{`WVc!D+VZ z>Cm%Ff9Wv`L<pzTLMTkEWFZV1CWPc-0@Xy2*kqj+Be)z&aw7pP6#Wx)Bt|&IaK~mT z3R6_F6fN1fu@r-Si&>7nvS*_mr?^(K9Ix7Lu7w&JxVl8u;+%a(UZf-Rzzh_W!kDC0 zxi6#`o9eDUGjVV(Of`4ke2`}2EwPq%Kaz3vnN)pESEg�?gIoVzgDciMS9$A7JK z{dw@wrsH#;5zlavCXe$*E@dReo?W`+L=288=m0TE8CXaZraDA#7NtEZD=p4`a?z!v zAk1Z}q}V&tAycAaKorUse2TnO!AI%nWKO&}sF~Gvw6$H`!EkA(rib(4PR*?^HDDqr zAbsQI=#4o-lJ*t&YT1lK`EKK<N87uv79uZIy-Kdaf&oE}D?}VU2Nql?T`;QIh9R_+ zRUH*MZ#Mlo+Wz_mDCRD#v#=7{?SzRl6FG06MOT(5)ls{8ILurRdbu1c4&L%T-Z|() z6=TDC*1B5u08BL#5e(4w!?K@gDm&*pS9O3=T5iC<ji~<IIecH$=-EwUN2C;V;l){m zy8-OSuJ;5TsUMTy;Mtn5g;2N-+{NnHawZG~4T2x2ODVt)izJSie&`wenDgvr*@Q`8 z^dru^;bS$p5{c8@pYwA@y!#8J^XiIiQtvv#nWDk8P9($$M+NV-4}^33?c*N7<tBy5 z+#=NrptYE<505uXUZ^|Qg$LTEjuHE$e>?q>4{_UST1R-cvmc^jxiK(Ol!m3xf-Df@ z+BGEVP|yJu%yP|(=EJ-jC4U1Zy;}D^J^m`S4U{kt)j>iB6t$Pd)#^rz{JVdD@6W3^ z!=-CRPcBaG?}MNs99S(O`rJ><_Xtp+4R=<>K^V4(QFNU9^m1GfR(BhQTN{_%4u)*D z927tgtUH<1n|glTz;`{bueOcN%V030C}YMFSd#!i`kg13rG$jGoakVhi3ABu+9Cm@ z2K{LqRSo#GpnI!4T-0h`_FUb5)W0PfR0BiRR|NrSNL$8N{n~NgS%A3cEUvzdml<9+ z5&BoUB;M_V`se^+5_><uw?N!_U5aR;lDM@9WL;b}QHSrYAm^BBKyzFy#lZgUhQrm1 zAROx1MxLm+QX>1ukto8ul_pa%NF){nIPB-pom^!kIpG|pR6YoEnh$DV_bJjFBCMWw z<PAT{S{b)>a`N5P4pm(`V`7T1EZ+4e65rDMtxQtFh*5U?!aTDbTF4s!(EuhI4+-U9 zy&?`$ht!5$MK6dlV9470Hm*+Bi<A=v`lsp8NigSO?7HrNc7#{XG2e25!@?;@qzR4a zqjob<U_=myJ#5#Tru5Va2N>ib9FYAiVf(sr{kC3l%J%A4f4!WVa=Tj=K(D%~J02k5 z7WB$M;#HOQOO&rM+e`b<Wo9_=pJ$jgkLPBye<u?F$$bJ4o-3WjH9W7<JQsVtR4=XN z;(pXE^i53Z?d_<pAn)&G1k2=h&;=6&OiT1Nn$l|8A*vW9>EM|(JF)RtF4*=*CHin< zRBRF=2KbcuOXXgm17w<hopX^6Ki3M3ngARkqPL=NbIAvub^n<Ei~U<}FSS;dz!R$$ zFuVgx)T00X-LH=J*}TvJ8*U*adS1iTGDY@nSwrMe184F!Vy|fS<7pMEE@&~V&1T3l zdXdT4({3E(XhhYWB<jAXOt%agnj1v00A^=@CezPs&f=<V_MP#G#-YhQmxp%KdA!Ny zHMlz*kn?58&SdJw=cA(-U7y!Ge(S$qVL0IGR$8o2W=+h1KR6a!`F^P<qgNz4);nM~ zYo261dLC+{;QXuC!*5gH_6>g=N&KB>(ytqz!YTW3=7}1LPWIxP-G(mA&9ic{$By$w zq)>IuCC=<;RL)oCy^15X@y#Hp9eRb6E%zXvY_K9c*TXxD>pz$0vLdE(GH|t&l)$t^ z6UUtlnvck8BLO17v;wtFuSxAQaFER+c7VCBoA+9+DYOQh_M4+&Z15!nV16>}KXOP- ztcg$pqxtEhUOtB!ZhV9*>zYb;XWs%CE)X<ERZpmK;)a`gmcPc+N9v2N4sYHJ`ZYmA zG!&}b-Y{m0=&<zfiZJ|JfyHG`)jS_y9cO#!G}bcRG}2J@czFBX?_VD}5RElt!yP-` z-!uI;8|%`B&j9J)v!n5i^~Hv}E|$MP&ZL@RG!u8-AOGgaSB$_g*X_E+XmZRQHMSI6 z!%YC%Iq(Tdo_>iDNMHH_lF*iz9`>-G(?pjYlW@K$W`LOv=q#bv@I8p~30L|2H@>OX zjE<<$BqWN%Q=|d3=dIYKWH#1->TPSPK${nu_w;H%!<j)nC46aFIHCFZ`y3>{0RuGn zv%feD^eq4yz5;Aq?_8HU%=;SX&j;<0DAPseF^O8=NKh^x@&qYztgxe@CpgUm-B5PO zrhZz>%*!3R@O~N*JkZ;BV2w1{X%%u6Z2d%L1_9ZN3{OVGla{c^`6<hJCho_Yz&tXD z=CMcVd-(Z*Cxg6ABpNqKxx@x?52fA`_=ay=+l*oYQeI1oVPJy32S-`4d4~`g)wQed zf3c;i=Xo>W_>ON<y|z{MQUtZ7YTA+MtSjF#JYMg=GH1FaN<;_3K)@i5s=gu2VJohx z2|RT-smVjXXnWmC5Ar@ElYWapT266WNU|*T8lxBO#~~fy6^YB{fZSD@c*Wvh3GUcm zc>m_t+4A}t`w9en;EgbH|1|A;?kchy?Eb?3X=HI=C)xE(jt&Za3fLfik?pF%02&#{ zWB%Ba$XL1W_3MTY%YoM_1CUPjPVVsBH$$#skqG}#SuQCWF(iu$VUL6u*g#$(-Bo{j z9jzk^7W`l^AkPyn4+FLUp!}6<x=!es67~my6}0Fpr>KkLBAuD10nZT77`&Xw$N>f5 zjvgmP9!{7LdJTUU3^D@AtRjw_9A&wU4}JFtu}%#5PGB7;Fyj=F>u)2S{3Fd^ia#44 z72!xN`(6e6Ud5;TjPzRG8YM(gN)X&OiXQdI7Y3kUZbwK~V4tO=(AOFNwD2l2-JDX# z{wN;@FZP5Vi+MJ9M$d@De@#E(4)t9`BMmoP=ZWe~z*8g?PU~>1ZgRVu9#IBU)Yl;a zqhWex$i@Y@{(1LeqQxbD_vFW@V&Lfm3^E6&eqzJ=I^FfL7&6`yUYO<$HS!316)Rd# z*GVNY2r)Kv_^pY-8vzecE>Tb?3`ys+d=v*VVkLiYMN_Ff>1qQ25WG)?CNl5f!vMyF zS`((}@A059C<p~FT7XYdNT5#W&y67dF_uHmr>tCVGFYS>6=I`BfF&}nn<jEbU4fi7 z`|zBlH!i>nfu!nwZ*XWLPZa8=4#EKD7U;<UHi9M7BHYdOE}6lyY?yl=C&R)iFd@$x zt`rE0DWB+0f1C(0VzSdkIb)C@9Ts|xGoA&(1_Pd$B2C_gj3^>IYoH1?#65>37TaX= zQUNba!gByF)#Nt45;3-sCg#jEN{(Sah;QwW%639L!niKukeUDxu+LdON_o!}$1DT+ zk;?e|>;O5Fw441xOZoeqp7uh$M4Mpzj4`{%v4MccQ-4%G)`O;~ezth<HkI|VKPSB{ zC@mLRUE)_<166f2w1Pf^+QMyr#+J`!=Ap=ZNapT*zx5jlphfuHsSfhDDe=qgSb98a zt}!lI3AwUQf;K;7;d%k4BR)n!A4?#K&W1SzPly*h0~hrn1DQ|B*&Jh(G7l*tgnubu zq5(;z0q|TJQ#~WlOF^mLMP}$kVDT>+Zk*Z4)z7TeJ?8?&2#<gTnCb`0X-T4vd5+W! z_)<*-cq<K38^>V5Gdh!Cc^>}p*u!3tR<aQ*AfAKpG6%`9;w6y#H3fZ~X^B^nIinet z{UQ0D9_Gr=0W6$03LhsRqnjf=#QjYHpm~9DDkJ}sOaK#C>aXJ$@B^<5obTie(hZON zJQ~xP#`*;p|5L|xcOahT3EycdT-=1OM^e0gQdm!OJxn)fs%1qVg`QY$6`dAA8*wp^ zgG}c#CZevpxIc0W7vUa-OdEKZ{(<G>Q6!q1#$D#S<d~lqfGj{4fW?soHD?e6kHv>P zOmV4QAaXMU3Be;jq_J*bBht-SyCjfv)PVhyhu;bDe~+UVj=XuziXvT*BA8TqO!*5! zj>1PuF_6@%%%fTZjVQ|w6^DCo`F2~J6`)DZA4x}qG5~kBzxl8@5CN6(AeklqFpZQA zC~<|RLrPzKN@IkZfq@RsrAJkEV|n)+!7(L%)w7QgxgJs<!^#N(tcgViT)}}G1xE`7 z6^((ItZJB0`JEYLX;jShg%|pdNsv>zOg4QUHzYIqaq&Go+@b|p?PQp9p3J^j%nx^3 zTBrtx225r;qWbF%;FYWtCSl8<y<fU!yr_S(zVKpj_w{7yte2X$Q36nauRNl#zDjDl zs2T%Lxrp*o3T2@LV9HqsTapUbpaNyA8#Yx%*hWNJkvuL4T-)G)L0U5bIXJ3HV6nXl zNAygDWqD#tCQ=wy!8TUGV2j|yBUWBQPN+%C{V{?14&Q88C7c7!z#lJX){W7)PsPoq z7Q_au@jRtTDuxN$T-az1FXe7lk!e(MEU;N@KKe*x=*$)QU4OT+;`Rm$P{Xn@+EQ*- zCgl{?UG}>DYH@5<RLf~OGKpHMcCpPC_2_|9+hu)@RsRfPDr**Zc2Q(CR3>AqHDbUY zxmb>D!NKdC%h!h3-Dymw{Z*)gQuZ+t%87iYyPrfe=x()HJgTM_LckXps|Xe8Ox~jX zZcPh@#QrBtC}x;1Gi@QZiK~rH5|td)w3+J7#a(xwm$Pt-<-3a0H*5q0UF&au)Tg)c zemMAcS`^4A($v#abKpsCS?8r}cEyho%SBzRmaPXDIra5e-u-qcu%wR1Ab(K<{-mQA zV~{r%{Jm-!&g(RP(Ie)5?BUK00i%jobD1<Oc^;m<BflNa7_wztHp2mF!-gqM1vS;o zc*hp$XZDzIni1`8h5CkWP%G^r=OOelNS{`gZ!r%LPX0d@SROM28w>TF>&>a+tYLh$ zJg7(7qfZeg>L5BIG_)hm3bpR(FS%9p(^8ae$KF~JIX>4;hPEy!xX1FL?x-SHilMJ= zAQfuDZkQwMREL-}LU&6uzhV-4o3gIkb^ct>y|q?7ghnnC)jO=>$5c@ZQNf^G26e*Y z7J^41sdMLQ_c$}EfRE^;A2a&F{by}8B$ss#$NGI?*i4M|Su8Rg8r?|@>~%#Axgz;y z;rGb69~G$Ac-CJvG2tJhK{AXEjCG*I=x}Bp4ovn6nDI8u$vn01Y<>|CjJ#RSI*#-D zefkiECq5D<I)v!-=~koyR$~!5qi)+l!ip&yr5^W`c$BS>GRO8S9l37;-se0-Fi0Rl z6!ribSlJD^Ki!ZHWU{bK!ew3@w?I`FUf5<tgsb#!2aQ;3gce6XNH-hSD?u24uK%{s z404-lwn7CuJ^|S_g%D_wzvu)$Gs^#-u&d0?cg;9=>}yhy?D98HC6iHVYuYaHY=js^ zY#h4yc3|Z?3!6D&)$@bq!$RI%D4NQ7g9Z&=_g4vdr(sc={(8pWtpyayOvmMZcj)zt zD*@@q)RJL-P@K9Z5z!UZR;+K&HdEmxg?!#RDeTJr&#_4tAjVLcbo%?JW<E5YhRmfn zBiAgFPn$eNHz@KfoZ~D24Ils9@IS-!fZ3X)_iD&-Yk0$F<PV2_zy<_t%vY--g^pYG z(-=EP8B`w5M*saB>xMkQzOv*=VY5j5nm+Hb`vurXtgy3iruW`z{6e?+nZ-7%PYL+| zU_4(wtkMTQc)NfaBYkBAT4}6XHDuUN-D&&Esm;>Wa(=dK#Kp?{UOC-^!^qeD@RDG5 z87)};S=GTcUIch3y3|XLAP+MJoCw+DIV|IZ$PDW9&7n@Fy>rhWva<P8zo0|^8Q2zQ zvJxFWGHXOM+rXuj*BCXZjRdBK8lMJi$<m|LqsaVw5q`q|KC>ANW}Fry771m{mJu&f z%3Ch>p8qllkty?xzyIE4fD?u~)1771ge18mq2-BB&BAF^#?6Y%rt}vj=6xhZ<h*CM zdu+hvxV}U5AOsa!c9BJ-p;Egd=(FuO#E3Ob{lA~^fzHiOn$~Z8D^VR;NWX>BTThUM zNM_UmqpiVvY3a_=81*v8`4th(EcNN3y>ml>$if&q!yK=tsV$7}P%R6F*Veb_Yboh4 zpLvX@{M}W?PrKQw5qAucpyB3h|BSCv9INJt4Ijw<{_J<>do=TbABKBERwzD3pcV-~ zmMZWgFjbXgGIVb7OU(U;nJ&HvrIoPy@dls9@2K#-ND<&XIL!%o{b^zPTxj_^3#%gQ zCSeaQw9VP+W}u3kQ-sCrkML{;iKcrwg+wh!EjIooG1~e|zn>f&;y3IcUW~iHGC>d0 z_{cdH1qx-lC5gIRJPeh2J1Xh_g2t3wL#I3Zl`*u=>=ufhmFFMxcg0BcMeH8CSNHc3 zq@4=f*%`Sv7(Mg2a83tKZ}5D#F+}0gPso3$$1enu|Fg6^C1%{+K`b7ka$}$AA-(z% z)l`b)14!D8zfLp0ybL~pO;mIij}KWp#eIE3U()qT5#CIDtY@|^is{R;AUa!888%P4 zm>4apkuR?aFL&e~ArTJGQyLlq50Pn8D(vqbuE(FIwVWcazjsC6kMU(pv=3mK%;-yf za`>q#!3>2zJ5CHo)Ia=-Kjk$1Z7Y1`f=?4OkLPU=K;ru^IDno-Kr5ZFs2Rz^uTJ7J zTGEO>Cv~qU-RORg7q8lrD|jRkAASNKOoke->ZP(6A<p`_G&NxD9lzGBu{e<c9CI+= zDVyvvq4(qGdq&`>%23HskKnnpbvr?#^j-vIT&zp&M?cHEs5_FAHNf~e)qGY!Eo5yl zz5&C5GXfg$IeFVieCMqfTx&0tsG?R~5iEj_T5d?$opsRY%#D)|?Bgywb8=|m=Vy~m z=Z&9~46*kZAg9LIgSo%EOjlaJnO2$+b^QoGg@P5qHa;!y8|eBgw<k<X+F;sIvi|k9 zP3f;fu8{>^FE;g#o8>X9czn_D18OWA+AZANN%JZnQZ2WI_9+Ul;&1cc`xpF+{{7Tb z#ZfWGaM^>?r^6g(aODRngh1Jij%ZK}D-J4{GAOFHB;=?9yS%llS<zMIs1QzgII6OL zPsKCENK0b31to7^t9_p7deob+Hq=3HsjAgb^SU12g=B;HEiiFex@_czNJ4%88;Z0> z(zS-2PQ<`7E#o@$x@_=nld1RO{c|*A0p@vPf#}P3q{h%b1IkWwDXrJ{_JlCgwE`&4 z%!;lsRr^Y`#La7k1#b(KPE{$_G)IM?r^H}S(MjPO=eowPt~}wP7DtUbUzy<C+`#aE zF|{h;lX!CxW@4!3a@du3^bY^l<V?{cclCBmJzD#%7Mp57`(2Kk<~i593w(nsZzU|+ zXmjd%VPlH(DFOp)W9OZ(IE~u7nHVBC6XbeRVjmgpSa=l<LFGgC9%8ceHAP=)UYh0q znJwQ|{&E@`;oZw&bi<PUi`S`kg^Jy|soQ){>GrAzZ*14I*^*hVmp<P^l<B+>Mz!p4 z16t3L(2h*e1NRJlGNlTs8Vxc6or)EGw?F&lGp>>yBjIe<?3Y;b^mxQ3?qr^?n|bFm z7V-i8;^~c#r8UNxqgna3l@kxVA#5k7lhQl0BTJz|DctR(GyHY1pzq&?6yHR^dxh}! z&CK3cREdqOHALi{_^Y|Db8Z>=Vy$0OwPc&o^(KCl4Ux_y$JW_1s(9;0K;n8uCF{=* zyd8huTIFk~8CnXlUXwm_ia0$tx1G2;n~=Tre5B1UY6RujI+A?BInBFg^YCNkx7w8l zfn1S(kHYyLhwRjFs`VFW&x<H{ycU1zH|AC*2Q3<tuN)U$j9GsowEOvzvXHiMUY5Z^ zVuJwSGKwuPQpkPfg&j#Pi9g<RPQ4@b6ZUxEUESKd$d$ojF~5|2dk01xMK0g6I_jXx zmAd)A{f)6%J7=>H?mobJQk*qv`Se1u2(01WTKjG<qvyBd9F6Z@>Wq2>!9`@4(n#GK z^2U9>5jo>&peBwdrwZ*8%>a0dOQ)<{7o5kyE+Fr8aUQv$6D06CT%-$j94nD=-?*7h zQ!=&qS00OVn2`Zb2yiy6Fx;7QbhzFfG1HCOComxrdTNbXAOTOe49kS^MUwz6hF+J0 zeGIQK%wZpG-I~DXMoPNYwIw&XfB%@`^o+sUlX`z*teB6DRR=SUf9-5vbiB-c>(^#{ zTg%E{$uy<FemseE7Ib_ieeh|-gS&H0Q4N0_bmdtJZvILSlYi&`_92TyYJKpGLMko( zLE^655<a&G&8=<suOhSmw4(5ieVA6@#y7{WSiEYRMuM7piKI8uWE(q`Yi=iJBKgN! z>6JgWN7va|M3byEnTrVc6@?a%eTM$5B<<tBoL;9|5>80c458MdL7SF-no0z(&yj4y zqP)D0%d)c8gct>hyn2DP7f+18<1Y*sY2t2+{Z}`db<KqTCY#H6a(sz$rRuG5*C=GD zOMjZ->}s^Z)XmIa&UsZa_a#n~8!r>seKzqag6Q1Iytlf1_TM?y>aJruGvd7sjrx96 z=(1jT&`<``=g{kYmH_|pU31Gn8QGgzzs2QR<R~?v-<R4oI}^_5?q)Q-2gmwI>Q(wj zj9RriCOEMDxOO3b>-0^5%Q@-|&f4?JS&)en@oTaDwI9B*a$E?QmF2HSJLg@vY@LD# z>FHGYcp|yWpl|VU1e)(MPDU~-XnlwS>ujaFxe1Dnziaqz_rRFR!`iI42>#)g(ro;7 zoo%g7E)pBNFjNhAII<vIE}4bN_c<*v`=Bj(7L+Tt&BtN*!#dd&Qc6}_5{gVRH*Gsq zdJz~S4t*29QWGmQ{b-AOa&b&X^z?PLA2POms3)K4ApAp^ZPeAQQ7|7@j9b`4pDayR z)2=w<N)2LpE|-yHrIAaXfoYko$jM?7mX5f%R*Q=$>Tv{%NNdccBuN*r=Se<ERD+<t zWb1hfFv~^Rt)Cv=dag#|>ie6~`3bUe{znvfwf6F6&5>>Z-;X5baM@><d#*QBaK-&Y zfek-h%Arfst2#NDyUemwB@msVJ}gpbdibY=)#R<`nnu4;U93)ddIJ;P=L6a<^Z9$4 zY&szfGFzX7U+#fs1RUsbs{NK$ZMHnzejo$Nd8rq3?mr!En+=r>cQe^q<w7oU=qPCw zZWzhEb+Aoc(46fu`KN^McqZ-Ocjs8>blO5)*eK>AAxn=szG7Eat8Ki;k&|7ptnN}J zR?}CA@ZR_^^InEg)bn$f@VJ+Pix55Vy%0TbzLs!+BiHDAzo|jX1o;0x3br!P=lQSX zDp%aCOy&>Dr-`4Y%TH2AE_#Gwt{}uDH%fHeM}*_<G}&QP>DYZo6Gu{L1tQZF835P! zI(rnHbc8)ufD(8n-QT_7^e6ra(vAtZ9j!i0LTkRwY5v*f9Qpd5l5d-#N5IVT{aFmm zdu_QafFdG@)=6umb4Xf4NN<>>!Aq!L82?x~$h_1zU)gtuGl*u(Eqhmfn&tX6`>Osk zh@)R1Y%I#eUtc}DvzNkfbLf4k)$XNP-=EK8%c&KGe98F0mR;$b=(t3&6P&VQZN}mo zb_Rdr>JrD8NM$M*ht#pv{#?0ic_~*!FxtOwBvI-6;CTm`(md5J+=aI-=r5d==}cM6 z$ud3Cr*FSjp7s}hE=?Gk5qX#2q_|(rmN#?hbW7_cTsp}PnR!20{SGA1=<e4)wW9?m z$3p{k7th6p*Vz4PKX6dOK6N2X>F<1+#|Mu;zp?Kc&QZ0&^ak)uS<-^K7yNo%dtE4- z_-4xH#mJe*RhhD^jCg~g*Z>h>Hmn~Aa^ZOP$P@Mbtek&a`5@8Q`)55L#x~BD*h3$B z<57Cv^q9lLxcAM~@`oM86vhyuXaiU0x4LM@ru1GPumF})pon;s#hj%m48Zah1FrqL z1Zx_o<!VC#8)34%C88qKJnWf=l$1x%u%@+sz%nXlo=?W)Z1P~H6k`D2u85jQ35xLP zV?D+KFwqo;Ky%Q)*(bq}Nnu#jG#2{lfI%<4NLZ!mw#!Q~{q9m+BaYO$r$nADi7-IY zvyZVE0L0h+EX%)}bO>xPy{^5xJ=ed(?C-Np<zMKvR0TRnto`($yDa-QY=N}!FL#+_ zdoKCTsGm)I6RC1NTVP!PxJBt%rzCj6i*NZB2b_6^xrD5;qqW93<1e-R@Zr)6hJjDw zRvxls;x2!*6L8>Q3Q9kpoc9_AxvXa2xenx%B)?s{tK-2OHRRN#k*5aWQQ?HMAaYm_ zm{_pE`4%Y7!bUyl;J9MI6Vy-k$BX{!$31SV&V{j&3CcZ+k$Sk6fTr5hN5R!Y$a<HI zYmx7+n)*|G<(RF}qz5~!8a<b+3p5(D7-Lt|6}<*t&?RqWDUdq4d`QvYS|xxBV%nJ* zC5+E(7KzNQuHw;3n1nrOt5CZFYje^I_YBX+zlx24vujW_u&{r*1?fF}4HR%glXgK* z>W)oS+4vhqN!YED*4|~n4@{r!3)ijCSv60MGUE7DN=6tAEU8qZQ1Z3eurQk{f7d*_ z5}inVqOS=nFZzvScJwj@2be>C5QI!n5U=C%o$`x4j7)Aq+8y>3h4SRQ0*R(86lFz9 zJBHFYd0i+9U)--~q!>Y<;QlRQKJvs`PsHUe=`FOfhz<>&ZfzP8$KHgv>J9$syxbg} zyH67No|nfoSRg~L&c8f3ZZPUgsgH_%%u$^QA%Y<Ql%uP7A7bJ;*j*t{+tEsB<G;{d z9vIwHdkit&NEH%lv?x!0fM(sXkCN#rGI53Jp7kOyq*}!Ym5fFs8+bTT@n@Ul^76%h z6)?NmxA`e(S6>Rf8fvA3WHAF2%n*vX;-0t;ht=@zwO#H8v0mfCb0iaD{bM5d&YNL} zBhIE@_Vk&&q5HmuCHtr%RhWLyE9D8S7cwlEE$>H9uW;0enODR=OG<xzAH@|MXs?Hk zfWN7MTtP|+pOc<F1DQ(LcUwlz-+@K(jJ%7wbqX!ed7`0D#iERn17U#fDr`hd3Lg-J zvAALqNyTtpLX;Jllyn%U5sV+T#pcC~s#j9pYl&d)zzc^+ZOGf-l5xx-@DL7RrYUTi z(2Fa6?Q^dEF(wFWs$tb7ia8F^R}ig6jlIP$-wNTrQP~DQ;FQpYDR_c`1!cTj)aGx( z!wm+4_U&t#EcXkhj1F%KSQ`T9YitqG7BvuFJgO(r$Q#UhS>N;-NPxF(niE8CS)z`< z0&68sm*OMiLRnP{uia82zn+^WQHpF9Cv;xJu%+~c$qa>rsAbF~?e~!XvkzeuhAU`O z`-3U+%z6EWaX}@@2S^mS_I>z1+i6G%^wDs(x{`SVQ_TDr`N45m`$zM-&hz2@5YzsM z@s8V3qu1K}Cn7NukO_E$jbPV~Nuc6Y0G1_0KdGn+yDbGXurY~5(ywsbreGsBlOv_A zuO#)eG_skabhFTPotr$f1-j8o?@0NE6m9GjZuKLnpJW6K7_Lr2RG6ZcV(&G7G@2L| z1YJ2R7G-!zCMDgb_~_h)79M(FQZizhI`P1eQYRmMiz~tu7U@rU8=TB5syfMK!04@6 z+c%sYrTyNtME#aigefLEN}KXDgrd1XwAqJDL4YFu25oMor5KAy%ACazy)n^z<<P1? zaa6DLb2ys*7QVA(L-Uk_;||HE8Nx9meKE2>#QI{4mem5-fTl#Ne0u<~CfOK}O6Vuu zET(2grsW6MeaDRCQO#WRDnAlUXz%hCKH^s_BM6=Qq7eo7SLv(w?hoayOktn$({p_9 z4J(Pr=L#c~L<AQyb>+ZT6ybs^W1A+dI#XDN=l|WmG@?s|+}hBHL|T!#;#gU3<=W_- zJg5!D@<DrV{!_en45lM_M%4Jh^zS4{N+JwSOkKD5l4mO1ScWVP&)~4o@czYc|GQ+| zNIN#sxm*Xud3iDM&J8#D^-Ex~`FsdpggZAqzG05Ca(>m~N){5UY|ganZ?kFwCV5t} zzfGoWa2nf8oSM{IxnQ7@3XQ=t^xC;E)k8k~wz|C@1HOcX-QtQnu%g@~e%Y6dzGR5H z%24+Te{NPnGRv<|$#%u#EXr&Yj2oq6!ct5Zl#TZ9A4yT9>jw$gL;*T(k)k^5eVc-M zhJB~1H*<@EIM}2XY!yenr1nN>*WSnemB0YQ8v4QFuUJosFQTUHVi=0zC^&NTnk36Y zSV^C|5>+tXR`Uv;)wwK~_KEhJjvX5+@LaYbnZ&Me_9YzvKt6zos<>MYM-T$#U2X%# zY3-^HR|-!m0f&QSU}tbcuPlfperbv_ZADC)0__ivgfXbZwMHs_2=`}=EtFo$NqqU> z#_44|Ocn=QFq)(>fx@{Q!$-lZ7?z&jqZbV+`LI>Pdz8rbwcf6*z>N7_+K2M%iDV4u z-h$3QLw%qrRMZ^CUTgX2_hNiOC6}L|oP3xpKxfAQDBM;tkOG@A03raShZo+WcrB8i zc*lO?Da)2gdvz$DJi9N$cy2vxVeM$@Zf<+^eTw}z%Qg4T7!!OuheTX$Wf!BH<z8pv zv%Ag}F%fqw+I*{YA1zy)YoC02XVd5*EsPN1!v$r2xBXF>j(wj_tv`ad*Toj0ERO|` zS1QGH6NG~8D1`0d9^NDZefGw-1uyA77B&q5KyQ@`W56a2?In0u(sgKdkkRRiD&^>b ziLXB-5TX3ulriPTSg;QwWTAMfsBTG>!DaIEEiS5=r_Dt$p@is|EX%0T<Su?Y-jHgX ztWN)Akv?&5@3tOFPBGH=2xjplZCtFfQ}O({b3-8-BZm|8Z?F-$<|K_0vaY4lHxuyO zNXys1t%0~{P_{Z$OXFMxeVY`LbX@CkX{4m-p6KoNdq=nj48U|xUnKr(FmIB@sK~m2 zXou}>hy>{GQA}Qqi`BEy16TS%$sXGMbU9q)*R^)=Vwy0H(z-wZD2*rdtk_=)<VLwi z`n&2gAHq7+zR2ILcsVgPLZP=d<9Ji>%8BXUJ0|n07>tJ+#X5>n^wa5}=72}}c_Duc zB0&QpP4Q)??`rU_HGoU%_*5KT(7Ea3pp}?ELkEo7d{Uvm?G~}KH{r9xcj2cNe$0EF z=RGeTq14xhoHs3Qn@}xpO9=2?gm)2aB5<4or$@VPark<6&&yLjr9ZZ&UryyU8Rgfk zUj8zvYNme8$#3<y{mSznB|j4Fu$FiFl#|obZaUT)zkdyFoSVquy-{4~iamme^sRL0 zb~6|pIk8(-w_Wr0IS!hCqY$mSX=%wteU@_&`|!v~N9+pWXQV16ujaNj)hkq<?7Obs z&?H;S0XM2qVJwLWjBQkY+{akY{QGZfFYF%SO5!h3Z@`?G{eN3`{T1aN|9gLi8DQw4 z8)k;??$}Jw-Hmj&f{4Ioh9RY-1%#nPKtQBKHeCwRQX(w^A|YvT{NDEu=d82Ne{p@* z^?E;^M$o$*nTKS=<LxG<UP0wpm|9<(Wi)NPRo@xI&EbEV$IQ7T#+oPp{p5_`y#9}P zddtS!?t*UNj|%dYQT$TPv5kX+YG(7rM+y0BUV*9y%}g?nO{FvJru?rQcuE_D6M}R0 zS&l}{Gx3~#dKDWFF$(5Q!x333XVD1N3NIa|qquR7Rr5@9T})(O@k5Qn+bvx(36j`H zU-{oY(B5&-v^Sv+q8(qe+!}X`{Ag;LO-NUa*^!kc;#M?NPwMN4+8}&TK%V!$TOv7$ z>T*zM=ib}HU+>h0{p|Z-^Xwg`Zyzvv=nR*s8ic_m>_76W3By;6z@3*~8>8t3liYfv zACqA3h)S<NTKf~Fo>yw@KV;UIUfNUy-2eP#Nec|{7Kpbxp#^kOTwRW-YQ%6JuPQEK zIhd##tz%SVNI{SFmy4Y$EkJ8`e-?Qlg|TRshk8PzQ}j@8))TKEFT2i+|5Yi%mtNa1 zgCXY60e}ry+D45zm|5C?{{%jiL?>X@;C+f1No7+|-T?u?NKT3i#UB<aJQF#>)~)_u z&-mUKNPEpX_<UGLg*?;RBnqCes5OD;iv6%S7o4rsQz~Rx4%VJAL*<(_`d$bxHrRC- ziOT!V57?Dpgns>)X873V`>`Z~Wt22Y6_83K7#1qF-V=Fs_RZe3L>1Q$NpB@47>V8C z$bU-*{>u7DO+(=U$V4uKlaO6~M394Pnf>W<ZEbKAeV@Yc6H;KUoUc^BCOf2+PV+W= zovjBZja^~@)R~uKqK5;1DW2_U10_^1bs6juo7MQN0v*Ntak(UxM9q$j!2=aXP7*<X zdLHdj#T7~OIWQxy0q><7(*OK<H(AV?uDAC2k2Nqdfg4NAw!|V{Bf3W(_Z;TQj@jl^ z+|;a;WSI~C+f*h4RAizitU)Aluz0@0h%NmZAe0)}bfnFNeknBsOp#NUorq;cdGlnb z-4<ji?MV)~q*fe3IPhm4S;@8)n5zmb@R*b@*V4}RDUR~#!yP}6;|*WIolDB2t*2n5 zHk7+NM~S~Ep!;Sogd8_8EmS&98Y}*yuS=jb`Zjq%$edQz3k4>-7|;1vxLdFy&GlyI z0f4f9Iy>DiQm8tJT7U-`t&_!KN=en`SzT2a>6?aRB#jlLzWq2|TRWjF(s=c{#s%H* zHA`2Z)WA%nxu4u`t&w%5D)UA81ENx@1+1cI+l=13Tt}XS&;~;H18FEU!sw@1=cW_! z^JvNoxOn&1`qf$MPNHV==zuYJDe6VjV~O4y@gEDt6f?{~z+2&+re0!p(Qnno<JS7& zjU2xuhh|qOVzr^P98x2!UdjaR2R^@~#$J^aJ<q34jFO%R8sO&!++jTPrQb{4)8z%k zHB-h8;wE}zKKw(+NXbt<vnDg6Ne|h64oKS29?o70ZJ9CEH}tOp>&nY5+S=FL*O4xc z9YP`E>*ba`UNSPIQUV8{+##Yr>Xt*^H8Lhs44aO!0>GPz4gr(D6*g?KCSYWkjWeDr zOm-(^BTc2`Gb*gpagdJUx7G3XGr!(h>YQ)E52K5os7Got((iya!MmI7pDW+|QAU~o zGnIAX(Rih!E|nNEfSTM+`?qe2e|jj@Wh=perXE$*^R%Lk{_~k97S`trPmGq|Ec$VG zh$QgonLrzsw^EE(i|$=!Q9YAdy880wUR%A`HfthnS10P==iSZVe^3eZ;oW~Tl;&~9 zH#D&%N33wW_8yS5iKl}f3~Ze624V(vqi=wb$kg^z71olhZ^0nn<x(8*&G>8O1Tym^ ziR`-O_yOE1$Wah&{xk#Dm9$BD-$qz%-qm0EmrGr$BnynL#iF5Eb0MX6h)=pD*(eIZ zP$4)hWY&^m6~#jFvUZq^I1NU;hG028FO$q_N%d6aVS5(A%wFA+wmTE=w<b8MG~1FM z-owMy4<QA_ig9Ddd0^+WV8A|4W`e^LChEGeHVv1j=~2AAJVN8TX02IyJ-qxfb>oJi zt=T2Ncm>fy6Q)_MIn}Cs!sc}omaVP1O;LQJZbI+wY-d~Z+I#rK@7KL^T+~tPVVG1| z2WI?3htZ5O{h$Itz4!UVt1~<_ZZK_{5oyrKwaucf96?e5Tdv5Yz$U5{j~5i}#BouY zlFEFOG6WP?WRAEet4_~AgFMB!_rZNCXwM7}=^<GKEWcA=>r~>Jxx=6Z|33=SH1j&X ztS2WVa?w7r@VY^+n=$P%-U(><FA(RKX~BElz*uidObLY8N@lXfByxg>b6=-cPZXKy z3V?C$S&%tv6n?PFt>DnJ<=67bo%2ZGVPF5XZFH4IJ`a`Q*c>C(s0o93;~4lZC4CIH z;9^*_Y<BSJSJVV;LA}*ZISn#Vz1&X3cKU9Pqtymta6v?clFoshTx*$mX&M8-i~t2o zU6Z<HXk;xTAMW*t;qWtSgGPET%H%{VARyg!1;atDl=%1f)*``Kmhm<=(R{m}=^;Ra zt4^p=#SBOj0Zwkn>rU3%L{j6L`-`K8$Nnk%N}}%_#ue`nr{3(l6bY$=A54!r#qBP= zJd<e^Ocp>on>tJ^3Uin;X6gK#K;XqMh10_l)Z6tlC)Km96#5&`2Twbq+|Mijh40Dd zK{G-M;tI!y$4t0qClhLG-#qEARs3&)DmkW&@1Q^wa5N45_{XPcFIL+`v%Ulu+R>ca zALxlJGz{7sWT!Zl(EQ7e5J(t@?x=y3YPDVX$bBA3*Q9z|Kg;Q;C{X=hVkI+$!YV4J zf+Je<WnIBJ74@tA_H{~a1r~qCWO8{#Gox6AtgkKZ*TMj^tsvU-%|<-Q_1kOFI_dt` zZc!ta<J=><&Ves1IsVcuQoZvkrN~L%e0j;?*V?Mx4a^UZ=i26oW0l{#?3sPC;P&3| zdmiFP6S>w7pL#8<Atpj2N^>Z?PY5=mjq*(2iDSXW>L?OYg@VG-nphW7u|of?O2vzA zw56ZgZIp1|`#26m&m;w$^6rxYwvP&?qiVl3bV8Gq5$ApTtUshy|7%~ajtk7u<&jE{ zfYQGTcb2)w?)Y?E?@b%k>78)({M@I2gKbWIF<y(t_qp@6t8WV;Tkm~4upTI1hQGMv z<2yby%wu}fLxD_Cm_w%TsJ}4|>OHld;k0-;<;v4XqT&7)ZZ$=>)B7Yc{9j;Sy43f0 zuC1yFl`N$f#YE1`{<WhDQFR_q^f8+2lClo;!s+2|nAJMkMWtrLOrH_+Iq=MV%znQ= zjmpj(SgEt3xEuQP>O5l`5DV|=@=YoRjY&%-Ht0X5YA^iAB~hBh4Fks3*zd@iemm!0 zW#7wvU%c1075x0sv3m!Iohz7GT=s%C;|Y_hL6_X<B(U#?p#nz7{Ga<4@19!y>joaL z{H=(_kkcn~^=izw9kJcjzRN`2BDpXxA=BK__DBa5x9`IaO)w|R1M8m24)ukK{xZvp zg26$>_S$yNfh+vPs~YgLk%qhLTl$w=O>A&4_3EG0(bp^&Ok|1k+_O|;+jHOO#)EQ= z&^~~u5~Uh#GPt1BFX9e-$&YF2HlqGy6dk>Q-aVbn%s<e~LY}VDyyy!lkMwX@A-wDD zc$4YeajxTAP9lsdtL?Mp7n}I`-?W#e;4@S61^B&;Yr3jWImFT!dCro*_#D9hGdjv? zSFAvFI&LMGzGBxY7tf^?yIO(7l+bb=n667}GI33li`B0BtmR!O4V|fBl#b}NDH%?q z7f?HcN^MsEo!;fEiZUY$<{^bT4C;7tb-dCA0d2!^D`bCR2#<l}>yHgmFqKed!9Krc z6^Medh|dj`rPNB1%G#ixh`C@`7W8`t6?m7WKY?wkaLz89IF~#gD8@I_G1sC@(UizB z1pMypP_z^~fN-xd7Q|9$3IBwx9=|t-bWl5?1}JVSbrBv7Gd}tC%)r8F<L%%NQzu0i z3y$_BEx;#xrOz2d3w^*?*pZzU0jO-Siaug14FJ=ivUN>CVwXwxZ*Vg$;L(5*DN)xy zE@0jP?oKScqK6xqG|!^Nqb-@J)C`i9$16_5YonL>V?a-0^UINVbq3~W(_}fTq4`JI z;;1`3M<!3@f-4FOQZr?Tk&J}vvUu$dQjEA^FieUT44WQX^748zNgTHDXA3@fby*NR z!B%B@U~bcG)AU|BP$NXn6$5n<*5N|7p@sdeKUb0dL+pf}kK?5yzzf|lV?ZO50)4@9 zot3e5S`d=(k+Xqw|MxR(X^fI25g=y}V~0^swRO5FsRA<!uCT+DF~3i9`5VTxR|d^A ztt{m+roJ9KjVqSD?rOZ*@~MujW)SC8kea2-<K;3{6g}G!PJLqs1#wWb122=|)Kdoy z+uUL~841yqY2fj~O{Da6982pn=dWnS5e_sSEu#z;ZO(Sl0$a%yN-@&$T;I*>#n?I% zShe#;4Gp*h7Z~A&RWWtB3Q74o{UF6aysj1a0?VS5X1kHQmoX1|HM|2HC}jSF&=QNo z_?IHfA+AhWxDb$0PMoz18m*3rjppam!V5WJ+_@aWJu&CY5L>?dlp`l~+C@#xYMoCO zN=frR1(o{8Isf!?+o;chq``hxU@<88Ndx`!Vf%nWi1P!Rz1&5BFYNT<<3CcP{<cJ% z1?G>3y$orG7z*41Z@6X2bknH3G5#B<lVVlMnh<XW9t<~N11oW4^APT7g9S<5&`B8% zKG6FcE8gICv{2Qc_txWQynU)#kgNE^QiXi)d32SxsI#K9Q#<P&A0X38y=PGUt$FO3 zAjUbz*3jC+tVU>^BWGYf^x{)^{Gi4-TI;wnxnNGUj~#Qgd1uM^Dw*A=GA=>6>zk zrTh>rhfuBo$l_)`W*O-oUZw_EU3Ub}nA&5t@Kf-dzt4S?vmHup`6c5#M^rZdBE;q` zJr1!VSum&_?d@`twG(}?=TRMhz)*KNhl*fQ-QdeZEzLY1)T~R&9<Z#+gQ!I;+4RpV zC1Ir&pA~O`mB6{ry1$~{FN$sW&>{{K#hm>9=&17!QgLm@TyQIBfjd2hO4&;DY?q4Q z9!f)kWC@IDC|Z3U-F=gk33WkJ{>>i{sq7E_tA*FeyQ`MzLdT#8YEf${4{9t62RFK$ z%)W`_h~^|?VVH;lMw9*J=&DOOaxE#GHLba7GwUBya0O8xC+`8Rr(Yox|5b>eNy~EX zK}k+8!P(K@yHML^s&pjaV|}u9OfoYpOHkAQqvZV3W)%^a)eF<TI5%u<2m~ol7*u6x zz*MqNiuFrls+H#l<)L6{10K!bqkL66i?WX%TOt+RuugUU*ZhYl3(=RByHufZ_gxr* zoD%uhnD9nJ26h-Oly7f%oYI;|Z(*FVTAZ&L=8f<nW~b~ea(!YwQE>r15J^wLwpB_r z@^H_|?4lk6wpmZThxSLSKj^nB8B0vCv>3h{9Nl!%UlK$+9BS1jM&^KUVjk~8(D$$| zP_r==mpmEK{LLATi+G`N4>-~yC$c$7(VsJwsv_oF;431)W8byh>LcA*6g=K8qvVCp zpSc-150em<OC^?JxX|o){{tc|<+gm%$W?xEa3p6Tve*3jGRgL7!8JeI7QfG4LSQ?c zPrnOD*?XbFCHHKLL`x0yY^ug~FV}5+`BWL)*^bvCV|szY@3`c@L(yj$dR{ElhXF{M z4VT9)If#vY+_OA`+v)kP`T9sCW@%T~l0k{z_~ISr2jzsn>M`V+i2*XjHLuq&s%~n6 zCAGUCp45HdKlmfHLe4(Hl%c~qv%8__+icpu1WmL}j`WE@<g-&cd?KHDo#v2ca<M$a zY{+hQ@Ge@h8K&Pf*Q@q?RZT2+hW)_y)7YYIGf^Mgudkakg$1>7szaq|O5o;z6HMyr zxgK75C!~|hahOj4^9w1h;eZxodAdasc)6kc{+<!CE~Y&Dsrn-QXb?BrJmAlZ^ptGP zKMg-{y#Ki}P9F^4{m%9vTfK+)c(EQ5;$tbhA2-ce%rD*?$J$s2XVmBd?s~2kix1r~ zK`Ia|MmZkvPXhEA^@mkpV(tZ3O9{gADV@_M_l*S`-4IPasbEvR7Cuge5>!BUFCUnL zkqU&%q3L@WG&|$?e|<M}zT3XHfp_adzwqEBX3Fy2&0!JHu0GE7-kmG|#84<b!~ozB z|00g`kJBN7&C757Sx-!fm~-zB)sq7kVQtjb%!ynr6=M%6E@Awh7#e$NFV;BDrRIzR z8}$?JexV=TBgI;8Um>{HRH}Bp#7;1Zo8l7SCk}Boh;JW$+nUtXJ*sS_4cC{NEc-f; zv-*3%5#h5M(=Yvm-HW6~BCKEfS1UHDN&N?^Fns}4(70e%z-f@(4P<{1GISWuEZ@^l zc@L~10d|M8B#)nj#WH10$Ss{&zt*!|^@NMH4X%>Z96vpirau!o%1uf7OCX*nPZzHs z%^%M6*YGpsnZ72kzZ=Ue>z9`FdmiI_c@~lpTeP%i3BwRMxixfr%jwq3Q#x;zUIxj7 zcll+&4iYj{+2M~U*Eem~Ok8+0QY4b{Z0gcNy}1KS&*wbY?c<V}_@;rY0}s#ypkZ#@ ze2S9~fDtf+weq;a4}ngw?wYlO!xM+7ja<!No0!-*YeRH=9*MGph&#=Oy<41H-D?(Q zX57UqEanHMAWko^xezyRrg>6#DT_>!5fy>=(j6+i_E}jU5#RC9bf=G?l$HtVAQ8{u z8|tqp;RMJE1~Zi?E#(O}^vBn)3nh-oXS}}eae%6n->6$K8D_ER_onG(XdeC>DaYhg zFDux(Jf68Te<CvyAQo~X1d0%Hc{qd9V=B^Ucd%fb71@c?VVpM^c0=Ch`N;)IilmRA zKhx7tL`Ntnr9N_+o%`~8>_NMf!ogroS{(d8)?`~AS1qf+cW4TIymdbcRqAs5lrcy} z+Ng8q)MYbzW-V0r`Nf5o<~+ak)o1T^_WP89ZYJ`f`3vh4Lkd5v6vWLpt%|1|xuw1i zGQ$QdLHkR3L+ovjsOX2h%F$JY=DaXvP1#~S8uy>RM=swl!VI!i{kXIwIkkZEe)sVA zPyNu%jMYJfI!bZUHny3(+0s3SA?IR&4cX3RamtO#e?Li}QH?G#U}=u$7te)YOpVWI z@(P3Q*2@ed9t9uOoGy3Lex>;yi4o+=%-}y=T=P}X;=j6gFHEVX<5{1&xr?^48uAj= zHV8_5{oh-VCzX?>&+T>ZT(5_+NB$gbHM-D;-F7$*-ofEqUo<^&Nt=DIj)Vl`bAIJ3 zP`VE?^L<sr^~fx+K~vHu{XgeaQw2)8A<o#JA=h(_kEGk_LS;x)C8c+z&X_fx<_UbE zkKE1eKNJ)WicB1Mq|d?r>`KaLW?zE;O;O*~yf_&7B3IYr{v_unMiu9N@rL&D&3#6? zPMjPTs;q}cZ~S)YRkz&Pd_k_yt^dO^jVj1hKNOu4;bwzX#N=5$t@isEr~BMNxkphG zdgmgpCzY$8V+H>xE+6_xbQ?1d>$Gaq^j>(4Vj_ORX2f8X>iP%E3)9}C_hZaA&t>U7 z;Br$gJW3QX`oX9gyT`5e7}E?<%gnzgSc}&}Aieif#m(Qmqt`CS4!@m?>iW}h7a_Zj z*Zst!ZS!wYE@T!Pcc4DRK7C?R`p`G&H!|HN74E1RUG?GeM)kS*!If@)FZV%~ga!aY z8taUVJKLd^)ec_L2qXTsjP^Ex$0jpKnaw9kZE2=*$!Ljo(rWbLU^3MfU0HmZ8L0iV zK^^MYw|NYjtvyNN+nOOHqr3jP=M_Ck7YB?v^xv!X9{&(U7%b)ZTE4J0A0P)$-4UjX zZqA;`2xNGD%oY4@uq{j@s)ut3Ga43L46w|aD{x(SlONO{519C>DcD*x8E1Zn$`R~< zE#W?Eh09UKRt~gi34D$s1*}_)iaSd4N6@--P7n<~`u0ZI7gLB6{9Q@<x<MDmS*7*f zAd~AjN9oHWo-THPSzLSaeS@Zg4dX??>}#h##gP~P^mgtB*cm<0s|fpVZ*{pq$><X; z>AJkCqKrb^ih1`-+vhRSi>Ob!Ogd1mo_bJ#ida>mf!Snz8XgzacATQzR1!+`%DA~s zdR43Ml_XDXYgAS@S=l3U;XPS=sz~i%@6xtNO<IalGLp<?o}!+ZYDnizarm8#b}5@> zJ+Dyv+2*Mx^FMENk$JEurn+y}XWU;WcLNE!K}@Ps^*{cIoYvnLo`4jFyB~;@2AdTH zj^{yWdAWr(&ph9L&eA9C8O$*ou6{6tfQWu+m>^S%8=4L6eY=r-{2qNll=w~w7%Y($ zF{L!C_gnflRYXg?xLIsOeCxE@fR-wk5GY?E(NY-x*bAoB*gDCJv_GqV22cEzLy*+0 znlPb4rV4U~3bTJ1(xWPD5iaVTPUKL%!v$AJM7S|ps>xY=wRlUIv|P>WORllPHS3Z9 z{25Xq&(m0hNQ)75w{b--rWfC(WY}L(0aO6N*~kZ6zQWIG|NE5p@=5t!Pk_Yb{({KF zq?xW6U)E7TT~j=HQ{JoJwWwrcY|-o&_BuME_SvL5u`!z(CK1-I_eXqQC3v%6Vv2xi zlR&u$AmCKkK`EwbwL}_!?4H^=6xUj46*%q!isKDhnTERN|HDirozNN!6nx=@q1vA9 zjVw3l{IE0BJ3byr4(j6&)gKntE9odXv@iiGy0QcI$Fps4v*SNko|efZ6=#QuC-M6X z7qZ5>?kvAnZu}~w%3G8qQq$4-^Y*5?Oi0;_$LQ?qNAuiZc^%XG72$o_EUH<r!Ys)Q z$8pIEWRYCEVfX$@Qe~hIVUj~WiD@b5rA>IBS`IlNln$qTxC6Qis(+A2U<<5L{Bf#f z)bQvPtM4PDLu{J7hJ|+NdPWUfQC$)4386<`tx%%-XNrJ?*3M~=`RGxai4x~$Gib@a zSoFLUS9Ik}T6`OiT1B?O$$DAFe=d}w`+np1H25UqZ8HqM(nHhf66hYicjKaNvm(nL zeCztmBWPX<j%=l+ISgrvy})L)`SbmA+qVnXm^D}L8Oci8hx|Q`Od<A*$ZZ!Bl8}fh zEZIP603`X?n(8-Nq}}K_%=px%A*5<0`Iyvwe{xY)CJTekVf*-y`(PohRzb~7zO#5i zAzF$<1G=KDoB%)Aj5GB`2%518&x@_hQ0)b#E7<UI#Z26da+~rqT?f}Zjbd=q^Q@{g zZ%lc--%qDWo=1LTnHgq<)r(9}Xs*MLbI}<f;-z`IrfWSpq+U%(Ph$s+$XwX-Fk}97 zBl_}A@i8pRNmKISx)+(6-1*L6MOYVIu!WYHREoBc6t5U>`;h#ld9~$yQtlH6G%KMe z1<SNWYge3<V=d)``pfBidm6~Pr8sKGx-uv$QS<0*&S{Y(cVt_R7=u~)FZM$^1{q}8 zZN|x@e-Q)V;Fsy2-c;&LKc&$UeJKol>==GYN0wX51N}Zn!PU}bsAftAaKKF~6rl=m zKMs}XlTB21be{Lacms(0v-GUZjBo|j%BG<S(s$}zujv}G(n9uRhi$x&l3J)D1F-rp z>`+{2<iT|jTU$_gmNut@dEpi7gWNz57B$fD97JF$>c_Jx!;QFu!np7G@^E#H)kH6; z9vY^0$TNCqaqq^G8osH_PjleW9g)&j!PrU=JS*8xIuk^H9heN-(3wJ56Lo{@dQyx1 z_~eBuBAaFxTql$Cb6{MSl$A6Lp1cuJrXm3KqDBaOD5^rpnCe-m^+D#)zZ<+db~)}Z zuW9iw8@sEW?%3Gol?@H1#f;S2KxOBOE%6n)d^8I!|M-{Gz({kr`z~Es&O;|9!M_ev zDJ}EU+!@0~%#!Uno@Fhw{E#43o2E~GbvHb-FeWcV_blFsVXFUj#O~h~JJi+$-5yYb zQ<e%Np;4cI(em2t^M+`c6fT|m5xW1SSjYpu`Ltkg4qvcHwbT6Jz<4G&aCNIG$QV(t zwmd||T@8`$&Rk|w*mVca#i`l|E3$D53vlV`g}l8QjP3qHyL%#W@0v|6yOVsvhHR($ z%sO+QGL-GQo;k&uE@LyE$A8E0-mrW{UwrZ2u;>ga!g6+ZXOmxdg77u1blWpxGru{) zyhus$p?$q*1=p|n=}UkiRFMtiCyyM3>B?5fJs8V1b|8}52~iwj*~@s^OK#(|(tS6% z>}s8i$)&0P@-wBnl3QdvPycc#{qFSz{G@rZKnm~qaH{~;oboAoSc#Dl1Y`VOK&~b& zBGsiqDaWxL@Vs>Iv-fJ1XS1rM8ba)y>!AKju=E(6{4D$9SmILI7us4p^0cehG|N&{ zWgV07L0s^c%E9-E4SdzgVcuy%#SnbA4TxDcrczIIv$@&wOy2Va`4(FXTysJS`NBd` z@A81q*HeBfYrZ3gUrMU@hB|6^mLxI9Gv;$;<^sUDkuPr-FTU?rW%`oBa#Q=m^VL}4 z2bOIru5+oVjV%^m>%{5VZf?<uw5<rHpNgwfx!Mg=Y@9xSckE-z)0AeC9;%>KIy!w! z0_AG2VT!uU0PEOg77d!}-QDirF0}eFf4UQ^mT&vht?>rIvf>5`0Crj%>bSGFFuy1T zq%I(itL^U-T-T{un0DrWH<0rAR<Skq>;4Yo=0eW)luA%;7$5jys!7Gs<x;%ueg3RR zyywD*)RMJZ6o)r*_vos6?A{T)YiwDB^D9ABO}OyYybKBIdO%!j>22Vm57qLKaN_>4 z*z0efCRB6&(MLLmeDrx-F#Phmo8?p1We}ZLgZdQ2%;LYBA+H2#>x5qDPuB*X;vQJs zw9CB+AlIe-0=3xr(cdgK#+`TY=M*op&!s{UUAjohk#(G+j<`KKuG7)t^iLMv8Dx>i zId-Cgv`Bfg#G7<@obP_TpLZhLQrzXN^nQ`&{x%PMj7gxLF!G>8t=*PuO7k?@WWpk_ z1A1QV*El+WuW<PwuSHpiQ?*LU_dDn?wP2>A!B!XL3BMwCK>eM3sunl&?-~)2gcxCi z5S?D)X#YU0r(SNRfQ|s$=STf62SAd$6p{dxXlS$7jwbsLESG`AG0t7OAyyh8Fw5)8 zVN^k74dL0x>Vf-rY(R8+2<0KF-6mIZJt1y<Y(xa_v$h81KGYuNfLfvU2lY7G@879D zCw2mi1h$|6jcKkPAGYH@RjWZKA~@ZjZ^H9%6fd#RK(GTHkr2-0k2`dz_66v!e%&gr zZc$8lE8Xbs5+UVJggHY(Z9-xM2WBFgg*A2{2Ibd?@{avj<2Ev_sX>?bNY!!_Ka<Zp z(Pm}6#LHQ~lme6kUjL)B)F?Twk!x$j>FL10J6KddOh+mZzr~3WdQQ{=ltDY~!y_uc zzntZ1<^NEZC&57GN|iH=FwlA3t-(D6C#TpFIFbNSxiUwTU+-vgkOWJlyUZ>Lcs<}x z>+~vMnTEA)3Y9nQuJiEq`g17=>*hTXuFXUo5jum<1h=PoWJxW-X5GhCokpUCx72_r zAhb{<P!;iy-Y$!#2h6u&vit>m7J^NAh_yu!Q9MYuQ^pnUE<s3xF&vDrH1JfNz&&}2 z@9<k`MsfO`y!<XAN*iSXwLu+{XuF{-;mxh=K3p51FFIw1Cd-98E`Tp}le&SjI7-JD zL!JcLf=j-)KR$IjaFd>b!{q210kDYMc(K2VPBlv2&qTHfDC`Z_n9`Fw14{eLh$DEo zgPqxzT&4BiN0w}(V#+z3L$%VSxIHmkcmUNQ$a;q;k<yLE9<i`E%4S6jLdQ9-r?Fn3 z9F*_NwVQDICd0%VL_XAU9K}l=^{HVb_%=4fddfKXdBWzgv;*HcVE&(Dbixaf?3m-C zC9HHIGC+3d_m*eLR3+EEUVqy*dpdygc0?k~jc>q(3^vGngRA?|Z_;4?>Mm!CiCVb7 zH(qL>T$%1n$j_WBotMjfN<Jo}yRclVe{-N(kQqJq&rm;C)AlAu3SxptSP>}m!u6>j z&T(x}vW;IYwb3i<yQl~c$H8%tjew&56GcqgoA5GN*3soksI-PVnLkeOS1bW$!M)Q* z=S~p_ITxOF;gWYH3+AUj9-^`ypi9?bltBe?c=GgkbY%smELAbzv<P=1xDdR9s&gXE zNT)0uJ-<KdcGz2b3uBM^0V7k5G<Mdh=DLkn(Hs^-)GkexNui11L#~!Vd=xIJinVaA zTeCKcGg}C*N*F5;bLP`7a=nl34V^T!8kEc`w*+cHTSvL*+W77=iM~T{{Fxt)SyFq} zkKv3#N_1Hq@BjWjq`6-EPLqXF>4WoO6CAV3y4vTDR|dGCB7)SO!fhb)bz>&>uZV7G z65ZD@XA^EH7<FU9R^f-(J1{XJvW^Q|8>xkDJV6r=+awEcjP+aU<GixS+?48-$P-PE z=ec@g*}w~HPWom#c-6iE^D6`t!{eBp=IA6aEtm*Hz@hU%^{oEuW|WGRwu&n5KAX@) zC?Cm8SuRNn`l)GZFh~tDtzU<71P*hgrs?HK{=w_`NZ~HkDXo|h%6YM{Ubw5y$zUd; zV(7ii(56IXmCFqgNBhZx>L=63dYpxMuZDJA$;&D3{JzW3Ag-9u+I_B`rHNd23%@(d z>6%P-4N_*=c;McaBrWb@RawsY^45i^!czIpe=E^>E>!-50Skja|HhqdpzzuL7emfG z7;(sFyzx+(fjxrX=NwLv16%K7yMATL4wm!F-4*n&cCFke$>JkIbK#O49IBkkKFBw3 zQj5zB_+KfJSF^HEAi{ZX6)!_yfbal9D?@p^tNW)OtukdjE&$~3E{D<pMV+pND4u;h zCL&|OfFPiQq$M=7h&~C%36zXZ>Ydor#d%c{2Yf~QUYhzU%JG!w_feuhm@F8N_cQ;A z<&qEg|8wcI@;VGLgr9O_DAQu%0r7MqAKV?rIXfN7lRSOAYaB&OoVG7yyw~rv#>^S% zruEHGaAKY#2EmmQWMRGi=(<h{IH5W)P6H{AC~`IZcV472p>fA8`j@;PH-9o!xSWF( z#~IdKY5E6(NPWyh`ucpZverk`b&;jutsn(}63b>A@!L+OCGSHp1V?Q!fcN;m=9@2d z69^r~l@3($N<A$A0O)?eGav2>Di6iIZVwCY<1+O`7_f+J5b>%HszsLB!*YXSEM7tN zxl^^0UzAVuB+&Owv(_N!#DN?UdyYl<2$p_c^}x?Y7Alk%iv%W*gcKN|Uugku_qj6` zN`%_z4|R*crGCg#c2(ktcu@8_?5=_bXI?J4GA|9dUXK`}ksRY-k@Vc#)HA-Gw%LN& zQZvcw_qyV3qk$YF5zgf0l_a~BIeruw`BHjdz9qrXRq+B5BYiWhCh>P6fHV6*yTp{$ zNJ3IkK2KQM4ZxU$mY5Cji$J&Z;ddaCqwgjv+s0w>i@Fr9iuYn(FHd;LMR?#Os&-q) z<hHVQxF~9qsit1V-OgT6An5>@bi-P$$4hzNmd}-KnJ(@J(WxrY@b3QRRBhavGBGL{ zMO7Z6j(aU0o2%@JrKL`kKwPQ9c1_B+sVi;y06_N6Eox<63JH`t5J1y6nlgEl%E)7U zMsyE6Z|oJE9?G_LEd1k6*ynLSLM?ogre(2nZAE?BnYF2Es99VZ)=xt~eX^+I6&xaD zO>%ETBH22GNu--Ewr=(ZS^D6td08GWh(uvL4&MPwHX!z9I6NiUXPUXd6fc!p^ZVHD znSY%{lV<68>JPR9p`B2vg8-?+?KnHbijEn=d*4dy5T4rpEnhz3G(+DHTPhE&`Ka8m z_bJ`=8al-n)jjbX;#69Fk0Z%kJ;}Cc-oI%r(${bivRLUXkL+&$$|Et@gejlvF7Nuu zrmVG-Be!CO3I=ot|I{bbp%>6znaY2-M$2Pn_$EN1B8WsQRg3En!BiQo+Ev&0cUE4X z`b`7%lnRw|xGiwE<igpj^JL7vH`l%H*%8~-q)ofE?gUW_E1oywap%0mBh~UZtX^5x zJdM|AsXCCl#FTpAY0A}rn!{ybXuyuaUN}t^7viwPl4FwE8`in3-rF+q{RK>!HtW8G z0VYb@W8hw+E8EIR6Je{%W*a^rGJM0sO-aoaC?))YM^e$CgKCR*0NJpP>KgsXKLDh< zDtd>mifbr?Kgdz8elXzbfLbHiaXA`0TcxHBa-|dKK8*9X@w_c6?^<;2-TcM7M#`R~ z8r@o3wiChkOS}7!M{R3$I(LWjSCeGw4FVj`1#6sk!E>!$ad;E0k?6k=MY8K}xju44 z4Pkj>rq=HoCMu|0{S#B(zLkYv7BRHoxi<P)vel9&*Mtf0UufF%0Y0tM4JKUZF1pmq z(k=d1g%CQ!vebvY-}a<pAXqru=*No*l)JIxH(q4mO?%o8t%z4L+9ngFlDpjI(Z%ak zg9Y!Gr)bu;pv0%44xjvLWgQCCe;_Gkf4?NJ)3dIi|8`ZBxlo=Z5T<1=Dafv=xRu%I z0vp?Hh)MBPb(dB>GHLAzm5Mo6{Hint7YaV<5En9tiVA-iJbT3osD<07mvj{%7NxxE zxPQM0Lh+|=&RY&_c)j`pHxk?mNb#{c2s=>0)z&-&3U58xG|#}q^Q6E1leW7la2yNq zy!drj4tfK!TVO(c-By=-h(@&#wRmo?KIU2<x@jPM3ye%|3Ta_bx%sZy@>qZ;=)!AN z9C5?X8Dq#Ri5U6L$E|sD%5EY0siiP_EypJr{ng%Q#`F_^7A02?QvA>$t`7(YTcI1& zj}`Q#LO<_jyNV|}X-nY0QMj_}B!qUW{cx-N^fl||rtALm-`yl{Zp;2%a>3gge}I)^ zbsb9(7Q;6$?;;4{??`Y0<nOOX@41kUOWCkDj&W`0-#c%@jn_$<)q}DI!0zFpzkx)t zeONFBn`+VtLGAI`4yS)LO<(83J<4=_Z|L*Bc=m5DzaY|;|I=MARDIOCIgkJuPG-N` zhiY_%o`MI6VhsshNdTMjUu3eiCaDx^)H^IWRq7RLZV3MZiO>CoXy6gJS;txZ@!os6 z9P2i(g%<aBg=*}w!Yi-+UD`dKFnGL8r+wc0_6f7g+A9~`V==++_0#{}mCyWSGV-|h z`VqTIp#8j4XE52lPYB!W5@W2o!asi~m&Eq7M7|M4B%Yr2alG1-N>f#q-|1~pdsX$3 zs@Z3`=P|_s31k`$7$A-W0R-Sm&%t-{7r$8!tg5GxTCbTy#E}|5%7qXG=fxI)d6l>- zr?<k}KLRRnleRB8ZnH1uftgl8WxWZGBCU5c1f5&Tu{os7LWQHYspf)ZEGW(EE>D~C z`4<@K7|TbabONz3R^Q!0Z^Y6W?sI!lpla>oc><~sc8*dO(@}hB=nu)ipMlst#E!3* z1L2N8oYkq|NrZrf=O7JbvhmKR@pDp)Po1YuuZtbeU`i%R2NCW&IXmMvh+G#l-8`@6 zn_<TEZG7CelH6_uwQtC89K_dsy>1J|Mb2Psu;258o1o=WnV;`K+m>U#wV(7Q8F6Dl zuLydEX1s4r{=-noX6qSWjRw5xOZHQ#I+J@{WDgEBK2?(UDNGU$d>XzkXQx}pA?!Gl z1c{svvnuJxHPS9=bDXj6F}rT&>d(6vyjWO8{MvM*Ef-~^G_##ki2^`(8VYWD6vsAB zTnyQKECIJHnM9LlW8HU@Ibwimc~)`LHsA><ppTB%=PfDLyzalW<?(Fk&rJA2S-><R zc<`U!jA$DFB)Mr?(1i(3qeGG$03~qNkea9|s?Oh&1#IXmRX%+$?bN3z6QuYFaAVj( z^jaq9o$_dB5g+l$c4Cj?M&>L3?}7jg+&5QDy6O0F@ke$+P#<L8s%WRQn}e;=Q1P0~ z{fma?J;QbleNeMu5A69T7GC0dDl>yO-`Y19gcEbJHEhxy!#^Vnhom}UXw;__zf;d^ zCFWA{f{ine3V(#|t>?~#0!&`Ns}37PPt5^ACJLz2jcKiY<w2c0r~*+)#grj&v{A$n zY?y~?bYV&K@zLMWS_m@WM<5h_J|SbImJ_=;vPcwQM0WxL28}29_f3WN72+zxj#udC zDODhx3g?#|+Vg{Bd^Y!eP>*-eG+}F5ASJtHn!g7=MSB9_s5eWn%ux_orj(v)qsu9e z4kXk$Gh)cioP)mfb2*BYbD767M~HNdW2rUrJxK0+=|dwpi@L%))7pGy!hTPNCeb8O zm=3|%q$3E8Cd9D;#vGPzJyQz|_5uTiU?e}o3E{f@QYVU|N+X*C+^9*xC$nQ#4&@Th zuSq%g3n+t*fMs;1BD_x!A9_^FSz9@wfQ?|C|MaSc)~w-4Fh}4!)6|@i=Z|)@ZpLWx zBXVJh``gYHo5}xHN;f^7=gque%S)U$CAdU`(?jruu9fI9tyW5*5+oB+R96G=p2vnE zdnaF&Y{DeP%nrm+B~---{omH|0RRdR0cr#O-_|mjYx4iLmRl-D(~UC?e(AJUj%N#+ z*Q+W$rQ~=j;x_UBS<4AFnVBslUr1Sn6yp9`%WZ;##X7yu4_QZQ=W0wUA}dkE8dCx@ zB@u2ZRrT}#V=WVF5ZAp1@aO&6m|Zwr>M*ixU|A|hP%w!fQ1?*u5j!N9w84;}@_osX zYU7Z~+YTx1w-4YSJ+QdY-8c7vZPP0G@q4%;;--SK%$FK->BJ=KxFN^bkNg`K?yKN; zWAmM2w-+MQ!;p1Q^c$8x_8Z@~2dJ26(xWi<b|7zmH7YBv`Yr8l>~GBCA7=}84NBY{ zsk@C(&3+*+y!Sce_s!Muc8!3ViN4#bk1lg_Q_tUA-;tOOvjFV<H-{Mo16-csoR_|^ zn62+zt&sh^>EmPocq&d~+Fjtp%z#)y%|zZj@Bh<U=F`IF_|cJUAZ3HE3B>d!ef!%P z8YDtH$(NtnX&EdWL*io%<iGA@n`jB`=2%$y?B*H^KZ<9z|K<EC46+k42H%;_CZ%%_ zOx`W@Z~wYiWQfATwJqdkFtiU>lE0KZI{WHX8v94cn}DbG^)5@|s`oC(?+HyS0Aayn zev43$4p%-CR-ocZ_{7(mk_7UD8pBM@_+oY+<$<8V*TD|tF9z<EaSd%FzK0DRiz$aq z-Is-jFMEg%{hEiU{f_Fz8=42GBy8gPL~bIWu{0gBf6EUnP=TZN;a26f|FM>jJ9n~H zzjck4A09vyj$#SVEi{28nuYBv1CB+zFTVHw|JE|8=t&=#x#v5@yWY(A3bB1s@BC&@ zOa>u2U9m6wf3NSN8k@sYUyQ>36%8HZ8Z9Im5&Zt5g+gVmc{nT31^;D4s4_TYLh(z( z`4sVL&oY&q4jKYxQDoQP%5wLUqA2=Q+}g?!ED10q_Rbt2SEY~oSpUtbCH^@xRjtpQ z=)C{svUg46<%)mDx69SwQL(EPu^ve@C(C>+k}m{vSNNV<i1*Ea<Ncbqtn=IkYJKy< zhTk+i;<W?YTVI9$4y$AP^elfe>*4Xu7sBK8?-Ym}@d4`LzSC4$ErLeKGJ(4nHBbDP zE(g9Y%~1ic5n@sMAwiSJ)RxP6!puBtkC~796u$pDzwaim=p;DStRw$u9)|ngn;3IV z$(970-V&tMFagR)(nPP=*ElQHGbKCX-`ai*y8Eq^v6v_p)s~5aEZN0EoMLf3?g5G- z5m*vBFO`vJLs;s4PV$qhmyKP0q0UcAtv&NzUOYO9gE?R+NTeV#C$Z8puuoL&q%S5T zUJ_T#^l7~B$O1BKg!~8ETwd`~0yvBFT--7d-zDk{!KuFxM-|{%p@Pf|P!rpTI&LDy z{bG`Gd<ZCs@SV~I6a9OSMBE&z?P>LD_v=ZjcMf~6!wF8^B#yb01-x9muQCAq{+NRW za`QlYkUdl)Er-1%x-%B9XXB2zWVI)q@f?*^K6^S?hvc@RO;n~Vr$O|+JDa~kdH4`g zQtlIU16kB%Lg^w0UU4u*1=C(nrao~@tr9ieE0PySfwOu%7}5$FSTR&j%6~zq0`_Bf zC(Yaj&FPY4%j02FXV0b?3W9iTlh_FaXmkO~?_&jyuD=tN$Gqc`oU!WF$T@{?<v8ZT zK0NmQA>7q(K)yoPI1-Ub`ecJxf+^%~z|jnf-Jt(`?aR_nYj9E!p}WUOI6*&SEGvPg z?Z0*E1IZMeNVlYx&4XRli6Z7JUW>%)Xy49cUD5)0#5A=3QO+D?y`Q)L;Nz|tpYfgA zS+$~^J<q%LdgZ*vr&B6x6pFBE=V}bjM0NK(YE*8^5gw;e%q_~Nw_vmA@5Xe9(2&d2 zE~@<gj0x<9CFs$Lf=K`}*-u&*Cl=egFB*f>UO0Tw``Ep5(R6>8%js&xsw-6kZ2A*G zs?`VVr?YB~H*9dBe{3_X9Nv<^*dH`M@o^$07%XN^M_&MY2~-=()wId=*4AH{Exc^2 zHEi^?ez&sNefhdM?VC^6m+pzXUrn+3Ej9`gpciXfnjLIzSmZO|)vc681qTW@5;c8V zwQmH7N>USJiN52$T}SuQ+oteW?>>Et?0B>ByD4H&fBm$uqi0|3dsy8&r%Tkww=?k) zQJ+`Wuj&=vUdJ~v%EreF>Hq~<Tny;RF$7tLS`D`)6mB$_m_((s9~#q)=P}qMv+o>W z>1|GsdA~`eV$)Aca+=5|x<y^IG{{1N#xeTCB-;w~Nw(-xDRzjN-`R{vtrM|0_qc&Y zmMAo+TQmR1T4rY*6BW;7YCHLyvGjGkAUiv!#$Z?2{(r3H*1V4QyW)>;-Z@jB=Ra)Y zQObQZ;qHkld>7>@_19W9B5IlYcQ=ez6!M5NV(L}N)%!2%KW{$7QnwNQTFYwmtkW9e zZRO09`&ufuGm-r0l5rTPc>q3BdhGwSmTR>Q56p^g=WC5#*IQ2>SmoQ1U6#Gl>f8W9 zmTv!VYdKB~Yp<~J*IK@8<m)?fRajk~O3-Ml5&PzA{&Qt<O1{0L@mt{ipR4QC3he=t zN2K!rfL(-_rn})GnZw4Xlk|?BFNWVESAVWwPj&QOIesU*eoVwb=zA>*1^P4gY%Jko z|C4|L6BHbXn36h&c&JZP?4602KPZkUG@Yj3|Fz9Uqco;1ewLN}Ylr`i`DQ?d0FtP* z|HSNbHGF4yUby;ePw_+7)WfOslAlpu-cM<eK%Ag#h2Md!!B=3m7~sF8YkR;9W#Sm4 zi+cOt2R5XN#B5WcUnTPqcD3Y<@L*tF(eEQ~<2NfGr!L#y{Qed^dQF_fgv}+2O#meI zfnd;+2np5o==|$9n?~0I?0-&@^1H$OeP@!Q3;@Fxoh9@RDCzv?S;2>%Jq4QUh`+ln zR)PkR=h6%oLjbzp{b~_A33fN;SbkEf{Kd=o=Zf1p5wo`{vIHuVNa=mVq|<YfXdJbv z5KSaE_7)Nm3|)I3Lj=u4LK{rtNSgl;At5NL!T>BM*oE{yP0ZctsPUh(pie|;+9q1{ zDB@?Ue}122+`ZvRKaCv)GOI)YxRsw~&S{s@bil~)1dw|TX=X4*t~1!(izE|9mPsIC zj(vQlfMtkyyk7%)N(#7<gr+xR8Q}N#m~n`thz2j9XE4RE35c~BKuZ9!Ns@s#qo5}M zB$Slu1P~$#fk44o!9=oxWURr!ND~kZ3{(UI%~pr;bm9%X!yOW_)I@-cOj_6y-pV_k zRy#bTkJO4lt||F|Y!mQ@87l_`M?y(ynn77GkOu^h+z;}Vgxt3dx3)<{T;mN-K`gZ4 zu3tdMR@hjUq)Vm{24`>-48+_=fzf$DvKdu-HyWu$AO{sB&~!q4n<1>h(OQxa<!Qjb zf=L9yq|TbZP;sE`!<5>B6ien{CTMgKlvK`!(pymDSuFH}m!AL(AJrW9#DpX=IGGg? z5~71=zIsp}kvdkJ0!&QgLi*(~r%dZ$8G@th3FI9blmG&`2m~NGW=2#7{38HjnFc^i zNONNWDuguIT5=kbq{PlhX6CdrmVaqKh7pC3<?khqcV_%b3VU~*m}CR)fr4pbfknX& zVU~b+Nhsws0I30)sUi(?4$O20t2D>61{3A%M63Lz`95aAShEy5Qke@9^J6mrCL}~s z@kCEa1s_3=sx!hBvv;)bQ(ygyxr+ck=~E&5N+SIrk}4P|5J3@U5>D?-{3Mtn-6WbB zM%HmcUT;E1SBsam%}pW=sZ@kopMXh1C}vI|IsiaIWsH=0yw#(;_%A{4s~=4AKS=d9 z+dGe%?#N>ZjxzM}`#$pUEFmw-HX<T|*e;egk01JgiP$oPSegj1(Vq);Nr}EGNO%}k zc9qw8Zu)u<0JTmHv(4|<zMpyXEXFoVGCRYFw6MA>oJt$GNC)JoGUFyruO0P&V3SXq z^f;O{qUKpqigi}XIIWvPQ8#OGw7}ofe;`FO;G`Wu8C=|Mb-zRRUpvwubM4##vS;s? zY~NmC)isJ9DE>=-^?ZZ1Wb00;WXHB-?@`IVZOO@H@^`D^k*|SYzdk)xD*a(wdiki7 zuI6!TdyEAEtkVb9*(e1Zl!Dm^Bz6QyB!Rq;K-o>8ULinl33O~_48DXSVn9)DS<yu) zM+$+co4{>XhEOi!RW9eZD;HEQ2VBykXUoNJ%O!o;?WVyp-9|Ez6;g#2%H0*}t?pXo zaE)#jEGx??LPE=~09jb6cfg>%QfahuPoJ&I%#Pm3u1Z_E%BHZ2zaK8{%4m06<y=T> zbx`SISM8}sYq<i~imdiusU|<IG(7=JhgJpJ)r2WmyZhEe+Es6~R7<<EKkBZ*`Bv*& Z)h4jT#}(GzI{>AU)YrPuLID7k{{^AHVZ8tV literal 0 HcmV?d00001 diff --git a/images/demo_MPC_iterative01.gif b/images/demo_MPC_iterative01.gif new file mode 100644 index 0000000000000000000000000000000000000000..cbe3974e58509ac06d8233f2e94904271a1d17f9 GIT binary patch literal 268207 zcmX6kWn2_auy9<Eij;tKcS#&b9Nit#-5?wS5|YOSErNuAa3V-|_t7Z=(!$@P5kWx# z0g-#Y_x3kCyB~Jv!|crN)N1Q$LFHZI0E~d&#F9k+8i9z6l$@JuPfAK&`e8XVP63KO zkWbi@fAdHI_2m)b^CRRJ#e{Xmg#Q$g8_G%>%HC?q$TcmkI&CXIose2Ry<3CuPD6(f zBhM5gpK@cvPsYxXCay6iZn0+WF=h$<X6Y7Ybr$Ak<>v0u=I$}(9<dhAAr}8|<i5r8 z1xxoROOH6qTq`Tj7^|c)yYONM=Mx9tI7bI3C--?*4_`O;TerY?x8P)VOtWW7n|E@v zPfCk#a)WP5qwl{-zMo&Se*pY8AgLM-e+o|t3JQ%0PAm@2=nQ%OIy5XQEc|PDSao<< zcX(`aWMq6~Ov3Y+=h0CKF;Ouw(UURhMKS3cvC)Xwrr0?2ZG7HaL>vNvPD3J4NE8~C zfcZE4YiJ}I{STus7$gew52F$j(WpdpQZfdWoH(6Qosyc`n3j^3p7|@Iu<B)QQD$*l zW>aR?%hy@CSy}zruc~vhvuCoiZ*wa;U%%ccM5Epmym?bUQPf?8t!OL3ek*(bzO4G& z``X)z@yd$Ls;auy>W;>mnAqC6+PbF6I^3r^+;-C=r6zN$mgXPrt?li7V;xH!oxQhR zsFbexZ@nKj`eyt3-8}kh>TsRixJldq?tEZzd~o2uq3GC=_2W_e_2}m9*vQ0qe&Iw~ z`o!4BiSgTs&D)9X{|Cav&ducZ?c~nw<k8gB*7el(?eyaDH2z{{`oqk@_m6vjJ|5i8 zo0`vWoGdSXUjBBqa<Z~=yRsS`x4OFiIU(`$>VNBsD(h>v>!-IHGz=RXUpKxTZ|3A~ zuCH$o_3q+#cW?Lh+&vGzUwu9LdieFn;nB};6;<C3Z;vi+kJ~zqN5;P2e*f`l;pgq` zuiNv>+ncN3M^~3WuP%RIUlFdaZ*Knn{d+_B`}g|q-#>r<-rjQa-P$?cq7rZ4mECr9 z-j0sn9v$EQzP!D@y}kKA_<MHy_u}^N)$QM#+kfkCzy9mDw*-Q+8e#P_;qTQyT7<s@ z!tE_5fx<}B!dzX|L{mykf`s^=I&fYALGDDvL?ZvI8~>{&M5F|wu_uV&gM~(KQd%MV z@rJiU7;0|4LY>BvkrYNzy{rq-d?^<W^<);^rqYQl0rM*RiKeotTnV?yLfz)~9}1ws zhwEfdmn$_9T)KxtM;qO-I$1&vlP#5>%1z$sz0qr}TCBFNN4q^cq<&NHJe16;-&V8Q z?ER_AVXCe6b31%{@{N9b-9~r#uS3x1ed<c{I3Vlu{kv>EgD0ce!d`WaZqGBg^`9B6 z7Vb=42&s&+*aW-HyirO(A6-2>n9niJWqV_D=Dkoh^fzUxe2SL$@l*YY58drQzTgrl z*o}HRPPfOigq>!3I)ClYzSA!@>WvH)Y%eQ)%ROD(`xJBc58;7vU(eOAgHP2?ANzX$ z{65*9D(+|d??~CWu5h*gODcgtDC5M(0RZ0kcv3bUJc3L%Pb<Mw1j>OVRX)HX8O$nN z;ut+UT#(eyE?wd{U7=fO*2qNHB$^`9EtF_cMM=D1*SKpc|M%Y`^u{-CFI>>7d~A_0 z2A{l0ErulbOqke2X_l^<Pw6YY_hUORtsLdupI^*fXxwK?<^(f)GeW^gx6;bJeE%vR zw*q+6Yy4}fQ6K&{o+T0dg@NB!_X;DgJNXddG(rbh2t)qC+W;D7fp_Uk6W;kRXXGnO z2rlIKvXG)iR1Ov`bXZZE<9k?H@xH36LhY88?4Cm&AqdUr^<HqVwqvjATV2n^;kSAm zSoo-6n8EL;ah$LEsA*dE+fnnZmM|Zadt&Ed>xyUfaoc(c`Krp7SxHo^cd1QX{`~tt zHMK2+f_&vC>8D~{?M*4d-4_?h^*#OHDQf!v{(Mwlf3;WbHvm|k3M}}|SMz;{TH9Wj zal^|0bcE5%e@A69s&S;oPfO(II8Uzs&k2F@nxB(PzDGZ&B*vz9R7w?3HJQnqYktir z{yzHk5!Nj7YgXg_o8$JE0zu&JovO{VPbS);=L;5(pPVmRdmV=``)0fbGuvWBpDnv1 z-jp!g>qkFZ^L0y<U1aT33QhLcHk4cU`e+!o;gCyk(VC4@xoMw6-VeCUe#t5|!sJ;P z0bVg0=eXK=^*G>aH_xl?YOgS?PX12j7Y>qxf)t~!uleu95)R)!|9<_gVNC4LQA>M( z2J;!X?s;<p`}aRTG`MR+wtu{jA0lJpslWL-E%)Q**Q~bq-?N2B9|y=*oMHjs)#3)g z1wOX^FWFk~-P@}jw~x_RD`6)Ce-_8Y2{&iUfrP&k!Er;&-M>F}GoF!Qi6A;S0P{)Q zzV7-K^L?~Lsw$NcG@i@=h9I}41~E=!!J^};G~Oo(Oh;IV>ZR(v%myT@;wG6=Mm%}P z2}-<&h|+^}h<Pak4Q+9uGBrWa*I<FPlv_Z8Wg>u+{AHpRB^OPWH-cBHF^MN?i~60w z2(8}BB;gKX!p)eb`}v)4XUgr7zOoMSS5p*@0tw9U1_W0O76?y$$Fi?8rm%LJ9zOk! z?boI9T~7`YN@yGhM0Z?``DaF=K`F;WJTYAcKKhwK30rZZw%&hpnJ?X4d1WGWjRNLL zM4-fX79_yZd{Zh8!1enh<C9i($*B|~W%t<_2gv$@UUW>CiG_8J{jQAz#=eRJGUMaG zjOKumkT|KV&S_7Dtk<Kdp3*M`4P9>MFg?@nW!on{1bnA?#ly(U$bz19iRa8#eMmB5 zKQZ$xlRQUXoun1_OpzfEpYz{zx$^k|VTvAT4xl8hfI;+T5zJ>;NHmUwG3i6J!r5Eu z5BwCGx_TrV<k?g-39<8du;l8&I}WN!9b+I2n15C(U|6a5iMwYk&83L?6<&pi5? zCXb1lkAxa)fV@5{SGE-3?)|OIwscmZQ~MQYgH<tWqM&pR&(Mm^MvJnPFxXu_P>9`| zsf(1+C3j!fpCFPaTgyuHHmtT?o?L1*I>{wadK<^<Eq6)5h-2-MYznhWeb?vpaa1+V zs@?zw<S)Mv8g*u_x0GfJn-s~>Ch>|w?*%nn@7tu!B8S~MDGWoa5wt^(wZB=0XC~RY z!PJ!uGZvP<|9l_RTJ3-LFfN{;Km>`I9p!@J5#(JL?YIwnz=C}1hZ+bv)k+ZSXah>j z--X;R?=TJrU#&^r?40dgWN0gJNJ~HK##8<HG7Ve%+0<ONtM<eo8@h7Q)m|GoQfcI+ z?}Xsuz*3mtxELB!G@Wt4-st)`hyngLLr%%7wZWi25+FGiIVudb2D|S)vO=G;rq(#H zCpTS^?ZOtdZwK7Tmorf+&dPm9rasxm=Y^E4kztimywWMtI`i1QHhGYDbQp^XkOL1w zo+R93<RrV3htHKYYRcTTw%$tTq%yA<;j1%QR2CSbV&WU&YdJ!RU3$<K5P>}_t9M1& zT`9bs(Nb+UF4Dz}1XtnoUq1|ljiqMI5NyuJe=er?mH%9QjJwl<g%}>F4atlt?ghn= z%_UO8<L=!)aRpHre$}(Pp3j?Uc^?>oHw}=UEX@N1*QR=SlDd*dCjyz;8d7u&T*xsv z|NF1z4t0n~7`LxU6F@<GQc1s;amp_XF%BI$O@gB$C%DY4)a|PonK{^bqeRdgDbE2h zV=fc{%>8i8Y;5u>5!LjnvIkV+95D$^S!58PM2lI3QQ&4z#B9?%T}WLid;}7{7~FV< z-uv@KsylT{x~t)Quk$nRNn85cC(D1x&FO06MtDo(si4ldBGQjgGZpyGgO1HY&y~TP z5zwY>smuBefjpwxiS^qaU}({~LjB3Kb70hq->|<i47jj653Tb}b1EG~!Sy<4B@g}{ z=xATR-Jd$?60!i0hsOiqaS7%+2#|1|>wNpndEN8B-<;SL%(Zm|M*=$UJoadK_3qo8 zsQ2qTp`^bUMq!)Evz#;qL|GD%e~SzM6zs>1F-Cq3*?0G2>ClH9L>D+d2C=}1@9MPi z5DgGhHsMe5V!g}z(RxxHF0|7Xn(S4P$vW0yRUsUphk3+lwjrvNAr&KstPg}~0tW*B zI}d0G`}mxs_Ut$AZr{l&trg*DKfe0>$(~OYd{pkHj`#x+1&`N9GBLvS#tyV2`j}m! zBmPdn$!7xN`pIcQ^(U&(%a}{`^caN-&Mr@me(mSRgzG>2Czth%il309j|%Yk6^JSM zG7-6D95_6VG%t?4BaVh6dcsX#njwxRPn&+h$Kg|~7XaM;o86>L*b{I6VG$GpKse8a z-9NX9xi5Ovj#!fl|BLZ|*y<w%O^`lNk1ZvNFV#`#NO%-(C`P2q3rkRgA~md$Pc7o# zO6z$$>-{RX?A(thdTPpdi4?q)5D7=s1DTS!t$b<By)2!bt)2Ua)x<Q^>7CKujOxDD zXuojulRR~L96*E`9b%1nM*7d20qCyCfXz`3XL6U+i3n&S(mD|xo|u@InB0+=x{{bq zxJ=AoOv*SAGRE?WhbvxYCFOS{P5dI}iBrZhCYL~yOG%Xr!;>rWlB-BnCKH@pB=k>d zQktMCE!HVd5U7rDA#x2X7(})8R|<|Xbx<I+^kM2~c<OjwYI_1WCNH@2GW8w6c$gdP zbprArl6A{UTkA+$CzW~rD-EB=wX%}7W1YSip1!NYC$N%=m5KU(nSPRJ_UaO3qyt_Y zPruB2aozDknI!F&QAku4q#`G}IQRk_kwN-8W9H`zN*|sE4J+>kb{`lRfJkSEc**$s zC3ELXmerRoZZ9tGXL3zE=cRwa7m+E@$u{4?=Zy!-on%TdWl70rN!w(}Mr1(=ud@_7 zvlLgel&`X2Os~}BUuj%rwP!sdCzGb?e04HwCZ5CRhg6*SM7$BKWTmUjf=#yV%r0Lc zcD%}VCd)BjCH_R4<Ni9?wKCf$DcMmzXHnf=xAKv}YQ{)ApJSds6PB1Bn;X@cOMjwm z5`sa<=YjYz$cVheO10;SuYy(|3SQ-9BxNd(#Wt7P3Ugp$&%zNq;pF&m$O(WRN36;i zAB5Bmb<Yn$<_DMN8|>+p>xRI1G}bKQ^%r#}A=)q<ZLVR}8r}Hr%BbEX?S3-tfe77{ zRSdVe(U=r!2AWGa2;O}fMI90(0#6t`BO2r}cq6FJa-v=;A3qRU@Qxr~z+;jR<0*n8 zi+E284t0x;Y>GC{ijF(=`%nNnnM{T<OZL|EE=+Mh!)qdD?0{Ujud5<I9>ANCOLIa5 zg_<aX0rYXiHuv+AY~IFc7MctP@dLGkp_=OVHMmPL=ulMwJfOF=faIb`Fu4S9QNW0F zer0Af9iex{WMgD4!hsN$tCE`36`8pzv}M$HH~=!5Xvkd>J>4ZD-*sE>1ay)W^`9$0 zJs@T=DPtun4z<v*xF%-YQRi_kV>PiBfR$NJmMyhwqd<DqmBv1i5xg1xS|jhD0?Yrn z$N&5pZ)bvtZFacv5&7KeP><2`iL*C%b{YIB$3I3HN-eBNcxM#f^{)TtyW5UTiD!x` z6<A6k6a8c&YN5B9mzCIjpW&~>&<4_66N;xN`T{sF#x6ivB(TH>z={W^no#7LfLJp8 zjo@VE@M<ZB5-l0zq^xR$Rn0ry1hrECQ3d3LEnp<lIGREGLiZVGJJ}@M({&coZ9>7W z&0))H$?Q>~AjDV7;VI7lE_&AV`fKfGm(72nq_eY-#|?E^yQbgQ>deY)GC_6Mdi7bB zmWT#2A8h#$SLLj?zniAMrY}HS!K7fV)R?@ic2QfZfi#W?0_PxO7y}qz$I8LU7O5dN ztHe-=2sj5M(*#790nFt1w}3P?1K8sc5m2T7gHUNKS70n(t^bVq>EOxTh;|TS_U;!v zc;?*qSC#39UG^DJWjjqI25wKkC&vt}dwk+MdoE{P(5m+hJjqeN4FX$FRUAsUx%joM zgo0cjff|3tTUVDmG_-D#`%Rw2bKDmZ^la#0v?}-Tl6+Rl1Sc}_a)J;wzK!fi6!xY= zl62vLbaBL))IO1;L2m6%;~Y&)am2b<3ON`tKb-6-j96QO;*A}knHs`~^$&LU`C)_X z|Jv2<<1?HTx-jY6-9SduM%MH@2!Zv$;8LC8q|vkX(Hx{?C8jvIZ-o~5%URF@Z{%xw z%Q2AW?>%SdQL>@W(IF?Tvis4_vUHb(B~Tc|Glbf5tDCH_fh@!%z|*rg6b^Qnh1fBW zvC{WDkM?Yk`_189N=;&zxoji5+b>S;+FiaP_cMOo2?wBvP!Ha!T)v^PGiMnimXn~c zGy&;0kYY}ps8`&fScs7Xg{`xD{sVFoA_x>t2IuJN&H&nG0CTaR`}@St83yt&fV%uZ zAq;6L%;n-eWvH`dD~!ApPU?YmE}i{njP~&632%D@`U3rMv!L&LR0x<ya;Ux1jSCeY z6%N-wQ~-9sgQqik4>cf#u;BuZ`T!hRIj%nx4hqs9w%v1{$Gdbr8vc?y>U#vvIj2&J zA}^RVZCIjGG9d5RZrLU<;{ZoOdRdM!-L_;$4R>)kDI~EN{w+h-gpoVox|zbVfdby( zM8|=ln^Z3e>EbB_cEf>P)DWTRL3=EPC7i6Hz^i<EqD#d3=|PpRGq`%mx3`<@B?sv= z9=vNc-HN5;f`Y@x$X?>0j}#o2Z7aypHXa$^ZY<On{;<yuVr~MK{N4JvA)vsdV%vYz znTGBqj#5|M*QRyUoP%_Zn#@#~s?v($m;I=nbKqGNX+AaCWet#Z3G{TDa+kud8$Rq0 z5vd*?zj_=M`o2LcpEyH%;%*f&3k=}AJjeET?(x}M77h}IDAJ$?(nNR=;V~e6cur}! zgUb)V2nXg8aG(?uP-?^AyD3mA4kTGKuL+!2Q(DmYpuzlV$ZOEIPK&%dqjt<5Qi`QK z9i5K-1PVNo8}kEC6nrp?dhXK@W_~jDU;Ff7x5H<<2d*3*D51Xfl!w%96lTZ&>|4+t z11DVs2*E)$*|0ol0?C#6==2$Mdvs^8VHrm>!)j$2f~^R8PKv{V`DD3x1+lLjRzWS9 z6`+K?<T+CK#OuPTZk9DwLje6Whz$nF#6uQ*@}8W<UI%y4WpwINlWRExq^PGXVO^j2 z2Nwj_`b4cimp^?;4H^T1_uhK|p4#jKpDP`Kjr2b}X0h!03|cMhv7>fPJOtY^40}1u zY!moK-C0I=!NWVtz8V~)j~N{B?H|AHgIniZ)E=x{JR^Oq74y~CrdtB+U;;^10_77? zPLDiGE)=GYMv+!KY9!+r(n^t^D~-qpWJThNZW?W2q0EI{QaIA{;kVF+P5}{;e7jE; zUQ@!)$&4hnLNc;z=r{AUy9>(~sFqAMBr6h*oCk?4*I3C|mrQ$0D9@gUwKh~N){>dV zJ@h1s38j8sH~Ix}5=|#t|7T;#4#)cSu=NKe<yZ2>az4^-qL{}0<?e=$t(zaaoxe<K zu3z<nZh9-idnt6kgQo>Va+LN%l-XUfZEx>|Kqea~W>#|*--`TatLgwMhWo|Dkwg%* z=AkALZee6&98}{clZ+X}4N;Wc91yvNe|&{>OHkyBk+?7)U>;lRus$^w6W`^dJSdNx zq^26gesR`{vCFYx-~|uj?@i;aJIX)&mTgF?qMU9ZQ#}IDVLko!!0spUUQdF3I7kPv zo?qaBzW9~rhW!hMUwoH(PM&zQHd63<)=m>qa(LRbVvi<G`aGPsr%m=E^*D*_@%NN) zp!F1u$V%o0EaL{Qh<vl8&zNnNxGoZ?3n$Ui0@RToeibCq#RDmdflzpvNCuEboaDg< zu^7jxF6>n1^AA$Y(AEw+KG)jkq;IQwIQqoeohZfu9iwz@6XN{yo1EiUf_58Uah;RI z=s?WBOUpW<kJZ;i)Dtf!!ye=OPbO6wT(Mf({h%+o-$PC~@N%PkcYD5s@g0;8IlKPc zJ{LX&{t$+SzZRWf=*2=3iO5g(jp@oOuQaHqgA5if`~$TEiZ$Sbi)R+91}I`nAr1El z0N<ewBlfrDbzG5s*@Gu17FEAlar3It?_cxiz5!mn2-GOxxvKa1oooC%Z0FSJq5e#D z@p73dhxJTMR{2I)B;;55`ya^n1hJ~Sd<OLuago8(+0PG4uOqACqq@#xt4xpE%3EBo zyHvt9_z}2|e?Euu-BDT%{qJTbkS)v+Zj@2Yo{^gje7o`0t3yz8jlhmvkJX1ke}~+? z#S{K^=-#f!-tHUg@|^sp7P$2~y#0L^%dV$d<Dv0l!Ru>mO(DZ?BGauQ++AK^J}gh- ztttX^SIA-o&Y_-okJqdw(WGSPE)#7NG+zA!qonI}o}kT79=(S?wk6VJzufim1)aKT z<UhUF&-Lt@by+H>Fe*^6{O{EjjpuZcq+1hmZQ<*u5;H$XQ8MFiR&@@&F`x%lN7hXq zABr>!td4D-U)-|hKOLQB?DAf~LpKqcXv+IHw;+4Y1PB8y72AI+Cnv7)NmLI5ju?Ns zPGm7DJR@cLr8%4@8hCpYA$2fUB2(aLa2>L{m~Mz<NwU1~Uuz}!6%cRpWj>J5ctQZP z*+Z=!`lYdJ7ujDu-E;hWn^L+%nJ?+svl5DkM`7s2jNte<;-2sm7R5sCV#mLc7sng@ z7<Q-IsO$6NFJr|{gqT}4=(<jVLMEC!1NI8H0-$_H?%tpZC`gb{BjYcXsA)Tj|CTB- z2%QjPanBe4-G{lyYfyU#+|#7DVKg14wnLt3GC7n=jxu|-NNTf$^)za;M(><zb0+Z6 z=x}2cn{;?`Et)2Hidlj{-1DSEs>1PhhkByzJ(KL>{lJF?l4Cs01`j`KJT#P9c5gP6 zTaFUT<R8Wc@XAztJ}H&D*lDJGI71|zCf?UjXQJMlaZH$1r?qS`(R!dsC#+NZyk$<0 zzBj~Fm;b}UtVXq8OP5hEb*Q<HcG-f3J};G9s?{7`%F4#;O{<z+;E2p}qZslV#i73% zx3vp~x6Rt^g{G{HN3KVkjaM;B*4C%Itj*T1j5WjRN&7AX)S(|FXHQx@C9#ri#Ox;4 zwdB$6(B&SS>#(-<fk8NOKkdF#*!h!OrwFfiza5^FpmXu@Ka`+fkiQ)|oZ^1H`DUNQ z|GvXDMSK+MmL|8?;r3z#B=7!mq-(a;u=G!>UG`(oPLEtCw7lnQuR0(1f<T7VqNlg3 z9?4>6@8!MUV)(ke-@UlAmMZs8_I%2V(F(qj1j&6uvG;lhS6X3{MwefGKlqV<W9J(( zujY@V=bf=YQ?=BGdL@1Xjr;Gr1G<06GCQ>V-m_CHYES%j{O*LW2R?LHyKvxjsb^2n z7(0f=F#NW1H<jN}ubuye+<s5+M-_-t$ecERZ^$QOZKcpfaigK1eNGrw`F7tcwIso| z16LD?XZyWjUt%H3;hPx#zVPiA+R72Txn6w{`^6aL$gkz)eb<L$2d>G2ui)Ize)Ow+ zV|V8Inm{2q)4vsUzU<W>{rd|>CFW|syg%m8k1>_lzrXkUV+jO^GZ6?11L$#5MQ0!- zaP2T~%q}~DR9o6Nh@9MN7IA;r87$MGdgs|JA%Pv}LaGT>qsf^?@@u$|TXv{1w9TT# zOYveQ#OV_<vuL>}=R2Vt>TDOY7!{x^H43W1#W0tst>H?O-J!uJJC|gPbfqhUj<9YG zu{jE9%LjC5KFA+pu>ra<jzG1fa^_OKG~AdMJG5lm=F$R@ZY;Y{ZH1+|^sr$!w$lSm zi6wR6mn7~SAbA}%hWQMPhC3I1r;e5^O@_i5&3#^ZT|KM$%-ms~`>dV1M$hK6ih&*i zn(}&P2pYEAad#ohPCcu(`Rsb6hlq!~zU|U{PKS_(SZJrd<HdY#KhRTxJ89C6;Zxq2 zhNqOdu7QW_r`I2mp3-IVhQ3yx@|OuMOb;774FjHiDyUu9lN*sYdYVJ~Y*52XVX@Qb zS=*;Kozh;4yYj}7OP`8<4|^$}cN)iBd@3dYy<s2)69mHo7NY5`)=Q&{l9evn3=y~! zvGSr#W1-~!h(PfA{EHYxYL@v7uypA?s=%IiEHOyTec^vWC0W`MQ6)ROo=Y5DN1dTI zQB&BAliYzW!PoJO%K)XYkWzL04(c%?{Hn^r=3f|@0R5_Rq-s&M^s~&8{;_87S(@Ff zE1j-`udwaF{~hP{IL1m3ZP`}$v+9ZAXZlUk7qN8e_iIg1W)6*yA6IbI>#~kKJQ<k7 z4lXueSiS5HP45QlxY6mOL<r^{_pE&2@7Pmi#`NxW+stS+i(W}U9FDKa8#1%&%a5yt zLf)o9>ROxYQOA<>e_ljsaMSCb`vrs+Jf81EFpQi)G|QRowiv>4D(Gs(#`TsqzFSq+ zWN3=ORb@UfFL%kQ?>=hno`_xGW}nwViI_ZcT#&V7sH_-OQRs5GXj|_6(fj?W=Of#O z%-kLWLzMKi<jUp6a=*R3|C1r%)p3UK%B+7jW%}E+5r&KYyEBW=d09H6cHF$qEUTQ3 zAN^O>gt)&B*GKUyy3*w4y`tvRpD3ceV?VxCUoR1u>alJy-o!=Ug$FAinmW+^UKzvZ z*UF}we(9B69-oN@Nih<7wl{BACZ;5VUM-)&#N(}6S~&dBFM2%sGcE5g&Ne2NDSArf z%0D#*PkEKSTo&WErk_Fu7jCXEl-{;=dyfVe$@t!#TN|Wz-j&KN{$^J!W%CiE6=GBL z$uxXj?S60c2%7iJn!^43v7}My_g9H`pKx$9WQ~XhQnA?dFXhc{gu>rjrX93pysLZR zsVS_+>dk$3Z6?nlwC-1pbytiVuHO4ssi~i>UhzL(TD88;KE5lwobaGW2PI^?xwTII zr{zO!NZ3e^e?Zvh&n^mOS&x11P!QfRw;UW7@Ad>dyMOgz)JUf3{AP*plNr&NsF@RQ z_zm`Xt$a7Jy$2MtLC8+tW^#HW)K7o=-Oecz?|s{rr0E~vaFb2H)b=bl&2Tp{Y<=4u z4N=xmewvxPzQeB_F=^TNG^c%iR~!>D?ZFo8xX;Z}&sbfs+WRZi@ABixe?O*C${{89 zHx9J5Bj>aGLf*@5d^HY?c;UfpJF392((HKo@^}8Ro67pP`Zo#=t)~ZNU5~!m60T}V zZbRGJTSY5?qT;Tn`?9~*zfYaZFE9W1tdF+UeJ>nrT|cwe%pTDR`|*6MaV_VK<u+rf z=+8ciz)O+p4VL7w8<XB}kNJ6~*{ndZH}{Go=DikDt}ekLNmP+yfg3~mV$nyE*RTNS zQqT2hN5h1#<6}I*dhAYabdbvJ45TQtZZWPk$EJU`wjXg{|G$fqGL^r_%Hd@<mk{v) zPKq~QHvYh8x_xc@4)9L7|2emh8GQ9MKQ&wXFg5nf%;uDGO0RWdmtRb>vVR7W{P(mN z(=R&JWU5o2zSZ%Un^)&2hDA>W`xFPM$p<50+1HrL2~MDU`K7I}MOF22Ru7T8@?)a5 zGv9`(Z4pvMUT$&>hgmh){e3TO-|ZSKHXLG~*tUM%$1?oLaz){6Uh?Oon#xDLQRAG! zM35(!72YO;y!LADP_$Pf*xOmnhX^CYGYA2Q*2N7l4#Ps`+q^PldMA4&*M%jcK!Alt ziX$~+*B*j&4J?QV;vI+ff`O62DDMX-)01k&sE1bL>dHq_kG+L5GQm;Q7;^o}=_bs9 zow}1knHG>Qd=~6Y0;AS=WP=02$7{%u8k&(B==?(R8%$t0*e4uhPmQvsMoEYajh9H0 z6f_$92|0$N1F_Xx!6`;JWyT95rmi?pOSMSzFpPHC8V{;6#W}K+Zs}JF*FgSJaKwS^ zaqac<a*fQbQq%I#?P?&c#`ml?iwrRzQcNJWcIp?#-eQ#YVO{ohO~K~@7dqVI46(zm z{?y5mT1L!=cbFH0AlsGddIgDbp;lAj+Bd@Es=tP;v8XRinw7R9wJT~j+~t{@0)!wK z`tzjl@+VbR|K>=G;Zz}}mn2o+w=lkVknOnK6}JwXg<KJZ?83aLyq{(RGpfi|^$Cek z@^tyCTAwM&B$jRx(A@miwvy-%*b$00rB*#aG`>YnR<OvJxS@)!(NRQwGqz(UgM(4n z>Q_6;yII;i`c;ebl20GuYW=fX&N3luJ+X`sA3SI`QiRb@WsiBP=CjiGZruSuZIrjZ zk;Rl2m)P<o1m1x%{??a%G_LxmshLtY!K@MNUmHse@xf|EXNmN<PtP26t`ByaziOLQ zlhF(jEt2NPRZr<~4=vS9EZf!8NDGKFV<4I6VLF+UVBO`N54uBBJyODiK%M>;HNyz< zrk!se{-dlBKkQ1h#RWD9-#hEvDK(NRZ7kqX{nI_R)x#H7SoK)H{g7qoVHEfYk>*5C z|LYRye`a#0As?x@+xGOQ16L-NnGK8%Renf8>^o3jrl(-~^>h|Pe+rv|*O}ljuqh5@ z-Q7V5G08paX<|`np)&xq&eE8R<IF+6&u2Ff4;i`T9D8P^=QyJ{1_N<&I^SmR&=2Wx z58l%(U9qi%Fn3dOi+&t7wV}Wa9Ac17?MM234@Txvo=<R&%*j3nnTA(=@~{3?UDaRB zd=k?9yQQr(8RbeX-|jsBJb#*M2jZoUW=xTm-1+de)XeX>*nl~R;EqSnzcS2GFrFEN z{F%Z8VYRyKOgDbEf2Zk02)&M#Fbz7Wvcq-l`e|0)!1U>a#jDY?nN=SUrs{{2MAcv$ z|Bnw_>y>&(+*wT7swBF$&<YFHmm!8`(JJ!Q-MddeE^gO;(bH~AT^LIe75|xO@<hnr zV1ZC0Y1M)9)u|TQn2Gtxm2OsFN3OrrGAvRs>fy2E)1u|VG9{fR2B(J5N{jG2^!&Kd z<r-S}G~d3<jN1Rx>%3duMlGM-Wci(Y{_w`CtO=+Rw;aAm65a~DderkE)Y#_<>MXxY zZr8{yf9^=V{rl9X*DN4A>n3F?`KW{P!@<5M8;1HUEt(zi1m-;Al-`w;T4Jsf61B8e zD~WCw`zq6lnkiq^*wC3}Gr@LJh|R%AD$C`7<5AWql!d^@NXE{%YxA{hbeF}VzTpgT z2&Kh=VB!F9nE-fUYh`cZA9NtC!bP}v7qOzXrp}+H)NE1*t@^t&Mwvk-`p{hWxd+)G zQ=*5QEmpDQLa_%eW8`*8y{7gjB=1lpsu?7(IFcR^63T&~g#zuJCl|<9iK6OoQpT~? ztFhU9;@9&}sMMpfS6ve74Co+(RUgs484%{$Kxy-5=MwUH@dC36bBiP}4hNV7f{6%e z$A~&Pv_BQGzy4(Ql()*7o`<zds>1M7<*`+oABbSDBOF}YAe_4B<ll1K-5Z*{e%fQ| zn32G2f|ys@nAhB(r3O0UQLb22BbWK<@S`WxkoGvs&uPpv2s8U|`%v|Ta~TQYH+8~4 zA(^SuHQ5<VRG6p3UjoO!{9XKVyZeQ3{)GsPCuYC{_?+QTIa3p7OA9>s86JYhlLp{T zsZn-B4s$XNpLiWqbsV_j;#IwoV*s0b?oL=9;X(jL0R_3XT(_y}^u-Bto`1Zf)FVCx zAqj!i;w$L<V09;%e?VItV%kDnTU@uCPXy3BR$IKDTYS&9_^n)(^5Xf&?Vxc9LPS8= zNrE~Y!Bjz_)(}tJK<wB6G99;E`c_Mb9M)TVvgs;RL)5G=Z@VCvwr({oY)3jvKDB8A z6r$k9{E3FZN!<;RLqQVm&nrG~T!Xz2z*^6Cw9q@+-_bfI2?}tMf1p3=ZaA}}|9!{s z!rh2r*M!f*M0VF$Yu8lS!}NWE!a;&^MuHF{f)k41jEm>S?b?m*+W)u9J-h2P>S4>U zXTt{IfdNEy0PkcF%s6W<95D+Af_avRuYs6zJi(L{WEWnub0(kGtjG}HW^G$D@>J1f zXZ-i`**hs{-XS&dDyv}ZfKbh#?C#sh49s)fepC)7fEpQd;T8LxL=6jgz~Rj)aF9^v ziQw~As{k2QpfG$W+r$GxQqDp0`-7CWgVfQ3w55aeJ@527luqIv6Ne9FM|^|_GTiWM z_<2G$dij;nSFID0*XYMeFa)O#fT<#$)_E^&!&(fRAQVR;))6mMflxTGgXwJf6uNbs zH=TZ-hqv(xj3^)T_Ka7#^$FR#>r}%t_JyN3j;8jX=V1)-NW%=E*$UE-1DIgtjbcFP zK#@8yU}uh>Aq=UBMc0*za`F5JDs76qG~?#;XD7!fJMVda_Yutyvll>nMEj3F^M4-z zGHpP<S|Smh1@Pk$3bOzx6sYBlG?@iKNgckPCqN|-BFe}GdY~OC%5ukXY3GCV$SAI= zzcTC4-FB4#DbX_7u4VF6A`I(4z8ta`ACAhv#Nzg2574&MXom`rt2GH{LjWfhp#<N3 zT$iB0h=gOozC;k;3h-$i`f`JF;C*!j<F|`vKcd7iVMIIdj33wUfBb3taWnek@6wOk zy&r^&K*BA?P-0DQbVqdMYd<Tf(bf0t2}r-gUuE213`fl0a3VAdfWd%T9l-gbQ9GEE z<7`4&Hpx7SggcHzDT9O?N(>{i?;(e6ObdS{hXgmQC#^quEcAMW2BTM|w<|Nx3S3s? z5w_FW@)Q8;XQ&^}Ao!dBGI393umD%=Q=xKn5NX4Anxo&NUJ*pDf5ag5vXG}7kVq_q zASL%px*QUN$3$Q;tSLJBwgpUi2%Qz6#<;6M9<e+gHQ9#z$IiJ8e~NavXktRo-ib*E z$j5%E>9d@@GtyfYp!OKSoOh;IPpk!Va(*yx6{Xo!0&>c(W(j<sxrt5??p}y=*bD7d zl>W)n2C8U9@U<f-5)oWjfCUz51Oxd}A4T9XPn~}>en<Z~{t`%piNs<eoS%8d2Cten z)^gA`=3O*YJZli3ZOZ#4nh5M<K++Zy^T#D{R{+%Z0ix8%*$be41Iq5-i|cXtAiIW< zR--V1B$fAT6#rM|SrR+AWaCr0|D?rjfNidEeJ#A_cD9x2G*Z#}R!t>%f>p*S4;x6B z11T3rd|xMCE<8bGJi#{uLpSVo0mi`LkT6n6I0wXYxrE+x`$_&Ug<L;w6Mx>sgb?Gi zV}~UPy6U1YA%hPU?Poz+2MJJtYvpi&zyS&LUzX<t*72sT=XxVdry6Q_S;<znGjC9# zxL^?m0u_xOMWeJBfh^-hoa2C&cI4ymP+kTMTw<r=ZhK7rFX0uWP6iU1NWz;(40S#O zk98L1wo0s@4Lp!3el+4^A+)~;(7IpmlM-o~Fp1bPXs{IxX2j4%MO1Npfstc|Z<=>P z8ZF?UF{7U*83`2L2wybZ)MRTgG<4|@Gee-Mjl1*icwe0wNq|;Z-_LE+H2gBICluM< zHul2S@g#vePNq-K@jsrn%`wmuJlfn<V=atj$d@9062cy6C}oK<%{$V^BSaeF8OH%y z4ahQvYB1Z4ghf-N_f`BL#93f1P02PTbj|KyNc!AL0ZeKG@aPosKEbP6)mT)zW*;(e z^S^a%R69t1JCaK3)a$!gg{^tq)$*G5U+L%ME1}0t{$GFcPUlH^&DZ$+;+rW{2>W^T z^%uWk@ZRC#_J#j~T6(>-?T&!og0SNVU2o%Ct{26o9m$)69>TB28uaA1XwD7nJD<Xq zo1T1Q_)o>mJaM7Ij(d{Jk&<5O%-V$0$&v%&>Ta8{=}55b5ZmlPQd9}2qxqdIc1@jy z?H4<CoB7W~4`xfW`-i=*r4JXX9ybRZU&|b=G<kih`)ljnAG_$?YAcZUbmwu6)~ZmB zuQ4U3l}7K{_2N>+L9K!rd-Y+qO#u9OwfXq(qsx;m55myzAM7m-txHb%GQEL;UvT@} z7U5Hww7P@B^Ti@3ivleczdl0w)516qWI`Qy|J|1t9LRg~?#zl;bnjB&nTC8!K_e|q z7;+np$El)DX<PS%Kb`ZvHpAFFOOf5C9$^imSqpbF++Pg-Pi394d?6HNgUL%loqIV6 zSP~&p)c!s>BUd--q|uk;NlM_(vGI(^%yEdk`lL%}AI{t~Gfv+n7k*2po<uL`&YAqU zEfGN%`pKu_o_Ztx=L>nlg86oCysPeArIRSyDbbgprP3_4rVU?-<#_y5pcbJ0u_h<+ z<>bTln;~Q6JyHds%Ch`OU!%Buk~?PcoJ%IjE`mJd;vF0>M;_Ql^Cnxf^j-@$)Qzj@ zOA^BQUR6{GQM^(jTy7f|kIbsQ_h2CgGd8UHrsSD7xq~qb9Xz(HZJ&R(vWu@>`WSgh zi~adtX+QWV5E;V^S}a+1{A?=RW6gz3>}a7O@4se_k`V6eQ%jM(TuAV5I@7bK?bh%y z{~)k@y#KPkf$QdUAVCnUL*J5`A~?Q$%eyW>uqc8^Vri!oAAXQ2cVA0i<H&-)Tm@LW zvI$bFm54rbwF_tisU}g%sjK=wTo4Yz7%O+5TdlO}_!*WqGzqjNY8dcQ?k-XO%}o{= zNzA&dr#9zpybv^{)SmmuQGmsRubigDqUZgJ>pL*n?^Ib0CBxst>r4UZD%)`LG#m+& zyAPg}taOFf$oi?iI$0xEh8nBzho4r3Zx(7ACAs?){#hs%+bTV&6YLG-No4@uk-|jR z3=e+M8e#m-Cu0>%_Z@NUhrRb7OihmYJAdd<oSE#UCW>aHu(Ya~EVqX%O^S|?{@~Xu zABtAI{#yNoCTw`0BweTpD4T<BOf;jUBIKNKC5!I+>ZlNrB)*I%t$#AEmUOrjCdB;u z9b-?TQ7}@bpU8|lF7;4PARUjf6W9%QRG;<$mt@q&scV0XEC85S3~u+<FqhzqT)g8c z)T}op8#6#90paRo>Bl-0!a4H)UA(3jqmbLLTsv2Qwmp*EHSlJ3;oiZ6xnZhiOWUgl z@c8!!4T$>%_b@~FQ;~>!jj6j2xS2myjLI}MrUgWCvuq2D$<H^YKbh86zMZ=pz`;#_ z6GUI5_>+-Jkyix0vl6ni|De_;g}$poOZg^9Ls4r!J*S6<?_uSHVTq*0xd4QXbD28r zrD&vp8%T`N1<BOV1g_x$aF6c@6Hq3Vdf_{e3ZYdIqn}N=eK))kGCrfP$vm_d@gpHb zNrEp*2g#8qlf24}DaQ6&bPMaCU|Wket@Is5FpDbyv&zeP2j#n00e&p7rAXweXSZa# za?cY66r+wOwc{A1OovI7w)hKMZfPl9#%G#r*08-ND~HZ$k0J-F^9UJMpou+ldy_4| zqO*n=iwk91K+8MxhEcefdRwBF4;|8uMcresob7Ga{U&_&*l3eR3=@q|bB8L`Iy_N` zk(fHPVt|SzfkNC$-Qkgfm0niWLWHi=vt~QJC1*`udyj;7qa8w4jgfcsNo(j4#H&s; zo;lfEA(f?DnI`#F1+H*HneY&krqC?9m;bPuK377GYKtflx(=fbB03an8DRQ#^EFDy zrox7{dWE#N);H00K~)+_p<jWe|JrdVKl}FX2VX1p>kePRikIa3bJ`4R0-VKMZ7X4K zklMEre0HnX<VQY-D()@@j(@QbUQ#t`8ID0oQVlxtTB|~^EA`W?YWp3AX11*i@SBTY zLbf!1)ZzkQg}TGk5Fj^eKR!S~%#YIiNL`_9dZ|_Fp>BJqSLgR=@u-0W8dmxx>u|cU zwZXSe@RRobzaO-vtppPdHMXc<o`~Lib$U14K(y~pj0BQ9iWx$`tiK*qAuA!>rtOo+ z0FNZ0Y4A&RfpRkv`k_G*UEflJ8Q;+yC(bCWGO1ksoiz>@@k1GpIDVuq8+){M?*+@n zT^|D%aHs&Bhf5X1ED+BGRKvOii|h)vYX%X<C0<K4N!Z~_0Jal#l05~kKO)0MM8(8` zQ^*YM=<hGz$lpz`^ygljdmT@$&LCfadZ9dx7t>2b(45#{0vRbLgK{30&>m-AD23R@ zDq4&9b5c+h3UsH#w3GYoTz@om&@5yaMNy&!H%n6l{<Dz&HoFae+?1K^Ya&tQChGSZ z|DOE^?fur6){H;BZ_yp_QOl92Ed#}^VUauF{I_Oevz2Ph>Xl<@?-c#=-|Voe*MZ{6 z>{Gm<6pfz(2phTx!S6v?&$D2Tk7e5AHoDqe=|&D(F*y4z=eVtV6*`05iL+mgf6OG+ z>6wZQ4p4np)KA@2h7Qu!!DW;0iR~*J58M|!O)`(#`VwPeTl7Fhi#Wxt-h^04io~C$ z9C}a28zLk0GEsZHnJ#UXTr5Y5T2mIoy*cDYZ5)02=2y>t$o8F__|k9IWIF)y5m4U9 zO(K8GHr*eh5zAs6gvDauZq9froGp}W<52Z3rUE6WU=A<N>OJzr<VGY1rO;P0aU%SO zX#xg>Pm8!|hl^Ank!Fy>8?0&nByKTO9binbKk2F8>Q{f8hxmm2IZBUJ+zA9$JeAHr zCT(_-Bs`TM-AEf`elcFf%@RZjAjRJO1J~lOxR+@nQF7M^uExSBNv>a$NvhYOw8h=% z9H`y*yN?iUbm#DO6yDX~k1C_6dk0WO(UWctic+4DOm*>=W-f)m*#CP=;o$9C(QJ)m zaO~gd0jS*pTP3{w!l{dI?*IEeSNCu<p2E=7$mjK2AZf_{z0#Hh)=xS}K7Yg`d-jX? z1hF3K-|L7D`#~<4sso&ug-DG@M~!tljya0tM{hCsyZuNg7UG)ONXc~IzY^$8nrr#$ z_Q^-{R0Inpv5++YN=-yG&2h1tATT@VY@rdXqvin2zekz(U^?!BGoC3LdykEihVLzn z7=e?vZw}lCM6-^}E!+`afALT<NxNcDKoNBRU_dkq0UhU{axI3kU?C27#8?K&s8!i< z#P`pLLFAiqJ0!~Pc-sFs*^COd7Sv_DSNt{UMOz<;+Y|AIEH1*3wDtf|=|PpmO~#9O zs-KhoN+2-~fXVp)r_LaszZ!LyDs;t#4P7EI$%MXgd0k^C(qboxPk)>`NPCK4v4|I& z9pv3fpd`mJ0$@xQ>H>*s?+wNrKE&PgC%&Jm%81Y6IC30H<9cYtDB$bdY(c7_ls`~f z(!FV9jhzris?l5y+)9*i1Bi&HLHA(l%B6!8f*^4sKy_<AwZf{D>^sGoZC53NzH%ao z7<4UyQ;VbP0TrDqAvJ@?JAK^-pgfMJ%qXHc8B)w3k%kSSQVoSUl6i2d?Dp>L{s3v* zhn2Z^+I))-+t>$m=j9YNEZ&v~Az++(B_ephKdD`tb7iE#sj&R}V-+W*1K_xf=dlKe z)?|6;jHpzA*h1~JV|dK?$^gf2p)9Cbha#cdcaJ%eXhi^7iG#dRLs&r)>2d4>ZxU{6 z1TPX`mPjouF>TV4ri8T95h}Cm<Na{-cBT|T!#RCRpP-k6g5weFEb(p?08s>qvOR!B zCxIz(`{B{Qy$hkK98%sSVo3?Uti1MCeAhaRo}PPQ7O4T3oSl?}4F^3B0%H*aj#!+B zQq)>a<_N(qF(}4DB1WzzW39HtI}Ixxe7Hj*pFvXCx*Xxn2M3qK@9+mPln2E?P$*YP zn?yn1l;et$ho})(o&kE%X=`*DuLMADnuv%xUjB^hmB28p2LOd9@Vp*#X)W`p<A0t` z9#)8HK^lGbK^9^0Nhf8riG!j%2EvJh*2xF~34rJkfD1V!hy3T<4cnV0$)}P4M6LBq zJf9m0pt{PHkdv`zv+kuO0&#`f!)o-nftyoGg~2>t_gy)AHREJ8_1T<)+A^e7Me58! zE?iqVDq+)y(t(rGxhjeNC>~?+f<f>DdnY1RO3lxaFjzQEC#=YK%E*$Y<+C8ona#D% zv&tBvdw+f<{l&Ga@Ct&BC0;ajK0;Mj2#K)1;Iapy+bPGHnDnzpD+^}?-z-(W`A@Lu zDa{Ky6rB|i12R#CPYc-N1P&0i2LmKN73k??0j!~W2Wd%M0(3=PMUi57SMa@O)%yUU z@<CGpTc(^378-*8%EksB*sI;M251_%5}jh6q=B;WkEQhlYnOzOFaxDC^$MYp>GQ*B znR)DJNz9t(6W#Rpu!#dwOk54c=as5vWk2r~!{C54wQxppN;NPgLUdS7J%q9${9Eb- zAb`QhMYXz9Ouzj7H%8*u8wcB`Wd`m&te|OvnzlVArNUrYV)Drz-|ptiu3KRoxCVDe zWI&9?{+0UaE;F~sxac_XoqsVr->>aCUxg1QRC;U%JZnY+M8+mf*}iYeZ&14*3s`Rs ziZBxM?%*D_0z|`82Rg<l6*HlXbjpR*AO1TsJaSn?BBKy~omd(!=zsv;NiuF^(d3(r zRl*Pp^NegQGQ|JQ{C)N-)AqB}U{5`tixm1DRY?i$AN~~0mJ{jLRi<jSt3{$~0f%F2 zB&H{(A?K7u-qY@u9yWAC6qE>DY7)NX&8opiPw6RY`C9y)y3Zk==%eG}>jI$@H77J; zJsU-yXE61>)*xb5bR7T%-ZP{6_jnO%2g;6VjLe#kMo(FXn*`@Ykpfb!pG8d&<fN%m zL20l9wMHn*!GB`k_X4tGYKrkB;vL_rt*DvFzlP2t@~PGCgw+10a4#j~(@=%gzE*vw zY+jy0#>YDw<1FzL<K<Q&1GATg4cH{1LeRfV*p+f(q}qR<O(w_Di&M%k+e0>QIKRDu zuWkqhR=6aKtPhr|tzO-V*B%}{^d1*H6{x|haYN(J1x&jq0OA$6-)zT^?&<$n5+QPu zuq*ws+G>2NnDC}B_Z^O0{2*TBLZoyZAZ{|SclzSacT60V^0`X`rLlJ{)5t}tQRnz8 z9Twt}I`c>wpjZzPuYWSlDWY7F@Pm>+$oN2v=5RdwYBR8On!Suh)pf2UWLUHm0oL$8 zr~vR}leAdU(7upl$_*M+atZdxi!vJ}bnqC=e+gvK5IG>@yotj!9PFPUOyVSi?&Z=D zB$fKoB-8fJ9Yw{EfQ=&3$dTmkdkAv)NXRf^K4<8&geZs8Pw=S0J0D8Hv_n!&q#F?O zOKtMh6UO~YvyxMiufEA3F9_0?YObsM#}gUtt@=P`4I+c08JG~LAmYITWDTlnlNyEZ zH%qcNv+laI80b61OgkCybMxrEPGnZG)$&x7;9d7-Ym}0k;)c{Gqj4E70!XVkD(jOG z^tin+R)T(dP$fJ8rb)1u`}k0grCh0dIqHoz6sG0jt-*~l5=I^*`U*S{M$6U^3*8JU zrmD03-BVJL*3fRzFqYO_){5Y09xNMHi6ZIKIellCbI;n?RpWHbdP*Q~Tcu`zKWb9Z zxkbPKOn>YhxM+AG-FGaNV_P9!ti>+HWVScm5PGJoS3gi5Rl@t}7ig%Z!=Z{TC_!J8 zW`5Y8K74cWXqzh-2pURI{Fj8JR)1h!AP1c)6OysX4PE<>^E7d2#vpi-W7HL@%FT1A z^5_?B8qhSZv6O~{R%cL4|A85yb^A5?p3jh^$lRb1ngu@4z&E{ggV7E8cl(GdM-4$! zhuBO2_IW_(K*Ghg4b#_5{KqE5`h<85-RNS;TX*oirkw=E>7jo`7Z2R)<lwSTa#;f` z(z^HHOPp{nwqi@dBv9Rqbuhta+&652gtsPMZbcm`k>|858#1+udYw?akv8iy<y0{! z+Ec0=U<fIbdS#lZGOliIuKoZEPzh0IV+{>?R1MC0<JDd5((_5gd)9~M3>_{B%l@Vp z7X*zXk&zhSib__5>R+|UA@qMsGc?t04#EPA+Hc$HLWhea(u4nqD@uDSbtFVk57J1m zy-hPkytwo=3_Dkop<lZr=B>&yor5F^Lz5=TTQ}&Jg7nshlx|3bYKSElhLqxlg0ng@ z_+M>O6TTdIe<0n&Sf($e_)V)>=(^|9n^GGG%nqr<snebfL}Uy-zZ>y9Uq*t7qI<`U zyYqhlUqGP0(|+Km<MM~q#&KmJN;qKb8~Ljkfy0haLKE!5KafLiz$lkA6`21ypx3GU zkyG($<9r6k%Fse-@<J-?tv^Fajk!xqyl1z~!#tRSc_%bKj6=?;1bcgVQa+rhk2<NB zx~ZQ!s;9cDuR5y(Sy4jUGw@JoV~zsP-{fpd#~?#B5Jgd%daskMJk+cetN}dKgL>y2 z>a@DDFFUh0yR$z#v`4$NPdl|&yR~0Cw)2SlHCH}7LxhL+L;*s6?&lQx49k$OD#L{8 zJPSUQgZiQWLJXXOLWlMFd^)J#`^0ejGpw<e?T6e+%4wGFt#`{31$8~+L*PnHdsXuA z;rMyv!4mMpMi&T!r4GJdJmR>Iw~r0Ngw<PL5!O6f4xVMPK%3_3M4`dMJrp=Gc<(>_ zc(Y=>%*Rc0nS)a@cw&t35$rT*XNzO=0$T7x!sEo-Jj*@I12qsr8&HE*i%OlL(9B2u z0<rDG+<cQKOp^3)&xdbImZu&;Jx^FFIl#j^P(l`b0#V2V+}OL+&-DA%ywxL(gC`>A zY(3YYX0dc6+k3iUjdwTbMi%4&H2lLmP<-1TKD-#t#zWP|D8@@pWO$Y|M~s3Ilh0eQ ztr%_p^*>Mo6`(>rEVRMxJ>rkPXnc~*uaiblr8j2NI8S2cmTzdZmOuPGI4l7kyu&>F zxIc(K=|f(iZ_=xu{&jQ9nKMEXIEI~=HrHH7Ebs!KP|dj6u0PC!H%JmH(7-J0$UJ=R z?{~lVBish+d+!*`J8gFr@IqvaV7@2?<!eJ)Bs^;Hgz6B_vrxYt<$(|=gL#C*f(ai$ z*s}+ZU_pZi5hhf)kYPiI4<SaBIFVvSix)9w)VPsjM~MDBh7>t+qriUsxIG*7ie<}| ztYFFt<-`v!m@HMPV(H2iPF1c_RTJ0mpE+{|@!=y`uU@`<_vHN}#st#5f8Waa0}0Rn zC`qqh!G;w(mTXzG9JRvJx|VHQw{PLbl{=SiUAuSjzWw*l-al=~MzP|Vldvk7s&FlG z66%)W!-Q|XYV|4>uYcq0`E$BAZ(h#+_=1F5Z&4FM{_2$@s5xI}*RNs6mOYzxZQHkT z=hnU3^;zG)9~!OaSJx|6g$qa45(ihTS2~{~=P8+2wSQX?CgmtlAVKZ};pH3m?Hx5j zYl!`m_imhb@WA26mp`9=ef#(Eixp1X_)nOTCA-BEBN)M@6_|K>j3-%Sd1Vyq_HqwC zf843(9ZIsGV=vVb>Mp+zK@3sE5lJkO#J;pCF1o^e;>C}}3`~xdRvI+!6<Uh_`KL9t zfHTUdwBFGQl_pLZ=O1^}iqOO*nQYR@C!vH=Ag0WDMyCY-!_t;2;IK(BSN>y#K?YeF z<rZy@GUvVd%*kh-Z{VROk1X10GaMzO%rh+Pc+}I+KLNFG%6h6a%%_}KV&#=foG9=y z7LB_J9C7l2$3ytO6R6F3$a#mDCGvnq9&j*QGtg5}O;y!Z^Bc6vl~&9NL0t4Wf)?ju zmGvfFs=<dJzCujxn{mczqzzQ&nTJ?DS#8$YXQ7RjqCv$`sU;a@iG>S2VmwYdS7dSJ z8EvRk)71Gq#7CTN`k`hGDv+Hg9CMhJ7S*lx%2&yH?d>-re*J~-q<pIXA@je&aB0Me zOK?FB!Ja59h8u1)JqpB%%lT$6V%}(i7;xlikEu%o_Vb@;b|FROTA1mp<d-8#O6Hkq zuG!|Ban4!ioq6ur=bvphN+7M8>ra(dCVPb!IjXS5FkK^qNf&LzsmDE_vCg{YiszAs zDPpql1Dtp60VkhwwN6{@wb^c)=DlXtSMH?#so9)=YT2TOy=$03iAdmfTkydNFWhj! z>xLO!d)mb1mdB9R$rdN{;3cqJb%LoHZu+T*<Pk@<XC80<frpSK03p>IdJ+0gafLp& zlsnin<<8uSeayXfP5)s=i5Z9pKKL1GsHODRkx!mJP4j6EOqP)UZUq-coUnwKR9t~n zQCh0W2Oo39X>UmnwIYX~cTCS>mkq-KSb2?h?@R9a=l`zre@Ll;h(0tC<PbrkFatpx z?|lU{AX%JJG(|~fGPux!7HB~W2IXWrEExqav{96<FsXJ%k%u?Rvjp}1Dja<}ph41t z!i0b(Uut2CTEZa>X>>z|?U122Zg|6Jl+cAB`Nt+^5QRt#F%p|_!wfWZLM1M-BLd+^ zJ&HjK8@+-jx0uNy3=|pY+z1y%ab2GJ(ie?MMTEN`VVjglK7R;JesZgaH@r~|Y1{%A zb+lt0W0A)^wnC46jD;v-LB~7d!bL$mgeDMC#5ByH4^0vOhd6Wxo<T7&Q0}8-M~p&_ zdi>>bRAdD%Uc|8HL?=<BC`JZ7cdjV$r5@xM<EP%Ri{Z3Sc1Tf*y<&HgHtEY7?)b(x z2+0dvMDSLs2uzp&<Pv4N1es;xg&zC{2tc^O35Vdq4C>$xZ_MLY*8z$6l2VRx2t+%V z%oA_WnND@GMPK~jhc<W-iy2W-7QE0xmky*%R&cLPNBPV;*Qqackq#cHu)-3oVvjqq zP%Hlg=tJ$&m46JUYv7PZF?gX1T|}@Iqc|oqml;x#hV(dvB!V9FkOU_H!U;&Eg)Vr3 z(Pz}d9o^JXK77;~i0+i9J++Go%{dZkX=4<1WC<?+X2OWai78yN&>Xo^`KK>lDjfG1 z&Zh`*k9n8_9Pim+puR{DHs)?G?ySZ$o}r6a(88n8TP9PRi5$7kwJ=!X1ta#>1uhuD z2wWh-2?T+QGL6D8x<Cdmo>7cyz+<A<;flp-7t|8@l(LnLi@xr5S2#RS3r@HJ!(ws^ z<M5LkKe8-936c+RbfX+{Y62w6@sDzlBS|-P=xOmnKW{d4FW}LaHqLsCTg2j+EkT-3 zDmcYQ(UrM!g^3mEFazTCt#43Z7>$nVQIDn~70BRKHO9CXAGL8ayT$E!(Tf+!ekCbR zIfM+P8{Zlvfnng1j4Hav6bY^BQhgbRR^>$h6@2_-bft63z0x91rtAeAazutK*g8+i z9ICk$wlG~2^@>?c^9n>z0vh^Yy^kVFpMy1QHNXK5Z=OV~7F+L!(i`K4*3E~$^V=1+ zpalKR01mi_lw$MI52y4+#sK9iRLnyaa!gcXjP>Siiwqa~F=aUAcm^_JAq$VzXeT`J z@|VFJW-*VM%wj$&EiPdMNyq{hPK^wf!u%4CBI6m~=&HU1lCLQ5na_Rpvut>TH~q;$ znpIGO-nbB$TU2AgJ^XWS^aYRqy2G`QphxM@_vpIpMZcVW1}{Wmrdy0DTwrSEsZpJ3 zRi9c{d2~?17A9DoAnh@zUeK64dK|R>dgD%xb+o2|joKHF<WBh`!XXX;h`t_?3pmOL z=LqFuf06T+3bl%PsE}1<skk3{%JW{n!3$crBA=0IP`Fl|ZgsEwFp-+x5oXbfoVYpN zy1MmqS^-E|NTV9vl=iRzo+|w54-uOXgc1Z1-86h7AF&Hq>_+F0@&sZDS-popz;P0- zeDz|PVP`miDZxaMnk5sw@X1krVVFF#3cBd%wN6g!FJ%}edAtQL#<&%bn55eQ_j!|i zND9AcVu*>1t{XH45=)jW&-VD>M5_^qY~SPJ;LwW0^P`pFSahwEdDxg!9(J)4CQ+<d zS`~PaPt1wEf{MxsEqEafO7R8%JS_hC-6zY~TIjD2M2y51kVuY!Ed6zxl1D$xK@F*A z)pOub3)bsnq<>Tc8MmOtO-kL|GH;&qogZ`AZ*fmAb(w;jFa4O0Yn)Ng;ug<fbUm;G zdAx5V*tNe4K~6RW;7uV4O3?8PB4M>(+nzU{af(y;kt}=2i3*TdvN*kCUdy@=r^DgK zgHwU|!EAA)-S__Y!7tM7RiScVvTyjkzkOzo0%^zqFQ+$1eEHvg{`G$g?rZV8_!6%V zbvlau(@9^BuT8)K!1919%4&6Vs<J+VJ9K1@MlCwRWb7!g0_7@EkSYll!Ao?)0_h5A zlFLCxfzG~R?u-J;0MP#bX0IbagBeJ{?`q*2{_Vw%OdbLZ5{Ba{jv}nQqJtnSw#uOx zbm7e)hQd7X2vLqqaDh=8!9ZXR2?=BS9)>|Y3hu~bqQpr_%4r2HA_ct=_v~T7^lbRN zFrf0~$mXFM@}LRYKp5C(0cY&V?13pL4_4L=3i0sd24e}0z!G944^b{r;BIv$$|=gQ z{(y=L6%l?I$4B5H9EO7$P$3JJKpB2zY{X|Q*eJHRK^jJZL9*v3JZ}_9u@uRS#1Mme zLZM+`&J<0t^mIZNQo#y?WD#xgK2pf%1Ooct!IdVe9zG=tlp!kq!SOsq_9TL2*yt)G zLyG|M8B-1e0ig>2M4>UD@#IQwOlScYGzO>K;}})x7R7NKD<UbVtz7DXA9`&TvcLuw z;TxRpPV_4gF@oBL#vh_+fu8Uh`H`;nP!6<U)V{1A{n5)_f>-VYr~aYm*oYh*@*yh% z99IK1%E22z0vrf|3iiMq=HVX3LB+zc9_O$gxFH%ksmok3B~{Y%N{`LrpvR~PVpeh` zNeo;JL>Hc+pDc#sAhIWYG8s*x7^%)3!XYE~paA6|930OdkTD{fPTY);Af-~Srb88~ zKn{4}6+kf*r*f`tZGlFx8v3Fkf3hsi(jmH{9Jq<<>H#C!a2DQSqLjs4zEP6S#RrFj zlOn|#(XTK6{qiqGs`QYG3u;0XeF88Mv&6paF`@xN?CvKIF)}4H$_$Z(h{7BA0UkUh z3)%n@q~Ra<!5hXw>GVY_DpM|S3M7U}x%4qHUGp_ZN-!;<QE;IMNeMOqa|%mM^;7{F zRE#frYch-MEQwPh_+lKwVLebG4>a;K|A8E62_8ZR>(uD_QXx`MawfHNJHaeb5JO=Y zW+g<CJ6DpzT!QsJGk45!c5IRGit{~JV;tTgD#n2lmcR-&Au0+2r%obt6yhZILfp9Q z>&UY}wR7cE(P#{mJY%9pbRkES4n8GxLe*k)#-Sg;VHWaW2}mJdNChH@!aBi>-AJ@V zO_W6cu>_Qyz~#IJOHTAf+3ns&K^jnr9x3!jA<`)5!6LOnPHX@Vo`D|ZfveVY9=pSb z;;G#hbV;}Kx%8mr6qHGul&QcakQlBmaWqREGIu16wZ@?yC_y7pf$EBpvBc>Zi=tp= zBxz1hO5K$6Ko1V!;1&*~P2bcN&8<Q9DMvJ@DFaS80X0zlj58SPzqHC9C}9nnfD)jA zqA(+0`hp~pA^Tj-F}m_nkpuL|Z>eArQ^PKq93&dJ;cU=IP$^4GQS~6^kQ~aP8;DWy zm|zW#VWP@Le1<~^p-0}v^G<p7^K3*Hj-VzKq*u4I>{!nm!U$MWby>wR3^U^+sSY3i zP=N}VU=e=v8+d5AmdjJQ6*@lY61bp1o~B!mu#|Wuw)~V?)pgkPi%<&CDll>hxL_7? z5E@cJPqUL;F}0|e&~g??Up<i4Mvxo)p&!z9T@m)hBu*UO!5z8*Y?1&FsG%BsjE}UE zL8201pAjdfr+OOZUo}?jo+CkSBu5x4Bo#JcRn|Qqu`h_hK2yLCY(bcQVk=?vW^s1i zummw)B#<5^XMwgvORwf`K?e70Ws&yh{J}`%K^`RS7W^O!EWiq^hi2994ny_`T>%%S zF&0_@OtKaUrN%mJG-=INvc$_A@BtcPp&06j5Mm$&@?a8#2^TIWYymMQaAC9m+H73$ zwgML<7G!XoHt1l__Haw)AC%z``k-;$Kn@te7D6E_M_~z6U<n$*lx)FniIrHND;Bf> z5X!D|-4wf6fmaq1aaEU+{$UsNPritN5n90(M8Os?iV#4c2~vO(LcwhVgLK{WxkP~` z`gT`=w?KVD7K*k~Y6;-nb9KwoAIhN)fJY6~zzw#52xb5WLgD2`!4_;+6bL~GG{6c( z0T+tF7IMv7{uUei!-|{$i*&VpE706n0U5ZVu~3$Yl+INB_kaJ4v7|xw=wK5f0TBQp z4r<`DXf1L?p}TD17V_W%Kwu9jp%~mY)aV!Gjzd6bGh;V65a|g=CW;LI0hl(RH%m_@ zfcn6IlMN1tKn5707*=9|WFcv0HWe^L2r|GAEWvFJL=-}}xt@!9{BR$Kn1cm_3Z)@` ziDG|KIEtGk_ZX>&-~bAsKz|NF6hz?_2Fb@9geB4!LsGy7;9wPtA$pD}iOUX@s(>*- zHi<<xQb>4>=u(RDI9gVikqo#GdT(!(zzMkEp5(v}8o?4QA=JFsK<dbC8{rM6)(T+3 zcI}q1_A+QO8B2<xR&2qkTojW*`9-mWj@o2B4fl0UIF(fyy#yHW++c{LNe#4^5dZ-W z;(!jgAPS5?kh!Fg8R3w*7=4R@60E=mgg_5|cyn_NYP=<`m<!ea#O^W5ju$p-)Z$o< zDbPWlAs@;CA5L?XVIz;>b1wveczTbo`ljU?d6+^W6fQv$`~VQNfD5?537nt^oPbN< z;13!>6fA)dtRMwafDkSLgTdG(xR0JN_F_qm%ap01A-bW#r9q&>Fla#wurd{(<NPAJ zqdoegK{}*G8lqnU8OWs^cv75I8dd%Q8tR~L<ZB8p;Xuk{ff(6wgbB^wc@b*43XZ@D zaG(f^U=OIk3PwN!kiZHkK@_A1j1T%bCNNgAG0aLd!+h+jX`u@Iz^FPkl)bvD={QID zA*ENkto3A#{=pk+!GQf|5iTL5jz$8X<BJJN7u;DA7C{jI?w}6XfC`R!1Z03q^nejA z0g*%Pj*iM`pyt+0&V5<J68zwvIO_(u01hB`nXow;BZW@Cfhp;3y}&uNMf;%`i&DJj zAL>>z1dDx}OIH~PX%Jf$L}3>~p%x<H5a7TGY9IqJ;0CIo3SQEeEg=-Rc#)0DIL2f_ z^e_~0!4kLtruQ$th+wO!2!u1c!jMK(iGsIAySu&nyL-xo2%;SFp%_8|Ce)6ITeE_W z25HzY`(8n`?noB$-~cf|r7F7)ynwHcK(PJbmx<dZ5u3Hu`xc<72Bu&NuHXuyz{9e4 z1{On}toypZ1t(qsb(;bX!CNlOx;S|USHYU(UORgKXau`<g3U0vOxn>3XrKxRI}{|r zmbm~5w!ohA*|Pr|m=R-;yi-PWp$cZ83-kaGhCB|8fY22921tQ(P3^0lT-_{uW|g(W zsr*mSx*DViVz$*Q!K@%Z878=R<%+=)7$Fa0zzVDY4!{?KLxB+(;Slry4(PxMqJYM^ zpb9WL#}RoY28qpP;kma3r2wIxQK}DWU<D*WuqK?sza=IFR~!Z`sGhgV7g0FMK`+aW zK*25w#jLJuvw~>Xj*5X1^dJjjzy{tx3v3sIi$N7cffn4E5f(uY;vf#{SqY%v&hJSN z3^|ck?+9jq3y6Hk?U~47xCX)#xsKOOp<@*Po`D<0iL5Do+CQXX+zFltD|51>$-mk# zQjd09!FNXi%~ikx!iEu=0i*25i+RC{+_@2W8V;&}o}FNq?_9^8Ku!s**lYQ(5`BT5 zJm6OiOB|$$=a7v~nc5Y8EY@?PxS<-bhnX+6CD^Z{BzMg{iV$F62yDOxtY8!(w-}It zk=L}2ctPCU`4VWk4~#&6j39W7AlTy>4r)LKPGO1|U9+V|8}K3865d`Wec@MdF9;^f zbOlo*XVw}RX~1{Qae)vhVGk|<267+^guoI;Arx$(8DdI(bM2^b;m2p-3v8JV+(4y< z9EMLI(UCakn=4UTVQP9_+J(OEfg>sZHb@+_!CNPADr;>`C*wdoip0V9<cGPwK|ljw z014h83#`E8(f8zI3K_1+4U!EJ`~VMNfY%LO1`?f3-TuNd>_JP1EbadE*~FiCp(hT; zcuAMUjH`j%o2fAvd~sn;vLFjm00&$E2KImu27wR=!4F`d2A}{5+Mo(#00!{D*!PBE zHhS6LG{bO&ODU;;H$3~bzcZX-II5vIZX$&7ZA~Sk;%9`_i$N6H*%GW?2vR@@;Qs_} zAO>Qf39LX6EL#rTV1ZA;ZUN$zs(}Ox8a#+Fp~8g>8xnl=iq$Jxyz-gzhcTnZjT}3A z{0K6n$dM#H!aIpFrOK5oTe^Jz2{We5nKWzKyoocX&Ye7a`aEgR-oJm`o{eIKG^x_1 zOq)7=3biRjh^?w3Z6zve)mOM)75n<Nnx7gqo;ZPGgh*N<HD+*`H8o<?xpeE=t?SCw zz=+_)1^o#)u;9Uj3mZO+II-fzH-r9#7gSt0QL*k?zD##uE2UN?UKJI}7U)*C`Vg6c zdPdu}M5bKAg%l#@*|cl#9rev`zsHPw`~D3)xbWe`i=#A`uNW<e4x2lFUQp>kr2?l% z9A))YtV@dy`9b98P<KY5WXWO<J-zz%3S;Be&D*&A`Sk1CzmH$0V|(@fY2&5JR7kN$ zV1Wy578foGF1X+;d6_r=pn(!jc#weA{L{~Fj^)Q;haP?iVu&+6R!=$HRC5$WdF4f6 zi|Vb&qAFFjA{Q$uCgoy|62_*=H|E%*p@>2bNo0{mGG@+?_Lw71SF+UxWt2=!$4Xw* z)z}o3Qf|p*Y!HodVTMT_NoJX5o{1()=KP}^maI^zW1I}3C!<7k%84g?5XllwKJldq zXrO`)Djz@f{C8B95$4ILLNPW9sdKVv$ICzBWcVkcnr_Nzr#mH?BrdLa8EL7ep4!}` z6#Y{VP#by*Ypk-$iVr^hwP`1+y6&p0s>S%z&#b}@OKhM)CCREd)rfK)jZ^UoZL}^f zH4!fV;B%}w#m?ma4?HD(3vRgLj!SO2=AMggy6UdWu0}$wiECWa&P(rlNLk5>F4dI7 z4@N_^3vj^SZcA{%#R1!oIM1*mON3oM3~|H~Uq&Uqx@bcVKVupUQ?~+t406aKk4$pO zCTCPnJ^8SCOT#L<a%a6V&rA@E0u{qeJ^bXe@;@j4d@jdA4~^Kd`CwF3iVfpPbJH^` zWu7+N^z)CaM6cvA&{}WJb=O{h?XS=N@Qlwt=759CC~m^YcH3^h4R_pf&rNsTcHfP6 z-lN7AOEEn62X^2fT}^o5f~8yyFNrceapR6ZzNM-cdTV&)mS4_OP($Sd&MRu`4SMLJ zk4}2&cFQ*Z$}`$fjd|;?zy1<N{S_5ku1?<`t%|IGlMg<@qLeA@!Vf?6Klb>;vS$pR zR~_!oH~M7XM|T^1;aLlgefHXK&;3S2{cAQixU?dRE9RZ|eENAlNlP_l^W6RR#Ls{E z-~RC;(Rq)m&;NufqF)Ve@N9nZE1&@nh`@Gz?;r4kN0N$>9li8#f)kQREUd*d<n%0o zUaOS{KM2AQig1J^ETIWch{6=AaD^;vp$lIK!x+kNhBRzpwvyBzb5!FN0ivJ}2_&Ff zXaieGs-Y2&h{O@nZ;4lXOtuWAjbeyGZJT-153kq|^RWUK;_yp7lC+=dF>#D!^i-0> zWR7D0Xh%R*GMyXW2*)_OO+dUD;up15#yskASlP-@KB_UkXJK)W29XUHwbiXXDsqv8 z+D{Sjagx~qvK6Y3MReLI$4qK+llY3!R7Syz3)Q1rwPK_xPl={X^+y{E!%ke9N66bz zr4?3+2rhWHrZRGHm%QwyFG*s&Zq)-HQS{s^$_KMoDs!34Y^F1x3C(CqbDGqQrj6>z zuL1rNY^dz!uu8PbVz>;Jv6SU?Zov!Qc}tAK+on6;2~PwLWl81uN8(cSN>1u?pLvUm z`BZ_6YFs2E|BC0<you0Q1tn!nvPdx$7a($$b6!uXV?i;(PS_cAqa5vM*N_8`%@qUx z7pb_Bo%o5;l(NlEt!UrMg5uGxC3L35`rcP$ag?P=XQFwE(Suyk3SO*fC^RjqQPUKZ z4Do{>Ly2PAu%kb=4Me3>E#01EkqTJ^kX2SYs#m`XqA)JW9OWnna<l<R*yO4@FRQ9s z?dGK~u|jniN?FP>O1wmZb+2avRg%PE4qFi=inp-Q`S!LI2fcN%ZS#^&i=mB`^~bKQ z;;UsZ`=KN)RU9Y6Un=bMimFUif;@!|^B5LTZLlh3AH*wWUkh8{obh|r7-=d*K}qK9 zue1%BWh(-jGk(;HvXpggY>$gv!wlE1XdNjorbsH@&Iu`_=vy_k!B9{oce~vG1rAL8 z5fqCA1s^@Dts1MMHuJR2pNtjVGF2f8h~Vs{8v~;~x{KfZ`X-U~An#E6QQNLyHLK^7 zMPheLGZ;POJmZT6PH|C;YKUW=Co$eh^s3(sYnU(?hDU~Wvog+oC2h1k-z(E+o;~Sh z6r;ceFNzTk-bwZ($Po%gHjLvOCnjac8*4QZ2OAb2#aSmtNX(!&74??%6`>R;lXR9c z9ZPx2in%dL48=gS{<s*o_!5gj`^qV`$BLt!+g_NdiZ3%c!jYBiJn!3KzQ%OUbgnZ3 z;W3V~8mb)i5QjGYT#RQtl)6IB-+8*+%u9k<nrZ&>QDX68HuH{E7)p}=oqtK?OczJ2 zjxpX?ak$!A8SlCeeW-z1oQje<+D5EaCZUB4>sYh+w-0Udb-D4q{*2X${q-Pb<E-gm z+sChCx>nh~r{xIOHmwWd1ukwO>svHiLC$tDwL__F)iMwt<tW?l>?`bWi@P}BcAy5y z=D`Ji4;)|ti#E*BA9a5ZBRnIUr{j|$9bbCi{O&jRHdk+rq=eXh?HR!HF^;Zwtg8!+ zx4*YZxra-9;uJsGMLQzzZhiQ}7xu|_E8fd-i+oVV9XZxaj`EbNeB~@}xyxS;a}fbM z<}|Ol&2NtLoa=n&JQs{#drqwVD4Z}QZ+X$n^pA45!yWIqBhZWgl_YS)I3t0<NLfqS zbAQ3(8{eqsplX#N)uPqU?lAY!pI#)apF|$>_{Ti%J6=da=Ds%h3-X3C4zbewG2+O_ zI~Mp3e24?<Y9|ud`|)RYlmZ>;_ys%uc&Uw{JupHU2RJT29HGOb?UY!;9;hJ?d1$^d zbf1SjprH(Al*nhmqdUxN)h%woA_zf%#XD}_#WW%7AL&?!@7a+KP4Hu#u21EX^3e~w zTGk)qkcZpl5oO}6UKm0k1|>%Dj=A@w9N+lIB4*%*BrxI~<X95UyZCosu)z?9zydbB zRrrPHXDHm@#yd)pje2~A8~#X#I^LlTKr$#{7d}MsRY5`j4*x(6dq4<~;6N589P{7} z|G)&t;4`0q2mjy=@~|;y7kc2(1b+t)OaKn>5Pf^sUw-!we*g>LunmPU2~|UQayKL! z6Au574C~+@<scb;X9~<<DR`77DZ>rgk`0<r3982p;}Csk2Rn~}9Nv%*Ss(<2U;(q> z58p5kDdB{5M|TN`3V~1$;eZds&<5i$4_k;6`!RumFbMom4gRnQd+-n4AP?9=bFk+R z+rSNT&<n<+e*ZuY2^W7XaXo@F6v)C1$<PkSL4Vu;5ABc${=t9nG!!ZGXX)U7?C=XZ z$PJ<<HWvqS0AoD$(0z-r2=9PAO+XFxAP*MjcJl!L4*!q@;9z>+Fb->g3T9(t;4&2a zKo1JI2GSr8_b`iifC{eYEuuJzm-a6q1q^oZ4e$_nh~Np^kbQa>68VuK+^{-{&<^iV ze;W4>H@FVT@DKfBe4LdJnxKQ`fNQ024gR4GMa6a?czNA`50tP6{xFNhw-{;o52%0# z?+|)rLkv{#58zM_04WnmB7y(V1QwVvZAT1ifDd_A4mQ^<`M?R2fQ|654b8v?*cf;; zC?whPck3_><q!^mbrKoES?>@G&|ndPg)I&lRzQMy|1b^H@DJ|rXMYC@`w%RTbV~ct z4gW9*fv}MBu#|WJ3H;y<YB+j=u^$mB2awSJ51|)Q)UXELAcQsnk@HXuR1k+J5s^*s z3`tiGT{va1_YT{@2H3!V@PG~5a0ks0EQKf{$k89aun+YofF9Nl^_LIUpb7Obj%HGS zOIHc*;Emn*59|;OoO5s8L=NO|HcbEyYeEn6fDah>4_?U_LBUjDNezNn4&?9+_|OKO zP!4RD6R$`Kc;Jtl$q#S$342fvRS9#EAr2u03x9wQ<Zu$?fDe;U2<51gAo7U$uneV8 zj`qcq^#=~^5Dee&XPEMw9FkOsrw#rv4c6d|tCKMCn1AC~HK-JkbEtvxKo9&dizFC& zdWV&Cw@?Zgg5O{f0yztK01u{#SC8TUeEjH-^q`>hU=F*WkQ?Z7SciV*pa_a!58IG3 ze^&^KKotEja~{%E+@PK9kPn=-5=`O_;!q0gK#lk?mPN8AlE`#`wK7t}bfC}<-T6BP z(=FrRqu}+OHW8ZnAPIC>m9+v6_OJ(?@S%mVpOhem;D9ajK%eix1m9qqHBk?PD3Pm) zND68WU|9{jNjWc<B=uL9$JQ$UP@KnErY@04*b}1r01EjanYb2;$R-YS`VZphC%Xi2 z^`s8#Kn~hA6rAM__+SmwkPm$#HltWpl;#a#b1n*MrPc5bRLV2XhYD+858$v=%(yP_ z;|~)^1-m#7Jd=jwKn+YVo6h(Ds3Vbv^;r#}$1_VMrA<H#11hS`7*l$P4cKr8*l;{@ zi4APv4HHHZ`OzoIzz#}hqAJmis+A1aP=9v`qkiEIINDI2b`nFx4#{8+?!Y7oM=*jo z6o8NfyD$z43YT*Sj1n0Rf9DvpN(F6sS3%knN!1_Gum&YKR+fqnOIi-|V6HSVq@)>o zdAFJ4FpvV;eJ=;BboqY%0DE{j2haeCKsqG#_Yds=3POpVEy0e^01A{?Bu%AS)36DY zh&-<1jqqR!gBh*Gf)UO~3`sx<)Q|-<a1VF*qGV|f@{kV*3aZ1mc@ww>yO0l?xfr20 zkZlm3DKUXfxsXnau=8O54uAj&rK*N&#}Cxd1odExU%PTJC61m@2qAf~|F8>x5R#G? zA|C6G{-C40b`nLXbiuF>`G9LdA|#2I2uoLg-iZ;M<qz3l3NG88vl0}o`47-Q1=NtK z|F8#(zz<k^6Sa~g6SxPIaC_dlng4JM4{DYAx`w4UflNRRXn497xd#6*4w@?y^(3~; zCsy*{xt|c4W~*{?`45PI3HApM7mE*S`wiKMk{&Xx+q!fmdax%tt~jWJ*tMe}5_Wr9 z3h!{I9mZMa&<>{14(!QC_7IVH@Cp84hqu=RTIjnp5flR1s{W9M7*Q*uTe`pbzJ(Ey zOh62==qeJJ4{Ry_h{&lQ_COBxPz@m%4#(mcx?2zEOAcxHt{Misihv1hix1sW4$NQ& z?^nDz=^^2%TIZOK<#uv?w-1X;u3)s2N#YLFYY*X&uaU%<+~5xNU<!|io>xh7VHA3; zx{zsjhs4kX3ki(Im6h}GM@&Et-7pW-gTUl4i)%m(w&=qi_rUT14sAdU_HdtLwW^*; zR^|69E3qHl7YLAWHbUVlqZ<uWP!3?KBm^^q;b6d6SHZ?nO8?LdbKngdtB2e04{Y#< z7VAOP^EKbolhd#c+?ymTqY(wAvfJtnciOAk1CQ|F4m0bG3luiSQ%~V)r(ooaV#8;= zg9n`;yK8s<5C5<Rv*3zt7popY$)$ORi!cbY95%pM#i-DH$MZ3V`VWw>2b=>qW0McN zIS#ta4{S%NA2Af&r;D6JHNBXK;y{A)5RA24agZ@okvebgL{$Hveq*?dVnfI*D1*l~ zIP(Em{O}Ik%CRmHcJIcr@E|o9A|hQBxxbJPQuDIXig+Sgr`_AQumZ<a01q38EumS4 zZD0=Win?3~#!J}-yGWppF^l|YDP?sSDbvw=@DASKDzy@t4Y~#meTPB%7@kWB@W7Cj zbrNM|4~ZkKmLlSuzy2a~YD-L}W_(Z_+vnIT-$_y7xY;G9Ser&@E%F}uS0Y^dHG zHi*gp4y6DO9&6Qz_&p}NqT-0B9HFxBkPOQZ&|^JkpzII)(0v(Q5A#`2WXOuF63Sg2 z%?aGatxKiy_JK?gV`)gLne2<}_78y&)8*GQwX&P$fPv<)fuw57tWpk^XT?c(V+6I3 z`C!cd(0$|FZwsV{`G5$9U<ZgG5B`kEz65yrz=Av&HhtU+OuY^EyTRQ<fAuJjhoaV# zJrp;Hqv6nZcNae)8ouoSSU-YsgY^%J=?`4JZ$lvu{E(3KFb+#4JJxLugy57DSlAAW z3J)617?Fkx9EVgIFuArSp2=q#!PxYWcauvFuPCcH%LE!2#U68sWXqJ@jo1BFD}VR@ z+V!y1E~$;b6yX0b2e5G9rKHrfeb@2B4dT!amCz2D4BFnqK=9TN>R=69eRu!8$o`QJ z>|hH0K(2k4;Q$v>ILg(8y-gPd55Y)~GMzF$lZX#H4h<~gA^trMn~?Z$gL#S(RLPWw zP|{3Ait9GOt62_V!!z@ltHgj0uqqOQ-KzSlO$#IxU>UI>_b-2k2q1ZT*f0moz-{Wr zOV2oAb^r_4;@-F241a(O220!~As>hP5Bu;7=5T{H@eU;(4CQ#eA0j}GY^OD=Ch!Ii z&Po&m?J0Wg5B~eiE78ByU=H<56GIW`h)q^45s{axfk;~zt5*wq01orH5(>)yJG$z2 zcx8I_pv$f(dJZXplfIg1NHE3b3v<8?+t8xD0JkUMmmz|6+W-rKfDg(`?2t5<e^3im zQ_m+SA3|}1!N3ly)sPiUjeDL9;lO|1I)6kV4(^Z-E*|b^>=>H$4<-zW3H`%Cp`gO} z4JnOB@q34U0131{B0PD6tO#%M5fq_U52zpq^h*!TPI>0*xr^Yn@xkhc4GE<gy)JR< ztUI6_IF|Ts4tOvN2Kjc}9w;C5ca!i3|A3ADV3&2Nip35hr8JktNsUeo^V{$Ty^wu~ zj31nfM-$Gsl10-l@m*(Q4wbMEM3L_Iu^*3l+>=@8t=EkdF1`r;!zmH}n*UIwEd59W z|BA%G1pENSeo{UAks%H2>Or3psZ4>bSPp(NbUCpfP>a5$skN_yfcz=bv@5;+`@dma zD_O~@X9%IhGRO*k$bGB`ld#E6>LE3s?8{E`&i;a)aA8Aj7}NR>*H8+k$PEQbcYjt7 znoo~J)gheq56d8~e@6Q1e$V*;j*>aDjr4^HxCY1I51SbuJO<1ETgNc*7zsGJSGgZP zI=QoZ7;GoRWvh8fA`j$H-KkCw>;$!K(D(8H>VZ%9#RBvA01R-OeJ0{9f6RxropzGn z3wO|`k&is{aI7g`?1u<6D%%fP?Tx)161nXT`%no1t!@7X5dXygadTHHn?G*i^8NGI z(BZ>|+_dqVwrm_XZvQkggxJyJN01>!jufe}AwPcLn!Fpgk)ug}-u|sYWv?a2k^JWU z`-JD;H+~=O{R8)p5*~QpNG^2<Q{FskOo*a{`B2_JVoiwB3mOt$xqqFIf+JT?BRq)p z>J_Cz3?DhBaplgX3o>86hS>h}5{DKaK7a49v4MuO?qS3o{|4Sx$P-+DRU5*~=Z#G> zw0A+m<J{TvXV9TVkM`WJpEhm(D(x#L(KKn$=ES+nSBjlLbM|2G=G_~#J>Bpyx&!5o za_->2hyK%+kX@yG&HL5+>)ZNu?7geQlNl%w(Q@TPlgmf{>H9d~yMfD-hp$tcf8OSa z240lXo^js%0Z*RYb9#8#tA+`Gz+q3hr>a?lnt$e@hcvZ{LS>DZ`0EcqncB(+z5e|3 z@Iw$eTkM}^uz2Sk-4=sq8(0t_=N*5x3vtHls(Xi<JDS<1q3wWcNE~U{zy?McLrd&1 zm^9)hpLR^~#+`v&3Q428{yFWRU~a3&9=wk9vLl!j+9#NN>M>^_!y0l)Np9@frxbU> z5eJ`tH2d<-FE_I3A3RVYO3KLUEYlv9!a*-hkM3gcpFtM+=P5hY+^D4q|AEIW$?9@x zsCoR^1Cpuu0W=?T<ng8+JU*$%!6aYOh|qrs8RQ@TxHdvd(tluW%hF8o^c7Dk0mBED zKk(rOt+U|y2bejwIdQRHqg4zac;4A2#~ot?Oxqv1nZp-`poIu68nd%d9C1WdXPVPq z<ITdq#QBGvWW*`Q9COMo*Fuf7=_i?W>~RNQ`uO`xt<-*DC!crzDpFsFv%`1MsLJt1 zo_sol2j6n?p{5CN!pZgF&nBKHoFv`>XP$WoF4>%UWMYDtN9A!jM0`;yil#@!G3PG; zCzffAPa32LKnq30rzMcfF*D!KETj~_Z~%<>YKZ@O=N~&f`R7=8pxuU>y@aI}YqXWF zR-8L}0ed@Wxv57HMgD0RAFDg_C+&Cb$vL0@b*8E3*jzO(Sgj@70cE<I`L+&Te8EX( zpE4Uiyc~rBucx!59rye{dszM_s+#lW47l*d!DAP5oHqUCdE|kI2?kky9k`hPp}oO* zUiS~*2xs!sX5@l~S*BEtzTKX`#xbV}2FY2zvwX7pr)vIAH~e$%m3}9mKVTu}?QOTI zXAW2_4X=BBwf?7<Ke)k$$Fo(;sF1qDKAU~t&fF4|c5vfombwm`@}UW9Fh?8w>y2qJ z@{V>Sf;rsSn{~|bk9~mRdKF|~_hOchHVkh*p~0Qa{16C!9Edma;0H0*kP?=WCU*bu z10+&7LVeW(EXSZid`8$g&V*-lT8ZKRXogZ0=+SC7ks(G8!=b$nc2I21xP!CqCboY} zB7f_PVu&)Lh(cU1SD@M3{U#wEl5vKEU6jo~m=O$jBm^J*z>WbCSP#^=tBasv(>vHv z3V$?bC>H!jJA(0z)@^Bfdn}i!{t?2O$#6cO*h32C;k(X6C?B8t$rwo(x=s;;3H6W< zCjCPWa{Pmbq#U7I@`fpufD)5_`v)|r01h1%j5GAu2_zwf97cZ5M%(a2Azq|E&ZtEr z&0vE$vX#bQ?j|FXC<Ge!*BN|8hKk#G<~5_Kq|}t+8m*xq0Uu|N2R12yZK7i|I|EL8 ztmYlfu~Kh<!wp21Vi|$VNITvCxi5Q|g&I`gM?Scy9G2md3DvOOBEM3Oq6A`AGTB}U zvC;-`l+vO0<PR!UsTKKXFK<GuMib!CP=w0F4~uxmH+omm(8;6?ov0bUO!?0lE#@8N zXj?afSdJL^qKZDnX>X=ktZ<a$n!wTNV6d?bwc*q>sHsOXmXQyP+*CAda>qLo(T+U& z)13|sCp+LFNOQubU#Zc=I>v#TWEC|;z!^tAD&>uhCUkbxV9!Q_7YI;&Bdt-h2Yc`# z%F=DrH@K6@9zGGe2f+h~4<!o7SY|oN7FH&WdPhi&Xb*Y_Rt}vAP|Khu*Q?oxY`wrn zRMT@K$Jk9<s3lEA{t-U^OOXs(gW1OXW@{vAk)&VTP@Fm9NWsJ4%N_qnhL$1~+`5R# z6#0OXLgX@>c2vR}5|I>iy$ceJh-_DM+Q>(OcN8%q>LK+=<;NOC4rHm<AN-&PIP$?W z$Q;Qfxobi+3|f!wre!VukZ645>yO+)0uY_;%17>^6MvBIDFOa&g-61fe|X{#|Hzh| zblR9&h$m1M&J#!Mb(zed=^^<5%!>X145)I;BVCNwyplm(+2qDQQ?>DI2BKB=0k0qI zAX7NZA=cf1(;e<egge3tWZJ?;uuY&@IVKCm0M+9@1wtih=s}Mm@=iVW7@D8Pp%xl3 z_8(0+2Cd+mS)>L3bS;b;gg@lrx(gLn9;hlBN=L)80x=;RDui;Bc>^u5z+w(|D-yc$ zvQ58uleV2p$Yt!|51R&userkWhGh%QE)J(3rdXK2`cY^;e$B=>7RNYn$}#3Hj9l0m zPCcfPKyK*K(AX(QDtEDle{iKY^6&>L#?s}{D6>$Wy{X6oL5Y5V<J74BEPKE~g=e_= z%9)KQB;K*-%z`dKOi-ClcEhr9sDv8k-gUVUjSoAd51F6&5k4+6j^DO>-U_*lIWT?N z&V1Mti1@Umy9k_tEY}pQG4+SQnGXQUrY}YHhsZ#&kHK<us`;3P;Hs-{>=^bvKE!g# zPb!oCjsw~Mu`vfP^Rb9Q^kW|U=nYst1}lSms6FT<%bQ<^%A!ExJM(b0Xr2<40u^yL zoBa+r4hr%QHAG}=09U^C=8u8&+v>Xp4!-cQjmtD7)1Db-F$1&ptCJWa=Ez7kOfkV; z&1E>#AO$~sc4@Vb<R2G=Ml#x=#=~S}AIWfsnZ$wjynlCwc$mdIX1<geCedjj$=w=u zu`*E|*daD=!Z<{x`MF^1K5J16g&lI2*nwlA2%g7t8^W@8kQ*E*(fgzFF^D?j62OV) zy+f1*jXyNQ^beV4H7V1j-p@s++=y*_JE9qD4ZI#OiaP@V6eYJ$Fft!PxZpL|9C#o( zie&x&hc!wuK@2O_GfD>F-Z2aHPqHi@O!&siUaCuYKzI+QXgNJdww`X7i9UO?-2jVg zi-v!&G8&l}e5jP3BMp3so%yQ<$GgAJxC&!i3#F5?e~_pG$tC#n57klxPACT=$vJMo z2Qa!GP?IawDg;g_IOX7sviKH;ptiID4sh~^h0C#_z`>G998(CO)X2CFS}S<422D^P z)9|D*Q?g)S2HXfi(&)NU@rH6p0%~AAAp0_`XaZIumAqMxt5}0$@P{uOv)oy!&a%J{ z0Xl!!6#}fbtJs|l{HdKmg=(>mnH#8gcql5&j$xVvf;&MnLWm68u)Be}VRDSKgC^kr zm^xp`7ff;(OT0u(%tTGx#O=Tc#aS+|<3v#e8hc2%e=#d|8bwuHMNxDhf@rei+8Y*Q zMZ7_$wwo^S>jzrgMPBShO{}Z?_=lU=G))8!kJ^PE>V}uX#Pz5L>j8%^BgRZrGeGb* z_6S8^1dcB&3i|6S=GnxFsl#xvzfChnawv*DpaeU^#!bYXo!A{6@<n-^M|!Ldf6xnP zh_Pb4v~mDDXgC&asYhP45NRC6YGJ+@Ji&eJ7^+K=P3$1xNR4$!hJP5CHpw1yDMf-X zhvqVeh6|>(a)(N22PXr_f5^Fl83=#KKDaW%Kzu0sDlmEIhy75j@W_X2TQ}MN`K0z} zqLfHO*w9A7@`FKOCD6eReBlakzz5oiotq*<K6?~5ga<gp19hAa^*gEgXo7FJ6zV|9 zmjsR7VuRkIAF-qsYsrz;nzt&%$Pf98Gx>{?oRi(KM|{*ru<V#Q=mmVZAh6^g9-GLD zd_RfFmwea<Q(zo`J2-m?2Yl$bid4y2yN-kqtcAmej|@xCK&6)013&4MH6jh5!v~ru zm4cB6dU!^l+zpg?2X|ls`y)&~+zA&VhdUe%!$Jl4@T|=|M^B-IlPWsi;H9vTgOiFZ z&9shxAeOJ8NzoW4Y%xpTn2Z_8rcPoA*+iy%@P%gbt(#H^Sg?b@SWM6VNIWXZjel4; zOL09UnIOfP4UCApyfc>Ng3Kb6&yg68^xTKDO1@~>2($QxCI|;_$h@V{nS7uERH%om z7%_+t8J;<_-J25L;YNmPJrz5Q6#551n5do5JdKDQ_mG1&><IQ69V&1K;sia1&<S(+ z1Yo-u{PfRg*@oNl1ey~Uh!8kLz=sp0(1#d@cgUByfQd7~1}_i<L4XE=k<YX62chBy z8+Fi+_zOj|8^n8vBm5eI=!Yf?D;iM}aBzoY$cAvhh|ugHbm0eg2!?%NyY2H3<%+d@ z=!-NB%U-J<BEliw;LLw8wgwSS&(N7QqXu%gB*k(^aEQG@yQFac%Z}G0wnadprvS1= z89CnU439bnkmA$b;3a(M2{J>}<Xj?uu+c)81OWTLZ)^w_`GXTdyBV~V8aW%(0iQ|0 z2Mu!;w&a}bfl@Ze2fQQ=I=Rvz&C1Wgh<vz)dO@qXvInxthh*3UE{)SJLYG1U1!L(a zhvU)=ip+^C)c`@BK06v@Ev*4bH$MXoLZz}*;V5!|D0AqO!a|RzLoi7lgd56EG7O8| zoJx<11}Y#keke3hrG_=QP#|Q)ZIMzN>{YTuOKyM#K@hPP^pTd3hFXY(>%ornXbIqZ zs(;wa+>*4UA(1<fQt1>8c`;TUb0>-T2Lxh5@$(OG@*_?ExDg5pCUn6EZzzs49V8E_ zhkjTR#Ds_A5?9Wsya5b3euxTlus_gfS7Kn$>+pwE5({|Hy?f<{diWSKaYEQIEMjPb zakx!X%7<uZ0z30m*w{vVpt46%TG-$bXlRya`O9h<S$W$HblDn12m(XE0!*+Qh#ie# zx(sJo&SHtNvuucO5Qp%2q81d9fA9r6aEEXFCNBL4+rXpD1Q9D-E&xJPm;4;^vns4A zrw<{kcPP_=xJYr`vw^CIafrsOTo0(Af^Rrm3)IHen}s!CP*Uw1jDdtb01qoWS1jW^ ze`twmyQ$!j+o#c<%9{oDk{*WwkZmkfahOWFEl+>{s0XJy!Q}ytt%<jj1RV<@n2Q*U zW{}do5C>h<+fK})YI+gDm;)w_w1{<8zO{!%L|jh0Em#N#L)@dTV-ip>F4<_GzC1E~ za8tIcr|~-tZNLX{V!OKw5!Ap3Q@92We%U|-ke<{EXf#)jGL?GR14nTXf&{He@(E^3 z)X@3bTWTHgcvS5;n+O?D2{k#<5UlZX88xGVHbW&K)5iL`uLa#nQl#5WV+_ZD3`=C+ z<(RtkSt^WFk$;GUN!W(vf`wqcBCw2`ZFtzd!3SXY173|{{Q=<cF~JtJ5quB?Sa{=F z+#^iGpkHXUJH;7uC@8^vqCox}B@qX8!aAS-nUVO+hEmX3Yt>A7AcrPei`DcEM@kjj z42sX-C3}F;_;6G{M7d}fho|#cdq|~VY>C`$%zr3ifXf{urj^a{jpq46qCm6ojo4~Q zV`kVEt=gL`QUs-1p6VcxX4w&EngmV|hXk%$eE0?|7?QogI;Rqk*8yPk>4yP+PPDwO zUeIGkibOgcQt}jJQ4!401<cbBhi`=v*#!}T@rTl7r{w$#`)Ug_;bo4}iF}v^JfJV+ z+?YY$2|xIR3M{k;M7eBB<;CI;rJ#uosa#(b8M%#M&S>aZPU1P-jfrU?6t>M?{$Fd^ zOErR~vAbM0z=s_M=dHn?1l*f#=!KO3&0At^F>WZPZ=gxw_=bE)RV?ifESlqQ4h{Rk z1V#9UKeTAa=@)w-H7m)^-#M~+AP!JWXa4zz!11wg1rcn;>Vy#5uvE%=pt2NV-qRrp zcz_=I@{9<ahj##(3%X^Fx~$~ET~)@H#!^RIdg-9t6Jzr{m*Hq6Hiwn-jd}RmHR#>M z?qzgQ7Gn9jH3rM{Sk5`{(YW$e9sxUSD7{l98(64p(paBwvjbq*9AdW7KbQo&8M`=! z2XVOD){@nL+ZJrVhB_eUJ(3N7fQDf3hCf_bwfdT};wNbBApN{J*O)dzeusXThIRNF zaV1V&0Jf*_54A`)kV$MNo@)mG0YU57)E>GR;-)Jn-aCKp4XmJoX(kozxe6EBkjMTk zq2aStp$8*Y>nQtM%;qrv{Uq!3g+<%pycs5&KBmb2hg5wFt<J3Q@Q3YOX6hsdd?4_> zqfVt+V`Z=d-UesR*oJM2=CmU*iKvG^5(h#0Pvd@veW(PuV^L{IxO`Z+fmnzyxeIrQ zZo$!p$e_{0&<LFfWu%ag8U2W}um|WlQNu8|Bm(WYps#-rUQ!~q!<Zq&l2N&!j3&CC zD&YtW1UB8<^2)n}1~E_|kCwX#8&8X|k$}E`Km<%6IvJy%z>wT=Hbj;d2ay3UL5YlB zm;+~uw7uai-|CfoU<SPZjblHj=@GAU-{YRCN{!W^hn93|-<b4zc<~8JZtk&=_`HVm z6C~&M5GxcFdci6S4ngjnhfpnY@D1$qN?ySVjtImGU@Md5g;!r&19LEMO|xOnSd_9g z5DUCm;IJ!S2WqI97-c64B|g{O$?Jk8$b5E~5T6GdtROg!*w?}bMDT<UkK-YIv9*Mj zX83~ud_aT0{{5^4*CGyU2rkkKU;s!`gcf|T>2W{H5FhaY1`xFaC)L;oJX#VNrwdY9 zuI9>z<LkW}XI6<Ic>UUlnEk5bI`T9}a^5M_e=v*T^K*?rkNZdphJXpd0<3gXCb^)m zrCbAI5C<!t3)I_*sKAG({{R#URhEH@SA59OotO}O(7lnDFUioM2qPkTz?Fi(_>dS8 zZ1@MN6FcN<^qBSp+0hn2Db~ym2RkncPACK)g>*pKhJ0XyUSNp3SUyZBghwQ=s<>Nc zfpm<2BB2H<D$TpQ=m#4!hk76tX>kbw$`XZV&+p<YQ;<S*$<p==$%WHd99R0d5OS2O zhK=7ni(fC>^#?)-1nvm1lAo2LNctA7FVg%>O=%G1=>!G^%_x^CnyPt0xr$(%y#^C5 zjWCN?0yM|J6PW0&IcNr&)X^&CG;zR$F#b^oZQ0D;nv-lXaqt917?OpD2s;^@Z>ek^ zwb*U>uop8)7S$Sj|Bz{b9GC9N8LqxDZ6I197Tu4{2YUGjexT~BaYd}|hr1wd&{?Z_ zDFqd0T`G(~fXIgm&p2@8$k|J14<5sY4j;n9hmYJpYE-`YqeqWnLT~>D1^NfBTs?E< zAfkkqP$Rf}REUX_XEJ5VgeK>CWJ2uUym<*}qQv>H4XS_gWSTn&?jI9s|Ne1YNb_gI za^)&EG3SlnOrT!Bf(<J+p+tZ0{&6bA?cF<xR8yAqw+$N`Z13P%eTz5WA6VQ<nmj3& zTiv@7As#+k>(4xJ5hddDC$}D(X5#$0wU?MKHh7W`Pqk;VZJ|l{xQR_IR-#FM|B|uu z7f!EguL?!~|Jw)Z-)wkYYXgV(l-oac$w=liM?1Lif7-PDTUSb)Hg5L%G0)DNYQk^- z0u2&*u=Z`7^_rSHn$YUFe`|=DT>iCQy`_*sf}>yirpGq$<;_!@P(&GpR8K86HIF<C z$%oQ<<wW#eK0ZmMorNe#6b?BjrIy$~o)oeTTc80|7ChK+c2`~%GV~7?zCZ<8Wd3mD zPa&TCLr!K<{d5*Ec8K^GL-^EFPCjh-k`HG13>n!w*vtXVW&VUE(L4E+CJr~)T?iam z`3MI}JK~6A4^&;E)K5R=<kOBR?UW?WIB15YCUnzG^N%~p(Wxdk+?caZDeh=Vr=enb zL`Wd@|Bc6-g7`GW6NNq5Lk$z;cq7l5swD(qHB1ylDT`lq>J6mC<a1PN2@P1(QLXW_ zR8#!S^BY(XE(Ov*-cWg{g;qYb>1vU|v(1eGF8LK`a~0-~RZUX)Pc0#OW)*#8zT*!p zbNsW7XWUiz&Ng>6gUx67P(_?4fBe%HlaHCT4I9wZbFQ-ZT=~Z&`JmP-L;m`T5}EzD zIVN#j2J9zvrC8$}bixMgkV*CYGtD|s<&#f?9iqFCKib#>%04P>9C4Rw{!>m9PMNb} z$qrGa;6I(n;g2`9nnNi#Oo-DHl`l6`UOmJ#A(BR6fjiGX#I%tQIHDqLk5GO<QqQY7 z|2M`IHT)n&qHXqAwNxOGjN{R$CWBShS>7lz$y4u~4YNXVHG{=FmkH^WiQAA<2qx`5 zix-6APJ&3g&X$u9nJP_ENIBjHE!AdhcvEKH42km(EOzh)8r^eXV~)LgNA`~|bDV~@ zS5G}xu_pig32?-J!Xv0V+-Re^L&Is~PCJQw{P3X(ofQl_DXR&z?y4PC5EJF7r(I9@ z5W~c-0m4J6rAA>-p43XOF$+)pc)t`Sdw}Cj++X$dj-^)1!;nVfjMGFl3I<1?eIb!E z=kj8i<sXW;LlA=S2Wa3U9Fn;gmFV(~8p%#?<v5EX3ehcp#RVIG=mj}E0~)LN|HE{1 z@J7E7Goxm(fp4CHh&k{v3C_KvE5MorySx=axSWs;-<Z<>9%3hMxT6#!iyg!a<tHGz zBN6SW&I)xm93Zx%67HzZb?9Uh(d8x><_Jd*t@u57e5ydoL&;6%A&@p)k5&CaML*QD zKA`aDAA4BDKfckuu`J{ts91wJz7d?BRK$92q=$DFv4>qP=#5^Hhx(WRj;B$mix^_k zJGg;~5Iw~g2V4t0)Fd~D9L9xeDdDgvs0e;htVs+(Avd=1k7Nl+T=SZd*MOynQ*P;o zA`FMHW>^SuY(p|YqZ=EzL5>AJL^8@;CNrDq%x5Z-b=>$}JqSgdS3)zJ|Jsb^KeXhI zAnqd^4|~cs%c)J?{i77uct>@}Y0h^>b05FhB0TG9&w4&ZW_b9-IF91ZduC5*)M!IB zXqC@3woxAU^hd_@`3auT<DcbxO0EczqY%O~p8^%6Lj6Ijd@LdmT+<XbGg=^~RO1~! zTPRDP39M$^VJ>XxR$ays!jd`@So(q;PRnUaMc5;kPcac)<{}w)615PufXYpe`j3oJ z(1L$y>XHK37mO_FF#l+rmij@}Y|_nc#A#+1wIPmum;xTRt5FfV<TYNdBN=*%is}@W z&TLH4ItViqH^4CtA+GfwdzEBx7+DWFKtha)grhkqYK}D&C2>;g|4%0nx!9W6!=I1< zgg<)Xy|b*0K9>#3M!9DaLjJ>$mK`lhRK<jFs5Fv<m00G!F$Wll!zAGlWj@}apU8nS zf&a)7YE(naZBVQqpz+Qv{UHt$N`@T0xC19M6PImlV-C$=(vD&&jyv=MawgF#4ZHQN z%YF_TZPncs-SH1o9IqbT4Ol{ch*o#hLrb@zuR=1X8$AVvwY9-rJ}PlMD%OLpv&AFD zsIi7`jAKQ?kx0fo@)G(<<SGvKW23xBj{5k+ks29eX25}um8EQqQ30f-%F&IE3Ploo zu$es2<vsQ6;S=Eikb+fr8<UX9EZjhZC&XbGVsT><o9L}S|MYSjow}{K95V}Nj+v}F z4%am93hq&%0Xh%L=v~Yb(UP9*BzzzO7T-`&IeeLqV8XIQPAUh8;E^q_wG^J-d<{GB z@vuC<lXvhCQ$BKQ4?w?DIQt03X>Qt6L_aYf*C>T^u8HVNCwggA=;JFTy3ngoA`s>n z2R?GEX?S=fSoRDSMVkN)cSQ8j&kUA5D1zd8;qxE*aSt&(=Fy0*;TYND$3pX|sZOBr zW|+R`Q_S&P5pu&^m?=lRrrTS0H8U>U@Un=!T2G?t@G4D(T|G*}-5EJmGOp|kgyNDh zbz|cWcB$%3-(9Tfl3Cm0sEj*3?M!kCCoTC#_p-HV|B`$_;}_&;r>qO^)Iae<ov;&! zk{sU5r-Y*)#?zR^x%sDWCL*v6@A#$hv9zM`a^&@Fa8^uQCQa8P<t=?mKI#V!jo6bP zg*@apT*K^LeP<B<Sc<Mi;%b@y{3!UK**la?@@>+5i&^fLJ@S!3d~ER0?`9@ZVH%{k znA6_d_yaI(Xm4_G2F%ZN<s4vfZppkmhKRt#z?UiZ=^B~d*pOE<&Sg%3e<(zECb;UJ z_>W0fTCghKjy<&Wk8GI2VQR7!oj?<gd;}vKF?!db6z01`IPABJpRI1?h>Ajwo{Z+8 z7}4rTCSKy<^p{i3#OjleK@g%I-nr}*<<X6g{~W?*I9rue%s958tBD-ts74cFC|UtW z?m+K|6g^V^E66Y;+LftRo3XDsZq4RwdxHfczRvly5$hj66491@BaLR&@?G9B_j4bk zwtpaE64mV(S!OgBazRBxsN1;o-I7q=Bn41ftVR3v5bg|GJDi5)c#X;Y$ve1%DeMF8 zcv8gJMCLGqDY(NpC<pYV#uMQeY^2U$Em&%NgE=$-eE5%rtOrHl!7dm?IqcR;1Rx1M zg#P@)`Pj@3l1gUDLp?x3&1}WuQH6JmO+nBHJ;X{A&<{zZ-V*+U4l0Bsk%$5jS&+0D zRmcXEKm&)Eke&4dc-hbdk`9&N!!G;*|ND{2Q;>s~&6^qq**~yS8bXGU^~L_l4Vf%O zX`s@f$pzny4g<*rl=R)~bsVcn2JT$oK4=NWsoK-sl(V@Pe8G;H_}iuNjz368J}}(V zu}(hViJoLkCtBjFHQPT#!y5P%JZ#;}@q{<z10FyE*UW==Tv&6cVm7fFIQRn)?pDU+ zgCjaq#`x2F)WbZuhRQ7yGJ3=wK!QCG9Y4?mI5a^xG*%^=6vq9-%B<cmk{qiE$LWwm zE^VFKltVAP;ov#d{aqE9k)z!y2|U!px=awZiOU=)!<2xXGHI1B+yOqg(vm!daBNGv z9HT@H6~17d+mOT7VM94o#<|oZ|GjNPKOhMk5+2&n2RGz{afpL8Nz!oS16rBGTHR2W z@Xk9_LOZY|+6+f=$W=Xv;0g+erl3L_XvG~_h<PAZf#icUtbtRg;2-e{^=*V$0LadS z131u1c9;<=>;e6(gdP#ZIQ&+2TuC5M0$%8(oo!VOH4(J<!`>B!-~^XvV1po(3z*f0 zWRwFm{6RBd&U2}h9RLH9v?ORW!vWdQTbK?T;0qa=&{^!%hKLS4aDzMA#q0rv02WI* z+?Fc+Pd_+EaYWu)NzxA$jAurSoj`{Y1y)j`$y0a}DBu^LjODEm;XgpaBD@2Sp$Yzc z!Xe$mJ>&zjr4bK8gwjO{|I~cVfjCk?We2UeU^V<hN4N(ih(uRr$H~>vY+V;V%t0@_ zlGjjXwv-0!lmlW8$@kS!d_doI{X^S9#p0Yul=O=lCI&Ys0w?6%Lu}PA)gKOp(CJKs za+rlb%$*;iAC(|iWjvP}28;>5*FN-vp`E0|z(X?BLOsNeuUyet7)L%N7|EE-5w$}w zsMi6$CQT^Fd8`?wTnMW)#`J;1Zt7984IksljDKK_h(1K8$OAPL4J26~Jg|hTHK#pH zBP9%-bOuLz>`^|1Uk~*kL;T+&29DgE1&BOO2q~C2;KQ~+<oQ*J|D|UyM8@Le11$Uj zFrDQ?B!;nY!r@Q_|1YrtENlvV=1@6o$)TMECMbe{-iwoxLv}tFdlnw-Ad#3n#|BE$ zpV&h-49cH8Uyr7QNx0W3YJ;J2U{Hx9;#KH~GM4XYO>HJpmw49BwCFv|j2xhvY<Ul> z$io@^B+wMeY~TTOni%vYO=Gy)2ztjJ5NUpFXmBJ%dk_N^09_XTk4Yq;S{#{Pltn+F zPzwsvZP-J5e5Yh3<gln)dcr9@EY3gl0_x}?bU7wuf>}cFl6sDye)<Cnk%`*iLnKVX zz}3b?F61`=r>_PTbZo*j)I;m6m+FuS#fS-@C`ZKHRKQwJV2CGQ5yvtlgD6faYHDg# zEX^9!i-cW>|5d!hIK&>%HAQT7i9hw^^@N2|$PtmsM7=V^f!u0x45?okDR7X3cdWrK zj6;VNYh#XGFZfZMHN@WB2(DRI0^tLa1Suf~$3%83Z@dyW;6vM(gOr5^LlEtf&_}t# zX~J@uJ@|rQ=9cK31t;X`;H3t}YR(^+gAF-^!?D^E!9yvqgD6_sDsq!#kO@EZgT<6X z?l4qCW+X5M%hURUqTUY0Ey>pPZJ_-FCXNFJQU@~1ZLayCu6Tr_LE|}LlSe?pA^C%j z_QN>v!!yz%$fD7U_1mL8g%47rQ5>4%PSigrXRuAkJWw2D{X=_H?!{FiBMpVCkkl%& zT3L`M|1VK)G`^B>{K#4qt}(i)FO*4K9PUHPVz<7TTMn&d&>QYj37u|VRYim{013sV z;-l@&e74J>6-%0N(cT^|@Gc~rRjbJi2R^g|D8!sUVD0}TgloiAZzZV1yv8!{%S<3F ze{n-e;)BR&AjE2_4~|WaoN1R(ghjZQt_ER>evdHv2Tz2BRa68OKvIw4(LvP1ClJJL zQjhg?gBhW0LkPt_WfrQUjpB&IQtTAeLf2s27L@?1@%}+)ED$nrO!Usd^cKsPQX7Ik z1fbkfyQC?Z+L?3ZCz?75S||ehncUWH(I=tbS+uVQ^(&evPM`$CU)X35Jx4uM0)sLU z|A(T<pA<|b$%$_S1_1+6K3GGZ<W6%qYNb+)(_{q{GRO);1U<|HJ`BPloCi4cTp0t$ zH{=8DipA%;V$s};g&f2`kZ?Yj@b+X%cEn6+xzX~Bm&tvD9pF}jpl4s0g^bwQHZ+b| zGzSn5ix3;6ok>>@V<tpcVR>ztxOf60Oi)Wg%hy&hTbRk#b`uES3m5-^LCP|Jc?NML z!#ecVC^M--unu&vLn*+mV0B4-^@BE~WF_c{enIPgSujJ;hdBQip$JCAIs|=?gwc&e zJ)pA;eoq^|2Ohk`=ialINQEO`*tyaKeH=tSL<1%B!#PKd{M1S&yXf}V=7e<&|BDF{ z_U!QxF3WV)!{DJZlW^-C*uz1lDJDchf-#iIu@+UR&DiZi2YoHFKE}q>T0S&RIglD9 z5g?qgvJ@XHIo!oLvcV=2beG19Kh_-2QlL4&hK4e7pgxB?>_a8^*};5s<CP?z@ryTS zW;k=heOc2pzh=x#qa+Mlz>sVnEWsz#0~8+0RRk+<G)Q?YNci-F^6fDpn}dw`!*0Su zivdWFesUmL4Mqzx`q>#b%%fyVu}U-p=)C8<K*`?8C2*waAG|bKE{2{0SK7u~GuTkP zkju9sU?Bovi=a?B^p9ohG}(cPQiJhz^aJfoHFa3^g4skq?8!72TG8V3|Hr)p2Aade zAn~D4%yZyFFen2*<QD&BG@4`vr_K>iOk`1Ch(st2D!AG^9E6QoFv~g3KR1a<_!AWz zL#>4;hbW;v5VAeY!W#U;Zu&#W0?1Q;4N0`n9#j@M^n+$_siDY700{ytm>*`v=O5I< zYlB8nZ6s_Dp?-*qBK(b=VS^n=$#!;(E`v>tR1z9CM7qjbXD~KeZi7WO1BYZO=UhdQ zPMNsa!9O0F$(dXu!p@y613Zl4<Nn*<rsOa1i=zQrvk?d6RoXE=t~>onK4e2Ogu|a4 zu8vccryQm065ChhnLFu^4f3kPRh>m7g=eVZQ*i3c8U(Jj)aN?J{|n9oZ~6x~_|xq| zQ?uoRM+5>P^uv}zIk(zDI(ij3w)BlK)nR}*ium0<iJiOziMnDFInqbGY!I1EWOMaP zm}Ap65C&e##y{8rj;y$uz*9@l0W<ieL{z7*WV1OW!anS)b$s#iD9+`n(`m33K5L0N zNE{JKl1c0eYyL?;Z0K`eb;=Hn_1ql!pbbuwL*^*3hqd57<xKURO?mKxMbPU(*f(ae zL^x7|Jlw-L5J)I%he<FYBot|{Mhs|B91Y=1n<3)=k(oSWiQDk>e|ITE<ij^q#$B+| zRj_eN1kN^07rr=VSu$~km$s!>#zOE?UmOH*nusOksb^&R{~f3;HW9}*S5pBSIh5}> zB+l<}|Jjv0hZu`PoWNbh`EKGqS0rw=H*!4o?k#|9PqBw@$JrSn7F<J77Ez)+H;K6( z!S_fQNyW`#>!P`~`(8bK`>OVQvHb%SGM_B6uET|IxiW7oLzAZq2iRzOw$g_y6@nrZ z{F5^ilH)^`2$0x!kd<c}v1|h@2m&V&$9F!4Dr(z(+5>E9y4y?%E3zTJ+l8IdMaLxv z#jJxm;11cZqBr4#+ft}-09tZr<}@^nJFv;iO9rG?3?3`Kjwc7~p@I`q%-mwW-+Pom z6%ByEyqJ^29x)0()cif6c|J77Zi>Uwr(2%U$~(B4|3A=2=L1x<Y1itioW!pXaa2%m zCCB3o|MlkC+@I2L;SwjR97X2rNoWZc%v;eDuTya`w}{9;>{R09nK;m4w)lfP$V<gr z9WRND)y014I~D8X#%|=7=&+OtCeajy{L2GGzI^WfO;eYT+rNMQ7&dhH5Mo4$6Dj)R z#}8b-Cd9zWQ^@dRMUf*(mQ;8V+&Cuh<at~u@!!0Bcu@TtSFW7Ek`Yn<gA|BgH*sxh z%9ELIC(M8R=z(iO?H{>%A(NKGhtJ=;ZIdG5d*@GQMTPnBk;CU}jzW0;%zeXx?d#R5 z4nO|mc6N@xe{+206Bkybz;}CLk%K1=+nr_%|K&~$2@jvAKmWG<^Jb@+IIMF+;)BL! z+dF&k{=u>{cckBc%9445hZJ>eiXp{uvp20)y>RC2$@a%ho4;(P>S@zP)pu2e+PJw( z<jx&8Zpo=ftjF&kwKdfE&3joLeASEaz%c<gZyv>-OsJt32spM!Vom<Rqt*s0`taTJ zeZpheyYM2C3m$C#=;a%KUV}}dwG@==9c~oc2A+5FsihEX)@n>P2)SVcn@I}EiY*35 z3g;g?3e)P3TI$p5yNXCN&7W|#>E(`m-hpg0)I6I5n{l%GXOchQITFbvm0XfZd+h0_ zAL;U$MiaZHtB=VnwcL`+B%M66Hh1^||7D+iv^nz2E|E+VICv`AhaTphRFlp+kA%`V zcS_kOLfiVW6VO1BWa^(?sIW{PG@Tqx&_*5A@|%AK8N?rOa7r^xdYa0IJ$mFZ2UK$u zZPX)F)|krFf4+HiNhj%<$DBp>05DBfwY=&`Y}oi_o8E9$6IZP;8S$M6=Kuzu4U=Ux z*liGjWsYVj<grU9as8(kHvV~soI*T#@z*RD9qk=#=70vD8}ATj$8hUx?5;m1sc$f7 zZCw&d;M@VF9e$+K>)w0Q{3l9t_DLq3cWSE@*v%4R$CQ8E$%i*a1GW>-<E$yg%quUx z7`<`UI3^!*3|rIUk5v}e9&aQK|KuM_%gOT9{`RP+rBFq6)JgfMKy?jOSFU*$Jm4{k z;gxaCr<XsrnbzGcgT<y7L_&k7nFAY&TF_=;X+aTu!g+AnYDYVZ4Xn`OhC+Y1_R^ka z=U|319NDE-Pz5V1WZnw#QAClC(`0U+N+kYw<$D#XO`PF=vn^$_|81v|d5o*4p2X|S zxE^*mW)5J@1qF2;Z}4g28GmpRo%JUFp(i^k!1-r&C7pCnRz!7vwC8+GCFdVveojzj zO~HX@qk86HJ<UkvjjFe#wRDo9ZNy>2ml@OAh9T(#ow}D0V5zTmIvd-jkX^{Zv7WZQ zNBK*w&Mk+VXG44EZ7v&&|CH}-D`TS>n!`>q*ijC5fa-m%Yf|L00uKVhLmU102dL<z z5a95m6zsr<aTM64#We>XiD*YX#KD^m0?IqYSc5-qGBcE&aAo#*U8I^&4bo(eN&Hy^ zP;wS3-q`~^)!2?X_CN{R{UdU$LeK2jGY@&-BZ&c{-fy<?2VaN^A1)NsKNL|2e3a%7 z?NgSm&bJM0VB>6MYgmQgfe26314sD424mFNs<<VqTyw*Rgn9wBI@XCH+^7fNyz;bY zt;`&MX$L6eVH_wW5QbZlpgWS`BH$?KeNF<^a{jT7Qb<f3;#f;0mvj{g{$(2L=!ZBU z8Ob!c3=*@F87W(*|EY1{;S({T2hA|Tgm0V&RzBpJJ>=nydaU6T8lgrj1%;E@?V%Gk zVP>P81f_g@1}=EpVl(bgj(@PB7xY_5{=T=FF#?J}+<*lZ&;pAn9f_PTgvX8k5TQHt z5uSgflivREymH|KfZ<U{BJ+`rQanx}$PrLd68aB;SWp`TDTOJ_k&oSgBt{rzh&YbZ z4pX#4IuZ;Cd=^TVmoyYg><9)o!tuqDaz-Ke02LLWl8>o0RG}{|sX#PUs5Okk8}bNC zLz&`~5;oMNJ85X?@UezjI3*?ZNNQ{vDi40lCua1(PDWwc&~(DWX=|w{QpNI*VD%FV zSipolgmjgh|0?GtSHTsGND@=5sH!w+ZAP)&nox;6bRqDl$7d=dh(5NpM^@R4H_=j` zZE!Py0((-Fv|)~5C}V;pj3O;<$0$%`3?JDb;6E7mtE)KaBjHHMK7!%0-IPz8t^3uu z1maO>_(QXsbtMqzF}oym<cT|rCuafWDthE&7C}QAqs9e0YW!>*n49MG7FD``P=Oef z0K_}Iksg0oOP|Fh=08k@4{(r!9@8}&n8cBlZOj3)k6e_UYDYB{g$8p-92arnrb&Dt zq`f;T2NapR+0*vMAKT!^ftqGUIyS1lpy3`T6tSv{<%=60h0els%ik?&!yfEN$D0yj z(Qup?|Ha{;SU%dJiH`#3G4fO(rtE<^7-#Su%o!DD)8s^(;f$^DP_Ku%WL$9gV<Z2N z2aTN+sUlVibHlAu>FUvj>~7Z^{5TTkFlVdV%|nRPz=x(NDA|0H#utCUh9J$ltRdqg zl(pf;fY)NyA)ioZ+z<yj$^jz+zwf{d@kTyW1lD|j<G_uYD>vs+846D;V9SBWG^Qaj zVG@~6n9B+|#3AB0X(JyvwP1_Wp$>wmSRr?A9dO=JxPKUjA(&=}b>#qwm@E&|#cPVB zY#rn!IhhbK>+;1=8;vCh!5!mZ%34&-GV3<s7~?Qm>q@h|g_OBb6O>B#0-I|l=?qj? z{|Pn4>{LA>DFUq9GNGdu&4zhk;~$(T1UDj0T5i09a?zQNw*&Q?a12<)&QQl85D|$; zAmR|y2nIUT0X#S>DAgUNrM^7cj?3ZD!=Rc9HRuyvjPu*e_HZr}#&O=0C21b`*h5V` zE;tz)dkM!|cH*4)k3dKQ9_UrtX10NkIrJh~Qtpy;nVV{mFA3X1?)JMj(~LQo=H5cT z6&|;t2u_$a60pz^tG@J`<7i?X<#1#_noY_yeYPLQ5r@RAA&E$AViS^(geFE<oHGe| zT=V7c+08MrWURv+;UIh2LoP#a3hy7`*zeJQn6owL!XNY4C6dsS9g=@z@*lg%|Dg*& z2zbEiNdDmR#~)=f%ljkCJFlL(nlT#KQj<|%lpzuo#Q1#DI8dweM>FhD2s>;`>RIv- zSN_oqHrVK6imU{5%t3G4)2YnH(S~LcdQ;$NW7yr(ySD>r4t691A0)g>cxTKgm#u*q z;}{3wpO2(s{$mf4i2TVvFB4)gLCJ|y8G0(z`FY%9QS^)blEn0)p$S?B*Fvx4V&=%Y z1}g@`6AIyeg0I|aul)k1Sth{%_R4L@Z;c{k5;%bye1Q$>fgGxXlhk1y$l)CZ?5%Wa zp#ZBN$^pf=B^>HOq+|#pUJwSAf+0Y~8$dx}R?I|t&^oX~7wF>~`pgKM{}3Vs;vy;q z|1`xRtcxg=%saSBHtNBfsDTjPVIH(B))tBj?ExInFDAxNCI$;V#zv_e3MuBP5Nd(m z=t@8w#6g@;4<7<TLL>sRrvp3W0jrJ^%)$7`!TElOVk`p`+@W3mOyb(lNpJ#zQbzki z&jOFmNo?$RrePBjFA>d-QCh+$76BZBDiSY{x)cH&>>&_>?Nh4DWv-C_RAv(u!Xv&b z6~*f+o~hSFg&$mo8t{M#o{V_PEKRN=k!Wx#s0VA<pd8vua};C@RgsJ~<BSTS8KjE+ zz6ufM0jz4{hak!xO5qxEEQ0>T8i%Qr2<-WsL^|GKUo7r8u*8m5{|1v7#fjd*Jissk z*D?3XVI1;-<7|T5axQq<pi(p?hI)fMbWwB0Wp*HeQbfrgx<OJ#02Ri85b_`r?BN^g zA?eVhJ{szVfJa2=huL-!Ac+fCx{Lz5<Q@6}3$o^oL}{3o!(d9G9ik&0&#WbbGEm^L zIsV~I_DC-VuuB*M#lB(fV&-Mw!5c<HDH(5E<N+gb38<C~9>#&Zg6114u_}3tnB;*U z!{I!HN;|&c|D<XUAR!-2r_J)IM*g7|`k)VLp)8^dduT^g7EdUT?kb|O@E9c_0H}Z3 zD>*9UAIM~a<SMcDP%<ZzIyebpK#7$aVw4^N6X#--NCT(5|7jQYfLjcMGAFb0s38gR z?@tDUrlPAePZK<x$Q<xs7T)0=<bmT_@f-NTC~Phg%wZl((;-j<aI$d{>Y)WAkOje_ z2xSvGqq8K)As;~Gd2sR`@eXc|WI2vw8kQl)xMAG_lRU+%JNY3Ppdm^^(H_j<9r)oL za47G#4}S9QDp2Gf1OYGmAQJB39-iU1{INU(#bh!f5Fo)HA_X2$B+2@r63g>f-VYMw z;2pYw91ir*n8J8e&emK8NgxD(`V4(YAu1Fjn__Z619S1n!5sbo7776t{9;QqDUnzS z!9qnG2!hgT1VvM{Je{OA3MyizPrC5aIHW@%+(AAg|FP>#PZ{uF5H>**KEV%cz)Dd; z9`510e6&v5)4K4W6ZpYDeWwj{$r)1=R6@xdoT3{3;S|8K9;gzC_`x5{!yd?iA0R{= z?&)gw1`B$RekzJf2eruNt2Bb(5ALl4ArmrX2vo8HIwJMe5~38Wp=0`?9vD?qH<eR6 z)l)weR6|u%N0n4dbyP!%AcA2ZfTPB^As?#Y64C)3N-Y$Mp&ssyAKDX%JarR+=O5l+ z2|nREu!1~(DgP+ORFhR%mz7hutRB2_4Qj$=24NAT64#g&TeDTJbOuGR>mQyXCbSG5 zK&3nEgQmK}Nl*l=_9*nk;jt8<Z4OLZ=apXT|J7cx^)L(p3lg<hSf(G8^wrEn`osYl z+94ZC%}gYSP#3mPsq_1ClsVjC8Y;mQ*kK<I#uQ8;7}!A@s-YajFo94HJBWfbyn!6T zVIIE0KmGGT8J4<wh8z%&9LfV61awe0@ma}h4^#*$^=qyYgcxq~WKiVkg6@m9MKAEj z16_7d<>FAS<|~v$^e{*4?4lax!5Y#*Ytvz(_~1?4!8pu89hsJF9VBe2<kgVj7u2C0 z{-GL*p&E{3A4JR)_Te}XB0e)Q^y(o}{vlfZ;T{@rT*X21TDEMrgdPSB73hG71_2|c z&1LB!Qm9}Apn@Evr$+h#x8krInuety|B^?-A@mNHY;mO=450-);c8Os#9UP&+TlC- z02B;D9cp(S+5sVe!yJxQI(yf59pj{|1UgD#8WN!rBBf(B<749%&P0q4G=U&E>cj*! z9LV7tO2w%XlujGsJ;)+5f7b~yN5$SC5AXmCh03qMH#P(!OW_X{>>)S*i>w$z{jz9B zjL$|i>LGYgefxJZ?Mg42AqemZMjC1#t|1cCKx@^(ZneRBzXAIkI6fV8XFij33H7t= z!XEZP9R>|J${|jzg<$HzC)+_CD0Ugz!5lKHp}=7gvOro7ayu{BZ0-RgX@D58a4fy8 z>*hg*d|1D<M0H|{Z|s44I*>{9|CWY*6hiy~5%38f=%5ayxDWV1RxP#~lEoZw;vEuZ zH|&98c4u^#m|?%mr9>BWrM4d8L}K<qR^vbr6k->mzzoD-3GzT8dXpu|I7tX(D)=lP z%Qh>7q*_*(8T#N46oZbuM~V5EJm<=;{-GY2fs&Ph88B-sOl(QPt%4VHi~}V;0dgj7 zWt2fqbkzhNL-MAS0UFlM8+Jh$fZ-d);lz+gfx37cI%pi;p_4Dh1aE4Ov*aBJ*-^6M zls!yUD7m6?c_fphk-0=O2o*(A6iRSH)PUonGEq%;W|Qo~f=DAf83stdh=Mk0W+v#; z#&u_KuRh^Mj2Dk#pyV&?|3WV`&V|HSQOfKoS&2t_^kPhA*rX=>sFpcGO{PK(iORuc z29IUtlVK8#Nv`6iys5@;P#xJBD8UPf)-RCZVXKxDo;yr>0+3+93n+I?z7$20%|RCj zSvy~Lg^wtpBk8+LQbAhwQ9nW%cSie&uInOh$3}WlAX-r%bA}a#uI4I>WUs*Zj--)T z#@a93WU7-xNjd)nN-*(A#8_XZArscYF3e%{L~>`S)`i58lJ?<N;UP*KN*qAgSx4`r zd8864ad!ur=$sWNBszqN@*S>W8oog~YAn=nHm<o0!}`IX^o^})bgO&0b@IAU<x3$h zg;8K@@x-`x_&U(0|Ms!P@*lDQhjqyzl0@Tfs?1KinomNe7y@{R0S~IdA56xw;l{G( zGf9XpP1g>=7{abC+p;kSR47qWD4_+91a@9WQKF2h$7O{n(k8U8wxgPL$_z3YB1ACZ zYM^AN`3`f)p^AC|DMpXRb~=$#yG9iSN`A0n`Z!s}K^~f>85Y8t1B;VCduO--8vbCu zb@5R<5HR^|r(-iLK9fMG(WBi#g7U-~h9MoyAvpA+ANb*bMq_G~^eaGx9AH<i!J(qu z!5a4Ayrx1O6$A${DkQEWK9v(b7h(pXqoGVtOv*um@PWdw`f=VN8v?ueNMj$Y0Xm|P zJCR6&6r?uZ|G^p_fgZ_0OvF`x{ns~+q~tt&%LFndyfW3q0WEn1iBiJDDMp6!pa2lG zyC|ku!~x4guU{F0V!T|iu!9;Fff^nX9u6-MYE~*X8XVAEE%w|}6f+{o!^789{pwl$ zj!ZNCeEdp|(FLm<R+thffrYx`A3h;WwR%AcJ=SJt31}ekDkLT9ObeS3K0cyAFhO-U zq&7H>EU-k&kAxeVAp{JeK2D3P5=pfZ=`PlSegvEB7{UZY$(mOw&Isg26d{}Rq8BE? z8@M5tDQ3WKx}uPxTwp<b>Z3Mv53rzos!ZxV{sJCcRY7J4#>A5w_#qseAsrAxFA_pZ zrsFrP|3pT^J=DZD?K12UmI1;mYjLK%4nu-q5~BHB6(L|fcU9w7U+p-=(@JXNMd-cN z-$@;E;V&S3g%RT7rvn}H;Tn|uNbPONxqUV<2lV{HD17rX!_YS?igfrvd4$BOs9^&> z0k}rvH-iZ~<Y6k<YKSWjJyNIuh`~RRh|2;?A%KSzg-ST{Psv=$4pZ(oF9JI}`qpA% zEr16-DE;%4$2(vpALb!*qB~1Dg+BZfB={j8W^XOJKD3vh9y)^Q>EWhE{WKGbG<pN6 zZmNL65E@#bZ{`;)SlX`=N;3+0Atc%GOA@DGWG$d%Dh2~}XXn}gew^BCA(#OOV8JUy z|Ba;lH^z$kuJ&Ps{-GWAp@iUp8P;JPnBi6h=^X^l9d^S#vqANtA>5mT_HS3t++i8$ zPC1QZA09#AG(oMuAsYzdA4FdytI0u0{~FeT9o!)suAv=jqaB`~9lYT;SPc8GLBXYg z9iX2b24l4}0X$2H-qgVnY8QI{0UGvUg}veU1;U`z;TImEf%jn@u7MrG7$EGygJ)0R zz=H@ADqP60p~Hs^3l{tbj~Jy+#LSVy_s=3meB}Ohyh!XHJ$&L&b;9_sp1gU~CO~p2 z@83IA7pe8D2kscSS)Hiyt62?aP<b_p7040@Pc)Iw77cRek6cJ;IA;mvM{Omg|5@(L z(Hm&aT)le#j^QL$trMzm`OF=o^!44mnsZ5p>*)2^xOwyP&5}dxojG~k%r)6S2+yZ{ z@N`iVNsZW9c#;AI+8_j8y?3+dM)OB+EJ1@1Q>#8G(O$iBun_eM2hSfjWs@dB!-rDY zwqBl~)#HY(g&~o^dc7-GaG<|`*kE~rg$;PGfBu?zngmOlP3W*Nafg=g+jQ>U;r(ld z$kVod@ZSA16v9p+McBqcgT}4gw_e-G*9#(rU=ac=*a62~Z3wlt+Jg`()Z9X4)ss&q z>4>CGChz#e4k-HQ0}4CbX!A}u&ZLu1INWfv4v6~vl8rdptdmKIpzKpk|26IWVvIHT zXd`4hj+~=UF6z{i%_IA~Lrx~@xWi39RQ96{KI%B44?5{MlS?|#{IgCjTb9y}IMSp; zraq3WV~!@qgow^G-&9lMFpsn&q&EGi6Q@3z?2}I=rnKYFHB9EiOgh8pa}JZ{2$Rl{ z=qU3}ixFn3>87pu15OqjKp?~}`Q-D74G@UBi#X<-nyL`O<O9wrHdwGh7RUT^k37_j z0Leey$P*4Dwcg51M+LkQ0|Z$JmsYWPK*P^J)C^$3wVzN1!2sa+gA_G*T)ROY-S9(5 z0Tv9vm^=KCb=W=sG-2%$d0e~5WPV&r10}l>)5Ns{Kv2y;HlS+({|%koa}PX$6d=Su zNZm7zycRGE-w1^Glg}G8phXD{0NcQiHy>ZS1~L51GvTHzpGKukSQsz|HsHK72^I;6 zzy^Zfv|vXN3CsbDIK@r!4>MR4!p&axlv9p;h8U2u9XMkVCM-aU@JBP_xKl_A2_#^E zA>w!<b<Tw}(;+M^gy0J~@y&NO5U}Kf2o}xUMmL&Rh!C~`2u9Pl2qM(N4TGn(taw8! zCsfw7>7?V0J6-1Uk2Alp!%mmsg!7p*QEJ1FJ4m+EPM80Xu8!%E=cA1~`#hq~KP7Ur z50s|2^H1#Tw3H(4>J7xFI=Sq#&LivGJ`FeREVIt>>-@7!|DgM@gZw|!6kq)#>}XSs zH_2q8r#9TwL;ODbd?TMJpt$o6qV2p>Nih4gqfVaoB;w3E>;xmekpA$8gBC|XO%<dp zA|VDOP_YCUbZ7*F00%V!u?Bj817p;f;2P@DD=XlH22Ie_Jz~-c5fWnpfuPF<;NTCX zKp-eofCN3pA&pKzf)X28gvN*g0Z3%9TeYDC1iW*PdJuvJ#GnQ$Mlg$a<Y5EEa0e<T zU>U#^1Tpbi0yXkLMPiHq75<nDD&DYxXZ&LcT66~?HZYkO2qA-Ov=FsokcAV;Lt-@0 zVg~<_561MvA6cNmKQ2g!3@$+k{HVqR@}QDD{=;+l|0v+5&hi{z1c43MkPi^-U<j;X zp&Z^2n<1KE2Rr-&8bC0FFW6uQUkrpdyn$K^V8J$3V&M<lz{V~nVF(};f*i1*n=gD} zoO*b|IL!#=B=Av=W+<Wsz9>iB3^7YzVB;Ix_yZPtA&y=g2p<I+CN=B!haebY5_SNB zFU;`{-bnJD2k}Qk#9=!qZD=1Ba#V<nfsRMk14ZdDhc@b=I>=P69mw+sK1`R7afG8C zxmbriYKPEu&`2BR;N3sS0XiwcqaOt+AMw6ny>-kZ6QvN-BOK)jb%;X~;;TnR%~1;R z<pZJJt42Ad@jq>Nj(GM6l8J)RK7JrdP@ph{|2zHxKX)YJPv_{VI6x{9cv>|z6N!cp zAds#RyrUlw<cB|~@sw)#svctvQ#A@;t#naAge0to!j#h10pI~1s3<@u!0``hOvWFd zs93u2Ad+KH@g39h$2|Pei3v=m8~-501fD}ee&m4$^ytV0X5lTB+2f8Adutv>kiiL{ zq91Jl*Z>BGM(j{x0^ooL4e}tLHO>PbmTPS|?ijB%zym4ys0U-v!ZA-xfD-Zv<Ugu0 zfVyU3WN{ft<F3jOafm~J&0xdK+9|fb1%Vsh@Yyzq1C3@HXOr02hDgd1%lQDI8N|d7 z8`!XoNdVz*c9=&k==P6qq>>z%P-i`g|8tyoVB?s+@W(sU)5~UTBR<<GL=p1V3%boi zn+~opEVeO+vn9Z7<amd5r%PQ)Qi*)+z)(8GCysxh!x`-0A3Nf5B4;Gy9|I-bI?9oc zgGRI*^lT9~-T~1aQxtjN5RyGKT8<RugB#|she)PGyl|A%9Z+INCZ3n2b@YR$?Qlm$ zu_wN9@XmYW0JD(7(WhLz;~hc*2m9PnkE7-zsqwQ$p4<TnbUbez*^rVr@X?R5l=#pI zDac*&!Gt%^MF=B!O<3=!Ftb8J91)YpGZsk~N*n_oyQ=J53y_CSAM1oAVb`?0co9NC zU=i{;Au9eMR>l6~wUfDrJ=XY*|8bnK6ZN?4H(E$VaJ-}-3JdK&Mq3#w1_EK7$O8l> z)7o9b)*m#;f=DF$4||vc9!sd>ZWq>sw<3j^6Ceb3lnajIel-hAa0fLYQ0h)lq9o)P zAfg%Kv;byzX5xTH3xWWPPQrpX#<9tB#8C~g82}3bx9%(P0X22@!Z_H_t}jw)2x{7a z9G;*X!W98vb>=eR1`fF|0xrvIDmcP;`_DJE2@Pxj1Df2Jg9tj#9c%>fGKt%FgyhMP z7QrqZ=*Whl!~wbzu_GA*d5x1rr#c~};}>E^p7*9Pjeqh3p|dNIHez=Ta}=W(yW^ga zpyZBld^>>L_{WCaQPOuL|3V$dYsZSVoM!QbBO1tisrZ(x_G<KfeBrPM@k&*VV$>rT zl~`&m@)VAw&O>^8MyW`Yq0|xqUFbsR?FjrJpG8Ev93xnSdKS@!<)&UFhmgZNVv;R? zEMgD*P*|^KGS>;@${%vjA*w-1kD5$TC-@lsb5O0Y#ZK$^`GD*iy8)94WJ}n@=IpUQ zE3tAf8@8y1_ic}V#wFb4wcVO+Z8xAYbBrU~@EG^|*O2>N{ev;P;uufTt*|9fL4u}L z5A!exfiOt;fEu8u5Y{D6*@a0hVjTUU2!${Y1oj>9Kn~520Ok|~lW;f+1xpp@3m2yd z+rUb}^fvVn1QV!o|J>jXsZ<UD<_o!$O8H=5G5Bo^)&k!^aR&AWY|sqgzzjvOVLsRl z^`HzQcLy_bN?RjM?v#L;LUaeg8|yV>?(kwZ!3|jA4CwG;>hNUz08md>58|K>T!;?8 z;AP}shFzG3B_d`>f@4NE4PCfpBhw{a=m;6YC-4Ce+>j5%(+=#=CRmmZr*nqJFb#@= zhv?8I`A}2sP!9Xx2sxEzc_JiGwhzJ3g`m(5_>c`Rh7N2ZDA#a?Y;q>0*oAZQ4JAS) z2ZV!ASU|0D7v=y7LJ$KnFaRU)58|*0Hh_yl@Ck1=2)7smHjpjgFbKHlMxBs*ydo1K z1P*)fi*B?F|2I(pB{2`=@DkLp2g^7Bd$3X7pe(pJ3-#a){D5n^A`ir{2Fv&cI`KrY zhK=KZ6v&20qUBiBPync)3siuM=~4~wKnY7=jHwb^bW~dtKoH}Q4+*(j@=y<-aElx8 z2DC;91!)5VU<2;}4oCEh8~GWRg^M%*Mu8D!K@~}$_k>OpAI*RT+ch6SAOb;v1!S`g z#!-U`HV@DMfu3NKw80zJB}>B;0%?N<Sl|mkLpTOt2iyP+STK`8FgDzP3DC3+J!uF- zh7FSdO>g%PN;#8kz)i{!l}x!|zz_s8`C$i_mQuMj@>CWi7K;xuA=ZT!n&S?BIAqrl zIoBX1|Azw)$>VL-<qp>1mvF{BhnWt6Mn3RhnEOCGhGstLkPIZE4egK&T{sLX!iNJP z4okKU4`mHaat+y#5Brb|kuweZpbg^CKY6$gigFEl=ML-84khvq`*0235M<$?o2!YN z`LH?akPg<MC;#wt>7WjDq77nFoa;aiWEgPp@Pu?}RlH#ixAq2kkO!Xt4wgd+dEjVo z_8EjQo?!G2XK|iyfC~Ho4)xFv;NU~$AP?R!NQA%?V8j)W01g^a4^1;x-PxVlSPs-M z2;7+~@<0#N(4X)C7#-1_fj|whwpaPkpp#)0iZ&1Y@Cm3;4+<nfjX<H%mIZl02=0In z{}L$#LQpaA=@tpp3GXlt4T%b~b{g6_Mvlf0{O}Ht(4BA43Gg5eKH8mofC}y)5A$iF zg<(ZiMVAM3UHQOanDl1NfKGPc3E1#Yn9vLPP!96M4fT~b`7j;jFb)ObPGE@%*ua&& z5FNX)4ZctaRMSc1kPp6KmQ)E1n9vMUItkq5htMzy*kBF;B&elS2<s#cuuw{z<O^ug zsHHSYEhedkfDLd14^Cs9*SRTFf)?~t7V_krLgG5FVO{i88(~U2q>3G+`iBGc59VMw z+z>#sI;+}HD%ubq@*%5E7MRZAhfgLB`9LEYQzEWIJ{~9%sS{B`BAIbftF*%#|Fs%G zwt-{0$|v<eK0-nx0}*#ZB2cobtQchutYT=LdR6j74nr{%@?a0Q^$zlYSn|M3QYH^P zDi5y&F)y*809ub{ky-yBP4hqxay1UW1rnxF8|Cm1^WYA5L2Ch|uN>ME3ihu3(6II} zEr8)I@qrfRdU+eA5Fz2PcUlhZk}~*k7ZDpD<M13)R5N$cV)Kx(4GRxE`gXM;uYjSi zzx58@(68|skw}rG15p!z@muMt5SB9ufABMyunjMJtZ}Cv_+U9sQx@7;DxOgf_@JHA zB@)lkZ7I266yXo$@EYY~55#)4;$R$LiXEj=D%Lft`4CjnL=gFa4^Z}G|4>Fx^YAqF zKn~@=x2!S_<uDKBV_nP&pa{6M4IzaSHxN#P7Na8&SNjkB@MfN4u4lmyXVDUxtC#Pv zRAPG~^*|5&K)9frwzsOar7N8c**sjgKYUBMVCorZ`x*Z58Xr}<Z$=gBu@B3@oPh#o z99j>cix&NmGSV3r1tCxF^Hpa-P{3Oc0};H4^+&uqI_NsNklQj7!VzWBk#F`6-ewNq zu)f4<5Ark)>pKo-Q5N734zZ=Rpcz{qNWbx04sb&onmV{A3BT-XuK9Z+<6x)(q@DoE zN9tR@U8}yc3cu1N5pqeR?&o$2rZMVkzu=IyvoHvY0B;?_X13~||2R0K6M_~5EWg-0 zqvP-m;2;igbG|hrPyax`1928lIG5DbDfrMgLEw~uNl&cE4Q)#f;^4n8!;4pI7HDA* zu*6I|=)XKh!^5!+<ghfXvL2kE2#UagHbF`8*JA&`8+m&grNRy0K)6%J4OX#(0aOm* zFc06Ljn);%^YCr+i;_MZz74Ud_;9GKfgJ*55TA;@0wk*n+_0f*$UhgK6rrjUR}fBv zQS9&wAz}^Q01mZ!5UywtuR9P_VqI}TtYfkz?BEWbd=^e4w*Jr$XFSMLNN78OR@OSl z%#p^L3Z~ZD5}yaiRz***D3|F=g-<HWuVJn5Fst-LPx90_|AgE$qIwWk!5i;uz}QS0 z0vkYaaT#MP6171kwi*}aKqUx4Pt4jh{+n;=VGrhP4uBzz*RljCQ)>a#ZRnb|2e`v% zrK+Wo%TXqA&M~VKA-d80q)RIjR2V=9)X$|t$gfeo^-vaZK_%#ls^YNB@$?*Mp&r1z zHuoh0TDo9l{5bqzXp+mdU7MZxz@xPh&wD#@XrZDF^0>lmRg#+!lDpH0vl_+9V-fw+ z!Kx7QM07j-#8P(D2(i;Xtr~><5Ko=c`}WjRJ=IOk)A3}~PR-O?-O~_()kUq<2T{GC zJIPV4)oCr&lswi{9oDOX)DI%o2Qg?O5xR6O);=wT|8nitZ=D)+{nxj8u7RBzrDCqt z{MU-T*o>_>Qby5@9oe9l%WEy!v8ZpBo!Oeb*__?ko~_wws*;~Q+N53DrhVF|o!Y9s z+F13Zl>OSU9ow=!+q7NVwtd^Uo!h#-+q~V|zWv+49o)h_+{9hn#(mt#o!rX3+{~TZ zu&k=h9o^DB-PB#()_vXBo!#2K-Q3;X)_u0n?cL%%-sD~0=6&Aio!;ub-okwlVWPG0 z9pCaj-}GJI_I=;@o!|Ps-~8R*{{7zo9^e8#-~?Xa27cfOp5O|;;0)g24*uZvtsaLE zCg%#_7JlIvp5Yq4;T+!K9{%AV9^xWy;e8bl0RR9Y`2+=I0096j0{|=leFE$O00{p8 z0|*>Qu%N+%2oow?$grWqhY%x5oJg^v#fum-5@e*YqsNaRLy8<pvZTqAC{wCj$+Bfb z3<D{!2w=jc&6_xL>fFh*r_Y~2O*#?CA*j)#NRujE%CxD|j+X=t%-{mW)2mpsYTe4U zYu80pCMF?x$*bA37lol+%eE~}5-S2MqA<`!0ILP*VDJ#&$gBV^><T<05U<<Ah!ZPb z%(!7#fq;r$<U;V177Q~RYu?Pcv*(>9G7H=#@WVoA0;_P4p`{=RftQXEWMTTV?UrgH z-QLX`YfTPGk`QK?#EI}5B}yEW+`GB+=g@iM-CG+WhoUfPRxh|cy7%wk!)yPwTGJtm z^X0{>U(de1`}gqU%b!obzWw|7^XuQwzrX+g00t=FfCLt3;DHDxsNjMOHt67k5Jo8B zgcMe2;e{AxsNsejcIe@UAciR7h$NP1;)y7xsN#w&w&>!EFvck3j5OA0<Bd4xsN;@2 z_UPk}Kn5w~kVF<~<dH}wspOJOHtFP(P(~@`lvGw}<&{`wspXbjcIoApV1_B?m}Hh| z=9yFa6COP9py?(~|HLWhb8OaWXPa;4S&}*Vn8W8k=72+xKWeJU*`0{qDUh9dHmZ@I z{s1ZsF1N@c%PqG^^G`pV_S0CRpeE|*s215{>ObO46rFb<)c+sHkGpf{tg~mFy=TVZ z%sYE$kE|rSBV{CxJI;3Y?Cb0;*-1Li%t%s6B?+ODjH1NP@4xrIpFiI3&+Gkoz247< zTT|VG#{G1KvC(s0Kvjwa*G}8*yyh14@v11i>O79hAYatG0Bd>RlFo?ye7gMACxi|s z+nBLA@U@5j=)gv8pkx18U-QLR$`-}8FesicUTba&-O&2py)-Thf1I)@Y9;$|?eF)Y z)A1yR%7f*XyN^L8vOn6tE+5z+sr%Zy{jD9e%CeocB3YWpho2=M`*VI%{tuEL6r^(= zfS-|S<>3$OXYG@FDBGHul&OBS`1y;Q&{O{Xo^vUIIr-7v!To0n#nTtEp4xZq-I~OK zgZAaJiuAfpRLIdQ_)|lR)_=G-t~PI?{I4Y+y|!R--{_T|I+ttzLPtxo^I6aumtS?y z`R6=iQfU%9x47MTN;mYNuQ-Wn^}+Ll6?Wyu_*==TvH5-TXZd}nq3_ypE$MPKrc@@~ zTVY1OwrX?ckfrs8e7Glt#xshqIwrEe$=0B#R<ktxqv5vc8uwyLHHurO`#M)ee$G!y z{@Cfe|Hb}b*ZFAo=MV2^eEJVgQmNDOtTwHuzhz&ZG3sud=0AUL&H5*J`&*xv?2%`7 z$mNd@ECrOO6~6q~f7d$m-bTkGS8!z&QlA@Y!QH?2?jL1>lDcik&x`l82O)K6W2eGD z&cB%+AU<N=|B-lXTTH2_mV&K4OY+!fpXyddfn!_ZOW7+JPdJs`#jFT6%06JbesR4} z7JmUhGW^`}lRk8LMnH4%(^_=2xV_H<zENLyNJFaHEnd4MQ@b_hQYrBX%?ExH(N!Nu zjEq>E=2FUI)BnEiH&$??7rJ!-QS?=QRJHvhJ37vX6`hK#;jzpB-}+o&Io1@1s)=S0 zScB_9hvU6-qi~G1h=y*%KUoY3=^WLZ2QRu<B{p($2VaR*ipi?~tKk_SUFDsgoP@h6 zO7C2&ku%dUmpGX!IGQv;283sXo4p8%VXPPQs>_OtHkW>4UawL-HRG>!Q2MO(dOl-7 zXX<cvX8Yv&Z=R_slYOxQ&HVbjE5uQI<{!z$ixR+(#+JGw%EBucdZeDjoT&JW!$~7u zeJb?a(&tY;-pSG#b$hKn=D&{rjMiK#er?M9XtGcJ7Drb8d(4hEXR9(WUux|J8^!B5 z<j11QSih!>C6<j=TZ~HOLhCHtOchduLdiU?!wjL=9oKk_^q_-`SoYgsj^d0ak>8Hm zVVIqKt=oJy#KjiQl%EkTnLDpigC3v9*xy5%?HCmQshPNcB|^Tda-P7ayXmMFNgH$B zV9}h-Z8oR~dtJ!+UV+lp`p^j9e_!;d*X5iV*LdgHg%4Hva9J^(V&p}cp3P^XC#7gU z{p20mtHw_2J+$1blqF?IOGg4|rk2<4n-On$%|V+jH)ip@-#<6kaGDohYm|~3iEM9{ z&wF#awXc+vMZYkd?cs_eJT?lM^<km1jrJ#t@A?>wG^(dLHT93#&0Zjl9!I8x*ja^O zQLYU4OsYW0rO76L3zuBg-;d_A+B4@QNo8hjL2o159O|Au?Z1#+19M-79A&V*`|~Dp z=LxGxVD9p>f4}a!zFQ8-+5bp)O^u?qFQVW}Gx|`FC+1tNk=hImg|Mdq5aOa=TG?5p zLzfuWSGP;~8N6kXeI5WC7dH4w@U;7n$9O&R$CPKv)$cI&a^6k1-A=d9_g7quVP6|R z`cJM)Oe@_{eMKjh(b_0Fu@$HD^(6tn<*VIU<oK_q^kkRcv#{WJ=6ctD8q~cjZsFni znC_f{*H1N==lk8%jjQxECC1n7no5n--nq-*kRJ{8W^PZJCx2gn7U+uZJeTr4pkWQ& zGS_SM{j}PVd24O!&~N~A`!l<OSf8Q=|FX*ixX}V~ERavT?<L*e?zBVq$(_vy(_a_) z6i*#=f31OLZ%F+7>vu^+?)SBuQn#eqhfNqFH>kl{G`(qQp(5D^?a3`!U3b_s70@q& zC-)=OTHB1ivxK)g6OsfHpIi?@AJ|ZN|C&5laAZ;2csux6(ECxwzb+SS%-gAqM)gtQ zYY`-1_ss0?n&0vwnn#}-ltTLIew%i_eQo*l`dMnX#;#LJRAbZ8yfM#{SGG934OhZ> zohy-jJV-|t<#zYiaSB`g?vyL6oUP%e-8r{XdOc`Uk=Q#U8@UVLWD^KP_as_*IyFm| z@t-sFRIa4$Wr+RScx8BHl;=isL;=;a9mahgp=)HGZ^8AE!lPSjO=@-*+hXt{$<gk? z?uYzy_lW$VEb+y?p5^<3V?Mw2hcnjxzoq)iBG8pvA}~jCW)E%n+aIQ{?IOoX-!6?l zlJkA|HLf7?QL0*8A?t(amL?D!ln7LC^SQ{Xt>(lKDvvPt7zTA2zm(kMpYG<8y^B-$ zEFt`^&9bl&%X5A_X*0B6{QPuN`}}17hAy&nWO<C=&x4k}c<p!c)08a(#FbK-a|AY# z!F;faXI(Mn;bxe6cAbJibz{Y=(cSew@192R{X$u@8oJ#4bKdc3kBJ6}qm{z_fJ<^q zN~(3?7$#Xxap7>DL^fz5LOqcyI*}(ek$Dm)u#_k`iDN!yIe-H|E=k~kB&lO2H;&uO zB-kHcwK7qpK3Dk9LX<K);9~;_lo(551xO;G4{YOINi@7<AYKX9!VReBR@n#M*()@S z?^C%~2fJ*4c@oU(-4(ZypU4)?I6-Fc+)5sWr}!NwdzwP*JHSExDIrTKVaF+09%2NN z7&)0@uMfFiLX7Pv`an}A0I^yxeBSRdO1*?tV^dR0Qq!eiHI&rU^QF`pcv^?EQ$K|P zC=9{E0d1^+2r?we8$_cNUtAYIrcZB3rmfaz=*6jcK#bX_di}+B`}$CFqL*d9NdDyp z5Efa2_L+xVm@k;Zh*TyGfSC=-^Z}PSS(3Q|V2WI&dw!gGdzJ1b4<r-;S}Ms}?$26I zg*_uP&cL(RklE`l*_+YXTP4{${n?+6vl=N`dptS&QXp3nIEVtdjetkO0Vn-A|0Z*2 zR&!{kau)hCpOs`nV@R-4(g#ZB0fK48maz+-FlL*}6_d+Tn#-5Qur<MOVZ<%+rZ2Vy ztHA-b0I<y-2m=5US0PC_;AH@$7Y-{zz#_09r*m(xIs(?)k={@v-*~9bIqqh+<tF9K z^qvwBFOnHg%WQqZJl^QFk7aRiE!@|K-9td#q@fu&h&lqKzE|i&UvvT99%ErWSXe*| ztd>;tc<-)<l%#O9ZX|Cpdx;ZIH2lt^;<&)Xy*=iE`JyCO2G-%Co_Tr;rJ{8DBHyVJ zzegqMfixNvkUIcu27pB1KyKtxQ&MR;J*47M>HVhCQfWxNG=#PaQr`r2^ag1t0XdX_ zmu-RFF+dwEP>ljYE72+`(OP=bsKbF=-r%fNNESJMoDI<0arrB))VaR2LjEn=LTgVh zg^v6n{>=hw`ow*u!rvF!U>)?e=WzOpJvtxhBA+x!CYe5!Oi#o@D*=h!v{I{MUVmOO z{l--umsXxORi2hs?gLmpQzX=0%8q`~&NhxayFgU>g=gE9=O^TU+ho>fw}vEGPxoYR ziiZej`HFG@7I6?!I6w_i-kC<@MlLIDsx~E;#jZjWmoFBjN?4!(j)sF&a~TV?)`ygw zR1@J`7+bI-3FJryq1?b3dmu>wbP!GuFpC#T3;KS8C6tSKvRcouPH%`qyEq?~D+TL^ zOI`rT-xP8Wfbnq$!!r{2Z9gbRA98OV5{85Q&}Ui%FvplPossYOIThmE3J-0WKkYHE z+ctheFn=PsrkuZ03yH9Z+GoB^+e9xK+aEzDs5IGY+<q{ABWIv#574x5#p9EHlGrhG zYI<{XS#y&cbH>{JM81|zzLqjL;4%dQI00j@z&u<$|63T1H+?3c21^Eqk-_0)Fb)gN z!_rqNF$|6}6iqUWtwJu7L9qa6d<T?P7(xU<FiOBArF@-}*zpC}$u;$G5jBO{(3r(K z>tYyw6XtHuIBUz;3%_6r^cJ=`q4RX^WV)bvaHIZ(AA%7Q9p1s$xQmS={$bwm#<B%t zH@un2v`ta?hkLe7Md`Aou}!~6Wv3!p|65>THf512@05AmDIJVG)Mw`90|eoqG-Q67 zb27e}8&CxY2(SW5UEn@6P*r|Fmp4PdepDYEFfkIZoZl@Tm}lz^vQvVSrGR+|_yY~t z7g(!f?Bz3x;V9MDM?BmoSbE>>!JxNXe+T3!0Bi*ZV@Qxj9IQZ}X^rglFg7mGndMN4 zC0?6l18XDPlJS*Ii5x+$Oz*!f(jQXYZvbJnUYGrkFE}F^UU(N?DBGXUe+%Nn(k=t{ zLBLZ1kb5{da+MA!OrP1&MWY`N^g)@YMtE4j+Y#`(a`<H>cp<)>&mn5YwI9OKD=*<- zEeUJaZ?hYK5WK+(2p~5Je3Jx@0l1t~SPu0IH&&S%WpJNunepj2U!5o2mh8Uq&{)V` z7Oo`)g!nLk!@K1#!<UIB;7^aQD8sdQ0DZD>7OJ90pTe0EbHPYd+nU>vhQdoth3ZvB z0awOBeQ1_#jrwZ+O&o*UW6BtrX<eTsNhOov4x6)N?1CY}9Zp|v3lFzt9Fm1gw~kO^ z+jUYj2U<pG!@Fs7yC2FjOc_Q28TC#8%=TUCdyawoS_+H;c_sj$CZI?-ke(~8{eicf zN`ApaWR=2j_<0Y)d>)dDi`A2bdpxeVeS<=S(_8utH|VLLQGzx7<fiqJ1}0LUc4gps zT(60FwOoYOJ)^Y2VQ!QX0tK3Bn@isvOKem;@zw6X3}-pt9KNJ2+^{za%B|S5zy!>| zPpTDjou`1xkGtI;FH-HkfE+JxsVk|%IuUKXdl1))uEQQ(7NTy88`irjBmH?)9<O+T z(rAEjqAwmA-ayz`!258D$6bo~jI5{ptji|)dsy?EcPJ%jR1FCx@RlKlM5_#V(uN}p z+O{9FIi+r@JcKi>V!h(oBnd>;`R=)I@8@;}te_%H;Ba~q*(up!sQL`1DWAptmrB_+ zis}}uX+Cyr9%@LUb;ZGoD7iX;44E!L9(?GPPPNj)x#ZtLSsn<~8_zZURG@H-`LPn4 zFw$egA9<?cpgKRM1as;D$>>81$nhJ`Qq9ka)H-#?xCZaBBWsPs7uX2|-J5Y51cO)W zlz48METi7-%M(fjGYq?O4V*zX>*CC(Bj6Z@ycxbU_iUA^VCb(5l2k=&A7u&*A>xE( z@F-zci1~CpsMb)J`x#N)iB%LPD-U^#O0NQp*~CppEnZ^~o1dgGIi)*tWw8!<48gCA z1FkRfewq@>GL-3-@157NDbe$FV~oBJZo^gF+mQFnYA;=^>+bUTdTYt4cq#pourx}Q z5h7LNq*?S^>9#+;%pP6M>f3wZ*%rV14xi<hy_qw<u{B>6ZX&Vw|9*T-sN1V^lkZY1 z0MI@-9d&0|_G+{KwyuaXl=|)TI_><QsPQ~>kUSpB=;f$&^|`)+;D(#R7=sguwh{Lr z*=72-26{+G!QI~DJyUAcjVAy5w{=FQv}TZr#(K85H3uOL>&}zcGvprjn{QOBy_%Oy znf)kMwcHXadfkAx?6|8fLaUy0P?4aQlFDGJ4?P}uGb)N+ONw9_(^DJs2^yOg^cfSE z2%+8+)lh;z`rA!=rb_3)NJXtRU4L`a8!X$_W7<Faz<H9zYS@?Xp?Z%|^_J!6{TJ(h zrxkn`e>3RO13hnnE^jZw&V1iBcl7jApoL1{QWAaI9yC-JTu6cTQ+zf0P*y2={B&BA z$;)hZ?+ub-%@NR$tJH?B_r>S5^Q=^h8hxPe@>Mr&rfhG<0?+NDUFZ%X%`yM#I-5J~ z!zTHkAM`tOXblFyG)gv?uadxM=t_taHvaGf?2rET7u&DBo?i>vS#a$0_T4ep%2)`r zJ9@-VsHAc2m9d-hpS`CI+5ux@SenL;*mpAwU0CLEGRqd6aeI&9-G9tmN?*SyF^qQ1 zPUQu&Uy_YpyCv~+?%T@l?td8?BQHT17oh*GJ)_M*C8!f6*4C1-!TbAM$M>g7dr!&V zA9*u=*`r_Fo0l6>F$Nl58fW9N4%4{;Y}D@d%(lq|j<Q}$9m7FP1z~;Up2a=-*X=B{ zPrnaSzHj07D&b7I(Uhh0f;v_3?W0YWy}3!;nJ9(~vRgeE_Nbe_uiinudKN)by_)n8 zp7z{(f1Jc1^YQyr9P`}j{v!OqS6lgNkX3rUtB(8*I!YL8b+zM~+C%-#>^YfS9wuv> zqhUDXD4em>mVO(sTdA~*`Oo^gjY2;uu%h#$jPg%j!Cx#%xFe;BcSg$PZ?1AH&0;R4 zE$;mo$1&5|Fny;$F0V3PJYQ4Rqp$-<KN&KZd{t9jVO3WM<=YW;i{EmRK`{d{<03Fs zB{f?VY;^VTqTls&p1Dk)sZbx3vj@%YfKC7$`t_%}85L~JrTNDt?}_|KWcfw7DQxD? zAh-GcPAE90V`1XFb9Q0=*IQ=TA_5S%%Djy@&Bg)E5RgoG!tD$EsGpyO$m@nnCis5( zcmKu9o5EOC6M*paEB&N)3};tf!&0MDn{k$i`qzqwK6Cmyv?c)k!aJo>|7nemO|fbg z8-E(vFn=YlXB`HQX{u#WjiWgQQ%dc>SpTPU?~K6huw`3qlqG0X#<6WvZ*^Zcna^>@ zq1my`bF9qqt5f^cC-Go@^#+~0G-sa%#?oK4I0wBFwCwNrwCp~5$b0$DT&`#kAB{u$ z9p+2Qp4|#GY*S-7bq<3UAv1R9&UN0~gIQhDuW#5^nCm3aeb)q_X6vjfjqkf11-)*& z`dGq3T?pygdA`_uWuxfTu*S{x-VyN(;m01)S(-s#xB-`<-Uw#Lj#(^<BRw($Tu19t z^0dO&pw*(hE>E!MPDJBMPn|DszJGX16!JQY`{OxV+TyI})#K9Z`bhz*@R28IgOiBR zGQJ<l7K7p60IZG(*<k{W+MI0{l39@zq#1gBfU6iACbcAy<3L6GrVgjGK(j8l7eU#W z_eO1QQ{4WPjey@3R#S0DT1)^XWjSc;kzMxuS~-LU`&sBJCUKXu(9b}+K-wQipROyC zMi_PbBiyEzFfP_*dHFf!vX$B!hnMx`L4?cJnqO+W=IVD_z6gazHf71b$KGuzS-}Q2 zQhGdd!RJWhOc%_5;>FVqoOTh{T6&lJOA;Bh3T%@s*sSDoS{Gf!dK|QEjMN+*oz>)f zJI|z3Y@AO|a}hKN!5M{#)%o}gi{2OxfOvCEUX_OzE7)EEpoz(|V*a^5%3)E*rQ`Hq zOx-=S?^1@GOJHCy0&unIyA$mz5oob(#r$Ws2*K7W=9s6fkhe)o)z|1m*S63k-JQn7 z)T=Z6_B}x?XCbP|kFNLo5QT~qg>Hp4%@)23x&&=ULFEeymmP+aStS)75%{xu$pC=J zS*|gkf5|5!?u@s-U~V%+Mr+EXKbcytVK2bsQ<dh%<6DzstQFYyXZwbpYwaOxpE>*3 z_45J-qyl`$1^dD<!&ZUb1Sh?<4Fu2>_<-PgJP!#)LV^ApMMk}d>M)V|60_w%;%2$( zuL3$0c9=%8<-drTT#0AS0G)1iv+#$$IlfY@wr%dObue5OLz=Y}ZnZBix@b$x;v9CP zj>&Dbp#~Cs0pvgvfhQ*4-M7eTf~cquQ4?G?Ix$ToryjXN@gk=%RwJ-oNR^Va2bWp( zVcvNzDElTEfWrm((<fKCL|!`Ec8XS>K;7CuiTSbI^gXldX$(;>{^Yt?MrCYjXp8y> zx`@*vyL4d!ES*LnW6X*HOE!{{vtzo_8p=h10{|d9CX0@-q)hh7%V%~u@u}!@fd{T1 z=Og!rP73D<l76%IzWtO>oZqo&ZY+@v5QceT!Xn1+j)~_{pdP6sY{lN?;$l@<yh_qS z_1C8LBklRIWER2d2qxWHq>+r%i*)BvU#^~hqY6{jWG~P)o~IF&`#-Doh_Rm-ZuB4> z5g6e%fUAY!3$&26DM#jfvdSGhW<SD6D0i)cTy$<u*`Oq$cbcAltl!jFeL=F5enQ?i zSN1BapNF|0SbqElb;HqsIiPBuAh=Jxsf1_E>lm#KGU{@EU(Lr)crI+k+0B|VmD@L3 z$HP$Ea5Hm69!w+g$S-%m@X<q_A}lS-dH#U8G>J913nK-)KHS@w#JzmJHKDirS<ux< zw)i8cf#(NRH5^r=ueV^OrQ<K%gPMbxE>T%=;rtQwm$_i79|&&BE#bmndEX<Z)!)6e z;(DP{0Wp&LarQHZe<O{5;y8!lC9<7I9mGAhho(F1AYHef^=<YxT`V!P^ich2tl_p5 zwA6j2sJFWgDeYo-UCX}igH-u4DO;(|*h+u@N8n@-SSF7IG~8R`D)9Y0hJ8s2|KuOM zV7UFw_Vblyr=z;C>OiNSWu=c}&yw^u0$o^->{lnNU<H$joMA7}|FtKVE-rqQ4Y13K zi)2XO5p9g^9dI7<v`A0>>*SKA;nJaH!yzbRth|q<vEZoT{CM#yT#4SID>&OM`QdP| z=h3qB+?`(QmF5ZgFuSTntHtgF-!U_uT!O_RiMz(u0AVWv>#KO3)O!5IN@3b+HtcoR zQ}AvE*Pn}dv1<ZjUA8o@nykfp*_a(Wk}pR6@5=??;IGK@D!-leCCudjcAWW+W7;d1 z!EXk?6h7B08?S7r`q>@mP(6^h3i0fy)^7?JGi(LmGpy6|h;9t>>4`ZJOZz(OMoNw^ z9(&V0mM}@P5RoYUTEvqS!fM@t!4}A-Gl1t=#<r@$QVwBP13pVc-L|^vxaiH*=OTCQ z8H)zVr^;vOce1iy2G<&nE1l~HqM##*lP@FVy{a|W8^VUQ?Rgv@=Yxqco0JI0D?vp} zXTXH7-9H&b;~4xDXt^(4k`2Qo=IPWT7_#a@(V#0#w@Cia9++V(TwyN{jo!{h{hGS> z%;&m0bp2WaY|}c>-%2x{H>^Z%Q)*w|0siAwaB=clp505ok85uiieH=kM`wyM$S5oe zdND>5lbe3sHxCiSn=J3yk|Y5id6?uO#XCFfZce0o**A1xc++7#{h#J^<E)R$Q;#X` zdi#NSX*%&MB%mt_&Hn>8VRrD-|JCH%<&crvz3y_`32`+xTK8maq6%eK0c+51)9ES^ zxg|`N=371rUj0lt2fL^S$g98FW>gaz-xX~+uv?d4d*j-L6(OA=mgoD-l1s?n=F$=Y zr*1g>Q+5J@D%bt`x80v7Ke-gUD^i+6b0s~LNmpqh#ik6@S7ufboLgdD!UQ<zp>4*s zA~oJO{RWyt2di2fyz{wx5qDc<Jxd(9zhJ%-vIJIr7i;8Jc}DpP3~t>Y?N&uP!=Cr7 zI4iEa6Fhk_{`>{!Cw=PtmGuSi<DI*W-duhSf36u_2hKCaoL=Lym`qZM*35Rjd+DS5 z@SmYR-RQOfnQu*i+R%wV%H=-CJv*NLfp6r~gRnJ1f0QRQPJgmExcJb|xNK?6e9CFh z5Z|*9j@#)nf6p1qNim<8^$z!OGMh8sHg8}<?ovw=3eG<Z?m_`Fjo!)E<QDnAxPQuc z@Z?mbY2^g^uSKU*lhR9i@?H1R<VJ<QSI)`gpWjJ*FViwaN|HVc-sT?SEcuiZ8!0OE zP+Diz=4Qb!osVbz9FE@X=brx(E&bX)=<(Z&1h3Im=<D8<B1S+P!;yM({6j~7AvXaT zC({FeyC_EcMag^+!);ZY45jJqGCTJgW)9gV-sBrf7seFG{nYMQrS`iB$lL+Se=;8n zhur<E-FVCoQ|(|lG*A|4|Epgx_DHv{rLd<Y*>51(p+hWFv&TyY0Spw`uIasxV8W6h z0qA7$XyB6;<kPpX&1*wKVrb)M#GBFJ&u=9!ZaU}m)MRw(e~}CW^i(ky_hG<NTLruk z(2t5(g&Zx9D6|?>G>$ZrDJmEY2VX<H67dEcoY+_^5;xM&M2kdltQi!G5csb~iyNy# z%-9=CWFQe_WC9d(okC1rcyc^Fj9D}IO+&>L7=3t@!xV(!84$CI6!cpY?&9zJ`c?A% zTFU7pnyZ_r`Uw($oRXkqq|lm-?SRBIYINF)RW4NrkB*0oj=QcK4+l!=yv-FXrIM}* zc+TU+kOO;<pS<C(526q`Wia(6DsgbgO&2K#7ody_2wOtD8%+%7X=hI}(PF0te;vm& z3Q$Ib8tLny{M=Woz&2~i?<vX;`TEX#;9@^u=!3_^zrqA@7f@6q@h*Vav{&xT0V6m} z5l_Z->>6I~H|5<*GIr5UyMpQ|kzE^LZCfH!9}z$PO+f*s_Al_jNm_}Fsq$!Zq2II6 zhs1wdUFHKkw|DZ#hQT_kNy_N^x4%g_9yiz=rpK-lqe>nRFc3>*@mEcaq7aaluk;0@ z_v;HR9H;cVq%yJ6<d;d0-O1oPFO+hx3@!zOvBwD1>1bz3dOJhoP<{zEni#uB=R29C zuAiJ73&}Vb_?0-#Wj6KbaK_$@qEaUId%@xy%KQ3Hryf62-@aW{pmr$Os0CMzjh+A? zQpCwKpJb+H2Jg>?<UR+@oomuJCMeZdb}Ro2Pp)pEy-Jz(ddXxx3gJdsc3?TnOCWbo ziSImsrdug@k0IDp)w?{fppecLkMtnMxx-ABPExfBEq6r0;Av^{N!jFeHhm$xw1j~{ z9o4LI5;3gbM9(D&bv$*E;lT2Y<<}_D?d42<tNsze_IOGB#UV>?uy$Vn$^zMJT7an> z0jH(ScJQ#rkcgad5L1^V{k@SG0Hm`O()u~=-q&Gh-HSy8L%k;2wI3{sYWp;t{AF!= zCu1-zg5i-2UFh2Lm;Em|RdcZY#0UVy&^t-(n7|}rhU0j?@0TMF&f+_|@(L$%tC4P` zQ+ay3bM?5#mp}PDc%SMEdbuVelsyXZjmA$_rNokqe;z{i#hxGez!YX5DRM3@BGFro zN-symJOk2Pmm2QFW)?LK!Y5h&L=WFxh4`jE(j}(^wh*s7Je=KHFyM6TFl`Fpe+lcc zd2Q)ncOWikRU^g*^?(!I1SVfEk-7iTMK7Vu;YqqkI$SFxibv-vy0W&l>p!WIa*Dc^ z`!l=SPK_=Laio;pueN%_$rf;R1|L)J^s2<vWYODNqqQtNvKNpVl5p|Uyb3fgft2CL zKeSwGXjDCndmZ~K?S3nS_nP4csh1j=|M`5iW4@Qn-i^|DJN3s!>gs(+>=G&{8Yp9H z_d}J4<#}>G%P^TSwv_qGrD-iq`d}$bjU~J1O|F`82Y*j)tRjO?vbh*XsQm15f3ovD zUHGvUkFZTW?~AZWi69q(Tr}Ql&pLiy$C)1Hy#4Z!<P2nRj1_-tcXfv69jha_UW}I4 zb2K>={M6D<3*|Ah6UQ<Z$+<l^C-<G8GjD=jh2(*VRXq9CvkP_KXL#frKZdyFeW;_p zRH&L}BE7(iA_r<22FRZ=M_S6^_j0Rw^25FLV{nk5NuaC?&>?`5a7e5{x(#2RQZh>) z2z9IZHxNr{>XWf&)27vFeD3v*(~;bQs>-e1<D&a!8l;~r=YrRlVu?o%^>M<aBi_wE zft|m=jk#63&(*zn{2|xj-UAYEY2@SQ%S&ZzWsAH&GoSw>hOH7~wjd4&f<(uM<UC?e z@*DFm*j%k%z4*%7KaUD?aDmmzmvpcuXhs#LG%%7A8}Q+|i<HW+Va##L_fXoN+DB3I zS3kbeM0bnN=y=_j%}*wjf4{<T+qI}@<5>?p`9_K3Ydrg*OI0{!<VV4bTq8a#)gT&5 z)Dc~MfHTVCUjhAE(7B~!7UykDp)tNalG3W{Oi2dTv2)VD4m^PPlR@uK33{h<D_PSW z*m=lxAHJ(nR(Ea6EwwyxKzZ*uK!MjI-!4f$1wI2Mcn`$p2x1Ne$sh<J{X~9x$a(an zm&!%J$9S`<>zd+|9KBY$z7v)U;22?MxO-Oz@~Z?!CuMW!##6c?=QvO9Z~c2brCdda z>PXUPOy;S8j5#WTFA~9{h1_M+k!O~uVaU!cMK`nRFT))zR<AntUr2j2a;kV3TIWpP z6LBhnd^;stPnwvL>0<gJw_M&S3ERBv>Y?5As~2nEZt+bsytIl$(0k6dsV*cy^WEBV ze!?bIT(3p1P9~63bOMsp5GeyK7nU$chNG^(5xa)j>uZ-bT^a39J31w^2cN8u)xcaB zT<yb-G4;IbJa#ND>TBTI$9KDv#Fi#zzosNazJvdJId^Ksd;i7lO=Hv)<ou1cs*kz6 z(d{H#9tnG3y+iLH)^Y0?Db@*xNFLDzk*-Malt_eGJPz7uM}Bfk3b<2mxbsyyLqa*t z&+t`&+`DN1zdD6O!sF?$Ua^58T32ZeN(Pceh~aep`|@4~_qQ29a_I_)%H~oFC0b)1 zHQ$!P;ULkF0qUjQ`WFEUNp^Ieb+is!DR-XC%uME!ieQZ^>rI=+($CnBj*NZ;XSB4^ zy75@a^UG!qg2nDl6c2qI+I|_<1c@LKU8m<z9f>HV&v)dfsy5R(yS`$?GC&2&UJ;Wb zU#sx>-s8hNmJud#rVGfamiv1UqurF#MxwO~tuP7XTS6R=ozlqtdfsSSGOK`gKKW*T zqDl%R<c6niwifE;CO`Wc%DpXrKfopq@#5}9BG%HT+TNz;-drr;`A>Y{tdaL>ubvc4 z+iSl^#D1;@&)fu35}hT6+urEZtu<kD&c^7;xBz8Kk^!dfSPCP@?gFR8k6~(l+&wyU zo3egPvaQsIKS_LQBB{Y{p;|A-8J>&O+g3$%2;H0v4ei}n{zn%}?n@A>*?WJZfwCtp zv$yDeMftv1c{i^BG@0qT0O03kmh`zVy6@q6=_PBcm5f6r?gW{mm8u?1%awKg+eS@c zKeey%#chcL6Kfuv*~yc6>LLtj{t~6v!nc0eHz6{VPX?l*A?Gnt#Bu~d4oj;EPl;MW zL?9qD#}UpU^I{Tvk{>k%Hdq*Bpx+NvydoZ?n}InT3^a@ihhC(Y9}}ll4*+C3&)Foa zfZzij2u=H~C$RxK&wHmwAXunuMvUMhW<}($Q)u%oXQ#tv>~zH*(RBrtK%$!(#~Vo5 z0)!yad7HINj@D0m?)YDK;k9xaNQS?6*S}k4*Ek4Ld+)#<IAk~EcbKAA@!hB+QLYgz zLI=Ul-*|2`1ApaL_aV~j2U4b$&b@?}1nc$8l<NN!acffI{?ZYz^6QfnSkT|43f$G# zg_goDpsAy|Q0EfdX*d{depm809W{9Vl3GE(TjsNXa}oX)bF<_i@>}fvC{5O?*5k)_ zhFBtwQz}~_K{$d0k8Qx-3V`Q}j@5pj-xe_5R?;T=fKP#YoyEeNaD$E40@bYMn_>Sv zEweIz!<{KGza)Nj5+zJ$9+0GiBjm0V<BuoE&s_{TT#F5FX#5w$eeDoCkLNGRWDX>> z=oltl8hdr;&Yu$TQtphu0Epxh;!QFEMW)e@j{Qu{JhoVtc&^p^F?P<}MQxKX*}*R| zU%Dj?Ph186d38JSy{`<qFw(l?4I;V%`UTsl{kQb41P<g=(yMSzH_8<Y4u1VqPjMld zs9TaKoeD&50Yz<TMUXURjeO2pLK^IEgY90Q|IEu}Qn{rX^<K_2C?LQ&;J-gjjWRD2 zIuo!EjmAtP00^l>t3|qpSxxp05UDUa4sm5Q|E>+JP)h)uoL)~U2?nCJtjid%m*P%- zI-RXHBfmre%~C;<wzT>PR<lV+nC$~KI_TYBv~anAJ;VqB#;p>vWh*?G$|iY*@Ow{W zJd^I<$=5eI2)&q(XGaGnjCmxvq=J8cZ?Fg$#2ve_aRexdjHGKx2YuT<kenwQ64~T~ z4y6`q&2#=ReDOEFZ<-6DPsjL;OUHdOrCZ&)DeXe$irQiHR{myNPU9APxbwraFXCv0 zm7$xCrTOk}w<P{A`yy{C7nAJ@A;(H<=cDP|HKBhNXX{PN)rCc_;1{1pB=Fu6l;!#2 zJ;(iuEpqyyr_Phpv)e&kV$%<UnhuU`YwmrzF^@Dl*!})jV{bK0^o(5<pIWZ<tZxw^ z@=XYJ_ng439{NG+h<LL9LUrkZ=hLwLoqshc&1U?vG43n;8gstCv%DUAKKP-oeRlfi z_ko6`$6JoeP~<9O5+OfFbK$7C;NBbgXj_Y)oQn&VpK&#OY6a`LAi>I0Q5L<8xNAj* zOl8QAc<JVTk&M6pYAl7qYI9R~?XngfGmPnrt{K#FiskEH%C&!P8v6)sDyRxr^RYOH zyPT~_5A(~hgx~Wo!k~g4i5Fk}gL$uazG8ZirMf%cU0$s7mUyiUZr%4fa*uE@hdQ6R z#Uk!XmYmVp>{k5}D*j)9TX`~HtW?gArO!5m5RpFtE_Tc8%$h=lM04}7Z);W-KU@Mf zFfO}L>884}XYcMc{36sh(@rhsp(=V08D(xlb0;KzxBg<bqycDN#{_Mph#Ryv$I5k1 z$vpmMXKx)y>iShs^G5r}qNtgmGH4;qGfq0lra)!G*y-U+*<FQ!?PhnliP~GgIpo3Q zEgQXa0+3$NaPZ-D{@p}T=7LR*yG};cyWI*S^s<8;MFw*XMN}G(=;x@@k~gD#PH<6A zoqbCA%YIk?DWxg#^0<B9?+S-kHP4R+*|R<O{Yt>>(UA)eQR}1w>zrRW3EN3fPKewy zBmR4;3*2MQ&r$2x<~JGyQ1!ZGaFy{ka={3>b<eA=dEaOdL{676E5E0{3{4PcM(&^5 zv*;1#D+po}7*iYMCK<WcAD1&@8_+qppDx>8dk?vmR@uyHAa91Y5_H8rgsQS;vs+I? zu5L#)GMupU86?Z<YHimA^Ims8C^^Z|i)8ghbKQIY`Ip}3Xg;q=-Ki0nEWZ3qdvEv) zG4?rjIEGQ!LXIX)g5&O2SzQC}L6Tha;1&4Wk>IB~zloZEWepDA$JhXlY(-5F4t|Nx zbbrsRvmgat1#``>pM`RzpC@?<;kG{fJ=X(J_gQXHt_gI#%g}5zU=$nlp&vzze_Nqr zHnJk#{;rj42%C8P4cvhjJYBV^SG~_L`}NXhAeybU0}=$%k2^w4+|_;4M__DEKnw~q z-ztF@mI8&i(pU9T4WJTAG;DZphlwH9><fLa5NO!QAg+NbedS>~IQ+Rr1>_M*sfwwR zY)m+2%{DTcxS=&gR1FI!F%`|Ghs9k3{PWQc$3O)}Ck?sk=OO+$QNxYNatnzO)=<PX zjwg4)Z`s}&BUL(cmv2pJ7%vRmgyY$yKcN)|Ua%e0GkR<yY?LE^rlUJ^qq0%rGFFoC z;^=FFnKCTmMc(*x6x8=l*kvNJ|1-u75rIt;aOc-7dFI3RGQ_SLqBHQ2`*oE_Ojm1i z`{Z!ejX_#&ziZcI-Kr*yxVp+$<jMp#lohYqeZEwHFyw32Cn7mO+z(8X<zUX#krxN$ zzXrcNLfk2rc~v8@hV)kN#wGz6RRNcwIH52*M)wY1jwWxgj%W}%?n-xcT}07i&;lA? zkcha7fHGuzgUwfyxW`tLrQC+cL(dkf748LgGPB~eKsfru4oA8aC8!}sO>I9sS<0!| zw1lmvF)(SIgK>=rIIN<h>Bj&<Ucd~Y22dsaBym2w%>UdjH@12=*->Sj1jmNyJ)!zc za08NE$axP>%_N?QfCce*jIi}f(TO-J!yG#dx#It|c%g6fKV<9es16S@AY(}~4vF_c zX4_Jy^HAX>3d{+bEN_{fVaKz;iTiK~bCJ&WB2QgzrJvUDy*IpcP8E<YPs_22(=|lU z&?|RP_@Tq804yhW!fhjw-x?0z#Pg!+QBaFy*X51$BOS1vAxG>Lf=FXNozo-$tV&Lj z*ix_SKi-Y{eFGlGhT)<ii5SfPefw0U?}=|#N)U?(ILRf46C4QUsFYGq3Rz<z0!H~t z06?C_RXUSKS^>at>VVq_>CImS!%o+J%KmfC@qat&A6k5>>CzGBR;F+FgUnY-ixKC( zkCWv?XfhkliW$uMX}~J01hK_Lrda*0Ff=RRZ|}k2m(XN`PR;%h|65e!Ua9`o^-)P* z7U3(ZyQ_vRdI-IrT(e@MFlzvwb&<>zhNb1`$F2h2FCq3&sb2TqULi{To(y|krMK8w z2uO{<zF`kFh~~EY)0{MtTC0eC`p(`Hqu|anpCq(LNkfkgGkK(j8LWH5ExHZ4PSjGP zxsz5jZfOw@c!>rm*?!_u)XVKl9^OY4>AjwY95++HvR>RFEtYO`6(1{JLIuI)3mzeA zqM`q3%ZI>?K}M*R!{q!dAA-Q|G9J2SDQx0L-)`U6t{n!jPAmwM8v2xu<{SeM2nD@i ztA){j3g_5vg^zKqgKCctIzH<R#I9>T3C{Md|J%3nocZ<O@{EMP@HZzN_!?Nf1IGzl z`|ew7*o4CYtr*roNu~pcA}B7Kfp(X`=#aI4cDyC1r9MKMonz@Wl5%_K=ux}I74Pj0 z@b$(UFeb4|gwov{8;?kGp>4h>&kVYi!o=Yq=GbW3Qidd#{iMNd@s|O*TTfp9Ytob( z<nJ_pt_^b=6={|bhl<O60`kZifYnPLiSs;s<uBJ=W+NAF5M~L&^9-xd0HTDTBJ@#O zPku<*XHYQ8&mQ>4O4}-&$O7ISUAj?$kYoY~OH~1RJoF)sJ%;#m<;RYGwvQ)4p9}$W zWl;(pT}&2jiHxSKIIq7?j$rl-L3?&g2Sr*BQhh`#+ccg@<%n<$b|fqAx-p7vB*LX9 z0rU=gDX76=SQPky{LFniy<?xxYL_sVQn9o)ly^rfUQ6X%AN{*a21ZyvkaH4rV0K&4 zPm|`@1wWE#+4~VdB~qfj-4EJRFK?z-ij!gYDgh#ygxX>n7;(49upo=g0N^T%E!qp^ z{7X|PPB7$Lq_9&G=_E=7c`h+AA)qQ24=-VUe}bf3a?X92M61hX`>B|eHfz9|$eQW? zVb<GVi?%SC%v_eC8GwG1C3G8Eevjs@lsH>1Q|Wy$KpuXMITIe`0_n?ftT0=DdN??h zw7QZl@6PpWE_>Vat%n;xU_@k+BN&X+juGUnuQJkfN3YTj&{Xk_f70n;%?0Ds!>a@~ zeagKTqlGQ7VCRCWazSQaYGg^LC5N!YTG4T;h`NYn8eY`cSA(8lVp=VJhy8^|wZw=W zO<1*LyogjvwN$o<bWyeRe<CvV)iUiOvc1)^Ln3nH)pBzp@~^AqS40#xs}*)d6n|AK zo{1>Y)hIEGDs$B+3yP{p)Tk(kURJNUtShQ&T%&3&s^(Oq<|(S~U!xu-s&S`ABVH7l zQiIGE)hw#f{7+P?zDBEERJ*rEdq@;DUW1ww)p>nhqq8EayIG^VE2{UaM(<2ipRQJ) zS<Il!;)?)Gbih+$2f8)**06VK7y&aO&t15TwBewiaTP{nW5Y8{0mr))tQ%$(tr>y_ zq*C)@rm_WUi{Uxy>v;75ye5`<3eq<j;MJ>0Sv<lN>a!T&sGzBN%6qZE(1j{f8+31~ zF})>VbY1t<P>YOLS;DJhsm_OD0IQsv7isHqrNkLvk$0WVBtc-?yoAyAN?ws$0a}xS z*HfhmfN;=5!-uKYv%e7-V~pMQO)*%i9+IjB@>da~z7s2j7>QkLWz*!r@UPP7WCDX~ z$B66r_i^GnD8IX(fO4S3D$ux$!TH3$J*fCEwB;F9RSvHi;;7MxmOe#0E~E9}b=v}# z0bF!}dq8A2jT!~5(@i4-!l9OGh1EeqY*Ts|LoVA9L0iL#4rZa=;z$A-z+ngo0cxDm z7=(<4PWs>ZW?W%A8V~`BYEJDh*;MtT(<s4f52D4t0WD)e{t|OxA#)VMSO6aeA@D+D ziFz|7%@#9?DtXQq4MgF9>^OWSZnNBA&CGg2fK+Sbx1Qc_^hDpcU>%S2h7@;$Gy<sq zH&0N+G_Vti9YCMgc+GWmAfa}95ppjY>>IKW$05ZI!g(G8)w&JT_VBU~w~P+$g}?xr zQ?v$!D%WbD(|x{hN1#-%fU4ji`5Z(MqKu>-Q}fzQjpD}iaA-ACeEJZck!Ch!pkDnH zE$xTbcDU|U6e#TiEcM^$5HNlm4K!p*T6}`nocH*uRA;kg2@n8sf^aH{c%9=-VqA8L z<CL~HkY69D(`~I8O?$g6neb~OEYsgnS6qvXR_aDuuA%in8N6d(_Tck+9e8PdlY(fF z#)bQ+8!cYjr0%hUeb#VzY;|SP#-Km1suymrKCGQN+Jz$YyAV+8RKA%JhBUP1o}?h6 zx%?kqamD~Uu%WKBqk(IB9MTex%rF`C)3u~3ego>o1t>)WPuKD8>D%dXEV`}ZT9!aP z>^W82lwcV$rs@KGKfm(>In8(iLCpgVlnfGwnDh#Q0dVvnU~D)E$Z3iX9et*!I(*sB zShKshaX(XpV??jS56n3t2GZBu+s0!?O-85|%@^hZymknuMmJu%8;_g`;(aKVu(e~h z36$z@uv`V!uTizc(7OG=pG()5x9tBdK7T4>gfW#A);9!@s1<p<V&9njCHy2;6OFbq zD-}i%dr~ec&g^YQpRwq!2>O!M1#L=mYXlxyvaVZVc#;XEEc&OX;=L58s@=_ADb1M3 zMs1v-c8G~?W<%3f-G@IQ6H|h~(HL@l!*jFw`7!YRm0^<q6siRNHl@vY=G;j48;y)h z>hoTb9u&w)FzZp^Ci&4BtX3dR8#z0nCXriuVusqa(i)5y;%mG_f1qVMIJ4d~YSeGF z7me(0Ho!`0P=MM6v>)$OcLqo;1&rRA+>*!wexF3A7^i}*ZeGDa)3d33aP&zd<0%Li z8HBMA2r<Y^eZT|i{7>v&$dY=80bnl^Isd|2PO+kK^4lg}t)fADRo=j1qh(xX#ZVyw z8=yPdhU`bT7`Etl@961M9}R7q@T@l;V*be~ph)PLI9f4Vpx6-6DJdB#F2_zV%V8rV ztJ0|L0n-9NIt7r9^ym6yI^-&v9S+o;#D7Y8rLK?mhzIWso{RIBe2*%UL#_YNyYTuP zqFY8b)3Y1X(y7|3KpLa=_|?493q1|R&tm2V`{NyC39WYj<|Dc9%}}-m5BGH?JZh9= z%SGq1i6(Z#zi@#T>-~%;Ep(&5n}BWr1iopX;v<&L3P>S=|9~Qvv>I4hbq+&$jLoGl zkZ-Sm-zBJOdu@-gpp+rB3IMG`UZ+2RC=BDJegMG}^}J2VrK4Z(4ybg3m>?z@`WG$= zQ$xfaUK37*^<DWw3gVX>4UJa1&uoY=oe6k9jv{{*0U72!1DeuFsVUKf9&ZO6t-IPb zn89v*UK|m^boP9!jmM1kMF3OJfFSn`!YP$Q@f@vk=q>g)G(EsU!3Zc-fOb@YZDAXc z`agjt*l&ViyK(eJ4vZ*OgWfy9&a=(W<`_6688w5>zCw+|F@>31wy6{R4`DZ7qZ|9J zJ_opXiO|ZevII4DA`fZrB)Q$Y)1tHfgS!i@#|rOWLbnKZGz8&IR$DE*f=VT*D(h5^ z@)wl27WIC#v<DFNrt1ZlxzTa(Y*Fq)M7V(^=3jqSggIlXEuJ&(LItCY;s|y*28(?g zE*iNJ&={b0Otn_1ohqaHvQfAHz&a?@%Mg8{5|gH-YAs2bcOvpJv#h}(Eq`RI>-qzO zQE@Sq-uUimz18n}qoMXifrcTF=a%Qx82@nHT37<MQGF3FtwfDnUpSppL=|tVhK$(X zQfw;uaU1&}L!A)PhtZkGBjr?iI6E)SYC*XX?P#?1(885Sh@~y9U?y;2=t}-Ej1vPi z%Y)dGHsS_tb+>5qg1VMfP0Ps8uKKM)HW2?YZF;ogZ7Asa8(N=nKXJj)zD;0r=dG6I zkodT-O%hZf+Sf250N~;$-i?Q*m}Ay&di#xHQf+kOXa(Wh(Tr2dt%-W6`HgIJjfuNR zxy?Jf_Q94D*Nu0>`hU2ouA5V-iRxA+iW&0-;Nr$HG20u{nCIT>coEAa%>tmM{lsDK zsO1?N*LT?@67u`bmNw`dy)oE+#HEUz44|2gYQ6{=h+Ef&w!dqZI*d(wM(N$ap^*gY zUFc|DnAM&Lfkb?PT1692fjVSk9k>j;Egt!B?#`t86><PTm8NbFpHBCPcutiD0UDFP z7d~jzfLd+|M%2JDI!pNDya$xB4EIP#Ww2&!pXtSJ^l&19@2|%#DXJerDj$bxpC)Nj zsL_wjTGG)6`|_Div3EkieCOzbKU<hGe2*nwiz3$P0g1y*qHt3sUIh0&pw1xhKUtW^ z8(@LHp(4Hm%=E`Lq={mS*KGKu7x0_7XjUyd`VNFswWTQ;VoQ&NEGCuZ82=zgPE~?% zm&iYuo6ffggIkaOrdX_g)hfVi&pf*Ils@M-oTKk@)Sy(tx5I+phrP0(=b*MHty?uX zrW#6`zb#b~Npnd6c(rEh2IMi>WunX;&5kj%2qC^BkMNn!45yr28JyQ6jR;=UGc1oO zp1-v<2=7RWPrK#}#QNO4<OV!!Yoi|ECwJo<_5@UcV#^zPha&>(RP`Bc>|tHY09s_V z9liRUo2YD+BGdR6uPHF8Vwzc&gnU-CofFmAoZ74(V&ow`&!%)k14QAHY*#LSVG5!Z zbD6YxN4;$G?J_}C8EDkHipKt>rq)K2Q$T~-nEP-vKMt>S?e@S{iu(}T+}Xc)%(l?p zxn+S2NXfL#5`9q@p;d7BGJmXLY`E^ItZspHfLpvTKoGf(M?L@MHXq?sX=E{4t5@*E z=Ek1g6->dmC$mdt?z@R%*y}pS-#$8z24y~Iz|;$#qY(mnn)CP$eO+S=2KISaZmWk; z7R17iXKX<BouMDh;d26>J{Wv-KR{_&5w`BxQ+$|&z}3BMh>Xt^)9ubsKL+X-3^>`8 z_s0LD6=U>%?r9izyz`2EqU~yR!mfl$TqEh4Nsf>~3P-7}=upD>C^+Co^9N-3+W7Fb zNs=fkT9RR;%W0>wH&-u_j#Epu$|~=2=(BQ@tSLS0@7-bGoAnQaG3pO}IRjswS3HV2 zJyT}-zli)U>pAN+Hp;ufQdkz-#w4l5Io|SP;%9C|uwC>aEqR1pHEbeAKxn+@O-hMo zU4*bn5o%H5YU!`jWNm3?FR$o)1LE27mk*Pg&-T-tm=^Z?6J+0+Sw7keok#_L6n|Wl z!>=*jk|>Mf(XY_9-QBrg%d4{c_+DWw9g?>~Ypeh2-+%bx2WDysdy~09ZUkKHu3cBW zAaB%veF^c1pZSsxf=5!%&f0{3*?4~1p;_m>iFzs%ELBA<J2t8MgV~Y5^)Od3Tu#tZ znc!bOo5rfuC`>nWC6t^<;G$5LHabjpmXqulX8Qomp=aA0EJIf+W`s_=&;Q=2^ty5x zTbtkiLP985bvvy*Kde=`JK?q2W@XgOl*w@A%%}1D36^h7s`>LB7N!XUsHP_gTyODh zF&vo@&9N)e4T1{NpdI7*!JiFG4#(w^m5a2g(2BS{@@QpDb?xqWz9~VB6zlQ#%X~iK zdw$Im<MjM8wUv{G3P8WA<$npbfuAdT>rWRPa!2C!EB(((sM$BQ4sJZRZz@*<gzX0S zm$L`MC<3g3;?L^w-A$4_cg~s`TDA>o7tEt%0vn!vOaiAbCFHq&sV+Wk+3w`;Ir-x9 zeW2~vQ(E56W<D9p&xVSKfxHI(xL+=Q4t?LGxoi2~;lEg)t$&gl)O&MI>C!7r>Pi!g zg{ntCYG?b~D(K4wf+&&qtNd~n4w)#;dgY|-|FUNt**?U5dPs$b#hujfMxUmYtmhGz zjjN)f@0a=~3tCB4maI(eS4y3rrkqS0PTK|U<{8`(xGRu#>qauE;8jJ2%b))Nkw9+0 zryoA0i<DETyB;T>eS*p7ot~!-4$eJ4C5DQ6EC%ZzehveNiE`+XyUU-xLz9>`#sSAF zTN5%T0AkiCXB;?H>+)T2{s|O7sD0iuwS4B0C!aNDNr+O9lAIEiHS+n!M+$BI4%h&G zPTN#Cku2>GSl+1}mO1bV2WrM$2Z~t=59@`-gqTf;9GiQGOFd%4Wv7%N4gc~HLl;r* zs-Aw>DLWi<`gt+!VfzWvor-!g2%(SS%8L7aK=~(}y^|NsEU3SMr(l1^S(u@S-ob~8 z{orMezI?<i5pfMFs4%L!FeF~`s0I`ALXWG!V<Vt3OL$nv5yRD`f-M?MJ%TbG{g{Is z9$}D8!Vv&Gpu!xpiC>LMa+BNngB$P&2R8nojNIkJdoKh@1;2xhIbg#*BKb!ld>DX- zFz+7%AqY3{6O{V=gB{7p9X@K~I-3AV8}4{c`G&I|tQf8x$zaBmB9_F+WW_3JS%ZA! z(U5oXFCU}(hv|^QE07EaRBLcwxvcUIJj`NH{J0T=CS#d}{o@#KYyXR1AcjTh5rt0? z;o4Dbaw7x1O^KaRkIvLM6pf7NAG50mH~R4oZpa85FiT@7J7O7b;A0YnAV;PQ<UQnt z5+~tGL_6Hkn<xq;NdKtBKFU$dQoS%-rC<l2C`U|f_@floFp}0_DVcPksZ90gMjWX} zB8|c08}-QINEo7-|NR3Wp!0`3+!KgJydz-nTTMOk5si>}%RlW2z#2YbJdqgCa6<9X zru>1jY^tU}-&y4yb_FwkY=azZXvW!Ixlo?PX%aI!n;yZWQFCOfNl)qrNR3!Nd^k}X zP$XCKh9e|rjzcb7{Kqn;F^-mEQ=<l*3ElqD1Zrri99ZOtRsa0KgrQnxfUKF&H-btG zkz}qOosh$zCJ4%*Y|0*_*aLrP)6@XGD*(@+!d^y(QeWjmGeTWvN75G-Du~ELJ(Y}2 z9`YT0AOaTKz!^ToaT7%-;vY5qj#lj2kz01fd-y2F`CgdUgxcdu(^v;Qv{9g-IIADe z!ADE&aZ<IKi-9^aML(1!z|nSOI?qZ(Fc*?o%D^Kz)JUK?A|fGp{^MWs>ETDZk~vVx zp(^x1ByIeZ52b4Aw`){S=Ek8^b1aNNyvpr(N^`N0XwIsG(rzp#L=O?+;S*lLmsVv9 zR|?_-Kh0o6Ikus+a=@$^bJ&JqGn&}JJ}DpOFiZMEng5l37{?vp2<&7xTUc#42Ra2g z33|Uo7b*tB9GOLIP`D9*@kJ{kVN7qO{1MMVI3>5#Yol7cskwZi(;o9tkR0IgNZ_`R zJK%7WSXV=ZWBdbye7P`3sKFPqtXRDOB9Ej#_Yr=1qaJOL4uBy1VddrZAHHD2&|dN` zf4oD8(C{RV7y1&5!fa^GO~@Uvv8$>5j!W=(2PoR{l1mDug;z2KvcxeVuuW}GH?izV zJ2jLkT4Ne)t(ufs8?|~YEpo)LM>*`-CvrGt4MT-=pg|(0Pg(UHkBpPir1Xz*jAIX| z$lsG!GpBj9GXUc#A(-}@5Ju|<bFucwAP%9PxBqfPOzx3GCu005M9U>+_{h{BCQ;b$ zRBaou5X6&Ym5)fn@-wrc&_5=G7%*Xj4cI_6&6ab>KWV}msyq^8S<Db{F=-leBMz8J zYmac`0~Gtvj+sFMzHm)L9p-RH3u7{D@V1c}N$9lZz-tq4;G<xHljJ1T%T%Re^|uFs z93}kd4R}MwD0Rd`;P^S(K#U68`nu2{01@LPd!&K^2(p4&6lK}s)sx&P#~*qj4s#rG z=QmM?9sCL<|3W-@mU&25#GxQxP>5Op-o_*%G3Tk>C`h@<#zdgFT9J6D9iUkBOX!le z<<!F+Ld!GJe^gj@hvOYOFQ~x73Xd_t2mc=PajIqlL5aXcq+^zGF%!U{mkCOUCZNKD zJ;1^DA3Ilxl=%37z+B=%48k8!^)X1MvQ(jrhY91bJKTRlbDM0V7k9YjdO336**$6F zY8(eQpfN<PpQsSFHdiM7p$&7eFCW3ouw<gt^@wcnGHWj1KZx{1+cW1Th2=&#;LK{! zd#gQmGFXeeCF`&>VI1MeueY}OKyXwA`{3Oz6ZYd<w9ADdlMcWhC`8uF+XjT>83bFf zEt2sVZsj0hs@((!U#4#)5<`_H0TUwXAtY-X>|qXI;YoZ&=1Qh3wrm>;!4tMjc|rmc z5MkGLhU&OsA55V*CL%I6W0uJ6iT|Wz`A&t40$?3VAs<@G1X03D;4Dp8Fue{bEfPpG zMxwTw0Pz%L+7!Z1{-HcP4`!yyJ=Vg!fP)|S0dkazZn`AWPQo=NukxZM)&l0`gyKf( zhdexR06ijh!r=~jVONTcBaUPe6k*w-Mz(B*6BMH5>X6mAVG_QLW(uUvu!S8`f~Vx- zAbKMoG@;#EibJNxCRz$w+Ci0kV*Uu@GmhjMN+AG13*8VcEBwJ6+~$we$|kJB9^j)M z+JaiV<#CP>5<HKlrb=^^Y8*y!H9qDan4lUmhsd1DV+6z%^(8=<;O&9}oStk`$Pj%# zV~b$n5AcB;Qlf%3VpZ6{9RJkt!)(SAG_fNp2peQ%9%8}{X+^WFL>#gN6AwZHon?GX z;Z}SD+t$xZUa1~_$@lOBy~Hset|1wq$HSzoKpp~e3Pw|AruqPZ^1MMFut=<ILKOpn z^1Lx5(q+@|fKJX!>ww}bq(iB4ktnL6G)AI4<n1UhMq`}f7<UmK%mE*6CwDrmd+Z@G z@WB@#D!y`1jY^0U#xUGy2p{I47o<%w-VsF(A`r7-9TPDdgMtvP1Rj1V6Tz`sx*}7m z=pP8BGn5E2QeqrLWFHJCC}$2l{(%aD>>bm^Jr-e6lp>Nq;$09=EbC$LW=y!$;$BK3 zGzRAr@L&x6Pa!%|LjOEsF!XY}xT6}z$|RX%mS!g(F2j4=j2j98CoxL;Oho||kSP3t zRiGihAksiGr6==D0)xXc<V+cYAv#biG8p0|Dr+6gCIT%|LmtN8uti&n#hesMDB{8$ z{Gr}bf*%o$AtWdt@bZr4Yqe_e7Dw?N-(~yqL?q3xZQ5Wg5K?+1P!!$64+g;$h2k)5 zF&qSE>&%2d#z7dVBmlhQT|l#^DnnE90SlTTCCtJhI^!KI&=a(y*g&cEaPu<iYO}2D zAFyHh7^tAwz!&cAoWc<vGUAxvp*I8(GH}8kn#A8GB0Z_2E3QN#YDhbVhbS;K04xi) zj%yR^4k0^1RR3gbs^&oo!NIpe5gwqBIj!O+76u&5At1>?KZW8#&XP`u5h(0|bKc2_ z24hIKlXaTFMw7)bCB&g(uNl6hvDj;(ngOD2<olQ}G`hkjvJ74n^EEGXtkle@mZK1o zZE<MkQMf@I+94RAsw<>qGSYD!6(r9vjaE)#OWh$D+MzdKt)@<*A6km{Fd|9<Gn?SV z#oB-xWU>6paBiaTA103<pejkMFgd0o9OmI-iic{ZgvkQ3QFuo(=D{Dx%VYX)phD$P z6CxZ^^(V#w5&)s{K&U1WEwAWP5g-%wI^s(4Va$q+2>*1Wgf%2?q|X`!Qi9d?@`}|` zA_u2~PyceKQ)z`EaDqvk<lkTdG`I*J;H-tt?ln`ydIA6xykS7NwI{~L6w1LJwud}r z%kSJH38(?9hB0ICz#qUNJbue2$SxliVG#OZMybamQ0O1_fD%M4?9$UFCXE_`uwBHJ zBZx~VUUlpKiB&<b05hxuBhy=`t{mpTK=IQeIix!IbBmy%4+NnOYGDZbl~<dAIOM_( zGQ&cFgAgTj8rl`$(zQ3-!5TK9AHt!A7SB`|D1}I28r%U)G&UrNMJ0qL!~9F&7~)d| z10EVxB-HJlGG-5?0zH2$DL{1>-XU-B&Bw}tIce%Po$Fx}WIR>tKL~ax{$V&T1ZM+m zz5i?ihk9YY*05K1QV|N_NjPI>OhiYKkuNmE0Ry1)TFLfkt~A_mVkNVaN~X2k;m!Kg zrBq`gbfkS+svb**5Dmf<vY|mG5kikI8J2;qM)bo5<_Iazbhc9-{2^o<t2hl-?%V^Q zsPff*0tf>K6*&$(0$@Bw?I}ls(=LQHf($7)%jHriZ3Ql3xGfyi@F}V8A8JV)`sZ?y zF>y~8GGGA_>cM8r^husFF1Fzx=3oy;A|-CeeV+C|yvH4wvQOn_CMF^uV52ueOK(M^ z5zEmzCnFMt_LGV)y%^$MTw@P9K|CASFMY);+@lGk0UpHGBd+#S)?mky(|h8xPyha5 zU8I3ru#{_2h9N|xJW@mPSh#TfK`gtnHZbTEz_xB#Od(Q(7^Kg7(~B}QMMkz^dnGes zW{GgwSG`OmF}Ng>G)s(dbsNwy!>UY)GK^QAaz<Rpdf~xl($IoU#dL3K8o&Xx+z~bX z*Gm3yTGqH)p+@c4XIp$DT_?gF2<%oKG+rNVZL5JQ$bv7-Y(O)I;e;U{_!Z)=HZ3Y9 zZxFa(13<jqW1h&OKtQR2%mS(khHF;%Blc;2Is*O1syKz1V1=rLmV<z`=tQ&-*-&C; zD5SoQ*jKCTC?W<Qz9BWPri4QeJo3R4W~7Gb^ABED34QFh>|p+c*jB%!LI0<TrOZb) zs-$U~rW|}iK_)gse1aXM!}qp%U+Tjfj$=IfIK9w98mK_-9CajObS}T4EOgN?+`?_( zhPp1&Jpcg`4sM<!<3bYlGnh9h>Oo)Dpw+m_r}{@xB!WqOEOcNwe1C|&R4G?liC068 zF8~Wa-k}}(tK^OrbZ&(l?7$be0w1=4md~bA{=gI7WGLwO8(gthPemL6xDxn*9`AP~ zwsdUTC$(4^_(lp#_Ti*r7c%_eC2FT>Qe&s%$1*6Dw<dT~e_}xEVbYFa4J?FEgwZVI zfgdQwDeyUMs}B$2;~<4tB*G&f#sh%T+9MdXphwFq39lhq1cdOJN&np?_Pou<>@bGt z)1r_#-#8d>S;Y?602=O7lipD)?x@?wLjj?o+dlRqxM3Sg+EEAtO8x*CT1m+w%pR_W zeF7jHXihblr|a;+_s;oCfVN!s!5pPGGTgx)_^rZxGqK1vay}t=hk_sI;U8w<thzx@ zgfS~LLqA5X#D1cUz5(zuM{#?1KJZ~Kze%%&B83uGAj26b+UBgr<GTh>vhabgS9*F7 zV?MWGMF6*b$H;8(0SgQP77U>f#Gze`m*v=tbr8W5`np4lqJvpW8E(ZRg@W{EWJF4a zAt1-HSg(S$DYU}JN|GTPiq<z;n652|=-^=;;W((lVjZSor2hm?6z_rx$RU5kn}7@i z3Pp$*>fvCrFL|R%J~Z58R#dsFVLn8wyA#62=JFJ8+&1RVKMbe-fP#&x`>alFm3{oF zUy{8zn3aAauflj4-7I|lqoJn!56VGG3PBNahg*U|m5iA~IpuwkZA3`eK*XW+62idc zLe6Og4D(@JwnOUVRKaX}Xm=_OtL3JWp~5x<9+>AH=Fvf&I&B_h)#fs8hQd$&2^I1I zckeU+qL4fGqn%ZB)HJeGKW)(iCLsXFV<1!^zF|~7LU@BBPU_)QC%ITZ3|EDS8P;|r z`m8}$gdQR@RUT!_xIqwl0UI*Ky^;<|gra4zfl$8YNdK16QT8O#{Nd+9s?{GgK^dZS zgr*-DYshzzhPudk@WDYvYoLK+IhZ9MmO&v50yL~VI|{-bUW>J7+lL~;tN#HKM$BR^ zrjT1aQUj8!fl`9PVhwO{)ORuN^h9IywZ!rpyb$<b92Jxd=M!nemxUVP72;x~TaB(m zfatR)&!#3vk5#atp!3TtG6fdwAbe8k=@9U*Bnedl;C4u&lahoDz9B$0kZP!1!G~h9 zODJcaJT$(Dc)EsKg#u{`M>gT?C6c}c3roXTLP2-VnF)|1>Y)^3Ti{$gs{Vl<qTTkG zrD_1fZK4ng_l$1xK@#%vAfXj$_yZosDe;nHr~eO)KG2UUzed)-hIOP$m#d~z?>AM( z1fV>pYWyBim$km6;Z1Oacy^6K%E<w{heCJ<Qu2i-A23J5xb#j>vVLTC<kK(wwuV?o zTHC3Zl>v(WJ|wIh8?Yf)^lC~?rI+5J6tV#lm0nA^2OolAAM(LY7hi3p<~Z<4+C-yE zu$Uc8AxK`|u9CzXgOnP`;Zp$pCr&~sn1Zci6wuioZ#lhL_`@C`0sib>@`vI^Mx8NS zNLca#ai&Y60&R4}S5ExlsskXa@%k76!k<5U_~8A6^~c;cc>V%7d<fBDzI^Zg&4KmL zTtk5l1x^&Wtr;6`?+n)C_U{kIasoL<jQ@x)0LGUNF$MVd?&iOj*w|oW7{DdXhXTLt zoMcX1!-z|VI(<5{UOjEv{v~SXP8&CS|KP!c3ihErd*;mX%eOAszi{T@jSUMoEJ2R{ z*s0|=&RkrmUi<ZP_%#4GhyVWWJ&btoSbFpFeOgn`+dRO5pN<_nj~}%r|G@F1_x2%U z$7}w1lNZynJ<9XyQCkDfT)A>yL&NoI?jNx=;rz`;OwZw(PXXr9^ZGjg9#jGJhV|-j zY`vY}0)Ue@&vxSN+~XoI_s$%wIsdi^BsjF}Kb$FHi4#ZAYi)b+-))<OX<Nzn@9_PZ z^iMf@K{pgU+&~jRGfe@O(<G79Q~w!6OU(g|b6|Oe-cH?Z7{FKrl@q`|rnuuyQe2hA zAw*^I^G{m;Xd_jJ+NDU-W%hWbO#stO^G}I1M#K#_C04S}KjN6P+K);?WaE4e(L>Ka zr{H0ZWHa&wk38P|vxg-9%#&S`UX6ywC;u3C<x}%`gHIFDj3bqea1kUGIR8+x$2;CQ z300ay?Np6C8~(FdK7#VO<c9JQc$h#a1pr_<<G_PrL^h5EPd>e{5uiBbgyvyP@6>Zg zFF(1p+CRRqfloLcG8zDS58<<mU;*S5D?T8VGe=N?rJ0(aPsQ|=u!%afVgN2`<5!|h z!sCu90gwY9rpGdw<XC0pl>ZDn0YsRhKVvzX&oBEFWbC!uX@}W7|1d#~Km72MuBG;9 z$>kzvf_5XSVE)qtI1SZPZ*=yo2{1MP#Mv)gp^ftoDr@8uPQedV`qEp$<<mp}!F4xI z0D(Y4Sd!`{wkWKKVIvM3&GbX5g*Em&(5h?UgXCqnX>`yZ0W6eqGk-v1-arKfhA1Za zRfZuxIkDkO0QEqX&vu0n6%n{ghE~>e)2vgDtN##WF<4`*N0mQUxf3K;Wpg){UqQOl zP9iT>Wtfs>m6K1m1sQxYjoOv<Zxhw5H+5q8cInSIVa^BUIEKTMoY_f2`A;Wue0iMK z1qN1U0BaCq4{e@1h5vCIsA%{kKZy=9$VR`K9Qacy-+nq}FKzP=)RoDau|3V^GoCnX z<&5c9lpjQ1fB4Mi&pY`<q6kUw$f|OJ0eo}Qtf`TM&m@I74Ps~pA(YRfhox5ag0)j- zPCn)Q14=t=<<8-H+`wqfG+J%Ny7xU~FafB9I|SoCCGl+^pa?)XvM0a|`NJ!j0Y|{h z5u?N)Y!Hiphj9qx6@F|9UJFayUdTa?e;k7frkMu><I)6$O^tSO*^(SOu^=$fC^>t8 zgg@kgzX)axcPZNoH-PbnQvuH@e(A?Qu<-|Gh{J8!>eu{KA`Vo|1s)+uVoCBLGi2%I z9oPuKPZIbo=KqN$B2_Cy7`@{VZjeKW55bK%{;`W>w4-)%gHbjrkq@oF<1ax>R8>mB z4sl$oFZ}?KL*DZ?Iy!|R|2UXE1`&wP)Wea8k&0IWMvl%csxiv($2ck%7tGCK4dggY zBp(6}j!{E?-9e)QB^5C|oM};#d<k??7LJne5?0xZ-ajx=2=H7lHL8I}e-JSV>tQc2 z;pm+&EHoE?Y=aywD@j=hq^-8d<PW9uoFZXylZw%BNrk-D{{AtIO`HTG?L3VBwBe3@ zl%gF$%Ev!iV#{8p$SeBeMmZ2^jv%c^pxc=sL*#MEOoC%J0gTIf?7^{WNClt*Y0SvR zVW*0Q<^MB;T0=Gd_0NC~Wq!<njT3`HqlGSMGIb=3NF@o-^;B~`=Fk;KghG>#7{n8W z_{LY3IFz|m1QDLlk3lr#l7C2J4$V-cMDpQ}Cvrn2(ff!>x3?3Q2&AXJn1emUmC~0e zWFudF$w=lX$v(Ox8P_mJj$V12n7Jb#reH^aKv>W2XzL#$;zvF5^1|*&g(@*&hh2kG z$#pVxW)K0BKP(6i#^hx?QZa|*!a)yy+|DS07({1K2^SQC!yaouMLxoW7=$fi50N<z zjUak3ZwM|)Ap=Ksz7<$?&1ZrEa0e-Bv7T~dQ9kt4nn18Ihi(K#T#|)}u9oTvc}yxk zsQ+?iIgp7Hqfuslp0L9|zOkA`g{mTj01!9&;ZO;=>JPx^2toK0fbwn#3-7RM1POvR zZPcx}LBiVBgx3#l^o<>z%^5F`MG%67EC9bq=me{~p=NO-9N8!ZKM0t&$sQ(h@JIqU zPQy%xC8<v42m~eIK@Pxfi4YQ<jm5^I+JCh6OvzI*z90bze|Y0#cqNQv%0dtBEuwoJ z+E6}7IGG;5?{=XA$u@w11xz5K5Y2c;f0w(&2RB3{+)#>)z_P_{^x_XrB^!MTVxItT z0z5_wO+^q=o~97UQ4aZuh93MCbChZ!x!RRVx+3MF*v3GG@B}#~EWq_lWNPb}hW|MB z>d%{|NTzyWAWo{bp0;i}fE)e?Rz=Mn5+&k*BJK`98uJO-Vy8O<u@j!gVU(2C<Iy@M zMgTZ@n0bK%A3K&uN>S~Q4KCsxvp&p3<{=M%P=g8okOyk=L5{{OVi1urwx;(Y2VBV% zr!A>ZISOG2Som`iSdd0nvbr9Tp2w$T1~yo{x{Yo4gdwsDt3P^@@3YDjJ!GViQsC_n z^uVKxY@o@!Z<Sv~7&Ri;*oGP3VKksZB`39*?4|kYS8WJn-0JG|FN`Pfe+tn;!QIdv z`$3gfZ)Z*TXhSEe?d|QX$4)ek%(1~_k7^`APsUEnMFT(#&gf(>>%k5<nEwEdcT5J^ z5D|6&diW1=G-O@@U_v;+k(q`zg=8&17C__k4@E?i9A1_QBJ?wmv@*pX6OmqfJ*9D{ zeB_A$$9SkSPDY;;ZQ!En2{h_4@``d1iQl3LddB>-#y`a3?0jGH6gjG7>;pt)=Z-i? zk__asC3%V6&{*Cxj(3=%9pNc*Tm}PAYy9KAA(pvQlE;{Tw1F7o029UzGZs6c0uQDP zr)8&orZ6G3PxqP!^1+^+=Tt@>Pk#s4fxG<lIA==^30aKlQJw0z{vo<)gFk}vdjT#= zssHfAAIQ-ghZwaGiogjz{5wQ~uy+#WAV*v3l}+0)4|CuP0udT>@&6CKFbDWx9?K*l z_Ca6sFb@9kO%dWBu<#8N*j&2P3xbgo?*S1FCwZkOES=XKpZ5>U017WM7%*dkMs!H) zU{_n=f+yn_X~Pbs5Dr?wWX^(M+F%aTpbq&^B1d9-aWOx{Km}lxE9;V5??Mf|7bcPO zbm7o!Z-W_{!5QNKC5bjk9^@LF;TgcS7X(66rgdiIPz}g3HKi98RJTZh5g-3H2iV{Z z0`VO}<8E>?MBh>l{^1Fm<c2g+5#oan-;fW>1QIC$AYXQXKJ^dKzy{kOFck<GH-QNG zkyJhv5_f<N^X3)U;7Ef=6W3D<g@6sXaxElxUnrpo>u^BobN?(dRZ#iRVQiBl3zc_? z0uR^FgX$tvD6tR803PXggb*Q96JZdWVGi$*a@_%KP?&trCJ&B5TVOH~h%ph1BMBZ9 zCCAnhFM&AV_YZhL2|Px1Ks6bG5CD)C0Ip*lKQa#ZKn29`Z71`03FkEbAU@jkPap9P z+<*{X<~)ff6x!4bcQ6mCxQmYGH2I(iir^0@5pO|Z6cNcD8nPbQgb&PM2W^HA8>uU1 z^ast5isD5SP0<u6(GUTNM5n?X_oyy!Q5E$AS3)#5?{F1Vu^!A-JFJF`Cj%Yf;0~a$ zCwlQl#~2Z1F-4RR2+>0$2m@s<<U!tG52}N6MHY>Fp#Lu)R8O;ECwo8%KeSmJ(nFW^ z5d45yNx2<u5``ERK^_4ObD#}5!IW9_ZwU!pegQ#Tl#u$NigBTTX(y3J;ZOpBLWhPb zFR_R!;Y^nJ5aY2H?Q}K2HYvA)4~2jU_9hoG(Gd7>2QU>uQV}G3)DHDvjJ1;+JMs_w z@E)W%P!Pc^?=u+f5Dd&<Bvqr7pA$b1)CBejhfZN_nIi}AU?opzbJa#uh%pxUQYQ7_ zm4iqQ<cM|J1(#sa7*5#_!?rylLkRU?gd7qw!#57D(n~uNJzE6~^Pmy$@lB0m5AB5y z5aN^iI6(sWb|sO0e9?Y?Fnj#wQ{*6t`Vj!lGXHnHa}m+AM60nX`QVO2F<<V*T>roc zitrGq1s0z<2fZMZKO!Adp)AR8X`d%aIpQMj@OgZwB-zuNsp+9yp&|Kj4W$qOJXm|X zc`>h*5B1m;GIE`_cQ3|94Agd<2y;WsCMby^9VxUK`{IScgF=Kt1<?1TKw4Suf-Le! zex^q|O4y;tvVQvr3wB@+MPnlfSXPq)Xo`q&gQlM;21jhr4Q7^23gHvrFi0V08$C07 zd7~{dVF#DB8h(-~WwjFwaa5cz2^O~$7Q+$d;4*M3T<`#b|IjUoxSuD(4dx&sqcRTS zpr%EnB;tT8L)c6Iunfr%NX&AhyE!J4@&5^U0G*;`f}sIz_J9g)U>fqUHzlPoDAbk( zp`ZZ+B@gx#Q5p@LAsMi#J821zepn9PpqnokR1z~F)VdvuQi$WT5Dryk{ncnV;ge0H zpehke4u}}=AQCJyZ|R8%lK^pv<qsl34wMI(YjkGm5di#EQ*u_Bo|kr$U=Q377!8>} zJ0T?Ia1{d8NB&ShVB}f#xg?+G4?r0JRb#B`vR9_C4~j%`I4UE<nX4`2q9??pCbdar zkyT1q58SgMQjrgsH7^!38~Ko|EyS!e!F3K%5iMIszr`W*Lk$6-Fi;{%kB1TjXe6*w zALKw(dtx+z=8S>>3m~}{b74ko@c#{pv`o&l4RfFjo@tC|dIt>H5c45D67h$U$`sAe z9NfTNP}G6l5g6nlA;I|+00j~6&<?9N7`jPEK>`ms_<6YzZybfUI-$21R1ft-e(?rX zi7Sp8QegJbKm-J`DY+idmJhp^d>uh`w5TE8P!Bsc4im8+Nw*e1N)wRl5O#t|=arAs zH5B|{6j+%V9~&0=$Pe!jFo?P(VrhM1XH(BwphBc^6+u)4noW=k67{g5|Cnhq)evjO z4WEc`f~hN9L|+68c-uf<F_yg$F^36RaqhznU)v0y(!4ii56yrDlu8$?A`ajak{bD? zlJ^IkXJG0=u$sUlRAHb3bpLuNu?xWvNHiFS1-1#(&=6bEFFDI}2zwKi77hfvn3-D^ zT4E3I;z6*LB1W-eW#L)5RGxxm4|Q@Ud(b#d#(ZlM08}6h0U{u52^X3bL;rv|-#`Tl zgCtxEk60;5P2)`5z*M(_k`Pf2^{}nw;Jr&k5aZ!ARXQx&n-9S7kzV$i0ib~S_Hfn( zaf-kRPU8<C=n$UJJ)>emLm>{>PzbdkKQQwU>7!@ZN`5xXA#+m-`;ZmfkX4d2H_@^W z`|}s(W5*70gW3QObfriH3tSTH9rBSQ3{+hAbI4$dD%CiAOzeAjycb5nqiR}B^_Ykp zQYZd^NkV2Z&_-;>0RLnD=gCkp8XXZGzLspP`#Em`M4f;K#;bk>JFi$kfu*;t|0y4D zL8<sKrjseLa4|u&!e%8g8|OnF-5NYfwGEBd4;U8_=tNT`8xe&t7?d(A?}f`xVL~u^ z&Uy6~`Opra04-HBe(6f7msSsbB^biPT^y1;G2$FCv8gvvff-A;fuUi2+YbDY6q7Q~ zm^?MGn@KJUI2$rQkdR5?VGiLykHi2*K?@?fQ5v7p%tK^s5~E2mR(4D)2`u~)x&_X* zQ=i-eY>-@r@)17}gAmUH6xOvxJ+Za_#9e!X4^Wecp~B8*bv^D!XVaX3bC3_#?2xyD z4X}U+5=em>;r~JIhZACP8Bb9?NIWY7a>##ku^oLa)ub%>3ycXCBBszIDcUexN>DEn z0CquOejGtwu|HFj4SJD9I7%Q=0WmIiCS^$@)3F)RGeMwC46z&+A_RrzphI7XA`v4s z)q&Fd9IF8!UHRZ^8uHTIVX*8JGZeU??_q%J)YEn_!$1);1W`>;b0fhzK?0gY-_akF zAdyAmOQ@nhz0(XDL52Y^G-cFI6;YwV6q)8FARJ-`VG9@(Xr2SLOgCt$eubLIv(6lH zgW|wIMChIk-5loN7nR*W8G$4;9T%Y@H@7kk%fJob0IHX)B%v}L_V9F>g_^^S!bwO4 z<X8{$(*MH@z1>S`4#UX=H_^$6@)G%gC!NuSVq${ku+ro=ZIL0@St2Oa0CixZ-il!| zUm}Scrczr}4g-m&vQiclqqHU%faGuy@8*wC(-46B5^m-xE;CjdVIMBTsBwV}q4`g) zauFcX79ZX#BMC<I9T6nD50$VMw0o+vhfk%D4YTL5(<Qk}2N9<EPQ9c^bYnM}`?&G; z3{yH8vunyk%R=QaoUz(U#;dzvvAKf6K|kbe4Y^5nLPB!4A=weD{vciW;0KW4I?E~A z{t!9=00|*8=MW|;+n@-TAc47}yMGt0N^3MiB@W1B4}ob<|5P3p(F=&Th|!C#lPeJL z(f?lmFpozQ<R<x<Y%7iq0U-|Y9|3T1qYV{*&<pPnGSMUH?i3DBKCMi?7m3^t?+p$? z;!q<E;^iF_*N_bR^DV7<EaCJJdqn13{c8Up2au3_;w>XdR*s)g4)<^m5u>Y;!OsUH z5A`slEkwn|F%NuB4YwNCOTq-UjOffsJGv#jTzxX3;!NV;rm1dSAb}4tPC0AqwVr?o zOw1htIMf`<5dOHKL4l$6=?~R33I2)EzjZZ5lc`FaaGyCqFX&9rr3@JBwOH^YiC3dl z<5&o^6py}&vnM2V6OiJ7RcdZ@DP<0^K_nMUk-Y9?nKlvlASCd#4h8-`iMP3T$p1LT z0lFOWY&InB>dx*hl#MZ&l_M(|LVs1?{u++sE^?>z5E1qe;SKjdJ8MrPDfHkI_V%*~ zRpX=(XO;Is85Ag?fNKGY_R(lsm&6v8QYfKzM)J(3$h@@vcjS-{;sYLGZ~3^=kYT?K z+~6`p&P<<@7>}oBf8Z)x4iyFE4wZlvW#&%;H4*vn>HiQ6`;bu1yXAjZX73DB@nhro z7;hkG56Q3&YmB2E<r-8VTA`(qsQ->O)Cut5^^mY^WuGEoVkf(Y57{xkQV!X(wX5KW z`T#==hk|s~vG#4hyO*feDRM{RLlGxG>zSf}eV=g)r?uPQ_rIU|8Uhgb@c+U4*Ne@+ zZSdaZ^HgZtJ9q*EOr%)x-#>!Q=6DkaF95fHg(l&9C$S<$fBr6}+!kO`p#b6jK?~3< z06u>wb?!X*F94g0;CK!tIx%H{eDwmXOZJajJ)cFTP91tNU%rylrq$zS?_bJ`RC%UM zDRY{&dhX1b6Wg}vRea+31=wfGXFs=j^#)k!PaZ#NOvZuZH#fl1y%aCbn-_rC8h-cg z{bNGyALFozD}KXA1=YWCeRW>sH_zUpLHxYU`-)ie#3t0_-J_V#XwKI<!;Qn&Iycda z0=ea5<IAV(p#uHE!}f<6H+cS(GiQTsTS}98P4=3DP~pE?f4IGqj{k3T)Oz*&y(4$0 zSHg+gs*jtBo#a1Qa{_$Z*6Yqch_Xv;4s7c2Xd?Z7t0*6G{sCp5s1$tdDy8;GCLD9f z(l9q}+<7OFc0RIALb0x*NSgpa36Vq=5A*9ENCxSLFvCbJ3>?b9kqn;7E^ACenb!C$ zv<Qi6q8xa<+Ay&j189Pn*-)CO$luJ_<CFl%QLn|55c`K2JFsCZv$1Z%=^bwV@B|}& zu38S8JFEkX$`bSOh`W3eLK6{Ku(1y~pWfN#j%FV6hZ}L&Xofxkc@n6k0RF(|8^sRG z%{Df+ai>LilC;Mhab`*;M04!Hi%Y8Pv1cM~w5bO~cenwmpZ`uLs&y(=JME_*ZHBAs zK%Z1awIWqjT`Rqb@Ucdde^8`zSgC}~k{odSdD5SG*6Q?D%~WN~9B`P>@g8E@cqahH zr0v!osEDEBpKx;BwxYEPa}peQ(%bexZr%Fvq*ZZa(VkE6I1t*C-kE0-L;w`493%zB zgp+b|O6i-B6u~GrfjrU(8|XY@gB)&<a}+0dwt+<ulK4{Q4{Yd@s?$f!@x+dQD4jBZ zb6*o@n>l<r>_9tMbaonMQOp-%v9xh@*?M~2ci*-;MRvGSvU$g8GMT36SfwoT+AV1d zi*5~K_>m`{RRic(GsfNlrwwAD3S<y}WNKT%a{i&FiT`}Sk(b!EF&>1FddAUr-rT~j z(I`|G+2bE?#<uli$OBM!C*=;Er#kX3&e-ACI!5!4T1a}Q88*JL^WdF|wMU`;?od6= zHL2qEA8Z1ksT@B4)l6WddS-FgR^2gWMa@sOe5bX<c}jT*&6%3<s^JMW8&mpGOB}B@ zXBuo!188UYe87LcDB0`jdzW{;k!P(IRei^tK_-WBa&P`AHaB7AgBtHbQbf$7xwdtx ze|sRrKfnPoswIYgj-i55P_c$!?d>(fVhuQ`P>sfjPeL>s2z9=Jjed!+BAqe^K18xH zdz6D4LGwwY#G)$GZQ~EHcn5iWF$Y-@?qsy<#s423BB(;-&P-BK4n>$@9{0Enc6;H5 zP7WxcT{*2Cpb*DLLbkr5R52Lr_(wlF=8>uCu2YA?#~3#T#*>^;CcoGRKCCxII8H=b z^k5AhK5-d-Nb7B{`O9O1L=1nBLysEVi>mnX4S)F29P^;Zt)xYc27zM@)KJ{@a<ev6 z1b`m@xZr*UsTq3ArETFb&9L^>w}$*f9LP~20#ou7MHB)+ohk=5fMPt&<PdcL3dtm- z=Rc`vD`o!JVGp-ah+2@YD7V558>HcrKcGuydJ$I2qGB760YyRrkx4SF@eg-MPbGP* zh-?0_k6_><UQ$fsDd}lIbATiprKm?ZaQ_m334$?=>_~<=!okj+bjn-(i%nE&xvqL( ztTOp%0xJW_$k)uHe{!HiKja|~5q{KfNqC3+WM@w`&I2$3u*^iZNg~F;h8pvb2h%#W zjeq=M64Io|LlM|FSp2~$DJh3H6a^8E;lv-?XvQ5LlCgYr1*1BV)<X2t8}69nI>aN2 zM9!rMPhgBhhYDMKs>q^Jov$5EL+F$)^463Xv>v9&M*8yMlfEFvWQut!*G#dGt#w5u z&*D;MOynYhOeCrv=~`R=L63S+V-4UKhnCz#mfXDcvGW)Q+R8P_QNHz3`CyDc0`m`f z%;PGWO^HVTA%{-*MIQLb$DD4{mj9F-Rw<{j4Ka|(7vCg?LiNBAD)3+qBn5YP#JdVy zfYywhWG1&GI*)SDR2@Bu0}-A;VR;%m71k0Y9Ey@j68XUm+Ir-$Jh_NRU||Q9_~IZq zEze$evd)P#hbCOr%RdxJk$3!~AuZ92LhW%(?s>6{ZAD;3TJ;Z2Sc6yEke9q7cs*5R z@tvlyN33SG$gvrCB5PU8rg+9+oph?Ekk|t_9$1dS{YF~iC<i`Hkq1IZB9Zh6=mzb< z7=;Mtqd2@Gx=ceiY?)?uc-%`(1F!~NJjTBTv=x(YxHqL#P?RjXl|&Au3_BR=j37?V zKm>IMXdE#Bb^u1j%7fCPbpP&Wb0`$+D(4Szba9CZg~wXr%LelVb*c7&b4BLy-%0T0 z9W^erSgIHm0{_No9@&TV#K9I6qvTK>atA29A*(X3>UyL0l(9n9k6`RWhW%=^g1THn zTTP@KdZd-71nQ|y@#7z88w|uyr7DQ|Ee}~B1$*kz<8?7+FyaF8f!4CC(6|d87{j%d z+aj$ZPlO(eZ1qr-`4^!)12;a+i>mS*0CxZl7+A5j6q#rqG<ia(J#2;@y0KM(kb5Yq zV#z-gp$Om2;UNIUv<>N%p?~<ossES*EHGl82u>5H7J;#=<I|#}{DU2)pa^s_t?66h zLo4XCBdJZkEw&~j8~<GSB8tP(p`H--d9|7cINrg8aD0?)&`KqavOoiB1fU#cWszzJ z5eNt7>LlYZM<5zljtq61DjKCIH7FqmczA;!WByH-sjv%~|HjMp#)eSbEf$kt!xxCa zMu79<9e?OsDz_Znc3a{PU*pOi>-h(tn%WGU7(6fj%(l-W9qGNS(I48#hc%{wPU(I8 zB*^1NJCdOcS+eEiqXyNc%-O7nqu3lt`A0I=vCDSnu~V*HL?F}#(y2;l^sGTe6I`51 zRP_%MftV4*0_qQp#U}2{kvjW+T)99%Vv|X(A0z#NdoK6c9Or_?9r7gNya4|nZ0H46 zyMyn-Xa6GtF8>5Q_|*12Co@9<j)Vw;0Ql%2yDe-mgd&hMLj6v>bpQOwJ38Htd@u+9 zDL$r=onxvCap;vYGB8r}ii?nye%ORjahhETy<2lDZTN?EP=^3WoI6szHTo!jXoJuA zr~>pa;yQ)^s4S)6uVkZ#0SX6yNDtY;3{+?XK$1JR_=ohUh9y{nZ~zB-*tRtK4SS)8 znzFCo0Er#?itkF582X2opa*=|p>i09<<P;d>YIL$kN5h9(JK$CFo~JylYc-N7wjr{ z!v;kNfo4D|326yLXpslogvaBWuwyV;NhebvBW=iuTOl={z>te51%5iVJ0d_Xk(P@9 zl`Vn@;{UTYgt?Wu2n>H9jBP_0Z2O14`L!RD2g;}hmH3|k5Gk~&hh}S$!f>Do$OF(I zH7>yo`;tVW5EkCqK3~Yf*c(IqI0)j%MFUb0uYwa;2m$~RyrRg7M{$wdP=pAGwKxm_ zMd%q$+&@|IhDvaUbON6=%rpx5hx4H}zS5B8xQHHdnsuNfesG%J5DgTYlReCuL+PS! z^cw$Z5K0JyM53*kdnr^YjdAcJ9|4O4BPGbd5f@Ryy#UB}C;&p>hi>?XyUN4FPzasK z35=NwwV{tEjJex76lnMZ=%U3qGmn3029Zpnv+79gFf%s90z)`P>Z%jBK`(wJ$@6fV z{{H}iVcCQT`7gcD6<+ZNbx;R!sE5N+#Iebu477$)XqL0$HhAcVev%0dtb}xc5YC`T z5Zo0JS%zfD2MTl^%L&A+`v=c>Mah#8J_-Q%`G;-*DR>CBaj2+|S_>@{iy`!z0zid& zkO!sIJDwQA0Eh-B!GmuY2hJJ_1Cy7dC<#s|gz+ee@S6%>dk1^?10aY=?FkjP5xX^n zg$QuC1|yrc@d{?FM?Uk2`)LM0!JdjV9s<J$pv)eHDx-2x5vr8GwOpdS$%koBhr0@g zgE|%eW4yb%2CUo%bI^u!iH^XusRMC`cBq7@h)%|oqGAz1X{aFV?9GZ8LVGv{4F95} z)zdXNKm~YEsTflbVCx%j@U27JMN}ER*$M<EpoDs$1R9WpemE$kh@BX6hjJi~HA<O3 zc#mYMOsU8_Y=8w=ctgs}OEp{%m1%)o6vHcXD+=Yae-J?8laRdmiHU#(ZU9iX5XuKT zi&i;_?;Ms4>jznByhI=)iEOTma0g{5g+$0or}2;s0#AzQ7sqQBuLPL3$+skBP$cc9 zlk$|0!UsI)gx3?&bs0i@c@lJ44yf1zO1MObnVmCwQDV7>1}V+4sVRJzg(g5Pq5Frs z!7J3PvNHs(iy%CLkS}QT8Sr@&lR!qjpdZZgu@2=45^520IG}9Gl8W54>i_(PSkZ>) zuu?<S27K6ubf|<<sD^0h24RSUI7kO{V25_dJo=<mo}ey^;j7=$3xDW`K_pJ-T+jaL zk(ff&g`@`@i4klm2Xe><*ea=cAV<|KF#5pBPvVI+;ERb6o{4xIDaxBj5ClO026({= zpO}QjD%R`#P)36mG^!P3#nq`eAehJp6s<CK<ug^0i3eGaQ>9d2h1Gqy26VXBbjXHX zXa}f(my#h%TouZRc!$5TjZ53kaNq}b2pde3F5EDQLE4qHn8-VY7#!&YgNc`TCD$gk zhf(?)x#^$$fd_DKA6R4&h(Q)OqO8~uhisW7atMc+T%`1ni8+{rUjI;r7kUS5Xet+( zAV4Jw#5gxiWEZ02*hX3vd?=1=a*EZQ8hJ^N2Xnku8IFD^RCZF82V^{a&_-iBFKqw^ z@bRCG{Wy7Hi=5ymmzqIfVyl4#8zq#M^Z*TAV}@)x1Ylr|i}(gApaxV#+Qg6tZ-56p z&;_56EO#i43R|*qZ3`uR9{La$a448@kRP8g5oaa1n)C!kz!-dxufRhDOdyBocwEo~ zT+|H!L%@QYI58^{h~Uty)#?X~VG29J%d+iFc^L<Bs0QEdm2lV<X~9|{)kde;hh;#A z06>Ry00v;FB5mvod+Hc}=mwU;11boFJ`jXA$bwqf1%5~ZYX86%dLUj@RTX*YhJ089 zI<ONafFvy;A%O_micCGrIUIgi)_NdJG(8Dr@+IqVre45;NobC52pRg#o&qGr)J+Wh z2m(ZCi78qO9#mM((k!mgglT9M6w%xUmK~%J2pS`^26j=43;?^RhiagUUoeGf*oTQ& zhd$_o6EO#J*cJJcoze&ZV4wm@C=8W?2UMT~I#>cicn3&o+|&iO27w<dSOQ9T2kYII z_AKF|NIr@<+Oha5MHsX!^aVQz;{qkx5;kAdwT*IEUGezLgsI_gAkJ`j<8YwPbZ~}h zz=v^A;`7a2D}J<VC<S+5hf+ufc0iP3pokg^fM7@lb^oB07Uc&fvj+g(11lg1$#5~r zFo$s{L6EXyxA2F1Xb@r`25@LLPx54*XpAOsn}wZOqWG`2>&%=$6h$zO^h0G_2CsF( zf;HBOe9DJxP=|Hk12-t<V&(!aNQ6pY2YGNBOhXD+F5#|WNz~O4nW%&wRfiREm3ok; zu)V7d1chn1iD#||0EG%XIAYa+iyEuk)VhZ`b*o(72_E#HZYT$Oh)B)3;N##{)E$RW zj%K1bGiI2z+OUm?kfr&h=6P=DiC|rxnW9~&15ikYbV!GGC<%&{$cvEFPtiPw4rvqS zw;DU9^y!TN)K0wU;1mgfTIj%`V1kL5pReetw*R3IGX~sIT){l1!6mEWkdBI0m5Qh^ z$vDD?a_AyG7U|SwtUHjB0H6crCFEkzh62TlNCc>DNeNq9YNqDcT*14cGw9;01D*JS zEZ~`(U=2S0>Wj?kdh%*=^+&Nt5Q;E3xpr$@U5;(=ghE*kW(a_SUf472A^@GB2r81i z)@yRr<EZEdVE`zKP=;N&rnziu#-64k%<Q~?3L?u+&K7Bu{=ln1kzR41lt_=fOAoGI z?9gs(*nABhoEA8<z}Jo)OFGTA>6*p)>M8oI++L7Ualn3Aiv(scCgq9EA=6<|jy#UL zRSDC2P?hw^v+C}M)QifAaFyF`Xxr9|OaE(&-tKM)noEPGA5Sp}WipAJ25SxSDHbZ{ z1sx65YbO^a3f|STih#HSIV0XQ+r60+uYj05Q-}bpMx)T~uXYE2?(VTt2`yea2lt1; zP^{jdDpyYKuQrjK@B~aaG5W!f;T8v^HfZ0e2>srPbPWKdCW>&FH9cE#sn8j3!!*RB zh&;2HL8a8?0Isjer`GK_6bC3^a&RL@6$)1=o``V9u7}#Rlz*uQXg!Ha%51}OWtD9w z{@RA#8Q5f5Ar>Es6n7i<=@Pommo3TS`j`kBI}l}1tS%u4u4Jc`KqD!lV4cW@<47nb zKXN}$jB&`jPJnZr=yQ>-9G%!<ss9iPCkyREooxLEhK}<IX6T&{_b-~53Y!=TSO@^_ znyQ#N367u$MIZ%cEeicR2}3BexJpFV=9EcIm~6`haS-S~zjd_2k^ry(8`zm!UxbRV z-T<J2ofv>ZH?+*o@-=f^ooES&-kHsGiy&x$AdrTM00I$60GQwj6Ayp{062;W0a?op zUr_J>xDF2%(o;HG4wP>&|7zyJb*4ENLI}ENr3e!XfGOAO1L=f3m;h0v2%&%gcd!Q< z$O6N>cYxJv5T*!$3(%8@C~uzxp`nNt==7NTE+8lxRZp~`D2ET9h+ZIcu_%IOsG=4S zx{C04bH9mKXPO?j>61tYS^v{;k$xw=_ysSQ_v>ud2>FHy(0Ai`hS%=%^*D()U}Fat zA#vIXa@YoOhj?-59Xkkub03=Z(g{Nl_Aajoa_|I-s2oM$2CyFrp7gk(VBKwa^Q)%_ zjBoj<WbRm$`QIpVPquZU&~Llvd9eV8pf9U?uy=|`8^#VLlJ^Hn*m;T=ftN>JGENY> zW>jMNh?Yoz5nIp_?`({}c0-`?0FVZrJRp`YiX!+39RG=C@CH}_g3T9Dpw6_IhuvrK z5C^M>|E!37$7Q^)ik--PzW4f_FgvPfbdk3E$FciNymkHPBA)!0C&!IUpNNo0tSJ(j zLg<}m*R_fGFNdQP$^Qg<SeS=qNO_-#v@t)4LSWr@$aHRaYPX4OG1pGawj6=k7d?a4 zmS^?=VCh_*e}D)ea3H~g1`i@ksBj^}h7K3PGYAgcA{z@o`3rFGA;*p$9a>;G?juKw zF)|X0L2~6ndoJxIEN76Mw-5rs1%S5=n@xl8;F-%e&}Odyh6XmnVo;hLfg%iY!zNIu zLvAbuX3Pl>AHJ(z5oXoul550)VGs6`DR3M&b6?+nwboIbKy~Th;>`>9?Amc<2mT%S zZd|!~1Ig)4>~L0qJOlIngA^c(VuNoAejDT%mEp=O{}l{35DP4U<R%692M%Vzt^vet z#b?eO--7Z2DE|szr)fTNu$l(2xox1iZ&Tk1#I!IURgc@|jU*e}^UB&<;n}nL8nQuu zBdLQ&Xc#hRj{YKw4$wS2d%W`mx((n?AUuDr0~q#qc7C~kROzYJ9(57TgIGrN)C12u zooql&KjH;=6><X2lT~>FepHq?Tn+ROXy(urfPMm{)m44;ou!|L_?43pK2~|SRXN<$ zqa8V{%?4k5IYoF-K3(1D&p+a<R~BORBp8uBD`MD@b>f8h4nMO&X^&y<3>JVn{X8g8 zXHDugpGW1C#m_ugiV3EgUxBmXY&Zn~r)xO1`I?AXuBq2Za1ykLX7nip&QF1{^j)40 z(E}Yq|Nn@_9EbIULl-{wl*3v8<)~#&I5341UpZZI!%ceX8I&Mm@Qf3pr3-yo5Ip1{ zX3#g>d}HFEhcaXxl0RYP&uk}NTIs4e;R+W&V;0ugPe`^}tg{6Dq+dV(NT*+Ct=5+# zV1z!)(WDH~K+QYN>IKh+%X%qdw+6ZN6O<mpTb{NA1$7~OItJEmMCWlU5Ng1px*nhk z`Da!D_=Kn>LE^|HTYS8(Taa}TtC`ir6l46+dEIfFQNI~~72`i6Vn{N`Z(XbqUm1ny z;l>Jmd~#(m%UrX~H{+bM&O3L<b9;jV>$A{96J4~?M<boI(n~Ylw9`*R4JOc0Q(d*y zS1)6owZ;+AthLu)gB`Zm8FxLl*=M7jw%Tj6-L~6r!@ZI@_r+be-FM?X^o9Wh1OOrV z1O;RO0RSuz01*Ii0ssO42>$>B2pmYTpuvL(6DnNDu%W|;5F<*QNU@^Dix@L%+{m$` z$BkwlhWtpfq{)*gQ>t9avZc$HFk{Ljn5N*!D>HNI+{v@2&!0ep3gy^Gkid~Ohbmpl zw5ijlP^0$j5`bBnT^NONlFGHK*RNp1ip_Y6(-t#e1STEJwyoQ@aN~|$i}8%yyLj{J z-5WQOz_T5@jO0tWu;Igqz1A6MMp@#=kRwZ;yl^mM%9t~2-pqNRn1NtEKLDUWU%wnP z(2bkUs8g$6tu!>m!Ck1bo=v;9?c2C>>)y?~x9{J;g9{%{ytwh>$dfBy&b+zv=g^}| zpH98H_3PNPYv0bjyZ7(l!;AkPPrkhQ^XSv7U(de1`}gqU%b!obzI~LI@9QrpX(5jN zcWpsXS^#!OK>&*cfI&is4Aen*qM1b3CIOHV08SE-vPm6Z93+^44Shl2LJ<~N9SH;_ zA&DOtu+Wf;0qo+07D)_L#Vk&=@n0MPcwho^bhvbiK!RLRM>GKpIba=*c^1GXLy}U5 zfSc4p&=x@&<V}U7SQx-!6dt6cKxCL`-Gj5ZF$)|49Krz$Ec{3ij0GKWNfiNT;bj1| z;K`#F95km49aFrt#TQr#G=*#eb&(}Or?okdQ5O~j%|Tc6@nsnW9kR)#P8Os|0A-p< z-61?C*rP#m3Zq2;Fv|bPh^Y!u<pwhWfC$=R2ni#Q5&;Z4qOJwiA|S2=eWQ$HSP8TX zX$E0cDy__|AP}Ap3Y39BE?O(l2?FsbP!gd8;O(^oxyYjj%9WUsT?M%TMjf~oS`Zyg z4g^d9bP;qDLc7@e&=!5<dx$b4QoGy=GUQ3nf(acl%Rqq!;6y<+j(aC_33Fs&8SV<? z1|4qn;U&HY5i1a{U+x=`u@<SUuyQDv5Ua}`&{@!s(jW^fn*?RM%f!r~kzYqgi!2Z` z%5ah;s5B9Dg&CX@v?ad>p`j42Aes>-LcB8S^32M8U@i_vB=H|XE|iciLM{ZoLbeyP zumTG9^~<P3X7v9XK-Cec0qsJZ(xFDkWGhz!3msG}C%XmVy<o)wn7}T?c;g*FpdO%T zAL0WEED-1dVK@=ANgp(L;?9}y0i3W3Wcfj!yWj!}C_qlokB<kSxxzBDE__5Em_1PO z!>gYB^2|5y{PWO9Fa7k?S8x6G*k`Z(_S|>x{rBL9FaG%Cmv8?0=%=s#`s}yw{`>I9 zFaP}X*Khy*_~)<x{`~jv|Nj6Cpa2I*zyccZfCx;W0vE`@20HM85R9M%CrH5xTJVAx z%%BE0$iWVJ@PqU52M9+v6MNW$gedfh2<uS}bC_cs;|Kse`tgr^xX>Ia%wb310S|$Q zqae7DMF9WuVL}tS(1bcnVnuj}4}m;`7qMUkD_r3UR*ZrmMLeMrx5$tzx{!wf2uA>P z!HQRyQ5C9SMF7kgfNK1s9x~*j92a6laWqjNst5oY@u-Sd<dGG$5C{(kImbc{go*el z2OJ6Vii6}a0Idk4IZOyfL&_0}1S!WD2_i*-P*EUed_^ms!Hs_uv67ZF<T2FfM}na7 zm3?gFK>E=SOs0~HS_}X#Jjup_z><wu)J79cdCN;O@{<wiM?L=Wk79B$9|F<EE6ONK zg&;E)0RTq;Y<Un=I@5wCq$NRIvBpMLGa;^!MJ!?wj!EY7n>y45C<8#ndXlpsoeY31 zWP$$+Z02K;@C2a=|IrU~JR=rt+~+<S(#wI^F#unL2RFSLPzdr6psip<ANM$sXW+vg z|Db3^G3Y{nykm^!^y4EP(o1O&F#!JX2Qx>CK^~T)96zKdECrI!h=9W!J*24yUC57t zO!JH@eMm!x7*dJ8Q>YHSp*d*T%v1<bmdLzFKcHGc6XN5J1EFRwm&#Qx)}tOsjG`W2 zS=LLQQl`uNhA2R}&z`nbjyM!ZHFO~hHI~z^cg<lIc}T-z(1Mj!^lM;K8H-kMlq0rq zBS06cKwGYontZef8~uup$x_yUF*PMXkGfXKy799J{Hj32368m<k&04`tzs#{S+xH? z6}A7P<O~^!)XZiivTqa!H*woP9)fhMt}HD_W;@)1h?KbSbKyX~Aw)IC)+3yiVNjvF zKW?5?8v)R0D;%5DjVQK=+~waOXQ)h0?$eBboycP&^4#>IFPzG(hX`+Ri-kfmqqC*R zd<Ak=`})s?1?Fih6pE7e8km2>WhEa6yu<A}*TN4*-%JBQ%!0sIqp&P*MB-}@X2ujD zC(f|=2HI2}Hd7Y22rx&exX>#;G@=AquOJDj;_$IpATfnz9;vw0onFL@>EuREb(>=z z>$u0}gNF#$=*ve^SR(m^u{mA}W%&)(A3+Tyh)uH67&ddqO|ImVySzP2x^Vx)bJeGB zQPSKUtC`1a=H7;x$qi5X7bVz)s6t|zVnR<j&)s9@cFF1AteWJ^h<0B-pb1kgvQnif zDMm9lY!E{Onb48W9yg(RRkoIdjpvkZsN2U6e)KsNu0ZlVmpf*HR6`u~Q1z<U=UK9L zB$U&9q#|{_>-23|AhJj-Nzf?8PhOG0pH6YHyZ2Q@+Ooew46lqi!t4MbW1APAHu$^> zR-XFWBaRkGUd1gwM5<OGv=HK-Q$kK{ij&<wwug(Gi9>AqmBi-7>=ip}TYRHW7UwRB z6k~ylX5QA|iT+1S!JCS5s^r4~D25FW4e{<7SKsg!;*~$rOMklakZAwz`1A&g&v~X~ zkFq2p4<p*cHLF~DCiI6pc-s<IL^dD&K%~uY?z|1#Fu`*LI7ybO$w`~o(4Zzd^eEa$ zSB!k=SM2j4*Nb7PM-RF3)HcRXlJKE>J$aR6vKZHx*sE{kmsd0g9N*1k?ZQ)vZf_qZ z6MRL5X4@q8l%g5K0ZmBTee3vZ<hEy$cly~<p09ZCIq7Xi9L{{*0G#(r01@72YdfFJ zUVQxWYKvJnd)6O;?R5h%4u8;6swvlBI%U!Ll5l<$ySySRDh@zO(=)77M7>7xN#dDK z+UbV>Nquv}>7ghT;Q4g4J?;4rJ$y?LvfRTic`*>-=MS1zC9?lY6OIuoa#WP+)-LR~ zX^(e*JndSnyFr$35OO5=tO=$~tM^~jrkK#P3${<^H+l4QPvQq`2uOegp$D8d5HsL% z1QBQDM1Jh^W&_a*2*?t9BxCEBV9ga%_4N&yM-j(B5G4p4C#V!TMG&Llc?mIBb9F^9 z2!oN75J1BtdSHFmw-B^YgN|np2*ydC<bCK?PrbwoS|?muBvm|QLt+#T?+`--F@g#K z4c*WU1Hm%W!3S!Pg#i#GivfmT_$6Z)hHjvR7=eWWfQ99<5xX=HxS)W)5(NPu1%7Y{ zasVs>VF>|HE^8A2E_grx7jpW9aF~`7Y&1&wphzOLUMv5YO=~w1LSO?zFc6bS5Ef!3 z6{3k3QEo$Ye4rSLqBx4ASc;~2ilyj@9ziq?K?=3tim+G<TVW8BSc?>q1ZMCAM=%gb zpan=E2fY}KzBmxR2#ma#g8|?Na!?QrBM>$4fC6CzL=XT&zyvTb0yr=NHee95@@%3P zKS701g*aysA$`+#j%bu^;&4(xRuK0v5CHWx0zruaAqS8U0D|BbN%9U*$6?JRWeD+A z?<f%WfQ1Elkllcg2ccW^Hx&POR$HZp1euTtxrXmpkp@wa0dSD;C=ksD5pcwDA}JBu z(hx|X2XcUtdf*2u`HR$e1TNq?1%W350SJgN5J&&O1-l3ZHBcjfkTKzv5ST?jsPql@ z#0vXlej?@&A=Z>328aT|dje5Z1DOzSpeX~PP1QgRZ4?0YKo9!|QykY#Fa(8~6ou;; zLoYNAFO*kO^+kxMT@9%e7lnU^q;F1jLJ}oI@i$mK^bUUsWbp6~;6RuX0fmvc5z{z^ zUQh!M;RgcoDqIjQdT^5hQ7+t947$`Q$!HXCun1VmdA0xx2H}JD6NEfffYhg4v?W_o z)Pk!=5YTWn27v}DqfPx+l?m~La6}LE5CHTr5A;9|3E@R=d7Q)+dve)zQDH<>m}YoZ z5Yo1s7Xc40L=N+io!Ysb+}WM;uyX<t1^WLe5Kuq?MllK!h%N$w16=Sb0&xj_h-|n} zgCB-|1mOfq00l;X5G@Ev12GDwIX~}~f7CQz6lhKL)JcJO5PC=u;HePb5DrpE5ad8} zTxVxNHJ2DVe>_%aUtx9<kwsaggdWNeT*sUav2GyJAkKIYlNkVrzzCkehXHU40uf2F z#0ujTN>oM=ltK`W*`jOoN`945IC`My<3cplf97_GO1BWPHCK^@3!2$Tc@O|H-~uWT z09o(`8P`nNNf1x?4OsMW>7z11T9f@@RFL!vaX4O#v{p@tPqd&aae$RTG^DR&q~F*+ zN=ifIV52M5OX=oeuONN|VVbzm2!#KD12T{TT$%-tWD5r24l(o&{3ugrmYnwk2e|Nt z2$4rAHDR%ofZZn$afl0w#eMqZ3JVrVXoRHi!%WSDO;uE=6alL9Sc#~5fu@-c<j{Z9 znLmOc2!{X&aj>5*hk^5?dTZ3D20>&x3Sc%`5UBU0qbGOu@I$aRgt&STXA}SxR}7*+ zsR$9E{yAO?s+{wad<aoZc7=CKc@XEAS**Z)I4}#iFbb1bd+zg9lXXsn8f)j2Zkj0& z7GMy&WDB9Nqc=K%x>OB7S5QEOqVy95i|Jw7hDPIMdeAyf^`sEWYOO?wKT}2vCEF0q zU<+>$11V66^LY^b3T&VhO0EBJ3*2x-?xu?RGYdO9uPE_`a(F-QmSV`Xng=+vqd*A< zo2WJ0M<H8)0uc+m;Cm%{KXCL9+)xZFwNZ~mv*kE_4KcL%LsfDWlw(D<2Vt)Mc}0<= zMk#9$`em{DQx5FNrmTq)%a~CBRF@A6dLpK_G01ZYAw}bbMz^31iey74nm`{WTO-6| z&4dgUCxBMAlt>T&c@T&hWuI!)c(9d6+CW2hc0j$fqld_C0ic5bB!7_SwL3L=Z@{@h zX=H^9Vp&CS@`pex1-U7dbMU~bg@{b#CxN1bfoe;#uq8|2AP)9Wa0`U4CNV3~8n^FL zN&g@Yt{PtcHFB*GXNLb<Mty`4RT}^w1)_3<3lqZ#ark>mnLm~ETC+zGl&Y%@%cB~l zn$~NmV;4itIa0h3VE(#3mE?Dp8<Yc43~FQxSOvDSYN*j9T&kv_Dbxr75Ghr#jNz5M z^HYM2#9#^=0JhMA%<4;e^s!Y&5Y04c1Tm~!q^v;-jU4PgN(yfu48m=Afuo>CyTq}M zwZpqqM*oGa2Eh#=^-bsG1^ej*0n|gglx)Z*L_VlkjdTfepaoTc#agTddSJmdI$lIv z5dXAD6g)!n3J5HttNHT{w-7~0sZfFDt7XIpI4}cte8+f<1D9|Mk;JzMifpm)4$TB+ z(V0r(f{%wR5c&VWv+|>L)Z}+@42ZI%3S3YFL~tlwzy)3K1zd0iL@)zY(8lzHq#HFv z%UQ-K^oOR)XzCQlqVTz_fD4wO1fYBfIS2?02nc{s$xvVkstRIZymep2Ojnyiz9&FN zlyQ((a+?_dqCg9@Fio;d1T_!`xXge#$bec<14`h_Y4ol+D#T?q1B=0;-35elcV^QR z#f?=EV0;U+T+P>f%?ua^HDCnZEMv$dMGGZMnzUZUyhSw-1xi5B8B4VIAYDHc&A~@S z<JAfku){Sw&GLN9xU9=nz|FoauRQf{v9(a5Pz~JRU~Q!}KiFiX8hTM_ZW*Nt6m8A7 zTm@VJ2Y~;u&E1R(Qt4a2^a}l@O$<r5h9r;o^K{AAOZnu3Z_5hsOwBM22pMezHvk1r zz|Encs-L%dvxZFnI1r)bu5!e2EWAHN1xG1Z5OK_}9eoS4z|<El)q)TQP(aN@;0K}L zrdCvSu~vv`oJb#cb~yLE(L{b;dZSbH(z+}ML=Xooc?cO@15yo#p`=dz<;<602^L(f z=<C<RV?yQ7Ot(-)1`$YI%1JIQ3bb4Wa3BX&a076V+Hk<jm*59(@B{$>2bKW729dGM zu+^F^J(>hbe>Y%*9ac9R2Qy&Fa!mv`Km?y$1AXwR1YrbKV12l^rU3wr(<Ml~-8=}E zYuf*SP-CY@0$~NZgrllZMXxXm+x(2|ecUrZ1X@5eZW^=Xi6>Qn-AY3QSYZx~yxocO zde5MzzBb%OrBS#*3zr}XvwaAXum}x)38JvWdDIF3dYR<eDVs2!VFYIWojkN!P#x`8 z6h`0lv`{x20MpG2pV|tza0@DBYU8zivk(Q2X#`HdCYDJGUftotQw_Wz;llSw<XsHU z#!-9J2u^Sb6rM(S_u_e^3facw0^tOw0R=Ex5EaYgWK&7&c3rBMzi?QCpDX1kZVQI{ z(4i-<M@<V%JP;bbO^K=H3gc!2k!(u^=8}rHv6bG*_~YkYPq3tvAGT6BKnFnMjLQFz zp>m!$p`}kQUVyH-Qp3H@fW^m$npmz0xmk4s1@VB3akq<3E6&N`-!KY^)l1Aa;Q^om z=Iy&Y^0Q9vlyXWCVel(N5)D8d>I#EQumtAZN8Sms2)Gcd^6HePMq~qVDYz02xvuN> zF`|o<3Q%r{A)ZHZ_5z~-%?Lc@mJnloq~@6pVz1SC0pPqf6i3cZHmC_o@B4YG9)Wl( z!h(nC;eL8V#^SLc4d!rD>7G1W#eLIMs488f1QAG}>f)hP?6O{fvLFh@@C>(h#Qi=q z@)u)Ldk{@Nd8Wz7Xm0FJK7_Im3drye-{1}WJ@JV%bK2y-sArC`;P3-cE?WNpH1>Xu zQ5(grU<uDa3c!F5-vAC{iSh*kM&*zX)gTJA2ekSt5YI;7Y-jW6_~%p<3zq;6TtEQO z01pu=^rHT}o~860J$ZOg1-pQ}(^T)Sd9;@B4Rini1n>=79}Yp!_4FZa^#EQ2LFNY0 z>yPAvdrM_=YHFOs3Zh^M_|W!l?+xIf_{~oD?J-kZg$x=cYv2sFkz@%>5CD*X3uaz` z2?(}z)ku6;2LK=diNE+O@A&r-&<bHjef4ba>7TMcPXyRdwD1pZ005=$_TTUhim&?h z@xKP4P!#xHawZVMdrZg%t^~mg|3Lb>Z~AZV`*J_`z|S6F^bfpnSXBQ;#G4fWNPd|I z`v$B^wuhSv((rA$Z~D7W0R4~;5o-O{&mPc(O@1_MwRf*JtVXv`aR5;vKrvgR0vuGO z>fpkIu>vsrR|mjEiU0@z`}Xafy#VkSegqj(<VcbwO`b%VQsqjPEnU8Z8B^v=nl)|S z#F<lPPFlBE1xU#1XUT*CUd>wgDgY~kB3Tvv=+GZTIu!||aWjQfy>H<>?gSfF>{zm8 z&7MV@R_$7~<?tOGD%7M<s0Ty&e5$HdNTmo>y?P~-R)BI4B@zGwKtR2J-@HZh*3}<d z%9Sl&#++I6X3k~peYR)L9LQFEO(p~^3s(R*uUfeRs*2UC!My)KHig@C9>g#Ly4529 zK#jLZq-rsfR&R1==FOcyhaO$}^o9QX{rhJfBw&<56^2@<Ft*TEt#C6m2>6vjZv3Eq z<FpG}w<#9CF=GZzn!C|oss9HsKmi9N5Wvsi@u!~vw9zFnz+8b4wvQr|aH-W6Y6`Vi zT=^>i+(3W?mtsblEdX%>2nU*I{(&YEWq=U?fJ5qmCY*8(TCPAHcjU20AAfA=Gtv6V z$2RrUOQ|n8JPZKBBcD8|7*PUHVWGkDF-M&DqB&)kTK<{AqJN|b=b(Q$0y0fC*JQKJ z&aAWUtI~uTYObd)4B!@7Vmk=1gzB2|ARz*11sN1glqUZgWsnm_noTT%#vP5!!Ol%f zFU2%dO;>`)zW_c%@s?QV`pdMBxNDNb0Q5)#AwG@TutM2}vW<`nmh^|8jHHp~8*rde z#?f!;fef5Yk3}|FW!wC$9|fz4WiMDy6YmvKs({0`y8861sJ#@T1(#F~I)tBmG7@JT zaJ~@+ntFgaPO@d^rMF&tpR1>yd?s{7u91Q|s1YX)k`}_EOeHlhLIe0Gq;XILww7I# zi7X#9@5MM{jW^B-)CH4zWm|?wE$Syd7AnzShM*D(LWcOMC!}uz_(mH2x_W1_969E> zXP<xW6eMmyb~z*p0V}c9gA5W+Bnq7*>5YyKdguS0a?0s6=%2Udy6byI%XjIMG(<W8 zMgq757o`*u`6GX28CM)iM=Nu(CEifRpL*mm)*ny320U=V+te<AX9feRBs%l@36218 zkwqy~MUtiR%2j>19DVcg=bhhTK8Tsg<jEPq!B0m$^#DCKXJ1`VdXPg^E?fkcKm9C~ zq0}s|oFQiqvL~N?Mf%5^PDK+<b>)|5zB1NZYMaTXiBd&EZ4PqQS*`yL0PlsyLB4tM z$0r}G&+-vRRHOVNi91te>(kVgt2K?Ae(Gsf!B067GJttvUV;@Ec93!S!(-(`U;-7W zl6*X@6+%&p%J}7~OQ38hMPmpCQ?(}(RcikvUwMZ&V8)P!1%OfuL}3b5c)*ZN&nc`h zSO69=FmWxVP9~vEF-CKcPK9kDTI)!|<`ID9WPu^?7zYqlxI`wN?lbv15v&4p!;wr* z7Nde;gig{IeBjR>ojPDgzTz>^<)egVTF5{0g^#z0v59Yl<HnvCfT4|IitUS)sU$%t z2*wJJOfi)H0>H-PErgASJmhD}K@M^Za3M1bK+X^uM@m*QW4tKU9YfMGSM<dXP6$O{ z5~4wn7)(9d03Q)|rV_u2gdZk?N6ZRWI7`;jmTdyvQeMHqBgO9^y?e#$PR2C(ovN4@ zb4k8H^^S#rBM(#v05}?HLf|3ume>EpCXZrfi}*z^HV_&L4lZ#E_EE1d+Q>&gu;W3M zU`KfQz=t@*(G7+f>m%WK*jLz@O@8+CIbeGWE!HL;3Hn7SdjiBS;rB0s{)82Vf`=ey zazE|`Kn(*d$2%GpMt^qHqm}8@)$lPqDS8u0vY1jr_cEJe&aZc@sD>H;aXfQyG$fz_ z4I2-_MtfjKo*{`@nb@erj~3OaWeFQePl7>#8Rbs~bKycFBnxtG^o#JYDN8&Cr-SS( zmkS{&QI9%Sveu+iQ3M$tmvWFJ#IL2sT;Bk(BUYK@3wik<2P6-Ihe3eErgSZ9U<K>f zi#cRkI1IqR)*4rlKqW8>iWC1<tvOMNhGY>Rfk)1M=f=Ty*0Vp9tbZiu$B_KVZ7G2u z9n<BHLW<=;U&-u2sE~&Myiy+3{A_M>`<Z`)BNkYkTxmO`1uf)>ij8$)KRy%Bti~ja zU<B2T0`RbdwBaDH)NOV>d%kbj@lR1bNYU`b*pdWSjh&igS)fbO5>lbBJA`d~wL4#I z;xquzVyQQK$B?^}%9{sUh&gW5T(eM=nF9<&8b9JO0@K&QO>B%E!&@N>?l%BckVAuB zRZ7{B=M~&I5mzZwDeOFqoq~uYUccd=eLmR5ObpsHV)0gnSdJmQNCkyCj5O0+=Zu)? zR0)kW4?-;Dwp4@1nHvB6VkRdrFW#g}007|xQQRWO$PEge7UaXu2=5@@;Kz>{0uON{ zS<FpFGXf2zu#vcIFLJoWEuiW&*_FqhXTHq#{PvZv(ss;ed~MdoIN3B8+GpCZO()-4 zmkRzexD(dUV$A^$(F~Q+J7f!V(c4D4HsOeAoT+>lVqZg-nqxyVNzrW6CzgWqh6yRp zImO|{|5WP0_^3tzmJk49U~g(%-XC;*xMWioJ57Qv<j_(f3zHTzJ#VdCd6;CsdWeSD zoT*1VKe7ZoM3W&k1r2T&OlV`58&jw*FO3z)ioFO=NSFo?Z2f1hgD`<+!wbh%&Asn? zISbXYBZ;&EfH?n_gnCDoe%L+cVNZ}?jo%Nq7cPz~k|Z30S`3lKAURtg-r8fN;5ZTY zhPcR_ks9JBcT=u^^5~E_A#Eio+FnG1oof&18+ab#L28O}o~ucC<rrSmG&s59>M7j| zDMrKa{G&7FYaaGcXD2>_51sYg>OQ(rG2%Ksmc1erN>d0a!}AwuiFwlj+FsUh+NoCV zF93U3NX~bP4?$nu?zQIdgv(Q>yQ~~Z+YvZ|I0D!K0k&`>T*xPWXu^D4jqrDeyk*3E zTv)fFLq@rf3rDHr)+seja9U;XJRg!pii2~jjC|_Z5=O0KxfOU)8_NL<R=SJ2M_Mzv z+o!e=(AoccA;ydE<5fR=u{4Yp9JC;JT&U=7iRW@0{6{~8?<So}zjFua2Ezj|ymH)p zkenVg@x?zDS-d)T1ILi%t0%iilTh5t60}F&0gihd7$iZp7&2=<e*T{%YX?D`3R#?m z5GRRq8#;+KR^Wx9`KpbPw+0M=+X4rV&?yM)zYA=MPT4F-Ybb;YfKWg_3xW`7Sq*sF znwcwyc`%*sIf!1UtwXW2{lmZ+WC&oJvxT@K4AY&VXupG)wbAREby|qaqKAdph}WXQ zBrFNAi5VP=4UxG7BX}IY6OYP^9EOlVdf}*ku)mMEksY!&a#KPY%olXaGM0NRP12x$ zm^A<0^BSGHzmd?sF{DF=k|3l=C=$uC8XJl%+?Ycmhk2N$g`k9k=&PKohm!jTp7OXh zf<vpDf&iF-Is`4B(uPq0xTG)}C$NN%*u%t0p2|uco3g-zC=;FAAwM*<D4@iVASsq9 z5dhq<@puKp3XMstD8Y%p0H}v?@P?UU2tYUnW8sH#2nV^DG*v9LN&JXNti!WnlA@^# zKQM}-agx9og=)|S1*tpc0X@-}413xcO$dNS@|$p2I-YaJO*n{)8p9{j7i}m%S#X8& z(2IlM#9LUu38Tj=(KqtJy<2P@9-542APLc!zEZoagNOu+bHD!68a8T}aTuPTu*d&} zfCD*8m0wz{C~B>Z6QA?JMS7rzZWtml`?0j^#)Nb*6srO*NGwXkk`khYy(kZX%M;j; zAHzzrkDw*x`AO@bxxu@bepsbm`<^q&4iPIiC6I$DYsGidIAk~vhR{e<kqd6X4us4_ z)d4K6$(N8iMFr_ABjUw+xCeC!qem<?C#Zr}td7a(hZ7l>0Pq7wSV*IYoDf7K1VKFr zTc-qRBZg@}A-Wo75}v|I%;oq=-7>6$n8X^GM8z6Ii42W7JP0MQ1j|zo+)yWxV95ls zhnUeel+cd9e6f?+f*P2DG=PH&nm7y$jR4pL$y|sUz{jPLpcTXs5o=5p0=@r{z%EbY zz24fsbt<9X?5u-Q4Utec48%0YIfy8z0o)7#Q5XzyXd~t9s7@)9GQlpO@`~MKGMt1< zhR~}+pvC~G1BP4;ZIGw%DJms$mdW^rdDs^`105uKF@+d~Rf7wbQ$k3p19l96Cm<nn zz=vDx#<5x>d`KQ|_`cDTB@@EMwd+c<8n5&G2s&7ZLpTH_2mn%O7{BSM(7dG}^Eh|{ z#zG>85gG(&0tvZUP%-o@@ZwO0n1NdGha}2Sqf#R1>Zz+a2)Q#$YCxkGtIHf631yfr zziF|-0=*W42MIk0q^v=z0f))pP0w0VCJhOVVms}c(jVKIQv``lz^?z8@d)H3E2U^F zqhnHGV2F!iM+36a&I(9N%bJ)$E1C(3H6<i?t0rY!ptI4jXGG5cuu>xO2-JMBpF9&3 zDZ+m^vH(~EilMG=7|5~0f$#!TGszAjB2RuJBNQndq!5XBAk=GenOE4O0I;x76{8<5 zwdJbO){#4ZK+=#fmN4W>9<tT)DVmcBg$<=uh&#LeVI6bevP2{aZa|-YT8&;x)`w#- zH1U|BGP3K6qyShFKf^R|$OjZfq4T>|t6RxO)wu<wE~5;Id1#pVvm{v%xYBseblo?= zs=l7Iry-I$1skGo7>9AlRwPuQBRGWE%U6B1x_xRGa*(crz)b&d4F|t@Cm>899CcV4 zq%Lw>4(uA%jwM;Z;fS4Mh(Ynzj;I<@EZLV8oPmU-N`VBCC=)}4*__oBoPxtn>4vmi zh`tgDb1>LORHi)D*`(DJKHWZeyN-jLF2Zn&+G9(lwOV??s+U;^Di9!F9Vy^R$Ey|F zWTCDkJ%}}U18FFs8>!f_bz5XvyM`%~dpHUHJV<Z@366c+y`>Hh@*8k4mP;Lp6%&cv z<J-e!lT-YvEAT7A2mt+I40RfspST>vwOk;1x={rxBrAt9`wD~9OAaci%O&0aK#+Xt z26_-PA;<!9q+3*UTr8T^(xqJinXA89jsyb<bC8BTVb1@AiOt#-Ug+>VT${r_pabb- zin_eU;dNfl*jB2|Rq6WKgLuo2xPj9;tmoxk&d?gs_$j0O2Xs>dHwb_)SO}#l20R%B zz3txjr4FHG2ob>ra)RIcZH{O-i9lh9PCN-t!ruU13n&PH?6rhZFwX$6flabW*GOOi zhTxrG#*l!?0MLSy0f_~MCT>~?Q4obzh!&}e;1M>9gbD!j{Rj-U0v-qnX;F$qwIEWN zpSD??0VHAPC8;P7(d-Qg4mO(rKrt@>0y?MyDp&#&I0z6ph)W2Cs#Kd(G0z9#OWk=A z$+_X-g@*S0h%F!(l(ET!*ib|$1ctCT3XsBsz+nF-)}4hgz`j5gsM;M@8{I3u+%pq| zv%v*{bK@t`Nidc+wDE*b$jbo0fB;AW%IseRUgOo+7CF{3I<DP+U{y02FZGZh4Y4s< zHLWKOi4zC_4OoaefC48#<c|;q`I#d3h2+CUFLSUzrjXUjx#TKbKMH}1kB}As1qnZp z1VmT}0(OEV&;sfFh$#-<RkqyY%c5h}M7Ur#%UcRp@ZCD85dSraI0%3%;Np=0kFh~! ztJRwlvOHNfzwi1kXU?Dq;Uo$ZINY#+U9-z#2!+<Ogho3VI&cCJC1ndH=4MWbB{_%{ zkOXA?W=gyf9P0}Jo*-kQkncK@KiLZ!18Dz{C<Xxa;2}I2Y$o6UsNjCSXokRGnA8Ik zw$6g4M6iq*s@z^18Vl37kWnD$cy5MO(>iiOibgw#IJjPX#O4Dnt|c*o3J!o8kO7l! z#h`(=RPZlVmI=pVikp<SZf1xcI06+&fsini$KjS+km`jv<AWdqBbdbX9O`lMCZonc zU{gM^_%1DT;6FA9oNPUYK!O0s0u>mAuAb|K;b8P-h>h-pgV-acM(fl|J8{s4Wy2k_ z_^t=aGN``EgYe-1ST#bREf)xY7svyt0po>OHS@*b^<;!NsLpY!%EDH{zp>@95Ietk zl8An+rm%%#(7MUC>i}>88Nh)IxPku_SO^)Y0T*ZjXgV1pH~~^%64V|;FVmf(AZ)R) zR-<^J#WIM~28lqK;3etjC04)ZR_?oVmLIcX>6o4e`UwP%H4hnurYPx;AcBRM1>5;< z45TZ2+7JNwV_lk}r&tL49f=y~0^^!*CB)V33xHTCzW^Z_b55L<+Y3KHghf!#2tNp< z@a_R0KV}{f2(rAG)=LaeZOOWyO~H+Xux=2)K$=48#X|8GPl-Tt@fer!88?eorSTgF zNgUU4(Ax1H_wgSG@*o%TAt&-8H}WG#@+4RCC1>&`ck(BP@+g<`DW~!(xAH5;@+{Z# zE$8ws_wp|X^Dr0lF(>mfH}n59NAomS^EGGlHh1$khx0g>^Es#UI=AyX$MZbb^F8PD zKKJuK2lPM}^g$=|LO1k7NAyHj^hIa%MtAf_hxAC#Ew)<@oTWkD3fnk;B6p~*oUsmP zvGn1?seA#pH(xTZxHKU}+VR7wCla#!8?%w^@?~WRXXq*{Y;_I=75|V2dnj6A4PaT< zk$qu@04R1I@~ToaG{Wmbm_U$UWC#&jb<!m@OZ$<k^}&N^)CCcwP%kU!(g|=6)O#o- zb5&ZLLY^JEn#f9)C{42l)mVCxL4<Xrj~IumF<itg9PDsJ<`&g&7D^!#iC%RH?SMdW z=(Qp|GVZiogv|D52)X}M7xwoBtb7XqNN9GIAUrfJ)zU?2koW~UItW_3Voe)azrl9G z@)&yXzJ<sulA<nie_64*7;oV80C0!#?GGSHhJVn8tTmB0YEaB5oLplj{c(qh7q`!t z2f35l0HCJ;Ab8r{s>vv!i@~&^ah8uPkY8vAj@UpIQc2rO3nd~4NL`Xl$E=E4gNC`9 z8`0RyJ&?&The13Da-aup$fb7>2X27W04arr(M~rM`dpmUvrwWnARvbDhg|!6lQ^N9 z+6Ctg`0HT^1_YgdD1|h!Qhu=fI0{Zx3W?-={F<<idMF2bU^t0Vda%lereBC$0|~W1 zT<p+>AM2ZbKsEn&NCc5@{mg*ITQ?Kw`+d|&JCpEs|NEPm5nPyHdi<nV-%+}|`zhzp z4s@#r%U3dX3Wj|d4I2-Th6#I1`b#IRDVcY!Ze@6u_(ec~gfS8cdC<<{7c6c)2v69C zkym!gNW0Gmh+6*w1o+pFV84FmxD6CG&>Td95+_ouXz?P(j2b113s6s@Ic*0wk}PTR zB+8U3Q^ITMvL(K71o!-dxALaOfdN`Z#3^y$Ac^?wwG6<Ipg*5VmojbY^r^<A6^lY` zYLBQ*f~KSr)HyL<fKmgs6|8FZV!HtLx{f^S_AOkE^VU|g>9ye6omt-=?Wz$hN^&0q zgd2DDYTW<CiWf7k_->oTcks%UYg`f^K8)k?LF^2XtX9iRdlJl7>YC`(OkWbD%G#&B zf87E=Doc>q9%=s$^Uezu^E<!<2dnjsk~hV0|8zo>H{0(#(yFIZU(C~7MXuE~atokc zZ@%#2ExO}ue7nha!6<%5@BX5{`0ZE54?u3*z-md!1<2>e4}0@1RbK$(1c1sK1MNj1 zb}13)S3Np~#}7ST&C}O%?`gOpPT@_2&pYGzgBgbtbthZ^+^p4`J@pXBQHds*qLVl% z#<*ci0x~5PJv$Mz6H+=p1rA^hR)vQ|i2Y>GJ8kuNBa~5EgqeW>C}NH{Eh!n}i2>}h zmv{d{G7|uHHpZBtMcmX_&|Ol(Mc{)3jU&!G=EU|-oEyO@;5_tD7(itKqInir;5-Rc zK6_A7(?{{4X(T@LxEWWR@>we6q!yWzXNlT$7r>etb@UEJgJ$X_Kkg88-l^MJ`jm+9 zPzcUiG=1aUa-2F<<xduwc~UeU+2mV%F7_7yO|2@+;X9cTWTZr3qUR4hpIS3mgO=u+ z6hjh`)#jPtcGuRjjTy%U7q-EJDN59qLtJKf@T#j>`OtIdR6Y@xmv5U*#BRAh(HpR@ z_6%HNcd?NK7CZH5L#>o8ano%w*pUS=!Arq}&!-fLbI-afUFQu&E>cBMG`ueMk39eL zWQB2h@C6`G#&ErKa?SbP*iu5tA+;M;6?HVxTE>>Bq{Q0TLrPg9<!rO86p<qxN+bq= z8AKP#ndDmX2<K;fTe_8$q!-;K?Nn%+omYOOKJC-ZFYEO-L9hS{WQi@IIgmBrww9HW zSPmDhOC0vpaar7`O*c+dMby{70Wbm1s`gl&(Z*NZ8$dM^y|np6^2CR;Sy}NT_Da%G zGfvrh>1_|qgQ?88MoMCK6-*S_?rg@r5C$bxq1yI0&R3zSDn;aSSX9UVa5g;c8pE^V zMBo?;m_PC$XA<f!UPTUn0ivE5%q4+EGvRmx#%lB=wIt5a0Z{%d?S=H{HtGNG87GrJ zre;^Zd$!dbb_~u=?Q2SW`Z9<`xGgEdDF?JpvK*TIg9*fV8CSyhF94!sei9i>j`Bo> zqu`4q;jo7WD}ufQuH<<W`NK9a_%z6Th<EyH(ThB{xQrl9O60;$1X;)uFx`q8{{SE6 zc1RH|!47)Gxd>R0rbMVP@hbE1+kj*RIU#NYGw&M}L1^e5b1;#Mu96RyQkA4_1*whE zA`I`$F%bWuXHX>b4nc-uMxS7(9th$Oe{3QtuWT_VcuI;tN@$d>=!94Nxziz?QjZiO zC0hM!6Os&B5{1RaI9N0zW(f32QGT*Saq1XX4n`evsi+@T!&w=P!Z!cKor;5d)ZyO> zf`?B0104Jy$90r5M2Mj78!O`1TFNF9NkJrkn>5bJ)<O&q{!MJZD#`37;y3o~5i{^3 zi0`W8w*IWki&KPBQtl9d7}_!}&iqGrVtJAAt!i#uq6jzocT4UW=SjNoNNLD8nR0;R zY+$126AM&3*vTU+g2df9H^M|DV&o-MGf6@H!oJ-&lWW}^%0Qge5ws0dStrv;W_;7p z_u%iG5UCG0oTZbMPRD;X+~*K0SrBi`BPkHgsCVuYQNmF(hY3X%KwUP}k|gjb#~>Ov z(U-}MT!mH=2~>74htsQxRGS3BMt87*x11HC9uZZ<KgLO&a4i3onD*$-K-f_wZdQjX z_^8A_4yC-UY9xP;^vH|60>15C<TY=!2+f>jlfEEyCG{xBKTdIyd{CnarF3jPf_T(@ z`U5ax1(ikiTCP8M1!pf!jYZ8d&dT&`p$Hj?KiZK9uUr<jU@|ISpUICG-R>|1Y29z5 zquG+2E-&V!%tY$J55vMOD@Ni+aW4WsXBh~%8Nov#xz<dZ+)<&rqw4`*20wiggpxTk zr#!3EOj5ODV$`B3F1ev9Q&2NT#ED;SOTyedVwFr0{0C3Lo4%{*w6I|E6BQSSP@{p? zB!?*FcJsTDacqntn`-BFT7p%d2CX`AdY()Ol24Ni3OoNc#K&@KOPzXzSi%{pQ~=gc z5O|nsLioZ*Kj`?sJX&O14{DG(tSd07%)=Wh?utFkaZ`<agn_rJNQ(WIy`F|i!g%t~ zhsx!sf0W}>Y^w;C8$*@lOzf~Hu`BP?k&kjrud(jQQkz|@5t@CcCKhSWKkxzHnaQI~ z`HRr(-0YJCEz-cqt%{3~CXv=%w0-pnUpe56m^_&icx}E4gPTzq25(j<VulA<`hp#C zWRoNjF;bIUB52F(g)_sIvptg+04h&KJER&4LOaS#Xl-nE25IzC1l+3t1j31kZ87NP znU^XJZPf<^?o}RL!%6WbK9s!Nds-WSO6*J6P_6$@gWy4~J*y_3K!deK#72yk-uXp_ z@ohz=rNov9Io3CUs8=^~=%8SD!kq)jt68WBf{b%ZCtfm?yqIrnTf`H>noht;5+81W z<G<+6*m8Jf6Uk)c$h9*vn@*z2leF&NI;IHa0znAeG6m#==y%36h)C^-F|A?F*v(6G z&BcfVaS`80hP2Tpg~bSY7sm+heDh>w7dUm^&=F!lPNu{R6>{}$iqvz9)wE{jq+Ic~ zn=U($ac(0i%W?Kis1hO`S4A7-PL0uzp0=xmLpV$I%SyblR5`%hBzKqlYO<oiv=R?Y z&6q=L!fTWFZsQ+pD2rR)o)W|euRG+`m$&~o?Vfc^!@Pi}$f5F4zM#x3C6y7hkb#Yp zJ+M3@nK7a}_xZh{;bR<_VYoyvVa9cx%opB4J5Ca^kN{+3D{R3@Pm;loe+&lrjOj<? zJ%04;LY3eLp<F{3cd}=wg=G2Yu&B-g2xIH%^G*?_FOp);tEj#@&OZreC=(9e$!9SQ zYM}HnLZfH>-25BL|4JMhLD0<mX$X?26;yad>(LFi{lQMW*F^LLHi*?{6(Cbw1!W`| z(K*HK-PGbK2I6$Y$dyD|c!W9R!^t%USS+CbO$0I2)`JM!$+gVl^&L)lMa!H-IdlTa zwV+mY7K)(BW0eR3R+L1*RaB^-b^QO`O`ueSX^1<3hX0+6JYWYnTpiPa3soq|_k6=Y z90K&<n?)?0TbRTAu^AJZM7@!Oy!fE!F~<1pLOsA4+7MQX;E_qp0RW~QsO_OfwAMRJ zLqSxW1wKVb8HD-a+hDxIJ5Zkv6@^X=1V!mk)|AC8z(b#?L_s0kaTo_!2w+usgCk}H zVC)<hy`hra$|MjNC#FWJO$2fQ#w$W$B_zpPfZbc53E=qPRrOa_unR=c!xd3MG~~l1 zT38Uhp+#s=|LNdA{F{HBg*}MkO%MYMw$C?U1G@|cn@xu&6hcy*lahFYDN+aNxQ!Gx zj&tGHhLA-tFoPfN5j~-T#*zQjr5OkJRSpwf2SP~1z3dlP5yWmqAiO<O<w!>_>5)$y z7l9E3$+X`^P=QCRQ1rOQL}(*MBn25xo!>17*4POyS_CveMqU_+TdkVpeZyWz9!@-& z4gMKL;GSE&lJ=$H0f`MoP0o{nAJ@EuJV>2A?3Qa3&frYMlfW0rEW)CRp+v!hIUyuC z;95ayghcX=Oa{QcFy%(n0~1Kt)YuzOwBmOa9tMI|jcg&<2@^oA1mZDCE~x}dmc*cF z!a6ia3Zew!tOHnRTWatnFIEon1sQPhlruSyK=Kn(AW1xO4a8JWq6OP|n8QD&L^&Q% zA@t%&6k$oY1ILMF^@;zOU(gsqsFO`x<?!4c@2HJUhE_j(3MjCnQYgt_n1U~wOJ3j% z^R=Mf{6mpd1lrw8J_rLY5l;Jcl#=|z_=TizVg+URgJwz(Mc7Mpxeu5uW~<y(r43kP zLW4;#92Nu%g#qM6;KLosgx*L)w5(cVmR~*y0xWQYX09ei{18v#gt2@|{H$kn^pFoe z$6A&|Fb<|#pbgbfPHkqyI8cK^tzi$g$@c{wMU2C{oWzz`mJo@};|*s<l+|+r97kFh zsX$~*1_(i1W&kt`Ck_TVghPjBgi6Y1Nwio$WL7g~gcxcAXj}s~ki|a2D0Kp6QSPX9 z-qK*Om3|2xFs1(lHH43H4#fQIMIok*N?52?ot{ZVL^&v^{JiDUyvERMLyJa>+X#YZ z2Bh2EL4;Vz2L;NiiIM9$%T-uSf32pE!e3^!-LVve<=G%pz^3`dhdg{l6MTd+UIcVC z<Q#pH4c(<hm=1}O1f#;mHD1Jlnh`mKV^oj|EC_;v+}xHC$X@u1EuKU(*g=Y@4Op1U z-gpj5aA#}e9Ax@WohDSza6^k#j#ieAs`*AOBm;`Xr4S8eLqb(YF;TJ&AQvW?Ib@e` zeVRmcSLsb&T$GKBDIT^dLq4qJQ1yd=bRZE81b@0uW~fsDj9VDR5a6g(05AjMja5lB z!yTw3pT7Ut5lY0XsKkfmLvV;#w`|#TRE9#zo&V%RS2EIzX~%NR!$+(^p%%m^lq(}e zs)tAgsX*5VB9=FlDTzI*Q|y8`@W;gx3^v><8x>YpEKYoo$UyW$mr+Eel0-kiYF}Z4 z9WcYoVgzJ3;5bDpPOw8hc#2tYl&3`*b+kjC$<&Y@P>+~{L^7z^fQxZlQUof+fsLa6 z=>%|Lp&@-;_$-HqyolzV#6KM-7wI7$hFp)eNtu4iJcNT!_1DluDjTpYroe;D1^_f@ ztTvH@Z<GV8_^4eSp-70<Q{)3T)C1wV1yvBq2Z0K9MCmQz0koiGR;*Axj6;v4*G)xS zdIkT0L>>{})~9Q+s!EW<Mi$30?gZp|7u`6{<1*cMAqGB}Dn0}eRZvTJaKcr=)nyv) zun3!}o-IXiLOF1pJ%Ndznnd#6+ik*w@VrCMbuRPH=VD~1M5x(V<`;9}452v%Jpij* zN(4o{U7Yex8``EyB<-n84OWPaU8PuQhyzXD?%k{tsld+(Mh4!1uZWSWKZqgnvP5Q} z6~ywdl%}myKol_<i8zR8;B84h)Pr_NZ*JvJj{pX5I&DU1FhMAiPoQV&k_7Jk!|75L zH$4tPbmdW0W=YJ$EE0_1*()f1roxmW8oq|Y(a)YN=j16Xd$@0wrG&F|9ecpWc})KU zJSEw37_di;sJA2p6AR2+u5Qj0Pf#AqH<-g?>20TJ1iq9HRm{UY2*)=R7uw-ojee$~ zmd2u0lX4!=RmKUn*^Zq(V!BEMieSf>ae|4~$<JAyMX+Pn&FY6hP*udnp>)Is;^|&o zOlpLw+^LO(-Yo3eD@NQ(6U2xCBgv%tA3b4A2R6gW5+zl%7{KZoRrrot_yd-_u$<%% zB~QfiDsL2jm$Lu^LCkVfcnUo1!yT%H`m)5<@Z$7D>s9$gj&*SD0M<?H0u>Ad2fKxA z!r>kPGD$>;R1|{l<?<{KM6@*~2my-Ug4aUmCq>wSbIK%XxvS~Tt4X-?M5O;?0Lb%n z(6ijthmjG&2TAZv$dN$ugQ<97a-r>H`9y|53qEu*N(eMmz+U@|6MPQU3?oH&aEhrC zMR<^iKWqaTx`>MXN(1+T9o!m52nWwfjV?2V;l{-`rKV`?#X+R;E#*&@sALzTggHzO zgAPKm*(ahZg&zdMJmg>}qT5x<?@B<!(7c+G;Fklsj5y~JKI}&TAVN&ynzV2+|4zam zu<&ABMXeg)Q&7!1lolbU8@w4wJ{XfH`-at0DEqjuam)tk-NfeDkcn||zLX6U6JRo- zNHlANUW-`(d{zKNLgIZSRH05*h(l#S;6{LjKlBh~XqYdK6f7R-J+A-6EH9axITL)o zg=&c)Jmc}NoKBTd%7}0T-}>N5OORLK!F)gqQmX{MD6|SS)U&=d0%OFX1Oh)$q)G_4 zhHy&&*nuw$4I8-X!k|b>b!TS$gJBylK_C~H9E53xt4Z7~(5V;^!-WmySjeJ;j*ZxO z<HW?l^j{8J<fug0S_CyP!Qi<!@+R&EzsW>=gDVG2c#IQ1#H}_7ScaffYqv{9SPdQ7 zcOKQCRGW`if5n5JMJyptHq6mmU<R7NZ7tg<RzSo%^vFIa$XT~8JXB(g>B1eW1ZK3@ zT438V4qz1u6cszLMR-uI#v4Ly5$z53jgUqyqzI`Pi`wFz*f{?n$Jj(%LWZVs6+~sl zAGjotN<<-eLQS-pX=d+Nm6ujUd84kRSy1sx7>`aEhto*2CxPbRwjk~_E|SY9MHV5c zB*FY}21_<a^}zKp`=bYw#8o^QB$OIF?6<_Rb84`k9!mrb^~_)}cm5~|IpjkjOaeUN z#K2j2t`Q~C1OVd6L<iEio+L$nwon+M_oXbytDU#R0im~e1<=MU3I_8}+y!pEwi#*5 zZb-y9C`Tlbw^wu*coDZ~*ux%phi=1me0a!`9SZdFc!1QMYWVA6DT04Hi=+s`V{ec} z_)f$2c3Bj{Cz)tKrgnArLc3}QtnS6hU8W7$1T0wfJ4pY<c{95v$#N?<2IRC7)X=lr zjX2}9gj%kJOsCEgF`?K<0wg0{8_OriQG#aPs!yn8hGoSaK!!_@2-;lv5-A18n3aiK z^+haQmR#jWKqNjmApIZ(B1{5g9DEa-g|-DlH*{G8D~5~Umpf!&E=Hoa<P)sZPRNih zQ^@<32H8Y7d_gn3q||A$P{bhg5^hI{)zFYQBn3oR{ID8wM!IRg*-d7cRZ&ca$3xkN z3{)ts=g0@VRBUsDr$kDhnYfJvJIsh>gl%PP_>?S}-SIn#7euvI39u?jV7I*A!9(~E zLmRL>{~1`AU-5TzS81b%llL4qTLc^6$(5^bI8gr}n*mMk1VA&ClV^LPP@uBP80kv+ znN%Ql;@R6qU_;v*G#V}jr||>yl2K`Ii8;jGdgF171;97#`H^zC=M`dv)B|AX{&+fz z0Ai5y-FTmSg`gwdZ5FX;TqW+6gUPSU6OQ4}<AgVGLqC8C4SfTL6_!qL14hbZxb2Wl zuz?~QOhM>gJmG6O6bW=H@<jOMTZ~yAkv2dC5IB%vL4yYg`txVbT)%?w5Jr?Zkzz%Q z7cmBa2hpIsjTsNtD>v}jzj_-vHu>jGpgnsa6Aq-Ok)uSH0qPl42y@`Pc?0cjB!^F+ zKb|2Ak|THYs7s;v*i7^XkDI`4?*cGHXjK0oJg!Hv1i<&T;6H)*h#us~#;93=S_z87 zSWd3JodUx_yvdYr+yL(S1{R1lYXG@i|0Q<IQ(@wKkMm6xD306LyMi%i*37iA+s6SG z2T+JFUjQmO(`HmSnyAr1WDh15_?X^2a|Gwzy&O?C=zl)J%@(~`;m@3%LT}#swPsnj zXf+1lcjqnifz}0nyFL~+=I*`+Hi!6`ps(Z-eX$WY67;}v;q3j>{axam^UCpq^tv~* zOL5>z3jix|yvonO0}a{>pCpFkYcH4JbI&C93S;V{gCv`XA$i0K;Fx~q;m4#4LE>ko zfs_iMngG6e2OjJ)a;Z23FPe&+LIVGoXPk)O5~!YS&?2#{0Ln@2qP_0J4W!!!%CHcu znv19=d<c7pEB-M0gF*}85l60qUZN4GF!^DrN&1+=QlM-m+fmFn#SD(7H0|jzfYR!z zM>~Q32~&*SXH!#e_^9m=(r6(dy@t?>NN*yBDpeACmoB}7fRq3U0i=Z9mEHuTHvvNg z0YyZb$PbYw0v3v(h$x%?-fy1g&7M88zQCF_bI;ssuIo5uw1W21su;jkK!ryKhgU@6 zmIZhCeL(bN!QqIKTW_QAI&HU<CdBV5Cw^5BGf#Lq*(t2+uN5wHE!^yZU`o@5kb&lH zpf|VX@8hs0G1(5rPCzRDN@dgV><fXydAzq^eaWlT4##x^t0nKOz458mNRtzbgaQ;y zt#^uR0hMelELNXFV)#*S)n2P_C&Qm+W$EAPI*UwR{kAV0+ExNm2>BY^P-Xw@B7~+T zsH8^xW9qapv`qS$0_+9eX9I%z(vtwr4!B0CAw5#@fzXMKlog_!|1jG)`+%7_J~hd` z$}{LhITd{>6<tn3=KhfrEsM_CntBv&?_>SaPx;U1hdUtG$?a;#4dUBQo0p<uHOhZ> z_^*RHID8ZT0qVAZ&>Uaehn#E;#gi!MDAi{#D-SZA`gWnO4<Hiw&93yO-Q6UL2D^~Z zMS`kRaQ^0-OJZkzTX<B~uyCPI=*Q>4GJ?lqZQn(3=))`W*R5-V&UWkP6220|^&=NO z+O7)}`{yAivZR_ylcaA=2tO*xy%pLOW%zRuFz~w5G}RgMnV0hO=+<<V)CJTDHR7l~ zq2JBJEGm_<v7IvTVEDy-`=V$X{<^@a?0;x~=T*`05vw0}gA>mZ8kDCFukCac*2vDh ziJ1^kOlV$r82W9Y8%CX~&*UGiU}gvS+MWU^+re=}(MLcIv+gbF%4(WtiuPc0Y2og{ zJi8`1iO*SoT<}tQ%Q-sVDGYB8Xt|LtjK6^7?kPYu-~J|z%T!ecYZ{HwPkp_sO<S6O zF<^ymlH<RM6cXL*O*<f!<M#aLn_S_W1P4Pa6R%#*`%%Ic##ofzKUpF?R!H%hVcw*Y zt4a+1c?is$ZSyp5eDc^MvUG%~L>4T0D$u}elwBEP5vj)^k|RgebYaFKFe$2|p~v?D z<1SP#h=90mrCHBU-53z)dp$+%G4uQlt?oou3hAy;+v#(EHhKM`KJcwfW_^a&@49D} z#_U<!;Yuoytb0XcS56wz2}jSxI9;V>*_&P(=}k~{I<5hpo!V-Qju;sSnDd!e6HE0t znQm?!q0G5cY?<XL%Xzct5X~{+EJ}@+k6tGG?{wQGL~E+Cu|%rW8xk`ccW>Kvfo}UJ zEX)n+7lyrQC-kOEPY@ml5_9;6ex-gjL_NXSO;&qFWLhn^y4P5S1UrMMWXX*hNw|v~ zxYLTg-!voPw0R`8F|L$^thTOC>5L5M-$E#Jai@CC6}v6li{UPV7_WNHEKn-%O+!-5 zsZ3Kb6}>aacEP_RG*9P0bGBkFdcf;kzRz5B26@^U65B+X+V;kxe>3#e&d12x>U0{k zqsjI(-AEZjlipUd>~Z&3YQ2ZMx-YT$H_`ca_uI{723>B#P`-AgS0Z=D^XkW#MAGea zXWs9~=E{5%yT_?1P6Ptr%HdY`(xL^@i-cJ+{|W}w*D&P<BrPA(K#YELPF(w2YZ$Pm z%~X15&JPWd+NH_GgT0eK8YkBpoL3_0$6Vj(xG|JjfICaX%fGME=I+zhF#nNp2b^K; z-n=k&sw6Pj++EHM)xyZD3P8L#u0ItU+D2Eg<f^w8Uhr4Pm_B2B4+&B3V6Z)MkE}e@ zQ*CIv^R=(TKl{fOTjykl0>_kCsrS&nqh6*^L<(}z<D~|d2Rx5tF0-_rY%b8h!P0M{ z`o;)hm`H5S$a9kwU8dVw#kQWHYPftOlWY3Y9@#UcOLZ9;EAdkp7)&ElAykm@K4Jc9 zOLtRXBcWcRW3$4`a^kF7PCj?;IV|hdrOJrHzDe%~2><qEm#a61>x?AiiA2P_*Efn4 zlE}nIq<_Nf>$a7BoC!ASh0!83oIQC*vs1*<V1W!n@(5Fe4ijtbgzg^^L{Na;HLoNi zlL`UE9v+eVZX(sHir6_cs2EFJEl|NMl8!ITdfI;;Jh_`yc4g7iUC@ITeZ~DU$72dI zDqoX&65~pmrRNruWWI963$zCkrwwk8g~g6pIGCEcTQC_-BRxRb20@fwDI-zq^Yx57 zVg1^?c=K~1Z$v<|D(Y#YA&x^>Cn)@0!NbY%^4^jxM6rn0XQ4hFGpO6cupolTghBO> z*QG?pnzy`;5zgvqdO9LC*Y8KsJJKaGROcPFDf(1K$oz%cjQUIL>rH4=*NEjmGRH#P z;nscaO2*QC9X#T^NN7mw?8)!BNdMco&&PEOCSNz9YX5boAAKR0nTQ8WJ{PCBe~~@0 zy=`yE9ws7;fM-0<NEG0b4U^rflXt%m45^gvnN|GCr9?d^BRHP+n<l3Tp#n%~@h@v3 zzDwG6_t2#`msbVK-=P=cIoCjRHlc#W2HXd?{Gqeex0y!YRv-P&Em#apE;yAz)SlA# z12W5?1~!L&s-9;{7+^JTzN$QTRu$=TS>Ew#`MXYfGLH=J!={g{PsM+|Tz~4Hg{0BR znDoD_(b8v;HVI-L$NbBK^U>$)DwzAyr)Wcg@~lLSrgIKr#&{Wj#RqW!cO)wDB~R~v z^jg1rcvH4N1sGdQus3|!FUUehCk!|ViO6jFj!FYWp4`}(N(7MfST>$&JwE~-pcY*+ z*S?qxQZknW276MM^S~$-pyUN2K>qZN)J_7ww7V;dsjAHMuOp)66vdi_0{TVCbas(V zshU?x;`s-_YXn%}QcX1ukP_)0BK3Yp>i~u=Ewg%s3i|!+G1FF=rZyd3l|5bsng0%` z+}F_g&C*~^YQAk#T1G9&5Lbp_Dn5`tioWgUOqwnTD8oV6>7wm_k?;-V_Cm=u9Hgzk z11uk)(;pTpoc(kFqr8aD2sYH_1&)I136?Ql4{2*u|0OUS3Yt5=xFY}jc3a{vI37De zbrKEfEx~aaZwPG(0}ARGR%tfn++JXaj5lc)g&=!HSB;n4;M;HL52@*lrKU=ZS;Pa4 z>po2aD|mr8;lXP;7ZHhqgX?lE8<i2HU(?`^N~B_^iIA1okXi|T&nkZrTGK5MBa#y7 zwZ;2gK!b1Q8%iW*<8DgZx>7~;UWqp{=ZSeDLNf+yC?~{2&wvWUq9hKE&PU}}1++C@ za???44D0!4D7TkrT=Zqqw%_)Vz-ki|A%#6|VF<1*UHD+cY4t8JlwLqVLLiDF8N?K> z;Hucu>?A$Q0}NE(mJn<fR9F?zcV<qe&1wLeN+4z>BM2N(D1Id~<0%3Dy-Itv_Mbfl zCezgxIw+pugr~Gs5|nlR0}q<i6sb1|{t}YV)x^Aw+h$t{0uu?VA`=pH+17biL;tOF zPgT*7w2>D|0@pevob;r4B;NQ`h|2@BBr}i1kX7tjYyYG+w5+BC7t9uo>zKd0H?0y) zO1^OKjU39*7}Zt!cA3t!>B{K_UrX7(G7&s9K}DW&$<;FAyqElL!c&&;>D}3uU}eB9 za<g9>Sh+XD;$;HpdWi9nz||?Olc^9n$vLFej$O}w^^76UQUcP<#P2vG^lW5x3qB_0 zs_6AY)q7@YRgT_#kH79({Q3G_S|E=64GCYbm<Gn8Z=dN^DL(slThDlG!u(FM57%P} z(=`DJBN|?_3}jPcy3gxQhbrY20gehPD=T`wmm|D;>%6BUx@B|BCuXRhxXw)Z7eP|| zDG4+ehSl6hnh9-HJZ)2GSeSa$B_^~XTL9$A+4LEFQbfzhUFC{+OW6&P3gE%2o{6ws zgnmg65IiwAmiuJHq8;Sk5J#IQ(A?G3+@WARA|<7#rk?uGEVvg`Ju&0kp_eDfc!fNb zrK{&EbyZfc6>^hr^xfXN<jUw;k&ce18{Yt-f9FaIx*=MNQDiy~rQso#tAMh|7HYA0 zx9q7qj6a>96%L?ol1P`QL9uXvB{9<|pOLF<a#$J)ZSrNn&y%ClOcdHdHTeWNjJMT# z<=!Op8$>|_fFHZQ)=b++Cx%(-=8LnKTor$9gwGXn+|Z>4kP_FCvsv=RkN3_h`7TZq zcvfl{(BK=7e!PQG!3YWl{Kx92Z^Xp#W<La;y%6BvszJ!j6oehAemu5jqGZNta;Y&n zeYE_Zyd#>kj%=z7KGXW4BQCt&&0wU>m%dS6Q*FLrCV=?Pz2o9!=(a*%uiA#<52{hv zsKY>ia(_T07pWe<?5ddvRc47O)iQK1O&0Vq3X17QAr5a-*1?@xs<+@y9-I6}F1NI{ z_}Uut4B2uAI};<7WbV6Jyc}-~3u$8(=e7-TgZ`A~G59mz=}~TFBd}rARq36p_gg`! zsY+MDiE#e?gu9YJNTanMP4Iaf;lB&L`-J6isX!eoUwAsg+o$QfX=U(Z@y$iaCj2Nk zkcwUCNJprx%9r|A5R-B+1Bi<}vJ0{Ze#|BZ9Az3?SDGF3!t0D;L^OQnBsv*GKEV~n zHZlxFWu0G1wRfowpJ)wsdOhw^Drd8l8*PtCQSE&ll&{@zyI1begnQ{p-iBuo`+_hp zJPc~3c_3hVyWlr{bx6Bn6BjGL6O+Abo&bwhRQ2cRFACX86qa~PeG$kNeYn6w#B`nR zIR`>ub+MpiylQoa`-6*iu}uG-K-?FBp_QtDXUPT~nhqKF+zRU*oi=V1fvy+1H!+{Y zty1x%yC$tDbuYE*1D$V0;1l|Rh8A9t%2rA$u5<JhKdE`XQ2`rHZPbMg;l`{PYSC~R zh_@m<;dyb{wv`9m3G-O>Gl|-~!N7{WU=N+zRa&Fk+|xnUB@?UD_~Hb2@%}y>pLANi zaw*UGt%BV4T~l7Th(uY&>*bh667KKLRa9JQ>`UaFrl{IYcdk*XYyXrS(n*>uM8*jK zW=;LCQFuF2@b_(GrUZ<6J-`<U*d3e4@T|)PzH9psRv>^ijv)okZWLW<m`6p+SoOi# zb<SCns{+ntnCb)tGAVr%H%O`Uq0z3;bqcy?C#Fhoz9f^k83m>=g}4xY*r0HE&QKr_ z?_Bc|7%TZBqU|-(Zj=$W!B@e7237#*fq9}E>aG<AL$B&C=3&f?RbYx1(hk`t4WwfR z&?%?_5|LCoxPgWye;wyM>I!gr+O;^$M+`<!R+KmAEBh)H*E<&!sg;*cvuT5MxOII_ zNQ?I<s$fJkUo6oLIfiz|Sin&eB8eO#Yu6-Pz2O^`+HTZ_u1J6zwSz1Kzg7|KN~5?` z-RtezMs<rCK<6ybhkAja1;XexcO<I7HYG@$3$tfQ<usTLHG^=crHj^-=9|;^EP4D@ zz(O!pc!5d==El3aew!M}4jOgJ8;`-J^P<@VxbC4^2T;opE~u6?co{YL3t6)+xkqKw zoMGoKZmf|YSy6;s4Uv)1a^AC?9{@^<RLEYCTodR~j7y)mtKUm8qct^aFN1iO5<WK% z5ydh>psQlDBeRcE$<R|ZEi;sVt~E@<1xIV<B1rJ!!<*~HNU?0GqxTuITC_xVR7mB+ zLz(V{Dir1(`|AYl^O`FNtzJE3nkOozAVa&xwgyYpYySf2(2i6>Rx(zdg!rRoqlc=h zv`~~9Fa-dw0kb6VoP*g$skmp}Usbo^aTaU?p`-@VwR)&HW}=X8$9ad<4-egiaz>;I z)LJ;fO^>N|^?))VBV3s4f<4PTJzS2Fs7xkT@~=hV?;~uCC}z+`e=yjO8o)TERb?&$ zVACuK-e{q7?R{2+LY_B)>n<B&8w`D}Abn4o0%utT_4F&<5;Of0=d~1PaNTcLLGkN6 zqwm;<skjkOEA;lVhuygwjB+RY4*uavzX;^e0Q)i3_U~SiQ+u^(DMc^}Cma}<)O1a3 zOZSr*x98K{pGsFhx*$SqQECZT4jvIH9CBdfNv>obf&u}d=w6l-2%uV-5;;nc5Qu9N znDQo=AgDy<4WO>AdW}3cnqfjQdO1@+1HuxWnQQ3F!TA1)k=ZOQVp}LO5pYedJYQG~ zgqwSF+r#hUC~wz;l>Gt8tt$Ve1mUG8=V!pkwmpp|t(X5j=c13jTpbtuYQ;Uv>^Ymz z21W4}RPx673IU@gE@o@5Cr=_*EBX0S`}xGR+rM%!P;^6|+8?bke1C-;&RgVn5ZQ4N z+@k9CTu-E4yJAMiy1Mpwe7OSYBH%7c_~^oyD7YG{!<V@E-{xOYvSvb4Q(l`^Ot_fz z1tU?aid|g=;OxS!PQ?bIl)W`W>L6jw_k*4F#sa{lQCm;$ry|?dS5j;AE6%GMsub8h zE5Sd!qsH4Dcm+={d%XUv-bXhIN<>kQJ{~%9xT2SQcL-T!IUo3(f0gRpvA$*1?2zoZ zMH|Jr*wg20r3EAryC;f+QFNy$W?w7qPi<ncV`WaqqIE?zvo}Q5YMWCAZe#RxjJJ3v zs8S0lyo+P6E@+<fL~LnnWee7bD4!*3bJRNh9X9^t!h_(+J@>ff?9s<3t|&dBum45U zBQnNH8`H?scm`VqZW+xcDr{)`n0}8ALGc%e``-c1rqrAN6R^7}KP5?bZG~b{C!)U< zm$<hM4!s$0y8euDgMD5zd&fR##U&~xg|`UgRg=$;oE@n9aO-OvpM#L;o|Sl&Be9$> zo|5J2L*c0dqKZe~!Q|CY+b-xTdp>b~!`ei}EWfW}zhb|Jt0aCWX-q(xkh4VOMr_l% zOB-P0gG%J~6j+9X{P0H1DH#k~Yb(1Ew7-fyhF;@WAyTc~IR7P6Gm$N1RHB}GB%~a` z*AGTs{4yz1O<tk={_*a~$LApee-`dHv{m%SoW5j;N!fSPFNEp3${z2RtHk`CBG9G2 zUAY-=GoA|KoaOC}*0s*LKbia4sN!Ug)tE-P)uE4Gx92bI&-#f{#`UPLr}v~MBcu(^ zhPZKoxPjEatZb@pKHV&j{wM-6>S);*r4H2)vc6rW@=S=8RwF|#+#y)`@2Vfe8z)?R z2bFxyhkIp1@f&@Lx>vb;wdSC&^Cf%xx86iwWXj{myWK|`srGnVe{l_bd}gi9{CNDy zlku0&5|)2V^zA>7q5bdYA7u*x8&ZPhe}#V-<*nj-FR}~lF&a?epV+v+&Uts@PV)0C z!xu-AV&7N^WN(|sX%^41g<AezaJn&`{hUWHp6TA5RFQ`&g*Ub%^B&<sb*;@bE=MK! z)2?Vit25NTH*kd|e`??(3Db%TWibjD=G^|x8pW@N%RhdUZFbvsD=|U%WJ6y@T7|jL zJdVb*sNO`>v)J=ts%ME$>!fF?Sk$g(nK=0WBhmscMOqvX`u`}>X3@{7v(WtiL|Pio z6)`Vh-Rn}3*DNf8L3GpqBhvC3cI~`@LSZ36F0O>P_1C~BO!{V`^N(#heLlQY6oVT8 z4M;nNJyoV20X{AkJ&n!(BhtRKoODJ)5*2SwmD@j<&y&@l?tA}#L|WD4BNklJ(&&At zuMkat$ER0CmdjjXCbw~ne0+D4mzBsYFS&Xv_+Afme|bmeNZ(9zUA8>I8^3TV(kgG! z0~x^w7$9N)kvd(g#{Y=4qqMZq&WE;Z(4jZBiJUesnzZ-B=H36dNNYp`l+Tm7=)68E zOWh0dycB8wKA3mpxJdsyeCdHgmKMOzX}s1FU?L4`iS$Z4YYuYiV(WMov!WLvtey?) z$vhD|>qKO-*hY#_f!9W=SY5+LnpDru#sirbVw>p-i(Z=<D%%a4nd(1xHnY$W@hy@L zo432iByXd;k^I$STXvA}?iR@zjG2oDUzI~Z6$0+%+`9yC(e^(yyHbT>^9<f{V&t|y z<*A1l%%CW5dl3GWm*@kWnz!AE*-nTF$41q*HbM;V6Y>NQjn|VEs2X%J>;W>`GZAGe z{RaHjAo8R*gQndpksSC78m$MkLc(P#A^k?IPhl5bFfh!;7Q_6MhY8J7NZ&=rPG!;l z#gSibGr2^<1PkFvg#_sqPjTs(2~nG{0y>~30{Q^&OWjt81fLhtq~wn@Wu?H}Kcj8- zn2GsRJi#>Vc5+8m0n`aJIi_J^SIB+9@L+B&GK@tR@WL)!uO9kMP8aZxc?&)arn8_+ z2AAHK&Ts>hb-k!g6R5(WlbirB`8Au1rj(Ap*d+IG)C|X&YnKlo-0$s^PKc!)=~)hE z-pX_6LSl=S<Gf2Fx&%P|@r6Rj%ods=o`;u?paDr~#mtV3RPwAgXWKb?IUslg<~4~m zhWwy5G&LQYtPb3MRAydj)~bB~c5=Z5kbCZVAgy_u*FCX?B~zd$;N{@e?DsEeYUt%l z6}U4rotx_Rm4T^u5nGVo|B38C7|un8BgbJs(dKkQ+E8lU9UbP*%^4~h8Rf-bK;lcX z=6Bt_Ke{^KS%rS+EArQv^LmpWMyI<4<EWq_Pq^9Isd?>k%iLOmb{u(;0b6sh#^RV5 zR^eO!v|MlUyU_^sRq*@2<HZZpiWD6roJ4<f$~}n;E&Bsm%3(%M<3J7*hs^&skrqi` z3A?3FVJ<nqiy2qaT2D~e1`Y@^>6P?%^`CPsA0(?xRl@I0Jm)(*AfoB35En%KQ54r< zioS6bbK%6Oh#FSwluXpDIvtf*C8k+TRk8I>j7djh#eTLC(dX+~*GjS#w`HK5lc!nn z2z)wl1f@xde4&;joDnFsiKd9bgV%zQ@j`;U)H3?lxn{+J=+UUTlyN1sj*L|G8liSM zeYwTw*#*teo2S`Xf$G&<k76Jy2ZvckJy@i-)RvGn%@vii=h+_{l9e6?)4MO_a1K_C ziAAW=Vpo8i-OYMZ{J$A*P?GW|j#DIPX0w#Gsd;AC2+}sPv{snh!o?VZlE;XNb)Obn zV+vThDk0s=LXc;3;?|9V;;9HTd}g%!=FKUp%)7|vB_Fryq#P<QO#GWR9yPVqDV|K4 z_|WFD4W1^e{BvQ9BqvqE!|QeUa}4jJXZdFjAkqQZX}Atx1(IR+Cio0%=@<IwJO->d zw#yJY6`KApWk=_(+AUe&5&x$HJ=w5zTI@vCBNT%K+JM$9kU6guSP7OMl!Yt*!y>=d z><U@FpNi3^X74%`!L*3aw?>?>QXSNxhdBXO$h=1X7zqJ?F3ZN{w|O6zb`AdSVgoni zYgeZpJN-H{ZKK84M8}SaP19zY?P0Tt;g1C@e`odWxt9J-|LP!Y^!}w!C{kZI<qn;i zjlKRR|KA;=t2O6~*`9X3g(4A2r^+`&+xey0;Vpi5zob38=tx99>8_Jb!@exZ{Fz?c z?FDE`pvNBnX#Eg#)v$lhvQiDt8g(Kn*M)tl)N|5n=U1&n%1*PGsAB!&F0D_qymHi( zC=lVHD{0rhY_o#msbIYt@icOZ_>a1z-Rr9VNy*CJX*N{HUvWtimO+_zEAK~(E7zo# zrR}I|#o5;{lIKP)%W67L?v=|Z*SciRBrA>B`bk-3oteKXIUUVmAbapLzh^coU>g&2 z)72~+HK%OmjJAkGQSH5sw>lk<(hbCA4LJE23i6*e+|oGGbVI`B(p(gvxzsaDR_aBp zZQn#wd#650UtvKBX*52trrQiW-ORyS_~s_*znJe)xu9%kbm~(Ft){^8pRMo^q`Tf` zMK?sfR@Dj8m|DjK=xeix<P*x+KRBdDp48Y_?cH1xSV=%~%%~c>affnZ26B$)D&XA> zw_^WGv6<`9IoUzm2fK&NQ_pG8Z%RHEU^qBiVoje8*B3W)^4B`$n0Kr<ak=qato1E_ z$v-_Q*Gd!Q_5Yr+{ceA9XMHuO;m5+LbPo%YeP(<gXM>1td*4`#Yetz$sYLg-n2KL! zx99a_8^1c$;mWlAp2XIH#csX9<;`eGJJzS+o8cd0wLpc~lE)|Elt-_F-s}DM>_TYg zsvXsx#3zUmSnI7DeIp;No8L7E2lP!Osb}*Wsl1xIU?9sj`Z+(yZ6p0#Bldc?n|OYf zAF7#-n)ZK?ZC<GOnW+#Q<}x+I`Skpg5~23~koT9EFZTueHGHI+u$fK#yo8|RpKjI< z%<8YleoTk_*7((Y__+F@@}slA->vD0b|;;!IgzuMucavpmzQ@QQ?M_g^~dlZ-g&OW z-yhotO>I}S*mmi^lXsm)tl5&-w5~OvhaUQ7Zk0Z3jD%<;(k-~i4<}*=YgB929jy@> z3wg@d%CA20rSEioQ+xj7^EI(g<JAg}8u<pl8{I&x-qAUTWgKw4qZ#(*&1&NKKj`ks ztJm|dil@UpV_Qr8&#YHAhPL%XpJthk$T*pCkE44poXRgw(rbnvRaXqC90=V1&PZzi z*ryx!qvTIc&dq7(UjtbC1o}{~7}A5!ai4SaKC;L0y`xpR8~@ANi7z;Aw~h`h;s=Cj z792B%)H<DoS^NL;bJGpsXis=f#0)7W(CZi%9@BpZyW~K9=yoh;KgY}n$A84RU$nUk z?Py@P<1gAALE+X<e<cCOLU}dKZbI=hW2Q|w`Z&D5@~L{#ym3grDN@&m4i@`#k!h>Y z>3)H`i9VV>pHVE54k>C@wU`J1Gj9<C9*5HnE-)HJcss&GL48Rp1natb+!P`DS0VFs zuhV~cx-}A`DhKg1%7LvfT-Oty28-0T@p*7zV|Jzx{!i48N<ZZ$1(OjTtKUG2oCtFH zl)(Eob-v!T1;eo6jLmXSy$!V6Kr&QU-0>_5WQdHHD8eseBAWWr7Ci3Lus=xmWTx9m zs+Ms)uW&anc%YM`SGi!&HxoXb5--M-PE&8cK#I*zNtct;=d@<rm<g6VO?d!g*73p% z3S)xD?WqNBEpZ4Hy5ILv4mjY*l6=8@Bo+YH^&cchec2J@_<VOA8TI#PdXqJ?XG6m8 zu(Z+nkUutpX?Gd9MB#6o9Uek5(J9QEF#IR6xU`?NYdF%kUXo%?cw@dv@4HlndS(%W zc)Y018!|&>cm}c&WdpkPQ^u91K1lpx*YB!Jj)V&B)%SP#Idi47ECWs%R%^|&JxHpy zE+XxDt+n>cB=<A1Jf#rhHL@d3p$Bjh7sK%&r<d?TKVKEd_<PM0U+7@}-b+*<V{`1@ zm}r5TD>kd%>~A=crT;!#l>J&!_N^tSJ{eOPnnL6(37E~eUJ>LqnR?s6Ma(;AzCHo| zf)3}+s3~3~g7T#zGcfhrMdcSbaAr)u3&iD{tsFD3dc+i@qNej0$7>ku$5Rdai`aUY zJ2)Me^Wql3#KuNcV;*Cus!RE9@$>@oR<E1pFWSZf25Iqxr;R8V7Q5rEU@hxX6p^`{ zBkc8O>{(vi=|N7z`!ZBc64yn2adidlFA=Bo<cCh5nQb}Bn74y1e#L+E*1Oo!+}QQ+ z!Nigc%F&BO+$tsa7OYz;FmTQykdQf8fbNqB%dUskYYPU2-g{2g@f}O~6mgr`pa)Zp zns7z^Ud1diDku(FMUADV7H|oL#Bz=5Z#y&oCK(afL(coHAHmX0RI4Kt)45)1%2~oe zBgFxCnQ;g}GyoQjL9`$MEl66AZYNZid(xu8x<z5TZK=yb0&+b<MWUpcOxN2$f(QG# zs@1vM)p<tOd6m@p4Al88*WEp18PW}<v$lsa)o{wz-~cd+EHw^CH*ZBhMyC7aSueR< z^%G$i)qC%+Ro0&i@6z;3D`1Z)TM?0N*Z9Qw0av{hyt}b%x$)syV+B`Jm0DAcT~l3j zQ$tBp(^(@Q7G8dA@_@DsMr9_s7|5&N0DTM5M?+OEDNg{k3W=Hp4G_oBC+%7D<K66) zT~6zKqiv!_`}2qEs*n1c7Nc91N?Mi&T2_`@{-KM3BMhVx-@i(<(BQx)IJ!P(gf=ad z3JH}(Q!B^-6*1J8{;s$)wGtZE=S;T%GUEV+QmvJe*vstqf*$QWnr{r63pW^9XhCqd zGhc6Kx!>Zlg>kR(&H#&dA}?v`q9zh;%Z#JYQzJxybt9SXl2GM)TvLUhrJ8}I2Z7`f z0G$i;<xn8Cs53|l2{J)btGLm~KA;=J(d{%@^RjplX`DD4aFpUIiNh|Dlj!*c4D0=F zo6_#OrVu;Hro73<eG=mg5*9E6CZog(aCA?F=x~Nz3Cle_h~5xiy0JAVaGeua36*W5 zx&r7jr~v6WcRFA$JBLsQXHeW46t@P7@oCocrHk`21C(mAF4&~j-I>;lEl;TxPpF<_ z3;OGPuk>X%)8i0eLPgNqZbv$J^M3=a|5;=TAwG~G@|aGbOO?YVxHv;!SpiKg?Hj%h zv#NNa<V-bYKPc0tMim6q!GR)4eHqR)ook$ir21iQs1C9!(HTUAgnj9Ds=gpQ-Ad`= zb+@c;yO$$su``)?->Xvdr1|!}OmAJUGQ)xQX`Cn55t7OSb^kq+Q@r=b{?5-YjYYcy z5PEo9DJfHk@dyE6m?8rO7|$_uFWczY=;<j~YJ(tZK{7}b0pKEo&YFN$Yt-6n)auR@ z88S5<4T~ayjoL038Nioaz=tl^sATAZ@6$>Ap&hJ%4og6zWk$an)&!A<sGPe#(pfzY zC$O>TVdssP$#jKZ?g@nBVpJn__3<~~r403^#1xNhr{q=KZ$I}%G%a)eexPeU8B%E( zv5zCe)Zt+c<NGr3CKiw1NXAn#IqrP?2*WsoV3<WR;H4O501WdNXohQL;LP)h%t456 z8`!4;a+d^2Faq6fgW=ntktC2*8>9hElQ%<K8AOwgyWEoo2V=mx7?6()G=5DyJwdS- z0k~3M^V!m*Ru9xe2c`n_0V_dN80w$Q_(v}^x!9xah<O)!F8SeIB9r}$y+tLy#MYDk z!B2Pp8%H#JK|E|?@*lhH@5kh#GY-U#Z<6#Pc;Mf^PVXb&`)ly6wdtb+#ve$=A8l{W z2j84FlWTS07Y8&^n3<?G3d98FPX=KTVDp0+#8vQZG)?si4V(Yl8e{tJ&V~UN(xo$O z=9M7%HLxEU?0^BO0H#(#U=Pr=ooG7X$n!Yb#+Mhh6|`J{4ji4a52D8i@#Upc*e5#< zyzU8(v43l7@4ds~@lXpX8YtVJDbn4v-DPe3;y;JtysfB9?Bn}6!}{8S(>M4!a`Dd9 z(9*C)udAVea?&F-EDt~v$onp62p0bs6cPIl#|<_)fLvX97gr8#s0e;Ns#j>CcND}( z{5JlpZRuo&;qZKcT2p}vH%eUzB|2Y|DV;NL2x!)=H)wLT*K0_ZVU3kh0b)m~*K4de zV%b?7UU|W72zl!wS*u+U1x>bpM-h^qjf0N1Vq5|H-V5#TUVmR?rm`_0TI%f&uDtpN z|54`7#r|RT>IYvF<9QjnrScEUH|WLzP{WIZ88g6JbHpmc5C~ijzE-xnld-xVw6uQ- z!ymv;W*9#q;HwzJ!*475Z6C)@8CMa2KfG&4Ja7Iuj{j#pp0rpsdKHn4Tc)b$$fIq{ zqb)OTS;mwumxLpl33I}uX$wIQH}AJ;>eaJW)}l1rJ9Rz(J7+#XzLCDYMlHP-T95c? z`Jqi=LWPe(_2Fh12@<dd(SUE=<lAx}fwi2s^y9W}_-^IRz=seFnBmPCGW|CI9J-G2 zKYk6SV%*2T|9t!O=i9VA9}}j8F|~X412@3j{4P!r;cA@&Z#TVgZ-p>53XE2@sB{ZR zZ_r$4dKa_NX<5jj7c=-NDq8`ue&GxcTe%gBM{EX>Tb_PwDJ3g889s=;<R*5>7-;Ow z?!$k(u^4Cq8hp0gse}a8Kiq4O20fCY>u#fa0{_zCL`TNZQN?}P|E9OU#%KVUc~!>v zeT{*l@%0G#^{DNwR>HLed&DIOO=W2%^nLp`i1hX!B77TEdEg9L59PDKuCz5To%_8z z|17TiT_n?f0UqntP=tfK(?Z=yapW3{UApw8;<$YxFU{HT{`v5J37V$n_8{=i-sn?E zUIh*RRT}>C1G;Ch`5<hTLS6mXTUsf`4?&mDA!pVh$47=E883R-loYUel=>qHm#XZ) zYbU=`cW6RPUw_|SMPyvav^L++YE%f7u(Xgjj8&9ykJQ76OJnHY`3+he>%B2jZD}=p zc5M8S{=cBz)QlzU8^&K~+U}qen@1<M&**Oacj9z$azhg4`Vs1S=ckA1&qy@=FV_7h z4?YsSlc=*9FVH8yoPHgl;RocZXwz}Hum`qeE$)t;&G4e4ZqXRS6-b0?_`mlv^+6hi zwvzEoIcvezYFZ<onzG(`XAIogTs3_^_`9R~zX^$NuHDu`B5|$gj;1GP)j@eG-&}Ka zd&g$zJMaAI`A9!FLthm{Q!w*q_~OrCAPqifFSB`TEdD(6E5z%^=G4dYaPs*mnqd_2 zckbHXdDFl10J!ugeZC7T;|m<)rwW7coBw_R;C<hxPp-m)=|5Uphi@JHJ4Q3^o5JJV z8@3(nl7kJMxz>9Iq5(`u+-124%&bs^S=UN#fym)Gup2sQtXG{zi?Ew|nY`i~&&MSf zC9R$~F<pwZ9)`Isb}bH#hOCk$iq?Em9AtM~$qnB+AeREGDV8dY_i8fzF1B_|D}$NU za&NxDssq+vVkx;O#qPW|f!p-8X}c3_f!3l~u<P;vkNFRA|D(e|_?Ok^rPlka_gA+G z)I2H&PlNCuUu&n^tZs}x*nQur{O+TBJj-iGr9wo<t=B(Q;vrYF`EDe%^GP318rDtC zP_6A)EZF_@TkgK_|CrgQic<}0cbyFBwmS_fzTq(-)f(M>SS)NHQE!VWkg~!w&Pu#6 z`V;Z3Z}7(vAD^|XW#H6j)xduY(ULN96R<xT|L$`t9IcE$y7Nr9W;5#y`lRSET7Y<M zc&q<&X&}Xxq)Fy-m?;n1Td$|QWqyumkN!G2h5Ug0gV0GsmeR?Q)aFboSg387l-ci$ z!h|{Q*0k$!2X0C6d%O1&L~_lj%~T6XzL_E$RiVPHjTHmJ>IdichGb1xafhK6mnP*# zTThHBHAe?P-dJ`dW|P(4k7=LvFv$Cpn0?3G_t)|dqB@JLsyg6J*q?s7Z?KVXx64CD zneO(!dZ8J1QT9rqs`>59AiRQ^fvDn+vf-sjJC`Z_xSlVxhLgaWm?GHSznN@2t#5gx zuv=ginL5jCd$n>jM{hV$;2n1mqRLvp?7$Mn4PzS1!BlmC-Zxaa{}dxS?S|%g-NM%9 z7bK4=*?ZeJ28j6df9kQz(bLo`y{&niUdeXDn7uk&AllkI>VJ#0`{lu{K7Pe;k$B62 z#Tp@R!?FBYElm}+o0%Mm>jHi_6-bJI1)fQd%X^Di?^N<dgIF+D9$-1&#pdp%+i%YD zr7ovHDBeR>eA|z>!nTroo>811^2WbVU`lON*{hOR=cQJarME0NvG=>4%h7eXf8H#< z#`_}AqT~4|W7RG)H4V4a=`yX>@j>-hYtX1L`C#Vf?L3TM@b!Sceh*zFe@kp8Ysp>d zNmfgO8;#w_U5IsmqY3KWO0>mSTfs2?z!+3mZr$KfnmY~I>y`57vav8h$z--%i(n76 z;tF`oaj}zuE}M=2?<5k7U&;ur&=x6)b-#qA?Vdg2-`{%_M_T9q01iI=-{al5`2rgr zy|Gu^fwIS(eSTn6_IbMZ^S{}Fr_e`76G6M!?syulj=o%X%@+mAei#=TUNKH^er;kr zx5w5=K<zTNNi?+^6shjTlqCvFO__q+Q!iVS@`Mk*|81d_TOPG{7fp8uqS&Vik04!0 z3sJ`O%c|8jDoibEeF^tggA$|~#!T*N6~A<-x;eBkW2eA0G2z-%Vl6Zy&|aK!Qlq4U zVmrLmC}w?gFPl+BsXfUQU!~)TNfNWlHXE26SB{}Biv!<P0Tsh@oODyKWhCCdn^W-b zY+m%A@Moe<%-BST7g>c%NJ+*%LpQDO@~72-Dyu^tE7)6C801Wsq$8Apl;;e!&}Ny7 z0t;=bl<gL^+C8frrTeGQtEgoZIDe%`vf>t^VG^H5)u*eo?2K?A`{l5-J4tz{zA|e9 z=2XvsmA|@Zz7U=*EZ`o~+HnREYG#ou<ne3yli9UVO<d2Y+=NXyUK_qdu~l7&CDU?Y z>HoG!2kr@`1_e#zA{Rg@SAv0pcKx}j>78Z!_`B)`lWBLwq)D$v?|#}r0IqUS!DA=x zqVplBVD;w(3p!p}k_L2svt(v)SOrMfP7T}V0-@OjvJU{VOR?@%{9tiKb8JS8`?lO6 zvzMXh!t*qp+qKs`*l+GtX4LDph2`g^YI$hV*&R@5?>n1cRJcuR6c{Q(DmS!_5jcq{ zB&{k4<;!7a(eyn#ulmv|RSP#Qics|Wec)pQ)@r!zoy6W4G`$<4uZGoV!^JiMetQK| zdS>MWI@Be!3%CGi5E9OjP;%Q#)rPX2&e~2MQyG<oYgbw{XA!U$Ldfg3jEW{<q85&4 z`nn_*GcE9H>X^|oml<?BAIAKaqBY%r8Fcx1$3oJ;)TpF*61&(VjiPv8*?@#NAM~7- z83T@(27;8v@%nZ&Cf`RN7+0ZuD-9Q}Ptw#RoMy1Tu$XWXOhl)Q&OQAoEOF+PuoUk+ z)Ba31&}*KY?haYQ?wZsDY?-B(B+KdFI?5I+x=(epO`PSUP`(fK)U1WXdKHigAMw|R zWIvkx)V#$9pK(U}_56A0!I+G{kS~d$|JM*FpU{=phgmbh*pkKAdT!lA+DA@+Qn4ga z)hjt%jeCl4ISh~~CCa&c$6ryLDv&hdYxrzPi+$k~Iwy5O?<x}NDGf;=qN`T6#9C97 z9h<j<Q`OdezyD$Y4y+gaNkKc<XdxR}Q&?J&h-<K#%h%SC(JXj}EjFawt25vbPj`1R zd;f;-_rasbFwW4F>IbS|c-ojT4=S}PKM<!WxNIdPtDUcM9jlw*cm-F>RY@BI*6~SQ z1B<CpO=rF!+;%Yge7)C>s6b_r>LB4|_fD<WR;rvPcXRn|Wh%3H8|A&1Y)4+1h`>KN zeX)laYUzo}CweJKJoIu&lK2f~VuM!Wx}WEM5L;j?SlKY-Cw%~@g8y@O_`t$nor&XW zesJuTfrVmVm7J(*fR4E=jEPz(otSYPQEys9+j2p`V0#sdMtp%dIy(mnV^~n)m9;im z#bUplx2zqc&=T4ZNv029AW;*l#Maxvo19tmAusN4<m}CCJgc72qCIfdvq#_So-;AI zO|OL)hv3p+^&58x%i2e_u1uCGeQa!pnA~jXw-W3swMkpb8rQy4P~*{yz2lA1Md$JB zY`rFrl|`}cnqVsq)7OqJ=mdPn5|G9dz`=ym;HZ28In)8TuD`wu2B;U3ba=|hrZ;7H z-D^XyFWq{aGq(=p5oXO^6u$Yp=4~y%Q~bjXsuwSMS*f=rid4(>-ddI6%~V9Z%kLdy z2p07-cA(~(EKd|2=>v-8!Rg~GO_)=b#EY+CHC^IM1`TQBSw%<VxBd;m{4;ZIZpODN zp-j{mLyJq>O(Uv%Evmi$0Hi3E(_dVK-gAx@OlYyL)99`VI)QHpy}I61S+HL5Ol>(! zkbhv^=jh~FJoj$hZzZTo!_z0lFoJcZhB~?K`iSaALydJGSWiFEC<taoDcj`C31&`_ zG0RLdx~Z}TG@VP*LpQ7br<h0X3jvmuOC-m05SKTevExTL`_tpRO6qq@pB3LUOXbX4 zCr~R0I;il<CJ9-tfmIuTc54L>j9}k#nRs7{C!(JjAwbeWKxvq!#r@2@28qL20_$-L z2k5y>O-5~_rb9|5fQ8J`S#YslcTw~u!Jk6FTu%AV$UCY4Z|schSHgIXXw;5T%f7;T zGt|<!L_u7V9$9NarE(u7SJFrDIY>Xh^4y?iH2vUN-Fjies}TWa7;))Jz{@0-3ZNEZ zs6=cCpaSOU!$V#@P7}*l)22cDsh~OPJl#Op8Qz4$><8R%%gPd)FHnQ#Q5T^Xsm@&W zvd<lURGA1>J%kbL5s3FuREA!URHRbrM+pnnglt4{=>u5x2ESSj+zK#i(}!P>>`v_j z?e`T3q=|gIyf&Q@<6vE`UE}xN%iN|$wQ~m)j-?yU%Bzu}OAk;AMsURyIOl+|ZCXkr z<P`mkUBgVwUX{KC&BcBj!B<-?)qdbW4DOMxTO`ZrKXDm!mygkzbluA15~49Ux+Nev zv?O!I&$U$@KqW~Qae#pxyzpT_&IkJ1Ym%8C`avs30~9*OQuHH@cD&Ik-VvSrYNj@? z#?aMaGPW{v-A(WIRGDE1Ss*GGJCW4M4XU0=5^N*TE8Glpp!|L%|ASiRKY2sZnM4Zp zs6H3ip@AUI0l5_fati|8T_PMYL+|epn{<ph26gHMXj)cYK5wk!OnNGBKv0)?TK!zx z=Pf!la!Sv*(z=L1{sR0UsXn>^Hd2AQVO}qQj3d?{{z1K2MpN${l;u_m9p?wLxL}QG z#+;A2a$tlDLML8$2`8wcuM{P8!vY4HRqx)TdG=Ode+MlcnJ9RW<R}JSP`|thLc>&u z^XG(1e@?Xe^^x(g8%sI#rOAgf7+$S-&>bYbq%711vN{;FaDD}~HzhN@d@u@jbOxye zCF(?i+*F8R`b1|mW<iJe=+erp9drxJ-%%MUq-RdushSUlskG&);~uF;=BoG^eeJ~T zYjqtUz-BUuoRJ{Z1jrXNGam+tlVO2%V@YmRqJr)Hc3soy8T=lv_Fh&7SY+6@fdrjF z_WG5sZJ^Fq)OudY)=O8+zv}T5jBS^4BlJO+<+>Fgq92;*A_ECqgM_AZ4D`KK_$z;* z@E3Zd`PfmaSta&ik6UBUJWudhE+I-!UK}mboycMX{D*w>mag_7cTUApQY~*5I|0GS z%-lHzyUGy5F(!9Up}{i57^JD<Ckv7LW$_4_;Jg}bVX34B^JM)7{z{p5YhXTFTvf`8 z_wSRG8vB#vEX?xfAS=0E4WNZ7@ZBIH=MvFd24XZee_MA^<S9Lg<Iypmt2}YhE5j;j zrtE224Q&^<LlGftFI&}vAU^^&lzDoC18l!Dg0bcIwtN>(D7jIYY_4yz;0FaFa1j_{ z_ym#SUg-YG`gocCm5+gS$1LCh?6oGp!vVGE(xjt0YXS^>C*`?RMFI~_`@#W1DCSt2 zbL+Q3CWj%+-Ik!y!hoMS$-kP$<8*DGl+cMZL1V~<A?ZWR8M2(_DXXJ;S5F`BU|Ba3 z(pCjQ0yDUoPMdT`c(Dikfjhx#0uqiP##dNh=2JXQq24M}@{S#OV|Mu_as`7{MqD-x ziLlFQs}JoUQ5%pv4~)k>qez_3si9vPlc3y&w_hU!tm|HXHR9#N8-Rw?vjPA(yT*J7 zU1>+NqC?Sup}h=qxuTth#dO<H;~jSpp}QdO!GN!KE;f>%Ti@(}<A#xIrh=c2HM%)S zB{>=iAcI#L%I%`nSKe7RMm*QK;~>d@wWR2Enf*+n(u5A4bn{|^JZyFP<nUCH4xM;& z9lV%Y#}i|eTS4$Sg*2KtE)eWI8=!#z;$y;xZ-0dg%0E1jzacsFp&Y?#yJU4!EZMP3 z!K|^gTB4$yg@j3`(rP1!@ecJ2^uq4H%9#QCr#RJvanCFrfq>-rgXAC_k@9I3+*6f5 z4{>i(y?Wk$lE(x~YEqjkpLD$S&}N#PP+`>uwsFoC0kdg(RC}56rW(2gSBqYFKmb;b zRHybp90aOr3whzfurZK$#*YmbcIf6yYiO6?<#fPNU+p6t8B~l?52L<Zk=LZSR^StA zfJP*OS#zCEd97YEjlT>r(D}(cD{g)$F^-h%bqcwN#~>~@W0ba$13PM;?O#c;ef&1i zxHV(Y3D(-S(L%krw!X8D-2sOR<LUYU6|?X>S%LAGG1LRFlQT-@1#!NGa22;4h)A|u z0(+o0@5z`eLp;8}Ww`fapu1TZ`A|4z&BWS_!J%lyNM8}#Ze^}(F^kQ_%)l*3Hfeve z9t??B&R5zoKl%I@s@Sv2nSu{lB0Rf+4?q%3^foaC+XunQd{!^h8O+qe4Xnf{5^b9F z$9j!b5{0;eLm1%^feOSzvf;SV{cTLwf)KsOBJ&gCd62AsO5_CKI00_n2g#Qo?|IpF zLQffQ#PCidCVq7IMp)+M$tMWF58RNr(9p^F8C&mTCOu%w>V23glJQ80m2_jotH_b2 z=+HG6<Q9AiF<Sz8FM-G(2!W*JdyzzLk)2Wzu7HMQ3-nH$f?X;{JvP`ww8*}ScY_$V z5;CjUC|PlcAZYHeURBY5^K`SSmTR;rJ%&sS#6i55z|I(mGmJQ2o)Djs9Np$!X5|~T zE)fiXMm=v{t9HKOD!H7LB#}ZmauLn4<GX1`GxC;Oh=)-NXWuSs?W-;@<3XV9tOz1O zyqqENtAwB(Y9NvjO-fd9`tn+XD-;H8a_OFC*$53mC(lz8!{F2IdJR<Thh%~>I*|nl zGDRR34Z6z2+1Y}hv{)f7C^(2q5uHqOa^Tw6jUILpv+ST5v_gzQ$w@=|CxSH__S&8_ zok?p+P^xP72FpYOTCu1^GBt;TaCd@u+xC617%@cOIS>KyTmqW`Al?;Fu+sOl0+xwM z=qJ8$k-9atT-ciL^#G?EjxsrAGp4lDa>&gBOlq2PKS8UG>ZS_!fu2<Be-fc8*}<gU zHqYdMQ%ESu<PY27e>TI$4CUKH_SU7JQd1cI4Lu*YVJYx)Q=>^_CwQ7);AzowYC{A` zx%dG(=UR*yG4S**E)M#Q_fTj&J9qglu0`G=&I+F>{E$pA(icrFNExa#H`7%JZmykc zbjVA!;hss*s~}wTlZZiNVz|r5JplB>s<m+84^9_Ue?zkU0e9Tj{lv?$-nt=89<XrF zrrUp^G)_+T%R63OR1!8xj%!dlx=TzS0G4hPGjcwA_`{gUbnpHeW)~&&dpB*O)5iIk zeF~xXaX^``gAk|p+La$Z70I@ME1EmW{Q&3-*OWD%X4|=Ar_c1Q_no_Df7~!V*{e#G z_%+$eJDvuS8;}Tl;R`oV%Z<TQIU@1GHh9xDV$>-Sr_npXq<4q?Ue?lj`E7-NPNwuN z<gGPA=RDZA-8MP$=kV&-_9xG!W@5k^G%}K?Nv4)SgFQ$@*SJAYfg(H4FZ|~eMxUB& z(i-M&%SGw(9ool0)iv<LovOWnpO*aOha_;OQO6i3bTCEE_4JoAE?KY;s`K6=32jaw zM%`<N8hc#1A}D9ENHdZaOh9-2=nM(xO1bWM)do)^_DFbb4n4{&ea{GXPmB~F2{m+1 zRKnq-i--#BDP5VrTOOq_dz*XFe&gZspBo`)>n9RSzD1aweEc@$RYhZmG)S0!8;=eM zLPq&4C5d=Z_vv>8%0zzC4QOSLi4>4k?`_2=PZEW~wgws{aMVZG{Iq0=2iuV>G2Par z&kU($Bz|Zh44}hgEl9!(K3ffvNeSXVFS;{zW*EGa1T&hY5tFhH_sM))7t`|#+o0Ke zVMrt{+hxad<lQ4fqbicsox_|l9nlp~N5;eXN1+I&H|jja<1w-30me@HOSWV}shNl0 zs$f&ps)6Ym>tQUj?BD*BaGBkt`)fagB17MJ$9?8MjOc{sKImPv4koC4`aI*P0)RO+ zI!xxUt|2M-CN??0odbc<6lTuhris1cp7@Kk;IBJ}6{?}92j0h@v&wqoMeZ>%cR&_~ z?q85Ij8cMXZroS8cl34lhv-a&7Loa?&#~BS&HoW;#pfH$>d&TZpYZkGt(F)r*|FSs zLuhqqr-V<^RNK2tLjLakY<X_gVlk9PkbKntSRj-_x0dZ@8v6Td{uitLJAez<`>tCF zBKvn#gHVTrukRRZ`thobA>Y6LmfxAFx|J*Kuh!@hx?(ZO_2o?Q>r#iy1&=+3tyTB7 z)}+~(kIT3B6ylXa|Lpu$pN-bVKVJr)yvf;jE$D>8%?gAc{X2XLh4VP&ikRkJ3;d^k zcD(nlaN3*s+7p`=+rP<w!tZL9J_+(on3J#qG<SLMC)^1hqm^5hv1YvUCU!Je5B697 zjq<N~?F?6oubS!VM?4Cd{|jJ1pTBqqnG_OxC7O65iYcnN;!ru|RL(!e(DDi^V-@(& zPZfzpR#~Aqu?Q}$j1|_6MSArLH+j`_kc;*>2px0@mE=!C`G6DCJj75U1RjuR^p7|H z0f;vqi)EU5CYougnbeE*RC9}OHX7N`PF!`xnk@A3!iW=>;KE8lL-sT$p$*+q%s-h0 zu$N9x{^b{x@Q`^BKIF_pPB)MJLrES<v~i3*+<gOL02*z!CaS5bx+<&WWwq6gg#u^O zLi80x-z{)d!3%w}Dx}ImvKnbyD#(~)S%hMaxh%6Gj@i>c{p2IgIN;19PdKPpLB%28 zXjINOhkc1ytL2(|F1qRFL}CEqXwzCj6%{vJP-9ty%PdLw!OL2&^fWKP0ly|MLAZct z*{M4@`sjlpg_P_;<%DC>JJGb{#xCSU_)bj$B%ChDA&WfndimsIQcW_prlXPn0|uaq zE4c7!$t`&jDQuAh(Nav6`9M1^xj-ZK<xVDx7~(<Xyd&v1+O81@b>L7-GSyXEeRXH! z`BRNRuCQF>fVSeI>n&=zGAOVw<NVcF^tqM_MwTTsl24H?45>#SQ;N?)nW{9)B0>m3 zibnH%_m4g7V!b%yjaxkuPKhhYO?+OzA~0=&?qn~GtlZ+`zN65`7DAYtE?lkkvGU5! zAwBD{iw6OQx81Vm-K0H`<I`m1R|PPRJSkC0O&&|&K}<|DiHW;TjywN6^s81TZ8fo| zP9OH!YrlPf0`k;r_qa6D=RpDndUp5Nr@uY>?Yr;(akf<ByRvi>wJ^i~v)gX_NGM-< zk2|PA2`Vgs65XK3guwF;1~pG_(R&~SBUqj$naUivkdNiS=97i^OHXpB0xkZupLqF8 zZELfS+wvp}aB#zc4*UuJ9JN14A*3Gk5Jyb-@efpVstwe5M|WsKrpRd~b`m@y5|ii@ zBF2aox9QD|i1f16>B0%2s}XHXc*3`gjuo`120j>=5XBt@FfojhP3%W0a*)Fw<funX z>VXO>Fkunz_>wm!rNlk*v5!iz%0ILrkP&JyM>LXIpKf8R+mJ3;TXc(U3?>eITt-6V zTFUIs_>-I<%pQ0Vhd8>SLvRpc30&9(HAq4aa8SvQu6!jdZ4#3ItB9j|w|QUtUb7SW z9Hb(+(L)tP(V75gu6yOfB{Gw#y|%FqQ82QH9-Hzc+To8$&_von{xObsyaQ9H$POWx z@tARhqa0$2B|6i2M0SBPNTa(P=JLan9mygVP5=Zh?sUwAoUWg+;mRm5LO;=*@j*w+ zrb=3QkZ@_l9WBWMCoJ?2Zgxza7QN`=OlC5{T<~jfdCiU-nL6<$GHnTQ+u7>#NQhXZ zF1#>@IPwv+OJ=QE%{pf^fg+D?M2Hw~u)!Wa(V>}e1Y#IHDpFacJGupu7b<KGkCGXH z^BohVdIF{{d_z@)oKKlv#U%$-QH&M_U?dA_(o`PQ7yOO?gd@ze-=zG(k9pifQ;@*J z5;~y_napGygGnl21FNQ-j3ioC5?xnVW~as8X;uwk?CNMy1wGs%K=Py~R5{4l&2qN0 zoh8UP_JTO(5wxJxv?glH%C~mm@E-iQ&>pC;hG<lyAKn26NnR+}-SSpF8UbZ7;Iz8N zeiVI<Y@1nda0x{M${+|q=}IGVoG<!JJvO~AHX#JGdf<Z|?vTe}P|<`oSb-Sxcr7`` z5h|kfw!QBCjQw<H6|89GHUtVlBZGxKTmYg9p{UtyjtSD}HYA1gQBD{MyF2DJFRdN1 z-A7`WTC@hhGM#MY|MDTgEUW<%-w2gA)SKG5t@geDCO+{W8yo;`Xag5e^{O$Si$z<t zq6%=}1<VNITwYF9ZOTmDSApzBFqT81>@g!X?`BXMB7{oj7>76N@s0rSkO@rK#d_-z z4#ZHnh$#Ltn1>P)7*&H7tr)I-el=1{pyf~5lhc5?h`j=}v>N%SM?Z|3qJl12e>TC( zcjhrspDv*f%#bN$-r<i^4Y9;wel(<yw!o|q<T$vDF+X|43qLqP7tSRn`fBClug=*w z?Ay^hUoi?^XoE^QEz??Mm}H>%!@DX805i5k1xnmQ(BOE7IU_CXVZ$y&=J-c^^5hn^ z{pvWkuraT&D6F=r6e8QBktmAcFcqtDJ$`=wPLlIC!<{4xALWn-N&Z1R8{{Dyy;dIm zOrl$2(>t)CIt<tP^_E}l_biO~lZ<<Hqt|5bA#c_(eTtEhesoz)e14QqL~D|JbfZ-N z=)@9)z=&D=<1xP$Ps8gi@{4{<FW_L!z7fI@ALk|s|AkpstNoVOoG&8TyX7tHY>s)S z>EYnE37M{9k`B4n9Mssu8eS5|Ri1O?PT%cF1S2CFQJZ}+7PxI*(H|Ed<W>S=U)90x znwW2o=CVkIEVN;ca@6B>tkRzhmpo#N5A=V6p5q#<FpGE4m77l|kE8$2s_AJ%D=3ZX zGSMgSh2VnCX=%kV3#>h_lNx&jZ|-mZcu@_+jY)3lS}N#654pYNL?aK=hz;xEjSdBX z8l6b`9;z{qdXOU=l9IdNm$HT2i>&mC%11FoL6_q^M4pa3B&Yw&qtt1UA##$u%@c1U z8Z~pHnem67(UnP`qw!;&w@ys@L5!AgVLKYZma=%?6eXyCWSg;vHmZROx|n+LX?wn@ zbEO4=s1MZke~4TZoJ1_rz+6s1al`Vc*wsLsg!!2@oeC&@LjcefF?5O?2m?4QP&tr8 z`$0t{bYRH*!<*1W0WQQ7^%C`gPP7qBLF@>?5X@|x4?&Q{&LEECaGx1Hm`{vEIlzd- z)LQGIf)HeZCUk?w{LaLHU{ZYlU;v;&0QA9<C}FFx7+J^yaTT8x9+GbG28}cX{+VEA zF@yj{pKVxSE64&bNCqYC1ka_5gM`}~3WZ6K!#9Y>y5YefBo8=P)2m6LA0UJ#Ac9Rq zp%k78@9>R3<QdltSLc-BkPIJgz=0NAkN|$6^YMsW$XTVmf+$Fm<@Esg-Fl*(TWo z?TL~`biyLoKo-=3xO|*Hgai>4B0}f^9XLS%Z~-lr%L18<j0oHlJyAt`&X3%J=wOjA zWucw8pyhbhjvPoT;6gQIL~{fHC?eGJJPWfN4R#rsl(3gy#6-FgLly|ZBEW>l?IB5! z8#wZw9vs9w?&6wol7-Fx5`Aq2yxc|^vO+4{0wXBbpUj5jWsh8BB1OOxGgbuJVT9@J zTmu=A1Z^J<I#AS^!#n)Xg+M|RyaY5H2DXfY4cbJ=Io%h?<EjWvHub}?6+<le#(wO_ z>fnM*;zBV<A}<irLBxg^x<*A5<XqIB%&`VptlH)=oF^fgA8BJZZX=nzjz;+mJoLkK z@RedTL6^`2UC~5MjKou#%(&EBW!c0GnB=OQ%6xGH*JNTv<dY>Zf?N855$p?Dq)rPu zL^4`ptmN46se<Oo6ku^54WUs&7@IkOLpa35J8;SpECMlLADG|;UI+%G{2d_JL?2iJ zS)SxSn9LiYB`?hXpDNHoJO)4wl%^9%g1^uuR9#;75DZEMiWUCGD8vGyP{y&bSN5UP zQeGD}LQ7%38}Vd;5l8~ZaYs08*?N8Du<>LG1;7*FWPoI5tB}ZMnnN-0!XlhN4G;l$ zlI9FRfhEk}a0TG?q>fLL=M%X?Dhz}yDBNud=5FmKQwGIG(S%IhLvXetD*l7*<(?{x z!uLogtH_N%6jeCH!3-!t8~{QbD8UmDK@I$yR>^`vMjvJs#6XlqF(?N#ff)|MCr`+m zJ$wU<sDv(*V;l&TM(m+Ec;m2j5H2JHfEt&8u1bNz1DLqM3{=4(1V9`Z!H?E}AK-%5 zc%9kZ+-=1F0-XHkEAYZtN#+9e=6ijp4mzN+q=q@ngEvf>KY#-z>;b#&!#$7$O|T22 zEt&$F*iG()N!4hobi_Y=10BqO8$^O`C;=Qm=)SP0K9=E2CSwZ<lQeGLoxM>#oZf_` zDN;EH9FAfU9frwJN%CmKmJH4@&{ba<S+XDtO`RCzxoNq;={M-88w5Zk2!bFSf)WU6 zF>J*sylQiG#jDOLVpW8bvJmPWs>2jf8}=5JTIo(uMu&hGI8Xx~ticixLS5B^;bh=~ zJ)okxm-m3GjhY10%&8k}LL^ASCa7u+kOGToLoqyqQ_)8(IO#JK!?=#CHneL@l><L; zgjdr46iPl?T*>F_P>FKd#EN1`J&Yd}lo#K9WKHzNKi~t1z8Ct?D7B`EwHB2i1OO4x zK^;(R8I-0nK!&)mST#%|H+bc|F3@2l&R_t|H|{H#MH9X<%Qf;uK9mDJl!G_W6@F5} z8Zf~gpaSZJSg5QQK0sw}#b^=)0Ivi~!`dj0D#H}a0Mj<@3<yFv*d|Ps%2gna!(8pQ zMXTV+-LJY;?yMF^kjRyINB|H*7PP@9P{VTY!#8XhcLg3oOy*HFLI8Z~(WZ*lU>`8_ zfg6;88K6O(e%QD11yC3j%7Wm^ZX>_4my=YB?eT*=kmDLO!6|g)0+o{`vExx0!9m#n z?cJ^lV8p33c!M;wor`|1Q2c5dt(Jlv#BquVIQWzh(7_@I+Dtr|V6lbF9K`&guDO7S zN!(f=`fg8j?SoL5d-#KvCR9G4LLg8<9>BsqVBdG>QEv7T=~SjDgeCE+N-HVU>2`1N z8ZSpg4)Pk&NQk4lEy7Qoqddrj5FOM}RhBM^ul-WZ_RWw)KHS`mQI=jy09<4sw1E)h z!2xl{;f&T%!PEUVFa)V?P{iW@=nyqP!V)aOEKoyTJ=v7mk6CIh^mGM6jF1DDa40?) z`ND&XY+yZn12@zaIG_R^;4C4C%SV2&HFX;ValyXim<j)|^W^JpDvPs>2`DE2i<Kmg zJ#dN<$iXLo13YM1IHZ<xj!S_)5W@no7DrF4@mb;i&O3y|`@X|BWx*EI0_stSWOiHF zD#;eVF&y)R7wce8P)Y46S^#tdIWmDCK!fetLphNPyHqV9#<3x9an}Y$UeIA^{R1&T z!Vva>V`xM;j6=ud1V8Y@A#bu4Gb%z%q?16$sRU0#J@N$;!ZPqx^}>TV1b~d-7bnMZ z0~^$@HpqM>4LM9IHTXexKmsvz1N<UjPG+$z7jpwA?sW|fV&Ew7#6$oT>mIbh66672 zF$1i6504qMHruc23Z^NF$!}VSKLG3-Gy)p(!dwVQer+>5`)-5*CL1RI4n7=bObE~t zT!0k}f=m{JEnIUu|8w_dQlq|MtQ}2AzymnQ!#v=^E#yHKXaEun!YCAjOo{@4R@Jlu zv_@0wuSQ)yWU@9K!$Dl9D71tP-~b~`bUwAhD9lGjZ!}E1DPVp~HI$Dih(asSWGJ*m z3M_#i*ur%Js9ZFsuf()bn<Ssz=y<d;esP6dgu*_L!XRXU1w^zh0JW;kSgbbZQFk>6 z?yrOV7AQRf3Yy?rwn8Z6v`oH%6~sUm=mAjkLRJT(SJ(9}KFL2Q!y)uR9RxtBHnmT_ zf?VKND_r$wjshX1fC?0lCtN3uq{2SgwPe?uCp*eN?1B=E<yeycW`yR+aCuEHwE|A# zv@Q5TF`xn=sK8=3!bBs(R;0p9Pqu7RwuAUXuq8wnu-|T2Vc4xsLC$I@Ty^lJwgy-M zA?!0Rhytd~Hgkg@9R$D)TtZ8dr=K1OeYAqA*#a^ImqTX&4D10VQ1k_f0#`S;c@tX{ z>_nah04d~?Dx8_+=~%7!3s<zpdQ!A#3l0qUK_jSZK8Zp$pSOV5TMaBiFU=%^*ClZH zi;&nzCekD>P(l{ifDmYbCA<PfyMkQALM(JpY!5hyzgHAEfiA*<92|rtVCE<wxJ=5+ zdjn{V$b~KBw7NDz9>hQjWPvBxf|I^NDwtGJhq#cdlQiuAUP44HPdxWQkhqP>fgdnJ zBZLC1BDgQjg<y*URMVs-Sb-2&Kt6|pFUX`nFLy)?xtT){#3(^}b8bRVbO6vo0L;Qc z9D*Li0T*zA6F7kpI6)P}fs?zXB?uqsKwe=(b*r|*AiRL!FoGo%12W_jVzud11*1WH z+L>Q^<3s~bOhEt`BMJt9O!kB%AOax3fg9vGs&j!BoOl2*I%XE6aJMQUfIt%rp(RYT zE%=7$)Ga~&B&Pp*<J|T^0Ky>{_&OJ4>d-}u@-8miWGGyMBpgH^zyY4)z!4ll74%1| z(`^92g8U#hAyj}4EJ1iWX+OtBK?1wFUk#O17urbw`Uv+VuLny`CxmE+LMTXrB$Rp_ zQ~@sH077U%02IO`paLcQ6buZ)8?=IWr}I%1)4E5znMlfw23sgZCszbHv-MKibo{3V zpi|4_XJYv!K>Hy8f|BFn5wL+5WWfelz)3Uuir0zDNW9ITNk=G(E%=M^0mZ>}Zru)c zES#a6733|jxJ<f2C|JTJ82CZlK^;T^42-}CG{F(TK>#!YX5Msp+k}7+^Ua67iG+%z zpdiZ>g~ktavWwv;I0T>|eJtSnK}35SBmoXEZF<LniI3(@<3|Z?woQ!Y36Mh9i@o80 zMj;P#Q9!)PUE<65O94_F^(7<H;{q)(0wHYw01b>l4X}Y5gn=%S_)gq9oY%mxFS$*e zz~QgHXE+dKi$?nhS!~!}y*E2A#{gs80U~$;BCt9xLP0KS0TI|lWd^_>9z+c+*G02F z^E<_<ToSMhb>UNm!A)MD9%NzDLMVJDDu}`oyZ{xj;<GnHFCYYi?gSC6fDyof9z?7R zNJ5NGfAi1(QFvb6zKm%MBo?KoYlIa*sA@IPRzYONMiI)B0Y(-fmPXkshAcpUGZh24 zfzt*Dj3h>CRAhybWJ!}JQKnS6l4VPmFJZ=%Ig@5hn>TUh)VY&qPoF=52C!$3B)5vM z0;mewQkBxAO`*DSB}<l6R##cQYBg&A)K*cgeDNxVD-R(U8LYhVgCu~OLw@w=0R(7} z940IRc;Z#j)l$EI0S6X5m~dgkhY=@k*-G(AsgGSjRR#I6Dy^+vSsuuX7p`K2vMix7 zBMOo>e*DapD=1`@QK<%AZ9JQHZQHkT=hnR&WmcrMB|nusyy;b~vTzM#+^U!@E;3}$ zpkV~Z4J~rygqdN5$_8GcYy}v}n|yim=h3HE9~2%ue<a73mn|Oae5zEfYQ;E%$de~E zYJiS~3}y&m1RC<d#g<ThThGA<A&gMM2?HDIByB{BZ@2j}97#4-q~c2zRxo3%h5`c! zNkt;IU_=yLy26aY8ELH1#v5z@wD6y!%xkJ5;^5QJvWjjAU=fTCNs^>nXbC_@9HER- z$|<Q#Y?LT{e5J3Hs>-U$FTo5`%rQ}FkIXaCOjFG@X&lPJio{`4&N=C<(@wzJ8_JwJ z`RvorKLHI?&_M|;G|e~-O;piE8NKbzMj?$<(n)`Ml+sHv%~aD(IqlTbPeBb;)KN(- z)zni_O;y!ZS#8zTS7D7+)>&z-)z({a%~jW3dF|ELUx5u)*kOq+*4Sf_O;*`unQhkD zXQ7Q&+G(k+*4k^a%~soOx$V~5Z@~>$+;Pb**W7c_O;_D@*=^U|cj1j!-g)V**WP>a z%~#)j`R&)=e*q3y;DHJMF4*9M5l&d)g&A(x;fEoPSmKE(uGr#>G0s@yjXCbv<BvfO zS>%yPF4^RhQBGOqm051t<(CDu6k9U`pcz?zaDFd<oOOn&J)3*_86IzO_ES%D>T!o3 zcgU&79(>NT=bxnCsmC01gw9&)p?}2(pL(no2b{6Teh24&{wca8p=)OQrmeZwb|`Ve z;ieptv>tOPuluQon|!pX#vE<>>BnoCXFIwdceMFi8?Y-HD(|){a@$s~E2`(8alk?Q z9(nHhT%Lcz**S8eP68Tknt@hn^{u6SbEtB-LHi$g4tFz8d)#i_M!x^iMw@+-aVDK# z*Z~}E%!NYzFgNZ0xq9kq#97CgWcCrh9Ix?_JnzYAg?^}f!jVTFY8ny3A&2sSCV+bA zd5?L#e{LIg%4f>je*L3m-s^Y%;fp!gp&9;ohd9I`G|AylN<%@LIl_^TS|D#7>tIJZ zG{FsVa079Lu~a`umk)Q8A|32t$1gVVk9=^$AMo&A{VbO&3;E+4{~$&inh*$Lpn`|Q zphOe!01kgN&3R>dUEFN)x@#HmAGN>&EDT|Xa{L2?FC1F^Y}C7<`J;C0NCpUtQ4D-k zFB$(}Ax7qB7zh4C9OV#UI@U48+NlE+H7p13ju=B(=_w!dpvOOskp)!nqaL9%<URgD zi8Xv90N(ijM-l0#Ke$y6iAJPk9(|{*z2O6Zu$Y4e@zIMvU}GFE#G@4{8KFrA;A-5c z-8D)PyuX=I8~#{_Cj7=hdz9mDiUFG|+fj;rxRRIwXh$O4;Yyq-F;`x@+C2WT2P#a_ z8}c9rIS^=$adg9mYv|lO$kD<5G1DcgV;eb-1-*)xV}<ybLoc}T4R^qU4Y1f;d%UK_ z8S%_^Y4gVh+X0Hcu`?g}xSBiuVG4Hi<8l8;<6sJkwt^xw8S4<oHUgkR5#nPS>*xnL z^5IXk@l0*Gf(Je3kq<afq95~cWJ%D*j~WtVk>;4k(9l*9l9F_1JhRD8ftoXC^)mqP z;07%J{;-XAye|NgC<H#n!B2m_r=$`x)6cF}j{q2@qW?JHo_fj+bF{-0?J(*Y8w0_A z>>?S-G)fEM;YxcXVjpHS-70hC4@d5S68-=OJ@}#1p6OH`_@F5`#&J!PU=oWmVQlQ| z@t$%Bq8Hd$YDRs*22QSyfe=!l__zU%d}JdT-`Jo(b`*fZ3D1_L7@Rml`cS{Tsc_uT zhC58Lj}__?Y{GlTK1$IJ+fovh7|G<ShQbeM>Y@q%=!QIqQn<|3gO}!LV@hYyTyF%n zB#gacB~yn*?}FD@(7RejVPS`VY=esMFzO#*@r`%ju6uZ#+;Mf2H$1MkmX+8CK3MDj zk4=ih9PY@6e^)4!(-j7U+V}@Mk|7Sa?v9-ZRcJrTaW%YlmQ`1~+7xNJGe26&yyhrJ zJpi}|R0KdCU>zsy_{S2~ZOw{$T-Mb9XopGs<Bq%oASVK#RQle}L0a>kP=5B{Sh`~z z;wYtuJ<N}Pcrkb$bkjP;@egPOL%#nwZ}ZURU<lWP9B}<vaq)Yq^Xl~<O&|u3-y_|W zV9u*dKrG~p>s_C5?X$ZB-?F@hGj3qx56$R@Kk^9=Y+&OK1st*|clV&H8ku+g2**Eu zq1)Qs4kK5?TsZ0higs*J9FPo5ZU0t^YxtvasI{V6b88N<?hKuuBJxR;n~y{PK!S9= zbcsB;IfzBP!yEI+GygVR&he7>Sj^i-FYe&g%i@f^PTi3U$62!o?R2F6&}Keh8A7!c z)N5#yD{x1>>A~c5tNGYRF!FI(!Jf^GV$Fsr0ubP!R`pZ+P8~h!QH|yXfFJx|XBydE zk(k~T983sD!RO7>o(9z=IJ3t%#$k?b_j5-+Z5HO<K@RwOBX0luhaw8G-lA!Aq&=1N z>TGL{O0*;2EKKdu)V2+O1S5IxxSBY9@}|E{V;cW(hjpcPy17X>q5J3u*35isPjMD# zC+=Jms1X2T2OxJUfnJsg5r}^<vU%f$i2>hNk9mkA>d^ah%<K`4aBvU*YPkutKNt-S zjA8_AsBOj^wm}Z}fbHjaeEI9doQwi1({e(EEtSI|;4cRTXH(4WKlqXHOJ*(c1>Rt? zJC#S1l;hH;z{5M{!4H0~#F_s9M-w`?PORMz^e3_OKd3Q_T~Nc)aP4XB|KyKx*v{K7 z&W#%<@dvLax^V8r1{=P?!WQmN+n$9qR+-+_wz-{aJTs^}f&q<u5LmWAF}H)m-D&|p z4IjG`v^e%*igz4Pmx+FRroI=$p~zz%;GhCEY>K;-&eR6brT$?N0)ZcjZIx=x_AU(= z)JF(}fEfZHs@QFlY%KULtrj@p8(a-H-h>?f!Kui>=VmXT-T@o`3ZWJ@r+LK3@X%w% zwB~9SN7OJR>KZGf>Mb8M!5U;~!Th4O9IO=B0l)~SA700{{9zhMfgcd4lo}9IB<a@p zj~bYObLL?lstV|u$9&$Q;i_RCpv%7W>?Gb~bZ*FO{s9%*z#h!UJvQ(D>?F{BtPl(# z2<(6x0O-nYqjuQ97x1C@@F@`CfgGSs4^8leIBYjwr`%}iAEsd$HYlTzkiOo82K&L4 z+#&wLA;8M7C+6lK0;+EisK!hQXC`qUKml-K&lEGTQS!)p5{;KSXAgMI_(;su)F}Wu zXAMvR9>yVej_k$$40<%DbEtqA!l4_w0UszK5b9wZ3WxjufbUFRaAz*fsWhk=umBob zkR-ZJFm_SlzF`iU!5k2+zM5~Tb|DYv%hTGAv&h4za;DpC3%9Z%07_A)rV1k@Dj(`0 zACiF`P%NTSYbnrXiaM$vE-kh8&D+GG9{K@$XeS>g&fhX+ry@?OvhW|OfePNie2A(g zhzcH{2^H2L03s-)b|h_F?jm_=^$c(iKB08f&Km-N3XZ`Znx@+xl1~b%sJOus{s6^N zkkPQA{YEk|g7O{8K@l(^v;v@@&L*t3VGevDZ6eC$genGU%pUq7-|~SSOu^^~%sq+` zbsUV!j*h?xa3|KtC^8Kn!V)7)aVRv=94ZQMnol18<%HQvf(s)F#)c-*_yM}`;1k~A z8@LN>Walk+ksSVL4RpaIZwiJ)&kWtr8|tA6n1PD=0i^=qhQ#3;=D`(na1H}80I*>W z^v-O^0Usto5&WSX#)0eVE-^rE8x(;P%)x9ljJ{e38~$Mq><JzUZwkwU+c*wwENmYf zGau+pBVSSzK>?xIX(@Ap-5#iR?u~rd2_u3krvMTkR1x#CbE;5FJ+<>j)P^~$N~*Zi zc1YqqAF>{aPwV)B8mK_45>5vd?jT`GK<VKd>Hz^2aCC@IXYLa}15_UBfu_s>9GZr@ zz`-1R@gEAyBGr>R>7<`TkSNy+Bi`XEfua5X{82yy;~&vxXqw>;uwm~i!XR-5q!eMt z(9s`gltBlJH<;7hxWOIBsvSB}s;HCQHs~EpAsf6bI}wtW%E1~m;RnTY-@;5AyrHbz z>L=3#s0NcJG}7NR)EV)B7n_D8{?jDVl;G&$9jp-bw9w<KluJn>9LymZFAi+bMzjKf z*BX-I`h?xK;VQEdIl=1L{@@#MisK4ndFrkippU(9)BExP9s-CB*2_IOv>(+2sDLyd zmLb9#r`vRpJ?WE`yt6DDhb2{XC(iF55}_U3sy;n6tT1F6rqq>uQsTm-K}TvFqzv-_ zQzhu}J`3?5)_@q?Yd!;1CFZl>z##ztunvCc%_Mx)cKitA>`d#V25rnI9IntLxywWE zB&RG@8SFr*rjkR;K^)ki83wUE0mD%NXf{W5U2{sKP^%Z_AX9aeRUNWN84>3GMiba! zR*5l_CUHpRs#SU7m)xxs++j<PO_KO)6HB3P&PZ!k?@L}sY5*tznBf@Eh8*^c0e=Q( zvXFC_ASB~dCq{=7@W8LG$!7S>FEIk8@&N(s0VjpVrSc&V7U3V}fgZj~4(CLEIAIbj zYf`!B<P^bS6NA0}V8?KC(yq!Mn&A(ifg9iuXY=dKP6;ggVT0V^I^O{wzzQ`@0)Y^U z=&G!Ff-ZUr3=)ej9MJO7R_UPs%t6#jar@k4nT8cg`plH_0UScdA=Kv{oDg*^MFufx zDBi;Wd6xeyjt^ntO;U=cT&QMqaFretT47Ijeg<qv5BA7G^>8r8<^<%P4;vy+XYk=} z@Qw`zHEqJNLfB8xw!sd1f$f5`W-!pG3V{=DM-VY{aA$+kgwB@ADD!5I8dI}*{wAO# z4Cyd;Cf<a3!gJ?{)WL4&h`cAOI7%H3clNI6?o0<a1=ISx=LLrXn!uqAh(Y6sfd)`v z9_~SY>g#kebMuCxX<je#Bv)s~5sm6=dvjCk9H|LNmX`+cag!Ga;pZJ-FBszydWH}7 z0IofPGt$Teaw*B=kjfnY1W#wqt3>~x7nCX;4}*Ei0UB&~{t8cc+0VVU;SYA9%+~M7 zrZ;T0X0`sItBwwRkBB5LHW`>ygOaW%(8htH;TOK4aTaTJoar|oOjL<0aPhN!Cj@T1 z=bDlg9K4|$Qfdi+fz0T^bucN>0yrOtfeJ{6s@9Jscm{Dg@)Pzzxr{b$yekC%0TRTn zbLv58yyimt)aZypfvAs7uIhixK@p->Mp<c3N)#3ZAx>OaG4KIhn>KiVCZB?=5HR6* z?eA!plj5@KY~{`(OM*^y(6+=O8J5A7V9S+#LL7$h8n((PUh*N?Z9-*E(_qU>0kle( zvmy-84-#;@$gCd!j)4mJm{>7#BWVa(QDJk|)F$dd%8o(1UbdvT)Li$965e6>E)s13 zh!XZ-9B>jQ<+MxjQ_%3?T>+E5-l-*}_AheEsO|us!jdZKcs)^T8<5hP>6kZ|muzk8 z9n$ZuP&0;r)E>gkmEh4QY-@;XA(sYI>V)SX{Hq=s2Q1qIX9}m=4!A}>tMG;bfKUMs z-~k*U$FJ%kL*-!{vNsNCPiWZ87xQ5p95bgivtt9`nmjT9s3EY-iJ4~Sj>aKby{xz} z%pS1rA3WF3lvhe-tY!iY9uQSs@r-8x=$*u2feRyruaX(c0cR5J#VX<(-c@a?u{Mk} zXNHRicgtG;?=wKXW{N~jgIE<Ono}FZVHCGiXLfaGx-BTT>T%ei6aYv161%4i5=x}X zAe#n&l2Jns?R~}pj@Q68|1&=KI-@dbilTuE0^r0*qOu3HS=SY|Ar2mVaZe6%pfM6{ z#1QwAfY?T-R5eN-97zsV%zOZJvd2W6*?Kko0TD1kT{q5lwkN&%0f6>7DE`q>k?Nvm zR641uBrl2$EQ_Fv6^O+)IpZo~W!05{aFVcy?gFc$xQHaYI3+fzaA51PlSZz{5Oh(; zmFi(1DuEx^d;NH(FKal9xCR4F38nsF7S<p^FITwnfquckd|0}_^Y4_+2Orq*AF4@h zCND7m9rrD>3dPnC4@|iFI+}l;$&vhk*Z42P_fH=Bff$$o#ODFMUy(}AX%Jh88w$Y_ z^w3b52W_Z}U-7}0KXGoa7=S!My)epv$uQ8iDgX*$65_3JPPxYwgVOM9_{frUTr8ro z=o0G|@@})qXF?MbDtWl!HqHFF{$?O0@^lWo66^as%;^Q&!+bh38tkFq3fO$$xC!cE z#@ANE^$&Ga)*JAF3EnIV)kd7!S7`XJ8XOKBl<RVJdIoI@Cnen<Fx-eM!VBk@8p^@g z##W!eq;Lc6Qs=m{K&~F(i|leYD2}G3{{gA+LFamy47pCw0s!TfFM)Yy5pCmjaO@xd zf<d<g_J2!46JzzP1okEtwyfB@Vu5e&2C}FY3_sIsM&Ra|)^H76uizf(if%6%$FI_h z=>C4T9;l%W#wH6Nwva6o9FkS-RJV%%EcL3P4S0|L7P+x#C?~U78Y_`?#Uy#%qlHHB zsl=f#kvJ@k$`cAfT}S*czHA%j;a%7I%kJlzCE2T@ur@X<f<U3Jq8*cH)wcS92<xqh zbz+15;ocZZ`gmOGn&)cXjT`j6F9mnpt?$zdksPj$8pa`hR=0)%ff6u|jenSuI!BR6 zC*x>l&o#3>W^!mvlK}mD_)wA;O_3x-FzSoy?3H~=;0A3j%{bY}%xEht{lTFB*}xl? zD#1PeQ29aRi*GO`#~x}&MANpu<~lJ}>D(lC+lNuw&(9woo0w3`CM;z_@nIRJfpIXz zE*YKK^yDAT6Vw_Wt7eaIS0}kLui>Iq9+n$=@B#N=kL+4}a*Qz=6G`m60g|{LC2AZW zAOR4FcIzJVV=pd|_JD?3i0w6p8k!&+z`@K@sY<?w*X_U)s0(W=!r5LF8^W^pYvO2% z3Lk2r5I)%)q<4)3Y#YSe1NHW1!`7{R%Nk;dic<oet~3B9ztyh$>;S@_IBoe7wR0zq zn?HX60>FC+@nOS>6a(0^$Bo;&Qv2Rzj0h55#gQaSnmmazrOJsRAI_Wqm+#OZfAZul zT=;MyKYHNW5X(1@-pH0BOZp2ZlG?w2BQLHz`H&w!Z~>T9tH*EQP@)#?f&14)X+5qJ z>;0ofB|tfI=Ey#M3pcLZiXrjgTgVOCpJxC3U6eS{X#j5j3Qe;2E`UF~bK_q0_wFC2 zLgEs$r5JMJyKQW+ZF|TzqC>!qOQXDr+TT)b+5%KMm~kmZt%_6ImL0$xH+SYt?ZYQ7 zA5+t~3GYkx4&LR7wrP)Cx|Ex?f10NKW4*LFL(|;5o7CEz-n^>esAg3Sz2Q80@Mf*~ zSF@qr?AmKLTw0IZKllHndLMa{a`}Xn-+j>0cN=uyfJMwd<<N)!;6(g<V-6mllrxWh z4E1H-e;$5Fl5KYR1J5?S-0@Fx`Q*cpa{;Uv87zM|SQLmR$@We@oG7wQa`W|NTL6r0 zR!A-6z_Zw0sC8&#V=Z;{kU0PBV@f>;DKs2rM2Q5^Z2oX#&M*6jQx9XNU9{Ri(@bOK zIO2@M(vzc=l#x5_ycSykOg;1$X-)o#(w6XCq#rSB<Rea>^(<P?Me@u;RTALTbWu6w zG~`xA@_6%4Acy?p&3OL_#-~^LKoZD5<cwoZLu_5tXGrAeN6i}Fz;mQ%5nVJ7r*c37 zsyz0<v#4lu0*dTgM2#50Hl8T*O>&`i8JIngVS~jx_#`|3(un?Ga|brqEVSIR+ioT! zJnv|WPo~^HwJWUVh~ti$>g1zMJ^d`Vm7Jr&YR`-8BvVf~4GC5nTMtgNPC4(C+oiuG z)%i{$?nw7gv6;Qgahy+jW6mCwi~|ln!?r{ZJ&6SZNj>wJV~@9jj<nuCdwgQfOU8N! z@HqcavPS^k91JU_T-AinAb`9RD!@Aj@RC2&v;mIJgP#0!$6Ci}^g|<Vb_X<{!DH9c zkNML~*xdB99m0Q}-AuOS<kQxceFm_ZCy4OlqsdrPyERl>vh_|q43lH9Nn8P5tvOSI z@=rbdnpUSf7PHn*KV3h`I7M};Y0W>}h?IG$eg^*kCs6?Z^9>c$<TFmJjC)fLBzyb= zj-_njq-%}U&chEiOqc_Xc&9sARH?DoDovJjwY1QB_;k_+sPn|@=S$$c1H(IyUZio> zsB<h4NMDO{M=xWS%{a6F)bdA<54XzgMUhQXi0E351`)t`%j1bctczW}^WFGD)SS?~ z0~GB5lW<a^9Tzo3I{zpIJI0|6ZamO532}!zK;e!IdZ|7)f(|$Ev5sW?!yWcuQF9Im zs0jMwCHWu*6Rd}z)Tjp^hWf`i7L`LCN)T%Ns0I_fB9$SQW+6<8o;UKr1ZvphB?oFq z1feF6f8b#j-kS#r8zL2OzylAc_=l*P*ditW!Z3zuyvd5-@sD2o!81r&(UK;zB8U7V zfIZUMQo`|%KTP5u;_y;!mc$r%V51pxOimD)v_}37&S%O<#>KECxS28MOVcUEHT;1& z%{3--6x4(@`hgwixr-#x$;ZIVF+WX4@;~J(m3lbUhB8_$Bxjq@KcX19dTb6PB(c<2 zL<Th^iEl0;k%wCF&<TD}DqtRKiT0QP4sh_}dJ=2Mf^3JoVRmko$RdiACNZOM$c}&V zQPMX4affD<V>`(LUp*pY7<?#XJGCTcZNAZuIlzKLnOWxecu7s^1i%#65FIyCqDenx zBpg(FM+W~P%DIs8otjw3K&JB#z{s-yB5aAybQma(X|0l+a*>_alvI;(_yj(}`kU$C zvCVO;K^XZcN26>y&W6nDD{G)c0OT=_pd!y$|FB^_yde*K&`+G~lgB;GVU>4S?QZ{~ zrabb2ianSkc0fHIOPfR#!YD!!DcV*6+qsZ!l;aPuK+L<mwT-kjV<BehXI=0S8G-%- zRwF&2T@H&_e2`Kb??}cj>cNeaQnMt9t?afYvRDtkCX}VQh&l4n4pX!P9tjbQWf^0p zl4Ld*%phdlPJ32blI^e!c@Qe7P!Diu?6gst$3IZf26KdpiT{9YwPtmeHB@6KuPT~p zDl3@ZwxJ%~5Z2Y&iCTL`253J2gqd+&We$2!C@cY3)I};ATR@?=UAPJW8=7IQ@5bpt zu$TkutmQVemgq#}NKUsbOEf^T!58L`D$HV*SS^{goOTP?b-1w)$XznO&l8j_b5j|7 ztf{BXoy&Qr^oxY#<Fex1SV=CD5qs>T5)LJiOAVObxGbeqJ?j)D%&1_0BDYr5*yci< z=1-zo>L15wg7r*n8d>S5C)6+pIV{!JmKf7!M&%S?gPfb339AXs3m=wa?4d3B<Ff<q z3;X&>5yt#OM&;NB(J0K!<jpp&C(=lk@7CbRtTm(-zAhxUMwH9^V;$2l2XEe_5(`&k zA=6pY3MV%gKqiA7_~6I?<QBJ*g!n@l!NAw(wgl#-`V)|0!A*%JlCrNfff)F3rX-Qv z5b@;W6MNXE7fA%;(hvn?Ye2;~+*HU4Lu64UV;R(v+D$OhL%OWvCago9WWO?t9CE}4 zlFp3fuWiE)$^dLvykjoNh~p3Hdq<Lt_G)%2<{!Rb1C4O~mtzTrZm5%Co$LXMeVC&) zdP>iCWQZQmnIp9B5YSxm7=Uo(BN*(+hcJf&aC)MogZS{xK>7`&AVK>rLG(v{W{n3k z@&h+lBz8WKSrpVnh-O1;LNpwHNQrYt<^K!-70Ngcgj=yWK&(a+v^nyO>#!pE`NuBS zAY7Z=WaS$-4R}!hqwPX)B1QhN<C0u7q;1SW8Tk;2sh!@Oufeky*hmZzV=lxb!Lh!o zGEfd#i8?`j&NulWOhy9*>S{%2Hz3s3RN>-TpFu;kM9cBBOVYuABx4<-!}Us=t~ih^ zWK;iugdF@aTz<C1v*wUT@R*Q~s@<A*BK2Lbz;cXyJb9hnA&PDHAdcLX!(=(WNap?_ zjVAcx8_xc+g!qvUUA(6zg@rs^{CYKYaYGTDfTh|cHY9Ao0ukh(2%O;+v3RLQj^4mV zI}2#yHQN`Ed^VO~79tL591x+gxkf1-tSm)uvQE=j1~<TAjvr4}C7EMQ09O29_Ml36 zcM^h;5$yo~3i)tJ#b<n6(^WY!L%y{|5l9;^1{m{D4#Z$&;4mwsCrQ?45AskCwE_+d zQ4WW9d|Sc~BiICEWnR=o6u0MdT9qp=27+Pq4pcx4lhRxo(}21rXQ0s*-$HKlFb>c6 zZ0Ls#ov|+07iTT8M|SWJ;lL=u^lEaV8qHt_(J&ljF(ll;27qQ^8Icd!U<&Y;f~%Af z0dNgxm_hb%cPp_P+TafL2M#ILh1sW6C9xXf0Duelct3b*4^b1~zy#&-5{4&vG!a!6 z@(=WI9w_)Sl<*$9H5R`2gdjmHO^^@aU>9x^68Yf|ryy3lgo)*qTmPVg;=msMkU5sZ zRe~7*f186T`Ot3PqJPA6JSetpy^s%y(Ry5>i=?$?c93wzHDiloK#_q6m|$lCkWzI6 z7>wZ$zAy)3h)@%x5p=g4sTFyeBpAd~hNTcf57iY;SP_d=5U`;QnKOucSS|fG9m#MF z8DV$vR(i5{h4Dgc|1bzMaVgbAOnq{C7J?6um?>wIMUXHP9GEL8SQ33!G~%U2p8y~8 zKq?@?E1c2<y5J8f6DuD`63a#mRFEP`<cj?OksKo!l@gEulR4p7V3*~M=%$g@f;Mcx z4WB_ka^gSD;tz$uR__3dWtD3r@mDWJ4)`EgFxWpQBRi=@l!f34JwjU1SU&A^KgOv4 zHG)D)+<<_th>rWSkDF%?^HMLqQ4ZVyhi_qfs6>aaaY+~zWh)7S@|X|FKng9Ee5bf^ zefAK>baIe@d4uIAsxw8L5(tZ6M&w|DMR5^Q5gAtTf{0~Mf^%vC(<}9$2ZRY#QuSs4 z6M~$w2D?x^^zc&8<|yP~L%0Kp3sE|9wnl=nD3$_(z~K$=Bn}Jlg8gDXN}^V5^^!(O zV>o$2dq$Myz<QT?EJ+Cu4^?JJc$3C5B>q5Gw=!EHxpRa;SJ*h6&uI^i#v6aP5+mhV zyU`E65f1Gbhfe`W)}TW5f|KtU7i5?X<d_kTXO~UKIq)!K;IIY_A}We#EK))LGE6{3 ztE4?uK@ID1Q}Bp)!q`uz=Le9$4^Wj4`xg;xae8Yo3oe72$wm>tlMey96X%hPV;ML< z*-nnL6y~;+g@=?k8CQV>3l4*A!&nkaxD9LL7g%#F5XBYj<1^7|CZyLpa5WgaPzY9u zZ6mP_oY4&484~?BXl!z5FjJoLM>K@<5A1M;<j`SH!4~zBLf4TP7sh}j!FhVZK#`?b zHmHvR2@z~@d(qGY_7Ex%BPeVEMBngpz$2&NMMZ|9Rky|`A~}m!C>SsC4u)7Y@^EP& z;aep+6|+)&9LgzpAPF->4@kOT2h^Kg0U7_W4On0Yf(1zANvAJWqk_c$6rVUOANZ8* z)DS%CeY544nM5t68bBKHqehdA*#}qO!lQi?WTm<z=GZZPY7UvhK;RV@Tq+m@5n(Ho z5Hgw)cKQ!=S4eF`oJV;Qm(dTw@EZ!DtGn8OL_rP<A_tvdMnWNMnPCr$!WOP04j2hk z6v3fi1qg!>EV&4wiMA!$^A6aAG=CQoFo6ndkXv46P>!;x770A4!JMe`llbt9|G-Fw zU<j~a2fY9p=QgiTi5J{JZoA1oWqCCu*DRC33E!Hd1G_k7vl#&p34oQ7T~n6Dx((n` zc31f{%327_N<L61I&`>V{E$j2T6$yw7$@rvrH~B{6&HT`4=9!YC_ma~S8HhbaHgZf zwFA4Zy+e6aunQl_4-|%c4bhK-5D0qe7aIdG+hh-ma66wVjf@kj-{?;%!zy8cA^SHG zRaFlfh&x5;6qi}3ZBPy<iKL<S7~@b5*f0mafDPnuLTvB{zgUwjAxV!xEXrU9J@R}k zOA?zg35bv)J-IQ*Gc)Om4SyguNHVN#JB^o>S8U*<>;*UrF}u*<eSxDL6l6gbWsYA5 zL041}Cbdx6pc}yf7l`scmV|%!;5;(KasRL)BS&b15pi?6NwxtzB=`<1XcQ5&6kmZV ztRr+cF%nYo4>MI0@2f`3yK^tp5K#p*UU7C5!4ym3TOx!1JCHkc&jB3;)&$`|4(Gu{ ze@0GAkw+X$yWBty;s8fW2n~*jKxmg8<pmAAn;71Lc6T%z`!z@5`)^N&NJ`QSygM#c zmk&Faze6V*B?7b$(Qy;OZfsBv!S*horjDM3ycp%QfEh1~^$zQx30C_Q@~C*rP<M&a z4;dMVY$|})!B}z`8!9QH{27FGnlrye1yhk9peTP)15BpqCrd#O^)Q3F#SiTBm_quF zvWk&F;}1XwWKl5{zeEi#!#jieZ9EJPKW8bh>BX@aN$2HGf#eDOB~_5I4bvw~Bx{qU zvO93JBYh;RnJJniLJs~gU@Ri5!w9>2_)^TVXbP79ZmX;r|FCCkGgw8Faybc_9CLNH z;W$(h0Q}%}2jV>GTf+%L8-Dsh->`;HVN&@p4Vxf3iPCQX$IQZv9R^X32V%lMsJ+9n zkg1|gR!DN{3mrAX1m7TfZ`W^bn_EBkL$v`RKoS?UksuVo9^hn&01PBy#2_wnA0?bd zRn%|z7YKtOG#nyyF@|vX01b0cb`CKS-%t;iYpa`7!*&EV&@eg}heoL(%<^1b0YFz^ z(sA2d!^NB$-;fWAFbUKP(ky(xcq7YfwII+zTrU~`hS5_UqrJKDI8!)t)Qm@t;|;;k zKt`Jqdly>m;1SY0&Keif2rM1_U=5m34;K~xz$Pt=31V`<6p#QCzUyHRJ^>V?Cvy?) zkA#ql!$BX1M8hgU&-$w#Q$YpQpcZB^&FE1N%Qg#m01uC{bLz~8xKnw7kPi#8bRZ38 zoAC$0u+g6L5BQT|BnHsuwi$B(4PQOJ2fS#Dv1aau6!!tuXC2q@n;oWF7(?0C_QBZ( z(hz#aR)m2b^kEk{B1nirr4X?Yk-;$i04H4mX%Q-aoaYYCY#k3(%PG-+V3`P3(#7w1 zv3i%ZQ^H~wr8$epqF{_YxIzx9)}X@TxAC&S&IDZ6BRev=AZq}xmME))ETsJ@gcs@$ z1Y(;LF)cgs4|p3a(^58yTF4Cn4*9_UUEZL7Ko(n;5+io7mWnYO&7wAnVZ~2rvzDvT ziZQcD#y$lGvLSWhviUrxwh-j7ZNA`Q8Y-a(1u(GPc<=@*crm-pu$#$ZEH||~U-A!P z5-@D>$=HX)4IvKnVlVg-lY~nWSW9T-;10k6%UxT|tnm))PzurkQdb;fPurKW_6Z>e z*ut&JotH(_W8Qz$rNTvJdt8}*v!4V?EkbyDT;?FNcUgV1P5+SP!QwYI<=-^?Fr@~u z9)3WMj2AWvjSZ1GmytJxfHy+oyHDv9trFQYvJEoF<UhF$jg7(58C2lcm%JIm@?$Bf zdEz(OrU9^o-_R~&+utT~2e1VHj6n=N0znw}`3~W5VAC4Lh}lkyf`B6z+)aTIyV0!; z$DV`efNuHg#qAqP-fw`TqOpZgY#|=zAPGSeD!jVgb50CxfK$NSmqPX+&tPQaV1=jL zmwoG-WWg)GRo+37X6!{pS&n&8wYL!qD^~SO)o`fp4MSPSedb1+^$=I&5Kr^8vZ0G$ zG4coX;AXgXYAEpz0Rs!8(c!85%4d@goDsC%h<xImWemZiyQ!Z-;t+Xt2l6B1TVfaT z7y#^037#f^pKI;IoyDwSIUYno!(1&s4&=T8Sqwq$uS>RF@grdJ3sqb0r_=1@^z7y^ z=TQVT`ijPyv=9rTgAT#}dWsP>tyx_GL+<(>k$DFg$aQo{=j&8d1p@jq^S<Uq;f?Fj z50C%|@DM5wTI}N^c9Ad%eIyv}DATYCC1zPE0Wb-QU=N5LW$6|th(#jX01STstP>Ao z$OkZxVGfAk2|>#i5W}*LZ0Ij6SIRV7m!f=@k5pZ`B??8gU&59+AAcL~J9Een^=DE1 zmJ$i^4`zr;n8dO{Zxna~w$s25fb{pYVeVi?6u{$i|KK=Q`1P4WYQ$g>SrdUx)du4L zRRzAUa<NMI{R!^@Rg<bcP4F=FFnig5648@Iz=e5;%KIFX$o^32>Z2Gx?j?>>U-*zX zs?0u7`d<165CH`L27p)4V8MY21K`6~a9cAr;oiMtDDdD#g%=G9toV-GoL=wX`8#M) zBRql%2l@+ujSV+)_DB+hSFT)uck}M_+NRRyPoP0hZuG}Z+rLEZ+;QXP?_W@;G!dRm z*sq^9ZTYN~%BPK60Dl#MGX0m$)IYEG`k9=nF=|w&`#}A3Hx8aXdj<WGyle06U%-KX z4lOt@Um!^Tz}2f4btvAw@BR^jG%j30yej8;`_~55KY8-@GQ>MnuvCl+>CyXFZ4EVk z^Hdg$J+4VLe~byE1iE+Lynm?LfR^X>^zp#v%mw&2sSv(!`1~r|>$I62X-`ofWJnSl zIX2DwiW8UrkTA`J3=3kz_NUiBiuks(<z3RPP3FG-K#S?mD#GnH+DN5$+S{d^k<^2S zJe<gJ&zt3tJFPkjE9AzUeM)J^qpu_ss6r4~8t9*YjCv=-Z<rE@#Ggns(Ug7iAupem zLZr|`f$aIGonRm|Cm#|)#BoR*ZIlO}KnSS^91>aVtwJY9q^1eWgdAuydprY8Hs+eN zF)$nVQi(Be`dQ;ME)&{|oPUT}qaen@6j3E7|EWhZDu@Z79yy7`k;HuR2`7L#U?~Tm zCbi>8zIW_F#FK5_0gI&yyYpuoZo+F!tPd%zaMFZ=^e3Eu3YjDTQboM+#!hWaR5DoR z_-C8{y+m#GQ&3eJryN-R_=W&?K#0FjOGzx}pIHA1C!YxY6lynk-1*0vY2I;X&LOEv zD6@s|aVH;8_W8#gY=5%KD1Sg{hdgfbkq<p<J;aOLQkDt8tAF~@NI_-u1<EaWerv6X zU-{W9T%Sz4mKZAF`35h71^Nw~HmDgVG_Xj^t6jhhPKX?Gz_BM!anhtoxo`g2BeBKm zDGlRmrxU2;Jds_wBz=*y^r1Vj5ect#2NG+WUjB&moxSeGha_=4DJ0Tt0W{cYc$8Dl zAA5Y6L!5HV5iqrZb`yv^$();2FRCv#Z9p}_szvCDY$AKuV&74&=GmB4PSRlZF-IG# z8WxOM|K2Rdi`2aN8Amz4v2BW-WVn%A9J}bl2tedqJW7*w!bz(iOGjIma=NSKx3Av< z04IreyqRZUhRq|a^}YC^=bbi)`R6wP8Ma3<RMs%Po|^`mndN;)&)uHYn8bsUdgSSc zT9W@kY#eYb)>t92_9FGnf5geGA+AG*%4tb^y)(YyS7PsuW>``VrIovrj1xs14{P1w zC+Cf4e5Qt{87#a*97XGk{=CMUy=>zj;Ta$S^JgD}=x%BO$cNH~X1#*o!#VXJRq(_& zDOdd?P|Pvcg%C9)F@X?Q2?<m`{;`i=2x>)&8j*Im@sD*RBOmUV8+Af7Bo}eR9qmZO z|2wc!tAAMOgZT>KJc<K}MSw#dA`6O;sI{4Y$e|PO2#ul=1&@66E+3rn;Sa$SCY3Pc zM^jo-lqSWQKn%hkOiH3t>c}d`w22BF6qTq_xJ0OoFaYJ)2{saRG%>MCfr?NBs!}Mb zj^Kk6OOq6*KqaT@fF(%qXb&*9ff5$sDusz$p+L4ljyd>(Y>67>sxmo{5yImiyI>m_ z^Fg6uvB4MrkY!^4sX_`p#T+-xMk$se4j`dWRi$KMKH$+0b_63I+~5sVj*`P2_E1gC z#F06~A*p0!BLK*}Wp!-zOD00;cHZCz6F$?$x1ez#-tdQKnwP6D{$mh?FcuAg|H;iN z%CniFVIw&B!H<M6W;tsh1~|syM}YdIg?hwC$;??tbVeme0niUNsL7H$z7ikekfo`H z`8*J@2p-!g1T4M*N*cB@ldaTb5+!3nN!19Co%&~&2=Wh{j>L?t`lC-y2@-;I&L8B+ zhc2~KP4PWOEdemfKa#Nwagb##I0D?F1fraBh=UxaP)7H_<uc*fgCQh>k(~~Q8MB4Y zU23_CIdVuB@;nWy8U34ElylI|*zPxetDAAeB$`DG!j}b++F2jk1Zn^;A876BTPm9n zd6a_~Oi&Ct5IT@9QiBQM@Wzp}cAmG?gH3q&gq`XESDNuPJ>a|HB>sSp|M+M`cis7i zFW7(&ZrH;d3d-Qoddr4)lw-1mW!7#Hxs7eip&0~0TwEoGT7O7pZH{|K--LTw<8Y^E zU<rT%kqQrns8LW0^u;X+tFNJ0iYe_d#fGv<EeQecc<(w&CHBD&tXPFkB@$vklHwKe z2FN%=8dm_;F^y)u?|QO5O<N37k>L1_o@H~)Ngy*PcQ8Rx#ewSJ%mLYa_|kP=8()2h zCy*}UVHN?H$7dZj4|9liOU8@Jhq0(de}o1l3zlth1u`r<z~U*yy$D_=h>bZwqeB?9 z6hyGLEUFkSf#L{{Utr6u0M%$4?$OyZ?FHrmWlv1z?L|_hlb44A|KktX0E>(OnNlzL z!z=9og*cXSLw_CzlNX&KS*}qEw4^K0K@7k(l0gomY;({+B(OWo6##F_#B=AQ@PyR) zRXrMOh5^0RUIHbi)rqzorKM9n9!m{7jryNTe3BJCC2M(bW)F+F-DgSUFC9<Ob6)~V zqWB??0BDhmqOs#n(HYDn!h;*-2oJS{1SlHGvKExg)+;&U+kce9WlkFOBUQMKawy_d zlKF>HJ>^O}lADtOY~Z_PI#Ut3(Uj~Z35n#B-EB;Q6XdAmctZ!~Yfi(@Ou?_{CQMZ! z5;4(E`AJnZVU2nmky;P;P!KIWEpG~SCTQ#Qadc~saF`=c|ADsbNl-14+Nn4pPRs`+ z01<$1%mb|oCV7Wn>@d!-_I4t}qLzL`Kq5z_birnJY)js>cLbah-`x0s;0jWl<`yA% zk<1?^(LF3LSR;2MmaKZh7yV^KBP4>=A7q4d2tJ%b+rWpq;bRl|z#}J<Km>g52S}-k z!yL{s1v{qMkDU_<%ro@L5EFqGzHK#B1kOh(*a2W|<S4EjKhC>uxQuCl!z*NS`qKl` zmdyC0WKFQ0%>QCQS@v@fflv%%Fv}T8$iW};pa*l4-r}DJpo=!YUGD>cm!hL-9$zj! zP>{bma4<m}s@uHji>vo-D1sB_Aliycf-Ov?(#<p@|J5I0!421|J<JwC&HD-z<))Mk z_7*;fRU}ggMU+UdY4;&-d%=dWk&37*1W%BSu<)R$@-Tb2uMBC2&8Zm{1CYP6Dt53F zZBmFI;WKSf4ib5w=9??Bs0C@l3bI+5lrX)%ItYJ31w4oia(F%cDhPRyo<UHIZE_-g zS_FSk9nJH;-}61WQiy|M5+(o#&w{Ju8#?CeIp?#7-*|`UtA@}37bYvY>+=U}$eBn% zFYvh@y3?hKd9!Njx=9$RqVmD5ak1-*x<3F01o=DEIyr%$2vgBN`Lnvw>A`_u5Mud* za`>c!@CS&P2RcizB?>%Z3I=g_K=?WjsM-s@|4D{*fDgg@32}I#UoeMp_zyJ<J_*UH z0C0!;3Wp2XJSIfJ;yDPs=%P*-4pvLSlZc){kRx!|rYVX(C@h`hn+_IR7RgyZ&0~yw z0EZ?pC>x_O&d?Hy*+mNr44VK4f0#WEl8Vwmk0RqjS@MNDAO}OjMg;_rVVQ(RqNWQ& zByMPrW+(>^D;WA4vXi)(UbusKkd*4$KX2TNb7TXZK|7w~Kb4r9f9Qod$Ol?EvXOuY zZYapTI=GVvBCS{kQoJF_YecE~5LEdG#<9R;Nvo1c26nKAdJwRFTu47*3U}y-ZdpXe zU^37_#jr!d85FuHdauD~7kHotet?H!|4cEJnU2uF#hjp`uJJ@P{J}k`hhZ$n8rzsQ zX#&Mqjq7U3w}7J>^cYj5FsNaZKk$SSX^ffSIs7QQvAG`w0h&9254qXM6`PNCB#2sp zhB?p~ns}h79K&tEsiEwuQ%sLy0mS#gLN?e2Y+wnJOea^NDs2D<bMdAhVYwpdlWoeX zk3&izX%fb>s!8-EBqAkzYq--$6mN2tX;=qm>Z6c4Lzk2^b?Tzg3Q9o=D99v{*!YLr z$PE#q5#f`E=mUqKOcY7GB-G@oS$n0TN|frE#oI}t<v^H!fRGXSCw=pYL}3$D*aJ;u zrHBfhP)eYG@H+Sqi|te=_24L>|DhE->W-CahC6sETZ&H3#5Z6P6$LWCav++Eg3tS$ z6G<_@Eu0~u8mfFt6kcLOU?3@f2$cK#I`b?{Wr;fgISR({Gsa9jhs!bm85bd{F9Ev1 zfoPP%tCyk_keaayuh@r5s0Vk@JerZp)U3;bpoe;xk{hGRp>)x{hz*?#hjEybz1S8= z2!th(oth*{8)ea>WRf4HG0poC<_rh5(w(h24Sx8B6N5D<4Z;t?3#%9nC~F^oV353g zM@IREKiCCw7>Vk_iEV%dL|__ATFbLhMNQ)de89hNVI2=djg?`EG4rIHN(tkc3X^D= z%plOLsgC*lI!S3Dz$1(s|C)wrpo<BGK>gA@aqyUBNQS+MJb@rlZ8(uiNHh>d4PeX{ z7r~ITaEGi~!a;3O@6#QQVG_hJ2V`4EpL-qTnTK%*giSC9a`2^CwTI;ivT@i&Alyr} z>qUhilYdB3UERfT2qWLQjJ`;p<M@p#4L1bA(nD-AWv~OL0n@tlDgyl|###;m+KHaX zmLcW2?ckrifQWGDMwU#&FEfX-gANys%AgQ1HZ)VaD2N-XLje*zwWP?4z)*Lvw02;) zzoVNN6bPoUhh;!C1e-_`G0{W|fUWXC$}!T<ERmxyg>3L9$SEKQa@7!xRT{jVacG_5 zY1NZ^QJwpQHE2#8|1*bjSQ39Yncdq(m~~K)UC}rllQtrRK<I~WAc?{Ghm`}L%&;zN z{0n+8j8DLW<^<ZSTq1^GjM9j@C_B@tv)3yX2bVA;f2c=~P}jZS(7a?zcNEb%Y!78P z*}UotQeDDJWTfxx!a#)@lXz3Gt=o|hSZ=U`_o#`i`K7h1v;as7how;uxh#lFQ5ac7 zk+htDfDsOvs*!X@Khe^DFp+i8gzgc%t7K4@913A1MsUDM$xX$R_>FwH+A+d0thtGQ zV5o5r$`A$FWaZYGn@1+7hM*J(Qdzm4Y)9bz36A-Ps||qCqRWh8j5q;XW-w4ovR8um zFmsRweI%On|2mqk;|Y2^ShgV5k?f9^U{mv~SLThHVPr4dWS7(kAJDNFHPt>|BFu7t zhQOSNyQS3K7?+~}J<)3lV@25AP#huphZ52TB(fZQ@Gp<hhU?qE&}En(nFvrw5sAzn z^|iiEEUuOLhhtcS-p$$A{oSZBhpNSgS-9CL0;^$(h9*dzoZa3M=2oaNN++XL&R_yq z)5YX%Jq-G?9^+thkez>+VdAJR6P(%xy@>IZrCwRphfQC@DvIc8h5=HLOYD_*Actbr zony7v2vV!(>IViY8+=Jac$K!G`P3~&+3U&QbzzBl*oN?>6mEdaGP4O}2^~4HoB$|= zYcQgt|8Pt{nKW3+2Y%3sNKH#88J2xGiw#xH9}3Rnh!R=)hF@q{KqEGlh0Z$Shh*%8 zf51uK6bv~TLVIAn+Yt!W`iCh24daVWo-(7KFy&&qof$0Nevu7$AP0O{IUN~J<QPKQ z6s)KC6lc?y35Jj6D1`EoHQ~fFd@Pmxi;p7<0Nd(YQUfNP63_mrQ$@&!_$asg0k}zs z1l+>3`W?<`p1iIZqwp9BWWfhNmP_(zH-?m|bdfk!Rp1te#Ri@Z5`oZE)hfK;2OLTU zw2+h^o*eD`mch#hNJWc~)GJrr4J;Bma-at^&KO*M7}}%;CsGc^_y-)`60Ztg&ZAsH z|FwtED2F}xgdm%Ta$u9I{fBRe2~+&QCQKfuC5B_0tY+-i;_7Aw@*Z}i3iK=)Qz0oe zS`M*Hxw9Hlu}fKF&4*@~1561+z>yz6Zic~3+p~&W)cOf*Y1@AmDrv)nNzl>zX<i8# zv`fs$LGdZ^88kOamrQmCX+tLMsE2<T&3+)2m=Y*`!8Tc9oB-g5#_SSWGrfDOX5c`W zAf-%C`x4h;l0BdV_y`nL?hG`U<jUk^$ad|_uAxA2qI%e@<~%6b=ma@P9oB}-zX%kz zYm+s&RBU4oPk!V|K_qP8GV$O-H`;8Fatg&p$V-g9y`2P-dS#V(&(6d%76Auy|4>(y za5ok5&44UVOcT61InC^(pnA3kZ}?-JAQWb}rA|>@4+$ZBgoj|LK+5E0Wr5^`s49}3 zCS)3jVKEofJ!fC8nM8@Sr1&$4I&PPQHWHDC+HQg%J;u-ukqhSsVsJ`u*x6ijT4DHy zUj=Xh_lej3iIx_Q+m4NVXvN!J@t}BRc_4=ne@cNdC%&Q(NwJ{uHaG^qXTb!i(Pgiv z(C#vF=Uf?~sAE%tLm+sokZ(|D_)w15v}bQq2qq7%Iz)-6vjb&l2=|@|y1^t_iiZ07 z2YUc+M-K2WK_ZFGykxirrZ{k9=?8|@a_zA3$QD^qREn>lk=Ra6ZuW=X|Jwsr9*2WM zjw%N!7SSVqsGfD&-CcNHUwZCk0_N@Z^Z~;`7-uJ%g9Ja&VeGu;xA--D@a)&^aZU^D z>NvIeDFnx1R~EN7)MOv>B9Z9OB^nVV74Kwewj)8p25;DjzCGk53b%hqrR4||VP|hp z*XHv22S%E2kC+2sK%`T{@4Yr7rl<#YD1}7?v}bGZgwS$6g9ii?*~Q)j0!#Jwu9>RZ zig{=6Q+92E0Ec{Fy?c7hK52Ck-`N_YhSxyx^!w#{XXdvUENY0DdZ=39D8is5cF+8a zk!~%VJaj`g?n^-gSa4G!@8wSklBmOkLdY%(x<qEMgXsbccfPfZ|LDU(>M3c~u0oJY zhA3n%htIdL>N1p+f4GhmL5b=BcNiR3gCG|Rp4f?O)azk)P|&ll7~P|o2GgY%#M2$A z)oTy&)DtO%ZvcmnqTbY$D!@YcYS2aG0G!O=j5U}A)hY+z=pDt_*_yOb*9p<TzzZhH zlUig=-lVZBMb^J4@il0z05IvT1$&g9im4GqHYkUZX)$W_vN(~pc*d>B$iD3p-;!6q z`wgE8i4H`V1jm5~uQkQHg)%7%!y+ZpZno2jzz0}3%THoPrH_0CBvEc?he}Witl%rk zRgP`($P(#?dYG^JYW@%|YT?BZydaSu*_Li`^9(j>D^$SQ|2&18rM~G%XctC4xo<6U zD2Ewzb&i2Sqa0VjIO2EcU3tg{BHlfnD{36E30$TEfZ!K^pFMl<4k8Soa3RBn4j(!^ zSkRm~fB#_F`A5zk#DxeyBE*Le-aBlt5N(6!&)>UklMwxT=Z|7XkMIJ3%y|>y%5B)# zY<mZ<UOk=g#EFCV&r_jt+y41eSnwlGqc;!M6d9EqzDb4fNrm-CTuOKa3)W2AF(<`; z|0tIGw=S7EcQn=F&8rYANQM)|x%-!F-9K&p`f=0NF3~@C+_+hss#7oJj)%p`o%T+q zzq1AtRt_CHXF-1R{;kpFk6by?4Xv8BC(j$|U9#ta|NDmr)xXvO(7pzpbMMZGll6xC z*M!)=aq{F<W3qYPJlLUum#c^GTa$3!_~rXd)iqwv2b2Gq^pBf8b807xEckRzuYU(y zD)Q7%Ch(ekVPn-%Ir(_?PdIUz7u!MH)We1^|JbwAN+J<g)o}r41y(;lVH4C+fBdt} zN(hZZ-dZ3Pv{C>p3C4~&+PGz+YY7eaTZA+H!%i~!xFZfX0c4iXJK~r_lw{*!C}T~Y zS+ox*{)EHPk;N%lB}1gyV_H5<RP#?h?p0}2X{U99M?KGllMfTr%p(szXT5ivaa4hp z*E{)85=czR1u{rK;1Fe$l0>~@&TjwEBdC=p|BCd^KYzf&jW~IUX-}j1IQWl3{xrh| zIotHp8AoXWNFziPvBb?Jk+}6vIpP>p5I#b}vkj!*C=_D=BGIX6k`PfC05*4Ym|Uh% z`EyXRi`w*2ivIWr&pxJ@^BA*~?gZPj+GyiWBJQ}uZD7f;6M$j;7%84r*FH3nIqjIz zP5?e8E750Cjmj=%m6G!hF>4fBj&Dk0iI!X8ba#(D;Fz;!IrCtv=$vw<RZu<uP}9UX z;p8?5B=69sU|-}}Tn{+*^!blB$xf*xMe%v|nO6Sb!=X%ZHv8XE`4pm_dz=Eb&5FVL zSL#&`c}CHlhF~F0s{u$#WO9#sQV)<f|ITUQ$iF@m>`&W(jn5puBumkFN~*YGR1&(i zQeyc`vk7890_m2f`Z6S;-g~F*)?@CNvX8mk6iRMBbn9(5vV7yMxI&4+QwlrcaI0xP z`S7hP-fHo^QrrH})@J~@DQ-7qo$q~l09I#g&U61%L&Z1r$dl{cd3UZh>Zt3!w?n0C z<S!NDe3M%sdd_2y<G!bz7x0c!vd2HU1#r3En?|LV;+Nw?B<2=*na{2)ZNn5fLItb& zLf3;oAwF)2lMgI&;6u(qU#GMySatKX_U>!{&Tic!Ni#5FhhA8Oe;1hpEMfu=k$g^9 zD)OK2)CLj7Q3xLR6Pkmr=azhh{|QBBIfyp60k3vAhCLwMTyU%tfWvUhAJ))BKPm?e zP!xte{UDCSSh$eGBqkiw%17n?!K<qHureQknck>CjqKS7U!xJ>M~E^#*~z0D|5(Hx z>fsHD>2G2@G@8z6L?yqBsvvR6*jtPTiGNf_T}V1(dD>%+HvMBwa7>;Y>6jNLwdybj z5s6mbfsZ@%qAV~gn${jjNTu|`4*uXqTqdCie~4%%=IGBu$QYm`VW%9ff`uXM5P&|A z!V{B#g&?p1i=c?_O4*vF3o}F^{BR;f+?Yc%%mEK`<bzj!6wN0QA{oDNV;_~MM+%{s z#4&2i9x&|IK1$J!%4uR9|Biu?eR}vz+x^WQl}O<~`q8ox4l{{Hp~&l~!GwRv1B?W- zO3A<hk3bNj9$J)y^uD-4Sr)U0rTU{i=HZQe$l;BkYeE31W3~&Wvm?Nv&N!IBG1J(K zYXnVE0LtMFXqdx3<&+gZQuT*KqHlkU6d|wPL5@EFV;kIflzIxa$$w6)S69)f{)D+2 zZp;H8?r4S~L=c1^7@{292*;$Nh{R?!l43}+6h1b?4No8<E=&oEP0vQ2fP!Qt6d4yg z>H(SCeKV(C1?D^I0g8RR4HWGt$3wlDR)!pCFaZ#X$h>-2wI0Nv|Byo`0`MGW!R9b- z41g9tfd`ez1E)o+{}D9nR2jh%Rw3MZ$2|BkQ1YzgIfk0WI|7iXk*$w1w`>Lwf?$Vl z_+uO(!OZ-6v!c5&QfoMAsXZXIjc?FYNTZ3W&hlaoe3&B~vC#-Q^6?L%d?{k<!pkjH z1(Sc&q7Xp|Yee^D75G7>9iRvoH~-o~spe`fZ_yDsdgPuycK4gy$cK(%QdeW%%e?3P z2xdF+j>BGSryo)5Kk)gFdw_#Wt0Bh}DNEe=LS#1hXhSEOlVEUkww9pv$Ll)L29;Gu zgy47wIKa`G!*J3ejlxII@FA9Fs6?3MaPb^sQX*^-cV^q@g&?+p4{6w;8Kq4zsUBRR z_2n)A_hrdu|AZ1u+>%OAJXJARO419IU{||*MeSDsBvx_YV;9L7oHX^DGewyrDgW3< zFetK)X|(q-8a6L@-7#K&d<jct2Ix+!vPLSnV;tmQaDaPN5PIN)8dTuNW~9^6f#GE` zWTebQPeY70jN>27paLBE;Xd^01vo_U2RPP1jpv$YS<ku0J^sOuiV#^Lh5QF66d{gp zyh9O%5Qiblv7kpaa2zjFX_RvktZj4(NZnuqHe^DyNYnB-&Fkb&R&to0rtR5$F5`a) z+LH#=hZB=%wj-4VVQ3r0ZG@}DKGp-7J#QPogTx0n7*+~vEJj`slH*h1{W!u+V;S~% z%t+HH|Ji4jc*K1aNv4UxY2X%mjQDy^J(2*9(P_*a0`sn~rW+c1@M9d{NP<i#+-Z-y z1~@DEMn9GVp^rf6eR&W9%_Z>;eni%(Xtang{@{%tm81~0h{;Uy5e|G{;Xx9@aa1`v zkC(#2ABy0_k7!10oT1!(Xr#zpl$E__O?#z%@oPgkc_;e(gd3SW$mgu|zhuEkM|G)| zzZ+7)x`DSJ-Ux;%l5tILT5sufUx<&mQHx~Qql7AHTiu-L!w)(Kp0$&QN|d*v6&;ic zyip2TnUyxr6?7isz{4m0v4=O3PJK0bJL^S*QE)K99r?h+Df033)>o-egP_DarWRVa z|FnS;)F1{i@X!Wu<bxbmyF5cKXDnEZL?QEN2C-C<EOPYX57=0d>eKQ+BbK&j;a~$a zqTl`1zuk7tkEKE`M-vK$T`v=4p5yUiEMNS@`Xg$)L_z2oLXLzB#l$~MgEiEHP1T(z zDa&K<NIUSuW4H_1!Q0=wgIp!XN=(T?a2=R<hLSMJIJBBSEJ7aSLFoyWFTumcmD;H- zU#wjVJGqI6)x+uSM+c&t0&-bi2+WA>!6Nv>8knH{OxL-U-KeODzchhAd_!Q(Lq6z& z=E(!ADa^lglss$_gveS+O_HrBou!0>KTJYKDAzlv3ajwP!BHD=#Yk5uLNC;q|IjEI zm`K;yQOWf*#0F+dzjav->P1}i%r>yWH;BWCsD$-V#$gbJz|0IGCIm9QgLwVixj>nD z=~TfekAcj~Om&l8nVF9S##|U3MKDRdBv&}p4T@onj3`gP{6i!x0U^NR9t_VvfSE$P z4l1+(Idp?OL|0l-M~N{3IP3;XXxj|}$Wu*O5h?^l(8eGH0za(5EFj8hIhcujPFzr- zY{5em<^vV*UN_vsJkWzT)Wg3ZA32;>7VcH~fJjOyg)h_?H{8!3G(%8)9U98g7^xgQ zbV`A6L#PzvWEmNfZJiu$PBl_j_qZ6OG==@t3;#ic4Z4NEq>J7NQ_{?o|0Y;N4iy}{ z;ox#zVg?Ea5nc;$z)(I+OJm^6Sr~|O*-bu(!+~JoLf9bA07+c@0|}1UJ#+&+5JM7t zf<Kf)XS4}E-~nk-M@{NW(wGBnWI-o1ffu<68ron+*+`{i)J_zHuDD=902d?-f}+6# zI1CzEfSO(eOK5q+gz<(#<VN&>gEzFtLGZ&t{mVCCR7i|OOB4bu;M!3nMQI^|Cver* zklRY4Az1CoK?ssR_<|iIU1<Rz#|hYYJPW1aqY{y%I(F1W{DC4&f>PzgvQP?6;6you zLq9CeJE*1|UQRpwf;cSS;5`KE*{0yprdx1J03^dMJRqzjOR^*f|2#y4AP9mqKm%}T zL^&AYj2PBwMB_WSgFI{o<-tP|?3HO1r5;g-er@AFpu!S-SUkA~<CrIIk_SD^L(8GU z8jPj#F^|3oRvWY>kTAm<fJ0yyA~2Do!_~t$)B`z0#VrA%Pb^+lAln_-<5uNQc`}Y$ zkc3MBfiG-EKyps+peJoA32mi^BK!kz@y(4%k!AD)IjCk~a7#7BPh-@J_5H{+tiu8R z1}eHBC03@<G?Iocgh(KTIZVqtl+acJsWz-bFrdRatOGhI=^+4vbGZWo7NH9sL_Of- z8lXY|c!RlRk-r>Yo7_qC)PpJNoDWS@Jy63ESe!p)=4D<b|Blk+Kh>y>s3$%!fy0ds zJ<!9ES;@1#4l%qFs|5h*-Nw8H7H#Z-B*4Qr)B{Jj%|CcWa%mt6Zr>dQ0D9EawZ$Q2 z21tyMAuzx~v%TqX>8VqxT=rO~juz536ap3)0zNQjA5E1>?vU&iMm1~#DJZFu2E#ho z0*s_4)DX^M^vGFZYMk1r0#=reE~7b+gE^3kS*ZlK?87f4L%W$yJIqBeWCP_qsbruE zdVUgz$pdQ40_cR;yyeEfP?T~|Lp{vHB$DZk7?eFU!64vV?P%tM(UZZ!YfTKAZUln# zfP-m_>Ynb;VZk0auo^Kmfu=YV3LXT=frCHn20Vm}|62f8&*VcPLMS{mmsgMlFL9=^ z21mh85?3&%)y>Em#m0!TDQ7C{j#k+=%)x{n1X94<Fqvey{DU;?LOP&>CTK!C5N$i` zgC+niH1x(dNXkD*&WmV6x{&N$0btcy?bXIC8X-ksOv5zPP=MwGG}ulxXoEsjgNot< zI|M^8?1MH`1IRrTad48w^h*F(>4(|}9&Y1W{-j$h!Xmg7L1ZSoOliLe!^sHD)HcM` zGVayc2r8;YK~RUk6u>d4=l?mbl@!FFb&S301}czRpg2+%QinfKfiNUrq9~6v@RCe; zU5d1XCBecS5RRxQE<;$YL)1&XunTZ}kP-53|JFK$z(gn(070`237A#wRMF+&w8J!1 zf+?_r1J=XY7DF{~134INI-~=Pa0`s`NVV8QJz%Qva$CU)Z%4R8Z&t53OiMc?o;LVW zKXgw$xUF-kZ2$;P0FVPebkB(L5Qiy5G@7eq2-C%!%x**niFK!b0mu7j1OV4jH1*k= zeqQ}W*tm8=0n7rc_3O2W1VwnM#z+GdSZrkV)lSUDKj^|5>=BC$rafX0AqvGL06{NQ zol+WXu-q<Qd~p1w@1t$TPXIwPj2O-$1P1R_OcK%a{(?HtMl}?JkIV{~G1J*%EBCU) zTqMRnF6!V0aTs5ayP>2hObRr_%YHz}|L4F3J`_;^q(k65MmTtu9}NYr*e!1WS072n z>jc6G@WwdwFy6!#5NqaW2CwekU0U>M0T4qJ-W5dzs0c<+h4F*nt`(19%+2Mgu-E}J z5E@oU2r!WZSuhnxd@!>NvJV?1?uaq&f`va|Lo?u?vjw2CoQiW@LnZveG&CW%Fv#Ux zj$4QXgJ=Ujtb;mmuQ$BIIK+}LyX5)3@-(+!ETsv#OamXZgZ*kE1R;xC?9gLW3p=C( zyE)h4s2@XsCjoyE`{@ldUvg`p0ysc&^|)jb0ng<e#4vYWM|7X(eDmUD4?s(^<2(dW zhyyu1Lp5BoG+W8`<U@ek(*_8^|B#@ITk!Mx*$2T^Dn57uh=_<iGtOQ`Mm0Nhl^C>= zU^M$J1TjN!ItOuDa-OCvazkiBBBTR5h;ulIqGv$Gf1t~J5!}^CFf|*sKhvU*KEgGi zXu%1}H_wY)qyryp!Zj>JFET_H5Ch1(+?jcVP|{Uo?b}hKn`yF8Z#<WoDc@UyZd+N6 zeMH(qFi=b!a0_nbB9ZkSwsKxmnK0!jJk&uSECe3_?K-r>W0Y1Qt`1Q!c4ITPt6efb zT#O_;Hed6#sMQ0=Jr@S%%h5o@P$+~p?1MT$#2K`-LJ-8cMMX0!v1RXBY%!mHX@o^M z3gg8oaxH`)(BthSqidtl|5W)lRE>->EQB&#jHXOV+SrRM*+*+EcW^_uLk!y{%?Okf ziDWNdQ#C|5Bu8{x_GaSEDuO8XgvK|p^v2QTUVHa?p9t6J3Qsd)Sc!_}$m3HfC2$l( zEiMF<>Fu%>by}^mnR!OBf-z!V#*e_rL(nvpNXCB$(6a@&hH{cuS>~wxZa%6rct6v# zknByw$JHE!z##FN#ow@rF)-;$`Bp_+oJbJs6hl1JVYtP&5(Qk~B;7QGAURS9-_&zM zMEod()%5mXmF?YpiFzw*ginl$V>rxC@KAg)LTh(kPf6lZRgc~j0O~EwxC?rt5uy3E zFx>@GEW{*e?UXxt|E>&PKY#U*8^mviG1=)#A#&bsP0DPV%N_2@PnQ;7)yrn!IYWqp zGb_YCfCD`Q`dzW+L;Of9gE@Qe8H9-3IE=%Dv<8~zb@MQcdr*3^l*q<}l&0Loq_9UU zefk4I8l>L@L5EK#{V#*LB$0S|GX%gSfJNpK-k!OKN)5CU(+!SW&{1Eo>Wm6j3-!F9 zre7qw<|Md7kguMn#YxK-Ew&$|2avS4bmt|yaRhmFjOkyoxr_uAz7B*ytcLV86uK{j zKs*F6b+WZXgz5x2`IeKjYYJM;gV-8^S))}{AbCe@yKCG{aTG^d;{`wquOSoJ4(Ts9 zloT^4L^j+F|CMT%kC;PgDTy;&^|h>woxr;ocQPszmh>4iWmLo95rslrDMK98zXt#% z1OPFJDMMUb^?W>>QwW}8JTNT8Oa*{42#qJKj<D3aT5R7!@I2Y1)lT@BLU@CSHecDX zv}@PH)MtV_C^5S$8AD`(LcA5Qcf|gH{jTT>rmMv;Jc7L3ym?JML!3eYSb#z_Y0X#3 z1_S^zg!?nyLjW*TLmUF#FT^f7M3)4>0605&B)Sb~z3?(N!?QtlJ_N3qQUc6DN9lWI z1VIY~0g!wXn~%NCXGnCX1L!vd&?!VRgu64Sq*~C;K6Jg)4^w^X#WJYH?d&f@B*W`> zMBA@D|3RI$TCn>dFhun##K>0(IY9lU)Mj^~!U#bAg*t@uXAdg8K>$bt%?AJkxPv{= zKo&&9y7PWoFnmp%eAePMLtwle7y>K=xi=_;A~3}EO@c2hE+IJt5Y&VrxC2B8y&(WZ zGgtv8;R|pOVM2umfi&Z`aNt6T6Dd}-c+ny}e;5O(J6P{xx_klnAuI<kz%O?Q-HDqB z@?g6F>&#i?hO**3jtI?ZIyf?6If~+H9t?J{<W8kanKs>t4<AsA(f(DFNX@B4f7G7s z{716l*8rW8(yMrH+(EGx#rk`P5a&CT8|J~2noulCc?;hxT$>dzQ+PNJ!ZT<fAvtUa z|ACT&rf}Q8f98rV3}Fc2wuL%@!20*?AURAQDY{iSFYQ4r0YD#o=sIw0*@YJlRtO3m zN1^IgCjBWf-0Xvunf9~z_7OX!;1I%8`1Ybf;nTC)v!_!kC4}TM1p3Rf;<1etJ5BVa zwB&e-sX5;322?7sgq=_!w6_o(bc7?|-IqxCAn6WLZz8Oyi_JQT*f{7N_7Ktup?CZX zAOQms2!NZn#2E}Ki3+KR98V+~%@@rm0+2PF{wM-Ni55FZr~_r3NF#+3TqqrO+Cfn{ zh0>|XH-wxa&MJgTdPJS?X4CJd;3$#`MULt@N+Bm9oDoae29xKWiJ*IHk%{o||LvcR z_HeEuJpur5o_Wqo$RIxmM97~YCz?Q^IWMB7fB^bhlTM@(dMgj;HZZFu8nPhFL5k4K zQn(u@0wMsN6bXPFg~WO+p=~yTs>6hO2>`PI>}c*$UtS9!#sEwV;4Zirf@ZA`n|X&* zi(Z5gQsJVMGyr#S>IWW|0&u3Hk>DXtEroswz}V?xZAz+ELsN(wW~l?V*BL{th`HyO zv*92i0vM0n0Ai@Gq8Jil4o__lau*?Q{`|-rI}xJy4Qh;|C_%I+LWPQisv#`h08)c) zg8pDlNS?hGvNK_c2%)#zr|<!ZNzGaf0t-XRdGjE9;Nhm35F~<1oM;d7|0RGAU!G{S zgjRiZ)r)eTNCd>D&3Lw7{iEzTXy3VJyMy`(haGnE8HcEZvRO%?9%cKNBItg0iOS!u zX=kK$T6}96*mlw;A$6wt25p5vav5kyImAcXaQ(~!)j_YlH-LJuUMLT~1EA&~dib%& z+Jxqb@r^u=k?2aj6EYA}a;&=&6_~)O29js|=_HRV4ss_SCGi@o!G~#+h#!6kg-e{b z8s8&W)&_}tDRU&NlAwb`{KrXX&E}QWajb(1C0|B6s26Nt+2vKde8D0J5f;kFM3;7c za-m0?RVY*3vx+hye>N(1ILWm6s_lBp5r-RP5#mOyn%ECO8?+yq|Lh=fCajG~6Va1P z`~jc&)o64JsYy}Rvb}`B<TWlC4E=^vL4^>7XyWS@IZBe0`;3Qb|F{oG=CKlcd<7;T zp$AOlQIC3<g;ns7$4cZ8qt-=^B}P(6NxUbhHl6Ps_26G^1_K~+<f9z(s0Tmhk&k)E z<4Q0@h`;*xmA}Eo9|&xdJZ$rh^XSBHePa-y=HU+<YEU9Ixzs^MBbNfI1wiG9kw)@i z4tTgQ0J^iy2>}EZx%@*TLOEjpMv@O>wdyV|8OeQ40*|i%#U3tM3nR(VGH!^&eB}U* z`|#mN)1fgV6_H~?24jwV^n+t-!iTZ^CPyLi!yO!xOqt#h|Be@yBzz^?i8IzApo)M5 z9$0&aJF=({XJlg|^Weu4UHA{I^-v=27-l^N^NwM@gCAGS<C@3^$^%h`N%qKKI2siI za@r?cY2ij%{&x`ehyzXRtdu(wVvd&Gr<M~r;X%T6N0^v$AvYSwJBT6<aG2~jL9rIz z<Pv~>n9m&Gpp0#BG8iGICN0!#&^W#U4snnJ9@ZSA!n~Q0zmUUn{;=maxN*smghP(x z=n(J>Vh%ZeWo~jT2RUp?j&jrlCfgtfOAYduAWY&T^(dxVpwdXj+{JI=2u?V@fe-W5 zBOGn|hD;4I)Opykq#Q9{H|t59!R(Wpwoynqd|3{$|LpEudRhwA0%|gxWUwFqsw3QL z*Ef*F$b13vWkoj9GWQh*9&!w<Lev^oEOEm+l$j__dMHGP{=^(nF~>MAc^_`&(HvR) zmOn;G8+#hdeDt6PTqlB4f8-USKZ6!G{P7jU?Np{Gv_~B?Xt%)yaX=gKPh(NFk;M+E zWGyRVu{wE2(#SQeyEETLGOLy{WihddgOxe1*s_-W1DJ@-;#yo7KoK=`hy0l6Qel;k zjkvHM*F~vDvS_}qPzEYO+?Zo`!e0Jz#E?SC2R_;v%86(epsOP*Q^vaB|2`OZQF3r> z)H7jOjg>kzI&S%(3t=r87$Ze(W`_raBEpcEYQ!G4NQzYqseIJ2#W9xgjA>kB8{b&Q zfweG>dE8?k{}{+Y7V?lU!eSyH8Ocdj@{*a{<o-Gt%2Af`l&M^02=Ca+S=REFx!h$a z6W7aO7W0_NTxK($8O>={^P1V*W;eeX&T;m!fC2&lA^8LaWB>sGEC2u!0DuAp0ssjA z00RgdNU)&6g9sBUT*$DY!-o(fN}NcsqQ#3CGgibQFj5B-8bgX4NwTELlPFWFT*<Pf z%a<@?GE@-2kFWq3OrVg-v!~CWK!XY$O0=j^mqr)~1bMWn)2C3QN}WozYDSs^FZl_8 zVkZf!V8e<XOSY`pvjbsWN)o`thqq|s%AHHMuHCx^;j|6#0k7Y`fCCF2tkOe(5?u)^ zUd*_$<FX7`2n4kEvE|E{Giz>%fI&ePhMATqvAMMA)2LHF2mpHE=+v-d%bp!LLx2@7 zXzSk1yLZ(JtbGd~PQ1AB<H(aMm&$Ru^XJf!qfryRy7lYWvuoeZy}S4C;KPgmA5Xr# z`Sa-0t6$H)z5Dm@<IA5<zrOwZ`19-E&%eL_{{RLkpi5>9Xy8an9cWe;3N|<q1_Mzb z8B-2U1xAG!KIDWz9Arq<6?J$hB0`r4GEfFC?8M(80RU4*02hwM%!o7&v`7^bv6Yp2 zzzB3<jDg)$V}B&95Wpf743wLS1kr(kVMojofD5?^bc8@mhKB}0Vu*FckTv2sS%(*K z0p^)#UQ~i)1MMPEUkX7ZP!$}=phZDn1u%;+QVPTZoZxK{m>Q9!c^^m|B$33G3?<>j zqBp!|P=^}|L_(J1F=*(fMXC5Cpa*f#A%uHnY2-j;=E>=*tnNf1LoCGq%9IIAeT9Om zT(PR_uDtf@>#x8DE9|hu7HjOW$R?}ovdlK??6c5DEA6z@R%`9G*k-Hkw%m5>?YH2D zEAF`DmTT_0=%%agy6m>=?z`~DEAPDY)@$#*_~xtczWnx^9z5_E1hBsZGd6I+2q&!Y z!VK$s@WBm7T$Mc(R}ApQ0T1*rJQNcIvBV(D)bT+7{PVFu=9nXJ#wmN8amX;IM6o&f zq}*}<{`hmSJqL|^bId@uw6i@g|5J}Z^&D+bHA(+7kU2aDEj3Clzf2G^0UQ$z*190{ zOaRq@lMg{oTRrvJ3!O}|Kv4@cia@Eb!iw7gw9-lduLKacDx<LfB8n;ni9_<pXct}( z!1&ah^4J0VQ;sy!ysgSBlv7TS<pHRo`Q)!~4mjU{<Km6VHRn_FKW!T>HN`nEp3gt{ zbR!Kfv9R*?Lz@Ghxhit^&PwOB1n^D3@T9D^>L3H0GCueO98Lhd+!9MHeFyM+-VNnW zQ0|($;>s&?3luQwsUMF#!uI@=veE(El6fm~<E^<yxqB~50J5YK04@OtKG4V;J0HQA zM=`6>f_IdYg#s5S5brh66%O&91YOZR2;vQV;gg0v>cJ13RjgtH^w+^!77kum4{!LB z1uhhbzYAgna|B@_<-&)wdQhw%{Rm;dl=nLE2?TSL)12@BDmX!mI4}U-lbZ@r7yu6b zqaR6Qo(>7-v}07y6$<2@7B@!{?WJ%a;1EYSjAynf(u;5cxt`o!A&Vml#ET};;typ( zi&&8CXJ(X_Kae&MSHuE*5wze-AgH?lEDj$2C|MrkRS&1_PJxu0pc{R1MBWXA8%<2w zBH?8Zl|8R^YlI<D@&>phhR<l`+vK=%Rx@%4<QPBPT@jHeNJ>hucauA%D#x`k<^c?c z18Ifj*vLSmuuy((<V860F)}Fz0FArc77jI8w}EtSepAt$-NIK5r+qM*-YQwn_`whV z<*jmI(cCcY7yx_-M3LYOXX@r=%CTVc6}J;dCsh{z&u%F#8tr2v_(W-y_+1bg)#zuo zF!oFKrEx9})Sp1a;Y@`}3t$C=M+XNIK1tTnDv`8c{@RI;dZf~#$Worla#%O`u>zZC zxhFnp=unh83vur3<Nf;hQL;?%cLA_tPN8X2VdV^-0Rv_<MuA0HgmjW+Iilrs2Ss=m z)mRv{#~xW~JvI7{hG>zS18I8FtM)3ZP<$gOVTu>+$>JO4NE%Vi3as>T6{yz)j5=rd zPWADVuE)CHF&8t~<^h&i%#0e~D%VrLU{i(Q2tYZ?5yhMymQ^1d8!vQGxofi3v8p(x zH1aW7U<RP9mmQHxx$z89bQXJ`wTt&OH`pfs_D`RwOD&o{I1Y1|aG-_cC|K*_JA_nJ zw}t{(J<1`FKfc1H*kermSOHmaBn`F5bx=n6aWrI%;uYSr8$kyX#6p(ThPlnIhfWrb z`zg_>(cK+kLfJWhGB<$g716-zk<jQGG`5$~S$>B^yn(>?xvhXIV_;Yed-P+j13nNd z$7YXwR6`VPq#)<Y3rF(ijk*B{2kLOP#|S&fmjP2+-zJyF;W}ovp=E_MxRFCVn%F>6 z^oP<8=+!rF5x{?`?K{(Z;{n;MeX`)4SZn!X!c<To!E2&8OI&3CP|TT*48V80`qJQH zv%`W}vOu0EzA{!hKR(MxO)&@L%c%4JZQ{To#?I^?Mb=|%?!6vrj_AGk2EcSVqqBcf z%nf9uqH^1Gab_wQU9Jk6Kk$qiXRm2D*z8pxU29~?tomsD42;YtoDEE|S2OH(dOZhY z9^>x!JwI#4pbGisspTVUNdt1Hv_WU^#%AhSqsMfmi=}X7le<tZlOTciHG5S0&T?R~ z6$_MGn=J$D-2s&#j#f5&C{|M@_U4Gv$fUO4GqlsX@2L``%`C?apO1B{8la@5m}g_q z#<IITrfVc7zbkDn@@BmEc2CI~X%H}<hONWY7^ee%p7j;Pl+{K}#F2PE6aJ6L4F8VJ z_<4&Y`&+@Lsbp~7_soo^CuOkzbK5zmy_qj_FMjT0=4s6wuStS@Sp@H6aSXaZ{n@Zz zE|*r8t(V2%65HPo%v?9Sy)RccD<AD`qYHK8(LRIsdw??<(@h>8bCS~NxC6UjI_yBe zS(ad-RF>Ls{q1zqGU<Rb2Xk#qtPdCLgOdIs25+tqFS7hE(|ravo_H*$@gi<0u{c2h z0SCq(q~FT=U^$$|+3-zVIGE!Fjr~fjqdkKbPPKPMFh_DF1OO0vIK3VyQ}DMP+UdPo z_&`KK@)@#%@4Zn4GPn^i)AiL?HS@<f+L!c%Kt6k)6UYn_f(U`6p7;+n*36)m-o4`9 zAg_hJV@9EQ)3OcYXF{X@IpA&W+qaq^Qbi{%J4=wu7eo%zx|yRPnAeIJ+%md@ha(}J zT!M_vl2dm%*t0+$rx5Y=3dJB0O5k__papsn10z5K%NGDLKoGW2EI5@u1<_^KHyoPx z4my)D{I^~igE-6;0NxM)U(-_X1305F3Zl>oG00Qgb2|fJLd9@532_4xcmp;-5O)v& zjbI4{A$Gt5OpzrE{q}deAxg=%Djzd>0+9w~-~>=mDcIv@#lSxkF#-aC14cj)ZlDEm z5CBhbBxWcOxWI*?U<>hMguHS?{jf(^G;a{mfu(UV$8{!=RS?qP1_4k52$6sUp$C5O zd<cO98IU9a5CMh%I0#D7HH&u;Ny3F)1#rQVR?#2|c++J-##VBK7WbzSA-IRukyTQm z3<FUq0WbqHFam550|GGw0`UU_;R6Ek1_MC_OMoM+_X!1YfexVrf`~#NhIGQ>aB!1h zfA>{iHD6%megqL^Glv|gSdALPG4?<}<1l;y@D7m`jsXA;At*3=G<0zy4FEL|E0_>% z5C&*424g@FY!L{75CBeK8v<bog5(E5*nj~L1p&YY1Az$vU<<c^3$MV1fb>$Sz&|x0 zh){r!fp`$YBwxiceFl+s3sH4$Cm1#-dT3!jYBOgJL1h<*L&?^S1ksIj7h)k64xn~+ z1R)RdU=Ydw#t-yR5QLBi2QdW(A&>+?2?0QqL>U06;56)0C<DQiVJIj8Pz6z71gt0! zk`M|BxjzcYg>wU6-nLV0rx5q^WEr`Q_>exupbK-O3K|9xq3C4Ds1Vdx79Z1V2!WCW z@eRV$5c4n(BM}8ea1cz;5Zu)`Mq?27AP@Ht0E^j@dpQtLc@ToYdQdhHmdFY^s5?K# zR+88UanJ{5_$7j{2+)^O8N)pM6bn*Ue-0r^nCKTkl!dM~mxm*QsWXBM;Y_l2jYNfC z4k44@fQ|?uoEZU>1R(_h5SRy%1$mGK0YC`UkeC8NPVYcY1JMuf;11at03AeddKr@; z_736yaDs-^GAt<$g5yh|HV~3fh5``>mRL>lSxuEjOX<gc?N><gMRF~)EWY;-W0ML5 zcpP{b6D9KwC&*mn$z1Ch6Ctt?ZXg6%AOs502@4@7+|V&lqdw{LgbEQ3;u(|U`3@wS z5VA)Q%wviLVFWY4A_K8y)<aCbV?V{j5UyZ(qY$5O*DN`gH+B=2P_b@8F-iD25cS|p zYV!``z)&=&5a7^<r)3f*(hx%MgH=kQ1W~0~LlCvF3tif!Zh|u=LlEyk5a3rbWAmK^ zk%A~l4zA=A%he(RQH%z`R5K(*me)H%8WCW1HzN5fXhd1sU}!&NbrKPh2C=6T!Dk=; zITdBP5O}!|iP@M5L8%R41q$(l2eAoE83~&Z0EHq6B<3`GbW~`HrV()u-N2ZuYNj*? zKo?VHWmcC>nh|J3F~k{=2MIp)iEhPLpa|hU8-fef6L}lNLEQ$d7on^O;Ze=ns6la) zH_4cai4vMR8GT?PpeYdBDiHAZs0+b3e<rS`vuQf!5GnXq2C;GFIW{ySuI7-U@|vPo zc6Rfcq5`3!D?vU2AtwZJ32PWs=qE|P`lk-T2)AH^$)a2wlv6&cgEm@AirRt9dO_$` zu`yIkLRJjTz_A5Eh>f5Sme2^JFbD%7p$q|t38AtLK@G$}4evxY6*jKov~>snArEC* z4$lLk-}sHsBMz8^Nl7zVL@N*{XqPL4v_+9KOglaUfe+8{HnGrgN@#x0%2OesXvu<` z4WX!sDoJ>1d&lPxcf*NylL`_g5Li<TCWJM0dJqbWvRUe!5=x;t@P+yq05D(>IuH@L zdJ*oB5TF(g8zm5Z>6eB(59E++CTS3`Izr~aY!{)lM!~c=!!~hM5B~5xvS2q@^gteo zu^qWA>!UQXa0|}Zcm5W11L1evvpq`ow);bf1VOvFU~!74u(>!8x_A&7pojs0118`C zDgY5&xP=RWxC&vZ1@R5xpr(3R4&*=&hl>#OFnRwFsZX0zjhi+M^?hak_CZ5Kxr70J zKDI?AaVNK6u)#u2{V8$^;f&Rmx-qIdFh~%*fD8P25Q9Jn{rkU!5CFeBz>27dFrWbq zK||QXka*)h7H12^0KpIpw{!!8oCt#un-Ci}4(5vxOiI4)VGi)rl@>(5B*A*?`z)-5 zVG2}S3E^@utUH`2fI2D=Asey?kpc#x!$Ob;qYw&2XbGY~gb^_cck^7BDK~G^3b&)X zPON22Y(4NZ#o?2|+33MEr?jR9!rt*+92S@B!flxLnjI-gowE?aI1r2y06!>;1ECa+ zfWrxKH?4pRI;fC!9D`;%!vtZr&!v8m)K&Fq5D=?_>Zf-U(Y>4h@(=#gpDb|+ms5Pi zf>8ot3rYxaTDy^5)<6MJ4E%`%@TU+Eiwg;8#Rg#up&*QOY&VrAOmf4@w`0XdjF||r zSCuw5xO_r1Buv^Dec#8$9~`R>p~&u$Zvv5kFQpQ<a0yi@$;mRKjasA@n-CUY14w`e zNT3IABV+*(3J00W-n>7SS*LGP&aAvmyi7S$EXoEb&DLa$74eeAk~7u7pH8LB=d>&= z^+#Q$5b0NkJ@o>pfDo`?3o|GX^|{K=h0yfb&~tOnods6&13$WaLcMIC_6DsDk+#o7 zG{Sr=G-D2I`!>%7q!$6nX2L8@%Ra1jqrFpbo3loIJP<_xj1YZegFXOxK!(5C(89FN zE@gR-Ctes-%jnA!x`0WJ#I)KwEE=dXsH?jfaRbqUMiAt}u={1v1spSs3!xwi2W`aF zvsbD>#qguBKAOvqS8&n@6qnXG+14z@(?25tRw>;qID|>DgiZI!SQdl}mY@QuP|64m zNCgpH<3+{<p#@cd*oqwhmXKjifuFpf4T$8M&SJ9|Q3XmM2<|D)1ECFnyDB)8Q!cgE zEoQ<ruz{Y{VnI#S86k)`a0w>e6t^?kwR$YItr2km)y$$v(vWAE6T0c<%_`6cTqt&; zt05poId7A_{*Y1b5<a?}5Z;)KaizA!iq{sTMXx*%ThY4b{|kqX0Yl6^FX}p+O1)2x z#90TCen}@%0f4}EbWRsN5~vpdbPxbxXcVlAGLhTS^il(W*nG=EIBs}B)~8_;grDpb zOxSbW5y5&mVtP#hW6gyNPBY#1q6AT(;euEP!HI!yJ+QRp*j(0SgKQ87)Do1b2Y2!m zp#<Lhq7067+nh2pl^H&J^~D6i%4d8Kv>-V!E)jIPdWS6*k*kgTlD*h?EZ_rUAq9%M zQ)y8y5EYOLykLW)h!J7v1W!-{`Mo=^6}vnEd8|O2zxOUpT4G5Jh1y6l;#xu2o#l1| zhnX4V3bDVZ7XVN&k#O(@1;NJ%*3%l6)+|Aj{6gcp{{k?=*J3c%WG@Ujv|JEOjN@SJ z5P?~Sl!<yS8UR~x1v+AxuWL*BYEp>Kb;jXLFnYBSG1UceKX$~v3Ly#-9ssFF1bQJ5 z8v>Pppan|61-EWZY^l*I;XrSr4VG={&XF{By*qf?V(k}=xFqKD831^I<*YkxraTbQ zT@ZL)6My4l@@9VEJ`#*}JI9Xf#&JBGoDuzYH#K|^OgIn`IS>;l5G@|Xl^F?l0tIle z75sw>_VYy-LFo9?3f~|O)Yrl2o*q!uIdkL9POW#pEqbjWJ(ob50kG)-a0#Jc$A)}P z`nwAlFA$`ugGmPKf%LTsgz!AW#S6b1Gu=hk|F(exOU6kQ@pa6FK>b+1^X>w{iP5E* zcD@khg~%^o9cmNvC2`^cp#oN*gQDPxLjUYNUK2lb&UM3@#AG=-C?$O`kqB`&L(dSH zV@I@&Vn=U{NG=ex)4I~05$bGE5Uli?TyL{wiMSBf=UnHS+-lK9_c}OS21W3yJy4Q( zq|H<6X-^wse2_cEnj}F=T6WA9Nzu;UM>JI6rPNbSes%XGUIfvt1%V6tL-+?lP>R3! zyYVsdefcRNgW2x(Vf$g>%<i|>`T-ycmq3}JtcI*+`V+TDF0cBVA-SAf^efTq1hE7! zz)=b-Z5wX{HH{G!q^JAq22Rk-42_Y+|A%k^fDGVJQpE2ZKco4O{}MV#l*JnWzCcet zP4gFlr>xy1Uyed~KR>Q!KLeNw&v4`bVa{9tf&~p8M3_+FLWT_;K7<%i;zWuSEndW! zQR7CA9X);oc~M|NU9SSXdc{g5tB?s*sUnDyAg%zE0>m&Vij}Kdv8oW11rwu6SFTi| zd`Zxis!;`FSqh+~pr24IQMQ8V>f|d~vSz-bNw8kOd@aqMMVnUbTDEQ7zJ;sSp1p#$ zVy0xtR^`i9twyy95DFJAs2ARZB53zg5`tDazT}G)vO!fQ1MKp1FjUi%U1f3gYH$`a zZuzvqi<?^YYSyh?zlI%KA<Lq1{~=cnFv=w70B-_h$xP4*tpKc&epHDN<*Qb*Sec|5 z368?00RStkN6;Ky+1<T=2OnPi_>1u1jck28DN>Vpd5J<;Oy^#qYmusI#j;hXMFF@N z1T3tF%p<Qr0}n(nK?Tjy>aE%WDC)rn`x<2wTWGS0y0nUV$usA2tFIt045|bneT)ep zop2Upu|*eOgi$<x>d{7*<YJ2uDeK@1po%~ULgl&;&w44sr6xOQ7J{G%fQWMn`h}n; zopDE;xnjgJOD(tLvZA^8DJKA1SgPzs)mB1tB>@9ibGE$NBI=b}3R-50030D`odD1o zW>0Rq1T;`V2W9b}e+WWN|EU0uV~x>+1mtDT07O|rAxGh|EPzZ1vU8t=%qc4XfBYe| zR8vny^{s(;iN&N#F<tI1nS}Z;w1h4RfS2nKGO{gZ4vIz`gR)DtSYwYxHX~3Q%S)!! zmW#D9gHizsB4_Q(G=N_T>hqfb*g1%<E0ZO+Tysyw2cLiJ8K|JVx?&C9txh6nF?XfS ztsp`OvH}-gCf(_?Y+XBa-MI)nH(`YrhH>3{?{n?8zF_K)AZm|;$uGMKQsG&PiAx9? zVf!)EpF|l(Ic1e)470ec%uJ1_BMI8oIu0S*D>s(fET}J0@H#8GSDIo*n1#Gq@z7CM zX1Zyo-^wSS8Qq0=|26f7q`5DxYwimnQL<p@##b#W>a#b&iDn=G1SlvUZ@~G7)TigB zyKazZEQwy%(2Ou4`Ve|)rG#*riP<;ZJ)EMe0Lu%U09roCZEzA@+HT7)$9$oB@ChLA z`^IMLHY0gyLyMB|0-d1BWD=!j8|nfPNsSg)CGmum3H9X6cjrCx(@(lhwW~w?w>aal zrVL|)aLKlp3ysGZ`G;sHs2Xw%0ze_hN!7h~@4ruYu6_v8b>4z{RZBuwP|DdLSzPJr zrE4K<@LH4ldNUSEDm`c?Xq9RZL*!?f<cy*ie+mHS81lBbfzN>tOxT~`W2E_E%OLFA ziTi+JtAscU|0NG{S16uW5G%N>DqH#A^nhj^z#z~d0uaC!h!uc$5Tu3>#9<BzWvC9S zPIhhyUO{dFpUebBdT#Qe(Dc&^Tlhj2d01XCK*Wlz!Hic%$%`m(@sD;D1Q>28h%yo) zHyxJIj4(3KT<S5yXx*hP9vs-TDi{&<EiOMB;|=*}W<K;8q$tjkRQKp%5N{L&8Z<m( zA{E&pHP*w0l}Vjif_M;KSS5}aiIysUhKr2_011`>%nt##x>xWBA>Y`9unYnXZ-oOM zWL#t{WeJ{fNpL4evf^r#lo@Kxks@dc92K>eubTKK0Dh1n0gq?6WmbzDBqK<u0uYUY z)S`wa|9j;uwYkmM2xN@`cn17#lgqR?YM7D;z$I|;CUQ>XMt@64Q&O-zya*0)dK1+* zsTlyH?ZR7Qge5lxI#9XH#UA|_-=DGtLRbwmYe%Grkr-MK<^TphQd|hM$mx$zb>mmw zkOnZ^fe_SGj-V$+X-m9GELGI+l5pu-0FD3%01i-+`SFXGtW&~z(QFjY0S!L;A&?aj z<Qv~$2JQ%=3~IiEE&)wxRHbSWL#=TjZEWXSBD1CpW_2TJdQ%<`Qo^R3kY4a<*Qo3f z4z>oMiw1EAT@W@^y4F=92zBH60@#s>9^`}Ta}`aFU>yjVuO;aFpI8IH!CcV`Fyjb- z|CRpH4};o6Zu<;?G)6jCyLQ&I3c1puezqu4X5?xRfnNZeK(&{8WO$H~$uLKOm;gW} z0DEYJK}IDGajYv{1Q``-zEQ{;cJH&tJ?_DziNZE!1X{j4i0pD(Skj&)h4V|H-sEEt zU6h3$-pYpp$K{WAgyS71GYDsqyWXh=w;(WaR$t56((1^R7Gc4lY9#c**4Bbp<hb5J zmR8aLn8(2EMetM`nJf6@*LZCy()wEQADVQCv2X#a4_R1{XC!1r<4SL$3~by4m-wW- zfUjlb8xr|i0te`X%!(PhVvwi=URWVWEEG7E0MtVs1o>@3)N5iQ57dQx+v`~#|8y-s z{G>QlyJB06WMf%`vLNRPz&xNzkbi{3AL#;fn0H)cGS8A&tpKdd(t@VE8l)*u_M1J| za+II~IhqCW$D!7+21IFRA)_*BnFX!GHF86hf6cC0o|}?_G~yOUf#U@i{aow5LZUno zm8j$<kZ;T*0Qqp7L4F(n$PU`n+T1Zb-*Oy447RW|e(&(+%TROVId1;=W&pUO>xKk6 z(5D7=?{-`}{MoL?c?q6?TH8NktHn%*L)f@@+pa_D4mF1YE}%giY;Ip}E()~8h0)?D zGoh0+u=e33(NdJdHP9eICdiejy^wyi>|iABcD`3;o?OQybgN6wn?muK{|JZ2GCPKM zfe)<kY&Im+SH`!#CBCqFwCtx^h3yK3=$uHZ##t;mpjF>WQUl+6kbNcy6%tZeL@j*c zFGm)7JpKy#1wcuvqd7!{hZ`;{{N57D=B^KA1tAdR9tJ4~u@J`DA;aA1UFtV<&5}z? z;6f|thKq$$`{|PJdLjlcbpZNN4T1>a6wAGL)1SU}K$!=jCZkD8q`nbH$tx<j=t`2q zW1dkZ9O&?{#~R1y>4F%uAm$K94Zn?#5wqR#UE;T2m#vZLO%#&e`FLcl#Bi5KB#j0| z$f!SMj&hWP?*-ZR<5l0HY|_FcT$#H?ZUZq@(1bC-%Q<X5&Wczd{|eC9#0Y2q!H<Fv zzaXnUNIB9T@zpoKK=8n8W4eMttVa~EC;69Dm<5|Z;)UkX;6}wO$HR>n%1}`|$UGi? zXSRw<)6R$g^ApvN86sQf8{rTKoBgbM9wh+Wz=s+7h`9(Z!1Fq6Gl*JHn(`7c=8L}v zT#cw1Fjb0$+UdBC2ob9@tk+;4%gBdvkU+UXzm6C`^V7BLD5~`nivR$J<$}N$e2sBQ zqq4Y#{OG=NLI|LW81-NU&Jc%uSgFtRh@U$Mnd`ZRNIe)-!nF_x^JqfU2oq$`4LVB; z+dBkYkc{eEw;Z{avakm(+79jz!ir!z153CdYnN^~2%Mk>|AlD0C4|GY7#FL0hE~wH zv|xny(h4?Pjfv8Ra^Qz6>Abf{qeHnN;zI>PGQN1Thoy7CID|xsh&FpbKeM?&jgS;u zur%N)tyL2Wn9v4csRx0O!ACrcg8{^rft&!qgJVEIT{D=)dpE{2#YnV8Ml_Ff$qurU zyUE*#P&fiTps1X?M6_TZ&N#m?Y&q57ta<<wa|j1jTEqfd!GAEoTg1kUm<xeGKPl9~ zwZMfGQ@6N43R%#Gf%u0YQ@gkrv2?+v8zKlOa)VEJhJUDsdFU<jW5jIaM<i@S=o_j@ z$+_5LHm~Z6nwgW_iw#{M2(nPd?ijIt6P2V9!1QXF|5x&dB<#nHEJAY_2gqs_lMuIt zkTLl23Q^z!VSJwk(ZZlHlVAG|N1Q~1P(kB6J&wdlgcudyI+ReN!iNYVN4c3>xC9(v z6Jbi8abyePh?;79KLr6iY=f#!xCg?^$(*b#mMe%iyT2TivwI2=tgyp(N|X5lAcA-X zZLr7Bb41sW$q_TaTvQ-uL<lONgk`Ww)XU1N#76WG2W?QDh`6ri@;8Q*gYtnSQkpa+ zYY>=F2}8q&e!!*%Bo9X<MeeYNunQGFI|gtF6Ucfcgt<(<v_*Eowvhx%tbr~^QOdRG zJ#iSH0MN%5`8|S2Isi)`X?g=xkOxmYxu_XI|I&QGaTynZIFxqz#)v4bA6lnoI<549 zw1NmfhzqfGd=0kL9j!FNF(L?Y2*V+>PT_>P&l?qU;D-BXNr#{oHZdMP%&>>>DmUpX zhbfhGIhX+Oma#a9L?MTHkgJ6&Me%IDSE|VLT!<l|ub}M216@%0^a_?By?O}GEXg%e zL9ajSvFou$%2YT3UA@Qy%*wbKk5~yT+P(*?h;~9UGvNmE+p=OQhoWi-jD$%KT|2qF z&-1|uhLVF@@QPw|h}MiXn+kwf;Dvw4hcC>u4owxUM6cK+hJxsYa1p~nv{9#9maQ}` ztoc#(kUd$8F7-eO&ftdac*AlrFyOm~|G?X^MIZ*N1WmZS(w7s>x5^-nSS`FGEg=;k zFdd}<8W{A@$WvJ(t(=Q-NW*`C$K;bu`qZ}<z0#^0GrNlj!ErKrfi<rJD-}hPp?L*x z5QpqIQ)6i)iCjEVe77hq2zM~PP&3X~oYRS`2Lxn}plCLj;lsi?j$FN`i-4!2$cwTN zh%hS`t+daq#E0t%lYcUZKxjjwLeyCeGOdhNQ(LLB(3LlNm0&U)Rrr_NTPB4ZrEzr$ z9z32uDpHcG#bX)O$_l&e$b&3Mf>VH{f2`JSYb1oqHCq|cFl`7+11vt>(*_;baXN{- zn5+riw*xCZbUX+=IEZf$7q7cl|5Ka8o>{EWxHR->3ME+tNujPjdI(s%L9IxI-UC9q z*iOtz(+lMXQt5<+078Knxr!yTFRVDu35v-plAtJvsv}ZM`5}Qlj<P8ZTnI(;a8xGs z9#ENwdB_KAEIWkw$Z4xt1UrNPh=e&Eu`i688M?TFMH2thK0B<8{Ghp)dd?uN9hT_9 z0652VESUrvGw>n8EW?M9Tf}ily1P9tA^-$HsDl5nS!yH*1ggNTxS78)j<E0p6hqIM zk-S8c2;Jzg00_h{^tu}T9v~#Oo|Bs;2!tp-x&R1=ByCjP0<^jUg#VzaScS_(;fF;8 zs)E~7&M<;d@QYo|3$b~v{}2hH6w(c{%Lh^kFML?O2jZ-B88LDws*_PUhN!GjB`6}0 zf+nfh->V!T{6T36jX9Eo&Pj>-$fe)Knkma5-Uz_$japbOBlEj8d;Et|t4M<Qu@wQ8 z-zypIjj9?bTqfnLVvvPY*h5(m5I<N1qb!D&@{qFOptWT-2X<Rl2#ZizSy?K@!0XO} zSVgxwJkFa;loCdQh=MbK16=vv!$VS4(wW{f0)$|MxbqAN&Wnv@$;MnAcu@tAC6LX9 z)EuhKgD}B*s3Fk{040b7U4Vyse4GmnVs6@%7w$cLN@0`9j`?NJ0GI)UKt2e`JCh_! zW+Kbws1Pdpzfk$%|EV$*czB0*aNmO<heahQUrga`G>7P`g8+Df0O*71hywpT%Z!zm z_oNR}f}cDJ6@*$^&qAoVs$V)d1*;s0bxmP`I@N*rCos|jI8XvQAOb(?zUc$1$hEKm zc9}a%AnN?AGQ1M0k%y6L2yu|h>ZIgK)}eGkJc0nDJT8bncwy<wV$Yzc3nGXLnY^}S zTI6!Vt6c~KtkRZK*xu<%TPBFDB?v(HWH!l^)M`$I;EcR*A%>t{<SI^P4rikqK2rO~ z28?EE)}ce;WrEm*06>IKJ_W!e2#lf`n$YI}(C4zq4x0V6<<j0XuB#`O%|=9s*c7#U za2#`}w$*j#|808FI-mnB{^S6p*n&`(VW~KjYq*3f=n_Nds7aT8Sj3Y<h_b*oco@N@ zG3beQphOXdC{PHAJ-mLv2i}TIh#1s-i`{#BtFW7<uq)GtRM%RTX{P}`f=Gh^C<8Gd z2ycL_nAS;HLg<$Z;<$ka`kjYF3;-%11!hnhM9Q|SUTQ^(D+1%ox8z_R(gi3&2=hwo zSRx~Ab4uZiU1$z~liSW^kWG&Ex}UCVmPI*g<lJnGU4#j<Ck%jYz&1(9f}#t6(v2qc zxZuLp?56p=tfW|LBs)CdAA@)Y!DHynMs07i2m6#-`{kT{v4T$c26?y#^8klDd*)<r zh&N8{|K2v0My|I2aEBGK?1ex;?3~d3^X=vC68KG*@WM8E=xVAhh;?yMs4CC5`Vi*k zZeu}>s}%w@*ac$YhZQM6%x;&4+aQAM?)Kgi)SzqGEF^+hgl(b5hEp#DWQ9RiZuj=@ zEHSAI)gHzB$Ee#N_4)4v&l0)J?#xyQfi50FUdi}W@Cs*<%bbhSTfu@5f=@sN%T}cv z{$6pl@DlHm(t}5MkkJ4jgl@<VF<KNAix3Jo@fv5O);_|6K!)P@sqO<(8wYX(!3Pab z2o3PJ9qF4OS8^>mRwuOIEY1Lz5EwXH@+u#X${H1Yg;iV-D;}}B-Xn1<7xVE@yO=@< z|3t`V2qCxr9`iPji|sJ!gTS$b5CX!vmm`5-H`nvjs0VT|2WfB>6r!1p>F10JqGH?g zL`REVtAjp>g8&F$tBa7@VYHl52tt4bpJJ{yQ}j+xiy0sSKM0G!!B~TU1zR9Hg!mVg zP%KY(b+gz4A^>E{&?tb*l;X*Q7r207=9yRb^`N<#2os&<*p=d;Y!>(DNomhtXZDN8 zTIHZQ>+sndG1?-<sixR2uwlijYxZux2snU(F3zYE#kp3%JHV)rrf3DIn5V)~id1M0 z4+&&%?{=Fe2qhp~uc6{$Bu17P1^6&`hj^c^P&0p}_fCIZdPaySP=bF&2*BtX|G?N7 zO7Mf%AqZIDg$VabUOjkM$Av<d1V2c4;V1}UteAWW3oIn8nh5}lCx~WHvG<X*MeF!I zuQHw4qlM^?IH&?9AzUX*c-rdq7if9E;tim>w3@f_Ll}9#l9i!R2$0Fc0Dyx>S1l)4 ztxIJHDzE}d=p>i%5Mfq&C3nGa1WFX`i-EC>OSpuS_m2R0VXeo6QP>xS;0lQv`yfvg zTG*B9Qy&uzO#Mg*OZWtX$oJLC_i4%dDhDx;8HzMnT!`11OWGAips72Ujv`=!4443d z2w#bSiD_Q^6n-U$c9-<z)nHnW_Rv;nH;5W+G=q2o3Rn_IhXX(G1E{cs|FA8H!FUK6 zr~ygn_0hM{4z7s#vEjdppB&!0;`l_A2#s6#mpQqFJfMMu$a;dvj66gP+9HS%zGgk> zgBp+l;b(c`C(R(6-Mu+i$u$W7v5fLD2*aa#|40Ha_+_{!i0Oa>@CS$h0tXT-Xz(Dy zgbEijZ0PVI#E23nQmkn4BF2mwH*)Og@gvBFsaOeg<tpStRVr7$dd2D`$p9~9(h_A$ zprug)kpy@{a26wiGY|qQ7!xJZq)L}EZR+$X)TmOYBK-Gn;44*BS8`Pala<Pss#=j8 zrIS{GW&uzc6cvEiz#3fy#tF~{&cGW~_ww!Q_b=eUf(K8mSC25(|5qhX1~7@0RV#s^ za0R$25l<2s0ZtVY<rOjL(4t3^E^YdBQj?Aks&si&pe@P@^%NDzK}!IgjTxiv?fW<I z;KGMDRVlDlWSyfZBdfAPZvY&01*#bcp&0S(+P8D>ZrbWW-oC$%ebq`gpc*v_p3pq7 zNfy|;z0<F6|2}?>;=;K#E_`MHEh*Mm07M{EgBpGWfSo|E<@X?j5lYw{Jn#gNPXK7O zB%FT(X_cWsha9p<03;HGizu;tHX(~Gy7;1LAA0xFfC%A|iYv0fxFe4}`k0hG_6Sr@ zITC&dlT4$y^dpl^I{73-L3$YBS5<-~Ba~Tcxh0qMZP+E4|6z(bCYfcLc_x}^s<|ec zZMyj;oN>xIC!KZLc_*HE>bWPMefs$)pn(cHD4~TKdMKiaD!M46jXL@$q>)NGDW#QK zdMT!vYPu<>oqGBysG*8FDygNKdMc`^s=6wxt-AUutg*^EE3LKKdMmEE>bfhhz54nq zu)zvDEV0EJdn~faD!VMR%{u!mw9!gCEw$BJdo8xvYP&7B-Fo{ixZ#RBF1h8JdoH@^ zs=F?`?YjFeyz$CAFTM5JdoRBE>boz${rdYazyS+9Fu?^Id@#aORoJCD=A71W!><M@ zWdIdYyzasSMa*Nv{`dpWJMIL)&pZ9V)9}TDnS<d#{~4EBPC533QxG@;Rp_$06*?S_ zIr!kSqt7?L6Tnpga6|Mz8&51GU=|AGFhBeRfRDvYXSy`g;~W;iJpsr=&^S(49d3{f zi&Ky};xz2@gcQT$4?<_Zb8^o=Q-$+DM;8=MKMmt;X~zGIGf+?m@iWgq6AP4bwpEKG zj?)LR&Emp(52VgOXA|AeUVmGDkU07L^LM4B?{U!S@XSL`09Jb&q|f<iPSDC8Pd*_& z`OGZPKU*7Q&p$ph?$pgE&mMs0PJ82z!^1}!q{aV`Lk>aU6~uV};M5~e)y`YnFw6zz zlMgV3G-JEn_-(wfHU(*881M179Jy0&M{Wx8|LwQ`d(o2yX_%A-7XUmIWF7$^N0GpB z53AvW9`%5jIlLFG3K^yz{}|dpwh@m0C69jHv5Lod*S`R4%^V?Q8A0F{La40JAP%#T z^)LrBkAV<wlp5dk{vn4>_=6wv5S>+O7yxe&q#W{4p$)TzzKW5f7XiSAKxUVZA`PU4 z^?_az1Hd`!Sx6g}liFXvfx?*~F#y_dSOEO7KTu6CXdWCALFhpb2};XnD|8qvw(+*e zO))|h>Idhv0k=}PLvQ{_8Ovs857LEXYy;s(CE9TqaTumTM-y4~f=9JCCJK70`{6MJ zLd1NSqe5<68W;;=H99WKl=x6w0RAu#|9pHb0Eh^{HUfY_Mh@q1MLP^P770Owe9V(j z!Ja^N*E)Md42=Wv9i%Acvs4~(dN?ayg{VgmXi9~bq`I9a>LHHY733QhLK!TxgEO<C zt&|7hCLouVl;Ra68lZ58@5)w6cyMEk!L#3@V26*DeWQvMBOy0cDW#fKEPPPOm^V*V zq>g3LAQ0swa5hG})*-WEH^ay5(&o;m;H_x+FqsD#nmOP_s$s0FA~{~^I)q5+9s=|l zxS&YFgW9Yh<rtxNX!wu){39D$<OUi&rqqh^#d^;qnnF-0!bp*lAQh6M5Ua>k1L`sW z-#Cm@lXBBEE|sZg3hQ8`1`M4F|73g$S!#At*1nnT;~(76M*oTzBtYWzsUBU59o2Xh zbvVqeOrvK(@WG9LbTpv$=m$^-V$6m3tQ_ehVn~8CRDO)mei7ADWf#XvsrYRmYVp`G z334`gc=EHovEuO#a<hY6#kCu;(DB~kR@xSA9hTx|L2WDA$jxlB99bDdgzF^D&JG>` zoT*<H8#i$z5wpw0&pViw4{ZR_X7rP1Y&V${pLJJn$<Ul}2f|l0)+3dFMbzZD+S56@ zj*)Ksnhgyo59o44837PN7HlvwwOv%XJ@Od_NpT^=z>L3q8Kdy*@wi&H%!b&+Xm1+E z4Q|-b9W{HbLf8jXe~b>p|0ofl6$#Q^sA|l_ib~=&O<bXQ7_gw=_!>tX`Ls03Z?sQh z93~9%vD@**W8{#k@REkcpUuH$Zp@AwS3D4gR_(%?{l^*ufXR5Kvm<V_96sJbQ6g9E zXsO(=cL#ORAWiQ=0qDdy$YGA6#n_@Z3!hX08WA`0l6rf%ibK2P$_l|vw^97u28Zk7 zk06#HY-pXvWJle%#WI)vi12oVnq`4-SgS&|AwSYbG^H}7AITsZHz=JD@R%cf*@ z<S39PF!X0BPRLTLD(V&98Y1I!?*T_P5MktF9@I1InEIE?W?bcQeVN?PIH5~;Bzd>F zBuHSl<FeQW)4?ik|14C(k&j?pC~=8f<Qol4CUu86a^EQ0;OdbNbYB!9h>cnt`QhV) z=+l5#iH6n=^U{K_*4s{UHU^F6SGy7!FxbPiK>Ts-%t3C^qk-#%bk|O_@>U@2_(efM zVm+sZZps00Sg*-?a;TcZ9Pfy2#IuO;2h}jEK^!5+C1O2~?Ur};C`Ub5s`8<K+A8Cl zhc~YB=K#nzA~pX9Y)8hAa!^mIWg4I63PDAKlml)(hl*8*oXg0C-EPtq2o<v$oD^g7 zXg5#!3Xe8crnJxE3Ta0{axSP_)5E<fkGVl;?65Z6SROa0h|yg>%Zwj{9QI(D-hb3W zy&Z;a@X)C;|2^##E9w**aI@a{8m>j8{rx*ox1o?qu{9LVoUB5Hd0z)3)V2m-6A8^y z$`9X>#BJS~SuH)U{qa&XmSY}5r-;Y!9l0Nlk7eIzLOl|Wv@CJF$p!HTnp<bX(xYUB z@L-wr$r^f5+r#suC$)F9A;^hHKlUF9QVUHHeug-e9l=fryX&KBa~y*iknhL7IRr!v zPR($S-9f|wGK9Yg1h5SRtc{6OA=_VskOXRsGYP~tRG?|pn?;EOQtcB%NXh3+6{C3& zVd+hJ+1Y|w-TX8f<%kVD2o8=B#5{<RMqPvp3Y!7uU_*=zyj>syVpKTz!*eapRag#v znMtZm|IN?*jD_3*6v0>mV#MFbQkaR}4Pu+9{f1u2O!~as2lAkuoy|VD+1b3%6cQXK zy%47blVm{`#ZXL<tiv?aLpWGS9MT&M=HF-(7&gfRIcU!Dunsy|RRS&z1@+I*m4hGJ z8Diz3LA2R2>DWSORz1{Aam`fH5Cj<2nUi3c=n+H!ZUp@8R24m$M`htGiI;F(8R$e% zMs%7-JQ*}36OV=9#8e0-1wfIk*o9qKgiMyK9mFpDL*G#$wb7D4Y@HK&)Mo)>LDa*M zWkkjdoIuEw>j)4fz{9(#VUr9GhM-TwkxUwLgdMTiDvBaAU7)mmP_wBP)lA<+I7}^U z|BXFpphi64TiFmkgoE!y%mZ>?P{GXsl0)PH26!aY*Ik54iQ-Kq+(G`xHn7Y%T;M{Y zhFjSX8|aZda-j!}U>eQVL#!AOrr<^Jm5M2vLr7Twv_m1`6`lQ}7;1-1YST{HBuL1U zY>8yM3D-QRVsbf+Gf|jm0aEWIQJ}q-mgv;vM2|qQfiD2zQ=Fqf)FLhh!0vEPD4NFX z8PwFYPYnqq=;g!h2_!?z97ygQQwddAIgP=k5c<(aSrK6X%-ujq85R6PLn5CILDK`V zRuHuw;0;~y4GHy(&<l~6K5E_!3Pd+FUBp>P*Wke{NS|Ob$yH3kDsmC?6b;;L|7G`G zny4}37CPVvSqNx~h9j+5J5&ND;T5_$#L{@+J8VtSU=JU@msLoYDZFD4t{4Ut4P$v1 zV$EbP-3-M@V)d+JPugA8Y|KA&f*cIZPofbcabT4tV};z5h2UW>%GmPR10HmOd+E$R z8Bjf-LL1Bsj^(C=%){H9l9Zeb@5mYPd{p}U!4_r=*4TqhUIi-lhIv*H=LCb@L{Mz@ zpwm1~ZK|VtUKjGj7EC^<F0BtXrJ4R+DAOe!6)=PJXw!@#j$MEQ5ebxSb)o!NAcm@7 zCE5d#C7g0mOwkBQ)4`uV(AWs=*ZgFOTG*t|{OBt|9XcjlYHCFB1Wf>V{{lJ&=rUPF zL1`u<8e(u%NI9^~Kt<d|s9yk7f|m7^M?e#Ifm=k38&vttFSgA+`hz@(8X)0KLvo-* z$U`d4A2JF=V+Md6QK$j(+cw=EkNi*Nq20+zrK$x0CMZJ46`@iP8r+b>9QXo&mZm{) z13nbO)Tk(hV1!kyQ8vKCreOr*T!l73qX5Ft)6fl^N=T648z(vh{8U7c7@9zQ1DTcM z`~=CJ5|OQH%*-sNKn#K|1>7h;2#{i1lwxSdD4Q-l4uv*EU}1yZ2+3Aj%s{}xrS?v< zMujW7pCJxw-bGRSfLKNFr-b!WEhK|*#$*u2R^qVegwR+LeT^O>|7T)F>s#(<K|lf_ z97a{)Yepnp02~55%wVe0AJHVJLY$4FZVA;16z!OhKd=>QQc;oOU^0Hp)?MQ!#Td#c zlOCboy&}en9fl?#6FyQz$d;-=Ad}wM>cWUakz@n*3@41pD2Z4|bzT%b{O8Dc>$hIx z4L0jb!3{O=13jqQO^FUfhy(R>*^ac9)7XK{0Odf0TpICBi2;_VDS|d_r9Nem=ZR)^ z`~xV6;>jMw3TY0@2+2K0<U-6I%it68@MV`o4Ll@4!qrY$3B=rm<=G~m0qFt>k%PRk zpr!`VLKVqwU1lW;RmzPOJ)EtJ=+t3|t>k2^G^VUa#30%t|J&CospOsp^%#<9A>LK6 z3?mlexWWTV;ucS31pb6;)+(ih4BW|Z5jHg)1`U*LUCcfB!ycFj?OFuR7{)jp);FLK zsV>v-n1i3LXksC(kARG!2HQI{7<4t<^EL%XLa&ewgdki+=mv(%IMXy-1?S{u@i<fS zNUuatOv25~+4yWifaUC>saFooL4rdTEiXefrkHkwVI*AmF_KQw*~nmsH}#J^wCAqo zM>9kr_8NrcVT1L3CM%*u!_g9W-VQAMfeLvqYPiEMahR_@1m4i;M1aSqf~wUdQJ5C& zef-VmJ>bGbmT{_~JaE+mON0%5!#Gr|cYTfTtd2@1|3nfLAcoK{eq<~!#ta-XjihRA zLBO1yO-?Q$g4Fb|Uo7O=fdm?za6{-#YqrB(x$Qm*gf_4YhEVN}m?dG3uh+~2HJ~F% zSdk5B4&xTYoz4S4T;xIA6pq0$&5cklZP5ef-1ix7NJ!sLoiKPvU!gjL95aO#Zv;!S zL(RA$$^s8i#Uv9C#2V!TIgG>ERI+e*)2)pS5jDX;IB`QL=RkxFN>I#Ue8N@0r`<KM zEs7Q$MK0|n<&VJfLbyyhJZhvm1<RmeP~r_2D-0*Ct>!KSaP~5Z5pNf5F6;I~`=F31 z4^AkD#@{%S2f<p^%!51tA-hQxEDrBQEKOtP|1urv6W@AiyGcp^fP*mm2r)l|XEI@5 z3~L7a2B#hkCuanBfTTrGjM{i5QC7sOJ`*>L(-dz<u_DA8G;K#J6zk-}EM(8q)J;Wj z)kPmyNn)0ZR<z0ej=`-eW<A3)_VbSX6qX{OK-@w62r);XV9JVKNlT8;NabF1m%~(o zHZ^pe4#X~EWxGy<C#f@XPO}z5lqjdDcNC}7uq2iqq#RY0|27^@E=9^v0aVQ-pz<*q zdXJRM0}AbPk8tiqpqyxC>rQ4+Nb)59k&gGsa9<#k=8V)vM6_zP^ZU-!9__Rp!z7vl zkJV~X86^b1*-(+ZlFoS}U@Z=WI>hOW|ARMZE{$ag#VB+{`~fgj%*Q-)F$bHqQUv`B z4Gh}Z#AF^|n4LTla_3GJh6F=5nkGct98#$lAg}OZ26uK?kyT9gDeM70Akg?6BzW`> z0`1z_O2a=CiCTJuQ0)#efI|$5F%?n4H;}_Ttk6Lo&Okt(XQDEG=rlp}0&0&oEC4YR zo-A648_V2U*vWKYfMt$t^VwjQyshraMFZ{8b=t6W>D~uDyO|d1-Pjlq^x^5z;`Kt1 zwZo7DT{i?CjKlG|@BD-hfty2#LIh+&CX8Tl6kP=CSlD~ZmOuzX6sots<~2E3WoU>i zM}!qA^ux?VP=-@ucdwBcYnxD-{{t@%gd8=DRYVjt(b&Ej5HT>dEZ4Fp^DX3fco8KK zR_^fNP$K@NIMlv~vk?S0sPI8NwKrhF*s*s-;F0wuPVX*~ka^FmP8?_`c1NU~cT&VV zSc5g()h&VqD6pQYGEMj?`C>NA0t$oy+13xS1%^yHQZ!Z$E3SfN%|m?lE1%q%vWT<& zgIbvRK8nLPJnE3Cv_|v{X19)QQDu^@;*Wy_&M;Kks124+M8<5`Rh$~{pwwqgPWxQo z7bo@6RFp|lh>5u|rqW;%w&<k>0#Jo>UNgG09|Q`Sctdd28i)fp$kDOi%^nuq!`|R? zjaIQb&CK+J94D_9YO@<<|6VfcS&W_IKOn+tzXOvRgpwl0Rj95<pjkeYEk2BD!HpIp z$?lKajXg>=aIo27vi86Zge1TNIas4Q62$b31LUdAKE*mwye=%|uuf(>?KydZdb~ue z8Pj+YIdH=_aDy~f79*x%V^3l-+8h0B!w3mBM=(w^C=zrr(&r^<(~&Dd*g0Rgj8u)e zHtS8%i1tJ1mT$E&2)c=s_~k?-xj=w}q(gRH3Iyvg{6-AI_OLq68^ke6#7_<hjbSzU zQuynF`84B9lZ}o<M9`}iJ3x1YD+#p-F9a+g0$bslj5o#5tX7K~gw&Mb)(o^m;QP1z zJ+3<qF{6Cbz(b&^|Eq!?gvFovOli}+Nq$n(l!G<Q3<_N5PlPUuvq);xH`oCd{6R02 z!#j9PIP;@QXAILr;WpeONQC0e&$vP${X-D{UPN>N8|gM94?CCwF!7kW1w%WCLq#4| z;v*F8F_z{3MUZs9@ue)4(mn<ii8rwgz#8KAS0YB4enAW)tTJ5=cTVf`l+<!WSYI;w z2Y=o~1)CcLK(N^sAOJpm1Q8}oI8b3jhYuk}jA$wx!G8VV!IQWV;=g|glLg4f5#qa% z0m5<f_b($!mk}{)d^wY5&6@oP+9TM~Ww~+$A?^8?Q>Q|n0lW<*IPa)Un=<(Ykg3p~ zJ#*#)L`6uC|6azXF3HVf>eXr4ng*qEL%6LRzM)D<UWE7V<D8v7U!ra3&n(F~&AjQ< zOA{Nm0EQt}?Yo%cwW0a``QytNqBw$<Rhs3-4K8KL1m7X7SCMjQ(;Ll^vsq6hA%f&4 zM}#Lfq1f1`NwOw*JAmZRBRkpr9KhaCdI3D{=8e0o<iP|-hkM7@E;o(IU5>O%5Iae< z@38qo6aZ&;+=jm)9Pa(#WHtz&b069a%RAM~&9Wn?4d++W+5&Kgs-iYB4<VIUBFn6* zGP+2uy*k5BLXxVIM<H^Kb4f9R<k2m$qN?IYEAFZ)%D>VWgvUZikP84Wsiq2mtAzNG zC!-W)|AVKhdOXaEpAt=sal*b}si++52=WBE&^Ee}K!o5~?jf(>F(}G#bUSD#A)Pu= zq4*ri$RIFz`btZ2ei~9DkId`m9dl0dP0E_qyKF@H3|upz%u1`XA+<)T(@!;r{EW3h zaLP)#mn=M}8kq#0Gk~k|sWhQM`||Uohx{z6#yt1(O`&`Sfn*#Tdy|w<j*^4NviAab zr<{5`;zmn?EPV-9zABY0PdSJC#~#a|#B?#v2r?%|V-vzIK5qIEHC2L0bCK9p6~c~L zYz0IJREPjnD6?(L0#K%*<iu9pX}L=%SDGx;Ey9Qb8RVaFlp`0nY6AEMQg$WdXP!+L z|7Dk^*{+LB)pZ++j~slj^YD+4W}R2QN;N`E%WpR-M?1@k)0d>rG`bDUjU;=Qp!8Dp zQ%ijAW0*L5B+IDU0P4AD%L%VFipz#t3U{iNPIEF`qn4x6OPLRri8g}q!OEqjKTHS@ zN(jQIL@FiRaGn;Wfrp%!VXTUtdF+uyDxiOcQb&96dQ#Xesb)F=aft0@4z+NSj8e<C zlM2kLuG(#?au)9RBzu@du_(3d`pC++o0O?=gmltq@`VWU#bPy`-1($(`T??Tv!r(D z@(oG4_Vkyk(ivxk{Gr@#{6bgAn@Oc+9U`t9vN1;AMPeIx=7`^oZUv7M(w?>-|4PxG zaQLdmpRsSJDa|8W{z_`Rjj!_7OLyi-%<)^Ktf`*;(d%^>4U()Gf-+kgeWrakMXSr1 z%N?FX8<M>8HH230YZ`o@!wn!M<apWZ(%Zg<kbZPS9#1mg&#;mq|6nf~puyM7$^^X$ zZOBPc0Z})IBSMK-C;-&J2@4%4k=h}|Fs>5Em~N#OUo0#>c2LUZW-^&O^a3|}!N>0A zH<|b4E_xOOn%$CDiU$!zfD3Zsom67G09r*MIFXC^7?YyH*+U!u2nIq{7o-Np@Fh;l z5JD`p#;UDtcL*8Ba|}`;d7PvkyVD4cVAM4yCQE8O5m7=cw4o|)$#+G$|BV6FCBXKb zsb>KwQqO#6kgHfm5y*j-+bCo~B7%l7=fl;dfLOT=&9GnM;7ckO5~b|vj8EN?nQq3h z8GWU0U02ZvJCgB_cK{EPY~%<%>H&`44ALf>g5J-@B1Z{fZx&S0jh7ntk9rhyX7Tcw zF}EnBVK$OLY#0hNm4l53nQ}38P>l*_QkBHT^Lb2S3ril7CN_ErokbI26&JZGUVei& zAq1yczM&;v)`Uu=u@@*G!USRjKrAWZW?9AtK%xwAZGF*WLc9^dgC?XZ`gGCr8g@U9 z_+uMWEQm@u!oMPFtticygE}<_Q`DGahJ~obP@H6?06b_Lvb>!~|Fm%}TdvEc@)6mA z%+XKNq)r+vk=CW=InswDB~&j-7je|nk$=de8%p__N4~1AsmMcHEBS{=t->*gtY=sZ z)M~SYi4bv+<AxEz#~*6(pp(&%SSWSMaBTTGv*@%Y$$1B{xG~I)&?<ZU3nuRfr589A zgn=S75LU#YtW_y+H)<K=MeoX&Hc*2fT~QEC2sadS)Uhca4FEAd@-?L~OrZ{89VL{> zQB{`cW_RtZUB||wfJ#NC3NZ;~cC<~I-~&k>wFj7-gAdduq!94Y(pRV_)e#njM=~Rv zIb;W&dQ`DNIC&Dto(E6Uyb*-EHLgSe*+M3$W{>e*qF2lo|9}rJF1`tg*+;Z#QTbBl zkOV=+PfYjPhx!DPP9mPN04!cYB~K7TdC@}{;$23fGe+;5oIxUkka9$LxdR%Y=Q8}? zji%3E@c6Kc^h%scGEJl6AlRz%^f_Ps<7jwgm{!o5)%!vuAD`HRyc8ReA){<EADmQg zkP~J6cmy6pIY@aCqOy;G`Kbg%TESwdm-{e8W%8jPOo#I>Oq3EH`4ERp5K*M8F?J*G zdeAHJk=C-zV;qwKl|R78G|B83S?e-Lj{v0D<ox)SShe($S2`Jcv|&OTE!YPkVGr2c z?lTdbmq(O|2UPrHp>$&9?3}7(9&ZF6jaz8|{s0U%|5KVIEg>%_hB~21mc>9j<On`? zOemfd`9UoXqgBkoqtdaB+8sq>eW9pfOq0|eTv_l13&+)j_!5i(2yTm*C{UjIL!<=Z z%2lc&meHXwAKKocOm_hea+uV(A89rG?w5~pobH|F&daT?g^fG32#2s8<U1!P<CkJt zAuo!OJ`aLynPmj2;)-N^!7MKEDuq9uo=|e6cAwDNd)qVnAQk@cjk!H=L*P&**{U+w z7`FR0@CH%VX56$5<%83h?wJVFeNrU~$-}CVHSMaB52;}Ts3KP1#Am`2wA==9dwz9} z*CnS~iIq_6DRR3aVvlT~L>t_IOqp>L+P1>||Db+a13YA|WhuKgCvZfLTa&|QhE?io zn^H}iv!yVa3}+tV=8|03RgNA1YS?1UQ$EO%FuJE|F!xbPr68{!-b@A@YUwhYygHe| z#;22MO0>+()6{k8>}V!;2x+JB5e4cUKkXRGI9}Uwj<CGfG69Fw?&SAd)iH)Jd<{g( zArIj(rl8-J**cNlw&pg3-;33*Y2tShaahOtP2{di%#m!+X~Z%F+pbx7#ErAhF#wtf zkVRs`v_B_E_&0I(@Smhd90CyDA*7y;Ie0Dr?!!!^Pq?N=NWww-%8y~X?;+xcFA`89 z$fhrDOaX~6r7GeNCPDBt1lkZ{4gv-1{}4krUXNka;v-B!K=|Y1)C)8KC`}fKJo@2U zLSy{?uQaYD8A#)c-Y<rdr@=~t`P2(Y5-AWk1lt(qD)!CC+>O2zq8?xfwRpnHwq*OV zXMT1<)0pW3(?=>=up#n+{P1G~X99=1?37|+0(m0m#z$)W;l`W}(bR89G6GPPfwRhR zU1Fy^EW#bqFLhWab#92Je$a|Qqa8@f_WEx_yl`Nm>I1h3C<0;3u1O|H;~hjKztpAS z5CVH7g51iYyf)<>+-CwMq#4-YC$@!&3@_*u!ZN(DFXm?;CaDM+A_q(3hsGzwG>&0- z!XKu=-0nte*2Ti?!KEH6OyFUP{{}7>SLHUosQ(~>fA-)~Trnc%A-L{v;C==iT1%^D zWGgOYLOSqvbmkynVXuse)?iA24#MCT<12dc8xbM{QK!|iiy)d|;j9i@%wxddL@7eA zFU;dxawW;Y3N%2E_fEssDo`7}Me%SZ32aU|7IG%2;Vu3lS3)Bk&dp%#CQkBhCq^a9 z21Q>OPfK(n<c`W>JmUXu14-J9h-6XcT;f|SLoYTDA^c@BhEnu;#Ub>flRU&HC1lc0 zNhFHUDRK}Jn<)K|BP8-cCK{3Y=H%-za%LLh9YB#Ej`AUn!zi_hkhn@H2qO6$$TjML zpnk``7*aH(%Wl}Iv!X<v|6C%(08KAk>HuG&lVHRyAp%VPa2}~Lz8nU6EMw+23`7QL zEBVn8hpLP&10tqqB(z~Fp8_7Vf!D$kqSC83yn!#k@_~{i03?B8YH(wuqIND5c@)AN zB1D>I!U~PaFU0{E5`rdQ0v5>9>P$)u`{F2M!ZMyt>jIz`VC5f35dC-wIEN#|w#gQU zq$&)gj*0_Fy3&e_h$`009%w1d`fe}P<RZ>)Gc*D;83ss%ldGgNIb)<VssejXVywo& z9AL?ASY)=O?kjra{n#t`l+7!yf-ex`L458&k3t#}!XREm9R7fmoYE|MAsnK_=e)#- z@S!cB#JYHbf9wDl{|czo5aO}!tTy|CNwlHl;M3s-gGtixBT}Tu$|2H>@$>)$fHngY zd(%_+!L0nTFOK6a0-%CK?O_5y)o@fuPeU>2;UvW}0Gfax$gwoeMoUOj5d8}wdf@<h zA|I4+F9<S9GW1}WL=ZBsCW@n4f^s_3F1{`Y8zun|7tOA+$L**h|9A@@E`nGz>LLaa zK*S*tvZC$Gb4D-dGQ`0hmdXLQEk)`fW_W2TbFfF84|9%-X-<T|w&*$j%Z>bTa>6rH z{GoCBVH=dJic;qy^r;@W;VMwk`*`9T76-GgwA$vvk^-QpAc~uSq;Ob@AVTbJZc!X0 zlc|2GxR{1b{~}{9Zp9sPrBbLc8Mwg^BT`-BjHlcI6iV|Y=7Amr4M{D+$cl#`LJA_; z=p>j#SR#lT?&vHNk5dTqzF5W~$YCVxKtfVR;FJ{ce$wmmHP*1B98d@w-hpN`LJ8x? zMQI{WOsl|{hJVHfZ<OUK8pkqnMlWrsMbu#=BoQM!bsiQ_Vre830TC&naN~YvD99!> zSmP!Uupn&Jn1l*;bmCaGlu0t80^u`7D3l^4qK3q0DxIVc5rYd?X5990%Od0>0oFGR z#1N&XQbt4o?X@p7sz<t(VFDJ`qJkcZ)Mz8ZBPxXrsRsl9Eo_@ZRpx=M0-z0Y3oF)C ztR#a+|HgqetSKCX(jN$xP#jeB`s^eq)b;X(9JEC8aOF!~%~I&XA>^t~?gLoRY$nuJ z{3O)c2m%>AkJX~~G^Xq}QPOU(V^hFkBu0{#!XY0H)+_g8UB}gM-!cH00BsKj0~<o5 zjzLS{c0%TsAmjjOS@N)aV{j)jcuB%iY>Xfnwz2-<#;`$H3!-1Kig`tBDvp#h;i4_h z)zz}aA*uuT{AP4bLv67_8qTPrv{yLz?iQoUA<$P%45ShcM0eSU@d!pZ7h^bJh&6<B zue9QQOQYTJ01FE^cHJc(IwSzrAZB`nfzN_Y$u7$tVr{(zgHIQE2jd$8XCm>He!_|j z|2x<z{(&0=kRbjwv`){?4DusBb017$KMa^MI*3-qK_`yJ{_=%_PXj=1cwLlKLSlpp zMudf^V0HT~ct(^TWI|<gMF0nvVGzS62E!8&Av;%dNX!FfaFc4?<%TWB7yiI7VgoDH zggb{KQE=ijwdi&fg9oQ5T&#hFS3+r2)+V~e8(t7lwJ{yJt$+C9fp=jX1evqOCRK3< z9;oNq5Q1OSLx0INkOCDU>O&>`p~ZZsX5L{S5aA!rErLvnk*kdkTT?yKXwO!(6m<d^ zF_T|gByiBEe)AC?{CA2>nK>deUCmP=x<wSRg-SxJWeaJKS0y8kqsgWOnU_W@|9&Eo zjp>c>C6Ty8M4|+U4NNt1m^ONJXYE3?LJ9xAqTrO$f@wl85Ca>|*FPszyMFcgh+=39 z%pV#JF6Q7PY6c$E*oYNGHT1){GGY&pMo1jhCdLjr%7NStT21H+9?VudnPVIxh|(Im zFZR_T@FgmkcSlCD8km4dq%<^>&V@r$GR`z1Fu}{v8BYI!aSx<gmNuIMv49YCF$!lW zlC=={t)Ck?Bj5yDF=wPp1E{wWjo9#7gjub;0)YC#IsjQ4x#}Cnp;=Gka?Ifq(gz&i zB22-F93BH924QxL6^L_CNBVJ>8KV#;0bRz~Z4^T(cxfKkd5tTRT0p5i{}4htzG*Qi zvDL_?u&lzC%fd<2!XMU-FRT${Pm_cZVjWmlSS;4OiUYx*c783HQXMEGL<$_lh7IZL zDuzOttV}0}fi=_`H_BP8c?H8t<0|kXP6ClKZqj0#B50vuJDk=jz<NXpf*=Wn+;r|p zs!PRQ>Y@vTC3(bF3EM2NgxzU0l!4zj@M{)k%#4|9tQp(b_ZlH<8T%4NDp|^)B%~n; zmBy~@vae&`Wh-k!$W|e#kj9!Up|Ymt@tpI2p8LLEJm-0Ro$Fk0uk-z$-}h4x`DKg# zcva9|mjAbU;H$frFU=7y&Am%;j>PXPp18*OV16{xT>Mt_-r*jD0o1!zqSfuXxRpB4 z+v32*n$8)Fo=Z;D3o|EmNzdKANrB)KRa#`M#h;kv{&dvnRUJRCGG6X?<)6x)?Y=T5 z|M7>CveP{8!@Kk}T)&_DqugSk$|Pvk3nC-$LsdVvYCBvl!@0U#DP&9fF7$X-ERCyq zQu>BhI<ZnlL^?>tm%n8d5?<apUb!-|oaZ$q8fT_&Q}ISJ5X$opkRyE4h~<CzU{KaD z_#I|OxXUp>V*fL7_SEsCZbwIQH=o*!9aP(+!fbs@Thd-Dn_9vsthfFY*DFl37OSND z7&~RQN6d0=FxVbVC<EV#8hJtup~|{b*MCb3s3n?sCTB{16FncoX9#uZMZAnt{Pei6 z$r%48uMld$a8M87=OMfzWZ&G7G`x7}$=mz7w)xkm++R7DDopA8RenCa2@@`Myei!L z%<k=;pS8Is=9WYrf1K(whVxzKzc<RyYfgweL1VJi#N*Osq3_(gj??NzTcRX>ruf(d zn*@r6eeMz{4+yJAjB|3W>FNb}d<jzaJqzvN3fE=tEW0r7NEmQDC$dbJ4JE3XXPV3! zB)ynD>ium1Tu(|?joQy$b!@H`Z7LRP5e@zt>v<Mf8kDma{Rh~rik2MM#M$^xIlcJ8 z2IY}PJ^1wCZ+Q7D)!k|?u?eica)Tv@*L_8;(4!Nz4=b~Xy%2#6qCkF?R*a08BrJS) z7Wc(mRnO}5UX_4aZChG(`KyDoy*K&p>FF2!)b3FQmMP+CxIyg?&>N;FO(IwCsnjza zXAE`miFay4yrkiUg7B*m%=O1oe)<9&vOsa?o4GG(rk#quAxyLT#yaEI?uIzPFMauJ zEWa4cb``5}wfkFKV+Gs1;Kd^XExar77pyx)Y#dB;fj3HSTk68_hP;!z#(|gc?{gRQ zm({PoLm91QvPc<<9tnr8$GG2Gfyga)3hL@^D(%pJ&Jav>!oP60J$!8{n160Ru>FJn zaROD|KU8tYWPdu3kVxzNusJUZ-!XF1my`vP{)*AnI_g)O?dOG>MH*#}eu6_zO-)J+ zmo%u<o%Iwum-g})5NzKLKr&dQBjPB)!@Z%-kP_12i4tDewn19a8MqA-8|QDdEa*!R zKb;|dBbMF@%>Mja!1Oy_Je0mAy1lZqo~wR)J7A*q6Q}U0G$oUNXyVf=uM_6`OysSV z%e!+>GAxY4EBK}?fuexq@5g|X0b>1u5^VL?FNIBW4V-Sedi70=ri5<grS%2NFn0;m z$<rk1cJDnB%SKP*F-iij(upe=o5H5(Dbev4{J-*DqJ2f&?D#sepFc_y%dGa>k-Qvs z{%oda)#kS^FCnCl6;i)9ZT#Ff6$X&c?A1Scz<#%_X*@p}yxvtSj>Khcb__l_ZEhzx zn)3p(Xw$d~PEP@BV*lLFO=fBZe`%89>Z@<*y*s;{8v5zU($3%E(<_U|lFxof=EbWz zF1+S*&brx4)at(QoXMs0ukAd67JqX7Y#5K>MVp(bH8`j0WfqdfwI_Fqb4_Ge$!{*N zbA@Gj{Y-!E1eB7z#<T`U7B2-q`*L9}?r$EeRXjnZHr1w|&DioDhx%)KRoIB{d47i4 z2ha<0Ffw=oZDKrY{BQS3W?Z_uD=rQKj6_>?vH49rlyz&GF_x0$n$cIfR%)TPzQKA~ zt<5nd?{LKD=R3{4d7JA6u>r~E*QVxwC+Yvdh)d^s{ZxwcnU0pim!d2uO7G&+2|!sK zPco=@Ucdl%k-yrA<2+yg?T?lgf<<n?CqI7+b!R6|fZyWIc^mCAZ^Wnk$5p5*_b_SQ z_@LOl;)T*YMLVWB@Ps2N?kxO9fd_C56-G}Oss8gtPjlf_w65JFsS1;?X{J*Tmrak1 z*E`iVeAND`{M#b>YjS#(*3W3?*o>1rCf^<qenge%s;GbXaoPE8i0r+I0ps(k_XYJS z`U`FEpHQ7;$IQYSuJK>EjKE(7`|$TzHsf{c?6_1TK_9N3YaBjyC+A7`MqOF95%X`f zw6n7`@9F$@YD7Kzm9O6^{wj9#psy|6czeE7LHnPqe(Yz|rrwJ7EL6>>+~ZAsDTPmI z&Bx4n6T$iVI%jBdpx|IkoVv4b+OnoDTf{r<8RCoK&=a|=7tD2D&23n#GfRbgEMVKi zpYk~xOk~8iIGM4xBU4kKSfoG1{<#r}u&~lTI1pnuC8$5kqEx418mc_Pwp#rm=M(PS z{2CvD%i`Y-RrHBr{@Uq$33C`dcd36U*FsU3!#J)g&+c+Z!2X>F&*1(}5vfef^Z97! zfTNr@dz6>~tEdmD_s`>0{>6G<6F-KMF+4@%%?tI>Ke6vlcMovF&ahCF*Wx49kZMXd zqx-l}UPdPmL^6rb7M$@xR_0{UVk5R|QYte^p`?hDEO`=6ad}6Ea(KI1<&Oa)k;cCQ zl$)X{!Tg{MXIx@qO#AS<{N5`*_Fsz~kqrR<UnP^1OY^Zm(~!c7vf-nm=N@~%!9BK= zpEGOlN-||0z^>?{5yk^PympGqM1%KzpW71h_*q?WoJ3Y*-+Ug|4-0~GwAb4EwZ{qS z3LaaT1JS#zahKVl_j8xtYBhZ`_6}tcFpNSfx9Jz>T`D}~C^D#8+NfkKDP?>*`pe}E zNAP&CoEW_<Ty0wQBvo)&Abgpqb*}4aR<ulli+r(}F?Td@>F~$SmTTC@3488Kzc{@= zva&bn$rVTp@k7&VLxNM&a(Z~$;J(pG-^4x--B<^_Nueh9uQT4yZ>NdRu-bH3Vxw<x z9xo&;+75_REKv-kyUs_e^Ftew4q!YGkXUBCFjRn~o?i)#))u>M`Dpi7c5jl<Dc$t9 zk7YxdxVhy4)T<Eur=+>4nbGrdniC^=ifFGiee*L(JuyeZ^~FlT8*Hg!Imb4`&(2Q8 zYdM;>!UBH?kIF=_H;d&OPssXUDzT&lS-r{}{len~dV*X(Km3j9)v<CPHaI?i9;0Gh z;jtEN%dpJ7A1x;J8%E)Vfrv**Iv8<}3J1Pl4c-D00>q&_>(D33+1*BQH!qKzj`~da z(Q}$FDSa$jfFF=9`uQ{~d*-T;T#|X>QpjB$$LnX^do!CtgfpL*h7W~Ke99>*MtzT0 z3+!tfCvTJ!5;)z3K3|+TQKQo6?_t;rH}k~IC!}O9y$aVT9*?dyIv5!PU?Gi@MAr+p zOpR})-CiH3ojf0EsPsE5nGpD6W#v78_3LHHi2QuUsu>;A?|aQBqxZY7A#Ke0f#b)o zk)Mo2ZY9Q0ABXebzds^oz=@44lofbvR!?@%vVqB2wKK82P2$b#=6*`CUZwpFWBrko ze;>72e+*r2Ge2{tPf_D=h1QV3YH^xw#s4tP;G(7%iL|~WGS?Db&Z|>-d0aR7KBZ3> z7TYJ_T=I#>9iIG1(fO)>m)-R$2}4I6X|3HEoj!BcOlvPAWdmy*$p|B$5G#~)k}Dyg z|DxyycmF994yUjrBaOGgeQF($1RWa}y%`BYeaGfi?hJU_NnKYDvS{|5+SGtog%wOE zzxN58Tc3nxhvjuJGgb*nCGUaYz6<N;uA@2hgYSl4E?1fzdKb&5<eC+&UcU64bjQ_9 z>Rh!K*W6Uen`&_dh)bzu=E%i*&Ue#guO;{loSHlR^#;yyD{7{2<?FZ$xl|YxmWVxX zjYd{<a}_syQ%^J*UedH)L!Xk=;!scp^RJ(%J-L58CnZUYAMV&|A50*8v$qf#DK&{I z@~Dn>4fb6rU(9-OZZ6*#w9jZLHk=noC;osC{*}M(cD&1_CD1Liv-{jo1Iiux<WkDl z&udCCl^9W03V)JBU(6gg@QV5xH27`+1au0XHFM&B#EL;RJ67Bb<-I{$UOMB$JeTxX z@~M~%B+P_I0AHyj;1=80gA@)-j5InaHg^dPM~X%R(FKXU(VOMl76SfeYEA;h+;{Sd ziuLi`SkdnW>TQRIp$){1-M;LW>%n1g_!ZGGpvCail_d49KT}R~q_NP}=Q5n)f^aXx z@+qxE2Q@9(HMQ-#yC;2X>Z3rozaIbg&v3xU>B5E|Vl>Slnr#R!s(9pufq5XV`Fg14 zDfWEx9G8S3N)Y>G<aYVpzS}7VMJ)KwdAeMX{R?`m=oe|2EeUVG1foENPF=Dh(i_Xc zuBi;SjIf6>qGRQ68)p37o#)?*d!R4=r&472SXw~<ASyQs@`%;QGe9PL$2FF)6amK> z!BRRn4X1U3KrSU<?Ke5h=Q0~FU(>luBZ;C>C3w*d-1NqS4j(BUBBugbL41bokg=WJ z2)0(_oTTv?Fcee}@=8*E?KSLoN!M)?*|Ji(qeZdFBii&@>^$Yd>GwKk>v6Y#8~3K- z?{?83emn~#Xb3}ahj<)9zX#O|>t@`Gon@bbnAKCmGE^ZK3&2te_oR>6A4o(znJ}Wu zKTp=btB7zb5#dagVkL2oNO5cdXaz=yyAyJpm)qSE8PupXrs_ZU(MBd1dtfNZXDM`0 zf;ANju;B&zsX>GpOujVtVhzWSMr~o}krg=MAR<f&&pdhB(HlZUfR3~WL0-V9B9n^y z8RR8KF>cWVD~;GGM*tgQ#HeAIk0hSs6a1++&u42PCtg0>2p7JS^_``{JQ#R^HA>PF z2^R@&6g$jqNMo<PQ6tc=7DAsk5R*u(+H3Z^9jtFak9iS0@aoYzZ>}lo!!62#6<+Bi z5qtrXZ=C!H4haZ3oD1WP`nu`G*bvnvgC~fpGq)3XE^)Dt{gp=8yXpm|9a#>k2W0^J zK}<r;5acRF_jk(7k?uiAQ2&}(CvV<y<dJzjO|IIQZf_}3GWfTKU8LjK`fxO1^8th$ zsUn6S?YN7dxp6!%_yjL!J2^h<4t_d>8DwV!7DKI9YH*9x(Dy#<cc0;|mBvZvgrfO4 zZJML;UhH$Cd}}56Wf1sYgPA_(ga6JeI-)(YiL*#ROrFQi;bS4g3LgL*iHCdI;@CQw z=N~ot3=fdBfkl7!9RvKY=Mgx9lCJ1rY?LImYz#3HI_BT-+vB{N#vFSV*cu8#)FL@b zCxwR>KX%+>GCt|j9f4hnowlVNM;B?2#HYH5bNG#GFFxfn%OTl`8&^%P_9C-Eq&=HK zP%(L(&YrM%Kkz%ZQ77)$xeTKb_Fq)o!+h}9a5`{_^Y_NNGZ0*{llm`)=t@6sM@qzH zlRY@u<x6eKWJ44o=;U}ZQx^7^qj&-9enjExlHS&)@h-#cwt?v14KLd0HLMQz-*}gM zB3dDvIHNv-k|PcwF1lyI*VvyEE{<)RSGW@-yAU52s6wHPgI-1QKd5QjG~ELd?>sea zena%f@UbEM$>)h_{Kwgs<Jta@%$a++2usT|ENU;<a-tI459e<ilP_AS^F8{R&7Y7# zwmqvSf+q$E7Y6IfG#`Io=H`YdiS3O!hZlKh74;crwoW$YDtZzX<U}k4!)w^Px;T`R z!K?lJ>R$W{BtCn%Y_yfyOpU-yJcsB-g((oLP@a1|fpf}&&(jb)c>9>VBHzwzEco5j z--_}#=#1S(T(B3D-#L-@w=+q}Qs+;n{B1A(xoxh9y<4+0zSaazzH7&m49zgFILg!& zarolaMyt{!kp<lwFA_PsH!m(0UKSp$RGg_W`rvrLVg^x3QnHmYDGszMifdHF9`(A# zckX<pF)zW}`0vl^e@gse&e#L`iS_NHGmf{PC<++gc~UE;#m&RF{ws^1Qq#38%_@7t z9q$Sp*A8r{DOpf9SgygWkRK=Gw#sXT(RCtnbz)Jr0xPxRQFSsEb#jAsJWh2A=z2xD zdZp9#iko#RQT6H-^_ms6QC)bc!FnCJ2EEe_xpVb`b`2&K4W|biV(X;ejy71zJ+nIf zY{ur9b<{JPN!Esrd3Ffozi5nyP+lnH(8vIgZ~z8}|JQ>f04s12ih};X%nU6xm!a;c zLo=gNI)09<=!6XZkC~yzy76gbmK;aA?3rXzFVUBxbUnDTNvY&r3fX!zy8oQ?+q|P8 zZ?#M<N{+;-q7B~|KP&%GajD+z%fPdWk5B)vnc@1r{PN)Qs>w#`|1mRI-XrC$Sg)p$ zT%l+ov!<GvSCO1@SK9m*9h4zQPUmPfnbD5(bN;C;Rj+5H2dRs(#<<jf>nb)7KJn$V z)U{5?P-*w+*5_-D@%{0S?$7tdf9(kQFEhj8ZJWCH*S7_ybI-hJxx;Axfc)*<dT3@` z*<xjGbUhflCHOzgjITL}IN|@884v%R+T94j{pNP1-_t5gWdvbPEHUnDV=M`NTo+wu z44RX_P2w~TzRg4s!=+~<|9y^_MoSl$&OVlZzBC&plV6hiKzZ~CBSv++R1Bv!9_c{S zUiABl+x}bgDqjC*<XoaAk2)g}a^i+q(kbH`!pRqGzZV9+Oujf4MhW+y;d2hv2|p6F zmqJhRc>aAcliKV56|2$40HDyBvg^RT?f!4Mfvl*dTz^s8^n=J{VoAR3GPN)(Zoo#Y zfO>AfxF}KMhC`~8@3Kr<{>@L0iRmeB%VnCg5z|lziQZ9B)60}yscaZ0tU#Y0-JnG) zz3r2HShiRq5qOT{kNd-$(0i3nUx`j$P34i;`ra@$agCMWMi(isE%jZwnPr&&x`T{W zBc?#1$x%5t%~kSpW2r29y=~g}QMl)a#fn>YH_}AT^G#qAD6Mc_kB$GB8LF$KPPTRu z2;<5Po5rpZ_BMJ2jt%L(CPv8Db-grcUGJC9ynyeRY(Kp|xKUmn(tP7&jT}b|De+Z2 z$<D^<9XZuazQJaX-)_KI>g4dVcy_Pu9x)?@XJgyX<c`{&Kr8EuLG0`5d#xfAwm)6v zZ~G1=%-C@sv6fytF)+)Pv<O<H-rV_OG~PT8Mc6Y(BNY-ib`__c=8Se{P`TNYp0H<s zx98%ee8R~sDt~{M>Rk7fZCx6v<Po#I<ZXgG={l{@Sd1{Q#AZo$n@wTT1@=~Rbr<=c zmVNu-(xeex!6R~P7c>>q(=XR7ydaGGwfwS3VOS>1W7B}Q!J66RmyBR2{}{Nt?%WN( z;E^Kya3xqj`A{5r5o;*wc(6Zx{8-*9ywmgV-@P+J<ORsbm|dp8=_}ua;(6?%MY*0M z$tpgq9r2ghSYuq_n8*)@2=!aBgpOR+C&k*$H`cwmF(R+3^-HE56#x!D2uC~+eR_lL zBRX{i7Z1P;4_@Ka$qtx7-xE=3H*WG{oNh8}jKZ5GkasrTXP1jhf?pF@E~ALU5<Z4v z;*zz-BqGc4$F;~Klpl}N6NRsGI5iYWz%jaJ&Np`(UtohQ{g3~$Z_behe-nd@(*m5i z9jR<;AVZkLr$DGPx$vv&H;kZwF>m3um%(X{7*`C9e~R8~I&jVN-{cIo;$jyooB=tb zJeW6CWD?=H$rS-~V0e}cYLdOLF3Eg0L_xzplL}KF+dq=Ho6aLTafad`P`H>P9TY_D zI2)oNnU^F}>H<Zb^&!N!EiK65ZY-a=Z&oDxQbb48#xl+PT$23D?m_Q!kuhgm<7md+ zZ+%<dXG70%MK6{G`%fqtp4}hO+_}Lt7iUMZmH==7P9JddsnxTYEz$k*`4wQ+lLfwr z8L7LQgRuFXf8^%b*@*?ybJMPFCoRq!8WDtrTq(Rz7Mkhxniw6wghEnL94;JG*f;oH z>|=5@gMK?ZXa9EznZ4Yi1U7u0!>8!e1`HEV8Y@P<R^{v}JKrkCN{g9Mx%8&|V&lMv zY7WWcSJ+qFPIQGS`voDNfuW`!%LlymMNuxq_ZNChKX&_cr&zslx94Evc=kP+=pyZ$ z<`dG_Q5=LU6_B=rkZGO*x@^wI^A1w?-YfMP5+8hsaVaUc>Gd~Ny^rs6d_QmzGDcxl zQiE%YLRbcOlj~}}6#c7S7*=HVZd=7*0NWT_7zD`>-d$o<3ZIN1(Tp&`FRHwIoF*5F zhmc&vFkAOc92DqaZzTdOE>tL=+D@zP(9L-bDi1Dgr)|mLDS2ox{&xUHZdovrO}YkY zq94rH8VPl-fLumV0hl21mhNmO_cm)s2gAH3n7a$ggDixDu{CUFWPUC>Swy_ACR}yM zkzKX0Q$DRGQU-_&5C{RhKvo?I5jK<`113S#(bdRu#JvC1D|n?ZjCaVn(wOHO9_!6^ ziaamMZ_|grh)hfn07R~fzcLd-hTf2$lRU=PuP%g4P>P141ZIzLA%7{k&`n+FG?=_} zXV_D-1%fu5IdIzZb~1bZqR?cstoFa7p;D{hDbCO?m`EqWEo(lQoc7lGC`3p8K1fCv zcFNJo+-_tD#?PM<78Wif4bJLWNsNTOjVxI=TaJp{@e1^e%GD;tvuf`S+ZzT&8hFgu zP6oWT{_cYy(I8kV4XR2r6i!OOk*ONpoXvNt>hnDeQ};h}+^D{NY{)H$N?}2EZUu1$ z2Xj}_2Ot-HfUK%{3q;2otc*9!WH<<yMT2JU8i{+7gRmHzx5&=MCWn~ykiO=(!`LQ5 zNOTIPS_^Rk+tCT5K9<CV;#<{v@E57KIHEN~slIgyF$Zozl>ki2?{1n{^p9YV`*YSz zb@kV(k=8-22MURokXYyjCMb;tgC)QOj^F_doc0Yu(*v658%Lhp6Sb7A)A4xl19zZ0 zq?W1@&G~@a;;V8Z@8_<;<kQqT3kvZFeWM-W9SLj%i(Ej`?p}`nDe90eau2)FtZ>RV z*}8R2>ZQ3LJowHC$5l=U(Et$O#h>%Y$2u5Cj@OU=tkMh=F##jr@p43jtL3quiC_OR z={*x_eQssolJP4TF;Z?!gn+r*CrLQ-Si|)J=QCm-&k`kh#OlW;pZc@gcSU|1iT&xE z3-6OyBB2%F9lKcHsAfyaNI*Iy;KWU1h5fqt=WnhMt>{;DM`^u!0=k?KHGL)*v?IEc z7fwKxg=}*>4Q|Z^ijJPy5RrYy2oZ23?(iB<z-l5Jtfyf)ubsPy;Mfy;5FhX$0vwxT zU1;>fZL&k?@V7<?He+yrYyz_kga8<xOJFM_a6J{jiMS#}bPgo>Ll~4#DZwy2f-4>Z ziHEZ(Ux#=4rds%y`ChMarr~r@&W9JN4QyEq*2@-%1yvT5$fXGpki!);UNYveM7Qt; zi@4s0dLgCNz$RaKJrTi@;E%-n|KX*bKTKZ9XA<@A!SllXErae!fj%8U`WxISmf^nA z?(oi_$>-og#C-?}9k4{b%n7s-9h`SOh<@Bh`Y?GV;Y-X^Ubq*F3qXR;ut$(sJc-Bw zdJv?B<#Z&--o#5o;DcNvpgULOXfPwtAJyr5CLW$H1;h6G!Z#uFJ&z$oO5AI~OODzx zsiE2zS!2!zu|W84xjyc@^bo>uM_&g|McjsMUI`ladAQAeOUj{s(bWp!C>$Rn`aDK= zJZ4(W(ONQg4(T@S=i{{*1sO)n?ci5k19@jSHq)Z}`+TqZfkxjvDqWzn+gIMCanDIR z*@k<cNR6>Fx;o_=JDnEKuNp7Oh&N<S;84Hw#VdL{E#cv{yYK`bR-0Ja9XI3Ngo`H< zMQjq!xbUyM4k3I_Jj$m(vXgjR{fV;8lM`j!GE7B|NgW|A84j^dK`p+dD>M#GnIt`b z4g;AaeRZM32~^d+Bn!UebLz?5PK3iS%BYi5#*v_YBN=;#qii$8*d+O?O^S<uitFK@ zRdb5R=M>Mq6e?e;w|c6NO{%Yds$Y6)Ky&K-fXsWiT{VD+?6o3wEMw8-?d$IWTc zpVMOZ(&G8j6V=m`Y|>Nw)6>$^Gn&)0KBwpGrPKK`^3^j6Z8D1eGfLAl%9}GPKW9|$ zWz_Ix)~RPU*knHU&umK1Y-!GH`<&Unm)XIW)uo=*ZIjjOpVgP1HPD<j^f~M8Ue+*Q z_NaRHm`(P$fA**J?1|>=sn6Ndd)W-WoLQ!N&b&>|qJPd(dd_ll&g$o!AA30)e7Qf> zbAQ|9Zu{r%rswWA=N^2{{kNA35a>`1I^34d8bC*8&`~XP%mf{~PX`Hk92$9Cws|}O zc}Ftx2rYR66L~`Wc|=0Ks7AiHZN6kczH~;uY)iiUME=qJd=jDHxJH4pZNZ6v0=0|+ zjs2{21PcOxTN9P`v;(E1k$MP*B!3KrfVZ0%C<D{fCJV3;1fFi7&YGqcbfB&qffoXb ze9}=?vS2N_=!$J>6O~O#wdkU4v9Ao<#g<|Zx6~@I#HXbo`6H^%qJ;Xr5SCC9uwSBt z@_}@e&<0YPNN7WfuRf|IjOkVip`rCBN?rR^j+BO9mMwEhFJ<w9L55L!0~rY#V6<Cq z^gz@pLP-60R2`#)c>_+PC8TAfWDqK@HWw?Yg13z;uBGFe%MdgW_`Q>>RCD*5RAvAX zyojW$fQKvUmCXYguTjYMmWQkw!E1cwFbHmgUUB1h1^x(-QC|2wkA0Dz`HzxGIfBra z0;wG;ezoN-9aRsvLhp8#LmhG3#HS1TKC!ov7XX$sjIi4x=rRzP8piFrolyY+m0`qH z4e-te9F~b11p#Dc4akjZoGIC+*6z}9M=A_+h$w$lN%=;pR~|}=ziu%UebMbHEU1cF zTfQ?;=f+en`HC+-;hwVFQh(M2t+G<D>|X}$tk89jlZ^uP2hbA?+#~@wd9T5=zRn&* zHxldb<ki_$psI<e(GK=Kpza)6oy=c<d$YI_EW41=VEGu$=wM#}feFGh=P2bE20WEk z?~O0NFN@Y&u7gn6Qb5!w1<Rz?-dQ<8>j=Z~^ZrpSd0JCmNiDWzz||;lLn_NFp67e< zPakC-kEX(>O?jyd7Bxzkvn+UqYFim)YuABc60sBe&Bj(NsYLLW2JZv1&jmUng@I5a z!|llkpJBuuGF+*KZI9S`_H^r?S$JqXl*O{fa|UHe00?r(GmHWiI-GX6E61cbSdn1C z8@P#ywzsXvG~{??PZtK7q7%tJ`V{z?VMGGRW=C#k5*wE?+utYpYeb<g#zSwBcyDAr zZzCc)2U#r0@ZiHQ*|kqB<G5B|j?KbbXeEdCj`s|zn%YrGMN=(c7C?Ih^(Ee;eS_Tj z&8_pjH#*R*sESl#x6D)FR#eGAwE=DVWJK`Bs|U0;KIPW>m9F<rb+;!_c^&Agj!x=k zV+yTJh16rE1+xSL78wl&9^KMPC2aFNYy3bt5uM0@>r;ELd$6`z;J&r?*kdHA^hQ>Z zS0+<DLianKQqg%e=q>=$)q$BNVVM*hlUl8C(Cb@VC&V->dV+q=jK{^db)6aPip)|j z$lwuL?JOsu3^cJf+q!bIs{Y#bH{`MCras5zp-L-x65We>NPWUlPjm0L7n+GQ`SA<M zH&>F;^C(>W0WNH)tINI<LhXBYpO@Uy{smt)VSx*Ye!5K>tiM0RUoqrc+ow3#51}@V zPQ58Gd*f4!bTSjEswtAg^uNk_n}m7Wu!)je5lqOyEt1|%YrR>G=50J&(aw7Vb;Ryj zyt^sixD(C0juB$iyadb#p(lrLcOnfbY>nhnF6a=O`Jm^}FxBxH1v<D(Y8;V&1N9m? z@`lHrS{ZX%#MXX9Uu*Q%O!XW_aswDz&U)L!^ca%Q=27twnI&RjGtDAvZ&d&CL=U{< znQegUbms|-olF@seQ-U=?7jI59&dTc1;U5BBBf(>?-#(vi(j1E+!`*k^N#V4qk54a zTaO)($31n>){`<FX5fXY@mq=?9G!4mjAkdfkM5nfeX2gzs-WYSKYr~&J1cw|xHBI9 z!v0d`r|2)AV*h@M7yO)f@^jMV&nXW+r)7W6c=0*w%jcZGpXq`V`6nj|FHaOdm?+Jj z__z0_{L4i3-w9RQ${IoSBz?pm%}JRMB!u+1DdxE8@ckEm)zYtzKJsU48b(F2=c|xU z);~_uz5Yg81BSj=9+^HRqS0bSW_>_8)S<>YnQJly%O&G~Q^#)Rv%D#~w>Pd?UPt=# zMY`bKJ%6M<1x}5xXd0gWAt>3VFxf_$-n;o>_hzb>f=Q=F&tzr(o>V!_<f&4|yGWC0 zxqxZrWd&u;nGdrF2pL@qeC5HuhQyaZre~b;pNUS(1P&Jcke`t_BVt5F9?fhxKQJTr zLr`33PAPCsEoV-neNJn7?$p0Ive3Nlsd@b?^M--*#yRt*|5B9Y=GaD1kB3S~?eiCB zIv;!i3%~_v?ZElBJkKpKXQmf;XTmOB1|wry5kZ*iM;Fg`3R0S?yI+7r5YVN7|K2R3 z^6JUUHSh!mXo>MVg|DWT1w_@S5ZPLo3ZTBxO9&O-Uw#M+!MSPNRyp(T1N~1)B_H{V zChoWD7=e^hZvEEz%K_h~V;1c^K`$x-vJo5fk9)#w%w4ES8?nr(xcu}e_~|~F6+O^Y zv)Iys46T7+yejR*P|dOU^5`o6iRZ)Spzd9`^>Ao|Dr|whrautx5DnUp!PH@@<cpeL znQMHVD5;8B*3SOJtDE^V+{s75=ffCS0s=XM=plT=`m&i#p*X($z$m^dpsn@*OEe+i zOKhb(2+$aaQ4LUPn6>Z6I%rvhnEGNb1e_tlrZ0fHucORsAa()E98bY=Qlb6;s)~qe zq|HDrr&)AhEYU9<nWuijEWelDUx4bs?->8$^xC}OR^%LjoR$Br`|jc9z%LiCZ^p;) z1+-tMnZGTBx6WyAop;!}_;Bk|?w0M#E&H!qSD0HA;cX}F?W+#kE)Ta|bGO}IZhL&) z_GE5Tg?GHQcYGXnd>`)k<?aN$+`0dCCy=>A6W$Hh-VJrw4S%>BnY(+)U_^i2jb-k} z3-2Xr?<G0xr99kA%iYU(xtH~IFNe8D7v9g;-Y<06FMhaRn!8{Aa=-HHel>HyM)*&i z_MZlaKh(|IiTzs5lbyEF+dgvOJn%8+&mSk@XD2RWXG!nc*PHih*dY|eZ4l5p*(b`r z9jXOBr0)FcVBcbbJAVe*VV$hhckG?VcFx*$emS;t>gJ!-um659|7{2}e`+&-J21B& zGIw*C`!AUXUzq@&%pm{&%nZJB^Tvr1<~jQ5=N3#;6fU=i@>wmKWvJYo?oPM*b|&ZK zgMV<s`6Y{dgBT%$jPu{m6`N<D3L{)tK3{&J>Pk<>g_VodmtO?3@LycLRCn#an;HDp zKkQrXtWEc1TCZPeSNOigB5;XheKUkz*s!gE`l35VP&-_p`P!-eWV@~qshSP)Ehy85 zRnYdg{{7rd{DJ)N)KcU6rI#0*2`9c#!<lE_^=7w<)OV!Aro5``cB!xDP~Kv1>n?jY zlwCtt3(~W`jScDTb1r4@`>tH$+o`&Kmh$w+!kceB_k{{?ZLNKI86oWO@BaSQ+Sk{) z4$Q!RfB!NOBr*gcUh^L_gZFBU4njDTq{}8%Sfh(RmK4_-lJm<%0Hd8X_$qx0|1^)m zs#M)ld`d@xc6NHtlQgva2ruW6sOy<WsbizmCn`6%rWvIS8h1B*vMV!;Vyz()ZzT<x z^yCi6NcF0FA3rXCXUa0tILW&+Qt-uSy>z_FF5VSqDm@Y@EY1=fp%>I4f-nv*%`+5P zP3gOxe`~c8IgmS~_&SFJhMZ*%s2WZ5(!XOk#_~brPYFPeX1mrMGR{UE<P>`mnf3VR z<~fasU_8>i&eh&kC@8<ITIgYEkm10S4mO7HCXa;lyEErMjEx6{hDpZ(_L&SNbA;{_ z)T+Hg-=#c^LL_^-K6?kRXM1gufEgURCGrzW^Cc1~Yz)&Zx6_87gM==-+9b8RN1P5x zSx6DF?^NmIzc<*$WA6V$##qRo<J=u_OMi(zHQq<&k#+cefzl^DEE>OwKTeR}3*UA^ z5)C5|`5yFd<(rQt&h*T9V%?p8&QArc($exx&c1?X1T}n+(HQu5*)>C6Y~bqYsPWDd zv?Zvt`fy18ZA7jud|-!Jeh+&>dIs>+L$<Op#F6gN`)rhi2k6;=yfa4%X3mBgzIBEN zp^yyr8W!kpI^O=zw_J%7i-d3`Zqt}VPwak_q+U<|&jA6Qa%EAX*_Laj_O43lV)Cwy z#(W-2z<qjNX0`F{;9`-#L_Zc&f{*&jz80+>28sf!tm=`Ji1xrUt3Zahv2FNxO%Sp7 zgdf7mU;n&Ua1=Umht57_bMp>W8}AyT`j1T&h`(7Xm8Inhx;{EXInE_qUGUEMZ;+(m zU6JfKF_|E6_(Q+yJwwUJ!Qs!fIsHe1u|b8NB3+LK4=2ho!y@8F-z_3^5*6bY(qiS; zY53uNNZdF}4bvJzH+1V8X$clzWA84F(1PyboVW@#_Q>hvrG%!Sp?pqRH+^9D8@NjD za<)^7gj~A|+M7giR6`Nsbs%uwm0dD=?(LvfR}R05c#xHRUr~5CJ4ZWQ*t+4e&d-^G zpig4Aj^01BgbmJW_h%Jd?0fBYu*oOFQz#tWkN2*56_a?aQhou&*W7fq)I0traf5Uf zz<lV@V+G8ANpmf7q%=I-cy-~S7klDvp6J7l5aBIQ^ch1Dx1AJi{V8vz=KK>;oh^lv zala9F=SR{*=#RX9(ucHK5Kl~ex-ItlqO0wZxQB%?H)hq$3&^ts@1}QpSUv2VyfKIR zNU6XsbIIuD)Mo6^u<?1Rt`vkyekHZcneeucHU3n(oL-{XxpmUjlh2#YzbAzVd?iL` zmUpL|L5T~@xfbZWWyOX+DlnXrj_|9wlmB5%OoahNL`-uH0#xHP2FY3X%5~iKs)fi# zpV6s<PIK~>LIS)K%Nobs;guE=2dcyhTk9&kABq;9kH2AX#0WgT@QSV|V|24^q~)G& zq9ZBjh{2lLn_$5F?35*+o?B8z;K8d0h`fYz&du-FNm%tz4zx>Ox0RpTZ{cvbyTOZq z-p3gQxh$V$rnyYS^b#IjU=vvs`H=cCRC+7w{H(12?`(HK^j3W2LA3V%2rkgIs@$5r zKsTa$lP_WsE}YChXE-Wrlq|C)UVJsfW23fZfaip?QCMWcM#B4cS@Bq^GSWfO=~Gi5 zk6fDLim7YGlPRadMmIL(f7NPG00sm?x&NQFT9)f@G~eSRN^VnqwFR%^i2t3UHv!+I z#q&7#9!OhBzRBRZHJjzPNqn0w_z?O<TDin1Ps3gEnLn4z;QyxRA4rD}btqo#i}v@w zW0rncs}ZJTNtK@tVf8c?&6Jgir>L(fkN%|munoGwHqbM8;px<If5bnQDeDb~(2z+< z!<8-4T-_bviWoD}+H`0t-s+T}I%&QYqIEV!E}&+qtkkN))6almpyb>gY1#D5_vXa& zTT(++{37e`FT)0fPPKV^PPHZQN*=YN{2Cri*Zy{TV{iOB?1f+RDNUNs>W8R%%=Kyu zU&<QmBTcD?7JvPI*+09jdeq|I=9ibrljC3iFxI<nN<`$+D!5%4LGbL69*-X)ON<cE zP<kfxuvW`E&zr|fzL*VBo3JbT%Po3CDC1(jbFV^*=;O;}pFUi7dB!qllM!^$IeM6H zEH73x$5=EjoqImtL5HI`J>dkZUo=q->OUW5VQ3Q1=M;($_jRR<6dBt1mPxqT29(98 zI!T@{CSOYl>a|BEn@FbLZ2v5w<2Ke`oaNBFC#iosIj@(`Ww>d99?D}&e-JK7=)kim zwz%rX8kWZw#>vW#;%~soMMYV@%ioP`9+W3w3;%bmR$5%XTwY|lr3YwtGnYefwc~Cp zRZWYB6n!oBw`?W!udGK+H`IN#<~5Hd$dTdcnp}EF(JSa)y=oJWdr#<IIi%<-<aFxZ z%6itcKGv*$`YiGE4>Ylj@qa1$!D{UE;-rF(2Aoz!xaOL+)&b{V9u0@Gd+EPq;p~3( z3N(`6?B=resO{EV-Jk+m)Kx`&LAeISrcP60Cq%lW^5=kj<Lb{rgz-ifPDJ~>lA+*} z<zpS}JFCCKY{Lm1AcVB~tH)TXs$o<>Z)mui)xZNRlRQoDfL(H^+Jf2LeY5rPN(8$v z3{7MJNZAeAnyy8?`Q{iVGvV7ipN}^w!ymAJH%CtI98Piem_H4@^#Mtu?9N0=RqxJ5 zi^Zxykqs5ECeF_MDJS?|ul7G5Vdm9)+GgQK!#loI&;9SECDr@OWgjOtu`(yMcF~Bm zHS%23w^+^j<4ne@zTgP0oyBfm;Zf}b=>*nkTaE{}Up+K>`5SwRs2FuL5Tn>)Qj7I` zw$>6M+z!KX9o>7HT%difxVO=v@gxh|$=|<V*X6;L-EX<txWWO)e$fDO*E$qvP4ZiZ zgmF5|d6tk_$yhiCSr@lm%#j@=&hGT7iySaY*zu32WdE`M^V_J4BjtzVNpi5n0X;+@ zei^ZC)sI7dBu^#8-EX=#1({fAE%kVZW=ZctFe8k+gAe9pS^1!Uk&-VYZRNv0G<8eJ z2Sr5Rd?&7%HiITwznW6$pkl5HKz&Q04^JBSE^8X|!h_W#Xd)tA41N4JH3en0IL|Xf z1>N)}w9E-z?9qk`CQiu)Pef{>qU}2Rh3J}n&F<dUS3hy6?iy;?CdL{O2|}60Mp9S^ zTN_Oe8xEoj;fXF!4v?#^k;bHyV=f%7Vcf(LTJNT(OOjQ8@458&9LhW<6(gAk_`J^f z{4TU_Oc)nVL|k+gL8v3cgzb@9PljSss<ftHycW@J-5z%n?sd)|29XN8bz+y*N=P4V zM21hg2Nr6&9RK!6<6KcZPaqNyy12yDMTNutlp1VLu$Snu*#mr8(ySc4eSo3R53htM z2Hf92apqd#u{)pW$3OLt=wD8Fl#MA9atXp*-PNI`h)Ef@@B$aHT;AwQWECU@ep`S7 z!J1DU@lPB4WZ9s_X5(xW;Z~{yC^;t1+Zq2#QxsSG5UqWoh^JZ20wGF)aHo|4V-_)C zLV!EmfCvpRl1nM&5}{DyG{U$5c8;wo9w&(95o_r&M;83;0cHZ+8|YJwp*$$GVh zpSlR!HKEsNu$uA<!1*BluO6lFj(yrM8QE<3cU_5@0UNfWB8ThA<L8W`2A=;_x;o8Y z;O72%;zP^xXV0u|n&s*M5GDWs_6E=a;_HdDN54c~Ks^bXr|nx6o*vix0};QsE&D)y zr@2O#$5g}R>GJprlzaGa+<oQJ%{H>jrW@~b!#|C)8I6vSqCyqpgVWo~s|Cl;+x2?a z!1gB^+jn0advMmML#Tr+Fu738-y~vs>4j(0H*?bUg>vrd-{(7V0VKU}@(jwZsSDBp zQH2hDksS-Mfu=LyB4$oab+?F4M?wrvV<fbiKS{VEVfcTYjz2g$`R_zRGcOG}&jx?1 z(v}>%8*Y}R6zSM2kkiTCSHp7Spa5q_a*Hd$TwU~O&`I&eB@~5Rg$z+xfwWHTw7h8B z)nG0PD4YCI>ow=MLgpEd=NA0vb0r#+dv8rk5fB$fjPaB&?}Odr_(<@ZE@wg~M6EWj zz$e5|bAKfM6hs*=5~D{B0f02<ahIB4g8csbAFu54*A|0Hd>CV;XYQ1<c)Nv{w!lPe zw#ZuK72C;)aR{BJ{L_*JI+l+EKtL^v76kavV7*t&YjxhNmIzn}vg<)maM3k4>wCKL zlpx*8H*1~_nIhBJyN%W~$c^D3C>Kpv8BRQWH5e+nL1QaDxfU9FZ*uxd<nvqfC6_;$ z;(uLo(e!J<!TfCu3FD?N-oT9zxxyJR_wFktCn}F0z#>kB=$zUJ3Oi;`<iq**iFpRc z;kxIfnLBE17E~yQIONMxEGzy{GPutGVDh^(vYBUmlAM6Zsk3UjX7sg({9nW)dHUGi zW_snRc7K<WitLie@d`Qrf++f~rT6TW;1Hke6`dV5lo~mRlS*6lqOeLG<Y5Gee_+;e zrc;~Vzgwc<6WUL<-Lg*I3P2Y!2&ul$4UXRAZ6dGS{)(KfKf1<o^*)OnQ3qj64&v4? z;5kEXeA{@17&!U&7d_zH=%b3YbM+a&SoT`TKBs(m=pDZWcF8aDa=`q1^d-&pR=uuR z?`*mI6Gu9LA$1G4@pY{wvQhiTWZeGZt@+Ov`?==pd%R-xB!23heV}s`4_rmhbCfjc zGr7-n1SdbV6a8?Oi7>rP^>1aajN@qgnn#(jspJW925m#JBk0eoi9NtodNoAIlL*4B zT~$Hg0}&M3cnARy-bA)$9)RNr5DWq)AaIoE*QAQKy?g)U&TSc9K!S3ASIS=`g1GbA zCX<_1F>;IjN#NO9By=Q5?g*e9iNSPAvy}!AYW?_lAENRCw|F1QL_jgt#2wWDxe)|3 z&*dzH^#%}j^pni0lAsj*-Zu%hy|Exf9t(Q{+%`T)#WkRO<j$!}p^}kA{nw$gBKjR2 zc!~vrKg<d1#lm+DoCbly;RvV>;!X|Q1+_@Y85$z!-uskrbS>JRj=sPI54&r?C6e&X zT3X17qqT-bGaR(rU_p(r_>d$nGgyN`wg?dD7en5;1ddQaYep!-3z-S9vuzq?&`6<6 z9`3B+%F>TcHi8#AkkA?F=nfVL5H3#-(_08<$4B@Y<Gq?5aVkbo8zK;pkgj;kXN-%7 zJak2*J!>txDJ@DC62c}4YaxPiv=BDMM{qm}LV+G9fpJHGi4*9)r7-;>R`(uIXAyih z%rbfjEF?xMxPm?w5v!aLQiiVVwT7)keQYh-xrXII&Ep6<24NB_<rus84EjqNJWgZ_ zVBCQvz*_(Wi(@ogC!CK5$U728?eVtILEW)nU1eH=p2LVj68LqAFy#mOm%_o?7!X3# z=}%ZNzSc!TL#VI;S8$Xb;#K33O2xoxV<9!@GyYeG`apgOOezxp*A?{U!vB>-+QqX* z0GJBtc${SlEFt22X_AbWz11RI4FtAaz{AG4@mpA_6evKC8<ZBg(+@7HT@M}s75R8c zWvuEqQl)1SP{j{_xPpTh!3XKdMbAAR@8ZR!?g*)Z?7Y6>5gFpwA4(f}OLk-w@c|BO zB6o-h)m|LV>O4t&+$rf4%VzMoH7H37c*(}Gof^n?$oi^+A5ycb)gQiX&RFKn#v`&N zmNIxbo|rUe_V#2;&D`cU3KeG_$^7-&i%}NdryjiYIcwP_r}vwG^CLngckZ+e>4i=1 zt_{ea{-0V6E0PMJ@RNChtZsB?K!06CXe)@0HWfew&{sqR@osd^0RirE5xo=iH+Rnq z9M)>G3OjuH=-Rx_JpR#5;i-gtS+{&<?KP%O{{N`eS_;Az^R)I0$Qc~#T!s3!g@yrz z#u<bKB6upJ@XUUp1)=DiM$viOqKg4VmokcMTZ-%_imvPzQ3%CO8pT&_i(LYWT{DW^ z4hyx3V$c0zDxt(%qr}Iy#5bVCFQX)&rR4rZN#K47jZhk_Q5tGn8Xiy@nNj+<r8Js3 zQ5w5n8c!%o)F?}`ElUX~OUo$BXerB@D9hO|qZ7*WHOdQZ%ZmfbOEb#LTgodZ%B%Ow zYX}u}8Wjz;70&}InldU{S}NKmD%$reItZ0r8kOC)mAwI#eHoPlEtNwPm2dYehY3}q z8dYPqRpS9wpE9Z@TB@cds;2j=7=-Fsjp}*Z>cxQSrHtz3mg?1s>L2^n8-%AnHJ<*q zeYzd+bT{Mae#_H?iKqYep91_fP|X_nq~!*HE1!vHu`AdHv^PR91vJ6~3S5Z@mJ`9l z_7SZ~U!-86mY5cL?b$p8jRH1NYWY@B)it%iK5h#H8fdjo=_p=Ju#!owucX(>{=o;( z5xhqLng!+%Ue_N)L2Byc2lJ|iQL>q}JQXN&&3cO!l(Jksy9fdfL5f!(0uMVWvd0B7 zG6aALbs!Hj{3DqS|I|^ge^9Ee4R8^(w;WpebiF1&aG?T};s<h0fRr>xH4B&u32H`! z>k?4~L{vWGxqroT)9*MWKkyX<dPtyWW-Z_8`lrLF!|t#w9#ud>m35%X7^vJ#lxr*K zEDai3z>bsQszlgLB7#az(y_zjWj5bkX);yES~*3>)-~p7wn^Dxnk+EAgJ^gsT8|$f z79%d%fe-#ffW`<z@?o_HhmN4~XwOwAo7$M}J_yZr#0svRA7I3{f4|ob6KUes1p6rH z9`I#P2hx58vAcq}WdSOKu+CI>B`WMD4YagKB>zc*TGp9GHf!*=3;WdY>9liTaEle~ zJeBRxO&p=ElOT^fpyGCjxSwDblbT{R%woL(*SCO?I^YlrjN}2+jfd)zKoS+oMTh?3 z2b3u+=46%tDl)O-K^_n{pa}+Uw6j{)p(at47L8af1@_b6ygSIQ*~uP-+a<MgA7B|I ztiwSMWwmEx1Gi0X|2vHP$G|~0aH0pjw*<O=0qmn7`zZPK-6{5@8o15y>%aq6WwNUk ziN%lt4_Tyz#`pO%H(32Q5G4O-FAIc!BwG#$yda_*Y3N2O8Ui#zC=FR!palbdh6;9- zq72bbt?q-iW~79{UZ`TH?Np5*e=~%HZI2pkX&Z#&u`^_ByTH&ah`p(WgOG52SwnpX zxP#$dfy&OU4jhw?_P2QBPezX4e{*32ZUwT0X!Ti=;r=ufgv?e-X3M6${UfJeNMxf~ z)Ey?>2Bdcebk;+^oMsW!0-`enfa`Lg@d~PrSSQL4WDbItPB&V%N!TA?k(=x@zzDcD zI8D`ubl{F;j}T&p41W*to3Y0LY)QmX@sp!sFA(~NHFwRZeD<hW4eKL;_s6plW6TZg zMtm=mfg7^NiDJ4$FkM)4Q2R7UtwAPI*jk9FIx?6OT}Rl2TWru^wPSUtcI0R+w6@n; zpqah3*WC=yUeS3$3j_s#YnMR}fgv~ZA@nBuu}N?X{CF!H6#9$1qz=}{e+;Pl*iA&5 z4!`+|dCL%B(TzvgP(Fnp9v^#rN@8HAi66ZMf!OTcEe1C6FZN&qyA}Wb$41Z02KKO4 z+W;r7V6eAiK%=bZa6FoYo#Tz%@Q?CN%qDJO<MZ>s*v9P1rWcbfF*R5IPImmAWU=hM zvj$FgU`7D;{ufgNU#5l>*fZnP9xbwtt+7&54!_O<3;HsZ{Uw|^$u>p=2L##Yzf27S z>_0YeTv?qP&b@HR6rrtmkAiKtpX{)ooZaZDi3Z)<I!~K|krtptChAV+0E^D>k=h2j zJ=n@$;ceHbl39CNbEb;XkUfP0b7lzbGs>r1O3*EM_wk|!o#Hv|cOJ}2w|9!IzL%e# zmG=Y(ED*uN2<0nt%GKZl%HgczE4aw3Q%AvYcbLD0ODo02@F-}IGw;%i1GPH2hI-uv z-ektiZf&stWUyb#S+MmSV%z+1b_T_IhNCim!ZoU);Bj-6ImmMqd^Ne~`EN1r-eLUH z=5y+s@0D*o6m%N}y~+QwZ5Tbtm<|5%{?{-%17wS2<}5vKUy9CIN{nYw6!@Na^gC-U zYZ9F;GyZ!5{m}hngVeC)V3%`+*c=4DCdf_lWqr7Lf8@=5@XpPlondwexblU(QY*AF zPsUys1S&jwHr|6TV(|$6RqQCTXtmq%O4%9ox0^XA{XeV2LTgPlOwTZ;jk5MBaBU)I zZTu}Vkg*oCu@(saU>yB1f9l8Aw@4cbBtZyvg7HH`XkDjz?zl&j%`iggD007jeYbl3 zZ_fI^x9i=cS&1vNERMLNcG%r`97Y(x<l+#U8?`?`c_Hkq1(ul&3cBM2(VL4M8^YRO z1>LbW(KxuyD)(`8WBj6=<MWV~#gvL#I`dvjo*W3vuJx9C`Nm?cul1MKJG9kRHeK!C z`r5xW1Am{2{cXBFHw=dv0Wdwr?{m!G=e4&ia4<D8vVhFCV8)h0W=rZojgc|kq-__6 z?f=Etd4{w3hw(lnB=+7Ri9Kr*Tg0YT?P_b47`3Wa)k=s_vnaY^&uXZuDs61F)%I5v z6jfELimDvvT-Q10I`7Ww=gsq6&+odg`}h6c_xFRj3^dYT;(ywIoWpYI)-%BV+?D?m z0{co)*oui~0V7zrVa#tv|Dz)O*ZN?1gIJMD`I;j*dZf>6u{Z?lWungAu|}PSFOrc@ znvnNjgR+J$4f{chpM%2;>DSN7S?QY+=p9$SJb3zL=^r&u0+25OsG#tdFX8uF`M(PA zDW$7)9k8hn)^vkf=e@Vi`>oGgbIw~=7=~E3?(1!Fbk2U(`xl_Ye5}uWL>O88_zy%u zG5@>4VihzD&h4kSo$XmBe%wXvt<g8R*FE`oT3X*WGThPs_p-v$-`}G>8y|FZ{|m^a zGNI)YwOdCO*?0&U^g(GuoMi!5@SK8+{yxJzuQK`XL?0#ZuMIesnLp<g^S2)=kalU- zUZ|UqEK!aQEmybxpSIekg4aCLLfZe!R!dhQ*_BylTuG)^#Z1>+t#wS^%&)PzZ}INt z|7)w&xKb~L^*R1uTg}Bm>K2(An)?}UfIIh2Kus8>%Vr9GEQUBYk9f99-)ary<FS0K z;#cLZ;eVM>s&u_cT9DL&ajdzWt|oWw&G&^C%Jo|21X=ygn5&OmzX-UUgsk>u{^!8; zdp2}q^qC(1x#M)bBe#)i^E9MC0%2eW`6N7KS7Wn^a12KtIs`b@)%2w3D7RWVR{Pay zK6~*m=J;*!95_d9#@R(4;K*pWrw`!hkZW)%!~P#zt#_~6>E`zgVOPxl8brpP*hPzw z^uV#XjmcDLy1Aa#ixpdH{^W8A3a{)u-B2d#ZhMD{nIe*xCUpKWYG36Ndpr`{gTRI# zd_pK!G@Hx3g8pEy$?IvhkpK8Fon-4An#v}JBa-M1j)>l6p5m{QwWp{%<aB49qwPMO zuX@QRFlo3cU83l@R2pU>M&T5*W@D<?wk9x#AB7fAi?&cM@IIAmo8ElMJl7$7lk^rL zrwl}!)g@b9*zbxlm2D*GXk70fu4xwRtHUbo68Y>m>S{cV+WcDKe>RsWdIt+`*K~v- z4J)K{un-VvYc2lA`^}6Fq9AsUB$*tT=@eQz#3d~?p2^^HZ|=5wgLGkc<x<2ZjhdTn z`aT+BzifC<{M?cw9L@X1qGbip)+zm^vMu%q76VIhZshlIPKW5xJw$pbTrW@NF}N9Z zjq|!O`PYQlRpxN=IwaHoTftO;I=~qFTS6u?xSvm2gnG}jRwRs8vj_fN;9HWtcj>R| zh<`h8kaCL<LM|7!s-5D`_-=_$TC8ECz1tbnCB`ZmRhrwW`zS!pa!oSAz~~n2cXhx! zY^GPO0I2qUP-pRdCLS)y=zT6Jk#)~njwMV;a34>#%tmFak9HV&w-dnS)*onH(1Mr- z<^bsNp0&MV5}n~w*6LYYZu&QD3nczM^dBN?&xruu!eKI|(~+B<kzXID8|Ba3TlrSt z?3S%0?SlUSt!sZB5i<L=y81&*<1H`8WNxER+IL0;S+XMZ{oj6wJskg4vSw2>L#5!F zcYf3C^)swc!|CL}*ZHdllup$hx=DSJbPx8|QhriT{<HY$Pkb$*pUu<AmO*u@jxzlw z0^`&cq^=d|0LUUJEHkCn8+K|?bE7^_UPBLh2aMS3XWLvZQHkG-`=6s!H|cGiJ(%yc zp|@K6Ir|8P^vC*aws7l^_WN0zQEi6eYPnZvm)vF2b7=%l5>r7+#S6Q5{Z{8d+N2W( zdE-q(rArjO+<V8p5D&UvjGh{x{9B7^1AXly!hod=b4g~@Q}`E%3B8sVoQAK(^WP7V zJ|d33fv6k6_T9R<oI$un#h6(xndfm%Z^(I6Eh^&kBQ}}BMiuq+Y<n+OY3J_FAP;t@ zL30mNLr>R`rl(DVp8nCfE8-5vW;c)XZZs=SNE)E(wB1Pb&$^8y&DFZsmP{YT9o<%` zeAl?%k(A#@u`v?jjFzW_ztVBfg*))ub{E%*6;2uYYW_JEvRgIaUUcg|69S3kv!!QI zo$$eD-dV?;1w9w@%T;>~x1Pr|nKVuL>T$JCEDLUl_VM-!@S-Pv{g%3$<Bc&^_1B~n zR~QA`pt#`&!g+m@2^QFNN#=-&%+~2j6vH$c2%nT@-&Y}PmL+<#WpvZPx#em6ZGsD% znQq+W%y&+rr%hzAo&-6b(<KzzuMga%pQ&@=nuT6hrgwH0Pc^^2Eoa41F}qS0(T*%q zZfbXI_2JSl({NC<$xUW}cd-X+@+M+zX>_zFte*x3xYPWt5q8+*>VD6J@Js-iS8Q@U zva_WGgoG=kFwHhUuFQMx2;?=WfP?R2j8u<ua5hV2s;_zi{T-elL^6|JyV#(F=HU=G zOk)8T%~$_>@BdrH>~poU(#XTpahD5(Y~T4Fy`k^BzM-Zrf9=diCgoi!Le>DHNKE21 zDNL`{G;{jk`uuL6*7ED6ltR`wpuj&0(%1KV-PV(XV~3R<Roa+y<2h*p?@q9$wRERG z>Bx8ernPdCH7QzM20`HVlGK+1T)pZ%Zj0Gt0X2yvp568L-eOfNN*Rs8Ig55}kNb3+ zjx@TRhtzu$J-Asu>-=TQynS<@mg5xleD)}~)QwgUFZT_$mwG)T+0vM)q#qI3lE`95 z2_qp3=X=p9%{KoLXl_<?qsp$OWgO%r@ve7q54Jtc4TFwJKIW?tlV$Mt3}hfZ^fZh{ z?i#{Jl$7U+OCQ3A57PP9Y)mKF9ZkE~`S*K%O3PirzP?*l?m`o3&Rc3xK9-0n<1<JA zfbPS^<Q3+IL{jV~UvT?FZ>QX9S1Uzu(i!P6nfltijVU2=vXfFixgba+dc@7!)%Tbx zZ@gQan>zX$-`+=Wowmxf?9qEeT}6;B&qeP1<X%hlW1Ba~|M0=hhG{!z^r<n|rmeXd z)Xxxi!k$>MTeTT>q~2vuZxLouOa1w{#}Yky=lgvNDQ=l7zq8{{L<YanBG>vcJd~SX z^0^?(54mJ>Xyo1$>%Wh)Yg#_ePjHG2GO-bU^PAnkKDX|*8tJIziW4b7uJ*d_MN^-{ zn5s5x4@q6`C^H{xuP>j-UTTvmZ5|Um6ebN=B@O89C9=f7TG~>7|84j|-^=dSGM>UF zL*Go7XPy=O)=wQjSN3}_$FV$<MC--OZ_+q}P?&LvriV?cIapMO*~6(sE;;JG?6`9; zNh(0r{BNr+-O*m9W{5CT4*U)Gq^ITJ1Z}W?YeDIJ;IHiQuP=;i+v`65b&2d;Qf}+| z)z0(pYYzAUF|Nc#q_$f)f6#ytw?cP)dJRU7!fWsc=TFQDT`N9km-5ZbKowE8SO*lq zdIwa@cZ;x+9jEC(3vTJ0{)_PDrt9UOO-R4LR1PHr@H!n<``;p8n1A!Wa~mD??&cEq zYYnD{y)a=lW(f#g<2{@BcO(4QoSs1@p|U*eH_P42FlJOWt$of19RN5w2OI{$hmpXG zceVfCC9Uy_XCAW0N`lLH!67vtqV;KL4zX4to$-4qp>X>6mAC9WO<=>Wl_&wr?@ghS z;225#eFC^$1gEV)twErjTf@KDQ(s<Tsx<9_duLcu>$xN7?~*=5Mu8&%U~>ZXCFd3+ ziI2l}!Yt?!z1=Mk8W(4j2VXnkgf=V+AE%X~&6=b}pp9Np50S)EmI-Yg!`;Y^^h;){ z_ji2gf0@B2q<DQAgfq2)bIN@pJOt2AgToUDIvV!9Z=;H8A<f%=@i7WwGEqRgoRs(+ za3}!Wzt&6ZW{Akwzei5LuRw~40#mtR#R$5G%HWVau;Ka#>-@fGa=Ig~*B^eVjrLlA zx*S`;?>XqpO+UDZ_TQqTr&qy;?tKhJ)0mr5i=W`)i|{ck;22E$f|g-vNV?~`u|hF@ zjg5A^0zR@vH=dB9j-l2#0Y$B-2S?#USLl&D{n080Q4oB*Bsf~XQ+x~L18JWV!N=9$ zONu{^mk(fD@`5|)<9YER?gQ}zTICUHR2x2;G(d@j40;$2X2#|>=758X-p8}j8aPvH z%+mzh^h83z9P5LHN5-W^;9%llObFO?9w;yfv{LvO4*-Xd@clpNA9I>-O_(M#Cdfn6 zLnTehh-T6!AkQ2yD)wWn<cC#(q52l~x^vo?nh%i#+V9t?P20fBMfgAU=4->o4fYmv zZ1l?{(tQXZPCr?jkfZ}oi75g{L-3)z_}GNLN=e=Rslhj*BOOKb%aDZN)UNyR%h$t- zJLA5j8U`!i0s4j=hrQj?BP$c8QM};j8gT3-W_U13?F8q$q8<}6*q31xy)-iSG$Xj- zJs`@2T@?SWnOf2wees{gUBX90+$d#*Gb@;A8V|s`z(;ixXycrF*u3e<xUr5E^;e|c zpqk=HByGi6kNybwIW#><WpImgoVY^YIR63Qd<k0z-#x<0MqypIQeth;P9yyU9Q_=0 z{G2hP%x1`L9W8BY<hezoio^fO=>6U@;yz;e&)cSEtDPp+A{L@A<4&yyz$=F9u|3s` zEB{D4W9^LVJA7(zJ0BmNfRBWO#4%VDfi|K7A51V`Ihx=T%qSy~f)c=<@KK2qP*`ej z^a*X$PCDV?08QoOemE~Z4lH^Oj%&lGdQ)rL&<1Z=g`LpOYJZmHVn{hpiAxv&fLL?^ zDXX#gnGS1_na}$mEy_p*IC#aze+wkzj78Px&S5(nNaHG_*2zcsFgTd<<E_i!W7&Be z29CckX~Q=&wQrdIx)*#m2Mm1x4uR7WD?p~}p9%sy>J^5J94tJhbz@W0R~hgjgZk#9 zSg|N927o_a8-AtStKBL6_sG64O%LssuBwXXkp)w(p*;y8t~bL{4ftSF;|lxf$7MuU z)fd4nefNoAe>hH7Aqfq@!<ardB8O|X?0u50K8S+jF&{4<i4&4sSNeKYz;!Bk)jPGf zGwGoRj@ydkgdh0G`OMytKG~I|YmlyZjA;}J&($-MnKu{RM-U3f6Q0=HBU`m?QkvF3 zvB`d*bQwC6ThfE(&EmIkyQv`en#<z{c+F_*_C;bm6sYok{@hR7R#iVTgx5dy!_TFw zAw^pEB?lh}Q|s`)1lW`n^ug;z2hyQnzdK2)MallD=J(r3Rs{~IZ7IUl`BR33xCFIg zMnJAuiW(+Khk#>&y40;q?Cpp~z0}il2k8+wZ$kQ7o6|q`>PI7O%?E){0LT<$x13-b z!RgR(SSbUi7SjjTek<)e1jjNZ+>ZjAU(WFmu&w}n><T!y6J95_M6h)^sVfeF0Os%F zgSK$81Zsl>+PT-3_*g5{w!tqgXU0SI`Ymvnvok}U<K7m~&MjT5b1C)Ih4F7ch3yD$ z`m^bV4N(=23rw{j?aY2rEi?+DUh-315$k%omEy+;@WhM*21PC1=tFBPQT%Na8K4?g z&{ik0gMmK9&HM>df|@hXb8s=neK~qT1cA26XE0A$Uuru7+anh%i7uUtfGE-bpv_9) z7NQb*B54F1yMp%|wFqlV7vfmC)k5HO{c`$6qK+{^yDiZuwcoS>oWq!~dUuY_j?HAs z{buv~7XtX`kdJ;`Nt!k(AvK>v2s3ouiItfDxOPPq80X$$Q>-8W8Ddgk&PuH0we!hm zPB}Qys0_wq59_o3wpzT}KYjlbT>k_PK)}EI`|d+#I)|E|=)qGDJ2FM;!sC9;e1C>O zu90<oQL?@>wG08YetYZ>+EGPLP@@P^wXdRjA*z%@|DpGWIa7kHbCNZImN$ae$#CRr zD1$!t`UB1Gq28%VeM?UgP@K3HVbfz7`;ofvsRb2|hfEe~^tL`=V(`AT@pM>}ghidC z+;<;?3xcg?`UewpD=pR>E=2c^-p<S66&iHowm=4iM72xiAm;OB6&yP6W8bmqrxWu9 zZp78`-DL#_@2N9Y42#z!V^%c%I!x+EeBL}1IDXLi;7iig6Q`dU8w^S5T887{x`SnV z_@eNll41+QATYhbWxfv`yKCGPI2<$K9H)%8-qO*A<GjY~DK)%0SaIWejJ;{*5X<_y z7;BQNdrI%UqH^2%^(Ksq>>#_g;gbSqbDCkR1X>I)VUj=}sOzWE(G%b{$1p+)p0E|i zP|KXW^n^cYvitU=5M2rfhi&=regJ1jW0~}+WiVPdquw{8{eu|k*8@6Y2`RtLi2XK+ zU2Cl_t3rlagry<>Z^PHT-SdkHsou@n(io6!4XvFYO`SAr$n^l(SlVy4OnIRYb2x}Y zBgr^NIF&vxfGYpS_78Y3*eyp(zm-Q#q)hI0qO2rH?fxTM)8z8Fz`xhKfVniIrCDuB zk}{^9*dmZZ22Zt8am$D5iDO;i(t_Wt$!*ef=ENk5S{cqK>QV8^mAyQnMP`G3AO4S8 zq9yMEzX-Vde)5i{$#@3uwK&qKN8Y4<X0|C25Jkmg^N3Vby3o1{w{QGYlq)Zj5;>H_ zNZ7t6055?5I@ta2&y){)_^?U|jTi)|rTrLn&-W<*CEJn7v=5s}Ewm*FBS?t`C#C9L z95Pxjq3_!3`1ckc(K)4FLVB;%dEv5$lce`R8AS0JKt7`Q7Xw(QWuLK_w@SS$`FOoq zI|1k%qBRXkK;**Z>;kyt-wsx!zja}wn5O;qV^bH%<%NTc1|QCialy@)ecQQUPVZ{^ zs*wrU7k4<KqH}q2)4pBQi4)&h5E&KA=qL|>3O;3Ferw6~3E29TB(r0n+&dATT4ry+ zE&#*LtDmITLPK6`)HNvCyK&d)uXyudMSC=l#5_4N`fke`+<uP6N@Le?;U&>Zwkn3L zAWW%_xM%Q6`ARPA4~c2gh2EN^jDi5vQ`1Fis5NqcEy*+%m}K?ABv*l?ntDh_e|gEp zZ5tk?XBOX1U0CR@=Stn8H$&nU$<*>8)Dj6vA`{d)ZCG_1q`*WX6a#X_aHIhu!ltAp z4xcBpG1%GGRw6<AsX)09EHd~Kjh@Jq^G7xTXe^lx_B*VsLBGhP*8qT!@FWh>+hEwM zz4r9&vCtZK&ONG!m2ej091z7A0Ma7?k)*^+8app<qSK$XN_S4bQr^0RqzxB(yPRTs z@e{*Ggn&lz^F1z}(^MCDwuR|`fSM%HHYzA7k!CeXpe9i=BqQsOi;m524tR2>)oFsr zz0owOVq&gKv%e=1=YqjW*CeSBd7~aD0@|pASCaOrPB@S>Vb(EWGI<4Q?EJzq(@||C z_c{PFQ9cJ)(-f`G3q#c;aw+gkT=}ackRS4{U4Ma9@AEsyiR2fjXJh-=ee!}Xvh+Hf zPiprsX06~&cKI8<a{wGWMs|5l^Y`+CSZi?d=`GSwF~pIWEM1f+kpR?~0BR&)7bk)0 zHHiYq<S0bZEr|z|gp8lRxAFl5USS1l5!N_ig}4lIl1q(T^WuZf_tnpm($lCeDoH0- z+CWn=Z5wl1N{?X1M?k|=OT7eoW1@)Fb*Z0DAB3vYIZY@(<*S3bo*qA@oK{oL-ctS! zP|oKl|28QX|9>d@9AT3@S-%6(p?qnl=D_a<Vk1RLzMmWX4#mfwYDOOHd_R<!AQ<4; z<@}E%{~r{+-An)9(z6Y&Z^M3W|CX62dJg2t1suyRw)oFA-}!MYx6~H4`T1qQpDW89 zG5;4u&v7O2L}8WEo6e&gv~!}kKA0zQtugRaX=9{B{qFA0sq+6u(W`7v*Ezio`gx|h zGvDkx)p+Nx+U`<&<l+BD(R0WLog)v{haM{j@1AQMZGEo3_A2O~=JEeR(eM7#I@wzt zcqAWup?!9=J@-2J*M-jc$-$;|3fP*Ub6@x8f1A&4xyRGcn8Hw$bL>RIt^G)t_QlB> zGw!_OTJ{6V=sH1TV+Cs+NB4Qd13;FIf+g~WaabWYSXG46ZZ5p_05F|#jOi_c2$`8n zDn$rO0Zq&cy<Z(1`nt!m7({B7+?E&MobhN}d#$MFMS@)6V_4yFz84{JFGR#DnPS|J z6i#q7=kmet6>(VUeyzZcJsEE4$yB?@!IYYx-afI`S-jMwbytt3tP9Nw3kf>lu}9;= zRFEcG#e*f~EIom39zyBLw?Ek$lvoZ!)_C_v<60*PpM(p%Tz?DWpM)J|Yj!pCjA{O; zIm}Qw38cH0^82WqNqyJyk(K81LyjzD#FeeZ_`T`FQN0xqYpQ;)O_QnK`rad-s<k^O zV|w%F9*}p=N8O`Z1*_P)VkbEavpQ8^-k9zp=e4Vfr!8LQT4ao}<a3E{>RWm$N{1Pm zbP}GKwX5encixwI&{t^xwn5XVTG6g#Y9zASv1D?(F1+;TrhS-~Ofycl(50LPPBC&5 z8{Q+{-+t~_iDmA8&mu_y)dlEWrt&jOt{g}b<Lb`VHg&sX>#nM<I`^1p#eRM&?dMVG zVy$y(|C(0ycesc(;2`{vMd$@?ZB%<FFLrU#<@q_=L#q61Ryj*cp+QJxTEH-D^(eE> zftfx3wcg%`DJ!LaVUMyCsU}>qRi`HSewovzzkV&Xn_52lh48CKzItPREn7e3u@3=z zTBMw<PH6~D*ZDflk)U@tc*vr9$3}Tvo7p(-y3X~BYs}g`PrTuCpRDa58WU%atda90 zRGAvT&qdCUYkX&J#V-XOW=k!E^juA0I6GuguOjwrPD(OKTj`d6oMQP$!G1m+S9y{U znAN<z!KeBSEp(b-2;Zh+j++4LO*Vt2XIG>|noQMblykHyerLx85@C{`7W5oj-|^Dn z1UgU9fMu%edO8Iuj~ImZc}tdGQIFsz1IJu%V)lb`VMFN>0aIGX@_11%K}v{8%0W3g z@~G#5>Z)t0@NBW{7daRe#z1vjk!5N@0!{pDB9KZ|+4?f%hL?Y-kE}Pd-M@0aRMtd@ zI8|nRejQY_Y5Ke9W|{#36LT$QLW|QD@<|oqiIFug*=>Cn*#_kNi7DQW!(<B-uJTim zFU-dtXJ55Mhh5{JTsyW+k66hT@XMP|RWf8QHS=V-;JyBtItM|C9_)c$N*Q|Y?__6- z8m@gl=@BI+W}3~D1ui7Px~6$B-cEGzD5*aOl!wq#^<w@H4&IG$>8h4Z4JcV(f3ahj zb3XCu^5aCaTGZHeim{kojJSGSFAVyxhreWN>LY|}cpS9l--iWrkQ7BT*>IO5aV8wS zNam8-I@MKEM*+$N<6X#ifzdXgnvIis?z%6O0$9>&wKctOc_=vRmBKX+(UnrVU6~f( zD+WIjn|f(_RdvMV8)#GW_O`F_si||SWKjpu?27ZR8bht2+z;1MQXH5U1;wcMnL|RD z5C<d^Q2B3#s>c5N6D4T*-u=wb=|-XCqTYS`ijgE5N&?ddQ|>rZdj0r7V91{7oZhTa zRV{qXD%-+Y7gsm}AdbP@&K_y~*q_Kx>DA{eVYPdY*Zf7du1|)LH1k5uxVRiumexLV z)h530k(LLb7)bnC`z+Ywf@XxDoVzgi%I$d%0fQJx!MBQF?-8_~9Pra#n@6V)wDq=b z$#a#BiHC9dY@xMxU)r&AR>kG_<bGDU@tHfEAW-57TjIqd`xWz0ldr>&=@Qy)>F)t5 zp9SO{<b9n%+RKV$Sj&=-!IsB+qa8AAIR|fZXO``)#~u0eeXttqBm+i>BbchD9!|f( z0{6icFBO4=w`v+01tVkcCK&0MSI(t<89`Bwp7tx9f0HQV@6{C<Ns(HnlHE#LkKL^? zR1f4Gj~5-(N79p&%tJ+vgzS_UR!xHcOQ8RI9Pt8F{HyN-Wl_p~iU9dY-Do$R1VGqf z6Wuq)ZvG|%9SVZ5TyyV22FCo(umZp5MKq=zURRp(2%RxF3d2FN_qV2U_U4~zyuZ$T zt@%VG`=5!=gPO*6rUsbWhfuqFDjxLxkM)*T1-Up+h)gptgN|0f4u2-n!luKX06#R} zJUA55`nSfSG&T9aYHlNY5n)<I{VDXx<!)eL4@zK&6`wn2td@hW2=lQi`19!IJMm!t zsVJLVPEVKsn6#iO{E1&8pD|(@{drr30?G8jOx#HFL6M0A{5Brh7-?_xA!(a`h$_pW zL{r3RIiT?Imkyuj6RiUm)~0_V;P;{peJM6L;jJiD_j=3?aXFksl(wI=n3e>U>qg2I zNcw~IHHWhXsf_S8`QRw#yU?z+=S6Ickt5D7P9lTP(zu1SI%AbB{JHclP&COw?GB-D zSmpW>6=U`H?bfqQpZ&TK-0HR@q;d@*ES}h?w1E#m)yW8#aVBIs^1^EF7t{~f4*UpP z{PC;E1mU09;U%vlwWRe`&(P)IGe7P=ve`tbkm{8am#YYE*&{vag`ZL6$Gf<H1Hv-V zX5IBx$}f!$^n4~$BBQVbhSSSB;os!y9rNXW<}1?xG|TmN-m!Nxi~tRO(5LTA5d#0* z(aOD{C)rVS{DH)uJJoZ|U$j!861}uJPye14E}l9qhL}h-+m;K8r0PYsny8smS@*=O z|5}=N(rTAuF0pHeugA`8IR}|<cor*pl!@sc@1=!WMk7v3!8#YHhi7r<!fST5M)@~i zr@zN6oNKfR&o8Df*r!BIyO4Vfn7ECL9_pk5RYs^(Xh`TjNRPvc9_e{hfnc*@-(CWD zRvY^Hcjw!`Z=g>2Cr_~=57M~q!Ra)6H~p~4J;wW8H~zqJzl%9EUpo6fOWuxszLojh z5Xn;{Sg74=#cl)C28=`aDZL)gxRD80HB@Z=aL(?@8M4GIv-lv~VrOT`z&0Y4ER^Ms z_T#RuZfKN8|C<#wBa8Aspm0=D6N)`oKWn@q-|iiMw%{PMW2tQmxB3eDTYk?{EtzbY zja(X6X+Sgb2^kSrZr^#L184ikx~gA<MYaL0uA()FY2K5(*C7bA7Asv@dg+x!>V5Q> zZJ9nn7`YA<vPse##6H9c8F`n=d6v3Cxivztf=5Y0vt(~uZf)mr=ohevRqu>Fhsylq z&M4XAJEN{;H!NoevcXs+)yL)Psn>>%oczQt4q9y)$q_9{jq)@?Iuh5>kq^c^bes~W zOS5mlzRMP>22nh2CGx>;f>!s^OqjaiC+MA=LZ$;cjfZGmRxGIU`7RY1?M9aKC%Zyk zWaBtxAxS)ixzG~#ob?`oMMpkA&}i&5^c-u-gp=eq9p*LFSnoN+ncloi%u=J#`ff2! zdIna-Jve`+HjNf;!7{z%H3=NkBh4R(nI{V3tkiN3?u^+sCV!3wonW#}RJ+s-OAP@m zNDwCyFm7G|vtl39A1QWQ!e^6u)b!o93vBm1QeE$$<wvMADj4QmKo4W5VJqlYG!xCp zg7qboa+D}TbfwKaUfmC?v3_HqIPZ~QZ_?JdRUx(3I*=HcW4!gLKCoMp=%)KD*FcgD z$w;Y`lKo1%|Mkz-3wPJz4|hIYF`cNk<u%yK(qQZsCiST2OuoI^+gXt2+-g*0DXLDS zQVZ<)?siplv_QdZI%h;oDdIW)w}EaHOQPbG+7gvYAo^j4+cn|77QwHYy7^HWhUMf` zJtA7ljrq1u@A-L#NG`BLfh)Cx;h+19tL>Y9{>gqmn@(ys;$m$V18)O$a6EluaA>zy zEKo=PVM6ECpgQ~i6a}0AE$C^F?-S?>Tp*bMj@3lbyQ|pie))V&8R5IRIN3#j@m#ZD zs@e+L=f*0ebfcwjN<G{uC8D>Uh*nZDJA>q8&@ixtUf0dt7)^lIEeO<Yjp^0A;QmLE zFyv&Zy1{+myy$5TO8hR~HzVN;O>5{(SNY7AZO>Ytz_5}JRJ-?OjtW~t{14lhAMWU# zde6hjv)rSAnK|s~cufIAf9=?OPk-oyqB$-bv6v}5>4q{Ko(Ag9V{{?Xk|lj;B~fE| zmi8sITOm<HHs_mS@7{zd2fQ>c+*4QD@O#=#MAmY3Rx)~wUr23Dr-YzSdPslzB{6|P zf|J@^oFg#JlP)bo-rlRmUn2kc`05@*79+hOaqxC+kEW&Bxjjg0AE+HDKoe)jko#Dz z105MnS4#EWe&=hxBPb($TF=HHKC|bGDX6Vb_|DMOBv<|8yul<*OoMGstviKEZN<uc z_j71khEi`vd)tP=x{UEVq44%h{jH&YvGZR{f3!0vZ)3(_SI|naS!%rH(j}tL#jXAw zjoeoC61gITTj$f6ako?gWv%z9V7gbCtZT!J$~CtQwS{zAR>zWib`xd|a%S~%xWr6z zj<mgAsTmH_uCc_edb7>m_y?4*Oll$n1?gWTwvZdFZkRjDa%?y#bzvLdxm3qUb6<w0 zxy|Cu;9OZdHnBfMORWz+@t%ohe)RO?x#6iK30(DfY!rJ-SGGqbq33zpLv-Nav)jT% z$&K!?z6TNY`B{U1`x<swdys)_U(`TaWM-sIqDr7cp-nAXcB^+s-1Uf3)pMr@R`ZN5 zLTnZ}sKz*VteyW+7}U>KC_mD5YQvpWb!o_CHA>3HQ5$)2b4`Y`oy|-6Yl>^z=k2ov z7(s%ioUz^)H3iaax;a=R^7Ap%(26vqOG(mMD5!|^RSyc}%I}GnlR<l%u_aCB6)^SZ zI>+67b#ZU^*`Ndd1g(6Ix>q;$J89vBwER6kz$kWD@97NTH@4YbKEE5HdqOR+bS2;M zmCgCHPgX#|J6R`<<ke!}a$V7WL_=mlw=PB;DA9}N+ipeNJam?F=#VMcxbk@)4E)!F z&^M4(<1-rJQEcf#MgfZ+5L<2sXM_g1?A$&)N6Qnb%;*i@RZ;xn^S`Nu0DHe=g&E)| z+y>od*<@N${5g>NhdCDWh;9>?{jCS$CA`=CgDHvNb1aqMBdZJX@4Itr?6%{;LUAkm zEv{-Jy)rJgkD0@!$3IibXld^J^s)BCAfCC<f)k>%yC0rW;3oGDAPJ+CR#6@GWn0J) z?*TNXBMQR4d>Mgo-0z;Isj^k6Do+Dyw4jCE@{qi@5iAZGZ-918Kd!ohGDXYurqP@z z!@^j)<L~p(sbT~N@x5#9f~OdlHX3#vG{-AikpPV7nmbd&I4}QlLC&15^td#QsRVP> z&kvj%0M#LT9F+Q(^c(`Qz!D`4y6IX@8(Gva%~hD9Xgfdf)p0BnAQp6Bl2Y{OO=k}X z4T`4GS1=S$22B_ueRS;&zyrI2?=9YckWhW45D#JzJ>o&`y)x<@6SBGVS-7r5!rq&| z&Pfk<f~Pk`JM%7&Uk%z#HI)#MT^ka|C3_?ZPk&YW_3dvV=V$4c^j`varh5N7H52ph zc~u16>Z^TWiPaR9#@pUOA-Rzx;IY)KY=msqbdRom5+=RDS%1Ce^Xl+1m;Fx^Ahv4s z%&)5m-Tq|;6Do(+_ts69UWj-zvHei}ysMG9U?^pI>ZY8!JGJ%Q9kc?6?j>A)Md%^p zPyLpM4<H=IwnL%sycY5X3E@LqqW(Jv^VZpvw2c;ykG$K`Cf^NgWVDHBu_fi-LC4SD z^?Vr2^K=arenc1NSj+5W=GMtzupbKW4l&9BR?z@lT$(1M#pu;x!uaIPMKfIh`VO5L zy9eESkfp}_^N*RzKQwPBRc6$e9$x+UU4MG?J9Rbv7bdeqP(3C)Gl*MPo6)!fbN}9` zaz?Ac(u68x!8`9(Uuez?MwRo}&jrk{RbY`DSN_vZSkzNM-Ql0$wFb@Epg9Pp`@D2{ z?tEQw!~_xb`20%b&g8V5%pG*?m_Ale1xx3sgtC0Z%3u(Z6`ohaf8(mJvUV-yk}=kX z%nV#|)KC@jswc|!oCdxK0k)LS(Ak+$m=EoGCnv09=FnOFtt_v@?+8S)kM-!qb_-3T zD@slba)3HTJwi{r{nIS-BO~j0%|pG~t`$#1O?&QI@eg{u%D9ZvOfR}J>`+ajX2YX# z*B1Uu7(R?zIJWnLow2ondURKMlCI;hfn#3^4Q$cOMiX?}k}9o3B^pY-yFY~{p;P>Q z;p7C>n%VMd*kv1n-T`#OkAVN3&l(k->Fqs^w>{NStMC-Txs}tbT2=(1u+)X_H^wzv zybo<qy?f#5!j|3AzupYf<B&pbh$!<X6j|Goq8B;U-u+XR<r{zcZfs7_1#9(sdCaQd zdbB30jh1r6ow1mh37;uNme-V%qSq(dD^|RTJ^7#hpaJ7Z=Xd@2e-I`|9|!(ABDuJE zI5f03mkg`t-mvYsZd#c2nzzp+u1lKDiLLZDp|Zm+S9x^gzSjKO`!gz~+k5R&z0~N~ z&)kN@1s`8|V%NUL@mnqbLEK3o@I0&9>|7%X=@zbmd1t_R;=8N(`cNbJZhgY<y=2N; zif*<BGM2>3+y6#dU<7T<wuD{>XC@%3PxyE^aE%|sn=Rem5A>#lFzNhWw_dI?T*=MM z9oIc!Ag#Pd9hqlu^!Og57i<m7sRB--|H?)hEzsyzBXBDWabIaKs?O1>DqS6wbJUAK z$Bp9-FSq64aPoC?v>PSv+anqwxqq+muQmKXG&X!OqLH|6fP2>V4HgKjL>_#@ZYwO` zyd0La#ie1RILkiwfP!#^e%XxD{;lJk8b@ekLXs8^J21m()S#w)R3XdIk>(in-m>lE z>!=i@rG0^FDW>;Jl)c1CqRvx+f}d>*5&o4)Sd+dP@hK#^{p1u-z4KE6yJ}{7m0H5B z@Q?GKNZ&td?!5Zv_y1hc?*i<ximS9uz;$CUr~|L9r?~;*naO;HgE?L%*)UWJC~e}Y zMkJ-`>fdTPeZ5?H)$Sj2)&g%IRBgXo>u0)zFz#I>`b%U9^gh%<mvBUWUTg^?vkMt% z7Wg~V+cpI)VJ0ZgJCk@{OYaoVJkgV`xybzCKU3ZjpTBnkG|6&v%ysegIXbp}em#24 zyyQBsqxAJ2JX^f|*2D|Fz@>Tjzv<&5WULsl<I$kml2)pYpwIF~t<B~*SS}v7Wxeq9 z4zR2HVM$S|(Ipw`_u8L;nzq<C3~CpDf~((qFN}mL{}I>-xl5)FETPSQ(gvXLiwG?{ z3+P6CDl9yICKwfc*d<Wy^ePVVA)e;(+VERl9lPI@?S;Q@Q=C79^#rW_fO*ai`a;9D zORYuE_@DSbkIzEja;%rhCPE{Op2QD_$Q^~A8Qw!*0nA2@Y{G=*kQIuv$!~)>aCsQ7 zkxT0K$?~~Lxo(O&KvM5%x?e>7EW^(prgnB~=Q9aa?)ZT@qx{dRU%X*QV~}@R6bJGH zQ~9gm(x?(Ti+r{3zSUEV<;^ldEr}+Qq51rqH81lT4#m3dWH3*IPxy8PaP7?jvQh2Z z0s7(>`#wSn98U%W?v@}oVC^75y867q=;3s2<Y@Vm(C$;&3F40I8?~3b_rWkj@r8b2 zPL0q0t=+w+c&1xKFV2byl?>T|i9JxQVrWe0Pr)e9YYhsTS6^C+m$WoV6uXYB8_)Hy zvR``=IWHxa@T~FomU+;kV&${Qv2(mjeU0~&;I*Pt2`kYjFV!8jecxYsN+xL-^GA<% z{kdZBlY+tsMIRulGDA6O8f8o<r3QB9TxEZ5>UVDYe3V^&w<#1SS(?Nfv#aRu*syao zdID?r56oc{#s7IB$!6Ic8XMHdJevcJ*@QV?z`;-YNp&sdtZ(;ynVmuDS7o!>>#CpM zbI7W#3j2e|sy--VH+lM0e}BVL1=Vf`mFSuLR94OMLs}!gS@E`5(0t?K%~;<<-&>gN zL4#DWgRSAGNwz}ME1gB~4H$T|{0HpDY>mleEZAxghO>29gN3y3Z#;=4l?wC6c2sCs zzqj>;I0(N*feLR)U2EMaZ#(tP`#gQHUD+Qc?ah9Fx%41h#OT~N>t=%tzpC&1?ds># zA1N*PKVS7v2LwYJX1;jbH$NLNdzOAC;g-_NS$+M-R3*QZ>Q999i-;sPfj7@e-##MR z3YKj?iLY@f=kVNCWHxOf!_JGq{l>SYrgRuX)4kjP{oqH9hA)L!{SC^vjoM-rWu#f2 zm~_v&mogNig}w}$NI<rja5O$i{0-Ot<=<|9IYJC6bR9uokQvmb%OhB)Z(3sJQQb2^ z>=CS{pi7YFKdCZS>f(`|npv(2zHGn2?tz*zWLGh~$%R?!Yh)pHBkXgEsQ4!nrTM0J z*o2DYn_6j7pLvP=o*9};Ato9tMJ#tlL|qgvVPy@@Ih{6G`p-4^f!M-#)EB*Y`*Mm0 z1Jg#KnvECqfuBc-_+YlK5tja!27${O&q_R^fmsraHDteY#qY?o<|u%XHTEqUXZxO> zR26xK-&vvCtgwv}6Akfe7TpRPu+bBsN~^J63a$paR0M2H5w$2c8o%@DbODw+#ZoLM zFD|#V%4-|>THObzHzX>ey%L`1SA)(rtsOI)z+~whqaWPi7}T3pWO^Po>e;gHN@QGx zU)YibR`-li@D%z>&l#1^VCHxM<e8W$hq^sYpC+*-s1k%>;G+TAfYTQvGeGDO0UT?J z%)W5wfo0t-MgQ|d>mN_K@B)WKITN$P+N#4Uq*Hx&Cm5XWTywq@c-1JvYkYo5`64$D z@jBrr*>^~5wKQuR?(9mBZp{W?U5YY!x7a1F+rRttcEd{K0g9P1%}{DDYEHMei~ZhY zzMQA9lW^F9Tt<I>mT@_lBL1%J5iJ2K`ep!5o%={e+{VQj2SzS8<0JDcwZ$eyz12%t zqLHo74VGREZeQMJxp7xc^o<0z_nBhm^J`-rzF6kw6*Qg%`hA2hk-R0j<2%q$)Kzhp z=wl`|l^)@DFL`f#Ierq)DFZVTurr1h&%~u>*B{S+(rZM#Et&5T+x*1cvXh${vE`k; zvYx71z{Ysj-s|~qm64D-pyQjLGjHtKoI{SeAO@oJ!ikClUCWac(4hHfr@p1BQ$L%c zdEQ!HTItF?h+)>!8*WvIlu4Bp+hZ+*is*kuU=30t%f&QWs3F<!!L94$zsD^Pb^l@| zN;E2mYKyE&zW2epQLJ~xL*G(T4eQebmN?`qO3F@w3cV<mSpCO0Z6~D_Y<UWvt(S8y z0AA=VuYJL_4ZE!ugqk+q&$Mf(=nQ`|RM0}s_LlXMP(e2pCOhX$U#xMK{5955@Ln*w zN6q?+U|}|r;c%Y23%g37H9BO&SPpp!&A3x<@t<|mgk|FnNcd724VElUwJwo=v_UC< zHt45#32kpY{}4RDtBoVoGz-S^yTt!Es2+=SEcWLPcZt|hc%0MoCoK`$rHz|6XGk2l zu<a<5D>hF>0m_=$mp>&tsP9cg&!=XS`Sq%Z^>WP}DVEqb<g5qz!qCON%$m`11a1rn z4IuQ#pEj}b-QX7Tb$R+Q;<4ZkNd&gSs-STZ^YdT?3!B#GM5@%nXHLB2Ye;AfR-xb& z#%lTB&e$v511wD6&qk#^bM9>S>~lUyQQVuSouFkO%!zucbE2l9b}^ChXXhlX<P<2I zbz9&lHP-3FhkJ6MgU}SnfZEY-8>f{g+4n?yV$9$D)cZJG74KZm8FMZ--4;-#@-a>F z9f-NVaE&<>@~!<yMY;VKXJO+64fK=*6cZoz_>!4US?MKE>j`HmHdwWbX3>-2++8*? zyqyxsVHR-irZ(%LgPY$5f5$;<A{*z+<-Z|cQaM==ZT^N<SqA+^`)1}ieWi-BV1LNs zyD`<c^MmCPoH<kS^^!(vs&-aolS#}ozQ8C0Hc0gDQ~I^h@6wA_>(MOgV@1Z14R6p( z3$txKimlCTn}Pe~S;5UChjoDiFmu}(%|o`VSa*CN=IywzihZ`FZ8;qkEA(!xXnFc8 z5AJ{ZId5pPgm#B-39UnV5xl#ogI8+MN}*%;zOE%1S*9qt4SQZnCu%a)=yeGtZZ`C> zqfh#)W;pF^MeexzHykwFaOZ6+`8FvL?%iubNjE2Z_xkPtxI1W%b1I$px*SUG=;D~g zqwvs_j5>pgbKTy>td}>DW1>q`uj;(cw<{FQy9M{CIFG54+>^u#ufPh&AJeiT&AWX+ zc!^aFpR=OBPy;;oRydTHMd3cIfSeVa2m{lqj$|X{c!fhdkcg~Ug;TLEW1*ZOTjx}s z8${?<sr6C_vcIckkC0bmZk!GRdDH+MK<m9B>(f9Hl{MxN!vV~lZ@h-a3Dn#>a6kjr zcaJQ1K!quhG2TG43pR<YltOX!e6cyE2}GvaI!AkP>AX?F#ZvaAQgPR$y`2pAUKaY9 z+u}v?p!dLsy;(t`FYknJY7C+zDT5xI<IIe=H|>_Jg&=fA&|j|Yo~+h6bQ?*qI8T@9 ztONUWx-%-Wk|{6R^XGP#uVt+e?RZ^T{jXzBCR}NybP~c9B5WrEv-|{8@#}M|KOCDh z-!Lyy>t^3a)CA^icp41GFb$U^GKFs+X_m?GuL*=0Zww(G`wWD~G%5~x2&7m%c`BaD zP7Nch34~3C!3_j1P#m+U=Nq+FLtA=P9)h~*qTl=eUQlIDe}ih^TrNu47fS_NX(3Jf zrNpvi>4~3`9(SwOU7^(F7pRZy$@h7UTE%PRNr`mbR8XNoZK$Ul{mY6Is=Ter<n=^Y zDmlqq`jFS?$}a?LBgcaxn;F8J@hT|I9hziTMJoh(*w|7QT_|JPhI+C!tdvDP96qS0 zZSdF`4D+|(>`Q$8e9~o*3RYC(SNQNw&ALx)zma`^Q+m(kaexhtq06X6E<9jy2*3w~ z`gSey48ax``h0~=s-;qBwsf0V!Bzelp=eB)&+c7H;!Nx&uOPY(fKOQm=PyvX%<C`> zL;vX{J#*=Nh*-h}6+3OIpdibi@PUepuE~`|*jDLd%N_pujW*7trd|Z}l7dcG)kQRy z{DgpsQ$1Pkf~wh8LFt8CspcaxYNAG9ZC%DCWSx`R=~dfEe-k!N1kAotMIDmQZpr`r zQ;<)&T0K~la$``t_w(bR?u(qT16EIo4?}MAqP+L2NuC+*KAsXI9!noQB%Eb5TmnUo zWMS(B4ns)=gEINEQl?bI6mp9M!T&r!yuRW+JAzGuXRz-C+Ea6=s=WMZ`Q06-6eI4X zaV*Tb5(M?>#zQto_h|Ci8TF@WWY0|djFVF@;DBx_WtWH3=4As&6q|eXtk9~aKLP_; z6}Yvn{5Z{2sU=O*-sZ}I;1JdP649PF>{eVJDfQQngd}8OGv~Yqw6*>{GU@6$ilZTM zBn4<vI%)kp1XdxAEVq;Wi_1AdISe8Aw7T<bAXxA8pO=$OqI+9Ah%QMF7T%x|#?^`o z4{plrir^WwR0{UrF=$$nF~$3v_xf$58kre{Vr?ts%q*)SmPG{Z>OjWD-czeb)I)D> zsA^7|HhS?S8FKtg(!DklLEp9SBlTGF5z_^gW*MW<@i(5E%92lLmJUkUkI8~%AcwCu z_Q7^y{S}CxqWXtvWgqNKE0tu9eOXqRo0SR>%(TS1u7niTYgvi(rn1<a8DWShfW4wF zWk*xggN5BlD5p$lF_(Vzo6pmk7v`hB?xP$frF=n*0wahh>P&?opSB9T@Gqmm2`>Tr zW<Iz<G4Gn8>6$7vU3!i|b@;fGPiW>IXVe9`FG})W^BtIU=`(u;v&E315@A4@H-JK} zk1#C|uVa$_c&GlDZ1{uQn+K=6LPni<Y2NxR<}F%Yq91yeraS!$R#r;4*ChaHvN|bE zRLWvgpMa}Kkw_lU=U^#WQJ5|j%ZaDZ*~AOAU9}D1jUda7<sMi}7c+@0JQz$hDX-%% z;Y)0h-U5ETpc06(;m&xgBMB4=1o5YOZ>oVbo;j%~OumcDSr_VFck`|T%~?(C2sWTN zHu{AF9n9!GP2M4(9}sL4ed08Y$%W{kCszRLgI0@2n$!t`i*&=R>fTM=C@aZi_qTO1 zW8KswvOdiXw(g1pGUqV~%1`@y2x|`S&*zl)Ws-!IBvgu;MnZ8yJ&E}geg}obU>Rzz zVGtE}N1dYiCbO|^F=P#9m>(e6QXLkM+(e%B&LXCSC`B;T($^^leHROR<wQg&#RbdA zHbGgtICMV+wS0s1GQ_%bDVBM<LCV<os4R{j54LSS&@Y9BZF&Xt=rNRWHX@dfB@=G2 zofub&N{^YHcFVE0iM&aDPD?K|J*4jiHYz+Muy4XFr60(1mM&4VpSw3J4PsR8xBv;^ zvl1?&9xR$3Z)pcgo9E+pIJ_`ZkrmtJ^ake%FQL6%KTMf~8K^jt#{6Z%<`P~xYLi*^ z$O0Xna`z+*mBIwfua$W6iOYrxh*NQN45jl16nO>JoxIV;l|P_RuZXMgG5qZNJ0>Z> zO#M~7(H#hX@pM2aWFjV@2ilC_BlNhg6h&>JV-vo&+)OK5ViaE;6`Cb6ZYBz~ESN0X zObKuB?opx4#cro1(oyT%dj3&JL0{~7xWIl~bjVe~o7Q`&cy|Cov}H^JKmnqAd{upr z$Ub7ihz(f^Q`tXP8-vGgMD%(Htk|r$D!^3o|7%H$L1jq?GI4`SIZyAL$2o~m1GsnL z!sm&3*J#zP3<MP%Z!aoXkj4dDibV(_yq~wCLx}cgvw~TB>K_%JNh#{2c-<294y6T3 zt(OYvCi*HX467*UK!PfF<nR43B=8s~d#Wd}19iz{EM<Sq2Yn^BAVyW1t>SIh+X`VF zl^zb(Qupu4+UCp~3FL&Ji3+N}rHP)ApU8^YRh$$Lm1h}TRR2{y$WoDwsSb#trl8rx zsft!KZqqBPA0T+kSgkCLT2ERe=R9(epYgrDt^2@<<!P&4D(Lhle)rdpnnE4hSG(1! z>6Sgj;j1Ca_eC}k&~5}BBneT`AHIczt(28giqMyhv(<zdWmx$^8Gpln(nmWmO%(G= zqIF>Qys1j^t%K+OE_D-LB8E8V^E3k!#kUw`kxFx4?f}z1_K&R|%!EW1{CeKQZJ1%P zUgAPqw5)K@!{U1jY47+LWIaQ4-=N#O13CtHD9SmWw+|%`j&za`uszwgAG;q{bh%aZ zzLkP1wvg3}vg!qq2vfTKn}6O}NBn}<@Ph&wJ2@5T20kkd2yG;3{VXJ>&*)PpPt%{l zxT)Cf9(T`O(a-i^T1lKtKX$)6EP^<ijYTLcT>JPIr7!02(D&}A9fZiWJh~fD6pffe z4n6;%^<!Iafe&-aM8^*(AdEyM<o^RFgT86A**_QfqQB=A5O<!^msQ9#zB0ZzkAtl{ zX0JOv{TcwEyKKW6Jnuc-;zt`ZSHVWu<!Fc+gVq=42v%B;yUo|x@BU#qZRSuCDSbAo z9cw6VL<=SE%|`bMtduf^cfy}*ite%KQat>^P7T6;M~72NxbS@QvhC4m>*ErOPm3W) z%oLCJJniEfV5~Y(k6u7Lkz@MyEJ-J#MXh!Mr<3k24fVX`9}r`-he@jScfAXX>AV^H z>hBmWXF}oWMBw(wTXAATKMU5R%7}Buae%4-H<YNql{oXtGxYT%Up9_Lhmi_{hjeva zDBTWiB^q|>%QhzM3$=bIBYK_U!3y_i4$3ZUpZO8C#cX%rkYG`q`>^gp8R2}^m$kL- zRpVomXSl^>6qPLCPQ^wfx7TVb?scY1_rcsM@XBS6?fV;d{tVfrjJyiqJM#0K<8c*= zfL-~|b)?aMReUg6WpjW-L5&_r$-TJAxCJv65>8Q&?)?wiAO70dBK9zG5CxWH_z1r! zztY6MUTXlQVHC2I_T7Bnt!-Ch6g>;#%U`AvFm#;<U5!cK+!!pqxsbFA7J}t>G3!=G zT@wS8&HFNqkY#`{ecL7meEx!dfbXvUBM@Q<A~u_d_9#XZG6niQIEt7po-(@bQF)5Z z{*?QOUM9apvgd02vI8toJt4sC2OWDtg_cp_t<rDdsY1Fn_kKD5mG{>#aW8O9y$o66 zItD<GC4N!m9UPZ2Qk6YbkK3c~W?&`2yOS9OG-Dx(W$0wueexlX`}G8k&I=kzrz{Ut z#>M%a|01eg%rcI5GCL@kgRd~>6Y3&m2}R#-EbXnrCGlPBS2^5ld9hBfa;l^E6lgIE zhXkuMoBdPILu)tdn!UDvPbvmqIQ|d5?mL?8H-7kkkY!}pn;5OVYVV+CYn7r_jheM< zQ(~)8F^kfwQIxhZYqqgBF^ZyUl<G&dLCqp}zQ6N3=f3~B?|<`0PEK;pJMZ^(U9aaO zT(`PdewpD_XY}jiC$sZ^YP*|)9~FoXXL5FhzFyjTYmHbp4kR5HoePE7&vj(5Zot;y z0-e!IG^;)t%1t+uRB3~%e(ZfK*Zs3IJ!_9$?TRj4x;RwG;#-I~IFO*}pL*WaT)aE8 zdE%cb8GE?XqNbsUZi_We<=Y-@yQUmOa$gtGf9hyi+uf<UeRgAA(<!vIofcpt*i~?? zo8`{mKc%`;L)JH*H|>>b7L2g_pRmvJz5piMoBvr%NEJE*Nq>ti(N!d|YIKjsWhvP+ z|INLf+rLm27SfV9tNEqyPL{&b#b$O&rbxf>gR)<)PZfTCd0?VWs?QzQym5S3mZtJ5 zJU8<n<{(Q|{XF&iz2*Ewq`W0Y_Nf=o#-mZ5jh)wyTFpg|?EE^f6)}2}05^socFJ!} zWqbpoK{BPzp(Xm4aug;?M?MgD_hs&Z3GQy61bYAfu35r0a2NYojwXDG>oF%qDUMF7 z670F$xH*BBy3A>tQ<{udO~w{5j%JInZ8jsmJCeEsFlFt)CFd6i8Fq})%6E$qjX&S> zv+5c0f%TdzsJ{r|n9@QQjWhfqLUjbsXoBlGPct(dEw6zoMz{2l5Q-b$bNO55X43d^ z#Nj@Kj4==}=`S1#d8%w|ro-7lvU!fsyukGJD-y?Lr#dO1C4y<f2TiZJut3z5ADi-B zM953>RXG&6kmRDi)z1kP+)i{SHgD(&2H{w`83E#<K=h;*I7OAHsSm;rDl8H>@G++s zt_TgnTJ^Uv)?LdRxUF*w6OES}OtNX?jz<V33e4_w_w9|0z%*iE(*!SmZ8nc^d_e`{ zT-@=X9~Te++Bhyp_Wxai?$0x7AH0=?DXuRvvSuEgGLCB;r@ER1=|5dD)m*{nkKedW zD;kzlqI)!@xLqGNs=0YPg+pyNj*&}LT-KXl{3&jhbW>^lrp5<#07=J~kt8>M_ZEya zyY#T(2)w9-Q*<`bU=12Nze#F&P|Z(-)iv!4o+TI?y^^Fs7+mJL!ufF}64pORGB&fC z6FBoJg-fNoIe$__Q?iuT%!8F|kL`~qHB)bs&+hJWr<f^sKahi$o+X5T+@Ncv#0Vs& z>TnH=<!Ci$XVLfcaYxW+C=X{NT)$QZRHkzUv5+N!JeR-?HvL+TomYF!iM$j7dYt%a z+`QLo!GoHVj&k?n7lrS*8fI5A=I0qOaZjl~0~TF84-p0cN*>(4Ss$?n=#5MfsnmAX zF#w^Se~pWB3*=c`ZOAl4@oSh+WGi3n!+l6N3JzsEOMjdVJ?_aLxRCP8*TjYrWqi4J z>Y1azU%X!Qc>nzeJ^GPm3J`bXZ;{9LoR7_d>mJ}L47O2R<Pb=Ee`zXrN?^)caZdr) zd{-_mxs_{=LFLipmAlu4-|^?}1BzEe!H0N#&Ks=cx=4x=2?b_8&hMKk+T<iHQe7(t zGpwQ|O#z&cPrZCupPBsb8a$v>TBVTQiQZBAu$#!WO7Xm7;6PPf#!OxMRq6#Z1NlBk zpCf7?g8upIsppCwKWSc#=nRhe_Z-1SYfc;V{kFv!RA1w7VOHto=5;bJ{06`d@Cz?T zo_)D*i&uiUi9gizcI8&1lV$Y_79|y^8?J1uI;Z*E%#2G@&6bxl&*};mjS*<dP+r+b zgxuEAm*cL^schtq`95B}mTJQ)YmpOyP2hNVs+ZTyNVcYCd3E!dkPeDj;ct7451eYW zUa$>(*?X;-NnNfM`6W5*CZnlUG*)*nE_?s(j^mj9aMFd=ZG}@8NqfE#&1h$cf2!Qe z(%tb}D~3<C1L89z_zab{*Jz6#zpu7fpD=ATm%U^b3>;UnG&Z`S5Xe`3?az!JK+ZW6 zk9RA%wwLncik{BxK~mNG(&Xz5Tg*JAjjxFYE0kv&aGEqZUHzk46QzWb_{3y}IJO}r z^qrNL#}9Z`Ylb*9_7PR9{TU9Vfs*Y}b3~)d3{Pk|kOxcch@VT4#zOl``)k=b<EVJT z%Wi7t*y)ZMNs3lzGp8)EDh6@%dy#N?`hZ9J?#AWFjZ-}hXeWP}o?F~e2~Y?qicdB9 z%YFXk_nXx`c3GBw_oBx`#wN!In{f(DvDzmqKr6$rzXRO)zwU}BB=OsAZE{o@%+>P0 zfw6zsRC8>9#(ck3DeC(hu@5&219!FSoQejyYAOabflJL#XOfa%ed!aCOr1(-!BSJ4 zf|Wy)wIkLlx-D5!v?-`M&~&}LsNKoVHF~!DR=*u=-AkJ@l4~jd&?k&GHt3X#7cfm} zaTUdjrQM|yjf&WrqWVWoQd}g^Rm=f1a7du?-wJWB7IRtQJ675_`fhh7!MWZXYVkK8 z#)cz4hf!Z7--_<YKLbs1mZf_7HGO`1lc>`sz%A4&Dxf_|w>#2df4A>K3wC{u>Q?TJ zR4=vO#9uRgbsy4?n?H*?w!ckgd&o9qKWdJ|778f!OAo1az4=y)t>C!}M+Yw2cB%K= z<kDOo{7;RJp8Ewo?*xuYZg|}j7gEJ#bkCpWT32Q58P%)=9IvT9eWUb=?5bt0>1`&N zCxPM~cNg)H*VAwPPWI;Yt734tHF~;GU>R?Z>#_FudVVNI+lC*8c@oS6Uq5da#QM;` zJI-cqGg{iV=m`wfAqk|IoC*}{B;3Hga})3yhAY&+HrBYV(D|9o)^D_2@=-bcwHV=B zuAdlF)OLFQ`<<sQ_i{18W`8~CrapW+TH8a(jODAh;jZvIM}o(zlzVq|+ElGMZ8Rp8 zRHzcBN`-p{71VmY>$8j7PHSEstnry<*gL+LkPODq7Vx9a;BD7=Is<P7F_swJFz1ok zk-Kwi)Bh;qPw9Dz*0nDP+Oxj7+lsW)<_{46-Bi^8xSnZ7T93QF8}xS1+E6O?*KJZ< zXSaqoWqt=eji@R0R^EMz?8ycOj8@E)A0PG+KiBTu<KgR1Nga`FtOIW8W3KZ-UaK>N z8yv-inKQ7-QKvGH;8$}(6Bt;ro>vi{^ywYVKMfvw1&B_hX?c7YqBTe~NbY(LqACD( z?S{C?apV;;iiD-xU2{Fdv4|P4^CxIGmy5f)vK4N)OIbt@R?Ch#-xjwBk<GjQ*XlOb z3GqrM`phZx15>D$frPL&=W*Fh>p{dddYN(==#d#$-~uP4N$Ls%slgx|?s^srDQ0@e zI|gFjFk#|_!UZWJH)Ro?vwF69UgwqksVw6C%}yB#yduYt6#~YvCd{Ewy!*hKDM#*h zJfaY7?pYzC)}(Md2a#+J@7+q&NV1s4!P6L{PEm%(ga-->Jdx%!zmNjDtqH~+a(q2> zmRO`yJc*u=LKB7MrpmLtK*M~|u;W%$;eNzlB4P*)`UXz=9OAIV;{ADp@6ZYH{kj@U zPtrg|$`y`F_7!W<B9h3O5)2GKJwcRUO}-Th&M+u=Y|}mh@X%GNv7D&kZ+MHkczgAO z<K5)PZ<wD|$iAA7(+FZbN)Y&{uXrh}_`FJKiIPU~$X4ZpSo=WW+#Mv=l6_1Xrja5( z+>kcdbjtup9fbDiw6KnJu_9rC3;o(48Tc8R`k|RJpR(h^F|~Ltry?KXRUBmTE|=ry zWRF0`C2N>kpQdk%=C-!NBLW=-6NYn$k%b;kG=p-+s~hw2Zq%5l{^TX~2t8yHb=W5{ zClMklHuT}TDr~RxmNDuc-w~Ux?!TL~W}6jQw7BD3#RiVC4=W5MW>{n>wK|F7UwRco z&JtD1CB9*yLpe(9MU3jx(nkdFWZYxPpJuQ_cxI8qq$lEI0*!e4_03@4X*9@!>83(6 zcuB@hiK5WCk;8$Kb1BdNU!R$i9HVek__t}T3>W&cLr5+b@eQC5*H4{<)ePSeIM<6v z0?>ZL+=!sKcS2b}WOf<RVxW-L;EhZ78UfGt@H!?Ljr54ACEHOor(FkWN!{gNLc!Z} znE6{w2Hn`toCK6|5FSqoDL!aowAhN+<s0e!{xxgDT;c7ECd4(>Jg2azCeq8GL*=tI zhXQuvX+5{92<@pNj=vZ^V<N11z2vQ-Gf`S&EkL%ZojvJ$#8{uewQ0Io0F3TC0xNPW z1*F#<0NLM%C&hy%$}}eou^ANRD;VlRTx@C1)BjpETZ)7vUKwi5v$V-8E1$cl1o7_z zESAh*-;s3VI5Sa?M_$u+R*AH$IFZ9MBsfm)2%F=32jL)ZEN;a5H&E3GXkrOeIXsAd z=B)dg0)9&1@>pW{gGD3&sEGhL%GtHr@TD<@%H9Ct`d>%kIYv++f-zrMxsS&=(hzV% zW2@|iX&-p2jJHv{q-??KWvkc=4D`TByMp1>gu5179HP^Vhf9GJ$63y5R}qvLnIHY1 zxWs`{olP*-S==JGuH9OxHBGR+fOQl7;zmf7(;J@eI1WY&#J7L~wtK#{)7lm68O9A< zhj#?LjU)mJZn_0MzBj<tk4JdxRU5dd9+pY|Ezqf5;x<wiUYq6liz|`kV92B}@OlE` z-B;VxarTodVK`RfkYV(cL&TcVzNri(zTux{2QVIadHzK(wfRsFR%QgsjmBF@H7Z?V zBdrb}$a%u4g$+OS8tOKp*Y3o^{(9)LYQ0{AU)PSctjLrVmKbHwvBZQ9Gz4o#v7`=q ze=|c&$UO4-A=q^fA;GC!<qn52`kn!F4gl~o!u3-mr=Arl2I(2EQs@3KfR6Ph+&z{3 zvoOxYTJjPNXWWuf5s*DT@#tO<qe>*7#n<yY&f6eo{(_sVgu;hXTq1+Lwdo};tmU2$ zA=hf@VllArb?>t>X5|FFk9Sxsuk))HNOZTP{iPS2V4%wqB2VZTa`pT0&he87Mj!Qg zpVJ0HoZ-ExFW2zOPTIT@6e@OAZ1QL1pBLKEXAS8nl`E3mz0uOw2L3o)JTd6d5=Y~U zk-i{k)YS>WwY#a;O^<^E9y~7$lp~MglyJ3jh2r?4RBitawExa^3B~YRQ>aTQU=8o! zNO<~^4%oz6X1$7Lzc-6wVC8n1)+Sm>>t3{i8%aRqIU=cDsq7lQzD08}{@EVRQT@l; z3=ZbdQLZ^O!Zly0C90?!m`-5g;6BUlWxOSKM&8}FB1y|^mT`{k@<~uQZaO*m9r(>Y z$X~vtGWXAlRG7MqhlPH3Ij}%trg;cXkT+K9?~-eAmgqY&yjBghe~2R6P364XxUck| zxTYhHp5JqM6~J!$RH*mKDISqu`AG`=fMiBphBEwvl?cmj;Q7qFM1-3yA=YtzokPL% z=ON+5><w*RA{J3}&&(hZ(u6VAmN#jgbxX(gigA^Fr1UsN53dr#sp|Sx_+B@Rx={YJ zu#bb0%B=Gs70ImqUHP)0AwAhRk%mT6DSI#dKA-tFI|HX*(Gd--WjHav)|$gw<nA`C z1y6TrhWIzy@h-}ONUWpluUD7h_IMU;Gv9AUp=yalZwyJTA!9x%nRG<uHqF9F_@?RT zL3cjOGeY6UT2pfV2zO0iOZ%-A04z8$ue$5C3yu1_18=EFNC{1OV=vDUBekhvWG?Ga zu{jea6#-W;5YSSxp&^i;O|Jsd{ODLak_ubuxVlq@mgIUsUPxLw>F~`#=4aWRmYi5L z^be{piLy(y{8~Zuts`=37CW)nKhY4Znt+3Ph$6NKz|R<uZu`pPwU-mBs!Sbhzqkr0 z=O^87Hc<Dfqk3K{KXOUiCPgg+Xj7d==R6sNY@q}qVhbf3c@a>oAT3&eSSG@jnqp}y zOB;jG^H{|f{V=oXajJR!kp}}q;^Y+~n%~Iiu|fRZN*)x2?``P{sqXu?3YEv)!nOw& zgDRw;&c-lCcyK(Eb%tPdA97cSb&rl`P++O|LHQ#*Y`H9Ww$AHllR6fI;8+(r2<~fK z6xA&d8Ia|jc~ZUwpp{Wk=dqfk&vxBF+WS(pBft%Z?BYpQ$;86!p=YdroY<KDO33s@ z1xCs5=y1K72A86&9t9HIRCRH=zK3qNz2(0MB=Dc2=f9za)>j-Yb^BlZiZ-Q?zP)8R z<s-i&;cZj#)fY(ms$3ynCh!r<Y1>T^8+!!#Mm9lFOt1J$f)d=-*4@2a=M7v?%T5q7 zSc$#PtDq&nR?9!<&2OZ@?ynZzFkGLpaW_D1#aR5cMN>SzyhXnEqJ-_zyCTGRI)o+6 z|Jb1(yst8c1rjI`cFZxn5|SL7_I6e7dr1i0&+5ns$pbXpVFu=LLv635@0Y!3pd6V5 zp-aNRD7seZr-c_d0prB*CgZ2|vI?|`(NnCBURS+FL$F*7`7eNla6{ow-MdHY2*$^- zkpPQPj!jhQ!`AT^<~=+|Yw!^q?Z+QMUOlFp-QDFA3X}tMjjlI!ytiy~?sikI+Ct#Q z{XPM&NjXud;X%PNjMm$KE!zJM;J1<RNe*;)_hvxeNM=&3@HCyT-Lf~2e%=px3Ic6> z0E4H*4>F1gOXLebhS?zDm0<->pAu*kty{2kGDi|E^*_g7@6na?jpqp8VDMp)*sa?@ zAwICRgSjaLxcUWlbiXn<fT>Aq5G<fLoM$><8xdrMn7)qO8T}rz&me3J|0vipl~PeP zG562Hq`RF9lB!SjPmP3v$y-2^@U>9)DSC%!SkSdXma$^~M9PoC#2tLk^`AH7*Cb31 z1ES=GgQ_QI#MXa*%S^Ep|8_VO)>(tGrkWG>u)&ZpG~v>4;{duBu6GBM_&@6ST{w{t zZ9F=%f5fQzwa;*nN+(2r;&mm)zZH63smam1EHHg8;fT|iaekPV6C`wv7GnNO{yqB# z7pNA_rnGonuBwmFz$L0=*e<UYo^@({bN@CAK<&DS$)T0w(>_Lj<f*&@;Q-Nz1M}wA zH2<tkm*Qr7VEhmbdy(Kq{YPx>E+QP6>|2&7-?hVM%W&@E5>6l=b>JxTH|n13+3WT~ z{-)kHH*kwP|7MO`Mgo&DY!}(539FhLxRa7K6O!8dAMg4uc5N^5hN4G<kL7+(nEv*6 z6Ij6@CWEB5ocMmf7;)d9BRJOmh__lQF@Ah=V>X&ApcR~l2AOZx4<L{fKoVTghOnlU zaCDXbPv48GA@<<=mnH~;M>~UE=1y~=6mK^<5nXbAV$7uxbxNdfUYyywRminod*P9_ z@<}`Qs{2rp(QP!JBWaXLND`p<f|B&PS!nL3MU8oti{;tx()Y-;*6u?u^BN<Z^FZ?6 zNfxJKY|HJ2f2?@7#oEBF$tt^rpEhZizXE5i{@B(=MoXl@q(go5`Vz^*$|uIJ1jX$A zm+HJGON=^A@7^g9lDc0_**`qN=`s1xeJ<}ulBLo+p7tIma{)ber;v}{hN}~u9_)ws z{+<My%5a8N)u7nx-Lz{{jay%mdd_K`<X?J)GgbKi_&xWn)3>|J*_DfArK(r>v&rHe ztK^F2qn^2T*>r`+VHamd0>Oq2j$|ZjET!~8S3|wjDb8Z*S|*DctSM>rVI3^|q9}zY zovqXJQ@nV&!HcLXioK$!-y%a?@ah~9fWPElTsdrC)wqmCBG-e*vf%VPZ<wFTuol>k zf4C%o*z+W_%8G8SYfiXvsFB?w??y}OV6EA;XJxVm29V3zA7f$7Jwm*`^Jht=p{L|? zia{oFLxyFq^BzssIGrEd`gqz7W(w(IPkA49T5EP45^EoTiW)S}8=f?KMVTM_JG=U2 z0h?W#NxCG{4|bQf?3(K;75sm%DLYU$@OU4W{SU!QF~n>3^^U0(>HUp<{gNQ;xyN&D z=`$e(6?Ru~OPB6L$jcyT{@q&%E02!9czj*I&ij#a(WBUC=8Ha;Z~vKomDC}%lSlxw z=&`*^QqmD`7Ta$1%fRJ(kUXy?WpDECa$M;BlVR$zlDN~Y1<qyda|rYG1Jq!Ne}S#h z*IPrrVxOEL2L`VuMYUN4QdF<>9YWd@!d+5!*)4b;9rPqnTju5HulW!DtnCO`tvz$6 z1}%XZ6@qDm+-`k25`Ovgr>Lz<0$EjGOig(GZsXN}#IWld?$sZ~J_Qul*nL}SlevTp z9U_03nMMT;guPkUb2LM@Z*v5uUT^nK8RFLWej??Y{@*<fEfA6<zy$x{R^I2>So^4( z!^6IRM9*}%(Qd}C1o>p7Jk2DuGRmdu@9#EN)4VgPbnRlk6tTcnpOwIQnIwCZJLta( zIJvga9jfB@-ZfN$U^o=!b<o~YB4eH*GdQ2SkTv#9_@9t;)VbGCQLt#O;8P{fZ`>!# z{$Z}<bny;9Kzda1(}mQ>Mas-;tHat*qndS(7cYxuY$7hsDjIBxGUOm!hW8|C@1<%p z%@LC%1<mM;YIMm_m{b6lHZmTI0)gm(bR61TN5lFnW_g-OqbG(G1P0x_o(zC=0=tkU znbsNBc4HfH-he{xTs3tdw{fcG95Yh~``0{cu;e$~AR+VlG64oU?7cSpj7jVLLZUip zy`E32hP9ri{WMFz<w`&g@55})T$Anq^%$R}-i(tLNPTE2AlJH%i)pLi64GLUe+bu~ z>wk)RZZ}G3-q-g90vy8y1s$Av8NQp}ycVlAPdGh&8(38LDB@9}z>oDzKcbEq@sxqQ zx?%WxPE^77VEEb=Ju3I^9(NF@^^ac9eD-c|UQ-6G?q7pmMC;EqUj_s7aFJoHnLCAM zPwwQc-NY(rQAe~GZ9|g&mi&M|;M&0D=q~-`+*k}OTrNrHcN3VfJAm-$np>KSH)g{5 zvYzkS7sx7F%KV2Cd;xRuP)}lLc|Fl2`EDbPKa(``CU8;b<+0#Sp6L8g^td>num(;I z>di#3SQheR|3GIoR>lDvpHT!rEHn70ef4~E*hV(AB(Dj^7(60BNSFa0u$W*6^HiCP zZPo9H&YJ4oM#<?`x><Qlx8G!{E=#=5FU$Cp?{WwgKZ;OFHX=yUd{3jKNdEL<bb_vy zQQ!jV&Zn%e@T&1$4b^^SO|KA=7Fx-JZrQZnql^Qfb!tKFKkx2)(vNkC0gMJHRdU0u zIvFhL*n2p&XvFfKPX45igT0zlp$Bla&7uCXrCJ>6WDQ7c<6yeO&>ES1zqSws=X_5e zCuV>+F0N^y(OYY{$IRw5zQL9Ya_7lxDXCwtiYeqQ30){_XHH%D4%lD>C~qi@HP~#@ zcAmsxI^z7h64)pfv(Z7zB^O<<P}{>kT31crZCr5al_w3$;9w@WH~!H&@g}Y98(u#^ zm}D!=IjrixysVA^)ZXdaXj;m}L}Vq0#VerpJ29qFnyrM=LNTp=EnM7+KvQ|?sP)8t z-L-nFQn4?16wOaVADlDXH9?m)n*JM$aCr;YL0v531}uJj69pKYic8A5?@P1A+bv<> zqSHvX+Y$bbSVlyjt1>G)g`rl<Qo`dH0h)l89*AK;NdAp#YWz@@+%V-qF&Z=pJLx0m zsA4*2(*eSiqU}eC>AU=!m;I!$EWg)>Xdi-6JXC80+TN5+Wd=}NPDaU~3>0Z7-vb|3 z4g)E&AAev}Ovu=5pkUMDS<|}5@wW)ebau_V-6Aip&AK&-0Og=U#sB+V4FW^)?z_J{ zGS8KD72b`>cR4dDKYYM}<VjU|y`O3GsaW%=ql8`~GBqBvnQ&azfG#P4RE6t|L(fcw z#M6;VQ-g1xUwa!vO*x083F-e@<dH7V@DWwkG5)ov5ncSYi~cE2a{JWtgI%e4Vp)}B z`edqIf-lm?yT5g=k>SPO#A5omPVOyA8#|Vms@Cv?syGgVPAMh;H7$_$JD!l-`)s+R zS77<v!J$<mm_CwDsFYMYncBP6<G<)8s59=BuI8Pz@AYu{E!|tBx9Hynt54LjC4vSI zvj;M(0DJ)0zu<Rc*;#DH`Qtk(S*DNb%Sj(Q)5eR$oDh;#w|{L8H#MZ*U7@deH*@a` z*!=iebf>2M&!|o+c8HVI0k2Zng78+2zWcWZB^QAQ*ER}O0$GIQA7NBQMV1++Wj9`g zCYY^)WMSSa6U4YeD%^Lps28k(+e_qu)Y_>F-;j||>Cyn_f?nnFX7BlU^OG-f@esVx ze=fc*;6QbmI{+ttVRu<t9*eKM-90Wv3SX}Xk)0}f<6O@g;fXSS@3ERY**j?eX)#7S z!@oZ$y)Rq8SGpdCX+TZ=344OUs(I#J4tY|)=36vnIYqllzMK9yA5+sjQzSJy!(#z- zXbLWLXS@id8X9;T4Pv@ZWsinLqoEn-U@tT^xl!MRrYoU+F^Y!&LL)BF>4EY{E-eOe zEs7O1<83Wwd#y7{O_pdawhXPPpdJA9|FAfLWQ#NU|7CF+5Xb*-7N-ayqX_HjGMaG~ zNX`~1ctwua%5JbFszv$HiOLB~zf_Ib7;m3*x2P7cFe)`_aenqp!ZnRvC!lWOy(7$z z8LHsZ(?Bs=zBelW);7s|nLmT}<gHyp=mI?BAG6f`_NcQ-=ICQ7r^e)ce#yE;iOt^h zp83aWg$G(4VYHg_ob0m8pYH0U^Kb{Iq2(wB%ce)ZG<;8dA+`MWqB!*aVw0QQ@xyu4 z?ot~)6?Z~t-F#n<tSMMLc-wCR&sibCaeDS+hv2{b`z`0ckiD-xxg;Lbj~CA*Sp5s` zPkrqEcS778d-+Mj*qtz1$9VOk^HJ<V!<i5dhQyv+5;w!VXodL_IJE5h)|tiGg}h|? zEn$^jsSE@E&!aS%J7}>ub$Hri;|W!1AUVWWv%ZloJt(}HAvf>2nW?m0v-wnQzHl%L zy$$`2)jT&4#7eMy+041ox>LzPRn_x7Pp;fN`Ju3T?N-5`?gxYHo;B-<bPo!=wu?Mp z*KQa4wEo<F9xy2Kqa=8~Xd8B8t@b+n!N!Qki-%V~J&Iy;?s>jUrCfUbBBSF=O_3h- zCik;ED{m1a*01?sxKQ}o&+4*d(f?}xx5ZiC`rm(bWiLqh9%`X_G}+=@RjGT|ek}U% zebaAIG04jToG2|f{#>N-MFB>K!!slNXY-s@`t&X5M49A5p+YB0>b2zb-nQ=roWI)z z^XeqqcV2hC>)889E7fsOe9OOkb1+?s=6qwU_mlW9F(Up?ahVnfDpXJGrBnPx?1MhU z#zC$leHsQ<-;u{6XKZ)(hfs*WNodD#^JEUCdQ3buZ{FI$nDmhN;kev_&*6m9kNU$& zwOKX4@l`N)^Mp37@gam4^DrJln|Q1Z;=!&_%t(B)ZzkLwiw+^&dxmKq<H6x5;k8LV z$6wq(Sst{S1djzx1q?}?tOPIY$<K(#I#JR(FOz&_XN<xEw8)E_Yxw`);#B+?4uAs9 zD8QEgzCKzMTqCC!y<Y8|{mAFPh8!iM;jLT$pT!v&WfZbd*GZ>DeM^dbsFYG2`5D9< zfbLz8S+Hv&%0*#&7Hb=z=Lh3`tWOvy$`p_vR(pB=9W8nwWN9eEa36jOdrC#kG}C@W zf2Whi&QNvm0<`~pvXlDwfy;CC;_~#F#}uDMN!;fh-(|Z2Nj*Fz2N46k?bL41qQPb0 z!eT4zfM@b-V8EfMTKh`R=c`qL#K|xwwYAkjutfHSRIKoAKJ6>=cx%9D@J9M8x?OM= zLw!A!i4%}(2SYVGVj6PajvYdh4A6M$gX8-}3;4Ze-N!zY<>P9$s&7=;E4uwBVww}W zyrO_dM((FO(QSTG!6fJo_kh?6i(%c&gOL%U3GK@U=QGtv74TX@^R5f$Zp#P8MX59^ zx=NI)3nDIh{n`y`Jguo>pPovPhjZOGS-~EtAy*ug^qeD7oe&2yDD&d|vPMtOpnUyG zIx4D;HxE2AYV|uYlBsif*WGZ;cIlv?ZM;e{Y-G&woFSa4?xmawAGM)4KQ-6zvedIL zH<-emQc*>l!i+%xwHt@U`C?kUBiD7UBM+Zbk67~G--**NJ}i-+wYv=Nsb#jOgtIwm zG2XLoQCu|<m>I9;rr#iGSZK`H#fbAML5v99UHwWpISLil4g#(eMcpAy304ZAMw_8> z7pb<9tYsL$Z43VM6%VZ(VdUxM@9fCgLQXt-AiiTR?LK;9iRoSkh2P$5rHNXTu+iBU z=YOlwZkwYvW}j|Zl0P&SsAkMM_xfpF=!f)@-`5#tq9gyJJ}2I{_`uOz&2W?@6kTgm zS19t#C)=OSxK8=Vy-(Dhk`0edpj#Bx@dzsOD(m;StIL5AESL#9%ve|0lb!GF2(n8D zKC@-5Gwi;b0d(!7fZO9KVkQXhSh0Bh+74?k7Qs4<x|^Ock^l(K<tJ72iNeN~&K|sZ zAVK3K&VI{opY&>tifaeZ@KKj?pKq_0ht1xRvl=--KS}ZH*1MpP696?3O~JkAaOxg9 z3!?OWNLS()s$Zilmsjr!^BQAmB`h6`{%CPbUFEk+o;dC}=_U?rpZX|i`3{CX+l;JW zI7#okIym`swf7!_K(A4<+Ms}|{)Ugknr*KpdgT8-6a9=z{#$&~>v?$J+oe~6xVPVj zf;Xg!v^6K(#e@l&$o#P?k!Gs48IX=?$Z!}}eG-8OMRM+UT*)g48`JcmUli<^^ofvn zUWN@!8gri2Ke(^lZuOz@b8f7zn21i1bz=@ku0uYB=9`{Q7I<S}tu8pH%KCPwQB(24 z__jjl8EL{#h3Wa$ZDFNPU!Y#l-NKXGwYRCi)7@`l$OjwmXmg$uQZ@c!FTyIx7N>!v zms~}D-VP6+$dn5~_N8KGc{VJO4zn$H)#g%0_vCy|GE?NvF#bQQ&hyW>r!Dm!#$=20 ze7<e6<z3jsuH(P+1w6d<y}7XuQ@%2QMVX4VJSExP?&lXb%yCnx@t(Kczoo^=*47W* zd!A8tON&>nZSBUtgPz+hZEAdI9lG=l@p%4qHuR)(T4Iln_225R{ie#NW=R5c>(DFs z=_d$J0EY8o4QfiZI46n8su%0XthRn3ll?Tiiw(A^@IewRU@nnw{1krXDaV!Tj&O#m zkPO=4F>470ohw_SS?%K<CWpn#7u!lx?UP}XhcEtJ{6Hf*2q`APMgN?jHD?XO&ptB1 zUV>p)t6HOB#P~PX+(7GCEx6TH!n>%;T_;56;*iO4<MYd3o~E5k3zNsKotJw7S^t(J z@CmuMvVMkFr&XKEf@4V-h)Q_R84?}divaH0FHn4C{dC$Od$q3?p!QwJ^la4b>Y#Aw zV&SJ`ShJYMVbL?S9eJta>6DLu^S<@K|9cuN{p0dTY`<C8>d-&`6TW@iSdt0}pkzk% zK!UBii7BQR8=R!mVbhNX&!#T6Ib-+7Qo0VSO)vkmBb_gLXzV`srC*F937)^cB+*;( zgva?P0Hg>MMB}Ne<4)4$uRkiAilp$fmoZnd_s_Pb;H1Il-K3I}SioY4m`B*VlgCgc z2BEny9YDAUtMay@QR;`7#S^N&>Tot_c+a!PT#Iq4gdkNc75^fYV_38bGQO@lk{p2N zH;CqM3wik??uJr=oWbK|YlZLm7?nkO4zQi8S(F+!W=9qooT$ox0jdKq%D5Q7Vxoys zL|s_CffIF88Ep(U@xLEIV#5&@!VqO5m530;vW@&A6-FqzLz*@S5c%>XF?}J~?=(Ds zEyW)iA>t865#U3Cf_mVURZmkG_)OkVgy`U?oWi3(=7}~#L7X;^HArU3Y1RojsgK1{ zfzR;J7#y^~EV+LuNMr$AK%OI7q_Sv(#^9j^Ye`k%X|-)3_w^H8A?Yqc>CVrhg~Ef% zE9lOU06PK*bDEBzkD)M&N)e_&5Y4-u#b^-2_MQdlo6%(gs4znr!8VzD`e`3f5NRyc zv$n(;k0;N}=pqABf`~M>xXki3i1ZqyKH#Yanie}8yZ<BfwPM&|TWDHX&~!ygK_hhz z0iq1eILQ^MFW`u&4uVSG1;qgvh?L^`nH54IDj2E(EFuFyWq^vFZ_6%A$t0KT*9xf& z*&@#L(=t$ypKT$^C`bhgf-<CK{Rt^w%P|0CDdQr!NJY6SKV!~PgWvEWv&n2}*|m~B zYMplK#{nP;Jash+J67ReOOdEugXO8xpu?qV1Uyblq56yk6Ofrsr(wBD1*7_5JnXa? zgiNNIY!zvsK>)4WDV3NAO(cdk2KQvw;8`d;O^HE4%-J*BF9imQ5>99vlPB6HLq7d% z;gh<^f8Vi4uSmOE7!VCu#zWtw=Bl<AsgXkiYmm$UYPO=FjIa~~JZ)eRRkcWR5R!)V z2}Cx6`t8V*l6%ivMN*biz!$<I_T_Yx^dKsFY>JmcZ#WiVgG>=X-mQ+^6ADqqP%R-T z0B8USnOPa}T={3Vx-{@v0JS1}#B5u*AIU2>#QLc%KImuL)3;?HF^}BhC#A%qT=jO2 z&U*^N8_)g9=*P_<X38b+bdlu9U|coTY+gxr1*IAwdj3Pay&-@S1pt=8SZia+yU@Wu z3Yq{p1*t{K(!c@?P#BV|f&qrKLk%#%H&1AT0?LU{D)IJm`C3TPy;pL!6$4=@Iw&UP zos{d^kdNdOW5f!!={r|Hd4PuC4gHwZokC8zxNP=pf-)5V1(>~8DlHwdZ<wOKMinVd zJ6uMaSq5^q0W|{3EmD9T7`ksrSm;?&j1%o}09^(qNQL<NzDl)eaaH7b;^7yco?5T{ zK<#l9tQb(jXb$mhu+^pE<seyM=?Y_20C6{KG)9I)hzn(wMpZyOjBzwIYAMm-M?oYC zBJv|ds3T@f7$PPL3C9544a=*GgETM@>CwcOk#)w4)vf_PH`DkX@fGlFaL5|CyQ607 z6~A+t?j6H2ORt!G@477O0yRMC3^l;Qw#w;CDo0WL^oO?!D$&_P@j}qY6rOSXHB>)} z!!3SLv7N^EJj?&a@m?;iqAt6BPTTRLFuirqwLv3ZeQ&G|8Y6{^%C^8!O=FL(qYH#$ zr|!Yv<g6eE#TusQNGLWoEcA_aytBu13H>k$#gx#(q*-VvkKMcDlse(D-1-wnqlNdM zYWO2;+!KY%<Ekk?kWMHSmaz<2DlB!QU3kP)E$oi>+ncJTdrqb2KSIYALvB3}t<;aD zrOg&njW||p$+K>8WNqQJizwG`sR?VjzuRI*+v;i;(YB~8`LJFm87yS|=6oS2_9O^s z5L_7fRvt&&Vn+K-x<Oj$5&xSw_S85hXdA{ZI60~<^*K4N*rxHJ)ZNM7OSNQ(Uj3@I zN@p#|ZYf9|+pd9Yf6-a`lCz`yR=k#2>0@co-45y$6f`~nDzwmE*4eHD=xDO*Y>w(| zRqd?k?Ce_Z{P?dE&)L<h+SPB@H5k=}w@XzG2=c}nWbfu(RPax4FyA>4n0Dt<oc57q z@P)2>Q|^1)lbm>OuEBw8V3HZFB?onmG?hFWcoXe-zl`6tOyaPP5!cH6rI(2lY)4Jc zM6>?svW|&@4*yY$sgDm2ssAK#6AubxBBkSLOBn0j!Cq)E>ZI$_DI%K)biM}G&t`Np z1M~jEv(y8p%jj0|pczz^ECFsV4YDKF38?kS+4m_#_bHY1sdV+Jt@LTs^RPu1UJ*U0 z*BSJp`}Ng&47&Pn`+)yagKrXG>(U@u9QAXjx1&TgZycy@y5EruadHj1s0}`_A0$r& zdX@}&cMab6vE||F51?aIhyyzzL7iCeUMFY<4FI5l<4DkS!KXmA;Y2kK{2PV|1@I=R z1@uQ1Bwt1sf&zq?A*!RmU+xSSmW;fjaO9R@v;*`xNP};hK@N$qbsV)94up9#Qol0F zL%~*}Mt^g^&B<)cRT^Z3rb$5q<pINW4Rwx$#&>Gt{q@M0)=^>eF?0ObO+a6-{WyVZ z0@M)p`tF1U1vtG6<c57evof)2k0hJ(0*^pO${c(v3=J0(|ItlYqd=Cg^0w?Jck3s$ zRi=)kr|!!1uU^23n5nCaDF8RQ&P@P15WtTK&{6_TH-YXe0e(q9a!)g;Pcu18vpk;u zAB(eln(ON{&*e0Vdxl?qM$lpA`r{el(ize28S$?(l9w~m+_N{-XXQu^vkH%Al}cw- zx@XnC&T3rFqPgd^)#q+H%;`OzGbo)i>Yls(b<X5+&W!u>9re$a4xg<af3_+8Y}@_W z{_AJQ%g;{S^DgT14;<#*AJ2Q1&U<&y`+S}EyPOZ;UI<cO2zFQqeY_A}x)9mD5dC!_ z=5hhUy%?{)nCS375NB%XVp{iN#@EHCmy1~LFFER8@*KVtJpNKx`lY!0OUc(SFD}23 zEzWZFrAmjT*N>NKN|)YrFAW^iyhkJ7O)RNQ(A1-l%@WJ%4*z3uc3no2@!WT7G~KXS zg6s+v3_&Cy#08P>jhO@SW0W#9l&@&sIIZmZAlB88bKPG>D4>y~GGveM*TWLTHj=EP z(USLvn~j%yxK~BY>Bxf<8xG^c5=ioS1j<0#|0ZbWCRW}PzEL1o047K(9(v3ggzVZ1 zp&?)ynhEu9Gxn<#cp5UJJ6pO+$+yP#f^3#Sfa~juC?p2~I4yyEi~5S>nOH?3Um<DU ze_d^zpm~R-p+M4>6PM+Fug<C?$$)Mfh87%0C2vM$8bBo<K$Xpp3=BZl6KFb0H{PyH z@e3eL2uKYc0MQqDzPJAE@+(LS2&RCJfuR%uP_y5o$G8=^ITe}UC0n}mT2w$Siklc9 zB}MTwH1fgkEszY=1HTQAj~<J@$OH}KQ7O`!G)aGgMw&}I5@e~sd_V;=q!ONj0zgU0 z2eiZisp8gNppbYZpbbw;^$OzSh#V+g!(Fb$z0e$X*kOoUNijigA_0G#c3a_a3KX2e z34Vn6mMpnTDTAQngAq_L;50RL&$hW!4WW;c49-r+Aa6M$WAW65X2`a+r3yTaum%m< z5ot;UI+-AIkbs8F-zCPhj550~1-2l8JBxb=A`ksK60jwWTr1n9Aj`f^$g4@j0R{op zf`hXm;PpxBSHD1UL}j+Tc(X0a9uV3L84v(XM*^CVH0RvE+X6P;8GmJY_xpXoGHn0r z`@N+`6zy9-38FOoga`hbq;`1Y{^2(?12%wRbV8ei`F4Rp{zf4!%BU%bKO%Vm8Pc>( zW}9_900CaW&(h!E?BB0Y$N)6*_X>ov=K$wBud<3<p7_d0e++s@O9oyK{1Cq-cZq;q z`krGC9Xcjw4hkoZdjZ6I7-EDe^oaPUbrSK1cu3i!O(gCn-$(qxeESAKbnyUWKJAiO z-yHwl4_D8hBl9TtffNMDx+78yvG(9S%{z%B5dE^46teW?x2vyzBaF`l))D6=Na7k| zlL$ZgNZ*jf@3jU#?)e940FtTM9?gs1`xm*6NCFZ-K*Gj&0plq0wdV5532}v6Aq89l zDgFWX;ag;jca?Pc;l)2{ihqAKkT>xiy8g&r?zKJc6*0u-9)kW7_FG(%_Q2uX@!QqG zThjTb0|4JGD?mI5#&gp~npxY5np-20&3xl#{A1zk&3yfOm<(?Dn3eDV>$ln040)n| zNa0lrB<}Sloc;Nx>re3=RG4D%;{!mHyIA(el#tdd?SDrVo>L`S{BTZi0Q2X3ble>W z2Q|<9wYTvf^co`5?*6iAbenjg``l{Jw$&HrZOqo<Bicdxm8Cy4m;Y0zmq6xQ1zF7P z9%@=f@gF#zo&hgsm1s4Y8`@FFbfbxE?AN;hEj*4OS}V!rn)i;(U5Nq!$#~~~ACtN5 zj(wI|NWPlQcj=0j*uaXmD6yKXvNX^WMm4{Hwt;w^k*Ay&QoQp;C&M49R5*D*w&wG> zzf46u!gxZY)^n0>z0tb6cXz}JbbK6rezdoskU9VRXZ*#V*8mZ87A10{OklWC5Mabm z`GBd0!2e5_`dY~oTxS<Mq@-UmQvdZJTvVtZIpQqdQGRhY)cDUz(DU`+fArO;xVFYW z%nLUCGWy&hz&iDKJ=vQ44w@MWK8SNgKT11CEtNqV>f$S57fqdn@|oNa83Q!W&AbZx z@0E~HBZlEmKO^58pT-yCOli2-ME>DU?w^M#O^GhqTg_Isfm?b@_)&ioEy%SziIdgz zRFb?Sax|e#5k3llFy3}bm%mSm8(_KpcskF*R8^ve*<6oa*Ak)+1Kho93R@cn*iy>_ zd`II`jO|LrYHlbaI$Esluf=;U#48Ad$~xQ?4>m(ROc%h!<s>QCdR;p}%r|kgC}3s- zp4@n)%PNs-dB*}4W*ToR10z^%xq{}+8$(XMJ{lNR00dMIDBgc8HB*7oJOL>=onJhH z;xp}aYYIO*%Ab6-S`A@dx3YVDYOm=$aQb=n%GYz#Y6*1anyqs^;z2GwrKwZCHBVkT zklJ0@y=XazAHxLgIC~XI&7jM4`~GJuX3n_eVcTG1RXHzf6WIyT>MHL)`IVX`WQ+5p zMq{ol%454@cR9mGNe=CN-0>@)KHu}<i;>T4j)~KmQq8STUMON>VY<sc-6!BepN}N) z>2y-M*Fb?NEBwy#qodoYURU<}`zWiG1aGfT5I0?4yy6coen$=(F~X!i>t7<klC83= z?}SS?cyurHf;rgZN7mXfUu2}MH9~-Fah6`HhjTrC{qOVB!%eB(t`_;X5h(>8rV%^T z6ZX#s1{pQ}z3b6C@!R{9wI^rml>d11!p~alY<RlW993K8wly4!rTlb-$%g{y;&VJF zVo0v(NgIU=U1Kd(G`31k%#>xIgfhtedICuCzr04$U7VRylN0z$Z@Qj{IEiI87xCB| zlW+?vcptW&tbWcX4r?VONzvIvrD-Jq)eVAAvb6#3W+0BAV!Zt>d~`{R&p2-a@9Equ z*Eyc6`1w^Y&Kzl@{$E3>pjDv8Y=a9!Rx>cZ|EUkK62?u5(MnxG>Jvs>IF=hh@~!)* z;yNzvHGWRe#vj>T`aCn?9X*Zmt<=ZOP5{IP^GF0j0po;XKXOC70@7o%n8x0t&bp70 zQ>a(OsdGntPE`&6T;(^jg1X8qlX$PZyl7KKU0v*PB2GT}b~=5T8Pa~S=1FLRn=fV4 z^<Skk&%h12r7<F1!|gMsI~6dlK{S>Fh@lVd(G~M65?F=J7ORumUteNHY9zl)KmP{w zP?}ZDcIyGdgHTXTssLzU>ul*CHG}!_aHNf~q+g5kfLH*ZL4tHI11Ql04Wco)O6?7% zAnN43J}XXR?q`T?e;_Hsuh0OSD`(xZ_bT~;1#JIhev}7`ja+2Ky3ADy<=<1TDypwr zagz%W5i)X9nSHGLHWp!P_r~e-XlHwl#G(DIc~2F~a+=%4&i95vjabyYxKv`wfk-)9 zk7g5~rN(;Tzn#PatoV2x-!hZkT(TY#BnkAQo$$8(EUHFm5xX0I_{<c>(2JgSc^fuR zhrFzaPlSf}?00569H`jzE=_4ZgQ8`kkMrCHOat#0CXv2U;wE~n<{Le9^33RiIQS}2 zAz(vmjWa4SP$+%SNf+7T<dk*g7xYN){r>&>b47+#?dBi{U%!y&QZF1ES%K>=T0ZM# z$kkqi32tC9w9|h31<ql{o;(FwM#;<epaGcOCt;%VWjl1CQ?-L;*0a6o2{X`M%J*m3 z=gw8;xP3kv)p&<5s`t;g>ktE|cj7a4_pgo>6}0pHZ?^5;r(_Km2PWEUMf9YKp2ig@ zW(pkAsX5c+Cb3kxf%faAY3zs_&Yo`rQei$Ej89wAU+sV-_4dIWT#4Zp^nn>}C6b9? zJVTe#oz^>O5c`SJ;ArVDO7{5y>r8EDPy?kFl%z<5{I@uA7*g`!(d{xUPQToAFvtyb zkf#e=Q+qdpsE?kPh_{I!zo&QT_hCHEPFi|6JJ&&naMTo!<Ojc(7#5oC^626><;U38 zZoq|TBsHE41GXNOn{%{J2S>=?iW-a2$$vYWu>rbe5O+=d%gfAA`sp-qi_(WTNp}7G zW@AB8XXWibY32Avkb3?#Zrp_FwccRf&PG#*O;Mw@a<;ZIP~dyDhc2;Awe+C|WqI6{ zQEp{%6<9etu6sV->35o7$~pa3I*!fJHA~<8oIi0e%syF#S&`M;xH~OB+j2l$vPBAQ zTbGIsV+HgIF_~WV*WN#orhjZM5_oH3dW;moS`ut^??vkbWeYhvzC3x`r`wOMH>lje z8fc!|BmYqmSE3yKNWr@P%4bTA7K@5n2_HRTDL#?Y&L*C*X=_yXTbKV~*64H5C@2ql z5$1dE=Ut~V@a=-v_kK$N*+Jrx49vLx4Hg-f2e@C^`!B4!AJSw^Ff9Ma`v6*CP!VAE zlI{*7&+hB5tl(9`+AyuX4+oFf9P{TXjj*^(CVh3$KRT5?w>nNrA0qCP?TO{j06{R9 z=ijIeP^iC&*zSD=n?&i?vblkHSJeTA*BkOuH?yA3dvt~CX}dHZ?r}Xlte(nV2>Wiq z@B_jD?{NXdZ)8P(PgtuNdhE-#zOS55%GKP$=^KyJ{{sNaIZ`8rln%58Run%eG~;~n z<2~GlEQvAH%DIOvQ!IG>I<BJ{^1vkDbp|&L4$)eDr3e0S7vFD}9_?W#tn61|$VA?` z9iWy{PX-P1$MZiB^pir6JzFc+dfK1#TumBG1=(CAQaekh7Nb%FhPwdG=qdAVPxd5_ z!u%BJ?)XCLe5afzsUK*AHCEGEHqxPQ9%kr<C#=0miK@{Q$>C>g)*7MYDja_5x0Vuk z3UN_NeSQi#>g?ecETs`oRTItvw50^rsJ%4HJ(lei0T%AnFghQ!#<x8QLS+L|dnd|z zrAt`eBv9K^133VR`B03wxGG5|Sm$vZwNPGn1P&fw26PL^20&AmI=dDB>S&$y779al zPO<MAp&!E`lZE`z*iOyhe&wG!vEeDM!l|YN+Wx5i+u}?U!)pFSGJN@oxCoCvMH|cM ze!zDPV{?hO*o$g3+is+?iRi?7_E|LRF5~E!=@~)a)1Mnq3w8}Sm1OM!(%7`<5>FxB z!d1Zjw((qT=S01hMR*`G<yRRbW#?0%8Q$}|-iMluiZZ=uBqSg6G>R=t%_;t#(kH-< zw$rb{FiTo1VA?t-gg-GQ5}-Xw>=jEKiYdwT$E29aL1jd`eE$w5h||8pF*4UOJ2BDu z)?ZJ|8%{JBn822k)*tF7pptsRQ$0$Cvu>uQ1JeS{sL9_2*ghd1ldLk%th{f4O&m$6 zVSexhIgEq!NLLm99dZ>>XEtOEuc3=3%WKkl5o?eDgH%cKo!Q(-)&sr>q(OY!U~ger zX|DG6!_g;dERUd&%EZ(lC?tBZeRO!FUT!QFFeWvkCT|9gABMnc4V&_A$&Wl4iGse* z8|%vJz}`%g6NGx<AQ5X%yX401*rQctuBk~wy8&A6Tr6RN<4(Y=4+7Bsij+-RDF0t0 z*(bLX>G-2+AmqwQ0-I5JO}-f2sCmCpZ*kmYw4gJ`czliKN6*2R!0W@o#-3fn5@(Qb zEabgUJjo$7d9ickSy#Qt@Ps%AqO2x2ARH2efplHOORO_X3yOcI!x*EW@&=P~=lG$u zC*pJ%AM$-5Tgsolt}d5qKtKY^&q={^{HOuFvvRpZn_j$u2AB@;x};WgE&e32vK$Iv z7ED#gC$Kp&MB8MXH(?WY`qFc#(5F)|6a*j93<VU}d-#djQoFn0o1gWB`)|6V0l978 zpI&#O{AXwMlWm&C%PgZfj>B`Jn0i`Yv`4W=&u0VP*I&bt8c#~ZaWGdg$(Tw-Lm$<o zzy=^|=?3BFa(qWsOzV)PO5=pGiSd7$fg7!qiFd^A<nooID4uBskb^zmrJlPphB+N1 zIhoWNF4YXGv>CbD>$fcAb8^Y{ZARZjT$8ZMTMN!i)o_$qd>Q4yujGU151K6ljXsPl znI`dtko^bRl|V?k?43Yu3tjapy%6(edusnRT0{9%p<qS>enqPp%kn$0L`+I7a>R0L za5M^<UzQRk_E}@&j!jba&>BP$hEc3ZDk<zxqNuE{VP~AVo14=yyr$)I<0)7?HLy^> z48Wf-R~ADL>by0d-Z*h9WIE9^BkW-YB#F=Wt5w{&VNvRnm>TAU)BJ1Ew^y1`HeLmf zCPYKNn!YcYiT8{L{4b`?G#u*p{rj_;F_sx?b~AR8eHr^OW2eTNtr}a|vy_lDW(I@7 zSVJm%NLfPCW+zFugd}@}LKM}v`THIBll$rC*>!xb2j_L3=lk_SLkjZFUgzpL=fE!I zH%vw4RxLOj7j}t#FJ?9Avi_FWrctbGfDfl?4NJXpFGIU-^E2eHx=p6@V3g@PaIzEn zE%53vWDC|6Q;;<@$qY4avFpw6eDkV=J%*eaeePBN3L=X)qcGonP84yE$Zl5COf4KZ z7waw>i<lGfc>C<RPnlFKNk(9Ui&knuX?$=gw#q5PqtDa4s_^A>o(%;DrIOjI_GKEm zJo`kE#{7&~zG@|VxSMrSE&Sn=)-Ht-cB&Cwmz;kQ(3Z@1>Sa}TLg9FC`x(k0MG!w{ zlBe%eZy~iIIGB;&P+GH|>NV%-`bN}lU`Ws*27J|)Db1G@pOZDbH!;%MF=WM%=DTC$ zodJ36;Q^{Yi@?-e{q*>@IqS|z?dNagDUDFuI!wx8+Wgg*y{MGY^hQJB(zsMP3V@pu zz*fmYb{>?U99Lfb)Q<4WoI<PD;ohexiYW*~onsO~FPb*<mG>h(zi&S^3cTB%TEf(X zH}Fv`!UYJ5iboGSruZ*Z9@Sk(<mowSP}>0j;}-{pGbv3<uDr!#A}8z;r4?or*^CXW zcW%A*>6j^A_+=%rqTUqZ?s8wD+Uxy-L=;GscxTdx9+djDW;(ZkB9KVFyL>|}6j(nG zTAVuPjkqmKp@T%O!uj(=?v)|_0~I?)z)z7N;jh&iuX{XAl}B?gAw+#BbTH!1Ns1|Q z{ZnqCE#2~Uk<#l7mh|qT@@Y+}0K|`u6TJwsO4MV@v=5!bQR>)yId*I(L88!fGaUR` zA>tQ1e}lj8zc?dW%<<Kd86CU-2u&wq6)2?+|7s~pxck(?`8ahkS}BF!%5%v@rvT4C zZ@=>GE0KooyrXxrCgu^{DpMT+P*FHV!}3mz@*j)W0BA$%=v>*ch)~0m9q&&lyKn<f zcWZoLi%l{|L9nDVv>M+<8@LP{@^DvJPIT>`Bf{<qv%+-s--6;mTK;~FK-Mz|cQREU z4M*Ekf_`ea2jl?;0Wtx!^9CpQ^BTikRS(Jv&f=!dQV@8F<*AJ<2_G(kG2J~9B=VkW zgoU##)D-4+FRd-PpQ)g;%&|rsx3YAe($<^xYpCOOAmIQxI2z8jCww*<j(86?TBlx= zO8WIQpq|$yZMyoKIG10Nx<pt;QnO&M2L#5~+zc28kik;eMB8<Y_sfmwj)@YshC}!z zn#Bq8jj}-vI#>@b9bk{GIV%FCRXqY)cS4mjzlH=6nw0o|AG9#kxlF!c+=W&FrC^oL zQUQf>Kn+lT{Z>%{kUMjswN2qanSgo6B)^wwINv0@P`TW58x*&%)i0CSbwd2P<YMUA zPAYkk(HY1vq%&UfpEVV5Y+78urDfM6BDB>qvPDU69cn_DNYf{N`rt;XT7F+y8ND6T zkMvufQUIgiD>>9<9lEWXVk_IX3;Jn6pcz<P$S4ketSQ{QSS^(KZB0-<YBbqxflpxM z#Kq$;+TSUolHVkhz89tfavnCbW1i_lOmH;w!tcNDY8^RUPX8S`rL>^2=TS3%xvecX zp){y-hR-GD1dqf{Q8DLkzj9eb)|&7awuX+w)*a3dJ6vCmds#b3*e>eCE|2^!ukJ3N z<u3o(U4cuxg4cFWr0fda+7-UPEAnJlbYNHP!>;(3U5Q`2lCVAWi9L+`o|NvMwB?@6 z**)1ydve$I<Wu$(ZtW@F-&1<BcXD7)`NQ6+FMBG#_Ecd%)K2_Rm;a%m`-7#j`tIeQ z?zP-<EtW(OmlY*E#r0rR-1^J`CCXZc-t&MV;%s<qbdCg=1izIiY=2HG%q+MwE0C>U z3b#+!P6-klwirICSLQkh&u)6(e$V+WLMA1$F!epZ1pY*pTq_%=FlTh@>ECq5<}=1k zx8ohGACN8AyVCs{t>@>94qjji<osdBg+@H_)wx&cmrGK)3Gk0^9x|3wDMJ1UhsSDe zZXcxf8rZ^Z(214J7l!*uRqF>VunA%cHiRat+z>VcCzX~syAG3yc`0#+${r0@!*BOr zR)vRQIoAYW4)S+=6H~)Jqjsn90(VfQrP1|=<2~q<>5^psCnIIb3|7rP+i!Mrs{H;Z zvtQpv^B<ab6I-Z6)sOj~N-Xl(??}U)P#lpDxh}gQA{rSzC|LaE@%ka_r9ZU31r7sY zyWzal=B-EJD9-!~={XmSk5#~7=<b{AW)}}J{6$Cera!y<Dl>-<UozR_2eA2SFyi;< zF1OWg3j1Xgr;<x*q}s=3*vs?}50gXO+G<kfmFZFU2bEWE4^DIUt_^a(xL%1icG8b& z!u@)XmEA-9;4+}3C}#791PUU?QJH+!b#ZSH6tm7`@BFw{)$~b2dbH)6NFn1(pK`p7 zy59=Ecyi{<aXDkZ<NA9vxrd3q*ZD_#g)M^qU(4^;v8X>wn<=bfVk+-2Z20U$Js}1o znX7}7e14j(SM9pR-~3luMFRo<Q56p6L*5s`ucfydpS_t8s=DT!LJ$A-WAMvV?c>~D zBsqu-dntsNHm656{`v+=QJG6_vrMlQaQ-EhhKK!>j{H{$ghzbC-QYlxKfb#8b4yrD z;j~u|U=8#)Jz!U=pCPjSAHMyxl<rN$b{F;5j?@#t;lKRJ_5aVsIh-WM#aljooDyXS za3%Ky{y!I|T+-^9B|`j(U2FfirX_=9r5kNpha;t>Wv&A`0<&jsPXlmge_uyTlzeO! z>^l$@Lf?Cu3!If>i1N&ze-#PiQ&IllM`i_)-><#-pyP84i#T?1dI?SUwU3%P+MT@R zMK(y}Y770_@Yy7!^3>ykK$Xw0O4<BHy$-KMyaLSVpPmXPI+=(5_d9<wFe}Jp7XPd* z?A!Ck(AX1i9qt80%s)?0zZdoWd|}<^P?gXBRfM@c|Jiry1jo;?qF6xiEN8dnjGDVc z%UyQr-cQ{d_$jT*d)J{N0enWh<}zn)aLEP``TiVZ(2~?0pfl%`Pg$Hc=6c~P;lG}* zB}F20^&y=FJo+sSc(yNj5?r8Hi@m?OIiEJ_?^^$O7D$&Ci}+ZJ^-DD6S?0s*=d_%o z;O(`zvmG3*mXd(eV?>jG#P_8(YB{Z+bXj%UEks)vy_Q>fzVDxm7_5kW$+^t-(8;;P zzi4?R@<*+_U#M<Ez`5c?{a;84V5ifhZJP@L8cNZh^|D?_3=GiAHeJ1iUEZm6&KK;$ zix=(02m|5{4Bu~5Xk9ISrz<Yvm+9=qR+{Tp+CH&<>vp6sw{=-RVLr#XtXQc@*8wVR z#Od(keUt6Dt`z;Ses|ble+OK5x-aN~b4`U0Wgah^I6bPf)2?0bxDG|l;JcS51V~E} zduOtgik^nrS3l3qv46xJ?P!8>X&EMFW$5r-;9YtaZV~q$Tx_~9?RE*zuIR^fz7N46 zjrcYHM%cy0#%I6cGQWD+Q9gD5!X;Ly@El5us}-hU_j=BJ!ffqWP_1q3kSFTI0Ssln zHIL|F)=O|$YEB4u72bJp#{d3%^OqhgTt-L4Pg);@1uh{8Y*(>$5oVw|=d)GTd^pYP zF26%+WFx3ZL14V>W;ffbc&EUOu4=VF%?~R`($wyCCn?y~7cqqE6|uK`rK<eHLwI&I z&-f;4&R_j}HTh2C`GQBHBPOzv+L6Rn=T(i(Gwd^h9rpKDDhW%4{~V2DMsy116YOP9 zTTv__&)+#7ywIDtj@-st;Eou(+k;X6@~}4#%Vjsu&P+rvcfYGV>*<r@<dFYxK-<|| zKvww%psQuN$W+?%FLLoOr_sp;miC4~G+yyjmcw`DC1ip-<Ax+S#T2BTS91i7Kf`m! zG{*%89v{|?kK|Y#cjR$nn5%woKY_QyoBUv36W{a{i}HyUj0g#pi`yGAh2JmVE|hlS zhs^kN?v@r0;`P;@W0sF=ZU%AV{57lB)tMS9&@sZf!HSV^*Qku1jM^lTBIM}EMS*{> z{he`~{8#;;(yAT=edixpQ+E%{Lti6|FMJ%2j>~>k#B2(3Z9zgSrcoEK$iy`L$g>_j z!4tY*fAdED(A^xV9J5CeHt`|@x@%=Jg@<YYGE+oawDy!rM})d%uod<j{c*^tzN@CR zlppmI7^Nwieg<W{o?xBJ(&utWEuM6hmG&u_9n=7<kf%jndUNXr%H}>PA?71^rStm6 z(fJ+>@x87LmTZ#P3#PE@s}#evzBL;5D2b5chK{2DC`|OQ)1Go^((_o6aS^uEE4*~t zayzBSjECcdZ6Gr*1}Xh7(85?a<w3&?4I^2S>=Bfjm*Pe!(`gzr+=XVAZjGBA7Q$tJ zmiE*2>rReUuxpMw4csn;iT>9DH||_i3Zqw)d`!!IP#^V@{bIGz$y6SLY)UcDtjv9} zJEKG?ymt26Yz%9iX8L@raO*#38%m<A<{zo&xwC!}&Z%>QTA-5~UE|_&qsd*2Km`YN zLb^?=ln0#`@Shv&t?YT5U?(S+Os~wQTWvf!Kl(*JAiCsb@9qp3^txBsj9FdW3BP48 zvi~NPE>LidJ;k<2Q1m%r=<c^&4zptSTsN*P>8qcD6Q%gcTfKXaMHJZsfqIUkW<dnb zPa}rI#eBb~H?wrQEFTDJI<B=VNisv}Zmp}_Ll%P4wlrCgiQ);P*%j@_UoV8adlp{M ze|SrH0~3B-=-h_u#njfZ9DnHgn{K-(xrIP0W3;1JeCjIRB2h})w>_^6!Y>aBw9;$g znGT7(W`=V=C2l!+;TJO?M(zMcKC*puFkUIa*+2d4B?aF9UQwZ|r@)THZ|*8pRnE3C zfL#&hJ3Hm;#WK>*xCWaOM_wkJyev9|)vEH`tiuv~Ol2PhHQ#|es|;P*;K_Qz&l85d z;>|wB=JhM^Q8TT%hqD%jz2)Tl+Crv5`K5JMn}Pq(w4mG)>9s@m4{V{cYe;Tq?-J)) z9W1!_@{wCJ@o){fFvcbc-wm{w?dA&eV%B-K*|^lK+0%^t6}|&foLO^XpO0U&wg>a` zqd&NGJY}MEsY$wj=Y(t1Qn=!v?ls)kbZmV6uygCohy0a_5|<!nU8~i}0Qx2K%@}o7 z23>D2j-MZjYgv@iewYEemo}VuAv{F-x@!TyDyEx{QzNZVWDn(vWH-*_!Z|=f@{)S3 zulc@bHGd%A$es(aoa=hT9+*qy(k%W%;>l$^9tjn;O@%$z*s!@#u~}sjvfNqMeE)@M zKT$K^t<45wZj?6e`d=&G)bSE^d4j^_?!wbf){C$P`F|ySjX=>=1s-abeQ)2~1IxvH zYrVF_g=+KX67nXWwCx-kt5$^M?e1`y<UNe&89k%8x050X>OyXf#C@^e)pG3p0jt>O zqP+fh4bSh5%<oZcf@vHq{}eN6zEZ<~%JG{+&MtDW?W4Kog_NseVf%zoE`c{i>aCi- z+3gMDihT)>3Ua4cH`YTG9Lo&se*UYm7kD9OqV$JM%;jH`dHO9~{$xXu+GAGTIccXT z!&}EJl0AFHA98Ezxor_r)w)!>EKdUu6Ua^e<eGWeRePJwV8*G=0h-Qt_`sXX&8_Lt z*?9)vPrbh!JTrZvx6-!D?7>gaw>hV^;Ez1V^!UrU(Jm6NGNglHmn%pD_l4y9F)5yr z)Vh-o5CT9U7<MT*Kk3YK;ge@=WOlmhuVG%+a<<ZcXGikV$>lqO5qjRJGx++E0$^YG zl?#RT1FZL6cGGN9P=Lu6(LE0mH8$&m<vGo1>w>y>KQF1e%6e6daFK_tciqW-OR}Gl zx?*)=Zl=c)11-%<sp>=82RcO;el|g)yxnZp1H~F;dpXly*Q$Ls{|nR*N^`tI7Y}EF z3EEsHJGseBs6Z9um7n9C!_PhEAdqaQn-P$Es9XM47nHd^nGh5G*B9<9&Jt1X&t~u@ zoMYar^I<ng7KDCDg6M=YwaeYyW|}THm^|`=0R09Q?0`V;n&Y>qddDrIgltZ2f>sR_ zvIv>?dpkqC>o5rB(SW8cm^bdeP7vlW2K2$Z?GG>@HmRg`fx^UIYXhrNFSP>Gc5wM{ z@zjx(fV;Uhd>HLQa@wYuwwnekXFvKxs}iFMJF;mpCDsJ;PP+|Aj;1>(m~sE>k$c%I z*-2qFNnPt4GoL)+4(|`7J8(oy|CDtV8?wh2nxz9$g~mC>Tr3~C6SUy0Z1Wu(Gt{K* zAVRw{=l$sUvwwN<Y6z!c$~(W;=2xhGB_B=V@%1g9dRGP|uUK7)z-Nw~y8$s*rBh7| zb8WNXy3v-lJL!5VeIE>aVWuB!ol~#ngOB{tLs~XD&XONG>Fs&Ly8CdEy1o=BdsbHp zQoU=L?iEKoi+ASDYWke=smBfI3*a;}=a&w4&v>c@79`JE_)m-1mQ;6v^(v(-C^DoN zGfbtJORB6xPT$NS-UPkiSn^g2?q~-u)jT3d#}#3F`3&kgjJC?;7R@Q`2yF<oVI{}( zubB9n4*>n1h;{o<8*=py*QZz>34(=@S9({(@HrhvYX;a@fz^GUIpO<z)i!Uz(aXw+ z$J=UT)c32Sx_Pg`oTS~{k}<S1{CS0im27~+fJ_3OFe1$>(yQxCGZra-_`aw0YN|?{ zY(P6AB4@U7Rcz555?Cb*bujO}bMLAY=2f`tX_}O5e_8rmZ;%8$(T;7%kN1@yb@=T- zRDRNrycNTI8VQhG)oQM?+VgRa7Iv{pDMvtA-NshDPkyKJ#c+R*mi4)*X)^${yweOD zE<+jfgLQ+He%d}>^p4?951jWz>chhBX3}<wY`f^Mw%l(jnV)Z!dmEnt=}58%^@lrB z%7(!vo$1*BDvY*P>KoS|R|<-ETkf}d0Cv_3xKf;lS&73kYqq35dnSJ7Aiwd3La?7e zaC@HzV#FHd{+9u+&l}-TG1oa9ysN&k<|hU?0$)9rY;&S{zCw-jdWg>Wv}%T%mMPIM zCBFkwJYR7&rvL7|W2p*MqPvH4r1vam(Cs8eI|%U_!2y$2Zrc83YP-*>*Q4s2-E1H< zjJu#}hx&@%^Vy+h-^)(<MuwpbJs`qvVeIqOKEc4L-U%U^g^R;krUP{fT;Upo?={V? z6>{DB620_+KopJ0gvR|<LZ_}8n&xS&;$3=EFN>WH8A<b0sI&8WfBQeGey=~lfpOC+ z$@%RWKn&j3CuOZt@v2Awpt24=Q@eUdlj&qpb$5Eijx31vT!AWV90#w-SJULDxww`H zciM*%GKU?nqMs(bOQ<Zc+aHmRgq@qe8$}-pZp@7w`|wBvidqBLWXiWi+Iw~`^;c%G zSz8V4Oxm_2-EDKK>>xy=NCOLyfKjmS3^l~LSLAPxAug4^EuclBrao8JIY5^5CR1HF zi`{%@@?qFVE9Rjg-iJ$-YZX~R=hMYg{2flICMkS7v@@!teF#erWeP?*eqe-7qD%uL zTv9W}3w~xKweBc@`fIL0`cydkYMiHhv=&W-Ru%g~AGj73hah$UY{Fd*JF9r3b?9~< zmm%H5-fDZ2+g{NPJchWJ9#SW6%7TQdg$1`G2oc+B%)w$6Iebi|__<yNb}qs+#dU$2 zE+7`a6`JXh-EK!Sw4yue51DmlH>?vPd<YB#`}@!}y*dIe))!C0n}@6<>I=s~$x>S< zUqdeidlMAVW!rvXcAW!RYNYp=vYVt+{#&c}EXsgMi0D3~lf{(TbG)6fVzmWCg81l{ z16N-Axs)JCnx4G*3SHne({r%jz|fAN!uZkJyM54;lXpM3t?!m;zl<weYGr{lTGaw= zgK>sDICsi^E{G%hldYfyyn5i6XX96B)(2t#Gx^@Ia5IF!TSWLC+N*Z=D)fPI%2ED< zh1tf4-JvPv@T;af3pZFcDSr2Z1s(J0b<>Q##!8x*`&%3K`dndHoI<x#Wldh)L=-kF z%7P7kZ{gdOTd40gYFqt6_j1q1Sz!TvjpH=$?n_2B{1^!3u;U_rz59BCyg5@T8&L3I zALy`tzvjFzp}LgqwiJn3>FL0AF|RK?-0E-qsJ2JbH3%M?t@18E0__2rKB)Ak_Yi8R z0Y3Ni-q(8l#UBZ>5g9!uL_7dn$)nmksZ3FUa-lD{dZ8i-?H4*7=mCR{;)<KEHh9>E zs%`DeVq;*T^oLQUeHsf(Z-thEh+q9$`etZ7rNYeOmri3kfora`9$t%RuaAc45aZDv z!*-})IK!!%MdPeMv2ojzg!9j2gMo1iI?RF{zfASb&k014nC4^&ZH&poU8A>4e*(al zdQTBrzzXeYT-x^@{T)7ags&6XeN41uHH$CIetjR^Cx+kVPNbUr<c&w8IQNe;IqYIj z(_#S0MZ7$vMX61|h><~`Pwi=J-&?Nb+eSp-b&~P8tiJA|(}s^N3}m{~L%0;*SzyIT z^%79X=QCnXa7N4tJ|fjMfUCL7;l`4X>iZPKD^@0s{bqC9c7-VqwrZ3fhY@?B<$<ny zhUOR5qp&gMK02ovD??`Mnhjx)g#YU6XM1=fD1p&Xm-S+F%mAlc&qVYs1H&Y#->Z0& z;lvo$<-B1e9YqaT91PN`Ga2ovY&DfPv|IKVe(O$Cd#*L0G(0Gz6L?ABl1WNc9vDl9 z7~_KRja@qNbFFKWDiZ|gv)XrBE1|x<lJU@(ZF@7fw46-UV7uP4XlDsei<Fq)o|t5_ zUwOb)U(0B?j51qr3d2hTvZltIVQ04PczLJ+4c_DZI-?EB9vrB1#RZ(?^)dTfglgj* zjg;)$<YJSOu~Jj5B{}(`le`<Br@PU5tKuwM3$)!6KRH|@N<JMN>Gk|TOAGuq{A~Ja zdLkS<`u$02uCIS<&<yxN!SKr=4M&KaOewow`zjN=(0&9?elNE>o4<Q>DJBm7CV*wB z{R-jV{$sN}>3%+U`gH{hY(y}z)NOF?zdSAyfhvbwy|#QIjI%vYnbuX3-I^vqKcq5z z#pwKwE~>X(+qHAfo`rq=oFc25T|ad<#@d7Q)czzlNjdV~{nDeU#fbaEsM^z|u`zg> zn^$m5o`F{3m!dbEA%uN=$|U<OjcorIzABa22|wl)f(73=O}8qkhTFr;3MNrXF=BxA z3WpFuG2H|&Mpbb6LDSnKaEC{VvmIeD5_U+U!8bC-r<^Uw$%p5fRoKYMj!)<ox_)_C z2D%Wrl?(puUw(R6-ZCix$XQyT9RPM<ohSW+GM7H&u`9KhuDS9W##H;4v4YLlQ9oTR zQcz|@Y@@|~pyL&|^SpV4E{vfC7TtLl^fpn0QPjjD+`>b~TP=G}vq6p|K3;_>h@D2H zGzPyG;i~R6kufuv9*ouT{ShLrUPu-C^1bBj=iFdg$xyQ%?lt)4;)P|JGlhyn*yOvd zNXD3Tu}4_cyg54^c5U*uh4Q&~g8ec}1}NRj_7AFz44->1tcOp22n~V`Tu73>V_>)? zubnP-wRG@wf|$~SUxT#=w+$oGIIJTzDjXCl@q>81drrHRRuBDq^PhV^=1<lMqM6uD z>(G3}daV4s_>7-7g~XhNA%91Wrv83uNxcBU82yVr#2eL|=%jL~DzWJA&l@J5vbcBp z?W?o)7Q<0SR<O*5&*E>XZb1t>66SNTv<va(X%Q_iu9$ns<ak*@X;a46L!io9&%BOB z$$wAXir01yH!d<)vBAB7n%oP$YmHGn|I>n|h`M<D1V>O=pp~?FV)dsvb(*8Ne-yU< zLd(B%e!uL8do1s>$Mw2Wo?TR&U7PkLjHVdd#dK$6(A~UPUl%2De>v3D$R;---v3c8 zncnymB*x<JuXkwOP!O0Y8W3LIMVB<y-xne+5h9S5-1Q&SB>S1F-Z{!gJLl|f>qd01 zV8_mr^C3s8@m8vUmrR2B@7oH_U%C?Kh0M-<-Ejs){XppZcjU8z&(i<3Kea1*U;XO1 zH;C%JlvjT?+51M*u&(Qz8N>J4+M6%AXp0wdPGKCDqxBz|KexIJ3`Wnr$i2?>%9(TQ z)4bnNyP^f>*xfgS#}kEz@4rU{KH<Q?V$L>reTaN08761-?GicC@OtsTngi*NfKQ;6 zi%Oo?b{BpQ%U-(PcyFl>!XwSi74h)ZHF<V<-Sgq4*bvwU8{MEUq^0q+4;uR|51+N~ zb2h!8rX1e;zCC^qX{QozFj)J?DvsWg*w0St_$T7X*^t=2$khcC=m}C)q98^(|N59I zKaDlaRR$!`KYr^3bY@%LP4qKRC!byk56AukS#5XS_Tz&+OB`qEE9;(MH+%OI&|ak8 z#UbA#KfrPI`a8_(mXqAQVhd$%lb9HWx;keD$0<VcFwa0q;$4~bJF40I%>$2>e62Kv z-WnqB#y&rSaZ}b(M<iq~<eciAW%ICAk1Ww&mo%;*5G8&H6%W(|J>TPdqZ9Z%vh*gl zs8>`;Fa5Lu1=Y1C+cq_qQ>&nNbYJd2Isd`2iM3}FHBR8eestg0+AqomI!b)qe@A{_ z!dXezZCfN)kFibrW{1L?;szDf$PsJ;0{7o~RDi@ZBq<@7`03%jr#c!+Q4@qOidyeZ zx`@??)#pH8>phd}`%<bczSku2Zf*7q_GWPr_;#d(_9?3~BP@^2*2M4w!80zqdhPSC zOOp0KEYBt>45mrvWQc~S>kL~i{oH|xg>Co;IlWsq9UhC7T06P0t;T!0=|d+wImhT9 zP+n5Qw!gL{zoV+%m;ZXCqL>_BL#R2vBzUmK<loGi|0j|t{H{~kH$KUzq&*(hm?;g* z{uk9sA<yzu<mk&~qKNd+WDAX-%Eq7Pl@x@4nl(0saz3|CN9yatYvr83?sV0%u{XL> z#Ux}<iTkrbN-vliY9BiO)O(z}o>#n4*1F$a5b};)>U(IL;LoAbNt54^<%2w4xy#|M z{vTzZ3WNOB%CpVu?*VUiM_(S6M1)GbQt!UBeZs-tYEmYd_5HFYW3OjIB7-&`<V8`E zpVv{(TJBJY4`Ha2O)6hA8ma4<H_BE&x*l4Zx9A6mGKM2;{ywTM9&)369m|Ev+J<oL z3NS%T__ZsX(LuX+1IPWv5}tEwByUc?Q_!dZsC^axTu8Ex_9?t)x0?8QRDuA>X?uLM zY-IYI`d;N$!FT@SUK{XDFR@(r)0T|v7};~5c~FrOlWOpq^2yxUk)OfbNtCP|#Rch9 zls09Ee0I8J5#-7j$DpNp&4`Cf&@oe?eV5hv=uSh49h>wX#lY<1z#XYxsd>07rqcTh zh48{T_OeLZn8lNhnEE>__sRDA$c;>a!RTG8KM>2JImvZf3BM*}n{^=!r*Juu8;w5F z7?`K>aS-u%F)XxrC}Xh6;B@w0rbqDYf1rg_iBMW@=aSg&RyG4*-z+vOM0&<_<Hu{P zp3i4+hO{`|CL&VBrYrbdG`f)nBK@+<q_?Um!nrJSzo0NZx=C_={^h?FsCacbZ3F(1 z#CTtI31B&K=dqx1)8pHryzi}@+i@J;Dka~C){4xerDJ98UrIh2+ZWQvj4NhW_vgHI z2NA^gcLy&~>;3lM+}Q`)FW!lbgV?cNjwgoo%z1{2mufmM-n)2Z;2v;?P4qwYs-&QI zVvUpwpW5`gJvu{+25dZK|FQFK_tvscl2cMyJC7eE$MjT$di2!hNFx)7RI}v(xreg@ z0+li&L7JyBKa7AFwqH5qzjs>dCFb4BsjIf1JH)F_gHQgNsin94f!(B3juw2a_A}}W zBn#yfrz`e8(Ckjp28cRqclB5-Pjg5J?iE*pHbo5{xV@3XBYhxN(mV$?#%xX*eA-tZ z{qeXz8&<3c8)?R@9`agbXx3kgGuQc8NKhOz%N#DOYSf!~(EK;9{<A3|%5}_TprtDV zT0GjEmgKEB87nyLn9-uS$M7lDR(vt;LIZifu@RdxSSjoYz44TI6%#2a%8qIk@;!qY zY(nivKO|YGf3&De9^MEux89gjZN5uq-N~g(Yre>z_F<(Ke#`ci*u8Np(THtvsfN$| zVew_Vwi9#0_9@*nfATI*FI1tl?aH<tv(1?P-Jv{{&4iprf<m|1-nn6ZJu#83Z$lZ@ zk*{Aq)?US(cF7U)ee7el=E-=LBXM4j(9=Km#&No@>HFP7l{-DJt@hch`FEkdByXmY zVqosC5Z{Nmek-F%-M7MA>0*ug_lc8UUM^j0k3PpY{n%Qm1JI-;KQzu2oqnR-pSGMT zdDQTvW0{GzR=UlV?;9~M&Ar$X!lPZQP?6M99m^QS9H?dA4*G@kab6TBT0h*6&Qpl7 z7zm1#801KtEV1jUV1hUL#7SEH!mP0<$ESK)RzbHc(diH6UnQWfftj3AZ0M&y15QtH z3RflxJ@dKqLbK7d)niV|_QJp)UiHHkw!e4cPPRxn*b~S6CZ2C<dlU`m#4{Fl{}Z0N z;X{lsiyD74_d`$2yx{&ffZrb}dg?*V@K5@Q(L{)^<ZrtzHK^mQ;CF+PN#_U4_CpH` ziW)IV#;!Eu@m#ndEb_Wt!J{Ha@f|PjFaclNV3m?e0JE8~8=Y<;;`bvuRa%k+nT<HA zRsOQ~T5^AVo=R^@4#)B-NQ6x!M@K0~UbcJ<-o52jq#G5zYmwCXo5!3k-;f%W+eG${ zBW?p7QwEb~JA<AT$^Agu7(Qaj0ZVusAmgdT{=b?c9SCO<yw?7|fUQz%#X^u;YI^~) zs(wstfEE7JcgB>*_-~H;;miCT4Fc*#q4!lam*VQQie6LgkC*R=IvY*-wrh&$%>}u} z<Q7rIR)tbrzwwxVY>(?{PGL6#hv)41&5iDimWV^fk*1LIX=*;t?UbT(OzL}|MeY9g zy9NA!4KuUvJ{9|^1@G4uc=X3?w>?7mIQ;G|I2@{BwKDR#y0s>fxRk|yB)FV$`O1H8 zSr&R1OzvA=l+~C|O8vPgU$VVDce>-zJM4N-czjj#yxeL1Z|{iPk=#qR<8N1T%+(iC z>;Tok9~qdXGeA?&3|qM{D}MEwhN>x}p*`j_isbDJfx3xZyjo}hsimH31M-F0nuPV> z=3cAq^q4yKob?C~up?USP~8g|jd>_M;~R@nfv<jKucKNG0`f*$%o9{~=^$5?+7`}U zr_x0K^J*F`J|{euk?o5HK52)>(ptoZBf%w^X>wj?e@Kp+Z=|%OSn!GII#WBP172nQ zWZS1XbWvX49f^k~!~TMh?yh)(u3Rtyu(&wiA5rSt;uys4E3K<Tn>Y*#VtyBQPWE)$ zKIQ;v7*=6IApCeU!N8OHt^-cz)eqfz^4CTc1>vqieW;`+Rjr!mpi;@w;2E{#Ftq&5 zq01*l6tFc5?yO?E1f=}p+M;k#x8zsv5~4Zx6SK=|Cvo%2@_)NhlABDrO;7G%(mKq) zpzB;-f)Ep9D1nLtv@g!^4e&<BR8EgrM>fWpVbd}uXOsL}rzYmgj+dAZQcaEf$iZZg z@C&p+q%%!&db}x>f|LQV^+w>CBte1T=739RoiYjvCDxRox&_2>%4CJtNC<37{K4pY zElEBn$b9OPya~I4y(re7D0%2@FE|dpWHG`xE&rrketq$;8Isr2Uqi|7zE$}_hmZX+ z4;tO08!!%$?~x=?H@*_(ZoZSa+puc5HA0dR^69-*lBvuUfeVLkX1;YnSfO>i9f!J< zrzi;46R-dXcVZ=2;PXXUM!EKm>8GFwjg>Nv3M=`K8R+BJ>7Jcz1SLL(N9Ad`&bNU; zX9tCT|4uSv220euV|$@_sDKG>5iwKL06{-oMpu@l`cV~rkDeUq7M1z_vfa#|qGo_) zTWs&P{5!7YyL8EG&Aaf7Wq}`h+*=%w^+X~>IfE~XAFq&WC6%Xvd(`LN=)-<-QCTU< z0B@!+kSJ1<=#bf@@YD?Z(L8FU?7umw6CZp2!BMkyPUSLvwgoBNSy9*86dUjM{eia> z?B&KxZb`5Fz_3a0V^!qm$s#|xjDM&6VNlcmB}z70#s&liY(*u3Eagf-o{kf07MJ8% zLl&Zs>+zlwI3&MRxN<*DIUL)qAuJ^{nJ7NFX1>`J?N!--*Ib>8U<F%3iGVyj(hOfw zEPZn^oqcMkM6|}T<WDo}qJ63K?;pm2;^P=Vd6}!yphd&vb-`}sV^iaLB>FcQ{kxPK zMCP95KMgJwg!mwa0h~i=Vx5U!IzsF|U3vpwlCYtQdQe5Bs<Hp^`x-~;dz%S^I>isW z#DkV>yMa2>nhr_5?h9Schu%8EX2OMC4ls~280Y-TRP6b&0GcAf{m2(F?y^~}X_I@i zalk@?$0;RMU))D^N-C7Xb86MTI=t1V{ef)`zHGSv**wGMp5FkjTy({If_2ecLbX@P zl4!#zuZPIc-C5Rg2-2M|^M_>FJ=&3*H@%5+8jXRC1~olMZk?<Cp`6oWA@p6FoFhlg zW)+XBlWc6`D6EbO+4ik-f0iX<*MjEDB)=w>p0_xQq1b65&^M(Fu_>aPi$-lft|k1C zE)M)rzb`usls3z`F0^#kdJ}(XcUH)C^*Bjz3~wLqa!A;8^<DZ27d&4<P@SV{Z(%Zc zCl=NcB^{#_zb=X&ni`uS9VfI7dk@yb3YMNXD27P=)M=F%+4l%req;qv$gjlJtT?)d z=^WDbm6Cr&zjv1|x2?$z-60fgopK%OQUM0YmL_8KL(sF|Wu($YSuZi_;uNuOKLbBp zGX1w`o6{r7c|u-Y+NwQK6uxchJ*eu}EtK_u0R6y7pr@P{kaP99Bv&E*c1>RA3COoc zK5s*kBu&Bkx$@8?_?IQ6F6IbIOZK)5dP$k+SKblw5sln+-dg6CmMW<uc-<3x)4Ubz zw0l;^B{XJPc|K8L+*`G`TJB1ou;aS(G*G0GaL1-AUgg@^pV@F>3a?z>H=XqBT6D~C zf#P{2vfLD1*@Z-R;fmR#ewuMRFWYu_$2Rsgqy=C3bxL=tn-5_stYVQg9)Mog1bjUn z_<WU?0}57lQ5q9to>B6(emG2aEzWmoCM0UH`%op9PBddmSP9;eb*4tk1A#A3#5Xj& z230FDq|HwKl3i-B2Q3zTGxhq@MG=_r%(WXW&;@KQB#KI5grtCLxWvRxRG1Xp0}VIK zNB=7oRu&?8PGjaPbY_7{38wdqu>j*k$!?$oLM9GYfG+9M1Q2K!mK>X7WbD(?B=SQa ze;s&vTJr=#A0rhYDF6FV+LgjK^2GPIX%@^(BHB#`PQ~buAM910OV9>TNU7`~4)hWX zR-SlIjY&p(OO&IgbTiYxc!*NO(aU1(gkN(p=qXdjzL-P_%+2>uF>;fhwY$(Mt7}!J zCx0)Zu|=2~vQ>oCPq-BGrY~9!U0qkhr$jr$q8BMbTotg7{84&J0l$1FPMS=kPq|71 zc*$rA+R6-IHOUUY_z1m#5fSZ1b;5UqK-c4e=}|LKb}8K3bo7+BWb}Qx@kQGNGjY-- z)kstAUT@RQrxF#2M&?XIKtY(yJ2kHr3BR?9^9|UAlo<057<iYa!d@tM@`W|D<(4mR zd}97jpP1i~KYY6R$N)h$5FF7}#vA9!>!g0d2ba^OIb~{eXVLbeyXfTOWIm5f;aDw6 zACL@)?AsmQ(Iu<oC-_xCP7WYOH?4h)2CR7pO8Y?MTC-J)(P-0baWkTL_u?Mcgp!<< z$FanEH+~E3$|y7)%6lRrr7{|XX3frquN{fbcGRR)J{W>MG%<VB;(ez`xg7XR0xzQ* z(8-2d5=R4@#iiKBj}M@inpZ0Y?nEeGN0*n~9{!C%kcBQ{0Lq<yB1;n<d{Y19*%WR| z8W*Dtf9-JEo^zn1NA(UpqA_hik$<z$;D;sGF@Tao=~7^>qVVO-qG$WPAA0>T?WT|B z7G-`fI{WOM@_2*2lJ($Eh3&&KagUfBbk{c!8Y#t}#V*bDV+O;Pc5)4<Gml0Z6C{+r zDF0n72Ge-=DiRWx_=sgUIu~0uJmo=eG|ehIw+ma@mbm5tYV2lRsTZ4-<Q{<ld>$M< z)-uh`Nmbp+zJi75p%6z_yy?^6Vh@hA^Fx=4O$)U{u0BbyOrmUrD6Ppi_DBsMUO(F{ z-dL`4x>D|Ig(q6t<Ck3&T}1wOnOWVM8ns8fWJ%oFk8<7&Ey94X?4-$q?jCr|y4=8# zj3}7+;9>Vw>_;ZEP3#KCby5nwd`#i4#(!H@=#eGe*weAx*mRS~k0Rv(M`g^dMfnx5 z<_$CN%`!#l{0X^oiSDjvi;j-$*PCKhbW8ljewT&6#iaLFdR+#E=Dv0n@fkz1iLEdl zxt90h?9UA)N_k6*m9NW?n=PZ)-mms3$~68en2?{mUqmnYGFWJka361l=RVV|%eJfz zFE5ev4z`GO>-lhQnSIaO%vb84pEpL(%^VVv-r$-k<|O>?`#g1<t#88NY@zbBwvMdg z=edc;-O4^n7Je(&xGQDi1m6mXY8j2|onMx`b8z8TMR?UMEqw@mQGq*2L%<1y@3r_; zNtN09jS1U)>taCNjcQW7YyE2PcJaD@jPH3I$iHVW68(}M)@>RiO^7<`D(qNtNmzA% zxoXSdH1uiJKVdEK<=UrSJ#MMB(1b6sFTdPKXsVR{ax-B)_2v4d1g7KsdVa!2(Ou;% z-HqGEU#k+nzDU7+DEQiByxDqQ=u_0@i+`J4cSBpKb|4S{a|D6<0e}Ey2!Q99`w0U9 z;4A<bE@stO+C_!)DR~Vxmi45dq-{#9n#%jqg*1ca2Ae7dvV<n!{Orw@uX7cg>bzbz zSG~EV<~u|SWLqpK!bW|ad;R$SyL&h)LfodMW~{<0SLvM6k7^BF;rvh^o7TGb58NIH zZM&sU=BevGNfWnitDkus0LF>OX8X-P311$%V;dbrRt(b)du{uq;qxmpShGq~Ekmt~ z&Uf<su$$E9ex|hTT|0MDQE|Rz@ci)6mOtHB?V5yrN6W@>hwQ=mw;ipU8RZw=+_k@c zP&C^fwK>JO_~iTN&j04QPd{(peb|$A^1?`bz#i>I1&lfG>06Zi!PN2Ii1=dkhViRw ztal18^<%$%)GN3=a=uzf9i9bYp1Jw*KL#GMhHQLw^LnQ*WA`&z!ssHC8!lH<YH6~w zus}8Zy8}*)uon_d5(?5{iwAF@%4q0hp>hlOOVU!R!Wx;B?DueRDg6Z3iG?diyQMwc zShHj9CwzOo6sHeapd#g@NGsVE5@Y~e_3!a;(auzXndLki;GgdtmRD6^9NFS;s%OT& zT*!0BAy-(tETR`>2q7;Yb3fVd6S%pLKyaiQNd_GM^{HR3@!!HcDsM+>1wPzHm`n>D zk&`Q8Y7oX5LCv+`3OD0`>^u7CPBNH#e?va^^ywPs+a_Kj<Z=jm8nNtw1<MUp!Qnq! zW8UVIcQO_7R%oLE{vw4<1TV%@Su)sfEsr!p9hreS6-qlnca2FhxyJhoUmXmr+Nn6D zCF~N;U<HNaHi#(<GrhI9v(5cca1syrG4h7^Vqb^W@PcFe!R42SN-L_b;M*VZNEHNp zs~dVC*DuubNVv0#Yc_6^5WQAf3E^F7BDYu+V=HSd&xw)M9xHb!Rr5+Iq{u$rS{ir) zi%qA=M%E~dGVv0V3h!`#N{OR}NWW$#f#VKw+@>K2HG!88)#`D!RYIlw6~6A<?4|l~ z>o^OjXsVtdRtsoLlsJ_)D?a~qf!oTfn=YB|R-W<{sMbuE#C>I<Qxy8<9)2qkm3@=F zm?Zs-$gI9<ikfnnn7l0#JWH?b<9l!IcOPa2Fw=hj+;kggCuOSUq}NGeXFgsVNEg&w zA+bxVEkwL|3Z!*g0U|CqGQ{AnB^%9xn{bC+Lkrs9hm1{rQAMDgfS?13@Xzt;dCret z_j)e{m$z_O0l0Xc=h^?}Fj8&(jC=gddX&beGY*&Dd(&m03QjsUV_9t_q%Uxly9X7Y zAalHh!~wCr{B!6Gz+^f4TsT-0JKpILvXmH929`%rIv==a$;#}S2}xa4e59xnwQn|k z?4u=fSdm0Qblkcit_~+_PVRsMPQfD;;2Qw;1bCkcD|!qr!)c1FfOl?RY=R3M;JEAB zJ>N|KG^N;;agu7NxJPO)0De3aaB45^H=3y;=ZB!cagxI|sa9Iy=**LY7!dQ0QbDgF z$la-~J;lr*5eJ01bwXP($6c^(km{)EL_toE?Rps=SR(X-N#@Ygvc0C(NI3-xXHVQZ z12e*bQ~_3fV<?n@ZW&brgtEl)vSB*WaLqXqj=JT80J^QdhAeS=izTC5)riWQ0hR?` zVKJXJO{Ma$BtpZFqa6SMv`rn3QW#f?40lYS{iI&mAi*O^&@Dep1EWSW69Z=+tV{Oe z=%%$iY+?!SYa`T!Z2`fSjkXM0WaSyRIAYG#^gy8H>?DQyLa2t-DyP4hzyCMV@iHOW z<m_O;P&kiT`=nHcMg!5XnZ&nzK{+OcMkMhg%LhL{O<0F{9Rk^{!Y_q}2j;+{kLl56 zRMD?E7$;&M%@P|_RgAR7+Cc8X&!xsHBpasfbY9mdt%2Z*<Ny$f?PCChvv3KVBVKVC zKfQ>PS%IBH<4>6LJ4ufuK|ImRqQjj~fOWJ8sGluMvMbOVQqFlX#4H_1Pd4>=e2b#6 zEJ~TCh{%+4-b{ADG}Pb4B^Ns%p!{kF2y*>-PrGs4yv43i9HcXGtWXMieq;Gl@1v)6 zwy^<ltC&j4lx~wG3vJ461t*K`pqyN4lgWOAuajP)vfrTy4V)2R@p0mtF1AwcKwOx= zb`G1C0)wU#R1=M?LWybH!cK;iLFydFMn@JzJ-Bk7iAdpqZ7UXVkm=`_2QpJLR<J$) zxwPR{sebo~;>JiWk>|`@szfj2tt{P78YCI3)Y~<206(8DV7Pe0ig4u<PcnYL;{LaV z(=d1?<fX%Tfb&6}pOXWv;8#^n%P{`LyjneWP7bDMWePlRU$&r^S89P(;gfj4FqdIs zM1=`wpx-%Uh(MI#M6b&>RjaU!5j$DIqgSJfx3c(fN^%Bmsq?-)?YXx`?#$pt!Dhw< zZ9kocr>u*i$v<v)iCxlvC#=ZvugNP8&!&;*-6Za@opG7L1DQF5;f2hwh^OhoUI(H# z=v2`bH0)^oY>w%WR<-V1U!&{#wJ&x-!rXN&)c2btkb0}>=_guui#ps5ty;9;#Ppj4 zsp4m&U^Y@`@D=t@5`d%a7%RQyW3j}3QSF`ZVB@q#z-6}{GbaFuunjQ%GaG<&Y6b7# z1?(4bdc*PeFgi)6V(=o*=-u_eQb-^QbDZ?2z}XGALqC2*zij^X0$F}JNV@X#%WmCH zf$__f&5sLz{{8CWa|};LmV8F4{!HI0>(s2ow1cdF;z26e2^D2?tZ8$ui;d~Vg+fgZ zEYu=gc4V&rxgsg8M;(4w`Xa^Zx>UeW?8pE!S+TTCkN}SpFLkieh2z;@0P#=GjqLlF zEONXNv<es|kuslu`RX>%A>5{xq@du9a6+4DRpT}jDly9JVI8ySu}P|4CFsD<R#RU_ z`cBQ|!6`KZCdUSelfCNSf|2p>&!_G(?)!bCpN$jle95jmNrpQeK3kB#Fr#G%lcB%+ z`~EGOZR9crL8vk1m->8^2)MgfBkv@#Qu|}-*}sFvtQ%Vf?~YWaZ*X`jP?rf&zbF6P zHP`t5K3VI3+|PT5<Nw`Izn(>mfzvpysr%Y>qTRnf**lzm_wwhHcmI96&ib=}e8oB( zIP-7sHtX;F=cQRiQGlWsu-22tvaTFWNF2Rz#Cyr4X<MC{$X!W2JV6!!8i}vO+ryA* z@?=Cinb#Y+x<f|Rpw>v-AoWDSm_(t%M3MHyWA3NKVIo?HB88>MxKZR{C<=uXrFM$) zG)3i*BB6lVA(4ZBA$4M?I)h~WcB<ht)%cK#6QY@6X#_W#MGVcVkY>|PvpeQ~9@2<H zNsibgXSXERm?XEtB#-tauj!=ohe;%%WFKs@pIh?9nB;)M<e>KCkm+OSXYw)hGZLF} z#VsW|CMBjYC9XXsemW)LFoi5cr(o$cH+pgmonA;!Yo{}&>6xrUI#Vb$2b-GbmRb;# zT3DD`d>q`IPQ81WS}K%Qj!mm{ORJ7at0_#YYfr16PJ48i)+m(Tj7@KGOK*!wZ!b*m zXitAWo&NGLy;F$Mjb-$@G5TW|gN2NtcE<2DW8{!ADwHvf&6sq{n2O1mF3gy1&zPIe zm_N)|5X$5`29cpN*J3i)3p0hf5ML@Yl`kRxUgKX`&s5P(WW#VY1Ni)|fTH*T4a7`f zXXchw)}Iqu&_%@IAkQ)14B`L=?K%JfaFj4090jOlB92KI6}U_>y(~!WCDt+G2}eCt z;Mi(sa<KC>>>$7xCXh)0V_<OrI8ZH@jLRjm)KJffoCfZk?K`=+R1V3fYCBdab9a;` z7B!3F;B?P{G%-&W<p9Y!9Eu3n*!&7o{u46Cb3k4N|FM4q9={ArS%8I-A>rX*AQ1{u zhtr5aXk)M(87#~MT8<*{M<;h;^5EXwOK8*_4pp~<co?3atcZ9>=4dD_WE>&-b_$v7 zMFnV+JQ90>B21GA)@>}(B|$XQfKWA%y&A|4jWR<+6pu5^YKSsYA*d@Sc18lbj{Mho z3!I2NR6{N9a6c2~hN^SWg_#v(j%?wgb`+w3Trwn#=mUW*cS`y+AZ8@+WFT-V5D40h z0ixn`(YfRu2*kUjo;8X9y+$+&-&Xa>`VQdUnz_3`rh-jvAq5an7e`ws+=C1`O7%P{ zf(jDv=%BzX>;GY3qbfWtR$$al&r8-YYc(*42NqEZ3oC_W<ypuxE!xlsQ4s{~Y0mm< zv7L3~w~f2l7;4-#q>>U+X$V=;$X*GkkWvS0*;D{=V09AM3=K0B@iekwH{QrKsm;#o zgvXV_Jcv-QW2Rzb<uw32r<1)5X8{LhXH{l5u$N=fM687YmNQj5ZsptT_gHF3R%5wx z9P;`Tj!rc~Ybj?333^}ezF8yWG7)xl6xL3Fc$RvFm9lA<0;y_<dSVH))*z`Ac8v%# zXW<~`r4TP7)T0ze?}Xp+<M2|<i`jsoJWvE;E-1SU)P(>%t-3i@)gFklbVnYL@~&?n zfdK9$0C$rT_c8#vgQfl@B7dkM_jVraEj&18z4aovMt8WbGoeEr^{ymn5b4}a5vVg6 z(Mx<dWy8s8e9)!?c0#e=MzNF8aH1Oc8tL9(U}+ox=CS~>?0j^(6#74KTR8ijUJg%1 zlu7LAwIae3P1I@BF>VjaZH;=y#{@aly(z@Q$ExyotE}~?PxYxg<l9=<#AP+^@1?ha zJ6s2y$RC|ZiQsA=xts;yjzz&^na%RIVUB1h=>*iF6G9^+@<!RUS+?vo3*6s{$Ri>* z`eT!lNQ<c`_u>vRkROnZVow3U!buSA1xWtXqtj%t3kr4(1;`0!FDvC}8Et5Y&2ezg zIXb?->W$!R1Q3_$7+B|qX$t$(cG>oJ<R+5vhl?P}J<oiIe)a?g<Ywa7Z=OVvNf4Wz zFv0@F8V5h-ex_|Ab*7sR7TQmWwEPW6UJHIg_`|(|L*6z(t^k_WnB=o)i<D9bbnN)| zSht}N=RYE1j*9=a7y1}H^V!Vu5eW3Fgy^|v+w?NQiH&(RRoqQEz1NSKgU`Dk;KANm z;I2m4;`39B@!@~kcto2}!N~Aux2A1hd=!1M!+iRUh2s8<Mk&-?lmCrOQRnz-z|lJj zvmu{RyA5$+LSxlX?l|`ErRConU#&L2`d<3@+XC{qL|#;T@cfATgaP*&v-62a4p8mI z_@B1&>!=7KClr%Mn?bOIo;B|vd_HEQhqIkFp0Sr9WJ=mPucrl{<ZIM_qVl&}?Qgdr zPmh+}Z3s_~&U*Jwc;}1So-copivX@MwcgQD?i)<Du$}*->b}3>>cYN(Pr>LldK;b5 zMH!tLL=U338;RbA6ur(cdhbL=jUEIMkwou3h$PDBB9aUtA;G+!_xb7h3(neWU+e61 zuC=ev_jzhQDWdO279pwAq5%SE!1J^>(A}O3oy;G)J(--_@VJnF?;(zKYgBaX<gaM8 z(U2f8SbPBZDFf7&wbPx``6dGb9EBO@hxd*~u8xX&m+u&jxKsCI9LEwP$CCWUJ`*P! z=+1|?2wmSkmEYvM?u&Q)f!?IELgMEjWxWtzT$PH-(`UH<v0LAmQ4IhZ8UNAUUZHzq zNWV@$c_TRP%+X=W=mU)Cy;kWB#-qW$B%o|c`|upmuvRf+hI0Y>o!0|p2ct8WQ**te z;@;&QX4FJ8I;Ntr&%M*Dz0=(kncMWVLgDm?NxF$xasy6^)K>DvPcw?GWO?}J(pHL8 z0(Hhex{It?o5<-s)kz?VZf%aHz=#gE**o{;hGTrH(?{MzpnO-_D>P5ucbS7J%9)S+ z|L&*y^b51;k7{w<?ElC8<acV{j;uT}d;Lf2U5(>J8BvS+nelTwD0ykqhgACU@5!;? zG`dXR@jo&*XL}(7TjpNYtesyLcXk5>aES)E6lh7$o|b80kS|=(|6puNz>l7#dH#Rg z&!_WT-{)8SXp=Ad)>fAp8;5_((Ed=Sg_G0uPgK5Fp__mXMW|C5;fD~dWY$?jk$5tH z`r#ohnq(T<pDyT?f3rH0bZ^9HxB5yiwfgA1=$O1pjpl1^;Lc{lcR(}h0j~TOe6~c8 zY28{v1lOqh)#q03FSEwIO?_0KW9j0Lme+2)qRGBj6Q#R-D<=fHK9$uqt&T7wia=a@ z*c_PwAx!2US)I(<2NUX_><brw4~Ty>KeYO`h+i7<CbS^eQdX})yX;A3Hoy+y^#+vc zRcz+3&;b!w&CsuJ8k-aN$~OMK-MC!axW3u|@Zc||GsfrvxTkbJ&C`BSW3Q6wg5LJA zrM?bzsKs9mruB8l#)5H>@GvckG$ZPa$wr>i+FXZMI^wi=6S{b=%$dfwlzdC>*|B6n z8?brGo35IzZMn+3ZMF4njq7bK+MOzuEJ^kqy_xNuP*c)%I_JYhc3@+O_`7gOyQUh| zQ<vR3D1{z@<SxF>sBe|~n)ZD|h&5T0$01FK5iK5HxaHDj8qIOh*HCpuS?$v+5tkJl zIb|V=k6ho6zTS^r&mN!LVPV+S{WqvYJf|LQJy<}ITcF4sV#%Hy4xJj&0M}?2=4dZm z27lt|HUOJ!oU3G9fKK+zvYQ}Zcz(OqwlD+b#rcwz=$CfqWr3q57xiz$67*HAJ2Y+O zZ<6~cBHyjk&w-q%0_Gr(VxQlQEWv2G_u+0H^q!d2rl?Q58#{XeefNVvv!O-n?R4|i zINMP?xM#vCa8W272Y#zMfcE}o$aVmh%DPA&_{E05GoN9*TI2uY!_Q>&Wmc^Oj2w&m zfN3T9(F>_-r6{AXTAEuSqGsW6I$#vtI)UbrKzJTNU;4IC<{hVv@d4O%Uo^;6q-kG2 zsaN#b3G8R)by7|{DqBMAq>ae=OCqzkt@PHCOf8(P31&~X)=KfbkD^SATvq1k^DuI- zG`V_npAaXY+y9-Q)Z7it3DQ1ezpH>qegU6hAT|_91Ww&e`u6TkRuhy;)u7z{Ma_>4 zdU_`YKDFLf<!O%k?DoE*CIF3RL+x5C)x_K%OzelCtfNR7a=aEz;_S*tKXmr=%I4hr zfB(E+7t<}pQtdDH%LOt#9V!44468UsjmZzZOX+u$sVZAnE9df)l1C|nE+qRi9@6DX zdsAh8q8_HFZ1$$8%z{k*CG*9H_|TKaY0)f}tN`cQKKYEF%&lzzXbFIJYrS`JGr_lt z=zy_Q4Y<GT6$QY#`f?(s-}GRg#<jdMmMSz0Xh$Gp#(}js%Jy~kA?8J)$^GB&?$B!! z1O14*#rYftR70<G0sT}TwH))B9*nz@>X31<8}C%y%4X~gIXl0~4Y^x261X`K1-1!X zR}0<+k@R6_%U<V7I=#cN-`g`TQSe_MD!#XGTCVQjekzu`WF!FWDN|##{Ay8a@>C;% zV`*2s!K(Qk<>7>tg!wSRR?K6PMH&GsxHTw5DK74qeo8WDAr!D$|H6KpQs&X~<=m#r zzuZEGt)h+~QWj*I?;I2nNY?M-h0rgT2y9Pdgtrzer~lY_d<ma%9?!Qhd8YT&Ug1NG z>7A#&#};N>#j8X@^T<<&KLLv|QU9Dc8uLY&tMod3m>Xm&s4*#>H@|*fu^cj<a90df z<E%}bE~)T2<?*@Rt{7h&-?knl-}jf~vQphk=ljh^888++cQ0!1vh#9QD28mOSqn@j zA)~c;;6;(4L64C^PzWqG3{c+P@_laY*8dY^h|>PSOi#hNODgz4OgInL@P;2C1wswf ziGtw$G!3zhV$9|i1~o#~p%t?^W)cj#v}_q;uH>8r9h>RqY;8k~e-DwgH<y1RzCMfo z+cwG*iZ7NimK_yjdLA^PbK6A0-J-@sX=8Ex#b#*#HVwW1MdL)=#K|@bzbR-(P#vV6 zoXUZN8xWb_%S}zfw{6+!Slfn9?vqP)jPa9E`L*I{^iExd=>C#(h$@>S7-|fy8`LtG zt?d7j)h#SncUn7yfl_Lh19m%Y)>{UARLdl81>{i?2IK%X_J|fXqq<g*c_AQ7+)UEG zXL#Ox1z`kz;74IZtNyzcanH1Q1xYJO#z!vcxY{X{XXaPm?i{h(;cNBA-dpUM)ZM=e zHgS;J$0;1E<N$_vR*w~VD&CpohFmYP+IF`VH3K(yCxcElai1*LT3;}^5CBz5k;;%y zlM-jZn?=y3yF-y`DG~Pd?a4&=pJtnlhNG%OEBjF8`bjBp0NlHVN)VAOTGsNT+NrSi z#{Dde{v|2>)(>IIY@RVpIa6qvJd?y!W?L<!3DU)M0oW)K=zn8EwMn^9fVixr$|mJJ zX9W9<;nPO7WUGPgN8@Ex?@2!RjPe#5(iC!FdxPUQhAx*%E>nbVW&Y7mE%1+_YGURN zqu8AlEQ%eZQ|^XukqZ~$evq-YLj^+&_0HTEVD}Pc*2^92Izz3J@2rPfWBkPq3OdS` zg1<f=70W5SMwWzspCqCEw(<8fhp<&QOc=61vL$pixbFU*&AbVoOi3fhR*}fg!J&-? zl;esD4TP2oy5d=x(hPL(_sos>pJZnO8N4FsFkHJJLS{XwzBc`kOOafmatTU`$U^$M zk8=W<q?eU-GyQ;JHqPQ1e*lEY;rcm#XJI%{K>8>Y@|K4d#y5FD=*yN}(z$Lgpm%`T zibCroudY{!G25h}dtTftE{EEh0nOOq#=_UpPqUz-Ts1b3gK<I2c8QRN(d*_($kGc; z;pn`n01Q5JDq1q40OweQg>&W0E$uNYk@0*MQe}MvORyLnQn1R+B0t2$+j5g4R;X46 z4d?^X+RGrAtwoa9v|Up$4T8q!39N-#a!O4}rhr3Nee14;{KQjd2_i_Nup=2ZR{XKo zlv&z*#mzw^J3)fylu@XoO+^7f@*adr&7IS>mzJ%pbUdTv+9Zc55kXV8h0hHGo_r`} z&l6hiu%1-p+lTL~i4>H1J<VOz%20xnO1W)PI(F~SizJ&17LQ7&*VG~!>c~iK*kfa& zKHwm_UW1IU=cq2c!Uh@{72=W$#SHmr4ZREm7ZR~tO~))9gw#D33sOxIT)FO|tqj^* zE4gimizw=aa96ok(vn<}v}&6e?ZH~km<<y*u{P?szu;!ZkLit_nRS$-GFZ7+_uRaC z<nrFV2J58;#&Bj<WwuyFg;|&rv%3*(T&g=MUZJu(Vbld$V_t_~Va!cXKqjNJwSURC zk!vXv=4%d|mR`h=`dRj{&Qy#sNAl%+$P^AwMV7Qn<2gu)G+D6)mO{q`+E2F(PP}aD z=eF1{WDHz%RqYpGx{VIZ&q^=bEwUF7#mY`r4Jhp-D)}vCGkG_=*Ra&wg?NVeECa{K zrEN7N?H!}K0l^83lVwfvfFAg`*}w57bNm3KQR~1PouHwHI{B6ccs<VggUxQi$KJ~6 zL+_V{rtqs{AI>+QPn`KEtKVru(BzY%>whVKTGTWfQ2#VYBUC<Laf`o#2gWmB+MKyb znU{P!Gz)+8IyViWmKO@-fihG2gnwlIH#~v8^A}T$`7T@^nh5{R@qzT!%5du<mFu9g zX^T%rG0D3GR|n9tvXwDugy@JQ+>x09qE*wk`dLzn*p>u4ny+qvSDH9i&^)XQ75Wqr zRM6=-<}*<=;`o?C%0ijR;az-WWoTxeeYRcj2uYZT-HDMzfA8kR(0@B?!R2R;!(>%m zLU+t&_D)ak*-fQNc-|WGE%<|{P4Oz0u5UERf1Ddr{b06mq~kY!(Nna1h{ZtL$21l# zG#l3jdIL6R7`(%@Ek7${>J`j*pRseu{qypx@^up@^F1riv@q_x7eyNil+4uqjJ;Ve zOb34Z!sn`KfvwvlZArd9Hmcq|%aoxM2{zAkLT|l-rqW!>WKH~iFu$x9($mOh^u`iM zi@XXp?eSq9z*nj}g(c{t8C?!7v3-YRp?$f(g^BN12N+lS6B<_^{3w_MIp*nWvs4SF zIR6vW1oj;~B6$~-@yqajbbkVGS)c1g0ej8+a)Sixgf^w3%=U0|!MmcLf=WJKT8F=8 zk(QvA5d8f>bo_M@rR7}mrS<CGojW~!W#0}D{wB<=C-k(}=M;pPBgn1kGo^FiJ#L|+ zzT<t5){S$D>HQo+xj7U`xjdKB(e(0LAodNWy;=F*jTO6a8r=J7ky7*tbsD18zrpt? z_kP(B=SX_Q7V`#^cX0RzI0b_^$-Tu}68&A7f1OPOUWU$uyc?R2<h*%_xqACdPpSyN zj5?H5Qg!n4GrJZE2wLO_>fJUjAAP%DpTh?~AoAOW2lb+LpAK2CY&m(ypl$V7x8HY& z?GbG$${%V*wY*AZ&JdD{`0y>X%(1Jd%Jycg;*Ze>@!n^^D{Kn4e$;Q?HH3@gE-EC3 z&+p@gkUa&*+fH#3Zd~PoQ*LefHrau8@9*1vRol%6hgARNCc6Y_m7}#>l3xqvNWPv2 zUXqhOfBA-Pkm^P)40mY*-|A1lnVTD+Xr<I>s}R}}=eMtWrA7~Wa?A_ODY6w!yxj(& zT<B-m>93+<$;;`<P1P#@)k%@Y>d6p)i|y4HdloSSMZRbsPu{?9qkcwA@@@sYk^VrC z5!HK9vH($zh@t`6Rk#_W1iN?>Ax_gu<~cEB9>E7-6#zj3*dQYm+HylkR`LEp0~+}$ zHS9_HHm<mR3^dyhLCIi8vfrsa7$SYs^ifW(>R!s<!LEPX#c`ovjxn&8Z4K%?Q>slq zo^eo5aF_&1>oJiI+o=@&oOMwo2^&KP^kGp@thvOngK=x{7OUQv2=pjj{*q^a|2dWt z;C&7W#gV{P&=izd@4;bDlBTbW1=Xm^uWl*S{bGhq^uA3ZsBUZs0Q*3PG?g41Y?h^p z8F@q^VW381<=EYcN{$3T0tpbeF_3T(Ddk_X;8?LomZLGoJ$y|m6?oEsvHnOG3RD&( zx^)y*ln`=`4FqUc0mo8K8;KOFG=@!-=I2e}MJ0fnc25x`wDpcKjy#MWBGWII`d~aD z_?7;HQE)#;Grr7$4H9$AIB^UKKTo9KPgEe!iz$N46GjW<4YhkP&O=!$rCAk(mfd7h zXZVP;GKaYuMHnG51^_|W#v=icGypbIKe<wEqCFC--Y(W0I#Dr4R%B0MW}G}dshtyx zZLW^jts@KV#<osrzdSXPG!$B7VtQvr>OF>~bHtHZ7$3!nr2|IQx{XkCMmk4#94;p( z%Xp&h<u*~omYzaFZMjAmOy)YU`E%qkt&_R{NQ~Avz*ch#Gd&t6?$Dp@Kwd{WFg?6z z5;K=W(F3^|7A5-N4PV?c%*Q||Q>J(PWL??o0BqB-VWtfjY!DkHEDIaHGSPB55krn; zzBlvJQARpDxlF#~MDT8e*^P1uL2=EzC>s_fnLSr~aZr7CB(6UA!E6ggKbjmenKw(+ z$(6mwF;7zTw|YV<SwD1a78yGhc5Vnrm?QP&0yCQg7GW<fO(L?e*W|<GXLCE1W+Qxc z8;@>^1v5q+8^H!aozJnTOM#m2zS~L*yk!bw!vwaP-n95XKAPw0gfToeWneaut}q?F zOw{s<SG=*fDX}4hc@a{H>WbOni^N$B#BvOTEyG1!>JTvt(k69leo)H4Q$eBFZ$k?( zC>b&291?sm9z70`$-h_3xUjEd@(_;&^jQeiK*JuHw3mI*a<5s|GUYa=2qj?Y9+|k= z#w)O40=gktI*X)?i-u>l^!eC;q<faO7$I^JyTu8B43?I8_@ra;UJVae-7++EvTQ0z zhZ~|FI~?G$5JG_5(_M087Tgw`3zxx07Ga}qLEc<0a*>!um@O6pES=n!8;Tdorm#2V znx!_cbWW1GG8w5=5-)dG+J8Bad+zTo2=gz!F!E6)T>M=e6yFO)J^naRKMU=g?YW$e zfhMZi#@qK{V?-e={vSg~Z5t`(p;6eTDM-W=$f5{B+5VQOzZ{!j`!&uqS_ncUL#$}T zCZ@W~C+)6GTx8BJYM)AA197<faC0?WqD{hB=Fv)le-T(cIam}cZGM-s5+h^_GMr0_ z)?I8nwJs$6tiW#ZpcyNDfeo5Va;-^J@&Y}5n-r+E=zo*hQe!XgjiYFgkDN<NwY7i5 zN0yoe(RpmT)AYGLA!{F#Y^F8`V}kg1LlTWg6p|8y`jR{(M2i%@^h)MR+ff|KLjrqm zYM2z}6|c)ycP(RDY-{k=eHFz1aof=x-Au-ohDk{OG)ryb>9;z)mY#2G^+V0Hc?u0c zfn5%ULdN=sc2}3CX;>VVDwFl2yP<C6kaQ=<<zc7w*qPX3td1@zQQQ`67;D+QI=`ym zyoQ@4qNc?C(L&Ih9VU+kKu(7sVoR&r!|UZxGxJNvZ`IH@9m_Fw*tdcc;^2iN-3=VM z?yMC>K4AoaOEe7yKdML!KTiwlmTOX{u!vH%H`*XUW9dj7a|B8F=t+EV&`79V<yy{{ zs}0B=#e?sVPy$(-5Jn;tWHAPb62wMl*+HV;u*cy~7^kcJEn)~{Zdx{KE@YWpkm62@ z{Ua5IE}jMM%@d2M*ked?HPr0@BQyp!>Ba^F)_|YZo9`6?^wGIqGn}+dW|7lB&d4$^ zv3Kzkx<#bXD`uz_@n@aRB@e+hkG4+u9kk@I(XIaxNox|dY|#o(vh+UFo@wnh3<Xc8 zg8Cd<kQ{KE>;8QFR-=FNgHA|w)R!2o1O=3{J?Ug2<6ZieuBwCkk^&BG5|Ej!8`*Z% zXDuNJk9`|iFS4pVtVUtprSPvl!!u=PK4o&cD*3-Nt#lk2+7_%YqZfTn_I3awzP2XN z)mf{JE});Yw3gX<U{(D+F&v|<J!VANfOi;v0Ai;vSi2p~v}gPakE+8{^tgz?N$)?f z(5boaK()u;u&187mtBJkFxwnAON=0lq3VzeelEVgOh@9L>d4J(OueZWoz4nrX5J{c z`JVIg?YuYplD_H2LR&Gm+X{VPOEzbez5%hQ@~%312tCpvRk0Yn@;Oo~K@kT+m?au1 z+RWE^rSZ774`YKx?E|wQkz-gNC`LGoFF|mFo7B@hagS77JVMW#Rp1MWX>zdE7<0mX zOT3}l0SWhMqKe>`;YTJ~v=YhnBI@NS&-9ccvh0Gou?bfY#28rk9P^ra0(PYpw`X<d zU4vehLK9iH6FWAKiz1=}1Y03_@teGk<wM^>+1GBbS2Ks^r%6BGew4t0J-pJp1N1tq z#@|zNIJ#gC7L5B$U*#P@DyAk3?<bZHqjl%VvsN>uW!)BZzKy?jwq9V<sP%h{o}`oi z@1O=}N>0Kz7VlmJi6ks7byzrQd?hxtXDyL+7kw7LFMK3HuyoTmH(vH%*Vrf?&`2W* zh(%6CLb0eh@-SSYwiifz4DB_h%}ir7JU;H^oKhcE7D)wA#*<#3d_AD;J`l%-wf>0c zd*BAeeELcv`OZI-<!43bx^zo&P#2dJ0qh*B{^v)xM*6*ayX34@d!I4zjX!=jRzLfk zOqnN(l>gp(q(}W%R1ur5_##iO4x#!RB$ys6wucSJVIus{PFncWMvE9Wn_s%Vy-u3W zec}*_<BTghRI62@Fxh8ov^_z8-%k(2H4V*oEiU3m|2R(K&I&8CrmQ5h3<a}){sbV0 z1SM%aOxll&w*4>dBx!ep2+-OND1xNUCFtV5BfVVnvJS4h1{W;L0NrrAZPf#*UyizW z1ZFIaqakiC_xG2Qehz;vPoInoz2{C*0{;0BSA+Xc;X^Yig#5pF37144+Zyezw|TK* z{_w=zV;bhPM-7sYTR+Kuz6}=k0*h-Uv|M8cBQ|5|$TkGpbyOY~(&!d*yZ1F?eQ+4H zzBt`;l2F^R@N+W9v9_Ftt>f#DGbHam%(8ok!UD#~Ljb-U^q6}%oCBf8QuItC^*8Qj z@sA)5SBWfvAYm^|i<aW{3Tv=*h$YsZlm_4yOCqNdKPE-?^dXZE<8%3@Ke)FK{eF^l zbhELg!PN-~uAHRAAl^6enJWtq+~Vcra)7L|s!43EAVg~d_AZ?29z5RnU5nh~l#fdq zNnMnsh3UMc|Lk*=T1gzd$ofLr8qfXDEiOW8I)98&wbiK@nI$FNOT7fp{wUEbJG=<A zLd&5j{y{Y!GExlzd}-!@CA>-dIC$HKhT7RBeE`NYH_oV=)SbWFilHn^I!R^%AjpPk zfhwikd(jV$Flq*d9;Vs^F;f}AEGyX^=o3I)KsJ|~MW$X@<n>5vGrW(u=n%cJ^x5Gg zygdhTMVdSM`G>(QhOKcEs_{lHyfy|2Fz;Te2HDY=NP=KnZeN|PLv@|!o4(>qGXfZq z6qodigt#r9_@h-Lfoh~5)U|}27NU*S^@3HRD3oK94`E!;Afz}wh^jSSDK_C$ta4tt z*=mqMQy@AulH)63Bg8w|4xXHo0$#x~98&_igo~Yf;E2#TSr{G4RoK#=ht^WeMY%m0 zL~hp(qL=U@KnF0Cta5$_1iqmpMiGmq|8+l=f{zZ41;(=YHT9@uwxM}|X6H5zX1tX+ zx*N2*@HiP?0YG)rt8EGPF-QVWp(TPo!a{7y77y6nDQw!TEv(G*CsOjoZERkV;S3*( zH)gwy=1BVfmiXM^^ReCko1)fhz{ah2;R>xd%lIbe`f!C`ILY`ldLX~85FmpHFfD7H zA3QKApyp`m6|<$baVltf=l0mj#%H~yVLeC6|F8VvVuQ^~jeoPN@8f$Z-%+CSVTjdE z|Btk9{=G0X2TB;YS;7H@GP*gI$!&275ano&WX8vn(k(}iUxt6z;0XCf*c#214!l+i z#}LR5gW0u~zt7XWT<|m?L;z-syg3~)`t;f+UMM6ZT#zA_m&DF3Srp{{$Hi%V+><`^ zt6eBxBD+sFU)VRkNBKxQ2EjRP2X~=4D~s`9BS3d+k`3S`N#7WU@0gZ0jSh<84zuGJ zAGbid415AD36tl;8o*u)=9;K{GE;8*WKEyMkZeoudHOo|S>*ZJ{zNJfNEk2@Eg*LV zQw!Vzx^M-t0f*hJEcu@DQrXKH+V;8MF{2^*%Fq`?k#Hthk-!lyTFE#3*vyI1s)#pg zO?Rcxsa-ytH@`V)%LXtkvo*@8IFtq9EGNMy2caxC6PXPA>=IZ|mj-5{z(xDHpj2i{ zG<6PM&a1MYQdOdDxZJ}{v}@I3O1z%LMVAG(l9eD>=z>m@?64ge;~x#`*KIUK@mbOs z9+2Dt7>dS?@x`Bp8OTbe%TfNPzqgm)c5(Pd`u&5Ym-hK2OM5wz<NWv1MC*34!PJW6 zZ8*s#$7O!W3di8&peT9<0E3=i?=g-1+|5;35w3O@*=hX3ge0-5I%lGWjC56cTH#CN zZRFWv?rc(K59w#aXK{*#?Oo@=?0lHMENvD9HR6%1`7p-L1?V>q=}{pi=<)dC%?4>? z`sPkQROn0_8QZx3p2&y4xl&vm`Fx*Fd!~}iI^S|>*iige%0kM#Ia3annc1-w%S?A- zktS(+s@(W2{xU9rhLDj1*-R8L9djQh@TZ7_D#-m-Yf7WTa~;Y>PW!5o+PfvYa5=gx zirukbKD2!BigxTJ#f4F`jz5+3%May1MzmQlyVQVP59i^$k*4|?OEXOeVHmSzNr{kX z(+22zIc4z#(+h%4s$4WLcM;^9V02+;W%$|Iml&cQ@u5hVn@7JdY)QOQ@m7497MUJ& zY(&i(4e!MS#@yre0wu|F*11rmX>pzsp7+xPqxcDgtZPtKCMt=aMFV-)T8dQO9J9q@ zMWsdKK|iQb{D909uY1J8+WBtUD5@fha)7M=)|7DrT2GCik>;eIE(Pt`5o$mtX(`kR z%z{eW5Ao5)4I>YL^s%8xYCjjCIQ0NsxJ;?E-@LLTjs`Xi)!8~h^aw7rWpH(T%#nMT z{{~w9u!WP9=aCFXpt_GN(Gn=c#!#&%+Rl&{t0jPPrBeIUmQ$eSME<Q!G<s9at|C@< zu~L!JFe`@<8VjTy67J&K!J86Gw}tMDO%h8ITEz!Icm01CbZMsWKk151;6#RX)fwkV zpOpy7<<?Jq=y1C&oy|_iC(3+w^*!#FkB3)5{j`5@u7rKgC+pVnSGUe+BDRi%RX)_u zWX0<8i7gnXxV)YTTX<Q{_K9lF!(%q;<mI#LOA#%wVfGWs4jh@fD1xbBE<vuNf;LK2 zM*udTY|&B4@>W#ucEfyna7Pu-m8d=vwve6EQ7x=4W_Yh*A-}z&Mk-3o_&)4I@j^$f z;#)D(hYcT|o^(9dxDqo%!xk$TJL~k+VHUX!i#2kc^`=oU%PQDXy+vn(^;?+r%Z8=q z;Lb+pE12ydY`HC`v&lnU-2Owua%VfSvpFD2+;JQB@%2Jy%aga_&c7NyzCG!D5q%}@ z0v2ECXY6WCRF`o3)2Txzq*#}lUaC2=NgJJ2#j{0^)x13J2gq2fm3}|)WEKBBQ>p7o z0=#2*=bs%KgAN!j`J#EvkP+jB<h+<moY|{&h*0a2Z(x?xL%u2B2!4`GV&|`qxXF>5 z66iX?IY{1ytxjt!caw}CX<jm{=}b>^t)64$=CU)qQAp0!gFEVbiuNBaf1~$eO&qV= z))Gu#z5OOR8L;1<858M7vs(mF-)l7g7r??>ygQ<}GDjUl0^mKTU)KD4)7Lzzy7kQ# ztFp+KA$r{PHlXci#QjDZhTuUS;#KHR2KKT~Q(Xyt4Z4$Rhi!>k^p$dJS&UxkUz{QT zwz<Fb=}=L}Wro0QZ40lks#^23$(#4tcXkuuQxy(dUA7$$zd`)pze$T)E#RbPkvU`I z%8-3o^G@nVvo<1WE48<fcjNpHr;2Pw2;P+y2!*J7h>i{(jYSHL7|IOjX@M)ARv4 zo;?0nO<(YbyQX_YvpbtE1O>kJFX=R#>&UGm&H622u2{MHnCfw?8^;+TxbmCLWYCae z7q7<c{E#o1(K`YYd#(B*#o}}^W_%oNHDpZJe3@ZQ>{DE;4}-=}woJbuJzwr6DqYV} zMQUx+P0O^R)2I0$#8mG7EMl|zrFmvds{s2RIYiC6DS!nMyXIl{r^jhJ{YflHiikQ< z>gMz2vXSmGPf28~g(k&Nvq};)-~;TDSu1-2yg$cAHOG!K0Np+OC+85@vKbvJbelH< zM}iX%7{`b^N(lZZt9@PZH3U^fUnGN71>uqq`1_pAdm*{&s$X1CpSXA>UTDJF=tA?9 zy80w<qY6c9VvNySKhDYE#{INr8-Js(LvQo^#%Cx*Zq0<5rec+xvR<E^^H#fzbdQ<` zCqMYTg^nH4?31MnHmjl_vSGc&U$4ibqq?I4WHc7iX}qxlbGf*S(vR!ao<@H;YVhn0 zXX$iL@<6<MHKi-We1G?dA#1MH*gH9E478&A_j%uUKh|hy`Ti;!%|!$}dD1_R35gVV z3$%^W8w&Uj)BA_#Pu5jkPf%tMz?okKjMXgCqKTfXYJbd&{r27b!N2dny9tCxE9w}> zOhKp4l54zXWIq}2i|6cqePqgVssE^wZ8@)tMugj&?0)rBapyxvcmKs*J@|9=YP}ho z^OPgc;B(dZ#>#7!!ztwGI1tv0R_YxbRmN?_VT!Fj7V{1H&D*L|Bba-^<<0+TPYtT2 zp^wI&s&(*a;QK|$zo@O=ZJAC-zh(WM@YK%C=1&xT<^}p92&{O@rs&eI<ib+nSd8&T zU%dv`cn>xe6VdQ)u!i8E$_`R_>T`g3vHrOoR@Pjj2`P7pREFEmOCse~3lxV~$WM&O zU-PuSMXzom*Ot)AG8@cKmT6cpD_^biioi^<U>~t(YGZ@JaZvT%Py9#ynxWv>$6QeA z0X_|zv!msRI9K|uL28RnzoUkH7}z|cJ_?EsJY^WlbOkB(qBS3If?&zYY4jgVz&Wy; z@W?F9gD)Dfh%x3u<_t`f6TANv_!j@C;IE|zRtVL+k4;OnrBP+96NBj&K*7bq)@0JA zdMx$=tWH2`bO2?O!0;XL&A2z**ab;IKHTh==mp0n<29#1Jm-VAE&hAC=IF;@hu7T} z3MM|o3UQ)02f6y<)wB53@MyWIensQe)7@234L;RX7PX!d)gpvyFB0bbu|J!1oI&T1 zk6pAIseX#|kgZU?L@PXUh0B+XJ<SllLdvf=!4K>K^vG5|Hv_$)@U+3Aw}aw5Is=`Y z6Pr6aDP|g%t~Zms@Kvxf4#cwqhFh}e3|T8!Bbj26xGOaIZ$5=fS7W_Q_G|Rat$6NG zkkTSjjANze>yBy9mpiScJqFd<Tq|lT{T=QsYCD5cm;GAT+h}D9raiP$ENC+9)7fJ- zCBG`+RyY6Y&+1!S>dOVHM`*DuSHM&WhE(gdLdE`5*Y~zUu(3Gs%$nLcShj;0XW50< zImp!1F=$)@3niM#^9)J8vxCYDz{ilI3jMde+{2$%BBo4~^&OcogWo@aH3?uJ1)#zT z+H3i4_B0DW3Gm_H_}P4<vc#9v1PqO-$R`ChnU#Lg+EPuwK}G#9S<KZrk9Pe02UNPj za8Xyy*#D}7kO0dSnV#p8rXuo;HesKTLaku`&4QV-68|`m{5e`&Z+2A_uPFnRB`;N@ zA1ZAI!d9QUvtTqY2c_yJ`Mef{Kk-EgW3cmJ^;mRTMZEGDSe>3zkP9*7UWb%t6=LIG zzcK;<_=WJ=06`&T=zbPO3HK0-#HIFX)PJOv?7}|JGK4UiJ7D=%qPCOAvLYVLc?$AK z-cO|Gn=3{rX5p0c2L0E0WUi6?Ln7LMuk+J<FNX`>bt1(&(5jB>dcTojuLtENkS=<k z0!wBh#`ofc4_c?Em3Gi*glK>UMmP=}{|=2N>mxte@Uh=W4f9%U1}a>B4A?_UnE^GS z{5piMnt0$?+=2fDQe&!4b4B#5&n1IrT{9A_xT<~I51cxEKg+&QeP(|?+sQF_K+pv& z7QdzWh#zNApD6RWSNXwzzgcA7A>|&R)zjFTGsGSXb8Ao0G`69|y4jgp?s$Z)YtA_U zcAkCR;efkv@r+q3<6SlA!OTNXuiKt#b~}$;m8`{~u?<9zY(-2|n3o0@lBo!6TmVjL z(N>i5(%}*iYIXJD@O*e?uhGGCwu4th4RXmNH-pe3P*7zQZ`BWO?_HjtGnUK?Hcl<1 zMm1+9Y3%tGx-ro`hrYt!{F|zoee&ZX?L4$HYO}gxCC|T3Z|Ly*Tbn#VbhKWvdM_)J zLWMHmyT7?BZo!yb+q2uF%(-^`*%CMW)cdKke~FlV+V$YGCuNlFxHH%C8J`2UUHflW zgJMU(_cMb50r#0m{LX}iPMubHa0o!}K?J)OlMY&Wr(n5cW^@lNa%({AudVdluIh?A zv*Gim;HHgFHnfU^TqtXg;}y-*0j@_PcR;?0p+uW0puc8hg>8Fj5{<9w>7e`W;CR^3 zxJg~!X?+a?*P!;QFA9BgNH4A}qZJ%ihgfd7SNQo?bPjl5R!BW<kmCTPc2KAzv!Qt~ zz~Oi}-0!SV>-gkM5Rv8R$1WOwjZ~=R@naLR*n5f?D)`m&pkd(P_mfo)F0`_x!2W<q z_LTsC=z!Lf=julS{R&+6uvOcV8og8Lfdp^-nGavupkmgM8m+T*-r&%&6t<}TJ6UW^ ze&I&+@=LLb9H#>KgLS>`A`&7v5>cENW!B<q_xcK~>A3ug*1zC-@LrB|r4&@~9IXV{ z+K|G??bXNs7L&_CL&O=f3z~zTa52jektvKryr5F$v9%!Kp;cR<)}=uj0hi?RZ$>AB zB^4RFii6x!NID;DfH4AKyKIv4eVbD3&XKeBtzuv)asuHAIJf0PA^hr^azfWtJJ3j$ zwX>Xnh=IW>Qb3-$<F{av)M1B41|9#aL6y9C<suuudI!HE8&yFBpzp|P%UHd8ou4Eg z-m|VLzp6F{R*M|qfp4p6p)L%Q-)!|`Q=pCJ12<WvN?AL+xiv&nXm4kUy5s7biAIHM zK}~vOueJ2>@t30lxtR2Ct((Cj`@TK2U#8zqBRHI1{1x>`E*)?0AK47HKa}fr9fB9W z9JmO`2p`~GbllZo<Ni31&O&^aXj!(ui)PE&6#OZuEwibqHF#q>hiN<NCXx&k*DLmc zFLg`cP&|JjD?%C_62&^RWISxQ3*8|xPQ<HW#F-+I$@bF7A(lpM|54Ju=D0x)9i&Fu z7l5XY^ftJWW&nDM>^2;4RlX@ju-t8uKZjqLp6$q*0hy_qPUTnqJ^>|2V&Ow91s4Nc z)l%QB9ZmUz?P`UfOhXp`V8@B>nNgmSC~LXEvFW9kx%nU8B|P*C`xsF&P%`lxj(rGt z)iUtbn;%;7Zui%8exb54TDZd#wD4U7gH}2!)Efj>P(FDm8H_kTk@y*>-cisRc5~PR zZ@Rw<?-c;wcI;b-Uo6S`c&;~tm2F19#|c6YKgyDnclDz!Ugmi%h=ZDL+Y8Q?nfgsH z^M-;R)w*R~Ag_c`wtElxU&$-mRNn+rgp@x6DY2>bf))Ef{A1u_f4RgmG0{kYc||Gf zF98~W@9i8<GnBtUUKP&tdg~1wVeFr2?;{c4IN@7q(WFA0DL8Fop{MExOt&!|12PI; zLfU!30O|q$Aup=<KS+sXOJQDxu@G%rA@6_SUy7JGw{3WbfHquG1AdTXIJ<f<#rHW* z`VtK{3&1V?B>!AP@7c7`9K@j%FwPTlduZg3JIf=O?VI7i@Trph1ZPLX;;EDWGPYZy z3;6oI-9m2@9p<BV<XbBpe7#zZ({gsv|BaZ$1$3CfLOHgOsmr2|;y*o`W(jIJ&HD)c z%kL&+Z=>#W@ck?69g%a`H<t1S7xjZeF%SO`*Hw-*v(+x=?(2Frzo4)1Bb-xH9K%x) zQG}D}f6wfodVQZg?WF#S6?qi9bwz{Iw}TQfbNVeehe$}CET^_wDS0U<$I1gcjZ=T} zUx>mcOwayJLQ&*bmicRR&fAYopUzuFKRQhyWnTc5;Xxfe7cmgT>iDrX#w;%0M`SDx zJ^C^{NK!U!5H9f}N^Hn0*+oMpp6^FJm1^Kxy^Q9i3S#HaoAnbX4ifcCa1W&?ssuJ; z{4D4Xae$j#C0Dqp1tFM8b-WTj_k*u+FkDs<W!>fU0zMaE`sHs}5*wlsJmnP9t>mC? z8_d6m4)a}pRQ_6Lr&8UqV5k&S7-py4R2*?8`Jox9e(v#=i}#~Ootj7Ux6Xss!fy-L zwSLQBLBN2=50-x#qVR)fLID!*qytBzPHJY5<jexpliZp^-(T!2_3RBQ>3n=Tfi(LJ zhLb#hwrwnV!N%V=;0P%9a2;%rV#9}(oGJKbD>aUCu!-pn2y&?i9ai7?GJ=;rukY*I zXSyMsKPxu6BYM5t|2~$Z3ekgdk^J}Iz@R-(3+17(8XdIR?pFNhmk}!Q+o<yPLP}Ni z7vf%u25W3!tv3CO$(Nsbzdc0umBxWUf^aBwrmHa@uO#?HT+<O6>!>Dxi3V~~Sl{3I zGdV5!N3r$rY7Z*H67MI5!PAAj`P%NmO7fFqT`+QR2&lxjJvgOY)}K4tG`}JA(^K|@ z7qPhP92j3(Zlk%nE@@BF@P=jk0=+%F6_T&%`+3&_5-aA#lBdfyb1pHR0`5BjYmL41 zl-BA8fcK|=eZ+izAG}MgC!d7kfeYi;h2%Y3T;9ekmh}Gn9f(s86)`uo^rjb53%`_z z2N$ATM#J&fG?b@-g6~QgAsK_CbDI-@lbtvR<k5eKs=F0>`6~H7R*j^`n^c4r;_6f9 zFRfclB0roobW^T_sPI2M`wJw&y>BN@{MX`zzF$P_XWpyu|A}|^AOF7bDRT2ryX;L- zn^nN-YG>n)Dd%QP;g$Pu8^Vcuz-PQ&>F**3kEs%K&wyUV&aW{SC+^o}(namzt5dtT zLph$jkNMnj)!32Q?!MBPEn>rSEO!*XbIt90GW$hs<>`O>+e$zG%k?21hFv~C2@a^< zlk(_jQ3bp&wX7o*wRzF$vkY^{6v5K%bO)cSY#;HKK`DmHvQJ(c_e~yM+~Io2CilF& z`xZ4oF|4=VGgG&2d%t^Ei&|Fs2!8=7&?J1?<Be&LZ`QecO&-e`3hEQ-n*KrbO;`BW zgz&$^Yd0v>;!hv9TRPRQVj?-%&3Jc6r0Vebv)SunkKz#6%jdk^v@o&8CPh#UcjT0} zS!<7lPg6^rDdQ9`{?I_UG?IsEQZkfKDVO~uMf{gkJdWDZ3_TV{D;Uu**oaH-q5?2# zU0x(U>*~22FO8wx+2@Wv_*91r>+Sc<);d4d<B|KGk~)%ansUI0Dk1kQBeZjfs+B#e z48S#AH;wZK^;CIqkr7wP2V;I`4e<t^A3vJ&teA$q3_dE}$&6WNfIL$?K7P*Qw?e3u zXL;qsJZ=5D?Axl9)m8hKm`K+uuAmj_rZ4|(K1F_MTTM_LdRBdDTxPgJ92c34{$VMm z=J1^%cV_y~%1TP%<C-WwW<^$rH-zV*B7f@h#Sz|ljSpm-m@AX8&N#}eeR}=NdGa~k z>CMw;cFT36mYG7ZTOw+r$9H&gqCrbM%Fqha@^pJEX7@VVYiy3z5W5J!!#DPVB89Pf zPn%{~r-<6a`03Fb_C)PTmM#cK;h(>$_d~=*M68-C;{9(359$>I#Gv(Ohp*e?*_zak zop|?c-r%92Z{M1`T&vhy$I=~i#Ka#y&x;xeqb`qTiT(oBBie}+#|+qo5QZ%^$6rSN z2JZ4^EQL?p_CNgeJO|LuHG8tL59(BPD;Ky^6L-G3|LpFv8ApT774Z`~CuGN5tfKTd z7E*87tn!sJVp&V*S&-<}sf92{u#Zr+%n~|0JniJ5Lby-t*7-l1U!IzZkr$;7Z~J#? z*6^bI--0=YDMc9WURAN5z_9D~1C1em+qAh=?AHZ@*=f^1poPVEFR0~Mc8h5rHyeHM zVN7}**>s;{3&(9~3VQBmxuw*9ap!|f5i*%PlX74TqK<#XSZaQsW)oFv&U2ET#WfH8 z6+5mvcZccWQyJJ<Pu}SzFoWPY&7<EB`CB5Fx&1iED>MAg<Fo~wYuLWB%A;+|Yk}9j zWd`x*1RcKa;|va9h7==`mA27MOY8HvPK^E(?|0J7kXS0tylvtq&gUTEhv(b8|IQQO z9wg-i;{&n#$K<M}p2%AEtjEpb<icymbY@2ayzY!nc<Wt;dq-8gbaJCmzKb_;)c(Fi zwo#)rkPZrirW~RlU2qnA7JP~1_+W7BGh;l1FlI1S$l&8WQ#pDlEa=|pxq;&N`S9s9 z+Tx9b0FR-r>3n*#>Lv<{%_%nGPTc0b<eV)gt9%s$7^IE)RApE~R=8w9noU7Hsd_C7 zu~j3<jxWXw${eS6s#%m<b&R&ww$c8#+#qQ75(^)Q%iM(5J!wGlmGH~4gsj{z*lOjY zHaabh5kyw~#Chp%CuT*Ofo?|k?wrIM(3ai$RWy4$?>2FXJ)4jfNcVJZQmI~)`8NZa zVzC$koxW+X)@7!i9E@nH0I>jEkdToA_LK#CPv6i;uT^VE(F-%%OH#`cGq$ZtYoo;x zl!=NT+|{D@f!yUfk)&NCOKUxA9I0o9P0K>mZ7%5AFIo_Kuc=YjZO^w{_U@?I8%N2% ztXu3Hy!AcQ7+syi9xjaL#$V9ik5iJjl>hns(#1w62b(KQkLG=DnDsNSXUYr8+?_8; z&ZGEp_@ARY53)+nYF@ujc%qBOT7lByFb->Hb~jD@HMOZ|8#XA7q)RyuuSnUS+)RR( zKgy?3+?z}5-dTb+%rj&*xcvv+w9%Tp1WSx*6D7H>Or*b{e3ko-XHPWT1^8(66a(0n z&ew$DH7;0XQ%+ay^#WWo=a_e4HuXcm9YYKDBxOQdrc2U&=TxWGiGmU){d3FLu&^af zP`14P@$ua+<99gC7)FAh$ns{bpzr2F5cO=nUQe~2tL3OL$X$b(m!dpua^<Frb?oYu zvOn|i3$3w^n#8Y~k%&ySv8t^5a$cDosD~M|qD^&ijsxzYAXN%1iF`H_#@y|e+Mbl8 zA=iajqFDRm$p#DremTdj0ULDAwV29$6=kgPBs&e2b^bs`@{y{Rd1i>3>0Epzx#=7> zFI4X0^#$OLavJ1T1cAWz8&K)2w55Y0_U-eISG`CECR6}q_yD7pBG6AZ?%!IZC*?L9 z@&eE35F`lCn(MVNs?B81oJOJWd-Gi3^UeQFve($iy6Vu58mr0=`nJj+ac?mE40?aw z-fwqDjM|z5uP3DTEU04y_A4{jq$i>_kHJ+UO(^#aInKyFsbOqRN9*8VHm^gc(Dm?x z@HLw4L;ZKQgjb19vD?dx$`o~pj5HB~%H`CGki^4zvikvnTSwn8`HdpJ)k6;^nRr+j z-ftSFG^W`k|AXxAl&~|mRj{INwj1nCXcc|S8q!w~Pu!>Tli#MBOPcOwbqq|)cN^-g zGW0w;rup2_#ls8wZqEj`2WgBDxp7*?0bER6Cbm_)`37@y;QTK!xY^Mo*$K77`D5Uc zEx(zt8?q<yS&>r;-x+Gw$83hAR*PN#8KZ#0XR~xY+0uQjD8s$t6TdzxLmBD^Xt?M{ zXLOwxqnB9frp?Lk#xbWUB4$*vp`~6uUXcqJdRyd|_+5XJKJI+{2S);9MrWyip4sz> zGAcxfSvOjixoafUxGP*V`@Ue>%An@VAcLI%hIh#p`Bylh%gLg+Yloa);#Km?@Vd`} zjHUwG2QM(zp3s4Qo;v6lND@#fNl)e)wD|Khku2&&`)uf^LFh0q#~4>ui{mwfcWd|H znhf{5VMds?b_Y~Q3ppn?nP$#ZFU0PibF@Ht5cc78G0_9uzjwH&GGK^1f8{9E8eXiT z#z`i>yV)Laueu7jp_F2M+3o8<VBJu?8cPzyBLc{>-N<fl^Sau&E4VhgyH$v?hWAMv zWnQgwB1$NpAMiHr1*Mx{0Y3l}pIK=Vo-yEqt9(rsSXMw!$$4L5rIGcBlJnB@MM?|n z9{yn2ZS{PLrmAxFhJmx9=iNyMZ&Y%fY)-4dV1x>;cYMpib&}oMa@72nO<O}SgC`}V z!>cvS{j@O0w*M>>WNNj!74^1p{1kt5^z3Ko8bN$g?hG@tmb9R?cY+_KNa-|OmwOGa zd+K=1fOJ!FJH!%MiH>BR%KJ0~-~{SeES{g&BUOY4n@LXKP4VU;5bhqzc<;pt(2hEZ zg6>`7)4Hcv3kM@W`1k94kB@X&Hu-qzWp9L?_k#Q^+r}_zM%ZaQCw)KD^;VZ-cKP|J zomQQ9<Y0I3f#9hZN3H99+zY|6k(_QmE@&;W=_do#zM#x=L%(@$`()VX_<!Bf0K=o$ zqvKni>8c	^C{}!j|nao~fi#WOrNmgbzX1ynyfbJmHI+qoXl0qoHtn{#%Rd-Kb!o zFBC5`HU=?kB@<!GQh|CsE)hS*HBtszC<`9*Uc0n1ikVcq$6vd!LMwyEOvJ7-t?;gS z1Q03ljV?rdjI(LaSdSoBFfQXL!T3g3FC0ik4a`}j`(ro+LwE}4H*yEKwVAdLLW2Z6 zJpY|~NlnE`fMPpODuOEIB<uOZ8u$b$>HTLCc$&7E2ri<{&-s71zCK+LIskGJ`o$hf z(GUacFuGfm_gvvK)Twv*3l5c%UAgx9eJpkbYa3`r`Yr#ODbyprt}wEARFi(u72mP= zB76w^mz1Ys?1r-t+REYV1xd8FEHFZN3qFW$wZ~C!%5EeH(5G~&Ov75yhVrf)J_qul zfvP`^ZmWUiKJzgg0$=`?>{Ps;AhDB284vAbg5^L``dr%&sXC<Yb7cezw+3y%bzc$d z;<#E2`OT1oBtvNQ&XE+%w(q{K$}AK>B4{?+J%BDQ(c&sf_#;*Ida7cg<(DN$5V>E8 z7y@!^rIP-1zm3t6irWnEA^G!LyraNZb**tus^ibZk^1(b^E>(5h9oSEZ5qrs%!4+= zm@DLAT@c($I3g%b4a{}YKj3J%p~zHf?4!K_+)^~zpqxSIC;e;CGbk44t(`8+Ys8sV z-f>`3c_Yrx=$2lmtu+2!kkZ|@GHAK_wt~CA<Uumu$z}lAA@n4Utq#YtxG0<_nl@A8 zEXB<AAb=>^ZpxgmYe&NH%PZ4jOHi@0uiYPUsZF5^slnWvxdbxhyK<fY?-KuJst@OK zt$#4h%gG7X4su?4gWIHAp}8e{AUIOVb=bl!C6ADVxsVHR8dktNc2*CX9tZ668g6n# z-%v0l!v8Wkhg^BPDtX~<Tsn_!1l$B;J&xh^GBsy{;kT?8(H4ySyn?Q5cS#jD5IpCb zuWK2S_&s2Z+q_RI!g@T^<Knk#w-uJ=1<GAj7!i+6B>?eKkthANkCt50=jF?8aRSgX zxpKG1`Z-qsoFn~GXRx?}GX#SVYkVK=Z=}N|V+BcD_5ebvnv{1gPviSNHDbSbZ$A&> zw!o&Vgp4G+M>|<X<(&^8IgpldxQHv1LCDHedwSEE_q3*E>-Og^ZX!>$4<(D|ml2*; zFYB~>k9icWMa>ky_g~J?-`{k*Uy2uw74;4|uvp$p^Aoq?9J;F1c8cgIR?%@rPKb?G zZ~~S7*go(Cf_;c%b`#oOZ9uNHC-=6W_%cwwi|lX4`#f<H;%y>*tV57I(f!_4@V2{! zJyg-}=N%yiVYo3L=Mm7fp5I_uQI0WA&QIU@SwPC(6aNj@hxjv1^#<XMepeYW)sV-~ z7O(J*I@Gr#@oB!%I&gP~L7LZx1{`HsyCJ*(FV;6nc2h}qwER}F^SpUMTsUg!oH~Wh z{gq{1@n021DyOJ9n`VNWfDD{>Z1a`gue)7ceb)fC#rQ9%Br>Aw-QeF_e1xqb8QbEC z3gOZ81o!)#*ErS_AaAr1SC*A|iX^XEKW%G`G}Sk0Vg+ASu48Cu@m!ur<N(>f7eny^ z0G~KsjU23)SXJK>-JOY<$^}db8S{P5CwjNJ)l<T#wz%Wt*!2%n1DAPTm?w9TM+bb3 z`@T6sDfs>1<MNOf1DUH`PwMQg-4yr^=OF{E$QTL7*cr2wwVKhYY>GC}vuE!zP4wS? zZY2hBD;}8l_<oF1L`YooaXfKlRnwP+Pp~nI1@{Kro)hwn+2s@*4TK-Y%d%Ai9;lMg zVr*@*b(U#Q#&{!LX@7VWeBVToR|QOLDqyE7QdamXZaEOg`?<30idVg~rGF__zq+$t z{mAqtfJ0p9#VlTQJVz!u?FDEMmYm3g#GC%<Df=c-apL&@0DVA$ziuTTa)rEbt2de8 z9qLD1*Q6<uk&>NgE}+aJeClQ67F7Jfk*O!=fYBUxApq!sKD^i?K;p3~SkQigFsd#R z5Frva@Pj944xmB6uIWp;0Us2h5U>U8AOfMjff-1Wp`vnF0{|NeVHe<vN=JCylsFMb z&2jBTFX|!N{$h4FV}tF9y%Ym~n3o%1M|NoEqIp$cK`G7Z#A#~RPw^6*$cBZQ)pXa- z9!B#Ylpz=l26v3Jop*?wo~uLR*)DD@S1v`$go%En43@x2HvjXX6Xbv=!J1~GiP*Nx zWd8)A+n^KBZ)sd9<aXhgnsEg28XlHOM{(jHq42{JYN3YO_HG!Yw_y&L!EZ<yKV+mZ zY;WAg!rKbr57<Bu^uim(dXnCu8L;3RmI)rX0TUF#pHLeg3PI0)+F8&gF1zy^o>?L! z(ie226U7#DxB=qK^|abp$^u3k@<B|-f?lxF5w~~F=;;?&NwUn7Uooj4F7vdu<ZqQ! z51lNXB4%9{W<cmilOp0JU<Dk!5>U?NKY+zMI0YwnE}yqda4eNO+B*FjdJSfw9wv99 z^PxYEL^bm%0LY>0?uzT6fpS2I2Ag3Hu;FglV!KymGye$VELJ+s#^Owapc%ZOhT-lh zvI3#%CPgx1>*|2F<BTvQCpLI^xc{;oIAIe00<XY^rvIT9{Gw=!Vq8&zFxa6K`oSGA zDLFplTpdKa`}Al@i2!K>!o-^~a>E_!!4z7Hy~J0o+va>WuL}99CA?}6!w9#I<RTs< zY~-0fU?m(RWxCr2We3EP`Knf#;N^18eEuOQ7l#~hsV-n`9Pr>27H6q_@d6u&8-{$J z`suihQO2)jclj(LHe)2(G>AoqJO4{BvX-7i6*_*KCst$|;Hw!zP$J^U7gmH)d|c@m zsS@qvp(242y+zV32ftEjm0W5>s&^VTAuS5ccmMP&H58KfG^3R;F&Oq?TNuN!Qi;re z!!^*ni7o}m(2qN8lps;Vi@@mFtRuW;ls=@rAW9dlR+I<546Wn=9^SoeqSGP}xKi6@ zW2qo@y2jj7LwEoI65zp9)K&aogH81euJ)#$e1SsL^)hJWMDk%E>q8<I2OxnMJ1EO{ z$iYd692@LF8OEpg6y*2#2HzR#A4Z)pRss`anZ5SSzA)qWn&A$3)?NzYI35ZU$U%=7 z4|oPbrT&4;c?Tn};=>37;`)voLg%eZns&M5cKqSVKZ8*Hw>(@Z>01jl8dkk;5*UB% zIW=OAr&C&+>x;gj=elGh><}l4*(b2FUjL#kyp|<9Sw^UkC1|44m1Z?3#~~*8uOPe- z!3yPLVX2|<02203v85WP))L&JbQ@3_xMk5!q`44auMnF?79)ph?UK0fD0wUV53pfO zT^Sp&f#+po=wW^m@L>lpFu8Btnu1kYSe^}r{2jFd19@IWSVY+41~o7V2}^6!m|irU zIvY$OUn}H5x3sg~?snio>jN%H8_U@#$w2}D;${bv#-sTaHALwTg1+BC2dv=bp&S%E zX8c|5XRLk4W8<+S!KSSq>=|SMq8_+^dm#Or7a+jDfBqUe^p`Neym{lQF@YyfUc-d) z{t=@hkX*fu5hFhIH_zKYIi2cxoB#K(q|BK#YudbtGiStw3Gwy%gYDfreE1ahV)JiX z!i78o5PcT_)*o@(P6l|`6CXTy*zPpj2G1$Jg+v=Ro3o7@Jb&2iv1yjIB+&rx{vn#A z79u`>|C+JE$1P^lfA;=Kv(wC;LWX=}Ml74uuQ#Z3#RlNYW*fGp^>ljvJhP#>z{`>a z(8evFW6(3jadY?1)V_S$nx3?Z^Y+7q+_d$xrs*H*rmQ2PZU+jVJ8s;t7Jm*sI?jdT z{-Ij)@7vXw4zEHq>2RLBdZ^m?ds*_^zd(fkfveYfvF`5!JM9@q@pC<L1M#3b7}i4F zb(hdY?|{QZHR9ou4@dc2C;t#X{M2+CKL}CN#6KCWCS8Xf&J<QHg=|BaR$Tqj%Qyi# z*3>rT%+bqUWo<-KT<>6$*=7Oc)1X*&!7@iuSBdkFB8vQ@mP|y!^A0zEz(S%wbHQ^K zH2;KUV>ya&BF>7TNx9cQ*mMOKJe4J+-Xx0nL*zgC6!jr=_RMLIYxyV>j5*r)){k^^ zy5`P5rm%ygJ$+ubRicV+Rnwx5!n4qx?ttRWa@-VF+?<h$vyUm^SUM-8agIvrOmh-d z-ADg~(+@o6n3HHkq9*j}hMlzW&r5T@s?r{m`14LZ{DitFu?f|q9uw63Lk>AP&Drcf z(KM0IOZmVG53!0KEC0|xknG`JIrz+}&_@CVKu@Ds&N&e{0WbkhMz4}vYP~s?)g&9( zRK=z^bZs+-Fb#s4RYTZt^HxJkVkzpWd%d$wA)e4v;*8wX^JG|0{Ua4V{3b-FJ$&^N zWL0MF1rIl#6v8B!b3weNIq&!r@~mQQ6_}C!lw*!q4Q=z!ACvs^PB}dHY_DfT_0tb? z@RV{*KFr0*T%d!}#<aGJCS)_$k19GR(|hKVNIUMJW+-%GYlBZR%ebc2)=AHusbXS* zlTRR&z*7#RbgH{mM);JM>pWXUOAQmu_EXu{^vZKjKFS`1PyqCnL~pbCOsiq#UV}|% zLn;jth<g&g8vg(}*E#Do;P6Z|4ubK@1G3$8Cw=)+u-Fkmb0<TjvLfFo4Cjp7Y~xiu zCp#)vQ4qr-2+=O@6#zE>yk$<mz+y88H06j4;y=EyA<j5N%?a#3B9bW9%iC;O&dl^0 zi>T3c6>=mu{eb!NKZQ(k8Ka%)b~j;K)j;u%u$Uuvbu&jk`0<ZU5e;=Ed6etI!n}xx zBOjfD4RaXynYI068k;~;bFPFX0;*6abAnHGnm~;JjD%n~30y~RRk&JpBys=fhCE*N zHPDI29C(<;J0=1`%-I7z`H%*+<Ux^a*&~DK^M`sMQM&ikgDBzn2Nj5+yv}s(GM{S~ zg1C_p+yAYQZsHI}T@+D>q^w0T4attaW>y*Fk>f3`TG$xfx3YTRktlod$2Oqxhs0>_ zMr^QBjl?3ZNfe?S;vmYa{9z_c6oMN<A*A!T0YCZu4N+d>Vv&xd9{w4U98YSH(XO>d znry{@+IR;j+VKwxN@r>PK+Qftkq=8jB#0@L2{A?Wsz6Oc9khW@Ts{-FUTVV}Zj;)j zrdZ5aYV$GpFd8__0mFPKZ+Q$W=2plxkAbv-82_M$4*$W!jEJjtpbOcC$`b%xjnY*1 zuuwi&Lb;x4O;N9U6-7wr9%mwiLt|{6<?KNZdVm8Tfq;Z~#$mT4Zu2?2GRIiv;0rcw z#s6aX_+L!&_^<%1j6{6vo7^1suaya9dUW{*Cq^{0HewPRo<M~323U^k!QvlBGakU2 zAr3GZ?Ozg`5Y6bct%q*RNJ!e>jOqc6%p}lg=J3}>y~dk-up=4&aEC5C#2aoPr>s*$ z6frL-w`Bff9c1N(LZrhRZMb6}rT7MOhMCQ;t`R=)>0%SuSq~rvwkC!7hCRNR%L2iK z7;Ttc1uYnnd*aF)w9`pSym*Xurpv8zOV4@+k<iXa^dE<<hv#r&PkwwWAK++~U`JJ% zZ8YN!QCe94@JBS1rjHYfm`4JaL`o%5ZyT^cgm#{4w0@L>8<<dp8@0z5XrQH&aQ|uu zIr3qLUJ!{#IyL0=LfXEf^o0%N*v9@qsHlwrH<bxdn0ABG(zAXwCbgNyG|H;q=;XB@ zZi5?Nju}`4)5;w6utzcobwUrliXY;*B{#%@spQ^vg|9N&KZLOcbMRxF4Snck)dN{9 zeYOq%f#PKyXAkjMXS1)Zof1F0hF#>twxo?}?Iw$zalj{{1A$>V5TeGL%t;>kz+yST zu~ZFjxHwCy3nDzh(uF0&SyIUd4e^B!;(lYKCMxk&!Vv%%%~LFeX$BSoz_Z`^gB#fR zgD=SJKB)+$rN+a@Te32j^&aoNqukc=IQEC>UZslSz|m%Q#xue021x;+EB}Cd<e|Lg zqZG?P(gqnbpGVgBHr^o#kID*)<$T&hr=C<hF07hSPkDt45!@jB@D6Kv`8zpjh<2#3 zqs6Sa#V~P9sJ}xPbNpis#280)m{OC4e3l9VBS%odGoOX<LnTdk22&)2x7NbsGqr9q zxU@Ly4!z7Sco`(|fVGXx0BtcZ3v(gJF-Te4q>FPHDx_9Z55HKOB$xzCzsE5YLjDVS z(xcbUO6m!IoD8{snTL*u1D>nk3rF6t>tZhRk6jcZC_7^i(zba{L-i6L(^v<9%lDy3 zX`>$2*hD=(h|RYe^R2t`m#dlck3&gEt}Q2rT2N@_bdRc5-lzv8<o|FUe!$YiGRfVX zv~yUb54&@p3u1cmL52TdRE<`*M@NXU27J_(9Jc$~kLQ7pCRD>8&ZLJuz(ECSOeE<_ zgd*OnLDX_6Jv!(UUy%9+CNi%DN5@;VJ<8&gNK7KjT9L96!{KLN6s4mJAz3%$8zzz^ z<=ybuMs)>QG)i`9EgUPE#*5+)ztFiMHQSo2vPY%Nl;hnHn}af%1Ev7eO;jmo&O4A3 zj&S5dqYX5NJ0|4~a9mTt$t7mUmLiQ`cw;oRyFN7SG2u#^CL9a&@!&@lRT&Rr5xJH+ zHgl44G*bdx;h@>p<%P7AQ_&t>^iPAluS84sAZtKdwpC6rHvbX%07HRC5A%=@i?9bS zF%QgFbus1*aYqgH5M}5088$OM_0UCS)>2FoF`ghj@BtZqkq`W`dGDuO2~iH<HB<}q zc-@2#Lc=WMfG9<gEwblc{qisRf(=_Cc$M)Zt_NvX!FWnx8M2Zn4zp94kyMaIf_9(` z`LGtA^i_4#JFnpmiEuWl!6A6XB0m=xphhFOQ4#}!8)=0PP=h4qpo3)iDo~*g|5Y1I zA!;1>Atcc*OmH9*v4_#-7=?i${AUjj6adt)2HrMeJR)moXiW8x59ZQEW4IGc(Gk}X zF4uN!b@UJZ)CAz*4?N;epMVF2gK;^rZLGB{`o@R3(f=4kq9*?^g(QJ5DuW0TM|WGK zUgMKXRxyYXQ5Zn7Dkl{`{xdXe=N(J3UgZE5i3c%W5si@dCXgZ(=D>st@m-R{EQ+y; z-tl_=Fb;mP4PA0Gy~hl|2Z@5WQC#>z*^mt30Cbor9Xz5;|7BOk7HVHIA4?$|Y?BPN z0D?#pj-bIK4m4KcP!HmeJp>Yq_40?{01gsTYMw!R_Mj@4SRL144&DHex*?7gR1ff! zA$4JonJ5qZz=><e9sL*)7BUWa@CnR94i<tBsF*7qk&-k45h}5W5eXWgh<R)<RE0z% z__7U?fCzLU7LXVKe$h?B$ZIrFjE5I%PH|uV#{U>fDKU(~Bak9V{Qxu%;VKQ%dsmo3 zK=TKlpgaS#h7i#hX2AyEKqLWxIvisMhSU&{7#}M{eDFX^{!j|+01m?;bn1o=a&?Eo z!8Bc$L4o--L=h>kkqp@&H83|X`@}*jH#U{94`FC1d?%D0czYQE4@~e4;4l%2buT7T zlB(iZ_K+%6uqq2iEQ)0_^HPZ*;SLQFV5g#i%SH^e8D+ZpD6bMxAs1pGNe*zw2ocCx z!e<i;)d?|Knl`Z&ip34A)C*XsH8Zj=f8age5oo(ZRBrczaMpVH5Dprc5ZEAaP@z~= z#tntQ3DSczMG{8|v=#*8Wf1cRz#w=IasM$m2o+6uS(~|2lfWf8)g`SbM_}Si8#PN! zqYay84Z;x^i78<+Ggs444y@vY>KRoq7AYJAOrQdO1tlGO!VhJ$9DHJa*$Ew6p%UNX z9uY;Fmlagzf;1Z>n+vuO`WGw2xI{sfW6aWEN%m0ff)C0vMA$M=#R5_DU=FDGk@N7J z`GAV>z*!VH6A={vvmis9WurT%c+c|(LXmJ@^D3sq2AYQ@8`G8zX=r0~IsZU1JLWz= z@eTBeEmejMfa+xlkuyi)pDCx5Fd~-_!Indlpf?dKm=plJ@CPLF4sCRV0pMP@M^v$N z8)?-JrLYgvb%vypSMVUC^%#<$c>inw=}VQs5ANU^2gw?%It|M(4#OddY5E*I0v`k6 zEB^39n8q5P#S$1n5$13m0nkM|(j$GjYXsLA%4!f90hJ}8ZT#>}%F?B~CLp1vZ4RiV zFR>s0z+#jGkT(H}^*|5IxupXGkrDY2N(nvWkcDHx7%y2#RP{Y?f)8khgX92;<Jzu^ z!4pGqWnhsIn>wHl%OjxJ5Q6s>Ye8P$kT6(57CeXzlduU%k`QbO3u-YyOo4`FVJ4oC zsZhZqKk^42L#_YtmuuuG%JxfTRh6S6bM?@w5!Pcz+I2yTC1MkzuhCYSh9ufx5BpFF zv~ekJ1+3CBtoBe4<`6~Dk^d6@&<35LA@VQ~kR>utrJggPtk;<lH_?FbL<Qk6r67V? z4d|tKu%-6H1kP5WpfMrlFbiuSfjxSDYl=Kyv9GO@C`1Az1Dh3H^d#MhEtV$}3wwi5 zlAuuWB<w>$TT!u-dl_>wUD$(3j3O!xL1%aL9g!Mb-L<n$XsPQnGe1)gFmfgEfjaIO zOE()qzaS3vM?-P4HuX@LCKPm#DL2#yDER;iv*A^~D^2~t4y7Otr~z1jJGDymumRv7 z2Vpr{s}d|>tn%;<3P=q?Mo(TR6M`5|@}N--Xbup#lL4lla{CF`@e<%RisL|oPI?pI z)(>CgT0)zhpa(1n)Bg-4*Ekro75-w3T~vd0AvDv~Dm7XY?_ds3@?1)YB21XMi4ud8 z@CVTPFI$oig9INb*Aw@36)*@5c7P4zKtsdGgHW+jQ1LV6FsGQ*Mz2B`DEEZ?_YV&y zNH)f^OY6L)zzy`c5LJp`jxr}zBPi^EH6AKp0l8O|z@eiFz}4HC&J+y+po7Drzp!P2 zT-#z`%UX!_Vx@(o27({~;9^z@QR*QH;4+;jN3?zeQSO9y)L<bNIf@LHSaz&rc{~tn z&|+d5xa1U6Qo%RG<26utBE8@&4xw9fU_FVa#tHG54{Ht$OP?Hb2T0Nx$hn{B85T_< zF~BlC+gVWgkpETN;0_T{4zHYV-cfrabrp~T3_wA{h7`NKa3x#?$hW&Ffffw=5CHuE zABYSZYg5F%(V=;Iq|$7DK-UhY@M@PL#nJ&NPi%|%8<<-BEcUQe7!ngTmaH%_3wR)b z>XCKhM7$CVJF<g+HPL|fun2+R67sN^X`Des7I(ye4=d@df4t0LToc}e4_}0}%&c^Z z;%oSz2!9Y<;zB*m(=rz9HQUe&cYqJvg}{S6vR%PGY?ruiN?Pa>4#)!yb`^V;>{$M= znXHVc;_xIdIm?z@BG&7KuxDN{0(+i14<Lm}0;F)-q$mcI55WM%7M(OzlMk{{Cv$km z{;bA8cmEBgaK$~z8k&M6OMR;SFw=`A&Nty<)zAcBiq4>6MobV6_izvJv<B}vTE|2a z;Pwxs!w=!GzTV0N?f?#CDobuhWD3Ym^ROTGAa^udvz|d@0q{lS@Iz!Bi^UQcg;26X z;f}nvruHBRy%3Ef+tCz}c#vB=xwTs*T_lt6(F=50RrWrf5ES_^KBdPHQ(`kf^FP<M zGg%cBVo^|n{21N=G(f!(_%OpQ)ln-%662Z=M3N1r(2xw$Be+@|D4QC;5Y|xnkEKSg zOkpR{&7oNtCk>%|E!QeMGO>Iyl4boR3c(NYs+03DTGvfE@Q^t60N42NbWu01-QC=d zG5<RHtVM(IZ3V3&{K_G*8UWx1c3{M%9uZ=~eG^ULLK036mpHXth{FMZ1<f!s|G=*Y zE8-6WN|+EOm%-6@K-!e~s{pwWP^nvW85Z9)r-Gq}=7}=Q70NJ+Bn+|Mpopl-Sb2Qo z+a(g?s*&RqYe;DpBWnREE8`9O8sijhFM%m@|M0xg8yJl}DxND=WQEcuYS$0N9GjL6 zVK}^Bo`?|y3Pcs$671d;IBlWDV|9bROi&JRT@IZf2k-C=l|y}T>45XsiTq^0<d?T4 z8n+Tv4~NAM@<0ywP!P1W=$^4;^N`=Hxz>F6DE^?YbE<LQ13sX)6*JCB5b+M=ApbGd zD1waDqCZ0>5K)xA;4cG2W<RqHD8hFA2IS*1Mcf3bL_RYN3kwDe?3?-8g;d;6K3q7} zQVB721QeJel+_%n%(w%NIs2Y=qjO~&5xr3kw}cOE<j|mjv${)u1(n5f4!1bA3xQqV z&tV|=;2)6F=bJSlL`zy<vbNpE*dQbl<~+=U{m&AG56mVG^PnCT6+4&y8S_vM#E>EK zPQ6HdfQf=h>N9eqUSFiOFuKKCGeZ~Ua0j4`N#}#mGEs-8lpX)T42hJ&J9im&IyBtV z41EbJJ~?Og@ISBzF^!}@Pqo}TS4BW`!)s9&Qci@VPMxGOD~Xa;_D~6C<Nq`#Q!jM# z5A6^P(ttwoyu_lS)cX(&_>fpIS1%6K4#~g_DCB(?pQc+e5ByLKc_&&X%o<yv9;Aa0 z>Oqr~bIX{O6?4MA3%DN@N-qs>5L%?aZf7@$P4Vub5`lnP==ObbUk?}(0BeW$92oUg z#_IW5%P}FqTmcOu-w;KU!N*m7N9uhozuPO#ls^URhKpRjFbADHd9N!)xzkNoVUC;8 zd%a-GbV5Pl$?W-{2$KLTePUD4ZZt&?m{JrLy%7Mdnuke4OaH)W92#_Cub#YN5B~LX zRzAhnUkcU$wck(K?w)d+=(n{s@6a*%sPzrz;MNs6f!-b~?G6wD1pfvgNABMzJpa7S z6KK!gzyRO=?V%I^Tt9~oAqIfg(PPJk_T=#+*5n^JZvg^9vInkSy^S$t3Y_OHAD&PD z=FI~+)8|j1L4o2UimxNKKfT_;^G7u1M|=e96`J%<;yZD7dTm=u)M3w`PVr4Dgzw!p zOojXfXc~1ONO%tYy~~FPh@pSn`uX!0S0hBH{;;vxhAqH5Y;&NIW9!wPIdcvnLdECr zUoSTQxWa2TryDn>j?IY^T6*J0)PDO3<kqfIJ9pZ++52bOc7T5UxM}-WiXA@L_WGqJ zUR-rQ-s_V6b0=<g#@jw~@9xb`oHlK_zj_o1Hu`t)Gq*dQ_y3O=m3rXF@$+6<a)5dH zC<QV{E*ukZ;C4dpPJAZhat!)pjeok4=b@tTambs00wE;5mu4!?A;{#Z=RAJE>88O! z`~jz&a@qr`LI!aXXC8X^<A}TPT9nYE1mXF|mpjhd%c+gtBkG;06v^wIvy$2-GzIMu zF(#t;!UhX>{MqJ?X0~a}t^PVn@~lZ(Xl5x8|1pY1fpBbwFe%TPLmATAqA;?*R_qAG zcm9E84$V3mlN)lZbSob!T?~pZzW(`#uX6sGW*U6>QPIzt1m%XCak44Jok#N-6i`ev z)f7-cN8{0yef|+gP)0X$6w-Yr4S*X#H(je#SiuYQAOCsCL4`nY=;6mte!TIg32ExV zCkbl&*{M}mUyUiBd;-j876Rpwr#4ap;D?@;+MtG@YGX>)GM&sb2^@3Ap@JHG465zB zn*K2nML^k7HdaOh4S*;adzqu0ZT9MRAWV0}hbnQ%87BZw{?H6uK`#wTOg6p=pqV=g zgC~H0`4R|OY`77}u(tl8&EbJ?#O4lcxVp>^ZluJxVP-R4t1TJl)QqD$3w>44e9WQO zr_>;G=O5+%$!@iu2Xa&!ciKtB=%bChSZW#b;>I0!5{XTl2m^S}Plq1GTI*GX`-r2Y z(-!JYa=;0o32Hj(I=c6E8m9?x{y_x~d&a4!od4~L`_CMD=*gQ3V)&6KB!{HUhZrXM z@kSm6Up(6*hswh+Z)%t*XY$H#Yn;J7Br!HmFx3W+vN!Yj1D1Xa_PWjf97^(^JH;s{ z09fpp3*U=POLA3A5c!9ydR+cVPl38pP~?YFcM8i$@_7fJgz=HGt&pCA(WuMj2%yZt zz5xxM1abUXQ-Nk>R>ox5$?M;rJ2mGWcR&@jefGb_^i+7Hic+&_SgcMpwyibnQp(bp z>Kw=yX6+<zOrXX*rnN5c2#O!`7{?lB0gpXEVjS}5$+v#Oj|}0X35lberT!7Y@^p?? z@yW+bT*b3|Xl`8g=v)BgLBj@?hFKeghyM)eQ4eNe%7Nd}SX=nAjeoqZ9M{7K{az+0 zeBq7_;SdLDY!;4I$?G=os7EjC(2UppgNojI75lo=mj(v$UQxl4B7h_(JKQV)%=#0} z@L@BR!Qv12*xeqPWht1bEsmUeVLoI83QCECb_P_S(F`?>dbmSH{&Uqpb`yY7T;m<G zv0|y5<Bonz!y09iS0|U4G)<v!g2brD1xslfdX(oBYj|5V`caR*DA0{RdC55Rh6i(e z10OXUhz0)vEyXPkD6W(iKGq<N$jDGyax9Gkdxkd@B8!`^>|-mRSdKaLVt4A3$*e5X z3@i|YH0czF635x7bs2^YbJ`3$<^R~p{>^K8XsO=y1ZfVJ-4Y^vxgCvK7N<W{g&Yq# zWDWb2HcfS^p6!6-qZCRnZscPh!N5m9Hp$6MZ7eU^u!kn5VKi>2w0@RUP5?A%4il1- zUa>5XF7WUUY1JlX7`)8}^YMv2RD%gtNu)|$ITL1$q$KIl)ll2j22{-OmYWhId`k2Q zgY__|M72$Xz=5B6s4HGNy^T9%q>MTA^P(GJXk`#nh+6yujBN15p!nF;pj2xcuCv1= zuyHYV@{fO<RBXxU$c;(Z@g4RcOFj}x)^<Aa9o+cCE~a?AN#FxC{;23bn)*OSV&@;p zsD*A~s#9}tgCCGIsn5*G*#F6htrYthpz0iDj&)1}9yhfISJ?_nKyA<;i`YW|CWqPE z2&x|R_y;Knk%v>jgB+)QDo`Z225N{yR}iU*J+L~%KDyFf0T{<P&KeGBwMbCoFvlLU zI*(x<H@zCehcfIS*PpmEPM#>lJi?I=zOqG}^Lm(B<Ya)YyyIm7R^nn)x)I=EqZfzR z#y0rDhGzJzilwRRT(<ECV0@M;q7_JKCt0eVq$W42O~x{=^PIH3XF69)#x6u94#;#Q za8!GbIsUN^P~^iMJ<G9hbOR2KqH;8mIon%;r(Zt-&zT7E$K*-{B5=TC2||d5Kekh) zDg$M7_`m}rjD;<Y%>N@p+VY_^Er*)zNOKLRU=~7Xbs!^MStt&93ArG#2dnfY%~<vx zW#*C?Xq2O_B#sj&3PBETU_udxq1lRT<CJpv;?mo=r<GIVCc(`PVBDw&U$;>X5aZM_ z%L^X9B#dHm#HkQIIv-IWGdH!#7&%NUMK-MVHMNCpHrFr(Ozlw*s=+07qhd!g@Bzjb z!|H&bXh#6Lm}*A*Nyvdd)*&F#Wy)pSHee3G1~zb#?F@O*;t>gh){v95hGZQ1Km`>} z!r(jW2_*JDg`mzWEo7H9J^vU)AQFw5aLa@{dNMH^pmC|h$^<e`d{Q$qZM=8TEOkMV z%f0>qqM%4S+W&$E3_eE1S3JeqA1DV3>w*Lfaufz-M1l-t5>Bt;I7%EyR`R2M{xfC& zBOA&1MsT3L@<oHu6!M#6lMfh-i+9l+{)xDY1P%`g;%6M!Dpld!W(7+4W1@jZ^Spgh zkbmf64fR0LdyIK2g)q71TyIzDymW9tg9pt2m=8SUF%GUryf{wb%pAOtri@Pp9zli& zHpr1iMR=kgAqO6K<Pvi30c~nfN0M7u1!8RcgRhfb8~Ti5CS_=EOu43F`U<H!VasM8 zrohJlEkjPRi31e-z)o(U4yNhYBN+0l$D)#Us(i4c6pv!na3J3G7JZ$FP58z*j{Y4G z%_UB{`u~W$NA8n)i0p0pna9`kMj(kWlh)<e2nx+njU>bg@ZT>@J;Kos3L*&9aXbB5 zJn$h4arlPfiad!^yFdB^Z(xI*t1Fg^4iMo#D{DK5JHJ)?2SuogUibr$VL<Om60jpM zde{bNs2I+}hn_RC(~6ZCBaT9uIyLe+b%PbY5So0LhIMF`o;kkYp%7M)6#tW?95khn zs)b~*2kej<?E4AZ!3XyOGR6rsgTOn#iNWx|!Cg_bi90pZ05g9Ggh8+h^*fAwKpfN3 zyZIvy)3OS@`3J!BlWL-%wE#5A3lkT#tpY@i9r=ezP#97RJzBdGdC&?n;jao5ooD01 zM*pK4H~EQCnG=851V!KmAR)oifD6lLwUikQxk{h8YLP|ypN0{d0GPUb;Ee)$zDg1l z-Al6OcrA=UDR9}10IGymbj7q8D(5&dQ}DgDXqfzp!U+=y_^J(gz^S@YzkHwwc*q;* zGL33cAaigbWLdBZ!zbxlI5Sj;7gEN5fSY`%hmm>3h1wJa0+D=BDhb0Xk&uTZ0=S=0 zAPd3=3epK0N}_25hj0joY?LX~TBI;4lsWJPZ{tIJf*?Mzt8JJBESLo6AQA?$M^jms zYPpz?!o`_ct4ex^aYzhoATUjIy^aKwB=HB*K$&d-hVf~^D{@1xBeIbhjiCXRdjF_C zPK=f5U>Z<~Eg%atsQbxx@Qqfiz9v()oMeYqG`<Z)#+Z<caF7UU_=HcO2CL|qjIaj= zF+&dlHgOX|4jhQCET(^;27k+kHIaxFGA#_$z;WvmaA*QBI<K9GOP{Ea18D<dsEzgu zwDhYahEO#JGC+ao7!cz_222gPaFT5>07KBkZ&SHOgq0a2Jq)v}x`2hq3WpZ#NylOe zZjc5xzy{ZW1+H+cH7S)dL$!{842@E{W|Ixv(92T!Nq=B1*OE)F`^kSu1lZV(+*qPh z`Ug<q2X5$#u5>%xOg4u=!++=lA;<#jya#!xC*b*;HTcUdl)*3*90JS{jsLjAV%ZNP z69xi#2@I4Phqyp$Xaak{yKtDDB-~4LkQQ@5g*H$Ko**M=3kNs2f+skHZ^#F1yH6Mc z#HfG=Zm5Mqzy=8u&Hh-)4!a9A>LO%263h(G(Nnq7vrsdNtZ|UZ)?3MXh(K(x2SI>^ z?%>1LES0sW&j1Jq<M6h8$OcpJhe!Fn<D##8;HXtu&UJ}4ftWFoDuv<nMbu)I-OD8B zFh8lJD=^xHCZL3dA%-^i26NyEdpMTP!H0!N8zGF2py~uUcn3LiCP<KjE-TE^C=R-` zOE$zv+i09=;ZOhUh+YYRHpoh1fCR*;hYiuG)R-O*!~}^k#J&3nbN?U;Rw2r=JWMF` z2@744AOMn5yEDEJhiy2`)cl4k>&ko}4HqF5FnS?Y`3G|7!;Uy0P$^X$J1!urhj$2u zeTXe(sZ@c0j5sNpaIn*#=?A012P9(-qcak7a>4Y&K8MJSEL;O-$RTe~CSq8FZ{UZX z$xEfGB|8JU4>eNLaHdY^&xHu8Kro#jic_iqhjAc;EO66oRnVZ2mU<{xg&-k#kO)fH zgE;vI_c|AyV2q@32tIj1M{`g_P|XP~MTx_l;<^}?6bCURC(R778vO@5Fo1kGP(L({ zj^K-lqKeMoQSIo;$N1RjAPUoB6=669bw~$NfQA6j1{smfmH!F=ZYxzQ)UQ+OL3L=w ze?S^>%|?Fk2V9M<p?%I4`AK(3hHS`(9{q=o5QmadtD&hzw&IKOcuOudhhF&yKUjo! z$X0rg2tR;?S_(`uJwAmCSgrh017m`BV84_TPuB}pLZE>~@XvZF2--N8d)c6W=mb1K zp`Bomv-%K&pclzt$)VzgN2NF|8XwkUSIPjM(POKX^E996BCN231kfHIwGFs9P^$2S zIWUX#Ls@&E$vZ8snl*>rD+N=yhJ8qeV3>y8a79P)hiVfCtZ=?p>Pm4Csb<rp<$Q|~ zF|u!fBy!O&>@bJhrM_M@hrbD_V*rL~$i{;~8b;HVfB%33RPcv+m0NI-F#Q+_U%{$= zh_7H1*W1X(Z>Wbg$f`Q42PUWnHHFhgH4ZS!g96A8vSXA5`3J;tS9!RHe@KG#%}c$? z2SRYT!em-CdyE4Mhht!dXuud_DvGA?h0L%m3pPLyeI>BCQPY^YW^hqcjgF9A70@yx zfA~L)Kv~!o3PB-OQX++4U<Vn|hGJk2bx?<JU@442j(@O*<!BB`!ZKOZhJ5f1b5JdH zlnFs`j(pGrYuL$EWvgJkhElK^zL<_At%N>Ehjhrgn9^EUycp7{2yj3lfhe?b*qd?K zu79WoZGnfvQ5}yI)|lv&$MH9BD3rZ{hwl`MZ~y5Tx<Ca~u!wSi#4!p0$N(e6>A7Q4 z<d-0n_!xvkV5-afjx6d0K|lmSu!BF?28tyu1dSqCz%*Iel$HEQ{c57y+SH7cu!(Cc zzSvjLN{Vtoq>v=u3(gI50Hdc>2P4ylYM5l~5C?0}guEEa+%Sc9;1Od6<CxlqN+4si zgbr`Pj;A#?k6}x4q7Xj$2T<^aa3E5p-Gm?Jhksy)b*KbuV3lA^=lWw1<|5ScP_({~ z7IE+(cmSh*Q;4;&V9f1Y@G}Q$z}C8*h;w5Qm2ExBpjtW8W9VrS+VDB^@V9Wtn{Z?h zkJt&efSX$S3ko&NDcl%NxP!jJorGy0IRC+i!V;B%9HVe`y^1wd6<#-kC@w*kiO0nl zs<4AzSSF2ey#$Gl^wS1>Xop}}hjzdYe1Nvm5C?atheN4Rv3UpKEI#nXGGaZjWLSs1 zXsm#Ihk%?H*>D=0N>;WS4VwZL=imz|K9ne~2HCI%;T)y9?o#tu10X>mzUaz=sE1=% z1AnlP^I(q9X<PX<jm+_edXPsjqKLe^=r<$|e{iq9h!w9ehmx=gBRdxq8aIxJp*5%m zf1qQ-bPw7&9!1Cp@k1Y2$c*ay2WglCY$ykZz1xeOQlReDu_%N;xJ4Yi-oGI^l-1&P z&>wA>WXJfWnvF7lP_1i7hF&~bM*s5)Vaz0vnG0%Epe|xddk862>W2Yh=<ryRq2X)E zWfhJxns5*n5Ru&7yEt-DmacS7jexs|t_BOrM%OhvcvzwGpoqEX9!8l#-yBaV{L(y4 z(|?EtlURrV|6fVu(Ad4+LWyiJiUfxX061Hdu$2TnKsU%}=?*usNtguCyq9{qtGrr@ zZ4e}Q*u>!$y$K&><8E7`0Nr<Jh7ed~AnBs({WVI)C-%l>&ESSw2A7&mrA>gEEw%=j zvXqEhntJdJ;ILUifd)aKgFc{xO|TSh00$-OhvBOSt|@DB>Y4ct+9MW+>CWa=A&QqE z&UV<XasUmlabvHupnPBgTK`I`NscAMVK_)A2W6lF+IVsu^q&^li5{n0dyoc`SXW=p zskCVqIp_p!U4va12RVBQL17A63IIIl1aTDdpU6fq+U*);3QU0_5VMDOAcs4EhQoq~ zzha_X2CN}Jt{pk@5Qr-vd7puZncE9z2p0%(IIvBahIY6Ps7wuyX-cDMhhHF#Z9cB0 zX_{DVMM+R&+yw?^PzPrq1$sVEQcwqPzz#+entJwb)v^ZRatHdFj#0@A+Wm!TXgY0x zhz?&_w-9f7bddBwArNs)dnlB%5(l`^2}NO(pZRcF7mE4}p^3n^U72klhs~fi;4f|8 zPPmYza*3ylO=iJ|82>VflS4<1_&#<L6{|={ss)i4k&{1Q7C|zLY6n?KOm@x<9wSF` z!@6FTYHn(uqbd9ce%R}m+N|n>xX0x0VXTL=ZbQ#zv>N^gaZl@CPzM{!YL;z>X-EcJ z&<5o&hxeve0k`(q!0UWa22*friuDW1vuk`Pnv<&{FZuD(z!83sh(kETv;sr=Yn*Pt z2TB+LLg=!8AYr@z4qgq9dBBHGScA&n1+}BD%@1<4Nt$+91c$=|RG_)?!x(!YT%WRA zOJ);fdykj!Rl)d!DDiR0sEs(;1v`KTMNov_L44x=X{EPVpXQ7R#fG)m!`nA4ddrPp z;teEQhf%7&7ynP6uIG(I`G!iciGfGP9UB@kZimT}4KAu#R@ntLhNR#)eOQ?>Z2;cs z%b$I?F@X3N03SYh@Cf$nr>)w*Yo+%6(+1C9fQl9`V$7(~-oI}DAno}FZr;3c@a)+m zs1lz!bNu*$^EZOpJb5i!YRsu~=gOWvckV>_FPy(meHMXxN3I-7pc;J+BskD1Rg5S} zz5~~US`&Wq<e^;2(H}f=^}xZ~18JPcn@&-h%Qr3`8(;6n1vrQgCCZ80=KX;+r&+$L zR98mDXLvE=#*Pj5g~zQPH>U6^HVx1+bH<kc>S@dOFI%vE{oIKYXU?9%)~z$QbeB(E zx>EVHY5z<3c(=}$33306sLgBud;TZ}(Dtp}x_tq-aq}mT_imKpxV>v<s+~7b<^mKZ z=-Qyrf86k~1GS6a?Rx!iI&SKZ9JznTs8sW+Ir4bD$LY}%+(n#Gms5ZJ@g|=)0=<(N za*Q1~UV#~1HP1iPyz#~-|9ry_e+C_=mpR}BfJZGum4lf*Il*O)Kkwj!Ng?9A;}1cR z5rmUJzC<v|Ht$4LplcHnStOBs{c~JJ@GW`MKPy_~Sv~c<qfK0-1rtC-(Os6$ffk{3 z9CYqX(++Cf7)hjO|B&NOLJ9G;B3|!Qqm4M){L@c9-=(=&aN&pp3Ukxc<BmDv;1!`k z&;M~`N-5u%rwx?>JZRXH<A5X2KZ9(=COLab*q@UAko07qJ1IJ0nD2xGjy;7@O5LKT zW<(OE8)Wg$JQ=kXqCqu{^UoTn{38!I;}D3EKjIMe&m@K5Lr!W#<^>OY&G>@NHWf)l ztGD0MYEWGN<kRg%H<@E<M)_Qq50?AXliZYh9v9qk4+^Mda0>PFk7D4#3hso#<x?&` z{^C<lIeLo5(R2b|lrKF0uoFx&?U?myzV%Y-Pr=9G7C<(jsIwq+;^>qjM&DG_VQ|#6 z0m(mJiB_<^_bO=-&c_v8QNFb99CW3P1^07e{~BFY&;q~YY95^g0He;MN>_Bj<^PDb z1|8`N^i4Pc2T)EpVh7jEABy~FBR)7AJtal;PM0*qbJML;(M9K6QO*VT{I5j??~~0Y zzmx`=o&U6?=w%xD7Vpq?Q<YhqDh>#x&X8ji95?yw<IJPD`FfFSeQjoEJL*(o$~D*Y z+?YSJ$gu<^{(wWD;w<t7@#4HzYb1djVP0T80rC?oMv5ao4?e^+vB)gQS&k7jwP0Zg zbQ2AEQuGy-Qw~002Oqxp70p_?iY->uM;&o!VKF-CXv57v?<B7H?o=^3K2VeE|CT)o zoh%#sa7W0Bv%N)$N;3FxM?2nEiAuyF4t1zQA95lFGLQicTWCWYgg}XR4F4rKtg)Z| z?$^H)D(x<hvq*$EQjc$7Di2xULK6B=Jd7Md5J3n+Gq9r<1oaMuLLA~nZe$OfD8nMk zPzFE9#V&CaL{Z@|VdS<)#PdO^98?@4O6oB)0Zl1cqC=o-{1Fa4DGVAGVMYLy!3;M_ z<6#w11~8Pdi)c)QY-9xD3AcE~KUO6|iMtmwgu#p(1^^mtOyqg+F~!%IgO7lmWccEA zD2?2S8xuKBLR^zHIZ{qDe9Fwfyd=bKnae8CBaap5mP&l6MjZC2hj>~;zU);iA@eea zHnw4o?-{Hjq5);Orc@Dc$isjmtffK30wp6}#Fz%`le)%ek$7oOjQ{=%B{wb7t@52J zciaQzZWM<zd3b|`6T8UU-Z7EQutsm7+GG)<NTgI!GM~ykVk8$gj&V?FN^pXbYq+6} zhy`FuQ|ewt6dEsmHB=+=D~!s5*Ai(~q!d8PjW7w~FWp##oWWC#7=dVzc;OR5wltty zDng$y`9q-n;ML;tr_Y^W^dg9ojy)I}q_9;qKF?&yYQ$*~yi90T<?EF{Y`PIB!3P_d zs9b7p*(8t(GpT;OY4Aw7mm{J~U++AWI1*xx&545_ZZZ!>zN4hYxd$OpOXzffWD#yu zH2}<T$5Q6@j)z*r9Y1r9JJ7@@i<Bc?f9)9N1hl)8h!iMtEB_E@TtpFjj00us)KUP% zffk=xt|j>h>ZumDRmV(LGYkp<I1Xzh5LN1*c{`q6Y4xPwoK{&68ruD!Sdl5BDK7!Q zMiF-sR&P?O9NhQ@H~L{kpK>*PciYoNdZt-4?MZ&ZgyI6pkvWX`79;YTsX&UB959LR zpx`;IV!k7gnLg(q$K@U7F7u?zY<0HmTp?<UmP~~1Dgg4Bh((H*%ssi5RslAQcdH_| zUDad3@Sul)|636XTV%nzSs{VLXIiS<Oe$)l6ggvBUg@#WXYACBPW%Rx+(tJ|`6}A0 z`l&Yq-4DK#QinU1RFQQg622B$M>~Rh5&C6B6A4X|H~;vX5tV_BPk;qVg1;pdq-xVJ z;7sbdh!X&)RfHeLq(p{ci4jE3?HP+0gz<FJ38>A&P=@)2iz`x-(q;skd9LlZ^sAG| zzy}tHs0fg@byuAbmnw;V3^c$O<GFRQ9_%{uKb(<{Uxr!80RY8wE|QLXgrh2)rcg!H z8%-2CA{Q(J3MkwG<8a2wsN!piaXP~|jpTzw8qqLy@(=(t^Tq-LDDbx+aJ)d~IVb6a zn4g2fmwF&_(K~4Y7QiEo7EFRMSV#aC)L0eLJ{n?1JXB?W5dd$n%o)>3M@5_go`eF4 z$G_f*Is(v+0DM{}?RbPm+7VfB-TNXv21+>|^#9O(6vo`53pbG>I|y9|0K*jl#~bj# z4{B5d6?RJ#By^TrRE*#v#27edsWO3*TjUu6uZV0aLXCk-+Ay%vbO1&`h>HLlu_>)v zWG=#ntlDAW6;Z@RnvoO4V59|xz{oC~QVvf9zz{|+Pzx>sivVPs;Z2efM!>fZl^LTV z!w7(;FTLadsKb=b2$+q8IgU`14<qa#`EGdaC+AqC!B4qJmX@6nK5M-?tt5Mjqwz3z zTBI7m1Jb`knh}Y&Stp9G2+a|S5noqi1M~3Xbo}^+i4*!FlgCI&s?2kKUStk=sdGk* zY>^-gS6@!Gh$0eg=!*mw7Whc#i~;}zBL5{Z0JpD53w*JSJA@luVYD2YK!J|x${kjr zPR42junusCt<yVkjy3G+WZqQ1>!ha&!~q|8RoP=#u%ZN*ryPKLbmJlwm50hNa*WID zY6LPnRn9en)T&rmPTbs=IbKE}6@g7aH60s9l*0rNLXubniG0vSU|ayOADMMi_*B(p z{9M$y7A(Mmk)4=Mh(j~6o>SlhEEJ!i8N#X+N!6hY8%$jQz=G-N6S{ncPNV}ncmtn> z6|A64zFCAisMjyh9aRKe_%R0Hfm&7ML%=OYJp==%1q|Hj-T66&LCC{BSYGyJRYg=o z$SuYMbVC0Ti9etj_ypL7P=!3q7ym{q!LJ!yMFimgW!^lj(nZj~8X%HD5W+qD*Fz0p zvK`fTY#GF4S)QdxAzb02aD%s1MAjV*M)X1e5S>N*Ue3Y7!@$E-r3p76AK_)h2?7!h zj?i7X8u`?g!r{~#ilSjaA!9fiZ<rxfq{H(?3BHM)k71!>@JS5Bz)k?kAP50al%asp z%I95#H}u~cP@obnhQ<YBiaEsuoP-@-(<fx!8_Y}qEWtE_UI5rYMa0015W+OlfX0Ez z;C)M+>>Phpop4pe3}OU9<W&Gvoi7AHApnIm1RdmvKmhoH>*W)U5LHfPgga1#IJko~ z;2!s21~2YJHXLE*KqFPa9sl(C)jA}DMWj<W02#h5Ly^s5FH#vsd;&N)+GUtuPQip1 z3CuB&)2{pjF=#|5kVpkaoW%Xt^F$ydJcBu)!slgy&(wo97Gp*TL?_(ET<pZ>y+lp` z$s6Rs9t1#-eFK}RSS>=1D=wNO4n#)ojti<xIUtLy4c|rZqx`{w9f$zzX<wQE8_^Nu zUr>^`+yp}Q4mVU;aFInt9M@m&1VKs`Z=j6Fe4$gs3w5EKQ;@~xED1N@g?e!VJDQ|Z z6pwyH&pQ+kK49NeScE)?8IwR>Qq4p0C>B`Y+;kwvVws*cMaw)q6r227fT_?wpuz+s z1z^5cLzTk~5!j0a0RKsZ<~tyhhCLLJ{0c=_h=qJ#-OS=9;RBk4RlfAhcX-s2r3<dD zMz=VQOTmg~$`?L{jb&z`e4W*Ez=v6M&qbaRQ7K>nvRFnml{qAYm^D<M<i$IXoN&4y zxL}ieVg$*dX1s8v7KK@W0hU2<W<_2mfKC}&2!v|j1vc&mS*-}GtQcm15<Ey#TrkGN z*x(>6LQ%#_KOD!1P~)t45mMnrJzT~=eS@ySLv7W_?vTi<flHRn137%hbud?3<;7>j zi*Lb7<DCo2d6#?9p3f}SgpdQB9Y>VziiUl|JkXhW&e~92)RbWqe=T1_JrwXDRu=+A zY7m58I@`JM3IA4Mrcx4IVm;Jxn3>}=+k-B~>}dpi6&$5lOJQ(BYnj7YP6&79jCE#? zd66B8HdRStL_NSqJORZL5CbA93F?InEkTLf(36l(OKU*UNhOryAZhq4C_JRb-Dt!O zIqFW>i=W;p)FEDxP=uMSmrkJ!Q`{7~^c0>N2xB0}b5aFzfQYa5(dG2X7U}4zD3q9$ z>f3Ob&>4oX>JPOl%VTBX0*Yy=@`kk*Bwy&Mv5M=sl54q|>$y%6N-!q6vTM7#>$}2h zy!sFN$ZNgY>%HP@zQ!26>TAFH>%RhQz!nL?*r31~?7<>z!piG(6|BNK?88EA#D?2+ zxuV2c>=(siY{vGFYG`c7dhEx7tdWRAK1f4A001HR1O;RO0RSw#03HCu0V@Ci2>$>B z2pl7@puvL(6DnNDu%W|;5F<*QNU@^Dix@L%+{m$`$Bz@qfE-D(q{)*gQ>t9avL#0| zE@R4^NwcQSn>bN^$;q>)&!0ep3XQmPsL`WHlPX;*QDn|C4bd>2N|hv3fl{k#6?!DV zkRwC3iXCe*j2E(G#fY)V!-v}+KYaWM-~+AQyA11Q#k<vMK^{6{f;c$1;9S0l$MWEj zcq<w-Y6W%;tP*a3!3P>z4nVmvLdJ|evkkCgM`+PZAB#C7Ff7X*0$)f7@SwJB1_pbO zW?H)RVu8OGmNwWMHtFG?7oSe3y!rCv&YvHQ9$X=H=?1SmjLy(BYO0Xe(*Mj60D;06 zbgRz&4R@{%_lMidpTAiC>E@h&yq`b+y?_1u^#|a80k-!afdvkzV1f!FnBaj40=JwO zXMH!+UO(Z6n?Q0+<<<`51<-?mfc;h-Wpf!P;)l8wRGMzp?FO5Q0XRpTjM*u7(2TqN zrQ?k}O8BFTIKpNlkTP;tVv)UthM|Q=i3e0+Q_&c}EF5koA!%(0gk_5b&7ucqI)EvV zZ$mOi9YfkJ)TVW7x)~>&+(C&}R#FaiSW;Fl;zvPsmAIKD3i-*1Kp}<_fE)txcU^q} zKFULZl2ZDprPpCfou+l#xzrh~)sz`R3YbS%hg!kV!zGu%uqS5)75@_e3;`%A5H7Ro z=0}JD@S;Z!j0K1ggIXF!?6AikMC_{uF{qHU)_IB)OaVCcRbb4PR9ATjT=2j%0pL39 zRJz4d5UV*ZR@b482sCE61<^8VL9P5%qqHMohc8ZtOc5#>e!+^;aN7oOzycR&lTckh z=nK?ow*+8ryXhSV*J)S^)Po$Vz-x&gfraJDU&!ria%2BQqC^@9T^m5QBpt>;w-RuZ z5X?$V?8haIcGeIct?1FnyXncnioGX$<Z#k4+0&5EC>4Bg!V8x?l^#9l)-I|wGKK^$ zjMgep*huJLs}DJR{q7DpGfmObZnxBLs0O**_D2OPaKQq2x&QX(jfQy@04-sEoc1dU z5q+GMac4w#<1D4T@{?e}jdwwrN$^cU0t7&TJX;m4%b})KkqTX#=^?KzjA-F*uK^sY z8!`b@gUl^q#|XJZmhWzo(+Q2?@=Dv5dO^(#<)Fi)Nlp4gSYf{$oDVu~iv$wC70ls5 zNOax1@1KD`)7%O{O;Tl?i96Ge1IItx%rME7kQg~Ow2&mEIl|ZVb(9bqiA6N!DB}B> zb2&l^3AxP?%Q<wcCAaKbk_yc|M~LPq?B{np&+mDDzrW)3dcU9N{U#pc(V3s&4>;b{ zJA-U|6M>3mNvzojZNSJ6y5Fi_?h&)VQ#MZjfDeGGTjs{H$Mb^wuj-}hk=LO_lAjC@ z053f3I5?dtG-hQ%oWm#R5uPx~X&~Q}yTHYwy4c`2B||<dA;pzwBoEG$k7NeylJ<Wd zUyM~b$0y7^i*A>1EhWn+utW}end+WMziZNGC0@v9ig8L$G-_86xj+_+=-a0(?u8Fs zf}dojJ(GVe%Gxz<*cZnn3ArT~%LEkBNj$it7fvzU!dW@3{8;tKb9^W+x~Q6?seT%K zEut<7+)-47d7QFF&7xn*XWzZA;(|0<LdR?8dI}Z@UO_|5EFE}p4=CzaF!mJ^cJcDS zMLw90z(h(k&V(O=gGs#v<84$GwQ_^`G)UdTUWV=2ow*kI_c7@P@?!Gu+<Z*(U97J< zWyl|3DE_f+pXMQ9D)@5y4>@Q7uLkJwm~HKA?z$;?oR;CL6*Md1Tqb;lr$DgiT)E)} zhAUz|@&0jcNttCkGfqv$Gy%Gma0tq>^<P~p6yAq3glfcLfpaLKE8P+T(D+zhP%3g5 zZFa=+{e511VVJgsnag|oc!}722%941<o7<uVO3B&;I6)Vcp8R}M|Gv4!tNt~WejDS zVqsJ1kkvC-rf?#gch2}=jp$&Z>wyd(5M%PK`(sTwrwYHX%GnbdpX<S?4*H<F5_$t3 zvs+TC36F7`wfxljg;R5@zsh5y=hMqyoLX>SH6CF#%#dEEl5MKJ#MFeJDDy}nTB5~E z@M+yeoVx5r@@XVAHQIC%Ro+!iFmFp^#yg=#OuO{;tiBAj4k@gVj~euO3dI{dD3*b? zJPi!%{W|t*y_vqRhL~VAG9kS|>$0i2k<~jgqqot*OsNSjS92pVGv#-?YC`LOe_0B@ zfPz5&3lw1h0EkfY{{ZE3lbZFZ>(KxoUO9OXi|>P4{0~r2CSJ+P{{>2EZ<fZtfHHBC zuma6hm`(veETkY3=37(tZ=m!vRD3A6E4B<cW$W4y)@G3&-V6sIg!j*P>My*@H@&%c zo${8_6!3Ra;NAgplFpIQ=9`mWUi4-zo7X$Skh0b^>iC;u<F}JK1SK0tJpe%d`KRlP zaPF@BSYJ#1>_CA@l9}N0V{O9UFV8xzr`+3HDsO(Q_ucPdo7{ABVTjTe)-l!=1Z&=j z*!-T<k$Tbkoqo&m-^^mGC$^DuZP&kzxchbpUed+)w8n9(F1&cYwZ{HXb*WY}SNn>K zKYwKB%a=R9H`f;anj4t$qkfC6{|53%5Ll$exR^Zsab^N5M%WBJ9xLud7>|?mp^V4N zgtEsIQ1R#qvSKD-;x4+3GLfj>#GXjf=s-^<YY!17Q*>u2llKhP*^{X_Ud&XQsl?T( zbPMH*sr%MCb5j|1W|-**=bWxiKXmq~n9g(yotw_W$75!)y)&=QJR+1;%;a2anwxn{ z?7+<C1`l1G&AT;IF`Mt4xc4Fn@~W~6VkP|8g=FPQc2Tm<Ji9o}Om(j0-s+r}w0B8* zymW5p{9JiKyy`rqB-3xcf>KsFUs>HWKVL=d;P$9W`8vB6NkNh|%>aUK(3@I1ui7HD zUBZ9yS(kFvVqKrk!eTwsOznHaprOC1bjy;T8oAL&KVDilm-U)9mFd6K!Y=a<L@egB zmfBWs;25;S6#wNHn=@6*FSl!YmtFyg?dz>jm^JbBqHHpi0sq=YZQXwvjFE<HwtOeI zMlH1SD`$g@PE>;WYL{Zx_A?~bJIx3#O{drON>i(~dXzt1TkF@ItzLU)u(7x{fJ3Al z?^n;&`0-XDs<7&y$D%YAseH$dF?jAm0OzCg<(=0EwQA}r1R{fK8WxB>jN_H10U=#3 z&EMC*5<8D>j09hL!5IpibZ3k@G;^OekGZU!KEaCGu(`#G?2X(UL`yz3>#&H}JX_P~ zmkb$HOtT9cy;ut}dLU?&5rBM9L!VQ>NoCAbHyeg^#;ABe7o9#tHGYp+i){X?v}Rkk zd<1r^Zsl6@sQ%ESEaqmrkG9<Hgoh@(Kff4%9r+=kUcC*#My#el7(~O)h*!Cq8N^}# zHsEZb@31tx4u|zYk@CK_&@T7-RO7)P8?~>xw5`4|-Kh1zOdklVezYosXqgS-yCCKG zro);A5u@1#xmmfuWrYowH1P@oG~kO9m4?jG2)t+lK^oFY5|u*!Xi5RXZJ5;e2;{+@ z8{Hyql2Y?l5^#bOaITGAL-AdC02fpckD^oo2K~`3AM(V@EzYXe;9`VU3M5RjS`VZZ zB;o~&B|G^#IJW^r63z7J6#dzHcc7at-t?$#A$&T7&Y!INR;d!lSXJ^A`GW<BSDAGf zORuJpt*7KGnhX-hEfo@m86poY3Xd-)3VKuBI=xj)D?{G-9~xAE$<ki~$pbLODQ}ev zEhj{~@FE}xlTm~u^zQWY9Hx^Ly)cMB&KY?nlc&|I=p-S@anX;gXw-M#SLgNC9-UDv znp9R0><{)tK6oyy+zH03bl9eQyXCE$cAw^nCC0L>%k@Uhp)za+za*WmAQ5y58Tj<F zj72my5XXfGxj}`+nJQ;?FbN>mSQKLC)0w^XHbn1dq443!U(Qsh%+!4P=RrH3asCs8 z@caHs&QdUOoGsQ57ozl&!av$cI@DJraGuCe5Vjvc=M<EJ&arYga(Dz}JSA*F6HzP# zA+R^7wB>_q>Q}xm(+deiQwY*M8X~4V1rkyzc8U+|M9TBPaH!&Ejv>n7et6o08G};f z?!lp^rDIVt^w-!*D)Llc1{9ws&F>5(Sh4N*>(X(ep+7$8Y7}KE>ypHRjrulPIM31o z7PeI@d6Rw48?WoOi@yWyQ-T)n>>{5M%&oqxrZ++hkCdN+5gpbZt~XLso?e^W(7eO# zVU;E@8P*G*A=4uERGd3W5Npp=jEzPnQK0skM8`;-q2~I30>x@{zDLK~;c(0qC9UpW zQH$fEbJb$61f06=HCDTB%R+?<oSMvZB9S4OgLas^XIUXpJkOuB2a7oWHBW-tX2XT- zn%u<roGK(&=n)6|@C8yw_YsBz0XoYa7SLEFx_!-2Kg{(;<;mEmHgk?AJKrB#6hRPp zcn}6Cn3?slntIk=2$N!3bx9(!$grD1c5wH0d6<^)4{}1aL*fL$5M2t4<79m9U#h(A zF<N3-YYt7np8;7oUFv^#`_0z*aWVREoE(v5D76Sh$YjfjJUrw>Upmi4X6c%_UqKDK zvyG)YnQ_MFyQd9n?~^~5b{%MFoPv-}0yHmIK+)OpVQ5Xy0h(6kKm}g@w^Sgl&sX#w zG3H8B27KKF!ta(AYtxH=RAL(~rr`@!p|lQaQ3^_r+4v8g4e`PgJ!%93JZl`<tFrwG zrll6f-!b5WuCe@0*F%k-`WM5(U&tXQ=139u79t~x@j{RLjRgmhezI(wP}L~&y5a8; zwuj<mNg}Vu89t4+^$cH(q^rigp)qlFqi6Pqnx1X_hDz%i$z9D_BKruz{YR%p4c7nO zGV0G?%8=XfnT4#LUx{a6X&om$-g1<N$d;iSpmq}b+R^ZEA#T{Meuw<khbAde%3UBY zmPi7a+cVl{O1H`EF<#iyS!G!3K!R;>e#o^Pg)_`E*pa2X;6l|-;;$Cst!SAU=2wS- z)}iKioSKN8g}r?v%~fE$<PhJOC!fh06J<1BM~7?STt>#R8?7I9mTnHTjdE<mq^R^| z@X3>J<Jiqt+{k5eXT-$TyUn-y9zW8q-<gs-w$<afyP7fZeELM{R)0j)vKq}vQr#z% z=R~dG6=9Qk1ShV$(GaNRLJPf?!#}|iuSR+0EIrcUEh`-t^kzjDb)zCog2L{T^>%-x zTzYo)=q3C9u&Cmq{gJrSf7uPb+AVAtxMLQ?{qwT`tmmZFpD4QZJp~_J%&$)ayX$S- zot4yAziumWe|_cdZVtTK-5B8R{^oK4NpQ<N3Q^=TdP77i0~DZvg2NyZeO)LU6yEd~ zaVAOJB1vYGq-i9XVUp}72}L8Bm$-|Xf$I<t1X^;;H(H%Qc$|(tDj6eM<ZtJx8Rwv> zl^wGs&x^5$u@ONJs-Q<oV@z+!$)7whY#wgz9BVCk7(-JVHr~5eh_-Q#o6&?1d&jvB zA8{bUFY2l=R^q%Yj`Tp3SBQkmx+?#xcXa^&p57G$Fw;X8dwl`$|9yc_DSWdt=tyU( ztiIQO`T|VOao^fKy;HlKW3pLSb~-`l(nR0q8!7_{2G@Tz@N2W}iVpZH|Lpvy-q|=> z=2<rSS(dHT`F#{PQTe9ET0WYyLA>Td^=&JQYhAAxeikSdm}m8=a<uK%nqEoO`Py%< YKuyNQu9JIuN0uA1>7)G^1pz?+AMs#Ir2qf` literal 0 HcmV?d00001 diff --git a/images/demo_MPC_semitied01.gif b/images/demo_MPC_semitied01.gif new file mode 100644 index 0000000000000000000000000000000000000000..d37e73c54190561de448c3d3679fedd520b8dd55 GIT binary patch literal 395779 zcmV)FK)=67Nk%w1VSoY|0`~zh00000{{RsV5G*R$Iysy=gWx)nJ3E8jJA~dmf!97h zKR-UOLW|@>LH|cY-$$oNNLFh~X1Pmkn@fMcOlfXTRF_X(bx&b?P-A~mWPVa-hErsI zQ)GWsT-#J)cvNM5RF2eEj?q_Ue^-ywT9aE_U;kZRVPuQCWs0_Da)f4=XJ=<<XKQq4 ziLz*Nf@zAfX^XUJi?wQO(Q0z+YIciijks%Zf@`vDY;3q}i>_^Qp>J*fZ+C-lh^TOX zlW~8wa)X<9e*SljsCam}dVPa>lI41p#Cv&udw<P+eC&OPlYP5>et(dEn1F$RgMom$ zfuEp*golKKmxP3dg@dq#gWH9Kg@uHMg@lKNgolNOhK7WOhJ=ZRhKGlRgolNPhlPlT ziT;R$fQW^Hh=qxWhlh!TfQg5NiHDAggno*Q$&9Owj*X9wjqZ?^v6GS6latGnm79~Y zla#)dm8hYYnf{okxSNE8o1f&JvB;gY)}Wutp`W3lw(6t4qou61rlqf@rRJutr>Lf` zsm`gZwa2Zk{;sj*v&H_kH8-_%cD2a1waw|a+qbw*QM$S0y1DhcSzNodx4X#NyUV-0 znVY`8$-jbxz^<;r$^OCH!NSG5!`bh}*wDq={>I11$BT@|-u}nq{>a_&$m0CS<o?Oy z{>kJ2%5`_j<NnIy|H|b4%j5pc;`z+u{><k7&4h@~n3>Pc&d>1A(13u^&;HTi^wV5k z)YRS7;?mXa{?`82*nx!DmY3Vz{@dd6+wAz;@Z;ax-r+qz;o;%o^8Vwlu;u>c<`x;} zqNM0_cIcIt=;rC@@Av7vyXxrc?C<RC{_XA3)9%E^@$mlf_xkhx^YpN>^#1?#;^X!G z`}p|x`1t?$`TY6#@A~`x`u+d={rmj-^Zfh!{QLd<{r&!^s{X#f{?F0=@$&xr{{H;_ z{`~*`{q_F+`2PL*{{8&^{r&#^{{H^${{H^{{{Q~||Nk#B|4B^$XKMe3iT~i@|M>a; z`~Cm@{Qv#`A^!_bMO0HmK~P09E-(WD0000X`2+=I0096j00000fC3o;00{p8B{lm8 zZ=Jz|2oow?$grWqhY%x5oJg^v#fum-Lj1R`9yC5joH*e^(u&EGC{wCj$+D%(mRGJ| znMt#z&6_xL>fFh*r_Y~2g9;r=w5ZXeNR#TE;)KbOID8~Q`zP-oM~zssYTe4UtJkjz zIeG*+k_#C!V7{nb%eJlCw{YXijSHr(-Met_>P`E0FW$a>>$(jr7;xacga;=!>=*H2 z#(Nb%mfRS!UdNT$66Q-evgN;E(1MwAgiV}!RoTgt2e!5A*RW&DHb|~swKyTwZrRPd zx9{J;g9{%{yg13@$A=?Fu6#Mk;Le{5kItpJbL-2YN5{^5`gZT#wO{`SpPhVo;N!)Y zSATxE$<ai3z>5bD-s;)-^XuO~J6^nX^vH4q7H54?+<^!tsNjMOHt67k5Jo8BgcMe2 z;f21L<b@X|@%9B5EEwb;e<YS@;)xYmCCL$7thHN*7{<7p7Fz7Kp^P}@sN;@2_UI#n zF!qMV5hxaE<dG!ax6VJ^;8w;NTYOR2W>i*b<&}4Jp=B3yb?N1oV1_B?m}Hh|=9y@w zspgtqM!5wTL?S8YoOF6cUp>Td;Y1l$^ftyAW&{dopoA7`=%I)vs_3GK{;8IhKSnC) zq?A@_X@*vi5oev8cIqiacM21Q6JPYXg-J@Js_Lq&w(9Duu*Ux?YpPNxq1&an=Bn$i zycVbFr@#gaY^bA_I@6y$^l-unC^YNrv(QE>?X=WZEA6t$dNIaKy>{#Ex8UOVtFYvj zdt|6iL}4rze+tn93^BYQ@4WQZYwx}I=Bw|$F`$s_pWKEk@W2EY4BWWpCakc2=&EbQ zv19ZgL<=>*VDZHmXRPtY9Cz&T#{K>~28{-nZ1TyvBE0a*EQ7^bJ;J2BF0w-O`|-^< z=X`SvCnS5uwpgGn^w31-sB+6lC!NvDF{`@;#1h-Av&At~ZS~X`$8d4gJICOzqXrf& z_Sj@Ec(l@Jr~MGRq(0298BwD^bqg(^K=;Khz|ca~FTnq+b;ecKPy^Q)_f7ZVEyzoE zvvpf+x7~~T+rytEmu>mwm~U~m+MIX3PQx=tTr&z<3(*HIxNwq3#W7Tz_25+hZL#aJ zZ{0#3qomGBA$w24N$Ppjje;GVOo9s|M!eAT<UnWc{PRL@?)mgdvt5Q3$HG0j-jhs{ zM<IDkqKC4F+g-!sF&u7j`EnCJ_awG_4?e}fc%KI&cC=swBZU;AM<JZ3n8*SKy#g8# zT$-|q0vE`@20HM85R9M%CrH5xTJVAx%%BE0$iWKI10FDwnH97ID2bt<1}|vADDofy ze;FZoLSV!s3Sk7j!9fo#$bk{`kb@K6ZxTjm!3qDewm$Lo0C736g&SJX15W5c0(xl0 z5t+EU82sxDT4IwHx5&jVdhv^345Jn`w<+qGv3ekES{G`x1)4SPc8tIuv+TCR?lGbU zK!{_q^gxOp<e(4Yn*{Q5pf!4NPZxs3VGeTO3Oh7wcResd_xjL7(!pSWK|7!(H<_yh zcJPy+45cVXNy<{15`rHLp}N90hBKIuYeLXN@%mtg6STl|-P6Sq_h$!5j;{x=*qtSc z(FY)$FKaEBME%4^$Ql4chI(Lx8|(%J8BU@PL1bbNenvn}dh?q-lHM7|SuW6-3R&+$ zf#Ik)3Lw@%ke$FqF{ar98RnrCgA+n4h>`!gPUKH+@_OGS{P=<x<e&!6KpiLk2{|_~ zq7#Lv!SX1_MsQm6q8Jh<IXC(#rpb(r?dn16VDJJs1Q7*3kf9KC;VvPNVwxxj-wXw( zPdn&9e?}l=?YO6hXC2fQ`RgGJbXY^W3E>qv#Uw_T%G3yHl%r6k6Wg>@mosSZgz^$! z9`vxkJU~HpTh%4Dd?$qS^?(t2$iw}{C%22epa#iY;SO`^Oh=N=ibeoyS~-!_ZDNs2 zVhpTc2TRz(8up81jH+TiwHl_4>Uwnv>D6MGJ6lAw2E@aKEk*$aY(=vNC)D92MzO*a zX02*1D8y!o(TaiAK$@1cSPqEyJ5K*h^ODTV;$e5o+ur*2w}^e}VuyR8+B7X}Z4})J zVQ{|XUhHvsgO}da7tp?u^llncTy@`g*NeebZ_I^P4Mf(|@|ssc!X>VH_2W^e?S^KS zoL5_iTF|Y<OS<;un{}-lJCFr#h=Ic|-kK${Tb=j72<A<C*URA8wD$`jRW8@K)>gr} z4`cJP*b8znJFB_Rx;fY{#-gj?5EnFFrd4W!SA5<DH~7V10Ub!qAOvHo^Ten18{kl^ zVe4L4!#d`#*6xd8l2VPNRZEr`&d^O3JNcq6hOv~lVos<DVObJgmX^27<t}^q%U}-k zmwm?MOg{O{;EeK=*PIa<??(SEsscis=bS1z*O|^ruydaAtmi)S`OkM&!Wq0!IW!yk zfF@Bhn-@(HbNcCLf6`Vf|1{}8LAuhIzO<$(y=hBx`qQ4Kw6+2@=!zct)CN>EqgTDQ zG>Wh{Gl_z%XHDx`+xphH&b6*{T@xD72)MuwHWyKyAXT&a*a|Txjb_q?C!OKh(2lmW zr%ml@Tl?DB&bGF<&FyY```h3Sx46Sy1}_lXJ((&ave#V^M{hw3U5Ek^=1uQ<+xy=5 z&bPkz&F_Bu``-W$xWETa@PZrs;6!lPxrJkFb|ZVLT2M<XeP96$Sp4D`&$z}n&hd_W z{No_k_ytBz@{*hU<S747dC4<yfsniW<uH%A%xCU$4=_OsBQy2Fchhi(v--g!?1C4{ z-~$hQfCC>$y3&`<^rk!g=}?b4)Hy))s$2c)RNsIGw$Amgd;RNR5Bt}to^-66{p@H@ zyV}>z_O`p7?PceH%?B;)x{oQbKF>R-T<tKmc;O5*Fggb|K={HN{_u!Tyy6$n_{K9n z0~sJZ2QV;!1Qg)%n9scCH_v&_BjEB0NB{>k5P8Tu{`9C%z3Nxb`qN`T?o1eTlXu>8 zy|ekjy!m_4kN)=F`~LT8$3Oxm(D~vUzw@6jK<Kx=0p0`u`OuHP^wU0fFBo`1*Jo<& zZ9iqUm5N4x=YjtRIFNzCxBmR-XFba+k9h>R|NZcfzx?MPf6$9w10slg`uETO{`dd& z)%R;^Q3hpzT*To7R$zcjwSC;zV2#xg$7L!*w|f}ie-^lZrndncZ~?>Deg!~(AQ*!1 zXMdAt0p+KE7np)7n1UFP0XBCdYheW;k$?*5AqG+glE4RhQeF($fDKk<Snzj&_W|X% z0g!iuNSK65xP(mDgiiQ`Pe^#{XL*+=f>s!Umj?m~Z~;Q#1|A>+EeM5TIEG|chGuw% zPDpqy7=RIH1#ut?o4^KdQh;AjfNvHhR)7Y=FbGFbfCOlVQ8Iuv=sccuN``odh?t0q zxQGjsO2_{dh`J|uD>#X#mvtJ*fy7sZSGbAwr+f(j1;sE49-x8dM~S9*imvB^u}5fK z-~@c|36k&$mcRyHfPhYr8@gcyq=E~A(1$WOgKA-mxe<tV$0m5^gFXm!HgX0Oh>Ffw zco{f_?Z=7Kn0yIP1ciVLq6m3|mx0gtji(5JtM~;@5C^chC!1giXTS$gk%I|n1#Dmm zpYRDE;RIU{2a>P}gHQ&iG6-zI2b-XSgLpYTh>Yq5I$xkALTGd-2#(IUfgM<dA6Si7 zczH#D2vG0`qS%6^=#U<{f@`>nWpD(85Hq#N2F$<)vLFnfAPcfE2u^?olHiiE01bQy zkn{fti@GQb!e9w5$p==z8O4|;WJC`}d6Y<*luEgjOxcu9`IJx@l~OsCR9Tf)d6ih1 zl~S2TQ7{D%27W{*i61$M(RcyuH<1)+g`jtlBLD&6V}j=Ajbk~N=_ig_Fmz5J2)J+t zd=dx5ppwj>gMzRkaUcwF-~?wN4814`#2^W=$P8uR1h_y9ATgMIxFwjGnVPwooY|S4 z`I(@pnLKv{T3MQ=d77x1nyR^)tof8&>6N|~e&g4Xbg6=qca~{ckp(aTqJTWrgbO}E zinTeMb*YMjHj*<*fNuDgvLFeFX$4x~1Z+SIaUce4pqNJ>2-|=<EO`b_kP9n9fbjno zn&erY=6Rl-Ig$pMj1VY7eixP>P=Q8>hV)sVWGIEgmx*YZoAg%z3@`zGPzt2b3BXVd zfM5aSXP*kXpbT1{Y6yE95}AA;3p!{8gCGlN(43@Fhs((ZPT&Q+cmy+f2G+?3k=dMm zc!vd~p6khd-Upp`33y^joc&jpXStvJDSw#903ZMYB47!Vzyhz=jSWeoM!I+*IcRHS zp%i+dAb|_cX&|Mdl7qkpd=Qu<Nul`o36Tk<eVBcOsBSIla4+h2%s8V*+JCo6g*cj{ z?>CY5X90GQ2cu|-X?mxMCyuh$1y)c7B}t)M-~^vA2xDM_e1Ho)8JK$_3BvzC46+ah zwK%9ds7VDmrix`;A^`?(0tS&7pLmLXc8ZD9=%)Qy00)o&7=V8wV5gtjs*(qLgC-az z!3Jn>5(MZbxmX6Y`Xr^Y1!%wq<+dBQN{mBkjFoDs<n(~5)T>({o0BJn4H~WXDS2j@ z00%&-Ab0@RiU6TEdZj0=;2N&s`k*gpZg*%BVCo?#ajxhJWnzk~$5y6aFoAUnt>SvG zPdIoGX?YBAdHwpY{u!_UJFo&<umKye+^PYuH=p?0uns$h<jMpa5-=|EW`oEUHfUh! z3O&aPujBNh;3uQ2Ds?1VvL<`7DC+?lAOS4fvM&3wFdMTn`?4aS0Vw}_vpAcxI=iz{ zM|EttbH35B9&1K!)<(=&aTnKeN{azY+q6vkv`!nfP&>6!TeVbswN>i@B<BGZZ~<Ja zwO{MCUCXs%E4E;30a|-<9>BF0XSHsNwQ&2kavQgFJGXWVw-)CCKJYVz2DHaGwDHP! zrDCS>!2^bSxQLs$io3Xs+qjPVxR9&3F2DmcV7QfQ1C>j;nya~(Yq>noxtg1~h?}{S z8@Z-?x~QAFs=K<Ut1jm1w+i;I!*vx7LAzsWJr(r@&-RDB+q=H|yTBW~!aKag8@$lw zY{wgI$h*7Jw!G9vfa4au(mTD>du_1$8$!!63d9f`vAqU)AIASxEHt<wXfYF0Fa<Gj zzUhm;F>wXz+rID{zw$f3^jp97d%yUbzxuns{M*0&`@aC}zwdj#1Z-y4JDO0{Sgdgn z{@@S&&=2Df!4f>d670bJU=T{ufF89cU0|_wSiK+|!XiAvBwWHKTy4R6z_ANe^-&Hk z91i2K4fQa?G+e_rY{T6U4(?zd59o8s8iDUI8csk2Lo9D1LBvCR#3G@@OWedx{KQZk z#Zo-QR9wYYe8pIt#ag_@T-?Q7jKoW<sVa=X93>C+@D1Nk!`UDW*&qp~5eIM_$8pRC zm>>;o3_>$358a@_?de|48kUo{s%@JAOiRc^I(>+o$cq2G$c)^`j*NArSbbxhy>wy~ z>o5-gFvHOB32{IN`S8ihPz}NG4A}q;&j1ajoDIQH4Ce63`M{2nzzj4T!M3|@K*ud) z5O_7)e9cFjNvDB?Cj!DO0z6yH#(d1koXpC+%sjgRU<j+Pd%cuAC*$A`GmH(!Pzm{< z56>VBG)xaxF~juW4@X%KM)}ReKn$%M3&{Ws^iU7|Ko06q%d18#djg|d5SD8z0TXZl zo)~)C8hV8M$OK)`27S;79evd|dka^HjQG%2K@a6X57k@`*uV+Pzzf%a4)1);+VIh; zk-_Vrz~G<_*nkZ)oXPv(4EnGPpMcW!FwY#(z!3jk)1=hL%u28Ote={funYUJKy8Lt zr-ZKxc@{@@zdY1Iz0~6x$r2mQJ+iR}GOXS*%_edm>d+0gVF~)656+Md*NhG25Dpl; zz!ZTE)j$v6AP>{94Ei7m&p;3101qEj5R9gb%__1Uz|WbNe5RTJ8bF(_nt~i4%t-eE zig$!HyQ)+-%r$Fu!i?C1U7O+vg9Iq0mmMLzdn=`afCDKU26Bslcq!NC&^C>T4U7%o zP!G-k3(3II^#Bgv01o894oi~K8dMeE&<!Xp5Bp#Yz3>S$tPQqJ6{mgN8`Pd{^PWZL z0U5y8nwWg2I(dRU+5A_65HNBJYj{X#0T%y|-Gz+--hBbteF0Q=0pHzntZLogsHfI< ziys==p8X)?cmyHwp)bM)l2EIk{ToyI37bF$xk8Q`O2%kI&Z~_l`d|*};14HV%{2WF z>|onk0T29e()7R&%b*OzP!A?85B{)dxMw5!{M`Eark)tsM9SXRjR7fO2Zdk<K49J* zX?1P@K2pGPFP;Z~@I5KuwLs86Zm_EPSEMX%ik0o1067R#>X>ZMr<rZBQtsat3gDKY zgLudW{%9&u@`qtlhncMw8OjW`>LF1stY;49{MhAmINDzRX1x1muE+;<XdqUNA0zS) zsYDLO01D`E;ne`c?`)Ko%oP$&A1D6}4*Ss3Gpr8mQ0P;JsS20Z6ej|Eed6vnk$_Eh z3Ek;vmjNR12mRAOG(h85=K(j~Kb9Z_5a0vNU<sp60~QeEs_q7H=jpiKdvP~+$SDuF zAO__)4(ssbw|E47650tEsLAdd<k+Y=IS69VA|hdZat_~~4d2Gz<*tYePtF^~zM;W* z-(jPRz-aC8tsB;^7BUFm2{@9n@Ch^cw=2`Y^3V^ey$_e*4Do;s#Xt}8V3Y<i;gHT1 z@=y-nuns4k4(GrN=Kv1a01y5k(hP=>GqI4)4c%yYd8ewdN6vrcX8|-Y3OoP-9)Jr{ zVBRQ5brvuQZU6xg&_At?3nKpj0p5)PZfOZF4+Xez0p(ZS9j}5(E~3mZsQN7n&mf0U zQKh7U1}54keDLH7SSq-{hhi|HIw+Hppatz-j+pQVn7{`eob-bb2V)S7d>{;HV11>+ z2ZP{_VUzTSIi+nc2xQ=jZ662v%?GFAr;;EDhv@}c-t~iU27T%TmLLqV2$L+TFh+SF z|4<wCfC-?G4)D+o<Sg+cZPs2<@Z*fq=%5dL&<|=&6_~GBKkS~AzP1;D@hHB0KW*ec z?|9|s0W<)dLO=tP00jt&gg(piK)?eq&jY~l2X^2FDInf3?gKy&2a~Ykv5(}idIlm2 zi@dmphA9R!`R+Q%2C)CA<&P=`#2SpafC)qpnKO9=843+g4hH4elCppcpRkksBn+Dn z2btoEXitMo`tE~Z5&$ts7A{$z;y7U=N!CJ1PGmtVD2d>pF#;LJIWou_E`pM*Y&r7j znJi&~tdKdfPUT9LEnU8Z8B^v=m-6J*8&~fcs&n+fjr&Ja=unycu+>A?i{HO*;A|3w z8dd64qVm?&6Xqn!7b{=Bcsb+4!&nIu3Y<ld_UwTK8aQy+5LfP8x^?Z|#hX{}Uc4DN zSfIfP4K6p6q+EClcLRnD7ACp*^yg0@2q`Av>NLrY2ndtyOp1dG!-ltfO`k@cS~Xq_ z96T@q>qH@+Pm=#W@ey{A&mcj#J~^=xr}pixTf83s;slq;<O-cQ!Og}=87G524dUbF z%N8rk#fbT2>Bt%A!q9Z(8b^|#Pq@UC5ynT%7fFMT@L^V85;HckB!!fvI$X{mW|Kh% z$?u5X&JZIGVc75@q~E+CV+)k1!Z5>iY~rxPf3&G*pIFj)2ODgHdP+m8;DP5RaJq?S zA5i!K=R~X4p@$w7cjOVnc;LY*is`J-LJP2H@Zf_B$~vonv=CUUt<qMbvPvuG@(VCr zlqf_AT!gRyF26|oYZ5x_aH9~)M9_du9wre20y_$cBab*H5n+Q2GPtr&KmVMowb#x# z;|S*@dC>nsHiRQa7>JH2BRF9OapDZ)w!jqA<Z!`cI@tnrA`W8MK+g+Fh>?X4C%Bt* z)lW8ow7m1UVq+6wgn1?__$WQY3hMaS=2l?_^bbHM1QBKoW|+B^7(Ox*#*6aU_#&iD zobbxRlzQZrCY${6=O3Vm=_MV1zKJKE6uXV;sSlCrrJs7bsYj&_*~K^Cb$-O^Ij)KX z%LfZYSkf%C)G8nWDHQ{>;fD9*fM6O%;o$=jz6?_Y5#V~uF*iK0KuriV@BxE?zwE3K z5j=>46A$*}(_xus)=N;>&LF}$K4d9FR5ofWql`~};|@1L%E&fTO&$8<IW{c0c8ln+ zO>X~-GOXjnitYq?&OcA5F5?JGJ|UwFiKdJ12rt->E;=;W$hz210vu#OXUl+_4Fw0B z)(Q!a(E1B7w$)c(cG#gO9uUzPksoZpDLlg({}C~r5C4%TsK__xk(_?F$~0gLJlKFq zw4996Eshzcxpmauy1+6iXz*bYB`&Z4ibBGC%L7a7pdp1q@_>MbNr0dMh~wq7ga!%R zuq1;IrgXjfnQbnkP=&5|+Y6s-i{ocmj`(6{>pZ$t=}3i<Bo6gHK|@-fyRu?Y_igjS z3icQEkBDE1IS+Mg!!|@sM;3!{-*xVjD!9pl3~~z)vd*xaMcoEk<nfub1{l6CpydA_ z9|U0tML0qdme7PJL}3WaQ4Xw>3nwXrVGL#X!Ftr=gW6CBI$$A-dDSCxGX!D~g*ZeK zUL`AADb*Q}B!Uc>?qI2-p7o@-m+6T>36mfOVWwvRD(vn9e))h83L%V9{2>Kn5dukY z5eE%mAO&{71u-T;gXytuig&b9@0dU+*?a;$p?c8I8ug4%9HBpa=$S0yAO@u^O%}N- z5F3mmDN-e85X8WwBJ<}cVGu(Sl1vUC1~kd1VR9r|+gYPN`JO>^aycRS&nA8&5G$l| zf5(zVdLHzVrwJoJPCx_UILED<<YXE8;D_VDakz91Qzjj<$>G2Oj(Vh{7w7+|2R8cA zk99fIn>69q5&vbRuq3I8276)w*rGZ;#SD+{+`tE>hXE1LAb1+M0Aoau0>s1xE-A1l z6FFcpd(r>{2gQH}?3sdtx)YucMUBn8For4M4Lx5t0~;c>s6~~bY?9QPMz_;Q<FL(r zmfFr2@TRG?g)e+&0E7N4!3RDp5)0hP=t#NKGmdJle&LH0SMU}-FKht~WiTol#$eH( zYE)}v0Oc9bfYPQy=tAGjP`c99Lt*fu9^lZ%2M>qUp&ZU1^ymgX(s7A*@MDGSAZuJ< zVwKNv1ye^FOTn6S0KW27VH_AuJ0bc|z+S+xtr;i=F0d!LaKNyO<$(WRGVs`jMwYUJ z#q4PqGpM3+CsW(`NOGJYhE-weBa<u+Nx3pwCum1gp4HSCzC&8jzETY6$<%3CdRyRx z)(X8%DOYZbTCSYdxTD3wNKc!;i(28fPZg$It0IqWf=EQk)CM@fCEcNb>qYd)1}M<# zlnvd8yJV%SIFl$A4_qJu=w!fI;(L}hipimwm0|`CO1&sTEHQC`SVJ58U;GxBH5uTn zadi4x1s{jO3MQ$hkh9>VN!Y=x8pL}jyx;~`7&)H}E`+m{v<pMn#1`JpRnHq0bySlU z=7NXjR{YEx<%l2tSOzw+0j_S&c$neT3Rk@1g))fc10K+T1m6Fv<gzeX0&bD#TjV)q zDp%RcSH^OdwY+66ciGEd26LFjJZ3VNS&v@mY=qUkW;Jt|&5f)jsop$iI@j6GD9KTt z^}J_3_u0>X1~j0-Wukh-LK^;f96SCIXht{M(Trw^KjPt!UI^n{;7He_HN9z0ciPWD z5=IoJ@P#e_Oo<jytYIl&0SjCJWTTrbLS;Q`TG!gvx5jm@b-im|_uALL26nK8J#1XR z#z;l#Lb8>;Y-Tsx*~$*uv!$(UEdZws)5dnTwY_a+W6Fa>1osec!jF0+;~f5=R}F0# zZgvN;M)Z(TiFQnncGuh9F{B5mgKXR~5Wxm6NI}2@?gIaS3w+=NM|i>&zHo*&+~E(0 zc*G?>af(;m;uptw#x>4x7ARp1X|}VSD;#nOlicJdpL5uJJQJJLC`6zrhlzMBj~uPs zB{j#9jxLv!deF!z=Cyg@fQ-b?63XaDM|#qgzI3KH-RVz<deo&pb*fk0>Q~2l){l;I zu6Nz*Uk~}W?>+W^)G$Yn+eanRK_hJBi0p4K`?^0!4@6g^(9_6f+vyE=zOy^u{lb=R zw@@T36u$69(gGF`pLoMJ-tmuzeB>oRdCFJb@|VYa<~6^0&UfDPlP?n3ML&Adqg=&7 zZ%K}T(hGF-BPaCeG3w_kj~ekqMm1WdjAf56AP4`x^uGsw@P$8o;uqie$4CC0Prq`T z<j5u_>W7TjA#;Dke)lVhrlQ}K<9etAnl#tZ^)>Vq&m9q|$wz<s)xUoBx8ME6hpzb7 zaX1snqY~&S5vKhi|DmvOAF!y0epn&v<3FlkhZchdG;o3ndA|m9zz2lD2$aCmtCqgA zw{<AH|Dy+Tpdq=lzz+ngdccHpkcY>iJ8=2H6pW$6Q3pOCf(n_i7?i;oq`?}r!5hTE z9Mr)b<iQ^F!5;*|AQZwOB*G#zLLS_L!MVN;=>|%}Cb%j<qIewJ0|j!RzOjnJ4Ecw{ zsR!|xz%K;DFciZvR6ns(K_EK2pOBGy$gcmn+q*O5yBd<0YYM;>ayvN0LpS^&&mjgU zfD|$W#6T3pK_o;F^TX>KG`ouhbjZ6b9E#@)5didudMF2+b3_gKhu?4lFen2s-~vqX zL@)q@H50{BG(|Nt#Z)B4R4heQWJOV2#aDDiS)4^xtVLUluvZ+#TRcTxghgNc#ayIC zVI0Or(#2gQMpgtyWF)C$T*g>b#$-IkQS6{2hyqDiLU~{zbO42(n<fIhM3x9aV{isG zgq(0xk+S;)A~=FoAp=oFj-Zjpd8EgBw8wkI$9&YsedNb}^v8b$$bb~cfh5R+G{}QQ z$b>A&-#P*!_=IN2!x^d}a$`M2qr3lzOhK?Jhfhcbc&LUG!N`#OAa$t+MM8;&Jc5)| z$(3ZumUPLNgvpqc$(f|dnzYHA#L1l0$(`iMp7hC|1j?WkN-l^4Szw1}ki8C>L{vzJ zY1%GyjER=pF=<c=69hV_j0&^z2XbHrS@?qk0n4xy%dsTOvNX%HM9Z{P%e7?7wsgz4 zgv+>;%ekb>y0pu?#LGXB1!m}mvO`MLOBZnXhI;sfYv70MdP=N>iD|mAOW21R0Y}A@ z2`sFk4^oH2!OYCm%+2J?&h*UB1kKPC&Cw*y(lpJ}M9tJx&DCVh)^yF+bj^MUp%(kg zpc^!8h=*h_25iuVu;LKOv={$*2+VTe2YO(=uL@4!WVstz7joE;5%RMWicS;avlOaM z>g+S=%uejoGwa+l?YzzsnojZjP814H5*knR+)ncBPV+2J_IywEJWuG1Px_os5lT<- zj0bXX&a0?Ro0H0Ph=pu03i47;m-wKgNQ!=Nt8+Zi2ZhiGmCy+l3Y}oS8}Tl1kP&*| zho)#I2+a}iqKBmL2cLsIOQg^gRnZk?QQ6~{|6I8hDo%5Qhuovke~?YEdIwm@hOcta z76sBE71AN)9Gwu!6Z)!tpfpCrh95do5Y(n*kcD&cp(nM{E5*_*)zU5H(k?wA&w<eu zYdLDl23Vj6ZP>B>qtO2`eYtnYE|ox0B9+rQrPDfX3A%cQF8!*12rp&2LoW@t%=w1F zEYoZP2X*)$3<T6gWz<G>)JKKXki<a$3_6=wAr~8m$C<PnwTT)U2dd<UkF1wTwbN2H z)l*f`7p+v<3oB<Z2C(`$6|Dzc-~%>DgCn?up7{jX3<}*t)n5hHU@gF)uuvcS7DNLP zSRjUf_{OVzP|v}IBQSw!rB)MI0ZABDVb#`c<yIdf)-XM<+x&-KkOm)(Ov$7NJ}?18 zx`QLA1UArub%lm(?bdp=*L&3$Jl)b9flPAsQ4dtXb>Po|CD?*B*n>sbfgOi+@CGX| zfuE^_J1~Yt0EGV)U;$y+z)02Djpf*m^;nM8S1mm|ZIB0YohE9+Lkv{6m1WtMb=jA7 z*={HU6X1hQ*n~T%ghd#H6<7gbs0R-G*q{~Kp(Wa)CA)|DGH4V{sGn5GZq9M9PX zHR6bYuv&t!+J(^Ct<~DO@!EnIny?KIY4x5;aM$&)Sd8sYd}Z6Vb=#=;k$=cjk);O( z?Z&1=*?|3rZFm+oAQZL%+>Ck~!DWND0bI5*T*E!w#r0bjSOJw>0Zgb5o+XBiHQLL? z+|1S7qD5M8<*w%g2WwipY4Rox?8Aq6hSW`6Xm|$Jg@)IK-PffCXh;WW*aq5dhT7eR zYDkA_*oOb#1>S9VhBGh$^@vzwumnMHT%YB@w{_m<g<h5T2QckYY^VlGlZJAbrZZHD zdH|qhZCM%`p?b)X%8a|p1i$JVA$ec}6Bq+Y-~&a#1O$3qX4pza-Q4`u-~HuZECth5 z<;_AXSJHJRJ|u%>9fyQHSb;Uzl^9r;$O%bU0c&;KBjDNMbq95b-VNs9d!62-HP#Z; z2ICyyAKe^21OsCD*&^MBKd@k)<yk|5h7IiC8n)qJ1yfJc;YPbn0XA3g+u=v^-Y#H< z#0g?Yg9m>o2WF5FNyvscBDXvv-y^2tDz@S)#^Nm2;w|RlF81Ot2IDa1vwDaJ5S}q{ z_1FJq9j5Zzf@fIa&7rQxDF;x<hVl&x{=DHl*5f(FQ`<yV686#3#R@BM<F(C~6yZ&E zpkvxA2j@K3J%;2+R!s6UV=)!sct~RtjvR8J2VC$1Xqeu}v55pd5jyq>Y>?zsR%Hq` zQo5}@bf|<g1qbfsWcQd?=}p1MNeX!|(KqbhUk2u27Up|PoJyXtOXUYxNQZDhWoH@( zdXNP$*am?WWo^{ndN_w<=($H;<!<(7@%vu@<&YaQH$)R;S=fSYfWpEV({!i@$25^| zmgjkPL}Okta3}|H_=j@dF?blJoCuI@@Kt;n(|E{+a-lwYR_KMkP<xK6ZbG|D;86dt zk_R;{9M6#jE9eGi%@>MxhF++Lk4#L4Ch3yKDu?E-LBoc%;!reQW5WCbpctl;9YI8E zQjRw1oYv`XY31tG27gF~Y2ZziHD9>%oKGkNnYO_4{RV!xgmxgeSsv!8rs}G;>Jz#N z&ka|brUzr#1a)}R&G}%mk?F`etD`uFW$3vT+Ud4-Yi<eWRTa#2kdc1q25^AA6aEKF zU<27?XW9b?as!2ZsE2R3m$ydj#1;xl*6PpgRAbUHaB)7IRuN9#1U5j_L%tD0n+A}s zKgw3@&=&1J-aVTDk~NHKmf+^7;K26r>wLY5rUr%4jaAXM?c0`K{}kg+Q)&Nthy}ch z=knU(GHxGwnBpuR<#$PIaWUfEcJAkf?&y~8>89@Lw(c(`W0aPz4lxmTxV^_o&U~qd z_Oa-EVIjdL?CSeX+-7gZR#ou>7kc5oZ@`?39&bKqUV<*cwws1nV8b+R?*LD1(&oQN ztOtLXra0{p&-nvB2p7$kx!G1G0jF@pj%)Gb&3{<LOik0(jtY9f4tnhto5+cC=mmM` zhHpOX@UHL{-w;ZLZ$wkWOQ?~X)|YzVjeZz$c{m(;U?FBGmvtxy58vQ)Ih;gY2XHx@ z0gMM1Z*KzUKNdQNYw(A0Ao8fd@j)o>Zjrf5SUd2RXDs}n?{jhr*KYrt<IR5fZN;hW zZb?@`7-$UX5EcRo8YKrTlw=O^K=PGr<6hbIE_2bo@T9D01jhz`NQc?(h7Jeqsi=qD zc;gIFN<;5zOsLy)RB#UN)C0FMZxDxSXa-#n^-%|2aoC1;IB*|&@j!p;t!nHG%^Z38 zKOpg;OwW)<9|RFskwFWQaxqarhu%C}p-RLFekcZDC<a?l_Eu;GQ3!=laQ0A8_GQ<F zW}pVBCSOWiXI3}q7j;y#tJ}6C$8WgnvFlzwkc4o+Wp>M)obZNTAnbnl)2jwI^QFWP zbq7#ac2RKlQt<auScO**_<{HLRak{m5Cvwp1!Sj&aF|4OxXl09>s5NE_=<-i7%xC+ z3T$w2OhhXOc(8RxSC2;Kk+TMeez*hzrM?uo@?ZTH<KBj1_=Qy<1%DrSgU9()(D|J= zcvkTFS6~HI;CE6Wg<k*$ay#&r=k^+AY>kz}NEB+s^z(32S@p2oAX-@(%86~bglm}I zi?sM5Qn!kxw`~9hTi|zqR|Qo#g;Owvw}<<<kNdV?`?hcUS6BtMw}oQZ20nMvum}9W zU*9u7uM`0nmA1WQFo(j<Z7oz(^@#MW#LTmXH?=F!cnCjDFFUhG`%-v?R#=5oV0)dH z`_hMdx>p6C|MyaG1y?WyQCN6r$Q<d#{H5<^%*pCYe0l#uGX`U5#2vvL$TwuD5G!`T ziF$wrco!EGX>_*5iL>W-pnrRVH~s3jew<&0>3;=&w}n>Nh7$~V+t=ek=f8B(M!L(1 zWVi;LP<of}hlGfHsL0HtNV|RbhtGcA6ghHrXog<^2ve#Cnks1UAi{(S7ZzMa>Xj&4 zz~Ir7CvP3bj2bs`?C9|$$dDpOk}PTRB+8U3SF&vBQsl*Y&tB3@>CYcFaP^ECtA|b7 zzl$sX{bOUv-%5G^zSXNItk=GJ<NnpGYV~T!fAy-_N_FbhtAeM-k}YfYEZVeVS+QF6 z%Hc0;^x|QyYxgeRyn6TQB`1@wRd(!%#)~(u-nIW^O~<KYNfgbdf8<v7s|U`UvUL4& z0`A;d@J(>d1cH5~YSpTSs8_RY?fSLrf^6BAa=5A)J$gtz^X~2YH*n9A{|0Y)6I-=# z=6IO{hizQHn?y}gE%WK$IFm~IZN`R9*|~Mtun8@0o@Kq<^mN%;RVo#$f%50muW$c8 z{k8E`jV)!$mM-1sw%d6H8h9Xroeeirf+bl5PC19AV@xGcX)}&Lxs62CWaE7Ci9Fer z<j*_U)Wc6K`eaj&Hs6#}m_-fBxY0ZGaPy2PwWY=ok3ITm3Tg?RB1&Ak#W*99Nh-PI zI({+8Bu5s(0}nXbfJ4tY%UIIXHa8s^Qd9rykRi)OlYwN>O+fYYNj~S4<IgwXcv&8l z<{eqjHm$VcUXVZf`KLmuc(qC^y6{tvMPJsrD5H&H71NW8=4Mf0H<i=PiI@q~6gK?$ zqv%HUkn;>P!Z;xbH0spz5t{s%SPwD1B$LiR<H3_5J&xKbk3U;=b=qoz3Og*Z#Tt7o zvcs|_C@ZEEIS#10N;@sJAJGF3an-J))KBB=qfb7v{Nvm>hbF3#Q*0c;!VxR5%Z4!Y zOhy!?@$lnnr_Ly&k2F4E^I|#WM5}FHxlLJ5H>|WmkSWPJ{4m7D9(0N-t-R6?RRn9i zv9wNVo2WeTz%yPt=q$I)KGl%d4?q9?th1mKCaf?s%_bc2Ohq@bOw@SjEW;c+>6DXP zJQiilF<<i3b1PRm?g%K<Q5)3SDREIXFw$9TT^yuDdHprmVT(OB*=3u3w%1L8qfRl! z(6i4q`t)LsiQwq;%{ujbVgd_%_<aN$e9Rn~KjrwOQ#a=HqR%x^VN*;v71cvjQ)pX$ zIp&#bzIoWWA!?bPV-1TR>7|=~I<Th@dhtK;&_ns;oXb8t?X}x}JMOvbzWeNRWxFvu z>ER@oKi8OZM=a);!;d^BN@Btkn^+>q5rS+Ig$a^4S5G?1S8|6r*Kk@5IFY~pkA_>@ z1#)Q5l+xBJV@W+f{mfQP-lzX`s=q(~dqK+ak;(xMi*N@y+dzjt^bv<U+(8nRuvsPe za0wRNp%O<hK_v#kh6*MS9r%Kdl&0j5qhYOoDv8lQZo-~Y=!kwUlp0worVI3$u!c6Q z%m0uzDWL>q9PkiOZb)_xR5&6Mmr#Z>B7uraM8Xk@2%5?u#3FJW24o?l%MAm=j+@k@ z8Kh9%(_Sb>KlO<fq^QOSkCw$XvhgIp>)*AwV-coU!UROvgd{AHM@wK&67>j2JtEYP zskHGf?4t)ZeqjnQj<Jz{LXCfHQH^@|Log*QBqrDRMjI9;H_tnjBtjX=m<d9S>j+rD zGKrPk*zFY-W27Tv$s_+kQ4ByCGo>nXsmW*Xu9v>_2Rzt8kG-)V4u11n99Xb|$go2x zzI-M$p9##Zgu)dCi5NDssm)=jMt*0^P#U8t&T*2noaQ`d?eZ3>8^Wj_&>({eWG2rQ zm>><%z@;v0!ajdg;}<Lhl3D^P(18+^ptL*%3njTUi=;1~4pm<c3+WeT@WBa3xabkY zzz1Ti>Y+H~RXy0lr&VmTq$b7YDNIqQ=rA-_9(^g&JeJAB{KFg1fCf&h(GPjy6Q(DO z5yC9S8d(zcN6b2-P%NoGpE8wE5yd1q)S;E8XowtC>1k6>!bLCcNg%2?DOkf=ELXTf z6{ctgHdwmUtg`=gNmSXSM9CpnxwiEsXrf0yNdctz6|}E@{i|9A!j`cp6jyaU?2@{M z&c!mev5vJ}NZS*}qEZ$i@-s+n3iXd>#_qA6{VZrhYtEM`ZJmfcZIlxAk8ZTW6>sTN zWn+sF)QqLIOgYjeQLEd|JaxCbtrs||!3t|O%qxIBE^_@Umam+#A23?0Z=(yC-bxp- zXz~X*eqkEe%C@@)fh3W@ajV=`x4c)Ou6fytCZG6IN2q%*eB%pWLDj|<Zp&YK^Q#xQ z>bI#QEJl0YW8CBtxWECWC82atkH+-3!FA!UgCA;<!RVqD2o;ofGrU(p4P>Pifo_CD z>_%RSw#5G?K5_1p){U^lkGmR{ZCP4D3QRc@#Wub%j%}<?5yO;H*rEn0Sn<ynYnZ<8 zYsDnT3t}EKnIj^DaFg43U2Fj3A#5SChG|Q&Q!oP?b0Tk)MQjl$hdGN=_NOQu!k^eC ztGfd!g(!dlj(60^rDeWzMiiUlJ@fg*O*u|`ha5``@0CYGEoy&C5tlbruFsBsG^A5Z zW;~nl%sCp%Kn$FgG?%8+rE$+?HBFX-*0&gxq%^8CGU-(FuU7yzh0|ao>shlV(TpfW z9&oK|Jxrn$uP6l=X)SD7tIocwQYx#XjNWATZ%R@HFbiEgM%og}4a$rsJ!!@QH?+b( zls*5b#Sq2pGV3|g=05i`U#1Ru6k`<bS+1xrD~eYXVrJ~R_qvqnfj_(j-tjIAD-^7> zrgRqF20wVD*Kw^?kDFu8u17Ii0i@Ybyy6zWIL1?fnmCxi2Yj%D9q0gZIsk$QCWr$I zDTeWtv%KP{3Aa1~#*T(FS*A2M;laM~3RYlRzNZ_DD@dUP6DZ*iAV2ya{-6X3prO_j z^Z9)cT&S7fyva^NIM%biIo;Ib8-qQCSdTRjSEPas9w<7}^WX*@(7*&z==X-hE+{R- zT<dnf`;B*8_5Ky6>tCnrSi*t^q95H3alk<YDj)+BlmYJ27GrI7LG`_h*yfbaTD|`) zvva_c#hPYEJIHnLgCXdF3XF$4;4AhDM1lG8s9m<}s|B*bL_B_+cf~2#Ky;)30S-L? z!XA`v0yM-L(FtxQ$YP(~C!1FJ8&evz-LmtRQ~%<sz&*#&4h0=Nf%ijK0$6GTmg<wA z6<~S!>d)nT^NzXs>z7vY{}FLmbDkBUkb()Quy!2eArBxIJ{#yrN+H@Q6bf#s-}~uS z`z0X3v{c?eTMNC=Wz`2Cm;eoMpB}`48}NY}(1FRt!CQz<Dh!%&Jw#9>9|QhYX{iSb zwxA2XAPmN!49*}8)}RgEAP(lB4(=ci_8<-d)%-=E3zda@gu*HmgBx6c%qag83pC-( z$V?&Vg0}%)g0Y@F_#hT$p%!i-7j~f+ejylgA;YC$oj{z#31ESJmnpo0E`)*(6hR#j zfxFD%93DX)*ut-A*}p;3DoD}*p&%Ka)&d41wM+`c*+R5U7X73YDd>VH7=a8Rf-dL+ zCrpARUZN$A!Yjd2Eb*bSZOf7oVpffzD9Xs0C8DOO!b9i+BkVvJl!7jZg2m_p8`dH% zg2f{Jn_19TADS8{mf~UEiTeTLlH|s51Q=?_*XXQSF-*b^?0_gpAq!0-oaG2@0SnZj z&fJxPE&PjMOdc`T6)A?JflL`NsLt0Nmnw+DDO6YyjDRGHLXIS2F6#dxK|xX}$eEIn zV_U%<Kbj)1U{^JS!YhnLp9mX$ghGYYK?mSLG>*bF28+fG8%0*+DkuyK{eqm}*FQGZ zf^;O5pb3?D5wJwfkN^lGpg<A8A~jASmRZ(UtOEJW2}qua6&)Z>3I)jQkOTf=k}zLQ zCe{_z12^p4<H2M>s6r@=f-WG!2t;BrlmaP`f)Ku>K^zoVa6>&jS5T4!Ao9;!4P#dp z$d~+sEAdCN%m>f4LNUBT9z-G=jsjJN1+d5+SS6*x2pmSV-ap=CPUc3ySVX`W3_OGo zPln=o0OeTDh!y<<dzePDpa#!9#4F%I2Nc01k^)5LA!^uVSS9}>E7+HjAZAeBq+m?P zwxAEL5JhghLxz-t2oVUBgymu;)<1AXiz(uAJw!1uf((Q~G-@Ub{hCW!<!td)H_k<E z+N4F0gFFnzfb>c?G($B|gLP6vbru6PXhS{F*=X`5*XZ4HHppF38La7{S&YIf^yX7~ zf-VRrHP)j&{?&4=Mx1#WM~<gP#0am@1D;evGZ4cw0K+fHqk$eMkq~G#kdHCuPfIma zIf|!#l4YWVMl+;YGMZH`PGxV-zzp<(D?#LN)`oF1#M}i*Gf<L)l4dv>O+X?FH#7q< z*aCvG(7dgN!k~sIkb*oiB{MWbH!#HsVwHI)=7b(d=9T}$E4V^#s)89cVk^|ahfd;V zQsYsUDBZOJJLm)gF6PyM6gx~Oj({EfbQ+JG-$j~&JhoOdFh#+Er~j1Jkv7O+K;NFI zPC+W9F4VyZ1Ob)$npD2RL+DkBGQ>3&irvtpetOL|xYCe}U$Y>Dh9-nr$w#4e*eg)O zRCvu^vS^%+<D4dqJlqO41XxP3WgSdF7-T{*%;joCn|#hEfq~n7P3YB3PNUiaBT-zY z^_9O3=PIPxFI0n4oTjJp1*nE<XHXfBt|uepKoPj7p#Itb7V0Cp$9+!8SkB2U{X?#* zLcdwul`=%4l|_(L4L9gUZWKm=B&)L8MQ#YjIE?=TJy3&vA%YRiKpoKHpz5Zz_6WsT zj6D2dr}kx{0H)!L1AuwOTTtAg&CgjR<Ia&nn;siGuq$vd-#2b7$9Am8ek{m_tjLZm z$(F3io-E3ytjew|%bu)86b3tx!#uddBkF5rc3V~cE5I70XpT^#v@FmDt<VlF(H8AD zb}DQ7XE^|vUNOu-jO!4d0$ZGh#n5XrX@t?5>|RRfy8=gUNX9&52plAVA;97&h-hud zs@j5GDwtJ~^vbc4;a!Qw7hRT+%x6+wUt64lvBges7-`q~M&EtIJZOb11OX)2%_s!J zG*YY1M$I}l!<EnlkrHFT;EA4qnp(t`V6p$jTg2HU<tJ|pV&HbhbAfHIOhOg30X3+@ zJj{bMPNPBc)!G`EYdnO^EoQ*<O4E>N?WzT9kQMrE10~s6Z&+UGeiX<|iC~C>e}2O1 zQUf=L!#r#YmCYkxS)}%EudFTCHZB_SL1-!N(_o0k=BdtJaj*KWMnZtsuy!XX#;sj( zZSvklVFZjg^vWkBK^ruKI<&()&}+;ghoC*Kk65WFkdIWssq%qLC(*-<TH}rc6qcbQ zD-drybQEt~9o}_t)>%ZCxKka}f&aRLHwes_1yW?8B3T%4LR^_CG$NvSFb!{xxQPca z$e2U8@N6ks=o(Eqy$tf!uU+}&Hu(Q1G~huMK!WSegL5Lvl$fIg^YC)9g+siSC=>%w zoDvF?<Hj1}dLUv%`m0r5R&BTz@k-SOyDJfY!~-LWRf+HtOO-cdM-=O1qBO;OCZd*k zCRphQZM@Gb%mr$Kq+nbNJ>&_`fsr5kF+RR8y#Pj7)-WaWSyTAMJ7hy0EHP2ELv{?t z*iaQBRat6~f|ltl!%U@nyl**NRVBZ2*|=u!LhZk5nOhJqMwrtOw=ql15#eg`5;uiA zj6*mGhDY3_W$ba<9_0Eq^P#QA&b>lT?2y6k&{iZREIG3_58In58u2i&N&qe|I|!Xj z*f+F;J3zt=KmxXm13DidNDTkxD9fXN*zLc5T{m7yV9M|10phs)f@HD+p;7VFylN>F ziWP$MNt7EbH?%ob4k)w3Ik!VC41pm;PCL9qVP+1&84ftSrz@~US7jqf%LiGNMJh-$ zIP_h?Idmmgjx){ZDx}WSm9$Nt&Oy0CD|Ev}pwIb0lRCMyP?J-msRKK>14Sdj8~8#{ zxWhXnE#`QRic(o9)CT;_?(g=TY|KWm76W+z@ld~X>`c=@F0#L6bs8GPSXfPsMU$M4 zGfGGXIlO~AWP(!rLQ{xCJ0J?iqQry^20KKY74ucE{%(C<qztV}A=l(}W!EC1Ct8b| zC)R4^)`U!iA!cW`W^eyCXTRWsRs?p?t3TAj6SM(d*MnYvHV<ON?(%L*p`M0a7HT|% z<m$#DcQ$V4wr*o#OF^G4@CPjuw3fLN1{cj0YBn3|rvn?eF&{=fWI|~(HELr^dVJVV z{q=<T#2$C<L2=kk&qvR>g**a-i3Ah!DfHzXCQ-u2KzR3ezxR6?+1sM`NQg6Brw{Y8 z!#fb~b5lVbNOw1E*2Q8GO{9<S&_i1;()0;gamteUousMBOG1O>m-K^ZRCRC@bU~{Q zTT+r0o)=JwWg8d9l(@s8)I%*$foZG5JGjVcRyIq3v2*b2UNH<&xdoi9r%v3;VwYw> z&N3Nmc>7-DlD_`}Q}nf6B=>l>)4VnSbU=&0MJA{?Q@=x0-7tN_1juN`M;oPE4D=X* z#i{CoPUr?<5IAE4ab%5@kdx6xwuLC9D27xytGqQ_YlK`oIh1#2RBhJ%cClRq%+a_` z*U=(cwk>}USfT3`EY2iH8uMZvOf|HY2u3#E%4hsEgElBCR_t=%Uingd!%dL3X{X0H zSXFV{s$>*HEbb^}zSf#gt=^K=aDjzuImB4#LNVA)x9TToV3#7TMte6hus;kw78aa; zgp=$xvM0N;f8p$XgFDo9baP2Kpc1vC@Mf#FdQb$SJdPBavMRqu=L$3_v;sZby4_Sa zwlBN7ue-8K2~HsYW00r0LU^JsSc<iOA-0Hks7?tvOmrrwfoc1vIJkqr9OkY_$G{>7 zHGl<zHat7tVlh;MR))zF?<YT(;vp8~#7Mf@E|*SgWwCpNrjO-Uwv=48Lp%JtY4=KM z|E$M`ymt6ygQ`t%EvU`kyv^H<P6$t@${aY3WxOIEMO0W>$@}~ql;nQd#e2lU>3eNX zm|WAf%KJi%c*9;FcgRxck@!Of6P(w3eRQ569)D$RzBs~!G{XeD+B=MDWF+x0dR6%2 zSnj$I&vjh`Jk`^KIEcdyGdj%U#h3b};6vBO+Nx?&Q=}R_)XZ*uO;S9-xL?z+N8J+A zgm!vB_sZ-4Js@RF;m<kJ?0R;^M~1>T>BpCMPxe;+{njeEu5jw$TTw3O+0vhf(X2z0 z_xFEmMVIvU6_LH?!{2kVLq9Z6dqFnGuWdoFkO3O^c}YG*3B_dG#7%e(^?Qz73k9Yx z$#XTYf8xF`L`RqG`c3{m00qBRv>U5$v-+=ppJbMT$);6|d;`W@IS2+taM5aUgZ@7Q z|4TeTa1)4)8@qb+{QZ;X&tJK6^5m^s2T@{0ix)9w)VPtOMTQL7u@m>M-ZMx~>iAOk zt{XXsFC%u8Ig@5hn>TUh)VY&qPoF<~!t__Kn5|W%R;@C%lxb6^PoYL#s#I!Kt5uVh zD%HyW)wX&Rfm$S2GHhA15+OPq`fpveXU(3SIweX}DY|z>$rbgh8MJ<5>nW6{@ND6U zFZtE02Mte^l>Fv>16R*sWw3@ZXV$!#b7#*piQ3YdRBmb0r%|U)t?HCi)vsZzPL*mj zscQA&`71p3*=OHu4-Z!C&l@mXrbxA7<;s;RRist1lFn+?tGTC2{VL{nFxbn!F@A^m zkKH%L(CSoy6f&|pdi21@mp`9=ea?f)ziM?V`gH&Q0Sr(;>70ATKwS)cMHg0_3y>63 zUKvnA0AH!jlxE6_C!VsvBFjF^*kb1&dfus~nN%LEa1{bonQbY#oRf>RRa}vd6jE6K z`K20q0%PaHi$WT2op1hWC!6#j`KO+C#_1=df5;0-%8-7n(#k8b?Cc+MA~dD7tH5kZ z#-yqXg^@GSJd+bqSV?868|BhP7fwp?GR&y5+6x<yd^D>hC;<&r&_M|;)X+l_O>{(h zpp@qzadffeMx>m()2XDKBhwUMs@aCeh?ERW(NReybRBZcGZIO~#u>+-Crgc0)>&z- z)z({a%~jW3dBt@d{Z=_8DNC`UYAIG;nM4R1SZLPS6?llllVDGgbCg-y7$J#JT4|+} zFNrlJ&tLW&O4MD~@i0rDM%*USyab$WHs_p^SKfN>eU8i<Z7If`gxJyWyWjr*QKz4J z=E(++Bp^{N9CyYMQAo64dTHH@G0s@y@ErX{Ke^_mSLBgNF1b=KPkCh&CQMkt<(FSJ z!3|x20Y(oaN+{utK6DXfDSS;1T3@@!WoY1_9PMpmnjne?A$N)*#b;Bbv)9FNFFh(L zQu-aI9{Mz7hn#j4n<R)JAmPy+e%^U<9pILZTkg55govSfnjytHVU5K)s@8Ow!~_=D z;De4h_;4c*H`rLg1wq0np$I(ak~29<!6kOwa*y^&UAixV387+ssZQ&@{VrBqqHpsD zqW3y;S{`oN;c*hjeCdatdHAUacF=(jUU<#y_6MB2TXZw^s9e-L4-=06utR$3|EOMx zW_hSX6a}xn>)X=&-rVSz!s4yh^GW^6A9||!#mitxJLT%-@icZ7QdVhZvV_ndR57vV z;SPG-t_{?H%sj@ymPPfCfem!v10fhe37(H3$HNi*q@pQZ6k>4Gs~#P2fCCn+AO)N# z#wc1bidWbLWpY_wR!U(DY#aoA=9?h;B%+~`Ea!Bw@!=0q1H)G6VjIBW(fJeurSi<9 z9lqE@66!z=b%+Cj@VMa>v6w|IZjp<LLdfw%L9G`7F*ahV*7J@ah(GK>2sqHe<mk|> zNvu#SNO2)k$e5a}tfF5GOqbGtHy(MsCsLzXh0qY0$dZLDQ^5-Vg)MFa4;}#pCLuwU zJL=&JJD|-M@|Xt#od%!bjgpk53`_CAs7O_sta2RWK@W5wfhVW|4}zeB8|1h`6|GX0 zvq4I~z6KMY2<cB<wADiBfsMQ&#dKD4<};xgO=&9c6w+D6Gq8b>Ua?~wB*`Qof{+Py zu%jIaB!@B4nND@ClbxihAo6CDlxap2Xwgx{jpS4eJ9vNvNNB?!>;O<Z<RK0$aKRjz zIZuUJZI6BI-yefFqIlF}8^}4zZ1R}Vj9POmx)_Hjc>)m;jihYggoHZO(JFNargNrr z=}Tdn5mYuq6s-A@M(+qd70Rg(MW8_oJa7a+2x5BE<3le0OMy|G!p4_;EC$?Kij#<Z zZfWCT$NH*alse&$KQ>+JS5Gq){OtuC@JNWoZt|6G48<QO2?Heh;SX|1Nr_U5>0R-9 z*O}Hdr#~E{3-PBnT@-^8M$kbJ!te?`K(DApjUx*Xs#LI|rm4W3h+rrQQP9z2qT5i# z-gp^W(T)tGs~Dp0-i8x;z(XC1X~#*TI3jY)bxO6(>uqsM%6HbZp1n+kQbK{OVlW~P zGXOyyJfWZsu7Cw@0EG0OE4{|0V2<(}Eh3c)$*)l<EL$pOI}f!Ge`Hl$lQnN_Vx*T} zfJ2+4TE{rd^Nw7+!7<ce$Tr@=koPEtzx)O7e*ql-U;+1Uw>JH&U#0enVzdGgI12(J zLZJ(-=#3Lc7~BzTU;`eo0K+UWffBST+4GL+D8SegkItnl%~n+&Is`|H42iFW&X~r} zJQ-3>OOJ|?uOcFK$&zx>hA=$BzVyIvL^MRP9Y-~{O?GnK#0!pUe5;YrBomohQ!QXn zA_yZWfg$81VZE(rIg;Rk3DBJ8maV`EjA(^*YCL1{xo(gk?MXb~LDh`C<R4(9%CImP z==!}#PYB@%JGe2Fc}SuTNvK7rMiP=FKbg{%rrUeK0ghLs;*NiF;VB}li&kuM26#xW zE=Dm5t&GV_ui!)>3h{?n&$<vQe8p1cCuo%a5sh;^28y0BrVuC@=c3Bf^|A5Dw_g^c z9tpWf*uD`!aufmyc&LRz!~qX0vV+N%_V%~!1Cx5N;}x#3lWXRpi(mu;5i^)U5O^lx zQIMjJs53<v6{OsJBS<UAcFJfj1dj1_yCx6;_J`i{Ivu|RZ=^7H=KLLTQ#i*Jt*C~; z=?sx?M0*~!s6rA9!Ht#7<D3Ks_sLQ2nH`I$kj#7vsFhoYIuu|Ai1389>R5^uDy6SV zp^IH|?z8wEyRWaXO|vuZ>zzy$kQ)03L$Yc}iBDZzN6{0X&iTn&sG$wDpawfW={1w5 zoa|-COeI4TtOJMQ6gBfiA3|_~Fl562K;6qZz)?0v|4fBis|KI0?`TciV0`RM`{RJg zGopID!WJZ6MVuiY`DZq?81z`lP`VL_Ds-JkpA=xD5FdKckDm0m`ihdGUJ3%8LT|;; zMIUBx0vRBJX2GZn(6v$_70J_TFw$49L8d&(Ka=mQ7(7GJmo$yNN887HGoYzX_0}i{ z8j8vM5DZa^W_MFVlQ#SJ!GE8M`6C|K_=Q#&Gz!;qq6jhwf+0jfGdlhJ%FvJg^0bl) zU1WOTO4kXV56(&;BEM1(&^qn@0u4sEWw1Em39zplK8YK^AtZh${4DSSGoyISPZUD! z_1dovXipbzgx>niDh?0<!34+ubYZo|heK8@OWs4$>Os`BLdJfp{%|k{b#MoHum|fe zI`F9&JV6iMtr^szoM?+363+iHunC<|C+r3ulu1rFAqPqz2<qS!*6sF?LPg?<Oui6P z^u-6sunfsiShUNml5Ut7uIbiAL%^XMN`Vv_>A*(p4pRf4UV#yeU<ZN#5&T6QzF{5c z;USpt2@x?7nWh^OqaLs!4<uj*41p5{%P#5y%l^(Z><|ynYbiF3Q|bX8yss>H17r5e zXO!o<RB;teAruts^>CmB>Yx;g;T1&T88D8!6mb`MaU(=z8~~#phyf0eAPf*8-*T?2 zR&g1bkzV3S6o4TY`@}5&Z0NrhA~fm(_&9OIUWD!Bq!Zfj4_y!U$i=LZsPxb=9o2Ci zg>6X817QTA4T7K+nxPsDgbS%<8}%_ZluA0fp~V>Gp#rc<{$U=K!OAM@zIx>31E ztq4L;6jZH_T7lW<tQRrz3ArmshGa?R!57qE1`Gig42CGqPv<aEAyxA4l<LjO0URji zEWGO(-lHaM@+NUICv|csd2$JLXd9A)=O7LR?*!(C%Lv|055i0oNU+}C>?<gyC#7;K zsj@1q@+z@1E46Yfxw0$0@+-kIET>YW*uf#dVdD^H9s*$ps^HN^D!;%17%q`2PLL>% zZI3Fl9@If}#PU7=Ch8f$t0v1YZ-&w?UoI0{QQdR_5k{aGZ%)GQZZx!_Tg+oH-h&-6 zGcz@Fix3Ty>OmHg;QhEkNy6^whN2qu#*7RT@V<mOv;vX@?lP0_1%HGhOw;_NZZ)Ce zj#R-FX=W1YpaVowK}umF?~Y8g!WB}X88|B*SgP<cGCE=EcNF3qz-}I>VPV?97evk< z%BlO}AuY;5)Uaddbo1DlV-=urPvF5Y#-kLo#33AobiT#@&XXzB^Ayz26Br=`aKIR? zMTL$NWklvE$VJD#0y?F0K}|_uz9E6iDHA>p5_};o#o=7mfl5Z?ABy5A?la=#LOLWc zB815-01z<$t&u2NVdD6Xk(x1)zK}uW0vL3`6N*6gz)Tl*feUp>=jhO;q=Pxouo%W8 zR5tTSku*t1<s4%$+Rmdf>Yx@z^ONQw95OVAauOSif=qhrMZHvLa>}$UGVvH_wZ5yJ z<e?lY<YYcnE(Gfp`XB~60J#uk7QE-~9;Ai3N;>#sh?-4F0X0wsRZv1A+DKv&+5ib4 zp%&aBfV{yS!T~=3<vs2O>9Bzs45=<Z)NkxUhRljBWb=H?)D7zcEOe+E_%w4?QZ;<D zMvFiK{*d2P4KH+#nNZ^?Ci4~e0XRyOL4DPf$Z{O=ERzZWip1%YwxKK!vBzS<QAAA@ zl5JK0_i-ugLVsGYFgk=(e*_Nmh851!O-(^ghEN73pblKY7UYr(=>luyLO-~Hvo7*i z<+YSX3dL~24Z<Lbju3$oXjwUiA+)qU?QK)BM&~k(vpAy~*U7B3)H+s^^;&NabHEP~ zp%iHF_B6F9Q-&0Zs8R>@V?j3b#^a+DgBaWj65i$?!l4_=fmVh?3Y&pH?2}-L1;?0e zG6LhA8i+PO#BP#FG??j2T@*&zBo!27xY}<AW>HS&FveU|v@k^!nt>dybzZIZVxUCH z>H!#)#2a!U46u+I{=pr};Ts%<Ax6<AL_{$}jX~_?OW}5rehV7Q0r?_=95e$y1@P(r zr0^H!a`>Q0?^1y^6oeD#AP8ol4??hM4=H(UF!GYZ_|^+yueNg61tPSKGSIRfyg?8U zs}@%3AGX0A$RlOpCMQAyV7HX_0Jn8#%!Tgf6~-brJVS4x4C;WEbzS#rfa?`#w82Us z4B`#d1oYN+*IxEWM?z6SEw_0ya3SD<NVE<PBvFdQW+a$bBZ}u8-T@qnp)SVcc*S?} ztd3Izu2;`a`K|<WLnBk~up3u_W;!7_Cm;+w0TDQ15*UF_YBeA65Qh2%A<)-(3D`3n zbS&oK7y@Aix(-U(!5iKoJpDB%G(_8+wG~+7XXr&*aZ0J~2OGd)fX|L+=>zTm7R(gt z1n^qXcY%QvieLsh00L-02WY@$C;)qul9>jUej2KEM7V%~_>^M8f@w!FKof07GcCs< zL#NR!gu-}e%H?RbSdt<y7cP5q!r)L;o&KjDfI&G56HGMGOG1GZXhstZ0R(2C4)8z% zV1~Ki*aQx0=XUsos71S+Gi3F6kFm&XnTQ&mC=9ss2+K(~Ot*p5$8}~9X!mZ4p+YH& z0pkuif^0Y3T5O`ap<7%bjIW|JRDlEg<@JoK=8`K7Ouz{Y#|={Xa4d`tBux5L0hmMy zi-Wj;k4E7_Vx`Kd8J-9dia{Na^@`DIGxkdLro)k$qCrqZ7er;rp7&J$1`<4)29s+f zV>`Jt+^+qKzz}ZE7FwYbh`<D(K%fGOdVIhH=)hs84#!@BvuL@N;dvCvqaE^095R6l z6ctLSv_0eFJIY~^^AVYw;(m$&8zdDxPE-IdxgNS<j4cJQc&Z3w@fdeu-h4Ei<Djvi zO9@OM4$4j9V91O~bb{fzq=RFK`5AzegqL+7B?hA%#K9fj;hjSYtpHXoRZm|Cc7DWE zG322ivi2}KgXyqDhrS_I&9MGh;q@W_3*|&*Zm;gbd7L%c4#Ih6@-(Tn`tfu@9=MI9 zO}dsf<UQomtGmIQEa3^BAW1%{8$wtfEEuc}V+o-I9I!zI`@>uRt8T0LT2rddnyiBq z3c9Z5Lt)X0v+Cg+m?K=|q7`uD4T8WEf}v-)u-{yb2v$G{$a#7IfulWIjF3%;Ug7lk zxU@~%Wx+vM72_8y0gAp39?U6FLY0foaea=5KNy5fi8Anz#f+H^dR;<`4BMCxyBma5 zerC)$x<wR1V0g8HDY+_TMgg-kntF<gW$3^aNFn%k7uRURw3t~^PkX${TTs5D9>C#3 z85$SjAZ*zI9@@br_AABOX&of#u5qMGOksQ#>Sv7a70g44R!Y1jD7DV?uz5tWH(421 zsawh|2zI~+@_-R&QBJDkK{(;6tNIUE=Ck8gWK_^c%6r8BNBq6c=^dZ}5{fZNpyV5X zTJ#j-R34%j9;9eL9FdTvE{dUb(rLK6sJM}3jC}|{Swj~Xp{Gh<2cW<QCV>+u@q014 zoXMHP(fQ%J3J;wl#3z}=xqMLHMr;gX9)hfTS85!*!oNaKG2X)++~HDf(LfkdPc`Z= z+tn81kJ&<zQADJRNO(S`IkC$vz2<xsc1m20Ko5c-XTksqG=Za)ps3tHdg$QH_`v9V z?|-#MZwMo-IlWQ5nn(}^6NK#A#>pGnfu-n1nEoNpumKpp#T9O?>b5acR_M+hCCN^= zgp&rm3_{f4=keqWIVX$~nbtt`APhzT2P(j2Hp~Y9j=%+)WpFIv74(I>0e4JZv-0?- z%ennXzg%o+#~r|d+M@Iw#x|ypbdV;h9;zW-Q**nKd-zPlK;$BTkq%I{T)3mzH%wSG zkb4t-=qMsH)kZ;1T%i`=z-3wn%@n|8(%=ttAr!)hE;A9QyqiC?D_%L>dA(zH($eEV zF45j0GQ9e$Y5I28y&7t<PO4*Xz^Xc=gDw=L8=B3VemFjKNL%Y81{XOu{YEZw&Ojzp zg+}2MV66}YVGZyA2Ns|X7D4@jVTB}KD931dhP2sEe&aC^CblG9IJeQ>KuUpm9=ah) zViH(m!XL~knQAc=Bwk$T{okb`o(zN)ERh!fBe|>$`RuJ^-@)TDRTPDrqIIi|j%ros z5Jb6LArm|y2vFbzb|4HoVX%C?rq=ZLYK&U5Bbzi{>#bJX%0s=MArPLx5GwQ^!tQM@ z8MmgHM=sU%@WMb^UiQgE_k{i~6s(|!;~iYWBC`IJ`us!wAz%~Ab?a}1s?IKkML)H0 zvJn9h!e9bwpyoKCB3nTz=uix4j7+2!9ArnXJwFklWVYskByd3uuy5qLsX608(l(^Y zlmxEx>>IG57+jAvyazAze|zjdk^!O~J%9h?{X2;8-@1hi8#;UlF`~qY3+p|jh%uwa zhVtb3qlfL6C{d<XnL3FwrOK5oTc$k!b!yc}QKMe%3Z~0Yogflk6!Fvwn66f&M8R~) za+Ok1z`*(Q*KwoNsZ^_4y^1xf)~#Hvc4Wtn965LXsO@Rf#+ST#^Tu_Q7cU;zu5{~0 zd`qqzIC${t)vHzvTd`ugbO|-AYp~#Q0-r*ymoTzIyIDJ0q+HpfKf$3yDNO}BwCK^K zOPdC*RF!I&r%H_sHA+{oV6PC>*&#s>o>GNhks_t)^k}84PW`F}52`%O%$qxZ4n6u+ zu;bkMeY7WtAz$j)x*Nwg>N<M#q?^we_pQ8g<<^xW51*dj`F`WW0|&0-)AN<rUFJ`b zdf+re$}2}9g<yg!vBuyjrj!Ez;YbC_hDZ=$l#qiSq4f6Kfk>@V3N_d~B_4n#o`_<K zl$E#+Sli4u2^Do1Vvs-Lj6=|J>!>Fliz+s!9(g3n1J+y_fhC@i`|YUXj}FE4pOXve z=g)won51BqS|SBumm|GG*eHDjA;SoIa6;HB9kz7TD%yZUPdq+KNoSpQ0?6J%|Bxe( zU(diHqc7sj!_GH5-iauaQ|dV9U5qxF=yFj?sh&cwv;q@o4Q|S5r=EW5X_u~*0;VU3 z?65-*XA)KlDW<G;il(cyqRT-4utQ#=y6(y=MlALyk9_5P!%jW(5K~7LnKaW+JKua$ zP_NQXOO>P-C0b88udq`8oNC^F3vRgLj!SO2--_BQsl{+IW(h&qL7Ofkm84WDvlcT@ zJ#SIVZ@<%q<ySkK1QA3g{1h}!IF0(tFu&wXs-k-7)l*C>#VNIA#u_IDVkxbZG74|H zyrM@CB^ZGSVk4;np)J_xs}Ok$H%xQQT>T1{T-?Y<%pgJ3LCwMHxbsd&@!5>@uJQDB zEuv3_1mVU~PmNN&5dKC=Z+(<7Lmi9YBvUBBj7X0{GbfF9+8V`0-a+L2!<H{_RAC4; z{kY@JI|SXzj@o|P`Eb*9QaPYWtgu3L;##t1b(f>Wri&*<n5>~;&5TG8lV|_UInv?@ z=?^z>&tpgu%JxJ5PdoFxUC`#8zYgSbfg?)gU#WCVT<*H>&U^2^{|@}_q<S23F`{@9 z1PC)A!d5-dvg11J()$}1Sp3wZx*<qxS2kPfv_5_K09s3X&fwIe3n>s{ta$rbvWBi} zqs$VyAwkgXjeKJLlOCkv|KF>(e4`!jsK+nbPz9hhi!J>aPk9^&zz8zOT9T=t1uuxf z3|7!D{-BsGK;*s<E)FKSv)C&}VGCVgqZWo3!Xc{hk9vrMPyT>M+cb#79O`g~JnW$l ze+a}N3UP@4AWvB4Q4e<fq6*4t20!M}4TQvph*Yei6|acJEdG!lOe<eUY>15y+6zk} zETe+j1fk3Sv4t9j&;cB9@ehBrV;ua8$D$;N#}g}pzCHwrNXHPm7)^Vmi?)YFh$ z<#CZ*fs)|pq#nKu$S6tyl_f8U$xL!eH5hvZe#XJadHBN@Zy3TJME4G28HACnWKNML z!wz-CV;p|@Mj?_=w|}^!EjD~$kRGVWRtj??mU-lzWQM+0s3KOWFrzbFQm<9mq8Rmv z2YJ*%4sj5P9QGRoHT)8ea2V;1!z}08<WeLT$)_H;D1&ymF|>B@DK6%$=T;z=sE<_a z6{UElKRM=_v6VwPPubIs4r0GD$igq<prbt>>MJ4@iH`MvMlGli24AG(ZRA+gSNaCg zkY;56cD;H^JqUy)O{#RInLG)D)O5M0uqQ72*^@eC=!-Typ%(txAKyd@)bY4QAl^t; zM(-w%w*_^n8ws2iv$&peq|YRu5sp=_iq))!hLfvM1uJN!uZ~!d9sj^l40F2Ecf3O^ zWPPez-wM~b%Jo+2_=d5vQ94L)qaS5`heGBG*uV;QuvqkuG0WG%V%UP8?E9w~t>!X# z6b({HdJB8rAr8NwwHEDgRysk-)I1s_mgA7mC&I9ULyTiQ-e?Dr9>N~>L@%`EBq^_` zgbiR^sgf}Xo^O8(T-}MLUZS98az1*)gs7(-;*if~JNu3N_>Z>XOAj~PAs<;JAuaO% zNu4_?`w&D@m#M{!k9p6F-t?+>z3i14T;v0ep@8UcE@i2GS6W{PwSt;$ZC$V)$Px8m zuetRgB@$}k4tIb9T0Cm6gC7jx2upav6t1v^FRWf`vV$A*Xop#LPzPUNuPy!n%R$on zOAM=c#Vl^Ii(d?52gd`Sy3!9ls`0T>9FBcj?XizZvniPb<{(Bo8;}0M+_L3V4VfTX zq2e^#@%HN<#9~V`_K*ZfPy@;HfXBY13}%Vgc30x5AvT%;p;ur@Q}=E2r|KJ%0%hx? zRB>;TN2$|V*l>T)o36B$!=tzOH_8$u>$6e^i7I4SK5P+35dj?LNOQ!n(hBDPjwsf# z1A)e|TG}+dWYUUi2*kfq0aiznT;M!2W*e&<=irtznU2gDK8~sNM`$fxR>tL4eDMn; zo=}HD8fzZ>cuFq`E$NUdgvKSU5;a6o3N~k|nVfcsr<KAA#$sbHIr2(W#mc|Zrh2FA zSS#Nw?IgTdlRWk4Mm4BWjbAY17xJbzGn!G2d~-t}md-Woj7E=+5V#(h2vj}P+77VL zP&vtNIFp!tTjWrz6{+ynf!yq7SP@4Qwy4Hl`lJ;j#fhx)=tc*9QHMQz(^>xrkDt%; z(LTYq8_i$_Fl;fCk+=rhITuBN?p=+2H%7K!e%+7={3jiRxE}6^;z0`k%8+zAT+(Bv z))(*7jN-V06{@MWf<R+0QM_W?{g4NKkPVTTdxRe2*akv_;LUb_kDe+b2U+W(j&4BX z<`Q~ENnQc?zz05eJ6F>)nz0SLqBDGb^$Rl)n2GMpgIMlu$Y()2_3@IAU%={1#ZI9L z_F){qC?R22NfFZ;_L7`h5pO?AOOI~KXSFGMi@v_m3}B=J+FezJD_kLMPaO{MhYN)% zTJef%P*i$ly{R~Ik*rMIZFOW#yF}B8_RP0(^Zojz^S1SAueSs>rvNKtVpvT(b_Fc` zOUO9NaS%u#K^PsRy@?D$4{yA}6%=PhD!ATtrr;qg0TW*Z6RL6lI1bVZq4qXmwGNYk zG<z}*H{}nKKrjaL4>#fu;j|F0)`6d;ePIT1(}G*Ya1zS|E2Ec5ssVVX047f153C0r zWF-#m@DIL_1a;63kf9C(u@LB17vR=zuV4!d0vg`}XQ0An;o^U-;0lQMbhnm$KSEYv zfqs^dgVeAi@PH#S7=m9&X$@m)|3Da_uq}vVZPcbQo~9DJH4?xeYF_qocJVn61QrCA z3Aof@cIR?aI1xfP4#gl6rLauA^%4%UG1GQ{ra%g=@Cz>^QGS>r8`eR>00>zaN8S)l z9vC2V2!<h5ObjDl>>&{Nkv_kdga^1xtdW9Bm<p;mZ5s#wCeamWl2|Qo;ScWs9^DWK zZonOr=YT<|BL|^a>QfwtsDhhvgqNZV+t6oTcqdmU4;<zWzMuwekW2LNB9ZuCpZJN~ z=P%+B7qV3)&F~5&VG3$?66~WIJyu`5)g}s94CiAuIb(}e0dQdP4!h(JwNM3WP;B1N zB2NK?-eyDb_J6zMX+L&VC+Jm&qYAdr3<n`=a^i_9@)X~|Ve=q2RZt71#TMTnXoKdB zVCYCm(|*BH4}zg)qM!=fqKZ34MhKEShckQzB7nLeYEMyx?7$c4CJ*rNBK?>IkKhhT z20mM1Qro~SH(4BP=ua=Tf2!~c-9QiTz==RfR^Jo<H*=E-F~k;p@{=V=mJCsKVpxk$ zQw_S{3ed(1zh{$;<q`w<mcKU=tDp-aG7#+1Hvk8ejKLP`Kn-=!2G!sX+mIvv7E$U^ zLxRYAGbw&mvs=h#m`iext;Zt?gFS}8M72;Xfw>NJ_k)mDmf8o7eq&?Uu$F#j6kg>D z>SziLxe98wbE1$K*nkb?Fj<$$9P~s;_27?&fIYNSdBkKH)&vf}03xu-kj*(7F9kx= zBw2xmB2dB()p2l#Fa(AmY~tW(MOT_-xilk4GwLB*^#BfnQ5dZ-FQ;&mgLe{uw~8<! z3bYa!=Yvet(m(U?4uc5?6DbadauxO94>t$@B61m-ho~kyMhegXgHCdX9HgCfqdMb& zmCqQS85)Y66KFKG8Gun3zaa{pF``C6pFZ~ry>Xx6fR%&Bo6(^kR!I+#5C)Ub4>ocu zrREX!Kn=fueA8wwK`Nx<!e+$Lh=?Oi#Slk*@}k7VHw1<YEmSw%@eS&bp;yWf;z6E& zV|!)>7=r<(#Q=DTp%??jZWd`X%avKw5C(Ms4Tp&k8o_QjHk&pHm)sIuc^W*!RU9se zdi3x;S?L@SC?CSGU3D`k<A8Zs%BW}gKVLx~k;-lYVMFjBsG_JNG`NGAfCRpff#2gR zkCvPklb~NmZJ>dCN-<3XVPev;C*9!x7r77yZBPrhvO258sJZ%pjtW4PRU!w$B-MkV zX#;Kt;SK7b4r%}h#o}lX2obGQ4+c6$rMe|;0#gH(IfJ?mpmcDu8V23jg}SP%ZetOI zWv&}^eiq~xCssD+I#>QsTK|w}x$t`ZRY4tLB^aZML&~rHDlUrHTlO+dfAxTcbr9GT zFy2}V1!SR6;jRx0u@Nh=fwik!ibowmbbdKKWVKrK@C$;3WZz?%5_MD6U<>Qhr^%?Y z4U!sf*$S{Kjo_&fktBzO5<}h~2yO7KWN{<!z!zgFuDN=e;uC1@6(0asoW%Ml@c|Zr z*#>IBW$C0ye?ba}!%WVJwLT{QdaY3kk2oY+5f^H;CrI>1bW;obKo2+4OKcNxG8?qs zxGxs_wk8rwM@bI!;E$a}M~r!6Cp)dwDm8?cqymw#7by|d!(o232XwPncq1pi>b7%R zmP0GKl(H7yP+&+Ped16obCFEB<FBDBy5&-UtN;@W2&>?g5iF7(e5AOH+a2EE7EM~Y zVMaj{i@Ui?SbkwmdqoXx@CbV24h8`Z)$n^;=a4I_yezv4sL{39kT2<)LCIARd{htI zu(*aGIt&DBy6e5)3%=p2L49&qwF{x_;1B!|EO?*>bW~coRdMtMxQSzW0*fyUml1q% zP2|uHudBVo#vbezx#pYyp(jbecA_5cz`4HQ2Hfxt?VwnuE1#jKrxk3$zGW}1@FJqw ziR91?@8CzbWC(8)lJC*BM0dbJE4L{OAmkxB)>v8#_=@njyfwTjs^J>XfH_7c58)&q zwSZ-YfVQf`4u|w8EF83yi^M7d77BcWKyV1aU@>?)zaeBbzu<BB8(w8)9qdE}*yt7y z%os*=c}23sSGu8REF}{oO5FelcrX+nqY725IHCa|qd-mT)({iZP=0Yy8I@p3b*XAB zwB$?3ul5v!Q3Q36KA?9JP)Wxb!&?Qy7=gwZhlaNp<qLAOKZbkASjwxPJU#~T55N!` zMF7V{K?<NZ$B{h$H5=Cq$N>)x@hk~e3r~<1akLEz<H@3or7P^q%>gCVFq>eq$Rl$l zuADemoSU~+C>>S{NRSqOAr8YEls}8jKpV^jJY(g%&CpSie-R3<FbcF%1Tx?Wx-bgO z3yU_aypNm;EmI8xp^<D6&D>QFtrc)|M;>v}Ki`bTh9$lOP0&~L6v@dgmy)80Faw-$ zitBj65gpM1=pZSy4&-3Z((DT$><#m95Y|-CAuZA)9ll`*&@iVNCJQ0i)(WxV2`7*V z>U@mKd`5`qkg5<0(5%rMJr9S(!6!Ypw@cDPP1KSxV~VA9ujw1QkO?x7H707)G`%3K zQ8lL^Ho(CDscG>MHFzr^UDRI<)?w{dp$yb^@k-XD3%0;@*>*TB9XTiv(;-8_SxeWa z!BwfTOdFCDCy)dprj35Z4*y)%1PsiBeNWv`5)SE7GVuzT5CWW_CVeW^EV0TCk~O-} z2PY5&h%nEHS&<T>euf>i<LS+!jTOLh&;;@d-=c~O*w_&u#UB&ZlP!R!@Ee7Z**lOj zt?-D))yt+G(1i`$GmDGmcqK?!+b5AVZNSJ;Lwd-Fh!|I2w~g5+pxd%B5~HwfF*w`= zylkc2-BVGA`*>2of!s%^3T|x#a7+poL&3qL5^BPTuJS5XbHS)#3b<|EDFX~M;W771 zyWt)GX-X{M(}BL5@e8i;E$AJ3fX5rhJVxW9im3P?q%tyscj2#aJH02mp+GB!u-{@@ z6s6D_v!V<2P~hh4RASBI;;T1d1R}6fUniko=Bx)NB-@>WfOz_rjF1O*0OUb#2WR4U zrROQB$Z@(*3P`X#A*w#ibh^6Gy)91VRc_@xMAj*8oL>YIVl?9_0TWkK3?X0$@&cJF zfx{k?2P|L$ZSLkKumUDP1Cwx$vH3n8E-ywf1AP#pArm$AMJtM_<ycDKgRY}}qF5-n zieJt+1%e1NKq{`H<E<=qli&g-a0Ho71V^yxN3a4cAPJn%C7tpT9&S8(9tONI3hLwk z+`SbOw9=QqZRlVq+_SDI4%8=U4I&IO)ed6fh=2kw$)2-~5)twWf3N~Jzz0AM2+VE= zXb=V6zzOU8w~R<eR=r=Ipyzd9n;;`93u58|A?UVVl4(rt#66mb-U<&Q;{<5!w)yDk z(@$KY3x7ZXN6_p-ZU=uL1V;c8zu*bFQ|frE?Oh{wEzM79Ht!H!fUnRE;1FK2e(q9c z?i1gM>Fz-g((Y_hezCFM>MYwUu@v=g0z8oKLjDIzU<Jg$0`+i0IC+AnP@ku6@F(Qw z3Xc@5Knm0VgX3=TnP<R1zY)lk)*A0E!ogJ!&gUdC*P(F|w)qDofAT?|@=oyo3;?hK z2IL9zj_rAF@akL>!^2p;$EPQu^B(tsLSK?WulA0D@rp&_8$Xxj*9x8x0ZRTG0+<pb zZ|^3L^7}3YRu2FGzyk2l(sP`mq_FL_NeVTQ@LhtSB2Nlv&m;xe_Q^)tm!A>j@i4m1 z$^*zI^IaP)a48|L5>PMo`o8Z<5CvC1_*riYViOA6&Kr%7E@O`%FyR{>=i8bOhFR|W z$OQL<=q<m6e70!_BTx*Z0D8M4c7NajM?eRv{|8bK1<Ww`gU<r=zzVcKGF>8g!4;pA z-}4gh`%DG=nosm%B=<;hy0L)-eBRz94$-_3^?v^c`@Zjazy_@k5C8=K3S`j?k0)KP zNS#t;YSlwi5hYHfXew2zQ>PSG1Lx15JbCLxjwD&q<Vln%Rjy>&(&bB-F=fuAS<~iC zoH@zWd-l)gPoP1C4kcRD=uxCel`du4)ag^G^6C|{Rf?f1tQWOz<$Cd9DP2eqDKw?Z z>nc&NEO}tT#tjrVaiPTFaRl1Hfk(*c;`9n@LyKJncg?u!6*qA7=s{)N*zse?ktI*2 zT-h??ozHS^=G@uyXV54?iUj#j9#yMYGe*qV+I8!RX%WfLRm$qtQm;5gF=1kb?-jv+ zA7O@fpowa>JiW5r+_}}OuUkJnwW^h_dLXrj=HA`=cktoGkN>y-j^}vv>D7-Py-wag zY*kCCK2_1a#Eh*-z3O8`VJqk|B1M-;;y7Z31CL-qK_>(u1}^~=kZ=%sS{VhR`!b~N z6x*(AZ#@u06mdinMf@kT5>r%hMa4vV2cGzB+b~1>1Vl@hI*KS}6jA0=WtCJ|dBqk^ zIKhPzMmiz#haZ{|$OHfcAm*QOyz!=(UqX546&h(QWt9O#`fx=u%QW-M5#xd9JT%*M zvor1Fc`?RPE?TY2`&wz`l@JioMZZ^AVWky8Re7aHU5XK<h#A7L#TNj?kVgRkj%Wsu zJPMg)6jCBu1<#2JTg5h8im4}_G2c{mRaRR)DI}gQlXX`AT5GlSpL*)?Cmw8?5e3Lp zK&_F({aQi7klaiOMU+rN(dd<6f-wYy8S2Qb6Jp{}2O2=4tY#8M7%9>=hJ>x?OItYd zC)Zosb@yF(<CV8vde-b|UVQV_moawN0jC*KSn>2zb0>O8&r(7#!joW%0R|X{J@F)n z5rQxz6kSH)q!W3-DMXTHD5V1%MmQzq%Zx56*v?f-J#}B0W0rYlnxkUVRh)A!2_%oe z!6wj%R4$kzFkLCekO{&Fqll%0XhDKH5Gm%*QFP;^8cQ-Q<_G{3Xoi!MeH>b%herJc zn{qx1NoTg(c3VA=Vy$^@y5Cg{9B^J)MLNFwhRu}!{H}AQ4#Er9MHgU#2_-kZHD(0d zNjMQEN@n=7%^}wOmM-X2&;kY<kJznybka*VJu>q&dwX>>K~jtzcFHM7mxZd^TXWnW z(rOi85Jw!CQd$v36o!H<g%l(?DTR|sp7{itZHPSCPTczz^b}F30bOm@yZ8Qknc}<| zeDX)+d8(>T5p?YPI2=Cg<|+b{l#@vrCCP6(DWv2cF)a8YtO)5F;D|>&%6C8nA`nFh zWMF#Yfxb~)<S!GXU<EDs7gIQA6&D1P-rk2KJ?xJY`ti{PP57g|SqD1}WMK>07B|(o zP==o2nLn`c3mI+jggfM64}XNbBGHc&0b~XLeS9dvL78f8Gh|{D$uvGEMsX(ecwja5 z!#*r#C_f4zg(yhzDXh4{6<ER3om^uJY|w*yQe<Nr!vjS(#?d4oDWFdj@(SCPO^<uz zV;}waM+{v=P#Dr(=LqJ<fn{Wnr)b9ZQYA-7MlvR_ilHPU*&cTM<4>;1Vkad+L{VLC zXsQqtD@q{>b*<5ot7Iig)C9*?Ix$YA`A0Pf<w;ydq=Ew@qqzWRmRI1-Bae(_F(diP zN*a@mJd4M_`lmx5MpK$7)a5iMXc&gH!c_2(9Wj;p%_x><f#8%P?0SX`XX&k%xnw8% z$|edldPH{YAZI<>NJ)D}u|5A#$18yUw!U@-R9J;H3`gLh%6ukNhR9T?6V2%lTjuaA zfTU<eEqYNub_hF*Sz<#y+CY4M6r|f($F6$ytCR&xpew!4MMzbRa=fE7?<tQ+ZQ8xk zjPs@lRE$S_B9&LPVsAoYX;CS13Q{x@9`NwyPMxZ=kUo`xHMHdz3pp69W>u?O-6~cH zNeXV%gESqLYFTv#OS6KHn<p)sQCV6_Ry?Fs|6qql(t6jN=@hTv14$+~SqitVbWorA zR5LoVD+BITv2Kd$V!`(js%%MM4#8+;E&IoT328v}NK8Ch<XF(EXf&BQU1?1#nRTeK z9^9yp{{lNUq3Q9IpDPEd>Y<qb)8<yUyESd<c>7!64&{8PY3plqX&7uAR&>E-ZgZV$ zE2-S;xzjbR8hut4R;bjtLlc!;O_fP{Qdhj=B`;HaTVC-lw`P77Dqy$EKI4g^7~r6* zPckVw+@e>%`(<vuc%m2p2Ux%ZCUAibd|(78SiuWsaDyG3;C{Sg90g45gDtG!_Fw}T z4$&L+toh*`7D^STe1)m#%MLNgLou^d@r7M{;5Zdf9^d!|J>8?77w1^VJLYkZef;AG z$B7=Y1F~Wsn9R_+1SH?!Y_7VI9Tge*f%W*4D%4j*z`U1es}Lh8P4NmQFSR{=wQo~J z)K_-2<F@YbM@^GVK02cRil4da$89$=TC~17CFNl9Kc?Y~Y}Dh)@$iReLjs>-;L*we z)pA9=A`05RW1co1E9}f1BG|pd9rc*RBYaVhceq*4->YMti2)6IWD-uP8+A)Sl3adN zA|LwT#WLzq4JfCGmj0lJ!%pD}fBMs_mnF6y{VAwa=pwmPy!4qsG7oncLTM#XM_t=2 z>Y0#Z9O`Iwh%m_xb^K!%b6CSJ>cNhsZstUJ?sg6FwhVNrksqMQhCH+Z4ziBOBmM=4 zE^JXej9dl8AYLCSsF9dL>nzjnpa(UEz>j~_!VUir$2(wGlXd6nJ>3QoZete=Iaosz zi%9inb;9me!wwt&*!Tw~u5oLQ)B_az=m$8=#4~!VRw36rg#^vQRiJmptA`RrqR#!E zW}7L~;`j$3An^}x)I$xmsE0dLJri)(gBX19MmWl`RC?r_<J~C@y8Vy~YlP$M@(4F) z^xEzggQOhw*as}=!4JIgqaNqz1wFL!kAz1#?DF7sHFPmN*9P_>11bitSR5x+tymsx zZpIV-F~EqwfgbHBpvhk%yL!YS3?;w=J-pEl*A0H`+>tR&qp=2hjKdm@*aSGj?RlCY zlfS&R_dk;H@_yV68#3QV$M9V@6#t_biux6o09QTebCScR=#(y`lKSAXLmcujL?GC~ z4R?rx9z&r2hCejT6pyPJ50F?F`Q0&(T;+H7^B>A>)j^L&5Q0kKu*Mp!ar?!13|3pc zlJFURNC!|52fR@^&_RbvsE3uat1`i{T$vi|@h2MTo6PAOe>$aAP&S*pzrlmNRso53 zc!zJG2Q}~oc?gGg5C?ytf=_D))Dyc`nY>N=g(on*dB}u4per%6K?39q#ZZTO@B>Y# zhj0joBTPbez`dC$50o1<Y|w^!Fa~ERhn4Gxnga)Zpof|BhjO^M6+yEa$`!*K9)>Us zQu-x6%A7%JE9)S-R{%j>nJE%<71*IccAy3-AcuBvhw!V1OqjUSBSV*H2XBxEH>ibi zn1^})cn2iFg{pgpA?%L)3WsP2IdxD6Yp93(s|R)Ptdm2s)dL5*1BGwEJABiQoj3<u z>joh-v|XvdL^~x>ASFQonxkqBAqloo8J<#DK4IduS=2*z7{o#d1d3}1co+wIXa+T) zhI&c58+!+TpoVGe2XPR;N7#c(M8r$%jMrfYYd8i@R0ogP#BI<9jylGbfT3|T!GGX8 zK^v2u*oRn1hklS9RlzaEz=mp=nz$OC<_k826eC<T$Pz1t;nS6m5G(IlxPO2HTj&Qt zgq>|zhavbh(}2fHtA|=p19jMj(CLODs0VRy2WuQhn82<3TLewmNZ4VAO|*t+ur!eW zOo_%Kz<=lldVmFVIJ&j*h?SFvN<fExh(LsL6UE3CY*@a-Nd<$fN`rI--*HH6V22ab z$#uZCl;EdvAO~`wv@$WLhQk3W35fz?GCarxDj6%$pg?h`hd0QCb6YAVyGxa%E0^?) z*Worl=mcxvLU!l}YghzIsE2+K!Is>a=o&(~D~EoVw{)O~#8{hG!v=nshFGWvZNP@d z9FcAUiNsJN%p6FET)wDW&EW$ucmO=9$S(<GiEYT0Tycl598K_mopGoKUr+-ega?tB zJ6}Kof7k|VTq@Xk0&0*4&!Pt=gM>h+hjIAJ&%mvEI0iw825b0;!_<b6W4nL<fI^sn zA^I~NqfDc7c)-xCho86`FZ_pC7|OrfEsYbOAuEUd?9Wq~rJ#69_%w=jI6<u=0wO2` zb^tYzs2O>v%e%b1{94eF{D*B|iWj7ZLexGrs|On71|6t}Z*YfpNKX^R6|oXGIe12x zOw7d$H}!go$Rxm51BY>_PYA>YlEAqq>jkB3%AE0u8+*K+WC@TEKRlR5Zm5GW2t-r_ zOA=wi2>k|3`Uh=%hEqu_l>iAEq=#Cd0+p=6F5Lr8;6|A$QtVWT7O97E`v<QZLvsuU zKd=VaG0&IiNw`a{bhw0ZU`1^6338~%WcY_VLsN(1%DOBBIQR!h1WqddP@@txOH4~M zHS+~3c+hrOhniHxdY}TT<3mX;i9M{#J$QsL9aVY=ghJp(s|(dMrHP%GgIOp~pl}Cz zC^z`rj41>y+0naexCVI82B|m+6s^11%e7Y8LwfK9&HD#;c!#hGPF}0F64}E_r2>Bt zhfLknx;%tKcn572N0S)UPNhar%}|MRR*Q4hSCxrz_y<{4hd}*_xm$x{C<iEw2`Mzi zQR~%uxQ1i^P18ULpP`3Xn1&op)--EX9Z-jN5L0jX2VZalbpTcKk%t$o2RNt&5^aZ? zT-a<3(Qsu~kr-8Y&;e?o)J*e-Z}<oDGrxAliKXJFIS2-L05FjM*ojc&wwu^j$s{~~ zfQ5a)8#Nj;?O3^ga0X*ohodx97b4d}ID}@D2XylXZup1wV}}bRS@GCIZ=eTH^#>Z% zRBK(<M?F2NRfz&J!diF(&MF|0V9t6N0&Y0Ln5_wq3x{0rgT{Qq!DB*A@Pl%IMtZo3 zx6`xss0V1^g?_lVu$v>}+XjBPgl%ZrRYFT{7y@;W2j;BF@M8xV^w3rvku?cUrb;)m zJ*e{BSh0fJlvt{rfCN0CxHy5`e+UFfkcSC#+Pf`BYsdvb2#0DbO(q;SQM6Mf8$gaT z&A&TX&JxXhGfFQ+z;s~BR(jV!Fa&?N&UGjtavjNcIK9XJ9TAaKg9lC9k$@fXdjm)i zQPg#%c!*s*uue?{3D~U%*(HZX<l4KPOW3gnkP}68JE%63Jvm^8aCi^oWr@Rmv-PZp zWRQi%wYikYyDKz?*b`SdQeUa_1=w-jmHh^Pc!Ez0H@f0q?s$)#s8GTs37^=s^%GIo zMTvuwikA&F8&izm3{DeV*ZzG8kJAQ9&;;QvPb!KBa0>@I2!_J++b9$Xxj9j~Nv?eW zh04U60Ue5f{MT!^;@b*9DJBYkSQ8zjlGqH2>=3`UU59za7sX(*6+}0okP4=oQu)(j z>6}|?I6<EfP)?P>%`4F`MlYBQ2RVQSYw(HqOSOLgFyv#PQzK>!<sG%2vLSHThfAo3 zbnqE7!<%$~1%B|C(}W~0t;=r=(>NO|aIFUtHb15!sqkoz+eCs-E8NtwWvO7e;H<U< zHqhXVurpN**?GZuK-qtwLEcQ$)H_T=W@4QT%y1wCS%BmPp38k5<hfz8WH^VrD+l^2 zio4MUen15jTV!k=ia+*+K<?uJ%uO}Jg*Si)ZN--{o-s9O2Cf_mu7uVh0K#h{iVRg% zinF+%$`u-{hf`k3b0#m*i3UG_25pGV06R<omIHs_WiU1`pM|@;qlaEN2MDaqljxam z7zbncgnk&HWIi(@?I;%8(#NY*HE;)VAW@_L%`|wRQW8GqJOqzYrUyva1Ag!ZmYk)P zbvOwHFp>DIpBCtfbDeq^W;K&Ibs%c5{Na=+N5B<aau~ACOEq)cTj3SK+_RU3jv2h^ z2kH%nG|FhA00%3ahF-|gJ1#8&jcU$%S4Ga^q_}JHlwEodhw!4QpwK>%T-0yCMtMP3 zFjeTE5FI{#16-&V00U?kJcK<6>`)5|6754OC_i^N>**35{tR4t5J7gPtKanlc))1J zm{E=++H8OYe+W&Nz?*N-$4zEA-qkgEm^&uRm7D!angCQ*rUrF{9U&FfG-J9aXa;q7 z->z+LdMMRXHA~o0#z4r{(PeHLtjJ&gsMuCrZjF>Wsv`&RS#CChow+mZ>s%Y(b?9TL zQ(MlqT~#b_V6smzhjCcB+x9|wxP+nAQH2{|dH~9;+lEv_UzjK$j|f!q>j!wy;F4`_ zthEFS{Rs3RR~^W1kHzj}WV%v4=I$m5Yjrqi&B&Up@Uo=ke7(fEqoNldS9aJ5LTCh0 zBvznA!c)PC`yLOE;6mbdp(>PzO9(W)F*DQTOnTU6pAl(RkugDARycr!83^xjkf{}q zNA1X1ALNIXluPC|P-=Jr@GENez*zAkzd#<70?OD@#neZ#R+M~)nl5TG6lRgsylwNI zjU$I8L~phMFebb&{)7o8v{!cjCJDs=N;#N?A+rfef|*?D8J`)xcjasJTDf%Sg+QA- z!bXanKnGB$2Y%RzP&ciI1x`2MhH4vvX6T1@$T_EYL4PP!a1HIF@QARQx^)mgyP=1j z$OO$3;eY0ATdllf7G$8vFB-H|5&iA}eM(<=0_$|HT*)M<z|BnBt$Hy+0AoO$ze2cy zC1`}x7Eq*MLOIxly%q{^$8mgZj7eUP8d|w?;DvlJ2WS9?n_cODq$yOiM^<b$qpSyX zm}^#?;Z-T+PW1(KfW)><HPlsdnnGqBkWN9&6_^fGVrSVC<o7$}+?@W0?hEX4fKDyF zF+ptEA=n0F)=cft%YT?s>0av7|1MwcyXu_zEJFPUVpxJDAclQsl>k$daL@!oIEG`W z*>LEGe+WX8_$+8Fw?!X`{Mv;zP(qt1pda@R5v_+!&<APQ2Xm-|K+^^&XPx#Kcv3g@ z0dk3+`8#^^ha~T9(k)+q=mv54+BcX4e|XlOMhV!Nhj!qGC)hTN<w=Zf2Zv)>LG*Yf z1Njs@1VeZS<-D;S#lezZ`OY@W9uCwP7C)0GLlb1#dsc_Wr+X4fy>QcnN1ufzIEHcX zTgL~FiT;OUxOxT81wx31PMmqFUkrB8+d0i7&!eM%*abPDhj5Veco&b<<F(=YJ*dQn zedq;f_+rT;AAj9u#uRgv|1iqG>jh~LQ3{T7RFQ|<tO6Ds2cPo8aoC1+U0|M(hd>R4 zLvY^-=h~mf152nnfN-~NAi;tL4<bxh5FWgG?1pfA_l_RDgY4L~Ye#M!6>9C~T`VY1 zo<wf`@IaC$u3Wj1BL`k==Z&75O#L#xRH$<&&z?Rh{`;rRot$Ig!p)LHZ`{9i6n#RC z3N`1rdW1Cn3uo=0A5BYjQe@Z9+9FEz)ct!(kY2rY|8^-2C)MCTdG($J&8v4W-@bnT z>IDa`o}_E_v<VIuZ{H<w*s!?;EO|2J%9i^IPFL^JzQ^(`e-_LSU8Td|E~8G3+TXi+ zzn=UX=Z|5zZ)$we|8vLAvOj;^=mj$LPMqD!68%x5GEUq()z1I*W>*iQ#Ls?vf0K78 zP`z<L_x6T<TVA{3ecg%s=cbmrjL+Z0=Nq<PI7*A$sZ&Q*6Fju_>ctnJW#w$M#xWO3 zrwJkDgwxMoVW|^NBb2PO+jl{I<`!H_vGtr?&&(AfLI|=m*gl~A!%scn#IsaA*BI81 zTOo;9qm5BH_D(vWq~lmlKCx6!Hn7z5SZ_BXDOF73&~r#3>WI@0L)`p>Qa{AG#1lj6 z)bmCy^619Sj|h##5IE%A=1)5`CaKU!@3`Zd8eqEPk~|i%!z3hl{KE}HB9YWuGei6% zPMCPQ=gSlI|3o=vn~(PNT{Lo7vsGH#6!n=}kaFr2J^%DWPcD9F!&FemtZ@{Z20>Wg zB4?#l5kbB6GnOB@{Ii>gcittSbN{Ib%RY`p_RnMdT#^nyf&u8Ov+z*_jyC@|lZ>?3 zQ1oAA^|X`@Ea_ka&V|pCtCvjm=s?Xs8HGiUFKYBdPPWbZ^&dR`)WgjXc{azJZ}kMi z9h3By8`OX8q=$zkg}O6YJN4{Y&o|+L2hTsvz-FknePzT>a?3qTaKR(z6;3@#)kBUt z>ulB4S>uxY9#HB;GY2#DkP{R;(GVg_%CX8v4?FrTqKP~fewx?J^%Sj*gD_9#R6`(k z+S5f6|JNf+GV65H7D3od>kKCHAXc^6AxaC*CdL?xjiWoU#E(C{oKxhHXLlM?J-)#4 z4mUWF*N#6=P(x0~>}c5##`U;U=bb$<B;C9JltWKEcn>rZ!u|wONTKiObdfmq7!rtY ze;Rb}KhzLv=&CSb^sq0=Mfp1BRX0VC%Nwl|4n4E@fpa~N-)>`AC(BWfrT=i*2_e?x zx9M6!@0_Zo(gU?o(cz$lx>V%cMUnX9lV861=bJxJP{)F@4?T_r)!Rs+3M*J|=;NQi z{`>Qfes7u4LT)S>3I9eCw|^v~Zr~tb{~GAP{S_o<kO)McR-`#59bymuXp}tgr#Wx@ z|Kkml_=h{*!9e|KZXWgc0X1$?o(?{+f11<CZRpVscTnVn;?vwaCMOSuFz`)rD#Ri3 z<hb(9P#y9})0)KOk{CiUisc)K?}`$RSRw8ha@fZ8r0B&4{^MkRV3}U5(GCOU3V*wq zRHcG4J}O>u9P1E7E}+K_DApq$cPXAha)OO|oFf+X=+Ocr!;(;)BN_GR1|J(~5NYuP z75rESw-6VVk%a3+^;i}-9EqeBWoHP~fX6#XgfMrxfgO#rT|t&a4-u}TgsdD9M#SNd z4AR4OmNZ*T-oZM*!D*HkLC<ukK@aa$sFw6l11?Bd%3UI48}vX4JH8P)1bOmC{}9rK zCKj=crwL6zJ)?(%-j+?B1Z697m_-_sW{q$ZrJV<XkTurO##j{uDC`J_^Pr~=>G|Xz z;KNJI>QxT3wC^xb!^Ss|r7ZXrG@^VF7dm=D&JL+2lb0BzU?eJ_W7dNhRbY)j^umyD z`~wFjDJf-eQo|CahF!jJ0|^@z(Hs8q8;zTcJ03>3W3tp-#9^i?`vsWMq2wPE3#vyy z8qWO)4QQ8ILp0n1wWb1QV_KQRG1?iHe>8#+S+UMu{=+5UX~R+*bE7-!X$^3yhLTis z<Vct`q{Cq2Zt;jmZyr;RSfIl(Eb_-W&(@o+CBrcM7$EU_(pPMxBNqGk|A%1gR9K%} zupUl=k_lb1SLt|(abnVm=G^rJdPJnNn3YG1s3b~u_`{q@8VPo)1c`b)Q??@^rYP$% z8#{fl9?T?1b+WXMkzC|W{%8gga&^t*HukcSda6CGp{b-Xh^k1FE?7P#ol!aMj^ay@ zAL_9Uwr0*czUvA-(Bi~=x|5Cl_@}Hc`5`{$<bTsLhBE}iqIj@`C3`*AJ}SWvBN3Ln zkm@TvuA#`qwj{bc>8m#6kql=r^uMxIaC$eVFoxM_ui(qX8~$-#2?Hu4tV3<%Hq0t| zjD#tnjfabEq}<=UArtGsl5W8?IyDeO9^-%qa04e?U-+YhmR-kZ|DE`bap<cq&t=D6 zIXvCn9D@$gu!dD-WimoEq8_2Dua&2ltE@dQdg80gG3Ee`q^adQ+MoxRnU}-He#aWo zSi?3h0??ksV`|y#Yd!V>i*oowFax>sK+3U6cyQ)@K`C>RM8gls(jz-4p0Gb2vkqfy zB0?;pw3`Cw4;?7=a07{4JxI)`Nh{=}0K4r*nlcsE#$z`mUIz%F*{PG#0}fwmB5CQ= z>Qr*D!}X|z8i46IJSmrT^7uwrd`;?vT*PFJSOh%e;;EpROhNHbM~iM36qfusA^OyY z9H60%l2U{r%&R9fnx&SJG{tvdUPnJ>Gtc;HxgYF6=4yL||5b`$tD^KEq+g=-B6Iu< zs|5`gKhmKHdKf8bsj+mjIx2D1P-Mh-@W;TJnyV!L;|a}BheQBVl6pMB7w{lXQ&i&) z<UD~Jfg%}eT$8bO80Y4)c!NB=0rb7dZc*HTsbqF4?4BC+;~ol%H1|#4yj18Ldw!?E zMD{H3)dR-=@p{lerNuYzhOHN|1|>A14W#X*cXVz9s3xOtx|=Gld-UW;_(6~M`J*3W zveQNSQD`D{<7i7ZTa9mo$-zh?7HyN?rW0Z(fAE7AguL6e(_4}d-j+$0Z1O47wJu^K z<mGA@_AD)bG>mwo9#rr}>>8im^yXynKU7@nURdlF|4#xAg?b@!G4c;zAi+1qbv=6M zQHVec$M>BNojk%(plE<|(NC4bmIa>f8s((h=6wcQm{R%aC5RB~a9XUs6H-c{<tW<E zcRi!An<A%|B4`0~KcpEVUd<Ke*a@>pLodL?WAGKWu|sXFLo7(ciu~8@{a=y!);RFP zJM<d^X<wUAm^@ShI&@lI`NQ|=#39i`FQCJU@RjZHolCIV8~DOa=pMq<!yZ7w1~t)= zy-9O$gBmo03>sHJo!+t`oAi+&LFCs6!WayBUU@vi9@N7Px!7(!%p|-44l+<LDN4Sq zlC`B5F+Cp^GU4>Sn1$2>8pTQ$sslH18(JJ;|5U`8(9}aP2m&4W!8UY<t^L{faET@a zkEP6CT8xSvu|#^E+x4m0;&}>}5W=f8$OP`4BMAmQ@K@Tvm`*$fB|5_aiXaQ}1itmd zABD?da2}^n*gs%`VIY`@#LbH+k_eLFaqV6`unv^e2{g^n-cUg<Ngtp{L_Oew8mNQO z<=*+F*D%G&?9c--8e<<lj-5!)1<?Z%5W_z#U#Y>#Kl}n5xX_p|g|MXz!8s#({KF*d z!RdJ-hkZvl1cM*gUmC*D&{#t^jl+Dsp;WlvCTN*B?1CUfLwkiCPq2j*wS+9@89mIw zEC5IxQqiPDgPN%uK-QUD*jiKsS|k=v|6P?zviwJcCB$QmLpC%9f~6yA8Oy>s!!?-0 z12PCb#8xxTMP~4bIQR%ml8HR1NFw=GNqW*nzzIFr!kpaDs>B4))q)!gBkHvhJG9(u zFih(ygircS%Hc*k+#{d}nH*6BW5Eu))R08@#OKAF4be#BP)W?aLwR^1K_Fw!h*B5E z;=c_|IQW4qv==^o+do7@Gzh{m9L-fums{8cm{CMG_`@#D0Y5y>9=cOFppkeP;y-M~ z9OMFk0189U!}V<!LVO2YblcI02u9uxCe=elZIYtxgk$gnIRKUg+2l`DMJMEgIpl*r zECVmBh-{b*qU{4Mltbb<o;*B8|34(lffds9#e_F3Q8SegqO`*|a03-I14hhJPsxKF zWI}r!N{H+RQr*^jK?U>ROW1h_qb1YBFdJ%t<xWT?H^3Z{HBo!MCt0o~>@?2A3_&&E zM16MNd{{%zI7D4E7Ol|38tejq@MJ^|jWz^>9LNJX?8eI2$3fvGe5Db1c^{dj(?7_; zE(qM1fEzSW%KdHH%<S1Vlmo2s#5m*(L5L>i^v1NnNIXCoPaIY~B$k+Q<&Er>$(+M7 zqy;v#1Zil-v?N%Y7!W<611NNd28PIEIh1iGXz?WHKfu8wFb+KE1Rkzl?#N1!A<RFB zQa?yUx!oFxP!j8O2WBo||FLliJ4iwtJVP}JC=8XBqV&mn^2E!<oSN7PpH`)dA>+gl zj&;7KI!0B4(nA+XptdyvJB))OiU?5D0~=XGa%Dw56h(?MCiDD*eQ*zC%Hl=LSy<WG z5=M@#;L2wHTT`IQQNUyv{f8V~WB}fdXb>m3xQ&Xso{7K$J*dc`>V#wX!!!tzV~j(x z7FsXhVT(e_KXeV<<Y7hrU)%J91BT*pc3w=l12w1tHQ?5fB1ELF-dWhr2c_IE{KGZP z1&I(DbHz)Qu_uD~!#0FL9n``O;6k1dSu%;vtc9bvDj=UuXM8fH-@K=qKxJ3T!=5OW zIL2bTpo;QfNMr34|63%5K#f+L#Kzny6|8BSSkYIjX2l}p!b6H`qowE^D#cbf5k1|? zMF?m_o=U2uD77X;Jut%{-~wSa#fzFvUx5QWphGN-1A^h~LDUsEq(d(-!-EPdLX4nY zFh*?H3E1#Mfq_dWJqjq*0}A%r@J#7IWFl#p#@GrVd6<?wEZr?C?GGKF8bB(I6eCW3 zD{ej0u7F9O*&r_psw%}E71RP-$O9bM1aXuIID`W{xaSb89Pyo>RB{PQ<kDyOWSro_ z8}Q=7%HrtkNk4ppL~yQ^>0do42s<z;5_XV0Af`I-r+v+3E(ikm$SS_+CHGzGy21mE zd<Uw~LpWqe{~7+y97rZx!E7$btZen}8fXhoSj7$O!mXT_bl589NJ~AWVv%4&i_}H2 zfx|b{gE1JxwUpvq{0}%RLkjlMCiw$8;AY~zu45${HuS@Zr~^p`AyhmTJ%~*|Xai)B zVNCc#CXAd;xh+D(!|}mJHz1Rp039T}LB8lIcPdj&TuCpEh(JM1Aeb0Vyn!r$$v8-5 zIe4o_U~sWb1fHhW<<>*+{R1(^@4xPe@_|lV1|lA=lRUi`^Q;3M1jD7KY>2Rgm>h#2 z9D`c9#DaDc?G~azeu_N!ZaLUawOPZh1nBt8WnEq|nOW!pQUWD}YPzL`rXB-DtW(MW zZEzOZ|NdgaIlO~sOj^<s#9lduI_!w9O6pDwpf=P)|00IGQrI{c!!(q`|KeXyTwVy) zFDN($HdO3f+}R=VgRpSRAxoE?ObJ!4>r*5x0ns87xMYzz@ITbT75a&mf*+X3PO}}( znA}-Y#8z*Opvka~Kg@$wl0+540Xr~bu{m%L!OIFWCFZIDqnz+f;uPWFE!y%?p4EfP z1hMwbWzpm=V7_hX@}KXBElcEzHOzt_*pYdbZdldB70F^wY}2if12{=6r2ub*?r`(? z0r!lor_78tY+K;{!z|1}9#${o$-`h++$McPC-Eu*$3wWJgE}a}fx)6w_z^Zl=_;-R z|CFXfvUtXgJXSxLZMc}HjdYE$)Wzubq$;@sO5H|UKCy)D);1LG2n{7Jszk%$L8eV` zyT%SXbOWk2%38AUAshmFxWi!h4zuM;Z@@`CJlzf1mr<&LKZNcx!HGNs;|nWgRI1YG zs2t1Hunn&xG;oy;Tc~6<s6V(N7ej?Ug~O=yN7@}DJ4llp1cM3fRWW*pAB35=$)$eG zfiOfB1EmGZq;9LKgFk!%A%roRg~d8pDm#!v760%*{PUwQP;bbKPHI|I91@P!O{7L` zLCENXkprTMYbzSVHGqR>+n8{=P5T&UD1Wx<It7fR40KT%G6G{U*N#uaUOlV_|CFfZ zLcjw`iBg>+2}6KSXpw`wBFa3_gAQ<m;i%;)slhKCY)K4(;r*6P>J76ouILW4JXoPI zbMBH9Q$0W|8M+ZM%)vKBv!|>b9lq6j|HSq|L+<iwxq%fSa0|{-go9kg@6zl(jS59# zaXr9A@y;w~ehQZyHa$xZxY5J5{qE7MwI4vwWFslA)k<DTYp9e%WbDM9{n3wZ(vGfH zW$i;OymtNyZ933G2IjAQVM8_4!v}KWBjcm2utY<k1CfYu{L+<6G)`_?^+BsH4O(zd z+sS>>gD3$Gl8nUY1c%=M(WX_!yO7+K!^t`vr8;cG%s~vFSQC+*ADDLQ|F>FWXIZCo zszZx4<1mfR9$={y#<nB5pNKwWJs(6my@SiFjE!XK=>o5qBrQcG#YM@=S5wMHY}mSv z165_{S1IaX$1^>2lRw4bhOX1mgk8(b0y}8<qg1SrfWm4XYEFFb9m_)#N5%e%Z-zye zs&@k=8iTAyEo~)Qp~b>OoyLOOm&)QxMZGbJ-nJ?M9Z;v`b~<N0U<?k@$e=zsHS`oo zyWTLhS_G4WIF?C&bjjeRhZEgPJywA)3<pZ(Sjw<gR3zsz;R10z6FG{KOQP~88rv_Z z0Xg(?T&i_9O$$8dUwi3}CX}<F|5N?BZm04!F~pV=r;`@-8GT1a|2T-Krq>sy6M}#P z`wmMcyB!0`nJ2ha@h<GfmRJRUGef5oBiTwcV>EI)>Q}CEi%05j2;T8F5bH}8#Q#Y2 zHt+~Vua=z{-Z}JwP~aPQ8jl6`LN=TUt}!!ZlZP$kr#$#usksO1phs}aVo#OhIVM|h zW+O!SmYKuXUI`QqWGQs*RppSw5UfLM%nqY~MErs&lQ0vQu(?)K!|pZS<;H^xf4wJ- zc8Eic#pp-7!5La_;P4iFh{%~B%tAGz^~}^qBUt>*lta->Z>MI3HE>nJQ;#)hszOS9 zAX>va6vggtdKeLd9E5`ivzmhFEXn*wv^X**OhYI-GHOJN|I?fUCP<99Xq;v6akYR0 zKNNJsz0dK>gZN4eS*3=(0Fol1l!yli0)C)6K$O%025(L0JDA*gJPbAHKs^|pUi=3+ zKHri1N>V!s30X{EyaOIuLLlUZ3CU_uoYE8i$9ez+J#p{;6*PDdA;Nav>Z!pc&)vIv z|J;eIH>BA=c<|~?O!#qQK{dYowflGyWy*vd<^5CFu^u^<1v|R5CWlx#njRC<qsOk^ zt~K<=%{<xhr6xc1w*6zLlAX0<Yu2e_=hL9Nb%JtPV+WMy$8hurEvlyu>pyGt=FEDU z_GDUX@Z=nW_pjzZtS=X7@~ZbPyJ%~|JzIAeabm@b{~0&-=MNmVexUa8!v>C?zs8N_ z$peR3S}cFsuyx*yxO3-n_4w6;wJ&mJ(~3JkzMKvgKY#Vg9iDwUap!mPXzgPu4|sCK zwz2V>7ONh%(#Vxpx4!vnyLz?W_*1v>^jCN8xYdJGtDZP{?0iEM_wUi3f8yG$V}G4- zXLs%7S$b2?n|8jMt)O-+f&-Ut#Bt}V!{UkODRSz`WQZXk`9~(|uFH-gB!21Vop3tS zjyrn3+32^;gnNe@deo?e9s$`&5kKV~EJvr8KA|KSf5u6!vzK<6;~Q;S@~N@3qVa<m zder%+IwaR|Dx6&Wu;xiA7n4gIKXN(Crw7?l|0f(TwV6^&#R}4ftVY13ryy(okz*F8 z(%ceGwZd8BnDwMoQVwW-`Ul5?q9H^UYihhMHF;h_2bOxeX^&CQz!@hUP|^tpo5Sv; zjk<Eesb`aG#?b~d%{F@soNnm3MiNOyT<25HQX9v$ef%kh#zhZfj-P!liEO$?eLWV` z&MboDKW^T6=QN+bvM3Nk-Z>E-Y1!G&A2-lzhd&LE)z6)Os8NF(aE+bvpLX1#W{7dP z8E>{mUFruKZ`hHrUU3)e7hHNE`9mFd#!<E&NbvZF8}QcYwLNmbk>?3tVq6zlTYcK- zNkSS~;)Yr1k?B*Pr2R*!dd}2~9z6H@|7Q_O!m+AW#<U&GnmlXvl&F9Fa5Eg9<EdvB zIqErBo|5w%%VRt9l(Q|GTi#4Ax^^kZWRrnP`L9BOvhtX(#2%aMvduQT(U-2drk;tZ zJNxXzKI3N{P|%5vQv1kW3>$6!=|!4<zNx3B#KunSGj;fZC7sLsg<EXjBxI(Sbjkt8 zaL6@pa2@IRNv9Inuz4`^%}qajZ@t~A2aimu@&}&7&hE@9i|~M?ZHK>lmYX5ggI#vi zA&-a~bufBIM$QXbHV}8dd6sjr6B>LX#5NC3p2zBecfN3!UASR*G>lvC$7DL>koh<d zUU<k$m++HCaxT+Na%_F@rJ_~#{|8FF*QfO->d=OjuymEF9ZqkF!Ad>+FpF^nt$*b6 zNm2+wk8l*kG(?*NhWh8f$N|tP$B=_I<YbU=+@wziWZwsQmXxJvqaXdN$4@k<mZu!X zDb@f7os7~$lyt;Z#feADe0UOY)B_#8pa(xbQ$%dkV;`XS2R~NRl9|*49IY`1+n!iN zmPv;m&VUZ8;Nr!UjDsG_ILFcQVn#O_<sI&ji4N4^t|Gca9+|*{eKK<p-VFgLk9p%s z#zPK&>>(5V;15C`Q=S*e;~h^)h&(1DNtl3RkpF;PJ)VICe=MjYCQ%r}1nI?c`Qix} zf(QRHX_Og0MTFXT2RZ1m{|h<%q>KldAj}%!j}oRtF4kB>G@Le*w1lHCSi(zKjxv#Y zOvQqd{0FWYNDeCk6HbCz0|^b%4|)h=4&mqrTJnU=e$+!L^!O#q(6Wd|{6ic3lS@71 zkc*62rykYlg|7UCpUylH9iU*%H!!E17(VeF$tXuUn)nZhp~g~~O2<1sQz_~6!x+vW z);<3v4{g+=7i;VXjyTFu@i^}vL!gGb?h_t%#E~61poctk_fk9#VQ>yB>F)kf3pMn^ zS<uqkv+B`|RMMw0l6=^DX4KE?5Y?#N<CQ4)7}V<&=pCr6$GqH8Qd`A|p1~l<Kl%|4 zLUiICS(;j6;zSQV|H0{@?TJ$~<bWk|CMO)>0E!<pQ4bM0)TxTW3OkUg2^jtZfAXNy z43l%R!JN>FS0Tn6?7B0=NDG}yDWP24dW@O=iH4e(gI71xw|YE>9;87QuzHb=epFOB zIMNMec;gfVI>sN^s0K)-5e`&Y6dUQd#5b4-j<_D{8}vvbJ^FE6(k4ed7MX;6=<~m% zzLZ5na7s;A2Z=z)16!n>7CmYK2f;ndLGg&=KV<Qr09hA@&t1o}{_%@czLy>Cphva* z@r}n^wO#LMh8nCg9{DOToAn@|RlXt>IutNXatVhVuBJj2(G(sRY}z;Ai(n2~Nt{iM z5}aN_3Hhnx|4C5^#+B3>tvt~+8h<GWJSJP&wNfp#eo*IIo)%VlPHlojYeFkk;uFus z;%?H(q>(=g3u(0Nh(-a&;H1%ubyNczgEb~SK2wj-s0@=nG%_~Eafx(T1{*}~374Tr zi*jtEC2dr5CM)ufLIk3Fa!$#!zJY{o46&T^VI3sc;a^tHxgd3Z!Y}?oUxOH^9#rrJ zMauONb|JbTuzSiIVAPJs03}`_aif9Q0f$Kh7}IOcp&WwYk*BbU5Pj9kGIs)2R{wa* zPg(>aR2FAu8f2HV@Pj+X@{(W2WoavpMhtV93qim`YS?s1I81z&f}mx=2HY}Ggzeiy zyQCZh|Ku^&NG!qwFDJK8H1jqh^WR0W>WI@Y#;J@O*x7)?Zy5zMJmS&8)2OB#G2}&( z<Kd5o_Ulo-U=5C(iywINBNqD@2W-z>sX7<p5bU5&!-eAxdK_X8pJb5OwowoMhS#ej zvWP>D7Q3ZFS`8n1R=*Hakd#A`MfA8`diL{;bqrw}EUgah+9eKpAgEw?4D3CzB9E!W z1cO!-3e?3l*l;Mj9~Ms1OyzOTUHAbTI$;@}Ttbh@Mgx}{5npOF_B40Y#VTaA#v(fL z7t2aZfQ_I;IiBPaZ3IeDV+YP&Zo-V=XapYYh@mX}FtfV?a7^H!O2s=fICR8<tQ0>M z|Be8J3NQmn9)077nR&yj!ZrLW97*EBd$Uwq&5a((U>loMMcRLU6cb#WPQ|Swo_D}& zmT}}bBt344KzuS>(=xds{6UU*xO}JEIwci&-kGn=gS<brD(@A;XMemQ6Z09*iGaSJ zhG)(|^mxOmBXaJny`&Mm{wvX!#Efv<1+--S$0rC84t{7I$1r3tszGON>@YY+gXp0* z5bHtWVZ;hzEE-`EL}g5FBF4Vr?gGdf^lnTFq95o=P;3r3?4=)W0vcu|B%*>4a=~u| zk9J0i5_oTJ>S1lh0UK87o^Yfe_+g(uW9fb+xBlTA6t1{x1XwO%8yE^3It-$8|F9mC z0UajJq2%kIFk>2$p&O**{J8Hc%m<Lz!QHCk9n|B_1VTnOVtbw-?zZr$2!a@pfF1&* zGw`P#&<8`FkNd2L9X8?{{sH_n&iiy=USwoLq>mn&feK1u<fzb!#-f^%#vfkBo!SA# zq{KA5DcdZIXL86(ASgxl;_CbW?Fg&&Y9!bi4~8<U9!luAf{6~Ift5ZmP%g;dY{mLY zP!8-5InrV(%0VVt3Naq!AD|)C5CV%j<2A5o&gLc_)QBF^OeH$voVJKH=;7Fk>>05k z95PBe!VH^ugC2ydaZ;ri3*s{Pp&Jyz2D2>C%F%~b#~0MVDYWMr5rX*s{{a`?AV##K z9>B$1s9+rEqaEjr&;DT~)?tx&C#6<uk=*el8mS)sP#pY0A_h#6_|c4D=O3Cuy9Pqf z)T}0=!b)K1J2;|}sErZ|C@%&}8~UOtSZ2$dLc#n%8~(41@a`tQq^auR(uxQx$YC%9 zWi?X9n+9@{`X^h~;A%Y31ZnXjQ9>O|kXK+*o2-Erdx9ejqvD*<%zW?%t3$SEkZtVe z!fvA;%uG7M&^mx69qypGbn3$Vfgeyo93o>1pQ|(GW*jIZGV-uGzM?6>55?f}-*Ao_ zevTnWL_oMf2fBw1tz#p&;U8{?C{~1Fo`4#V=P~bz5BCca$blT{|7;J^XXCz-F+zeG zFjM$U(-eOqhWw!JVhBfqX$@?QXB2NL@`^P#5uQ+JJxB_oULw|3u^=8~GeIaS8etP8 zg)L^G9stl*4r46%1Ua~EgXYgPLn11@#M;urmNLw#I)jrK@j+Up9%LaIimTx6i8+L8 z9EwXV5$A}iEZs0hIaK3l=)oLj&!I@iW)!d+>fsZv!7@_i+-!pelYuqt(=Q?FDQt(( zO7gg@54-$}3aG*S<iSAx0e$vkb=Z!h8U<Y7rN81Rj_P3&%u5cF#sCjYMBAZvu4Nvu z598FKG%ID5%Hwu4ZVnyLtMIN&y22_pLc%(cWwOR8216S}{{%Y!6H2T>9{8jj3<%)J z%IxI87YU^t9Of~P35DpP8-|I;EUP6tV^k=Nspx@g$gME<q8^xGg#K?MB&2D=;W1L= zLB_M<q$3`BVH)tQpzf&(g^M4Us8dR-G;%LGupvIJqchGaiF|}GK}EMfY8tSCpw4YJ z((D=(l!{8RK^3C`3(g%z;yH2fJ|V(+<N*i9L0vS|8|c9eG6DIR5LvRL9a8hW;z&Te zrCq`$RQ1MPNc0=#K|MyZdu(+x3i5X5<2Vb``hsF8e#G_G;Xz_3{{A6oE-Oz&$Qs7# z0o8&Y+{sZk0!KszFTC}ym<~?XA!js!5VpY&g259_|C8uOC7s9tEz+rkhHgE`q{hYx zM}%_`Qp-LXLr>+)Ho!r+mZ;ro&!4EnHa^N2j3F}W4SVvEVPT;kMrukIrBV83G9)f7 zAvQ7EGZwPJQl51Lvj;LZHXXE-Wd&7Lw`T~(5LlJtq-Y6|oK-`OZdNbSK4vyQVAVX> zFOJ;7cnF0a5>LeZQZb3O9p<4PFizug)?fKh9-37^cJn%XLPFv%Ca?$ZL}(jm@%`!{ zTT4#x8jFVX=dgTYV8`{HSkY_$b1$Mn6I8%WQjBK`Q#vz?C@4r&(4<AljvdOO#!zfv z>!D7kBt?)TVV`Sag=L@)m1a%L7&f6Fvanb3{}PFM0o*>;SN`dVo<n6Yw`iZpav93F zD9=*(fflx5S4cNl^$=Xxff@jkK19%8S0@wTfE~CY5+N;U-9=e_B|9u4698db#-Y0w z<{SJoSaFqDXOtc8ta}a?KeFRpo<JVR0j7YFU1egipbw&wlrU(qh2+6w%4$l!Rs&~| z++0Gz<^VJiucV}8RG^_g)&V$2ECTy4D$9YwqVB3*f*9l=9ExJD<bap}3t_cVzQR)W z{3>s1WHxRj;Bdor^TsDSBS6*2ADT;CwlHLyV;?F3%^DR5FJtu#)rB*rHX!4PoWU5% zK@0DeX4_*!_uvuIBWDkeIuJ%-fJ*Js|4<!VmO;lQHC745aKJ}C$q&QN`PNPoLo_vp z^=7{TT)5#0xPcwUVeKjfR~d7w#v^&HLoQZKnL;=<Ze|Xi;VkZBmv#+<+ZM+N4^g_) zNuJ3MPVh)f23e#8MY093fRjuy%uoUa9IUb~$gO5(<Cvgf4q(wBtbwkqA%@^MG4k{o z+;IkbA;}^U(|F^Y%uGV!BDbDUq!f_II)Wc!?;Nu9hq6c>>;~!_@*wc-JQa>Kc)5oR zq+7xdT%J-TNW{FJXE@}+7d+`D9nxhbq;>iM`?SiAggGUM8Hjm~d-|}Iz(pM}GruZr z&IZdGW<d~UM%#cbo9LkvmV#uS|3(|;;25%`9zP;4!T}l>xF~kXW8{Hti!p1`B9~GE zgvf*rj$s?*<gH-Ri`Ig#o-<B_>5YwY9VVBwx-1(&VI5FqJ-tc?{UI67!5_K-ftTtt z`a!tLp&Ky6M@u&~K4Tvu#pkM3KKbEq2+m}0PHwVDqOvf9LsjMe!B@eBd;fA<EMn2> zVIy_}mG1CxwYVVANUO>Ni2q?8_~U6Cltb#U5NtG8hu~Dv*I$?S<Mu!x7LlXyt|c`A zf+Fmlvkga{LX+2E8!&LH3-ep&U>BGTExcivI(e^e7f&h>@J^^M_^7ZKqpjM)DW**m zP7DBNL!-TlqhTT4X4qH4|MDD`A)jQUh(phBaF|#)+d9fKKx07~*1;<mW6J8Gqrohs zWiYt@;S%<tWDPqpB;u-P?rw|v37SD2$e1JIvAC_3_X=bl7BUj4pc$}>w_k1|1ECPQ z2VS0&dLuUdtXm!yWQ|8m@#ujLf`OCuST5F~F32Hq#ZHqUxDp$?XfJ3@|KS({+3w_f zx^a>cGy#qHj}ocWH0P;-#^EW70ybsjQzVyyZ_bx10UiF~GiJ*6!q*=z?=cuoV$+Qt zARHccJ7bvRw32~XdS%M!AsZrvG*Fvn!_pYe0UnBSx)0+?o;f`RB)EU}A~Iqln&L%V zV!P#waHjYd-oO{C|G*GzbUlbxrn~#P>7#enBgh>U=jg!~;NV#ziF`9gNJOz-Jxotn z%}EMHEjC$dYQ$@-VP4bfALamPvUtWJPb8m>9spdg8;-MhC_?I?FJP!i#k0YYrBN2v zgJqV7fkVVE!L>lVJfTRS;IpTF<%pPwwm8hf^3q5k{IwW0(r?Z-lnWG==yKxxU|!@b zrX0GKx*ocj*ihQk0f_hV;ys?Z7K)pHw!A@A&L6D%A7Yg|v^%D$yfdtE9Ns~tC^Eb+ zY&Ph7gVbS&KzM1?ln~YdjYzB<Vg|yv4)hL#%%fp2qTwB6fe@?`uHxKnD^Q(%0>IB4 zr-5Ts$W^bJ|0|i;Jz^*+&}rCZvn-(MAsw&?)g!h?rDGhBOovkijw2CLROVseyk!ye zvsr_1q=e9Uq2E8_-)XjnS+^Go)hn5t$^o+;kYLi}!8miAsO(Gpe7qK%;^LjSJ@V9x zHEAAN;z2C&(3{-o;sZb;GW@1D9v-t%#N;9xrkU?)R0l_FmzYH<*<@S@9)3we`huMq z{%_aeG0-R%)_@Nd;e^-}*3F&l)I!b8TM&-nya}h}c?Pqd?k~JG@ID2UEBxv~3LTj1 zay)*6;{lA&p%PLH970-zUAZ1ixWea#wlw^O>0t;5>hFWS!e6)=`~eoS;c^;3SUba9 z8^RZy|5~Qwh#vA09_XVFM?xbEyU?s6erLQ#J3^%(v~5bhMoJzi3?Y3O#CClJj+0AD z88C8Ll-p2|+3Y7~{G96BUF~_|gm2z2eWEDnWH3U6=9EKPYDo^%q9CTOC^jSR9Xz<s zavyY<#TVs4q~o;4h|}BSoRZN+J>#QrcpcReGZJc`K$Z6vb{x(D6a1dSiCV`q0U+G` z^VW_XyLAW?DqOhm-Mf0Y)C`<QuNIYh1PwCW$g!ixh5tT^94QhWJbChla1-|r52SkJ z;=v=y5#=|3knpGzr;%n&l=A46le6oeI(qatA~kAF4l#QFqW+5}=$JKj|B(7bi4bMf z|8QW#l^a`*tIxA&J(i=ViO{h%?!c~1N)sv8U~=eLi@GasIFBgnJxlu$95{LVVx`lD z&7VKQfaPJs#xGr^bl)03UN?Cix=QsXn}xg(B{*#4_JQIj8mQrP^)Br@J(~1LlZNZ1 zgT-32ZJI#kwQE=LqPTXoNg8zckDD55^XC1l<%Zqyp1;$E%ud=QyLu|ct#kSBTfBJ5 z&wlr%rXM}*X;Cg!r%lr$qw3NlT-vWGv~W_@v&$Owd}Gjgq@Cy0KL(A(-Gd#W6c0TE z`mqZ<^q7Q}T@=dk&sG1-GDmq`$-|I|f<cH-ZqxJ<8aDcI_YXhu(1K1q>!4)N|78Ds z_ToC*J@}7d{M6G6I{o;z&T0Q7mQH6XibSN5=Y$qxln7xpTs?a{QqOe<smIPc{&4e; z8nw7XkuOyIBaS=pVJYW>3WBH3aBBEc4?74#W>7og&_jiu!^L@)UFujv$s+Wq^G}S3 zT0_Vu^*H*EfO(NK=cZWd_|Gl|<gyJ`S{?cxJIDAD%sY<yp-DaA7@80{f=OlTt+?iT zt6}4Sl1)9})FY3s#1@<DI^)!n%sGwPIvG2l>@!Yh##UQwu&T`nY*ajMlFUCmS}U%& zQy!V*xae97C_Oq*^N&03q<gDFW}^AdJn|fJh&yk}>+in+%j?*8aMV%{|C`pu8?aP> z)<Z=zceb-|R#34MjU3VJH7-5S$YG5-2MI{vH^WYB^2rP5$j>uDh4k-y+V~+0J>$?b z$1E@zyH1J^npV#~y^P~eJ>`Ts=g{cDQqMR+P8M4>NrFR<i7Il7%|E@!Qeau~oW>6< z>GV?$j+~w-+0UTNXjs__{n-vRRB*#ip+=uY?>|rY(#|~bJRGsCYzJNvJm35S$sX*m zNe`H$xh>D({v7w)c}%Tg%~kA_%28DG5Hp80{jifPA&nF$`01oYRS$!tMM_8~^pNw< z&EshL5zpK?hD|-!e9MnvSH?#*QbX^<OM#A|L@PQj_EQhp!J}mw|2Y4ovzlS?_#^c` zu+ZaAkeYLf(qz`B!x}hPl`UWF_2fhkH{nY!53RMl;ZHa43`);%(W8DkN+$V6`|#io zHhrle?C9T5hT{*5(1RdmQD8#M0*`vM<sW}pNBk19ln?piW_zj`?J_7q{{>D$=&@ai zHuRo;Y=aOpa})^65t&+{j7V6!QQ=Tlta@~V9<h*y_JUOp=Uw9(>(EA4c=$Zd2?ZSd zP)9GSgbjH3LmSFsR*{~!Ivx_MiQu|gGCt7{Z3N4UJ*-qcGVz9iJg<ZDdR{x;(TpL~ z1AY(t$8gZd$39-F9*&_^PToNc9USmv{&<HxzM+O@h%R7Y|J+7BNY{^}K;?^Fl%%Wn zBs)Kpt}K7_qbR)y#)<JKX1Ty1G4kRlE_U%&^1z*K#s|f8T!I~w$=;^Mr^HyGV_Gnh zhkI!8tHV%@J7$RrLW&29b@YQs{I~=^x<Nw|p2slskVY@m@eOcTQGGzc${P&!4uh0% zf<Td&FP?CzOu)e(-|$Y|Oi0g!n1mbkI0PQ(QHVoW2Z6sa$TsMK1YcD0oC;Y`IOstL zO3=eSbWzGBtx=Cn(kB{zIL3SS6VZBlG)nvlM=tyj4r`1w9FE!`S7<eu?3hLy^uWY5 zUgW)9b`2ck*vBPa6qQ)gA|2x}CP**Yk0f1f8p)W<|L(L&k6dmBoGbi?^M2Y5Z=U3s zDl!XFXoUlEm}GS;JPS(N;ST3O3=(gs$2J(W!H)_qIO|cvJDy-L{$Z6cD5;qt4)Kq1 z1c!xRvBnyr0i?EakS<8+OQlTehjCQWux^d4Z4xM!!D<69m7-XB0@KppOphPF1eTKI z<QT81Myd1&M?IWjjB%I|p}>)cV@wiMSnPu_z1jyofOl8%l?)|CI-)<Y(Wgx<#~lZQ z13wb^DAJ788}fj|BmCh`9|BIYfinod{NV$2w4oO7AnSEw8x&vIaU1eTU~kP9!SrTs z8-q=0M<x0lyy)e!a)3uA9faNf{wA;(bB87<|Dlb?&KI4s{LS;YR}KNLS4E|TA~<{r z&&hzp7?`NXYai@fpv+dk^swGOjD(KiVg<I`F^FSq=?|dT^iP2bL?Qa|ruNFOVQ|0& zBYp8Gb8^_fQPL4R+#xY3u%lr9AS;SXBaaGFLk(uqP=u(ayx~Db9rd6DB|rq(90lb) z^f<;GssWZxEJ7S0lQNLkT$f9R1HRD+2OWZeIm2?+vs4q{5oHT3a5@Hy%g`eEK#>k{ z(B{W@UXeB`(+fp_rW#U<2R%`uJ8bkLT1H*6NQAtuE-emD^AxK*`1KDNt78b%@ZNaY z9Ax3(s{+*cZg@eB=XOBX4Vj=ZKsRC%|GQj@9AiNgD#<~r12e=VOo1Uh!XXDb_k&`r zj`m2tq76A5qa1>mML6P-Ib(Y{!J<aUSkwwO#|SH|a<WN1m{&x@sOBBN8||DZEfkvl za4qOTv~PLjBQxqUt5g<FJGe1~cYFh0n${paCUn0cumjcVfXAw(-Qf~NXN_%$fI;0+ z&QRZ&C0(kAT{$8ba-{YtY<-VBjv)tc6d2l5j+D&mL62<L+1nJ4b_ccLk3|ro9(1sZ z6Kk@w&I+&6{ZP$muJ$Mw&-<q7K*iFEw5)e1(aWbZN<#kO7>@=guk@hBh*ziY4wID{ zPaqt^%RXgfbE5)Jzym+lk?)*y{|YIwEJ$U>0gvL&QsD9^Bu0?)V1q;jqjQ+UHpEu6 zPp#oYh4pr+#=?&Nz>prn5JWVhVURA{9mq>r$3O|8iCOpo9<*}0*=#s5Y-mFsl|T|U z&IqJYO64`ZV1_@In~a%Wtz@=WT^GGq%HWI3dCT$#fOyC>b&SLCjwzf=<iQgj%42NQ z5Jm+jWc=<=Y#sg(+9lCQWOb+`PvNcBLj9m^P51%LM)`+*-l4JL>#U@fbN|x3&;R}# zYoTpndgXv+z^5xkhiCDyZlJI<wf9zCqeRAF4B!wsVB>lTmuT1p6hEUh)Dt9-5faHF z4nxBZRzxrKKps5dacN;r|Jjov@Zf=;7lRxjQ1lQ8kYIj>B~|qx41Qn@-M|iVfHU$S zNkO<eG`AJ<5Dwa4IU>?mIU<8H*g;Lv2y@UVp2t#nmMrIx4EIA%UQ<5*APmdkTEPT` zHU$n?WDL%58bT#%Sm6%zP!F3B1a*K3#K8{chIZTlFB69r<e)-k7>I2%H}Ak6>R@uG zq7d^D4t|ge+JI#uA`kpPQ5NNS==2rv;3{naD}wlWc40Ac&<KQpQdbCWNQe?;A$COL zKc;~V>EI8S02{FfEZ{I{SapFtBN^DR4Yt$`P$EC!R}a5119iX+wXg?ofD{-~57aOO zZnA5g7>($JXOzY&|40B0|Il}};cF~s4Y8sQ+t7#$1r2i$4MW#vJF^RZKomvechU%Y zEo2RiKmxlEI$ee$M#m8FQ5&U&MXZH}Z5TKTB8l~&hFBvFwCIlSh*v-{7W_~S%<~T2 zKywl_kYwcxa6k?H5FPJ89rX|$|DZ2K<_@^HkZy&G!ND*2R0uoKaSB0s^k91Ha21ZC zWfa8>9s@F#sEAi4DF(0$X?9g6nSozcdDfr_1`rI-)@A2migYIvFW3+KFqQn!5B^Xp z<P(d%QIcnImDoTJTc{8E&<*_XS3~)CKyn)H5L(?NK|UrsL*NS!^bX@7H{{_BXMzj$ z;1Flom$tz`|Lmb_>BSJ?AP+%^L0Dl8EcXuKun3wE4oiu18__}G01Z8OVr=J^Y!fM( zKmxPCIg%D32e=S;_Yd$EEK0RI-sB$hvs%Ug4-Z*Q{{s}0!4Ifl4q@YE1F4y$;Wg2; z4XqJ8!O<`wr(|>UHb`)l>jV?;;10a`d0aV&R@4pt00)`y59FX#ZiZ32&=cX{4yw`) zYXA*h1Y5qwAkq1p!oyJqVGYr64AHQZq4^WC<Q4K@ezVsP(x4CKAePgx4W}^<&h!sr zcN)o)nJz^&L;_U7Vod2dlw-pW^uTVl*mRMBAp&HBk3==^uvU0r3FPnyfq;4@@u2D% zgJb0m|A9#k{xA~?Cl$gl2jTF1<$zNEKnQMuG0R69G`CPE+FxGbD0~7HAAyf0@@HIh z4#sc^vCyC9U=GW0379ZqyMqbmzz)IUR{qcr-SmW5_oECc8s~rs$$||+vsv!-4&qP` zb+iu0u~F*)4>iLLRe*MKNqAtIrwefqq?Tjfunqp;V@6R9jmTy1@eire1eCyuFsP@3 zc%WL*sH^u3<4~#7@;uPs46(qUurV3MfDPr~57(d%=>QMrpfs_GpjdJqExJBF=BQ^8 zq497Ixi>W0V5zuTseRQA-arp<<1Th3Wb^P21Xl(9us0?Os}$!D27+qrFc00(4GX0X z|NX#nWR_k)Av;_oJ3FbYY=#tLaUPM{KZ4;(*?<eDst@O&4KP)y&G|bMxedI)3#7^z z&g52p*N5J^5a%%&<A4tOa1FZWN(7rM&m#+US{@<6k0ePAwXi?5wy!6;9Pc1IwJ-#h z5QopBS{6hINhmuCaUNqKsS+EF$|Mqk5eIw_2T+g?`EU;DP!48VmailgOhXRM;1A^x z5B}G)KHGig@u}$`mioZ5DjNqX%LbO<4}6dYNe~9qa7e_$G_c|r-1oCso3-9YWd1-6 zbr1w;a0HuB54k`GO<<1yFtS>^wruM~4QMQ}^bE{E408)eTUu2uYAE$a4^<@-|IbOX zXJLMTD_KEdU4TTlh)3k~$Z48p(+379@2;V8qR9qgbEWn&QfN>7`+5tr*IY=fPc zN({n4p4-3-iw7j>35bEnx(j)-xAP1d3oP0o7FSt(u4F3<M?~e|GQJD9&vO`3aZGE= zyHe2=wO1{%gd=TBEW6uHND;l!`#d|dI)K`u-(xGu8z3dKz1G5TNWrrvBe=FQCeQPN z%{#o_1AOd2Y~xZv^?<&j6iL&I6;WZoNMV1Mk`*;uEo9fTO$0`3F)l#Dyy+V-Z(A%y z_lJLoLMKZ+SLr><mq7xg54Ru<M%54CM<&^e5)M&XGs+L<@_O1sb|zsG|6>6bMdf2s zW_YIg4pR1EsMx#f;1FQp7|!B~$*_j@`bS;iRm+w^MdcX8(R<<dVdBO$YsSD#{D%m^ zz|-hu>*E;8C~+j{qR7T|{%{^BToy0L4KvUIQOkEd<z8y0aA1+dUO_8>^bQEYan*n( z@bV4}qPdzo77lS9dYo^;Mi!K|8Nt!T3xdPjQH`-QeSRem53w{%{0)w5Am}q>?Z736 zpr*)i#a!&75OPc!;ku=Ax%j0~>O~gSWEP;D3v+M`!!j1_RmLSMTY;)xQ9;TGak5bn zVNr3EJ!p>_o1NG+HP=TL2T?(qP=$XnBvxgXeR*da5f$SwA>}X*|LOo1@Wv1AFc!0C z4vFA<nn9IA6RNv6l{y=${BREY01vt0B>b>YMu8zU3c6m#%Ii>-RoM>9wWU%i4n=j# z)l3fRKqOLWmCpnY;xG-_&>Q`b4!y7sMTHbaH5be0Jw>7n%22iNCJtf|Y;=*VsACu8 zzzyW^4Qp`{-@pwby|eK^4&C6$;TjK*Ol-rV4q-3=5Tj%v?a1kcK?67rBs0JtEx0w4 z33w1X+C{97;7A;oUXMIB@9~G+05T;q!{G49Q*9{>;>h4IZs2f;e<;%5&<*CNtwgg% z1_KWqM-6bGCwy0<Cq30=F*j>E1kM;8FD(yx>`}rN4VrKa|2;(xU{NzjF%FFRi1a}T zDo_*{L_$DORADire8;oXJfrbo7&RIW-B3Hi^oL;4O$K2N!O#hygF%z@DzTD{;ec!) zQ^%@B2qZuca6%5-5Em`>Wtz#%33YwJJ2t=q5AU!$p;2k+a0|}B8K?m+s998~shU<a zd*uKQ+4Gg>;0V}gVZp1h&Rus)LW{H*EUpzA4eCt0<22at9pbG_>Hw-bYZwXb2<Lze z#UL!tv%Fkn7`vkk`T!0|vRk{;Q5=0bbu!6Y0&0^CFY&u4lN?^cf)a4Jmu0c0zOVog z124(4B?tsa#8D3<IXAA2T+SyCb<hECvNr}XtbHXc{}se>7@l4Oe&E_E6vW}$^YA># zB^+0YTwDZ)4#AuvH{f#Q4oNmF^YAtVpqJ6HP#Dg!?m%qO(GE|51oW`v$aT$jJ)iaD zw^FebxobrPTi7aaZTnj)j`3_<^hcFay-hT-1p6HX3v5NybqJwaDli9KB<2AkEceS$ zH_#2*pytnGNzd7o`M3@vn-0bhHvC`=w*?O8une5~BH0iL&VWn10}W!i&`h$Q`p{aF zu?@+f2sg5H=a2|4D;xDN4blLp(l8A{HGxA^57{7=*RT)Eung%y5B%T^V(ARMkq*gF z={G_QL~9P!kc9PM4yYgvO=W56Fbw!W(b+Je|IQGH`(O-F!4H_=vcpi(*Z?$QiH&Px zk_zq)-|z@Q5C)I%<ZrVFVGstt5IOEpKS^K+=tU-mkOWnb33%8J4Fusk5#zWJ20;)A zMe+}i;0usY1-L*C$KeZau<ki44j#S$J5T}w@ep+&1H|wy$n^|$5C(5R4Re$URj}@r z+?+l}91LFthQRP24-f5N2yKuAknk?`Pz`m^2J6lYiK7PVz6a2OFNc5wncxp<BIG5o z13KUf@_-A|C5(>{+wFh{IIsf)@C19w@gDCBNjA7_<0-SS2B~Zi+RzD0umqZ5ES>j1 z)$jku56-fVBRhMqh_Xi=`;g7C_uhMF9OIm0J7#2LZy8yYbZm)Gcq4RV3sFcVzCO3x z_YZize!6bg>v}z}$K!sdK5e6Z3a3hvfD9mDXR}*dL~54&ppqBV!EM0nBne7iPO1$q zW7oIP=qZ@iOJGVJ`4;+D<U`0cNs3+@l&jK8_84$eiYbM|1`y<A4AgnYoa<bavTZ;b z1nIKjO<xe|YCxqpQLOn2UKtO|M8jw{q4zPA6L^|Gc$!f_$#dx5P6qW7oKoET%VGqq zQ{wV{+unOTbo-bmReb-qgEcXL{3B33^_UMOWmE1&HIAn_KkR64qrn|@v`LuEm(%n- zqnV7`U8T8t;|Lpfph|bF-3y?ZDx+C4gfZ#{|3`!Z2C_=!U4Q3Me;T8C`oQ(ikC9~v ztoVjqddF_K&}c(5lU+G>4w=oa7=GBxzDx^D;g0$|IJwyFe4X4H)tfN9LgH@yMpY$& zZ;3mtL@vCGQOa4iRVb$zxj$F6Lm1FwDZ1$TiQ=!h8Cd?AX94`2QmAp@%pPeJ*iM(2 zxjJNqn_#))j?_DTnzh2>Zz<Y!)ND`Bq!$-l83iW>6UyQq|DCAc@GX0*Mz%ahC)>&{ z-LDvM;RMlw^u%R}7&@Cn-4nUbp7LKUZ7;nIJVvaImS(T{MIG!<y;5;9>y67;Sm~9- z8NTra<G)zkf5ciN@H+E%_KR<vicwqLI7&C-Ko0+S)sy!cvF}Qv&Y<jX*Gud!Amcj+ z#!Rh7|2+2RFjcsuKYlZtoO(#KK#47KyoN(>6LAy|xh9h1@IMOh&T?VIb}?C+hd{}m zsIq}%o&ds$AiLe<(ipSdOod>9V}av%woj_CKq>M$NgcD#hd{p4(DOhbdjK;jt}M8q z0ap_H@#RQKR3}LtM+n=JJ6p<lJcvH_N>bofY}>%7_PzJo;C$c7fgEJWV73Nlu;077 z;us!z9EZ>pxu9;~)yp7GpVSj@zTGZ&a7hT8JVYdDzv#sqZ$E9VGNJd5S}d;n*#fjN z5A>>MQ-m6Y)J+WjCG*6Yl~!jeu;JG^?HP|ToS|#=8fD4>yS1G5y_IzdFq=>SBx<{8 zOsKlALNFa<vpNv(yXi@Yx0;h2#>cHyxMe9^4{~wQ1zt8(CC1J*>^uuw_H>Ka`k&(! z)O(U|7MFvp<Oovqa94}i9MElrt!4MHcrjkoJkuo#g-h9s)MMDac;u3v1^wO|6Y|<O z8e<<{WYKyN#(S<+617H%XN}XXs(nU5>Uk?gaG?Q%=IduC+6Mk{g`i9#t9G6RRldU{ z*^V~2r$C@Z8zc-9?V5cK%_nNPQ9>^r3*-yXqfg_mmNH7OgNz)XfLK$u!4G%2HD9uF zpli!E2gz}LQ3<r-B_5_8d?itpCsirVmt+zzgE}p79D1g5ZY8#+<27tQ00QbD-)3&^ zm-18=2^&EZC-Nb)@|7OL_)YFHPOj@6DR5bolM0w~DN@^gMzK`obPRdke(zRD+br%$ z?3(9y_1N;hZBCK=m6%DV-HMS%vFS$DVLqcLINgAphO4KmtLi(qmT&`gWr{!NjCA%R zpSk_=3X<w9Q!#M~nXqF~UH%(FO!;_*C8&%kyWnVCFJY|5$78$n5hAIbL!4cB6*3(O z^sNhLmn#n~<zyU$&CuEXuuw}m0HHz-9^@Q1E>PG$fwdt6ME1+IAXEc1g8vfbx4aN! zgBp1X<7n1R3y9K!bi39mnPrg$K-xv4DVF%2Gb)?pVgCSkyKf>#C?Q^fO9fybFv`@m zr~(lv?7+<@STo3}Kcu21xsK-wbUwh3wQbVg^Ajs)JVr1o$@Nl)wH<IO5QY>NC6ff_ zs@&x7sF0UcWQHx)m{JZ;`SrVHR328c9w%od`L!igWS7(4l=hW(HOY6Fso7EzaeRLr zsrwF{7;mh!bkIO{auxz$_ChOYS&btUs0RADWc_81L~fuVksae~AooWl%aRMpIyDJW z?mn-dupGKg12>4dNrX9{Q{{Y-LhT_tX?+0{46y9cDyIr6|4Ux>PjE<4$Yy%%1r%w| zlOr`z(QsZ(#`IliEY~kv$=9KZ1EHg(1O_P^&Q-A$_G-wEy9gu(-DUS##uZ0YWJRSX za&HBg%v1t1&jPO}Vs2EF_xKVr{O&Xw306YXUIoq|5ANRDF4t0yXm1d$sN%RR)KnOy z%|saiOKzw;esd=@<Hw1dj>+@Q(JEPC;|VOMi)5_d)-w#!)!1q4$ws}n)2sW`oHrd9 zO>ayF$Yv2ztl=0+*DY^}t(ox<ul4fJEC;t=Eh!$EDu*A3S*je^X>-}VTv>0;E^NlF z3M~#rX9K0>x~S!j8HQIXU~CfLG#zyw&rOxAtPE#c-p7!R<rD1eB^eXtE>^*AJ2OhD z0*~~;D%77q`FUpQk!RyOnyT7WzkPF~C`SVlv}v3h)mTg0wy2@&?B%|=oVPx1yqN>C zsw;%s*WW#W<du>z2A>xk*54pYZjKoq5ynNcT<Vfp+BCMcqHOCKSS61C%BAnbD`ptR zOKZ33c~3eqo;i%|pkEU|r|){x#J0%{4rGZIsqy@f0E>Kx&vYU1uz&wVn>C)4X)Q;_ zp1Z6i54}h23C!YPw$97zcQm}ExWQIBgH?zkNuwUBjB?L`6zykINjlEy4XELy@&ePM z4#?R*1tjGqm%zdhk(}Q}P4DinS8WJ8vwXyBD3~@=F@EDkUU?)-)do_=B$2V#OW>qR z;weJf$XJ^a0?N+%+#mc}nvMgX{%59<8OO&>)r&5t3Q=T2>XJf=c6ni3*(nIB3ReTd zHA<`ujiVDtGqbM2aW^KUDR9NJ?ppwC#!g`2gbk+Ph7oQ?uIFLN3Upb7k%v;j63A*9 z%X<;(V(N!!;p1HPq~17%<4c+`O+;Gf4=46Ae2Ntj0J$s&!$^%NBiR#dd|Ys>-?+2l zs2;I%e@^ed-%jq)w*k+xV<zcs&*Ua>(-jd0;G64|Y-|aipY3V!k|_rys70(e@g9j! z1g`OK@-PJ#Cax)w!y+!#*cZ5x0&c5tdBe?eu03m)lwQiJ`t;G!2o6Z@wsYY8JDv>A zYCgu0_p+YuJpADhDOh$=%xcKP#PS`e{Oa2=Kb{zL$6z|>R>|`O+0{LRUq2PDb;D_m zLBClq7stfZyI`@qiP66o#|qoBsqN%8I1|0b<XvP913a8L-@zS7-py?V3r$CS!ml3v zX{T=eLdMcl7+Ca2MIcfxF>I$-L*`s%C+1WY{mT%nOo+dDyuwSny@<W9G)d!Gu4*X% z6(iY!qYlGwuuZ_rrJj~hEs?h=|3xT2fE&XCbaldZ+R8Ly-#ZX9huN>nH5r2B&|DIV zbnN5Yd{Ofm=Gw<h_Fki~Mh0ww@Cehrax8^xB93jMobgbb^wDU0X7(xBt#N-ed$vXf zViQiTSpt#9&v?72$l%xkKFWiJ5Z2qI?N^o1<sT1Y2|eP2@m54ESHLxz?KWu`5o}Xf z4rT_>{dgN9!FTW%H%sw0I2adhh_e!kKm7^1;b?AqqhU@s_v8Y$sKh`bRtu^EK_|r$ z@vwE}M$!D~-%kVTt1+K3Q!H7wP>8=pg28R_osUWUP;jLs8Rl<RfCCOqiQQks2q223 zxsp6AlB}WtfF%rn8~+Y7PB;(d-5YOkyH*2FR{Zzr-QijdhgSW1eljRFY!Rdir`b7v zY6%#E949)Li%0bis0<G@h|&iAg(z7=K;Bs!?TAPVxyW5yEEjHdw=RSTi6dr2$Z<5V zrl1B2<9ea2%V6Eptk^|J2m%swA?YK8i?HYoWroB;uX%t`INfTT<q9@%7bh~HfMNp& z3kjuX-+cDqK&vibM{*n*=L?5OeuG4!aUt-=Pzwg5TR3;Vx2+YL50*2tj|EhL;*k=y ze&t|4u8asgBrZTCsv_gOaKtWUFph}x^<Xi&yd5eh9ndM~SB?z?6i0AD26J%PT(XgE zS|O$~af>j&MXYBeBu?l}tOYKd88XO&^MfZ-x!eF7pQf*5H1f*cHiiVrjTo9jf+zc1 z*TMD|JP^60@NvySg`S9V9BNj}C><B!K@-!NkNFG9-vrBjWsa-H`U47w7O{S971IOs zfy2oq#yEF5?8q$a3-ku@3Kp$|1YKNX1J%^qe}k9FAl^_&`XcOr99N;kZ$yd@KL&ey z-~y6yp#T~(wam;MiL@#RFp4MO0viyW=hr3xROJe66Ci)Y6t{>S4iS3Q4)#ah0wwAM zN)4wkY7aI-0s?fFMa!yBsRPCd_&l7*(qt&0xTG=1JROJfq)83XdG~j6KolH^r29rY zwQA9O<dHQUsoSwKSu%+Af<ye1Z~dm#2>Qzgt0<lVYK6&V)3NkmK2Op$Bx7>*1L~8% z&gusZ4NL&*R@+9tJjSISzehQatEc0Bb|#}7rRVs1TzO?x)5eQU8L&2x#XGn!KXJ*r z<#D@&8z^UgHE!YH5v$F$mR=Ihpc?mg?u}N5W?b95;yLwGb%WZWG#?La?4#7k<muB+ zITC54XA<s@&-*{shN;H}dd=@s(~;;Pp_vBVnnv7l4ql&7LzR?T&fN@2oKA?ANL|cq z{50G;%f!hbg=Oo3wov-l7k_BzReCQBeLSPY+f(DD5Z%emsiDXE<3l5v0r>NWz>iSv zTO*fu@>4DHv*FJ<-cUlTcx2hdD8w4&QEdr)Ix)Q%$8ksqUdZR-cKPp_om1R$vat^U zH$qqLnhf<RRHxK4=B755<H?_nG)<jEXr~)Ozu_RP<Y|i;5}4`_%~0)sw+EwUcvt4) z3e|xVFMQdIZf?KlIl7>*hF6El8d6;!W|y_&lZJ!va~!LgCSA$2|6087%tS2ScMUFe z7b0mW?~jAx;(kBX2+^TzL4Cf!mGVs)oI<$IY8_(Q*7A(%=|8?D$J#)#BpSw{z0;Or z3tS^6ol+l3eGOcjO+^0SoB@NoP@KGPR(5%@dCbhTW%qOi6lN)Na>=A#4PCusZUhnx z<YA9o)HY;LmwK~k)rnGSd9}Lu?sdcmFaC#CZ=i`%&w}M}F&9k6VyIN;lJSx@Y)PA- zdqbgX3%S72Y3o-dEHSPwJ_CJ%vM-||XD%lf4D%OfXsvGXPdT~bGEmF4s}}V!%c03j zrkJXF)U}qe<bpiLGU9@*<|}ONqNO!v5v=z~9<#XmI=QqN;#UvyssdZmYb%1x(hip! zK-R|Ztfbhj3|D8Xw%&YM&TuteZqzGr;a@S(FiEdpzOQG&+6TQq4|bXX>dApyg{_BB zH*8UhniiAkDP4ckrHB9<70gTxd#Pm0;%kPFuARwthgLn96~@x}oj&U%G33s&t`ESb zO5qb#^vsv9W-6vQ5tX^A&5!rH{-bGMCGxM`|7X2`DkuEY-?d#$m$ME~Dy^EDE1mo3 zx?(qYmi%SVE*;4qzDo!LjHhboEwPuLD4Q6G8LqL9$!{f}O*XJokByC}oMH^Wr+@jr zb-nhZ%MMw&m=W;#%l^`-s{=Gf|EKLrCVzAA9)#R?R&6qaszf~&diyuXK{b61cwV$C z<~SQjq+$8e<tkxxiS=h5|Fh*li{;CaUcbz!4k|AW8n+<Belb!fvT>+aMdd98ymC!a z;PuVAGj$)yFUN1^lu-KhVeVIv(XV$FzKYp7MYWiTgEu4?HzWl%?twc+Wj3T>&S;gd zLL6)2F|P!|z6y&wC|rG&WprLbZ76SVDAlf?U^X5wZYqEKh~U^%<JeS?aZz{MeDIjw zNx~5-@Kw8ZQ>T0L(dee`f(zZz`zSmpI^AAu>jmk;#)J1zBLSD&n$9B1TN<^-sIY5S zHjWXCtFI<9TMuhp4bQ)tYQDD-*h0l_*<~uAINTg%T%9>wZ88;Hwzn+p+}!(J-4<S$ ziMv?~xOio{d6&8Q=)3urxw(GWHlo@w<Z!nK@A$24`4?=Px7eGSxqEQ9b{^PkC$lae z&b!puMt8gWt?tD3@5C&)qtD&rU>?P6yRqWC(Tux^-8)HFJ6Jc5WRBg0Fpq=>yQ!HT zv1PmI{kxgl9*G4WX;&Vp=N_2?dl?*in5*5KSdUyc&x|n7JhR=rg1!7Q&+P8KVoi@s z&8P0f#D~Y==QXQ=T>F&*`-w7MRUEt3;`=pj`&H*VbsUhoSg%HXuO>6EW<R6-`sZFP z*!|c7uj(VOHV*F&H?P(*uTHaXT{7RA+`h%Yyq}AEKhFHt9p?Rd&8zQ&cW>FZiX-p0 z54>OYd%w~59%TGRkU8jC)2@yOBQ6rr008%IAjkzk0=NSJFayw}|40DPYXBLP4cS&c zkodnu+jv{W5Dw0(Q-W--97$s)D<A(~qAiO{EtO5XqxxO0kV&J>yN=B?HZkXk673hY zQ^j(@`z!BW)J;D_BvP>Jbk@&SA#+7+CpsHG)frall<IUf&No@S@LHYdYWlC$VJMaT zQFrsw3y)8Yw(q-JKKBG{Oq4$AdA|BO;^+SA`<~V>Z_#9wH~GM}^`T@sQM<|B_Kh(- z@1ru^mmOR03-5ccO}>1wGhMEh#-aDBbMI5VNt4~wtFCYVwK=~p(|g^0__;Uu+uGFY zp6_1>iIklBeZ40e<GG^tANpSY+!=WjL2FS<b^2|QTeC<tAhqCtIAnf3iC<SkQ!z;Z zk#Ft#{vIqqVi&oLlK%a@`1$S2^xL=B*8s2(5e;PYAjU%($4MaHr(|ps;r(?Z;qK#1 z>lo&4{y|krMs-dVRz?>)EZ=SSco4ka{A=o+?p+>lB`Dv!G%1QY6#(1@js}HM@g*U6 z7ld5AbY>***;E+0&74|GRXiohI1ij%mV=%z*CO?NER)kmh?KenKuajFEbx2^0q@D- z*$ZsSYl{NH3P^J(7`_f=<d(DSls%zMOhd3xoeHWvrWz(oj25_UiN9SRF$3cEI#wx9 zHQO&t&16ifuS&Ms-&3Qaha>8%&htqioTPvD8d+@L?Kh=GUONm#(F4l`n|nnHR4GV$ z0sPPUwnYxwh7(S00TvEM2OX0#-ws~PXo?<o&Y5{1b}hO!9d@sTeLL(SVnvU7Hw(Ov zUhdX59lbi}{&w{GcvSRz-|2$)_cs^YP2c-3&;OTbgZTU>Kz71?JOHcUhEsyb2iqi| zT0ZarQU+DH@-5yzeKwN9cx^y9GcR(K&sk}Pf~1+yhPZ52>mV@G<lrCP<@C9y(jh@d zn3BH!Ml-coXfypm?H60%L(&tU(~r8cho_$mwZzWmOwE1I<}KV?&K7LK56}K{z=@qN zx;*hcU-GDHIbZhaIXwRyFedhECFDQfU#k&2Ex*>He_bE``htdtUl5a+{4Um$|3m73 zO_zPJC?}|>??X?T%|d9;dHi&gJ%1%INhRFn$nyaONGz(P0B!^22gg^P?x_ym7dUA8 zqo%KH{IP%kA-D+LarC%x=rO<v@K!`>rkWQnbxrTvS2RUqn)P$q-2dO%qI>JV^Of-L z|9%m1cdsrspZH(>UZ~5V_;dHE(}ZwcTbv_DdMD3y+R2wJ#}<;j%D9v!iIHm_7gGK{ zRR+?)FMt6u48W8N;B)+ibZ7$$AR=yX)aYBJZT;kKV-OU9gh2!;4~&wKZ<T{`-04+~ zXAa;ZRpJgbKA|vfQ{hS&zo~4ala%0m2~8Fls_V2Wf~k-$Mcjo7fLM-8=#z+3+sq&( zgAa3klz@pIs{mpF5CtG1jV-M*U`2KWQ0PSeN@%#*FTW$dMK|3zn)7lSnQBh2Mxzjs zh=^qZFxLBo-AbzR|Jp-gE8#?{5iufqHJ1XQ5&@JF)hRGS<7*{6^d!t0%x>sp^Uef% zGHpjd2=@e+S&q!U2}T5!Jz=t2$sAgUVAqtV(CANK=ykz}SkeN7%5KTHN^SgApQTXi zE{9gkfP@h*Q&HfbPkJS{glFn0`6dZ)l6psW%-(~uY)R})=aewwH-&OYIZYLxhFHVm zdwJ|98IvS?_B6>9o=F6KEAxoZAM<Mpll~Vnjr2$n%XVG04-ViMA*>+CIF<hC@v~kd z&|U2cN?W2M>Eawn&3@J}OjSy@w!TW-$uh}lH-V0-hKK*5PH_ZwFf+Lj!F;bm*N}oQ z`HRb*&kEDS!rLT}GOjH|^`3s|=xB^;wTFOLTcYKk)@OC&4MwgnCR{U(Y4~@CM5XrM zq6puMOky%bgd5Y8Cb^*2TkgU->-quMGwB+5gJmKbYCD|&%ua0I8ucPGbX<*tggB~X zr1M{Ds#6QwRMXvG3Qzkx64~SajXk_t&WLiTqEjLAiLty|=)1Qd{p|uGKfX@mF{c6! zT@(>kZ=a2gEs)M~9eX%R@-ph0NJ5@Wz=|I{`S^hX7~9IA=d(0x9yyoDwsB!8h6kho zI@P%PP<tYCOe?cgzuHMF#FY25Qv^E)n9iVDL7$fN<C}x>=eH*9aevJZgPu@)@wJnk zSXV+d`e&x;wYpyoWJZPX0?z6|(J?n7_w<c0jo>9cgZM`c`~Tg`bj2Y!M6JT-s#r{+ ziFbF`GyR9poj?OM4>_ZY`UlB4(6(c8PkX2l^^QYoCR)myv;P5*=c6((glO2iRKGC% za9;Ku#r|0(KL8IDy9*gja>w`oL2*dY)vH^cpn6DuOICmm6!#rn_$a?~>N1Yo(*`-O z9m+BE_U-Ak+7#ZV;k)KI0o*}1WaIewio(BgB^Oh7*o9r{a#cgQiaCGM+{8LN6{~KH zoIWd&lWK#f5$r|$-#RL~oQ4x0q`UCiX8BKUu%|vx;O_pm8)|s>(=(P}k0r^hu%u-; zI`mYIUdheWUEpI^t%Upo+YAlXN;Z;!Q^gV+Z)^AM)_@0+aX-^vvmi)0P6MP;F_W1{ zR@OlZeHo>K8(X^RIyJL5PHyG$KPP+E&kxCd%Dl40T%=leY(J278@-c7L1v-jTd$$K zcCyRz>Ehjw1ziuC=<fgzi+5jlTXRd<0w(T64{q+>JsJ!+j!RaH=&F?oV}-GJKWgPT z#OGlD8PSCE^|U^`<_&)-4=ef_<oqFSF&^7fY!lZjKRDzX>BwWd5~Owe!;hP#c3I(} zNLkIX25oT}u{pwhi<Zm^{at6Tci-~w=N0|9KaNo!6eA;U&pn2R#<3s5qI{J0DHdKi ze|+N|e#2pYmN}L}-VxX(cmv7FfGDdgW&!A9<_5~N);0!0<i0N*`PyA5U@u{BuLnMS z_8n77e;v@t+b^+o^~;`@Ju_hP_c(U9RdJbnJ@1p%hbLOP_Irx3@RedpWWk~08u#Z1 zoDa_8jb0*7A6Nmxdtm)=i1PSsMwz|&pqmNbU7DQt=E^qgn{W>0SFB&QTjT(iI94Hp zctVMlrBRcB)^+@6l^A<~93X?UY$X<z>LL<S^!=}Z#d;?!>SAN-hzrcu?|T)MJjCAj z$(&;+qz5N+Bai1cgxpv}pJ44s;D!PB+zyU|uJF{Mc;Mq1s(S*kL*hLSq->ZWx10lz z-w>!dqg_WZI?>W}`(f_m?nvSgj{=aNaamrE**~Q7ccfD{LJ5YzL89d(kB^Nh&b00L z<Gz^lW@DX65J6dRfHt0do)NG*V_y%EmAnPu&4sAqRm2ITcV@`X>C6rDAO6(h%{g;V z`=pd>2qGa;sy>kl{u!f*S9xd%iXlKmk3}gNQ9(c(@tjDYk^jLAb&NTU?;?1v97f6= zjkpfS$ji#?)2Uza>X5~gp&TH3^Z-XG(}rWiz<bsiOaRP{KfEoO)G>$yCo?yq^6UbA z7X`m(D6gyv_oo;1ld&T?rV50E>lSHpWMN56fPn5)GVWySArnJ-l*|@+%nYdlfmFsp zz91*ELmHML3+p9<Rq*7OT$ZBeG^tO*98Fv&gbZ9ppqg!DAsD?ohz#I>RsfGx2R|HZ z2yz6FU(H0U%+PF%2e>-xG$9PDi4+3!kcV8sS0+>-lQhseiOdYL?$}u^A?lDwjYk9H z;ef$JoBL*NTn(|xyq<I?52}eeBLs2{F0v45oyuV-_J{m4I)LRO&ys91+4XEV$&4up z0d`EJe%=$bsFf)jDZL+@*Wf^*3Vg`m3Ms-sk`a$uW(=AfQr_H$cf*m)m5Bib@P%#a z>3r!JGaAA+1&G!|CLcku`JfT6%OGtYWk|u$WxzJCFM0;Spq~KajjdktWSyB4iTNM4 zqO9*nT+h(Br66kQJ+`Fb$8;2R0IC}Sti}w93f%OyG`tj)yriz9%Fl-t%)BO0*A>7O zkkXWbIiPrZmre>iIaL)JDryM{TB7(n_wb*Zc8NATrYM1hH2H<B)R&p0HG)jsyW%x^ zwUa7}?^P79G3a~cs8?_*A=iAbJ$PQH8=OZ)jW?R4jruVH<ab>!(?{pJw27l(RyWl& zt3spiyBhEF!P&N~QdIM+iPX%Al)gml&~KZL`!YR(?sBdajlhR<Nl;BV$^9<trY<v> zj>d0S0c8e2#WC~{Og_g2M~#R0m{3#_5{FHV(j~}dEsX}aC~)(Zs7^QcMV<)@xNeQ3 z#(mg~CQY5TjL~_8ucdA)9>Oj`ij{aG^t5uyMYRy?sj8}P&QGFJj#m5$+aM&LyO+5q z21%JvbGvG_Izag0;JYZ3YGTFJi{jVs_?~Q*kPyg`gq&owW{h?jNr037sQspcaXJ8a zPmrRzTCd+#09mio?5fq`0D)liZ==+JDm5-cin7<+G}v?4jY!+NfczoaP=x`2%TIdr zqcSt4;W<4Z9RRvlha#(}CUKxtq?3^~ccwI_IYqeS>`;0cTCg$HdV|z{nDbtoSqJCo zwk<(ku;gD#nf6uZM~z8m7c{@~su4V=J|lWyCCGlCQ{U(eV5ugS#<irhX@oXts010} zsp{{}r=qR}cf*_Q>2fYLp5`z?kq*#3F6%=8buEzsy;vzun!ExjYB8kxU;*SZ1eOu- zJ@Tfp(Bxz*SS&`m=~ckQC~Vy!?xzFv`*PM5(c|m_-TSoVn3v)%h-%<wrSOrdSW#8A z>9XhRu{IgU14GPzW_<&=mtvotl|Ku+)}+3gfxSC3|Bk3ZPVnS1BWlrZjS_mTQWWQW zCKZNM18oM&+8X6@@L81fBX{S05z8|IOzNBO?**!X!mx*G_umFs07>G-NFNH&Q*;yX zgjB208t1?C=8;{Ms9HDMs^>}LutD<|huf4)iZq`CJh<fHQ!|N!o0Tq7W(*8~vSYA2 z3Q`HD5}dFqPO*2}HFI62&;d(JP`U?<!Zv4MpN6{n3I0Ecuzv{0Tz>a&HL<i$x%br! zN9X~`c!;i*1*H(2b0UF$z`Dj$%4W=dc*}gX&2<i++z&|qDFG8u^Mx8ww>Xs2el_@! zr#CV~aTa3cJAuzHH1>EAVt)OX=2QaqX@fd?rn;Z2;U@z21079GTS(FtedO4ElJ=;4 zlcF`GP7#j^%hMCm(YU4l*5*^2#OsL5k-nQKNcn#>*^RazKIa}ih95uX_B6BmPm#hu zfK+dUe1*04FsY1&xeH@SP~M@D`9u9#gSs5zus=inukBUn7<|Zt`a7*|U3ncP5~5;A z8ae~HjcE}2tbd_E;A49ccuvizNuA{mo!Wqr3tBgl(;lO#zYionkt!W<fb!0eC^`Vk z(9kjoa^MNY&2dw$L|Wt0#ZH#y>^OXs-%nPA_ULctWW@vg%U%o|%#Q|Yl#@LqYLOsF zdOS3LSG7<zIq;?XoLnDMmuZGL%6d)z@z|1h*Z8=*A6R*p|7C|T*?qvvC@xX~3Ah&e zUi2yXRq&_<UH|0`98Qs@pZI){{vFbJ@KY}BTW>aWy-uO2?g#-|gt1bY@6<!ULkN-~ z4ib`I@hB5CB`(|m>wPU?S*1bq9Z&9c4Af<NcLZ=vXnGZR$$=h!R7;@HWu=G!JjWWE zhe=b^7`Bm}K$O3#sRx)m6_Lh4Uc_1Y<CbWiTgBdVha6d5j|FIKi&{0UscO&=UWqg; zks_zKl63upgBm*7hF~j5vq7NwluK?3h`zHO*(3^om^&>NWDi+|Ffo9!c(bbGw`;Ej z$W<WEx!xLG=Z;R<_~n3THvifY{-e2SqdrWFMp@5@R<<6SAaeuE9Es#yX_Y-Xa8Xy% zK*O}-#Rl`L32tp`*45d)zpyWaWJR?c=}MjMhBwypANBQ8d>Fc-I`}8<!2R&5^(B%P z)H(k_<w*#$U%FsN@EEAk`$r!sS_l+n2tYc4yvD)!vDc&b^b{3sRt1YGKoY2lQ>$sB zGq*hak^xXPKWzYrK4+>aP+h1ZK>xA=Rq@M3!{p8XbXte;jYRSQ>gi)$I4eEGr5PTa zaW}nj!i?3k^pIvtD@dxbIscY1^_fnx10-?=a^H}2#+H=C0jLQ8Y2qP-86?;!4g6EX z?OOZB8PWuC{-l5Y#PTooAtH7SWOoMdWo5D)WEB+squpg{#888*u7(6SK*G=v4Ztdk zDcpgX_puzgz*c(&7sZh?il)8t_~YmPsiZCR@CpX#PguK_RYw04t|gXpJlC(1pxobF z{&h%RXsRNddr!2Dw8Dq<fgv;s4;hds&58U%UPg52`n;h^kX@a0RE|GH(1=8@e;SHM zy$+nYoN{YiNZzWr>NKl%C>}7RSX6{#0=9Atp}AZ@WjvXD8(G~dB)uGx9zgX9Kt(`* z@hu|$4z_z8CB7k-r$H4`cEb`U*h~$@yZ>_R?Wmj@E`T$uw;sP$%~Mr%eZ+8$qDsw# zre{JCL^81%(gQg%M*?}e;lmM!?ODZL4pAc$>?6`kvCY-sOw^7BgnV#=+Glc#tTa-m zOz29gd|S?xo54fpC51Pp^8H+=-s|4ho89~7qUs*WLpV?c4XGq73xvLDmB2S{QdE2p ztNIWis1#BctN0N-;>wt^l92Q=)<Sr{LXefJMPef*6B>#?qD7G1BBp5=n!AL)dB55I z7GAe>?=W>taaU|JZNcW|hv(R~i<poHd`3Z1T{#spq^3~q0i=3OENV4`^!Jk8#*-oe z&3=|f^W~p98DeOu#4aAxjeH(OJGk@h49C^@$QDeiuZkffGJ{X`IIfS@DLHG;-=N=e z03F-Ngb^f~GY~wH{BzCv(G2wlz;Y;P`a&FDInpPR?(*p;?1;-ctM{<oHGSvD5BAuW zFV7M8r;SqdDbgh<uw228TwtwZ$RwKbR^9q%gmp~!PH|wgBpZX09br-MBW^qUOah8r zP`XJiiwpIV#YDI2ix(7M6ns9o&uN})M<tD<T5^Dna)68Js3zO|K9OZY7(b2)<>`iB zgcx}%Abn#-E1qTj(dJzct~e!?Jp3>ja#lVs{TGOzu_tMB8fQ8#%euRB_LtDAlZvtE zWdX4D+RApHm%xFFhM>>@$WsZLujT7_jLk-QV&yfHEB0Uc^+Wg&%1ur3@Hf?~52=dU zTvgw((Q$5FjnD2{U0(%N7v`D5P6)|gxnOI=#)iK%t8L_fZ1U+$uAGa_r?RbUgZ`W2 z8I*7|`;D+~(>9Ok{}XLM7UNB14!>SdAG4$@I+f10!`dQyO*e|tSA5u_{p&=ovi5W9 z9@<^QN{x(LEpmPp&3um0Vr=2<HZRlY)(1Yzz2G%?X8R@<#A<e6(cwB(Cg!PgXw~gI zU#8HdWBMZbN}$mtJhZGQjA8!YPky9vA-f`#<8mHcu*ZM@%1WKp^2cU|=-r9tJ%be) zzj^c?>A$AiZ+(kLem9xFSks8R5_+a|+ge65a^w1Heki|s>QmHbo^BU&`3>){BN?1p zWi~H0d!~w?++rx_SV%+IA6*JOFLjFgQXi-Ygu+!G_1=0FY@Wr|L%g*VXv^{T&VMOP z_kUJ_4_=5}wWwy_(x5lDT5m<zJ{7KIk9B*Btc%Md6X97BU=yh<>is=d8cAxjAv`tF zFgEa-6m9T;&OlvKgF(=`X2jIkvt0va>bS)aK=5pNRW8+-S_#;79IHs$_N=RQi(co= z<VvWoWK3E!+T|SOuxXztGi$8pi0k(RGh16o@)JyS;+r(gEaIE!rRV8u7)axVvEp%8 z+;x=~LU|dy3QRvn;e4<_t@{NsQJ(6eG#XOZMjBheFmWw&PYtH!5WdE-Qt?+5P5#|1 zJ4%G;6O9bPIb<cH)AmW-cvSyyHzRXduZBlg6E<7<=5Em^lPvD(f%&&>9YL=Q^?!p3 zeO394%8GQ<DW@xQP<tJLdCQ{)YW1@Rt@#wb-%<W=L9#2I3#q#!Ec2Z;x7nPX-l>$z zSRtD-E+faD1zxZivqgC|)W8H*Jci)m-H|)&QA9`S`lp&!$d$I+SM9YymksY;*z2pj zFf$87VHOxYT`8Zlc(2GItkHV{(s7#&W2*BrL9%WT>8JAOa-vaVnH9R%Y{=hgdsiTm zUEq~RmA&%MNr1XAm@UF=6e`4Sep})CYsA;zQ~D+Izuh>fcUZ=lkW}j`sR*h)O^$H4 zTR2qEO4W2tRg4q9v}humxzL_8q{iPtc8x)N2W<b19#yXRlBHmS<mL*~H|#v{{bu}* zMd`d@;<Lliik<!D_!n6m%i98PLOx|EemXXhnvmSDbjz`^jOxzW`3U$!?#C9S{|L$9 zN7ax>!ATlf%@S(ZROcHSt=l~ix6gVMl860y(hW#m`kQACFu1L!_2pjQ#xZ+n$f(r2 z^luEiR*@sc=Vd)FL@W8&QoG6bIQKcDxIVHFtuBSNmMcTq)6@;3AnFdJZ*xSYK;;Y% z6QG+sf_dzYdz>vP3-gN=FdSm|n*ER&_YhqNW&@})cJGe)M%{<q;J++u(mwxudO~U9 zpc}oam}_OHF4uF=hTWiiW}{!5$Dz{7m;L&g=KgtB;0>T^1+U8N6<8c-sKH^*TKbr( z1|c3co5o>e1@JlH&6uPy5NNPeS7HK~{d0~yfa7GjXt5G}>r@@(Sg(D_%(1@rX-_Jd zWnxuQty)OM<xV+h7(6MYv;8$|EifYLCzM`uyc~BPuWKEj=8Um`%syJ?^Wlk<K?i~Q zL+|L78U;%3c7M!=lo$bYRWd%G4dq5E=xFtVL`C+r**B2uKi5>!t&%DzP((GEa*`~# zByHi7J=eYG*pc*=T2|n-aW1zOxEG&2UHk>OBRrR*ptVP#TYaObcSxY6x^hY24s<Rh za+434=472bc71TRG{U5zu6NsWTZ_X*u;_O-U(+cvV2wKyF+a@Ofga8oM5nwd7XYwP zO=Rl-_jJCknYlXvBQn>a7qow@A*kW0gL-9bd)Qdxo|@+`eyepUrMmn(&#sn_ac0ka zA~V);T0^nNppsEKelvZ1xU5H$Z=0O2XmkA0T6+f19*`+?QRNmDH<U**iS59GcdzY& zCP1o+;kk#A3^hx?Mt7Ik10_D<14fEjiy)B!;aL{kEw=4-fA-TwW4Zn8GzIZi_OHx& zMhvels=9=DnxKg5`vmSRidWAY$}TC)tyIkdlAZ6K)-y>{I3~07k=$C^6;bSMSE?8H z;%REol6&x~ok{w~<Jt(L){xiMYex%Wfm7==dhs8EhO<PU*p4wq{>bugYv%A3LMbz* z(vfMVwf{FFUP-(KumzU0-F6(?@VIC9!>gumN5ez=xhDOc=e6GI`(uiKjM9|h0`M+m zG962zaD?GcRC9xtbS!P^;X2-VT|FRyA-c9d`%_7`kf!p&x(&Z3)tlXnf=s2cj3nkt zQ;QR9NEBb!zT1Dpf-*+Jo7Fm@nZTDnMJY)V^WZnuFqW)xQb&RHw8Ob1)_>5ZO0ys8 zvc6Q=V)yoR@~`_`@&#Bl`$^ea9R8#}(@X6@PU@s}Av1YYNXa7z1&XS><qMUIlkVa$ zxqCKW@qHFmMKv56WxsO#N^l(I%R_XH4p5H>G7b%|afWtqPPzi6SaStL&Z9RKET}h- zg$<D#(0Xv}d%(1~$Qfk0^t?&?T}nkGne-KjOoSZG{XLD~MwD%VWTQN9mg3h;aZ33Y zh08oA5fG(uqn+mq2|j@yWU)((=vKG6RzF5cUy&b1(xEi({4imi|K)r}cJLSr-?WU8 zm--(2z|7NfEUV6Z*5*K>bnr*=M)Nm*VR0i0tNYp}{7~l(v_1#5&b;Z{bC}np5yj*2 z;hUMF+w}u%_~0*@-rDyT6=jpv%{N|o8&)yj)YtP%*?f#LW!+E1H7Vt&TE=(>@hSA( zRd@e1d8&6W`W5u72r^nm_PPFZ>KGS|<)J_yW#;3(00v-8#PC7&=Zr-A8fm}GDP-dh z8n@U^hDJPX2H|uFX}-F@mHX=V#Bjd}Pl<6GRx<JGB=a+zjJ(1OC%bKw9rkMF(Eq#k zHzXBf_1h)UAC*%b@CVuYJJI3yBO%At<%tFtq|#T5qd)uYe&w`*IdnrliK2yiQ_af) zsOF+<Y~uCBRHzpyTjzA^P+9JM6%_LhW2$#ux1Qv&9JSj2(s^JIjup(7``|q#wb2e^ z?7mLAJy);BT*5^Tuc>8?Yfv0g>&R(>GUxPJX~?!d_}A29>S7p&5tBH4>cR1sc(w<2 zxNii?d9B7)Gx@Jvdc5UV8_W53`?G_ggoBOaUn0iNPO_IDY3wids9zr66ya*)ko^?x ziWU`6Te+s{6YlrHgaH!qBNaODPZ;At!Azmlo!?-=MvNddaia*L+sN+kO>>?od!aT! z&zBaS^KdLX!-ozRUeE4D!0@k={p`(X{ew-3kmXQ+mC^eYzzZ@%Vr(O6_tgfQSOwKd z+03CBx81%%6B+R)T)^kVIs!{bV%Z~-Ok3lDyTBofD$ehURWAs1%k^wQ794))q-&YQ zcm-toDY8&hln{9WQL(}p3pGGC)dsnR&30LX12G}9w{8q3uM?_7RucKpz)&PdI6V8j ziBinv;eV7vkAP~JV3m8#oUO0#-KL~{L})~eCnX(2&H+u2D%I{#0=&Ewta}-PbOtR= zRZScu%*$nlQt}i6S(eL_^BQml5-o3q3JaG8DJ#{Vx2fy8XkO&@xU-~<?`5YYLn16V zPAwGUcClLMM6P-=rwH7fL;6`z0j*+hGLjkuWLa_Q2n!htkJjqiWr(zCLUBD`h%d9P zg7_2R8z;>v9)gcwi1!X8$NP*Xsw4GvUwNp%dR>wFtCHDkJV`->V_IS4dh2EC$TxM; zi5xdBka=%EaepY=ruy6ap+`ewzsA#|j&pC+k2is{*`i^NKo(ntfu!MgNqsf<(xqiT zA-(!i|1DvYh+z903;cbcX#+0oLgWo4dnFfFK?B%&MxcRCJ7;)8lbkc80W9{CN<0{6 zwfF*bk|CeS@ieJm@7=pDoA*%1k+M64s`|{Ph}P3%X}*X=`&~#}A#Uqs*XlQQVtsOG zJ;Y5E;~OOtVLCbDqU-fuiDK^A&U#4{Ac;>xDM~J5G^O#}Q1h4b`{`lzH<fRCl_+jZ z-m!$D0A#Y8$B>K=&@TWNzKc!xtDw&_>BogJ7gE)EKe0Ba^P|1{`Z+!BW<J8kC10y9 zm;d@*^&jz>kPkZta^XBv<ihkN>s^7nPxugIHpx$XFB%(O-pg#nI=1(lAcQkjrcX_$ z&s?U@Lkw($RqNBLZL`zd0k|kQc(UTA=cr<@JCaqH>KgrlL_;Mq_ro5L;@*qqP=fR- zEiN?zVh<(bS|t0|1PPyc8~&Oq(oo8wNDH~&0%w?|<)4Lb>GjMgXj6cFC6XLA-uJ6( z^772E)XeHv!kN@&s+e_OPLkscA-PpxwR%!MJZN*hYQL8&3SMoTOgllw`6Zg*e@|G8 z0)u3EtKg9lS)NRrB7ghLct^@mZ^EcP@4iw|$^wz=pRmrg!dEg6L<Uzobnvp?PFq5# zrO*FfZuMTF(G13XCh^udFzy)pR$~0F^qks=aCm%OvD2JpsA-XBMv=p75Xl{<WFdqH zmWMp&?;OaQE4TiUL2%@>5oY=)AL>M2Rm-uwzbJd<4pvDho<|65dyEZ$&!~;ecZWQx zyZwo@^Vy~oZh`s3PD;H98fa3DHTS^O=SnqJjcETA*h@2mpH(OwmYF~?PDCJ|5UIfo z$e0=P+~$Q1zqu`HTy<lf4P=nP*KW^#x4{t?8DSXa0dD>?8rjBRjF`?=ogQ`RI5)lL z<|+yw;Xa(jJb;oY&0vg~LDHUJACFRNvHw!0hOh0q7Vi%yr_>AG1VVLZsFjoR%-|rD z9!BVm*jnDl!IxsO^9r$tWyljCFM`zH7h`Pr%=iMt7MRgly;$~dlKhp$M<3<CgwaR< zM2(q*WroabS6pqm%&T<T1O?*!qozKg6zHUN(P!mV+>xjpudr*9?EG<;4D4eF;W*KK zhWh*{dM+$-?j}Cj8;UPRQb!uz#67W2$4OlH_y@;k25*+Fl%BDi6!*)EzD?;M8(P+? zG-KxGv*!lcGGln~@x~Ws=aC@$B3kH+>aMeuXVl9x(y1?op(<a2)-xajp#&&`RJ{-d zXz%+epDSIlx~x3e6q=^QE^HD2vPA%|$t9AU0RQ<6GJ_K(2sw+>D7zlI)$K!dcFzoc z*F|#xwR&MZ9RfH5fDcK6&JJ3#jX>7z3^qbQU3`*?oW1Tvq5+pglaGNlNrCd=Cr$+E zzORLKcDAP4Dnxs2>&*U1upRK<yYzp!EMrb<VT>VwT5XYpetfMhbios|uq1|Y4<K_P z5UCc3ya=2j9CTY-;{H;fnGjex8GRszS#dG$F{C^H{r>9T7iP0AfS=tHA>EtV)`c?2 z$b!gTAOFCRXwC&{%rz5s1{n!~f{{RKHz%qO5Sni8lfBw(awis{glJ!kcT6603Vm1` z4|Bn~gr?+e0lhF=NcZdY>)uL(T?>c)mc((rbuC^SZ4pc~!6AAar?jvU-3y_50K(4= zsRx-!aj!qXqYpyqgn~Q8u#`+?^paQ?cfO5sjf|}2=YZZ#Npko;185><1H%CF;OAs9 z$~AA>P#=fb5kamqIMf2p8i9RG0NKOogpce_)=dl$@qYgnOt}VgGKjqvqD<S9of(_X zW$W7gi#m1-2!Xm_BRb<Yn|V;YL~@=vvt_f%Mt1y`BXSF6=4v+%vCza?^%f$ql)Yaa zH4&t0yC&yLdd(xB9AhzYLbxsU?Pxn$*CQ0*zOKTE71D~%Q{UEL+r(#EFVhlaE4Ssp z0C6>R4Mw|OTh_XU*sX}nV-$98WHr4<%0}xVY{-V4#|7#!GJB>Q?r9@=gFYZlo%v++ zf`=QY?d~Q^ePZGVw^#-?a{|QWcssz))%3<ROmGN>;fc#84#!C_z~?<o2jNYNDZd+w z@?N9N{g)&A%?n;q;#ebmA2BHVVw1Vc1C(&&0`J{>K>f_LB_C_%n!F7%t;dAS;M55i z_hW}CS5T`sn75F`K#u4t)^=7c(+~^VYug`|d69SI9$D{V!2US{?i#qykZ_(P0gac{ z+|AI=MFn`<MR?ftVq)6jZ{nz04q%!EHDfM}lS9(2dNS+4+;-oOo}nK(mo;+0&Li80 z*PoX5zkrVttdhsfM7Ill);hHcsmUM<Ycvlq+((|Kc3>22KgJM10tb5$fu5sgGtk7h zu^6LcuQSiIJlC{N5zx8H!J6CmN++NEFrR|3z5M<B(~xY&_};mEl7o4W0~Br)0dfs+ za^(sj%}R=qAOXMuP6V(%9AhK|R>#LHw5^<cSoy|#kVpE=c11DT?>o&-<*%|2jlGU) z`-0FsB4>xzdw#Kl(s_V3mfz3G<ro7r4{+S|GL}f-LO2$qp6wPNynlr0b>NH=5*K;L z12_NivfYUG*Su&`<}DgDIHc)w_ZWxUk@+~*qA<_}fdeuDK!RWg2e0=GpleT#&!07y z&~|BA@$|MHZ`T(O`Rjri0)LDam^9wOY&?I}b>Y7+eX|<@l#i2~5IAoMoVr0s3=;PZ zjMf@EV$yPw4qRAI?MIqW3T&-}HT=|f|55b%=e;l={(l$)u~`#YO!48T_ho1Wha}Zs zAoF7o$^jT@c=K#1Nv{;7&Ucs6o3>`G(+c!qbxHN?)EV-`aC&xkwHTpq)Np3EthXv5 z6wkg(!c7Ef-n^k6!a5cT>PdQjWM?R?+HN)tt)~4TE#%@Jjw3$`$AvTOmvkgl7mz+n zj_BlauRi^tXDb9Y+D&{Q6d!+=#2$_IH%Bu_#Pbq+t}mEBYqnkUAFu|BSUdauO6$4h z>i-{Vc+uAyazcecAyFn0eja~4B7y%QNiz0ZaEY?<*6w6ei&*z#@Ksw&?p^=pZ>+n$ zQWq7sLWeHOWocb^7&n9PO#s|U$ujqooq6p+Jjv{&tM3U1NCyA`8KT39WFQ<?wJlM# z5U9@#I*GrK9t)_a13Anr$us@wzMCdM6Z%;yid6S`kRigX(BR$nkUOqA+BL}w0Q7)^ z-QWNc<|HSfB%fbN+_3E|eF+p7DAbd^r|yz2{xR*f!hM+XEo<dSLqsP<)q~+aThCx) z2cSniPP?4UFMt$a2nZlxMsU4oKQqsNH}2PGe_c4PyIU{UaMXtXT`WpCv&+9Hy}I@L z0Q%mUD{3+X>6qk3z$nd-*$^-icaz)#j>j@&@?w5wiXgv0;-KWQH~HK*P0Wop?3O&g zg@2jn?sI?@R9B|YwH<)^LO>tn@k1eqoxe>u5Q-v2wTSfY=ZRR4?Ej{OBg&L;w*-xw zJx+K=({IZL9qgX)j^lZ>a_)Hk;G4)3G4HtZ(yw&r$vyXv&7MC6K9t<$?yuImYu8tF zeRY_(^FnAQ;<Qbgu4ccoq29R8xW)?4u+VH_Qj?>QN+)PsEs(*ZNyX9L25IW>^=>RD z*e~u%QxWN$-uFfQ`f>Q}*IgnZ0rG9$^Fre5b;&W2fqj2bQavnZ>CNd*t6dkMS)fc| z>->f3bE~eW#v>y6B1VlG*<Yo|Z$DSfl}q_Swe0JjSot)b_ZQqreQ*#*ch~Py?#JdZ z-F^SE+`7r}gKC;mT}y$PD5720ExB2)i{r19nr{@IUVcVBw;+$s_oA=TjuMb;w2f7Y zJvMoi(g@c7VK_l9#}yB{9l@0#EZ@VGD5LGZ>MTuSZXns+hC`X!teWLxYtzH5%#A|@ z4BcxZNErod@Etl>Za)tS^V0kd3gK6CCLbRD0A5%pDF3<O#j8*heRS5i9m$uYEmBl% z@JQT~MTRhEhF7z(jN~t{3=_JYYzeDQO}}o=cUm^Hdb(F5Qj=F{s60UZTc9LxLS8WF z?#LWhSu%;Bfsw3=Y_7}Q_)n(7uuw*Xdy2>_p{k5~xAUvAb#4orH6@c$$rR{y3YL~e z{SmIOaB^`6L_UpLe3n8DqLo{0zWD0P9$R~Jh+Y;DZ8k!ArN%u?{Uh2oKtajZP<Q+B z!6Ssq-1Nhd&IF;Tmpa}QRbGvjUpq~?=TgNV|B<@WyPm3eWIz7&@qy8|Q(hXGxAmU& zzDt9RLe(h~kL}%q+JCazZT|Utmp~G{$u|IEjg}a^;jc}J+**(Nj=k7Q^?lQDvRzAH z@$Qp+Ny2j}InI4on+DUuHW%;)-b8i#&9y{r$D!!v+=ij@{ov^PALOSa#iz$q=lm)} zDc?AzcQZ)w7BheAllr8`D|BzpD9+}EE74=a(p|&gmGpnMJ<TW;-kgtAGRm_XQp=uA zViwcBvJp>=P6;Mi;w?7gWg=%$Z)Cq%)_qMCC3Wm-$=E_}!|S|7`{gzSUjB;+&i+TY zm1;pQCAGa5GhS))@a(hPZbjM}?Pkq4Ao1by{1lH(*Q+aqgZB5Z*Uy^)A0|X=9mzgq zR{gzt{k@jbKQ}a24>tM5W=TQu=hXY>^=3VSoA&b0$l{dGQ)%A*Q&><rrBRgr@6Fm_ zb9Kp$RVX^*wdf@(aY`|iy-fMv*~X;u)%Cr|Y4IPHOHVlgWI}|$fTOrdj}g^PqrRA> z)_B;ZdHavC`@2Gq;t&20en5f07|Kh;*NPE=X;J9gkU*}LH&$TdAC}qE{2r*n6^crN zrF+nHbmW-%QSKBh;-KE*^+9bRq=UBD9XTLU!97`zg+@H$n_TF&1w!b8j;W9+#zdyp zeTj<Bo1GP3@rr^V5FFqjS>li=#xcT4iEZ28OHenI>|jF|q)=YosMSM?q3?gMP)#wu zSeH#Hjf{T$BY`4lMq}*{LXeS1KiI*PC~omfEz6vF-ohUQ<_K|p1SBRiDWE|<PBM7; zheLMc#bW3p6s1^?<vMsD0kU!xSqU5|UQrDHY}l-bn!F`02{V&Bane}O@d;4wG?94t zgC5_|#Ve>qzQDzij&!WbBRyoh^_YSbv#bYQz9kXs*)o^j{N_n|DLic^&L{O~<10uZ z%`&|RThT=2DO{loYJejm{aO{qx(UvG@^d8O?3pkva=6rSgOs%yhz(c4r88;CG_P=l zSY9zta4<xhkFg}Etkchp-tV91+K4~kA&;6-s2HJOjVtk%%Bo-ma9Y$ND^|1$UF4CX zmkhu~L#0uU@-$-}{isG3gO`yil9YF>W-MQ-)K$E6Jz}AjC}@g}k%qKi_jC-fcG}ae z0_>;9+6Yj}Q4Y(5l%(IN1~s&}nzge3^%Tg|g;aTG!eYt|9uBEs??j?apYW9)kI^Pq z1A9cN5w@^M>PXG_*pQleu^MP~EM$vO3~o5qi(X`iKS*^EzzVjrp0$W!Lrd6_kkoMO zC?-i$J2Pzh<Q=X(AxHXplEi+twto~YZViT0P=<uIB*j=!_Cynj^p&>5Nv&;@8>hSy z2$Z>fZjo^6kS6g~M>HepL^%79Hc7@;**zO^!P{5a+J&#*JugVKTV74VM7b;3lRw5W z4u9x#IO8=ha_+0&{qncJ{{63iAF>Ycse>Hkm>*K&kvMz?^EYXXA#?(@4kGet9hRAi zWvUayhwS$w57w-3!kDpegrgk)ca2AJWUF2y{$m`pJSVg2TP~bz(yPq@kUHE^kNElH z9pKxMWjrYlvEDN{3v4h97ic{r%}>Z6hLcwP1(Xt}t{&<jv5fg*n8E&|9QD|TGp4bP z$uV~@TUL&pY;2edilZLBcmyOMahY*A##j6M9&ee*z=`PDkVfiPpLUs?okqE7;0s4C zm_ZMS+^9G?VIgq7Q4dMvLm!rwOFx!#m>R3OCi`pgKV%VvI)tGPI;cfC+AI&DT9Cp! z(lZ}n{Tn1%=gcILNl6GjnWgnhtm^njBW^H<In;w4ixDzl1gXF4JUM$1DW*35agJUD zpiStA#6GZ*sXfj(F$3!VG);so8FA2~7I291KdA8rS+HXqi-E@pfg@HTThJlMwn&m0 zsKyyGd(-}`Nk^hA?p-qt&*3<RAEH4IKXk$$%vy0@B&0BK6h(zzl*c||kq&M1<IBD9 zM>uY}7v>lU+(P*WJ;qTFT)csp+Ym>a>j8&akV6~`&QYr^*yKG+WPuf7G6P925?c$D z;P&P@+M1+}XvhH?^sq)Q{P2%o52q&oAjdf50hDF~@7eya+CM6Bj&tr#8~%vJH0q&^ zZELwffi$^KB-4&}P(ugBZbv&H(hfI2p&s9mjwMm(#DVvDGDEy6puG(ep`ZBZ4W6Hj zVMs2B_@p28(1aiV>JbiW)I$!lC^p0k6P@pQ`9|=dN5z2!lXV!_%oN=RDC)rvn6!!? z`=|szv^^M)73^uwh3>~D(&O;Gp%(RUhnwEfjsQ#o4)qX+JCLJWkMN#gAqhRsYNn0= z5TX$QAaOlrL2P!Aj4(x7M?IMFiPWLoue|-$Kl*W*dW<75{pd#tmofHC2SBX+h(|As z9XVj%N-#*t4N|Fi8aup$j>*Cs)PpzdU2w#Y%sfFejKlIxhU8%c+=SARq>x1zAV<tZ zgiQv(d4$htM4=f+mYD=~g#*)B!v(>^I9Nl|g<Shx-=c}!sI0?Lkb^bQ!5rKGG*|;Z ziOTn=95&$p0x{47IKUfUK!jKYKsLnQ-%Z5p@dEv^&4g9hOQ=K5^n*G8hoEtqjY$Rr z$^#WNgF3jDRmp?QWWpQx12-HS!GYjL0NqB2An9}u6P2Mx^h*k61Rnmy{*X+YXjmbp zgwp*3B~XGjFw4{h;W1bPPPO1fEQW?Po<@+MJb+;%5W+e%f*)AJ_Ho^E<p`Ob120rU zB{;)2w95PGh1Jvp+L4{FfP<vPf;2cGH~_{1krXrh!ewYfy0lk<xX?vhP&?3r9R9;M zxYk4rMLUq28u$V|;2lO$ANY_Te)XYq^kKe97$8<e;Vq(az}p4Y!!v9H>TFnEC|x~J zLL+GZgBXGj)MehU5n#`GW3_2VPG!W&g#$gv!7+qGJ<P%9vBTCOW2e+ZH`IeH=)*pg z12`lDEYu7piUg~GLpsF5KKSB9Xj?rvgE6?+RPkUq`5``a+$P*XEW|=K1c0QK<AHEb zMLb9Vki$P%pgJ(5f>{tXdILS+fhGJyJGcWnUc?55#HO9#9xj_?G$d3O-M*EXfB;1? zA><;^!5LTsJ)D+5G+0Y$;y*B*HW*=bSOex+89Pkj!0^^TYy(d^(JWp>V}M~N_(3~t zLp^lgI;cas(8;qc1vc=*C8WbSErc-`gW7$ON|MB7phHG>gCzll7x4o-fWkgBT3<l_ z$54=@A{YZW@B=#ZLbj!(a5-d;xJ{|>k#xAj-c7<A$iqCe157NCJGg^CGy@g<gFC## zy=?>x!401AQAN<$O$1bO63^j~<8V;~H|1Q9h}BSpLomoeJIq4nNta&q6&Q-&)B(j% zSVK7YK`{8(Vq`=I27u-H0UHPcSfZG8_K^_91NgMVB4|Q5{Ms?Bf#&T9Dh7#I^#ecj z0y;dV?9l^)F2!E_LpRVvGMt0lydjkQLo!^0?1`9y_#o<aPm9&VHCzKYj6*fB!?ej> zo7g0Rm`+B#gJ15!BLqNF;**fU8#nv|9zeqLZKNeV1_(ZeK0R6jR;55nW${4&N5E+y z5fLYF2nL?Tpfza2UeW{A1;B8c#Qe~iA83N+S;rWz!7iX!ys@YI!2>kN0X>9b0A$@= zhF}+h&wr9wVA^02CK9M<8#|ywB?N$fgrPs6LoCEsWQv4#^aDL`razb%MfilIou+$w zW=mX@VfMp5T!Ph<-9H$EGqlPtzG;w*)-+<(GR6-zAi<*2Ma|@tWqd;bKtdqM!#Ko) z&FtPqk?O5}MDT@5&D3A_8CWyQ!7c=VI<RI-AY_+n-gP0QCJ;hA6l-jqjXG$9ALPR3 zRVzDeUq}4jF316iIYc;U!Xo4*KmLd;#sWHgL#sH1w$TGGYDWom<4HjO2{!ZtpZde@ zOc!`DT4};UIt-cN<b@}C5j<2vHt>U|mS#3o!p7ATuF*-F(U_L9Lz@LcAk+gn#DhqY zp`FNGJN$zVT%Bw#WzhjC((y<Sp5StJVi#JSW2`J68A(X2AYVvEJ#2$P&J01eB|NT# zhFL>)TB$m)no-PxnjTosVgwilt$C(tG>|MssLNkA0z25__KB-IsDrlBNoal<D3oTa z+#kpB={d<2)Ov)rZK^Y{%P(34I7FyPmV>tWs7KU<%v?h<&|jNC1V2dVIrKxwJ?z?m zQa!wZFM!Wtcp8?n1K!oc9@K(6h(kM^EuYyXsHUt<6e*G7rQ1>e#5ta9a>N}w0IeK= zgF0kdJsg7^q~!%oYBvI{e2Sq^*{pc-<mHZPIV_x)s)KnNB$l?|Q2bi=u|qh(M975_ z%F2nCF-rjYo!5;Nq9W+mX&Bw+B)ia3Vv2*d1sTs-4LEE<-p*~IE*?!pB!c$CJ6LD@ zeHkp!1C9`du`Z2d>}I+RLFDG01wGil$lW~r10=Y?^C>0h3aoMxU32o`;uao)#2xR7 zYqSNgH4uU<xMh}}1UvKtJXEVG8k=2V>6KNhJtnO=5-&Zh!7&Vl%!J}Ugab}h@T>)Z zHADj)L_;FI1PePv2hWL+rC%>JteY$gJ)FZbz}UKsZ$>QtOFg8ha5_;%)LuG(Lc=av zOB6+B!XCo@hZBJvr+V*zE=`-sXf`e`pqSt~u$me)gRxPrN6^~=cP{7pi5Es^<>Hwl zim-CT-MY|0Fhrsgm4nmTr5bPRuW9g4vRbyr10nlkeR?20K*JoIF!)?v=E>mgme&Po zLo}?x22a_-%|bZjV4Tn^Jv65G@)0<c!xQsE$F*%q>`BL^s5bm$nblqZpljIjUjfPl zHfVz_rd`@PhPG|P6MKWUv8cvq)$+N4@h#u#jo#u)L^sI85KzNu1+ogpP(W%f!1>!7 zXKn(f$_Ve9H4n%4gr6V00}DF_K?>`S$*W4Fj(C3ma{EPwIv{c`Y%s(za5yXiC1C6Y z$%E=z1D)Yqa{|Q$(*q@Fg4GgN01(?l#0l!`&J(8t!ltA{K#4X40B2ToN)%{4AgJGM zqI9}v5ck4{8u19W*GqUA?A1d*sPB&O!#Kpk*cGebI?X%q-9K<cj~ydT+$ZlC!o_wR zN)w{-km^LNYylrB0*f<~8c46z11Vx`0QkdoN;M%|9pJ4*_{jnNO=VExW7Ng6SZ<d4 zMFV=mgJbaS8aSO~s8@surXbw&TZ2~s_(3_~aw=-urP2dOO9Z`2TP2ij>zag)NE#}n zgXL`_AI-%%Bttn|aV{4HqCR#%WOQ&;M?ZZ3(PR7dqLC%e6q1{%!TaTegppq@khVCC zGe-ECJ4=K&^HOZX={6IcA<?XINC!d+Ydy@>RjcsOZtO}}UiUd~a8Q>u90MJg;uzjk z+@0kbY##Wyr#2+?n1OOqw^z3Q!+uh7F!{!(D8)GV?Ktp*SnU~R^3F%5139oVNu)Q% zX`B}wp+#sLJS66#GHUh0DR4k&J;1^~EUIgJSvt^yJbVLDlxb*J$Bw)~CfwysSVtN@ z!7u!S8)kMl@?(4MTXw^&Hp?+>d-Iv?NCou>M4TR-iD{0E*EnP{_*L>p^oz=|bEAgk z=w>H8{G@kTgyl8s3QHHF5`(w?Bxkw*+CQi+G-!j4aMmuY_M9B*I3Q@Na29QKgFnDR zg8E>s>Xl)RvN2#oH&B#DO!*dH7E26;7X?7ZrGrIAgmDGH!mL9tNW(Wsnhe2sS4qT9 zs{u8f?#~^GLsTO@P=PPhgEp!}&8XL5Q3O_1Uq&ptlOWcX3&^*~LpVT#9~=Xtu~xQP zg9cwTx0QrX%=qVV8*N={FywGX7-N@OsWx5uBV*~CGjdpVb;|9?)I}dOc&Cu;$z^3j zMy_4rP@bv^F+>v6euKJ1L$PF|?0q_fF4BWAWaReNMY3xyy#|0Y#KL1<P=ld)37O<J z{Ic0xyPQlXMbrWn^n*8SQ*e0yVo_9MJ=B65{Db6PRmccghGjT-sjNy%Y&SCqu`i<? zrx;)1V<Rkr7($o=U0GWa`Mwr)cx7un5JSR&^?2pDJak_<$g{rcD=2YZ_bCu^)59F( zf|Wjd0)l$#bSpi0yuIb)4a<q&)dMD+gF2Y`W_c|=^aD(kD@JHrI$T0|dr>}<3`J!_ z5ATk|YeZ-sCP-d!t<qNQaf2c#(o`Y!(kve&?14XsgPzM}k_fslP=P!|AYd#yqu(l4 zhJB;sx{}bzw~Q|45$iun#Fa%|e}>Pbb2+iHr61TmXZgecc4^071Z}~C4Ql#&!EgWw zE5!e~Lxd->S*Bd>+1cR#xq!eIzLwCO`yHc_Q*c-fJyZfZV7-EOgx7fy?5RUVkEQii zO=;ExC?u$AHht7uSm&#QBB*k!_zHFHPRC8C+Fh832Fd1rI8#=bgh>RsQNb@5dhSC< zL=?qtYV9@Bg8<VpzrnqcJRXy#im3z?o`5sTG8la($DUXxJD_ziTsQYiny`M?e#1?t zi|e!g1CnXovra8Q)GPPzA3b^j5C$+vkRG%(*3=cGM^GC*O@!E~GiXp=M~~~)jf*E| zRy}s`;B`!hu-{6TFJZ=%Ig@5hY~c2R;@6K|J$W+0X{#3t9XV{+YR;?&j$gfG=iq5W zSg&48gG>1Z=!MSzA2@?alQN`-tsc5q_4tAFdJrbrYst`3B}f%)UAuQz64bjlAwj!) z3A$?+kBYB)?cC9Q2{?e>ZT{e73c&7aRlEuP`I`w?Z{B|h{c`>cQ}k%hoG+(VU6Wq9 z0P3_owD$9B!f^CR`mCLrDqVKg<Uq5=P9a-_28kbAQxD!$%g&EOlM{_NRpj-8$)RTr zdgFh+>-DQQXBIhf#9c-U5Uif*)$dbxB#W+B0Dj-V#gvb&-@Z%Wj#{mpa+-RoA8j(L zi6FA}frXy5@`En`kjjZGnQQ9N20fSfqKCfl1Y&1H2}!gIq!UjRaYC>}R55^f;vp`R zH|QB>oe6LMbO}X}T4ZM&dfv$7A9hrt2}YDqDiR?WW7^Tl91(hQ$CspZGRh}k>d~(f zxm*b)b?V8*k8p;gY@#7gs%Mrt{vk(6)lkX^xM+rxXr+$W`A4~h+&hjQIsM4Rq|uP0 zXU%`CA?QtzIvVF6@-n(Iv-8L!ryP*F%oHZI_@M_Bbe5WFKYr4wWFG+Ev`Z~{(t#x% zwZK}Co}B!FkVKHcspm&m)ygx=4ZmUMl5{4LhaeX<O%}%;{~5>8At!6GCJ|9YXvTlU zDd#7coTPRgf9UZ=jefpi@-lkji6}{9J6pEOm8v|E%6R2<x88($R8~`h!l{RlM$Ajl zJA~l>F_cY5w}r3YMlcHJ*bzaaXHRk-UI{sM!U<GFy<q%D9cu#pr=LEH6VVzmyUDZ2 z&mtm8A$^nWNUe100c9U}u-UTO90?jno@LGnFV(sRq$eF(#<>Zhp*_Q<n|^wcW~m5Q z>j+bF>LI3=SHaOXCcnV>#~EYF(FPoKT7o%QC!75)A~b2jvqg|l`sN=se9>%Zt9RV^ zA9(6%W{7{fL3g*Lj17P)a^Q&vrHbvvG9h}QoSgC;owPbyxz#4I$ZhIjxF3x+QdAyx z$gzfwVA>J!aJy=|tr0)!Ax9mTI)X8yW9ERSJ(7`QCz?5!nJj>g;`}(|JP*J4WIxvb zQHPxYJ(36Oe@X6~M78RXrWby0DlIgGgt`X9rk=YCz<P{v<|e9>!bYg5)q;Pu1uKeW zngEohiF;Xkk)fPzNqb!q%a1-GiFddoPXw$>X1*bhAy6Y8nxRQ)+`*4^z@ZlJKn&~- zq7Hv}BNy#pPIo{fzOV7cfhkNOYB(gC0>bPz*dyIu=%S8t$RQZkXvym?)31Nk15D|2 z379Cch;rPnd4E!q9O{v%&P?QEgpdV2(&mzd{6<XSh=^hkLY!T!ApqZ)A&FoVlzMyu zE;j)Qj4~$=kSrw~sL+)>w3RR;#bZI(C`T-$Q9pC(XIpCdhcseAE^G)4FCa1hNM?@G zk7UR~9snX_W;m4&P^2Rq*x=h4OC%zAfX)(d*ux$U(+;^YN{>Zy9lGLCk8U7=8q8tk zowmhFzqvyk^soaY{2>li>TxAKLe4)B!woouVF%2R$2;D^xyV_`a`C!SymZ$hIPR!6 zd?^kn<0Fr7Y-0`7`G?$&1dohpLrf4cQ)>7Wj&Q8u7z8m_N4kl`ML<Ly>&i<#b|D8u znXV(B(MB{L!aRCZZ;R|4lk`v`sjA4qV#WcdU1X*Wehdpje3Mcd%h90BRF7$-`9~xH zIW@2tBv)ub1v|`E!A9nYZw$J`Kkl<gwhV1%^|-`7j*=NnUGzP9@<u)XAhCz<Kq3(S zC`X)HRMMr%gO~Mq#2)A&4tMM=mnmvdJH+viJv;(its@dKqva)dv<VKrP)99>5X^Qg z^qM=;+)(R^qEA+{O4ZBjI(n2ZqGHq|2$5$wZ^So)#Hk<A$c{Wl2SmHTs9*Fn)=0PI z%8@Oi5#fmJLJRwvf6M}kQmo!T)<F+%lvANoWvn)MSf+LHC;+oioX;#e*qU?%li1*g zt9&BIb$Ikd)mxu2j1d%YNY$h_K?f+%0;{-rWI+9Z$5xgiQ`Hpoq&NYEeE`Hrm<*^X z#(+vcio{&q>IksxSl}ApP>*?dqaA9PL_OS*kdnHR9bnbWAF#Fm)zHq1M`sNqH--R@ zc9_*qxST3j>oHb#%wryqzym$LAu!@n(^%)J3XJ3?qD9$Nxb*Oc$G&r%co?L>BEsxc z*E^Hfk+YuXJRLjI*_d{KEEp%2Y*Mxuj&^#p!IQyQJEdo1c?9n^xe14eJwlLjAk>HN z#1V216dc($=QzZPh982lRy)NQEJ8U)GVCK4@$F@Om~civj`CxxjK#bD;F_FWLY1bN zFCJ3K?Oo;~k013SXy`Q}Obmhz55WR0W+XFS0`m@XJb@bWpzuGaL4|d=;~m*s;esbk zjeoc!zhME4VA#P89n?dZe~yWJ{h?}EQkWi;CI_ic1H&8tjUzMOVBkMi3`5U&2QcGc zH8jB0lf(fA&yS7?m=>W4ZH!FK8!48f=Aa3ItmZ4Qu_8Tg_YyD$z#8zN=VZi-5Np&! z4!e-vRTTF-dCp-Mlj){J*kRq+zS2)^Du*95;n^`ednSu~3t9%mj=tVFlbb{pS_z2| zW1sm!(q*p9nBo)+Ez%$Al?krEK{G<v!;=ulojh*Bk6vV>lHfoV!3oKudiVkf{@8|J z))A!79ORZR=}|`(><=BN;~NWpIf1<j&4}QQ9?>*;G1=jcf7Id)&En-hlIlSQD*SR- z^939{@Q8P8LrU;^l8B8B4JpvT4F+)-YTJ8sn8U>XmCEY`xNQt&kbK72jc7yw@(9mA zVQdkUz<X`{>K$v$>2wi2-i;GQk|Aw#@BaYZzcRuRkMQXjbcn{*Nop);OPePiU$0{P zQIB5i1B+E*ObYpg5OHiY9dULwP?+MWeRQ%icIn5gpev7Y|3xo`%*NK_*BI7}r6RD% z20e0RtY#Bj&-B0pBuo;IsRZB&^;ky>O-dDa_@fz5XcIJtZ&J?mlBs1BZ)L!Ex_aR4 zH5+-y5H|geVTXoLF{(!r451&YfEje<#9nXzK7%0I!5=b>8t9=G;2;1xO@-zzDf+=3 z2;md(PH{RzER01t<cZt<Bmj;<4i>M-P>|gJtf8Ea190kLi|BzF{2&^5;wu0{hz#%d z*kUiRCII{Z+{Dc?*g+6-0V3k90&ywj_(2iChvRMpuiPb#?1LWKhaR-yoKyuI!s=7} z0V(dHAK=Wl6yYCUrR2gX0CFW897G#9t|lO9k<I}VpwHzX1_`0A9-g853hX$-h}4)% zL}0{jt`A#aj3&B;9mGK%@W2q>;Txbz?nGq4W{wKrfxdnMYjjQ=yroC<>X{N_tW1I% zsDK(4jJS}lMgD;s<}VZK!5iWs6WqY^{DBki#SUXAPmaM4paDU~tP?3Cpx)u_rtc;A z1fj^pSW3!d{2|(~$ngq_GLTFi_=daxKnLK!ZN=(}94vwm!hsxy%fVnO82rG89?uT> zCcLJ>7{s9)0w6OE!rI`mIOKyK&S4o4&NY$(<osbDw#ICZ2P{D14JAn$$U!ZjaHZ%0 zSH7VhFyS1)CqFExCb&lpt<Vc?F(HBnto|Vr;J_W|3(*3g)OJfAR51_&fz@!Sq~H;> z+#y`xfJiz<e1NVU{-F>a0TF3(NM=qA{vjOFi(LqUl}xA>)Sw=?ArTGXByVoX;;}e1 zFEGTR9uDCU-hsX-25&}<Hb847FS7FTBpB9UJH*0IG%w%&q44-=HNfN|qR4c91tnTS z6KLn=M&lXjAsR!EUkt?$E@fW-`b87wpmwy6EDr)v5Gnw&=pr%c3NZmg_(!OA=1C~x zAI_{+q)S2mfqM|?9oW$HT;eF$2NV7wrXun#Ktg{0!TIJe3;RLk_MsfG;UH}>66awZ zsGu3tVZjoDCJ{m%plK#tM0e`p4SeAOO{8zwK{Nhg2)H5Kz%PvY%NzcoFpw!HHFAP3 zu+;qKVW3GBpCE5&k{-AL3A{nLs)euiPWI}dF#16p<{^TpZXCjD9hijc&hsLVg#_iG z9HdA}@T4D>Q4@UV9|i={Mw1=@PH0SSOT>d=*x|`WLq&Q5FK^6|29L_5h{bMXdi+J( z49w@qEgC2)F)tDgm#Y&0xWe{`tS|H;(X>I6(xEGSqAoPE7hrQO@FJ4Xp%SL%(CXqK zZh{}v0Un~SF0eu#2#tT96A34!9%iH;#$hEggB#8z^{8P8+EXO!;sD8E2*{x>+Tk4< zFaSP?Oc(H~vZ@_k2r$r(8lHd~1mhig$qj0u9~Nvy*YuoHPh7}_IKWCB)ZiETOX?DE zN%4~emt!`*<9AXhGlt}#rXvOIq9UxZCwvqmTaRHd2CY6OIKn~9_<}0(1fkwxHsWnB z2IAac0*utd9i*p3+fhbyLLT^mdZxr(PRpRwVOYMye&~)}jzS$`AscvNxt{J<g|8`K zVIKs-Gp7ng=A#$?-l0~FwI<Ri<IIQT1V%QUO_%B+5FlaHj?OsruMVM3GmLTw2K6{Q zQ84PE5Dozm-$Cx6vnPm>aP~qHeZdX-Ynb#dM@X$6{s0o%6EUQ&7N~&L=E^+d&P@CU zYb=a#7RtX40jq?GxJ+^GR;DNaP21GLLRqQ6P;2oXVq_d|`r=7Msl&<~>_uXP9ZIko zqDje4M;$~I8hjE*rtx$d3(Q(aBKXGG+O07(59-KG5O!hm;=x%9sCwoo<m@OVLXTlB zl(#HM<%q$0o{G!n3?byFA86qjY)r$B)lUXQBWNKVdeCLT!fDsR;NSv6miFR=D_8vE zLGTerDv)pgz-1wEfEzLcMiz@}5yBfL<4qE;ssf=9K12WN0!1|My{-x;J7PdA*K)%M zsRBVB67j}hgd3LAFy?kI%%!R($RB?5HHNbmz)eHV#TVU+9%zX`9S52)?Fnwj>CW>$ zFC+1|BzImmQOH9cNJm4fXFv#I@xbiF3iO+3f=|jpIv^tNMx;n|r&FO}AZ)BaKV}V} zVFImpZZpCil1Q}t1SBf!7>E|MaOp<~VG-)Vvxci|iK<8zGF$s$X?M3?Py~|{$1KVQ z95RDmT>?N_g;<dHGODW{%;z71#m0`aLYm^IUNGHcBJpy9AJU>6k&yDfZyS&Ra2<E5 z-hl!C)qomMcV5jkTKo$RCIOiQ3?NBtf&9S|@StEBDjprU9)_S9PQpb*#Mp?lCFCY3 zbA%?TuH&Gpmx6>HGRz;&b1ym~U~xeWf=Pu%?;nr=H+8pO2-q$JD^s{DQ4*AN{wiqY z!9jgyz@GO^vStqWX_ZI}Pi!_gmh1640!(JX58%OJVwG>MR~s6E5>SlAuB;p6;1~wt za4a+;uqPb8k7+$kSu#T?fF>?}XGuAuM%5ue>H;Y!u2wI#CiJWx&Y?cEA>05hGnv94 zY{rw*k0!_>8QjN=M%md2LQbtpsl;J~L8BeYQwOM_UpE7pq7n{pAvZhiGWG&><-tw= zb5l)$vtMY5aVm;3YM}~(sXZ2AU;;oK0w53=F~gc;9p0fHsBS4@FNPE_Dq&G!^-CkJ zMH3GYRzZVI=HM8(nI6E1*?^E?0-z%9;w$>$-*Q14nnN*4BOz?|A@bHcz+`sn;pSLW zEIh^<3Xh1)WFa&niCpdowFum*!tip|G-n8tz@ar`VITY<f*989q=Zw-;Zw8~TyD>5 z744Lxt6I6Ga;7Q}>tP>aAw~_UE|2w%;sG2M(ixHgK-!RlX9ALhA{jp6K=g}#2P+cW z0UqGM7VH%CwnZ@hArQn4oCzrs{lOQ^?;D`WcRvm}OBi%}I5+VLw5rElCjk!su*GrZ z=ESJsgxTU>!3ArEpc<ehTHXO3r~wCL3AF;NfuIbm=wTGq0oS~vR{r4$n&EHM$v%Br zHNsdXfEYdMnvfWR7~~+8NvBAh1bG|U8lDV2e(ZS5K~Cm?7!uMuHtZY2=wqVoY=Bme z$N`dF7GwbnW5h8Uw#0cFVH1c*B8F<Hh+~h-;q91KZHnX#`N2N|+6ikBrk{{gTzMb9 zf#ZheaKz&&!h<+2r(SSc8|2}ql4gKB4tSNi9%LaI%I2x-yX8pb62{>hTq7R1Rkwyp z0o#Ebh7L}*j!y(5t*Jn@9uEpNbOF`cD50sqn`C~c*d6R<f=ZF39&8@}<RR-W)*~XZ zJgI<nrCGQFBQd^CPD$J&NR1qrj?}iqZzB7s3WFYuu7M=`Hlx{XHM}lfF7ZOlOuoTx zrnV6IgdVbE+RS9P>sn-}th3#k7&oFP_V{D=!auh~Cy8MWRC_?;Bq1{7Mz)D>P>a{r zAZaDSc__i~)WM8NqoEP{CnWi^#n>Z`;*ie5Y%+GkafLwsLA|B%STRn6hvm<0jB;LL zKYS`1y3pl}T2$l#rTGCAvLP*=x^3m?SkhK42GbS^Vo!_G5j%UGAJ7fd!Eom+65ZiS z#nZBj{EVMT(*A*i<e{^VTpl276mLzMdqlE9kxUyl>cYwn9zh-dgsDfWst^JptL9-# z_5#X&gd^*LtyMTM)YQZUjCbLKzg|v6D#TKC1<2f3dh1+6!CYjlK@%1M#XR#mNDEP< zhsY&!dZICQ5F%;m@JiUcC+UHnCc;lLA{-iF5i(-6(TX6HBY~Or_B2I4t`J2}s^r8S zJ-<aWaKb@4>R4}rW`4?(|H_&k4>YF%6DnQ1Kpj9fiXWV+wp9bYYz7Uxvg1Mb4Y1Fw z--Oia{5$dMtbIfgv5#?_j$OTKu81<#2KYmPu9tM6Ie#456C=~c!EjwCS~yJ<hxx}5 zVu9G<s^lvtxeLnbh8`@eJpqxA{$YW_C1DZ6TW%e+qiXa2CIV}qA=;Q@Nc<_JJ%%2l z&7Cw9*GEGZ{9xJ=ow;Bn;r`(w*ny%$)~@<uLdUVrp);VT!>3_4efh}R^6h4&9M9Aj zq3a$dzO-{JejQLW4EJg#I#JP{tI>S5X>w*7l7S7)aGE4%s{Z`Bl*{GwaUJ@lG7EYj zRAbNDXt?;C%mUIMA_5OGf$c}+SS+s|kiZv|HYU2$AHLHc+M)S}A4S|*uekx5%024d zfg7HHAEFMdUtAu1Az?|)TTYz;8Jis+Peh<e8v$a-ws!6Q{R<GlAiIU^;K5^8?@g_G z?iM06XmA`oB);ga`v`I!!jU9PnmmcJB)xj->g}5Uvt)^;dIrmtLrIU`KXumRJS%4~ zB*~Bq4{D3%=NLJ5Ia7|zY0z3dIkRZm3@H?(Jb4D|5%Uv`-M_8u0$2;T=GZ}#A-9H` zx=UxyoMNNN*=8+aQ<VRX1*jL!Dcg?-$q7Czc&lQ0*y`=8l#U-ZaP;I6797%_zsc!h z?W+e4++vek!D*|9=^8j}*br{T3LEQIgp>KDtMnP0LD%vQZ#|vtT0MR?XCo%LwI97} z*T#J_emuH#%<CN1qc%jHICqQbmJL9T9;844#w`{a;N3fJ_0-h**A6;j*ksuitObYN zH}$-?I{fxeAcnjnP5?}Kv`%jZi4##K@~D&l(^eVPGhRL6RVL3u>apX`5Y)WmPCdN^ z@DW1|!9z|xIFPd;JH}-sULY3cgx++BnP{Rx;XspAPJ}d4PdW0D1Qkzm1mKTYG>Swb zlOIXAjy3eGvCBUP4mnah@f7vXS#kv9&p!^mmY`)?$pclFQ&lxqhU{3=Q#4GD^wE-T z)uV|Y^q4nSU2?!_&|bWa#7;DX;Ns6ZZDNT~Td&y&=}7<7gAOe9bYo_XC^?FaHtX~v zO=#d8X4*f_7}E`FjmF06Ws+`F4=m`gq|kTNt#cZ4{t#D=t<n(&4nLPf)@Y>0{#qS8 z^fWU>0PehFk)&&_Q%^HU^fOLBa}vt`j(XRrK}|met%Ynz2DKy3KTrJf4}T^7M<E{n zq{|L$3voA|l_fIN4LxsU^3PHyi6b5!^?c(HNeg`h&p7qq@&-lFGDK25_4x9{Ki$A~ z>~UPOqmDLm5W|u>@~i<(UjGRCluqh|Gcry8Xi8LBYAyn#I$9ov5mUMNVNE{)kcl2_ zQNg87z3YJd4<(BPc2dpo;OPfT2toDc8i1}$4{5!r^N%cqY?Cz0gMn07$BA);Q9t!C zSI;=H-MWruoz?@YsDqYNT4R-<Bbjb9x5_GS6T%HoeZI-Fnr*|brkRbS1t4r>tEr9o zVd=s#$wAN#jiyc*t%Za?0bpqVCPEs%^ROD~crz}ebZ_MjgKGTJPm3faERRI;xFe*| z|M+tq4)lDZ*}3gpOhrB7#5W>u=^7G<Kiv2O&t*@_gKj;0JObjxTADaDHC1@i<icoY zUQ)Da9`mO*{k*)0CfbzUwMz83c+4E$XcH&|4FxN7p~o!bP>*fMC4WQ`U7(aj2~Aid zX+bFytDs_*e|+g3<Z1~eC=mes4e%odnOY+Vu@1R~t|hbZ16~4{5(s^Q5aF1g*;>Xn zu!(6L>^n()48o6C?Smdd%GCNcb*53tBO9RT$7B$)vy+4-9hc|_KSHw*qLqYj66(r6 zV6mtA$ZmVJ5mu_O5jjZz8K*bKz{WR51-c%}(Hr%E11`wH!?Mi9f&Zx8Kin`8f*9vA z@L=69G6uUWMlU*KvI&9yfdpopXd!#C4mXBipLY-qBpR}w8k%7y<y~h81cIKz*g>#b zyn!C%a0m$pw-t2J;}CnGhd3s-n0tAH9&X5lKLnY&_Tfl&i$jQJTJj@#SYsj92!<SX z0wD~Uq$PQ($1=&a#WOWU9Y_fV2e~GnE@FfyTJw}x+Qdb!n57<s&;&iyVUrNn!)X(Y z<{+^Wm|4uB9{uRz>HGjB9v()9gb<9D6a$gC$)jO%JPDUX)Qf%iqZ|j#6p2#esL;?O z9kdvSHsCn9oM>kMim0f^I<8{Dl&*?!455^z`gOYe?FBY=(~U8l@r}vQ!ym--;fPrC zk7-n*9v_W|KW^C2<7jUk?RbZ^=BK-uj;<Ya?B%@Lv8uh)P9An-$FmI5QzR~?Vf2^; z9GoY<c=#tt>=*(!+`%0qZm)LUdqh8;XOOLauO7f86GCc74-YLgab{W!LAdb*YV<L# zdszs&{;}8RP0lzt@>Mapl{_`2g)2F62R-KC%@G+VLK&)uKL6pVMJ>`%+w2L+0w_C- z)B}FifJX&4$<luu(3<CDO8x4|vXD6BALD>oFe*|Oc4&hhKiWw=4&yVk7-)cv`bRnH z0TFdP1H175_)Ajv7MglYBNhSZhG<gfDkO%aIO%{zIxZK-lYFBd=ST)W*>PS+Ewxnv z&{Amn;Tg$*Lo80&o@r1c9M)_vQlYU8d4p7|uzojcOUoq2<iU*=<&q(fjjSn4(!C)x zgF|eM)b{){wP%zLuWee0ma0`c^_=HSbS=aoP&qDHQo$F_Ye#WJ`@4d;H7GN7tUE6G zj{Uf!R;u%Ah^RpYa!A%pm2I-x45As3h2v)vY)Co4mM3^X4LO4~*=|*aCD=fvA6p(9 z{=x}l2%S(J+c1chiWVEXn05|bQb=Fc;16qnb+sVLa>(d#jG!qk9L#ORI@Ey}HGPSJ z1B8nIMsl%)IppFwDVp#_{=phb4YeBB@N0C|TMmB6BN^w22R4%Cly3ZE8Rxh!I0!ew z*w_t#m8dmqj9TC_fukOs`OF*B8>w#i0~Y&G)NVWtDTcuVK!JcnhLA0-0K^B%0=2AT z>G%X+V2`lJ+8#r3p$2w%1G!D6>-XsKEcFpZ+wD+?I&=V^c}xgn^|&5S7r7M>LG}@R zMQ)wC#=Ul6#~<Wy$GD>9*n&VA90XBclNA}QV-5NrZku5^?A;WXtYJ@(CbN#@(N4hJ zd0Q*R%6Fh4hiJ_2Fga<-3I7oeMRANyA^}Or&s>xM90Smaqww~${H6FD1Xqm?AyP^I z(j}N3V`*nQscB;lKSIO}n@RnMs**8{)sz~&EU)@jY!XCPujAD&QVef2103P-N@-eY zQm%JC8Sxrp8`{7|!eTlY#n59Pv?xb6hPGfvB9t9GWcI(^Bw=XVeI)D&x9NJb#t~UW z;-nmjnbOn_e>6i4+z``4EDNcH3^xGa8VA8b7t37+q7d+jYgX0@HaOH`Pnt<lwSPz8 zm|n(P=>7-n?x`hm$O8|MINskguO4ocgZcF6M*#Pw$VkCCVg2aI*5V<$Zo0$zdr6Zu zPIe5gpj5r<Fn>M#Fq5`psf*!2|KL)JZK3SXw0<B*UJ|knL+1`T_Z>r0ChXAv4<eH? z1jY{KunlVv7RM2Fa&Qde;423w5^q5j2@wEtkTUf!VOvpC^>7E4gALdgY`oE6cykV* zmT{gZ4>sX8y)Y}}pkE?EXf1~xwUG{rU>a!jZ&mjZDN<jW;V8(`WRP|afAI|l@@$f) zRO=9Z?Xi2~vNxnb4LSgVr=u9JR1lEx2LHefe`jJ?5q<vv2bo|W7-t{tunutG3*loc z_JT?U^AE`553s@!T@zuN*DXsn32)#JQ?@UfaXoJU3H2}!!6zRJK`_kcTx#VeCgL^6 z;t&wgLgi3&WYG`t@LM1!Q=(%H<uGYivPe3JPxR0Ti$D)h17`}s6Ttxg7L<e_`KL|$ z!xMgx3)p2K{1*;6S9V#oKi&5;C8HzOpf#{|9B45#Ja;uNQw~2PKQGe>X2A~6@Lgmw zZ2J%k>Cg{Kbc*u<5;7P7`v403G-$?AQ~a<Gmmqfipe_8xbA=NC|HTiUaWI*Oig5Q2 zvQm9>5_vE<R+JI|{m>2Pv=#v=c_2~`zn}(JHE1TWI_$9riRccOktR!)2@!)Z-4$Op z5)%CJ5AFdUTQNSF#4P=gVVWdYXQCd|a4qz}khqW^U)3fnhY;%V4-UCl(ee?;6cJTO zW~cNH%Yp>hr5W{MB3MF+DKUQ!@(+Zt2!KH%_0dd%5EgCsj7KB?2UT(+C}?->*C&4l z4=Qs*3;}72Kne9`inbUMbkTjfXeB!#4*&%imvK)A$4oyn4q&qo<xmYVmoyT#T$(@# z#C1<}!A*WZ4B-$J##Ij3C`a{B4|`#K*I*8&ky$n}Iyu1_R74I}G;I3QI8+o4lc6Mh z#22H(ng`*T@qn4&@DA6tg(uM!@}L|vXf+(DHkOeNy^swcC?Zg3BOtO4==M5TB^V1* z50DrhrXwxsQVS2s4SPYE8aF)F69Cm#9wyNa?yzu8xMT^j7Oe?bxAPD4Fb@GhOFiZk z{;(eE;tPF*5#*^E_3#Ws;GTl<4l0QQ7P2x=IAQbve&aCz2gguEqw^-wum<vzP+Qq0 zJ#h>=L74&yb+QG5xQG<HSQgir644+CiKZxj;h`yk5k+DRy6A++1SC1fbtO@uJn=K@ zU>L^;fnf7=0R$m=QVxPvo?J62LuX9}flOM*44#%8^iW^$urX(XEGx$upkRV<b~iVb zQ`i8HGv=190(bNf9Q;HMHz63T(GTcQ37Y{9@Bp31G8@_u50|hH0+o2g=@hgRAAr<` zV^k&@VF))y4)H)(+hZOQ!AgLtHbRkb3%8Oc;#t0+2J0bXUFdRNMKFQr59$eJ8WLCf z=qyK850>{~C^kwGGdaAWdgJg9cpwXmcX~q!gO&CFf+%5<Tk<Bz*kxPc9a55VCL?&m z7&e43jZ4CQX9pA^^Fi-qUFA@IL<AHrAqTB^e_*L*I$;*NSfk_+m5qRN(%OFHd6mm# zApPJEl+Xy#U~gB*a}MD))#RhAViVzkGuwI)&WfK6H96v{o8K^}r&cCg!5Z{n492h; zAhj5baT<Ta4rCgSrpA7bGExD64!yunp;4;Bw|2T=rvC6zsi}R@Gi=jf3{5zBbc#_- z5@OUK4@n7dD_cmH<dbFMEGaSs)c{w|SZ-(1RLs(EEn<ju1Tdl6k^#pZ)bIrA;4qLN zFX>_>@&{ya1t4nR3*v&S2ogCC*$>Zxt|S5fScMP>{cwB-f^C$ABUuYNN=c1`@PA{X z7?38Ft(XvsWF_>_34Ra`eJQNjbYch<05?H_-SuP7xD|#0e-OqsVA*nMLJu$pTm}jz zgA-gn*Cg8j4|7lzNyBC;st!z2v3f~0^l(iVDixH=akIfqcOjWQL=^uJM5wS08Wl{^ zp*}Sg00C<n12#Ck(JB8B3)29CV^=dxd2z5h8;pYuRCJ$3L|si1YM`(WS0p$JnN1@B z4&%^{ra_)08y)fS1S5tdtCDMFVThRIE41Sdrz2v{qDY2Yva8})?|>aF0asXNJ!tr| zrbZY_b1(532#+8SK`9UKkZXH`RnvL@hw9;l3}Q!k#8#|wFH43Wztj%d=Zth?c3c4= ze$WZXWfSVdLVDtuOIs97(FtyLATL;1_7VVradW(?KDi1%6T~$n606)IZ_ZW@FlVkj z0YBMdil<b=DMGn!l8d?Egqvh#k`e$f(GB$nI(%qd&J;qRgMj0@2!7#dWkC$R@Lt1a zp_~b7*uW2F3L2wn619OF{7{cHL7rV~o2|(;Q`8H@03Nkj5`(t9*&twaY%HD$#<#H# ztHH+Dd!Zq+kp&FEh!K55Fcxb%5+O2rZ&kkRGdi`y4)4}fb^I^d_M+GOqXhD)wg3ok zpbnRe80|n0j!F(IS)WwJdbl9}CX9>{>Y;2p0Lg27#cv`AyP#-kGENL?4e!8maVraS zi=&ig63;d|l!<_L0Vh|pg%!$Xov;Y^1EiZ=#|OchiTfw^W(|s~N5-6OlLDYr0ie0q z3CLQaCK@twzziOFq5eP&bI@hi*)6gd4B2R~|BwvMP`m1T80$40^)M{q07oW~BIt0A z{1B~kQ?m5IIP>KUu|QPkH5dzV(7nJ=Nu_G8D##U$N&$eh>QKvw;c)+8V^<X|e#EtR zwPe-|k`*RPcwh;&C!nr_zNmL}ZRc?E;0sA$2>p;as7Gdw^$*ht4=cGnR5g;g&@G3I z5)Ishy7x;<Beq;pE72nVVK3sW204k_V-Q0Z7|+%eh2nus{LguYi`wu(Uk1VlVkHvV zWp^8F<{~EBaG>O%!`rMg;M{V7t3g%aCP+aHt@@F+X(Z6#&M^ftDVhr({Ap6MffE*L z#;^(M@J7%pgmps?w2%&$9gctTMSCI^xYp3J!8pSv4asmuX*3wba}K@W4~G|wYEuua z#@Zbn%kPjPP}@iT+{o!-33zZ<SY;~_9NdG*ZkThx{$R;1ogM*jNb?fOQFBVX+(+>t z)WSp%^l&@r0n9M%4~}YY?s6E0v60q;J$UIR&$g7Gof0(i54*4i0q_k!_7PfQCE*Z3 z9~Vtg#Gv62JnBpTI5YE$6nNDxqPp)l6GL;m;z-xp;1A73Kbk-`F>G{YLQRB#N0^8} z%aq;6Y$VL!m`##p-N(*A@uLW#33KpWo(T@c_KjSOoui{1%vO&#lpqm{Ey*l1yy+Bf zj1f}=4sf~}H*}jEM1%g&gzg<FHGvS9z)#c?$Q|7drKba<d=bY%$y_^#%9)c9Y-6Z2 z-I!CM@If%MS9`|9LCg{W&%+l_O%L!u5JID-T5dZ`{SIM*5z8~3)<fPW;h_bxkrtw+ zQ*JCC>M+f9T_ifMGyx%VyUTsT4)C)LOq|ZEiOr)^kO5$rUzQ*?gQ`Ch7UFE^7m5%S zDi07oxbUR^i`SH+*sRP+{H%^y56(2CE?vjmgfhHHnNZ=2+Q1ba3L&%51m9ItJs1F6 zOrXBaemN0D^<|K^ttE#iEA?PH3(f4T;;+FH0L;r8X>=J`R34lC8T9~cg<XcAZ7Kc4 z<hWfC<d9fn9v%PSsNw=W<a<f{U>F9Xl^v5NGKOT|nO6z1zaSF5-b=P9R<YhmM@WD> z&th2bz;7!lJI3)y+e>1vG&+j2$6H6aVM?r8f;DoBw)hh{x_%a=-Xs^K6K|pki_jAP zfERz!LUBH5JD1sXL8JT!4&6`=f-nof#n&q@mK+{8OtA~k<fBj5KH;DVlu$zl;t(v< z;T#+PLID_pxT&P}#qP{b9mydNMJTePwI}^JD}^OjBU{?&;Wn>5971x;{}3AMz>Vop z4iqg%p%DQ4>_*@aMYvrO48pax6u}?PE$M-+9x~mu^A6pR9TdYpApw4uqR3dQZM(EC z^`N#kLRx?CQ}<%ZkFW;?=VI}YB8PAY0V5BRD65L$N876oM#v-^?<SFwCgG5xjXS(c z!c6Z#fsUCI<HLV9G1{}8YcpmLb=C+=Kn&49JiFirVDV@s;`I)_6AY>i;b805aBvNq zAkNB4VzK=&w7v$x40_!ZcZhN`0gTTGGT?9|N!4KV&<nmM`-fU4{d5k?KvY5l5CH`L z29PJOTfJWB=&fVNZr#Im10_zR2+`uYg4n?A>&34hIB*gl`tyek+dpTR`e_SE(dEmR z4+ChchshZ|fihw4<k{1uJ8}OC1^OqhUBjLY-MJ%2PY1Vl1OqgD=T6-aaslGS^VxOa zNPqvh4XNkuUBPzZ=&8X~_MKO_F2T~HM%L)Re@nU5d*aLAQFck$xoh_?lbfRN8a~9^ zuwdMY^ysluXDyc>a_Sm7gc#soLu>Tb91AO1vbuVN8jTCL?w`(`7dx*D7Y_6+KXT^m zZlui`JG}oO=Y%MkoxEdmw6&Whr=B{=u`m7`XU$J8>i+!9Vpp!GPQ3Mq&C%BXPn|?- z<wkps9zZhQaKVQAtOt%CLUi>#&!-q1Z@+XvNr#|%B&vs;dZdYkpLpo;4=>0bd=MOM z=z%4h`syiAApgL@rXORRk%y)B_=}95kj4pcKyd02&O{g|Dr^r({&EMxp8g@}n|k1= zrJi@fE2|z~)c8jp_hRf%M}H6u1d@7!`lp?CxKV=|cHVhQNw40a=a(m<EbJdG_v&j( zxcu=F7bCqH6GtxJW5=3c<e*2h_k!~bK6<vJOd`|>A*7ygkkl|o;Uo<1G@QaAWQlqv z1J1wUApFO;$`%Pgo$bm&lBYy3oeDZXI?-mEdgPd8suE#}?w@k%v__r(^St}VnpAfY zs8y{#<#HmB>d6L_nXn;=OR!7|;F4_mF{z-8u&D=~O6Xzfp@LxZO15ONd8Zd?P;5z{ zf=DunpG&q$2P9vA4FH<}(n;r%Zr~-iU3cMn$Dgs_AqQK0VJb+RdNO%~Uo9IV7!OGP z`34?%@(lnia{e(Skb1WHtet|5<VH)0d#Z;THMm&{uY?0oqnUo%d5ouWgZ#xvDmSw^ zFc>in=ek+hAqn8c)<JESId0WVAk-QmL^#)8mX6zX+S`hpa4IaP9OI6Y2Vl4?!ql2Y zD3NE4S?Y<1pn!?n)w7DPtF4|nf_V$#p4y{lyl}|Dc`A4=`|VQyoW43c<N$(AhZb@) zipL*q=PS1)Y}Tn{AAS@k3G#lZEeV{5wz8;eZVM`h$82D!heUs}U56x)=H-VUkVtYG zM%J<6CxB$8K~bXF3Fm!ljO6jM86+mtsdvEv4$5G9zR_~ve*!V&z<475)gqF}@kjaq z#F2*`j%zW}`F9!*87yw(c>_v!sB)*CN#Ib&sD^kQC~K0q`KPaVT>gGiycA?B^U;|c zf}stD$nI0nk_U7&;fH!yBY^TKlxmnZIG)VrA}_;>WNPCb$*4|k+bYgvDnkiP`QaGy z;7SHdxG}$pXAa?@)prJWt8m0EELZzXJw8E*O+kkqFSDQjyTI`cdTinv>VVhckhMC@ zQENotC`dm(a+2JY!$Wwn2=Z(w8<5arSSta?;$Bt|e#qk*$vB-<(Dp>U&_p8aN}KQQ zrM!PIECAmq2vP*LKzRfO5_mw^Sppe7L%ib~>cHR=6GkL8)B_%P;TZEiW=K0qL`&bu zBm3M}4>lDAFoN0SKh*Fe|KX@HdmGNz1QCqi_>6JE3);|%7E8QXBN}pu2CWR8cRbX8 z9LLYyxjV-V`|Pt<gp|GaNM~eMXJkbo^GXiKS#kE}tejPdl2T`n(1~PKRzfO7Y5cmM z|G$5HAK%C0`~7_1<N17bZyM9w25<JwIA*H5QsV2(S?{D;_-&{TY7@>o^yCkm`?^WS zo}(!~;h8$Mw}FkCt>q@on;R^1Yo0!_^)BK^l22x@UQ-sb@7&3ooe6gpE~^R`5h1&K zOtx0@D6?}-AS*$moGP{7>z7?VL-n{Eu;0VBRcGAI^@dq;KU@u$$dtF16^S}k1vsT( z2DIz%aLU#=t`SSvo;bn)^%M2XM84CwuH5DXL}xOxSmn9(-c!;H4?5$j>%?@@W9*on zNutkTd1KcPu?EKX^j2vjpaE5+uP9p#>Q|{Sl@rOtJuKS6VA+z~%JsfjSY5h(FG->} z!>)5ZKzaF%dbSbt+Od!BB2C=$`cd|m%=L0a+OXiG>Vm=`b;%V=i_<`y*c7W%C0f;L zQ(+ZVsM#L+x@S<o{OHx7F(in!b>!@Qd$Gvko7gy0euL-j4H2bVt{<P6YG3B@VBY<@ zEh6_Hr_OlKq<rH?wimP!XFGF*2+vS7D$vq>%ZN4TZ_+)#nqf^ql1H==M;Zm2{*x44 zYi#I!r}oh5=6`)B*2&zA`_n<0w5BvI*F(*$Upy}70}!ATX-)6?H}*c^a~bNUn)b=l zy5fmv3AV3W>}y9fw~S!tDJIAXn1!y?(>xFHKt3i~Lg#l_=GksZVeF*RVw({vf><Nk zRx7b5V<S9WkR<kxIHbR2kIV}4HT$RQ6L;D(2LVKRJG~o`-s(ez$D}8~B!<;oeS6=` zah^ooq-NbR;)uOnE1cs^HIJ;x|9RF2=5bIPe^tseh;mlc#%shCc1Gq;50hPK&6SLt zH_AHMcs*^hXY;4?kt3gbjELWAis2}WYX4s!*en%lwZpHO-bu~{Cz*Jh%uwEzx4sOk zRtwpgPBlNiMmIlu-Uw?h@Yi_2=ug+MU`xBhnG7)fHP4<9d&~ACzB<uejD>ESPCHj6 zq^*>Z;<CE0w~Yh4WCRS}|L8Oy5|iHdA}i;~Rv7YJ$Gq9sg9{p`@~fiGM%+~_#AQlJ z3EbTU@vJd^Xth@(Vh6nij~JHMP1NqXKKooQos#C6BUImMEF*V=o@}5Tr*;KrWc!@m z&V45=)z~sxlt~{F+A@;9<2Wc1xextCl*l%F2@-|hwb6NIk9tJ$5oZ489j(Tbij=bN z36IFjkaM>sB1!9Ni?sQB<3?=O`3(-I35-hPi#M+uSek?y&rat(g2mWkW;km`lsERW zjn99au~D4Ou)f{(C*qN)^}R<f7|krgtY+lTAh|~$Sj%7SLxTjWtxo$IWfRIULW%^a zc}U#p=#q#0e~2y%(!UK1=4#Q|#UGqD*O7$TMEJWi?0w6)jD0)CrHSNigOly-=ok~F z?0FMxZEo24xsM{tdr;j%<1AUzqU%4C)E706Q8Ah8VqL_6D}VXzAA%x80<H`wM=AB6 zc-n*~C<85f4((=WkFJ4|vmQ3K_=NjDidAXm+%Q#>7|?xLR#m2*-i|5iT8s?tF5cqW zo$?2XJhNidc`}*8989GCC%D-rNB?b)3O)masOc7C<fODz1Gkb1$0>XsEj%8oka7{= zGF!s}g%Tis#|K*vgDV);&nP}6)8GVrp4^!H-LNFvEpknI*Qz1BiwHKvL&MO}_%^UE zx}Gh9U$ZUw4u%}PQf$PPF?Xx8sJl0Z1`(!0!$P4f{q$9=0e3peAT{OUYra45>|XcA z^VQ_7CCIKv+s>^Qm~B;ty$JFl#2QUP+%(|pJYCzN9p46dyG4%23ATKOs{So#rJ@Oz z^cmGcw_MEF9+@x?b>DgsiKhXm$#FE)8y0;A(@QaB2kP!x1j#4=u}qD2Z8XSGODoZz zElbr;Y$SB+?rG^U8q)#zJj14E4kWJH(Z2iC^pp7U|EeM3F=AVA;-{Prt}_i{`DCoG zUOd*g2#<XhsvboI{oFelva-pUp5<{@E$lFcB%!VqC-HJ2JvfBwN?KGn%ot;Wv0GSv z0j&xJLkKAAd!9*)BKZr2eCJr{7Kj{9VP#ck<4WR`17o%fp)*=Asb6Gfvnkk%>Yr(v zif#4PB<E`K{aJzj77};+D@o^u&B&L(c-d-yTkKwVaXprfzMbJGR{{ut<{m>e_gD!q zt1If93hV%=N9Ub@D)D*t2izlR%srz-0jbDtDTDsjl+h}?T%!Pjm3?rLMJ-1NgJc$f zZQW^C{HtidAYJ;-@fikjk`iBoSyXT|u51h6$KMUd_xP*dJ$bY~#h?Imsuqjt=|R2E zUPcQCP|6m0Y+shOX_T|0Byoq;D?n6<(8`-8k_=Z0CBY!SU&Ikv30q_gHy@7v6woHY zW@;_uAT$go28Uw$<lF7oIj$H2<Izwu)uw0#5~V2}8$gc4=E}kVcR3A;a$%{B#TvBa z8XCDQzs~2T>a66Gya=dhZ0@NgxKCZ``In-v28wS`M}BQl$F|4;)T96k)i&b{{-G9I z)A*;DmP@Wlkf+#Lrh1#3&B%jgTHwnr7Sr4-3jG&WRbqBYpNhHvF7k95o#&2)p;n<z zE99?xJVs|^zI^Wr|4WW;CR-bl$M?~}M6$061a3tmWwI}*@Gn&x__MIx7$Dv3rU9^Q z|4CIB?NbO?zSWJ#cDG=C{YgAL68~I#|J!G86`IWYV{G&+kASZ79S7^W%BKeQ;|_Th zrpq>JxKhxtEmGQM5cvipf%PP&CM~05jjH7a`Ve{n;y49D+|?>(wfY5Z_Mp>UU;8>< zSfF$r<|9eZV28VD<xi2-_T;KsQsooNGyyYMHSL>|npP6uvzW*6t_;OR2_HJCBtSLo z2`;ypoX><2ud7TCFY``B6rng_xy_6L?zVWtf-`KQ+zaet0-0}5<;EZL%Ss7vEKh3y zvJB~%>zZes*B*P{=2TeC5#NHyx6a<GmWp0UnODpxUqh9R<!!*oC)6o1mZPN>dLB!X zLIBX$DjU&b5BJB<vc7yMn59|&>YqZv`F$l&m!zFpO_-1BbKT)%Q=CuVW7Y^pJd6_+ zsCu5&M2-t~XP#`0p_GKuZn~;!JG5L#P!BQGo4S^oZV$Sm`G!!?wdvj@i_V~GN?QRZ z$0$%yGx;ms4;N;}F8qQh{2KEd>h2y@AnTCyaQ$A%9A&Gt(3m!JwBVG9XbCJku!5Js z#Fd_;QGdyQiXWfbU7Gtfs%6}*<Nk}hrHFEvk+Z8$OKBnB=@ul9&V-*5{!`4aRQfh{ z8xo(JrrXI#ka&EPMhim2aM+$7<C@9F(5E~jedtv8(4_CKZf*7Oc~5%Uf1KvO-7yRF zcq;G;mb~F^EIg@X!A@MRBj*XhrKL{4fZvZNcK@>Hn8Ghiu5iDhX4-E!WDy3MZ|Yyn zAzyCRqw<b?2Ycl2r<_eqIloQb8h90voRMf;6vBY<k6EStf}*y`5@n3JC*VlDYTZkI z>l|{lBh+u2Vx&o?3ru4cC;$~DrL~LER_bFQO>QHB`FvN$*XJvhR23HNQ<z$$XqEKf zxK`{TBz`{0g3{NT-_+I(_xA1C3U)SjC4CCjGIg^F2z}nf0bo^p7p$bQd<3_VCx^IR z^61oFgqh`~y7*8v7zY(YYh+$F=v{n^O^gUC?dhbW?Mh=y91e1Gi*>WNBCPu2(^>qt zJ!FNtv|zo*%X+SY!DRVZXtJLE&Rx#@V2}Wf^@F14UF||bH)g1wTrD?AE52Ce`hfJ# zb-co?JTRNuh|roJwo7`YFR^&RRh3W-IuBTh<H1)%I94TV{oSbtz%Cfudpy;JnHH>6 ztuF0eoB0zky8P$GHI<YTxoz$3ng7760QYuF)f34NjSy3klFX^d?0@SD<F`F;-_I!@ z76TPYRaUTaA+r;$Ebo1m_LRA|xVhM?u)@y@H)|ti*}?#Kipi1GoZ*YFoi4ga)Ih<i z#gX$Vt=1z&`;vASpF7`teyT77_)#SUOS0R8dJM|EzI#ax;(_|Qz;}x5?DOvI<s<+M zsyo@r`zw{_k>oSY)RfMer9jIGLP6cbC-r5N8^ogDa*vnS3a-&f2zh*p&YRJsq~92= z-)HfwdnsLX)+(!R!X89GS+(+#7AWEJ9UJp(m{!m+i<zKLRhy8<xl9cjw5Z+RB|)aF z3_~D7E(5a)eFD;O_2YX<CRr%0(Xz77pZuqkibb_w0h+%sV@~-=@>sJ8Ko--L&X{Hh z)|fq74!uYA)oi`9w_dAXq4f`+PU6G+Oo!1;v}NA&$5tR@_;E)SDf4hqHe>D2OQ&M1 zZ0D1N(md=1Uq9>4sXL|W%W?lxP>PNaFa}+dZd#)5-Z}TMa=~is)jY?T95m#;hQl^# zZe>e{(D;g>WnegmM}wbeH&kbB``=#};o?F3a)6fxcN<#nP{~)1-_oR?ilmfWU@PSd zw526akR4{fH$Jyz$4=dQ9?5}AaD^mmrZq*C8*-;&g`p`JzwY_;@P!odJs*0nCX;PQ z@(I8H$<Bcddn`544@d6!$FX+rvQ=4bEEW2LH}5p_5cRv~2|+V8L8YOl*ZO;)qi+qB z;Q9_g%L~^;jo-gv=h5}@I{4YKL-;ZOAn66DRcHFny@jvoBY_nrrgy#C`3UbqZVk;X zcci8S$VK4je~zm@$@p2UXY7Pa{u}*D2!JSrs>tuL-i`8n{Ka&$lB*~Itg*!@Cl2LX z3+Y@bCOIzP_-?EiBCK%*J<nAWQXvMEGTc8Az2t(BmHMbqYr#d0KX(r9Q`z1aB2;AZ zfv4T1+;SvUXKu5w-wK`>X(2}tS?`RVvWjX{v32CV)MYr-5EF<yog^XJmym6x59NoY za%RY`K;Apn)$h&EIPagW>Kx7U5L@W_naQrgoDth`h8nCp2(!sHmnBQXAg%BQZB^O9 z!mg2k7tmS~feLa}ll_z&u68F?$>s#&OwpQ`Y%RW;*2kDgV<oH$kDmIXmJg-i$-b22 z@QD=G_HxBn6SRMBv!Ab)+e3XQxDW;;cgt1%3VAuH%5VkxP%hH#`woE!HbGY<zV~yC zE^2X0uL@3brvRh&AQzt9V7eCDQh9%OXt5a;G|i@bZ?102ONyjm@Bbyk-AG3E1EGlM z#OSo2G!AXe6gM<!yzYjMbz!2k(@U0(+trlP)RmY#h;dqr*IQ?R&}&2H<}J2rYiW}u zP~~KO-$@YsAeOPo1;w`}xf97Bnaal~(V>*RlslG*wm6V<mUVG?W;|XYYOjC10$#qr z0p|+5)B!QV-Zd33eIX&P&(h@sBOcyFls*2{c&a5JhN@%KJNw>co^9G~C#LF{5|^4B zK_gp0(jc!i=Z|kZhKO2QJslUWxstP(hJ)9;TY1X*brzEebP%vOH|ae=TEMJik8F!2 zCfBcaR-C%>FxP*j?ZuC5Wt(l!HdG8wFlGySZ87VHwJebZgIuaNF9tQAtVuq;A@`Rf zBvn78{Cx0@zQFC&>zcT(@ooZ5DLlq^bn#J&`BKT$9K2{uCpwLe)9NGK)e9uw6?%B% z<gaA%@~1>FkOnDr|M!-8V=XEM8iXafANS3Czmul&B;K&E(CY8V;@PPyb*S%6FgVdc z9`W}ciob;0pcq69;K>p>!Saz3wzN?3ffS^eai(0D#1NU4+4yiSaIBoL`|rPIIfvDr z`1Qa0#{7ntiIJbp`*pX}0O#)fRSsE#!i5b&SNw)KO3^e%4gAm1KuW6^El#g*D1YQ& z<;4x=&KnQ;Z(_PJ&ZzO5{Mfqb!q020G?%*qT9H>j^drWzMCRjXNnz|Ouf!H=ZZ35- zf6B1d3;SZ7SbnPw`;_o>i^NX9Uu9rWv79WV@d@(`08vz%qK(npAF;02*tHTQbRL&F zsgI{eMH)BG)5n-5E{*RsXq{p`!qBPWGZDQzdjGY0b~)8q-*h=}L3rrKt6u7m<R=zm zjaaBnw|-`M^lDJx4^l>cR;+#eYTtZQHe2*Vyu$};X%~I&;rm$bsH17+@V`FiudU*0 z(#{^ixQS=~1FMvoDkuA$2S7F?76QM8&5N7W2%tF}L==XyRELSRi0h8MpI%>{pS?My z_Hx$|dG1zhD%#%fV>iVKTi|#C;z-@J(_5d2tg>Xbov9PQ$m3v%y~W_Q^IxVJP3j!9 zyE^OcPt+rItbe%PGj(X6eV_HVmxri%h~a|W_(#vf7#$LMkb0y5;|u<~uH2J?OS1!+ z!gI7*yCNRuN4C4C=7^ouC3!uc9BQ)@P5p4vBEESIXyqTmcH8)w+Khd?<CGSySTf7u z<8iHgeg0+eYXkjy6C1rf+_9UfX`16J(UiT9D7}*T>MSo7+!?UWnx#3vXUCNL7ZdCI zY~1!=29pNQ9o&v(cy<{pj3}qKbKB|Nndm@>SCD2dT;X|gDCzv8x}>%1Pta3jDb{Pq z&Lu$EI>+fSQ}TkIwLI&T!}n<yly>{*%mv+pt*657XZLfF2G&pVRbPlq)fb;T!X#M% z7WXt)wQn^#p6vK`%Og8ko+Y4lvv)ZSb-s3LbTCY=2+bMk3LQ>audgkj^ahU;Xxc`@ zwxbe<%oY|z<$vx9*_Gmttvcrqe?NVrP2iJKGc}O8iaYb0-g?2B{pHIGfL>}|zRl{7 zEl0q%sWoaoD7$yD$Vj`FL;D~A#I@=tFJg!-q&(bp+NJHYKV+fs({*O~M0+f=v!!_P z&U!`&JS5OMTji$Zc{{D0zh^RpM@Bgfeanz`JzK^g-VV1c_V`UF<wuuZsTX*LPoCW@ zzL}+8JPWcrd$d(IrEzpzDd@9%?1UOlVpgta=nhGo*IQhct2TCU`;F=>d1i#vxMTg% z4&T+i{|e6x^|3Kh6l0Nn!`pm<CLYd1^!Ut>F)(kw)B}#n9!{izx)<`00ingb)obNp zhWg@#Z1zX_0I+0J!DrMQoi_VS?`4SSCmdKM^G$vjL&}l$58{#Wa1APjA$O!;rMEZN z7o6}#>>Z4Lrem-!JYp03Z!5(B$dYF0D*@PnQ92X1%zmOdR8BW0>kM)}nfVKfUP^sa zykUP5jIAozhg(G61oxa)ZirSAu+kXMDFBQb3#cEE*@yB<c>b#ud8uh}TG<O7{+A>k zJ@{&Wu3cPjE$1BAG3Q;Tmqu`KZ4!KX%9vWfTQiX)7=r<xr54m_`>7S0{c><wvzLuO z@eL&Ri6ixD*$i5;Ps2)HX|Ax0w3P%BJDlvkeRb?l8#NKkMQ`Zyr67*b6I#sqd9wbL z5%;^Ho$%LdOF;xp9$)2~XO;KM3?_22FC6BI*Ev~gyq=SBf1Y&e;F^W@pESYUwsn6d zaX?bIL*KqMIkGJxyLI#9D`cDsk_t%Hp9t$EbeehT11&TebBNH1@6{4<FiX1qg*&I# zv0;?d2g1hV+6zH-YKU}$_x9O^zbzHw%jGXf*IY<fNy0F;Mzl|qjDvqca?(Czn{h8A z&7NfO+qGADK7604EKD}u->TP0<#h7X1UDer(xQl|6q@%@^=GVwrQn9Z)4+WTq=-OY ze#zY9+vp2S#_*3v2PmHqS~Y7Q+?@Ad2Ehxq_?k1@!f@-hmETv;xyl^%<yU)4cUP>7 zK4QcJi6)<gH?ng>Xt=fx!Qqrg9c9U57ss4+8zZiYuT}HCyj-KMoIWDrZDhG2_ot*c z(=sEybo??*rXY)O@1fE5kh+sl&iu|PQdY%i5u8h^@fbmZ+wU4bf|s95BP-mzl<F#y zOZ(mgdh)b+balL)Qg-kIyFs#yHHjICp&scdI(&`VR-C&mGAJt?vSLJeUFi_nF3u>B z2>AF}|EKbJOS{y(iiN}7B-87{y}VbWWMAX|liS7{JB(NzPiIYKMoZKuHe1?ye3-l= zd71_0V7xh&b;D^xKt5|EBcmU2Jz`x5Vo%PrNaXz>RVTc049R2W+(J*fgR^JdANX<^ ze<U3a7{4gJ?tfW=FP?FX&9Tomcs~77Wu*R$qri7j7e!7!4XLKA0%+EYT6Ez%ONp=b zX^}f!a+ov$A-&2`>N`*M6cT8XW1sALdAAu{b@Qx&2h70CA@J3&_16yShbDAz&gCha zm#U3<#(bF+ZO~}3M8aVOXQI2E&Y&0D0>te{80D`_of8iW*;;gsLr!)O1Dzg8_R?#l zJOe3s!4fY6RkBl^KnwM|t&AvkPF;H6LoRXibVprBtx<8onWGU+xiF5D-To)&g%ne7 z$K51wEd$mbb&>x75Q$wl39Tio9jNw3*lq|EbZy=0*k|(Ds>ewEf)UkbE9`3Il+dsQ zaI=d<j@9UZ&`Y;~>{+E7IXH2c4*H$%O$(I0<i@z9{V&r^*ALKH$a}<8bV6h6jr8uB z258Q(L4F^5yyoAs_aqoixGd`$%}>B6el!F~&DOg~fP|W-cBW5I#Ic>_=#n0Pb7P{r zl&-|u-lHHHqaUJ^#uF?j%r81T>3YCl>@;pvS+wS3ry_V~`fPB@=pS@E#!@`++n|3+ z#P{N56Y+2NP7ma)Gc1cG6;+JMk|ggelBJ~h=qU7M{KHQvpO-do_6nGEWC>oUn|wpF zv`%t!waA_x<c9_tf)ql3{LH7an0_X~{fx55nElT>j)psoU!P^?mGb=xzs&K5_jMGx zE%hCY&D@{zLPuOoROYeeh~^J*1W|S{4xR=*jXfC2){x?28fss4T>PC%m8dtHhEB$6 zFPy{7E#9EBw2CCM|5CEhq`Ws?5#*{%#-RmLhTh&P7&-@7GCDRk*aJzamvx!)9!Qf; zgo~;hz?YpO=8YgyKw^Osm;?r~%~mXN_M5cXn&7eb6U<CplOB);xB~2d+(nwuDSZM- z1LygTP5X`7I3_Qe44oxO5U&6Z-2tZt)K67g)|p62CEW$nx%$9cUc9<=Jal(fGSoOh zB+<k-M^KJ(>y$|0B=OUrDF$q)<eS4p(y{fVch4g(pBO4XtX?wFC2DxOaqs5Ss+W!D z@c=`RTY#~wFiFODhzq-BT=!0J1#h-7u5}y4(RXo8dQfd;Krdg+R9D=@^-{nkkdiw1 zbnu$W#(;nVY53B>(NLZx1Jv}y4YRT+9twJ5Klo>8NKvhFsL%9{ILq65bMT&tu=1d= zLpp6A<B9PBs2c-Xu*T&R#-_uF`4ZEK1QswrTAk#2Y-AjeM8W{Xcl*DHh~}AE8c11N z?k;G~PkxiPJ@J4VXioOg2ds!geKEFN=fGN{8F7aLnujJEv$HG^fS!a;e(c;{8dz^< zNy**wvU+VvXfpYHoyk0csa^7Zn|B=*jvSLW)orY_^ej2+G=WnA>(P8l4F|RJO*Gpk z{zML+Pjk0%OI4`!u_O(O?VmrAa&z`&jXMT?AR@Hx`bO9L5_|25tt2gT3ES>$W&Qea z(u|2I@9(fwcz{m|Po|>-X~uP~b95<Y|E-g|vqNlMbKG!W=WG!mId_j=A52$I<%&jd zmx2K$s`YNKQ(n|bU(vt1xSDT+XLasRM!>o8c9>GnqA)G6wlC{n5{K5r0#c9a?d|8s zmmFEl_g$Xk_1sK76*LmK$=Gx8NhzuNSbD$U%^9V^tmP5&!p-2<ej$sSuwO1AnwwEy zk_{}2LxBFF@J~Xae5`?-pTZ>k!xj94F#bW2o8iX(5!Rn9S-}ADUtm^W01Mz0;3Tty z2!sLwFeU&56Si!l_9el%6+B1Vst3quN$YaU_8PNv0`OV)XnXBQHr6Cv*s7y$EKkm{ z$#bmZ<EXHnOh2*R9xIt}meXA#1_*%{879F+tUGDbwU&7bk;jfJb{VSPbo6nv_e{O( z!=QKLUCnPFxFu|@`Z5aXe7p_FU6xviai==_WmcQV_uoB@`M$#%v~dcZfO8fw6;ciA z7iMLH8lGy)AMT|{+Em&;QFG}cWNxrgEmCE(&p;Q)S{lr<T!2293D41v&u`m&UREOZ z-_nw5CmcBRD2`u^(>d3gf*OWA7f16HuS_k|mV{GpdR8=*uA6V2H6Ebp<074SlrlA# zVi%r2`}Ljk&2QmYUZtOj*FU_C2@~%9@6Yjfmnl)|@P#g^j}%8^rC>1i4orr&lKAt@ zp=c7?TyB+QTCu{HjPawbo{%nEt7L47+*+zsVZe!{>K<(^{nVqawG5SEx%Eu-xq$V% znwzxsEZrYl>)D17`3;IGU*JZLrA*^SuI;()jXa#W{KtGJ=fIBzu6~Ul3q7N@KNjIr z<Ts0b3j;Sx0`4_#mIgoC-Yg3pmj6^9F&Fr$B4%^@BP(Wa+rNtVPd<Q3LIwp?r;0WO z)MP5}1k}du$Zyx>I|psod)cY78kKrmGk9Gv5kvfyg+V)wCS0qg08?0JP;(2M3I5#D zF(>%BwR0`#+Wlu=cbf0he+ceA=;yQ9Z6A=i*3vPm{JG_U9Yc_{3Fn74gv@zous}c| zLd3@_;X+>@uNB&SeX@S<+Wnrb`=75r-Rn^N_VoL(&9~kkn;zeuA0J#h{diV8?F)VW z4qgcg@!w;Ca%k-C4WKPf?GN&}1n&=F{9E>ig`;=dM_6294FNEYL8Dlqx|W0SQ`{2= zFHezAJ#+>@0pBMzKec?H(*5~Y%}AcTvx6Z78w_Ot<A|Np!gaShU!53?j%IP}PTvL2 zoOTNzlX<KA9?I^egMK8-UY7t94!|9f<{+WN7<Z0Nv$^y4dp(zcX^75uXjdlQ2!Lll z*>vXjL=#~whyOjEgs+{~$QQ=rqk}ng4m*u7nxb?ub(QN9m~5sieKZG(iwYNX-AFQQ z&Cwh-Tt{z^xa(4;*0&2@Ms+|TZ2Lbq;9-f!Yv>L8(GR!{gx4}Cgv(GEJ{j^fOBQq? z7LWo3khq#{a`cQ1_f#mT=TaL<LX{UDJh#sAKrM|e*r>t}!(3Oown68ODF~Jo35rOn z;;5AA%JU-uv{bzf@-Ivx*-EZ2w1FG;4f0wLmTGvDWuAlQ-wMRj6OaVuST(bZHds8B zB`Le?DQ>#LA|8V_wvMTQW#rR8M%ZEFf2ATFR4BkT=(RIa4hUw!%^o}9>*D?0=YNyz z(K=va+6Q<IkCH>jkGo{D#;oVZ-Kf4qOF)>c%{!ivtsI!b$hEI$YLCX}%+z}JCH(3p zA>l=6Z9Z@aByC;jXE$Y5JlKmMg&I7zw9LBwfRd`tiIUGxG)o_4P0Os4lC>JMc0b51 zo~V=27#p)A9OO|s>g6n~#vMuz@@cm93NB;g&OHYOZJG6_{H<QPFCG+jPt+?%kG;J7 z`=E%<aZiP8HQ_Dzy?C@dUkWUa_8yfiVR(+p05~Uu&iS$e8_8!MYoV?FdSMqgHdPl^ z&LzkJxs%Yc>SOlV=Zmp`Q|M97HhFY3&7@+;*Fr;zlldx1m%D1n(*jUwkM=&9yaLQ* zG{?o!gjvaQwpKqaI_Gq{`(X`cl4h<kKAlB4ti>W4EiJ5H=awGU$(?Vsb{T(N*mGE~ za<|de-+HEW@$jDJWTRd5_)O*R!v;e{6OL>>TO)WxvpnDAP&7V!Py475celx@!TL>; zU7D!#M@h4X<8SU0c<&v~2N?hjvmT`2M19US^KdrJJ?beq7aZ5@`N{fi&*IVjn91hL zKgZub|9$j;h-kq>ZRYz0f3!(oO2!M;xDI;n@HD6-%L`}7>e=?IHc*2robkXZLEnzj z$QdvqoWyu;#S0b(o@HN4xyWkBQ$N}g_=c3iWD3-s4805mfLM$J&G^wnY3=~T!FjPg zJ2=fPIP{h2)Fj&mYK)zTVNERkSYrjBkMIVp7$#}xdSSyH??;YFVc?d1X;E^6q7n@L zM5pLy0l$+({_TN;=|-q#v#+;S6=fVO#R1my_rbG7a$;LG&jYz+pW~PHPIbn-P55NP z_l;m-S|2hZ)FcID$dXW8)6Vgn%U68K)tR!!TZK=6{u>4c|2PAfzdaOc(jq-pn#j`= zlZ?8JPL6rhJ)|Pj@8`R_Dlp?}eNI12bw`E8wA&c_dqynZVmcj=-_L{8?<lZqhdZ<w z^JfMaaT-@=IK#~OSq#4`GK2vV*Pbw?nW@)OvB7BP;<a-R=q7Bx(L`rTKTi#;lM3oh zcWLXNGQV@iYSbtzOjzBNB5hfB!6;q*Q#II34pQ1I3>Y&fVA1y;)?7$rgaogP-SZ=- z@_fb*RZ8%%6c56NJ^d7+^uAW-mir;)TlU#t!6jmf_M>S8SL|<|9)=m(k3sgPLLTOH z?WZPu{(NEr7kPCI6>~Mrc1jwZsg4;^EDlapXZPhDxqr_7pAph8KnM_whpLZ?`@=p8 z_NV{Xs+7K(CMdOfCd<u?20{m2B)YykWkh@W3jhF6szvWTmrd^ASj8<5b4yZKBo=Mq zXZZiF!}!Phg^&RCQIOy|6L&<)iW9oDQ4LBl3>}GG+P)C4y<s$VZon!FLZEtn+^YUz zh*eww;0TihiV^2)&va|{4IZ@2@63#>n}wO>8+-b(<DWyS%EWpxnZ-tEbTzv}aqo7; z*G~EC*CVQ3DrQ-_wdWRyJKj+2)I<VQmj`%s?sFoyd9k5PxGtQvXl><&Mtc8;yGJQv zeX~n==-WU^T$0?60T!CN>`4W!ohtMSc3Gv*tRklR)SXWV7XZ8aMCKi|PU~3Chyh{^ zZ%-G*#BJS{4|-P&e%O2XIqT0;-ZmgW4ljJT1yz4-e>a3trnQ@@&v4n_QU7TKF+wLR zGv03wIEoxwcxf=t>~KO^bU}hZ03CZG9lWrTC@@u}8|-@;ZC+F>*aAydittKBPvF<< zvGBS!{MOvH6&IdYZHTWwIsVdt06cIV%P|26Uc!cTaK-`Kk)N@*4h>PehR7iRN2Lmj z6%kf?&s6<q9F)ex*yA|d<H$AS=wO6)ql5pWqxdkl4j2hXdx-CQC)Y!nMSis_5nG#4 zikLe)0EChpdpDN-KPmvw20X$Bho#^STm%F$Ckz;BR|WOe5OE8~nnDbAat>gHxhoWt z%=)e`?Qw9y5dCe4Bmlrd1<Aliw^t{0@W=gILG5lLz8Ru?0$?jR6rIBUpbbv`aVwZv z%yZop!Jwo1WH=afjy*<V!=|9%eA;JvGEf|~i$x-n*}d?oCs5jVDuM-Y4P1S#=SQmL zJ}T=Raz`b&e~;tU3h5OZ`Ore3l9mAEjC+p;91+<sG9X=ss5KSTV@rF7k!u|^o&tVA z6$TX}$I(s6SW-bAy4)?~^xthm45wy}V*p=NP_H_XVQ=8~LStq%yk}B*MO=~ZRuJ?# z#0K`(3z$IVe8O%FZlo9-vci5q$@&1WXIVk9uHvt0W}8lvcj*ZqLo;$M;@w?iMKqBg zai~{@l;?Y>e^?~HJc`Lk>lksq49UKKLK187biB<$T|}x0WPRR43^O%Rw^ktHZm2b! zGiz8f$_!l{8msgx*Q_tQMl(mp64e1s&uvE@qEVV9St%4S*%0w>1+j-lP0MC-aKhm~ z0#RxCN(ng++LN6G08IffwNThH+W+ec>ZHuaS)uU)0M{e;8f>JWn?#I%rt1-k?ZlXa zhrPqzT3bOT2ypV4!S7?e;$tOTEQ^^d$nSU<xv}8i3i2E7<h~Q~o=64>01gaq98yZk zwozZufXi$VwXu>lfu#pH)Bzfaltw1Bl{C#EJ`xi;1<F*pGKJ>zfz!xuXuwxA>;fJ( z%P3vPmodTR{Z^8<<<fyU<?Ep^la=zO(HxoB+-l~0_8T_IlQ(FMPFY&0Sf&@Q15j?R zm75D`xf)20#xn94;wu`k&On6~6deRs0F!Y|fw1Mh<PTKjz5taW8>c?TCAgKW`3uQv zjo8BI;H}Czv_(I$l_`kd`d~;c-7aVDA(!@$!t)6VJvBn<q5*DPf|#Nv49p4*TV|m2 ze<829#R@Lg{M@fO-Gl~|o=Er+N0cmecu|-Pa<vU<yPc*lC_byj$tmc60vHy#QQy&# z-&RT%NjRKfJ%>b`=x?;3X2Gs`dZSj&Y#Z{+UgbI))m!`CRX8UTSJnhUjm$&J<Z*|O zYQ3}@*d%hoQgV#k(fG0KU0mh}vpBQF5V3{^Ea6b5?)8b*5?os76?EfWcghvH#`san zoa^1-E^1K^wo>j^yj<KnN_mA~?)GuzX@!P{9&ul5blh>kB$gf9SpMA*dCRJ~t4ACY z+dS-w+9Tf19fumBA<uEB3AtDSOr~-@dkYobsA6RunCtryHw%Cn;jRO7sNr+9r;p%% z{DD`s%&NB&4xLdS1n<L+kZYkdNwdfUSM*^g@bnM(5F@M=?GdP9f)Oa*r6RvDkl8rc z2^a%=gFO0ufvnIX$m#~?1C*oja2D1)98`n|d%%FR*btyjZM#2EY-Magdk{)!bQ3Ko z`j-P?&l|W3xqafxBce69RKVsdY%Bp$*EHHb->i7lNIju^N{HYaIQ?KP)CvIEVbLyK zaCLM}8<Yc`07JE@AVDf98^=-Ne|0*_5G7r@Lv3LYp%($rS;HHXn947LjzC59e}~Wr zDnuI%Fk6ABw*jjt_-8}cK5L&r9bMokd1MJ-W41-lxjIV8T>h(YMb8kVO@+kbp^SCQ z@sFv+i8&9g(EG%Tn)2vuA~fx#a~fN@ydX_ZI*9TyeEtx`q5@`>xe`T(A{zBk7g0RY z=}|7I3)S7<Pd-39r5a{oe*Az|lcy}yOOrNG|DkMkE95)k#TR%sD=b>NseBdP^iQR| zf~o1?%jS-I8@A*R<)S~Bx`<|+(G!7{$J2_2k2x5Q&{;ZC@=5lOCWjfBZjBV5RtAI{ z2L&2kVBLo<Z9cyx0Prt6U$}RrgpTU6LhfK=?-3lt{6n`2;a7)!y;joM`+&+SY&}?b z#CP02wHIs;ea=AbwnZ<G+t&~{^B~uIRN$h*aQssP3p!Aj4%D+nzrgqB*C63(%}j85 ztqnSb!SS!896VjDJQUPjc*FM|dn%eGa)nK+@ENH60qZGrVCeP2j*Dr6m6g}fpQ+Rw z?N*Wc!V5Mx!CpSF=@-{5{OClOcpFGF<vu9&I(+~9WAV#{-eqAu$PGp%3zL|45sTK6 zL#r;??>|MRoO3ga9t+xfaV;9&M;!X+4<n5P63gLYkNobH`vk}k@_=rwM8S`gnsowt zHndOhY#pMcHRxwtVl$lY)7TlnxQ6G|J<V>QSAUJ+Xf78K$ob-fO6p=n!9{wfqFFP` zW7ot#5tTCVS{z3`0Ez`n)T+SQqGHhPcx5fw;~v-lFtB$5xlHho0<YaId5lx$wTly} z4Q-S4L?|~JA{*n)mLk|Ktc~PzD?f)0QUS9tP}>1_O9acM3W_q>y~y{*%5>oYe&91W zu%{>KuF(|KH!8r7{T30#vcg`YjWm?+QZS1{Z@!?^n`Sav7MXA1$)7L~%`?BE{Atzf zaafiYE$2Ph#`ftwrz7Dlp|N5zp-q%$nH2Dc+XHKvcu>yO8PK&JK$JO}#fu2*18}?p zApcnAo$7VqsfRz<dtD~n*@J^lJo3{}x>;hYk$yGm-*0%73TR?@=+9Zl1a0aX#LeEq zuXUv_v=zVh2o4fa362gP8-^L90Y-FK)^r3k#IZoYU;gidy1yQ+RQ5_V&`Tu-M8l_& z74BG}A2qPkRp2q9z={zzEg8bNEgEI^Qlg;gU<GwZL_9(hG4F0j;}f^Er)K%po^2MH zmG~v2!NqgX#%0ViGyk=&7m{5yBE>ZwKauN1L@To*xcn`2Eh>sl2J_2Z;h!RU6~aNs z!b5RDBL?&-|Dy+%&l|AUhvsq|G960dmZB9<^F+i0Dzt}x;+|f_Cr|m;82C>FM+N1U zkVt^WMBHo_e!H;MuF+x8s(ft}c|<{&5y8F|S6M_nKAl%;VidKm1ZUD?C5f;qRro`I z$0O(WH*KHi)g$J<*b8OlTBp?>;d>}J#CiXi%}WYM=g{=4{w1s&k5<^k_37HDI-F$) zJt^+M>N)hi@sZz8umuYxA-Q75B?|0pyN0MIE10p!Yu&+bigPD16+Uqcpa>4?%g<2@ z@F)-=Oc#&ke#G;C9<_Fx10*No-+%bPWFQaei0dnjIXl6uqfhd3ulq%Nhs;4e^rFUo zz%?d44l^gtS%l>LfFC-S{j0FoyHoKtt@4PDxTOMCvdwsov1`V!YJHK({TI=j>6gg> z?R|;uLvtkf#qf)}Z3zNa0Gn)YY8&mUI*)N3q3O@Q1X$c|ja3WLK)OZ!H&4K_=rEv~ zkKz*jJ_~cYy#XK{OWp}aZZX@Q9${nu5pS=B7KA7wzYr^4%`W){%U;(<=f0T@xfhrR zVAa6^FZFJxxGcnd;>=><;4niKxY<vBO~Z^L()DX#Iw)n~p%pp#V@Lpt0lWeSmc;=h z>98^9D3;ILJyG7W!?S$*9(1NklMeDc_lwob^T?wWcBfF7M-O6^-ffwQmii-OEpj~@ zaS~(;^=<I0F7izOZyIhsfn<s75pOyhZ>u48FK-8xxCiOlBcDLRHJFFhIs<mHvSV>W zeN;9t>RT@cw2}zRRAEb|!!%UUF6Kvk?XLMfyB_hCa!W`iksV=!IK*d6`_q_p(NM1s zA>r`m-nC3BRJsjhMn5^dpt=mVX8sEz=HS-v9&Fb+*}s*Nlx-8frFqJs-q@f*(2!-y ze(vMr4YzELA(?7rH;(6i^fp*3C5#2oQMw8Jrhak;dFK)D&x>-^$sW%6ZjCGFFM_K! zR8WVM&Mw10cbR49Ep*XgDHjX;{etyns(yGBKsfq{uowXFj0y`q^AigOZx86j_@Nm# zgK|bF-_s~S`}IqJL{@~TX)$iqI0Yf1Pr}%*nWpn9T^=m9uQf~r>LEGy?CUIIr9t#0 zm+W`X2#3qF)x#H-U&LeDd7bL5*X=6x;{N>&9M7jY)<*EIJNXWiv{SNn1kDr-8(qrL ziwoRzJAgFH@-qci^=f5`_hhA6ne!L-NB$Pi<2-UVb)%1DSjPr0h`flF5i8_z?U3qD ztnYthR_+=$?AQRLyk_0KSS6vhgMD34!Yw}lzQWo@*vmE&14nAvy;Lyljmfz5B1OdG zhkJJ@(}XME<;Jom;eAtQ_1vo^-KgEQuKTVB?{pHYO<Ud1di;)f*yNg%*wUPxgEZPn zh4W41$xWpUG=-lkz*0%}&+eEnb@N`&n*H)&r0PRR$Ul*{+xK5m#7nmuL~a1_Bd61? z6&i$NDUz_W|H;&aR=ad&(4VqL%A4`n-;;o8Z`r91Vdc$d#<4Q+^sg<$Kt^&!heBPu zxlmx8yoJb3snmOkvkUh`gNijt<#z_X8f3-T4rGbmo?agdE|RRJ3xporR%&pLF!D`Q z(UmvnN9jq?^7(EOSf3|46M>Xgt{O>z<K^APaTt59e;1)`<KYE^>83ynqifcd<!}BO z_A~k87wvH^GHx7rUL9uL?5Qo&>3SqE!i$tQ(GPCNIvB@hVjFeEw@gX@uxq`1leujU zZvORestuuUII9yz#bp8Bl|+(8v}iq9^wC7i*@X&AEAAXF>*8t{mbxXLZLi7pMIL9C zkbORJ*O0TCuenZ*w_1>UyvDWQ>f=kN!jg*^i9L-Cm4>s&^<spWT7Rl{g2J3wd?7nk zAR1LUnt!o-a)Mj$pe?DxpRH7!Lyiig!{p4_Qn+P-uG5N1%W_+1A}**t$R7^x7@cz1 ztR1N`=e+mCZ}9jb!bsq44p}&C=T~yNNw*f)W8Ec!QxR8)pZ4pEt}<8i?XAabnMG=D zg9E9$D)(za$*wRuqz&Y{%H7-?rJRqm<OvE)X)2F!&@Q|8^lRrD?<`enDYl`~c$PNg z`u?)w$n~C?OCQ@3M}?B9Syc+Bc$_%Zs<C`0p<P(LLpjr;J^bud6Z_dHyD6==dNA$J zd+Lj!Z?728^qHZ2Y1H`0`{c6d<yc8{%ob;ZNGVuHFlv3;`q`OR))y<O!=U1i1)mV^ zb!dihV=Yvih&FEIiYl(ovO2_@qVPm5NHOEI@TD)PCH=UoZ(!*bKi0p+SNzEKyYi_! zel*ZRPfeBNK5HUu=?%5sdra@5^?No4*d93eRRV4g2l02{Ss#OY7_0y$rx-^f>NX=$ zbOH<0nP(Bz?Sq-m*I-6QZ53bFrFT|%-+`3~fFfxvzqhib4(7#lo~<IIXe=@ZTM)f9 zdsOW5b@ByWn*vjCg-f}ytfNt(Q(LV{8@`>#yu?i9k<(daff`hP2>{`M2A_klplayO zis>ww-p^`yy;vaUMyrugL`gCZTvv6w_~CNrfXHE+DMqb2D<1qnGl5hWSL0KxoI9p6 zFMpD8gXT~RZ$w6JnP6lnKtv`L;Ux$3Qxmuwzk6T!0|u&<{(aPPF4w$^EzKfa9_?O8 z5;a;JmW|ubj{Uo9gzmVic12QR<~&8gOJJthy>IMN-8SzK)6f*NgHGYLBtit~APFQ( zTKsIYDDVtk!@Cg~r7%;`F0g?Lu|UPbrp0D)N#Z-I*|C`>qH<bOI;@L)$MuS)Xemx3 z{Rqr}sUuIxGET&5pK;+%E}I<|D5SOz^K2U^KROsWH#;^WC2e|n@Xxy8#ir(%^g7oO z0SmyEc$zrQMC55sV0&hlL#6UP>V|^7|FBg4LByyEqZ+C+&xQ!V4e)yrgV3)j5Szb1 z{z<t{7N5l(%w=emmw8>21ZQW+8^H-myjEdANmTqEM9@UVG_hwI)iHP0z%<bIvWO$R zy2ab(8=9=$<^I4Qy)F<LASpDDCI{;#2{2UrnOaQMtdL9-{GrLcX$SbI=u~R_pO^JU z+KTS4l%>dJdN6DI#h#4$?5L+wA?@joxdfsl@p<Tg$~$r02a9hW{~WUlt>%_r>Rs3D zxJcGCwazAdOcm}JHIuRHPEwd%MV1vq)ffAg2@I0RhZSBWHi`F@S)}?Oe_E8|Yuw*7 zv9|tGbwB-4)iicjob8081!Vm6`1iiy!I&aUcg_geURbMnc6EVeNVVn8p`-@O*079P z0+h$O4}BXAHUPOk_%<Fcyc6(1$>OO^=NgBE-Js+3o<FFHNApAKjpPK-3jeHi-Jq_{ zqRmx7Bz2NlF6(t4k6XSXvHnRjC@y0vpV^cZm6}v#;J7B*Xb-dEsp+Rs1|^PTM+sr; zLLV%1b^lG95;D)`R`iC&3#u*EZp-;WcZbhuYx!To)e6O3v(g*2U+>t-j;~Y7VvZUW zna~r&jLS!I)1Pf^PauTP_lSHU?Pf=|4fuaysJ!~yhq!+1jk>)uz}Ae*IPaTO1!{KD z=x+Dd7n<q{yz{^~JYOgw$7G7$W_CY>6YgAhSMJ%l<eS0M@T0TqLVx!xqE)Zu2n}ce zywBo4{J=wN(rPP<D)#RP^nU3)kxyM5|IAx(GVXYDU5a_^rIibR88#sa_^!gIS88<E zy}R$d4y<43wmAEp4$_m26^KsCZC$4NfM8LV%@>!zj&i@1MZSg@+PK{+T&^9c9VgA2 z-=f*$#XRZ$)6FMRH8{CnjXsmVY^N72p5!i7B%-?(HNpG+1HhB>-IR<{Jfqk7+{-PI zz2g+^$J5_bZ`SfXr?K+Zt)!e(Dg3k86!FK+xu+kTTa7pqV`KHqIi3L$eghaj?d-Mh zfGg+q_fNjO`dICAx5RnB9h{=O*Y3?9<3)$M?tO8^mur806Z#%wA@d$Tvzn>9q-OEg zZKa_{(Lu^ZgbnZv?A%gF-FV9W^{39)k~9MMD%*{KbRDW{_I>UK;nm4Tqn(S*(yNn4 z56F6%3)YmNjYSjZ+sQ)>n)Qjw%saeKUX6XL&DVUQktD3j-r6FWtwGufI3ifTezoIu zBT~5Wa{dR$wJxzLM;vElUF47E&yKn4v?!^e-witNjk0cV*bhu3gQa#tNs`a{PQ-xb zI*)9!-z7w6e|&q+daQ@#cE*Psa!>%PM+|LQhyT%bFI4xWzOGqohI~^vX_`E2{Ue@5 zBS+6e2=ruo8)f~TilxA=FD6E*F`SADsTJ1xdx|iIcO&N6(;O4|Ll3g+T7l_+`q4|$ zJy@coWs(IE96I`t5K4X*BV`<z&z*mFdJP6V6qoWK#~U_;F_OvLoW1b-%BHAZpvmdK z{pG3D4|zNefG4UM&oH-@n25irZl(3{u52tppeu&zYep|>!}@tPOh|J4Lu`O}7%fw- z`|!2&KXm5lKPjOYGJrt#u1UF&3lvEOdB%|Z_T)By*Xs?4t1S(bscOk*%4)XstCqER zx3Ruk*Ms>EIR^_-o48I|w4brbPBc1;N3$!aRg;4&l#-~CDsY1;JGV37?aQGUq`QcF zu-A-O<1CJ$l1~ef!(rrb05l5I>rQM^(FE$ZDO^96i^nyT7C%$FNde>|?M<6=u|tvg z``*W__MucK3YSag$gM*?SO@DRYTA0hK%PnJ+C0AuP*_TeynAMtw98g)$t|-FJy?X1 z2DCVY>nK|gW;ETh#0wf`sD0ZpNtRCX!KSn{@rPr`cSds{s=D(krz10E7n`6ld(hAT zNXD6pW0ryP*|CZZt1cZ87c48DmZDe9_V9Pc^86@)NRmC_(r^ZvPNTHhRF^08E?j4F zcfmY+n)6}`DwBMl9S}faHK9LN!Gm@MYX~e4T&;7P^6$<kz3g7jDUyW7IF*FU^LJ0b z?A>_z{P1P(DSn~cr$Jb<XM$FmWv*8v)QS!Yf&ol&#zzNXoSey5TsaQiVV&AYrofr1 zeaQ3ep7>){OBk4EF-dPUIkvcm064P~Iu;48`PT>yK4x_=l)F7RxqO>0zc4cDp_l<{ zWG-7JYE#o1%B9Clr^v<mw&9inw-Ng@RqGBlzgJ7@+}Um%+Y*T6cgJAcfF!OMkR=-I z=##d*Z}2u|lFJ7jIbiIe*~Itj!MnUyzv^E7?z}(>XT2B$3EqRo;9wKw4QqQ4@mOFG z9-5h{>n=FB;maUXPVa=a!wML%0=tBOw7P!XH=V;b=&iRF610iRwvINZX9niMjEZ6g z&&6rpi}q`c{4uw)2<ohAyJLb~(?XNYoLb3B(?wl^-MKg{c<e!y7Fa3(B72KmvpWd6 z>X1Z%_ftxqDYpK>8dfDie|&!Iy$T5$1uKLmVPPQ8W7a!OWWetfq9XZ2SRb>J@$~RE z`@(_3J1pxPIo42}<QIc8x^Em`JnMc`U3~=r&Ee)qo}Y-JkYCi24OPHVzbDYwUR#)@ zhR;8_I-7kixl1>J9D|2mKeoNIBUG0MlqV|a?y)+4hZe$m{&Q!{h0hfIl_gLoU2w_z zXJOiX(;h=_o@p1k%v+cXKAhpoEc#R8X9%?1g1#|D=O3F|Dw!L4>U(!`0>PQ(L6oDL z2CtjR?xQ5z7@z_X<RI;6zRLUPx5$R;MRLGJu>*_fQ-z_U{XY*)-sQW*CL>*7$$kO3 zt8Am-z<RIqiSB#Qa118F-Z{c|E~%BrJ~%&e-p=FN<2&EUwnP$^lE~D<lr~<2itO@M zBsiy7x|DNf-Ygxv(xzExl^Sd2wk*u)xYvDC@Npt>VC`7o3J!Fg0u9^B@G+jRP=b+c zT`3G5jh4Gcw+8?!V_^X=d@7(PO{os4MB^Cn6%|<mt^u4gmH*pS489PaXpyL?la!8D zIhE=uy;S*kz=1LpMAu2eRL0Xs3CBs|E0CCCwsnTn<Bf%9U$||$5T@$(!Vjw+{H;2D z4JuPcj!+?m?3jDXQ3?C>FyiR^nEMOXOeQtOnX37@xXQ|EVd~<-NeW&t`pk<q-Ks{Y zE|CNdgT_$XYgr6?lP|e%XS?dam;&VMhG|b$98?N`=VE%8zRg8T^@^Bs&wq0N18G2( zzmBfMhExmyv`fZX&8x62+vw%Vb5VtTl$Uu5l6tU%)D507E7;ftUxYciW=pLL-Is0f zhgtIlUjWlH-~(@X2JV`y4<nRGE#9~gvwzTqR!E#EnG}QY+yKT+S7?Q9fVqF57h)KK zMdF7347AJ&-w19R@^#L(TCf~3x<^1EP$P!&tS2xl34yuakwB+vnA3wYS?87B6~0kB zRRvOb25>-$dYK8D%@@m(;2egX8#7p#O(1y4PIIz^Phg`zD1<FzP5*1hTvSKZ5*XT? zq7*(^0j6T#6AHs{AwAnIpiu*q6o+Bd;V`b7@hvffxSitI4gY?k2b!2NE8BrWs0B5y zhi*uqc#uQlaY=UEncP4{umCEC=*a+J;X#HDGl`OJD2HT&1T|o!amZOQhGeD@MT1~3 z!ARqIV5BWAv>h;nPap<&C{Hk3*N>=NSc6lw(qH#9lUG@YJ$2<*cIDs`kr!qLBea7z zPzS&ovvZB)UbYzm)GRU!i~zXgcDN@)Py;ncf=ozFP_74c=!PaT)W6NT5T40qnA5ZK zHj1cX&lM3_RfS*BhBs(Afqh84_2qO<7R+?Xc@hkGSlw|52MrqsU#J5qpn^IyHG0@C z@UlWmV^<#jCz*s*_e4gF=;qGtLhJwrBd7)8Xa@)3W&d@i=$eT_@=dSug9mE`Wx(Uo zBme?92n1?SO#@=5tjojP*x&pF+lheXmwsuX$O%)(4kR#ya^ME-T*->&=?P9V3^bZz zX^<=RhKGHJS}+78V1hk(gfe}H-H@eA%?)zMJweupgw{=TF@>{(3`95qr+@}*7@i*P z>9TH@tYgN?Ef!u<2ln%ZQ=NxxkUtsNgGtCLafIBLW7kq1+9g83Rdkz(Fj*-U!@@S~ z!$#~X(UL9cgBd`CSE$TDjZ(9wY<4k9T^ywH1Fz&_v38I@D$s$d@+c(i26d>=W@M{t zmWrx=i2HQy*M@ESv<{;%gd(_*iTZ`19MsC@?f+UiQCJgNxX6(l+_QgB2Wp7KFkk{n zV1{xqr`_n6W@Ir~jmNROp@!%^g1~Bdl@FungAv%@saXZ<&9-Ij?em@v=lstyzOjE` z#1-=gUoZqPO#@9xhvvGe;U;A(qz6=l*N50{0k)#9o&jLUB;j*Ak9uA7X7F}-Jh_C+ z=KAOErHNdqg*E_F><S=WQ3sFE?|J}+`RG1YMhL|2LV_^y6jyP>ZUyf~f;4Fb+oU*G zNCj$$nMY~x9A9VkYE`~2j@|JFl%xq+sDmBY14!`H@7m+s_=Z=Y@q<nXTovR&w$TP` zn^k}eLjZ3qml9-Lm}YpiC>=N*C-dh7TK`I=$TR2Lc*;W`#k;lU8Fpwgaaf1+g@ir$ zQ0&q?*5sAkK^CV$2$&Z1K~IG)lsoNsak+b%KK=4UeiZXA^GMH+5oXuf`a5{jvrK4% z-^c`0olS%Jwp7sSmd@^*^jx1D^?S4;+TL<A@jb%`-SHB*HI?*Q=MzdFiITYFcc3>l zXoDnpI&7S%P<Vv~9PBGval~%GRPR&8PWBi_^!>e~S$!I6$70dtSX<ZjN`dfh-;rYZ zhm9UI{S%T}_{cUe1Wr(&R``(LGbk4R!g9fmc_#&hnbAI7cAcc&EC=sQs&_CP5ne5Z zbK3TT7eHM9h$E9jZrCzz$OKVBg8x3aCiiUVf`A|GHgyOzjK;7g4Dxue$h}mD!0twL zJGvtWEGR3IqjQ3EgLio|U-PVuhuxtpf3SvNu!Z@K7Eh>}i5l^PitU=Kxl@2_J+K2i za08@Q`aEESjt6Ji4laJzh2**S`8>NVLB5yQ`bjS>gg-yL>pBGF1WrPPBA0+Xz>Lh8 zsF}t|8!Z#RvV#>cfw`x9y61sO$URxK(H4((Qi$;y%?Sc7%mv^2!mm`XCuO#xhuZ59 zh6x7gDuNEkgFeWNSHKQr#K((!g-P&$6`()*bAr!j0TVz2+bqM8R|Qs|decXF-^&SE z{07#TX2Yj_Ghc7S7YOHmNB;#(nF<OWPhg`K=z~!R6YR)ORj_haB>F#C0T-YHi1~w~ z2Nx(<0UO|iVjpn`g!Vo_0$uQXiEI6ow;@)DeSvBD+DCu0KzzY~F*~9p^MLG!$_zvR zpBb>8I?7Kd!E*F~MYsV7Q?LF|AOgq^LWF<*xLLu1(<@S^R;@B+@!}~}q;we?p(`RO zQ>QMHyh!oXDORkw)r%J|0L+*&XVR=`^Cr%mI(PEy>GLPhphAZdEo$^A(xgh4GCjKP zDb%P^r&6tI6{@^{_3G(rMUkSZ0HwyhYDMZ*F;RVj1c3rkmr7C<O{Gd@v2NW`15NNa zm{1`UhY&^9C5f`tDF0o3kmw@Ss?^Aml24{w369>&rkXc%?(F$9=+L4^lP*p3D(cj# zpUP|9nrkankxPy(MQT*30J<23DS^aLuwc4Gi3+ePrbU=~|5z~iS798%uS80=c-B({ zU1LMeu5P$8OP8%plP_=nJo@zN*Rv0>`aOK9^yp>nD%&E;<N++!E;UNGE{GISLJ)Zf z_eyaVQB>F~fbjL4LT;Gw&~&HNl^=Dh=u(6s!$F20N+F7fQeLG{^i50gjMpBEExPz3 zj4{fX)IT-acq5KE>bN71Hg2`fKgHOxiiuwt2bL*cy^`A~qr4J;T0zX92O_`(Q;H}_ zGWZ8ye%bLyLjTcGDAIzdsG>?Mt-KOLhopq0%2#p9Std%Wkn#;U{?IccpMCoIC!m3D z79XMSwH8l3)jU?DcO@OS-6+AlBH#!!)NvpwqMQ;ygA^R$WkL)|M<kN6wW13WeGKO& zb&X1f5-Y8Mlczr`3VJK9x$3$ri#_`KE3h|i<xf3AE{UY83KBV%D3QX2NDw0=!H6zh z>E&Qwp+YB}E2>y@renI)&><(aC5zEStH9a{o_g~7F1+!|J8w~i+KXCidMY|rnRxm8 z@0nmRI|?bnA!5i3Q+o1>E`>Ox1Qc<&5wRO__+Ww)qja0DM%AY3VJQKxa^}A!+a*#; zt*~S(z5gw{{4&h9-a9i^uH{>-EyvE4>`bQAwrnZEmC{ET9l*edEl`-SG}BA3V8RN2 zyb@wu0iIyUE4V?1;kn<+w#upXlw)(uWt)9A+N3=N)7mt<oi9C#lDad`$Xx`JDa18f zZGbaKU<46Tq#?!;g%_?x9=42Cmt)2BF#{q9j)ih}=Tc;%Eyc(~&U|F2{W<8Niw;!V zZqIykHHv46?ueVlBw|f^*Cxs<!FUoz(L&^*W|N#ilxZk#R$E6A42v>Wh#<BuB8dEf ztxG-rj6OZ})mv}6>G{Tk4KQ-mIcH21$t3<w{b9+lE}Ya6#0ga}!bma2=pujouhcO? z82?%0_ElYT`u~-(FjtIv1b}7MJ0JoRI4|tE%^&^%NB3Sqkuy>7OaZXqOfYB@3XV(_ z5z$Mv5YdMc?4SoG?12w}Py`u-!4t)Bk_0nS!5Px9g0Nx*N`8Tja!5~sKKvmN0Trwv z5>ZDE1V=Me!3wV}&vi0E2~JuU0F>CqN!5CV9<r!KJ#gY9XBnCDnkYt#sAMd*zy>{f z7{oQQv5iKFici+&o^`N|f%ZC7JivjCByp{4I7t@J{BtV4@oh=w>e{)=Sc)^kqgL{8 zBP1g!Nt;ZCbatc}9_zu4S9r@5XIfrOpg0pz!bFT;F`ps(vokTWQifh*1u2?=4gUuk zaFVvXWf0*Q6ggh9P_BUuk@~0~SIGpC7>W~F^kSmQArg?HpvEj6iOXqH6M=H9qfU6) z%X`_3jzZ!W-R_3B>d>T_-a(c*U3HSLfukkTtR_6;slaQ_M4Q_zROkM&FGfk`CnOnX zIs@7@6P>C?FsY?H6RJ?N(UX$*<fc6IgpFSir(gf#iODjm(T#FcqjXwD=ISwydOUKW zCOzo_={QGv+Eb+u#b+8HSdEl;hbRKQY1d96iZiAWp(y<+PzBY})YS2%SFss8*dex8 zaI$hk!6{S$Sqfl)V;m|fX;8DORX(v)H8L^kd*;KAe{@A9Dp8hD{-@Tpvj4TM{aXbr zt5FVe6cDRhy(?Z}MAUkMRW+>vlA@+|R=S+bCsA#bFuPVkfv}{JKFup+BRd*{4yA~e z1=d#NQ4ef1LljEfPgsW1(b1+NP9!7k$u0-d0j}e*l6@^~o1)8x#)P&*?dwy-%8sXi zqZ)EKlYWHK%Ha~1mB97nnM6U=8i|b^b&V}_qbpmL#u2ygsRuZ^a-7117ASW+EL17N z3RP5tq*;+Jdedtj>!PM}@_+|Du%Wo4fH$iBD~m4vVKcj`x4-@!luOwwmA^iP9N4G^ zr)*l^s7}xnwkU6AT>IY%Q@ALXy>O3OQx4e3MuRsAE@&5w(^W{Y6#vDz3_Yk@;T5y^ zC>VaRj<O;ob*ZE-Hu-0WMJ&*ON$?fz@`s9BEaV~gM8H%@sz2a?jbentNFNrbjz>I~ zRt%8HR=%=MV65dEMRXkC_y$u|aU_~Fv6RI<GnxxS;#EMHSOml}oUd%;sUVddaGSA{ zp9o4c^SQVedR{%=;S!lhIL?Mv@0_KQRM*6}7-qV0O`~j165|jU*f=z%<DBTKxJ0SN z@QQ^}A(I-4nbf8}HL6XWidgAF9rZ|RreodWO<QHr|3IQZP;%NDUNF_Z{xuEjBAYWl z64tUl_JnC|75&P?(_ZQICz&bf>NJtWrXWQ%Xhl+FbDP4-9{;dwIO|#Dg*rKHJvX}J zq-!OzVimL-pc=a^@7Uh9-qy9*Rz6*%ttDsL)Q*gZlz6Ik#v|VIJ~(8*T@?Zo*d<8R zh_blr?~+9Odswn`PxpIJ{vy2NCsjCVlA77g>LL^gqTvLAt#XwxRV8N{FO}Pw6=Qq6 z=3A}gN)^6n*Oa3i#duShnkVVHxcucPDQ_e7YxAYw9OQnL2WEQv3cJ9y-Rdg0zoQL| z0fIxbNu@c{!yZ(e+nc?^A|Nnynxwmw7Jw#6w?*kB8&S+}D;tLi*u}1QdEOSAIcG0{ zcfR3jz=ag6rVQKbn-MHgc`H5d`9JEqqC)Sz^0sVgQU5nxK<93y8pSw8lQ{{est?wj zBr;QoT%n70I<V)Iw><2BTDndDRpf+cg(z6z3Rb*AC8kwHMr&-QuYn7MD9XxtJEP0k zGv9}auE{^j(auB_V@a&);9^U%YFF$&6=BYlh6X6M4ZqsC%7;qx)1N>%TG#JS`MNyX zS&nbWZ#bf0RY;i1R1#0e@Yf~|!&Cz{Y(?a~9#Sly`X%7#JYUYWhONQPR`gc=e1!e! zO+`^)F?2&Upa@K~UO6Zr2uc=Z!Gw(jz?MbcO^o17AejSg1$ODtfmMSH${;jhLpz~Z z8mW|0y;%tMpa>3;3G&EJ+z3wOivt~@3vLBH!2d%d9U<9poDW7}R#6ra#ssifA&zK< z1KOEu&_oqVAs9-M3Zh^Tjv*P6V2*g<8B(E+prIMcgbLckeArzOs^M#$;oi+h&%r|g zyhA@Y5N#dXd<-Ietiv~a16>VT01)DQzyu@i$s#_YBu*kFQld_5VJ$skc@W~~M8$Z7 zgG)3b)7gwRz(iHWgaKNaC;r1YKw>?J1EI-7Rk$BjWZqSLl~?Hs0-DX&*%=+xLmG+V z((zV1NrN+>!>||}vb`TWyu&us12sSbB;W!&gabYNgZbU!-=QC0&5Yl*$82%q4>=dH zbb=;?Lpa1C!p%oN$OATDgE_!NKJWoQkpDwD)QB)@nxb)`IMl--Pyz0Qfg$+AJhawc z&0=j?g)J(iUUB0tPLCYT2R72fC)~gTGy*t`)qDivXmDgaB^5E&114O<I}pn?EJHnX z!`&SkoykKx^y3~Bf;yy8Jp@7__`^8(gMJ;PICi5{EaXG32Ld9bHLZh0*265!K>*Z) zAIw5H&=q=w<3fStIt(B>^a4Gk!#kFPF-!wHykja>SX4L=Is8K)45U1WgEy4rAsoU# zhyylKr8e5uPx@p~vd2&cne)-nKUhOO$U!i`15(aGJ+u}Sc4S>9lx_t8IPil%T*5wp zLjd$#E5gD)7-c@f8EZgYim5{YRR6;e1ll_!RXcbCJE#FQii10>$UQlfN0JBT&Cxg3 z1kRz&Kd1vd5W^f;gF2{#Hpl@qSOY#nqG-&eUh+!hm7r++gAK}qGZ+JNVndCz(>b7| zHXJ9M*$6wlq(4wWGpIv5xC1_hLp}Jy6V$^tC}R+*BLYdJI#|OT5JLd4!+UDNB7}oF zXax_F1`#GF9>z;;dPWO&!!{^F0PsW4u|q%TQ9XddKIBm}8Cp~@;Wq>TB)kDDCfQTO z13k>-8)U*OK2m_5hC?!BdBmnrj3{mP<axa28)0UR9D^KKLpaETXKI2U+@@#l5{niY z9iaw*0x5twkT%rAIV6KTy#K>Dd|&`zLy<~DEJSBm4n<d~s2edO6Kc{M_`*B11A#ro zNcn;q_(L<kgEm!{m6irk`shMt6LxY2d}zi~FyTx#f*;g_HH=j_Sc4xN!%JjlPLSQ3 zt|<H6rOd2`XNc4~IA}d^4rXi*Ht<6_TtYX1<zXsCoZiw{{lh!-qZ>d1J&1!&GFxl3 z!#vOf6;Q)BglFCbYAvdVHuA(?wFsh4mkE+*Q_6!i(gQiHgB;Alp1fY6Cgx7m>bn?g zQ@kTT?87C%;El`*Kh#4qI73PjC!D@VB>g05wgWXh!9Q@rJG?`UFyl+g!y)WJsJcU| zx@M0GC9%q?iLywhGXI4rT7x#MK{WJ3B+|oR{sTF94o=t`yxwBF0*bvbMQb>zNS=d% zNhh<_$N(NGJs>EP%4vWR$`4fq6OL3Sz`;L!0}~daVY)**{DUvJfjWr8JD{nM&Sr7G z>rGT?!MdwL4r;v^W{p@wF!(_<r~^9?;w;EPqq0NSb)ioJrC!n{#_A%rE=6lZ-mL6H zB}l3b7Mx7f!#7N7KlB3uxhR!hY%WGpQibbSJpq@t!+bKFEC#?hsDm2R0xPm?UK;9W z#A>m|E4#jIONOJ@@`TOYW<4wdC1`_Zij_J<gC7t>`MK#V&a7RcAKnT|7Wzt4)QD2; z11+Q^Owi$UHveWa$bvj{!?tn8uau#3x{;0e!#mUiF1$gys-al@LoKMmTVAS=m7uWH zgF&$;Qb=S!gu^0e0^vp?;QB!>@Ma|9#O?}VmaQS~?#Qkn<g9*eYkUJeT*EcgLqBY! zis{im>_aSQB{taXi^c~eF{3+(13NsyFZ=@&c9l!yXDz(J=A`19x@_Ght>fZing;Ct zE=4VlE6l#=)BeLTtN}fQLsA)TI2bST0xF5xtwSO0{TeLIAVpS;gFIMfKNx0BH0EPw zgJiBN0M9EMk*hy+tIvij|E>dR!X*{>0zI@tJCJY$|L>nnFU?BDKLCl1&~1vU)IZR} z0n<Y{<p0*5u!GLZ0e=3hwcc>!dTkWH>Y=&~QOMEvf`Vj%17#(ZK{e(}phGy!=ht1U z31_Tf_MAJ^10FzvCaJDmLd95>>mEG9E7q|2g^mv6Wz9<PP}s~&5<(-?LpVG|&&{Vb z90MI7FXI9!%o-;U%Sg-au~58YKRhQ4G9xY)={aB}KM<|O9_$)DMU8~(H~hm8P(ygK zX3flTJCr9C_=7jBrtPw9di3o!R`4zNapYd{I*h|V_<<%QFwH43;vR#(PH-;wazZX` zpxCV+Thdd2<t1c8KU8fGbyHPhLpp#$IuLEqhO+tYWmF^;$^HW_c&s>hX*PnJsn$a? zQ2)VpdTA}+ZU3t2phhzvS5nwI#X7iJQ=%hP)<}B#K_mP_A!DZ~LvhpQa4rrjF1x9+ zR>D5;!#mQ`c*NiM27oa5gFQ~^z>ae+jcg4U!XdE3I=3n_IuJMf!`sTkRh91my9gym zCD_iMJ_ChBA~ZCt0dF$fhQ@=d1;8*TG`pU$Y%X(7OEOik%$HK}*TO_6*8_q|=1t7X zI-o-(_(Lgzw5#$n1<$k|YipOXgAS+zIjF8O14+q#=zm6aT}ARP>oTlf@KNlv&icVN z_^jHJLp=yGLUSa+(zQ2Q@Kks)3NE$Z%0tg_?UDXNR|n#)p@=l}f;zk-AbRl4UjMLM zmrYBq?)<)*dqMF(5KA*4K|g$hu|2h$x`cQ%+isDsyJlXD6!wd{X9FK^eiGPD7qL;t z>`(sanqp6&^avcHAoNz2jf|9Kip>z`L}NB6GD_!C?x#@*p&7QJ0{Q1w^kW;d12;hM zO!P23{KIMY!#FtN6Ys=)gu`3`^Xcje@1Do<0%0A}NI(38Aj|@9?%;6h*8%&(80SQC z_b2ZbxPL0=e9Nm<w8nhE!#I!wIjBQ`J#|F$)tC9hK7c|@s7OnVM`O|hC?I29apGnR zDNkN_^r{#V8}f#6!xK<L*BT}(XWl#TgF3(gE_}l{tgKRln}d%7Jh+29(EkH4_nb>~ zwrSj@lIQPL7;(=Tr%*WfHU0zQ27_<{H62|e5w8IsYV()=I5gY!pX|sZ6{!n$gT6k} z<i0g~yW%xqLOqnC?%D)pMe9{Is%!%V^WJx#Z}&gYFnH_09n+!m{zLlK!>8V{P=qNJ z#IQ#LV^Gz1<N;%)*F%2#a28rva`J1?HYya}W;76jEW8@@A$NcNa<7{1g0~^1FYk=B zq}pO_JqSZ3+<`PiU{r8#lgrUN)`KxP12~jo0K8M?Igkx9YgWz*W{9_&hIQH1rHb>4 zHmU7P*25zNLYLw(fze{A_M=I^<ts1qe!0dwtT8TxfiL*N3<v|Kj{jyJGdPL1X<fIZ zD2Br)2tqD!4idBSw0ok1e>zlBrQ!YqB`ktA^aB_A`<8EJS^fx(yN2`@N^#>zR+Qp3 z@B%vQgFf&AG+;x1|F@g-1jKUlC5!_<%!&yD>TteeI`l#|JWxB)2<4u78s4|{lyZ8y zK`p?;I{O5Xs{=O-L8qc^PizH|4}Cx6r!T~EJNWod)wfvH!x9j}EG&WW=J!r7c=PVA zt0g5Xsw3bYe8ML$7P{d-!~-90gCIykIS8iiqWW=TcY;5!Lz8mkRb`PrCp<8yG+Y8b zl%fDndn_vJ$*26KxoQ9uX)jEJ9+fauH*?EU`<~Nw&IzV@e*bKt$&sK_1EHsMyx(wA z^&=$U!M9TQ8^Eo&hCWj_`I1A0L{?)i_`$H(!yIS=ruVSx6Y4r}&aV;>%aF3G9XxN& zq_s{34@Sd&&jQa5=R*#6<a1Tc%*RMwLo%=;v>ItL5Ks@taS&T&lp_AKW5YO{gPb#k zA4fakgQH?6bscGzd5YAIy6U#(ryBTzKj85tmK0p3K0vS|*RCBs9qQP*YsZdV0EZ7D zMwB>_VnvG+*JWIHkz+@X9yP9$C-2|CU2E!%3!pBVA874JhWvPO-M?}5<jkt4apFH~ z*5pK6$BrI7h#@nQR2N{*tZ?NT5n^YJVMd8av2F~IRsZWuuU|W2EgCPLKYz5+!2{<I zoVI_xWcm9BZlp}G4*Atfb`D;+x?LxZ1PAV&xJ%=-1u%Qpq1CNi0Uw3zm~myxS0_h) zh_$iCn{R3f#Ed!QIC_Ty)#Db<Z^e-e-@U8ni%I}-{@jVH2d9=lf+H^n$EcOFaN`sm zha^{zP@{hv`&rYpC_q1=^z43hJksWzT_u4(E?Ux>HaW)vT$db@ojPm51X)8kYtBDy z8~?7CnVIKt{}xLM@Sgy%smB;&>glE)c>)-Wo^)X0XD$Itx~m>=_@QT+bLzonv5qeE zhaXt>ai|{SC=8IJ6f6AC#T8i`@Gb$jp+}8c<o{9cqmpzB#1OeY<ft8Q>e=Iwf5Zu( z9dYP^#0}frc~QzKsVu1|qH?OI9EYp{M~?6Qsi&R+TfA#LcEahzk9x=n^Tdb548SLA z)`&*Nhy)zZz3IZ~$Gtg-p+}uEA*wJ%IqyVNKq_6t3OH=|xnvuDz`@2LdFtuspS}9= z(4XQg`fH?-{7L5$e-eWS9*Z0+r=ARxxuzbs7-Wn;<oMH!QQ>k$sx!$t8&w{KW>ce^ z*hbq7sgc~F#}_sJDF>c+!jp`wk>2sAn<uELCpJ}8dx9H(R^62}UnAn`S92}P=*)0( z@dKPehYF{jsNzwlsQkckm!9^liFc*zLjSrF%>kV&rz+w!GB}!`qESbkaDwr}nsL}E zr=0M5)h{_+*_|mQVb!T87IgmMN8|9y`DY(cUL6dcctE8|Buul3&>?vIsWu{EHO}jr zYyPpcU53?t?A)3|=CxOJaUF@E*{FEO8<=WcS3hRksb>go>Io;x;T&SfpV^S0XPlWw zGR=_G#_?I}us~+DzoqYPTD$(PRHqy|oI=Q<k{*V}uYZc746MGb@gtY}5I5>El8st3 zoSG8X=&$88S(7TC{K-<s&N_aKX}v$<YNUSpK?@sf!W-#zdSaPoR!_6*h^)5$iA5T1 zHy#z&q(-X8RMs^n>n?Sn9xiFcQUCYq>E=DYdC7kcdBnDMK+=3zcho^*8+lmETrz|6 zdLt8~RK1d(TGU`C$pGX|_i4LH@6WF1>yF<3i0BcfV_0k(B~cZ?rn3%-nXg~#U|dkF zk)EQg>q_?`1o_HkI*l;IUWCv@J=9SXYtW-9|6qrz6n85PCe43d5fC`O5r6|FXe|+` zR6o)IigXO-P+!qTJ$fOHaF{4j7AeZ>OvR6MV55eWi4mbF^28#x5G*lL6cjsBk|Fs+ z2hC6iK_s`Mf8@p=kJy7h#Nm!NU4%*MGvS%wQIBS*fg1tH)<wufAw)URiW0#h6=xEl zaL_{&bD#$~CMYK~Rm@HUTK{7eBlnMqorfv`NMwsD7!`KZ=#hhq93t0n40zluj<b+M z*ak%?DYnQ^di*0GT_X>(An_9Xpp?;$@{euQ0~YA0M^UhoH@nFW9O;NfHv9psz{n#c zuan1t1_KU;RAw?9Q6VhpmOoz=2YM^KnLFOW4K+}sAMS9+H0hR++|<Joc!0;%>IV^c z+~gT*kl4)_k{fkUp%(NI$2`zEJnE$`SK90!HkBC?S4D+Q>|saT*6<y9kfod5D@s4= zaSS<VV~CNn%WM8I3qO=29PE%$NXYV!euM)WbBG2>t`vY{%%MD*GU)VJh)_SuNI>5( z&^0jRAjyg8AM(KHIscNOtpG0SBS)+UIzaItp~mSVM=X#tFj2G`QuQmXWGWt|xJR9W zb(Ja-D}X*(k4(H_97)QWSJr8XH`L>5R3)ler$(E?w4)?q0%I-QP!Dl%uOelg5sTzB z*5KUrCJ~iWQR0Lq3)&=+haJ!$qheI$1>mkG8k2k00F9OfC{6<kpnDcU2@n!xOG|N_ z0;lN7LphKhB)MWM6^pmQ<fRwr@Q0^-w!3eP2paNO88Z(Wky(OcAD4((6FVZ9Z^+{u zm`El#%Cfx7SaZ9%6)5rkL5^{BBW^i87g^c_2|T1^D0?#}JE$>Eg3K)<NitGBxW^EN zfRQ%ugo)CWRsTBf;xxJ5?M&vLa-QIgswn=T$HS@tkIYrnW*PBIBi7WW*wT+A>?m9~ zS|pQyp;i;H)mVF?kqbp4&UrjBVadiMqlM*8vA_hTV8HQ@<7opNJoDKst6{Qf6b-m< zH6lG``43~ric)kj@<eP*mT{bAA18`uM{JyBqlB>{THZ1+4GiThW9lYi`X%Np3Fa;X z)4@I+0yU<kF^5#vBkma25Sq~sta&+%M52N(@S7fXFe^&^pn?|{aveS|TFpmhG@s|p z<uF4;%k9wypUANk0JEbX@Nk@bMh6xS(!&q4P?)MDVq-~0V-40A;zMj~Ns}I94dJkc zmBP4<I{!&5)m~0YJ%~XJ&I&8mlQt*}>G273jH6OPdI&M$@v=(64!PaK3q44*rMqaX zAK0!kfVF!%yNP?!`w4G7gb@WaNJ32PAU9UX!j5`yOO^qJYXG=Gk2nA3$@P`=!Wgp4 zH$Z|-6D2T(zk4eh8(UfNp4fCGR<fnOW-7sugP`;k%)K#0W1+-#vH%tUSv;~}OVy}0 zZXHR)RU;^xVxXf)((O;&-~pO=^<Nh5-4}WY6v&*5MJlDlO6;Rjdi2PNG6V`=V&jz- ziBmn0N{?<7IErEQNFN#gkQAx$S-<#&A(G$_vosw~|5#EzAh8E{q_Hxw`G!CCkO_6@ zrvH<$K4d-M$0k+=NH)|+8#&}5>D#VSjEBN{)+^HPsmK8upss9(qtTLMNUXDv1P47r z2~)w#R$uYb213S@$A5IN5!Jb*ecsWWdR#}9h+5E6=(A8lNN}lNHE>9lyAN2<qsdoh zNH^%wi*wMUAMvQR&7@n8Z1jR3ulvxI1JjQHoTC>3=tev^Z0!JNrBLD}NA=8md)o5o zA2;%oIt=j#oA`t5ongp4Zezy1+IuFj!8^3LfvlfR6#LKKC31-e9^`=<hQKC7;$sL5 z{0=UKsIG;!Bk)d(PNIP-6s@+HNta0NgUVrlk_#*9p{1h1r0C3FtfFM%MLsglU;j!% z8|a}q-UyhULmT|T4;o?hCX8VcDT2O4Vt^tTK+K~C3XncZ9(KzgdP^=I@KS`QL7u7? zh)-j3PFbW&9;Bfc$e|i==_A5J`p}^liiTXE&wdaPGUTMpQlhAiubRX!ScXM6jD#J$ zVIIEWAHGH*{$d0fMrxQO5G+A{5{=IAN6>U*t^6VXsAW`$hb&^KY{nskMCE(_A?|Vm zYgCAT7;piV=`x~_ni?jU>_rm@Ve}Z{^b&_2=p$@6kRwJyPr_jlG$GR>=X^Advpml_ zGAHy{&<{SSA<`@c>4BkAus?*wgy6+ucyKzZBN#UV;i%|i1|uEn;S%<t9REBeR4~PO zP$2-u0Sy7Lz<f#;mZ3wcQF_*)Euyi?1|!_KZ*b&cIe_64f`J{dAzKE7c*0Mo7%(2f zg?`L}>(sy>$iW|E<M=RRzuEyFbl@Mp!JHOkZ=~iQY5@-9;TvLuE8@W@rsxrKgC6YQ z5$3KP+RK{+Z2K1Q5*x50Ht}dO;<8$hI{G2-WNUEbO{2OYOlpN0Wzo`7OOj%7IIM&i z{2*coX8aHb8sxwlTuyS5;vZNo9Aq&2q_D&4ff6VI1+~E_UkaG4LYOY1-=^e+a%>-B zVTmqp^Ns=>x`7{j=R&|?OlE?2dafS^qwcbZ$m*dI&_N#C5|VnTum5tS9+rU@Vqq|E zsXgurv9eA;dc+V?f<XwvABJEX$ibZ2kF)Tr9k}5Mx?wWM=CGE89-iPA{^5=);vF7B z9r{nU5`wQHk{;#@PX=%B%nGe~=(f%Z@p@wPn8P`W&nUEFLFi#j$RQm3pc4e8GRrRX zS|S+E$xZOc8p=U*PS1dhQa&sbB24OGCeWt#C_watPJRL*mcs?Nu_llcHrZulh_Efe zQ5=N@BErKg+JYXO!5HAd`96g!C890Z0Tznu#7>fUUZ)?>p%U!lF(|47Gec9DNFHM0 z9MXaK&OsTZ!9JwP-MUM$94a>cff}Ab9XQnNZsQONVeZZeL;ue!9=0(M4nZMNt%3Bg z9@O9$`XM%OPAlHQ9qwcs1kIrcVkr``9p=Fy5|o>m=iqKC2vt%+*Ch&75OKocJU%Y5 zBJGV%a8Oop7V#$ZXw4@gjUu?ik-j874s5ADFenCPEG|-Vw1FxGW&5&}C{FR!?1erg z$;MJrZ$5@p{Gl!6K^oPeQtBr@`xG3uA%~Wz$hyff<deC2Asq@e43mXG2(%JVMKSVo zz>s2J_|H|sWJ5Zn7_i|R_F+RRg&b(>9><D!J`=Fi;cD^;eAM9}%!yz2R32g@-+Tm( zEYK?jDn^lj82;f!0Z|+V#11sgpafFh;J_D#RS8QnTK@~mI7~80)lhM+Byv2iCsic$ zT&+$tMPnEUSE|&*)&S+c6o4#HPOJeZbfN<FBmi7-A$sykq9e6HX#3Qx1)XDv7-Aeg z4A++NBqcRCU~Vw>p%?n$Y_!d1Vn-gBh#$t`5)zePaK$Ws=o*sYRiN-BA!0E4K`eI& zDw&Z#a7-P1CmwiARSM)~%0Xqegbc+mBl0Op{><zWjX}2Y4LIu^=ucU81|H-MG`0jB zg2y3;r62;p4UpszD<bW3Ltg_(egfca`oR#THEU(|KgLi23rqzUDJV5%vjQaWc48gc zb@t)`@O(9vN=Bqmu_xhEczgmUc7aUoj?)@P#s5Swm?nrFv>{$f3Qm!Wq|PJK+9OJX zfdX%ECQ_48aPPMQKw~*p+bp6{^J2+n#o+YwA!dmlsPDP7Ya|qe7ksH_+7@rr)2F(S zA8PU;=5rcip&qc%EL2sexI-K94i4m^R^>red}^(bWY88>Bfy0K<$>*vCN}Ef7oGq~ z2&<z0jO3POSm+@W@Sq<k@({08Yo`Ztr4=*2(+@_jZz-ZEN~Uwd#-vg*BnITxbdmVR zH7ey~kkmJBkn2oZf*3l=XG%gP0^mEO7GNqy8~o(NrlJ!TK|bVGJIrN2Fr~LLMb0|n zbCK$02cu*)!lxv-$<%Qh_X30pR(01wWB<?y7Sdr*8j?UTq#sVELu_}Oj4dO~VmaPM zu#C1LHY>iUAwMZBBUYszzF`RDp&i^|gfD`5otLf%Yi=KN2m;{yqSsf7SRDG{&FBGz z*3o;7bRGR?BxO;O!hsMz;a|}3e2v0A81DxQ)_pOM25rzR%O+zKrXF@d4t$~{{6*eO zsUA{pryRoLr1nlfjpGz%D&nOPgRx(x1m>7XP9z0C!;nwgVnhN!V}fTBA*CNER_v0A z97%^BbWd$KRfD-=mI}leoPiwhlT+I=9cUpXF4;G|c&vm)RS@aT%z`1VrHH-ZA9R2k z*nuE^HYDbW9xNdciuj0A7bP_!HviOt9Mr%Ud}CphP)HGy8gLe!)RQ3SaJsZOYpr#Q zw^mA`6<4lg9R|n;H4lx`qaM`c9U76oNYXr=at@B6WfCa~#lwtEDF9N=#`yS@QZ7Nm z)FHmaN;D{5UD1I3=8&ynIpcVRyelJ$P8wpNQ>bkwut6I}Bpu43Epd`9Y>8qM1BsoP z9?$_6w2^*BS^=5JRMN89jIUO}p&I-F6V8E^sg2z5aUIA7-QECK-@%0DcxnRS5q#rB zeTHU-nMl+C7t{fqP<lAB1#I9T6U@%u_RCp#cQO-AG8jZ5=m8Htp&oeVro?bsugRPA z^nSQf1?^Z402(~J(lJ=d5C4wg1vQmAkJ1+9SkPW00QxxP_P8EIiX8s9>|V_wmSdsK zI2r_DaY2tBr0gHEWCN8HB^x;_IywL_K~|ipnLoBIWmg<O20PhdF%qLbwZhp%=4Kcq z9eM#8X0yVwqHQ)sR;CPfm2kI`=ylXkL#?Mr3PFCx#;G5(zv>FyCZ~$&;SDBXj82pj z-R>WF<BR6jA?A=p4UiWlBcHfu65s%OZ`3YkjGV{WsgsnRxfW^e$9}jJB~mU7$s+*1 zWSX?Jo-N5ru(BcMR|(@(rsiN9WKiYWwbaOgD9R-~ILIN^M6i*IA;RP&5=03d0;3wC z5m5Era@%9cQ9YkALjUBlh6;9f+7hE_ccYy<JUY4_FabeE`=#w?cc!j(gcuy!H!Dhl zEb3t!P}o(<!e<x)@b)4cqFJ+3aaFAcGr1)pm>Rjz%O9pWT5^X~-@!w}D@T8pyM85{ z%C8p8ZeaOz4&Mez1S&_H7Y@D%YtGv|)7wbbTO;gxxYs&Qoq5i4DoznwUKX2NSE3#? zfwOjr!%R{I`#~EVN814L*^uisCT7w5mOSV|Ix~pFs%4~xb(E08q(HG8zK_FFDuCA@ z0KOr;NjND$ynBeJF2bZ7_JJ0_f&F+9iFa!pVu9!sRex@#qyNDfl4074Dz&?^R^&64 zok63`!eZ~-egA!3mD>WkAR_lzx*t}CX3E(CWxI&m;Tv>7h~I0_7(^=y2nn2(9mryz zwPL^E!55xDHIQZ1H3(ZEQX=2ZX?JEh0)gQ0cCF2c8`NP4eBm7mf<f{(jG`sSxDhxw z5T(eXrpx9V7Myr)&=NZr(Am&m9?>X-Crit81?3?pa%8hG-i|qo0{L0MArN2yWvMt- zA|7@n_Lk9?s$Fy91qWnQVhbiBha^hEr?N!DRxut*;*Q0nCW==iS5n@!Pgr7TXiP7# zDdHLbK^nt>+L)b4<KY>PNiN7n3mF7bOhqNIfq2FZpH};~u)$O&<#k?ZxBPSA?OX`g z0hiG(5dTc5NIMacuvdGpd?<#w9S9KL!d)GuM(~HA5Y4GGP>maic=4Uvsm<vdY{VDb z0iZC{jfI$~*ms+Fz11f?A<iaBp5tb^nAbJ&Y2H)5YyKZ}5ri7OBHY7qOvr@58)zTn zfFfPR($p+hzdC?|7=*SLqXh(~6e8qor3!^pU!xwHf=z-}Pr!i?I>BcbKGl~IeEBpn zgl~cs#w%8*9)^bZ02EBuv$?=<3GV_pFeHgE9JjGzVUxib<N;=Z&a`KjiIQn6@%*g; z;@!J%|K4O`CypJv01O*4WcSb4kbm3Ov6Cmy;ktG3;E}6$=+M7!^x`=@i83X_jTqa# zYyUQ+9yfRHR&s<F;M<UI0o-9kxp8B>c<kuaQq!+n$Dr#lD)d*6nJjPg$o<2}bfe9z zK^4xM2PsLQZScg&W5-o%!?f#Ex=qOyqg;9Q>V=~>x2?vY|Nd#C=Vz8edi35hB;3~; zLu~=BW^~I^-oJXg{6GtL)^Nk0?84<Dw9P8Ue?@cov8JwQ;gg61So4!BoJqokNqhDa zjvPCG{%F%<*N>f`T&OR~Qwx;sN6pMNV=PyWUN%tv#x-8pydiIF_4Zw=$L||BtU+yJ z1P3l1EpYxAUfr9$A#{F)uhk=`7WqlGbo>3Il@2!G)bkih=V8OoKcMV`4K}>7rT<@i z5;7NANA*zi1Uv22w3c3dz2grzYBci?O?zP^5I6rI;Y&YeO}JlBE%`%DOyAJ-Qve<P z)6Ed<a0r)-^0d<qHEK{(;ydJF<W4*P;35STZcsyyPsgRT)jEW2L|Q$7wBd^(NI>(? zIR6l)5La17n4Nx+1)wE8&@uGPHUWsX<YOBl#t}1epmyeJZ|OJ3EaRv%CuHkD$4))7 z$Wf0qeG#UTQwpJV<~D0YqfP*b^-~Wqa{x*YJaaXM7(3RO_D*WPk!DRWboir=I*!rx zn>yii0-8l^Y6amxdcjCxQ&%>~k9XiS$Q!ZPl(SDS>GXr%uf}#mPcqj8(Em?7a^*KH zb6c+Sm$u*~su@?{Xj6|gu~0i+fhj@P4?XAfQqMT#sYz_Vnki&qjrD9uo<n^FAPzll zWYW({Xz8U;iu9;aONlx9%TP<=6g0`e?kI$!IQ0}FQpQ&%*OE8&Jn>6E<G@p1MjOB3 z<2$~np`trVUI{K!a{VJt0C*S@z&!L&Lj^VKh|DvD*80m-s`W@hhaAk%<KMn|MK);w za%dAArG}yTPXP5Wgi`?6?Zs3$;av1+q>~Do(xnjnQw}t8aOx>Nq-jG5CAkIa*4j9! zmZ~*@gN+?Vi2Y-YHEUQCTmV<*=rl{~oQ-jiLdCPuy8pz2j(85XC;#Dg?Dis!c=0l2 zGH=@algv5(^aI_+Fz!hYyXPdsEj)Og?0HbzA=pbc@Sr!;TgUGM3V79K-g)(w%LC6g z^w<H3KjHv+QeW<f>_#o>h|`Wj=E?JpJN5jchB^ex>#xT2?D2>{^Zz8yI&WCwu|XND zN&moKm8_(YCe@=BaQMeOyx|XDz=0a=(^}7r1&?vm0~c?|NdWk9p%M859-zw{>|(?w z_@J;U|4>IgG~tJOL<2VUP)ET!^tgIF<4?9CjP6h}l+mao8hg{m+E6B!Z`30&^(e>O zes~gv^d)b9B1ZriHN?r4gE#e{o5=#uDffWUH|$V{Hso-O;{VL$an?A79JT=wD4H-H z@Zg;F8q$|M_GKOGqDLjrp^gR-i!j(=7bv7r5A@_Qe3Ov}RC;ladVs1P2g4X|mX!`v zNHQa3dy5|HLP%_QhaTxbj~(B#u6iUx7XC1$9xHiA>-B|5|4>8AbOslO(DG*QpygyJ z*~#`jNeu|$kl6e+OO?H05<_~&NmLdHOK8ZMhN;U4>j9I0c*7lfY==1f@q}im14PQq zL~5GVNrSzTLr?I9$Ho_cN9<u~++1WjW0{hJ`K>diK}{BQBpE%rCr~Y<$09Ug4Tv1m zEq$p=*}|cTMXV!?Zee3R<gg1@mE)8QE!#iBVGT5v4gWFf2q`q8)3<OL%ryZBMteZ% zH(k*o7?e9nT^M4Gb@-tZ{y39K7}*$sHf9~d3cxe)xtXSM2YUPn5IEw2y7(NgALzhD zKg4sxlOPCs;9$su%G0mVr3V!0@JBfe<FmQQV|LdthV;5>n4y?58?dN{HXP(F;-wI& zV_Qv2=;4be{9`5@(w#zRNevy;1ATY_mq7mU3&DD$9Z<xW$PQ76e{9HP-t-3?CZSml zS!*MYZH5~7VIsA$V;l7_NI%Hok9UM)fp3ThH^${Oj6kIp9fadW{$Uj)h|@|YWE+;y znw3-$5gPR<BSaUWjarF~DIF<eNSOi5g{mYgAOHOaMoFXArlqPJ!SF*g{DUsT{KPNx zAVect$S8KW(Hoc{+({fq4>QSO7IJzOJBWCUpgG1Ngt3)-*AWh)x(Q1{;wzlMx)B%N zs~+7r+g>%J$V}Fw8mG%rv%t~RON7I#sJk$7f5I+j7-JlF{i+J*0-a^~BOS0PWrx)( z5A^hdAHCSeH%|Aa2b<Wz1oo>uxOtQSa6=%N(@RUzR}VP&VjYx~7m9rH2S@;|%3p*L zd6vSBiR`bLHBxeF_e$D#a3cU}$OO>NLX!(U!A0$0NCnk^i+VH#w@$tiVLrklJzJ_M znRr8)%AwX1CTC4sQ>l=X`<oXMLRG1WM*m2Uq0coAuZ3qMMmXjsK;CU+#El?C3kS2B zs9onDrrAcV5~baw=IAee(8O<`<HAy_gSGZ`$XqnY5a^7njxfwuJZMv77cQa^@OYbQ zOqf=VT2FnC)*vkQVOGgddqRoqhdO#p4s4KT+YA9QR~=$EV!@7Gn@Gk#m=#sk+AU4S z3c!He<&V44Bi_l`$VT}g4@lMn$X%H?k=wM66xD-b^hh5&hQgF>1Far`FvLKjx{<?f zYzWj~M|H6?<R~5yZFLMYcI@Vo8darz54lv!Z2}^zWC9OVhR8cMwy^V6d3^t1U@xnj z@k<5Wn+tS<i>yQ%Z~lV{;v`bK<^OGP!#o|`Lgx$Q!huGj{`nuJ2Cjnjf+kcQV^rbz z>Rz8t(vVsj)h%ZVcn?|}=qS2FFAu<7+)Elpy)cGg6PBYj5`efRn5e+rdpXA8Lp{Z* zY{yu`J52Skc}u?P8`0sxgUX|NzyckX>s%s1SUVOk5+$h&z%<T=jaU<_lKkMuf|ljU zS00QptV<+Z<1--Wy;Z1}hf(`(+s=kJM`U<_L_K)INTRdsAMoIJ^#~)AiKvrEHS)(d z1k#*Yx}!!H4?sI2h!k}+t0(UGhCg&5KPQcTpp7AVG|vY<BGDrga2TKZVR?C}b;1wP zweK$0kS_scQ#C{nFw{FeHUA-rV;bSmFqL#Lfl@}%um;;OTYb|U1ww1K);C1~L-3#& zhS3-CKpAq7Uzj&r?xi-d_BayQZ20GZvgc7(VR?MTCGQ3f?0^ojU{|--FX%xZ*KiGi zR9OK~NTY)e<<KBQI3ZerApUR(>F{HrW<35NAT*W^|9~Fx(H9L;53Cap0>Ur7*Bl!W zXYjLS<fanua5P9DCv+5X8bVvvhkbXn5gj2JYTyfnL2ch455<=+QaE(;AP@Lc5A)Ct z1i^7mcXA#_agd-6JOML}78#wT14yEX7%>#%)J|OlI}k=a50)-{whr~O2?*6Gq+uJd zp$%G>YKu}1E;I{sK>rbbGa;k#QGlTd1V|5DK~l>VR2`8Wzcd-U04b7EQ0`?{{t;^Q z@F@9pYzi@3Yj6ybp%R}mc4Pu=p12Mlaa4R|iw*J*(@+U^bz{VG9_euj<G>GHr5_lP zgnvYZ;zmDVwGP<uLH<BGUG-Bj!f4Ne4!r;mrNo2H0gl%o3G^^Mb0>z1l4kON3&b>8 zXqXZLK@LN37QiSZB2#Geuw>L^J#`2V1Yrn)Ko1Fl9k)d>n)P?dp>gy834fpt-ar-d z1T^zNZ3>~09rO)LA&KiS6d%D`{_t@7s9G9i5MGxR#&tm<cOsIJMcR;1|G*n9R1bku z9DJ6Ek_I{WcmILM!7cq@QnM2%OfeLVQfwpEYvQs`M6?YFr7G>PDfsmki31x6=64#j z2D@-JP?ReE5K)I>Urw_X+~{Bq^==MAI`kkQ(k3CHln$3bO3T8PS9CVf!w(z9N%!P0 zgrSBL211O9c|rAg{?H5PFhcXl96s0&m%tC&uu-qHkeXqb;}d1L@FO1i7VM*DNU#k< zK@W8SoP{V4M=@CA*EyBM8|GJWH>Vxk5M^#QhAi<9DN+y&QzTD7CAicOb-{B(&<&2% zQ}@&tBcw!!U~xfXQ$NuRNKg+x0h@gFf@Vnw<p2+T(R_&^fmivPz?m5JAdPs@P@p-N zF{KTk0slvY^GgL*5AL;A?IAWd)lp>Ac;(=hiXl>}F`zB<4?7i=wqY7zV}Y!(PXX`= zgb)s{;y3mLo3BI{-H24<f-IM?4K`++FmgNr5DSO|dodz{=l}~j!8;$h4%<-=|M(B< zI36n$8IlP-{Qz$hLND~N4CvsbX19{D*&$3KGDAQjc6b&;sS>n#2zyYH90D*QDGzT@ z3-Uk?%~L(p6_Wq3oC%|w1OW#XQ)k!n7Wjb?so@TQg@;E$B0+<p*CR}X_&xOIGr;u^ z99JsTh9>Or4%<*mxNu~|)stbkJ3(P!@AWp0(HFB77~4o5lyY?#1xD%B9E5?9jo}B4 zaQ`PA5kvtM4&{JGYXfUu6eDCqM3Ivk7K&+w>Ph|J4+m9eeNj@2Kne7Kq9{R9^uR0P zAYHqdjT=FjL}sn@&{jJJ9d1f2$D^&7u!A?m5=Ghz@1QTlV?FNJ4g3HL*<gE0*%rnE z4kXcT16PhXHWzi2gQHjuuLD+CibUThLEL~n@F0;WF+TKQ34!1}bXR_jN)7Udnizu> z3j_zpClDF*K7xfl7NLYmbx!W{3sf*7KqHh#L|X3iklIvbd7?lJ<PSQNBevKi{_qHa zV1HTlXbOpNj}s2suqk`wcZA^|i$Dl=(H6d`ht_aWyAW(=g>bxMDKiud40scf8vi+a zgQBWeQNIC}%34F}Ko67vU175tnt2#0+D32G7O)ag_aUqe!A4kj4AaUV;0bXzF@s3u zZ{^@0*N_Z$HFD-C4_s&r#;`8npi&!Q9bWY?L^eC`+C)+-ujc_aPiSM48G8x=j!(!B zNvN&@%aRD;l5Zdrv6UTWQ3wu8s12br+~5yf+Di$GF^4q|^`HaXKn_G=A@HMfwyRE< zXLC~78)hO8-r5iqRIrK|bQ%``flvtE^D#$sSd^7mCFyV{q^V1|c&f61osxKnK@V<Z z4cr8ZK@|?r;0Jd*w+Wb{AT>E?ODUaVwv<D*x|$tk)CiQ&LbhVIjN`Ry3;!npa13-n zIeFBp#;Ag9TMp7VH*7H!yx}(1!9^~LPYvZn|8Q;gW<C41EFmTiu4FLlfOwnNM3;vR zR8<K9pbg-lwwRYkxyK9jU{(Uk91XG#D(1qem!dIDx@-FpfdC0rQ7X+r6Y9VX*hwU3 z^C9koA>06HK$pMJ#5lZq8sa2LbEzW)S(25fyQ4PUpc`&c7t}cfzR*j*IZ(6I4)^m2 z?Fl{(K@%i#r$3UJ4mLL$%AvLbp_I}OjrVviSQI7N4b9pwhUv7LU~0G%9cRN1+5j5~ z6`~XJ5B*>#lrXmcaKD5cdu_W7{y`cNs14C@7}5r`OC%UY0ZeHul^ro#bz%QSW<z9o z5dcr9NI)DPXp(UCfC>W178O>SBV-e?<ZpK&4FGvpO%@kxB@aLt50@Do`kNAS(GN}v z4(fmomC#Dqz`a)*n>1k+L$D3)V3UQ55((rEDw2q6d?mEmy7VwvA#1oqvJN`H4maWs zv9&=Bgg)?GJp!RbcUlkcpr~zO#oVA+<nUPc6sc?M3vAe?k;oRE!#k6441!>3tT@rC za!_StU!(!8e!wmH+c{`rMiDj1opdIR7Y>ih&u_sPn&54a;|DYaYMKE#;{Y3?84PmZ z4h#&<xVCrn5S13h7ml(B!B8g7C!}(vM6!?!{16T|IAHxUtDsUl`4;~fa`6$&AT6eH zD%Ddk<<NRP77h-QzG+2N!m}W^qpHj?7raqnw6G5ZGSEJIaB5-BvRjEw63m4osTUVc z>QKE5(Io6Zlj!4M8bfi9&^`k3G0PVK{%{t`yRK@r#<lPSGBJmfSPzg82pYRH3#D61 zf}N4=580@0aY9u8R~=fDD)b-=xbbSwOd9YIQT`;+KItt&{SQb>VHpt}jnD}7(imN) zh3gOv<pn5>w<D2!UvkkAF63V0Kn{2JUflxCVq=yuBq`UE)!5Thl5hh{Fb8u`L$=&G z$0HBP;0)UE!Y$ob^HC4yundHo752!&@4y%fW<6(>4rhZ7@7DhwPGgVtFb&DDEb>@C zj#LjocznE}HKdEzKhh2uyI5StkQT8J^-yR95-}iBJ_F-$NTqT9010kT58Kc_+G9&D zgRta`Plt8RM<S_S4U*3J2F8~Vq;W)+!p<a#J_DU4P!kj%QEK-Q85wO2?0XDq!#fc; zfuH7g3vMzHagFj&E3qO6-X_xYsD{$m5Ar~aEjZQN6(`c&2nc4~liYc3QI?Kk-hG!= zeIYW0KnMdecErHBxqUqRkfVu|ul}MC_3}IZ&<$#_9o%xwRA|~vSu8en4#q%*7?%~Q z^ADA9dZN4FpyHzxW~Jalx>^bkt?NA)ZrmxcF_3_|vaA26Au<H(V18+XR5?Nq@>G)T zBQh-GGCQ-7?VvJGfD6+p&<_LQ?C=J8m_D7PJ4}*364Vcu*fe%sEaZWB`&Ae>#76WW zjnt?bP;Lzy{K0A48P+fdgn(0YKpdLfn7`2(@K9@Yfp?Fan{qJ}eZkz};DMXcL(q&7 z)zv9-a2b_^UtMAvoMJ{;=TbB{r13b*^&pTHD<SCy4&p#o>!{6oVUOzo3LoUb++2(D z03DYEEsz-=aK#oIwGVX#Dwc~eMOX>@VDS+i#6d?uc3?h14&&v#;SzKf0`U|dGXyFE zjF(pr^5hTOFthJqBuF9<jxOjLA~J?x3BBtMOu_#}Fd+}$^A>r1eiN(C+wAmiF&g7A z2fI)<CuED(5DtWpi|Wu3XwnZ7xDDWbM{*%a{}2t0AP9@F1ccBIBUU}oSb&63pRd|P z!u#Czz6Snq7n*WjWgg9E@$b(t9)1^bB?a&&`dV=AV1EmG=RgnN5M&F!5e>o)myiuk zdOAO$&6mIs0<v#?y_s^dMe)dE(tw3L$Q2s&kNE}P1|k<XnuF!=-aQ+zVi<HOf&=}) z4PL4iy2B=C^9%Lhr5bcISm^v7Uo2{2hw*@&`&JY5r^Ivk``J;mx_LB1pg+~S5!b{) z7yjM8mb~$Rc!qEY?9lu+9xl>8??4L>x%~fh>&K2By>$uK9ZVSD->d-jwgm`qP~E>> za_WWq_mAR7kRe5iJSb0Iym%+e)gvbBShxTt<sBSZGvq;b?84D&L?~W8KeNKU%Sm&j zOnK$X{Zr>|k*00do`&n!&!|a|2jRgBpe}$MXiGiDOj=G|JxzqvSxfkDTe(G)j@hJJ zw<9=k{QmViR}Y)fx`89sqX-ULxmf%7VZ%o8AU19FF6|qKm#|>WAM4foCoe$cUedm4 zbLg<+zs>agfujd&pTB-91FXwzlQF-2mC`XjeY*B<!JFUx^Q9(dJbJ+0QGC+upFh*$ z>fwR(?;E`2z%zFoR}V=ub?e&Is|Eju9XEf_wXgRFuimdG|HQTH?M~dkC%yu>dl#5p z0CC<aFDH2X=?J6)*Zb(8fBLaTlSQoY3a|y~xkwW~>apfOi~b>`5p}|mXDkJ4nyDUk z$T_GUuRJSpq-f-bW*0gntSGy{Hv7jQfvgF~k6hU4XE3@p3qYq%2$={q&Q8;Yo}kFV zE<0<ikprR^MM_Aie$oLYoo~R&GAo4EVT>MhD)EOg$LMhnomlGOr=F8ia&gR%@Crbh zSo$#xs~ZzCjGlc!DW@B7<oRzl+O#tXFMjCZs~&O^GD)FE@ubUAq~zJAo;M(&bSsJg z4XmB})DT9Vci_oMx<Cx^=Q{s*8q$=agi!j%pCPDGN1b-)sYMNSxFMCSTR{T!o#Fm@ zqZWGF$tfpP>wyE8Z}`JCQ$`b__P!yU+sf1zF~uoFIfAjKBMK8T>X<p8p~oYW&RT?! zjn-K-*#$47FiQsesfUhTj*){OcK#{p&X8=S=^r2EI3^lDpwVVTa<yECU1sEvP#u#{ z`e&VTtUN{?gXV=8N=<IXw4871$p)5xw81801x-qiF?r6Zq@HT9Nlz(|`Vrb6hPcIZ z%cb~1Wyk>1!*u7rjB&=V#>Uin&3evBMoxO<!Ia-k6+-FN=`vAgSM@N<X}N!Dq2eQx z#G!|}dT6!P<#lxR&KLiB+#$y!Q7cuNY>=4chMqSvVP_t86lJHKcc@W=ntzzxyWw?A za>t#24td0#cHGHnYz57whn=+qQFlTdMOsS^W|C9bLV7-2XQIOq=a)g9=s1RuMZ`(? z-;vz4JsNH3XlIr+)QN`O*hx|uo?!fl=Awfb3~{Q9P@+gg==pv$vP#fd$FTJH#jDF$ z(kTa=_CGqOmjJpM8Rw-lt)~}s5GEe}z!XXtBbjU%Eo+-A5k2aW4ph`*9GqgH??7TJ zW(9y6L-+?dT*N=R^d|ssAcr^FAwFt6L2L};SFYk=kXpP!9^zPBuiDWLeOXXh^4N-s zGJyx8Y~@w&@CE+|x$(IQZYv@0SPm}KARl*Js&~J^R6@>zA%Cpvb~ahd9BStkhlImQ z(db+fb%>{PSz{I|m_sx;vc<Y6FCpRZM<Z?^heqh6O>|+9Tj()|T%brP<#5RCpaG9N z32}D)OUTZ&u@`CN4IE~yjjguU4S(<g9RV;L(E^Z+bNoYp3OOT1u5pde#DgqIi5Z;a zG(S863LM>_M>1sLk8mVPY*R#B#z036DvV=3;3x-DGSkGEh~sln1m-txXu*)ZkUUSM zAwBZr4{0q5gk)<6KXky98+IgNkO)NHjz!7+xZ@)EiPn)S0-VhuWsYd^gISWct&!xy zA%pu!jI94r8b*~eS$(Y1ET(t6ZGOa7N>K+rcA<%5NGN5P>BzdG#EwClr5>}G1H?+@ zBBq2xpPFjqn#2SOIqB&}S#n`Qy5kyu)X60M_{Sv{B$G4Nk1)xRVsc&@KyVBYdBE8k zHo!5CLM`TK_beq+I)bWy?BNmhDBW>X`5S)fC!Oq|h7PFOj)Veib@j-^8`j|s4L;$B z?bsvP00o%J4Z$De=#S#+F$7<{BUm`KNkX>rjep=F6a4_0Owbt^7y4}uyI{vc!nVtg zf}|cDlc+<gv<4duRiHU@Q6E`^9F%DGf{ta{W>`cILax*%1f|E7PP;mGAgvLLphr0D z)LH+oK%<50prhC5F{hwjm8INTiP!uwL47rd9<<npn2hOG7E;6=?2Bnxssf92M1)_D z%8NWev5x@glBs9p6t%qJ4>x22n_#Vzf}ph@=@jA+|F~gTIct)^X|)^mumm3b;f>{N z79^;mhg1o}AEE?64Zgsp6#YYAclhE7>)-~ncFD`WHp-ILsmB_2L86)%1suAKM#4Oz zjqGi&q16+xrVdgL+ksdxs4K@#9vj)!s%$3^Ssg+Bv4&$P>R9+3Qx$0gj&w+-xkuw0 zMU=vhdY}Uq_2@=CNCu92$RZj1_(nMni#UJStf<(ihcS!+4lzeJOX-QsDaXMNynO%J ze3EmAKY+;%c6=@;_N~bqV#37xxS<y6m=B*7WZr*J!52`T#2yIEUICk=9p0!%APONL zX1${xPW%Ue4NZ|7szVLG_y>O+tQ}0r1j@wFUTv%a6ir;lUQlUki*4;FzWzoY!H@$z zw78>k^k`#4R&D>dOQ`q-fXO7)@H)s5<zB=CxfCIcF+Q_d5Q>dz>9_<x;CwSRbG9(h zCdZu0(O5Y%+gtUJFgv!fqns!xz!aH>H~s;Ksm>?fzB6w<6n&8X`lHa{?xj3#NDp7Q zq15~_-6Y;XkAc@_()ExkJ(zVm4A&&pGntn<NV5p0r~@SxG|IZ>FpC{A1up-Z(8iD! zc59gHn&5oQ2*eI_7Fqa#D(WD%v-u_{EKegA^srgR*Mlj@)FXXEYRn_AfeF8eX|tE{ z2Xm8Vk~y97Gcr!rKhV66UdVz{^+26K74nbn7(!Ol){aLg_YrQ)V;<jdgD<}7P93t9 z9*4LzJ9_1&wzU{JgTp~T(qkX|IH!JYW5-th(TpdsL*M8=x<b77Adp`KXPlzQy3%qa zrqJUl9}{iNO)u7*P|RW@+EF-0k1`5<dOKdnGA7QURDseXeQTl!HpY<*X<YR(X7@+e zlF^TDIAk;ZSjQ#6^cNPRksjdq#-8xUn*_DEBecxV$g<Q9^$@1`5)S{sH)bNx<<O%U zR9M>(23H`M(<3D#tc3*ab60A}WAT}3&v_Q?576Pd_0SP^h>>W}qQIbu<X8j3K#g5k zgW8&n)0;rDp$U)kgHCW2hbX``2nU$JHhDm^e(1K?NG%=0hJUacc96P{_&^raA#eGQ zyl}p6b2gdjh22=T?FzxX;D_&GjIwJg$$^J(STGjxz7m;-%b1}6Xa){qI}4(gd59Y- zIEW$W2A<=JTkD|!fCM~PhjFMgYCr;R_y=MO43touz^V>$P?U7D6*zP(rmzOg+K`D# z9>+QhUel0-dB6bRh>f8@L6kn$(FPz95{GaoIdD9#lRd;*2R8pRzIZ4>9P6K*5fg3; z2cu#PZrg_42&%x_!EHI9SU?ANU<|{k2T%wgqjJQ|K#8pg2ji2IdYB|qDy6p>54oua zWm*rM_z$##1B$RW!BPjqsYFeYqRlV}HE4#iqLg*e!bsyGco-Z*2n6{UhvdKmdN3A5 znz?NepZy4c;^>EOxVU}6Ln7O_@j(kh_y;d@EED0l*{}v6$&QS03@bCbLF`Anpom}) z1b1qv4+#<K0SR%u71bcKWVi;fS&88zo7>ojOTZe6@S1uUl88i{1bGZ>z>P~lvyY?) zV{piwxC|pnmXzegFM%^G6TrL^2YASYJ$Q%t7!xJL155vq2y5~MV-zUU;>r9l1V~sL z_|v|zcn3REgKqeSd3c9w%$xm_xOV7=UNJb(`HkKP2|p@GFv`A>z==O3giq*-jq0d3 zN=biQOYNwwHHe16Ig1bZ!w?g$)Ttthm=otChZ}K4%rJ?GtOVSX2fk1?yM#f7fD~}> z8gQtF2l^780mm1SB@_$|>a#`KNVm$9G;#0;Dgcig+P6w-l=^BWN~?le*pbkRzGRdM zUBm%H;D>EM8p&+3BLPNv&;iW(26`BRYUoJTtO+Tk2TOw@jN2R|GcqOOt=ypm7Ac!H z5fXdM1$7vQe>geh;zzdJ&XJ%)i4vo?ggq7$o8kW|DWh5kIAI6IC=kvoGSXU~y!eM? zaE9`mlZL#uG7+dT^AcgGhkb~IY*4E7@Jqqi8c4~Fe$WOnv9f?7n~iISd02;k3#Zz= ziO2e!dT53Xv>eQlM&AJx&v^%K2m~(U56(bF3$hf=FtB>C1vr?Yc2J7v3JlM22ZW;n zs(J@0LeAt=&f5%tF`^CRu_Sq@hvZ-fYY>QV=#DvvwOt}m?)1l?V38#C13UDjw>r$b zq?&rLJ#t`-sZ17(BaLM^hXAMwNnu69vo-Ge2Y!HsUeE`0fQQ&f6d_y*egHdk7>A?r zj3C^><$#1e_=gG;p~|x`a#*kckeg0JmQw$EF?R5VzzK(yfJt2Z59z3dGnEHGn6HRy zOL};>XOSQuT~4HUv3VgSh1rI;gqjR1yMF+(i#RzC)XXULN0Z2jod^JY=?8hhK#4-0 zgwzzg;I?%5w)%n6uvD3Zh?!H;zW~Sv?NTW1ls=^4jdMr`cmPxNP*xh139CQ{l+s4k z2*qTv6)yC`PAiJww24z&oIp4PdU%9A;6=95p-w4_@*^fUu~lP}htK&233ZM=$OOGI zoye(Bq+ph3D=Yapwb6<}ljw-gGSZH#2TGs>yb}zI2!N7#OL~9?8Ig@!Em^wA39m>C zw42UwU{{eC))L88jDj|4+YxAzoGt%(pi6iTIkBlUgSjH@4Cv#{>M}b>ToW=24Wf%0 z0=mT=Ob;kqu;;MZ7ZD<V@C7RP2OyvZatO_IG+Ac56trWUiogNEISGGdl(XTgCy1Hj zY_{^67BT9CCPA&PFvMIqH|>B4LeK<%;5Bz3tN`#(uq|A?tHX?t2kWfR^^l_Nla#*b z2XZh$9Xb&Iqy>qnhfTPK1Py=z^42VI)fO|)kIap6P*6bm(+pe3Tf91Xcs3kB4}aJ* z#tjJv3l=J<g(|QPJ^Nb2Ete`X2w%W~0GO}FtCecCU4xSjzI!xsahN0h6?>e6B}g(D zn?oQ$kr_K2;_(N8P$!YQt=j+n-Izm}@zDm3`UgNvQH4Mn>~M{G@CQ#KuOs7!Wxxf5 zz#o4pHu42tlz=gQ7>7yG2C3<s@x{YT=_y&ng*T`NbOc?B_y<TJ$9I4n-|gSKjKTe& zhBnxtwEd_XVz;cFydM1sA*qKX=?4rkiyf(ln$x0}!$SsP&ROsSe-MOOFrMQ@Q4FR) zTVWk*AOu<XqfV$Tu(Y59a)vW&MO%vuGh>bMsXip^;W1f}jPwU_t;G@16pz?S5VM=& z6bDT)5+$UFZ4l!FreeWh3MR3w?6B0@u+9Z@*^%gtP;J%goQ0Y2h!;L$%<u|1*o8LQ z5GGOM?Ocb;(23c)&SU?uTM5(>mochzsDuEGOk1l5KB0$nh=pvh4$3uTu_8rj_y?mJ zpvuEIv>OL<$WBRX2Xz>NamceMN@Kd9hVlzjP)4<8gNJQMn&ize>l_xeBTu{pi4YND z3wel+8V8GtHPO`$LLh`Wpoa;f<y_vZA<2a~SOYq+kULDC;W7zLlQKDh;NLKeB)f!d zpvVBot_Hp47kM9gm<&pR*v!!2>SPj1p<VDRj#=?qJc&04dS`fMDL*ad5_y~ZP&5d` zI5HU-iU|hVSV15Wqdex2^>9^`E9mW%B28n4PLLOhZP#!XC3+~+%jk?;`%rl>ssP5W zWS9mc{a}u!R;>S+MWVImN8IAgkcB|NgG~sQao`HT3KdG(!8ojG;LXfmu8VIW4>wQ; z6LP~U5~6zGwRm8Q*vMFG2w6WkhU3u=AkGC6*ah=d>OoAJkwKbzfU%`usR+iD13`)R zDHJqglo|CMlrV|zxCV3Rh2{!?almV9zGkFAvwDbyX+Sg9fUL}55bLalKyU*~n1nV! z0tRyoZnzx#*e$en(59vfljxy;P=op-2Xs@2O9_Bp?pq?PsAE_IcbF`XK^Ptmu~hXy zi-x1mHa(i~4E3c{`HKfQjw8$K2ff$~f8YlL0nESH6Qs@SGg6I+IEP!f26sNn-lih> z3}67Nhl~Fy+5(jvy8)&{V3lA=A-i*r4I(s0-ER245o(c#7}}9&+8c<ehd@3O2ZD*9 z7>B8N=GrI;rnunv);{1?KC%l$Kc*XzkfIUchj$>edME~HfCi(AYrZU$<(?nqv9-qd z&q@Zj1OJUn+~j?L2h^2J<w3gufQHNQ6xIQ-`j!rQ4S>=q@$E*6oDjHw2!ubtG)0MF z+WrU_6PQJytu=Tjf*$bh(eXjFRgWOj&KL(i#fEf9hGkd=Hh_X&SO)O=hHqeQl*R__ z-YiZ5hj8%3!6`i`uZg^o2Y&c&ZCD8VT9nG60?aX?2Jwe?g9Jc;2mHvt0MOCGe)C(E zS*8CRl2Mh8V$+F?r3y2|m1AgvSy%#*zBQUgbm+vjs6mv7kOn?b26He6bbt(WFb7!p z8Zv_hP<RIg9l6lHON!VE1)X9}|4ULXhfR(osq<BEB!}V~0!{*~)98=I$&d0NRCCSs z&z@~Hz=ckmH;Pz`7q8pZ>4#{zbV6_w(TurGclHt)2T*TkXNUzkoe9S12BoS8XNYNY zK!tReuJ@)^_H7d)gjsRVFqnZ2{K*EXvvQH(OHTR-e3R-ZLKe5<h5#Vmdu{T4H)NTG z4hQlxXdQ<Se2DORWX~la(<*MGjrht_5Sft$Pyhve=!*dGHY<;Za<FpVG=~7l2Xp_R zW;#h~h_}sX5_$fkhuc60URVZccsGsv2xtfcL*S%3xvC`^havIFapd`e{`Nwrh`N)p zMhGJoLM=iH_wt-|sRs@|h=Vu?0Dahp>}re)?g$CrscI(Aus7U=1c!b=2Ytu~C<uVD zuL&xkf-<DGjpWL4@Q2W%B87^3?i?9}sD&_)0w(wb(WR-aaC5}}Y+_&rV&DhE6Qz}) zTuezAzEoviibJnAe2%YtWf|;9nTU_L{L7CCiV%i(8*ITC2gym8+8CMt=wj6O$NxC4 zvo_;)PVjo~$5QS6F)^(_F|8N_{0Q!i-f4&g*~(ICaG?ENC?g~otDY^^44VH6#JWh2 zpac$*1`Y$iRrxdAl=MI&*%%|C*uV!4>(3HDp8pH-*a3`xv_2eyCl`PS7Y-i0a^(mH z2(WG)xr70x)eE4_A4P`=7a|N0PMf=Q3IBnM=kVXUgyhHxG}x~nJ9Y^PE?h|Q-8*^# zTCPlJuq8!`;J{rhDN$R1WX^zEOsX_tMSltVEsZL5D%Gk=TUrgEt|hyL3FU#6C-5iD znCobQ#Tvk!yRY)HDy2sctihcw9oCEI^c~#30l=M9N|CO?a9{ncQzsBC#g_2KQGLe_ z+}NK;{bHty^{qmoacxGudzGERgoeLL1)KS%Xouji{i9lrUbz79I$QtjYVlp$00swh zUM+k$@u=ZID{aTGVp42O`37(bj^6F0&;!u>wzT?f&?JQ#l(&vwKYs4SiKFRnoH%~t z)`4A@(<0Q1AOnbd+V@{<r^pks$4_wsrWTx4a%EMUI_iug7d_;3vmilWHN=fN21-Rv zYvpO^TWcCcM4&_Qh!j9Q;C#akH{iIWA%7MjgknP7SVWF?(fJeNR3(boBWC?r1I<WN zmDA0KN_mCjT12e{nU6|c7eJH&$kPyL(A77NQy4zkrI!w2vtB}%S!7Iz{?J2aKR~@k zm5xh=7!sA@dFI?t5y1n_o6J#FQbS~BcA0>0epx70BvP4_JK+Ct)=oPgIrL6DF9y(# zQ;BAFDPA-M(2zrq?&z01^+e<jss4c4TXaw&XI?_8CIsqI!4WE}p-=ups&8;<(?~)* z3ijWvQq_l}rUB3x+px<ryOgrR>gSMv3H5S`McAA})ih2<bxlIcq_d7km~Hdnv006) zOtb4o#Thpi+4LwL2{CizstL6b03ymBm=q`d%##ovLDcaKmsN$~7pzK&14$BX7(&l+ za6y|C4%jU<CA*lZlh7J-Xw|V&+h`JuMb=QVabKrlOr%A*)MKy8DtnfcFcu|4V^Y;* zwTyG=B!gN)=mdaI0HByS+&<hU#Y<9{NR`MkgjN+BEi?abtlFzeDJz3TRP!9b4i3pe zPJULMn^3?Bjm=b2{0=D2e?eHpbkbI>J)}}Y)I#-CZtOre)=|NYu^dTxvy>(Q9Aom} z4v}Dyve2;XH_Hy${W!bDTBNBy>Q+@BI^cW`4m?E1Hmz$mMRNC2(|T&rHs&N%n^KP4 z<j`%mq(f*rw<H5-RU!5RTFshcEpjG0b_@rm4&hL7RKQx)j77Cr#82T%slz!{2Rr18 z>Q%|WkH`VQeZE8Lz+>rBB^@H#k&pO|buLQHK}Y~3)MJf9{$or94mn2dltO}CG^-xk zD9J2H5Db4HFc+t(4)Q8UmEr{e8O@PgF*=tJX^j8FX>MBzHh^-D)(r=DL$k;*@KKL+ zI079S>k<VmIII~)N*wiTS5jnFl@cTb67JB{Hw5A)5n(R?B^Uq>-ZjF6)L}S#2mm$S zRDnS3Dk%*BA~S55kOO9J4wsWsTNdY#a;PsM)(A%A{`Vzeg`*KFIL0>i*Rm{1#fM&8 zmO5gi3~&4+9n(0QL*(I{g!C>U5Yfk9K;sW^OpA62*`ZYwF|MVIgOMytn?rDS$fAr9 zE}9C5G!i1cJq}1?oOwn7_7H(-$)b)@@kIcdkw&WUiyyRHi?S|N4p1#XO1UZ2`0i2< zLv-Mh3DKiN+Jb`yO`-zSh)p5-Xb}QXgCGCYcm(<?*cxtW1AqX;j7xGMz+nli9<vAl zG;~y(HJA>S^3=xmmeN6oOv54JSVjP(F^y#?BO(G)p>_zRjay1360+KdLwJFXQcA^k zS^-l+ZqW<jt>zZjAeuaj<B!-y1rn3^2saZl#i<Z-DtD=807_~rrBomQ-un^`RF?^d z6pN)((Nrzo04bkNr52}5U{;vq5cy=q9VT1nvOpGqXPkx-_X|KLoN|MyCgpxh=qOix z;~ZHUZA?}9Pd=w|Ba6tx86s3lFYbYldnluxnM;Z>h6)#OWUH&of<%OzD7IQ~a%(1e z(h&G1gG?+;Z^H3~Ujr}%A69`I%#8m^;w&=Fep!%Z@L9?>ZZHda{zEjoutq0LnUrxR zMSqLv(h?pJfYmPLQTqFzXdd8)V_;OTPnu~`Fr*I3B!nO75Ql%(k{<ziMI^<G$3k?K zAAj&xC-EppJ=QS}eypQ9(7Dt$#xYaeacg_<z#(RkiWl8JsT=$NDLJUYjld4*cthew zH#qZ;VufQ=-=Ib}iL)TMY=b4lp~hBN$_{FzgBz55Tx_8Ak0LGw90t+Gl<v!ygN%|M z<XsIp>d_7VHOMv=F^oJ!!X!eS6}@}Ri$oRj7P&}xA(SFaX~x8-rBuvz<p_uEB0`T4 zZDU+^Rk3a};*cBf5kVeh7d`iooRpHlw}Q8vtk9~m4xJ8&Qs<2e_=r3ld0?41l<F8k zNWvd2<0vfhFbF*SfhdOzBLL{onJJ;g6_<=7BcJp#pZo0RKbN<V@`y5^3*FHfb4JNQ z0ggo$LZT!&WFNPwOF81hB}iK&#rHBar#tOwto;~L0ifQfKW%C+#^yzEGfSgmqBX)? zq#xP{QAyN16|L2IqGvocuY2w5UjrN1XvQ^bNYoQIlPDeza?o4EgqvVPJKEBoHnpWq zs%3NS%+=mDx4Z4_ZzE4A^2H0O-gM?LgFD^oUN^hj{iGxj+uib>H@)lqxFOp+-}>G+ zzfJv?fB*m?`2+=I0096j0RRvHe*y&p00{p80|*>Qu%N+%2oow?$grWqhY%x5oJg^v z#fgOiz_=(82nvoMLy8<pvZTqAC{wCj$+D%(moOF905b8#i;V&&32dQI=Rg!FV#FLu zw5ZXeNRujE%Cu?269au#gaJcn0ALe^oT%ZntJkk!!-^eC_G^zkqYUB__>rPjfjM5h zE%>oT3n&3NmEFs?uiw9b10#jQ)`vhLx(v33NHrnXf;`y@Oq@fo<;$2eYu*g@g}^*| zj0DI7MK8z~k4GB`oudZU03UIF){}>`?c2C>>)!ov)LMhK(z=~Hidd^jJq|ujo7PQG z-q52<pH7|W#~K?O@6-sA=gk)_>MsBG%oc@Bxz*FFU(dchMDi$Pk9?aQp-|a1Zbo*` zzrX+gw#6WnfUubq*$b5|grGs>0qEd^5JtEjPVyO4UknvWsNsejc1ThUP<bfgh$NP1 z;)y7xsN#w&w&>!EFvck3j5OA0<Bd4xsN;@2_UPk}Kn5w~kVF<~<dH}wspOJOHtFP( zP(~@`lvGw}<&{`wspXbjcA4Zq{qQ5^m}HhIW&r<qspguS$s-Rv^a$i8L22^y&N%e^ zBM&z9VB_bXfCdUqJ>bw2W<O{e<mQ}gHtOh7ZmzSAoa>A;j-=i6$tO1B)Pqhk=ICS2 zGNG1As;H=@(+@V_uv$+y@l^lnkDQA>YU`~iNlH*Ty!I+7JmYjTXg$Q%lZ`p%7;{G) zN}!7BGN^{S478<Ia>pgkTw@MD0SwEjKa19i>$v2C1Sg!l{-e$|@)VoSG{&&O#wC^L zBWgO;XcJDK+OXOxHvJCzFF4v%gH1Nj>T?GlcVIG2r{Ihuk3j6OQ|`qWF9hd5X$Alf zJQH{GO|kw6gUKbm*sBgd)r5m6J=jd_&p3zj)6bzd=X@wQ!v4cfJ=HXm&N=$zBg?Rs z>d9!vOlRyS$7otgPqEN^0!k(MTm#KE0T2sk0G8tEX2k?mY_{37a{SLY{B#PlKlP+z zFCWiL9RQ+D=Z!Jh<naFkcb}ugg7q@Y)J^O^BA-n*NN3mc%{c$i(+ts-7{jMJ?D(wr z=8o3d4?V5oB1k^^Oe0M_aK75j#EWwj?$QCA-3>hNyn~K8w3tI^KT6Ze`R`Y{>Ceo4 z>S9hl%bb(WJH+}q4m`uB6mC56_#S|t@x+}>CHvH)jXeH*4gC003eQimvJ~x1I`#O2 zO)>sJKm4pNi68FG*mR?gr=Vn04y*B?ANd9tq;T!39PR3d`@pdeY4AcH`$&iT{4_P{ z!47t=n^-}pr?w7)Ngm*+#?<UZEU}4;fC0e31ysnw6}qs6Fnpm5V@Sgp+OUQ=yrB+r z$ip435QPxoSjGSJWV83}BN?FR#XewGjCc5>Vg@{l2h|q7ehn=a>1Y)_z@<STdhtf# zO4G2wF%3}g;vDCDA3XA;HYjRvQZad28#5<FaDZc9=(xn`x>1fV`Voxa^GB<Ul?+~( z10ATth6w3#HX&L}Ad`|59Am<<u_=ycQ|kpf`Vo#U?!^fKD1#QZumy=+;R*yf<sTt3 zg((<h3RqYr#pw8rebobrha5-#UM8tV`ivct3?>|Pr4l$<@@xkDhoATni_>WX9GW@9 z8DvS#l`x8W0tp{E+EtHpTw)sC;uJjU@w!SbN|@+O=SW~jJvX|^f{QB0zS40Ce)vgq zWpP3j0<ixDE%>tw4sikz0szVY478vK6-Yt}s?dfq^q~uls6!<R(TQ5Lq8O#9MlZV2 zjB@m&9t~+nM+#DsR+I<{1;Z-MmZ@%D;*fpnhdKfvk6r?E9TiKbPKEiB#ZeEN0VoGO z`0)>P^ul{k!wd&Fkiw?^aD_`9NK~iFRH_ERs#vY6R<F9%taA0MUJYwk#|l=minXk0 zJ*!&H%GR{Db**lVt5-J=)i2J8WBnM^K6<f?eXPo2ZXBMZ-WjW%8a9|GX{Xtu$S8pQ zBN>}uhp_13$-QWSAR@@X2bRj&&T@dR8`yvdMoZe#n)bA)O|5EI%i7ku_O-B$t!!sY z+uHxyR+hr+RNOF;k8{+c9INZ#VTViHNsa`W8g!&NX{N-yVh}7-_yR$uiI4*%-~b00 zNCwv9+3tGxyWp+ne+0X#xYbK{uPVnB*UR4aLe0GbQQJ#?izsyPqEF8yixtW+5Dzd! z1KQ1ifCo(A0vq_i2u`qq7tG)V6Qr&L7D!z&fPtm@Hvn{HYJeNe;SPKF!ys<3ga_gU z^2w1;^^ip`&N0q=s?AMsLTmtt36bK`*d$4f?>`6@fOBAiP%*1)Sp2zP!(5mk1qeWr z2ciKDt49P2i7J#afZ>6NKm#JED~B}f1uv9RAkxj-r0ketd!-{z*q|ePa~zR0xwrp= ziE@b@`9Tj*AhM5q!2%YnK#(IxxjIxHNQDa`;DuPg0uZ1wQxScE5kJVudRv^E!o;U! zD6t*^&;~hhdQ-!Oq_`zf+#_i<GNblG8+a=Vk^B5#E$1e*4hgNR1#*E8Ksh4;C`1YZ z;O7?cmrc|YUz+%Y4p{isPvP)~O~ZxGk=WR{91-;_E2dX0<`tT%*1~>i&})Mr009AL zasWOs9Vl0X2*rqz7zSe8BUs_fT>2QVhUX`C7(*Y3<j1_ZXh~wq*x9-oZb+mZyGP!$ z66jEepP~pBe}>X9y#DV%V6B_&TEHMuX!Ld)f{X1!;NljrgC!sk03is3+!FsP@jyNi z05&Kj%vE~b>*%3NY=~+bni}56j42N{66D4J2en8T#i&*Vz!=WZRDPYJg)Veqzx|as zq$?ir0Qf)%Gzb6`E}jr2WL+RMc+Ek85QhMmTfEbuM>s|%jXNOHPlA<X>x^>Plbo$p z{Mg4O2!@TlIDOj>Y4X%_V{w6?0T*rvK*p!O@c>wYAT9`iECfOa02c%o7(hAN+vLfL z4Nn{Gt3)rd7-U`rGpEpYiO_*Q5%FbHkl5hIHe#`laP*y~LiS3Ld9C?`h&wukABYlg zA%u%>pdefq$R7e=0b3J92?4M}0OF8`I7~tW$KQNr7(NhkkR!#HK!^W8BzAhmAtm5C zg`^}y;>arA@*Ga&epwoSkOYK#@VjaBNRktPNnAV*oX~9m!UQUJG5_#=-LwpJwoT}C zHcnA@BLQbYMGyM`3pBTMVv$*`Rvo)05D*s<H1Kt`rXjyZE|bD1>A(vL=qCZ-4^!k7 zN!4B`kvehH3(w#W-}e_DfPV$?d*wC|YtefLK@7jqc)u|adk_F?K?B*ReVSoFogxdo zun+IR4|XJTk+OccM-<QYZ><+610g(u)D84t491Xi0#p`fS6%nVgS(M+9T;d6cYK<s z0dfd-R7PcM=!Cb?E}3!-qX!SdB5++nTtg=h)H6H;QxBMM4z~XnWP9NQ7e{{z(S*~X ze~wlVmUvYL5ojEchkVF+0^wNBU<`a$Q*P93VNrLiM-hoQhV+05*MNq8;Q<m5Yt)ee z6t)nBb`Tsui2(qNp(q$)_=m|*591IIY?OssxQfFBfgJIQnAC{>gALI`7H5!kB7gz6 zxDe#FSsd^ILdYKCSdQa3jJP2wv*IW9P>TODOOkRf=Ry|pSdaCXL9a(J|A2Js0C#C9 z7KVX|$yX2ph>n}HMfEUGq|yzSf+la)7w}~+U`R0FAd8yfdV3Lhkq3Dq;sP7VA{}Te z^o9-l5DUtKY%ZuagH=;J^%edWNuD+lGDmGOgLHdhjsO2>kUH5EuL3kmqz-&EHT4jY zV!>u_)-e`AECSIg6*-F(1co~ql}I6mDA+&$@Jx3@h<%}z713DO@DJ4Jk5W07FF|xY zmpPpx43|bT!W3ib#1~!Ij1SRR+5nbLiIZfRmqT%t^<WOlkPh|~WLy~-G07446qb0Y zmx{R(7Sj*)unn-lEqDTzZYF_j78pm#5qbp+cT*0SwwR!a5*!11`@lV`5@ctiikdN) z6S0}`&<_|GnzCsTKT{2`&^@}PW9+44n30(k0VjVri;nr3vss)HA%^q@4(Y%>%5;0F z`If5*jWQ_@60>6M6Pw1FoeIG*-QW+_DKTe>T<QO}8RKaYqxlcXQxCA2d)nEa3BiJ9 z2s5`wCo*UoyLl00mJOibIN0W%{)rHa@(=rR4aOi3?+^g-z$mC!o|(a#5V1`A01E$d zjsIDp1hI(j$ST(3pqEjY4PllCmvAiTAo6FSH8N@PP?yD44|E2G%w~uk3W2QmT*t%? z08<YLXQPnl9&j=|#ezCeX`(hlJlmi|v_n${A)Vy8QxY*m;nWYHun+2Bbp7!$9|J`J zuuVcLBVnXW%E>)}IXrHuejbV$&qff>#X(B5Kj&~%u#%wcDILiaKdD0x@U*2ef;jcC zV)8&|@PH6y8l6nqW@>Xjx9Jaf#vlJsEMWfvC*RNv(C`h^b2xbVB7-yy$zXfn5U2I2 z8=V>v>_89R01K+}r`6##l*LWsur=wR3%2kIu-Xcw@CvP<3)=t<{GdVP1U;4NA;Pv} z;Ls130GKYep-Q@><JpP@F(*@6mq<r2owS9vL8J2U4dB2r)Bp^w&<d?E3asD?slW=V zunMbi3a-Ek-0BLt@C)!mEb`Dn6@!tz+8;_e5SgM$Y~z^%QLpsrkRFs9mAPK=1*if+ z4g|p}^t26DIG=KQF8)vrz(5MDa0;hTuBLFY7@M)IzzU)u3aLN}?CO|y+C}_2ul=zx zJN6CgfDW-xbB>gx$J(GWsu1n+58MCH4c)K}{g4dj5GLd#r}dCMuTl)az^$sF3a_vV zM|-pvORf}4u}2%O8+)$o`h8neq9)58;o>L#pa^WkDw*SR>=v_v>S?LBud)yaR^S9q zu(n5F3<g7?xB*oAIu6BP3!)GTt56CXyRk>RvE)jwNBgv=aIqU(v7`X9#jrn$g|%5b z9RUh@n#7`ZbeS^-qqZS*2vHBXzyc=lxuE;GgAlaUgBye;N5$|9q+qV+Dz2)~w|&dB z7@G>IAh@bPv4VRFiOa5NvQ60exX?j8cH|HGsVU|JV?oNHW{SB6K@WUj0!P3Hd=LkG zkOpZ0z043NzZ)20SP#v>3akGhuCCw;PJ0S}`>o_#u7vxv7fZP0O1rK=3ePYoTr_vU zD;?tFC-fvHb|kL_@sPLSeF8kd1nhlTO2C)04QF5iaUcnjunDoyFe|VE!axrOs~dKj zrNCedu)DDtd$H$Bt{?ot>w5}^y9&0T3*9hd_sbuk$Fr0>C<_6=xbdSle8V_QENox` ze6R_UU<ry)36e0u!cY%qn;AXYC%<3{tU$YmTezk`xa|wYBRs`Z47IQOt*P(})ey8T zET@PFr~NAp`&n;`bwXjtlEIXPE%6U<gbTkR3rA=YpHRo2U<sRG33r^we2m9<{KF6I zz(-&LP7nuda0hqb41fQ?0u)RSc(%P^A&=eL4C$&0S6srFoXJug#pavEmOQH>gnNtP zzhAr=Be@R!Lnt!L5Hze3>+pTVzy@P5O)f`WXTS!xTn21_1_I%76|u|m63oIp%)~4& zjLZUQa0Dyx2a+%dj9kP=Y#D=94|fZ@Rea6ZoXr}`3Z+mAw$R1!pp2yq9rQ*IMis*j zVN(kl%{UeS)B6n1z!34A5VyJw)Zh(U!!-u64g9RIZ1c}KqYlK>LG?fmXu!aqKrcQ# z#1u@Nnz1<E+X}5qyBABl7JbneozWV-(Y0Hyfs1pNJI=N-XY~-J&PAv%=n^S*1k3<8 z3{flxK}BrzO9uaOltX!$8Waa6kOqTr2bC}gf)EEQzyjIJ&VNBHaC5h>P_gPuyG#4j zP#x7$J=IH##T1*uqbAaQ2ttD*4ZUz`iOCS^+-XJ~f!)9cgJ8klr>qVkzzJbvyg3kS z^a&Ge0uy}KJj^bfXQvU}3ah}x6RXLBJ=lW{xT_GqzW@#&1Ib#=7i6{x=I}2!lg^yB z&MonMpWp=0aDZ$bbanS);VBRBAPFqM0?J(4(F+Y0%z1Ew4Zk1?r9iIMYziD*+qPZX z<Qm(yPz-j;D_Pyxf*~n(w7*se4)&W6JQptVxDxf?4O1WqK^rGQI)n9yg%h)ki$Z4n z5Prl!49x#P49|cl7tGjSL0FFS3bvrWr*P5Q+}`e8#YejewA#hP<G8@h7kr{EEXpfp zNweX3#+?lk-zN!Zz%H8>;Gbr;splqhmddCTK9uFVaq1Uv;@abDyYHRh8ji6~{0lhg zfcIS%;zK>Yz1``MCSohrm2EZ%&Jo}D3{Jpu2j1cq@sjF9OoW9dpmz?*;1Auv4wwVv zGj$n`G$-}os<*qb6use0p3Ud`x+%P<ARgj=!H#CADR)z2lEjQ<4HES*2y6g3EtxAj zMXicBGT8tN<uDHFC0~~zM-W{N68+RoUgy{x)$!X5Tf{|Fe$>i&2?}ei`|8l!`KcxW z%TE6w3kB`Q61WoXRkBM74$QO<<8Xyt{ukgw4|iLxerw6JecPZO>K84$A{@o4z{OtN z=YLUZUp)@9BoPdH67?Xxd4gD%UJ)GHF68hJ*U;nLfRyn%-GC7;<-iWxn&hrq(W1WW z%r3PXE76@ox2irCZqg~5<PYm<-vtq<B5{D6dj!M~Cu2_Lu`aES!?_A*t&}AYqzo8~ z<J#g%vEw_qgkA6UPS{N=-=xqCik*|w-W6`bD*X_l<<Ku^I^i%|?jo@bY#<0}qMGDB zs8RHlEDH|{D}m$<7Q#ah)nE%zJibbv3U)s7+U&F_%-jC{?_B|*d)F`IePi5i5t#q& z1a&jxa+wl=Di7oUH+JSYHL4j&MOnJw*L>TzOWy2AFY1Du3gbI68L#qXd6WMDFOT^2 zWD1=l@t9x$-3ANsI6tUn)13Vf3yAbg?>gl~9yx;445Xm6x4Yh{aPM+I_a!{Vf4lGX z06oVI^+-|Spmzz`U{9-D5i%Ik5iuzP4hGwxEB}g=Cqa}0@mpP^N$a2uEUX*!W((b1 z>LlO!+WgcMi|T*F_e~M-oC2m|IT0~W5#Ig`R`3Z1jP)lGlP4zWy&w%R)1SDJIbBl> zqwor`9k@w9{GcASsQ~(_u-i|Q#-y(lc+?AQQ@M_><>)u=7x8^yem-OCg(d&Nl^oN> zZ5lWIi|~N)iuJ$^uK=#&`q!S{{?|;nN4u@uK<LeH6ydT)D;iu$_406C5dcB19x*4f z>X8eOaNR<N2^~I!7*Qg`g$fy7eE9EQy>Ik{^-9O?A3b{V<V{4GQsqjPEgh1C2M=5` zQmS0JQl%=@PM$q|{sbCS=un?IbFyNkid3_5{aikU8dd64s#UFC#hO*?R<8c)UAuNr z<JF60*FCH_wH_Zn<Nl#7%ax+ph5<}!#8wYota1FXfjcQzuvC-m*!iPZ%vP&YNKc(I zW$N){%9Sl&#++I6<H(d(ttwT@R<U{zO%6t#TJ>tytzEN@7ob}JTKoU%Y5ceFv{aHL z1N5d>4>;9$^>8^67NGdc-oFO}hfdGA^5WwLf~;3Ax8by}Tbo?>PnWIGk<Fh+pI-fX z_U+wEKJ__gD_!ig%j@o4|9<}c{r^uXo_N3kCjfpxu?-yD{xQinm*`q3x3>bw52}CQ zi9?WyFiH)=v=GCFo^&qh#xHREK}<RT1v5#&da7w9mB)5^uSOehd=DudNvY;Ue^vxC zNFj$LvL%zS!RDWHFnOmNa16_;tla97>K}nVapD<z5Q2+Cxjd|^o^A$G1f736imk}4 zOhOTyUuw#UGx#>6vraoTi|i;?N)hE3Y)~9aO+g1Gv{1Q@%xnLeSnAQHz%L=3>Yr`M zkfa<gyQGpUFcXsJA8quCg&%d0G-)?Op(<4#coO@i6r&=e5l2~PT`yK0S&477dPHI{ zuv32pHrQWLM3SB*`)O39-At7V%>0;@h@5{U=>nS4B=Yi6vr;W*%#YG3M;ivqDF;en zRa&-Fb#!6ul$<()j8=K&m9sKc=wqkUbNA)9-~WhBbkRnkrD{`%$R+q8fuOm<k}WsP z6st`cA{NxX{u0Ste^D|irh2$>rInm^GOA>gPewUql~-ojD3XoRF_dcRL2+Z7Z^oIc zVijf7QElUT>aBVPVS}G*v5j~uNCOb49!#(UjGdfQ+O7YdW=u&+m0P#wx@)h$20LuA zk$UA7RYYk9Fny<HyKT20LbRS~FhSO5O+9o;Ac73KG@@*+a+aZk<f*5ZunsDRQ(xaU ztW97@sSMsbC#Sq}Js<Ovo*&=lyz`p@uIHRedX8svvOENjA!Z3)D~{Vz0=lZe7XlHS zabl5%9wcKzc<r21ZJeHJY?1LZIp;+_`N-r`CA85rH_SoLr>DM9(0OjO^obHy3BuIV z;$9$Jju7Tyl>R<lH+fK8NX&H#N5>y+`stN>wp*-cyrhuY>9Lmo2VejJ=)a@TM;%hL z%i^lHKnAXeBuEOt-0CJhtSrca8@bk5PIDHx1)%>Q8R|#U0&u}VUF9tnBniOQfjfWv z#a9$$TRpDj4|s^_6*$ovD`KTQ9?t7Ap<zWUzCp9#9Ib&zM51><cMgH6O>u^~U{q$e zj)VzB7EWNsgkXohsazygZTgfncyW$;U_)8H>l~ZBQVmkz5Gk-CN*sd{5joZoC^-qu zDwd)-f7maHe*|P!9+)V)4a_An3>pceXqtL#0}Ya(2L~r|!UaVNHwlU2Km6erY@A~m z``~0bno~VQu45*oD8)|R*h5pagq7%d%x6|13SeksI)TJxF0;}mZ1960mq>>^6oi|* zkgz3b37kSQk`Q(L!xCb!R^KQ>q1ZtMOez1AUp>ZAiA8}UFY+*qfT%|jW!0k?t!fM_ zKJ!Xfx+eg%iX~`P@r!C`&X2mpXFfS5k8aST7wG7RJm?V*jTCc18ndRe;C7OQdBGB< z+aecP;zj&0Bqm6zhcy1#!e&;odb?SbVjhE(b<!#!k-5rwPAaRC;!!lku%`m`Ia8WC zL_loP3opb}P;m09gv@!$6d@uINuXgH@{lIPL^#p1q)r|~tcE%C5kFE9Q=lsHT&k?} zidH0LR_{b9YvdKDd+DMcsgh|;)r!y4$YUS9@CE`6gHWX@Gyv?V2Qvy{C8jR5uM8oH zJo*tLbo9a;{P3oBpr}O#qR47UdDs7(=oA3Tw5D>FX+<lzQ4evh)w4AP$EPX*P;Fqt zDL;+U>@YdBIQWCH5%udz7@`r8*s>nZPzE~6NRFN^wt?n)Q7Ce_JXsdkxW-M$XHs+A zRRo~9%$4QKBIAlwG=pXk{cLsvNi1;m109v{RFW<!818^cAi^LYJe)F7YF4Owsw)+* z)L}JHgauhi@@cPri@;O5!g%fq;A={j5CNL(6u-C@UA4Pl1|q5-`v65~u@R9}Wu?3j z(nvhwz=uA{mO|}yFKoZ)4{&^ig^k*kx$gNkHDcozl3AsV_!HKL;K*I{R1kx8{6~`n z^q<;XXpqr`#)!-{Ulnc06^Z|G5J_&ay&r}xMf)*W8A>7<w)vAk3_~siCb7k~kmo9J z1SA{BQdc9aUs`v(W}NM2OvyOMCe@t4l^7XfM*iOWw!sETjH8-!SsK!|wLX8$tRAvZ zMp)?4DB7|kuz^`I+XUnl#pH1nIr+>_0^kz>^&}xf`EO|G^A@zuna!uZ*+2F{3wo3T zMUi$0Pw{N(E(zqB(D+9)d+H_l;tfn4g9nOGEDU9sV;}wa24L>Wt3awTIK^m%DN5m( zQ^Zk7b!6UrUh$73!y47!29`+(G!Aqy$w}Tub3*L=*Y`og3!6{}6%DH2Db^b?1hSew z^pOruE>^)vRHK+erl<e+sL4ip!WWtigKls)Tume)5I_8pjBCKdmH|MdLo)8SCPyVW zv5^EBwvp@bppYJl)QAi#iE<et<{LvyM>58kj?#7`O$mYF5lJFLderb6H$lox;soH7 zscB_-%AqS*QH>5KWaAEpda#Q5mvqEp9|L;QcvT}1y?&w|@L0%Vd1{tM2kycPvCeHT zaSocpl()3@GNG+TidWpK;DlPwj8Z{19)Tm+Q3rg#3<HiKN&^&SG$XGn%p$@KA`b7M zp@0@UXxjNhK<XRxf{-czX+W00Lv&oi81E=;I5x-dj}rQntEfBwQn8*><p{FB@cZcD z9(dXVN!;Kt+Bu9Nzt^V!riSPh20X}7a(}a<-gHToI!34$P)xNRwmV>#Yue%$p91LW z6f=5&71s42r4;kbGU;nSe*LI1wDJIjG{gjslB|X#8}4H<i=XG?$Acc@s9`-~t`GJ5 zJus-9DK^m^FtZ7zV+EBm4`E5b^nff?@RPIpH}aFfAc45<N{3$92Tu`+)Uc966N4pF zzF6Zn={vrPAct|lxI^OueK3a-8;1~7H|bL=!cmM>us-TqJ@rsP_V|qN)0GhvzX=pV z)p#IqNC!~J29EfK4hev9V1q%ZhY*7Z63VXySqE}38YDpnSXhR0FdCaXHK}12X}dl+ z+6iG93gU7e(&)JVA#}t4c(l;^hjb`5#CnH-Dz&wNwN$whE5J2fgETa{2%dU1c_@dk zg9qy<23=T&d{_qEdOmUa4XpaC7KsPKVHaGv6#{yUed$EXnhZ?4G*++$U0@KNdcze- zmsMOGR?Ne|$hjjrjep1sez=B8NQXizi3Xv>s;CEOAcKd>m_S)PideX->M^5{Az8== zeK-ekkRc>dhxJ;so05l2)Cr;3n4f?bS9k@1;Kfudlu{uFgpnZ`(nGY$C-bwN&;bQz zkRN3$wFsmdjFW^i*oFY;C;(ijQqu^2SckvJhH2mhV@n5jKoV^z7k;cnd2kUJd4;>{ zm-UbjR@kin&JxEU0k&gIxpSlkei(;saEBC0Id!BdUg|l0d%k|)hc0Wh0Evw$o3eK> znrCo=PslY3!Z{Ton1AGlx4?#CK!;=ig)4K1YQTnm+DV4=tbk*q>{C5W^OvA_j91vB zU<<;Gl#A$*j**}T$fJg05KCaNg|ZxtW+(=A7ze}<j&Qm}lZ?B<U<V{ghjSRCztE<B za4p=xNQc;s5<?OsDKSA{18F%Z1d0i3j5U_T3*5_wWmpDUAS2x=26!lk5i7L?1GX1& z7gfrd%JLV`l#`=a3LnWzt*i=Wff7x62WkL@U$6zM3<XgTh0q8MQ3wT6u!Ua$hGM7& z?dS*pw^W?dJeQ2yIKn9h$U_InT!y16qbW-Xh||AmNCsm_hU!cP@}Y+%ln4}Y5Vf2# zyxazJSO!o4g>#6XGSY^fyOx}Ly6n=Nj}Zk`$g~`!F@Cwv^N<r(C{4#QBGlZEbzn<> zI44m!h0t&pvRQ?oGaFptlTawdYM8IJdCy!bhh+1Ib1(;3NCsyB%qg43pRyEsfChX> z1Y|(b6itL_D5DrOGIf|nrx=I4kfC$9#Y->;bKtk2yu+ID%T}Dd05m;dAgSz2kDF-^ zrAV7X1W?vc&BHjkZa61CDVw2_lh0_t$56Ub&`n^d2Kv!2wu-NRn6hHP257hjeUpX% zemF;M8iyB52qgKX6s1!X#fN@sG<F~da&QtEDzSRl2WP;9JJ2_DkWy^umS7_nOtPwm zGrwPmEX=r>Pvpe-KpP*S$0p@KNg>P7D4UnDw2~Pq9T_RJflytbhP@QdnaU0-qlbOa z2VTGgX^;j;Y*Q_C1Z22}d}zjexQ7%4rEO@_bKD17MF+yvw`)iTq^yT<NJPZw9Y$r! z9Wy^*Fa;Z|HW`T*w#hqF$eg{5MNM6k|C0yBkhZ#ml^iOWpmU?G5k*xng;KPZvwF1Y zTg&Gw26N!meBgsPhy!8BhHM~^eK=8k&^LWhhGEDD6g{?IB!+BY2FHs7WzYxzUPXs} zFe9YG!UXCq84SEfWgcqF3AQ;I+gt@(s3$G+SaBT;5NVZFFu<{CKs~vYl97>8Y$kY! zhecJZw-6<d42EDphl=Ib6+BU7Fb7_6ghUvIVL;JKsDxhV1$^Mua|niC@P@rCsBUlz z)NHZGX;%Vbn@*gJ9xMevX^LrOS*$P&ZQ?3i(NY7XSyG)0$;phMBZbU?2L=nR()tFx zQaN161#>vjdvJz*PzFa(27EwKV~~b5-3X0<IBn<#ZTJT57(vtwo^x8zk}9d3p-9jW z4MYXgwLO%;C=SJN1ydNho2XB_QxDA`xK*H!k<+d=r4Rv;Fu_EJ!j%U9Z^(vZs8|$* z#K1&K@GxDcBce)6r{ig*sYwsBMOjx%-ocQXUt|SWxKdeymy&4@IsrNeg{ixusZx71 zKq1q?!iL_})oe(EBWMSGU|eKC2YG0ea!3<PJjO>WM)KQ@%_Wa%gWLNAUGs=1=fQ?> zc!zMT-m9P?G0DVBQw7TCiJFC1_mJI@$*gARjhN7`mka<T*@s&|(QCK_08oN-$kltu zMFR0rbIDX8)GAFfCoo&k15CiSNss<HS<-+9;;h~;(w$!jh4S!T^f)dX!Hnh6p;XY7 zRq4fM3q%USCU4@0b3jp|1ONcIgnbwWefT=_?Tu6kR|y<3jbNAmSBMWI&Edh|KJ8PD z^vD%c{Lu!U3gGI7%%V2uRh}g_kI)Di>&i7YqoHsJom)T$P}pJsC<FcLhBmb00B|gM z;3_dIDFWt-kx7M#h!r<B596U-v%0ECR*UO$G3I$CIj&nI7PD8d1z_L?hm7KU0zi@= zmtQOgHdtf;h=NA4T~hv0li;ce{;!1iM7cPHhtP$DSmuOyh3q?Ktf162o@08QWnfl` zaH?U@IFJ9jtj)07{lt|}V2YRk;sy(heqe@vK!aTdfGv2DZJ4V_RwI!ZW@=7m)o3n< z$b&-2g8;~bJYa-Y*yrVPE*m^qv#MikUJ3J~38N^foq(?YiKgg^{x6u(m0hG(c^C(H zY-e|71A6F&ZlJ~nw#3W4=SzOx)>wf6XlaKSg#ai8PgcW(KC5$PS)8gg0ZwIj;*3^s zg&{gdoSvSuSO;dH2VHh&0AK-r*oJMu!v^NL;;09%Qe$t<XViFUi7)|&c!ilxjmYr9 zWxlEkWoU^YoNuUP0Q=^)zFT$b6KoKWGF~fYfQOIXVg-l;HeiEiXe5#*Ws^YZu2O|6 zRRz@8<cFYx0H6aqSnL4c10qO>??b)8xRuW+#j`qVmY}|x5V{<a+0Yhk9TB=7rWwgw z*}6_@05Aa-000H3hkn?GXLyFEhQS6FkiphO{rH3bgy`)6u!BEP0uw+3)YH4Iu-W3t z>>%B2uNaR~XkMZ#u<34@Te*qf^k6#kETcy1BT#^CU<LsI07)PQNst9$U<P?6<$;o+ zw_Rh`=xRG~2s@x};SK;cC<Qgn)~)D?9<*uZ#^wiZ25(G?m$9P*M{v)CtW&TBL?xX6 z{H*l;1ZEJ1Z7>1W_6K2j258s@z>ehHrsS?#W8xYNS0IG|@BoPTgZfqihtS?_<%;td zYt7zli7>J?vIQ8!zMhsBEX`i+Eh}{pCMU`+a@g>H5C-!8ge@k9ZGZ-~yzS&Y=>TAt z31)@X5Ct^o>fe3?3D|?+ZgD9H0R8r4|6cC@{@v`t5Sl7aryb()S@F!92;>4uv(F+2 zXh;WQIB#6o1_c0s75K#sq-TfRS$4SRPF@WYP=en6107HU`gREXE@;7!ahs+NqJBeO z1P3;XSsi)vS=nCcB@Ng5-~gxw3g7Sw=K}#~EokW4L3fd=ZiQ#|aimy@vY`qO(1L`} z0U;;^`nCfxZ*kPPl~*`u`nYKTUt75(78@=bIhR||9_?xO8pAFd=9%?$@vOIaYG?q- zXQ*&%VFqaMa66vzL*L|;R*7hS3N#3SIB)|AfP*}cZ||t|%wA|<W<^Q^Gs?adH~;h+ z@r>+yh3Xopw;Ya{(g=0fQ-s(C4JU^GPrwClPwkv0^u%Eo0#YfI0L_(9E{EWQ0H6UH z_;NQ$2*>7uu9j(<zE*_BcQg-dSPYJz^RI0Ecl!)@fe*zC<`X|*($C_o*x+br5C&Wz z25-MPbH8{)7n#WbD|L^Ej+cn@IK#u%1vjvO)?R^^-ui@K0kJaR|E_V<kh^A>&!O}2 zoR<~KfFmCqb(mi(b?Am|@P=&=mEObcoz0(i=|uRLi2Q_OIWcCXXoX_XgCwW}C)nzj zW`QF}u1VhtwwDY`$8<Nuso~K?9Cqu?2WMD{rCIk1xzw>YC5MhWYr$sv363mGo(QRb zh)xUzT_A-CD1u@z_J_a)hv0<&)#zrIr{l37PLtUCq)=(KM;^~by;k7hV+8(c)O$9s zm#mhGu&T;pz=H{Z1liB;F<<7}cL>Pm3dyhL=C`Q<sfJL<nsDa)_16p^hm2oX&-f$% zgaRZ1+-Xf7S*kFK0H6;>0EiYvJOv0)>eZ@*r&PT%WvU>=h!Q7KtO!vRMpda&om$mO z*FSa^N0KaQ@+8WXDp#^B>CYdwU#k{otZDNm&YU`T^1QjR)GAxW>iPTE@+i`zN|!Qi zx$f!Hrc$Sllqb(0y<)aXmBQ%o)G4K-UcD+Z!;r350cM7kh>>bVuwZ`%)m2Ykym(gO z^6l$as@1*!w7%-dRxaZI#EKU)ZtVE6+^?ousl6NcFXqgesjdqE73${DC#_=D%GIl> zgauWTyh*B607f0^6btY=Kt_iJ9qP`U@b}ER_1F;?ZTz@jtMur}tEa1#D#O61Q?G9Q zI`-_?9l9dbjHti8$j4_6Z2mm@^zsTWKl(W;dGc1@WwjL@b?=ghAwDd)qm(YBKvarE z`EABqYO8Q1R6PNdQ;vA?NjPCufxT1@HKe@46@ndl_#ucPiZ~*P3aRo7Hh2B=&vFq` z_~KH<1t4QVc@-p{i!8nO9*mojRv#<5@ir1;5W!|-L0q*(o`(r7hz&hh(R1T^Jz6QB zJT1xtPBWyG0v3t?VTw5>nFua8Q~)cscO{z=nMY-g0hqU9npP3FB5^LRiPDZdw#gT1 zFxlctkg6oKQA9Nr^cF;{gfa?5MP#B&K^r#o+eV0rwoyVD{d9^gP=;4!oPU}+m3hm( z6w{YrnvyB3vC29tt+m>E>#Pc$LK!*rtXS%)r-~<~s{XuFPdDoPgVnF{5J%%mo%IP? zuuYK$4>rIQYUnDOE~?767$p>B0L7GIL;!u%mLx)Jb(<-2oU-L4sMv(#Pqq1O=1)CZ z&EzSr0Si3vzz%K13M;R8*PxtL>f2_s%F)A3HPlp7%r6=LVoS!&P}58`EJpcFIU+>_ zEJf2&`|wf!fySgOf)N#In_7D8P{%8}Kx$9`O9o(|aR`FtiYs7+dhebrE3H&sRy_w+ zLS;%lwbbLXa*B7@yt%Z5bN=IXHO;uv3MrzPZ8le>oV`%T+Rzz*mJ@9)k;*G`jgreU zDYOwr2u}nSZV+)Y!wdwCGL}JXedROYnKh1BLPW1Z3NYZnBPEr0Yfh4Rc_G_MD>E$) z8R?~)4%y=3t`c3SFU`F<a=-pl4?Q1;LdtIlt%5M`tPoAKDwC1&3^(;yW~a${Iy_O` zpTS;I-iJAa5z*f^ZksNi7!d(MrHn!#SChLM5zv`+7{I{@FFcNvuRs6%oa)rmOe?OK za>_>kRO`S0h?B2kicq4&o+-VrJj;{EiqugJV6=iJK}ub89LPJeL<e-xDBjobqL(ZY zFlC-;US~d7K)GGTAK(B+Dt5;Thghw5yb(|_iXa1=9jQ`4u@Z>DqPAv$<0VNO;ro_T zoPWe56}}_X3i$`3k(^J7EL4ziiqbG3{^eQhu*yHkfibi7u8UWr$zp<+no{7d8Qt&| zpFRje_)w8bF9An27UIGto+1=E>%#=_5P;{XWk9R=S^373!-XvDawuyf*XT4DTPTQV z2y<e8$XAhv3`sXi)K&eyVHrgFWkn%r4#r5)k;0q;VUGObTsR_^-t`S(sb~c&h*yvQ z4U$A!Yh)uQFH{Xts1RYTl#3`@Q4CL*1rfFhKpzS8KQ=usG5@Oucn--)ePMA$&Z*xK z5q3JjH6|t3>)AFH;}BD(q8dFM)in8HO=^HHaz!g;q4M`3FFx{qry!ImSka7fyu?No zvE?m8m`i?DgA|2|T55133blm72qjRLrPi{aHVtwWuP6t@q?yiOS<xu3pv-UTStdYw zXeA;dDVcZ|3SjUPof}OG@(PkgUD)Rpz7(T8MFbpqfkkx-0tQij7?FTF50QaF7DDR@ z7D$N#U17+XfC_WdQ;8^H%5vTEUP{gL%#Sh%LZ}jv0?Bb+?L^RoheoyfPpJI=C?=w; z30V2J(^M!78sPZHI*d|Oh*+_&el?j<H3*Jt28S)A(1kAafP^Bbr4^7;3oEKMNU$U< z0LRO!T21wtVzH`KBkfJh;Ico2ooSX&No!`^6c}XbOhGjXCuFRK5uuEOIT}paEz@b0 zra6a^avX~;7!iOOAfgzKB@0kimnd*ui80etg)3gcj#<(&wfWN0s(vAgQl!Ro5SbZO z76VSl{Bl>ih!Se8E4O~x;(?}6-B|6JN?)Gh7a=2uQRqfgX-%`5rXeFKiZM9i?omSr zIf&9gqzYCr2!WVYuduGd-thg;iGHD)D^n5OGp1L)N2Q<r@>wX@ZZm5C9&yDPFQ?x% zzVx*6fJXqZVGB{1LT6zhE@Hoj+*dI7RH(b3Di}0H2<xjo?EO~+ONSg1^9{PBFy~94 zMdTq{F&^x_pS+%^oh`qsQyHObq3l}^v|fg&{avj*-T@D-n5zvFsDmhUb`ah1Sd4$7 zj=QRJ3IK|#!&4rQc<%C?n{s(A$iZ`-uk+mC{o<T{)-3|_+ttv$YjN=%-C|M$x-*hv z$N@bweA*!ndH|ycIH*G?<h&sjev_*GV+)Gh_vb5BGbFD-B7R1+n-B#pOr$LZim>|V zjlzSyu2?WDa(Zc<DkyDY#+OVX;>l@K+bH=pDm}(g>{_TH45a}7MliOEkXE8}NEGdl zh*TkpW?<tbv%W4p>QN1BvLdcaJU6qsf+7LFdm`2($150FVOK4iM1A|HF3>a7=Cx6I z@ThG)eBp*5WTF_aSQ}~x9?2e2O<_=WX}@V*LN1ZQ70M<Nj6nNppfIQ?8SFQni1-VH zA(UV?zg17Ug^_)-BZIl6;&Ku=j@kKw3Sp?lI_lviQAki=6uLQOU%?H_kvZgSav3lP zB~M)a30F=E3Yuh1<SX_zl?5*o)Kn;B<N3SVo}^+($PsT}1Rx2upvOPH(G8m#EET#A zt%OuAqKyoVQtS|_)q9lP?b`c8f9dg2O7t(vSY15Uq#r5&5z6JwZ~loG0Sjf$_#mtN z{CV+^Q>W?S3pG@s7PA{iIIK+5nKW5DtNCMmSd-}MbmSve9CqUW@}p{OCArwSy<hs6 z6zxPEM-Nu3d3wG@!{qwxB<dYy>#MainGBbll*czLTMsz2z98aw$BKGYjIkI-<M&Q^ zn7%HQw*f!+eX&ZfXbN9ln@aNIlsdy8o^?qJ=p36i;ZG{`gaR(0O@P@=vD{Et+4B|9 zid;@Tgdg5n!VF}>>;ynN7!TW(i*M-)145p0lwgxBge{np_}Smp^-Jhb-%a2~MpVmA z=!(L8hd|BR8$E+47!mJ07l{pFVx-Rj=3r30RNl@1Ls1k$64U`d{KGuVL!i||XULdT zCDG@RPC>L<UyvAC?HP)cL%cDJ3&Kcqe8We%$`&@0zDyM4RG2C(3|0&fg#8F%bcGlZ zAs@=c7LpasX&-uB#`}<7(tX1`9E%e|VLePCbHD?PHO#6sgB=~<>2#sb_(e07PAjQR z<-Ef?)ZZDxh39m`ds*Uscwx0T2B*{)I1HjFat-p-12}xtYwel!Nlnfjpe-a^)s0YI zumd?TVLdpZAy9)qOrbl-Ls10^IAjPCjR_$2+OCO-)nE+|3EKpYqGnhHB+6STM9@hk z*obrliWt&1BGQ`p13YlaDQ-&%#-lvm#L)Qvjy^>Rw8i3a=m~QmqOTYuHT1(2wnINa zqKkD-Jd}eP2H|@#V7S->RWOP?%F}CL1B6r;H)07pg2T*dAw<&P-Q<Kq01!0AgYx*( znVCm+;m!f(A|#QP_VLpI>0@XZVvBr3JK!Bas)I82LzJ<Di@}LiTvOVSNx215Q&7#< zeFQjwL(`;VMq-9D0)s(SpSj%)h%BXDJd47;RC8FCzrd4AjukJW2}&vr7LfzL{DUL} z0Til3JIsSRtV4QD7<W+(O7X@1$lp+aTvW!#8+FMkaERlf#6(d@RtASq0G4$HS~q}B zbc|(ujf*NAgeFN@zCgt`h+kXQK|d`2i#TAE0Fn>_v5Ht)SW;Tj)Hn&SS)^b7<vx~B zwzya0d6QhgUy}rfFs+C3&}6l&NOrxK(DWg3LPq*b4iDi8V+PAVjKersmOFGNH!RCI ztOGkVC2EmIJj^DtVcIs0S0=7RTl8V4tXsQ58*FMMJrEy9=!zSX1X4=KH-&|(bc8GD z0y#L#vt-t^`AaFBQs3R2fC?zU5Y3ZB31+U<US-A*vBNjajxfZ5TSj4XA`nveP(eA8 zmu+391n7W%=zw<0DNsYZMPho6M{%&%s=bS>l*CTJ2&`n>J+(sdSdmu!9#P&?G)g8U zVFU!;#mQ{ra*QTiz=wmngX%s1K^s8AHh^Y9yo9@{#8X@dH?$;=N+#jm(<=;?Z=PsN zke<ASPI8r$VT#v_fJpDu=oLZb`^d;MY6w|nX>rbJVpy6fa0O+21Jyaj4)Vpba6>!z z!|Jsj-o1l3bmdBj$8<eMO<-Di(J41UDop^zM>I&6dg)4}Xdb#Jc$P%@#OHA|4ubSe zDx6V4Bq$J_hs-e@n4R2}DrK{+(04qg^PL1Pd7nu<#d5e9o`jz}3~DV{Rse)%J&Yck zTEv@#sp!lTL%ymK=^HdbTijr(0g(m_DhQd{=3#PNhqTfe_2#j{PO+^Yk7XFFc&M$+ z6^IhdaDv4-zNU`!DNB(5-ai!2Jp3x_)q?SeLr%htZ7~ILU`4jzj@7`57oqFACM>Ne zgeU+5HmKN;QLB$Q7^50Si=xB~_Q<)uN&+I=)G5zK?Ut2&!*d`}5>X9eIBSCF5ZFbD zQP`-I+D)`rCp&b*KfHrCa9isc&pe2OKR^Y@#t1tEW+)^V(HLwOsVuCjLMZSMI$o;8 zj)ayV(9?|R#@XhdRF!u;=*vYcC)EQt&>PLM#ZEMt>cG|N%%j@gM8as&sqSaYBE@=S z5&H~lAUuH@=xaTQ!#up~ngYgoltYy!(J9f>7p*PgGN6|sOgB&+)JAQExXwRREZ=}6 zO6VT?qymgcq)q()hAHrnPzKhAy`xe+2Bw|vhe&G5iWu;S!pFsw*D_C^6a=oC#FV(h z-5Npw;0rnAX9+1!?Y4}5Hb=#(ju*9|>K13GutKF?1w0Tb<N_}DO>P4v*S31<#(^q% zAO=r~!Y|B{OFiz3cq2?`S8`>Tc9^Y3q!6ZLN=?WM=W&_5(46-UM+TuPQ|RiyiUa`# z!Vnx|JIIua1g*Tn)K#o!D<}yrwonqquLD0YaP(bAtl%r=#aTx0{Z$FF_)aR}o=T`M zqof2`V8(B_i!XVHQ^G41?N)t6FxuhbWYwu;x@({5r}Tc1#H>ec1%NDsK^Pq4JOsdI z-U+o~hN{s212!}R(-BSIHJ;MOUxlrLD1-_+VsJN(Ts4FO@5GgOCI*}2W*t>dorLS= z5N~^N3mD25E^cCE+z%$ssRV-^QNXNH6xE90Qa#{8L=aFsDCe|=MqYpeHlzmXp3W^M zFJsixMv!QfTJgk!qfL$2Z6<~GhN=vI$ry&ja<<V>s^RYxuHlAqC<lPyMuaGzGAi>9 zWz3Eyv%>}R$qpJ~UUgc7cthQ>2flQJeky0?7|^LwFG8d;JyFl^2(vM#vX}LuifpnY z1IlV;C@71DT2KmEMAlz)Q7ZhXCT~<AcgYt4j~Jn>3=5u1W+`Pr)7v10jJ!=}sDu1S z1Tjqi$#Y8EwV|j;{KLGtRyc=<tD2I@`Q4Qw#<S6JGbcxLK=VKU%!GKbXz>PV1qC|e z@ADK3N1g_<S*4gLhDnvw{y@#T_0W(qg^IYdIxNQ|NJKr1!z)t=R&WW^k(CpV$k@JW z-+XjG6trmQl0nV%RhFqLjsy!7L{LLSoLx$IQnEv{!h%3qN;(TZ7hmG)L`7umw}3ED zSak{tq6%|Pl@P~MghcTaL?$2s9zcRRK!kNZDSASL_;R%~c7yM<(iS2w_R$0}M>Ps| zY><StClLqq;`EokSg~bsBvZ9XcuVFc1u)<NV^LpIY~e$<TrU@5SLexds4)yn<56P& z+DS|lnXIl5f(kVKt4X-XXAnp6xI-=kKotalFBnAtk8z;D2#s9Rv7v3>9c+iV>R2v> zFac?r)H7gH#ZeLV(E@ZO|IH+y1Rn$dAGiS@*g+ZuKm^Euq-=;AUv1>^hC&1dHh_Z- zbJCrR!>#!pXpa;{XtYJB_pWVrySA|}F_>K>1y-;FH@JiGWJ4WP!5)a8ILye<j*8gD zha$~eVf-P-8ey|KtAhVeun9OB4>wEbk{v0VXxM=r1b`ht0TYNo06+qz1V9a?<`Ye@ zIT0c!B^~C8)8B>Ge41%ocrkxOQi!m)mwiO9NNoqvbCe+>zC1z|Bta%9%R9LL!w$=o zaJPxTQlix&>>NFD`gmNs?YM;d1v`Rcg(Wvh{It*TKtb5SALIcL1b_}mK?+2K@=3*4 zK@kP7wL0=kGuU-~nvQ`0UV&)$r)sxzVRmK@4UK|yMF<sMeS=8+>K;6yFK|N;>#`jx z4J|5+P05pD95N#BIbu)-Emrxy5R^eJ4kl8C+7yHd9047K`Irv@9OyxFyTD(#iu_eW zInW1{Z_b*u)h__WP32rqR0Lv2M6XMPydZW6(_jhq)aRB1Bu<2k<i%IBLv_}JJ2V3v zBmpE)!&wh2Jh1aRtn`&w5x;1~{oE8i`XOGcEo(})rVF27%Uj9S;7I)cdP;=49*nvh zkU6UBfgl7x9Aw58@};pvX<GxPpfr*z)Lg*aUdE!WRM3h~u&<MN?|D{)noP+*hy&YM zf)r3(Kd?gpx5GQY&GWobF_aazD6GkMXo7fRiKcsI=ybikOF{g)>ZF8EL4*mc01i|^ zss{ia1VA3_J7&m}u7nCm&pPY~(a;`QDU>c`kdJmxgqCaT8fRKVvK*9o%^lBjPS%4k zK*A8z0X2w&JCK7r(<L*8P|$AG=;f%KR{AzM1f}Z2U`;E_6L$$=xu=5@6Ft4<F3MU6 zNO0xAsP{b2M+6_N0A{dZWtPGU^3zj}kmdEuC|nIHK8D^;qeVpjy-JkMbCuSbp7uYK zLpT_ZH}r5DfPGx{gF1LM&B};G=L-=DoOilC=iAe7Lx>sHz1>szz>VioQ^Zt}^2_@T zZ0G_av_KGqK>)BohD${AC%#<p<seSe1rFLp;{>s@$@_Nf_G^<We1vkE2m2V$GqmN= z^>I6lLqD8$Ulou)#DgGfak<ZbMl=~UoRjWj289>)MVKH!1Q0lIAS;8c1R6|8Du6CT zEp`|RKuI8-fp!21jN^etr&p&4h7>uHq(D_CRi#R$>Xof(_58_`SCVE;n>TUZTvv}9 zDOaaXxpH+9XwjlHO_?H@G-pVrH-QRFYSbvvRjqW%V<+(c-#B*l>do^-B}g50>*xjG z2hX3srf=cKg}b#_t5v0d9%Mze=v2Oc0SBh4veYVD#p<n-yO?of$B!Z3Y+J8ds8<G~ z2FOhCDM7snS*a4}@JB>lx=Mw#5x|CxBQ{n9kYa09WRXT!tvaR3Wj%QG(%KfjSf)VA zq)4qYB~)cnm8k+ee@+r*b<sJi!<Am!x+<W#fs%UltsFUW-@?udv?D;RfA#2XgBMR= zTY)my<zH8PAphb2`;!N_`r^R`7@(>H%DLxqt4_KHA&gMMq>^e-6kxCkV5R_olgU2- zK@3sE$Yh$VvR9fjMLO!dE6Ski5DEa808WUgp;B=F44{xBOc2O~*m@jMAeFw;?G%^5 ziOEADnY>S)w!mp76jSt4kiw@r6LGVgI{VA7S4g1-9I)EaB#9j$;pRPW=3!^60NiX+ z&YGaa<`q-CJL$?j`RvorKlfDWMOH}B1wFRrOjOZDos1_Q%0fBlN}GTZw8|L+Kw<`o zbO~UT018W`6@dyF=#Nq@;Us`pLi8&s91o*MNk&5~(H{dt6N;!){A7}^rmn=z$O=~x zWtDl{sU?sZ>hMLKf8-Ho9%voSFHTw+{i+ySa4gbKqW}%}PlJR4>acp)`RAVjv2EAg z$V?0+H|3O4swM<gIVhA*0~jHIJ{k&up;BJ|!Rr)J1bRgmg%w`)mD*Zm>eW(g!KNH| zK75xr4@;z{8e4{X5hcF@u-8|rn%c5RqU3$0m`MyNLJdf$>1UpK#E}PDYuRx$V~qji z*dKbL6h)L$OtI3{r27)r=_^w#MU-l=k?C5XvCg_AcH=!rX_E)a3}06QXr-7}@{j=$ zRs|LaN4!kZETp5ev~B51Q-QS@Sv%ZNYq?~4$79+~(M!)g7u_=D-STB6lp~8Ng^?mA zsKOU|<hj`$c=8j-O*eo38$d_PspstE=B3w4aG!4dRZ+}F_j7ha7v1(nIj+y2;|@B! z?tz|CB@|m0#-oEU1R6CpPz$atOT|I|yt{B!3hT`uM{j2g9@A|BN+`XET~Wl;t84H& zno>_{uT)q81{g$&kYNHtTxmv|ZN#A`9(B3OUQt=gVW(2Kf)y!}&;bz`p)0MTU{kAF z0Knou32KcU<<Lbd@U<Y3T<LrP&_f46C9qcD=wShX7-vk88<TV}L@HS!N=SjBp-r$U z9Fs>qF1Q!HV1`#<qY3on@++u-By6V`#c4``ha!}q4~VGCEJA@8b+C&dv#T8q0q3^> zkb^RIS%vRh7e->~CU$Si9Tw5ZB&&Vyh8Hwa4}a%2gb4%=0zp_SMo};m`VeS-0ScI! zfsMADF^wXTiKEh$!@}**N>btfqu7oT8KVfSHbB(ODUfp-T`=MV5(q;d7&Z#MC1#CI zDrBv+!VYkN<4yz=<16t*C|zI!9BjGbDRF5VE8-A?r2ykiir|TXyy6ujT%PFoBs^f0 zV~|?RC4U_Ck8ZT06*}x4N>Zo7l4Pf36q1WdxG9jlAcSqIFok$d(}z5CKy9u7hAv1! zLRjhISw0g`aHyC|#_)$@<oJhyLh+z%4wRq;T~IbJR5gEGi;((sXcpJ#p?_TP6or|W zK(tAdQLT!37PVb%z;g=aEVG%n#G<W^Gn7S&Y;{D$NgUsjC2pRC6|NwKWpq&tPZ&W5 zI|zd)6o#Cmy)8Gba0M6tP5RKs%&v44eWPHY3YZE7r5N0(2Uq@aHFteTU5^6GSNG>k zr9#F{*qdngd}&UmDQ=?#X$3LkiK9yXjV}jDMKx;ama#g?L?X2mOBvUckb-773c0Dm ziouCO%m4&+KtxUnmKw&PBrmVfSyK197&oa)Kt(&+Q}NXu(Ta8z$x($UP9Y|BscUvX zlgWGP@elLF2O7<Q1~j(84u8T2vze{Q)h61CJXwbztm=adics9bnDB(Q8*ON~k)(yb zNvUAzE4^sC7sgGpCLC;>$mEiglVEfe;5^MJ^w5J61fdU6)Z@eO1<voX;w3|ipl?AW z6Ur3BXeq2piv+X(tHUwS6r#xKRkgN`K@Maa(4fXIh*?ad+LRTq_(d_ik&bc%Cr*li zAcFCW6Z&imNAl$(a-Eo(hk0j$ki?fkx&h+MqO=)B5}6-e+Fc6i#f3UvioNm_iqiyx z4nZhE5e!iZB#OtPJ*=xiNYM;g%__vUfyaE}K|8P*NEN7SDUSJM5S1{{XgPgP0RHi} z8`9$)&44g+TA?EE++|nDLC!0HK@E7MSsk-8qgboV*TKmZyE)#VTKPoRNLneoG3MWl zpX3j4{32<&F^D%|Y7<MzCA&NnaxmV9g!T4eVHXr7y>Q%8Ni{>dy$y6t_?b%mQbrfW zA|{{!gCbJ@7`PbkX-iq@gRR%DqjUlAM=^epn<iVD70kvAO$&^bW<YQq>1yb!3DU7` z-GxYoHbke&X2Pg=(|>-VX)3yb=GE@iy0`iTUc{V=OqXO!^0lNmiD(qPghCak0mdTg zP=XO8`82H{#Rv-qN2d9ST&7_4WMqtO;n>%7x(J0Rs8my80{FWR%MF!^ff$(h!^0kS zmxui^4rF^Vtp+il`MR_5Q(%P}rCXB3M`B%iV1rv}MdvV;d&zmf3rl?h3Rdb-ju6`l z8^731Zlp8xBB~5!mlUGD4HBtW1S1%TFkTRXxe8s3A{d~;(OM@3yggYu$|Juv&gJ4~ zcC>~69^WViH6m;@qb>4aMhgYOT!sznVhqrV`cOT(0Su6(@QW=nF@*qQ=~tMOc-x3A znl*G!xNE!TNlR=1X26MJeyVvU<L<rP#V2K7MHltZ*=paOMy9`8q}h}@zESU)(6nes zD-j+m4ztNH%wPhJby+Y-AxgZos83Fj7~{MAa4N%nIBpsmJ?eoC?T7qq)GLMAxKA~~ zkKFZH>sU2@VXW*DON`7`$zi$?99Ju~V?3AIX^PN+KAbI&B?JjzBuMpi<0=pX_HNFh zbZ%Q7=6kfOJ8&X($V((Xqoxo-<BA~|JfR4Xp!gn37l2_DjHb!(CcdC!AjT^I2CVV_ zenF6SC*r6NK(6nrv=1Ao1{?-t<lF=-Ob%!qB}%C2VZaCSdgvtNiwJ$M+w`PZMBx{j z!S%531?vMI48&{@K?dqTVMtH1wu^|w=Wj;qB*269%J0M24JNn;N8;`FtPZMhk8ye@ z09c_IE+`X<-~>v*v2=m!Lhx;pCPmWj$F4+VR*;$Q3kpF5bUXw&!r?dKp&XPh^9Z64 zvE{3tgdP+R4R^>vp2Ky3g3yZT;nJe;mhK<=K^vkW1B2kPz+@G_=%EDATo6MP^@;P& zj%nHuDaZ|lq#`*?;cZeQ6tDs{@W2Qn-~_?|5r82WUI7IAYhHvf_lgMLc&K9km}&kD z5hr2|t2QgE-lVnE4H0o?LmY8?(C@AOYKII5z@kdwCgxnO3?8yg7SX7420~r<L1!$X z1L{D@4(_dx<|&|2(fFbru|ZbAajZ&&d+y@n_=r;ef|7W#6GZ`?EKUzjAOeCQ$y`AW zKWh#Da50F*Tncjft}#TsakWr#wY;%iCZii%!Hb9m9WM=*nC2u%D9SdBEl3g}{U$BM z0SWNnG+2=#KeCVn5LU1OQSi(46hjxfN8y6V(7H(=?kuM~K@WUj2X+7vLg7YA0XcSq zhl(;TFpX&{Mt>x+Bui2ffuk*u&7y`S<Is^NRU{RPq<VlM{^%|^9_rEm(hMH!VH*m8 z3VcBx#_rbs1eb8l6l7?7zRI^;Pbh|>2wCVRdMqT6!xeIh6Y^jLW`MmA1~vLi6?COV zG|@52XCY$+9<)j==OiW5OxQf+%CO-X{!S=hPOV_10l#px#wokNkQ9EQzGCl`I)@#Q z#TTj|0I0zo8UlkDhcZPYocw3Bq$B#IE5sbd^<JS|AVjblFT0B3ywYpb46K2MYLSG( zFO2Xz<6=7oka%L#H5p}%T2oQ1&mXp@7)C)inBxc^gvSzSLgexw8brdzp&sn%q4+}_ zcBc@MfEv`HANJE0Pzwyp>wqL^K-Gu7z`>Mwl62&unDzqdrlThRa`SM6XUL!+42~?x zZbUpHjF>nog+K*w-1D1K!9+z$K56Fw>2vco<d7bv8j5NC>e7G|C`kuY-U>9k=A{&d zlW+JkmlR_hc83@uLLJn>*c9Vq2yH+&^ngMt6<#6fI7=SUh)By}M60RxxC>a6Vt7KW z1j0ZMl+4r$h7%ZJ5(1!434%KsXE+#*dJLoWGS3==)S)=0tOiFpcyt{l6)?ukNL+3q z--?SC^pv8h8+NA-lHggqp&c-1XzWh}1q0s{tqq0c=w9I~9I-fMPad{&Ro+yE8ge86 zV-$`75j?XG@>G=Ksuk>j1z3Or0$>F^AXx)|2lN0AnM)1-Uy4GA<WR3_Qx_HIB1*qn zf>(%=E?Z|;c*r2`q!~60NYjWM=HVS`K?X9R9|qz_P4(R@N?fu>T*B~NJmesi3OKk^ zxN1)g(+-bb!85;Y>_kbA2<8u#RUlX(Hkfq<Siq5T@iDxsM_Z4&vK0#3ElNnCfY_(m zPz_wg<-ee`C5j;cc2I)UWkA@$8wAG<!hjn7!5z?ID+Ui6n!#Aa$ad=GPj=&6R+cCA z%T~Q(EPqU#%BB@UVF5yJ6h<Mg9tN(sU?ALp4*0+g0>B~!LJ&$QdLYkQ$)RsHHqc@% zPX1wA`Y>c?l4SAKNIESvMCBFYPiS^hHt7*K(nTEq+MynBAqgNsUBuxXSnG4Pvl*zQ zXR+pKrm?=_QBk#qNU!Qhp^{6I#uVP_6>30jRHbZiL=?JGm_i~C{$L=OAOPZEM6RTI zT8~!a0dmXsq;!TucBdN5^itE%ZQE}Z{_`$=K^tVnbAI%1tR(>AVH*PA9onD{s6k!l zAryzyb?f09F5_$LRcio6C2;c;ej%?O4R#~fb(M~C8PX=6uR^B6A&Acif=OXKa3EGd z3Q9Ks?7&orAYnd2Djj2i;<I(JHFoifKZXYV3L|cH7nUrALJXrAW}=i5Ofhsu9p<4P zGNB3}K^@wm9=TB<fFqj7p?cZTY1*YT!iA>)Fv#Jw;Yq$%O|fV@-LyzDY9tEk<$y65 zT%iu?U<V{X2ymESOl2faHx6_`6i(1Kj4)qY7kmL2joyPDsHvjHh+bxRimAAY8B#Aw z>m{2Is~#<D_BH^xVGo++ALfCJu1qBKHeH@`&ZO9iW0*;_Nrk95Bnu}@va`zcr%lPX zxi-jNa4koIF&Ik05P~2KT0jCG76{y+5J;DF1>%0)<})6HyO4Mcml)e*!ecY^fDafQ zPhtgKFD-!vS}d;{!ayRrLa%H>F}5WvS;2K2NluFHX+r8wUSeo73oT#x6uK}ZnzT}T zQEJNUG)RFFn7{*Y00&Ya1%$v2+<<idm0%!liWC~j`C_>yx}%a=_>yxe0d1jqGW3_l zd7K|)LG(guu;Lpy#06>PzNG0L>fsQEKtcx>CpshmK4t(jG<OkbQO0>eb_40QIhXv^ zO}#_DSfn>atD<~SAoxXVop}aiAenh!V%Z=7LN3ClIYtO#oOsA462w{unwxQ{jc6mS z6gs6<dZoLA0Yf$v?8iPdCe74k9O!`>q~H*^p&!Hnt8#)JnvQ%LhoviXM2LC>RRJq- zPM1kEu%a;}CY35w;i3j24(y<j8QBfu;0P)J2auo$d|(nrffI5HHTD8IY6>(I0tJiu zk~G6Ah{uvi+PBcM8pH!%qB^ht^?D2AjYv$vdR(h!-Ju=|K@Hr49{h=>=W~_8p)ywC zATDF~qPnB?Hz$OMRiR2;Lj(8_1D8YeQH++C?Xt2lTT*ugOrjtFlprJQ;A*v&4v4@5 z{(uqkpbloB1WLdNjNlK(?wuCKB$9(-bM?P4*7am{uF>dPzyTQIsoVDYx%awC{<`(r z6kSDxNUzLizM&obArJy#8~$N%yErGHgc~T3GzmzuqiPKU@-3jdX@Fu7p=G2C>4w}? zZUIyz$Qe53rQ1y575Jb>SYS1Hpjiik1uTJW62=bfz{u8%!O2dOKzAZZA&RXtZ>-g` zkz1cwIsF2b@%B5!Lp(wMM5+~{YlavFII=2#d|?P6fgRc*e-;CPcxkxWQ^ZS<F>o9} zJM9z#iN0r*bXG-IreY0m<Nx$Jg>Zyld<1@zH4nb|`|xNK<dAs`AqSvf2TEWD)Ctsr zK`1Y7D%sn~tkrm57sxkUWAdpU$bp*JIMv=e&Iht4)v8!n&6dzSF6>ra2D=_C;SH#P z9loJ0)FnUiDIO7>EBNyxf+fx!L(ctzTwEc#^yj#rNgnjrsGO{aZlZOlLMa#`03<=w zN!=1AftY-;V3r(egFy~GArlb62qb#F7@-e3K@JzjadxAKrlQQ#{GsyGWAoQ~Ir)Hh z#TTvT(1nEVY#JK>@Zb&9gl|z2F8t%4(r@{|2$s4DaY}-dadahE0V~MChL%oxSxHxf z`Z8-`Iv@m~;V5B3f>lt1ft1an3I^4UhU}=kQxL%rd;kc7U<ZOptmTkKA15VBG_E1> z*Y&9_nhsBPMM-yj;+Hf<;93{x;Ww&uIOtIzs%0H4&lhx{7Wly(+@Wxl7+O3l;wir6 zcU-($<XqHPiTy{vMwG}QUfr8Q-B*NO$g9AH>g+<wL88<b-zJZO;fQp>6AYmaCIAOe zpe#zk6MVZr_s(nr;1L<V;T004Q^MuJo<McQuVRembwWSV#U0=o7u291+`$|AVZMcz zF`%RxrpNLB!ancEc~@4jf%CkDv+S&jBu*8DPg*K<jNTVT;fTK6A?hFuG#~|vpa@8f zc=%5jvI;*m{3h;m>#uu50`nz@BHN3-^gHxBMB&cw)-gIh^HNS$-k=J02TNPuG4zXi zg=?xu*7SM5Pv+%9z`^g$UUWF7LKiYTb)QyxK1H$V;}TzLlwOkzAq<Kj0)9Xbiol6d zHs!{F9L_>NYX7%1*7HYX_G+p$7ew#%e(0%36kI}9hJPTyfBr$99(>^mYJncwp&i^r z*#RPez<~q{8XO3(o-SLZO08OzDx$=R6f0W1h%uwail$7lVx`IyHE{9dnLLOxrOK5o zTedX+Y0_W4VhkOw`uI^`#GEdB`YhP7V}PJUAFgWHFaXk0q5>2PHVRRYFhNAP;Z)0A zy{+T6sbjY;tk|#yO|A>Tj-9}<Kij%}3pcJ@l`-p8tEnm^(Y<{8`uz(y@ZX0GZRx64 zQr=vHW7++4r*%@8TJ*Y^T}O{zym*=0o*bB2CQYNO_?|kATCnQXtocUF>*`fKaPZ*4 zRJ=I1Zi01bHte{Ql|Y=rcN-TfFevGV14{)EC92e`V#P*@$`mFH6DhcGZQV+5+qkss zOs2g&HoaKm?AyEFZSvntTSp(ZzK=iu!{FTN2~0Z|SpjU8)<50Q<BuA6^z+X+{*b5t zR(t-?gUv6cobu3VM4^^ieja*A*ebRZLk~Rfo%q&m6OL9&M5hUKT3&gf$lfW*nKIBR zIHINsQ_%r~%{cV<;tN%3P_aoi;m}i$eBE?I&OcKAlU7)lt#wvGY|+SNm$}^rlR~YS z(qbwco{46fYOcv<n`-8DT0^Ud(hN57{qvbiR?4HEdH;x04?AvT!cIHlP?@K0pZVht zHqD5lN`|Mv>1L&tURo((rPzWEIR4z`WvFGzBjsqPye6ZlUQ+teQH5dSO*>8g;}0>y z)UiVqZTK;dHwgvG4ms*jS>-y#Zi%I;$}am8IMt9+nkh0)OKr8*UW;wE+FE=6+D9ER z#c4hA0O*!_VM$5OfuA7Zi#p#x=-!=D&i2Yjs(cjVw)*bNuf7klate^lE}L0Q6k3Sk zDtQ5y%E0bL#PCP2lmaB9@xUXFH~$16A2gpBvO^Gc@Uh7}GS$P)H^Q37&SvJC>u}7X z7Ay~=*Z>1<X%K(NGtWD>dekW+B4`rLdai@sI-51P6(n#_)6X~q?Fs5)nH4y1F|D|Q z6T>}!{oyL1G~-_YMbjg5mp0?9qbc^`SkOdizeUtUtdP=-r~U{eWm@8xyiPy;sAI_? zd+bmLCb_gT&sN`X6IQWFvjy|qmcu7cW)(K{(avChe&4jGwW7;E^lY5};<yn0Ne?x9 z1OnMSh~jqQl(aT#p~8BB&U;`Xl3t#aiC*rW&A(_!)KG8_hZFHW`E_^Rj1q)(u=89$ zp}3F)0>=(v$Rf-2Td~7UTIH1E^2_Nt&%RrW&c}*Jta#pgU&`0dAuF$RBQEVdUB)tY zeB&S9P=g`fK@JnKEL4mFM>BLLk@`t+FPh?1IsDN#^0W_g#+ww-RuKT^D32h>*`Ps| zV-(on4IBZ;(x}Mu4RJ7T9`E=DHEQ7oHv}OFxcEf?<`IB;JPv8<Q=dSLX2K+XMoPM9 z1xP-K!YE2{ibfF#bEt^LEJoxZsvt!*^cEMa%>y33cmg%lAwzQik*iCj+Da2alEpa6 zagJJ)$ee%y4g^7HjY&-1Z7L+K&ZUAceQb$e^74^t)T1_46Uc3Z$0%~d>U#Y62a%{i zg*MdT8P8~ktoHV<mc^q_FbM!XE+eI|bY^NUETpo)BoAk$qF(ch-~^X<zgtr37bUWd z|5QS?asA^R+o(q&s6dT$Au&{7n$Ic{c1sDm2t%#t6yNZqy5YI9CtGP?GeSX2`Vpie z+q@C<ULlV~qKzN|0u7Vu(HVchgB;u7$MxJnMo4U@4q<o(H|9~Ia0qZ6{~%~)GGn`h zPH8JrB1l8asVeZq!-1jz$?hbmlKO3NIlsWh1zGaYDFu=LRO*mPAPmtDdAI|E@+n(H z>w&bJr9u_?iYD*iqzclBtCbLa3(YoT7jSyZegPm3L;=&SSFi(~r!1w}z;wiQCTktz zAV*ik_YX)wf(lH4!y(G|j?9QdfF`L8)}(Y$dK9spJ*ClY;DI~cMJiezy3zA+Nx}~i z$04IAhD(8oG(H(Cc;fH}HPmnjdc-P~fn}!uOyVpw*%WknxuYUAh!%D%v#oT2$!44d zscE7n051vvA}!ih4t3--v03VER_RDsJ{C8ZNy|9K!8o*Jq7GEhK_MRD3wpRCtlKCk zqxLkGv%Rc^$zmmE7t>6dnBo+!;2OX#McUHBC`~H=LDP1(i>Yqmq#>lE5@6LcrD8H8 z43MY?IRfAhwyJ7T{wRl-Xd2%9>X%I&nbSxxNUl|C^SLQ$U^Sk38v2zm0Kw5o!%TQc z{I)`={o|lN$U%-^xq}|#_=h3tpoSq#ViM|L>TSz2xwRsTl`AIjPr}qhnpStH3jT|G zkn_1#v;rK6*;`7IOR7KBqZv=&#-G|@yVwq_GykB;#NIYppPA_t6Rt-&BIM$^q_c^? zA*vN`Qk*0T216qXl#-!aGaqxts{i<kl$wzpD!4%y-hpR5x>4N0s^wTJCd+cO>=TpR z*%hrgZC$<Op>E-=$7g0|dgLLsK_Gz|l|kMAK?cmFm^2D!_ljSXd6pqnlo_*_26RfW z*2Gs#N-y3mXKCL=QxW-99iie(S8R8~9a5nX%*e(&@BEDbf~C*IHuXvvb!Sop1$mfK z)vGVH+Ea9tR475OI!cU(1G@Ki>}w!4Lg9*qO?SWK#?(ic(oy04(%3#(5q(yjk>vF; zBlr@UBICiVb%<jdxEazTLKX);Km(xSBCA3-cJPFY)Y9xm34$C*ic`&06&sNogCE?b zh&Z_7gCx_Y6v@+pAe>4<uE!o8;SWz1lGaX67{^}@^OxW2i*RkY`)WoZTSQ0PemUx2 zc8QI6d}`fY0+2eqA&$(lV-l9w;UFacfz@}BgV<}e`K8kg4xGtvsDiN^j*yzLQ?SA? z1;_G0iscXWs-eBbWq6}yrs=HbjIN(%&A(Wo({jMp>MT(aJ?<jc{*q=OBHZBMLpVjI zRBY&_Hcp}-bldB3j2+Yn#38&_vU#+F9^@#W*%(_yKC8#-1_L~phf2jS7hYK#rJ~^P zRpzH+DS$#QBW2Qv;)hz!B%2WkIKa`wXA*~w#3z17>=iI<FzS3}=le>+<S0?B+EN?T zZg$bMMNy0dzVgj9n8qTdalqrA@9;-0+E9fZ7@}nEXdE{(oIY66EUomXe^k@j)|fbj zKBbs(EvfG?(RL$h(h+$vVc!7%Q-O6gC>9>|Kn!ZIRO3J@e6~Shau=s@cjcym9byU* zms5uUERE-U1(6mF#Az4^5fw)~97hzd-~gCFXTL>YG&f5W0D}{GG(-*5U<l|J1eqWW zG_-l#U^eMPb$td=(bWo^gA*CyU@^l*)UqEG@irf!W8Xj<@IV%-;~3sh55AxVLLv_C zkU>gRO7egW)DVTW#4s_Zh7=)gs{k!RLn1>rf-XT{<?t-whF{FKCJPob+O;N<qCfp1 zbRy^_OJqC#fIyR^c|=kNNbm-2;0xD75APrk-_Q?^G=xRuXkxe-TUKbRCMj%^HVdYQ zswFL*))6!}bdf_VLLv-m5GCOt|0UBSd#>b(&x9%)m|xMhGxhRCv^a+^fg8*B4fY}< z$kTJm!yyBMW4?o6Iz@DFr#iNCKHv}z?Jy44b3Nmb3AKO(YVZcW@K5isNY|EPnP@~U z6mkRe8G7^&ZzLmK2VsGc7wDEpFi{}GQV)Uf1_LBRXu%uNxO*_MHqr-Wbr)^SwhFB< zYve+R!ALGb^a@UNj2!qE%cv~PC>R;Ckh*{%6*!I96d!|=K>x%z?cfWLpaweNRn$-q zh<IXVCwl0ZB?8iY%Tj_eu?<_pH9Y5K^Z0dr(JH4<CyYWf?VuHVU<lms4uB#Lwb51( zB1DpfkmFWa4<QObl4Qa7{}YapPFiD8dDu1tIBs?&D$nL7Au=>3(o?n*A!(rw1XmBW zz*|)C2#|0x*hp)cwHE3~lj#^U$W{%Z0A{6VBiDDB?BgcK#|jPc3yS1R@X%rP@CKQn z4($LB*z{a`)MQ6^A!DhFmhv+$s0%#CM_kzw1d<l>kuRnQcGjmVtzi@&_mU48gF)7N znbkKLW|H#Y3w2NjIsgc`fPh;e9!i66EcTb{;V=t0ArJ><H70L-=sbW?K{R(ho<t9D z@Cfzrg#o5k>*zd*5_iq;3UhUk6ZA7UaYr7-cmj!<B#2^WGa9S#3V4{1XF^&6c$TAu zm}z+wSxFl{W}C#r|3_gWK<Xe5<j@Y(kO@<91d_lE-=PlO&|!?RoXq)3s$)EXbY1$1 zk!?YpH1Z;65^WAKA_D>s;jk5z>7BEao14iF=ffm76CL>(nr@O85%EO@8lM3<A)C{G z_!$`Y!;JSq7+HBiK1O<(Bbgm0CB)zhhOk3|kPTYVB)8>u89I8*RdfYX4G5E-Ke<h& z;Xyi851O}~oWKuXIEUcy4X-d$ZS!edl$F?kAiDRX|C45pLJHJE9Q;+5{aK=JGEI2L zKSK9*GO9+7(NN-0F#jM7AOi<*P%`9L9#thS*W_qiDxO*vWV1LQ7eXl*8KQlJmTgmy zrBGf%LYbM+{}0=s8CcVBnpPpvQ5vP1qxphJseq=R;iEr#8_q%s*L7NgG!YxpHW`Ii zJu#yC5iL3<h{@@E!e$ap2`HI?3!8u|CwEVGrWQdKRkJ5p8M=vZv48^65A<LvV=8Yf zQChkRn<%1@%7I|4;0oRl54Oh-u@bC31yuFmf)_$#9rrn0#0n2V4cH)(F}kO8m`(B^ zr{gAeT|==FrzQqree;SE&jw!l1t%TJGXE-uC}9%kGcJr1Wc2_EhZ6*nAPn01evV2m zsuZ4{+G0PkN)6Ry?}nrLnG*7bDt&08R;dcFFbeg63u;gc{%|Oqu};7WpWE~qoZ%=s z!Zms*|F8PB6QnR|=d-8}dv#UAMD&4RS4kX{@`N1c6Khy;l2T?&T8qy`o|)5BQMDNt z(+})0IM<U9H;4ysFaw5=3-f@b<#RjdQc#$2v&)I0KC!d%!45hGFl$Q@2Jx<@g<pXR ziXh}A7tw_GG77qo32?9#U#Lw|>tdfFnOi{<_hM*40dtZfZm-ahopK%#E4D9IGtN{B zl){*4dr__75=9Ck2-Z=0G@qz>RwC68Cc+Qza6Ro{Sb<OlRd5KtkPQGu58N;;O6RDr z)l|2Ej&U(B<uH-108M0iaRh-TMiqd2!6Brn2UQRb{s4xWB~`(A8+M@!@k3n}<sqmN z{~ORz4A}6J=C!+UVXMD@tI-l1!h2}UnpX#lm3X8WjRcX7nnCJDE7<sjnil}Ra0pUx zy|vH`j6)^dkVmIOEQ)J35CTBuT6OB!clfwe>@bm)n}V535b$e^35Id;YZ|K1SBP)| z#lQ`o^iUdHtGEFm|KKc51S$0*oqaJ8O(=cTfhPy*R0}MO-b4xxK?=4T!4@UNZp#vG zn-NV25!Fx*umr{&gF0?$O5ZTOhE)r1@C0vwm+&+X-|#L6$0z_|x913$!pJi8vNd`^ zP6q+M{%48<QxR9`hPt2!Mc@e?Wig2npYn1$Q=AIW@(SlkaTvic)fE!Zp$m$1|2rc) zwR1cwpM?$eRyV0&jCEyWxuj9JjCZ<_PVgejC;=ds7yz9oiS@8sI`BHauu|UHywo#n z=BmiC)C?dYPR;tm#UZ?{7MpPMv!ja$GB7c}pbd;dvRT%|y*tIN03EC5$f-aY9Z|}z zFv_~n$_yovu{_KvVG`sZCNmYf@w}rG*DnW+(AzS0eiaX=+0O=%K^7xG<Zw@rU<hGA z1ciVLro(x{B2wyjC4TvrA`PT6(F|jZ%h!Sug2cHe<hh|TBbqxcmz>F^ObVPVhY#z) z#PXcgfX^MMY&^2c&_UE?ys+?OtzZ1m5X&*XF?|VBd{HgcQ}lZHWkC<p|9nerviKM^ z<M0mb@Hf;@2W@}^lCaU=VWEs-l<Nc`INM5h0-d((HZOe;$f3&C!i2iBMM$d)h!6t4 z;D)VW3y|s1Vw<~;0T1j-9mVhpx*!UqP{xhz3c5fY)quN&t<`T45A}czwg3|1b;VT~ zHpm-v4V~4QeRT<?4pyZV{~*?3AO%t&3(xQ!T1qNQgP~_ZlhQ0D5Z7tItIY#(#-in) z%c86?LJF8%1QT|IvgRL{y{DgX9xWv<;7|^Wt$ce!-MF!psO=Ud2oEx4AGs{rpo0@H z=-s^QmYQ{2F8m9>KoxN?3DCeKZPwl#vl7dRH8)eN#Noq`TuUDt|1(7_&VMZmI#w8d z#m_oDCA5eq-_hOw5h3ZE-tbjl%>cXjmCzf`;n^}xRko=WE*EOC4ek&`fkKy4feAFU z6&VK5f8|hh{Lyr*aJJLgV|-es#j!b3vD0L612Ziem)v@Q1f@JCJ+di&CAV7r9e-sp z`zzvTCJ>(m4)u)2Pra*Io+cbwUMNQ4nY~9SmKL#6egS|BxPk|Ppb0E4$nTY#bqi#1 z9$4ptC!LLiIWc7{5!2>$ihKSZ8%w9tWyF0w0=f_itpF{tR%Y;!yQm%J4jYir9px=i zFf-8#!slrmVG3-_=`wf9WTxa%_2ptae+MOh<Ev8b;0<9#{|}QO31P4U8vQq%S3Wgc zIqQR5ffc0uSI|Emv_av%6>F9!G7&Qk5krmy)zu2{jG`pM=w>(SoF!YdMeVUAVAOs# zVLRzh<#)GQ3U1>Up<UkADWK)&#M=(BjYQG1BPG;u2!d+};Ulx;AP;XoTXLQmVKE_h z(GbW8>?@&hJdT0^PdCAh644fIq~q8BOA4*9pW`-R>kxtq&Xsi=kXw!JH<uX>gdsxQ z;UCZ8MX?GjJiZyf7>6A!>rRe1s0LM#1du=sjpGh*x-rtdyjUW`g0>KDELW-05(Ga& zJyBZG=I44oSN9S^ub>Aq&_qXG(4&J+z+&=KzZ>Ae|0GrJ3eWVjTCU~x(UDdr5L-d@ z#vxDi5W+OXh%NsJ)F62QpfUhC5VT`n3k6dFu=A_7_5Mkn^?FyU767ln<K1N=pjjHF zj0A=53JrfDq~#*_67`?T<S;(=x$)q>@$KW@Goi*Q;Ltad??>xKAn<@dhP#cm5D1PK z2<pHMDaQ`0jagm1y!x&X{O9lgj!UPyU6cYBfzA>|ED*1N1c=Z?qcAZg8g2TMPLS^T z%g?7aV+*!B)zL5g4^hhPdG5^5r=y}6YH?wjhi{o+2-|@Nnea~HfMLVJC>@MVOSSW0 zRxJZf5Z6-A)n#2p-xANXdM+&x$LNNo3=lF9|LGc4>Qw-Qs#dL1)$o+7SMuZ`l!(yc zMT{9WZsgd}<42GoMUEs{(&R~$DFalr=noz?YNAS+GIi<{O`AD&?&R6i=TD$MRk33A z>KizE5|yfC+SKXOrY!#<WJgZjJaOu{8LC60(4%_v>eUlx72&_B0obuyS5H@~Ri%Wg zve}TR&V;J+66MRv;i-|UNYVVbQ`M+fu8{Q6RjSk~nvr=zT(?plJ$g_zZ|2<D^JmZ+ z<^2N(?$xVRr&6VA7}@n}*s*2LrY(EnV_U`QvHQm^^l#w7Gp<Ez@gF&I?8>#9myT-^ zBAb5w8(VMN+Oz-UxrJM*^=rF*S>+61|C8wIg+v>!K3OUNVUDhCnj)p^mB7ZY9$R$1 z@RX`nUO@{x;R-bHKm-%SNFsmgsRpi7`kJpc3M;fQw%bJc1)PakQt(3%QIcq?afov# z8(``PBMC`}fu_1{#zD&;dUUbH6;>94Ej$VTYe*IL-m7URlHv$}hX7h}3?Z8`lJ78G z44GgcQj|;$F#aTq@F2C;@-0L#!xVE&i$;_On`S~;XqCHEOXWg1<8-Yd{~|P{8gS6^ zkW4<w^pdx6-l1nkV(Qr8jVf}<=AE(F8K=fpTp4OSH)&FDQXNgXbhXuBBgqbgOt{Dt zCb2}QKgdWaMvo#g(S;Pp<Z4n#|C&}aFQR$|{IXA8d-e4x0>R-XQo6pA^Vnn6V<o_P z%8@6YJ%5$9z(3cL2%c>O&6OHl!U%#7K%kjtthYkR@yc3LX;VD$IyEIo_(J+406XX~ z0m%Sht@G4(-!w&)P+HLik0MSZMPDZ)vvteube;BLh$AjjDS!Ogt{4daLU!W{FSW@Q zJd>JeVu?$BD%vi~ah4r%ypd-uZY+6ZhcE<rrkP-LIVF^vOj*UEzszHouh=^B;0TaN z`B@{JP8mfPR%9r+6)VfzNWLutC`VV6P4@b05G%&UmdAdiD=4(nR=ej*R}lpm4lPq^ zWU%X2X+*U0mWUpB=9woR|3Q5*q>2)Puw#}0bg?fKQD`#z@gMs#o4mSy#AsfOK+P!A z$!|KS4<rUErAqhWwMeJGiee|%wCr~M^#bXMr=D+KA?1~R*VKJ?-h21`ci<Ot2tZv* zLuf46lYa`cGRIlRZ-3Z{GKd*Us3VU~im~q%o`t@YUG#hpV4;hM(41a`Ft>;`cU@y8 z6oQHfoggIxXlNtd$F~Wh?UeWb|IJ_q9`z^&*&YKKjwR4GaVbS^>hUsmFb{we><CLR z6OVXYgm3U5hd0_0jGS@86Ga#S5@yhcNsOWx!8i@i%*L(>(I$QO(#ZJ`!kSX~Ct$_! zL<`=aID_oxBUpn-|3<n-K_n(ogY>{gF-W0`bSY4QHc5|P?!=+WC{c?W!HfhEf|*9S zB@_k884nRL0~DNK2X){CCyD`#(}*Gz4RHmI&gHHcx+VaaJKy=-Fe+08KvF7PMG<C@ ziDDGQF;}|UYwE<m-E2{kla!lVl%_CFWm1!y<YXs3sY&4hX<5426(uLhl4`L-BC~r- zDMTR(QgEUbAk+mS3=swi^dJazkfSb&VY^i9>|Ezbh3;PS3QKq(0B8t+8;nE+C<K5A z7CFd|P9X{vmI4kl2*d3Vvn2cJg(I8XUqt9;N_4)CC98y%JPL@rOi3|;bRq>XumKN$ zEHRz`L)o8L|I(nhyh0|Y_}MF;MoUkqNCGqnLlHcoIA6YMFg&_cLmV>-B?Mpv8rA4V zFH*Mmz;ArpEP^QBf*Ab}DL#>@6SE$8nau1{reK@fN*p8#bjeeJK+**^z(F92oO7lW zoEw9<6BnI`!X~dAT`6?2i_@qG1rkt0ABr##h`xmsp&$ic=xGa1#K8$iK-xv3fROh+ zO>uqDLkUWH($nZ?B(7OlfL4dWBMw!s(^^Y8j@q-e1$J#TahpBM(az%RRg!Z9s4e`G zDV@YhvQEWVE9wvg%%(sCa6p6}UZFkhy+UyZBW)|%$cQ#_ViHNpsxBB|1RVq+45A2t z?M@S`|151}Ryx7SDj=e#r6^XozN%>e;K4*-C@px)WiE4ZM+$0Sqhbylt`ZqbKwDJq zXXL|(O=2aA)A;h2j1WZ~3bz9qq#y^3U<4u<p(<Y@q!{yk<9q|aUPk1B20Pe60I(|8 zxC-WmsrU$Yx0{+(*!3TH6>4=I%%_TN=Pe6a&0ipQVGL&&!=Y>iDT&j%2m9|&7imy6 zZ1IXonJpthvWQ?vArt+Gm%Wqd!wyPd;~)T`2Rq)ej(6+>9|Xb1g>$ds^aCsJh_fV+ zTNp%E2h<Qp8N&X+Msgz*Ou=SZCl#iPD5wFBib<K0G{VL&{zFW><Q5~bTE&rJC0fx& z|FjsL)kB@_d}lo{;<LUKtxRxB9+U87VX9M$m<=5!c1jqYI<1iKOwr*7TC2f_HW@0t z#8@WYXi~J&tx8)w+0l_=6r+YHXd{}{0AN#*GC>HJngW}0qJ_bfrZs{X)F5uirD<AD z8%-QD6oGN09#pATt?iad1~Ks$N<}lENA;S7nPQQkmh5c};%bDrXU%~uiBJ5K;9``+ zOU5R*fv)8sS4g`~j84~@-i8f&SPX(tE_bEptx9=_%@#6glO9C^6b7>SHr2*$03L&r z@^D)vuEC9NMwZulNBnLhvluwA!3v-G41w}oNF5>5;nGx0f)JNDaf`~JmjJ_O|CjRj zNO+Qwp42HPsS%Q9U~`*QI52~jDS6L3<Bxwl$T6p3G#y>>N<4)*02uW7*DQ^4dNhOI z7>9PCovo5tIR(}^*G)XU*mSUqXk=cm2RMES<Be;)lN9C@s#tM!lj??KVXvE{D^?Gw zvxyb%Vlhd$d%q9`DU)>qSv`&$Q@SVqBPW-L%4k&fvlH}RXS0y^TyYb{1)v@kTMK4L zuJ|!Ay-T+Shtwz4a{r;qmG%_5$UYBx*a!9TX1866sgB2<%}EtFvWYLL6JZF(-fMP; zN9jc|sXYD<Rc`x*bmjee;R}D2Vj;&b4;C3!yy9GR(tDeZ@B7WeBl_yh|F=I%uPLGs zws&<i@a|mMeBh5?{vE*}UdQqc?cI(Q*LU2HNc+Ukx+jt0JTFPC`I8t7D!asBA1w1X z(@~HI1PMLLow(2tq>#4*%s`HihjrKv+9?O^u@A@aE~kR1YQTnJ>paBMz^{q7-FSso zFuL^Xm%c-gO&W={yAq6}hNNIYAC#Nm!Y44gzi;>kZZJY@ppNSJ2jF|UN&CSuDJ}(! z!QHbX_{h450g5I&g=#RoeBwDM48x1~hc4=(ikU7D6T_1ElV*8~@ZdhwGnt#al633B zc=$p!)Iibmr=n7sy`cws%fo45Fs1m10{V|SG8R$+8`>}rQb;-s{}jX@gtC*9M6Zzu zyCWdPc$_#anaH3OjcbTkNQEwh2Y7%!OH4&oBohgGpo%du6sw%}`9x2|B=vhcfmw;K zTSZ>%#fR~Scqp^V$s<pB7}(%D)>sx@2!OU2HeY;3Xhbv!x-~Qj1r$?=wCluQfsZ)^ zHo4oyXbeYjG?1}y32>-}u6o0>p&W(l6SNT?Rw%p%amI11M|<oH(PJkEnIm=diD_w) zo(K<{uqWOqu6sO4gnWvM0f*XQ2q>Bjh@lYS2?by%2Vx7Vgv>~d42ik17VdZ~ht#lN z(Xcm6g)bWoRNP3F%t!)}uvYMkHWA5iB9r^cu!XUmZ*ayy|6EC)>`9(8#1lKcez6b) zk)hX^5H1V0-T0D}^hu|L#$+?GMM9wF%AW(_o$&#l$Pt*A3cjcO%9SLu<T@ZZF%WL7 zjXc`QV&EG|6FsneOQ?J}iZMT62nB<nItt;J2>c8=(TO&(1$cYDXW2QpEX;7cwQ^_% zqNt<OAj!wc2*BG6$VrHBf}BtakJM<sXTii$GEC3(MSbiBbxFp(^B1FZz(w2)IpH!M zF@<JuzR!%!akRe)dx$!6g;|shP^`Mnu#na0i#i&QW&pEDluhGQ#hSvd{jsA=VXmy? zE`+ekz*v*$tjc(rygIT8pW@8p>`qIZ8w?W0Ng<}(|GW@>(YiQs7iEDoXMw4v^iKE$ zy`?BU{Tmv2DhUPpo&b3T2NKNq{Le59mTE}92x*s3I?ztq2*E>823;6OYd!#tP)i&O z7_6f5EX$(72zJ8|-*QcCkWdi)!I2}NR;Y<Yq`dnim7*bx4IL8gBu<PBQ5ls_xtyH> zn#wk@P94pk9kot^5}4yK#TcDYB2~O{RJP-@6u&r|paHC$Xi+J`x!j1i<DthQz0#&b zo&bn9H2Dw5Xf~c;GS>K!3x(3z7&yQzhk3+OHdVa4s|Hg@H}vxuAEBtBAsRD<6Ubma zJZw{$($bCq)SeX7&=?EZ@vFBGniH*@J8e|F|2!6AJQm3CDX;U>y#lU&2!MX*2T9|} zxmkyG=v3q&hi_1&&ODiX1IoC7As-1&M->mpj8$2^Fq=pPqj;$(`?}2NRKt`C?Kld} z!-jrH!;Q4Gya|AC2mp6z2W2G(ivZQlK#M9%$A_FjJ6+N|MHVTQJA)i9mY|)fK#K>8 z&9!jGdO(MBaE5e{hi@R(m6QljrH64qh)2kTN1%pv5QhM8*NHPlaEJ*?QBvO05}%N# zNTm>WVZOi|QU~*^c|C>z=mv|}NuK-@P+gsLV1s<n2Ypb6W?)7z<Vk29ws)WgH9&~V zdWL#%p7;C+3<3wY7*nFS%pcJm?(0#U{|%ngP!CbSlRFeMA=NyDSb{mQ26bQuw**T9 z;RkvE1#}n(ZTN?MsDyL?){xyuQ2mETfd(~bhP>g1uI-0*pjf8xD~x#sAE~HWU0b%D z)mnW8cHj`XjIuA0gLbe;O|VkKEQfBWhfTPKOpVxcg@u*<hb;0`d2k1R;07w726pg< zmI(k~c!B`nhIe>}pQEy0aE$)@H6UqF&<))N-PW$8wK<rDe^3W&kb`KjhJIKFaNI}? z0##5&L3HQ^b>N4iu(*FP24|>;?F=rg9fx`d1ViwLZh+Q#_y;%$fNyXI%-zxzJPF34 zvTDGoHu2nSO&}^-h<96}mZczQ|D_7V%hYzzghd#KOjVh;1cw0NhkpQtedvd9m<VjZ z27VZaOGpQ8z=l&z$h4@3T5yBMZHagIhhNxNafn{dP!8pM$XdlRUYp>-8j_jd25^9u zDt$0O^@Cj48sEqTKL~*2c+1*FL22j(DoerzqX&Mdhifnff8f;rtw+vej(T_kU#N$6 z7~3x)2N3g(@ZAV%JTZb=h2MNs3SQ!#=v=|j1y}sSAttH@+lH+PS2+lV`t8=01XXZ| zTKO%zpJIoF#D;XBg>4v_*tKDKAO``419mmV4->xtcmmpSiOmR>W-tZRxDwXH#+(i0 z-szmeqvI(1LygGVMj(Wh{~cea1l628hh+!=;$=qKWypGP24iqu_r2P1q}_G!x|~D; zU+{-^;7kIk2RPt_eh>#{)r>zW4H)d+{!_&5r4a3UH>IQ7U7=%mD2I5hhgpz=08j^p zeb+Oghh#Vhf8Ym|VT;-Y2Y%Rw{k`8!O-N9E2Y09kPJn|}_D_qT2S{*(sd(jR)eaKv zI7xY&2o_y;W>AL^j8`ZP0}L@t%v5U#fPBWc)U^f=?hSs;NKoC5W`>1y06tJI4W^9+ zbf5=kox5?Ah#qDKHTVT~xZDm2K6g+Db!gl#tl^YkkYKFKHlsSTx#ii&r2ZqQ{zQv4 z9x8S!W_tL9MR47T{~cCAm<6L%2h4C}jg*KFT?cfC1&hQ6c<sRQgSXptVdJ^S8-9mo z7y_-h+z~6Zm3RZ8?TocpNN!-v?fVgwmJOAjJi35CpbKbe@#)Tp*O;OQN~q~#R+*^? zhegl?qm^E#{Nj431a$ZZpVC!&_~L)q-(S|-dIZ&N_=iA%1a`gLj4<3S%>;zlhR|4@ z2T6@ue#o$XjU>hiQOrq@hM0Q(jN<qQYY>EEuxaFB2WvQnHAvRbMo7mS+=%5smKf+W z(T0Aw21!`i@{4E=T!+hTR~?oIAHE2w2mq6%1{whkm#9VrI_b${Vzsfb$nlF)NYmAM zLWoi8;K1B?|I1p_h6ZB(N>KHy+vT8Le%5s;jbS5PpBmSDyxe;Dg_Ct<vh{|E4GoEa zSvRcHhiqH3`Qtx!Oz$Cu*91PY^_9v1W#H(Cde8(yK-PW5ZQ}I<O`wNxfb5EO6nf|d zbjYW*0Of?1=6Z12vin(ayjb552YGmcU+9N-@CWZMw000+0_N|3IIaf?Ch2BkffTIX zg0u{dhtV#X!>w%J_y-Kvnh{58b*KkFXoPwQhXohMqfWqX;DvqYN|aIPdN77_SO?f# z@la)lc5sK~{s+g#2x#rhf6&*^sJLoy1-Q7*1Tv-zsguIO1_rzGv<?moqK*KV1&e%L z+@_9Q|B!<!Kk|({*Glk*{_RssCN{s?hf82;xjjq>5(j$71U2{v%Vl7Vs2Fwl2Q~18 z)J<B?u%x}KoXvJ0O8E~ACcsK`FbrA?Z3qTA2nQKiBD8Sr%y9IB3^Q$z2ZnZ5q&O!M zCv*Ibg?%80(wO25%;t9hVmPRUdU%H#x8${ubE+^!YTv-528QEXw^$e0>_)+n0rb6M z@z$mTgy8A69+ZD@ZFndVd;>k7?slgDYHg^8OUQ-*xZjNcRj~>9WcUR0>ttvo5O;8g zoE(B`=;4>?h^-EQOu&PFP>1zS2?w7T7j*S?%)PMY3j_y;<8pV!x>$7x2TGs>E5``T z|LA8ARtxRm?ve}n&%o_(2!MTv1%Bv<rcUJkmgaQ01a;7cxbgQq9I+d>1U&Eu{EqE) zfQNse1{|;s!wuhN_i4@)8*}%LCk<==AfB>|H{d$7@eN{)7}igi@T28odmM{lmE-`> z2Hqf4<DibMNe5Wqhi*WM>6OH<Lko8hhkB5DsyFA3VDrUQ18Pu*8Rz?t$eUy32;}iV zT?mDm_={OAQ&_7M&Tc@TK`{@-<65ivaE%5(fQEe~!|Ck@x26Q6jiAEsxvz)T@pbx< zn443-hHI#YZn*eFMrxIL;br#g_!Gl^y0paIW-4d~b%=O`=yr(~hjnlRNQm=x|L8$a zcJtl;`Xzd1zXk>zDHbLz`Raz?Chiv~av*VoXt3dV&0r@`jq+ip2X%lcfS?y(;J|;@ zqRENYj~zUC^ysZyM{pv=iWV<o%&2iA$BrH|{tNJLB*~B?KW-dZuU@};m(r0FsZnKs ze)P^Is|Rl-%AP)d0u3rO=*V~Ue5p~#?jg!Uhu%%(>9Hi$kQv#@t5?icsa0N6rD7$P zmDjRn%bGIfRqWZaV8^;5^$J_Ph(qt<C3v!=%)A!Y2@D|cWJQDF)*KTkl_Oujjvs%F zXg7f5%9bZi4k}MxxpMvZ!GZ~n@Wsvk{9)6^@6tAY->{t?xEV6-+O|J#|7NEftGwOp z#MQ%N=-s!55oc#~*KeGTdhG(}W=hdA_3G4R%ZnFpcK~qMNR?7`YAh>Ns?vf@uRay} z^zGH3I;D!NsAAZ_`6Ij;`EAIRA6ACkW|;xCpFAUtQ;#2-3<Tgh$c<!;HETpOP-hoS zb{%Dx_1B?eCW%xPX`}%q-9N?{<DE<-Mpe&9-lYRdI{c{Up^Z1<sMk6P1_H@HF$I<p zPwlWnO#to`^v_}#iD*(|8?B=iSF5~2)++H~nWdKTnYU$H=A~6iDXkO(4mk4U*da|N zJrvTCcs(>u0CMb7*P8`d6AmGo)T7QocTUtKi)j+7(PX+s1kZ*M{~;>bWA&hjO_CdJ zh7DaP2A~Z%g>u?yP`b6_&NtlX@J~DK<i^fM?zp3lKXB9%WJlIXq~S%nomLMvy10^x zE3T9$o_yvJTdc9i68p+4sk}msq#+LK=}(sZvre_+U~6q(er=W@K@dqqQA6zfqlq8& zgrhA+v~nn|yVM~X0JiFo<S2ncVUx}!-3&CERT)KODL?2`;!ln4BAhTqpte&_EpYfF z4ywJWy6%JW0Cz|r^?bu<#TbT5-AIjAcI$5a{8J7$x{$(3uk4w!p3E?(m6ljw0V~QW zz*K`@RSE-jT{$ZeZEd)4(!-8A*5q>TLZ$UqPa}l<qs=-W|Nq6Vqd;>i@;WUM&5uX} zZXMKVmg>t-I%f99-*l24$d60=0Lr!9IfCkqKW;!mkHl_Y^;<oG7~)UI_hP2?NY-T} zU_IWs(n?r0n-X7I@qzW_d}Enco+zRKQ_M>AZZ<O3cYCDUX5{o~$tRL@Lr*y1BCWJG zP5+~gI?@dkQD@}N;zv2*sE%gV>@JFWnk9WhPd%SlvdJ(0So`Eq^#oAQHP_HHPP7)4 zWK%Ebbf>)eX}Z(SKW^0GTsyLI<PJU5JfY<Gh4Iy<I^@XH=D!~GBLLVa#w$eO3T3@w z6>=$ynAQ?3wwOW`rQjLSjCVetP(>Z#2!|giAq!df|KS*(p~uj$hnId>LlcV#M*#8H zrg2ON8u0kuUIcZ&3)bc|;OIs@_Q8u~NJ0|&SVmpg1V4@t$V_re#x-;m8;y`{Gd4L# zFX+K9f&dPOTI@-H<l&Ec_@aK?c*i@mlf{YfM}0%!#!}*eor+M$e+a_fkK|D@#*Azw z*l5NoJ|{s_umXWyLEtNZWgZCvgD&+bo^A%Boh@1{QScyFH2e^ZF9u*2a>x_8E>s{3 z4unG1_#Z(c(k6Bw1RAs34;;0IJV@dtBH9VqKlafJx~+sC=ZMAQuwhEt`D8Pl`OGcD z0h<kh>^Ph$hdSzU4kBvfG-re*HKBAhc0|b+|5bR$I2zKBk32^mNLbrsruiRwjO0M| z5QZ$?fv$gmvLm?ihx7JWjAE3cfPP#>1pSy#W!YyX4e87@tBFNBR?iysn8PgkL5}6n z0~#SLM*s|jmvG1-7}jXy+w>QWHEaVOc5G$uT-h#z;>Aq;*hehV@tSUogDyB>iJ9Pu zxLK{EGxbOZDvSvm>KzRu4w45r=<$+w5Y!(9MJZF289O!9;veid%_BL|NO92P5qqG= zHr`=Q%N!^k^l0WJq(B8XIL{sLXjJ3&lg{jjm1vf_XE9jziefb5o|du{Jx-(4{?Wst zOg*SFl@^YsX@g$j7#=+|F$a3Y<XcC?|0(N&2aj-w<fbBFhcy<#AbRnxl+{_3tp+QU zzFNv9+4zU00;Y|6B*Pi00f&o-@(*x)BLLEfMPNb;l7F1-wZ?D;JNP<T(;~MX<=6&2 zpxP%=exx3jz(WAMp}v%mgdOhiMm?xNg?iA#7I5eXtJD?U3c}T|U-S+(9<mbCP!GB1 zm8v!95Da&8G93S)M>H1E34hS5ZXFrP?537G|6SxCHW9`gtf3U&Ld%BMlW$}sa~k0~ z;~z9CDp9eawmbAAHGS3WMq;B4dGtaWCbTAY0)`E85NsUUc-B%Wyv0N%=of16$2fpm z<AWY401xxWbFK!kYij2k^?*bm|HcXvNZ>&o%w?rdif2*48b~)K;i!#4#*TVuf)L!4 zYD7k&4QnLiKnO+&*}@@@Mx2X(RG!Ew>CrR??@m@GrB#<d;@)!jBOS01;7^kjyP4+a zh8;O^iZPo#k_`B^;9$o-DzP?y_1Ux|In`0901xX5m?A{02N}EZjv+Log@QpRbW8FM zcgW)#L+Hk-l=hD&G(#Tn@W)S<v?L2cn9j##Dq$W%j(^O7Pvsz&Na`UEn-HQA>u_|h zSG>?&RLeyFW6GDC7LEtAdQyUla1EydY2*f%9=(_bI5hQ5g0x#6px6gFytBBVc4Ri# z0|h@+?Ga^;BzEHqpmyGx|7jaB4k(}!$3OP)2={RrCCwWG5+$RXSJ$HuO%?}KfTLC8 zo$e>TdE-F^H0Lh=G9vZZ#vG2(C<Be;7;6Xs@pfbIkEHA$h#5(+S1pn=%ONpK(erio zTyZ{A^C6Y$At=DH;dh@68}J~Qt|q<ThYTBhZbAnr29jH)#}gx^`_VdjagKWUIP3?v z4c6Q4^I*!O9o(ftGt_Y^MO%c7$L<k4#E}uOZ^j+KS)&(;+>T=hz!zEnWJL`0WBEQr zX-xA2Ido^`-e~a7^!i=M+e#2^1fA!LH%L9?FpEWAr0s5BwdxlyS+}bmrJdo2y3cO4 zbyRgAx=GNW>3JFw|6}BAOxLiPxCpme!lE8>f==hxPMcTuWa06kf-ma9D!eCd(+*RE zJjMu>tog<rV0=RWcRi4C&?6IgXd$nipQc~tj)S?d+R&rJYK8hC7XeU5?mfbkr7Z#_ zutY_vonE*Joq${7>{)5Gk}JtxIsAj5@q?xKUi(c1>m<WD@EG=4#HI{HF9-&0VNiC_ z!#==5_qZR9j2j0E+m~g+8}L{G;!(q70v!AUH#`ykWEaB`&O6{>`^Cl(goNv*AY_z8 zJk-N1$U!|E+rKzTbj-pW{DYhM#Q%ju0QSk3tyqF7R7Sl6bR|g*{ZEtp78#z~7V!t8 zNy9hfmLtUj|8hu155dCFsLoF~9X)^oI&2{_84BEV*gC`lI*<beTA*XxQJ*a!wSeJ4 zX$R}n!W*aq!&$}S@nJjogD>bF$jpXztyMid0X2{jN3{dP?Lps!O7RroZ77rPNDU$M z$?t`WZ{$uT5d#EXou4Jm(&Qfm5}@0p+&VN<@Q{PmSjC<x1=$?p+aw|mZ3fug$3B3< zI&9cLG=$r<+dou-NO%V&QiRim#6Gm4Xjv0{rA7c$0y=~kjmhA&B%FLLBLNm$U=YZ- z$b%aA0y~UD7vV<S0ml>kLO;A)hFr{MoC+9ym&AzT`!qxSgbK-};`4>fwCNnS1pq8s zl(n!!|2TAl@X$*R;+)LY!zclnXtf<yC}Bv7o^_CoysU(hl|#~C6JQWsA_5=R2va?X z&A>IG<AKtB^usjp5+T+kkZp=Ibe%Q`g=_r-I>drJXo~6Ng-Ml^Y3&)=+>l$L9}ZB1 z7yVN7sY*ZkLi<G=cIbxS)q}&;1433zsBptSPysbOhZ{cRZGc@w(227l<A#i#goGY& z72<%cgUp4)MiC%Mt=g9b&o_)xF;<6F#1%87!~T&_ZzN+$y(28q-X-jVy)B|%*hC;c z7YqK0l1W1^uvU8!p+!8zeW(p<SjuBa7*)uZh>+VE&cr`poG-w^_k~(V)Pow}g7tl$ z|JIobR@nh01c1Z@25`ZHk_AGOjYI#;Wq;J!Mt09FM%YRaSO6@7v{50>O(B?3&39@< z<kdqk$Uy)s=8_muC&|JbECD5a+kVy7popOvZVN1xX1@@K$>|0*$U_ExMrRBqff!Xb z7z}>=WyJ|oImnGMG!Z!{6E_}@L?9G0o)k5$B3SX{g@RHR5u`Zq+8(@v#QaWSq6DiX z-a(FJ7rBE!P{R-y&h=Hx#k9ja_`(}Zl5ybMbmB#-NFE{N0`dHV85xf<{f;~wgB)lB zto_e4jh!~o!-Dh)*fpR`N?!g+)zx(oq+ymHEJ8FKL$qm7wV<MCB^>mb4{}gc|26~= zI3UhsjKt9F11%^YJUIx|P{fJB0yL0NISl2M)&zhu5l#}+IyN3cZRmsoR@)g!pel?& z&IUcql4Km}qh1Ue8BgS~!zliPRz(bw^dh2KL__?;FFZk7iYgpB3UK{Hj85U2l_gdU z0X6iMLj(qe`Y6;iXzomiguK;&ke2>jAtj6zJONgsLdZHu>4GGUmA*}b<f1ibDYI<| zr=CRS`GGp{gE}BYHK0n3UTM*(>G?bhC<Mt$ik6n$Rsh7vjF`z#B8QpSQaY>y+mPy& zzK9&6UGXJlbpYvZR3<F3%SkBeXl2c&wL>|4A~>*$Z|G_OkWm1jD)xx#|COR29zen( znQD!yO8Wf6ArwMCYy+(2>#pu&>73^rh(k1m3x<*nxol9-T}?HvW9dvALPUeL^xQc~ z-W&+SB5^5}l1oS|4ILZ<o>>EW9;-4Xj%6+&Gs;6VWuP0GT!MuJHv9u7T*GO4Bx3|X zGDOzDz6dzzOF#6()%rvi0SNQ?1_R=dN<P~-@B=wq-oR=qsLaDZl*%`-N~#3KH~fP= zf?*f=-5X?rBPE*deQZ780{KY{%07l&Orbvz!Xm(fzbWg1`~!1ETSmScukJ@gC4}xQ z75r(CXHC-3f}L(Olexe{K6b8x@JXH#2u)@v>agZ&q(f`<=tX!3|39!)?*iz_R?1C) zU|xiT5+#Ey^usrJU{I7<jrP?z@X$AO1L?r67R6D5jM@zG2BdD<JJ8RMyxPe9gg<aY zJs|Gyc2PY*gBnmnNO<H(s1-NR1FH4I#7J&b;+`ATL$t9(&q{{>EGe)eYg_3?IRrxh zM1!B4uDyf<G?ebDF>1HW$t=*ruKC04L?II<Bktnu-MrRrwNMllpbmLhKWL_Rd@V(= zs*;V5KlB5E{;o%8N4wR-H1vY56q-kvTxIA6ZRHZtj02!v%m~{Jb&yRr{KF>@0TW2V zq}gmcQp9PjZva3-Br@(;q6Gd5SxB&|G8LpRP{BA@*O^8H|Eqk1KRCrdh{Kuo?@z2G zLmb92goG#Qt5n$?7LrTPZN@h(jT{hzKd4F;os(TG1qDBF$t{ySkV8bZT#>#Tnni;( zB$EiEAts!|*nY(GI#W)FP4tSL1+~z##F7$~!@Rlhf>zi_fQ>NlK_!4fFT{Z`1VB6( zP3~S0qx=J_)Pq(v12t3u64Zk?R8&ls*1esE;1UjzLB~)u1idg>a<<aK)q_(Ap8EWc z$25#DAc6XZV)M;$>Zr;TZbQ)NM*rz6JG?_XPzcKOoU{f2IatFS<bu#f@brQM1@E5) zTk5hc4es=VI*iNGP=Wx;vog}8)S8K)jYHa=>_oH||4z^YKXgWCD${+WgG;0XwMp+a z1+P53#Eem*FRnvF_`?KZgFfhkG)O};`~p*A0_`a%qymk{M1()MgBom1_GEM60LOle zurk#H{g4AxL~P!2VvMTq!z%MNjUqizpW#Iu8H=bI{G(cV@l^URPH&Oz5W*)=)Z1mU zZiK@^onD^lX*3^$AE?quMbgEDL^x=}98e^7z*p{oUNHC_I}}_<z{AcBE!5tTK$gw< zM1<g?LoWo7bO7Jj4TJ<X)3Ws_+2pX+Izuuznlw%H+xUi`SoDVd*cd+uYtaKbpaMEN zk9+yUH4qV;A}d(Gi)4&qFdyWpU{xSkf;^0a|5qUt)D%xWaKjK_%w43)jV@%YK{a)Z zB0NxErxFQoWLc+jmp}Fc8O3R0#}aqL5^^+BKWGCX$O1E&b%jQRennyK;APlthIRzw z5^96y8fKDgLjW7ApAcYSDXAY^GDn>TMft%jh?E?Y7Gfiv@?2OwjE{nKMxF{)xJgPc z2*aQHhIAl@4rLG5n$Qcg7-@|}Mfb34oQd(G$;Ie!X{LibYy)l$DqRpvf<njYE%j}n zG{dk%b4d3z2f!Mo4+?{*t|bUDQ~{A8$;s^_xmaQtiL<Cy#_xfV8r)V@Nk{Qu94^>k z<f5rm_Teiju_{I+WLt)Vl+%7_N0#P-|1Hk*e$%x*%K<ZlLp)64rUFw%og^lUW3;Xs zfysljGK5GGbxujmxj1o=ZbwGa1DtgarzRqh8&8eb2HDu#K3qaQbVG^f8|VHBQ<lS1 zN>%gChBo|zGZ;fm{V+RDFGq)lr2Uw6yjEkQjJqY8a>-3&f6<}vMlYYX_}Qb<P*prM zk0ERfR>dSo00$i4!Z*aFPynuAz=18a5J$<<c5Gh&Y{N*L2B$J^HPVmWO}7GW?~x(+ zVc&3VBTjXzip;6!&1G_K3^YgPIz{-8l<o-=s;i)e$n5yJUUP0*Pfed-s*=2QG+aB1 zrfJmX^g5&#sr#^ZW5f{CR%t4{|JK^((*^)P#6mW>Mp=h+s`F5aaSX?!gqe&3Q+5Z% zGj51SQ;eGlxj;IOqzcH^f*NcyM{TgI#e{a(3gT><-n@Y&ILE~b#Z{f<Bb4ZHZb(D0 z&I|s7_bj4rGz2%u1LDH5v~zidm207hOm-DJ3_p6?Xc9dv=9+gY>1C8ig)T)zh&-%8 zFwD@JgO8L3KqDMj(vVhKBgTQG%D9kMMp?tt9QXoas!eikYRJPm7FY4YJpn>Ijm+C1 z-dh$`)jkBkH=xXe{Oi~$5y8-dro@9QTLjry$~!0mKTP16gh;BqB*R@pPKbKND-5gZ z?Qi}<B${ki%mY@5Y$Q(i|GjSr!*GKdG=p}n>St@JOkmZ|I|oT_aC6>T^(9&}21Zpi zGd;8~R&9CKgN$KoO^yhpwr$qXd39du7nP<<ruLz4v_us8gPd7Bfl1Ucv<;GPd7J#n zlFH66kqzr0hDZQJxpMO4#f!%-K*9j>`l%zh4q`-!6C)C&M-Lvngaj3K^!O2ENRcB0 zT>SSBT)lmu>hS{yjvz;p1W&%?_Yc&*Z`k_v8|lyA%XF9C1t<sZBFUNZ64nG4Kv*w+ z*suXrDidPLUg-SsJDSiSJF)Ei^#iAkUo3R>zJWU_Q)yhebDREyD0W=ET59@z^H(&0 z*mv&OannK8-&lm}|2p1f*DipsCjq#<dncA|NU`qP(R;MVBgBgYx79=93**U+Oc%-% z8@8TgwgwYYv>j3DZHfVKXZC&7b%2w@Rb%$3TA{Uiel*onw|b;R#s9`xlf&#C@{Tmw z(aYsWTSI{mqeslh?%y#v)~vmiXHs1~O^d9l`$teL`R7e*uX|{_KZ*!4h&<jH`whXk zPEyC8bCRhC8}w+4>mspU>W7|l0;p#ke^~nnB7(Z1=bCE*;3q+mvI2)6e_+`Mo~rx- zE}@s|!Q>o&s0uMAn*K?soN(&N29$oN63e|5l@!UxlYoj(4PPD;OD2QzdZU&A2y=~{ z0{auIopzcT|Dqml+;L~gD(R`Go*~phvp<3|`iB}dsQGI(xD*1joqnF6=AU-p)D1wA z03>wDMCBol(SM99ut%}N31^O79z8H5i7cXroqnwOE*y2#Nvb4H(PJkZN+=2MAA$ZW z@4WQZD5t%DE)s|xb+lQ8l7AWkN;`zKks}y-?D9_@LLr(|o_ZYnG0|v6`llOzXxYb~ z;Sf{}oP7f52St)j8Zj9YOO2K|o9apC9D2x+%SnH}sRtccS}I34lImg6A7?h~Mq4(e z9atg8fU1X@A=nWIqzdJ!1&#p7p(k5twG-~2((r(!9&-M=I7NTp`G*@f;Z*3PFg*iJ z9LU5C|5O}$0x9GlaR6%+XKfYy5oe5bCU~xs*v$Foj|66?9Af6^21S8)7S5!9tO>`D zT<YnLo{m&gCz>^^iHFg-D*PuJIik_#q>Se5r|h$RN+{}t`l*MI=E!kWwMIJ{N1;*I zWV0TSf%dJya>%KNm|oIhhf6OrJL{ibq<Kljh{mC3nRDvtN6!@hI|-X^FKMZ*&O=-0 z!gOFsCv>q$g)T6$j0`~abl`dEA|3}%5UX|IDXow|>R~v)0|{!!n|gErG|b{ZI+GiE z)Tm{~fyJ7$WOm$n=fC5{sRt4})M+_Mk9rK#A79*9=gifV?XA4`ciY`iWP8Mq@nk3J z|0wEmpjmG}gcA)tI5&$qP^Um~OOG795f0awE>r8MkUCP;EBkEfBwY)KH5S#QI0ax9 zatOdU6oZf+k*8zz$VDzn!#5xC27>fk3Q$^i4onzHMlt+}j<gW~$sGkI9}3AzdPuMV zf({(%=tVYA0*(oRXdPCW7mmi!!;`#DA^1~Gglt%k0Jz0g^l+REeIpP-QR4~Rs7L$G z)tYvE?+}M@N6TJiAcef+8}gW5)&?dM^kC^n2&vFxV)hw&w9GiY`;R|3^$#5QV|%U> zqp}Qyse&EoQ1Tli{r)o=rsQut717^nayO20P@)m_LC9PRG{6x?V-Cy+z;iB=|GRa> zrxAo;hc?y`#{NWbfVr{;ujpZ)T4qf?i`d{5`Dl=g^zs;UfX3AZ@}5bGMmTqq#SNA) z2Tc^S9@Vs^4#_Bzv&iET`%p*d;^B`?mZwG=BGOdAajGuCF97fuib8-QkrWjVblO;# zEco$_a`^L-2?0ts)^&}0fpLD0u@HZ1gdTF1b0p`B%oEBq7~^zAWwoG!KM*;Vk65N2 zxKKmQPKK_8+|3YypvN|T<d`tkg9_AmOgkdFj^Y8OJ6KvHmGmdk5+1c9#yM*77UR=< zw$hTjQw)zdf-GF!^HR+0R5*y`&Zv@PsuDDoI?C~#@L&x|zFN*K#u1KQ{~Glpih&!a zbVW@27~~`Z^+O|^a}rHi^B?vRL@umh(W3UIAOFZDJ;D)<MQ9=%h9%WIG1@SCU_&Lb z;0HauxTJavr61aWiDd(T4Soy-Uoe3dx`y)-d1M0?yF>~fLy|gBOa&W)8_7kmQCXlB zr5@9(hmbn^k()My3g6%iaZZY+UreTDPK#DXMs*0`T@Gb|;^`2!p^h-g<s#qs2PE)N zvz*mMZ!b$Pdc)@1y7&xmfwLHMKN7WQZljmK$y?Nv<A+(yl96>`&l;kEp13KfRK6M} zC7jb8j46i@jhN*~0vnF`sB&nH8kH;vQ6H`ygAUf{2iBzPUf}Sf{~p(P&^R)3(Ydf| zU$FBCHspb$cMa}-i;CPn<na_H^%xxExWu<!LR7g}B>?eIND)o!8^9!FKQROfH~t}9 ze-H>+L><gOED?yBL1vW$<3<1iVF;4G)jt7vqd#=O4ez#toDea{8L7Yxc38%*y+IU6 z2!&U5eB&GBV244Th|yQ|@*hB%6ghkck3&1ILiEstALvoo-`oZv$5;bOTNBu17B-BO z<uiHyu|YW;BQQRChjorYUoAR{9oFbtJJgZC;$>uRA*@GXQ3XOdBqpsc_ANvNg5no} zgT|vwkWJ{pu62Av)VzeULaP@oi4<EN<$_R8LPEoTl&CB9|KO5u!10X$5UC#wZL)9R zF%B-5mtkMs6RPBqi8pj?9r4)Y8{5>3)f$m~^gv^+&-9vj94-@h=u23_JZdm~j|#r1 zhoEYzXWalZA|_naoBlD6dAP$}h!M85C_-E|g~OKf0}{S`UEGoXvNbfp5G9l;s<5ad z9+C)vHfn84x=2JwYdD6n@LKBsMZ-QPA*x(Uy&Sv!2O@c;#~gz34hAKLZG`9qsOz}y zj%1h~<)DW*R`(Ls6!$mG);2b<I9ICFqY~(NN9cZ3;uJNiSu1Htj6p&<(7puG8$!EM z1XhpCL5Pud_j+~{0+=CCV;%3PHj@yB1b;YCzQ{Sr{~YP@gkQ)*BS1^pJpQ2rQH3d9 z;w|$#7)D`crtEtGa05$;<22^B_anrK8bYF5h#l;p3blAgJLVM++LDn}jtYA{pn;2A zFvDG$@7a>+;a_rGUAHfT8Ug#UK|kywFz_&ztahy}&Hp<jLqiojgw7a~u%jN&m_va* zV*5n<!#)un?xNUa5}y#m4@3<9t|r#3BN`Ipz!q;idQ2PS!5EAI*@EchMy*+ff*w!= z9300WSPm3UgdEDDe3nEaK&L8VK^n{=*%r_yKp`FYAsp%n*4j=a3=SStf+bKah!k)n zI>Q&>fUJ}(K*Xve-T}YhU=k+I9iYyscu)-l|KlA*?Kd8-P54232!kCm;%>;RW)i~S zK%`U*!ZPHcPN;!mghNl>2a0$^H1gsXlE4tCp&5Lk3JRecSWn#CYw7;sI|N}71`8e> zLVvo>BZQ7qHs$9;3CmDU*R&yPo<kD|;h-i9ljQAmmZcu#U>9DG9H=H2LZ#uNCSEXP z7W^PcJcOt!%nyj69Zr#2=z$Oz%&qWADdHjY28V{QAsu2N8&D?$g)mWuVzZDfB$R9) zXrUee=01c-1S5h3>%oRXtG8O?B7g#I9HbveD1Q{4hd0&#AIGn2T&}xZBlEh~Cga+h zYws-~$+Za~6;ftKWUplJS(jub**mTk^+m3|%7~KW{`~%d&pDs-d7txseV)(f>+vim zNapXdyme<s^RYi5^0NMTJbag{4X+zC6t+%!vE2jp#)m0seW5MoWPUAGNKSGh3RXSb z4PA*0xVo@Xd1Gg>F0&+=CV|O`)O3-Nrw(On(}IRde%zZHC>RO5+auL1X%QU5wP?bU zhi1pYv*UXdfyG6vW%A9utTN8P)}ybZ8o8SheD`|UM<Z<&bT(Fj+uN9&&!pSiqwKZ1 z)`;GmCVf<d4wsCtWs<kGW_)8***%;mES7!@3$x4&aPkY_7LP<t_q?Os)Vtv4RM*_+ zj6n^S@ISE3^oimY$8aTUvi)|`7mrj*w?N$I<q>z~kI?6gOG9mL98K?*sW?k7QsAr6 zsKhuuXLkwxK`9z5`~DK1-%i2Kg1n=ywCg?YO$SDUJfhnrEX!oHON>j#FUU*>pIV^? z)US8#D<0L^!>v~KmJsNVj_TOOuy*(L^<(7Ieq169%{JjaR6II-Q6G~v5T*F+%MwOf zJg4ry_}npHjO%o#r%!1DTQ3GnC1^Q|?=h6xHT2zeCvlI9ZRSSZtBtkV_nh@v8{Cd7 zN$M%-bUs8<1+nz9VktC_Hx!Je0KZDOBm5tEO8_=E*vCsaJ4n1SJS?63K}hqD)dPnz zdY!~K5;=8jg)5&FtS|~%T-6$&*eb54u_nVMJWvvsanNz8j?<_`7^{FItuyU-c}3J9 z_i^vfT}*fK+An{J_pxgeT_6|=AFMekRV|u4PG1&7c5kbl^kc2!UMXR?YRS9Y+*7K1 z+iZ2{ig4VdSG9D$wuxiu#k0gDR~`>)X7SuJ_iJQ{vf9;{ukSfs=~D(0a|aDMa1~o; z`c887eZSVunky|>%UB{~zq9}~lcde1*I54GxkWTE+ZX}0sB3aD$Oe;4maFb&m;hUx z)+GhY=O{riwS=OjsCBPn@mu1#CFdn3xXV}=oH6<f%?NxJz^P@_pZFf_VgV9xN8{nP z_m~g%xppyH^Frtn{@6S|bNzd8bPsnP=&nP$HIyp6zf{Kgxfl%}iq<)Kfdm!B2aA`H z%AePpdvO+0st=d=u*ai1P6@7>&mM|LJSX4hndnna>4A56u`Gha5!x1WE*t`Mmk%{y z>lCxDskh8}*|#;em4;=p{qPn)vn@kW*H1njgg}`MOI6TtEEUU&M)TK^t*0(lR6Msl zF<iqvL$&EwZ!7pbN{hN$U4@Q=%9}k2&w-lNVl`w*kK|?@&4BQT(Nlf7)DZh@pxYL7 zbctCNm=MzH)$8(bSs-!P`z$U~aK#m~6^e@WTxVRwX<H3)T#}#y81wWSgP+qBCSpvh zBe>!oSjl*C46Uju!ObgAlMS6A@A#<bVg+U?P_?l)B5MC`@^b2qXUAvDHkWwkMcw-T z0HfKj*f~ty*R#aLt2E{k)h5CkOcrb0t>mm9j$X+4*e1frug^QIi%7=c`LkqMe{r*v zFaYo7!}jE`rD{3rJl&BcawPU`x=$)CxUf~7uHhh7UY1czkgLAZj~b4Zl4~+m9P5#s z*gekB68`6+9Lg*bT5+5<z%PTAoEXhxWULs%(EGtSR_mvC;SO%19OXj+TXugGT&`7! zTg6s#{a#@xz2Pgp#wYIK@@oK1poOwc-;&psGZLxsu0-uOsBph^sBn`BYY>m91(>~f z`Fi@MxfrJ=TuPd<RzVKcOGouvP(xr?sW@`}s}{_i<ej|38@kT3TBdZDUxGFgq2TI! zs_i{%@f0R#?-~^wOvlnhjzj_82r+02C;;u7Hu;pDkDU(h?&;xXH4<_)92eF->{?pc zEx8!@f~GNCB6#kYM%hkNv#zRfrA?t1Nvb!sL@%SbP;{KyG~t`WHz<3!J2m{gtPGM4 z{8FzzAmy)Z3b-i7cO&=-^(ogj-gxxq?U}<>rd+P2NY23BPnja&XJ>R5pQNsYDzz<c z*bp3uw&oO+$mPu+=0!Y!%vp!{QanWN{F?3;xfwg~Oriy~8KH7rfwukB`NQCnj~l1y zcbM4_9}uVblTIZ1P%ho=QC3XsHa|-T@K7dDoC>HlfoDr*cqk}~N$O$qgQ(KPntN_@ znARbaC^(cf*iOj!$B(COP}xN&X%8sGyn>pbnzX846U?OzQ4=wo%Q#kr{wdpNX<#?< z>L+pqQpD&QA+UMGBjH9|r!!TA2zLAzQHrTuVe9p?_$_MM#wXGIVBAy>3%QS6jwr83 zc+!lpM`^$``Ps}EOyTjE5UQNeg$96lWJu2I<5_sVi#33t7Ga$WrK;|H>kUkd@)U2% zYg4C;K)CiO9-H7E=kY9ORMV9T5`Jqq0EO#?b@ZPpWW-b7E|pCc#WeK@5_+=a0(mTx z>pqrTe}UmX!En8{_{N@YE#My!+V4Ld$<m^Mnx(Mo^h;f2(cYs-%?Z)u9MapYM!_Pb zC_++}$Rv)-{<ytRC&;Qlp`0_>&U~=Etf^0&`cFc8jPwPCHr&hhD0K30t1>JS%=aHy zH9=3b52M-69V`;A`xjkU=4~Tc)#%Q(tKl>tmaQCxV2NxooX?&!&m7izMjij`V;QG* zg{dlJt&(A(SwmH&-gmuO=y8mk`9P(X8`onn?>32zHulT3aQ^mPgVeIt?H;ka{fW(# zOig%^Ge*&nN(-UbKyiY^Hv80xfC+Wm(B=SJQVEB)5$Bik@B|rSmS^IzliUIn@EB%A z6%pwv-rlkbO`wy+0?GJ4jg~k7>W5^*Br+_fiUT6@9Ldu+e(>!$_8X+eO*6_vNh%6Y z&KsnQHR<PJw{PvHA@VM}IqOyau%W*Uc8HB1?9Sp7?tII50U-OoR+OyI`*v5s(B+M( za|hd=<<CJbA)Qzapa-m+b0LPERv;)=TjXK?V*^&J=18u<RmFT-p`iX|n$Bj<i>Gfn z>{x3St2OtT80}t5xdz4PbYKdqonL#~S=g?{eAYl?|8fbMw#)xkY1QL8Cmm&9XIs)} zkw3Q`rMuk!t~;Q~xu_wRImWeKUpE(|u)NJJ^9to4?cWvIF8G9}L(otDCHwOJyR0Qy zGA8rtL?8E;g(uxI3!d)9bC~8S_hRI42;V&$WA7Abd~GXUT$_^1V;&WFO}k>T<f{L$ ziGN76-EKkKlmic=?UBF3!RP#)+o9bW{P*cf<wOyl&JSl#Te`SSVoWD-FO1Y--{H1( z6m(l;&nk7t^RB`&^7&pR>K}@Z($UWwQ0s5`iA%5lVdM(CxrtL+#86?#S8mOavoH~i zVKhC(yPFl%n0*seXNl1)Eli5!4gNP8S|IKni-O>3fIZh-No$)Vj(x3+Lb11$6sXq^ zOXeS8cS+JRj0@I<&m~g)@+c9E)oC>QBX4QK7nalhri-_o20AY&j?%DW2Rp7a%xWBR z_fLN8EuqLryT8}tM2@_XY5saq2d=aI@p&!<xkv0%=<|vV77_)QNF=J6jG-p!VuGD@ z?q*CqTc}Yhn0XS7e$B=eO44@t@pXo8sJ;~iAtAs@1zTrB1Vk9RgM+j0#iyjbg84_= z+R!UJad8!jur3LVCT12Ew-eSjdu%Zzy2S|aa`&}GJn9F{m{4y9%wvvU>BnD6)CI*I zNJ!h=7yGxOn<-cDS+WA9l`=e#NOlfPm)7EA#~)+S=wl#yeZ2OjSw<0n1iYX};0je@ z5t!GvhKLxIVDjZu+5A0>b{qqnsp!pQuJ<laqu#kxr7dg6!Avf#Zc5}7d44T?wm9;W z*Esen@mbgU=Gw<3#`(zok>)M!*p=>zI*>QFsy{RL(+d`f<w0_#Qy-1Kp`4d?1{Sa8 zTYW=x@*S)P|M!~F*N^u$7I!z=kM?Yz`?OAJttO(zlEhw#%L*quR?45W{dqi}<)EtY zZnx&v`}yxiA>TV|%F^4HRQyg>T+g>ANQ1Baa&*UqCT_ofcpT;iUXA^#9&qa9XRLg* z^d8VP%li9@rF5%>h4ke9#o#yjkV~FXmiIwd$?{XBKaG{iO9S6GAmkZseMg0dK9t0h z887||z*FVDZ`>_=9ibHCkwqFOo@J>ICv{G~_@BmP+*HB0yXPvA&M=9gPuk0wjAg!* zzmO$w_usLBozA4loj7C|t6r4zBb|6PW%5<NipH3#Mx+I0lQk0thOO;5(g)0MPB65V zq=YLnSzDjDQW~l+IIZ!d8;8U#XrE+S!6m&fq?1+j8#1`fyk0VOE9|OhyimEev}plY z#r98RTCaMrDt`y)>EK(ZW+2Fa&1=a9xBtAmZ6@uWIVZn3E`5bzbw$$1kbR<yR9qD^ zEedl;n#sjRVyAY-!4p3x89%KkZs*hO@?(^DZQsTVoK*ju)Uor`w$z=fCl#yIkN%$I z$@H8_F?%3D|2gT}Gpk9_K!DJYIC-7=cAbQ~Y^{9+*LlvPJzK`{U{T)~e$~87Mwsf% z(`ym&yraKTu0l_1X6iA6YhvlJ7mVFf+f=v-GYZ#h0P+>4|2jh|gz-y$J61%6K|%C# zhF<A1Q>&^MVprn{Xq}@RL0!hrnCAYCZB8@z0g%_O)mR#Y$!oRs9hu(UFqkYnT@;v< zFq^gFAiU9F<+e>++A>#MOSLlf{AXT9BRiz|$PW<Q()R*J_Wx;mm+BysrHZ$2#DSnT z;rfaFv+Ykrzukk=g8IDf^8mmUk>Q2x+48>pof80cimb2>ubzx3byk*#o7<SRJ=@gV zPwZ0*;KuO1acjKbk4!x``xQ^CNtq8+h>H818E!IKYv#=`MNDKyQxhad$2%=o*I`Rr z15XK4DkiYbeUqAw&eao}DT~(hyX<>uD@s{4NS655y*BAfq0$73u>H0rum7D`_JK&E z{P*g~?Vgr9_v<UED;0M2zrPB=NeKj^4^n^1?%wm=o>REQ{Xe7C@@0owCC^q{p?*pd znnr89lJ<;ybP5i1uR^`I)lwY{kYD}hE6G)&#Vezc;Ge1Y<lMkE#_39|`lG>k>ICYa zpe_vX<z?qex@N3-6K<TZb+vL`_@nxy6VP3Xx?;jl#O8K<RUJrhH~4HXg{%m@O8A|g z#qJXxyiLk2=Q`Cly<EggW7rQx_s{HA{Yz*b&Q`h|`fG`GK5G8>j#AP3Fizh1lwP*F z&vi-z?=h||5YkEc)Mx)nL(ySb8`m~jBNNPQhXd2@Q2~&_XHbmGtY#=e6SF}9GT8PM z%!qMu7^0o&dB`9JyX?d0oD?^S1M6JIo$2I>F-oG>+872bC7sUWw%IjkKaKnIIMxo) zA5g=?=Y)Cfzk)=8M7ZUMCF)dPPomfYK437y21<9+_x{Zj%OD|aQ4^O@Oa<E$o`@D` zk9WiFr1-8MMtBA3srr<}KFv+C@{fq=(f86*`P^sm&zw@+ma;`UIo|DHg+>`jK^Gd& zd;2IxPc=_6#_)qnhPr*6fdH^@9o>K1%j%|rP!+7D-|`C9605$Bfav?iaFT=Zs-tNP zanBhI95v^qYk$q8;{3RVQv1kqtY@Q(CgmuiLcV$uNZIYrb+#?61@_yCypMGscVn)u zDq&UmX=ZYrj_UGJaJfzYnQz0&mGUXh0{2PUsrpt8;!BDCJi!{rL3c`BNa#hxoMr{% z`%}u!Bvl`DY9%ze#wlNDybu%`P>B1ZS9p0u;}GV;dAKlkWd94UprYw1XT%X46Tp~_ zpz>;Qo>Xe4s0<*wz_8<E_(T!OKb-p#ozL{w1+?27VknKNESR2MI60inmgQJ~jo)?( zD0`Zeo?uxXzbz7(j9CV8bUs_XGae${<jVKvFJM6ZOtP~yuN*aw>s7~&!S<hTys4^v zrqgJ*;7hfY*X=wcZ%DqC_$XKlWmdebpk`>E{L&S*dZ>p6Ger1yMx#Z4>PZ(C!vgy$ zQRoMTmR$?5(M=0?D2tK#0{-^q)8?9w&5R~8l5wH7(fpuSec}riuzBj=L+X{7XUMj( z%GdR%o>VOb{{>zyO`V5VnOQ&wMY8dRsa;c#t~!x{o}D^^K(PXPT+u(Uq{HxhUGyNf zx*GbxA)x*ipQF9KO^O!NYRV6yZBnEngU1|D>Ra1dQA70gmF4>Du%iPGZ;g!gpkOJC zsZI5|hOXbN7L*!x$BN@;?l7x|i}MWl;Gzc_(utSdJrr(21M57o^08tGZn08<Ns73& zw%w)?IiGhPWc1&TgzJenfWGc1#M{1S?Y>SyJEXZ#|M@Fomww=*#PS-X9M_#qI`y`k z&n=;k8&pECJC`2A1xK_JJKvc&?O5n~A5i}vC#=#&!Kt{k^)8%4T+8&uC;K1+sZ<?N zjZhYNxZWm@1{=0^H2Q!L=EF<XPLN17H}hG3VE2Rqew|EF8ZN`>Pu`A`UGIhzK35qz z6iUf@`sw&1L%$)~zE3jg_t#rJ(G^lMjxT?&BBILW0YBow<c{G~f4&&b#x@3<-9|_} z)kT%3-{QB=$4Hhxlum2iG|8&lssEX~&@wzINBmhsJi4+^X4d4MT0YsRd9%h7rFeS% z-;!)NEBRGxW&4T5<wEkCe=f*-wB4v1w<lWr`u5B0GQRM>D30%(v3p@lrON7qJ0NIr z@bQ@$3zyJ6mV38Rd^5LNuAE;}rWCb~6L_Z77|-!|{ejZOsCtJ5{Jujp>YLL@X6UE; z4MHQ_G+>;~t<lu`wt^@#b&uH*dLO8pc3HQ}lx^H=!t0<l?nnh~mW|J@H>nk5YF<*Q zezql0Gs2xaMB;SGvkV>g%ZM@G%<Q`aQtaCzxd10|zBM@L!-b`QFc!YOV(G6x;mZ*m zo-@HJcqEz!A*n4Q9Bqsmf&}7FEt;U7Zu#E<0VVU1$3tQhK(Rc05ItU@^`RyLc-vJF zPPUkW@A%U#uxOn=;PV?ogbX0aIM_)ljF1ZJdaFcw7xqg>*+4@_D=p|0;al`bI^`64 zSxnPKg#Sb{{$OF5vVy1hdjM8xf(L`;wUDew4_1z-x&Y`XJ`W0;TVyBN$Zptw0L~PQ z(+R@9K!Zi#2sRxcLK(#Qpc%V)61HZk_<Z`VO_OV&KSb2xE)jPN)f0(2i~sN&x#kqL z2gFco(C#{+v2rmY0!;Sqkd<=iN<<ieinVj=NktnU1={442v-iKy8t+j2pVb9M)>70 z1d`x8)G+%Xvr%WxyHud?{+pxIvRVY+z;e5qQ&nG3?4G$@*OAnLzaHJ01{sTCWS+I- zpnzKa<a#!!Kp!ahBGTX+1JknQa~x8!9}ODp6{*T)Kx=ZZ>A7&MGarEx&f2igq%b7x z_4OVYRDoVVlJ|ET;|D8VY#TH%GC6<S$U;V?`3l>Y0ks_Dd#j)5$r6KHfKvEN{`2R; zXNcYjaspStiYpL@q<B9(XAKC{wL))g4qwFSQrB>oYkFKYoOS^~GqiG@8`vk)a6h!I zAAs)EKSEZ~k%Pxf3+)s~t&^w8cxfvRbG4>;sIn(T|Fqbmf1O_>GsTIGW1g1#Et*!i z3bug_jGuYJoy+jS3huyilm5#?z%MtIHfYO@Yd6zSK|6P$HDP4F0i-xBeRiqO6VHq; z5c`3-9a85`OEq`%3B2o&CYMj9g4XHwBa6r8^zQ&5{%8(NLaZngjEsXaW2sWnakyMf z0}|rtZ<;0|I;a|L>KY<o3s>cbdjyMdTir2mgKnVjhwWHfFl7(g=}Te)c^^T#Hd5a6 zVbs!DE>_^zq@R3~j8>;c$~r>^0k9K<O<*H-Xh$QmosVV}(wG{v;FPS~dM$>Elj$AI zblB+vY3$zw3r0{}I7yLjSl^E0Sd5?wPNgfN^Zv}ra6(l24*>0r;<It*I6>T7j}|Yx zsjR1qe(k|Wn=WpamN3o?ze}L+!JEX&6$;d5%HM#K`^ypavrzd#Sp4TgKL&n^?t&6Z znD?p63N^zH0K9Vui@EVkFwb(x%I2Rr-CsnZyfj<3ZtVP9#LA$7W01ro(ONT9T4n@l zfTesAEnEB>u1g8860)a2o8_d@X=XV4R0!$m(qjAL&lv*0qERtK2UOgvn@Z)VZJRgc z46MyGpfW3nHTGKjH7jO*i8h!Ei-1clc8vhd0l@zH)AcfXgoaA*_o-37g;x_aO!&); ztb-o~<J%5tj+~?pd(=)7Of-%h4D5=!EkIP=&~*U(gw9pc+ii4}^E{LD^HKOyTNdn1 zxKz%o4})rXJn+vrxKRW`Sdk?sw8j-5LjFvoyN{(0?L+=q<rQFH4$Okgr|OhXS9A8k zH;D8)k&;Tb)l<9022;xSNsvKv_*X(%JzH*3fPUya+`X!9O4wVXClE#v_aIfLxx7+G z=XEGPE_j-iAPg7WiCc3Ml-7Wwq9k%gnD*DOCr&}62rIr4!uPL%cS+cnS}vclLi2y# z9Aw@6LZnw~E4=JZ<$2HT8o;&HO+SW)S!lxdm73I!+4$0Ke(;A)dx$+gVnd$kT&~>P zMYB2E=Py1l;AeN(&nQNLP<-HKOcqO4dECr4CyTd=ls4T9CsChk;T5(Td#P%&WA8NF zpD$5XPRhoGd}YEmAp$kvIRrTQ80VI2SrX3HyywJY5eQ2lz`vstSLs^aZJujcFj+~$ z+URNx*>e31ymM^mk4u`P?>?j5yDO>@PNDlG`BrdbyZ8y!J2Pz-QZcmUl<Py2b$fy$ zzESFQ!_v1-BKvU%&fSeMfZ@k+O^KobP#^hU?2YO;MO^PKG{em;tewldS6zvGyzgKZ zC9uEdbUOsteGCgOP&xg9)Wy2lucH>NJQ+vZ4>_+C^O)7VdF*~TxlQXLp7f!P{RQvP z8Giwa?my1Ql`1^4kE>kB>t|D<z(RNIpssSfDR$95BxM&_uQ%r(q1F%X@R(#iesVqN zL(WUx)kFAWDYk>|>LU79GP6pd4Gpr@`PSN7=oiUoqyoqY0b$rMc(H=w$;zx~>tcZ< z{D;SRxAtNiuagfyEOI24ZNootIFwDp&w<xI{OwciNu_W9umj-lGkAsIW!%TX)(J+U z6r4dG25-vWTjvitHHvLHdu4`XzTxX+YNEYQq@Ay2i`!N~sSJ3o_jyB_DSRGXBbk1~ zJsyvE4Rqn#zU%IeFAg{EwyuVq5a69?`b&h;KAZP1X*R0|`XSG}2rUVT7sC-g%9qz= zC(YqY<|fBjm-|jZY_3CjPMWXuM_U%z)>6louuom)#&)dXgZ^~OM7T8zlgWNgW!M<m z9=kw<?xw=donYii?9*RhhBYE|o>T2E72P6)?#`U>x|7s94tQ<tc)0P$JZjF_?(lW& zvvmYa&O&h)0ey=F$s-^luNpTyCsif=FR;*Q1QEbR+`6i~Us1N~4g2WsW}Vx+)rryQ z>0a}PcBVpl{nJiy&?X{{uQ>?6GG&dX)=H%lJLMW;%zZjO>0tDLqZi4^C);N3eL}o0 zbpw^|6O_98>?L~#zI{f7izN&J3IKq!QsKH!W_26j2G5}_tG+LP&U7WRDi6TAGGJS& z@N)#fyc_X~fG|y^@j}qxv3k34+)DuHGGNfLqw-N=bT9SX_vfsybfEZdXg``3n3m9U zl12`L%$JWt#&MA4l>m^m|7#^|SwB*Z#grFVVIGPOtK}B{KHvO@iA01iQAr#C(fv3` zFAjR52@BqVUFskd<~VE1Wuy!l#NI7D)e6hJE%+%-vBq5mq9JT}#M3^a9<x4kHmk9p z@oMNTQ&$`JhnF>t1(-E?x35I#rv~UEaWUpJK*2@uf*}y2@lM!U(5Yof>)d`ai)#b- zSgQ14h9Jz5q{_;I^nJ%D5+Y4#sPa%L=jPSkBRJimQ2y~=RONf1_dFYYNtC`chwr~W zr~FWfD1Yfhu1lvN7~ViRjbVs^={FPeS~na*!9R5TE#hkAY>kNPLG-?d9W=|3Ro=k{ z@tg`m+A{1Ik921G$m<_uUcop4N`bi_Z*@!33{Jjf;Ugh*J&*@X3~fjl%2eNHmE~H` z6ApaPHWHcLNZ^^{RO*dWNki$6v0OV^i*?<AYpfb~zBhE<P`%m`yM%heNTNAdPf6|1 zK|Y8`2IV=&uRzwGp#_HJo008Id}#<KwTEtCxbCC(Hg>j8Y+-aqZr_>SsY8+a9FhWS z%pWU!@$PE?pdE%|%dU$T<}5bHij0&hNY%7fkz%_b!Y_g73tZTNbuQ}!BcjPjci#Ad zS;1Qn{_k-2iNdIRc5~5KT7og(H^5+N&{_e7C_P?t&7X@dO-F>1jvN_r`>0^E(D4RX zAK4kdX^X#pHV8dSyS72ZLo8q`0OeK3g;yvfK<X84aXtaYuxORbFa;Hekx58EBrGe{ zzc@JT=KH+5UdI^Zm$tFLteRmOcf)O+SUc^cYx|w*z^TMy4#M!uzO9mx#d~>aWd2ZM z0-@ZIXPm|$b_0ffgN_-93ZC#Szr>OMep{PBxVmoRO3dK+@5TXo%6NgHDWkqVKRGQ7 zaDq`1#h?KH8NsMP>ht@FW|3q3>Fs!;YqrhMm=rqtL*pA$CXs5kmx-%~@f8EIjB3Mk zz(qWTyMFU+eQfk!C<D#(w+o+*t{KKJ<_r?t3`?JsE&@c!6Dz;YO7_$OPaoX-g*e*% zLu9P!RIu=kra(~P&9R6^5afvd5(~F+1pNTqHb4Mg0=W4<GsQWXVMxLONWc}c=2NjA zx#8h>_ixt;g!#vNks$bYCtBbCQ(3*-?hH6Jsw`-pt|i#SFWdx9K<K7ud4c=JQ}xX} z2NVEk^eT(aokQiRrG8wV`KKEJ&M-&`#I^uF*nI)9fYh-fGgtjZTDUtV=ov~NBga3K zdoNWY=ZXnf7&IXcz!2N5Dve;+f$akr_`16zmuXSjtSfhVBfryvIfdXPrI>%Lj;`Ac z%RN}oKa4~CQE^WSrMy5tDY0NU#yV=>iOq_<X&iMr%fHy>zLF0RWV8em_E<kfZ^WY( zE5w%vK#=Gx2q2mCK8BR+IFKiMT{WgT)UiMNd$wc|>z6F$`JbCT_ZEsr%Y)~<%K=DG zvX*{po^dDSdsGH{_crc6RnBXzPSe8M4KKL3V?gkdq*RJC$@+2Ty@*G7cJ4|G_pam+ zT8;ZIXTO~6V*jB(?VGo5_GHn1`NKFAT0DSLTYJc<P;<OC*a1hbhLpYPiJXEhqiIb@ z<BF$InDQ#;;`PXRN>6&6CLti|q`qOce08DCjzY=np-0wP*!j<S9zJgLZEYXO)RP&( z+DDqZDGflzsAtu8x1DKUhV_0COutVKbFS~YBK2(-M*1a)0Omxg0tDtBZjbdnjD1^Q z@TmVNsTj@%G%cs08P(=|L}MAp5#DA*n+_{%KajkGEq#vGV(;UP@b%`<kK=o3Je+e) zt6Vq-;7$j@9EwA##sCpKLiuf2<Yar~I$(q^YPK;Deb=@Y3kY?`U|2_*Gt5l0qsp7i zR_!4X9816Gow%)&=!#jBf_H>J<^l$)3DKE$n+2iSbls(Op#jaEF)Cw$yk5VKe2vx3 zd>eR$5<9P8CYu3O*??+{V2Qg_JERIAayanzq0CI?Q1sW37iL552(O0l-R`T&Wwmn{ z!`1c<bN8Ba3)+Y*b}sO@`YWb>2gC_>C<Q^4zXPHQ&`9QR!<h>5z?PkO17>{U9{q z|MlIVbX~SNX!;(=FR9eO854x|G3KXz<^0R*3>`!(Qbq78$HdRw-5xuw6)k~u7rVlO zAk6o%HW{c$x)yWW)xz%R+K|{q#-V6WHU0b;bEcZlgS)h7M!N@XW}hRAfp!8m(vdFc z=Xoq6*JAD5>H4CN7l-F^d%etVXBSfhB_uyU37N%av(o0J%IvtJP2}uLzsG!?N$`H} zHi|5;f7i9mp+h(4kG?M%)iRkSX~@bO+Vrv}|HVNpXFt!Y_5`0UXU(X4Q7w%xifi1Y z*d3D6w^^=Fz*mQCKazP;3{Y#GcA6QYbYOuzxrQG@m{@kj*wi{n?^Wep$k}lz$3IVz z2+*ihMC$Eech%zu=OfGm8A<GMoLQ1Vf;T&>Z~oj)7Tb56j2sm7WF_%Ni2`gS&Z`R3 z9cXrn9QGpB&JpjAwuNR{rLrg01UX{sT{-d}gC70pOAb#h<5(obZ@MFUNQ-=4lnfwB zuD%zu2L4L_ZR=j1wB~(+#&D8^K;@$ptao$80Q;;%dczhll-(M4-u<{B7?S&%qbt{j zLhfI+W0sNGK9SD=km{<;dj`2F2@X3t#tjNs(M6xoX>lo|7E9MX{O~P%z6n6eG<*u} zYRGat#Fh})_FC<a7Rq@%mt8No=Vd&BN9<fre}y4s#;x8zhLY*zm{wPFFow&ckzK?4 zZECRpMrx3#D<8k2fuRjDN&IizZndtu(L>~ohZZjlSbh#|f0@dt(smQMVZf-+G_Fjf z9kR4h92;7A#=~SctiH_vx6=HP*i7Y)eWo~me$pq6;&aF9*(t<ArCv_PxXV;1nt0pH z<jwcH%e`wi@skta%Stf1{$9~EFncC{E8h$U0AT)5QM&>t0HTxtB;W~<8VH~z11M=Z z^$Ep2(X@;r4#R|!zBmN0VZMH2>A<rPbBD#@#<HOlwAOP@gQoJ43?ZvphmocV9agYe zcaXG~6EsKR{_f()+p5VTTr}`IBVe>HTN1*~zpYa}Q)OOeSYY^W*Gkn-rB`2sn2h2L zwO?2Gs)?SDRt>bhJ=W6jU#tIG)2tBoCcubdJIaR{Fkh$X&Appt)J7on#WR9l1n_i! z?sSvwI#gg2NE%Cq_A)Ivzg?Xy)=ET~<YAtVPyqM(9Xj6a%@bUdpICg}T7T7ae{cEI z`$yWJyQ1m2O*`9;)`l~#-<jxa|G7mhGb%Fu&~duA@b>Pvi4X68AFT8xlDW;gI{*CK zo~gSt+4b*!$noM>kr}th#rfIKy)D|0A5}t67Ow#!fQ@~y2q2HP69CAwP=urVAxMfL z{Q=>_AeVY@l|yaM)QC$lTAo;@Y)|J$hXKKuh|8qD$wcg+P+8LH@Xty0%aGvJWEI0! zSQwyJ$V~M#!U`^@FHp0dZiKXhC(-^A+Q=NG*l|`rQAprZSU~iRs|~J~rAVE}8&tk@ zOMdCDwyB~8!Cs<w))m&Mg4fioH)}lbEHs3PqCEr^ci~099iQABF2hvrT&5Pz6yUHr zuDIo(Ra22|6S`Bml}jlsF}Ce8AxC7&;FtS%62129am((m^%EtszIpA}i@puHiTF`n z&PUeB2*vqg>Ew(7Co5yw0f9u(ra|^wqH+|o8Kza6nG7JI5o2js&e|E}x1yu|pSx}A zn|!4z5tl+K>W62H0J#%?wg{PA>nKCOSZ-fRwt=6PU>pD>id7-StWEa(qv|%3UGTIr zQQX*fF_o%zN>5flP5t?)hqP<^V+b90($FF5cWV+iGi*7+|EDy1U12Gc5mq3R67ABV zuvPz7WrKKSL>(l}q~!l|D4XP(QK&H~z{r1>(c57ep6L0H$cs>)4nl%nQsi5SDlSmv z)kgE~`TY749&4L?#fG_Z@)nBA%=jBsv|JT}U!R{Whsl#?8&wY4tdeo73z~7c=fze@ za)Kb-gu({G>vV)6PYm(Z^KZzOdS4Wyq*CW0kCEzsD_?%^R5PAz^{i2?_(}GN_9d## z<D~f_mK>7r>*W@SnJa!fb1;(|$zOvj)KtC>n>l=DWTtrF1euUahh$DDYuhja6e2H2 z{{Emmy=qQ6iHSB*J>auSP&l2fB^@7T?D1%f5k|}=Pdqb9e)DbAzyI;!ecD=VP_m<S zG-~O25%6~=p$A{axM?0MNu)>_oQvk-y+udvkCUe8GU7O1h?9Cf)%EnuMT6cL|9Cp9 zj4UJy7y#oWG8>cbHuD;N>|^Z!GOMAUPNF%-?P$o9fJS^pALlD`P)>xaEVELYDi>!Q zvN0f;SilPi?$wnS(Jw8evhV=b49OR}!Jd@6+*%1PWuNI&FM1KpIi)njkKB6wZ2%Ol zyv}XfwfzxN0XEoaqY+Aufu=MZrGASXk~g(UxgX)o_O}=$*Jce%niEP<JK^DeLW`y> zIAG`Nw_HOQjD82~`g)BI%F+Z%Js?o(@zT$q1@&sE+lgxdHIVA!X|Sip$5|DS&HHCt zMd}aMTqjct6kiJ=ME~*LSDY#nlYiNA$!VPPx4K`UIc*RSW0boRHX$9y3~(3KV%uIB zk_Qr@ua5kqUxtBIw&(^Sr%Bw0+XISUJ;?giPUw8V+=^16u%VNTq3!<Fe!^j_0buZ_ zAhBGKp3(^oz<Y6jz<#5fKaPY3pOkT&b%TJ0(<v8pMhn<#waNfZ|7O2zpPjX9)PZHO zANts`JnvxM=Q0Xr_F(8}app#b*2$enPYUxLnflK!{2iKPAN8(o8vlMD=p@XxeK@2P z-SkXM#tqFYR%@%8&L4j0@|b}soAo0F%r0sYJDtRScK$PEIPx`WDL$?>I4|S1+%p;q zM2{`#aT@!})39yafa0_T%qNU8SNr)V>oUWx;7DGs#sv_&-bjW-7^x080>JC-rFvg7 zaInq|seLXP2n;3^1@4q-eGC2clYAp8N?$40?7|Q+mHw+0R3lKBYzMbHbS|R1zl8H! zw;32_x_?d6QpHbM#{cl$8%JmaTokbQgFQya{?oElwgw;HJ9-=^kSMSIbMXt%@R9!R zkQ$AmL5)NA`!cR?bYm8E0KPTkw!*ah`V^d8f30%jNmW$U%hz9zUAS`qphZ}$X1*<n z{tLAa;78)OAAvu@sAcq&l5|p@UX0)n8Jl-Q^$`9M(cCBTIuZYgye<rG5mwvA;_DQJ z9&}&l8q{A*Tba^^_1MS+oZi+T9HqFSuQ}`4jNG9-r1-YmmidHdv)IQ5Za_%Tmt3py z!T;1b<9r*ezBgm0vJ!b6&O+Afi=q*om`VxNKYED^d*e6wXzbgZ3pe4+PUZF9rsk`D zk1gpzUtem8@L;TB#*#xK8Ip+9`z356cY>jIEoLlygBm2TI)2xlLv6Op8vMB3mPAED z!j(qFNrXxRJBvEstH3r<aL~EZd2L(<kk}ckxNG60IeEUo6gkP=BYDTGvtcTdeKkPA z(>-)MV}YRC(!vPjHgj>|Y>aUId!EDzL+$693j8W={p6S6^HSfGCGYYCTpTKYq(I-) z+O_999$Nl>!KwuJp46(O6=}+TfU}$w7c-sF$!i+wd|05km&pWi2>Ja7B%f$B<VT3+ z6pQf)80{1fpWXdtPL}&M@Z}S1#Z8!{5rB~QZB~qx9*Ty4WQf=$LCwpxP)CG6qY}&C z6{aY;KBNx5H{bA7QEgU4QZt36mM8xSq~idM{UUx))~1`+Vjpeekz2I+M188HXtBjD z$D9A3((Wd`+jbO7vs0>g5Pok}7~2UBmhxk#Rihb&eO+INxH#P2^P7sgwh8+!rEq!V zcnDnViJ+bgWjR=jOc~$CB)XolI<B6_5gT~DM&;^Jt!_hn!hX48w665F+r4a^D=}ZW zH6ZUE0pY<oDjo$A#1&1++S2`OmE+^tEdb@_o9MD|>>tjN;DA0LQ?S*oA)kmhpy?3` zm#n@GdSK&UGF$x$70+Qe^?N<?j}Tn+>CdNN7l0b;YbV5^#78A9CHJk?sfTdK&=cry zf9)uK;ud^~U{Ms{@~-vqcRkAQTTh|GPa(sPO;@PhaF3t?VMA32_F-zsR3w5TiW(Ee zSslsk8AUf0IdC(IqYc5A8zrRAPveZ157e9^>W?5`7g+oy&TO8-q=%CJufN8#sT;cS z)V9S}PkV}Jd&&_1ltCd9*7n$<o0>H?=Ds{4yDAKa5Ba5sa%7FAV~BN(N4R>1xCF=E zu|;^d#rjmox-Z1$2qGNxk<#&c!8aVnu)4nQZvJ@ia3WI9Q4reb6tS`*9sirDM=;F3 z_%V{q8ku?)pK=!QeTx!K`_$DxJV7H|IL-V(6HctcihmYQ8RUY4&>fj#H{)2f(TL3< zpxg?uNg=V>HnDja*s7l>hentp01d&2kJSk_k<>zXbchiB2d6;eUvR2Yj|f(-1wpvJ zCM;(K%G;7Or^g!64f0!|F<+qxAinrUo4l%@yzH60weVuMIynG9+Z)fixblQWQs|$5 zbV*zE=K&bcqbFc@IZ~7U7J}Yv)mc9Mg<quLsX4U8iN0Y4+;C+F;jSw1(#i?ohC}c* zuQb*ja9wd4qhcECpR_mK;5X*b^+Wi2G3;Q0#cxZ2kAhp=#$f~pD;pL+G&i9o+xWrf zl=E)F{#vR`3~BQstys07Eog9sIk?gvT;&8d8p$-?$ut+vGPldBTgl}5l7{dCw*VlC z+Ex|r2zV93<s~9x0O8@4ou-?8w<bHi1>u!|a1+k)HORR)lKm(Iala<#!AMSsaP||r z+yJj^mCSfVByV@Ln8c<t+ey&Hf~pdw<Yg+XxY)FQo@Gh*s+kIMRXJzd4z5Aul`7_y z+vQcV<rN8oOAqNmvzX(y^w$9<Ng0q=SE3?9Zf`~9BsF7f>aM3%kiI5-1WjMfhhVm0 zHjd%#@XxF$&NBUzPh=~YRxFtQl2%omc8Y*E0bh0EdC}RB{cboF`HykvXReRJFUD!W z;;YVqM{p1&>>~nPPfV+_EBa+u^!ZC>B@vP}o4zQ_p<ER{LR5;=_pUhOO0(g^KJ-23 zy|&*3+a=^1e@Uw?2LBEzVf8L>sG&bi<<I$3RDwan293Jbl^zdxB-6b}t&v{wH|`}s zR*4T|YZzfj_#puH2?4If6{vhIQv(-F`~jB}A!=H#2b87d6ln2S{tpo_iee~8i|<}Y z@ifVwDu6efCscdY`Jmg#^CZtqgOAk;(sBqs|5HY+L3p0$bA8EgF^7=TO7#s{m3Z)E z1ij&q4M@vReL;gVOY*-J=zm0rbtdG%Uw!F>g_NEOCEJzU6)6B7RnLrM8nlDU{qNe! zl-&nkm)Y_v)_25iN~>18KKZI~dPwJE{?yc;%7y?O?1mozB=J|=`1FGG6MB8&nsoM> z6nk)8Nc7XTnm7_#Y0J8oNdHXJ^<>4S(~e6?3s%(u6u>qJpd02y=xivB@}4uYwdU6q z7gg8PnHnI{*<XLINvr77?j03m4K&HApfv-Eg#*z)J6_$}s8{S$^g#ejyFr(sAg@#! zffcId6_fvVk(U&(Nd(xCt>DHVLKPZ;7|W#9Xrz>EwDJP`p4Xis>i4`^Pt6TZiRF1U z_fN68$IUG3geKAVO>&gb53HbcG+mKDsF94Oz3xxd+b!;^!N+V3DI<VCg=DFDBU1Aa z>0c`uMoO|z8smESFCwb!sbPv9%>K<Rrs?n2h>2l1x>x3Ok5(XI1fXatlysP6M!`)t z0<L!g*LJs9vjJvC>efVBD~l^1-ECE8&oc>08!EqLI>rJ;qL0l5JwHRKVl&FUpVabJ z@dUhULPI!?=$dft+3yiWPIN^CItoI2Hi53_F5Mh&$17}y^y7}IG2rzTs`r6ZSx%6k zZlEX*a^nBas}8gB01Ix<GD~RW#y7GmmwXEacb(JQw%+{o(>wAm^D&@d5<q`}g~?pY zwZgRDil6~n(D?Y%P!Qfw9a&M6BR^0^()<<aLNkDXJv8r2yY}7#6<^UPD${0TTa<3S zk9w@x?L=SeU!eWCSx}=O(;j@U12guQ#VSt3;F{o~m087&!s`?b|KVuD08nZQ=%iB* ziztH0p=SpGolAwWcS2`VVchkqw2fD14?0z69@Nw%qKJs*QAB~!%PUj@=5$VbkY@zi z=#{SVl_CogH<<{1y#hA2E2$7hl!PEFb~1hbYwa)>`p>T0T7&N|@W~+&dgB(eiVUrf zxzf$&_g`pL<OE5{ZleVr<^~#A?F6R(*G(gkO7r{>6osXY0t}e~plokhEWSd@i@^pj zGs8Fl%=W{z{zzsK1T#6bpCu361%{A_;?_y|$1Bc)+Vp?12B8C0^i%cxlA=w;Z^8VC z>wAcnI)tbZLyf?LPq*N&&<#K6$7YmhmwP++G~w@Wfp4@An}0zf{!8=Ot87rL%eY`d zZo&swAmT0E`SplG6(kY-Ha%5x&wn(JPfhS8%pLHtX$++2PZgC46B=P*eVd<^m-VY1 zSz=dW_cE)Yn10RNWgzVRJ8C>-d-vam`SgwVt{=g#tehX+jDHrjDShuzZdeyb!2YFP ztsTK9yCDaM@YUlIoJCNQcO{!qf%s9r#g$p2SUy(U`E#EUXsLaPcJZ<abX!Xb1e@?v zG!*$$^*ebalOKOl&<Y-OQqzv=wY7wL=#0#t&}%7oUcO=^3U?ZMbxygY@_uS)<B&+q zgc67_eW31SzQ@fahO06@Jp!GO-OSX9;~wtKu9PS-PGz?kwuFO_yMawB@c&ZNe;v)b zc++dXD$-d(PAAOPInj6cV}*xAOqP(OUQ9+mJc|I|ZSKDQU9cANnKK}L4FL)(7D;`A z><W={<`c`o$}Aiju62I~qXGSBxSANVaIX&Q&P%R>N@a>}_$_FhEexc*z|naBp$&XK z6=KFy=W9@bpl(QCp?atVi_{!f)Tr=ESlE#<5M=s#>I4L!0pk&47ZEK=n7$Qrs1mq9 zpKP3`5Kv;PSia&^&gA=_FvYunEB9S8A3)uVEGZg#{i&MF-{+VZ)nC93Wtu1+syBa9 z><7ThRF~BEX9{iqLy@=-QvKU%!GA*X)FksxUV@GP(3_vb!lPHVp$u5BtCmtDFFrMk zqrot9IE<6&WZmm2l728Xl_-TEiY)<gE0-%X!v%~%%&N<wV4bjGYp+JNqcP3v-2*G| zh5Pq7x{!6T&>aB%T7>Eb&TpZBk$4XBSb=hbn1$^9|Kk;r07{+<AxczXU;tpoWQDvU z5mrHBOzYG+2EXopAG-Gy*EnD0pGK^mG<b>x^(heb;FsU0%_th$QfZnF=dKVIdh-9A zTbTuijBc!BXQq8OXT$&x*CgbV84v8BrQIKsRPqe-!8lAFMR%*p1UQ_&|FIv^>Kc6D z{$v!2iIxuPilv>+-v(yA*~9Ufob!cPd8eTOZfa|p;(&g(`IlWtowzc;zia1o>*^Gp z=4^TO{@|G1<+{RUi9z^tf~s!%{gE!lNK3e*gRCIi59N~kC+1d3g*Wt%G0D6;nJ@s@ z2?+M5x@>|Tt}r^=uem8TC#f*c(d9WLKsU@aOw+#$^zfgU2Rrq-Lgd`l19*w-qrHSz z!JAB)C)~_@THAoDAsUfpx_RQb>4S4!H-`#2C~ZGQ{;-3)hR*kq>3206`zyrr;ub5P z+=g)dh3^v_!RpAW-=rSJ+E0s&6L+Z>LRZx=7UXW5aTEO?To_^l0E~r&VVC9z?L}w^ zkqD*eWlRLaI*8zJOH)AZf<J#IYIzVi?h`JH>2MlwglQ^~`kNYs-sL#W5w5V!52+UK z*tz@-llYxl5;l(gG7f-_qX9rH?NS8&_#s4S@mPW`h`ApMZO{Df^V1?A&u0%@;vY@w zo%NsOKK2jX!gb3>8Q7U@oI25&VrM8%e@DEL-k(?`cVi>!a^l|{^rGq3{Haco?+S-` zDEOH$uMfS!mHg#sqyT)!QG7@2)qNtyg@Y=qJ|akDpk&Q7{oig3qbi!xl8BC6M=}JB zuTVL@&<YhNo^Gmm&hGu4F7oj37$;mAzw}Kw2q2Ok05H0!{Zn^SqFXZ-%B2>=YQduw za=h}V@7Hzax*K)IFY{O}*Y(rk>V+~7cCBkHTWaSLhmvm_<jMLj_rJ8-GA&ena!GYg z;F0tB_v<#W3i?Vtlq@oO>)MUo*=p5!>bAU}-`W(y2LDlVoCwZ6Fn$-gc9ZV5YN^v$ z*5mV_lFkNVE}hFS$h<N&;Oq+9^5ag#b7wD>*Eh#M*IEjxv&W7j+=eXc?00HGH~m~E z3RJ^sxa^yUOTJ#>m8xKzEf1VV3}y3W1=~Z@$@wZ}daz&H>6Qh_MhkbvK8^<nCjUnR zwQu$9EoNY(F;i50(2220x~kl}o-KMq{K9Xk((t%Stu|-_%&8E1)c-M#`_5%p@g>%q z9^lQbUP|GRQE`Cz8l$+H5gJq{(j8lQ9>?jw`*Jh+$vI|J?XNDopjOCWq;9TnZrXri zAWife0^owJDr-RLn6?~%vO@5%S{U*(XW4pH<OM%WYSiNnr$S2ojjz>f2)8NQldWYj zB)%2kI``m^qdD>r;Vui^EqZ$<IhY&N+e1^=zK)?o1+VUGX*p=dxO4O@m&Fx6+o!Bz zvvgF{Va{ZUx>}~^a!Jc{?`8v`7^Agi$QC-+Duzo#i8~cV0V0;uqZ5VACncdYij;XY zkLXjU9~AD!qI^%LK%BvzGs1<?jJq=?NTW=T;XAgwo|qff_{@^q9Ouc*Sx@aoi?kl= z$l1At>|J43LjP2~qP~;Z*c0ln2+R@Dcp+IEem+%+@(}s5RdgAAuE+JD#>K<t55h93 z;-(}1S(Y33SJ@BAK0UFh@E_C)PLYo_A=6LG2Wl;;L3N-!X+AbkkKj(?XxCdHmL}uL zZcmESGa&Zo!Xw7F)blqYRNcP(G_7gPwDJ+IL`i`v+udJ13w<se{a*2{r5~oxx+Uh? zxd%e7#ZGUPb*&WC=9?}lSaNTHqk~-8X1pjlAxTQKLVdS47?Heo!&KPphN;~E%Xm`3 zANSU8U9F{wg)eNZi+J-Csyd6xO|p4oM!pvng}jxScq&BYQDm5pr{{Py^-pr*v!ho< z8T*Z|r#IbX;Vb($Y(q9Uavgj*{ASERQkWQGWCbdw2TcF)iw6CeI+=zszr`azbscvP zpJVpxX)<J<)lp8D^+D`@T^0LJCFCuqOzY5ROnwVxf|!lgEypf}$oHFhp<Vdtt@<Cy zCUS(c__88?5^r5;czoRu=lwI1p73Aou67=!R}2Fp$JV^SN=+wfz7%1acOR!8Oh&>l z#uc_T5??$qet4~ZNneUKvwW_PjMQ_|U5OB6|E{6^Af6r|!K%mPAN<|L?|R8D7T7(Q z3k-FkUnpedeSRk*Iz%GI3GqxH+YwfWA}oMZM<rQ*%3648&>5-5lVZ%yw46ieO;on0 z@<NGaJfvEXz)3(dAc>N5gZTB=MO@l|b*0XeQIdh_Akz7EOt@CR3rY)_bB_U(AobX) zH(y_DVmA7^W5_qpQly}?&K1A{aa-;LpB&_$Bx@GN!A+Jdms>_8yRKzG*)m#k{~4uJ zX>Xts7wYe7f9Hr|<BQ;o8YmzR%1tVyuF!0;S!CVg>aH1*3XX(<nfvZEH@{5S&nR%d zVlfLo{!dRSN-meWTeXIKWfyTzr|7+V&GD{o^sf|k9tD>MOBY8K&zLjDM`af|?P((` zzN$mprIYw6>={SjTFY2LDf1gdz8v-QPgO)0?hgyGDzlP|u|klS&R*u3L>#|{TBh_3 zuN)Qa9GIG@i_2F}=)>1L-CQqH9EI@=GG5u!UbU-5chW|1ZeR_@tWEB768v$?oOZD) z!=q>+%4vIPYhy=i5oPx2==_qT`<axSKmM~&vJm|EIkn8uV~q2SaZb~&tV@tIbsZu> zGsV`p&tX9GTeIlbSAx?tx3)T+EncuQi#_Fi{Ga*YzwtTE5Pj3vRg5<Z^zm;pgbsM? z5t;BWEH;B8_w?~!L1dwLOVK+5P2L-f3D$G$S+S}<Hv(>W%%4*vI~RL%AE8HiS{3?b zKMOOxS;*L_eDwT|=bC1YuMgr)3)@V^QR6?H9)GU|bX3kd8(~-H{$j7egv$hV)7nGl zye9>qQj6SLpcz_@%5q$_3ArrO)72&o0zVJC%NlwK2gkp7)XCeb!KcU2gA_b>pG;hj z7sj*ezkOa0(rMIR{T~2fK%T!68>le0Dk&s=`<t9}Nl3i?H6&4y30VA*({x~>7yDQZ z8i{(!db|T3ig{)M`I!o7GNu%DH06737N;FmB)^35mpk|Yk8Kpg#y4)pH<*%;x5z}K zH#3VomT?Y$gkx4bWou<a|6;A(^=?E9uBc^s@|1c^mni8l#wE_t4}Ww6E>gMU5V27* zH-7SFvvo;5Mg<iIt5{J#)-QJIVV`RJ;up5KvnWEL=RMoP7R_h|Is8QrAIpPBD^_AX z_7RJ8^uwt{`$s}B2<e7wu+opqELPYzDc|4@)0T!3rWcYBQr814s-rL_^2!f-5H}vC zoUfdQDCtdVr<1GD9Onk6xsOx^W@=8On`_1nEh5B_z_^tt#*3?Yb>tO{IYlV!+>B~y z7;Zypr!$hV8f?5emTkrfZ9d41om$Gkv)pB<^XrdygsH-LO$brSkrlAK_>^ATjsR<9 zW|~cAl)rA2u<s?4|3VwP&c9IhDxR(I%9Tyw^O~1>mHmrm_-ku6TTeQ`5sPzh?8x5+ zH%Vwij3aCUo#uN;g3K*6zc!Q{<5)<ACmCs?6zb4nrm3M_^|g~l&vcZrOw9gqXo2^t z#eB>TIG&*kTO^zm9=Q=m1c<gfJ$)rlH!(9_LTGm2yjLb_=RR7;YFVS)Fe4fV8~C7* zxL)PlJ2?=mgn@|w=(QZ-Xia_z&QMfFr5v_?-Wze~wvX(}hN3I_z$(%-riX$>D5+Py zZn*E0sHE4TxDzzMA?kqjR~zz3hAiX}4m8GNkYcHg6+AT}kRN7dbRh>h7J?2?1VA4} zQO7uB0%3;k{~enptp+Pxu`+(&485Ow#fZF~_#pW&F$gckv&A-j>YJiQSACf-E<!Z^ z%40qJ_{SwM?6{dB*(c?cMMRHVQJoZ~AG5DLI^={RFLt-k+GJie0%-WcZZBmD7oF~6 zK1JEP=4l025TNQ)K*zW~R@fDnNi%qG8+i!3UMPzIWC#qJ9iLc-dXN$-al1*g3C;_s z>S~C!SP1eFHh*azQ{V_vI2#dr8_MelR!|_AkhKBq6?%XNrc;UX0>U5!!V;4_Tyq6w zdxm~VF@dodYbb|g5H62%pYs7ZmHR8OpbenfhInYZm7^uq`i}r0G<9eeYygI9;Dv@b zizHdI|K-c3df<jTIVn@noPDYp%u$7oPz6y~pe5A7rJ0$xpt)aox?L%cLqx<xL_``% z1(x_HYB&?paYG=n4|t%5W^smCAP&;ozREJYlCTzR*$df2ALX(_q6+|Qm;`fB24^^} z05}Va6Smf}lV2&m5n~Be2!%eJ#6Pr-H8Mc%ATJ>##$ps37U7|9u%rD#mNmi#(^#~% z&;~B^L<4)fh@cH<5CcgF2Qje{DMPm>L5x&9C}q%xX>bQYQ;KF;tC_MDJ=7`)QZE$i zMPK}k-GUceAO%rcz<%_{UTX<mXqI|xzFP5zgAhAezz8MWEdpadiJ&h&I2yrOuyeCQ z|KlKxDl<WFI74L^vUGR{a99Yzc#3uetBg1qc;ueLVg;7qmvXSj7`eadss>WH6ILk3 zoYcwk+LaoVwt85`&eJ(?=mw@R2VNkKZqOnvY7f(MA`{84PNa=bZ~|d4BqzeGgyExc z;D;sb1z0c#bZ7^L2#2y;hcr?ycf^Qa@Q53-L%2CUm&68`yttUOjyNf__7bmBxT>>J z#J>bgz|_N6P@874w}9yf3d9C}I0pb@i*caFIMF~2TnM~mhuF)Im#c>+^Bu~B2yi-) z3G;_=Sq*ex2y{pXY%rz(fXVs-HBg%=)oHahDvy;ECApM6*tARWFv#sNg);lc|KL<W z%S#D9EEPXo7G+w<gGvSr1BZARhw6xn(<?PnlLz);M=W78D|`(ye7^ud5@|4oJJ5%P zaIZOm3KIz$<|7#asuw)u9?EEmZVP~!+|AL53%$IR#t=N=3?<?8H(xWR#R8bc^B2@Y zNOQ;sOqd2z1F0xe5{mqX=OBg(C5Ca>1Seny-?5t}8i#fwnrV=QN<f8WFo%7ph5!f$ zZE&yp+s<?=I(h&xH_ED892k|5&tJ<5g1k?kh?5>mjLP9lVF}D41rPE#Qot-cmuiKC zI=X?`5wIYX>@f#@00n0tw|XEH30$+T>8tu{7(O@x7C3?xC{r<DfltVd|AuTsog0U4 z5Xpo{2Wj{Oh8Uw_P*H4vxf6*n5=qO%lhHQPmCWIu8gWF-U<d8&(a<oFQ>%tn_$O7U zm+0v~0HwYcsXX&=LE&?SUw8>aVa9;*PNLWcRM7`wcnMM~qjAs-N@<WdFo6}2)mfF* zPxyyKZNme}5SXh@DIx|au)XpG1~591DFjEm{Ly-#oU<9!dMQ)`S_sTwvqj~NiWm`U zSd3Gsk*wm@ZuQozYKU$PS8u(X&uLOL;ySn4ifwohe?W(P&<8&F1?4C;|9H8tAO;p# z0X7f>J{SZ+FoP8^f%fT!*b|I7E46BXhGu|<KcEABfY)=7r$Gw`|1YCfi7?Q=qZ~YG zRwC845u+w)HOY(h3GmvEmFTBKWC$Z&*^~(hz%*1IQmkNup>BAGIfI6CfLMHpg=DY; zU{KBMNeE(C0Tz&iPuPS{7=$Ar0~26_>a2!hzy?_W1WXu&e85_Kzy)cr$}SSgZmdKz z5nD4s#YOefWp&wIan=CH71TkS0MLb79a)lXKZE2*Qg9ix=}%1U$B6hxz70@P;z1tm z75jJ#Y<LiOAP!>qgmd5pe8`7bFor^)gh7y1Ho)9C7}GQ`Q%Ue#OMuvXzz1WPhEMne zkgUY)c}7+72TP={k)m6N_)&S-Shj_xwdJ0-mDbn|4NGLY|CFM<*b-jHm<UTPv6V1| zS6Gkwsu=?%Tlb)l$x=dpNQXK7Tt2wmIMCb`-~%Txfg_LvOYmHDc!%mO%gmUpVt9+I z=&lmtT~Wzcc0gMg`PgW(J_9-#%vdPC<K3W$3pjK@PcmK`{m<acDpyd2W+)bn92ge6 zrnq<u6d?*5voCre+9MDIq?Lq0*aSXsTBcB<)v&Rokd$~p*Q}gdyX>yBZ3WN4HA%IX z?V*fl#R>-MU;mw%Itifa16-3J-jTRez(tA7VFj1)p_&R+MnPhljSHq&rVRN9Tqs&W z@LWmQ1W8~6r*)HE1z{U@2nLqj9HiD2RwCN%oB-&j|F-1}^O}!RaERNwVW23Cf2f8w z>f4_P;sRdMkZrG<OJe0w2YPshBXC+iFl6@eUOpHe`<To)&WRso2s~L*H8zYJl8?to znO5iqnc+M~Za-T)n>;p**lLK!kfYD(2vUHCITPa{V!c5yfmoL1SYCnXK#<*AKTjr! zvPI)m*cCPwi;ob6hIoaAC}xIm<If;YJ=x?=)McKC(r$1C=}Xx}gp9WgfZEhsR}e;i z@fX5%8$lZfEOvr&b^<YogHep7X9mTU9a2Md+0Q71JP3e7(1St<fIAsH&Nvxn21?{) zXPSr;Td9nXIKH+`DbZl5RiHeUX@!^($yAE8|7}Q)bf|`Okf3i1Xpyjw{91`Y#pa-} zgB5TH69@p4W(bvv496e^I1QOU-sp%J=s<lYpM#IWI$l+%o`ZN&A#%H<xr#2zo&eB| z$u#Ot4rr!m7hTBaQrOmb<O~l834Hd5&NxI<Xl7HQ*_aNAtnmlRc_t(cY3oo#J?Wu~ za9^3yXs&JusAQ;Ti#!K}YSEyBC~$}v=8UVt>VIbInn3GEoo0H8>&T;zxZV|rBg_E> z=LcHrz792GPG)!p=FYH#hfsoN^9*j?YiD-siI55V=mw3jK|1tS`lwOT4q4e)Y}E0z zqrRZdUY>smzTtBbc#e#C`~!%Pf|T}*{{r%7&W3Fh0!os>lS#ebg_vykKp@*yIBq_O zkkg~a?rXV$2OZYiB#md#sO*M71GWW?!rN?s4sQL*zkeDm^ZMaSu0G00tX5U)b^eLf z2CI5#22o;YU-nDTpo2UR0xF<qhUjjUhKwP`YQ-Aw>oCaX356joAX1(WMl26K@n(Op zPi%tkka+2cI65#EI3%X;07{vasb9$010DE*J#dK2&hO5Urtm)Sh@cZf%p6g^X&0eB zmQkB}XqT>o=^*-P^V4vqe2d*`Vgj|t{~50Uc!dLY1(CpAn=k<-umc@1f;>R+0QdtX z2mmy2<7Dm($!lqtF!C1%FU4>L|Ik@-7>?_Ocyitt?7=Q(wS5I{kQv@er62d1-KsAy zb-p+e>OC(GAgZt3dM_k@Jcko-8QEu%aD`9^fECbz6mSDQumd_sam@Y<l-Oim?(CMc zrXUp{0k-M*@Hv!FuM}k<`F0xsamco&3-a~{aHs}qnDwZohFdR&YM^sI2O>99P94@K z@@R91aPWsHkChpPVzBfSumd-+bT?RtI3R+Q9&4Wvn@tz*&c=@H`37zd;QmZ+QvczV zSp`yf1|O=wfub)l-1Bvp2nk$>ZeRw&R5m@U_j>;YV9@mw0T~x!J~{yh%OSC{Np52A zzlb<QRTza=&;>mJf)sf4{{UctM`wYFX9!(La?fb-O(&ffPnhyPbE%_oasLxjZ;4M; zb?&*wA1w#8CWmHV2F&9K#BMfZ6or3!hH4NUe;M)~*QP@$hd9Sn98L5iMVZ>fR9`U# zQqToX2!kL%1VcE2htOAKPUdR&3AEYkS4(-`wU2N3g}6=`r0)?#EMS+68BlGkTt=$9 zLN;Y{8MkDadif_DnU^CJ1zP}ygnC})D;;<ocE3INmJNW{(gi~pfjZCyU>Jo?-~@)4 zgoWq?C4Z6YUTMeRc#mHQq++9xA8i5-kU!Bwe+r$iN<0(sK&Df+nkUYcQAA{f8Od}C zpU<X>keOp{*%2=Z|IEqfVn75G*nv#Yg;7Z6Vm@YFIOdcHCC>N`t<QWi&lwqAcvYz8 zUeV_F+(o`lyuoOXVj#qN!S8Pse^u~~Q#f;CnKOaoEZS}1w1r`w7zJI>1tUNLL_q%N zTL|?!g?ldrNd*X1s!p8>VDKQqgbEij6sU@osaN3Y#q-DTBF2mwH*)Og@gvBN@<z)0 zCr?)^SFBcsZ0QoC!-uR^ooWWopT(Ctck+BW(jPr=&qS4awJKFAf=ZV%T`G{EDO0CZ zt$Njr-oJnB*!Aq{_3OxZ@yf}2)#}x$l>%RyQf0819wY&Zk|Oo0)T)664-zzp^y|f_ z1zQ;;2lz1J|HO*J#;aGY6)U9y`YKM`_tdIYrA*nXM$g~K%A!XnBq`6aS(=$wvu^GB z_3BcmZ0RCrk|gQeiN%sNJ5a4&kE{cP(iNbH5k$I56~((MYG#AO14P#yfN%hL>(*KC z?p-lFctS<B{_d4EUfQ2Sn{WTobUk@Mi~S;+IV%4A`uFq4UsaSSwiL6TJO<H2k9!Gb z#9LWsQI}V68|8P3D6JG@$OLVOqRS}E-Iow$?P1o6apZ`lAc`qs1XMM)c=((tDz-FX zDXhFgPCYmo#GZ^Q){`SW*fdj$C<FC(B$E7LMx;&eymMlYQP#tbZ)vge)LsnjXV56X zAQD0l|DG&I)Pwj%d7UotnYP`TZRW<FKlK!2%U$=y=w?Tm5o8uO;IN6Od!}Xe8A|rS zh!moUD!M46h(@&%a{`w0j%hps`euRI{bL++zzI}cq6i@s87a%<A%h{yje=cfp}Lo- zo~w`;pI9UPc`2@kS)_|Cnzf2(t_vj^l`5v#6rQEQVu}+uzc{y=K#fW}t)lroch!!W zD%%}Bb7}@0L7=80-6{qNWLGha$WVkXx{%UJQNRABpsORMS?RX<y2M^R-=tOwb@S>w zFH)<C0?ee8YOAkkKly`_Dy0+*W0Dmo$(n#VGOQas-P$r2xTi#A(3Szbs|zAXOdw`m z|IAUBUysn0i)KCKB)c)r7%>LUW6z0fCeGGsX38(v;B<4&T{(=+FGdkttW-@&J@sT$ zLlt#YXMICaJO?JNn8zSrsn^I0)zxkhGW79^EggDzb%-g3tJ<uU-ugA(28jhuGbyb? z3M=C>OxaSgc1BU&V97&Ij&j25+|?FW8~~DY6I3*Ti31jPjboD>HD#vQrAr+X;L+|V zbG`EN)o02~kcG6yW6<52=Zq86M6m>P&LeA93T-)>X1h;0!sA#gt;{X?=aM6-=P756 z6JI^VcjYm2GEb<~-z0icM3}F%{4(!&Mh84L<z%<8^*EpQjz76O2XoTUO(yHT|Nn5; zeoG@U-r|d#C%`*ZtXQu|MbR|Izn93#Mf1B8LjG1NUF4tyec)68%V)mT*dl!k#M@6A zs2TE=t#_u#jB{SGwGZ}harNMp<(g78gUFCCS*n`Vq=po{oJAe@V&O*E^BA<ykSS4_ zpdQrr3SHP|DnE-GpisDq&L9YgILk_$yoDK>NG54;!we~^ag&@_F(aqJ9W%&drvXAR zA^mAyjFfZ=@m&QdWej40f&`2cKJ9a)SOr{W5Cr9vf-t2R$mh0&!cr719AvzsvbOW1 zDwT_VUt8qgnn96ALJ}dN`9}a==)g4|DUlgrqtG@ZpiOeJlM7)Qz&=G2|5b$I73nGh z5|pzX4^^#%%2JCcnt=^h=88RH$%;zi=1UVsg-E{`V>!yf6-aKUn(M&HKe~~M0ro_4 zA|uf_=wZ#;xe|B4xYA1Q6bfK;A_z0k!x8}mFo3mjTQXZkFpbtqV)ke&wpvF$nvn{! z)e~<ri&QZv0uDb_)0HDBM?J7%i&U&8hfw5+MSn(1Xl!zL{4@x&sxg%Syh0SkDMlC= zP=|QRlb&(AsGDS|ieQ3c9Q*vJj2sqF!1bk|IV+s6R@t#C^7Ax|;}uQbNI4DaL~>I6 zg*HADADpgFERJc5$aDdWK7gPOuHX=J<|#6RngSx#=qUTBnxdZs|EU>8Ldr79Dn$zg z;F>oDB4g^&4Oh5=AV|rfXr?Ab+Wez>>-(s~cm|*)VrY=B5Z~%NWJ!jtB`vQwjau=v zGzb3mhI#XAQZVxhc5tnz^6>}Xh;q;JJm@?#gN<tlLL@ON(3O9(>SKx#iWm&CUCEP< zLF{rA!Fh2i6UkO)d$gVTIB+f2V~t-gtG{(1jfD;a;ASYMA5(e-NlW#QW=`=;cz`CY zR{YaH$l(rp=t2z<&}CibA{fus&sr-??wPi8nqstqC|GJ=eq51?YGjI>EaZ+ny7n(p zPL?$N8EiuR!JYjPa~<KN#vgXDQt{P=Kg5IGD*#$u{08br|GZ+3$Y4rVVuivc<}G79 zj`x^WFqnWo9nFzs)r#ps>5kj^$2g`}4?zSWRmJ#Q$>RF8sjM;{1}1TPtlEteDkW+F z#?MS`Qrj|)#3bMN1!x=fooRiF6wkm0{CvzEa)jeYxIls-`r#N`h+>O=A#UOhTF8X5 zqgF45vTpL)jhGO`xx_2jWP(`_^70d)^kEKMx9gq<t7esVZ67(tQCL}oAq>9wM?2c_ zm<(R|uTxCup8;*2(`YlaOEJ%lyL-al744dkB*~B1!K;C|hFssN4s51!7K?y##CX$+ zrt86JPsfQI9mDQ}R@1(6F{fzd$ceF4-LTUJ)F|e1|44ggR+&Y1@H4JFCN%i!-AT(a zDs)_QdE2)Yn<_gDZSX}nw?P(vzylk=_#-KaXFnp9`_kH87HWqgia%~s#a}z9c(Fm= zY-{dE@M{sTx#*Ud7}`1<cS`_bq9>wZ!`!y32UdVwSbrqp-lP@Bfv|{Lw@PfF;7*)# zqat9Nc<tZ{GAAicK?+xttvZ^MWqKkENqThcg*4vc7hi3jrp%Yz>5G$LHTMlr&%+Q& z@C7~IF%KMNMdsl6_iE<r@O&+gq+vukQGMPXW;G)eQ14}|aYi`&#V6*VWMR|GVV3NH zu8Shti_{*Jbm65sSjUuyZR*i=Bm{yR^biM*|E#IEc<_uAh5zsq=NQH@%Dp{_{ly}4 zp7)&1HKF7D;7Gy~(6eN)!R$uTD_Ftfcu*Wr@u9ak3^4>lP($+UAWHxa)N_OMi;qlw zxS39oidX!o$EE)ci+UASsZaZNB<jaM4%B;ndDJ4Xgwe)99#e<RZMN_hKW^}JH?6ee z9rbWWAcjv3cg&+3KU4@rL5%d-+|j9mso98D_}TSs8*&+lx73L8&=>K<1S^C>H-H0_ zJQ>cw-*VAIi$sp3xygReL;^|JI=~;G=$AZfg*e#XI2^+8aYH-IgT9%B<{d=Ok=C5Z zhMj1R{fvm~=?@An;I>6m@=4T-6ww0N|Bpa$1J@kL4cbl!@t0Jj)AL11Doqh>ZN;{* zV4S?5{>`8`l!FaYn9g{MwAs$Uom!4)1rc^fXf#j~Hq{lX$jD5EDV&w{S<gsp1=GQh zD&(Hb;7S%|%sXVu9!3c}0GUOILm<EzH}IcLm7zvNQ(?i<1Nq>rX$CN)PZf>d8|uVA zod!y%28^&p9j1u={0%UWUR{}?6rM)kyh60NngmA4Qv8)EB+v95P2-`+I@m@4Or9Zd z13S#aH>ksOHIx}Gjvg5b_Z1fki9!i-VJPNCR*+&VsGpK$#M+%nxKKwv;e-Z$%~sG| zC^$zgy2_aljLjKLGn9kL<rjCb|HIaZogu&(HGrC?l_N%c2Hz~wqTHFN;2EHd3M()P zI859xUZc{;gZiKZWn@OjX~eX&qoT0lwV5FQT-W2&Sg@oLHR{uu{L|LWU_KJxKfJ>> z9Afe*A4u#CIHX1@+7o{4Nh(}m0PtQzI%HRXgTIi}4SnN6D3u7F5Ge@LmbK6EJlf9` z5m6=x;rxtXu%W?O2YUn~H~hmq%tIg~LFLI=3vNXehQw)@h1wY&4&5R+a!+QwLZ2+9 zPaXz*RKxUvU^g<vMMb4|ECqBN%tnG@uq<By;KYe-hKJ?KcEOHul-5BArcYFgSj?N` zd1VqD0yhKzD22m1u){y?|3qW#Ai#*58`UHhLPy;|=3KhORw&kR?L^4{3UnCDLgs`& zk{_-;MnYy{LI_Mou;XY9%dEjpD{PGdx(7RuLpu}}E(Adk9Kt^OgFD!tW@-m4x&)3q zV7UONnBmFmsKTsp<Z3R4b@EJGgxny8#6Y%5q%D%QT_wYq2Hi<Tz`2C&iH5a2h*{K; z399B!FkQdQ1LNRA72F#&^us)igF5(=b>1dN0EI;PigvA=Y+{)z9FCJ+=XiRBPE|uF zKm^e6B|_w7n?Tq+zGC8Bm-Yb%Qp5yIs9(szXhl{=XZ;1d1QR_lq;6zI*AxiM1ptBG zo7mBynv`Wv_`^G3|00!5#m6=2`rX+;U=BR^=Z1nrJx~KFY}|DC=8Gc4jACSZoE1FK zj)rc`KV^{vQO*}>#7hlj;#o%M$rdB&Q#5^MWpqsde8W6c4}n&JFZjbe1b{fe!#Gt_ zR`f(-RfD0VCDq``)xcwIR;g%&hX>YDY<5JOR;WQliWnt?g9gi?ijd2Yi_u*KY(x-j zAqKE%Tq<-Bd3|bRZpA-*LpxmQA-uu8Wy(AB!`&FFLHwOgm;|$6!_dvmbo5$@&dk#g zL|n$3q#}lncqmn*A(v*vseVMMibkR!RNN8Ifoz3YgwE;}W!@R(xCPaKP*+cK#NG5< zdi~EJ1VJ6t{{pB5z&JGM>mA0AAPbcwQxAUExT45>Jq6#b50yTvMo1E=lBh;pDxgG4 z`iv?66xK}k)c}eph`1?6V5~<J&i&MlVr&OQjl=N-Ks5kDkrh@wh=V$qV4*6;p=ze% zphagP1ja_AgGG%%EZ$)uY-M0+MX_Z_aIAGi#b2D-iP{cM1k_42ZPOMYUv)!07->k{ zVAqVpK`=wS8p3Im!#LQ+Km7@;f<)N~Ymlty(}sl8vV?W4?M%$6FZwKpCRjY^kNOk| z+j@s_td1^tPHxPEL14p89ITt1<MA{@mYOR_IBaehZD=Kr)DrHGP1mmmBRjl<J7j_y z>_A~o|E*@OLspD!Ph^EP3Q0QFCq~2-<0?kke2StequeIOb~FnJCI};}&bXN7OZevC zuIskoj<Y<_eM(3O!di^vMNPQke|AkdY)w~Y!V}zE^}K^P#Ozvu12>e_N>s=2rmpUG zg`MosDu^jibZhMLgh{~C7BTE8eeXf607CG98*oCo6bXz1Ms$=*F~EcUWu4~W&M1+l zSGZ_KIM<h6#Ed!@Jbr_Yc0{2v4!;@1JY+*1%s?H0T>yAPJ7nc`imoW0)<XG)0Sb-* zgItr|+_&k50<VT$)WaAN?)fgncBpT*eniI|a7Wm}BrpdGcLkxL2|dU|cqEPrhGqbF z|8Gbj@rb(bK}^>6{K8o|D@Kr0t&qbZwgUwR03!55oM<pvgonn+rFVoTjUlE|Deh8r z$Lm<7N5ybtlBtq1u|g<uLeRlM&;cKuK>*+Y4&Z_Kz)NE65Y3Qb{3VSwX6MtPE>Em( z6BjQ>B-yMbUFLkm?8pPH9^xb<K@dPfJ#ZyIw1Yu}hgjf5+y=^NMQF`IG8*UXc1>f^ zG_V_Y#SA-38n#Cs2muXL01foPTmXz>%*(7uQ<>%rKz)NmQl%UN>=H9F9I@{lOWJpm zNMV|n^(I7Ce8WLd!z2X21*=zrN>i@z8{go?rBbMO^hdEA3w*}%d&mPUwbmjB|11j_ z#2*BJ9SA`H41pU2z&rz2V4;ag5GLLL=#&lM_H?Y9s@PuA7hf*))jR}=2%-5_v)4eL zL4a~T<3aKngg6{THM_~uR>Mp{Pg*Jj&gO<PVVNk<);hCuM<56d3vgwu01p5{02qM| z1i%j%L>zb=B1Lpb04p)8tL#++ea=vfzQh6JaEuagPppM1@YOarrblfDl!!w(FwP+u zL?$RBD2GE<XDFGLWTj*UN}z>cB=tf#wRaGjQn<p6<VbnJ@Iq9IGa3j?zU1`*FFB7Z zQ?uzD<-tMF01l`@9{hnF)N^iN$zbS$No3$K|1N5wofQJ7MKa2rS@vP9|0k?e#oO7D zLj0ID8pI<!K^+8uGP;91$m2&V3!1*jdaB5xK$z#c^j91RCUS&kV?>Lp0x2j&5g@ib z+cO{JhN}Q|YrD@W1A{9-%}E0`bi=7$h8`;<<)TUKR&b$Kbb~uo4>730P6t4!8N@<m z_cT#$k5o!Txky!vv=YilQ+&#tmIQ;6Cr(%+=}wb1(lracbG2^lEzTDWnT#RXfdufg zV%tGN^s}#3hP~W|?`oEHX5Wht?R!u6;kDmLI!XCqt)NN*5`;l5q{AV8gNaD&4SKNY z8P7OZg@D;&kAT)vRJSITgl3AyXa|6-mTlQpUyQ*+%<{K#BLpV?|Mx~n-9i6$E40A` z)PW%c0Q@S*Q=m!Leqw~5$tcemEmGwD=1T%QgnOddJ491Gl!Gt=X&fYhA^5^Om|LIC z&MTsKIHT4~u7am@If^*fsHlW4OhkO-IAV-MKV(W)bTT<alRVNxIrurUT=@bqsQMbY zMi6jJgo0bNLg|D-C<H(uB!o>L1RJb?3j{zyiUyWg2w4bp&g^RgT?zCMtwIYefP+M= zQybjc5jbpgEx3V*LxVb0k4@RQ?I@q)a8c+%<t<wHM>GXRvVwp}mH$=-n^ccCKm#=l z$zx^vV^za8aK)4`qguf<Elau$nRFLLMUh-briVf?*u{be{{Rp00K6N75*T+X;6(rw zLt#Qx(yU1^iqcd>8bN+Ucj`8<xCFHz3b#(RK^%i2%z!~GDD{%%2?lYdRF{flWu=f8 z64qS87vyg1M5El(!H}fEI{HOe%8y(gHT(i!)dhgecy+VFFBF3}U>$o1`L<X}ZU+Fl zXLd$b6e|S4D6G5N{ZRl&0uR71{F;D4z^@Z*Dvb(`%M24d7-7%i%+YL01Tu5u25ev? zCb<<ufj|Q$v_SwE0zYV`IJCorfqN_xG%L8m8Y%NRABjv1*bAdPMx3KXMBX@T129Zf zX#I-JJl5}=OfysiP}nsw@wIb!#C}XgD69g9)IkEY|G}oO4q-e;RTzX|CqyBnj!Xka zddA`?a=lb|J$^cJM=0(q1Vc0gz#dRu0Cdbn6RQ5SF&`Glru54CCgw9c^G6^_DpYrx z*o;tn1u2tqH#~+d@RhMnXw*OtfFutT=SYw8y>dH=zmbA3OTK;-#N}uH=KuDE8-y+_ z5&K6FY1FXoSQR(q9$wm*8oR#tHgkvu06U#FKm>RsuU>!v?&u{<C{NxxhwBVRlsJ)M zMT-|PX4F`bVSs<tY^^G_YLzLICIg_1sPd$#jW1WaOnH*zsZ+L!73>HTV?u*F4c3EZ z%T}pUHd(Q<*^=o=q_1kKYW9tuzkl);%Hz3}|7%yC4tIhJAZlbunHE_(4e%;Joe5!F z>3Y>F0I5|rPf1J_Ae6*X0seY@nU*9)h7JWMRy>g*LwNA&RSWgkY|F)$XC}5RieeH( z9u0=0SC2GlaEBpcR=rwc$A93ciBd(fspZTwRkFryinb|Nq?&>AM-S-b#std^FIKeF zt5>R$s#;pRrA?Aa@3zv_uU^7`>~x2}{BRw^c=5!N?G5uT=U|9Ngb7uQRQ&*zbBiA= z(_~?T*vf&YIQ<Beh_nFKiHwx8OiIPU2OTVMA_ysbP$LKnGvyRjDte_DU91`BJD&nb z=s*ck<mp6kz<FguRr*^6LW3gIuR;h-|1!#zSJ>%}9`PKj2b*778R-?1SaI<b2T8i| zL6cOOjimN|DW<9cQ_RvL()@v}8oL^_up%Z`;Y$}_5D8%hL*z1O6{rG;Qp=Yx6sZ)P zsycB_0v%EizovM~Pcx?W%V>lh>hR>u06cl+w8y~Gszl-%N^Q?e18~frVp?&rH$YKr z%DTH&!Kt2jj>GIYdB~|}o4Jhol)70(wXRcUu<^$qOfijAS3hmTD6dwELF9x0*sQC_ z+j!k5#*u8PMl6F6Yj!nV!D$A}Sv5*aP{k}mDL<PeIx7G~VlXIKgG3>#m1^K|D53Kd zqSV?;8N#+1vT9?tz*?^}<ri$||A_}kdHkuTm|yIg@=sc4osN}OvU>%Zf-;r#UJ3I} z_)GjWqU#kSkkth+qe?kx<CjP>3eS}>^VOdrk8;@NGTEEbO`W^CS)wNQT1CzPMwuvr z83JG>fMD7M%pg@l3GOj=*f}mzEMX4MJoK<JMakZ7_HQwVCz>)wl2mzx8*mCvRk5Am zNf;VZSb=dByXp&D@4fFjr8k#z+BM^>SF5&TKgFJKFN1VhC65xq_^ZBHc_#d#mP-W? z9%?PM+$);P!V52h$la>+#7+-DbkaxPh_j|?R0TM29&?*S&$CqLANnX4o!q>_8(s94 zpbZ>r!H)B18(=~r$*xmS|31q1>8Yo_r6^r-rI}L=#+|jpB{OUFiR@z}h#*AK<u8;q z9N+t&MJm<G!QbcVJZykT<;5t69-1fqITWV=u0~FwFjpP|FoKB4r4;RI7w`lKBV6g~ zc=gi{)rK=9QLG{<NwEn4LCC+vh!B8CVMTvT0Ss*XBLGxe%|HIpkAG-zB>M~D4RM%5 z5IU%M|4>IgG-g4;L@F|&;Lrdmatd9HA_y};gf2uD7!e9FA|`|uHpEgvDjH^nzqpHo z#+N#cRL^~;Yu!mm!5NE~%pgW#UFm9aieFSC0PomhmJYNI7QNzmag5URBqGL&l#Yxq zvI)vop&iozku?|$|9~z+61qZ8l9HkW<0(3opvK%$Fu$S(DOBO0KLYO*p<oLhLePg- z=z<i0dBsRLsh3p5suU{x6~<!OljVryjjiKJA;)+M>XgnTdGSz2)|WCt*2EOHz{cis zsh?FLY-YgVSNn=dJ=Sfrij|z+vqa%c;ka!vTdRk*HV7tf3a@qE1n0o$A)p{eQzP_x zWGg-xz)}(`O-aba5~Ei`-$nBjz|jW6=$R3EaLSGT8q~LhWj%8NBLIvr0@47}rZzeZ zRAF)%Ho}om{Wzo?<zNUnzF{^8LCjnfVQF>zW|pKFr5e~kj!C<hn8wrtGRwK<bYA+> z-PEQgiPXh7|AKNJEk@HZ@PHu{^J0ot8l+f8D1j&1xW2?CG&-}3+fs9>Fk1j-JzdEU zsL+DVeyMRHVZdr#h~~5!8U&*Ev6D03VMmb?h)W8iSXtsoouRUHuqR1Mj_wpV(hvkQ zd924boI|RI1(mY3v5s9t@e6RgV>mzB>qX?z4|e<ms;WCh(F_uTN3!K-b&X|oLIDin zBn+1c-3dV;c^A5>3?{)E>~7JD8&c#2coZ$d3^2->R*WJrYiUk%H}X+<==HPTla#(< zIwhc1mb-rwg=`-KLwT_9ZH<WsJ%(hLC;^R7v?>>2X*Ck<sDmJztZqa)HeM*sh7?6( zL<i7k|FR;%vaq|QqD?LtC23KxQq{_(IoaWgR&Xe|-Qul<ZBtCnu$Hv}2tg4Zsf$^# z6=kn%C`<tNqe$IXHOKjfUyTwY?#`GdMkP&2VW_Ic3<r{A!H(Jb<xpq6v?ijcMmdx^ zPmwZ&YIz+kRHu4AMYYjs?#(4iUi1y_aZaS9F;O|@^2G=FZz}+N8WPV;CaBm%JHX%s zCn^#QDwo)1qD1pVqC_S|V#Tv8ZY;)5x-XQCN{5BMq3Eu|idB3!SCA<OwN!PUbGo8# z((#?4%`8BP^lyqdgp!m@1x-IkL{|aWRHt-d2-W_D6R&(Fgm6euVVWW-T0XCzzdRQj z|E0pU6$vVEor0I)0s|PNz=IJafKh|Y0;_DbD=8re6EK!a7eLJMs98fA@Pt{rv!-!v z$n?R2RvR4U7)@;#!=;5ra;DPTE@68MG0Ztf-Fjm2I!05BVxs_~tsL-lMt!|gaN|^c z-s{#%Iv449rHtGhUi&DbhZ=Ms40V8_(;`9^chB0uTR{njbn%bWfEC*t*_uc22PIP& zWu29DP`k-e41yW#DoXZ>IlJ+ucL&>>znmnJk`jt%%(kT9v8|-m@tpu{gC6C`Lj({} z47Mx?mJRnaDXNWAKTCQo_~f`*`xUPCp;jU|SRgCc*RH@=-76n|BoG~3a@DYq{~%H) z%c#Cht3?xwr;IcRdCN&naClK@FbcAj+a9r)N@tEdCAknC!a{OvBO)N?<9&oI_W&r; zq&APHm(Q*6%k-Kr5rK06N)QA_Ma0C>D@lPsZtWMNTl0d6=dW5sv6$waI(O3r7Kihb zhNwo}%i#^Y1uGbqdhjN?(A9ZwmrI|Fw;Kt21QP;4jZqA^_7;(!JRUvj^8}zCY|-Ch z$ZU`ko`SWEC<I0k!3n8P9V$j~jwu#*=GA~P_Lb`XpA#a3is2MQ!8t}HpD-<yQh|S1 zp%h3#g@DM#0B`O{s})x6(?V#|kSNpsr_%yxz4~UoL}7d4L2y2+AH<;^|EPfq3V|E` zff>kR*V50=Kv2Fyu4+6_q{45)6r)0}gF`wj0CvD4L;-kqL`h~uLMZD02qa-Xq+Oz< zgA}dsDr8g=4LW4UL;P+hCa}B+qKNRqNp_7Ql8`H$qzacrf8<DWh$EUPs2;lEM<hWF zYQZDG0T^0=6>6kLO0EVI$x586bFl5sHo{2?18Uf!6I72~Tt|A6Z!yRuPUyn#m@x2? zCt<)rE=a*Q8Zc!}qC#Yh)?OhM(&!az3Wn$|2fN}DK|(!b<P2rWBKWWn&(H@+#TIno zN>mYd&O=xFp&tT(8Pp&Us^K3*qa3P%(hw~F<SyK90;I-a#aQe_{|J#Qey2Wkfe}zo zmDr+anu`%8AtJ(&tW-h@qoW#qE}M3w8@8+xG2{74&>z5|8l0nDIB2EX=bOCdl?qVi zz=4Heh!TyXF&=~bph&W+M?%7gdTOE+TH#$fFP50>8{EMi9)S+sp&i7bh2YR(X0hZ( zMY;qh?yBn>o(Ak{1?$3K20Q_})`BfuAOKi^0$5-sSwJs<r$Sca)9!*D<Hj9zZ2SVC z9O?lau;D{YK@?~$Nt~l8okI^<p<Rlh7<wdb)Il9s#D%QuJitL4QsGDdh4fehVoZx9 z_-KOs;qjUUDA=JL>cJQGU=Oxo9J;|Fex)1eCQ8I|ulnO;|C}i~;7$-lYFC<}Q^Y0l zT4Fvrpbv^67(9V92+Ra7LNaM&tHzQyRL2z9@z#Jc-7p3`NQ1NLp&X7<7ot)WLcxJl zvpI^P8n`4aE9EfsLtonE__!rhUaEs$0VgtriePB8wjp6Y0SPkU9mWBv0P-J73aVm? z2~`ffXv@#KBmkO$H$({~gKZRa!7Ylw6M`WaUda?ZAqoOO3HZPc_`nVLAUy-%2m$~Q z0>BmaP)u0EZ#1(VJ5x70CWDT0D*f|6u>l*pBgu|KC|6@AbOj`04FC2b$Rs4FUXB%Z zq*YpD7f~ecP(yjh4-Vkq9e%_eS|}kNLadD9BeAU||M;jG=wTe>iOcq?)T+}g(6L)) zg3Yv36zTv3&W969p)n)E4h-TCfHV&PK?x#)KJ^1iNWmvfFhBKk$8@D$q*PbpCKXcz z?&{$nJrVKdggP7~dsqQDP6amAGE4e|9p-@^Y5@sq;T<-Tg-8T3vNV$RlAfAEK7)g^ zP~*OSr8=b~C6te@P-Yagvn}dC0%{-(ihu@KfDHoR4<-UWDZn6H!7_KUC6<)-ob+I( zX_^e8)aZvm;sG)W6D+xOPlAOvRv~+AVqi|AOj86b{(<tyVGruS7uLZWV2D5~1s>Lo zax{-nzLMa+%Kr|InyAwhq$CJ?<`rAU{*ECS|8xNn!XON6zyowZ2;2aH{s2+~fCvm? z6vJdS$Yv%=Vl$g`Q}M;Ta;iW&X7HdwZ{P=0ZYD;UZxo6FL15KgdvzP?fgQrY5M)Rk z-r?FRR9CQpIsC&?>1kp6CP@f_!K5=`Viav!3Oh@J0NaHWJOmhyzyy$B26R9NJirHp z;8Bf~4p^x^*v{knW!Aa@95_>5I};*yi9s$5X5x$5B0?~&CF#_`Eg@kDejxzF!5xUw z-h!eYx+Gy6$TmwZM*K!QzC&sE>NTmeVK@jgKrx^=fe1_>4hq2z=l~C%Kn7&M1z5lX z(0~zi;ccCxJ~C}SFXTp4hu30uW@)zj{|-b_AZb*}aAW4v79W!G<V91n<l4pyM7co< z0%08LK^%6GOX2~4V$dwcFaS*Sj%oyRc(XiwWMY$50qce}Kqz(Mzz$T`4)S1Z<A4Y% z00(v;2xveLIDrv9q;dEt6c#7ee(8iZ)8O{@{}O~7Sk;E!2Zxws1cgI*c?BZg!5!-1 z7vP{4>cJh53MTYuUkZ=YstbUa<R)@L^I+6EQz0qz!_p$c1fW1j17LOS;186*0{}r6 z`T!Avpae=l2y$Q&2vrw~f#u}Z@VE&hBIFc+x8R2N|6cQ)LSYJrMv$6?kOt~SL}Fm# z#%i@h<o<yi+JPPnAqkp69mJs>|2{QcEkchVD`Q8gWe*J6rX;g+<=n81Hm5{7W>7zX z^nF#=Ab7w8_@ETz;%#+75At9KN?-=U017xkJKpvv#-e~PBA*&4W(#J4HSZFKBwqVQ zf(d7J(hzX!q2{7bJjjD;ijEypkQ(B^5Yzz$Z%Y-M3W#1oDK^BkT$qzWlF=k~)Myim zmBx$BP)t+;J|*HNS-=MT!XcMSJLTdPM8OE^U<M$Ebw@#3<)SZ^M04$SCZdFotk`+6 zxQ6`!B%T9kbkcKlvTvG$9867=3j~IUGJ4NR4IrT&#z8a@*CG<aS2;x_QaPF~>5}Y^ z6c!AH`BWYS?TBV{^dce-{|v$eRv-XYfHEhd#EgPaiA5L4q7G^R3iMYG`k)hl0d7<C z>pIRL=z<(fYLw+pDB~eZCoBz#%a^_w+E^!6PN5rW&LGNIHLArSB<&l#p&sfW3AjNX zyulp=8dW^+Y9z&%6}F3`P1dprg^n59z$bfLB8Nw>C2+<d3LyYSdJ#yv6I>x_EbTg) zvVjOyJ3qt|5Wxs~0EvqL5j3Hk<pMP);}iE{fXHEA-C2lmZgNVYM(VU#sKY2=Wa#>s zPu4-H{^4lr0T2w~AiSZewDKijC_#ULa(pY6de8S*B+0PNvkHP@yoQrEw=0mEH$bUO zOh%(tt4zwIFQ3Jg|4d92f?*VZp%`RZ4<-P)Zkn9+%{fvND#%Q4hx%A?j3B}XtQj<O zvt~Z~@>!#$DyZh43uhgg%wK;22_WG+M03214y+OagJ$NdOCc!&SD1P2By2DM;(;Vt zY-aP2{a!IejG{g^@wX$wwJl`K-efJ<MdL)_l3yVjJi!q9U<M|@2!bFCL_z*oX%+ec z7bDO@8=I5D;ul;*PF}ICEoVkJBz{cADlRnX+Oi&M;SGFYs@*~95X5IQ;$5pjHu5aC ztBXt|l<%@wQs_7jlP0#48aIK>X)LpWJfUd5GZpF}!X-clihvv6cB}$`97by~Y`eSn z#5J6dwPi)D|7)XDdStvfTQRC-v`V-h?BEHwp&jNyp6tsjxbjPsB&_X}LC-f@PDL8G zE*{E(9p*wQ%#T7=rWR+UaxyNtmj*mbp$>vT1ArjH*+L;Gj~&#(=(wW8JzPsVrbm7` zrh>VC43UFO!8MDOuf}0C-XIgUJeSQHc?7RTIOv2XTcqlwfmBEr-&x3se4g1N!*aHM zu&GR7Cn6e17nlZr!+-`PU=kjI9LTF6Tv_-qBA_4Q%Q0n+%dcT{{Ek3cB$#*2S>td) zn+9q@9Tr-=R;A0!qcM_>Iq}h@2*uEAjL*w~voM{-5H8TA<F0ut)Nvi8{bDSH_-#1> z80sJZ|I}az1c4Zs!JiAF8_cc2Hl5S6W{$taj)|R$Mjb{5=BZWuAs9j<-5U<50R^q} zd;AKR4cuHR%yUNlZm1zwVDr!awa5{8knH)6Qiohn=494le6xWVAYljEAPEe@8VaHw z$YC5Py;EaTQan}L^@Btn0~}ybeIYKFD0rn-q45NVoH7DKu^r;2*V$!AG=xv686%?U z0VKqXf@N)#k^~&|1m=Zkz*8E1|If^DMmyYrU?JmQD`LJgeCf#}HM|_-QRFcaHh%0X zp+ZQMSRuW6KITVj9^4WR+5k=G0f?w(>n*|`DwpukCW4yTd-l6{nAYsyXKQr6v<96& z|1Op<&1Kqf@jJ9q)S4k8-XIV*!RvqI8_0niMAY0n73#$!E4pMkVhm6Zd}Y!CACqFf zTIjU7yS^o2@dJP&=iv=%fgQf#F-ppx6=E?Ue`W-2#52##&$knO+#gEH<o!&{Lt-s3 z*VhVt$2~VEUR@pLVWH_k9sEHSFrf}gpbZQm7v_Qd*nt}~TvsCH=^g)CNEBx)pKw~j z&RW40=;0r!1_xiF>7zOxV5p!oK?bbX8``1lJOAe7fkimhI%3~~`qG001{(k(Uc3MV z3mQC#FrmVQ3>!K;C@-SC0QHL5S{2|G#)YOjntBK_q{xv0R;?;k$`-bA@aRnp|FCXd zM1$eV`5WhJPn#WhGR>RUuHLtA<Rr$7NiwO@rA(VHrRTDqu2v^adi>}#E7OjuRHaI# zid40F@cgl3H?tv9m`5YJqc{mqzkllB!PCl6qP%)iTbU|V@+#iJ4Lh22<?3WJaP<7e zOiMU&(~1{Q1xTgPq(RM+J2NzS>Xb^GkP9OH_btHBpwy^kq7r7uBVRwEa^r?{ozkPa zJ^TJ0GNQnG-CDT{t*Yck;J~eVEG25OKYyhi@)r1y-Mo64-u$E2?wve#0)a;?_s^oq z^~;%S<=l~#{8!+}I_~X0Kf$#W)t}PXk$wUuWD-iYRMVJ2dJ$w7Jny^%|Ia_&tVWM7 zz61hW7`RaLQ$6w!^^ZKfmBt%y`}M}(fGQ3)TsK|GcU6EZ;uRWu&;g^(bWjmg-9c;V z1r#@G$kom~XYr`lOIjtl7d_ZqREl#l&N$LlU!AgwExPyvk2>tcv?G<wQKkx(9w`(f zR$}4>-7nZQ##cfA{8P|$1VJ_3I{~o6%}*57Qi~c?)KSMX^}N$gJnMYJj)!zUIwzeC z&ADc!Bk?sIIL(lv3M&DGW~ozFrou`qQMySFJbc9oQav!C=1x0dWYP~i)6K~$aC`}b zO*5i|2CQJAGBj$GwiMIYUc*YZmOu1VV@qgLCM4{#OLg=LDT|4C|EEhLt^?ItkG(|C zJMP>y&QI>BV~8PAP!WhBn6^U{IpETBVu>YM%Wp%O0%OW5Uv&g(zg5PF<*}(o1XYhn z&NSXX^PonBFA~qgFunyj+*E0qV&e)cT@h5R!6bWBU`i|bQ;)YMH`OdW*!+T$L%;(2 z@<YgVr7bvi2Ee32P&NE*w*kO24$|_d+e{sX=m5wewX7;mH(&mv+qfy3m@~iA&0LCQ zrrg}M&cJ>ZWh=VWL)}XpBYD<M^x&d~#oW*{5JX817BtZEOw|==WfydFN6-}mPFZP% zIXFlQ1^{-Ht4w?H$ud$t_`s%wwHUr{2R9Ks-GtK(JwK6?|4A5O93crO{j9ppIA50d zdE-<@^bS4hl_FngUsY~<W+#=RHb35$mrz9GMkG!>kR;(tJ>D3}&WQs?<WG9Gyn>~` zsbFsHs5PdtO+Cm5pA`1~U;_*(r+|M@$><lvRnIO(1`as#kTcFWEWa}kY8WC6K}f?U zn!z$xbz>c~6NtF*Gd~rn&mt&sP6P`xwo{~n6x{IHeH?O@cQo%2dpMLh=utf%LC`mP z`4=fzAtf~#EKO<C#gQ(kl<AbC8lq4I!ElB{hXm*ptat@ELZqauJdPm$AjdX}Vyj&E zq7Fd_!zQw^4SLk$ALHo8L?Ut)t_4v)?D)r2Q1ZJ^|5;{?3Mo}H*yaz1+-e=;a2_5| zGY*YeN=MZQg%2}GHiH#zY^zXPcFxDfhpeL>)i_0RyvLBQr164jbj2&?0<`?B<0kEh z)IV@hhaFU*4Y>fy7TH0LGOmMCiPR5WUeO9qnPif!yi6(z6di2*Od)vkM?2h64-)=E z9PLPAr4q!Au5?6_lFZpxQl=6(xvG|GSqC_(5ireBQ+Nci<TzL<AlwntS@fXBBx3W2 zKm3Gcj4H}ew%M8KFp?C<dEc38c@>k0LKJSA4vBgb5ib5?8$qZ;J@V)>wpgl+fa{+8 zLY1cV<kB7DF(y0>GN*`4rAF(y=s|q<ia8+?|2Q!@OF2BG8gDqpAKWN}Bz6!6Nk9Wp z^<W31l!u}fCL~23MUp(L!70tLr)-@0%ti{7B?Q4EEhC!A38_JaW~hUh^e9K|^0OdD zQblr_VNZLg<W=v1hCbkUkU*B`(K#J)Dj1<<PXl1AVwf*PYmx`P(lw8{l*1Qzs6rAl zv59$5v>x2Zs65J14kQh2XhwVM#^mueUri2>K+IXe2y)qvb}z08GR?gZOOHBwqi*%c zB0Z33Q7VlKY^#vZ$kdqG6_G7ie@Tg4^LEzMdXyY}S%p2_TFYk+?^v#qlmwF)lX%FZ zf9m3fFW~S7B)p*(>Z<A8@P)5;I#!PB|NDisOu@{uF>}0_IS4cLDT)KJ4W~p)tT_Au zRcf$99B)|`lOl4>!?;3o;kD&}$SYjKi2@ibY1?)WGMz>>l$Np8Z18-Sin!Xxz+w`Y zxx(R%BDI4a&B(+Ps_=$iG()iUSO+)c;lSMJ^uPi5+An+yn##Vc!88UIQVpp$iF8AH zr2Ph66>49J)MqN(gRo@+sh@(~>}Do;MJmQJ((T4%I;z@T3_<eHei>%C)vyWP=yX+* z%7jVWm>$b~@fs$)p$?_1hmpRqO0BK<qFPH2&Fl%kR&qrZuFyqx!gZ9h%mW_Hc!GR0 zd_$g!DJ^G_$3LoJs<7et44w5~lWi1-2ODhkXr#NlyGD0+m$Y<Dq&BwEqmk|g0YMQ^ zNoi>rs7NXxDj@ixB76A@o*$m`x$oyW-*c|33P|$~U%XlW430(kizc3K1dp!ElH{#O z$dJ4IPS1|*HhJFWsvny4CWmB!=V5;wGb^E1cFh`$6}CJFr2jaJvDsvJ-Roig;Pi_k z4@tnK-~_Z~IrnQBd6s`lM?o1ipKp^P>icHQh|?S?&=w)(i4yn~1rD6?eKuO^>OCZu z*_dBgSH0<d)jNjqioou(XvCu>$f-d>4%~3jdi~!P9W9Ss>0*yi=Xy9by&O~%eWxHt z=`ei`d?J(M-x-I~U)_*bcfkbmQVhzq{h06lsvb~WL`mhJWYAM{x?%6M7OB!NzLQ{7 zvp-7Q-c?>{4j6D#fL8o0HK{P2Ox1f$+|+@8CgHIk=JL<*dCw<hjvlOU>xIAmPfANn zB9yk@pqHWEx<yyS{MYAKFFrhL>?gItu8aRl6#3;tELqTA!6nGZ+wH)`KxIbzD5!Q$ zezsO1JdTG}D=w88NkD;Pvvlt?2~|ZB&Pg9u2t6{tV0PCb4J>^U5>2kdNr>$miu!hX zvP!q$JseBW`aw8tIOGK*rDM{-tB0S`?)x7Aiz$`o1{nKRHTHV40Ts{K*IIPx7qOX9 zXTE0p7T|X{>HC)yUs$?b{>D7f(dikU{d$EP=Spy#AN<+A{9@7F{&pbbU)+0MU#s+6 z)u@MY&jhhO_6A>IM4pw}q(KD^nhZMp7kH}gORDU>6s-lIXsCmLjkVk;U&LM75y@5p zrtCf-O}exrLddtsv)yBq_#sKDD5vK~7f`TDFZ^GU(Qc|SgJNT{qHj1%G8T$krjR6b z`?Md@@GKsB6>^amKr^bR7QtXp;2C*AQP52r;sIIF^vWWnB5C$g@`YMG=iXo8ezHT# zL5-~UQ<Cx$az@dFYA2>xK*kFbf8Q4hs8v6Okv4YwZWF6Iog>(H4N!&5ilwTdKNa4b z3lW^b44U+)nzX2k`JU@Wr(g0I?nPJ9alf*F^jJb(heaW6>2jJRoC_XJHL72A3q7%* zd8t5iBj8<3m`aTbjJHYMuYo#E<0Zrns8n<!{0m8+Hu?lzrczKNSl9V+07?OzG#nHu zH0I3ElK~+1$o57FTT{l5>s1}4&#ga@(xQk1fMq-&jcZKu>o$TApWY+(z9TsQsL=O! z(0{tnc>}kgF_R`qv>`p<;TeQL)5PS?mKEv#XxE^AFK2;{hQQEG%1&ntr;vCQaCOEj z_cX@A6aCB^1w>JVD(Wd)*<RM%xuBTuWN|4=#0FuIJ}D~kQHpnHIsTP&kyh8wc@GIV z9i>pd(uL?<g!EAh+2C2mSFDjx6!L`t`s=xCsus#H4;_#%8PP~dI%B-OCu)8{TIUfg zCzQt#P6PC#4POh0u)~Xg(RTlOK!!d88G1lagqo&>MlbsFf3Ku7GMR_d6;LS!hEB!Y zjL~;Uk`7`?G{O=m4!A5CRR5!=wjyA5tyQv7D$zHD(H)zg#CnK<sCF#K8@k#5O=e}& zdTh#uYIx_3%Cq~9KA^Rx>Iaa(0N@ZT$vtBBzi;w8Tf<)MdeMUnsXQNlR}^*kEPXDU zoRtim&euO%!gPY@saCN0-sL|ApaDAAeYtQD#>-?A8WV0BaX-VG38mbO-rdmRUU|$& zPjx2Ac#>@Y?d(DH2<R7%>M4Vh=S05ab$Z@;fMjuwOhDziy^ujGX?!|FV25OqlQNgc z+=k&U+9w6n;Y)SnBf;>3zjUT_#FeIxHM&8<9(k-p=ZW-xoc4+`n``8M@B4o|wu}jv z{THdN!9|I+084v-i<bnimMHBI)`edjfA8`#*0P=sKpETW=>wtng!x@3N$YCJ?h?v= z$%yQT@Xx3)Td?PRU%mMsCkx?5Mkk(*WD4984b>pjvENc;!}4hSp1hU8AXZp_9<bBU zNRnd2JInYTt8BAF%(7DVo|9JSSuyUvD&t+zCGK+P&rnZhJNH3;SU+iHojm3YSan8P ze@5CySlUmQk=@6R*=0=$Y%K|Fedxy-aTO8J2BoQ0vpvUdwEBLM51*#duZn7_nuYqe zQnI|mCxD`ed!g}Ss~UovWmQtXFZq-l88pC7D5*NqTFC}!&O3rG>60^30s4yfbQXDg z98wK6tHK>^VTywdx`?SZ18t!~OM0XMrh!3q@rd7dSu(G;lfqK(-?+}U1(~Ph-S3TO z!YJjwWPD*s^H7hWl@vPP&W6e}U=LpHT~IyPU7fK-Dsf5rP%A-=Uf~C4###XXno&<v z4YltIX+#m5e_0pEk}7=?`<k<;Vz+)YvX-WwsSV}A_8xi#pwz6lN*JXWfU+d-5N}HQ zm-$IlO*}nca}ES0@;!uF3-{UNmnYkI)Si)|EOi79OM~h74*`@s0vuho{5d*(j_>iQ zI=s^I_ZvUgOQ~=61W-Hv1w9;Y$?=uZ;rEOzKdupd50$YDA;s}to{`*HcC{oS6FZb6 z6BM7Ilrdb;-93fi<6>gW0Pg2gdp~(%YDCpW=qGySKQq<cKEjo~9iMr!)%rQ{cRK=_ zXf7Fp*9L=q{gLwa<hUiOwdHQnpd4HSbwOJFHwU+Wbrmda9akx;oEZqkMn(&2J=SB2 zRRPTh-9S_g$y0v1Pc_9)lxS4f8LPFERE^3B4Tqk$bNr)M97+de2*(z{bjX74(9r`L zn+{^5>aXp6=3Z1hMD--bB*Yg;g_Sd`Y#K}(p*=ACAN(X;En%Hx&&_Hd{IkQGaVi0= zo|+w=JztoUt2(NZ(x(pgHGdh0-gPSZSgiF;KG{<eSf#1j)T`HkHOw_K%|s}a*i%j} zk>=2OXDAui6NtK<ldfSEAFzz%rn%oZX%U3g^8ZZ)g`>PZ#}$U@&Mav60GhNg3Um!I zl>zxT3*Jirx8kAZJ}$rN&KR^zy5iijCPJg`)Hk13?y40&=mCnxcKjS*<?dkN&3cGg zf4(uH_O!3ode$VL<yAY@Z49IBWjp~+5hC!Qo+cd+crQob-^pF7nN&d^z9(8M#Qq9E zVtz*K2_RAYS|^_-vZ^CA@nweTipuH5<cXho!u{zXgHhRDy>b~PZ6`b^x`r${r6Z?Y zY#~|U&46pdvaxRp#iVBBEc{u0khhtgj-?Q3M-3U|1>@H2bk#HUkuc*|Win|UQ|cR~ z3t4xKD~5e+m1c@xv?fv58RXFlWlrq_vB+i-l6%gqT{7uPj1?Rp>u$d+Fb`uu=#-Ma z%mh0T8p23DSwr@>&wNC+tv`(>r-Ax!VF6o%;z8!Z+YTYfKT^*M85LzEwkQp%PWl@H zs_&AN+dGu)c_b)K;OGC8Z#`1?Icd8#)9Xy2vqn%@BWrR-Yw-z-r!9YYGa131O;a*L zu$CG|7Wbgf_~qXrac6SCN7BDKI*R`i1-N1dEy#!aC6im0Np|tQj}=D!o#jUqn|!GG zhaawkwPFdNl*eAGXIPSGPNFZ4WF$6nYC`pMK*!e^(3XT*e-=aoTnyA+&Eo+Xlq9XU z&_c~Ch4H?l=4G9Yc0gZH?kvp>LSqR{HwoF+A$y`{-RYES?+mr?4L}y<)2Ta?Ur(j3 zq^rGya0SOMQyl;(S$^Ny-SdG_RRi6^jnPjcUmAkXpIkZiBxFNhE>Pd&&7B;9NOzN_ zR(7bUqWXh5TC!mXk!-vN<GKa;Y#Z5Z+1mSTMX{$EGNV1MrcnJlHAd#V#x3fu?y+V7 zISxwsgA=MCxNYQPVtQ$Mnk;y?noR5?*lzU*pX_iy9M7P#Cu}pieks#QOua=;KtvD* zBItJS&(vy$t{a3APMMJYJ8_0kb8e;L%*i6NKT3mkMW0uS{QL$b|2f}m5ea>^BSK^O zHJnGI#95I2-o>M)e@}Jsn&j3tx}{;{$2G#gT=n3!@J0v+G@$xRCtXr9bYyb3+`79e z8T2Tu<DPg+OsAOGv&HvYPss>I<X;K+pDUMJ^`mEAkN29W54`lYOj{EBOw6_8H7B`$ zw?u*<LrDUu1j%@to*sAzeB2>Tp*~!58s+u`6P$r9?pVy4Q0}L%nN3J1m%w~Gt4QyA zg+gO!f2gxM+X2&;)=u?{iAOyL7P_sUrFz-BLHO4i3@2vcF{jVBXi`2+&{4h9rzrMF zf0+CfI+V9FLJ@I40Mb?CU<cJXgL1({y?Gj(T|l$Sq<Qjz;reSKz>_Ck%RYZM8v%)^ z0e&e=05h2%XU?}1r;v<8u`t2m5gn=n3rHFiq`FJ1sYO)_C1uxo%;GfI$U>8B0X6G7 z0*wL*y2r}WrqFQ0Ff4ThnCaUG=<kGuL-BL5&%CnUk)QZi$H&;m=$VCgKhCS3|LM`t zkfMHm4hhAAR6I!fq2#03f;uQ^4zj$>Vl_pWMs?>0WO;{3D<W#1-8HYI9RTJ@h7_bz zyZhSwc46Rh{~ivJY!+XTNv&3w4W04Aubcc}p`xR{bH<)rP%U6-1G|ALOJK~-#pXZK z+A|Rin^Ue`U{o>`V6IW{hQ4{E1qLV71(0tNj&WORtc&M3JlJ=KQTVAi5&=KtrxXq= zG)Zz@%j_A#ngd<?n9q_Sm}Ej_C`gSBP!UFcAN14N71PvyK#}(|f&&nKR|{Z<;=F>a zkyTxeZ(-4u_O+LpH`iX@{S(efRiB@~Q{mZ-HkPiUv0&JKfoBQgg2tq*(5+LfL&=@I zx*u79sFOjuXQ%Z5a^X|;;_%+IjQ-~;L;TRYaSZSsVgCyUSbGFSkbD}JmNP{Sc)|fl zt}MtZJLF6$XWw3$rh*cH@RYm`OFLRf5_)kT+*0iw#q?b#+1Zn_PTNMaJ2}{_4Zxa% zBZrqnx}i0P#Xg-7wNU*!3D2!3>bUyZv_dI*yTU-yYdB7V$P5G)*KD;Sa60zNXfdm# z6w9KcZv0AbZPlO?Lf>y$BwQdc+2kU(G(k#BU{b+1kYPIwXmBE0niSN8z@n76_#n?~ z9c&xQh~kv2x6LNf=_UL=;Lgq9m*j{bJK_2_)~!~*AE{m(=rynprHC*lv#E?%+CK67 zICvir2P`P&wl!K?@u=5MYqi!!<f=z^Nl%vbe|=-^1#2QdGpc1sX(*&jAiAGQuG1AI zL=i&U?J;%>S_yW=Z{NgU9y3<uT<2B@TeHBpsk$v+Y936hIJp^7xv9l_DSuNZB(ss| z-6$N)l5b#cFfQ@X(YhNAbi&r4)unyfnA%G-MA|L(VB$reE69=yQWPKi6sG=Jsz=`g z3G0?v`jd^+r=0QxD2<+^=nn&?Wx@=&Gi9Zdr$Nl!RbEaco%J~wQ8GTkkf%iD@LPhw z;m0|b7jt>sW&U-zr~tnDoL9<ih4yYergZX3K1f=f7+kG3tN%2DTJO&e5=Pk>7`ddS zl0d|ik|BiAhFQ=--pY;+_H>kKlXlz-Ly}%dN~&C4T2FApNmx7vGcHAJ_-qUMZC_fY z(c1-&U+UxU#G&h}QbN+%Y#H+|X*@;`SdV(=4DQKV=v`_yU}$3e<<abQm61+nEsYEr z{tp%XhZ=ZwgKZt!3BXmjP`UqHqNw2{6@feChEIQ=s7wyu9H<f5*|{hk(ubX-qpPBT zw>DMq`3{N310C+8LSmKKj6zEcPZyKr<r2^MJ)@;K?;M3UK<dnBlFOow2%F9d_z{7X zN3pZ~iez*tD<99Hx>ad^!I-q}(}a*awrPY_Wc<-vw>i09zDHtdPmyL$(AG{)b|SBI z6;^+hj@HP~A#?%F(Z<_ZQhi^}Aih7reH^s(?7@jCg+)(}R+oEjE;9daCz!sF7JRz; zi=_weB9I}JoVq9*@Evhd^<T>t^X1l8OYV|{iy7LoIrRzJhgU__d%yoiE`@VH2${8u zFDlBJSo!TY5m+Vh)JECskUqGZ%l>F7QsCGhPAuWVm+SCA@QSE5Yenf`(`R*}o;-qf z>aBcPrH5(s^V>hE`5$aJ3!}Lv>DLg8n|{0DR-w_>-=8&>!DqucVo&!KF#qvo_7Jrm zroK!+HniuOjB6k_iuX;i3Nq_aO1&~oB%7~nIZC1U(MssnweM~wD9BKRsk`?KfhN2+ zFtWj!&1Nu0tY_j?06)G1&d3;$+D1yeC1^3`XsG?fO>^&VjhFR9@+wHB?j9$xB?hug zj@LrQ>2SUhp}$$ywcMU+W!9rMykuGeN=1;`4{#?b3V8trAx+|DPuSB^>gX0Q;^R6< zmw$mPPoObc^tX+E%6~mimANzAJ@(mdk3QVfY7wE%Kg+Om+W9&$&<Nn2&dp?Hy2F%G z&3^cr&1mzHL~N7M=({MrV-!w!AWulWI4|#l_Jal}y=iCWfqI*R(X3hhwB?%>>u<lo zD!0qLv6eG&LkE0~kWFI`;>9HPbI0Q3JuSzRt_(gMJ}$<A46kCc$1@F|v1SFZU|ATv z12+wlQNo(IS;(+(Im(=z=OmUkm5~qgtBFSxt{s}hR-`o5(X_Tle_l1%;wgP>gAX5B z<+7{+^7-Go>5{tknODnQ>Z=(Lwc4^u#g=hpF5c9?O!K2t3#gdM?cU{`WBO{J!4qI; zn!(yI638bOKVyuOfn_(DB9$7l1Z$!c82?bjiOlenNHSa36r-a)#H9(kjb?D7tXpT( zZS=HjGXaN^+(6R6@9);LT;4oQ4VdGwx)7`iu(R#Rh;LB2Ikzky3v3PQd@PL9p-_8O zU#w1j=-?=CZD7|VO7i~X%P)j}FwVBSlZ#DpzL1oJ`&V^>@7Mbt|83aa%yZbVb$sf3 zE*>^KMvw3C`JQ~g{7F|wZ@sCB+6i?-``(YFtdLVf*@Cu4k7K?jKCz?Qo*X>f=NWy+ zSsmNoE$P<|C$>!^Yr*Eu&IhOr4;<&c^0AFAlD#?lX9Rjp+j%apml+Hx{=E@#A}Hoe zeJcUsx%c<B(e<?HIj=@7I3PnSBjKfXLZ|MG<>7_QJ(TUsXBj3Y{9beNPW(k1?=d1) zTwUJpqF<Bg8Tf1o<btJ3=vec97#a_fDx{~<4_+Sx{Po?cmd3ekRf?#c{?|}(`z^YQ zGi@MC#EWUwmQz#dv(lmydHz+H4EJF7vAmb4>&R8zSseF`7kSh4<whaWbA?mCOsOxr zK!>38qk?9<kEqB*3T_Ac2>+YjgI(^?6G6S#Hcg*IlTKut(`V9&L^b#W@#(7FCNjnE z3#8+s9{W)3KMnV@Ay2vtor!+cUSkf+jq4MW&FHW4!{%pv%SvA=V4uz>DV7e?l(ev= zy(j-?&d=z1aM-S8ln(t++v`V@%k2&sCP%C%Oyv>$(yC7aLLPk;eaXxJ{V89^Dj#Qz z$4^FZR<mYerub_>F3;rJdix^^@7jKwEipMrS@plh)rJoC1%po#S5xb`3Gt6^BYyR- z-dN?7{S8*g(pPH>AK6G@DWLNuk$+>^7192%?*`fJ^Jl@bHoNPS%gXbT#KErEMf*vU zm-`Y4Hu6M_E_<|Kda=L1T~}*Qf?KL=%EyX?lB``0c%CTUfo#kPVvBw8bfS_X9VUAD zQ!bzN%VxwD3+V(~RbB7kS|V;zl<^}8pJ4)j9ua=~{DeNtiV)c38(d2UcX@tf-TWtT zTBgk^osf@?&LON7NtZbrZSt-QzPZrlYvxO9b`kEnaqqjW`Co5tAB~3}znMX62HrR2 z>Uqt%wP%Q?evC;W#(ktnx=uTI$-=d3%!-c5#|MPDAoUXt#a_2MikP-vfVx&?74>G_ z-7aIQhg5Nvl35KdC7<-<jVSHz2$*q~Pn!n=fRCtevSlmYe7?yO9Bi_iPqV*ncyvC; zeneAO+JC7Q6Ev}RX~5$C$FEt)u6g3&=dU;F90U)gY~;s|!O?4^_wX8fbFZ0;EKzi4 zGwOT`_OJ4N8n$=+kHXu9{+^Mgb7+)7Zs)3e01fCWEc(GUDg~ohZo$Jwhz3R!*%;EN z#A%XLXcGR;IP@T~s8g|W0#j#XPir=8&J~q7pu;&UmSva?+aVGDEpIs)SEXs6{Zu{; z8sfQ^=^oI76B%}xEqXx%i9XYqE5{@Wl>|UBiAyNjwIaTDv{M}N95DFino2=L{&JMJ z>wWrX6$o6L#CE47{FoD@S|9Du>kml|sR2g}2rSPPVf?G%I3!>ittg5to_+rGFFHn& zPY9B%3_(bG5GPZMRdzRWjH;0rNHp#@KJ!o`l&X?H#!TZ0p-|RFP3guEhg85B!e5b` zvqObCp$0xc?0pSh6-Eb1g5gYPr(RfFIV6@0;I2s#Uqj462Y#%X739UzAxz}pSOM4> zaJDSq6HXHm0&6uil`5hD7-D$oT>$xdwj8rbg9%PfvtJ_)sX-fQqGMYsXH~Le&WMxG z(-NWJlrykX1My#Da>fo~D=2j;A-&{Rv8sr4i$M*z1sdRw)J;Z*K+w8J$e1{xi6O3D zsf;K<T2wM`3ILplLpvCt!@H*j{|W(-NX=`ott?-74cGtxijka}UK#;bqz?z>*kOA` zK(ypuOmo=b*f?|^IgGe$CVh!G2#fH>Gu8T+5@{uaqb<;eyoPz1Bqau@pfhlyWM}CS z7_Nx+aX>e^=szWE2w_TnuvEyw1-7mu&H%iw?0(7b&GiS%Xzn?5<55u8!tQ896H|jW z=LCfq2!!~9E9v^QRE9BO9Ek?gQIegjN9e@6?xz9R$pE|}nEmu2MXcnMS{x_|indtM zG8h3m7C`pKN#J1$SZ0BTTtYmS6}CZ*5d(s3E)5`0aFD~Bby4(#7O?3Vux6%cITGbF z-8V8QmJzoQFoNU(f$dmd;JwiC{@~D>RM}v3474B`1CBnLO~M$?4w6_J_W41GJkI5H zMQPl;RK22l9)Hl{yFq*7vA_p{=$9R6S1fR~RA-zFTL(ZpU{Oheq~jyR=u@x*4!uQ^ zvBUa;j|>TG0f$a=rIw;|RFP_mVzCxo(YvVOTCHz9(4JDx(R%u_4lZeeyGNSBOXr-p z!9iyTm+7gbqlvnQ*&8}&w<B;(0VYL~bgXCLuBM`=mr8j`06WCIOyEP=#u7L<wgv1C z0Yry^TUXO%g;^D(`{P*id3x!r1Z8Sz7t@(ow3m=JycjqX>DY}*1k4Q?)5I^Kk~C-G zJK+Cz^DSG!3`O8X!Hn8zlgH(lSR4v|jeuRFLp(-7WKfnz2$Q90ypBrQK;zo`;d>1h z@pYVYctKJf<EC3+X;L?FkORWMoA1ALk{}4N#u-XVR#hG;`R@Z7ZqS@EU1TD|7f>@x zH`yFhgA!1rhz&!J1iXz?eCcF?xO<1kbd>;-WUHr|id(PrqL~$>i+O)mq@5s*+WX9k z5FyZ)TeV<sNz^K7M=B=$LmSu=Kopxf)b=ws#zR{Uknde#=oCyGe@#6(AY4A1D_*vA z(Zb6@H(Y4Qn;>hIRD;yj920880H9!+Xj^j^^ww{5$SHcu)3{EOH1UY&b^^6h{$h7+ z8E%1aszK+7*6)(vNx%u+Yruy$>t%7gF`N7q(n3Hd)}<R!iZK-6h3=zXVl4=95Z(g) z+(bH}1+49lghRjuYD42Vu!F&5VvTj`&RzWwMU_s!ZyOTuSW1I};}wyxIB+CyySywd zFtgB|7vjN7lEdPhRyraPRIm}X5zSrV<AMN4uHISct6im~T<71D>P8BJZA~!IOeSHP z;5%rbA`zIiNRg`(Yz#rdq3BouG_3~gUX#k}nuTgZ{UBs`(aKV3(1RLb723xbn2bl4 zt*w?5X=uXuHaANh%q`dHoll72$wX00_Hv>aOiLxabP>KpJl?6?&X(#o@IF;gE&2?s z*pdc^8u{6-#E5}oq>6r@sFBrer`2#?jV=Q6CId4d5ofG5{jRBa&P6#usdn~@QbE#m zwoyNxS05%(NdqX;rK$JXFIGf0xNX4^f+Yy1w=(3(PFS=o2=*l#Q+L*tw51AnrKn;N z`c1<a;UH5t%)Z(P)+kL2gP@V6h`_MfRneiUBgO#0Mks`)G21fi2pu&5dekson~8~c z0B4<oL$PLim8&!zX$k=5MJ4w>l|h|Kx3AIa8|gBu1v}%NhFWB34-fMcF-VNX9UIY} z*427woH#}j6`)8ShS|DxMVo#kb}#^Y`Wk1<6>;nmTQhId=|H46pK*DhWg4Uow|K(h zB&;J}|Md50{`+`4yn)xPhW8j8B)Ax|q@PHZoY;ca#n&KT_<%*!hqfHi#?!=!5K+L4 zF;a0gQn9_J+ub$5!odcZ=#P#sZCb_ggjyi-I@j%$cO^-b4d4p47CS#%?NLJ`j*mqh zWqW0`%kF^1rq>&Zipyg>xna{p8V(CX#-HHH(@_8ye^HEeC%C1<@={pQKLH(c$0>z? z^25M)N1949ayl5j9lt^8m2ZdZP^#0~j)Z)BYCjOC?j}nVo`PQJ>-X7vw<_!>A-BTP zWdnCWc%Oa2*Mt8HpN(`t4ZO50YZM7k6$!RL8{<$>XK#Y)WwsLR0y#hCU8D6KmO|CZ zKSym_{!UxicVSDBMxD9baJGg=%-EHa0PqzaOG0XVnZz0pR7#(00ZXm1tw5^C&`J$D zXaJRTL_AIJj*v78<^+3(5s#fR*4>3gBPkwiB(WF|wia|~la1*slGRz2z-tb^*=mnX zv$QjLB!u7kZ@Y-)y~5=d{K(KMtA<`EGO6YhG6!O-LzHq>636t_=A~u)bYJ3;sV5N{ z^mF%ek4>B_*JK0{UGu5H3`6V-4vixWgj%_qX~tidEXWpIT5{X+v<UIkt$!CoKn3}f zIo}J)2)0={Tk_I@Dn?Se9kB>8wNr}h$G8r#s+?cj{<|uAl-mwC!ouXjd5rlR*h$j1 zPzsl7eH4ZTt1>~HPbNySB;oiLG)xj1J8e`dd0L_Qs>8Zf0JwlomL`KyzVYs_Ch?IJ zdTm+$xdKB%aqF0Jy;G`L2KNVPU!za;9t_QX%eemj7D{DuZLxzq9M6F?e=z@AHL%b` zENlUeOz=%(GIJ&eUEC70g^-txxrnW}B<GJnE{n@G->=yb&5R#&J4$C@`{d2CK$}Fw z3XpG)(*`JLu1?aOi^3{*&^}mVWap=}ny?@<;=4D&tf3HieX{PW8&(KrYvPVbIaRW4 zX#ImOIV+;xluD2ImIf6}Ne(e3ZM8pg{AX4o#S3QXx0HAnK6>n^RGJ1?+`Y9z8>gWn zFp;BWB+3G4i-q$EJa#$UV)fi(GVK>yA^J3~^n!`($JFo{5(DY%L~~h8(L7JzZ4mkI z9=$5Rom$Qp#XyavvHY5zA3VFG;UoQ8`oaIrllW1B|K0ZaV}brPHguhBBfPq+!k^zH zpU|73$HYj+Ztltw{ip9F54Z_PMy5R4Lqn~iG5ag3dT6E!_7Ztkr~5KW!W=Yvr?6_$ zt4@Z$W5Eoi(+)mf*B}jlP-0l_s!{L6lD_Zvua%~dXhB#I2F#P&x{`_6=m5JMA<g}X z;YVnT6aR{CuNE60v<2@+R~)KnDAio%V(EUM1u)eAQ^G@vrMFSx(8Ej)T96|+;@XWl zGyX)W-4#Dv{umWru`%F|3>SiBOiRloJ-y66$uFfQ)>uNiI3W4_kzp3-2&QsxRI~&0 z=kPc)RH>JdB*i{M$A(}A9E);uKxwrgL+1OMeqE#rk|tunvg`1FWk)Dow9&Oih?;kT zHX&RQHh*w(R)tik0Y5nM<B#>;s<_fL8l7oD+hf>-(;rO5CiF9q2OCJHkZ=kALHj!Z zgP1Opa75bIpa$QpbtH<&Jr~Z2Qd&aQkVlVdzp?-kMU9-m9d>^gxz=btL_kfN7dpTH zVg<bx0NNcyVTi2dGG0myq~lP-!~b&Z$0I61t59@|1DfU5%QD`@e;PDhkto)BS%z=t z%N)T}(B}Q}et}FW!NAit$iJEQ+>9>oIELlckS9k>Tj~C)m={mipaNIUJ0^SR=ei}Q z5>x!DFPY1|o4Tdc&Jqmgp3Gp7@S1PQ+k2g~(?^7j%Ju*Rub=$ezY`_{;_-yt9|U{Y z2LQ+7zk&Bg+>@ifO2%C3KPl62I6Ap%XSC*DZ8EFY&MrIWPzk?k1Jwv%58lLnUu%7+ z9m2YrbbgfA{v~s!O3mixT=e-`jYSyFp$9%0NdM_o(=8#TXq@Ek>t?faF}_&_dH6oN zaFOuuW6hY8Be6QVw|5vOe9jC>vnl&fjzv*#JLCMKd=MKCEbB&swGS}mW`=*;`A|Wx zdUy64@D3t9l!#wRF|yBfRf@l;Q3iv%s`}gr`aBWFH+74tufDnt*-=&f{64%`Z@ySw z`UP+{j9<fbeSDq-D?5++K3r#BeY?HBN=|v&w{I@?V9A<R?KAyBg~cQQHtW`2sy*wO z=2^<+(bkg6C^YE-q;xsSgXBfB>GGiE-gW$>Qaz(%e5?H_nTW$${jna^oiAv0(UDy5 zGFR?$S}HSukNYvNzQp>^x5j^?ify%U{y!IGd)DerO$$5`&c#*#`rH#}?(D3pm!~je zwU1$q4doAt6-(|9xUO01OC-XmSo_yxaw?<5k8@P621c6|wugaJJXd(k>RX+#6l;pK zw$ibUG-fX+oKUSSkW%e-?I&vmFU<-@^?)2%hAofYThst5Mf+%#U0YHq5sm6K$z9ER z^48Q7&Xq@AC0H*CY@9uPton7>fm!2<H`2`PU$)RH1~<K$Df@{|ry{ZL;(1QwVPS!p z#6(ShaMEb+d+~~cx7Oxjfj8sX8b2HltOF2!7kV#$_Kow?zgpWj(|Jq5OD8{AVMXee z&`8rWL2K<2E}W!$!|48`w9Z(n_WPGEpYw@*mnz*Y(&`wh7YbiA*FrC?6fZA@@9TCE zb(76;|NKyhP^Cw%7KY`0b<zGiqJ66IM@f!b@fb%3P&_Pr$GJ*}=R2h;!rMfcso^|U z%{9~tTz@^`x-W~3{I*s=!g@uTA+OWTaA5Yx>xH-N=*26~cGYvx?_7;@LECwe*6!5v z$;V#s4B>|1{4(>1l8=P}PeErCO3oBI7aE3^+UaJ%<w|+`!wzcGekQqIh}ww_`;gv} zSwOv(%{$sTS$72RK<{r6B1h|kHqo=9H^JUFPkLpleagQD3s_$g{e#_HLZzmE@jiIC z-%_|n-orYRLJMZ>c`~rFAw(UCd-eB6<n$}y#=?tPkxK+qu12B4lV#Wigq!=-Q$0Xd zAN_5b2;dZ=ulO!3>r0^-chT=D@dHj?$E)1<)pU}z&&WGpINqD12#0d5S;>PEec`yl zQreu3<wgmn#_r5=QW)xB52bWj@fPC}x92&nkT&+DWKjKZ$#eLrr)72<#%d=u+iz)+ z{<t2x4;W{(8`z`E{9UTLLs$ZN7slO|f#S&Vq`(~ti#+j8XYB>`H6Q7uC{~o)-AZN3 z5BlYJ`q)QNUQkOC1aSUH*6-WX%DLzeclT~XN8g-NfUJ0Z%pQ7*{_2@B{>7h1yKBeq zw8Ht`cS0$?V2U<@K=#&hPU%N7JLQC2U1}eKeJzeq6@W50Avn>&x1hwe30~N{%u1r~ zHA&)A87(n;bc08FYRKNcb5ASo&yHX<f4Q7cQ8IPBBw4cDXKYa-CJ4o{tmk(^FjT^~ zB2Xj*VRt9g%LtY!vpQ$HPfnPdpKernnG9B28qE|<&#Yn^)ic%%F9ZO-$NqK!hp*(5 zpJxH{eiSyJw#b>9a<5?r!k1S#m8d!Y?NbbJf*sYjs{8vXsQxMXXoJW2RiWoB64Hx# z(^uR{$Z@;LB_e6V9@4)=1(Hu3h@{m}6pc~THka27x)fH*ZVP(?QLy{RsiO-37r)lM zLcau2Zwl=wFD2qy0mPaog+>io49RJ_?sK7~CO02rqVuhJ1|Lfe;$)7RZXeU_K&unq zdd6eU7JZp`o2bh@jZ*+vc6aM_rd>ni<uv{nN+>DccD>G>N}4Ru!kMdA+pE#I?8(VF zn)6_IMQN`_|1~E1$;^uh&bRT@YL_K7aGUWk9s0C?aFsQqygi9JL0zd9sY>(K`uZGt zPPwoC<q>@?d@>ErvNy{j9c>})U|QStt^K$1rU#LnGieS2v+tfgi+<5;2o}B8S~9l< z1z(jCn~eBvXLL&fdTR7py?q6a8-Vottzfm4mTlk$H-NaD*5;NL;Kj)WFz$nB%$!rP zUe~i;)>!Lr*TQ%;$8~Q&PXI}FpFS{~NllARnjim1S}z}-B(EZA!cCJ?Nz^4!^*D_q zbh0p|#-C!#V_9$h1nuHK$sKdCQ;lab+0Po5X79o3nK@nLW?GRU6?%+gwlR7COq!M5 zd0H0N4rzymy=U1st^5=SHw8G59Y;ib&O9v18au?Eyl<yf60b7_Zt5RKeP>V^=6<4< z1?-cF0^jY9qho`|*-VNIre6^W7kbn)l@U|pls}gKtAxA_4;8m1+(D<dc#B*jiyS#_ zlutbiolaWN{E(gzhL5q_TWS*UM|Hc=lh$i1V$+ycqf}18`y3IE`_}7#l!;3`3`b}B zKgLK5aqJE3MYt)_p8l`X`Mk<oEohni(L;&vkK60nqn{u?u3hFtzm3lM@42=em4PN` zD%4HC`cR8P&H}L<b!)f1<B10wT-ICaTH9BDJttGddaG|++3R9t!o3PYt0e}7TGG@` zvfL%sk9@lBcZ8E`=^$ixy|7p>ueVxLEF}aG6zfjyyST4Eoq>j#N}kdDo$wn@{-!CV zd`rs2sL!3<Z2!s4dzwY~PN>>gfyJt%yt9!VDmbPo`TSLi2aLb;E+_}(rQmtkJOruO z@zckG-(RDz5iIy*82|0=%V=YJi^wNL^?Z-|V<$eUzY3dD)ix|!iHh30a=Uq69n6jk z@S@(G-k;v@d<Mv>XV2!G(72h%nUDFx@xBJlA)9v)Z+|d*cBXd{>h{a#mgmJ)GO^Tr z{NZ(<<4az|+{0ggTGQ~a>Fur{Vb!6n)Bu5I4vSpUaL6oGyo(oy2g3OKi>Kml_SJRY zUcK4{Lgx^15`SrT^|WY$i(LO6sO=#1d!PI$P;Vxpi94IUn*Pq83LUE;Ic$5<+LS}r zX`o-q*dH}<urL}jY&6(euCIy6xMq5L1)jmaDZ5*FyEM|^WmG}3RfLeNodJ8|A9tzg zn_i|$4v#BXWN#Yk6oE9QPpfTAa#fiSaoszryKX~7m9G-Eah{-X2ckQE>qpRtiYoeA zcY=xtU?OKY*#lH<Nn@_C^X{P!?;BUSPGwfKs@|+Fk3yn;6MR0(({Vt_BXg8qR2h<R z%61SC@a@<P>)>T^Z=UoOiRW2LV#Xc093u|5B9<v;)+RJO#*}nOT$nz^xK3#lI+Kik zXh}CMs(?wXjf3^l8Usw#IEzUiAzXZEDu3%JFoBGtfQlb$;HI?Yf|K$i?>Ezp9_^&$ zET>bGR;tc}ua|%dkl8DXImM-M79YZJo2vCbgyQu$?d6gR5-1wF`-)&Qm`+DFYk}RU zWMDpvRTayfMy@6~&RUVjY&-EhYC?Vu)>_E?>k9m$LHD=_rZ|jdJtZXe+hCwsI3p>& zaQ&!bfL071=OZtE?)d4kR^~<rmS1`DxrL#|h_-STEYUD6jc7z(a$H6dsQAl}X?E58 z29dVFj+a8>lpUD<8(lp~W`rG=n{+IwB%7;+0srlmQs%Hrv;mDRC#V>-HAEex^9^Df zP?FaKtj|0v<KD~%SKVH5o?fR&7LFTZI8^)*IsSy}k{i-xtZWr|%Jby8FULDJ={Jw9 z?C2_QMeEY15mBnueMLI)f>x$y2q(iSD??rVYY;9ACOw_XlQK@6zy2l56i^D3H~^|2 zAk@#azC|O3bPL3N-IUHoDNi+N)<*A`s1ekkb%v+4)_843itA-z4;>a-sL}Q<1f$&u zx-tE6Ihe0dnJKrS;<Z+L#jdW+8~luxtOHELf5)!KR)Kol(&|8G0(Klg#BFKpEBFb| z?Vl>Y)a2`kU<CoQc<aC101YlvH#lwf9Vvq8=XmtI3R}uKw93`td-i&+NgclOF51OW zkFO@{d<{*tN@2=pNR5VZr3pg*C7qHuUVcZ`4=)L*g(i7MQZxp}RiNObtEtSTnU9Ws ziiWrkyQ%+KZbf#R-hWj5>8dQ{mPIbk{a>x04M;$X>0W+zgDy7H7YRFZ@x}Do`gX%) z=SOAcv-B?YHJ}#9qmUVwwa6Qon$40Ab*cSADkpARV(c-k8cRe2!quXh)G2!ml+4!% zb4#4db~6Q-z@(#KNrrm(bC|~Em}L}+f)nVYAi4Y*OyUUPtD9kn#HjGX@X||2i@5wK zdap%;*7yWi?Ha-x4g;KdjfvUD==y2xkiEnplI#5AzE1`2rtm=_4pv<6*HT$-5Ot5i zTf=vj4g~XBrJ^9VDnzj3AAN_fOU{am8uT8VeImH#t&}L(7!Vj~nY%Ec<JnrE!8<8_ zJ<3MPX;@>eI1M{~Oq)UvQhY~VpvklSq9}hbJ;|TKgb5*2IDVP7qaWz1QIo2pz47QR zh<^<issn!91?wwB+Iv+lL)WA$fNBXI-ZyWQr#F;5Qk4y+961}G{i3P|C3Atsl!IaP zE3jVbdT%T^`g5h0=&X-Nx#X)+UfH$}7Q2BICTa#BD1SM9ULV81Pe3pv1{VJUcbo-U zTNqmfZ+{)GKYaOCBWkSm&@xVb4&SMzGVsQ3MBn!;<1JQ4-vK8&uXS2!STkljT?pf= zLFB%)iemt&sRo(aIG1OaOEHa?(u<){tIBKR>V;o^Qr}@+3pF5OYS1<1OCWc8qlQN_ z<{GhBOc5MUbl+0TWLQUXb}ot3=z9pbnHV760rNFODJ;P_9a5G15Zl7glsK3gxrwdj zqJf*AO4vB`8mQEA@W!hB<=gkMeP(K`JcrVZIartytD_ReWiXpv<rOJ$T4u^D(7#VF zz+@dIx2qk6NNYXPhyoI5!4yloOlm^9E#{(XfPy++_{2l@XQN2T%P~c0apIEo^oI#W z5U+ITcjc@AWt;rrcYLFSkB6mK`bLqcNto~q;(X+5WZ5_3-pmy?Wbz<HEoxk4WbM8Z zI-8%y`Zq#Cm7s^5D^A$T7?PoE0i@4DY;&)uOw)`kBi_8)9RD+3$3RYFBtEoT(-K;W z1&y#CjAiE;|2n1(cK|M=bZPF)E$2^kb@QBRR;DH%farAqgtI|T<Jum!c3PFn*aH5F z<<K&l-jx8wbDg-jPQgHN(3Z6pz|3!kqUA-UwLz=l4Z`IYLOZb`5{XfTbiR`%KJHtO zQk{c+TWLNG9U5WarAC8hSD?@d6U*<3eL%dJaOsY))YB2zOY#)uqfT?|JnS-483Vfn zq*D^}1brJ#Qal4b;P4Ek1=3>)(<STn1Wi~srOcR_Dwkn`HK6zwIq3atiy}J<J~q&J zF#pa4J(hDAtvnwPr~M#3flOw3OkH$ZNWZ5gVaJW@hnWq?g^tW?Q~E?rw-F_w7$z*3 z4C}$R8-APm^=JI4;$h1_a-78v^(DUG#$I^xj|Wh5v9k%Q(RZpH#h>!WX};~m{C0ZJ zi7^=+mt8DR$*&fr>|J-j4KIm@*^vbYI8^T@D+9KHu$^COham6zj6Og9W9yu4YSj-8 zAt$s~q7yc4Fet}_W-^hI<=C9#0$!SZoHcITAK4p9oE*5-i~W2?(Zs!oGg5=XB+g(u zm2aL>S1zxEDK~(FG)R}b-YOQRkp&bzMMSODbL0i^oq}RUgi7_0sW$pbHskbjE}J7L ztBy{wmQft}tjj^RhNd<r*#CRekH%Y=&~HTj&Y7O#ipGu>|55m}TAiy8EbNyvwd{s! zSYx#Wese*Q&47NBX$(j3evkG<Pz^|FXZOn`Z-*$Bb3RqhB7)BvL{YM;WO`;E=+@b? z-ereU^-oop3^acTEfBl6XybG(kCO4w)<~vM=3qFx0G{jQt7g529To{1cdldS7*==0 zWlAh;X5@H*s+#W?ug>ul8GLFk2&n@Q^s7Wguw)9Po*4qGF9XleG3`(gD2yO9$OZKR zJWXyuu*W|FUw<Nbhj^9vZsKrHgHubUd;E67DP;`y=tx8jC+2?l0kP5VI5R3Uao(*) zWa~d3_(6|$d(|<{U$$dZo|R9+JS|I)U3H+|Rj%;!p}X6de*D_F)QHaKUw1q(No8Zb zcmF{0OaYpdyaTGH7inZOI3tNu1g<bEbSYAam&nWXo!MC~U9NNVfPKlRbg)vMDen}i zuD9#!895q|+DN3)D}=<pp_-s)FJHJ0IVp<x!_HW*b&VY-Ybui7Q}LyN!u2>5YBF^$ z9c;?4=E7wx>V}v0x<}QebhXsY3I%>g^+T8!G=jI4CxW%I{0V*&09#q7yAaiiSVamQ zGYYt#;Tozo!_&MGyP_~09+&F0@U&w5?glY#=*?b5Jj24=(;4RcT_Mr!kq6DzI*ZZo z<Gvff9u>PHRGayJjalVoIy39EQi=CN$<%y+q7&mAiOQQ;WfchN?^Z1_99xs~`%e?F z09hc-0eCXwAlev|8rY&uuhZl6;-j2w0;jZ0OUm6L+QPcsx{n)wHx9J`?(mD(a-G6| z_F%v2CC&~__Wa%1`qS>xCpZ1u*hWRyCH7a-wEXl7_0hMV7ve8x(|}?SWfBiH3-9|& z6z3=yUO+U}cjk0wY$`gkfl?Stxdk6u($Ur-Gv%!Exq-<ij}5*mIDUt;s-7ZAljnB` z*TKGh$SGsuBc=n2Eg1u9++8{AnGPLR!G;rpy1_f!y}+SwqZ{cTUjP+U2^5xmRGic5 zI}wT|(W{GS4MpYzo|d12zshAFU)mIK+yvzX{mKV81~vp^BXkulc!s~=g4Ynh-~Ht! zN8HKcCi6rc5Rw#?^{UO8UOFZ<pRd&)qPwSw%xkm*-6fQ#qLr7%6epIQuYk%PB=BI` z7neW{Rv)FpCoP&8E)X#de-h<@Gi4L>I`IQMbSjm8jH`RRN?6+A_T2U_@SOr$b%O%m ze6h6l)gjbkR~0uUzZAZwXa3$m_}%@9n2CIeft3F`AHuW9Uby_2;+c8yiGC}8uH*RB zcvvSk(?kF0FXJpiS(8mAs+%=T)P$}bl4PdRM`_o(%sPv30kkU<52ym~83RC4(fFex z=UC|OD1hvqeAG46ODCP;aAq9UStaAWLl{<ZP3`r<?MT@!;b`&G7@Q0*CQCx|c^tWa z@>m9J#-bWWwm%7L?R4vnyt*!OzNhIq51{X{-M>G7&n(xd)h>HF$Mvpnin4J2?>pNH z+Ts1eUAvU@Wz4tP8J0Qm<mYLN9m0I?-&W@UPTsNeisWq9YM)H>*OM-CD8#_<Wvz&k zzOD(R+UBEuyB{3Sqc6JkevwOgYGd)Y0rg+*zk8i%%w=zyVe9tNHRvQw1(&~F2Y9!W z7}_$Es}XUDSsiE2Hj@n^OBd*Huyjq<LlWZL^b>Zq-~_nVr_YYw<g-Mc^oZPt);_or zC0QAo7JuB4xJB5(`||cvZzQKuC<iluW$(N5lUlf>Gnh4O<%JJxB8|^mj*62!;zD>E z36>qWSs&PDyg~x5_(sf&)dYSypJJ55aoulDx7b6m%LO_f3!)5U!a9@I{6$4+I0Bp5 zg<DeQ*nYjM(+5XShc{2>8qkJSh99NyVw2v42f;oO(}m5zZ}NPrVvcI@hE>#$kp2@% zl)?fPA!C-SCNss(`%H1TQM0)u@*91&c;$2N`Ql(7gYoIG^0(DTgivgy|2y0p=I0=~ zLM6D9vL8j<Y(RP+%h%;Dc5P-Q)S4c{Xva&%MVmJ6LUE_Cim14YX1VqnGC-wUj<5iC zj?ZCp^@EY))^}GJ*DrNh@`L_dNk^?sRWAR8+SsdwX(*b$9PA1t2h9tCS*kN!i`p`v zfAyyB&Af=IL{YXuM8a?5>x+}-3z`K&Lgo*$69>Xcj0xRI0r_g%LMG0g19f^;{kUxZ z-Z<RvW(MAqJhHiP*Pz(eq|fo_a!o9RCtVWRdcPvJn~$+C8Yhci(u@-|r4q{F$>&K9 zCtNbzFWo-Osth}N%+ntp722S#^6+WKz}p6%29Ai{py%wSklz9oMoDgwt4SSPyd{7? zznhzlzWp;R2ph1Rl5PLyTIjnt|L;qM4@Q})tLke8Jxf?(sJ~*=T{8IKipHp0&^xPD zpcyjMDp2mQLI7ro|KsS`TD@O;e>Cc*^?utx=OEcfu5Bf0@A7-_|2W*SHTTQEFfo@_ zne15DM2)aZIaHL1tjuz7Z8(yNyiAHIE)%E&e)U|eD7ZfluhANVx*ydx6$?<d-WL%) zr*jq9TWh^vtW?a&%Nnufc}GTlgMV6iwa9b!g}nYTLi~868~-`ts=}>>BPV6*(aA2@ zbPbl=x%@VU@GRFHs?9<W{8l+iTHbVim*YJYsxh{UHe2%M{6y<&0=<ht$cb14Ei3O^ ztmF|bk86E!+&Vq!p>hz_VG~hZT`Wz_jvC=+sR0_9UM^=RCG1<*rkhY5*HTw_cq5}n zGgO{=k*HqROHQutu5Is91-7IxUoOqSFo-Tq%~bXS%#`=DfhxEvH^4K1#%|0q7Y5p6 z`vjQ7JAG!1vFKq>Qv|6@Nad#dej|Ygkjo+a^5a1s?3WN7uAAMQ*m=neiiR2f;w6mU zd@c21fO$`Mq<|xIjQPX@4bgb2x$ZE|9Em-osawX6{OY?<KEt3`+oVSRLQHKEynGk< z`&pE9fa0_^1(!Er<h6OIoOfsA;>ej1lT=XD)isyKU<!q;F0slMMjuc|qnsfcc<(3~ z{9O+x1WLnjlnm&p)~%C8`XD0IkLem!5d(2%;yUk!KkJiU=5T-GqO}R8G1%IrNE+ax z{U<pOD~)>0WwUQ^bD5_?ZcV0e<6Wx)^Wr2NRcmL$)OXg8sSHb5(op*dECIZUcd3gz z413kDT9+Y{|K;idgjuyJ%|d4T7EwDh%&8DP*(x8QY`C7O+D9TT9eT>>LRigCAKm){ zDEX~vFxzf7iZ#cw731F`EA&|R+)9@+1do*~I&DW^9}%#^hXdF?v9`eYZ8$>6=QtLu zb5*la(&3st4$4DZv0X1lhWT64V+RoGDDK?wBM>`!;!t6*C<_n;jC`1l(a=NzW3%=- zu9?5+_g&<wsn)ThNE~1TdHH@w-)AZ=Q}P3QWD;UJ0tT`=MbAcYWm@E1^aRF$n_6P` z4*tH!^_zK7niRSjB*v(jKswqBDt}pPmfa(>7WJODKF^5FOKJ4|HZ2wH)WCdNML*1# zm_C+5Fd+oVC^>_Awg(+r!TDMkCVOl3j>96w@!tVz)1FUy<-+75l2IXgn{P}8Gt_IQ ziIo(MSr<a*ZE-tO>cY!;jiSEzXCEOW1~<!YWKZs=Y#DXRUxFxs+53@O`TG8Dq6G`5 zacqLWYl-`hwoQb4*|8%qwO3Ma_KkeRu4+(};>5h1<vt<<aR?2U+1@J7bCPV54%H|c zmM@`Tc}+cWsu$o~8LvhG+6E)5M7<ndmOZwXqNy9sRA-Z3@_tILY`GjR$Sn;oyM*J; zL=G1?sN4Q+1W-EsEv%x3xJIn4U&8iJ4~0f|GvBVq8`kURf^fmJsp}$ssg;c?cpRMZ z>ZlC%XE)d7nyc&kiPW46QO+ZSE)LcJcb~WcF?fwvgn3utrN{1zwa>*aQMWy+r#C`E zlZYw391;uJd^z9DXIyId(cmoRRRMo%kblr`M%KVuhJ{~U(7U0$H*Z5a;y8OmM8`7B zPDZo2AQ`#p^&Ws0DJ1<1-S^WA)J{>TJ;Xt~ULZs><n_1u4AyL@H=IP0#k28e4I}ar zTBMxe98MEHFVN>i?-FWC*&3~1_QL<%y7`yP!y*JzBqVw5cG-h!kOz6$GTqQYozwNF zeyq;)e*k<ygTIPNqE#Vonfk+X=Ggq`Ar#P|n<dPlj|z89ztFHtiBl8%XGHwZlBgNn zHJhS4&O!ykv;*6lZpc>f0ErciQ)9gotdH(pkGiAGT>dc15V#T2kF*9W{ul>4)W8gR zgri03afdhR;f7lDh8}CoEdS6Lf(J{y8pW$(mul#Qr;1>87jihYlj}#1)hvP#E6H2e z(>@w@SmV|!;*NLxkc*-Yb85w`ha7eh9hyvMOwQ64amLAxssV~OYNDBF5$6w3paXQp zHr$UHk_?^k7=Y-g#C9rI?^R_R{T!2fRj^beenefgzoYzXW803sUxkqM$OInjwUeZP zg&dxM8tQ>(XwOzSqaJEO4dkJ?*a04BLd)u*NCFNfrl=kM;St~<0J7-M1nwmuVJ}u` zwKOX%3QjG$%;L%<0JMP;D1jk7tW4A)92OyMg6^nXF91-(+iLHnZm$z;L{DZx4(ee! zOb*>h!!#BFX~u>e$p1==NGaq}kEo<C{;(uLCZreO;UY{z=&%I-CZc)xp&qWmZnS~x zUg94r0UcTb9KI07IEGz@t_xw%$JQ?*4(UN|=sJo6+;psA+MyrZz!(0(Ft8%h@b4Y? zfgNx_@Yd*WxWnMUVJC*|OyHsx-au-wj2_@%5(v>9oJM1c#W22s9-hD#+`*90u3Vl2 z9_j%JyrLCThd7+<GX8EJ*eBs&0z3NQ9lFXI*5OWy11qc{803IYR*8X#&QVgSJq{6( zrp*g=>@yTCtmuLGQp@>L&ug0M4xuOW;$hGTK^DA5sp1GFHm_2!gZFYlP{5C%R;3;` z;TrnkA`H+f68|I}Kw%-w2|(n*Lpq}T_R6UCsZ-i%1^)pmJYuKPjx;{U7oH$9{9%Bs zB9D*&8puYV+`%83!D7fPB{GR$)<GP4128;~5Y;0dq^1_&;E433Q1l8S{-_~Zg6%#f zBK`q+p1?Sm%SZO)AB<uafU1GYL_>ncAFi=CnrhIjVSj9p2S4LJtmGevX3r+(Pw3&$ z?#ro+Vh+M%7OYAl&*~_`p&0Wl7$<@_3<Nu5Ww7J{9KOLHWd(Hli~H82g#yGwWTpHx zhU-K}+S0EsQH|Ja1{=mf8e-w;P=XrIPyJ|yI8f`1K*|tLt&P~FGq&Oo_JAJ5;S)*n zAL=dun*R(P&jeoBp^Lad0RI6jv_g^!L6Kz04bklp=>Z9z;UCKEIi$_U2Ii3#A}QOE zW}L?FKCd0z!5x`~fhI<3h-Mtj&1stE`D&w9uBsDsgFArlDK~~D<X{#sLxZjn>GlvL zT!|i{;TUR3B^+*xux6}wfjgY6<{Fbv^n^sprk;YVG*_jCawZ}B5y+&bA<lym8!P>M zj6~{TY*?(}YEN6_1qpmB7}t+oSkn^ZP4BS88~z~>3;`ZE%Lvy){({68vSKaVp&P(R z9hk%pA)+FfBmt?Q%IYCEjjSgC6mCGGGgO9=zJW=`Zi&3nUbG<?3~g)x1`X>0Q__fC zxc|f-3@98{13R-5CK7^IrlWzZVfec9ET?q9)@gl$k>(ykXRM|=+C_xwhq0syMCHL% z#_$@X25;EM{CopTcETenLJR{S8FnHiauJtwP1i8TPg{l|ID!{;<^G}#A+W-r>H!zj zz#q2Z9TN2+N|Q;xVI8`Hqs+xl0>HU;EH>%1VYY$_25})Yvf%s$ELOBq$*e;q2@*1+ zY2<X%4nim30trqvK3i3!{4Q1jLlr$k)l4N(YG!4|A?EC*8MkA6Xi!Q?GXPR=Ou``= znu#2?bUZ^NsFsg1BVvqJB2#|RArb;Ru%;g7Koj^;;C{v^_`&-2!Asgji$XOfLjQ~% z&Y=<xD}`vqOwVB%>OsXml)C^^bq2K#Ip!!p$0H1uOGObgU6TWkb6kPZH1jAgxS=md z^dF{-d+e_R*W-J(A^?0L0GOmW3(g;S)HtW_@KnbrPWA~dgC8<$58uUDx2U+RXah}6 zPzTI7q-+Sv;|UwnDjsf}yyKX}=Gl@0zv!VlqhWoDV>^&k4j?73eDqmYabf~M^%^V} z<^UU_cDvRLA@W6b1gs&JgB_8JQPg%Ji#Evo0UNl@7{=iud}1<v1SKekTVi1!%Hd8W z1s33yx%ib{pD|Di^k%p3!4|SF<K}tf4@syY030TD(2{{rqQR)-U|xb9{Qs>-W{+W! z>m}%64<O+qX<{XrjCs(`y<Vb4<;54=z=*s-=nAlBO~Q~C;u{LXcvc7x9^qgnYEWU< zE$Sf{=3pGm(A36m(3Vkbo8up5gTW?fbkojw&&CgkVFjx*uA+2eo2T`PWng5m1#M$u zE5-RP2xY=l;Pw_M)Q}wdrZmA9IS)b`<l%;FlCeG~0Mdc8_VX#xk7XdEKVo4iJak~O zWh+*a9#nQQC8Bu%gI^MZIH>3!1W6uxXKcv@NYG;5=HW7AL@g2xTik1FC`dR^L=A9Z zINU*7+>vYE;Vhn@SuV-NkgGHBf*PdYk0v!(tpW-CK~(yoA2tW%2LBBl2%!^@PHOAJ zz^o%{f3#@>AQxb14XPm=c8oyT)!SABP+0;ilhz&y71Qcz92#s<KX$Nsjvnd;-THwa znr#QA6fiUCZ5J3Jf~y{ei+k)Pg1a%zn2T};aJj@m9v}*g4_7_f4w62r9^fDowgc?S zcy&0YEJn5s451nnPhwoGSipj_=!Gxlhh-lE;+CTBKniO|CuqW94uWBToN<8$Vmc12 zJ(hD8#=$zScYwuH25FF5C2WhaLQeg1jU9rWlsO!jxB;J$G#*DkTu(;*Nc1Wqwdi3V zXd!3dkCCTXVBCVn3RPfr>s;ueD-@Gv+$+s6m@x{MB{Yy9T>r|KB{;VP<uW8$k&4Wc zrv_d;#xM+_3Tgorolj!<?H3wI9L9_)ptIlzFtvWvH_ZbY9BpE(7fsZ`Q7+BYP|JX< zx1Yh;Hwldn+F?4_K^uVan}5`ggr-0oLO=rG80f$nkZG9@5Gl4}aGe+&Lz*g3f+X_H zB!I#g{7R&!crSfgx)hHdgh35JDlD!xGFmGTEWt|Pfu0_69ms)I*Ml7j*)TF=M<hyF z-M20jPlKo-3G|@W<i(huM=JsV4sd}-H|8%~3${2=tGYuQ#Bn0gQuZ26gGO%~=D<A{ z_o%BveEI=h=inIn0b4T(GWwyGig0IIq)bptR6vMCDF5dly6qw&I+Jih9@G$w7h)Vd zEAkRM?T(^dV3J%oDw1pAbc#f&OST?t0U|lmW~}6<<AyZE@C`D-O6uVko`4-%%D8UZ zA=n{O-NF!d02)xnJ_?c{fF#U*c&f#u7Sf_}Kci{>p<08XNnl%S=;3?^LTt3**1lmN z3Wc>BI^-H*3H%@$AlrV)rBJkC5hwwHWa8DxiXm1@(wd?k)KDElTdMbp9w~<*%7HE8 zd!Y7~2k(L#bbuZ(_5zhUCFJ23Zf7k}3lE69PbB-twqm%k#vhLRx;VwGm&jvmmm5lz zd#X7-6lqHEz+Y6<9*x$_tcMEg0y|`54c39bKL0fHjF=v74VhY^ABd3-fQ}s=Ov1I2 zG>$<9X5qe(5!}w>Y=Uwpa=3x6iU!L;QC53nhOUO3&c*;ah~ID@Z44?R1VHAlSw6DL zNfXHK(jl;+o<SnG{((wdFY{_-rQ-->(uEMaAx7$D9jH8Ruvt(f&Rk{T4LbI<pUp=U zB7-u#@uZS69I!*{K>!_4H_=u-rG#Hz&0g}`d9g+w2tgC#A%|W}MhC4P=%j1dhKWlJ z6q)-eiSF^T=9V(a4;kwp=max*0&o7I(X;`X;DT2oV^1ur9`plXEyX9{`%K6W9JXN} zBm&R#oLoHRr5h+<FD#GfVYoN5P+Yyw-2Z_a<bhr)cZ(@qr_9?od=j-T@nS?&0(<1d z;s%3fycq~7Hc$#ktVkq#Q-~?W9sYsFi&NicvQr+7JB8M%&Z?-ap&U@-Z5oUYW}zMO zs^ZDrtQ2K)z|E-kB2*f|vhE|SLPZlE55ds<9@}sqK!L;B@W;B^H5P(d7G!>*XtfyV zY*BuMR^mStb55txBQ50L!~uwnD>5j99v)I2jObB!E2>3@8b7Dt;$kI!ffqwB(y^H) zxB&^aVXJ=(kc31YENPId;x8N(4m#EiQB5`Kff*c4m7GyFx4N$U;MG277yQ5*wz!;? z9;Ukx+z>Bl0>Hpl18AOwPNKuZeE&Mc{Gk`5!6HJ0U;jLOtq>gEZy)KSA!sb=9sdnu zH~_-kU4lFX4+aDGfO{f78sXL?+JPH(#1h>=9h4h#Q7+NgbYvmYcAr2P<l!BpIPDjr zq5NTYuFF6uPsu97thm&l-NGHnfnz!N%|Q;EtAi3WA(eRclxqfWWCPcB<{#Ks48QRa zT|coGNI;NPzqYtt$N?byEz;EO-#>Zv<gE+9u%W|;4&}-7=MNh;c$d=gvq+KQx`hx! ziX7QcB0YNA0`v+{uiw9h;IR24NwcQSn>cfd?5K^NM}`zX>ZB=AV!L+g)KFXZ?wwGO zLm5g8;O*a=PcNzX`gb&H)c<(#B>JPrO--|Y)Rg{f>NTfCcI?*u8%NJjpnBiNg{#L* z4YvU0<i%?nK<GP$dmz;t=MgH+lL6F4TLX<A+^IL!S)&{dUcFfX{*enHuQB1%s8g$U z`0?XOcIv_n4A76=Kgn{Kg@b#tbX$qv>Ya;Kj~}=I^x_F!%^D=;Zvn1d^Ea+u09uR# z3}()~d&uPyv4Kk`FXM54&V8f4EU%qEUr+vVJ1p^E>!BYdzH=w<kR^7tsPPUr?s(T+ zV@8QX&mNDclZhJs%=Zp^2AUQ?I|?4MM?Le*<BuDe^y5uC%6YXML+!lN3=;Bu0}nif zL3AQ%@|>j3XMU7pjsHP6LB>u1gvinvJ#)+=nom5^SmBaP61JQ{)<h!*L;tXYV>sHl z^qX%d@ly{h`_u!DLQRfj9V+#7;}a-{$yDZ>s1+4JaMvV5Pd9QI1legt6}633nJhGu zM6EgI)<pjFL(T&9KoW>Q?!fita_u0;;6DNS^9@^YI;5Z>Z%{+c8<70N-%EVT!yBGg znHtVb5`nc&J&h3ZPdE!<CSz-R`ooMI){OJd8oSV_UZ=<=+nj5~{o_X?^{}H2jJpU` zPFo*=RgO0G$dZgY0e~|jveyQX-AdMlqmZu3wkwiYKJ~(kKjf^_=eRf#YOg%|)kDn_ z>>Q;pzOX99)c;}i7*a<C>Lkgofy))>Pa%i+Q_B<eNJy}E%XRoqCP4&|i8|iQBk5`d z`ul`D;<VEzNhd*B&l<<*Nl&4><|hx7?Z^=fJ<rS$&CYweYjl~*Wn0fNYt*w1J-PV7 z5IZMrOq9Xmr2~pa=lSz6oX5g+^w<#T8-PsvToQmbV}_loJ1&Fxk2sOWRj8pj>C8|) zzSPlAr9LI=jyt32P)}lbHKq5P>`1f?JN)oN&p7L_16G`>{y3mKaAe|-I48qQPnF>W z<3}{S-F)9eg~t4kHT7u1k{`K*({R;zldXGdd)_7+B{*)Q?mxJ<C8p%PobwMhavh!0 zCZRRtW&b_7@9wT#-PDtOaS3$?_di2$!w#p+K{nSv(MIp?k4X4JMLmPpW1YL@gyYjV zV+GD!mG02fOnl^^$4qQeC3;X|5!z4()%0f*`2~O-)_B$&<Y5iBS?_|XkzbXp5y3eG zAR0DH5~_w$j&jr^9kAF4Hq7QOex!pT=m13kUWgnFD(h}}GNDSKQIC3cM;!IY#2fJP zA{?Tob>SEXjH<UJxC~AnWy!=INaivN!U-%ADPibVBPq~b1%BDNiIl8?tHLm`A+58F zWM-j)S(M`-R<xlUb<(<eghLo~0T<2~GMYnSV}`NFMnAw&E~~*whQ^o%UH~)4qX~su z)BlLY*_4E>%8hS8|9Ap5$WgZgoo0_)OqQhnVTc7#Lmf@|TBqL9xHx{2Deh3&h1wCy zkXUIJbGX$WNrFRzs0kY7ScnfBNlg6g3pVQ*ojP{um9bz$IK3!NImETPc4hB6Gn5J( zi<zwaEG9bFkjFSwX_Mu^1w-|i#2eNjj(L#NNoVYo&gMamIt-v4n|jAP;RKg{wo)~P zY6>^X@rF$NV;-cbNy7-S2zubkZiaNoNg#ueelU=m7`=&WPBNIAVGb{Rfki*|A{2wQ zt0Mu}2P)8UoY4FOi>}P*D;vX;e_+BH>tI_%N0OfaG^HMzL?w(k7EiGG<{f-%M*o#w zRKmrrGIRdCTxu|L5)=OKAJCy>M0WPNaLgeXV;NXc83L9UorD}E3`|UA%FU$V@NRTm z2Sqp%3u)BDA_p1UN9tihX*`WI-DB&d9OFVz?Bh5BG^VHO;V5-{Lok@xsbCxP61cs? zYg%1jKby#od5FU*lla_W8p56uZtxg#cpULATF!NV<z(F(;bdp~6lSuHCd(-YIsBo$ zbJRl{c{QVCi7FRu80@WMoo!SwQ$mZXq#FI8%RURm!hTU>2<o8AMwP3Rox!C_7~H3c z3dN4Wv7;YUpvE}bv5?*%1RUW2$8F*<5Np_`cu~>WaJehT8CflNINX^<`u|Z^f3Phc zURU*g~7@;9yy`6IYeYMr5e2P8N=$>9E>248%RmJoIDgGZc`J${5PLWE5b*I~jN z)#Enx2!<TS5se2Ht&;mCv5tk?8gf*px4#W;BW=6m)l77947tQ6ZbX}Yl+C0H?B_Sw zu?@!Jpbm2yN}<SyI9iQ-VlBlbWQcYH)N;0OjGj$x%|(ZfYs_OhG-`jBzh`Oe+g z8#)wW*8}@Qs{Q5ioNE#eT+Qkm;HZZ=mXQuIwUi;*VazyyC_oLz@)K{EizShp<3V@% zBrl2wJ*wP3u9RaO4Z|fNZqSKs$RQf<D94RGP3xTW(IN87b#VeviT_^k;~&6X$BSMR zXd~7dp8e>@AG>i5hDd`L54kl<gpmncRQnOOIK&XYaTH?{`Pj$)$cy5_jVBBOef6Nn zB3_;7Rp-JTFDao&j4fDtgL@=>i~}D6pznUi0T#W`$2DRitP#%o-h(bpX|TZ$hU6mv zbcn-4&Jchkv>^;Zz&OV1z#)^V58)uMNuvDm4@gks8G{IbChSNTdPvT~A&>cOAHob` zFyrRLNC#s^;}3W&C$MyWN{sF!=uXcZ<m6Z+x*1Y)XuL!i0U!o3ylW612^&3dHKT=S z0$!Obm%ITW2l{Xw51&7<hdg#`W4_JPYNnmjTc7FMy)K%E9RK;q-AFV-UcB^>R9&`i zF;vyP0(h_A<nQ(gKsc)LOe)D%ev=l5<R!n2u;wI5J2Cu&DPkLQ@d#Z1poshqP9>T+ z&^wrKlAv|myxS(bDdaHNo`@axhgbwNv_A>?AY$Bbu|z#g@rM@w832k*MIFfwhdUUf z4t2m|I}Smq;+yiLB=MscihRhJ8q#yGM|ra$DdDhT4i>h!1JELoExU}a`8P%OBhr@Y za#F$&pJXwu2D*POYuU^JUJLy)mpcZLRq&8()5H*wlN`SH5Xr_6$Ojk$^bm#T5Ka~j zFCl%$ViM)T5G`{U{_qa`P$^CZX--BCKf(|r=nxIJ5C35l0Fo3LtYvsFBNE?04n77C zRg)cs1{UfdZ8ZTMzOjJ}@ha`7S7$UXCm0a{AUt98D)grg^oLt`6BhIUa|}^GMMysl zv4Q_Ef{!K=TH+8`#SmZE7BaDAUo$_@#}HFCfwt5TG1w43D1*l`IEuG{UGWg_&<;Ej zQxmo;#TSTKs9bB96V?y_DsT)!m@k7kHWC32+lPW;BNF>idMxn_5RrrrkqnBk4=IQa zH8F=Fp%2vn5iM8~c~%mQSQ7;@6oya@5vUV^AUO}g2`RWFt;ihApot(SWDF4vm2-$B z5e(#@4YIR}4+a%Z(-63z4*{SIBk@Ps@DR^1KmQ@I3{ue$&GvAxuz+4MjSbO_QGpD` zkcvczj3+W$5)~5iAPhTTcOfAT4YXr!cx>rb6H_7*^mh!wKo~cGjLCvhw+M$KQ4Hx2 z2?N&<kq{=%_7BRy3(nOLe>h1#;RqKJ73pvd4{?qT;Rxu^aAZZ07WqfpfC|wR0L2iC z0O?ce$PhEY56ut&wNM)}d21=CU?JfE+W>tdh?6VXF6pL;vtW%5p$*%>5XG`L3;`Me za10N06FCAAL@5#~pm;wCPtrCF&OjF-Q4H7sj#5dG2pBkJ_(uVN4i?!K=HL+0;1I)r z57wwZQ`rz^NtdU%l81o<4N(H`;0p}#4*%jH5AfCy@^~6S@P?|vi-LHStFa5IXePnY z5D&106KNA3gljZWV~pt?kC|l*(TWG@45AnS(f|(+sXr}w4S^Gf4PgwCFpv+Skq{AG z&RB*dQ49^S498InEr|_D_mh8E4>9?f0l*BHNf^`s2`afHNl*p0xtWA<Yu1nwvv8CT zQJG$$0@~1$nF*bzfenwz5WNQxUI~`C*$~qpmJB#rYnc+ZDQ%a43O50Y451HgnHdl9 zLc{@S55YsoIG3nW2b}N-Q!`uqAOkGnoph8?I&m$lr=XK^6O6H(5J3)g836d8lr_Pc z5P=HmP>NYa6JR+E`7oCOkctfH5dYo~9W8~05ZVywPzxi*WFPmUUJ*<q0WENWol&s} zH}Q`gYNIhS5(7jio>C*=03H0$d_tHGh3OlGsU(wAq+!z!l^F>jNe(XY68ta@Dfoec zNJ9`|k>k)4F9s1r=r&!-n14}!rNIx}0GlB}4I-hK*-?nx!4E&8DniOT4RMaa;gckx z4efwrHL;|=VWNFnFfef(R+pePp&q_*GKC^)Tj&sC>JWHZL*XK8WJnsQk`6SaKSCCZ zfG2O>sUFhj79zo&i`qz?P@_vyVe;cj@KBGhIx9Ir59MHC^?|GUGlOIm4=2+rv6!LK z0FpqloG$|pDD`L=$`BVC0HId+s@wq*ifOIIq>}8Xt#6WeyBav+C4mogf+oSMvNloV zG!5ur9bz?1TNM(w)@;7v7=r4p_*!IRk*~FOuOv}I_lF?IA|8CiW4vUqrQu|52(FvT zuMYdL5PNun=CAZXl;=8r(MJ&)8?hYQu^!ugsV7Gv`>`ZjvL@Rde}`+iraL@>t0()i zFdMTnJF_%fv)xgxHk-3LyR+_M9RUFVA^8LaWB>sGECB!z0Dl4o0ssjA00RgdNU)&6 zg9sBUT*$DY!-o(fN}NcsqQ#3CA@*pIv7^V2AVZ2ANwTELlPFWFT*<Pf$`~+Q%A85F zrp=o;bL!m5)6NN<Mp|&>NwlcZqezn~UCNZ?3xz0#GU_DoXVa@#vufSSwd+YE1Q`h| z)e=SyfiO4<DLBTf+qZDz%AIR7ropuZQBZtQV_+U5dW__#0W5&tg*kfAUCg+#<HwK# z*bRUyKq1K@Z3Q6KYLa4ub~$mXj5f0A)2LIco>`-BjhHzmf8_Y|MGL({OZQC+<Mry_ zz=I1P{tyO?!^D#-U(URF$m2U>2+Zxgy7lYWXU33zv$kaJ*~5$fA5Xr#`Sa-0t6$H) zz5Dm@<IA5<zrOwZ`19-E&%eL_{{RLk;D7`cXyAbeCV1aE>nP~pgAjVeV1yJ__#lHA zX4qf=6LP4bLLG+qp@$ZhXkvL83M8V28zQtKhAM8@;fXZXcwLGfvZ&*ZJmP5Mk3c5( z&yYkGY2=YeCV6C#Og4F1k5EP_<&I8PX(dlS7WCniTz1K0j8}#!CQI~`Ne@9~3S{P* zY_{p<n{cKX=bU5KX=g}t%9-b$eD+D_oqz@k(TiR}X;GnB3aaR$E+QHuiyt96;f#z{ zTBoE_p46qKoB}E-mWFmJYLJ+=xD%mYj;d;jpDHyem8-`88eywTp$e(2xcXOWqDa}A zs-+iT5bUtR7EA20#wLsGvdT8g?6b~B3+=Sh3Y%+2n0f`{t=D$DV76{$>g~Ajl{#0H zIz<t{7gl`ng+x<KK~TKpQgp=?23_%Py^V4Srd+;KT2vWj@N2M5IEvetxB|Nrg}hco zJcSkx5#dAtL<n?o#uy94@y8yA-0{dDlPq${D4(pd$t<Vb^2#p94D-w{*DSNmG~cYV z%1(f+?!gU8sT#UTW$-}&8C;M7(o1KM0R|Wh1a$yYR~@z0R9~%i)?8!l_10f^4ffb# zmmT)mWTS0%+H9}ww%TyF9rxN%1D#{2PYO-c76fVk@WBR72k!I-OLIWD(HtbM_~MK= z?)c-7M=tr~lvi%~<(Ox#`R1D+Oc2q+fv!`*2^|ms0t0aX+y<<-?)vM3zb^aho;&wX z07@FET#`I#LGc+7)g8d>#20V;@yI8yyzB(AE|BZbZy-?OtREe~-_obf0qfK+@BR1S zhwr^W!ULb{ro*A1llcdsj(Y0CuV#HhP6wa?(gCP0kOm@fph5QGSy}+jFb0aPDtAQ^ z$dH(WK(_$!Gy)Vz{hIf{gIoXt7q~zGL=XT7Sil0$t4;)C)uX$ONI9az3I{My!Nnxb zA>A_w1~QO>0OUa+f1tteYKOvCmGExN!Q1-(8d3n$tuTM6xnD(m&<q|rXIG{Qos4v( z6D(k1fI7tALiCqEE;2@S9=Hn#TZj-&aL@u8gg_n&0YWH95IY8}6cnGRx0{^72M<vl z8C@6v4F&)RO2DHO{D=@B@L(W5@I^v=;D#MK5j8~PRZ8Fi4}VzFA4&P)5c9}F)2Pmm zQW!-X0uToa#1DxAnFK*>KpBD9frAB^gb4Qd$hVk_L=%yRE_bQRGWGII0kGsahS`mJ z81tCO97i|C0S{jKQXXmorlzI{D?1K^kO?`WC;LbcDNI5M8uVfS!Z?u2KtKc|1cD6% z0EIue0T)WEWmmFPsE+Vbm+^=PJJ_NBOG;WY9NPc~GLM-JX&CgN2F(UM20Bbi>QW#N z4M0Rol0utUKm^z{h!IZ-84!L1FNNTs5a5X&CA4Kx6&1-oht!X8sN)~T90xO)0S!sS zp%Q$^hfa6O(@In#4!D5EGw4wdb_`RRE~(~DJU~nMsV0km{D=-}IL@XLhkb!U67GnU zl68zD0R1>-H7vmgedrV))7S?th%wNC5(5|LFl#>eu!#T|vmgDK3Gavk%Pn#gGF+re zUlAgVQG`$+!YGIx0+3i9{8gS<30NIH(hq(Z6C2p*#2?IhjdNt<m}N31IJAM;(pCc- z)c^-k>0wE9B!d^`7=<?c(U05zK@^%MNoh?8rx4Vw(5j57VHQW&MMrLsxDw!?>XZms zfNe{uAJOFk1Hcc<)&m%eP)0s_aSmw^wH~F#>^Ic$QX@TcpWyfgYRgfNbT~sF`Tz$u z_~DOz8stqAtq62)LW3}7G@Gl59~s5jLj9qWo6Us_!=iW*U9zLH;4Q{El(7tRpd%gi zphs!J!H#l(BLMat$UZ|Xkd?CI8vy`EH?&cXahwAc=m2kCd1*;Xwkf|7(IihU5CIsb zW&<x&NRSQEKZA%f!CTR-J$2a+Y#0+5`cOtP_K}W$6r&iU{pyf-36T-ALm=cJ$2aP+ zk7Z0F9P+)SKPYKqHep2n$2Tbh9zWm#<|gERhWo&fhtoJDM}|+)-K9VHf!Th%R~hHn z$2;JG*>c>C%N5ZjgXCL}0Q6!R^4%wc^66y;?Gwili4#wB_*jDc*UzIupzb_k%t2#T z9nOI5g|Sf#f6${G@hFKg%Y@l_7y}a;=5PSgM3TJ{g{lQXc6d^tZ1%WdOg>atq~+mi zaKt0l=GX^3uKW&vZ26uMg)~GU{b_mdgC4zzF*)*?Phyw*P?JTqyj7y=f=t&U@@TR# zKcS3l%LB9F@W-ydOAupX#NY!Vwv+b(i+b=wplb?A?&eMLuKFvNxaH+P#v#yp@H^WY z#s)dm@ynLz5**e4@JB4X3l3|uyTts&Ek&eV@tVKcR6msDLBhRDf)vx^`7lR19zNSO zH&Y((Mu~L)(eip^0~GxrttImbbE@lCh^pCw*0pXBuG`!|>Wg$e#<6es^1~hRKrx6% zY?GFsJKg@k#?<x6c5MBME?dvL-uIsOuOq15TYYmd$-a$VBqJSV>PAuAj&5``*^<Qm zh?3~CFLzn~@|e%O<}>ei{y3^4mBp+xDsc|*VxyAnMk-Fg@eg!>!r?9Fblu^-U$^ir z0DRBA?zi6c&hMvzTb=H`A7V+&?t>Rou7@^=9r<Ca-X**S$39;FaMdEU`4X8p-gnRa z+&jek3E4aUL&X0O@)N}T;n(~4)t`R!cb)wTasNT&f1-MJ<R85@hBEdMR&9X8l1m43 zHW5(^cL}iPa-c?gFya+p(0~r;fVua85~zC;_<*;Ed%UL;52zm%=zs~)fenZdAP5E@ z2!bMLf+yI4DL8@yu`jvxc@{wrgtrXWP!COp4KSBL&Sw+(G$buIee_U$?3QbG2WMG9 zFi4n$O1Okf*n|WV0Hou4sbK{yVO!c~5s(*mWOfPD5OQCJa7j^s2N-b|afNPi1Ojmc zYPg1M*oJQShHjXK0f2@FL5ET}7hIqcG#3%NWJ%p1P{Pm)=^zi?AP?%GK&w_1*dTqN z5QMS+_i`7phgvZRlvs(Dc!`*piJC}>cc>cOU|S?1iF_yz_3#Zu6$_P6UH%sjm!yL{ zv2+X9h}AcDw>5L|b`@XdWxBYFyx5DrxQm_07<n}ihe%O+(=ZMp5BNt9`_K#1fPdJ) zS`M{K*mn~VRead64+bcNkZ6kwb`?tUCb`ols>XcJhbC^K5O1Q6Znh9@!jA8l5bG$9 z?Ff%%Vvl5q5c8;y^+=ETco6#tkm=};_ehZccwYmljzoxzk%Dy?R}aM`4Ek^mQI}We zHG4<#4`X%>HOP%tr+_-w6i_shClrk2k#h?O5zmA>(TEPQzz_1^e*h?RN|8^D2MRI& zhJyhxgthn(k;Gt`M3O=ok|s$<Mo1AdSPy}SVV~F)O_vS5Fb>?HlRSBKwI`B8Ns>i5 z9;yb47}1ikFla3&4?t-Y$RrS>MGv4L4fTL#lBZQ&(Uo#Jmvp(6)gf6#i4eTBPY|h; zg4lAmm4MbrljTqj@<0xFg<0t!i0lv!;SfzXca%nvm6S<EcDWq9lZX{zYhbw!ga!^Y zsT8ExW@uRtu18(+RgDg@K!BGOborXFX@-{x91SCx$+%0U=$GjrU;prBOd(w<Ru5Np zWznDxvA}=f5SoKxLU$Kgl{u6-GMiE)iVl$`_-C525PCW(m^@)gEtd|JfDgm}FrMR? z2sMZex5J$va&cJsobD-|zhQq8u_pCE4lsoZ=}->n`46f|6u(pt;E)fAfD8m$paeP% z04jI>pq>ViDJ2<{%;}z537?QeO_nJl<3??9hYkI(ayMv6fvKE2adN7a4Fq}*_>iLa za1R8EpO`h1gCaC3=_(RhqZIlZdo_F%VN8~l45g=bSmB-X<qQOx5BgAM!=MlNfDDeX z513UZuo--<$rQ0!rB*7NH)<Njb`h-AYv@o3Q5TKp*c9hbr1~HZ`=AU;%A`(O4D_Ik zS30Fi5vOz-r&;P4csWH9k$RS-4P;gcLziX?+H)d-3%DQ)1A(ZDDiDbODiEI#0G|-4 zlKQBRx(SwGsf*wYpg^F*pbX3)2#d+0O^R9T&<``2A(FN$M^U4!%AR*B7h8%EWpZw` zun%Fj5@Nsx1;Ykszy<+;2EQ5rz6z`b;j6-WtjH=5m!Jp)nh1`N4gzoo^{}L)iVdY& zr<2zd*t)Gz`l^p%n-eiwzUB<_rJyYV4bTt(>AJ4z5CGNCuGJ6#+c2;6I<EmRO#E<z z+d!nqkPo-84+0<naexkqkO)qS4dDO}2{WNI+Nus)mfq?Wv5FD@CViIx4uoc|CIPIK zra%QzX&JU!*&2NE^$zH8qQg)R0Sf@2aC`?_4r6L>2{f15%B?p4TbB`gE)Gc%?67h4 z;G<)=k|;qAl2n^plB$l@59zR^1PZMJ0000G2l9{(+u&#s;U!G*unwEEba9mu;hkeP z4Y8nnpedpvK@aQj4-mVVaYqi<Fbqw*vQWzg^so)x@TNINokgLw63Vr30caP2jr;%# zfhu?1SQ0UNb^bth)vyfcfDY!+4^IoVb6XGI(3B71C&QK$e$u&~`?=|OkbaxB77DHi zQEp6D59g2!<p7gNhmj*e4j|Eo8ukzA01DaQ55)is@F2I8%LesO4cj154&kc3!nayG zx>upM3_)x@h_Us+T{6}WUbYnGICk|=c>53!<**IRAi0$P3jmWF2mT<uwRI4AYMDfV zyzIMx45_?2@skwMga1&N^pFm)kPeIJV6dAJvKta1R($P+yHN)Y-YdBQ`?Qt-4Kua4 z+b|AZiN5l=x9!Wf@Jpq@*AY!84P)zn{V5V^8xn-qvSTL@-b)Vw3k?bY08T&;vLFk> zKn!-<5AS=WMRBt@T&EY@p3ONCg4+wZ`wbsv5>D_59qSQPhkxL3yZc~zy5zmvU;@HG z4}2iL+i<ADKvTu&v5%svxP&kj9L765nWmeePUd?5P<;%V6Z{K#;gG$s(8T=k54+^O z?@A1xpuzya2k^iQ^V$tttR>GiqqkTSVT`<E9F$)Fi*bHx4Cf%0Wm^)v`4RS|4gzHi zm(Z?@C=mIy4aD#d%n+&RKm-7w0OJ4++YrbNs!4nJzAt#l51YuxyT}sZcK&b)`=DVd zal{^>#Qb0k#t=~2FeD+i4bSilYZb%70JWCj56}?7g8VDS3&ya_s<OPQJ!}y-i4O85 z66+wl-f(+sn|(<M4M8VR<<*<MdCJGU4bUJA+wcW^Ft5<yn++PFgd8+V#uC+R!Pm?a zy2Di;;db@Vvhkpk5`sJS))BiFchU!_>+qtOR1oUW4f9&j#6S%9Dh%+fcmpAPa7hri zgR?e~!zR70{~W*BToE_9595FhYwVK;L9`YBQEo%xf4;^G`=Fn1`jG??X0m(AZ}kbd z@C@7Vzg>Kl6Fd|B?9VBE6J-n$Zubv330@-s4Hr|N4Tg08fLHYZ4K(O*{`X5dYK0XI z4aD#a-f+~a?5azhR84KoU;NZ?oz!`mp;O(mjMkHpNDyCz)ERnP+Ua@-+GzfePn5(E z<Y3YKzzwx!TVZF{JG&C?o2p_=*EB&TGm3BW;CAwW%iSzdW_uAt3(a~-le?sE=l}~Z z`45Gdaq{5P2yr{IJA6v^)_VA`sakF<V%f2b*<>PWi93qr@C`kB4go+8;^q-w1%?fw zas4o6=@1M05MwG<50r$uqy4c3p(lU;(%qU{6QB#a{L3I~;!NZ1xxfwA%=_HCv~aNC zh>;A!4{=XXXH2qyXaa{>0%1wS9CO}?wfOuct~^Z+t7#a*OBq5*Q{vmSvfe0BLIo}n zx+Hh5=Wrf|EdoJ>m1f!sp^RYVWJ(DOtQ&IQwsgzwlX^SN?A@wGa!Dc^b3+m(odzxt zp4-uO*Y*A0OAN&QFqYd55wd``quAABRu8xUU)k`|*zgVYYnb2`<O$K<1OA{bp|uVM zQ{T`H-S7>~@C<)g5C84p3I4h>ZsRu|;ge0_yOd8J)?T#04^lVL8L{2@wM)ZfOi8W} zOD<mtJ0yjfVgFscrCUuCF4^4wa^>z>CM;r1|F8|f@C&DK3abzRq;LwqPz<SD4`jIx zjJ^&?3*~2iOKJYf>RX2DOb~7t57Mg*77@X`oDgF^4(|X{d%h3t;1AzG4m~T-h)7}! zk*6SO<%<5CN8;tW&<dfz3IZ|d%pL%t;0mwM45S$4&spjgr{fPX=n1rl)4dNGIm8Ze zs}WJX0YF|bg$=jfZQnqOE9Kz<p6FId>@s2OL{f^cU<;<83a;P^0-*}3Ko9}n3cB#x zot{sWiS24`LM4%&|Ar0ha1Mju5Ap@#3IS7M4pUzFm<GYWe2JL-Kvd1J2=KKJ;Xn`F zkWZEb?2)<BG1|o{O_KcoJ0xXN4Zlzds{rt<zzV653IY%C03QIhP!0944hT->q^|JZ zyyouBk7dGM=XMRs@L4UlPqJ-SkB-XKfXeE?2N1<z|GiI^g;~>J46x<WDF3EqLP=H! zZZS&b61=b&+Tu`@sx&5W%|HsRPzt3m=>We9m0l1)&kBIw48tsFgPI|q4tZ$H;!58U zQN81VS8gq*w9@NvwN-bd$P9e21x|1TpHBvCa4{habA|a2>OfzY)e7f;eAn<*{B2v$ z)O;}=%}jr_6kO#}B6~|GaK&H?fIsPzju1Uh5UU^xwxA1YyHA$HAgMb0jgQ-pkLpXp zYO#J0irEX8kPf8(MGpMXAh-6_R$v0;PyQ=F{!Z}B@Nkc*|Kkz157VHgy`XKT_YFii z5+e<lItr^Ny$%2Yu34*BtXQd1b?Q_Ah7BDuT(v5pssPpGk^7fX<HmpW>Tv`aa^pji zB~6}0nNsCSmMvYrgc(!jOqw-qwp^D}XU>}e<o%S#Fe5{D>@>0i_idcNbD)-8!v?M% zIDg~lZ8E_k4j-<3j;t^ts~^99^yo>&hAo>jefsWTLYM9xHf`PNkt6xjA<&>c`>Na- zSn#@@g$)N7oLF(rpN!>Y>{qXttyQNC8Z>1JWoCq!P1&ke4_?N`I!k9Px;XJ+)~#K? zh8<h>Y?L7XX*2Z55L@VU=k)bjmX2T4dWB4+k(7K>oB&5mEFuSP_qKHCmMx=o?HoFP z(y?u$*K=q|ks@!O4=}#`diERZeQV_^z^PQJA}Um=(BP_9ty+a{FTnE9Bd|aN4@8ha z)mkfRufEDDC!=qqljj_B__zZUW3EBPgf5bkM35EYNW+9nt}$mBHrTkN7jv$uN1kem zafcsx;At>Djr5v{C)ET?@U|a^G)*3(*7*mUUrtdaB7<B~sI!Au0j(Z?VoWSGA_EJu zOE13!^GhOW`>Cj({PCxsez1WM9CXalC!ZBqNaKh)S4ab_eBd;vp0lRHh8%VtE2>aK z*|BN=Cx(6u^R+D>)hV8MZhVEZh*qHqAyr(lMHfR$gLJS)M<umXQ*UDQCB9hV(JY35 z`bW)v0?>w@dj2rMisS;|Ll8`yc<!5euo>q@c+~u7P$LiJktUu<S`ab9PIY$LP#62@ zMsTVjr65*pa*~x-NTG(RYg45*U3J$zbv0FilF3k_iu%VNe(D*-gfT$0BspLuQEHrj z0zebZ9A$fy-JZ@}3?6@!EG2*^Ym%~*Qhvb(O;8!0R$-4n2Kl_jyws~Btd8Jg5J3hR zgbx->_=FyE;6;y7E<=`y<HY2V%$5Km4j?m{gq}~8PXE!_U7VL@y6KgkMHju00;q@o z8Rtw`A?vJ7aN-%63mj5fr(x1b+N9B}ryFro37|gwX43C6S6s0xX&}eOJ8!*5PH?Dy z$f*YxHUePbt0RtJLl}7es(DMjS%TVbdf*XA6j2a*8(fK4aV3>!z%i09yE}fobknI- zRMfr)?uZ_LykREx*q;$6yn!3%``Ob`8a*dT(X7UnQbY-$vV{sW=#)~b^vA57HV$=n z>4j8%_sF9@uS`U#4q#BTzNhDQ+-)X(`iFX7$1I+85xx|JSi7%MUF3;J^mU-W)_na@ zg>=#K@y1?(^r91_ks~MMK;U=~=D7du&mp5b)0Nc5iYPS+Q-@KAf4G6Pb!aL7X$}P8 zNtD*R$0^23e50P@{1?LW*)4+gXa*?`qKf*!?}Fc=MmaPl51omPg+El3+0a)uy{*R~ z3Oo<%rsf*k=tw|E6kiC{BcPCYBqL~2(kmp!iu)YTFcAqF#$1;XkC=su1Nvbaop{Co zoi2dm)7=8Ehr%GLQHbZ_3l@E5nHj>S6srIYRqz)*AKKA;Lo{I_0jM+sRnIloyJNKC zm_`WFuYUDlpOoJB8YZ<u7oy?IAp2)XHzIPBO`BsK6~v_mvL<0fR3#~sCaL$l!WEaH zpcfC*MgMGrD*g~<!bs^rQ!;XqD1_rA4U<YqT8oIXv>Pp}!MV)E#vtSW3e65bILt#9 zGm)(X*&AbH%+?Unf6BDu=+Gn(88XCex@1jf0?>?Kj*gqs^Jdr{XT;l}@ilF{Crj8^ zp5|5K7w*H{DZu!e<edUzXd0+_0=m11R&<GDOBFg7M$VkUa+I;0D91u658&BCGZU-f zYrqJ|Vz{m}BQ?v7a^k#1PIPI^%%?Czrc+lsvL-l<mQ8urJ6la=BASwoLYQQWVtnLz zJX}Y?nn#Z@36*I%Wf&?|Sk9aA?_5>|Oz!~4zEuE?HWl>bpd=+2vq*}j;sk5Eu-ZeX zebuX}i%AeU7T2NT5vo6_Wqgo28!63=XFH)Ogdp@%sB)CArqb*GT+N9yyM{HgHHDlr z_bSB4LQ7{E$w}Hs;fhTX4K|sn&nie!jbGYtq&)5Hs3dDoytNUDDq-VGG_uBu#<n&V z<;Xf<n2LnJ^ERv?MKdzy50HS*j2-#NMSZ(2;8ypEb=B<1Kxz_wDl#Qs)#!8|$grPW zu{*!O<-}yuMdZ@cVP+aBP+%+G6V8^lH|-xd9~jBigx9lKrSEqcW|pF?6Bwk})GhlM z8`B2hq0Ie<r1+wxU~)FVV6rdzF#6FUp0mRj7O+T3>JNjK;uLdJZ)_}PF@@Ly8#yV; zjb3}d#;VT0Af}#&GYsIpjY(80{4kDR!ZG+>X);=z8-ecslM0OKP<w*$AZCT!r5$Uy zgjMG8lyRan_{O7W5vk86U9-uGEw81(To#ns0aq=r63g2(-J9*!=DuFbQ1GC~k&m}f z*DSO?b5jMCbP-|HtT`}Ib}XG!C}+Bw&bp5VsG<e>=;lpkO5eIoMCP{CPa>(hl3pF8 zMV;GYvJ%T?({Wcp?L)shCN=-)4{1|Mn?Jjv#e?=V{@`2HRgaU=h|Jq%Gu-QrraDyG zdyFnxp%6aL2F%1wa5uvDkJ4yq*ZqAau^*Y;U)%M@>YC$tyX{PEuaLh(Vk~1|-HJ=g zq&_JX^GZ6C3T{OACz7(ZvP`($a&Pq9;|8*Rr$<Hq9rYVF)^%OlY<bIBmn5YPCrPvO zgP(eP`XA3FwZRWQYL1_Am_Ev=z%`y%ouO?Y-a<%&Num(5nxrx;;Y^_EZ6$wX$<S;b zd5-{oUp4YN=gZXD3#$<dZ+S)~5t~FF3Ze9d<iR1DNlDCaSvMLZ`jkJf*3RMlaVcYc zqasEdHArDxmDs`!ENF-c8nS|zAk{8AwEBF#K4h(1`G-pM+iq_=_nL5ow*j(Z`kG-1 z3%-N`CSd{FUxJWVnBwhMimr9}9+Qq&-lCH?c+yH!53!$kZlt9MO0>ujJ~RXnbg+XU zh~N^&zv30EsP|j5jCs1(o#(VCHrNXq3Z*jtMCBzJ97zfR1tv(rAzfTK9~IKMYLvq< zo5lT>ZQnz3N59ty?@lumnwe^zgcJ?214I5m2OJQ<4MKoO@mBHs<4eS$G`HgAtv_kY z*WcswU$y2(T#uob!XTTJxQCDewF`hh_yaYl013c@hsccYQ$Lf?l;rvbhY6<c!awes zK2yTKZ;LJc1FU8!o`f<9(@KRnpa3)o03*-=8IXac0|bU(gNS)Hm0*QX00wZNz#6Np z3v8hb)Ie?Hw?yl#N<y3d`@hh0hzeqe8brYWPy!uLgFJ9Ll5m9pbh!Yy!J>c=L)k$d z>_HzSp<e4k5Ys=CW19ewj{w*t*K>&fgy<ILNC6;_LOTe*hj=|EVF^_*1#SQxW#K{^ zlRF*+!ygQ=ViGr>5~?!1lA%+u?wb##@{eL*gcR@qDJTRw41hYcLr3(!ic24QIFy^) zDnTTjK?JroE1RvGE+V{=W=I9jQLv|jx>V?vR|tb5kOB|j0p_rS(xU@6paULgh|y!e zhR~0ha}3wg!JzWOe=|ksQ?&442<M{4Y7Btz0G|M>#%<(Ap$mn}Xf}jUEnO%EM38_m zPz6g+yu@RH#IwUxfVz}ezEtQ2(19v$#7F09#)inpe)PwG1jvBQM=g`ARSdcjW2Z~; zjCpK@ay$VUcm?*cg*+evv{StQ0GN{k41iZSg<|wQQ+T&MY^`OStbKe&yTh@96fY42 zEN=OuRcNS$7zJHm1w5DmL(qj+uo&0lgh^lsTxf_%7zLP!h=kxndLYTGGs%-g$wK5d zZ!*YZTb81bivDOfRUkS^41yrg1zivYi_t^2>B^1VNL^qE1Y^DTskd~?pM7*jrX0hS ze9JJTuXFhndFYS%;E(wz22Kcq89)SG7zI-Jqx#SyapVt<JRZ(TF_bWfTjB<KSgS^B zMz{>Jx_q<8Vo6I%wpO4BRS*SF!UGiO1K0b$KkCTLfI8HAw~vfBlwdqos7J}HK%cw7 zeBukz;EVV}jVG(RLU}&_y6nJi)68p$FL_Wlg%|~3@B|qsg1~HruWUR`8LawH&DD&@ zl)xNS@FaOChuUODx17tQDT?Q+hiyR5ZSaP4fCnoA&JGGiQB*~%sylPDsYf|ZEyPP# z@FZX`0>JD_QXovF>OEQX$drhPKk}rz0H67sKlEWN(ZPtj=muc01zTu^3-zRDsD^%M z9!t_q`1%RibI^dQPq30o?J<*juuxslgA%BNoFs)&kiqM0jRakuPXY=OZOhv<CH%P( zfw0h1cs+@@5C8au&_GI{kg%y_hslh~`!q!pg%p}9FKVj?cc2_jC;}w#gjX1aQP85- zd$%+EqD%RsqtQ42K%716E2a^Z%y>YOZMo2|yfjuIh$0;xF^UHWp{XvD(>aT)6Xif4 z+7kOQig*|Yk7xrK=mTX7h81hP)>J9uaj^&qPH244r>rE8D27pph=Qmf?n_N^@sDP( zl_iBSWdTpyl+qKWPe`dYa%hKo$b>4uNx>W*i<yrD?TIdOu^4I9@Z3Oe`iaQEhGzKE zBW$<|+BBolg>4YlP;5#n9mH2v4g2{Ab$Ew*;07rO17DyAV)#m4T|cPf#GA+r9KBRD z8&+i6R0w5KFY5;X&_h`y30zVwS0II7z(IH2QK}NukUB|h-5E>DiER}JZ{33-@CARE z2W$X_mpoVh&G6Nm=%OY=GueaFVfDf{9WjII7F<f#hEgh)s)zbn7W=t9XnID24UBAY z7+|W0g$<lAFoce9hjD-yi6}1GSg7{G!NpldIEB)#i&x13MWgtKa=@fkATAWcG>B8b zh0>4Yave0gHp;ZtDJ9s3froMcMZ3s`BnSg)P=|JChtUuSQ(%Scyp8%0S~NLW^+`&8 zi#|l!%@}%2sSQA?brMcFvsHapq~#{dEYxmV3^Y-PrKpEMP=jCShkw`xsgjORur;!K z4Ji>9Z~%uTEn0bKt3ZX<VjZ1N=^0b-KUg%nhj`6~xTfS14S$HcHZ>%~6*&;XmW&{W zEBS^0I0yu8SO;%d93(-TZm=b0yCB(+TUe9|YAq7G#W~zN-9q_?dTj+vVOBF;JcnAY z+Ko~}MU3%;)!U6((Y2Ltn1_1s1vRLGTKETd5R|7{AId1u^@2(MEQYB>won>fmQ}U9 z9ilvXm|q|Tn9L=axRkO&*?thwyDdoviq8qA;0m_j3&!9IPAB+uHFofZD=7pufZu-* zhjzHqWc;$1Oe%%i9H#n+P=u*Cov`@y!VJFP($JU`7QvZlC_D`fo3mjH?m65=MBOct zpAd&`orEf=gO2cq^(`Z&r8arMGi<OFJe3XBWQZh9*$)0+^lj3k#aqm)qzL+({-93( zn@BlRSOrn=SI`w>+hrjl4q!u7H^*g$FsK7=U<Y?-2dAZ}WYNtkJ}Av~jr!Qr<*GJO zG+NR%T-uY@b&8=adR+zfSr=xmHO;ETEhRdR96PdJc#r^mK!d+le|Ur;s0DSHhj|DG zSSb?6@CV9ihOcCZN-m5t#T4ZtDF9AJ2<Bw0lh=5lhu}Ggg}PXkkP`n`)ITgyV)EoM z)?LSi1SHsldPwDQScf=%DoM5&Tq<U`AyRVDp_&s;ALW=p#w1(d$Zkdnc+(VqZH92p z)VA#99&2W2-kmZbhk5viW_W`-paymj2eoqK#h@i{z!Zg`+B40dSMXfA9oWh|NHXFE z|Nl_lbd`zyaIktBXDRwS`}1hlNh5ZEJU|EnNXUq#kYXxISY>;;*htV-Xvl=~h{%(_ zW)wBa6o^oGz}85fN@=RmfHaq_=XqwDE0xxIkcA;I>3SFk2QHMt^|EScg-0}Gj4i9> z2@RDk+`C!I(YX;N*`fsArOMz=U6`D$CRY6!YOdZL_)3rVtOsbQgR_m_b^t9J1J68) zhh&vymyQTg00u=4rDf*3NX|2KW|F}&45_OKnnP<L9Jr5`?2&LFL1_nXsDmWP1b=9U zc}QvCT8C{Rx*ax*)Pl)Spr^+OYVi~`BvCdBvO?q$7gj)3i<7)LUTaqJuDod;|91F> zc5sJGkO4?&9&uPKSeat{1d712XmzECSC|lxc<efcWEZlev`MnrFbIqJ1#QS>ULHke z&TY1K8XozZc?f_^c!DOb*>?aYzYvT?7NyhphskJZ8&ar-6js&V+8#AsyLn|8k|E@) z)HH1>V2;zLir~ne><0I{$3c?-KxNK*f;RAlzj=pu$Ow!RwcuHZcS`7(Sh3~7hA|Q~ z)~+s(0A`3O1$B;zcj`z_5-woAZ7Fi_8>ei%sRs}C2Wr@ZAQ0E~-f(Gzv@((hi4BG2 z4H~$82^%dQQE)E^<IS43=@hq;p0OCBadDW-PJ-x&jo|Qs3Ze0SWQA!E|A6*~0Kf$# zfCP2;hg25i+nH_!Uk7c$1~gVfJ!Ep2K!|N-=-J%~deMjlcT?+T2gv}{QV8+VhBp4l z>Oj5g2Ttqh5y(on^h*y&oG~MZz=bNP0yjr*pGa5^nnp|qAMNq7$>7z)P|&6lX@6)^ z-@J4${GMyHbnV%3WmAQggAM9bE%(9^raex#;>J?99*-jP=>?NAiC=gKfOf!xD!A}= zsGaSR7xMj)+^m-ZwwM`wiH2L(Q*bfY$%!56-|+o8pn4SP6|Qa|g=M1;?(MS+QV20Z zGu=dWNkMRBrz~Voc44EIjwLC62!L-003E1>b#R9dE}1AYHseI@|BR3hhEQIbP+o+f zhUHSTT@D+<u;-lHOrdK`!YVF|*>5e8l#G~6c8Baz`*-qAmz*evVyOp6paO<K?{RR_ zgTX+%L5-(nU?rD{PSR0_4s`ic%K!E&llw*j!5o%youj=GNtybAF5=Q*%DdjIk53Ta z!87)yf;}J@3I8j`>G>gY7^zmn*k*}K0c>oTl=ya1LL%yNQ+IS5F^Rn;h!FZpU8<%M zE`i+%^NQz|->^Ys_l-bzFky#r=vH5#f-tBB*Xafxsy)4xj?Tf9Enjjq>=w@z^g?Ud zqz#oK<3C$Ch>y%-kYt;(4u|h4GI7@WNx!m}FLMORk<bF@|BonyB=CjFMHKBJ8$?1H z{_{*eYTY)}^SDv1h;U)}6#b1ReTZMgRxkzSt7_Iz2wSp?InTD;G4=2V-GCMUOcxXQ zoEMvwgdH%1^caWkVO6tViSn;TSO*7gScOzzIC(D#&IO29r$jXa2hX28dH?<;r04J< z#E23f2A~+=BF2mwH*)Og@gvBPB1e)eY4YO4lqwVYt5?icsZy+1ojP^$CdQhpUU93( zj-A7J@fJc%*ifZIoJyB64Y2Mh)TmOYQhl26>B5Bx7ygWTwJO-KV%Ie-tMMmScH8RJ z6E?#TwTt5vHXUo1s!(z+TdnH5s-r1W7gMEj<%*T6|5nB7mFp_j@!h9pCsVF$xnyLq zLfQS()k^Tp%Nzq=RHf?h+O!EFXC^E9HA%@%TaVrRlk>l*S+lY=D$lAshrnr%y%-gC zM%lWvy8Bm;SeP)~*v*^A4&%?I#KnH~=MP&kSEpHJ^!qnJ&6=zXyP}58`%&M(Z?hX7 z89Dy^`a5p-Di0n!oOveROf~6OlWDJz@(eiMIVRjXU)fjHeibIy-&pi5B-A?p(DM#I z<A^9?OKf5F4{I2PWg$ma)k6+D^)S;$6}7C>jyN64gWYvZsR)))|5WpeDKe>o*i18- z78on9s3Hn5*fds;Lb*lw+m%nzmm*j!diiB#|H}0TAUyTxVvA`r^+noif%SzTl=U1W zVSixa_v2U&(btkc;}r9YEw%s(Xfwt5Lr-pLO^BzMEc!-I0N=3V&ODGjQ42f%%oD&r z4)$mkqf@aI4_mstB1$Q#AZD5>ItfGyDX)M7jze29gymFQ)@PTUz4~g>j|l+?4mYo~ zf>>V__Lbx*z<{GrRdmuh)vvIHO4V*1)>F+dzliefw=tDM3M<`qQ;$}-UMp3F*aBEj zJCGo;M?L;{)8S96ed^=7qRQhPIMwLl%D1Mx@(OvZeEUi<#ekC=mHI+h6_>?Tdojkw zsp#0Yq_~oif%_R2K)Kb(>D^NhN~<ol{~1pvCZim7$lEx;*z#=vs+iZ;VWo&-OELX$ z)h~tlN%q@6<&49YrFBrljyT^Kb<tO#5}ooxR4xP#cmtDyktn(p!wop~`bJ-dyWZt8 z+rMI{CvF|H5}0W$CTof<)szFzSGBUtYui>|tFNuxilPd_rqx6kVQC%~N;5tAvnZqb z*_UrO^wbl86i!px4Oa_c<eF>zULCD-+g4M|>exI?Pdr-giZ;=K+iu~H`N|WpC;<?5 z5u5r2W>ek`%2(&@rsL_`SM@YQN-D3MSKcaWo_9)OtyDt~d`5*jo3&6qI*#VP*ntE! z@61C^KelFf+37RymKKU^K@`8m|H<qB8qBSs^$#|HK_0_|#zJojK=CHG4gk&XR@0)& z{<PDtuDHY&rclN2K*A&?{h}E32oO6S_@nTlZE4PPLlQC}v~k44J85~JW%|dc|26PL z*}@;YWD~(1!cRp)!NxBFP`y>zZ55?h1<>korHRcfGdw&A(K_W1a6Io|PEtilKIRJT zX-z0}qMZ{j!@MAk;~ghVp*qw-jsUQwd&t3`hO+V#hwLVfOpM<X^Qb(syp0|}jEQAZ zVG`5WLKi4X7v%t_N040YHvf3ZDo$aT41R<#O43;=@>VY{fw47pA)RDo_YZZngDsCp zVL#Z>jd3vKC*H9fR5XS||6NrKe~Y|jS$_1#QzWY_oao&uOhJl}b%ZcGX@wzo#Y9CZ z5|<unAT*;XO@`Ft8?A6fOnNzz^rYvS>PS=r*)q*>{=+Q0(bGcIu{3&YA_#TpM*zm* zj)b5DQePq`KJ%&1ee!cR&irRd`U%YdqDPw=F(`RH;(|DMVqB(bMJYVemm?vQAw)rx zKt%`8jr5Bpe*A?XFG5U_6i_{;XofcY!8dh@(3465jz`P!4R^4molaASINZS*0C}f- z^fVd{#WzOpU8$2-+bB|71j@|#W+8t}RY*T#piwX(B*4&x9*WS4tqNu%mfWHttK=Vj z=`Mdr?Uxtj;h9!l|FR^#R8lHNQH<kV3nx<%%0I|a%6fbv2{&zrH{=n*|G+~iLa|d& z?PAp0CAG1~nGJ1N@*QB1VtON)ga=lj5jwab4r~Yj4fZgDARt0Pm9@!1S3%LRQfy0W zJL^(a#F8>KgO{c;%t*J1y;dD572l{ALa<cJFk(ii4k<@DykW*k_>~&msLs-WbJze( zmqm#U%NNzg*v4{KBN+0|A2AqJkh~%f9I?Y6@(_m=h@c0E(1k885>bx4DKTNy-B)xa zmhNICqtXQLFW8!-rCc(S&A>)HFzVl|aH^aqiKaM8i3=pup&9C^jyu+o6pmEaOAG!m zi22Fi5jS|j{{Sw<krG;xKLo%Ib^yd5;Lrmbh#&yC(8VakW!a5jucGDfP)1A4-w@BQ zC1*lXLW4(=G!YSri_!2y7A$0th%TB?YY8;!PzPU7XCC5!NAid)<}uHY#6$itfd8_l zz;rbu!?Q^tOweLLpw|vMzyT86U;`F>BBJvh4V!a@OvZ38$PVUiu$Z@ydTax?rO53~ zbP`D<>Ovh0ENtwur0Ed`;CR0Ai8##I3_KtK66&B-i1c+4T_N_m{z+tFV+cXWg3`=_ z>yKprcpfFYxvTNL2p#@lXB-$I0EGy^3S58@gYsA>6&-AR{$|#sl6iN}<K@npGSTrg zqa24C|1(FbY~?T40~(};1UuBHj*8fGe`J35hi!f4jI!k&^eDzCULljYwK=t?FoiD6 zdjvQ50M7wnu}QXFlV?l$(2fliOSWZ;gsFHkp;^T*un`Ug(iKm%mda1oQtoqiYJL0i z4b`URHdnK}XrgJ^V;d#!n<V-j{&<PLmt>0Eo`Nu?2!$>Ru>up|`40#$=6HKuw^dYB zu!H6FKV?Xqg#d_DFA-z`DHE8OB+)3y)z`K3yAJY=ywuK_hdO$sYW=mm<xaU%={^oP z9nPGi%lp@Nej%7%j#MYH(gi1a5C9gWcO!JrEJ>2Z^suH?S1pBk+;KTLdDNpDTZJ@b z|9DwQa#(4xGXzRJemn9cK*BlV_@*=4&T_a*ecE;R2%`YpZ;fD4m<;no4R#O)WM72N z9GQeJdIyr<v7+f@b?to`JLacQF;+U)dRK4T3bG{_-t+sQ=(Ah}NU-r8YmB@etuKBN z>!->kCg=Gb{`!u9_{6Ld>AwT>cifl25P&DbMR>r2BiJAS`)7ekkcNFR1Rcd2K*d~t z1VszwooXr0ZZR8Eu*xYEggd+gfP7tW&_h+A%$2kh9Yu<BXkY2o!#mg<?fg{A*^cV1 zAoxkpg;Wmste@O%N3Q+CqY;LiI7uil3?djo3G~4$1Yao>!Vz4AoMFTfF55?J|Bz`^ z)HgKVmdFfor5>K}R0TOnfux6JIN&dAPjKB)f27s9lv^E`ot)U5Mxo#$u^<k~S}3)l z3?|x%`Ni;rf@1XG4AcR9!AdE-0!FY{A^brg9-DlP1gi`nVJ(F04A-nhT`bLDYa~QD zn29YMMiwSX#We*tB@sp?gcL@GZ`g*&K?99I0$aEPKlp<`CDj|UAq=|Vb;%$kG8NuE zRV!3hC;$x}>LHHhST=o)sdxlxg@gk(oeMdTwC&dc;)&lR#EWdvB_W7-VV+X(5;Ccb z(<RbZ9M8LaLp!ihHk4r|r~|xIV7jE>Mzx|V)(PFYU<}GqEY4hHVTs?I|JW(egj{h# z5y${9j)E^{lMtB#s%*s09gHEi$|?AmJY*UNcHD|A<K)Q=CidMhPKJV*%zS9qUAWMN zy+Z&n7aIM8IFJtvVT2k|;ViDBOWm64t)Cp`ozIK{e4RiZ!k0hlo4y^<NGaKlRg$V8 zN!LXM2ZG^4Zj`wBR~zLW$ry&tLEuvG-6>pTgJ@1Y6ktBl(S^0dBv4o_kkUMigGaE1 z@;TV}l_i5+hFMP2`hi$dQjttz)ei7tDdbxp)}=ta$!-ls(rJ(>@Qiq<f-OjiDrSXM zl3zN;7A*=3Jye4&L{b*Q1~>i1FEofhVBq7egJZA*Im|;#SVD7M|CpCO;yJY&qN$|E z<<dI3q-+URKZFB4VATv10U{IwDdbyDii^HoMu9jP_i!LgC8Nth<Z7-%1x;E{ibh|= zM8<gs2BwWFQKe@(&1QO;&2e0n$eU>*4=lFiJCfLspoloI#UzZ@d$odX)@5BDr&-K| za=MOD$jtpD-(g~iC&ojJct!xAn0V<2*O?45cAUPzgUB&M9DF8ViHJ~epm#t-J#|-h zLfuOt<_c=eh|#Ch@dI1*RU5n)jvb7+)TMr~0x38P)}+;|ZCWD=r-f3UXT(I^1OTs1 zM)15s65$3S2~~%fP(Anp3S|O60EJEkKu;+U)qz<YKIm()|D<VRXCxZMHfWA8_?0iv z12Bw2es0wfIpt+o5-A*5`#gorfSr7*Xn%OewlqmeRU~94MgZ982GRpLkfS*8Xc(xF zI>^H~SQ;(ui)te2ezoHsJt&io1yT6J7(&AysDXvigFASJ5%r;ZA_pr#jzNG>R5*lh zHq$>b7`;_xOH{)Jl?E0e2b0A_E4%{bX$!h|h)RXSPf&^>s6i0;s2Y*OF>2IBh@~tx zSo)<Uh*bus`szN}+Ev0S35uXPyn{C^#9B3Ag_y=fg#s{mTZt?hTU4cj;S($3iJ3M- ze#Qiw%^pc`6E|^0&!s|5AWSpVgUonGJitRwRENAc|4l!rQ*+$P3*E*^%A=o7p#=5o zV^t`3$ip{$!#so|>9xc=xF+R6l73dm2F--Yl!FFJ#qqh`KT!lyAcbUsgAFzyHI78M zhAZ%l?Bb-tDs(BW#Dh`jMOEfP8|*+JPy^+8!#s3{0-+;v?JB!%tk3=|&<3qVEQQb( zt<fSyJq_(frNmKaiNU^uA#C5FghM;blRVfQHrN7sP||+5=qa2_S``KJ04=qBSW^B` z&LAZGl|+n|Y`97z-2}k89t1mZLn&>;C(uY&n%=z@<|^ju=J0HP3G1(x#ZeM&kj-1K zvV%9eLoEz}AxvV`j)RRJ3eM?Fq*g}An5rQ~|H%A^lR(YqYPN*KmMeOwDPLm5$gZw> zumWM!#AJTMg|)*s6hale0j6k58KKC^DB>du?&wHpzkU+HDkE$~#ZNGh-L^w5Ai*2> z0z<gNToBcv1dzvYEo7qB5fzf0JPJLGk-y#&qeR?GxTxAH#p<T-&h6H224;2CLKRd2 zTyz;Ll~tE?C-A~!@hWNYwhWnK4dc$kjy^#fKyN+dl>K&WGlasqD$AoLkpfLcbB-x4 z5m_7ETVwv2@9gD99HIw*Fsm?5DzHj{hyue@Lm*T^7}NqafTlYf3RUJ){)QV_BCZT` ziaFVE;dYm`=G8pB12ybH7)<E_)6}Xq{}A_3(RzfeZqmdlEN6)np#4OdK9z0zRgg3? zaj&T_>!!z>)dbL-${XN-A=Cnu;0PKT<_tg6;p%XiO@<qT+gL(PJ#fPwB!MAljyJS} zjY<=7egkf4VSeCc#(5j)j;7yA)3*LdTDd|cCP~}o#4wU8CD+6kdod}9jVIv22}FP% zR>ySM5HwW`t*x<l#ZqeiZlLyWQQi_g=}36;)eJy_hP6W}5!IqFr<t@u$qJ7th-fjq zM{v={Wwx>-Vu(;s$$+d16LYaM2U-B+8+`SF4~9W$1p_d6A8RxaBbstZ@DUr14*#-p ziaOJEtc8sQKp=2NpVVhqsD?|>|D~2%hI&8_aGi}tQm`|zCAKz(u^h&W667;Gb9#hA z0Ei7E^nnbxQxNJxDYODG)PvASQzAFeMc}G8XG9#I<yji;Mw8hN>1sw$9xIhw60`xQ z;0R|Z#36s~s$wbz8_~1s3@NzIt%lels|c06!pLwf2>&z)o0P{ej4jx~43H;$<>cah z(^U9wl4i70spNK&v;RiWN#+&jiNhWQfG<=fA6p4+RIj%{74}xf0X1E&<nvRD?soh{ zJy63nJ>~|Bun1d^>yj*tssgMWbTPC7BM5=+Awnq>gRz{dzDZI5bi=c#i~SleREtEc z#b68C6;<nV^0<#TwnNk!{{lDA!@YoYlY$p8gu)PMF;mo65@}j78}l*a8s5>v^ZaGV z&~+*VhB5htA94gMz*jI7LKw_ITrvWDjSEEe;rg0JPnf8RJoXE^9iaYeWv}(^V73|g z0u>xWX9s}vG9q^29XL?K1!dtppZ23d@iwv)aIy>jitp&QL^B*ouT^q-%!Kq@#3V4n zeFp%3k3t_5K?wwb9&jj*;pP#s2^J+c%ci$<Gj~dUPr#yPbcb)4krF-lf*RBaJ)rSw z*G4=bm$AHPBx{=yK?$|u7g24vDz`Qb;+^vxi37Ur$j(Gy@bX1a008oy2+%+ezyYe* zWK1Y^MM~qj%!z_)|0;u*a)X~HWkmQ&vQ2$1L@Y}}jj)9{3?_Fg7FwK%al%G@*|c^3 zCW=4zKBF0Jsfuab_S>e%MAi639Kq0;fSds!4RC@ji~=eAI8H`Vkn>Ui^o0CK*^zIA zMwL@pzQ#v`wEDFTSx`qQZDk#3PK2R|Mu%AS!i0XB_DMKkCbPrCjMKFq@i^u5imR0K zsET=Xv1y3H4!*)?5kVa2fDZ6L9Jm1=U<4fmKu+r0PGp@V&qPm{c$lkqpnt?sg$a|p zl$hhkPkAq=RQYqXK^<^IKU9ZPmkuam$&-6XJTxCd26S0u&=Dy{Ri5`)$-@L=tRB6j z^Q=d!FtDm?{~-e#3@`x0D=@+euz(2IKozusd9~Od_y9(L=mtYzUkFl9R6B+YJ7jOi zdcPbvANzuX31_^+HUt1Pyg?NNz=e5(KZH<J6NjysX*D?C`I^Nc`b@?#2Dw`-E<3i0 zgFK5ba3&XnE?kwVEFR6jLMVhm5#Rs{TtplMfFS(A&>P(!Xu%P}%GaFk$r@B&{CZXd zdsQp^H_u(Iy%EG)Hki<pJk^6Cw1En>!#wZ}fY6Els)&cL2N5yF$sVGJ7DU-&yW9f@ za=}`PQ=x_S38R&QF7$UD^a0?<fDW_(0Vn_gNPq+kzyL&m4h)?Luz(Kaz!M0;4+wz} z&_DpV{{eh$KIiL#(!&Zu&cwMiHgQnBu|IhDWPNcYdwy)#MUz8#`obPK4L^J(RFve| zV@T+{M974=NU%v3p6aX&X?NGXk#DMhIYgOILmmu%7}P-+>_7vQ0OEH*5ClOO;H0T= z0{+E;9kjth??4dj021K9;L(5t&;a@y0pRz6fOq~yc0*x3#Z3>Z>2GSU9{LU^dWA43 zK(K39uO6Tznbffx=kH%bhXEi)bU2Y>MT->u`NIZG)G1c1B8C(>l4O8Yt4^I##mZK( zdjHm4q)3q9#Q+aW=G3{9XHTCuWd^PJj~={w;T#M|p}_|bBSpdlLF9>(E~~E~ioy!f z|BanLdH#eAtHeZ{P@Fh1VpV5HkR3a8Nbo_U2BSWGNV%j*kKVX#<H*4bTJdLL!-o+k zR=k+;&W1N34wgKba%IXuA2(K9bQ{4>LlCOl1`lUW%ak*MqqgeRM^mN}zlQknW6EFH z$}ybza`#Ze6g3AIj`{S&dfT7{W3+sE)nc!pmy-TUdZ_@RNZPRz01y)sZgiD`{z@0b zV!D`5GE~B?j1g?k$a=<%nbDdr#{m{Bb9jIM{{ajzvf>CV&_Kcj+zB3k$O)hxXzB=q z8g<5TN1n`lI?$n^<f%s&TckUwv5z2ng_LH%iHS0rc(W+M7kfI8FMsF(ry1zN|AUSc zQd*&|IuRing)4}*6C@(<+<4_A)^^-c6kW(8&#GcX=|h%W!f0y;H}+sdmU*CQhaQ61 z`G*~H#))S?3}I~3%{MjEP|i7vgEIhm0$`_`dfKT2iCWlkN1O{YW79M_S<DC<5LZbh zmDgkoAkvZ|b@Zc^T+xLca4cg{GCN^hN7PYCE!EU@<dH|zRBaSxy6Q-=4x&{^QbHs* zLb4$MI$kkFm0wel&eiI~8-<in$n$5YdSuz8mN(w2!Vo@knP(m`3Hs(6a>z-joN`iS zGoEqdVTYYmK}}a(|4wb!-FM-QSKfKweKFOH{vl@|M%;izoqxnxM@@D_{|(99lIW$^ zA$e4DbroM%0x5uBd2)0%+FB}VKXc<vHQsd-oO7Les3FCb+D>`x*I$85=@gMz;2{8+ zSqKTMlN?=A=T(S(rIl{LvDTY;{z;V{a_FJvk4Myq77{_Ev3AUQzTrk4Red4|<gK|* zjLxsYo(L#7+3|+tJ>c-AFL!hk`=_uS0>?vAOgY7slUbRRB#HxY`DK$<sRkTE!|wXO zgiYm3)Qsq9#uVBtCQ0v+ObB3wi2jJE(bxR;+mw?`>2*(YNhe28Yl)`EA8PpV1&~18 zc*~MWzO<GmZoZL+FLNj2i!Z~04?ZNsiFeoI;*mEMqJlL;_s&!a|MkY5dJ0Lxkaq$Q z#~*Wjr-xLXl0Ws{w*OJ|7gsM;#i!R!VtJKTbg5@>LXGx5{85G1?EX<xYbF3z?na`W zoFWw?kwgFr5rElYMHMN7)B_<{w^JwyXwXv?s^k%la<JnY;%Eoz#>5U^Py-NgXhRZ$ zPzPar=^gYK2nWAWrjZ;he>Gg!{&1MX;`xVkW%|cElm!jz@q->7<k&in$UL9ua8%|R z7dWutv%mEuB^P5EDS&~EaM+KD-?O1&!gst>)x&YLfym@WvI@G5q&(y)#mXS!C^^ni zjwxY9D)tnvqFL~Q@_>gs-oZg{d~hDqqlYhi0f{cKAq+`4{{%Iv^$s!7;~U+82R%{+ z4|t5rd0+HofVwEJ`iT*Gp`2H6#s!gkjiVmpFhmu6p$==kgD70Y;PTeN6H_+PA&Xj4 zPxy8zR`iG+^@xWpS9L+;eNunPGuIfKL5hf-5jG@=Tu4Gx3fRaBa3z@|=t76bdSrxD zsp{bopBayLz=Is!K;1m};)_}wVhB=jLmlcs4QkAzh3$Z0IaFsTW)3ts%-bcY_@YTZ z$|H#fEmeO~c@uKL(-%W91U39Ik9cInAIDqFE*+wdR{af}C28MET7eQ<2ySEyC72Eg znwT&ub7bFW4Q(XWCY3et6!5FZ1~DkA9**mr=ZptD|5l|Zeq761|EPr_ARz@N-~kV6 zn}@R6(XE91LnJ+n=~sJFFo&M%Ti+_`Slu-oGj*mQPZ)<h+(C|dBvW}{)FB^fQjAuV z;+Hu|$;wzk3S9_JReEG1F2Nes`{}VvKEqp1-E@+a*dl)Mu%J*$XDXtSZd{s7rn$7` z4SHD1T#zt?8gu}MM?6w@^?1iPx}gqrK!kT(B}pd}J5aQivy}g!iEqd0k9Ck^w-41! znc6WuT;L!R|8U1!MWsoFUhtz`H0QZ4h>a+kOk!08+{z;Mt1OQ5TgT(={&K5W<SA|) z8IhkZTJaGez3C*<q3m2a*~bg^@Lki@V`S99|1H_}vmLd-XAq9S2VD39xP9qHKO7R# zkl@yW>CInp@mh~+JmVS7=<qYRv8TBf7k|xTs~X@ijv`Lar4<f<7Z3A29P;J5=KKdX ziXkyo;H-cXi&!Z{(UN+&^qG95D-JE3lN>gLp{{7fuLSreM@gp@z^KPd%{!{gBJrF| z-Y<4VRT0^;qaS5@2beMugfJX|4aE2bgb4zVzrbUBs>IXtqzjKE2XB|;vTP~qK@MmD z!xo|tMJRR@3ZHeDy~S<JKgKbTObh`R&IL;SU@V**Ublzgsz)(6A_|j0hgKoUl;H3M zlc1V%&q_|-@g@RaT3ypkQ!YhI%yiv^{}r{!rt0Bi{sE71XwOXLLu6axAO&1xqZ~A8 zCyi)JI*8<XB)DyLs7#sVm~^Nd&46zxsyVAws81B6_=Pt9p(a(EO4~@@i3QD-k!@fy z4tStOKiUzKk1@ufoi^G_ict*dn1U3dW`!zVQ4G0_Q;!X4G)!Nd%WIEhrX2f6F>HYn z0ebgE^}RJVRM+lM>d|=)88#4U^bcGJBTFdWL?Ov^rhY)!OxX4BohPoYUE-@l+aPo( zv{}uRSc(-qa}+ed5zuwB8Zl)eVm&OOhD`KB9^+VgyN5G!B4-v=Qv=60tfC8re?x9X z8CRGcvdf&4WTu-P8ODEgH#>R!|2DZ<D7$HjX^BJcc_LqRZKwT?p%sNM#MlH|_JD_K z4J6RA?MFwU=hf$}9otO2yQnm53sRgyvMS-}N#t8!_-*4KR8Jf--K~>UjVoXO@WvbL ztqyTmNMP|uCf50F-MsVh>@i_cJ@^8Ae=JD2DsnjL4@>#s-7g-W22m++N?)FRJRFb@ zAAb>-CsLYAw(~Gs@FyXOEWN=HFMkI?aF@F~Usw5X0_i`>QH@j--6OQ|?n!kP*k4p* zociW6_A#s1vM(o!EMJr*6V$*G5`rHDu&w~ap*Rh@?nRTfhjbd^*Oo5%+AktzDwz}o z82X0Cq%0Lu0vM96l<sHw|B$D)pvO$Up{f2sTU@6OW*`tUA!^3tAFPHQerE&Q#PTkv zA+C(jhUJY`#=DU4Z&2zLI)j`r2mrY(RmzK|_Dv_uMI4gm58j{|WDmlQEYsM9#2V^& zj_3lht0B(I-IS>PW@>z};TI0>f!f4TUL&xYfj9gvVGss!B(KO)g&baR9<*n5EFlgW z=@ERvTKvI6tY(jV@Btl49mt3jSfO)VhHpxOVnkv8LT>A_%+Gr7lt_Zc7|OX+3>Ti@ z5E_EmGSIjLgv3N?>(G$t9ub#j%6#Ul)=1Fv2y4|~v0bu^z0BoX+DlKYMR%&f7xq93 zPUw+r=N+^qAzZ8$|Env9NO41|A>&HnuXu{%aze5Kphr~avq<N7I!n5~Fs&jEB6jBt zyI~*#K@GT}9)_kNJPU*TF6(~rT}VmS4hpe+usHa_ID!isszDSQrN`Q2zFt9Y7Q{CU zq$CifMQ{T6#w5U`CIIBg5Qd-)+JF=Ip&i5o8qY=Is8KQCW?AH~yE^AERzVb+AvctT zHwMxnx+m2v10uA>V6e~^o&Xa5;e#-vCJV*3UIcCq#8WneBI)ELBaR<;PgF=zlQb+8 zTmci^#ExD;u5OPCPpPif&=%>%g02xk^2MF5g&r~i65e140wEBZfgSvz9lD_$@2m%% zawj&8k8p7n|8UA1eZu21hR&d;d-$UFE^l6XutR2#dcvR<>VX?lE>Ezl2fZjPn@KG9 z5${ef4^z+wcMZ(6OdiH%$b1H}U_>_FCw^MYD;-KR-R0p%$)zTuV9sQsh(;a^!4RGx z6@6hQ=@L&aBrnxVhsfz4K7?mL?~WAGFmi?z_|FNC>>f#J-;~I=x&e^zshDQZ47beA z+C?8XQ+)Jm%RF<L){za1r$aQ$vOL5V4sMPFBxg`U6@-i)Lh&=J5pm3kGD(py0xTTh zK_vfy8Y1Kf;$RZE0k~d^9qf!a*{+LHqZ&e?5>G)o!0Rv~rvznk7D?qE(eroEgdS{x z1_0%Q|0bfLF!N2ub3BQ2Ud|I$GS3LrCo4Y=9EvZ83TiBA%FA#|Q~>cC_+lQYp%%g* z48|ZAgrS&#ZyaU|LMcv%;!PudK{^}-%4j1O15-JLOgGvSJ!uPI#>5Ta;NHvz9BQkf zZm30F6haZF6@^N}S|JrwfeynhKxCs7ZX+XNv<jPP4T%Q|BO?GFj3DFz8jMuU_<$Iu z=Ou&<lc1CX7mHA00^@)LOKGhz>g#=8ftAdVRPr-49U?HG;SHt^(&zySS5)WNl*A&{ zGK>!+%3&ko%Qfy)KvdyGumL9vWKi40Z3e_e9>OST%O8f#A83mhAR!2<01vVuE%Rg? z|4b4>zs6in)APVf4iO_I?xq>&q1h^eC{H6#@<h^PAeKBxSOp4XfDI|#l|Ul(DU&B7 zy3J&;Qb1_q6;Lfl_0vs|2TzJ>T-re#yn&Yf!51vSE!^M{W+`9Jg;+uJ)d&Y0E7TGJ z(>dpl73|9;Tnbcek3UP%9dvLH_TXRUjUH}-ds6kBgr`+^>qRGZeBzH3d<>2J<5zm* zr<|});e|!RGhQ6Dhcqc7^d)sjBNGB)2EyRwu*GVg)F^3a&vK}TGNKyJ=Wn?2UJYZX zUZzV`_8dheRLL`30^{`z!5_*2kRFayByVe6woR$gFy+>F>Su24M{Z;dQs$FR|5?H% zFvxEI6L7o7PUbcM1eX*S>Ou45A29M-7{b7ipb9eKSy_x5q!3*AZt@cAa5>j^lF2BN zvzsJEZyAGcdPEW<P#7!IFzXhR<Ut(j0TN_@3mem=GGbg1H-9>JcX_vWeYbE8*LPqx zhl~Q_2JTjcgMCoq6jsWZq|$Xc(@))RT49s7ii$GN$&X&^wXCHbxWO0T;Dm6Y7Ho$e zxIx+iK*AEs8dXPG)<M=BXgE60j-a!>D$vW&F3XOn1sk&v0ztMOtoRy=hSYaW-}YtQ z^sf9!BT`CqZ+6FcMijCLL?O;_jA!exugIPW9=P{f0-#9U01et83_z?N|A=N=u*<^s za*Vox6t+T38Dpp9D*&278|2}BRZZ{Mma~qjGpfOQ)S(^5!C;@44AHk`511Asb$>{4 z_;5_oGF3QE3djV<b$74b&NDsT7GBP3)vha*WXnv@5|eyk($wG$5^+r0L0gI@x5VmS zJ9Zsfg{J_-jx;vN_>VLw;&Qjl0#juk;DH*{pcZ6l9<q#-qOHif#-Nfol;V|%sInSd zxNiWY^H|{(zG1{vG<j+$hy08b;~@Ylse79N62gEA_MjH%!5!!_9L@!-maKd<!WLe^ z^DeeA{D#VOp=c_??<PW$=wT9&U_t_h%hE6akC<y3S?%IgUU7(*|KaQ4V7M`^v~P_G zCblembSsxW^I#S+97xYvn!ym>Kn4l{7bLMB#Nn-+N0BegIOzf77)TXtRx!}16<Q&a z$Hy~SPxk7;5ZZv4-C>h`Eqig!f|prGmss~MM4lnoKbAyKK@NI(v|b2`k%=dfu`AHH zr5$L591I~0m|zcZfhOXC^fb4VB^K>`>q8FCed_o^#p6W4;U1lEB1ow*_uvrbavo?X zAF<a#QyOG2I-#|>nVor3Qv(?2bea((QdEYf`P4NzImuSgpaTFf0!19CA*6$V4}?Kk zRA)54D3<G?8yxFlkhhX0xTfLZTc+AO3zL<eVF-ZIlD@U9|17#~5xRPfS`U#rsju&) z=%E@e`IZ?&E9FLP`!&7Zc!&Ov2m8W4{vjKd^^A$(s_-K)AOoS9SXn3(Z;~)LlJHmT z3pXS?)f%cH%*GeofWgGUV5cxVzv{2iE3o%R+mQ3g9QdiL$+TBt6gZZkcPL`H_@yqB z%lZO#8^RYjVF$t>4u}C;xJ8Dp7gXBthN;x(niD{jm#<c8aCoctd?+xOK@F$@(o!uQ zS9N`DTV4WNQh|}Gqql0GPmM~AG3x6SvS{6S)-$gSGl|Eex=J9#Vdmt48X)0>>Od0; ziIUDFBBrtOlBXTb2gpt;ib<RErq8En#C{gaOs?t>|I~mVUbh|0umN51q9yLVr5Cs1 z1&gEdZ_5E3iXm1`>M(W+SmsX^=8?Bz6sX(Vs%H#kfnw%{#$2eu60)QaxIrW%bCb9# zzg~oW@8#2~)H-UEnzWXh3ura>NWW+-C<lUMx1s8GR=<+lja?kDk-B4y%oo>zz3K-X zz@dFe_b{?{n08q-NfFLzd&s4BTIp(e4q3m%#<JK!9MaW%4Iv367Y8Gg9QYa%b6XzD z>(f#S`fv(0`=j$*;T85IztE1T>H!acvM=btM=xk?OAMCVoL=JFulJ|<<e9@4BPCEG zi+l)9@eu_@@gx<R6gjASzxNHq*B9Jj9;k*K|DdOU`{UA?%tLyl{sM?O1tcX*B#*66 zMWB2S9)TWFyymi*n+3hLV;u}<eJ`JPar^-sszD`a#i@CMuP)inYg5jTIxmYlUjDpP zIM^NFVQ9{;NZ~*YssIuOi5}jeTkunHcl6TfwI1+U;~=NI|6|HF@dSky9*POo|AF-E zm%UF#h0|RfXI-$nsF-BU2ovKZgp5-E@sTAKB2=3jti?hM3<%(W3p1*^jVY8h4Tr|( ztfi>_Y_;R+>ozc}AqJKnz?~ik8oAZ+++jW4Q+^La=>s{>Z+v1yrMlZ;%Icl+s562c zI2azZM-eljHv_>J&QG0V$l7x67SAu5|2UlJH2gn!W>38|Ax<4AJA+(eR6Vgi>!Y;R z|16mZqUGaAj&#D-gnP(%7EDwAvEf{(B|P#bN*oF_q?w=)YN4NEi|%Dgsg=cX^1E+b zM(L$v|8Ugl%RJl%iR9N@`DE;`5kK({>H|CCvCxQf{^}G$0Yxy29En>G$)4twpLvcd z0JudSti?cS5EH6lYPR8DGGagBI5pr9usr=mUS{%r=;H;yA<q7sXxq4Ld-o%Bm&}DA zp2K9WJtQJ0M4rTNH(6D)PsRWufWUzS3mQC#FrmVQ3>!KmxGti^i4-ZqgD3DGyK&>% z`SS<OP!Ke-n*FOsZ(Kiu>{_yW{}`a6%$X8DVzad>04r87dnR19s?;i5#p<zZH?Q8F zNA<+HlgExGMS&50TD^)DqSUQiyLQbAHmul&UdzgC8805VYPv+JV)g1(0968W=2Ug6 zm9B5~KFWg{)vVyEV+$KT98+-Gbp`2dV^^=9w_0J^B-u32ol$b+{&{W*b8tm^^lrLh z1r#wupr?lFst1l-Jv@;9jr$z<tLoigMf)DiJGgL!o&$J3jy$>Y<;$V|!&dB-DN?6( z!hOXmm8n<Mu=#t(JiK`E1pf^`kA7hB@yiEBrq}dcJ$dSI)!D(PndW-r)LCWEo<F78 z^2#Z$xROdLr<{Ubf&#gs|I0X<E!C7e>;RZtdKwaEo^cp{2qJPBZAhY6zjgIjOP>98 z5;knTB1()hLdXp`_5AZuOMm?p5sxQMRbr5cRrRAwM~UMZe2@f@gdw@i(+)e|uyfHx z1pP(Tk2}f}Pd&x7a+fL&o@a_F39j;rE3fcHn{D!}(^8LbmL+6*6D9Uzo^|f&Q=T)C zCY5LPxL8f0g>uu^NB+p!5}@n&=%++{PWljGGvQg0kB~}a<UI5EBTqAhgt3Dq|G1+W zHv(aK(1}}isSB8;EVy85=K-}-E3NoLp;Mlv^_QbwQM#L@jA0t7Sy>WBY_rQIJJF`m z$|GQ8*50_~j&hb$|BjrIIty-ZqG1`2K;nqgk2?KOQ%4eSWRlH1?|kzOm+`Qg=d1O^ zTA(U;F__+hJFTM28;JbV%|DOM=`Ee%8fGlCz&%VcvJzLM;y-_Jt1xnL!s!yX()w9( z$)Wj{kw)Zr>JBxvs9~8f^tdyRJm2`YD#O41C15e51ZAtO!!6hfDY_JK$UDAj#Lmc< zN^0_97b_bz#UX|mnR29MeH>||F~{}Q<W)^JhaQHQ(Rc888kx&gR1pX@o(3=uIRVHs z(AQ#XTu(W%(&aCDWtREYD8<x)1UT5dBcHW<mp#_rl4l6Hvs2Tw>BpJMgWTnne{Qi? zdavk@aqMv8|7knE7=nZvcu+&yJnD4Dm_Lh^^;cTpsLBehz5|Tdm=7Aw$OxWL1I|bD zH9RrseI9$cRL)ZxJ?1*kl<oB-PtW~8U1eMxWAC){jyI^vQw!^OJVFoobgRS8?PjG_ zPd5RyGMB&l>yKDmaj~L`R=gq;C-8(TpkWk+QN(Fm>E2bUcc;WSuuc(!paq8|!3lm& zQq!ska<ava-Fa#pkf?(U{=hzzc%y09(_Zen#0^sLBt83E1u5bZfl%ne6U_hzJvgT^ zZHY#MJ-Hy%h*%;cD$!v`+#m<d@-b@FO&nP(Ar&4$jFY5fVGNX$@?zM#Q}}B^hA9(4 z667yk{~Zkvu_8q?>Jblrct%f6EaDM=l)*X*iAYQAqfGQzIc7cUdlw48M*Pzbel(*F zVMu}`h~baObfX^%oZ|wi6-hAu4tQ6ILjZVizfzP!AZ5Z8D~#5LI_N@_ZcHAivV}50 zW(7!>lBMPRh|7xD(uoBTjd{i~N%%3N4nc5(FT5cS{-}g`5}}_a#rQ9**ufyAFa<%< zI0{`L0tLk&MJs0Y3vAFMlI7^4Zgx4#2qNTI=nPUW-^tE)l1-hV+e*gXv5nh!rWQ=9 z17>cd4s|@LBF=2ZX#f~atNbAVcA$d^Kp6m1j4}X(Q$;pCfdfy7LRX>;=QvZ88^OqP z|D<|^Cp<}7vI_cUOB0EmH~v8nYCM9Gn1Dv(xWUC2?#`e)@f}#)V1j{^GA985$}2b_ z15do76r>1BDLm?rC~6ObD6MMuRBF=dS=D3_j1-Ih(GG8*#2=$*R~rl=4SA`fUK6PY z7zGkIidqvU(-a64R=|P)NM|5KGn^4rISMeTLX@@;XH?nYm#Lm}tBiHt<Q@yz4>h)q z8DbARRyGfMki!>y2tyD)funZNgB!NnT`F8*ic=&=craP0K!7S#Xuic1x~M}DicyMJ ztYRk}#YQ>g_}Iw`H;`GqV3vkE!468~t7w78>{1s~U$pBDzVK8ezY#+OaS|+^|2znT zbioK2=;D661<EQ!(G2e#mZd{Pu6s)s+4#!WIPV4I)gp7*)HNd$NT|XaexZ(f%!3u7 zcnd+u7ytw-q^_?e2r2R>z)+k35la>9z*;FFjX<`(90pf$qt{^~az!~j8(;a_(GP$4 zA`?`20v>8%3t;Gi6r_-?{>-}y))FKRZm=s60^kIJi19$AD25CW5rEvjqK2mE;SV+U zn-EKxg6#Y-h^I{4hGj1zmh@4MT7tSyQNs{n(18*9pbK39Lq@bBh#3>If}mbAS9<9~ z5p)G6R=ha?=yl}_&B+xk3mQFEHtwK#X|YW?4IcgIhdBI!6i>8k27N$t|C);?imbHa z6gx4TZFPYr>6jvLqU>{G0lnBmt9nR<p4zINhgGw@3A-^403w1A1PPou&8wubP$`-a zPU!WUdC6uUj1a3lFQ`nSEQP6G`K?z=+eFZ7H67_W?TQJ~Rn($~&vILg9TIZ~J(z?j ziZKuxpQ71l(yLzm2PRX5qR5{v#ZFT3FQ72{+3Y=0w*MU#Yts?ny!0j0`caPn;Do88 zctx5yai0;$V49o=cU(v@@22KB6=77xywi*aBiyeQrU+x1c2XBN)&m}|gfi6#4)d(Y zcjjV?`Sc(QD_e*XO`>eLE{eg3Q3YTIL4ZOhj8=^3h~jsmkV`T0|4@Q3v_%x7R>hll z;;&P_F&^~Tu+6_-DS`VN>|E8-j^N>?hM!_^&2B}*1+vOK)S(1XhXNEP5rANfLhr!{ z03)DKgd%vNElEBI)>UysaDc;OE<trI$qspgh`o7{PpR1>sSBL6X5*-7_dxWL=2z4K z3U=55-A_+<8Pq`!aT!IDZ57wl1n?E}QBEu?kNa3pKG3)imsh)8j9<)(qChziT;84A zQj8+7KVPLMo)3McUOLI6-19)jc#0c>)RJTGJ=u*l$lcS#`yMts&-{UnUx*RMrc6aq z2eQ<q#%S-On8ot-J_=HZqS*>A$QWlI84-~diFJGAS9#*s|3C)ldwz0$HvvG_r(;Fc zY|XZR6gYuGF;@$r3Pdp<Amw=Dr+|=$fV>xi&GLJXl76*9R6_+<`*UMJQ3|H83V0!d zVS-}@v1c1t6bs{W?Nx#?H-f45gL{%Eq;Y=r&<r}keltiHeAQ-!!5TVf6d=_o^iY69 zNN~EhdstY0C(;rh0S-ync?q%;J+)nj(Nj{$G&-VKB*=we7lhdMhD7)qYzT(U06bS0 zM!RuxVFV271yTbyhc<_RF)@fHScgqxFN&8Yr(r9r<$eJWfmbmmS*Hr&lvq7TRfh<6 z#c?(?H#wa6Fp-r^^6(0+;4eaR9y{R*q<}mb7FnX0|Ald=OR~5jD>Wx<7$^VmB{?yP zs!=8h@(QF-4U3l?%=B`$2ylg{jC;g@f8ixMClnhu98stj;7|_W!!%dejM*l3TG5Rf zQiMOWC4;hX{Wly!p%?!^4$Sm{au|-&R%r1^Ws!0b{s0f@CrWXJ9%96SfPsu6MUMct z9-w$N0~sWq_=#de8W$0ULh*}+ks!753bs%U33MD`Q*#Iza|X#C99bux2wB!54{M=u z)W{o<7!=|3Cdi?Y2MLnP_)alNB3-pJn8b*u(S*SfG^fx*7a=n7Ac!>iY91LL3)vw= zIUEWZS)|b=U*dkMSVmR%Ag=HY;J|V(DLG21|7u#;M_gGf$>J!vQxDaE6XwN-RCzzI zQBL;)OHl@vGU+*SnM4v}J2$a&M710KA`~3BFwsVrvj~`hd5aSBh48Qzq3{Y3DHdi3 zRqyzCgb8!i)_sy$n9%YUiZ^4yL54fgX8}ohmMM?*#EqgE92b)!`(g`tF_C8&76(EX z#YljaX_|6LnSazv@l>0HmMrIImZG#1)^`<p$O^8Y7kxu5kQte~34|cXob~vOci9Y~ zuv-Xa7`!zUMbU<E`J7nhm9<ns$JL#M@ts?tDLbM&-0&7zH$!1@CO{zyfB0qnhDYOR zpO!f_9g}%F5f^o#msVj^*x`z<bTRj7|DclTg)T8I0%De{08Qv<6|}Mntxya$QiafR zpcxvNz5!)kmXFl1bgbc;5AmM8^;?=)pBk#7M0qg|2@cqS7yM`yeTaDJ1)AKsqB)9? z7vm_AR19Y+qY$bP|7SF?aS?K&oVA!oI?ANYh?!dgA0WDuk{F2$fncpk6yqc;+apL# z>ZQtfF)a}pvBDE57oiNo3cf`xC`y}O>ZYQInk|V9z(Ad5>Qf7mAVOg{^{@^K<Z5pU zsE24lutBD(AfgbuNvRm0>ZMhI>Zo)0q#$Jzbn1j|mVt7mKY8&Q9jIJ``KX^7f=0O_ znn?<8fn!%1i9qod)PX!L2~*<)|6HMX9H2_8Kj@KM)2Gnk3hx#)4hk@6vLL{)gFy7E z9}!=*imdg8H^E_)eYy^jQ4DLgbZ^0N*AW*nQlu*vt6kG|$C|9)YE_ZpJ@6r}hXIQ3 z(XH1KZl@3<yQK;;A_{3%Bk<5Tf`SsTI&)a2kZw8={;(48KpHB_Dt<vP-(ZA0k`-Q~ zunWtu4ePMvxFyOX5704VHv|k9TMV)>P68;D>+rB23$hB^VF4QeX+aO%5&$HtqqCZD z0gy09be|vd59-hki2@JfFdsRSPI1~&^pF<!;v&U>4L*btGs`(_Dly(UvnO#kUP=#W zClJoS5B|Uxx@n&oLq+v4{|S%)36T*F?*K7M<QWLpfjUE<jXJVj7ht)N3&o+b8A=-R zkq(}u52$bs`N%n}(w!4Av;Oc5br1lIBn6zH4&z`*0jESsini~yE#;sN|Ii2lFb7M} zvMQ=O;Ls2001Ery4)A~uun-PU+p)~~LaXu*;_wc>AOp3q4(|XD)Sv_009F?A5?GN- zmV~s6tE|f!4%RRS$50Pz5DeCkB=m5g+yV~Y5CE8P4gOFJ)esK*PzmXvI2zNP*`pb1 z;0ynNI^LjSZg3Q|i?~Z<Bu3&#QWg>Hpbp{S2f4rw+RzD$01tNaw$J%O;)D*p5D)wy z5aU1($#4zzfU`Oy|C!n28UEl70pJF;zz*Kf4jwDJknjfeunjxgM_XdPfBBWj6%hyP z8OJaO&>#=i5Daqg6#sA$_+qt|sd)TA51YFV+5m>&kPfuqLuXT)#p@YVL>uZrS^*Fl zoZ|~sfWWm27NUy8TNz^Z3K_E?2mfFV+dvO~pa}thGxuo|*dP#>5CDp^64;;(@?Z?k zpm<AKz(C{<?eGu2pa%WW4r<IaN<$BDfD7MnKFeyswAiNa^$(#-2%4~Rj4=yyAP?b? z78+U)%v%rI01k$P4cNdB>2L{(gAH9um>e5m&F};#0T1P3NJo)bzCZ;{5hX@!6?&X3 z9mXoeD+jZ%{}}-=3n@DeR$`wYArP9|4g4DbGt3X<5DVzQAAWkq5@8#&(X~i&H)jVA zs-gz9@U(h+%BY;89L6F65Dw7b2gjgc^l%IT01aWBq4op7mAfV4G|v2hu+SWrEx|ZQ zxXJIZDAo2CRAdN-@D5ju6}c<T(i37|gK)Xv2igEXt1=J)RllOC&gZZa1ObNiun(|M z4=WKE>a3Jsg%tlV1hDhQpg~`Mfp*k@1CCL=SMf11p|~T6z8*^t>T3;x5Dd{!9PAJd zi=YYGkS+)M5B!@Ho%=r%-XF)uu(@pJn#(quyGZWMEo|<$TuZ3jl3YhfK4BP}`(2dW z$vu}8rJDO)Xe6Pz=2ju3!oI$Lz<E5*<NR>m=e*yq*YgFn{ZB%I6?)v*9`W<n-8} zu_e6`<ll>dzZKmBG*XLMYBIaRj$!9Y6*q+GHvdLGAS9)fg&{sP$ZD|ykP8y*0@=S^ zeB5|OwC0?pp_v$<{%=_a6{KfSqQMU+r{jWG#yPgep)AqxGu)6rek5w1=dvtp5k+~L z(UUR?_nLP-{M#Ai0$D6hml!$IzD%<(_WpyhZ|n@vo@JkGzRx9qp8Yd*+&y>KnX?rD zN}q;0G4k{}L%{cirACwA497Q5fQjS%XGFSb7sz)XW6*`iAN0C&8aa=523RJ#w*C*C z#W)}yIh^zz>@ZPLoGl|0*C)BFCOMCbfh}L=A%SS`ISy|W^E(u!yn0Ii`^`2km&Y^^ zuht~9>yWznt)ef@S8KT*20{mQ>1S)g6wI>P^bFDopi>IO%x}mc<$M}D=pEqhYCUXQ zPK261Uuq6{wg>$SC&nIf+1qeNIdkUDqh<Aam)f6jMYjyY0Ka?|2Yo+%8)s+GrO_y2 zE*pa97z7{sA(aay3K!o;!@vhFjeTEWg^HK=6qrT{_<R}*-`;}L$xU(Lx#>n0g_D{K z(fGGF+TRQ+?-xT30PK`GPF_DA6%Muy8YeUK>wcc%S8LA76He$cZi`8Y6$w@Y%GssB zYQJ+*2~1I)kUh$$ZQVEasZZVv-?oB7eTqj-Okh6v=3Mi<`~=7e?K9Pf4CeZ@H_qO* zv!-!b%6V|bc#r8_F@1$&_uNm~dmIHqw%1_oJpap?Gad$}??7H<u!a>wmjFxQBU1&< z@1E*{zfja2PC5HsHWsZWOYaUdjB}nbxOa*nGrALu868tMS=alk0vA$HQ_vsj3p?GI z7s)UIODJw!Mg0rxoE~()`0dL@&gEjL20-U%V7>J18@W>Gej_*=2Hh!Z-lJ`=QmU86 zO1D+|Jdix@PnAWip=zR#x3F$U_y@%Y18>Y*={xc#JCH3H=jKfqYHEx(<~;T?EXw-F zvoc`$!}<TxS?_kNpFq=6dYhD;IJ3vWYKWbi?!B`LJFK73d1E={y94`p*3U4&=+ox< zA4pmw^syQJZK!rF%A}bU4)Eo8Df0&A981|#U=7gaT(W9$O@;kHK^d&TBp6_I0m^!L z)ogjjMDDiO3Fn0F=jrihpWKYK--D-Jc5JRZa&i;<yz}|Qs!x4YI`I+I6FM>jGy16X z1GUc`<u`juIP@jM%6I3zeP>O(4|qq<SM71)t=NAO&VS!#$J1W#;9s7lIwGmtAKpFJ z`uR&Y?JNN&|A4}IfQJq@4iq{xFfj;s7IAzdtYq6x*o|{+(xA6Kz%n}jKFgY~yLA!~ zO~mP5x^B|BufX&Uf9ZZec8%vgn7%zwgjY)0PTQ@?kKDxE<otw(_*96!`?{w~gg_y% zN1OCrAjq;%D|~;to_&0L5l7~duq=0&STaZ!RP~>0Q*b>al+OJrQzPCWM1eQ#ox^tK zHT@6bRepVHSnMQ$c;bn_pRecy?JXfZu5sEFhc7w~In7WvY^$s*EGrzRN^DcFxB9P| za(%N1IS}G9{rmG4wsgBL>HWZ+no&wa^NuPd{#S+*sYMHS)QojX%c|Q~QdON(nl! zdOZ4NX4idyf1}-YZpTS0Jo)13uirm}-%7n>oGEvBzK1C@9-OE(Z@76ub^E2Niqn@v zzq$61pKJ5~Zh6o;mCs-O{UNQgoRjC&*2iM3DSbGK{n^c@wV&hAxV0OzX~??ZlcBo} zWIE)_`<s(Pe9m6;C;uINpS8GiN7=tG?tSmuNFKtM;qT&Z--`S;t;KkXi5lxg;Z@eL zLQ##i-e;cl7qH9yv;SQw1XzicXEb|fjS2Y`F0&#zZ0)!zp#5l)`gc@qzo7f;2}7}8 z<5_D@VxW_F15_+^^A&nw@cjFz*#{OWQEj{ZMF26j!6LxIP6aY_GN}JaRMn1z$&;BT zytz_8?_NVCqYJsDKeE;WspDCFr(;$qQ40C9@2^p{@;~CX2-Upy4*a`i5Qp%C<j(R! z;foqo#o^5iaVX!yo}nw|$|2+-K<NvxiG*@=+2A8d4dZv=4@<Dfzy+BXPfrfR%8~TI z+1(~{=X-Icw)K@Z$`-HvA%l-yR>03NU)~8>@#thaW?9@Udpn>~ycunnX_3cp2Oh;# zFZVn$IdIJ>+5Afqf8-0aZ_`G3$nUqIS8Hyo+;3Jgdk3I;89u#_c?!N|e^PybzMt(| zX&gAW>*pFTeE5BSG}!%><?9hg%X;^9*t0gWIlI{vKMXN!g?yaP{?tLCQ=I<}rPCAL z#>@L>Af&K|r65@TPrL~7LZNJ_QRjvf!fH}R8W|-o@!)R9%i3==N!!1hr4_S_dkMGx z%J7xOTBd|dJATakS>#!DB;{KfZ13b(8FithL_|GvSk8yM+x<8)U3Cl9mMD~jp!@x0 zrH$29`hR)t&v-<9^nTMs>UNaB;opYXk>Pxi7|L$DXxowLnvh|I<v;vnyM|Xm6o+C@ z5gscFFWcVaAt6=qg1iO^9hLpV;VW<WkYR0SaCoNv=>PmyWaUn3s{QA4YAa@}rQkY2 zO@>be5Swq17GT$^qL#?Rnyn|EH!ojoU-<(mh;UJ?7Yf-@ml6y+N*osHW`9Kb;xWcb z5_v#%mno11-D(I-iR$o0ywbP@yfCQ>odB}FE1m?Xa%aX=B(l8-Cpia+ayoo(;D6g< zKZ|V^QKh<>7MR{-kFeLM4)#XS$*zsB57Rd6FXH1FO>!~isa^vNLI@6B`YBShm6$As z90_#66Z<%=w#5|o$sn~CimB4g%buIHW-eMF4gL1&8$61mSwYjByVPzq3y(5=4coL^ zRf~u@(KN%6$^58eMpj0#QT@NGC~xyMM4R5IHDQm7gfY)Za&||2dHDno#(pV8G0CkQ zB(((rdqEgVVawR21l?hk21N^DKLPHRJQA``fu#&4!TD%c?9RNjv2ilFC?wcYaearR z#uz+oVE`3=WJY>GxI6SKPMpY4n{#2*s5PX6h<qQ$SkKEcBsx?kT`D@R(L>FanJ5!K z04KhmTf?rXTAv>?H-@}o>@4N2g-_2E;K-9EUL&h{kd6KVemWP2^mm^8&|{FR6+fV? zepqE0(Em+fD%}Q}phqh<((uxQrnlWy=TErJyBgS%0_DwLN+${1%^2x>uB7gy8!1yM zko#2G%p4Q)-9*MGfM78~Ryl~Opkb@8WK+fN<My;Xi+hCJWSJxW$*{Z|8b0C%B|LWR zC-bDJI*1`-N{n>wpg~wUJ^md`!k~T)pVM@i$SHwY1DUAvfMS5(ATVo-_TcL0WE8h( z{St}SW%#j4qHFnFk}D-C*ZRKKLF^`ZsyZd3O+C;Qo||k_6RB8}YGi&`cX9C&H}!32 z=rUz~cYII{WZ5ehA2a0rzCCBgb*(n`{4Gws(o{OYYKdn*jB9-0905<oL4!(3@X${9 z8~LkZnuC*<Hqj|Jsj;~bhMTxX>lFK!BU)F&rR1LeOYo?3e`DfggthU$av%W{-s{%a zp~k8FO1#o;{wB)@Bb(;u^{Yd;#8;bqU#(Yn2X!T!i~H~ZnwED?s!4;X-qh>Kk)cBu zPbEI?g51|%B^5pvTzJRQ*u@lGg*FlH;%6uULL<x_8oliJ>2D>}FE|EvLSt_sXyS~< z?u)8*vuKsJrN$UD!H);x#~6Q&q$)58pBQtxH0nK3v=kS|3mWOT?4HAGUFjFcNm!kB zevT&UH#H_nnxAHLEtm|F&hp*7HqRvgjPzkdOBP?=Yq^q-nbj$l8$kdIAm{l$u~4^2 zwo(2Vq2&fH(JG?1{4op@Qt&B%@*Y%W=P(V0b=LwW?&aoWr4LL25fh`%wp-}5NFiYG zDuv_5i;^<DuAS_|cKzkaC+=5pBO=TTkJMjbX;JXFt9*)u(Nhd}3_ujb9<7gOV4^>P z!+v(gdBG-73+C(_i^v;H?%C$M+>%_@*5bltkY~$jBqBSBLc)I^>!t;U@ythB-EVN} zfW74(7kP^Tski@=)$DcGTE~A?Tko_Hzt!W(pumyBzBJ48^@&By7PH2>YdVB|dLb<X zsjij!DOt|gdkM*?`nS_&Us5oZz9Ve{7}(_wn>I3O#m8zmPRYDd6|Y>O#X~2zN0zn4 zKk#^$4&b;`gNSjkOAcKS&*<)oB|)0db<@bcjP;Fz-)@U8@gl`Q`#A8loEQt&(Wy1m zYXmJc^W|r*81!7!_`&n|H}-nPZD~y2%U}ICE5e2+E{9v0Ds$0kxWDR~k#-NF%bxu0 z+X{NdP~wUFRW(RhFWdnbKXbXYfYX`N>#6r@L;S=zXusq72z}*_+$HoN7cvyUN|!2o z1ARL?5{w~`6D&0N0(2e$@zGz#97tQvnlF!m*d&mX>_$?LdqaOkKK5S~kk3__OP5M{ zi}Y(()vo;jZNuDL*S$%9-bU#x+w)p(Zvs=YfQ5XK<7H7h$d)pz?`iksaIZr{3j2D~ zu6_@D8=gl*%tULW(BYJhE3rxryCfsL_KYp%%Jq)W9gw{%iN21?u&(?Z&7?`Wa35d! z!U6m(hDob9bCNOl-lTSgVnsy_>Bdg1Ul=LUh2-u43<rbOP_J26ltUU>jIu~eUYZ## z@!@$ub%r->?L6T#@!zb9)Dy~oe9j6F(h^eQ3<1RXD!ipsk<r8XMVoAqJ0L4vlKcu= z;w;GloQ8UnLT_RJxUQ>J%;K%k2{=k_r)iRO%SU5@PU|4AH&BH?Aj}bS$WaG5PdPkH z*QYs!>`nemS7a*3b7NY-mkQLJ-NpK<AUk?pfn?QCFv#d5%Uo%0!iI{O2Taw5-NJ$B zCxGQB%Z=K3=d#Ya;YCgZvzs~)rw2QNq!VvA!~z;w$lm8)Wr3c!idccQ_J=Du*_uPD z+9JV;Unj|or6eU4!xUOm*f=&);3A7R2jpMk*1f(-R#t{%;-zBJ;1iIcc^>w&R9_=2 z!ix0Kz3^`txrU1rMFE<%)!p6_;wVkd1eS15rpvPfq7?K#);9FTlIP3{|Cly5xwEJ@ zvQP!nX;|!1Y;n!6_lX45T9t~=Q6pI(L+qhOqnJ^6@e9LZViZ7x#+u;112h}%X_-9x z=s4E;D8#>&?x_Anid<*;V-lao@t%|nt^;$dmy)FZ%Nz&?Ke2vqHV_|)&u8-Kg#D{O z`uhT!G;}!u^Qf4kUx@U;3*`SG#uK0)s#qG@)kNE4#_UJ})SuPw3q_^pJO&T!Wu(oQ z#79ZzIk`4Oi-Y=WK(zLph;ZcUgd*f~0=yZyeV4qO$E+hw!dn%kQJd$u8Z)wiG~x6h z_<M(zk&_4Jzucg8&GDH`?{5WP)LAE5=BGY{S5-7>mYRTigrEg_ae#5k>|<TyjCcpU zDP@QaSq93kCOsK6<x@dG6HHVbW!t>Vo`dCivLR6fQovF3*ydQT6((xkQj1Pt3Pn}F zs2<%_=aYXBYvMo(r49SqXorq7Ebb!uWQ)}Qk<jFX?>!RK+2#s`Bov!Pbtl?qyhMnq zFjhc*MP!Gc=Q0C|h-Q=Wk4c|PpYglHhLcH%*@Q?GzYYvE;qj`#H*wKJr)TK09aEdX z0Lder`N4X85LmtMzlNLAq+P6~s}Lx-iWpYKLYW*&M1#6uyd~;yg75>Y*U_Kwa#c$d zfR!0xpSQx7&A*tWtINh6abaDb&pw|cpZm%E;&>?vlIqTuKt6jB$9>gRNPmcXjb{t1 zB7OcFFZVzZRsL$JE$dWlQuYS95r6qUs&6N7Jg3oC=ZJ-0(29{>O<G<*&&ri`pAcUc zW6<ve##_BN)g=Y=w3+*+9h7nfDM+%y-&@p!%rT@$yiR>pft)hO+K7_wJX;HDC;}gk zsbaco3|bTKxR;G6n*oOD3OiJja5KPgf>HX}2uPhAF#c#*^hJYL;#<KO9ETo`0r`!M z2^aSE`;JXaQ;vxMUqEAyXU<1;zr-nl%eW1pUSpHBqmS4pl(I5X6U<b*r#JV7t$GzH zvp}OoI-T=6D5Nc?sf>i#mAsNPAQdS1S_s$HSWIrqda_9J+mUsComIVE8$ABZwv~K# zUWva*vG$h_R%)a&8p2^L5#yu?UD6|oc)wkc4&?exdi!VfTG098_~9<O{C}WZc;JVR zS6^+vjP-)~`td<cKC?0vN(#m(nu7fergg#QBBoFBzG#`P*WF{*2+^(xV3S|gXg!*| zT+Nt0;?(J=jpXXShNYlgv<sgSI-^wWA`x%!c|gL@?EWN6IErX+B>3#M*fXp5e|AYD zpTUu2Ql^DzQln@jfOEMiDI=#Z%g-r=1}lZPD)z+V38V<C_<L2QgX%@GVD>RbQXpBd zq?q(Wu00H&vz-8DwVoB9nC_bD4<R`EQ?BL*f&DEIT2-L=2+Ni*&=6iGk8yS$@@1t= z#nZYr#5Of-hFN`Fyp}dUBLfQeO7hq;=cRv%-|Wo9#47o;8*gvC{aQuh`~%@>wZOZ9 z5+CbClJn~~N8-Y`OSM2YVx+coU9f2KpFbky+wwmRI;J5mqpEy<rMC`n`EE5VAH}L8 zisM2$KYOWzX`N@2X`)^<s!Neg3k4I{E#b_xxn4q2Fu9hRCl`i?1l+iKXOk8l7VAiZ zVUvV|iL9aElp&sL>)&(syaz>`iI(HjZ<XD`9hgkPpq-LWjuwrvVEG@Kc8LUYzbfP! zSY#vbnW}@PWl~`jhUJWiN)CLwde8NK=c}+r%}6Wam3l1MBP%XUDVQd7tJa-6Tg1kR z^R4kL`(a)3e>d-3knUZNlVa6zrEiiVs)%k~Z7-uc<OH*$DA57BVC+A(Lce%Q_7&BZ z$HIk7df2RmRm)n0+G733ueV8os8ar5R%PKBsQLf~;g*~y+&WO>6?V1EHi^-ofyw+s zIK(dCeBz6wcm{Qs1i}bF`YZR1^d%UJ4s02^#aqV)^1)1D6$NQBmp$f|A(j_^(Lk!l zvXQqF+!v@(ZA@`Y$*)x4-<+QV*|a<tOb5zHhwAS{f9U+<X_p@njAxXinQ%lNfnu`c zg&2pGA3S~PryX^q)lMlke$1-*>kG-MQYj)POCb|athfDPX;PkZXMU_ILLDML`Don| zQxz8`T_Vc%n!kHhR=co=zFrtPV4lIHz82QHSUWMou32+tdB`mc!n=i0>OZNQ{3=!P z>RZa2TXLqvGq_^)HQX!++|I|Q(ZrezRmiu^#}NlS&l*MTnad=$K=IRXp+D02qf3k$ zUhjkE8^UI;CB@y%vyZCOfU^_c6vi|C<+I|cj8cfdOQ=}(5Q0)|%v|^|^F|;oUC)CH zw@X2{&S0V&9JZBmQ9D<o^U=^gk^BM5+c7V@7)TV2g=T#v{!~Ytl|+$9iu7vLU()}9 zCgR8S9wsNsPPs`*zKe3$<c}R;8f9+I6q+S8&De2FShMnejK5)5+fod!l~46@AUYFX zx3A`$9FStd3L@xjL(1ltEhWbyVK!}tSioMbVH11H59(Emx^Eq1EGxSz@6dtOvK`~u z)#C8WOSmZ?^k6(X3Zs3W*77$GR8kRh8^V)>Ck;1%{2S{-R#{7KbB6+888e)Q#~oQH zo7;}up8qAVRNj?g@0Ii?mV2&^l!Cs2<6#^{CCDF^8=ysY7U@1WP~{Vps6k^HBpeg3 zzQf{|hpzb3d6gGiE!gsIk%V_3N_a8p<i*0}tndFxG?L+PY+UL6BGqk8x(DSjYrj35 zPV!xka}$CGj;%HfX52N7m!C6Nx>)4Ib?JQ@#!}PuFM=GtKA1{%Y4*HvO32jQCHJ0% zT^g4R(r13uSd>`0+PuN=F~9mybo+yKs+XGB+7%~tU95Rn@l3wj?)*)#AIq&3!{<pd zB<qnUyUQappA(e&^ujg1dKM;`#;}ark+PT*s$PG&Go|oahU-;&AU!r|3Ebxe2BAMN zBaQ<zH!8x{MM~gojn122@v?Ew_sC(Y=76WaCqwr_eIj8bvpmQjH4lrBhP!0ujZz*i zbKzmVbFB@1YL{18qhif59}t(<cuJpg&8m5)f%SD-9ASA(Dl6$K1M(&D9G@sKHYPI| z>+Gn}?LC$URfq?uz^1aiX?~q&#iSswBnE~9Q6lx(7HLN21$=*DS)H{so#dVl^verb zq^G`Yp&V=}_A_)YTvtiLerr7Wv*0dG3ORc4WuE8v6!9;^+_&OouMKEsh^%FGXmqW$ zb&`BVUI5wUj?KJvgR$YgcSMT7q}$pJ6(vr&q4+cnPA=9rMuOK3GUV4DoD<01ks?&z z{?eW60dlF0yF>s<u!WJ0%|oq#Y>cz1kL1{VNg-86LF*icBf~~k3)zP{89usoe?Tep z#GO|5Vgb;2(FpbYl6MJ{sk8|~q(Jp>K`Y^lAEl)d@F(8}6gUi>U4QobX^1vQ&68_i zL)a6}Z4?UQehAO<gwqB_Zgg~9VEd+-YjsR&LP^brKI(L6j)48wBeaD`Dgfw`y6FQ2 zO`(GJA@NL`T}D*4H%XzCA7dto0xkH4doI66ItRZJMdvv_cugd0DrMfng9%~3f8HVh z4mKh1fri41;-@e9lBE?1I<alkW1erRw4PL?4!_n+143K%-Fo|f*BYO;g$Ll9e5CNG zftVk&%vGzBW$%foPxYD(_q+h%%TUoc<6xPOm6l@Aa-*L`ukl2WoFvn<^(NJWA-?iI zX*Z|Cr=_`+tA3y~<EBslOz`SHwJSk>hjQGp7*nhV)=y>ea4hIVX{*PdTx%$l)LHGD z;DD*Sy$?@PiQ9SxMRvFcy^PEH9jvkuqbtG4OsW@oZAx!+mAzpV^7`iI)9ADOL%YIt zKnHtY5(w(7;kdV8l5<|O)Yb1G^G0od+Pubs?iG5Sd_b5^c;jL9sl|)JrqcPIq+1P0 zj~(&?cuDlz*!`bdTP#99Kt>L419vp`SU5f2Yh`3;PS>}<Lpz#QIK@M&%D6NY-{MAL zC-`4u(R<?L8+uD`#jKQZOejlDFu%&8?y~PkkpP>DOH`s?h;5pj7ABBM{-B`$3sJG* z+=`8^$<(ysJ>6f^I*NV9IjSiSxl=uKd);}l&2ozUa5Her7^Y(|>yhd`IM0}aQ#6xj z9{q)}v6!97!8Ml_DsDc6x%bZ%%z?@hNc*@-=4RoWfkjS})kfPKk#@R68B|l3t(q3n zAsC;cMz@Pe)tMpSt{7N6Sa$|YQnT`cxT;w#)i<26*6J>Nah0}9f-IKW>-#oWbS_T1 z7m;4ykm9pi-Ig&^I`IOgx|*%Bu<M-Y3w_tupHy~D*r#-w=zRAj7i#gm{8cENU*}%> zihHmHBz{1~eSKc`xxW~*uiM<OxzqvlkHd}QQsbp9nM%pbkB1jEx{wd;w5N_gTGW|W zKM2rHrgTD7raE?6Fc%J3s$YlzomO-@2lUc1pM_>ixde?@kKHxWE2~g-+FdphJ4kP_ z)B@(<g37jE7>N*Epyeq#f%dgQ+V{rW%e`C*|9+LfmyElD_ogqId~o#7<gs+(apXxB z(J5lzvz=xf7Jjxt$h6cb2-l+Ct$iA6qWv|DsAlz*de2g6fB#oa#Ev9*8-G0BoTBsm zFQ#nSi!Oad=Y-P7DgBR00dC#uCiX!!bIvcc{EgsTs?IyDlCewZ$7?<S#nxXR#Qtmi zue4J)TJtB28Z0H-SfP#l*m3YW_W3(8md5aRp`ji{u5-t~3?&6EFh@G}Jh3d?=>xWD z8Xp$~Ga_WCZHI;D+ku>zE7YLpI$lXo@5TC0`YT)eVU?e<e*w3)baF<qP)}>nS;BRi zp`0s!NuZtfizc!qT+({hA={(iP=5CY2{l_xdQ!z*5E4w6I_G|mH<=?>wdN=m+UeD= zF=O2|Fj0n#%!|_*VNxmUh`qfaOn!cJ?tO*$O4PnCNUoem<|<duRdPPr&ih63z4al~ zgb=irBkLI|RGiG30aE*$D;vr2%+9>J|FZ6Gnn%etX;^SzhcWQd^aBqR+6{Cmn9}ek ztUQb%tm|U#3;nyJKA}IH2H*XyK+DCfJUAe9@Aq)^#5$M=cvmrBg6c8*&k+%pu0~Vl zdm2$4Wk`u#W~qp(J}+iP_&(X}X(E<)wMtAV>4-@S%AINnV-($Nbb}0cngUOk1tJNC z>iX`FDhA37jQ<sS@QZd8^;XA7+4bK{ov2cV^vKhv$$dgSyV~6x9v4y^nC@80RI?%~ z&aJ203mF0HhpRn<L^dt-9{(y>-&wYQ?EFEO(s{`p6AN$Dv*L6zstD^y6gg;f)(-l} z`(qsUl)+)NVg0V<pTKzGgRq#3n~SLtF#*^gGho#!T_{iI&k#kKufoSo8tDvi%DVqC zs;)4ky*&YPrYo3|x=0NR!~p_Hq35lNiN?o2SjhZck{RP}S^#FW6z6WDeYgV##<A9z z*!Qb}xnCt&dMJICnLV$%_%^h3(+LG3oM&xfGW8WT+Zh<qkrcPpX6+L?IWhv!OT?cI zRC5tATXy`|WOc7IzyQi?F;RciQm*Ssk}6#wpo%eV*sDxr<llt+^!UZU1lGEsU-n5} zO`K6Z?%L0ljFraFX#rJ0N7^#<%Vf#rrUtG{55MRujm@-wiF;16*?pFhYn>Kts;YTi z4<uc_Y&D_5EPbzzB=sf3CU${zek%-jfjjQ15q1f3K#TvpeUDdM1=l2a&@aBaI1t6* zFMV1}id!hrdeapfkX3GU$zL=Lt(ykNmDp>`5rw0UNr>MzBq6+O@fP+HU>7!yxoMO= z)F1{|Ok!b;_|5fVPz=6^>65w~$Z=mFUAe>5ZsvHLyKO{N7ItckpWV~(-;_XaH};i+ zv(k?=ULr){BsceL>9*jdJ8eE@I`puDB#oysU8)m_-qTHK4&`FWEL_W8Jz-Z8;4Lvt zi~W}!bJ`W+9;nZ??|o@xu)H8CN$!RaRwo$@NtF*o)5}4=r(Endy)0-ONw!GrgN$Sv zlenJm*&HmR<92Ui%4!zJ1A9iL>WAGT@OmRH-ob&Wo-rv@)3CAO3a9zlHxYDAzkw+g z$}r&`y4@UH*h{+fbXrV>m333cYqNUgrk$)0S0cMM2Vaah5jm0`d$X(~TRZAXwqsWR z)fZvufk*EAmj))~ZuVz5{#S0yFi@mAP380tFUxaC=8&sLV@C^EWzPC;3MH<UVPYQ7 zBiHpY9OP*|%>dilKo-e#KDuy8hUX;)m#M21?iUY&5=H84AZpOpg{+8F<Rd`ZlN0Ol z7jdDs3=}?{9~@^z`HxVj*>thd@Duwh*bZi&!ca*M$zS$nqDQ^L_g596{RT<FD@Xl5 zP8AnzjnbT_BeGffAe*7<{ro2aG69L#IL{wpr+x|yj^EYb9vrz>=p7^;jtEh0y*diB zT%GBTB0t460g;bqURo8Xy%>7E)0k44)TG0qLX3BZFM~l^mIkjeDPlqsdA+0X-jOJf zIr2NJWJ^x4yZX$3sOU|L!WUc+oozSNomZCH8a~<272h_@!dyM+r}pc!&w?H`-U}mK z5RTL@|H!^1s&=ZFvPY*F8mDMF1LQ%%-TMlEwv45<i_2=8Ed(#o(lOF6cOiH{-D=fD z>Qqx|W|~rj7mvmYj4doQ<25iqgVtxfUNT)QQg@3EW)g2WR~m)KL8$3hR^%}sq8pjC zY0(n;1DZRAZ>Ws$#@IbdtPTf4oYtx7@<gX+v}TbJj^|@$eB@dMw3xyH-9|al<g^_V zfI^{&KJWu&=*nVh=}K1x#>s-{;xGU#w@(Y@NSd~@Xt0QzsJLn?ZKP1Ir|uA&@?BtU zUbyukQ$~}yx_RznfpnLM-pmT}EdyZ7Xxw3h{`Os<)(BDn;hgRQ)COdGA6q(JH`Vq? z)W9eHGZ?1V+Qom}H@YHoYkQTYb_chU(dT9t|Lcb7$Gfgu<ZK<4SRpU!lPRL{Ti_** z&a^23&2oLc?Xl_6yl}Xk6E#K%KUu>?)(8V0^?owqAV!TsO$Cazyr|++35kP1vt%G4 z0_D15Vcr2UVx}0+6&pXmX(zK+EoP`cHN>36qA-TlBQYZ6nOEb^w*zzF3b@wejO03d zA(^79WCyzx!;Hr6Z_GH%T)(4=VZ(esM1HY=3dBb&>ol4JvT+@C2@`TyF(%5RnT2BJ zjC%z*In1YfgDe)omVg-x0aK!#L!y?4DU!|OMev0BLu++HEWe%yme9@O8l!A(_iTTj zZe?t6o0b?1XY#-Mwe$oRmU6D#peVi(hjL(4cX^`kdqdm23#kvDiAcUGr+>kY0V;@! zZWA)*7SiTm(CGk5x8t;DVr)jcwFp!TCIEcf*tBj+9|ck^PmLMXXVymGtU3{Y#0QQh zoT)fK{)kR`_xar?o^jXb1qT)8pS-AZ(w8?Xuw#~xW3>0;E`ni|SRboA(2wJaksP?y zJY|I$>2$$^3zz{f+6I3UO;G-~u*|wXe{km_P5t?p^6eP~T*tLm4Fz+Yzq6X)_jv+m z3~{T5h|DqkHt^zl;=i1awt%<_O84rD>ocl5@iQqO-h~$Dl=WW>akznI!qRnkM*=XJ z_%lW%c}!v`_78sQglj-2EcW}6NEaW|9k9Sjj<J@Vz_j1+<Y%JhIBw)mcQBUi&JKjB zITm9M?kX19-#&NrwlJM(@n8g|z5gYZxli%v$xmIh`w;_1dhlT-YhLkMe@?u+I!t1F z97|j#FuECK7hcot%Ws@Xw*cMgx#qMTBb!miKWn5u9;;i7&6P2`o!Pf;0@W^#Inv^& znKR`&Fb)}GYdvt;8NI3FWl29W_4=ORv4k`jxn>9*)uk9}o5x<h+8v<osjutycd8ra z+ijd}I+s57eqeT_zDI|*3q2x!Vw}{dB4s!LvR&*Frr<h>rAAC3dgv)ml6+1*nW(`L z&47030qdVy<0K7k*U2&6KQLO+vIrpGvB{`d`4casepP+^w&y<Z4&kg?ifx1qJ2F{m z2j_g$MOwS`NB`x$%WINl%@`|`j)7cF;{C#W9ds+lJWeC`%^wD>{X2)%xN9R*#VkwU zOkk}<Y{C#*bmG^`->2^5KOcsCxXf!ESCNCY{Hp33qY(@|++DxxWz@6VE#ZqRGFTq8 zAG_?~nUkNHec`il22h<tFDm+((G2J>WL|vMQjZ80(-<N}a<p}TrcZD-eX&BvSe+xI zLlZHxMj+qLm{vzOx^3c8$J)^aH$atJRWJBX@~60RCe9lqdLnP1W}fWVqqQLKe%+N1 zg$g&E^t<6&z%fGF<*DvlYF2r6OW}2Qov)hN%P~rLK~&?qh4y>%0oz*j5-R(}UNy05 zE;qUM<WT-%Xj)AF(~?65g9=|OB@EDaXE{he75fLG?G+npm8-SAsp{N)FkTf-v{vKI zPz#<roXVn{#H#c#e(~QT#9fWj>Q`^ej*qYP%CN+<#OUxo`|fH)*3HR2HS@aQCN@p8 zSgkJ~VArN?X@$k=pcoV#Rw1e1wVH@p>j2e}FYQZ9jtSJfObO{|2idV<G%wctA@v3S z7&>GlTz<Y%a;|)!yEd<;a6LY4d+K(ueUk~3o&%7swZ0v-Vv^<U;o7;m>4;N}VDEBH zcW0)&JK?xvWq<)2Zu!M&+VtwEu+Vl8jeThdf853NA-wYsuZL{Sa)Vb8z4y(b8xJ}B z4!SO*u31#Y>v))IdHJOGNLM<J{;8R0L*DuNm>hSZ*Vsb{PG!_4KGq+XQJ<?!pV^wa zeZxj$`(hQ2+#_d9V7L9#Wl04>;EYBJCbE+_$x=~x1$k%W7Md4D*}jmdxP-wc^+qN~ z3}kDKSYarMYK}k^1t-!*LF7=Uy!k+FaK-LvL*aP$&W}8`b>AE45u<?$4#mVW8k8Uu zhuzK!quOI&KsN8IrHQrA?brgH8MQsG)B6v6Z8<~&UqA#zi$ba3i^bh^!bW&DjIRkO zUECe0H`^Zp)K(}DuA6R_kF$F?uAx7-su0vWA@6WtHFaT$2M?6$?B<BMLZCQGQW#G4 z9L=f_W99sSEW_oRBpvZp%ua^Ju`GTNmFGd#QQ$t&OJg}_xonkVa)j$m6#6ugtz~uN zV>Roil*#FN(l$4=_2I6vAZ&vGNn`GIZgl&0!&PP6V;Y?BY)H;(J7Mfynwqb}f0CeM zL!z^ix7hX#{I-cZrsVPd_$`%P#U7xhLhAS3A<hY6aJp;ou~FXMXO`BXFXsCG$K5&1 z1T{IsxrY8l>i0k{=C2Py%nP^aO}Tv;ufGQ#+~khsiySx)E#9^@7GiQ6Xm0FQ8wZ|b z;3_wMeVmBBXw~`ur0@fvx(dqZlm6~_&>2?SR`iJjGYv4^Z54A}_BC*m2~dNU^xn3S zTo|=bR=L~g)VeP0sbE_W$AXq)jFdEV2=14HVLj!D2C{(`a`9u5rrOEgo?J{B@7C4o z^|=1V7t(H52Uiq~SltNWGzyr|0M95h4TAmq_YHV?LkiRbS`-Dk^_BXc4d8sdz6-_# z$kh(IWq-aLkBHy^X}9@xYn9Je8@-BQyhJf%)qC`6r_Wk9#x?^O;_-5paTsM2dpZ^C z>X1~oGLjU@5gVq!H;$vPc#575^8P|)brNi_9_0Rr^M5Bk!H)c_hm^FuviFZ#U6P(U zGShw}uWRNhJ)86|q&{hQ`qZwjmr8rq+h=kc)1p!ERPB-K(RRX<ur#gl)dg1eG^j`G z_Kf1Vp5~FT(^Tx3zk&81hjwtlr5S|?FZUJl3~>tR67Va;3#v2n6Ho3N9_p*NV|*-N zSW#z~sRqNWFDw-X1>j8u)vwK}g%;fy!@$3$%Nyavc`^Hpyg3q&%@5bd<;$i-zP2Jp zUH#2=to`nXMenk|Ts`t4^IB5&1K#8CvT|DbmMJU)m=2tzu-6fOFIH0@a*s%3qrE2M zejT#WRmRYWF1ncSQ%%%MU+}e7Vg(?iTbwl5UeDk)o|R_xv6Ou9-z5Xhf2{k2)`&;# zH8nZp)sV4ua~I;m-$<qahfR21oClHiS$(DPfOKB3O(L@HBQ^GO{E?5*(B&L9@qW*5 z&Z)WyZ7kC(KEYgn;=A!+?*KU#jrFoY=1|DrSnsYF>mHn!fy1&u-z$pV^o6whBKBse zPG!m`4XYa_PkBv_(_2Sy07|g7_-)C_33yzQ@OzPg3H8W8ptdn*Rcr5XoQ<lAn`sZE z@NaiX{vDzzTPw#rJddxmoNq1;c%yKE&WgSkHI)6Y-KZ+l<qs}vxBaRwep(>?Nh9w4 zM4Y4?mi}Ib<=r_MRaYbjBS*l@552HhNv+Q}*@`*|vE3d+80W8|X~&Co-K*n3j0?!O zuKQe9O3HcVyADG-m~OY>aJvJ;shzINbGaWbf&!R8e61-FuH}+Xcmh5?f*OBIP?+CJ zku_N-o}^?;LOL%RHu{qLjqheNewws;8%zH5i+cYA1~fWzm6^(9?$>=gP3ATK(Wz7Z zLH*Pe96vCg-!m;3k<%7(!V6X28f1!FaO~xEWlEjV?-uxIbR+Pinu-gFPNley7w#wg z4(@%>9rW?t`gBLaC;Sw~F95uk=<L`nq#IkT$Uip)R5|Jtf?@YraI|60t~!gmk1u|z zj5wnPooEEd-WRWYo_#3c0bIpUM>Tt^<>Gamx4vMqmoXmN9{ZQ}`_dkT)nocq#BrAf zI&y!%D|cy_>h7GbsHNSK336uIc6@5T7<Qx+_v!_CpE&p<x#yL5`y05ISKuBNKzuHB zFmUp(KlO%Y-~pBP_xIS>*CBf=%wW`nTSpl9<PW><^W4Yb^PAQxce!qx=EzF89UF6& zv^qx)RJ$9c6`EwRlubC@tDDnF!u*@^(XYDM2B2#|D_(JX+g00E+vEr|EXe8X4<MX? z7YjN<Fis6-2_I$NM7>!NPiZ&i(Q4I@DU7Qg6Do0@pFSy*<^1+OynoHBnT2zqK>Z56 zRxMZHNaSVsy6)8SSqF5!?}>yB{93^0cEHL|3_C$S_cnfpqjdgwR&*`$*rj4CzFrKQ zG$S56dkOkv1Mt|@=(~W{{7bV}O(xX!=CI)Gr>m{M_z9*L!k1>z;?OCH-upi`Pi%fY zfBL4xU+F<M)JeJ5f1gVIYxFbWV$^p_?}tB|>i|yJs;8mU2QiPs=K@KT&{JzMK-Am= zlIXhCWHRM`)q|xoZV2yi-S0}_tp@z@K(Ejf=dv-B&*rXsZul`{GBV^8UCtHyQc?O{ zqW&?L8a-F2Ur4>U<XMJ6ruW^R9DM0I>N!P2`myTECc{F(_x~vkN72xRsT0&iI(M_* z`fgc9IQ6<R+(J5<#W-nb()dYurn-^p;*!T*M3^K{g5WPVSzmZBbHhkDR8r&ahnyi9 zQc-w=Nqn*1RAL?SPI3vUC`jp7lXc?NWm2KT`0g`xN#TeTjr;K6vfOYs>fQ4U+AC|F z4qpVH7XrLLUj)owO)<S3zC$QSI?)_Rn#8IkTU`bjo2o)xwm)~U#GVqP;xlQim3@wa z`M?tpLI_mYTr9DR@?lb!?0q6oi<gV?e|$SN>cz&lcS3aaO%Wdsp<I_5yqggsFj=mj z(;_!{+N2MrVF>l<vQBdIVft}j;weWADPP@YU+G5ZV6_oHcFBIL(O_+co~1EjeBh_* zc+LLRH3vBja7pBPey}(Z7UbvfG|cQ<W}rOK=mLIIPzvElaJQ(65z}uijBr_efyB$b z5b7{kuI@i4zWKRNBxPw)uE&W!m{#~>z_6>xzW~DJyGh$6Jw{K<FmXn8EPm+!dCI;c z8p1Psn2zO+BvGQUHQ$6e<5Jkru~nlzDS+`@BkPW&q)<eiN`5RVq-&atc%ZQhEKHF- z2KAM5a6d*gc3yTs_$3obFw;ynwZI86Ptw;bVAebDXg(^(SP`d(6Rsi1h~&a3YC@m! z{bu5~r;#hWY{r}VA&!q7)+Y?F%y;I0poWDhS4le@ZiKkZ+b+>lL~OSfzhmk)dQ~W$ zmrr^<Zw;n1Yj;^gLl6oQYwU!JR0?#GkZ8ZPGk$54AwidlgST&e(djGE0Gl$QchdX8 zB2A<yJV~_upW`3nPf}rZcfoTzAU9fPN;qXyujGm8TE_~faCPT727JFB5-dEoAr9Y1 z5hYz1wYOzzjK{(K6vnF+VZByf<FT~=7(a6QP<r(h*@kpH1)8Fc%z2W=4KMjq!D2t^ zyb(ZzW}RM|dXJa+K4syKiXQl~Xpc^fdtYH2IX~QG34THw6#$Oc0;+(*W)Ix8z3(Y; zAk#19clBtz$S?_|vLfC#n&VMq!EkdieulhTNSSK7N$hyj<v^tY&Gm_7^qIYUez#bQ z&BiRL!`-OS8>h^B8&+bMlKVQi^1?rfwD6TiF~py~FAuq19s9*2PicmL)Lv*{u*~D$ z{7SvXy{sUCZFvJX!^47VMRomd$%DpnMd7$y+ch^RuWX5nNA_6tOpDa=(cr338AM!W z@XqIt9=xk~j@bRx{35LaeGMB*q;rhO2_;$Jw?5n*(@nf?W2Ehsk<t+Hi;(vK<Ttrk z9pum_a#&{cZ(m9|<cNiEI5aO%-JKCwRU)W{zH1L&;f$un3bX5Bx&Pedx-Zwm9RkK# z@P)imo3zp;f38GB^{|{0TUsrX(rfa)!_Vkfp+UH~56J3Rp75};QYE*lf|-g`{D{8r zV>pk5^lq>A)mCevU0YZEN>M!_&hwyUcTA)Wr`r)jk=oK{yMlIp^#NSy_4B4fHXd)6 z^sZ{$Rs@3}6{(RJi2%<|7M=9NlmMn;0zHpK61Lh3yI`*$j5aQjo=OSwEknLdH&l;l zxdawnQ;u&=es<{H+KlS4Kd55nJ6(jZuqwtvYCv$`iL|W_v_sI;e8}e}l(PgHe0)SQ zbi=@5*I&uG9gxsFfG$9?JE9Hqf%d~tE{oQnyI+ir;n#oud~>%ng4qcEUN3d}F7JQ! z3|VR_nvyEB>zWjUIy>nYfvM3LI#awg`*o{Y?oV^s+@_Cl@(W($>n1Cq^kN49w)QQ4 z04=cWu<ITtE-JsoY5S?IPe;_=suAM*QkqpxZPSCpofihz*F;&e2>`5&m!oEkD|8;$ zt;TG8L>bkl=qLbfPeQJucLvThi=Bu|msm#Ecl*MmI#a_{mRY}s_djLN)hXa*;*J-v zz`Vb^Y>2q7_t5sN#FoIqDGcYnBUJP*m0dBz#f)ui$O&$gTp=2Cb9Q2$*>Plk!<RQ9 z+im+b_^loKQ`?HJu#(g~T@_o_Th3D=6N+|QQxauXC1kl?nudQPSyG6_J%>1e{F?cT zI=>s;8TnfB8PK3?T#pL<p&ejoQ735R!;pj8+MlD&w4231)weW|y1#5gE2D`rjaFRw zj;jEyBT%=6O2-`Q#oZdH(cBDi!>(DUT^hiKe5nUT^I10TYzJadx&8OL;%*%}N+C6h z`*hY8A>kY)nVP<$_R`J80Y^B{Cc)U~>N~-o1n5Pdae*I4O!=2j11+?6fhyRfE&E0N z7PzdX%g$ti@EpyTZv%|Key5KIu_BVT*CKg*W{4c=72iUU$mJ4gv^t>bPa4Evgrnu_ z5KfrxU`RX)d|{^RtqR-bGQi}eni7`a=7r@E-6vv1EpPa8<5%yno~oFf+m1^F5MSQ) z;@^Zoy@TR-I<MU~_VY)-*Ie!?ylGs84*UbtbTlG{&oz^bm|T$GcbMVtI-z0W@^kwY z6Q*CSl8AHi_mlI7*6%&)syos{x>i3PE$AAH;@uN*s_U1ZK9lHr$s8C)L9{8_W$U^! ze}Crn%1_7hpj&T9fzRZq{H~D52{EJtgOc`2(BdM~ocdlZk7NVaT4mjRgbLP*LjpjB z3a7`z<$=O%&&xv@U+uFhH=+xYH`YXZ1*LoMbT#zaUDRz%I^$YGXY|Ge6wZ&A1_UuS z0m>y#>zCcw#rS*oygMN?u6Ps!X9u&QODxI%qQih8WLx6W_H#uI_Wsg~0I(~U_sSPz zQ&AYbETp4rizDX3`t#Q>F1C5~i01uNEncyHs4q4vFF{FrI_C=6*$CZS3^7gWRajb3 zlJ=ya5xQu^CKSHZDPlYhIah%kLVFK%ieS7%++5WRYapzWmp2)Z*?rpahDT6ihnQFq zc{G4G{Z9P(e=}?QR8bfT4d`)|*-?n`twJrJczAtR<d}JFeXQ5Sk;bG<$1%k83Ts|9 zG96Xz``kkfC#HeD2ew?HmgxHX16%NE9HQVduf$Egho_9Olh4m2^cQT(k$8QJ#&6v9 zjf$0HyF$yFu(DkuQ+SWU-xsdX(9Zn7XgJO7R?WscDCs#REjHVH+jNO9!b3!!-YJr8 zhzv*XykPj!Xw7~AN_KPqs=)9=3FqZ)$yc^2Vkt>FT7+I(m3+wX_PhxkKFaLmw%^cX zUAHTe?gM_P_p1;ffM624#&}=l8Dg^}PFH#nAb%nscdoyQ<6ku5^g|*eUaU_39L2Tb zlnl2!Q_uwdb6K)EY=A+w*C^n&HsaHAX;!~-k&dOQy>CJB6X#We(jKnOYhbsMS>Z=| z(Q>iK%o2KIiO4YnM?%o>_R!;pp1U@2H=F(RA6vz>G3fP`?UpVt&AK92Tsgt0npw01 zhMVqPRkQcugO)Us4GlYHh-Z5S>jZbsc6RaC=@QbOUyTWoH*d9E;}N2Fa<q$|-?lj^ z7$tl4yLOcf%uK45b<31}kWP=erL{HH?156>L5xB#Oq6ghlw{jjKZ=im9|npn$jIFK z=&iDBEz0cm8f_N#!;^*RytxQFbkWRR7Z;8#nRVIz@gdI}9LW8RIO3)|ASqr!IX5o0 zs1~cllS!m?!Y-3jb@kDzu_)e;&#kg<5oEhZq|foY8ofjp4_K&kW(!9U&5DVLHY0am z53Y1kxow_+#>^HCS*6@k?s2_LrRo}`L4orL$YKV51({(XF1=3f3+{SCqCmJ|ic6cc z@*?dV)fFpbFq4SQ!b5QX1#2GMK?=$9gcd`&<6TZ+dXvMs<#f^er41LC7-myl*X#5& zO4FKEBn8%K@hcJrZ>S0I{jKoZ{6h?%!G2|SaUv^?Kll~Yam;ov^`ILiLSC*G^bcnJ zWYMrPk;4*hLK*aDBf=FZwYq5CU_|3CMYN&U+FbQU_O<t#08Uw%J+^46)+@<g7F1U_ zzqQu_@C|>dL@&C*lYD>AjTP()zl@cy41kncZM6NGs!TyHNyGiWTL!3}pN(tm7!w*A zH=GVax9%wu4BvG;ujwoKGPGEJb=ekg{}aq-v$O~gM+08CS~DJKuYVUV9gu$|1LIgk zq+6iAP?upmpKQF~9eVJawbnvJ;ThLX=iXY>mPaLhK<L<oOTk`vg+cXJ41)|-_!y1d ziiXBSo8Fqb{xe%?x0Fk5(HcD5IQL^;99y*gts*kmeosYiu!Q>%4L{E?Lg|d=mvA-s zAdZ@_^B8>9uzS(ixaejsyqJo!to;2_3}yCGMP_O}eNy2WRtz%`yS^w)d#=narC^!R zIJ5Y7g#rhziJVr6FedmFHm4u!!9qKQ1-R}6=8(J4LhC3YMqOCAMRk1UMPPZ^roQdM zH-nUe>%B2{V|o$UNpNt}omVf<C$n70@Kkk()oTCM1zYl{S>(|&=I4egssw<~prjon zXP&FfH+BQMKRPda&}Pu2N!bGDC9ir{D4EUxx2#N;uY?zOa;BE}c8_-cjsDM5587o< zBk%<<>`|O^@80j^B=?|RH(De}OPZNW-w@^grhqw*#Tcw$lzIgw8Tcmk5Y8KcckVY7 zRNC59`}D*t`;Hx6#tF~}Y;22M?|!45<B*O@+BH_;_FY<2tNtR-nSV3AxjOmlaQTfD z*{ntMRuwhevgZTQ75duM!s8Oh6}SKR7g;9t5&mispSkawlVC!X*G^+r52f$@b%n2Q zloB}{b#S(l8L-+-%n$=2ESi5L8Z}b_U0w`3hq-gG4_9!7JIjbJT$12rM`G5w^ev@l zqmdkooW^6q$0g`Zv~xm6Tz92SEB$#yH6t43=4E1?aLS0j3^eRpbgNNKt+F_y51@iC z29)r**6HzZpafQGjZ$Y+1v8|kU06dqo7gy$|LSG#vkJd-6@Kk1Ebgvq+9h%t&41|n zUHlhLLQL>58p(2nFoDsiy5?xVahJ%}Ci+1G*lFM34i8?3F-9ZT&XA&3U_Qa@B;0RL zW+<jaL_g>I`rS`?FS##xCT%R<7nRF-e}p>Sl=`b2j?2$9Rn_fXO!>5#rGd5mW+arn z$UOtd|BT|#L?fWrl~5ZG9wZj20EM+AvgWQniefrmBPku~Wuk)iv5H9UCdbQO@V|>z z%J;yJ7e#bOohDf#TCNwC(6L$zB`9q3*=~eG-OQJ~gnd`6`-m{GD>Ro9+W1+!2#Z|7 zL|qLlWM#QPjyZL(ln}=iB?|K8cES%!vYWTzBhmZ~uBzh<{CiBo{r<(gM<tiatVH5` z#`HuAT#fdtg}DPH2BP6C{Tc`<C5ffFsuBo_LC-lZESp+&O{kiE2jSauE?AeJ2?sy? z+^QrA7sqa`Gu&D$=JM`Q70*iuD22<<lw`ej>1&54D`}K7@W|_l<hq($8JvARgx~2Q zEYHI}mUsqTzrWXSJt(BcW?VF)CwQbQG`V;?A0pAlz{yb}a^z+WTee<91FBp>jCu%` zJ2Hjj7}>GsY4kkuvFk^ECjo+mblcb#CH0h2N*&XXAQ~ty-mfZeX{l$qzjWQwhLLSw zPo#k%eG6SctZNz2yUR#{?|1$Wj6ie0uuTYKXB%=yLyoZlreOgT;(!hUfDbIf5<DUe zkN^n`f#m+uM;o#t`hf={M!Au?B7&42v?>VFK(Z}jOoIhOCE|iDV%f^uuRkdp)<K`X zfh5q$FA@h~;DH~=ZHI3AN1h3quraxhxLDwU9=3rPm|>Ap!XJo%7=$5G{P3}u1clyc zQ|k|UUi)0_TX)i?k}QiDQlcSCf<hq-nktdAN&G-%TPj@QWk&)lzPmL_jZn$$og&Mw z=-anZ6g*yQ!N>pT$E8EBt+3SIr;=Jj$gxmD`dG)S!mfy%#9hNqrPubtfiPvHl7i)6 zFqAWKEs?FlK&7L;AKIX<wX+^&cawZ_rOcsF;{V1iCBoqy>>MTV2PGhzOv6Erg#|G% zqOJBkakhMCLPRNeQ6<tL8JvNq>LEmeaztLMDcply1EA2~ZZp}kB5=CKPj4j*0yEwt z9#S<W_G!)~bx$%iQ(ukR1a*crBL}5I(PvjTM7`&*JODN#HZVhE%K?4egPt{t=15Q2 zKf*`k*djX0L#IN{=Uh=zVmvJ3QM3_fYdgj-ges7&MsTZE!_dW!3DF_4Bs^p#j2*XB zV!#>0!7cy7MqHu`MW-DGJOG@1U9G*{E=ii%)f2M;-z|b#^W7rk_^cUdU_7D`^U)Kr zUCzf^iAltXzVk=MZm7f++oeOjxPcqGq2APCoT~I70^qiOT$*Q_0hK~rQ+3z!ol0}| z**(G?0!xX|g^h0BAMo5F(8W$0XfqJ~n8ao57z5GSbyLA}+q*r2ph6>39%1O4D(2hH z+1(<XtIkn^$n}IV>d?MsNH|jUDNMs_HXY5MefTU1*jQap2EHyW6jxi5FqJ6frK0GW zR6S5KclO-ZVT0AJDkbJ#MCc*!Wn3!yzERW?D&QfSyip}MNF@*h%lC<XP=a0SA)8V{ zP>%n+ONG;_gCaT<VN-?zPQ+y@&|#lM!#Dz98dN<hLR2c;ek!UV`Of0-`#dGm!6K9) zDxjfimN-R)J|)`wJw$aX4q-=B0v9a4IEaCk>R_*-!ud(OA}X$TR3aZK;TTqB8>r%C z(xe(vA{fHGF~k+|)7&C*A=V6EC9WX=gn{?<K_&J9?Te%PrQXV=W7BzIDqtTV0tg%^ z5R*TF;|K~Yr%>R(0JItk)R!;TKzZ`kt&_;HqsNaRLxQX)QsN|eA|I9nxpAe-kR)Hq z4B%!*keN6?((@>XAU$gh!wKAVOs3EPOI!wfw^JesiO`M)h^bKOz=S!oYMqIZBQO7g z`po6~=qO!3h03S~Aa{14HgNUOAp}VdXQXpY0|<>IPUS#v0hS5GhIL?Fi81>%Z5cq{ zK#~|SYTQb>vcP`61RnI5SKyGg9|tfUsLr9wW(pw*<kzsX$OXRwWU{<9$-qZyX_wsT zH^45ba|i_>K{Z&zT>_y6=nayXLU=a>O3fwRr^kBQHqIgu%pdYxN8!2FO}@Ost^{ux z>z5l=fNI6|2^>F=A+LV!nBThg?=8J^kth^VN!K_skX$(xqfjxMl>|>i_z0v-0N4cZ zpm`X+gxX6D90Hm^r8N|WM9j&Q$pX}r_|8nVWSA8*A-ed|H{)5=&4mFNFcAMZA4;S` z06+=k$8+-y#Ex+yxfV_%Djc)TZ~^4SkVovuXr)ZdsiRUl;0TnCLX0&OPXK8VR1Rn= z<wg)mnB3CMO1$Vp)s#_o6ks(CVe{sW;N+!dgHr7@O*)04cjckWWmcz1{=~+PI4gG4 zOeU;tRY3q%iZfe7NF<@ANVf4)X^)6DlwzqJRXLDU+E{Z;E<p-Z7pWiZGRr{G5pqMU z0gR&pA=(VoPcA<SR4hlX)pIK}a|W;mI5?sztwM(>^pG~;R5}oI5n)rzmr+)D;6-5Z zLJvP5elt}=F$MsOA|lBr&@$6}M3t)V2^2{(Q|>uXI&_A#AA*<$;7|X9)4CXwA(>19 zB1meyK~g&{%D6xPkxJCh3>a^PgSH6|R11BFKJ=+X!3xynKka(tj&Zks<c(DUG(lCY zyf!q4K+haS33UN<a?lMxD@0vVA-lNFKh;X4u0ZFI6sAJieD#fjPZHE6NF{c3%QqD^ z-O)Z@eUx=NAQN=dH-!mQ54a$Kb57C;YdX*&EraBaK-9R11SFCAD-b(Pp|lmgbdyYX z0ETa+PR;`n5{*JBceFJ~OFR(3A{@0703kXCuq#0i_;JkTi%Z+jKkJkeZ~*)q^i4hT zj6)7RxIgq|+S;<i&cW!iuF*r=pq;lO;Fc3lIV6q44`c7}^G^Rg^*Fy=L&F514L0aD zUgtOoO&tKh{m64++YPPL54h}{oVsrE9JCETd2<A^swEyKzDxeF!`564@kjk~(zPp9 zDIMH!-{RVZK9~HXA1f*cJT?;!p=4}TND`KHIzo<mbOR{k*h#d6B9Ae(N*lR(+WV5` zy2sF?9P*$F>N+x~c*Nsi0>Oyu0tOCwv_%{eaScPtK@YeDAYk-}i8uhWt{nO$T8Ik( zIA#bFa;@-+2D{+Fn1e7ZdQl?&P+Zcevp?D_?IHf?&B69YK<0dk9^U)n6*JNx*ZIyP zV;bD=5Oy$(;LdgHkjEVdl09??4tLM-o$n?H53GnQ0Qcb7kwUsC$4XlAl9;s8>lR1J zOnTBKhH?pH4ClLl2(OgF)5sv9wvPwx5QZ5s9PWIl5kJynG6a!}N_tbqPx|tg!1QDi zSLmDoL_-{L45l(U(#w$aMv?45j}E8A4t1bVARCE{_eROO>jgj~wcN<bmR6)?n)96K zOy^dHIXHEyvzZ)`$1@dK%Zz{%ckqA*Myk}05ZTb301c=>2TIU_u8?}vGi3k|)=8JZ z(<8Vvs6;19(TZA>nbSh3T1=@>%1q{=68Y#wM@rI?n)IZWK~F?c%F>p)^rZ%EN<aVr zA^8LaWB>sGEC2uy0DuAp0ssjA00RgdNU)&6g9sBUT*$DY!-o(fN}NcsqD6{&0=&4$ zv7^V2AVZ2ANwTELlPFWFT*<QK$Q(T;!ho?+AR~b_5n3X60tO0~K!XY$O0=laqezn~ zb@)@@PKz;Oz!3PWV$-EqvufSSwX4^!S%K)`WYCtt78R!s>;a<&LbNmsUIk0HuHCzM z^XeVi0?5Es2GK^0nlMK}!2t{lETwU;<HwLAOP>5ykC8kBJrz7bappifmi4sA@k(F} zgO&?XUd_6->({U${u(vVt-w)cJF6AQ33nmH2ys=l(_(Jy<H(aMUyd|~;-7E>oaVUE zc@57nrVl(F6-A5U%)^WSA5Xq~M72HxOwGyhDq8IY-NLW&!npbS`19+Zd_6#opSyun zQx5FCwNZfkC8*$n4Bl50d<{k@;e-?tb%JdbW~kwY9Cqm8haiS1;)o=cXyS<|rl{hI zEVk(4i!jD0<BT-cXyc7I=BVS2Jof10k3a?~<d8%bY2=YeCaL6-Og8D{lTbz}<&;!b zY2}qzW~t?tTz2W@mtck|=9pxbY37+|rm5zdY_{p<n{dV{=bUsh$Up%B+^J^)d-loa zpML5Y0H1?0Fpvfr)T!vA6LH`uqmbT*K>(9hO6jGRW{T;ins&<Rr=EuTX`&u@Adsm6 zn5t^30bF3JtF5m8Dl4m~o(k%%qUMV0uDbTh>#x2}8tJfE(ZGYT0vW69K+7h3Y(X>x z5G}IE5^HUhWn>#bw%l&pEw|c&TZXsdf-6wD=%%agy6m>=?z`~DEAF*iVqx#S_}VK_ zzWny<@4o;CEbzbt7i{ps2q&!Y!ud`yg}wtlOz)NJPHgd;L`0Es08t1;gcAdOED*>6 zkZkhED3_e_$tt(Z^2;m7?6S--&unweIMb~2%{%AJ^Upp9-80G}s|?1)R644(qZ>5M z!9b5j{j}5pP;K?pSXZ6()mnGW_19a6?X}ook8O6@Xp^n>*=wiG_S;-<@F>zrFKu_# zO^cxS-hB7}?f2h+2QK*Fgcol3;fN=$_~MK=PIs3F43vQe8-!=~<(Ox#`Qx15rGexb zgf9B%q?c~`>8Pi!`s%6^H23HN&5c0@b2nWO>$vBx`|iB!9{WIEbRH$1cpm!ncp@w` z_dp*EB!UJaIQn@2$v1es7hY^JkoLk$dAxGM3WUM;0)>81^#NFLfdv?7@cjk9D@cC# zDa8}dK>hHe|Ni{+6979Pa^L(|W4nepZGf;MNFGwaDuPrlL`S1vMA$(=00w{_{@@2Y zuu%_ec<_VZ;GjSL5dacq2muHPfcpZ_yyT#7B0MMtK^Q2aF$`oJ1aX2Bz97Mb$m54V zq+mb)`Vo$LfTI}caE3mX$V7cyLmS|Lhd(?ty#N%@HHor-L8Jh`L^T8#1JPoKf;W&& z1RxFy;a(39@<V_4qZ>xV#yHSn3{YIc80N^M9<Q;CJ4m7)1NotbJ~zPDkV+sv5JI$| zAV!2JAzA|gMnZrP2S(ItjVoHmIt0SOdL*$DmxzTq(DA`ieo!9gz(ha50S<X=NPx)6 zqCn7q3pWISi}Ukh0G=Wc7X&~S0--|{G07oK8uOUO1fnv5xQ=mvLm<L12Q2h)4i9#4 z9N5ezHU*Lnf1E=R)c^-QfLNgw#xi{bQ35W6pv4D<ksyCapWLPg#sJtsAccs-Bt+2v zLSiNenE+jfGBvr(ACBW6^=O7HmS~QBgs>a%7{?TsDG)b;qZ;%8g*1%VN^&+R0V*uy zYvA`0PWUANlTe=<_UTRqF@cQ!3_w7U`Hz~aqaL2bL;&=W4SE={8|9G4OpPfJR@NgM zp!f$A2Px9m&@cc#;D{2K1<47GE2bqRVNJKn)phg(r|H0iGOkg=0DR*c;NYrSwYt>+ z7!|1j@E|?tQO>5i27O@cCqjr(PhA>h4*{sBU9pNEfc}u6^2i@H0ua`*;`Ev1C`Sd^ zaae&0HJLzsD=a#Q4L43Ga<F7hv}hPUf!MB}8Ypc5Qt-J+RWAh?P%UA}b4-E%%=Cxw zkm5V4;mKGi;~f6zpf&(F(4hj9mH$AhQakGp<0`17$suX{3IbgYY(NC=6cz_!E56z0 z$GC{qq-Qy33|^e$9scm38|^2^fgn?+0WC*4k_(G}c+j>(T@Z9*lL783#C!)i9{B+5 zUGsp~m~-_9J)l?*VJO2KZuB5I`q5s5)E2(t^#?e#@egA-W5eKZ<4hOSybn0)19~kF zidUTC0w-v$FpjZ|=X%(GghQOwNCqhO!4D69!?JFya6)DrVQtg{7R;cBd^I`a80+Vf zF1FZOr(Dx@D7YL&tVc3<F%8aQV;wQ}>_fO3VQi!W7U@`JJ>+4+1^Kf7LN0joh@N_} z0|S&E<KQ4VmSK)`Z15X6EQm4{a$!x{PaOfc#x=^pk0o0cznYA)q+3H}uFe&|-=If7 z_(09Ll7q4X!6`&)N|2hek{{^+MLOh453Wx7)sKlZhV5*>+}h8mvOono=m8FiQjjA; z#)gq)u?)^qaIUhxFszrYm1Gmuy$GfUVt+W--1=i2M!ZHc!tq9Ia8<|*5wbiYi&M_} zqY~)ou{aeh?M=>_+3*I-f$>|@2-jmDyy&wB!F>^S;B*@Rr$#vT3=V$OW4`%~x5Br= zRw@fb#{Mw!I-H>lbaYT2Q}oC>%2AJgNa7a52>CE>kqCX%gB+UwT<gMD&J{ZYS;OF{ z2Q(fWfPO6XBP8UYJ`#b9p8LG#$ruM($2nq_8@(u%-YQOOdhnWa&>Z<lhdksO4^dx) z#`37gIPTH&d*A~f_ux7*9I+2pyLup`KDydl;&Nl!I~|p{hB&P0QDDo1mGa0&&+);; zeB=Wk$Vfyru@R5vzIW}2XNhy+n_vxp<EWsR20g-YV=;T=hpg<!K6;)HCJsX%fEWC} zFRSdtn_eVIZ)@6dn%J15qZbChZvd<g5>}35^T^=)GWM~=&<}q0DnGsOHEw78wvis# zh&d)y9YS^VL%tUL2nIK-`Mu|31>#6YGJNmBpaOLG;J--!+mTt0ZqOqe=B)=m9?xD^ zio}`qpocViJ`7~sVIN)qM?L~S_;MJ&viKE#0{9RvH&+}N0Pvt^%YY7Z$6Nw2XdOWg z<bY5zw+VO9b;Cdl`v3quuz86<O4v{i@bG;DSb_`zUb7}h_Js}n;0&>l4j}{%6y|;) zK@PL0b+{l1PT)s?*K>)G4FUiF_qTiMWq74$f=KvocGh11&<`H8L><=+;v^647l9Lq zQ_rvoY+wa^APda^4*O7lfhP??2mnq{57poe@PKsy2wzF~hO>5f2JsK9bZ!<`gl%Sp zI5iHqzz17^29iJw2!##wa1P0E4(8wt8wdc5cm(wS0B~Y<gm8$2NoNq(Ru9_H3+RwR z94AyAp-DD~g<8mkvak*7P!Hj-4fQ~5_23WT01ePkhK=}$+n^5aHi;(aa+QTxB}9nl zP;um-4T}{3)HY5u7!jd}gM9D>WDtm3HAKmm4ws-m*w75m5Q~hMjZPpB00%&_hKnYc zdIqr$Ayg03&<o^na>SR6&|nE{AO>By4e2Nk<=|6~*AJR#M32Y}*qDutI1b$?Q{X6o zE@z4K07vIgY;-t<zcywBk&Jw(gJ<B3KV*X#mtNqIYWq+RXcZ6JzzokIivXYi0w4f` z;12;gkl`0;2`6h7Wn|M33&^)vTh)*bd4=`=kcDjE1n~%bHb{(j7jyiOj~uoR|L~F6 zr~r&84FB+m-2iY0rINxoe#%5bMrMfqCtvMllMMlpIp_p{NDOTD4-)ur#>h(P5DPs8 zML%?u{0IOh01rxe1mj={pMVR*unpbdKT>IW1z8ZuXO6L8Zgh1)#t4B2A%PUwj_=r$ zfb^3CacKd-TfJ}&|6qRc(3acq49su@wa5nmAOPDS48lMR&#(>SfM|VrdJb0*qK0ip zmJApaeaLu<I5-GmFp<R24^>7`Q&tafBn!#F5982oDYp&8pbqpP3!e~+0>B6Kzzo~K z58ZH!tGRZmmxpr&Mf`wnoE1nB0Z5Gh36G^{gJfw;mFA1R5CHrTLPlwnZut+w@Clz# z4_h#j+W-yYzz&;ao!6;w##LPQBVMqXkNoft1$B%I!3=}o1iJY{Cr1tf8V_6r4#7E` ztRzLnc$A!p3(p`7%peSmhztBsi|_f3Zup<@)|v$2N*vUkyT)L|SP^VcidnY~5(uBE z$3f>XnCjM5nluj3aE<%`4Y=S9gCGm?01efkK?13wN4Iza(S$f<plnqUgV1W{If4Ih zq5xG>k5><$Fr3N9W+H~3>M#z(Ne<mW41)L!vXGbEkakeYa^iSF8peX&DSIdi5o{n+ z;~<AB7hLJs4^X&D&tySsbxcD4N({0f3&H>mwU~!>3ZN($01C!o+C~rU8FO_v5rGD2 z7gl9Tm61CJoN1M!G<8hs&<#Th4FS*%<e(08TB*!7Zv(Mmg2`Dm#cvK_1+#~8lzI?M z_jp6O4|ygK_CpXeRb}d+4%C^WDQBzk)?`g)ln9v&{`W%^<f|iLl+n0j@F0ak)n3*L zWAS&cfJCj6HhyI$m^0a{^3bgc8WQ%yk?Kd3HHCGPHGap`rR?fr&K96RbW^X_itG?n z^IAdPN)bO~KlPSg_ZAELKo4m34;I9&738nz*{1=ERpZBz{~(P{hz;yuLWtQAp~?^x zR8!@^VV|IZQzs9tc3BVqNO~MAi61*#mFQNjgl;wm4nakGC4o~IWMtQ13`0b&{yC+= zmz`6#v);9M76lFqsD60&sSt4lvQU^l<VvMl51Wt-3pqsX#gaK2P|PZ|APZi)>VjxE zj9OW*sAq81a0%B?aOIFzCX}|g%C@t$ctv!u1_uuGY7yQ*n+DNd9JCL;kPR`|UI6%g z16zE6TVO>OLj7|IFz9U<tGE*}taC_tVhal!xma{-xqo@NfvdJ|^>~<Y4kcStT-gu+ z3k_rtZfu6A+GcQUIgWq1x~z*;RJNU3W)1~sM4|hnYl{$bMTq-=3fJ(R1p&3g>Tqh+ zB9?Vn!)suerAc-FxDPMrL85EB2eGmQak9Fa4ZX0DjaCk#D!kCvpG9XP4|_jNiBs_) zncXWM$J9pYWn_Db4Gr56&j74=#zwBBX6B#_vBzA<ma_%nZc;iTgH{jkAP(Qq4A2l_ zQj~H1n;idpS#D%x$uPZ*_DmE3nWaV$_Vade*SVG#hn7odu1g~Ki-y2p3q0HkuW(T9 zSHK}08UO2sGMH*TMu;HH5k|R8ZggYyAPteHb&sc^IJ<Z{JHZ0!u_8i3YgP=uAPQn! z3S|5XG9*watF=QM8AO&|i{)V;X2l$FKUg<W&V&uguvr}xVkvsAe(bdi0mvnCzu?de zp&$yYzzV1Ta0;qm3Z_5`%|H+Lv#e|E8Y6sb^?(ksP!2HIN<hiP0@+5z8O3+7Yr^&q zOB}%wTxd5uBR?cx3RVoZunMKH3ajAAWL(R(Pz->SvcOx(dhx&N=MTKF58=RJbn6g5 zNiv~Kv&h$Rl>mF)=MR(Xw@nKpZHaO3&<d?U#*Vzm->eF&Knm%2vljMjz+4vqRSua( zY%dGHA#rIo7IVa)i6c~xyJ*eVJR`YP$fQ6Dsu0kPYznq)%cUR+zYs<6z;7g&&R^kd zWyTMudUHZ-5G;JNxy7cuW)Avrhf1u^=sY9ShH>;D%d{NOw!Fx!&<ZKN3cK8j_glGK z?9fa9abaz_g3`!X$wv`5+QI<Lqp)BO+u%VVmbT0q(lm0v0-+17u*j*93IZX}0btOj z;KPxK)HE$`M1@%gdWfqeMG!I56_scARtd&Xv9h|Z94jOlc2T6@3a^mJtRN7qzzP99 z5UTJBtxye^nsH*C)pW5*$aQ9`#$10*!?&2FecegM@LM<~g}pg`Kmt$^wiqeB$frOM zi)_n}{0q!=w)+g&N#U`|G}zN9jAt6bEo`1$^$&v(0OAmZI3)}DU=EKZPKU`%sw;;v zB5Ra<e6lPMobAY_U=W<`(#-(VG<?*eD%wcFl0PJD_26Lv07c<-ct&}0+GKvRa0D0s z#9K0#484#JD+mt=2oD2VTPzvB)_K^O^lapWP_oPzjw}$1Ob~Y+0H@&6x`08I1={TG z+(%KXoJ5GAkPYO3Tn^XM+aL*XkS%CX25i6wPVh%D*9^<RWt<fbYluPY#-d5GW)Rv9 z+)T^$y%3xI3R1{%L_3G&E8uJg-xn#}v9M8Y_1{<g599FKCeY(PZUO;74B!9_8Ga52 z3RK2uSUCI3^Gm^@ogyfj&k02etAN>=9RMdz5Kq0xuRsdnlw0}C-0ueCN+E0k&<oOF zR_O|SYL$+}zyd3925~UwaUcdOumY8^Wkw!C`{`3X>m*Bu%IO6RqQDpd@YD+bG2EwM z3co-P=*7Qe{?JzD#`SRE<bYP-wTdgi0y-4{n=lAR0OyKu4ef~y;c!q0Do91w&_Oc7 z$A=BJU<&(9<qbjAp1rM0eh}^*=`4YHkCzNx3q=%k-S$&NvS0#7APAcv36dZXM_>YR zfPC0w)Jby5^#I1Du-^sE5Kpbkyi8eF{N%iT5?QRQ@gQHG6bV!3fDdSB@qlf|egu** z2yAc!D}V`XU;=C~P7+#Be|sdC91o|c3$~E$w(Jm>Z40_UStC8}Ls9Oz%7Xl`L?Lu- z+B6Q`P<69y0xOUPiqH#u@Y?wv2k=l1=_p^0w(HeyO!qntdR-cb-VibW-wLiU?5*tZ zSOJZCRtYdzZayz_!oUZ2umVTG2bN$7%&vvd-VZ6K@=kJ0_gW34@CuF`^A4fXudofe zE$%o!;D*Ut=a3J*kPLwE2ZAsNg763W(0S(|3wIv!f`AEwFbHW70MIF{Tmn$Jg$=+! z3R7L>SFRBEt>26c$^Mt*T;KIXQQF;bpxN*V%=xIyX>q}|4Q0UbD-Zyiz5*OC3lZ8S zdY^#5K<g6`(5D~@&7ciI7Vb{3_$zVKtmg9w6++}o3~T`BcYfzbunDv}rCOrod;bdt z4;T@F*#Te++Th>eF6OSk_&}6f`J+t|h~7cQp4mW}q)80v@OV!D`}>#$+_vxvrI6*d zUeNpP+1!@Ttla!ZalZ;?5Y+|`UYxG}T@SKG;8Sv2BwY;!@67<QYLzKd0Sq2QXpo@5 zQ>RAhsuxe5ymb}V8LXI4<3^4hJ$?ikQshXIB~6}0nNsCSmMvYr6gd&3ya42E-Zc2{ zA55M-eg1@LQRupf^6KeowW^fLQma})EIQO8P^wj}Ud5VK>sGE^y?zDjQ)f<{|LWDF zN3UGHS4mGXJe4YyN4W+C3T*XiTSR(i&yEdHc4t_^g$*A@oLKQ<#*H^h6&f#Iy>D&p zu0na2RJVx!AYXJGTJ&hrrA?nk-SYE9fBwK#3ngk5E0>)AC4Uy0TK8_=y?y@%Zc-|1 z*Ue-%WT}c&wR*Ux28SM9`gH2muL>pJx?VL=s=OmlsT^22c<^pRww_-7diL$350}>( zTr*OozMn!VSNSh+t=X}Y$~^%GB(OjOyAn*Nvs%OEms0HWPL<3U0;WHI5-jUL4L9Vl zLk|ORPACQ)yo;a-OEJZkYUqJyqR%kG4aN^=q_IXD9mB4u5g)t@vy%jB%9dj2@yErX z5XuO|BX4A~NhhDQDo57pDaIBaeLQg$75g(Xz=XVnGE6bYBoj%{R-1^*R<2YDNG*pf zlA<MLR5CXu%fvHJJv&SiK7XjRvZ;Xz`cbJ;Y=J2M&Mwib^SM1Ag*4LkFf^;4KZ{vY zP?p|$iXCt$%`hPh$&$2GQ%^O`xuPig2Pvfl+SDms{*g1p7*WMFS6vUYwY+-BamAG@ zO+2YCS&dxORyucOwpnMXLetmESYa~&@JM3lSUDGk@x?oz1vgxAOR`lm%3g8Bl(^<f zNv?*TA}6X4HA-?^d+)`!Tind8EZqR=3Qt0Xm^;rodO^!KVTGA3cd~x11-MP6M4<*7 zTkAat<Apco*i=yIaTwi(U~Q=sQK|taEl@jVx#d#(oNB0v%<aaNR<2!1zvV1kHD*UM z{@G=rhn`VYdCYAlFPH>kW#`tCT@q%EiKe>$>h@sPx1x#4o3A^PNg_xtfCW+x<)>?% zw^6ItW?Mi|b&}7xyA&ey>y08li0J^#rswU00BbvN!P!GoJNh(Dh){%dNl2hnyt}My z3k`k@;lVG*TsNcR7Nw(C3@SvALh>*u4?QMXiWSvq`**J8$ZHX8sV&dEcH2|MjWu|> zo;v_yTe0J#R#s<SpjVdb3~DfMXTEvH#-en=;$$OMq$5mN;g0}RQ9W`~n$bqPdfpz) zdGpUVY<8{Vn|_s7K1aw$CJeHJ4m;|ng9!@Qc!iZy1h$JQei6Pnc?*39L||7o*FL*> z<bK-Yh+GEp3v8UtOH)f=1~u3d@^P;JcLzCz6cS>GKRi$g0YJm&#Fh#mm4bq;As^s2 zI71q$WPx2<N&raq3RAGb1N0*y6l72VH@G1HT_Bq(1VWGpy|93{s$mqRD3Tk>4K4=} z1sY6n!u#1l2SdPt9fW{FgFsG)hH|3vf;L4qwlQlmV;}F9NT^q=A`TV^Knec<haLc7 z4+&v~84c3J3O-R;ZbW1ht0)`y8H5$7I361Upo9_%K?hGD-9gw;3Lf6&eM(8A>~4j@ zM3%C7i!714PH{Xf2EYzL&_NzD82}L)BwdON03j_HHAb1TBxzYyFojtZUy2Krav@0A zQW1w0(7*#!$U__g;08Oyfe3m3BUTH6QAnu0aaqL_$xc|47J7hlVdO+7If=tN?-1k^ zq-aGk3Soi(u;3so*a++57l3APQy%F|r#V-`ngG0}8r9f|WF#X{W9BZ7R$N6x9uf*8 z`~VL}z^6g%8326d;TI%Z$ZSl(9C#SAmkcGzM98@fUD!etqF_cf;^B|-pcGuF<Q^$L z*M}g4!63Le$RrNJ30y1%Me&=B(>w!3o0{Yu@6g34L?Nh`J|ks+qDfP8b+L7LFchmO z1|wz=1Vmt}6$W_);~1CAT>1z+`Z-x=C`U@I9%P*0c*aW`639~=N*6?0Rb6pqE6#}m zDMdg6B6RVJsg{Birg-W9OCKu`ojwjBa%q~`mTEx3dW1MpebD<xmegjH<7}OMS%@a` z)cK^f4l*c$C|)rNPB!H}4e`zjHKH?;nsj-nZB*Rqlf;JThZQQSM?YF)C%OXnMz%7_ zI>zx2YapTpv0ZF!o07~PU6x&RbEHz$=-iF0)*scd#j6I@BTl{ILc6pRd6~rAbpSH} zGm8g1$T1Ih_yP$sQ0(zuQ7wevj3Z<due^S1)Aeb@EG;d?DU!+Eh`vP>&8SBJ;$)C+ z%GXBDF&8-IaTZIcp%%J`YNoK1AItVujm;HklD0OE?X)6Y|5L?;G0TdVQjka-7A1^5 zOrY7N1s?ZhhdAp0!H!2Dp$=xT#V7{c!0?0uW##D^FFPxlRn_ztf%J~!Qb7>n<x)r* z7UqJ7tReaaARantM_-6h1w2rr9^u%=`%pw>Y*m;QuiyqaxGc(Vl6M_D`GvK@ybAp& z@h-@D1&w6_wD_*sLrId%f86nodOYI|PiV$J<}r_OfTJzN{cfQ+HLIh=gK~ym$A1pp z($QAWcgb8GDSlCpl6uq9e0mNr<+16r1mX#q5cNF9p$^J8rMo8yX;Yq}+_bEZvz?vD ze`?H%U|lhBrZ5%-O*?5d|N3ec!LLqAdKO3w;Sv96hq8(ECsW^ST`F<cDLPe-EOWNp zh_v=P=0l4AQv?fd2q81I-ejrqntMP2YPEF#K@Uhgp$^pehd92$Zyl*gy%JkBJ2>8O zGgTVka4b)QrV3JAf;X3beOhx)>TvfA<sa<$2B(|xhKsAC9qgzFvf=|M0;^h9><IE2 zeeKH}y~7{HAkiE(lFf*6?-k?-x;*})FPamXC|V~+Uz*{DAk?BC?@&isWc~F^W$NH1 z0oYSyp0<)JosE8?l9b<4VU09|SP#nam1Ae}uCHf(@*sye=s^v#LxLUu*v5r!{`h}X z<Uf}h#m7_PCL#Ib9bB!ukZA~?e~{zU$pi^pB-D(J58m#De-GPT^9{w<qYz1egjvMV z4qEB|E8Fbw2R$&=))kwig|@&3I9$)wS4&Y!t**y5bl7JgiGqS9Ek`*5K#zaJ{xn;^ zuh!X7o`3kfFP}()A(%aCaAdeq)&6=(8}uNTJV;1@Ey{nuj}ZO$-~aosq5oSSnwpPL zKpc{=zha1p?6bW8V+ZdGjwE?JC98)?sDe81g?flLq#Ly7yF7oGKNM-XlDG>|*d`X~ zw=-cr(L0~Qfd^~=22vmeKI;h1gNSfI7PW!E-&nhwqcMMg20VBJUyz4*8;6Md3|f%~ zxB)>2Ilw|$1yVS{zDT-n>b}vFihqCydO)wFpuqz(l&AQHxtqBiM2(8@6?WK$zJP}R zKp28raEEwPhww9!HxdyL1cpFj2?;WVZCWn6qcqxaBR}E7K&c~>n6NQyJ~JeZ-!q5_ z{F7?H10-;~cJPMS$*P0#lSm8&YiS7lNC^o81_Fu)df*npnw=?Wsa*P;2mzpvxDSFc zsX}AK(qM;oP_k{ngCWShQ5y%4i3gC_#Co8QyAUL}W1*cXDf76(VnP$6KnlR~L<6fq zfiOW9nZ;Vvjei)2aR|Olr~=0uwKc@DaM}sMpsDSEB%S)gk>HGyD#b$^6~Uquqd1CI zkPFfJM3E2(S73#HqN#b*#?gowatMHWs0Au$gJw_%Zy1O2fQRfO38~<+d-R|Gx9c;` zXpMrI6RpY-?SPF4(MM_o!-hbv<$Jw>42#?#ig9=cdPvAN@P&Wy2W|*}wWA`)z^|Zd z3sVq5<BKRQfr=MP$x?!kiFgfC05gI(MvsWLLm?@WQ%S|puY;t9JxGEKq=#`ZNDxtp zdTf=vxHn`}9l2XVfdsB|EDIuO5HNd1l8}o8Boa!Q%EdS|#N#w>_=6olw&?Q*@FP5r zC>-Ilg#klELQx$dL5qO9HfPjH_Gu6t%drs@3HuvL1uM$BjFNTWmv*QJy-dG@+=kEN z%wYTy6(l8?S(V^JFZwGK??68MJ0z5PzKV!U9AgSmcnVtSz>{J@&3uXf2Mk86G=z1~ zz<IbY8FC2)K?`|+!5M7Fk_-UkGcB~Ns}3SerO+)BG!#S$I`RR|uh@xsc!z(uJwxz^ z02sB4P|lSA75RudAF;KmGlh1l&j9elKN+7;X-|Q|&MGN7kf1uB%nRG-n+z$Rz(~;W z{E3A!$Z`sR^!r7Fc!yS_Md3hA*_#ikD~W|5g=SE`Y+O3W#JeidJQiDpxGE`cQ6E8M z(2`h{4D$vEHHZu}2+zQ>f1=Tr0H})4j&4v&pd6%9xUx6_s3YCcQbJN;3qBLgA(Utc zz(bxKUD7H|(q;*)?IR~3%hC_2h_txLgTRF<XahG}Pd9V5j<g~FINHf>Ko@nv$c`wk zS6B;SYtg{GyXSa5$$+pYG>K3A9-i5jq+7&YQ7H&54`Dl08d;zJn9z10Q(t%oUqn-k z`OS}jkHfpi6a5H=PzAYThu%CGt{X&$N((My2b)m^P?VSyr69>bCl=+UOO2GEYYpun zrW=_Ee&~yDI0PN=1%I%_BRj>-v^h-SRF6151thf7q|L_^ine%#y#qNH!Upq@%Eok- ztvQQt_y%qm!}6K5Q5BHK^TvAc24gb>^$dV+02;3tKzhK2K#9)0u|^77!Y&O&TAiW7 z`IE}9w|Z69h_cpQa*=PTy9;fW=mUm8v4v*%#Rb*G46Tm;ogfEMGXx|s1a9z$d8n^( z1&jFGox^dtfd!>PTDxXEIe#TaK`FjsVWCnO#rPn~HXE0;@I0uSD(-=-`%6y)k-(e# zhIa6Wj5P#|Ylm^TNdR$CuF%k8aD`Rf$L$fAMq>ppGzgUWj}EIV=P;Z_YfA2vuwPga z-^xsI*_x3Zo?zjg2RQ{%2sDWp5Miq+Zg__P@C7P31e**1aR@(jG7KXr2XNr4Po%QF z@}E!a25_K=Lj_#HLQ>)&M%5A6PJNZmdxt>-D1&%h&fU_j0u7^J&Ge!yseKC<YQOea zl!fAkc6bM0P=hL{1r2;i07Q%ighm^aFhU^~zf-0Ew;%<G&_5yL*9~IXW>~cO>`<S4 z6VFRCrqY#Rg1&EP1us;+RTavOJC8{NS>3>|RVhWBBTv|s-Lr7XodCb?{ffhj4|%l( z=9N#>yETJ&sa8OlSbM-mX;Fn$B!@Db?r90m8<N=RO`EmUrhOD6i5ml~Bh|T&F#Avz z*}^N84)Xhkd7uaKo!xp6hj}<h{4L(=D9wRmg^*eyfMKG8@DHY?ll>)8I0DH~a5R<> zVA+J;aPd(hA<X*Nu{mm?0V*k);@{LbG=rdw5u=7DC|`69j8;=$#X!R?1XADGy9u*m zRl)`h`&m3y*?#q35Nw7}V1>#Z*dSrndf>SKaywvL$qs*L*ro^;)mfn${#ob{jFQqi z<OGL82!mSKiQT(7j&zK`;zoLKl~Twz$Z<68d5W6^neGc=1Zq*@m{<QH<GT?XX)A_u zKsrKIK`TVyGGX6^ss^Q07YCNwGU6Vai8Qn@MGO56F1uiQV29hQ18zvRn|nkS4vp`X zhb^4fE4h}v`yZbrRlyA9{#~FDyks!+out6J0-n`mh7>zt5FLszQ1p%maa&M4p6#pS zNG^;o?Hh84Guul)j6+U!ct9nz-O-pdY&aYr9u)6r8i0IdJZ-AYk=I}NAD76tyf_Pv z)K*j>M5qhUGrEi>(uSE@D1<$YYJ<H0@sWfer~`iRImOdaeO?S<k`GgRpBbdE2NCFb zdt%gD=JcZ0k$BlNdY4y_2YyS_3j)N{0udsiwUq`#Glnl}hT{4vhl>q>P1pfL=mwf} zhsWdE()dW>^TIk(m%D(<l<7Tl^IG>Uh-N+rQ}B_vgXye8k4h8gCm9NG=!V$<V31Iv zebb5M;b^T83YC$#dLRZh2n22bK7Kf~E@q4Yyw%qbg;jb5?|2{OD274`I)}Szm19+r zc%M3&)=>DI!q&G}Fbi5aq_HOJivYgjAce^kP*ut-OW7<zd}{=;iL)SvHb??L#zj*M zj3G7+?v)1`!<4|LTv6DPtb@J(&tMQ+uokV3LROFgmwoAfNMlAhV9mafvIxEg*`9ix zqvHWlm5FT!lUT3ti+_TLZ!imCVC@Ya2YDQf{tOQ7;D*JDEL}*x35JLKrMdU)=fFld zuGWZ+;wT<)15VHdM34bp5R~KQi%}`>>^5k0YhU!jj5zhKd<!M9_Gu9gy1k(5@HXFf zII>QLztf)WvplqVz=mqz29)8oa>(Zhf7X<SQ?VJU6XFPZf`e9w0A0Y0Rgl`eK<*TT z@Pa0j95GHz0lc^D2quC`UgPVna8yoP?Ijk6@_0ZV|BXp&4RT7)!QgO@^k4T4?&8yf z6~J$Ua05EvgE26H9(aQPKA0`Hzz-ak>4HA;`N~3Q1a5^630PUUnbxxPB?@k2Hh*XX zCU=Jx!QU1}@ziJygqR44T-rLcYTS5k;8q0*!i+vF1da%vdh&oh&;@<dp;i4<m~Qin z8PP{!PLQcFS9rG6tFXN22hKcD^VSM5JqU7Ohj=pt*)4}jjTaO52w1O<voJ&KoY!eZ z2$Kl_(m8@lcO_S{13ti~PEd~iaVMv+>;X@Z*fwxnLB~j(DhA&OcfyZXxXVhh&a60e zc6i8oa0f_0f&icfc@T$-eY_Vvkhf`H6K$R9JN5uLf@Ke$2l9a*nuO1pFkAZSQUuQf zKgx$1F3S9fhIoblRA>h7Q^Jd2bgXF!^_BH*w3LdwIC+?dZxBCW8+F6`Wbb>%p(}>W z6T!Ib9F4l4JR+ey00JPOfsI<1PpoXCAn2Mdm9kin7j#0cCJ5@bcER`xb|AKTfCMVI zxDGyQ#G7||FA(xskbA5aW9KMlf1m)kBtX~*xWI8&CU9rj#A+D&mKF&C(uU@gmt%g3 zLoEu(<1~tM`evBaZcqnU?VGHc9jdnuqnQj>q4NOfoIEgrWRH0_&;TmX18Lf=xuABQ zmk3WDtjD~RK(TM`w7+Y`DxzeGNt2AHGVyT;hkAGikEaG*H%<sWG>`#&uN%yj*G|cQ z5M8Kr`Y8neH_(AS$fPef2(PC6nk_>-@ol2>(>m`?1uX5q_leS12YP4+)sKge=Vb-W z_SiRh-*#X85Hpj}1wE)IJ_vvx(1B$)2oJD<gvd8nsP>+pO-K=pzp%%)NY;>uOQA%I zzqodw0El|^z;Syw&k<)c&;_M~@x5e*q>^tZ4Bf#*7*_a_s2wBgl{<N0KaQ@+8WX zDog%r>GGvNdf0xII+ZGwDO06Hy<&7^B8wF%cm!Z!u@uFd6I;FdS1%sDmn{RhTxs<x z){*PBa+T-xYq@%_S_LSzYE{mWr&ih0Rgc`(ukyIk<(hHpM7kH_@r}ps+q`xN15vBz zPn<vhe*x&xlN(na<HuPiQ?6|JGUm*hQ`YVJHStVQrBtc9X=)YIPb^HVSV7S>#aFCM zO+0(*6jOQS<i+#a`FGvT!iRT;n7CdwooCOEw0+9et8V2Y17CMiZp(7q+y(GuXHVgJ z;@Uyvo7ejA^y=5MZ|}Zx^>tojhCY=u=cxd?0=y~0aaBdOsgm1M@x+H$0D8T*AZK-X z1rI#nG($=$X_<7}Dx_=!4qpeN_mO!P$-~V&^!Nft6`82>jyU1`!wz)}$~Ys9HQG2? zeDl?VjV-RI;@l{@AaX(xuWVEbQWQByV22*sbt9A)0Vfwc<A765C}yE$%55Qa8NgZp z;DAF<Z(kv(Ac7b9whlyIK_yQB^Z4V-9x1BB&NlAU!<&KVr5PolfeJe4WoI5ZpG?1; zqRMTg?5D>Bh!j%_DWptvA8lX)XwhxC?N;WRX!`jip*D6lpFh|DQ`T~;eEAV+6RAQ< zGX-{b-k%#W=G%+k1TbfvD*iK10Of#F&Tep0lxwNYI{PfN8s#VteTvSyiY|=EP=qeJ zw9*QaXR*S{L`hm?8){7z7%Hg=jvB3uQb`5cFQT1=X-M~;MhY<HBqp!CAu0A(JN3|M zCp*LnB+x}u!TT`85d#YFygSzGs4jR!TFkelxN_TV7G{LsbGm#poj(*;<gmp5?M+K> zP0X3J9Ie_w=vZ|fwWQ8C{uo>*BrS;(07S@Aw`R*pE4_4j)5^1>Ew2<)#{@+HqYEb# z%KR!vow}l1Jn*oqAg&)Wtr=bp$^%cTzmT%rL|li&O3gRVl`}`A`r<|a!nPPyh-9BV zIN^n(H0?j?RMSi*MFioAE~A9I=}2a^Qp}!wjUAl3%o={xwD8bVj4fqZ7%NDq@AOMG zhHVa9MF@^V(cW#S$j&(9cs0@Poj>XM=fMlFw1;NCBaj;<^r6cuq!@`3Qnp|&pP9dN zejfJ2s{|ZG?~FdmDq5a&mT1x^_WJeiQbZ3$fKbG<i~ooUy!Q3m4{!1RcW)z*EJzsg ziY`PE0Fja8CP<RrKl*{b><R9E4LTLI>cKH25pX0o5rrshfemo@V}TSw)jIw$yI)y? z3P}inIs!lrs`##f4tyaD3FRTaw1gZ2fkqv|(2QzS>Uk(JAX_l^5A^-Xg)s~X#b6>q za8<|@N+HQv4p<F;2?StNk;p_C6OR<OV<P^m#m=artcGFnh-N%vjgsh+#E|13?!aLZ zYSBh$h+-8_9AEf?SdVoqtR5=6;!Dt265#Nq9^DuV1@BXmoE)$i^yuK-ZWVyt#p4^` z=%OJ45D22x!yV&blZON;%277$K<r~jLFQ41Bs>B#-l#`2>_xf%nT4+u(%Yj4W0yWs zW`r@m^rf5PQ4ek)QhXQcQd{J~4!QhtD_V>PIpi^qc|al|R}_akBI1=_{xXZ~<0Ux5 zi4w+mlbel!lP~|mom#lz5&d`zKi(lBS*9e4dZeB?ySYAYiZdf>BvU=UA)Cp?Ek7jb zlrDzI7<mbVG2D<QHIYyUYJ9Vc>`08x%Gl41a?~R#^P@yA*^XKu;SIh}$2`Unj|57{ zRWifl>aek=DprMM6R~MWrSzL%4s$FnU5?y5g05C1w0diLkwe-M(TN5?JnaZ(;M$eb zsZzCU5QG!5hS?5xkkq6t*+vI1>JKrEg;6hsBKdxSjYkgu(Mh|^>6G}?(^j~uHnUU< zZi=coxqd?&0{KN7l7I(l_~RX(L>kf9QPssVc3B6~9AFIggf{r%Y2pw^Ti0<Md6ac6 zcRgq+fT4|lKvI%ArC&cO)=*&*b2j!-WC2sL7NQQZCA;b?J?im`H>9W;DI7;XLMRW7 zHnzA_ok|jKJCAp8V-I2QMQ+DqTW;=YEU$Pi9#<g>wZ?>|e+*b-8Cnm3e#3bI@N7Yw zvni(7kZtmaY(0okg(`q?n&Xh)V!mnI{Z>^fG#&1H+d&U%>>&w;@R>IR?2_UBav-m; z#ZOOin^{o<8{Gvdcvn`H#m1+Q&7f;4ezYaL+BHM})c}V&x=}E0SfUN|t%p)onxI_r zx5hD?pJ$Ne72F+<8h<cwOxj^lxvYsX5#boQDku`tutF5AYm!^{8`s3lvyQCTnn6dB z6YZW@AncGt5b971cEos$EtIN_(|lvK(M5zl<HjI@U<jue79!kZ2VZ<fI)Wbb6yxG@ zJ=_~fycJiC0s&1dt$fyw+;M<hIt7KmQ4d_4A<TD@hd6q+tFLHS&7RhtO<&?&r(pQL z$cb|%>yf*sh47~S1!+w7Y%a8tMmA55iWNU?Rq9bWmPx{wqbD-1VUsHW<GKlxO%V#I zaUv6L2tzHrky~<TbG*2232Jq%ZQ_}&b6$D>$#B=<ka}zb)%|!8wZHNrUDCxj5`?fZ zz2w>av?a5qb!?5N9HCfl3RAaf^rcL}3Rh^#6s;hIDs)kdPK03wL8yh#R80?fG)c$G zGUB!~p0qo+BqDcuGpaA$4T%u>;ya~Q+gf!J%ekd`b}>}GtAna}dRAXKAw{Mz@(R+Z zV%fR?h98131OEtQJlj0yW3sLBr9&*Pc4pIx+QE%K$obsw*v5<YYH?l4CC@2`8(LXD z#Jx(gh~0*(%uz0(EQLZ8ZEt(G_H&U*1b`8oFbe=V0SAZcK@|Ie#yi-AvwJhW@Z5&r zU#6LfDj4|O?GOh<D&iGnowhD8i?>Ms3}{P7LXwEqW9+oZ!Hs`V1AxE?#_3V7hddO5 zB0=%M3WCA{9uy)Nj4(nGiU7G{Fpm_};Kn#$M349wzW5KDAvDS14z41BvMrfrZzdA? zNpjjE5IjyZB8=ACXfPa|A2b8sI@Onm?!5vD%ridG2S)6m1SM$y3~Eq=)l9@SvJZf3 zbbx~a44?#vm;@oL-z4b5G}XiL><Kq;!#7MEIqj42Jz%Lw#H+yxJAlLTWr7+|md{Mn zRzS!kot;L=%W?3~rUX?-M3F6>Si}VqN3h^jJqBNZ!#4;RGcZFKgaH)@K@R{yA0UDc z`k=za!9>u38_)qC&_MtI0SnmwKn1+P4;Fz00D%wq00YcG7zDv1Gy^dZ!*acYfHf6C zd_z41z+OS18M=p|6c0IwVPVz6Wcfl&7#(Ej7e=Jv$wA1K)X}1W#Bzv2F<^tBu}k*s zn$n39T|h*MoQM=iK_=7!H)uoL>B20u!Yqu!L=b@qK*1m6fgL=-4@kfd>;V-7z#0TY zFqDGAbxSdXf*~M6Er?<oh(R0FK^x3jH2|JJv;(z$11}C2PMskzsz+zgkUY3Ubh#mA z6`ea|T|8*T$;BWz=mNr_M1}wZI0#zVogK!B(^iznIMl-+#8E^{Q#b@e+aU=CVUY7+ zq8kW-4rl-pR6!nGVgR`Rfu)2`I*LM&Op`l6Mm^MmA!I@w9KjJVfg1#Zij0GR)x$h| z135gTIuKVdPNZd|&0|0WV$=hH4M8%BM>gSEnKTHI)q}TyOqPKJBbh=oTw`f*4$S$^ zAcj+sy+u6)f+38TIBWwySP3xXV~{Y9F6e;`tN;!Sff@vYAP9mT*uft#K>)<TE7*}v zgbSrKLpbo_ICMi`2w7nK13-oWLGA%0Ji<2`Ms95bwcSYr9$oKHq+5D~**%6=WF$1; z0TMt0O3lN_L4@5rkY|Jt$DG$mm;xz?p)(Di_&HV~j#5iJ9zE>ABfvvDc*8dUUpLT0 zH2{#p1wbF@0S!$5KoYzo8vMahmL^mBKs~+!er(xUkV5N31h!GzL$U+p`NKR6jUm)Q z9R$G<q(Ln_!ZRG20d7M$pvri?C31RHO|=9KDc=p*C0_DlG%ZX6u7s$WWi`+hdWl4r zyuvp^MNKK^FK$#zxPxC!LLk%vG4zoHO#&hqK?<aR!vz5%biycD!BYl+X_lr_2Efk! z+fAf`iPZyazC;M^%r`94fz|^wY=bWZK^UmP5b%L8-~u;L=Qik$nI$KOVnj=fp)-ZU zH@br`;6W8+l5O_Pag50~F^o!FXSL81AG%aqWX`oo<S)8lRWT$#Kmvq@K^oiv8?ZqT z?7$9$0VhoV0wZ(_09oP+2*Dp*#2=t0RPvma&dO`5kyPZ)ICxKPF{CtPLJ&ac7zhG1 zK*N`++BmEb2zDq%Rz(Pjn;5>sCX6X0G*v_RQbi;NM!hH&y#$$HLoA)-N8H3IY@RYn z1xV;<N4dm0RLP6511{u3F5rSJ><E)G50cDU9M}Oxc<Mzwnw1V{fjTO-snI%YgE;uo z5J5vNK*A0L0Uz)IG<d@SvIEbsnw!4q6%7~9klH6C!9=A{0Q5{l(IKD41Rb)(t38s0 zn1!q`3ZZg}XCaAN0F*#$zmdZ`ffN#LSV#RyL`>#8w8Ya41T$31rf%v)M1e(s>O{~0 zMHE{A@Z5m1{|$9)h5SrQo4|=Uc*8R8%p**Kk?z4B<U(Nh(HedOgfz*nt_MVP+%oA# zvK-yUS>8i%gU>L-AcR33_*Oq;nm;^UTT)-h`sHH`Q!20m>X_iU;3F^q;>WVX%b}T0 zh1W~q>O)c)Fi^-Vl)}!cW-0^#9~1>p@PJY90BqDoMJR=92AZ-O=z$`a8o?$zyu&+q z!#t2$JxqcmguxEHfgw!OJOmUstOJ{l=fZA=Vp-cGN$k?B1DT+boHPT97y>h>gF0-3 zkqO^=nCd^2q?Vx0MLf|>WJogrVq^Hx(%E6VshzLc(<&IrEFEnCn1IldMQwzPDPU=! zi4J0V|DIcUMea;Q%Ghl!074S%z#i1XG#!ru_Rfwy?8u%iO1LhZ{DZ1=OEYvsVGWU7 zluFXo1!LGyV90F}WP;<(LmP=}^;P6=Y}(Us%xOH4l2yc_utId~$sGRfVuIeu^_pmm z%WaGcVOqo@wBAJ!+(pc*vJ&5!Io-qBEje^UoCp{-P{SjrK@wnLGfdN)`ATA$t?Zga zd8|}RjKhOr(6=<hH=NJ%%1~XjM1m^SD<%OX4A(Su1A4@+Z~zC7gp2chR=^dM^$G-B zu<f=fu4i~}DS$6}Aspox3G?X3E64`C2FTLVD`G}j`%({IvJE_RAUv>xRtA88`2w9h z|G^Ck!!{Vi7$zu$K***A@JP_^gGi9u$i~i=!neGGvO3G}7BD;*AS6728e{@LFyuUh zLvbq8!@fsc7zRA3%G><eh*`wox{4~?(zlUe$ZjuHz06qonz3QXUEK##gwIBth2~=8 zZ?Kz7RtH}|M0t4OJLJwZwZlJTLMBiF73d~rG2~ygQJ+e&Nqn0+T#42!$DeH%2c?We zMu}vwgFA$)KaBCPk{M#GLx{}CW5~}iJuYbgTv7-qTChdyzyt59PsYV%3Xj#QtO5%M z=+Dl~4X^L5pl~Sda5ut(JBVmMTrxF4f+6St91uo3_>4F_Wap6b6h}}s*aB;^|E4O8 zg)YQ|vlLPQtZD$f10)Q=M9D)tY(o&YF^v=lsf~qwoM3DA3)_64%zoO-?A!OEtSXF4 z2#W;Gw2r3ba3jN{_2Es2^#(VG1J+%#FBn1)P=O^pLMQnHJZ!`C%`7|f&R0N0K<R=l zRCH8M7|*dnC_F<eYp{(d(<=plFc`uUOcX<O1NLqsdnkyV{X;PrTft?DG@FLNwZdgW znKrg*abYvB1@c4(bAXn_;4W=q9L-#Kv>k2)?D!6qgmFBK14%=aFX-kD@PRCZg#mWM z3f)wUD5h7tW!DK)GlT*wAPG;S;BBzZ81}A>L^7U?Au+hvM7hH}MC5A4|0IKK#a^|^ z7}~<*02^z92~qtDgME{zoN)Jwb<7a5Fn0tYFLFz+_D6$tTWfP&umd^d4lR2FB;cSL z<U)c7MDDNyvP_>OK{iE7#;=S{z33sPuqKia6$3NK09VAsse?cWLtxc{A0e+g1U4+I zjY|uvXeb4+Y09G5LN!d>S}U{0f%VKa1Cor(m8!x>#L9rU#iw{)NU*OX$5jZuv<(Ra zHPixxo<T08!@^WaV3!<CH+KeqMgSB8_>@AU0qAYGf>!^-UX`35heXKYOkRw`H;`5? zgh3odSMZTs0|yEW3X?#6j7`W^mjGyKsFm~Hjp6CVZ>*@w1;7)j|LjE&GQA~Kp9na7 zJTh>&1KzfTtFm|<tie9$2}J15RwTwtCZ}h|gP2$^fJUp8ZkZ@F!>`CUd&IQvz*sJ< z5_rSdVn{N~4t9+|5O;HoS*=2TcX%tv6r4D<r(N^n77{Trg}mC)H0R55&=#L~ZdW@p zAwIOBl$_nn1;0iFKYRitBteSsFK?3rV?YSiI=4{IH}H}Pm^XtdT$g8I3Rag(0J!(s zifr{zM(;qxGpW$|VL}@~+qrqt4=b}im3Ky*H!yIC&E3arIg+iPdgA_up<9=<o<(f` zhpXh3y%8Eo2znh_&zjKr;~~b=_(B`ZKpkvC!IlG6xUFKS|2ah>N(U!NtUFpxXkJ?+ z#@3zLfZI7ofVL?M*f$h{MAZU6_(Sf%17}Cfad5+JM5VsaOyM%{i1Qb2>oS<P7Rti* zqR(h`CsgMSnzy4(a8Te^0EV2r2qe^j4B$Z~T=Fm#OF6`}86rrikfe6H0{U7A&rjvI zeB-{~+gp=38%tkgsY4-DK^>@rKVUXo<ZH!8$w+2r9RcXRtb#Uh$da2))N@$c8T!EK zJmAI_Lh-K1CuS+x{Ge$LJ-CBXEmwl$Zy4Z$w1urhl3_DWWH1evw+I_6+;K+4iYZV7 zIB+qI5uQjuR*3{a(l7n6G~^yVw8YE@m}A2!h{B=_|CA^I!-*lC<VQOMZN;8=OZbrW zwI_16JNn>RWM^~zsF2g6axpnf6JsPe8Piu5sn8r&C+OEjAytFUhc88=egJGfJWy>P zJNf5%#L*#QJs|ywF2poNQ@xH#*E7gku1%Rlq^jg2QHjYTWe>EcS*RtEKzNU=-NdnV zylhvi9tjhM<ysnPl#8;@c*Ut!21bIn!4tp%Km_3CZXUaD>i(_!7l2_yhYuk}lsJ)M zMT-|PX4J^=-$I7+{K2c&EWj$0tXNqzS*p~pYV`cotJkq3M~^mX-poiZ-amHk0<bGo z#Sk@h^X9>$SF<70jZdLQby$yH)q3&*tg9EG|C+91)v$qs_l_M+hfbxYRlAn0#dYf( zzGe89ZryeA@XCu<uUM;6s!p9UnJU%Om8EP|1LrTVyt;Ggww0WfF5b6Q-{P$*@147G z-U!a4761>9J=EOEbVn{g)wpmc$Cf=i;$zBH{rSW8%cLn&8cVIRRqSfxc=7Dog=|}* zW_s+{iIXWzMp1R%=Jo3b51#YO^qA8Y53%vWc=Ym?t4dEjW2~*|eatI&e0}?E!zcfa zH>NIIEEys!D&K+|4yMNRgYCYJ=wk@8bvASCF1_Nx%OHl>p$C#AsCeWTdg^J19Cj26 zAfW|OOc5iwAcTpYYHSJM6jf+c#UdIR|7t~-2_?kqHOPRZjH1S*tA`jh)ZpizcIHus z9PTWeFv##!WXm=9B9yN&`RHq~$}ho`$jjv_%S)+ZY*{5R!B!D4BR2*61)Fl*OE65f z5_~Hjc*^;P9oFXgrH(4<kmVnl{250c5@8$j&POME@VJ=JRCBPxDk6-fR!C8dr{o}V zw7I;Xdq*Z>+Nh!ydXO41N>Cw<Rn}R<6!oD5;nD4v83QvZDw9?r1(?O^RE|~#6{M^# z?x4i#D1QQgB#a=~$fch{$Jr(!TaWFQqPqBtshn3@ab*?Xe8VWPS5m2_oa12q@gls= zBj+D~P)(widI-u)LOZ<;Sm1%v|4Q~Xa6zI6n>1Gm5Ywl83$__-a(mTSf{~@qqkrPr zhMk$9sU-*`Aju}Rf5;i<KnXD(_^}D!x{BNY&`q}@-)LM#lwZUuHa~+Y@`)UO<}pNH znZ!XTx7^}w+3BaD*6FOAX!1v4hH;b%*q!UKnrgG4#xGHE*6BwcY696I3_<2;ryh0G z2?wXJz0C=xkz7HEmB8Gjs76&v*|}$#a)Jo0=7RbrHAs*!gf+6OwmLq#DX*OF1pSEz zoMuG%OO;EXqLHv>hy~bkWTRxL9dAIa2Ny$jP@@*4=u!L~rXxH3zC71~F1L|L0ahb7 zJC`#apK}j#)Or-J=NUKf|1fHta^QiEchhyxUVHI)4;P$jLh;-on=P_g6;r?=*5WRK z-kv-Ot2(c<dEAMqmNsTEWRrPf>gJ#L{=u@WG=y93(@28&qp)9;;uI($-_3p_qW}!2 zYwOdG@&bStpUk5kzJNm&GNBHCh~pjTv7nfeXFwIMkRn%-$a>a;7w&AXbA<VuMr_uw zZgkB(Fmz!=ewaNNI%slPfeun)!i__`p$d~|MnBr|4{kuGDpd60m4e8^7GBYWxmnmM zg43{#tVB4)@X2u^bVVW#F(~ZlMgZzz2{nZ9AL8JkJetMD^{jD^TJ+-|S7aA>jDv=& z$QnZ)ND<%ksuVlq{|>CEBqaA;?=E|yhd7vYC||rm4S4Vc5}m{-i(wFu6H$)8thO6b zh{6<N#7M-zxQbT1LLTp`(0neath>}>9B|AA9^POgq}&ByUTRt?k%`RY$WSEUctuJA zU_%>a#8<M^MLleJ%w*~kRzAw$H;@v5elU(u%*f3=MifBoZSz+8;SXQ_6UO0TDmba2 zWpNN>thzu49@~%!9+1F^evG4+6e?!!BFRpLPBKr&k;yAuAtTUH(^9s$rh32wvlK?M zfS1!}qwX@60C=MvAo2y{-tY)+Fo_)LT<11zlN?Ho;uUIPNlo3=7z@_rI0-3fCP=0Z zJC5Uj8EqQ-|6aOKrRr{(8q`HA0E3dgUF0x{smCp2+P<Y$1Ulc~22$FQ2}8)h4ZZ-; zAc>jFg(A=~@_4GHTuD)eyn+;@%Z>G}CyzS%gByFOgD(Ogj&UH5eexnxN4J{Tr`g4K z^gt6!P;yABf)O#;SlKC4s91~mqaEX*-^Vf$1|}5ZQ1uW;S^Ndb%(5^!4($dhS~1aA zM$k8OwW~iUX(D;-&>LYe1VRRDBHp=0t(rBi)8z86b=(e3uPB97A2wN*$cawyy4Xb! zt3_{a_ZtBqhdabU4MPk;4Z;8sJ;ni#JV|neNVN-InAeKfvgs*=5gstYk*j<bcCht$ z1QUE=|Jo=*hfxpG=3zm4Tm`obVaIvLJHP>qR{AO<HB&`h!C^w>W_Q64$;&^!K@M^B zgBtfsf*^<ylX_^2Q3qCGQ*#3jY~&3<S_7jg<fPvX(*-)xp#~KK;f{BBBPgxOZAB8= zVI|XweRz2=ICujr$yy{Z7ryN%m#mT89H$)AQyDgyVTd45p%&gSl{|<#T&<oC#{MWI zVFL3j%2JoGZ}Evbj3m35C<Vbu&GMfyHl_*vt{R=YVWuz@7*@RE8};xrpx@`EMA@q& zz6e7S>X41k!Yv^?<>s0NM#&g+PM%WHlqhV0ja((DBhoP%HROTGpd6XQkhV4VKrJtS z|8b`tg$5RdDdHxR%u*o+CSb0Qtz>V$1~209MsCyri5&!Ce;}Hof#a3rfQj18%?KZ` zp<)uj7znrTU6OS6aEOkmSEH1y^{wGO8Alltr2gXaxS&cibScslG&;ouiKEklA^Y8$ zjZizpffaf*qYgVbjX1n}kZrA3+s8^!71`m%1qx5!hKZ#`@ky_Ec-K^cFvL3`mqBc2 zm6Y*z`FK>T>oOfj9`$%CU~HDihS;n?#Nm+uE8cR=(%U$<41j07(T{IzC<%~2$~!_V zj|dHy!R}lXJM;>pUr+fWuw)4Zk<%i*($5zpL-{-`gmqjV^yO_2^`Lw0mr`hC|7&up zm~v4V^mzM79g9MWXMBN&B!t17A@Wm~cY57!vGpx6fl(Oa>ha*{h#v5;?mxOg4`#H% z7yZZ(R^452w~wASg{4dacQbc~1)DIb03+#i%yQCegkEET2kl0Zi6pe)5#a#JH@>0M z9h;uX`gxE@76$pWi2D@sB?ncWQ%8FEf(i(+W0Y1dNzu=q`}gr)GlHjciS(*dJoH!h z*OGR2e03iDsKub*;0qz6`D50ldhyvR60J*lnh@)^DqO)8z5yH@gC6{e8PtFq&<rk) z4E-GNSi%Jx3axV@h{_t~6%eIZ9#AR>j2!}CkUXnx#48No;1FWsl6oif|M1W1M8ZEP zEY75&%2Z*8%EB8uhzjfllc3|%ifaRXaCcIO=HvmQV36w=Lfov0DzIYveo!JhV;saG zCjKE4>VOIk0T=#9MAWVUABB?k;;H^kwl)IJ8i*BkC?3Y49uSZl{vpk%jtQGE4%y<J z&}47G4I&Q1CF-F&dSu7s5GuNg{ivZ1!XOM}ff_)Bpc2o;7KD;&?y1@WXU>Nd2CyCc z!57?Mip0SkJTUb1?hipxEl_WP!svl=2#f+?Sad8@Rx1?eg&e?1CTd|?P^@*@hzmba zGMY*u9x=9n1qP!626t$OhQJrv&?mUi6_rsu!lfRlffQ=yH)!h!|Nm{#-U!Q<kuChe z9q^1_U`KYmK_uA04LuRr<c)X!;jK7M&KM$apg|kzVGkZb!0_t+vhf~gBY?;OqD<iw zY$yQyjZIX66?8-<WC9;!BjfyG8=z(SF0Bs0YD5r1A-<+?s-z+lA|uuD4l@D<dqot0 z;U5A45>f^usRkiY5<kjBD=LLe*2EuEAuztK8nyz<;4med%?3N-5q2O6KEZA3;o3B8 z_^#_F2M%FGPAP8gbHqse5Um|Wp&6)Q2%<wI*6w8zEG4xPBZMykf1%%)&%V?|Frt!T zpe2LyLg=>AAsQo%CI{hKqk|f551L_^f{!R=?;Lk=9eAx9|4?E^Ou`5|viU}#7=C~n zpr{=du?N?(F<G%OVyw_;q#s{$O-$hx(&z5-(lO`dJ*cQ0km4VrtqPhBiGa_bJW(Z^ z$~l~o6kcH!oC_*EG7LrG6-*8s2CIaIkG*)4Gkr56@B$p*NljoWFijybgfq2T@i)2h zJ)Yz50>BsQVDM7R@Yuor?$0QBa6*pbdoFXrA}=CNkqm*wH5ow$-k}}bA?=cpIo;DH zYR(@Z>=_%#-vTgjCdO*sqba23JvU+x-{JO3YWgyv3aa1{zH1)F;TtH@Bu!)?ZsKq> z!X#nhdx8fbIZ`5iqsr(@73Av`P{0?+;dTheBqh{8|53Cxn(3)rVIcqV6%>O`&N3HM zbRvXM9>@W#YQbpsz!%y<F&Ffz!tQ!>>45U28LNR5_GV2oLKj$KQ)-G7NI@6spa`(R zEW515Vy;I06EC{VDyV_3R%uGPA;bJZofMBtrQ!*ZVjM=W1mEFMyrCSl)K1crxZ14O zl=RSW$P`clwoc&{WPlTZVJZFr@%*rz)YLacE;qXDb|kPEis4G{CghfFQP(0K-XR>w zfgj?*9m1*(p1=@rp(;dVJN<0ljua#uPf61vI9NhTbwLk`Ko^(+8{XnejcUCx)jgY~ zBR-}a!eJ(G!ymG=S7jrBgeFJZLA=@^31p!f|KNzAd}1*fa5?*|ObE?YOCmfa!U<L& z0F*!!0$@`(Wl(p<vW&GH>=9Yj^iti``%ng)?8VZ8U=Wz$AjcuCRIoQub<kRMNjCxt z0)Pbq;1yIM6?CLZbph30f=|l9TFo(DQ?e#3mLn+EKK_SVMH6=1pv+9A9LNDLb4gY6 zG)V<^Bf>RDpz#$Zz!P9A)u<;+i8Nzv_GTxe1NTH*uEH1EU<Wd-Z9<G3%5i|&33CD# z7%$=v;vfKQfMs<74~hU7MgcJtV_n-5XSH@~pCav?t*9U&2&j#N>Y=69VMvM8-H?=9 zHNp-8U}Xb<Q*@yQ`al<|HZjWK9T1i6|G2hq{kA!qO&r>T;bs62G65;dc4TQ57vGCQ zdd;3z4<nkkAzTv?WT0WcZcZS!U;nmqJr^RbWF2y}{kQ=VJ_r(Wp`-)?B;dh8P1J7o zq8jXpZ=y>h3bP36z)1@vEL035KlgWmmm&rVoaVt)r~wbu;0=U<8(0Mv%dx2(DoJZ< zBiz<t<CY~(01<S76lQWUx{Py!H+(&JX}~LK*dY_1AbCHjr2gc84DxlUh9~s&6<`S} zY~d9U0SD|>?#Qh~zs5wwH-H6r{b;8dq~#3^!3IqW9PUz2&^AG$cXnaYBH{oF;=l(2 zfCvJhFpZ!O$VKkt<g$2GfJu03|BLQ8G!-7m!OS{BtaQK)u<*eMszM%VRk!sOdc|8G z!UR^p1RCNMbO8}2Ko>$mzH}x(*HvOmc!~Q~<hp8f-=P-X00#=87E<Gqz9C}EO*uub z*AA9;pJGZ4p;m*36^<B7BbH>Dc#Z#7gHT4q4n-XdLA3S&8f3x%uVq^-CVE{nFluH- zUP%{Z01;k+TwYUH_ArTwl8qU8YoWu9JECk$rCA}tKsO;9%0VWmHA>c&e!<g_py^;E zViiU~NBZCd0syvFffcN*XZCi48#$Kywhf6YD1TvE;=mHTK`Xp#9PH&mdTr5sLz@1k zm;vM8;&v2t0S5?KzJfy)|3U%w>WmR(xtiUzcQS5YWkMd_Pi-&(ahb<Sh&Gr#nJ^Zq zGL^QK{*7UuRNRE6@_M%-t$Ci?7>{mm9!d)r(&h~UVSh{|DD~78{`eH4v7r0WH927f zGJ&p$^FpQhm9v(fCAvl*IWK(A8-z0eaN!T?U<M8W5~P8D>VXwPAruJOkd7IhWw4Zs zfo`8Fwrm7pqZy4OdZKMQMLRG!!65*Mw}k$I8VbP<rezXvAsB)|7j%JUN?H^MnljHh z6jmXrXCMqxnIVw5BtTMqu98M?x~tc6OVE;t@B$W*;##=D7x*9!c3=l)01+nPsE+{> z3wf@AxEMMC5ki2F|4UilB1mU|K}Pqh-mulH3Hv?41&z9)8_N285djfE00%-K2zH<d z5P=gIffFp76Fi|0X5g_sVS7_q8Y75C6oWgyw`L1FwYii<{KcNvp&P~_7)If!b-@s9 zyQ5Pe1tfq5Bp?MQpau-#v;CqWvc@-1qS4M{eTr1InHxosvMXC~l|(_AjT)(~`?__3 zYPnZ}BI3A(G_W77xy2hLTPy71haR5lNu_(erCUl@sm3Bg(O3bw9~hR$`@U0>lDaH* z<H-~P=Scxv^)5mN>AR-!`@ofvl5k@<OR)mSXe?8L8;Zlg5xl~cu_6~d`RL2W6ipY@ z&Ot3a#1mYw|5=2S6Q;RJP0l9I=Xm0@`BubXTn^dFi_#>;W3Y_2d8-*S#(A9kx<^9f z6B|e^Ln*32bYW#|GFh~<$C+Hgc;~^e0T_aZ$T4CiPz@Wxp@(*r_?o=SyU#>NZI!J0 zsvkUaVIm>?S0_%?%h}xJFfs#W44tQ{%7G<>V?wV^l0Vyg&)sgu-HaO`io2<NBC1N& z&Q!;joX-_~p)gW@xnY)A!YNh4B<jj6eIm`*e9<+%!`#c>_Tn4Jg(c?vBFx!O>nf2u z4bdld(^-A1V2m$XAtuveUD~B*K1HKiJ=Y;^#%-<@%5~H&0?q<p(Xb9!>vYw1J=xc) zajm8=|I`H75v>|up)5M^E$~X&v7OVIT{qIiCCPmJkQvSf@}gR-9+5rU(cO<=Oo3`l z(s#}jO1<YC4X>*G+|&Ku4G6}@LC8DjDPZvHh{HY9?>a{g-wpncI=xJ0s2OrtBXT%! zfWa(9&YP_3;4MCxuC+zdr;u|-hb5wr!N~5A=i*78wKhsyW5Su{%i-CCC6G9uD!Sxl zo~e`^HY}#*oPERTP84YJ?v4XP2!7^;{>8M_vEpf-h8Y9FA%J$UjhcSwp`PaDqp`3d zwi-OxW70#fi4SA`7NsQW!5(T>Qy!w66p(q)kC3vgirv7v>%;!-!=^5_)kOod|Kj@; z{~#V4+6wRBzV9oi#Nq4a_}al8g8A^%EE&-66+e42BOPPi_0EOx^^L-UrL_0e-WNaf zYh~N3!Pj-ZTM-G~Q-LL5Gc)0V6*WKg2?kNvy(#xi-%8y#T7fvqVt_1C^>P1LBAJJJ zt#f*Vw$MdDd?nR#B|^a__lLeeou;Td;^vyVpmX?)&+;KM9r<U)Ah&{zog&W};vjXO zCNi*68r+~wVV3G)aAt!0t$$#chM=Zjfb}S!Is&Yp;yC^!(XS-NfT43_P%HsLm8w&! zS{17oK%PQ*0UA1d2r;6>i4-eZyofQQ#*Gmbu3HB$9LJF)OPV~1GNnp~9@qJM|A(z1 zwsrp$uDpper_P-iKQ{cRkR7|ALjQdfI#S_3b?xfGgNGC)(1rD=i7I8v)T&ikS+#n_ z>Xa#9*x>nF$dISnwQM00UHY${&$e{y+O;dxpFeE@(gm327aY5PcMBUnJo2OB#p?!- z8&}Vr(5M>+yQ^1kQayI`;^F)kw_dSUTe)sEMQZD*SM|WrqlY-QY>FS_(d$>wTCM=) zjL!ZI9C5sO>(te&rY}Igd<e_=3l2THTE>d~L9U0(DZJqgZDN$iu3fGqVfNJX){ZjD zyzsy^yUL2yt5*U`m9lkE-amHI`?IAES^zf$V~tR+`G;VF8%>1`HtF<|{|#o&IKvG# z;B=Rkf*Sg_*iVcF^-nwhP(wu+hVU~Ec-~zk)H~w*GlVbnsNsu0=?#@3N}z%B%`2qD zH=jVHkWvjc@AyO5hDw_B(QBYt<Hszs`0-Ca>MV(+l0JdMPd~k!gU~kMz=BRa{s_fg zmTJmI9d+@*Qx7z1)Y8u*=81D-MnYZY%Ny{}L(LHHeDlsb>Z$Y(HoBZ5idU%Va!>#@ ztw||HuMKw08sUT^$1dzN#$TnP8rER|;DA$4HlVOmO#pDB)5|*D=yhO1IgW~}RBbNy znnLY(Q_micyu-~uPc+kyIP}~qkwWE^BThYm1X9m70SHSEp7ktr{}NgOkRz$0rRYK~ zs%F{BY_3Z-Nsmz5)I&%kam_NvKjat)o4We0wc|JRe3DE*76#A_J(Zy2&#ATU%dn0~ zf(CJ1^0d=Vpo6wUPbP2B^Nn5^z2gq5Pf#O{H}v3Pi9C4n^buwjV)kuI4O1GiHTC$> z$hNb{QO`IH!8~)&CoOhrI-sP(4`vr46aY-vcr0|(7wx*(aNo%D1|*xc^CA+@XvboB zO;PhiJoC&$k1uNY<BmHkqLe0@0qCU{Xm3lcAiJQ2V~rfgfESG)!ASPc!gwEkkwVzi zbIvmL@Uvq8*7ns9)QDg1(5?y<T2C`igy@cS_1KxMWT8&9|7Wzq)`Mp}{tQ74$cL&V z6k6Whjd^rawOq{_)>!$EAh}qh4rlr1j(h+u%ae36U_QrNIRV6zj5Ggyvrh7O&!s$d z{J9wHBlR2!@;{U8@eiJ}Ka@H>e;D%4Jnei_k0I2GQ+vAFU#>Sh+Gw(faHvBa@Cd;0 zuC%}8eWYmYxI{V{R5|E9<XNBMUIO(+wRQNaVne9MH`-Pxbr_2p<7fx&*vF2x{X-4E z5F0n>afth!@PdeA7d!gVH)7DEc-9Dp9Kz9$)6r0Bb7@dLrqPRfG$=q4S(b-}n5zsb z<{yx$1sv=p4|){p8!&2yJK7NdAx5M{^k~Kq)RCgb|NMg+PvC}j)(1tQp+zWx3r0Bj zV~u0bp&cTO<K-*_4osW_91XG@M80t$KSoiCTa*WlY_zN+se>MnzysUhh@p4LBT)Mh z3fJhN18#^7lZxDz4ePP9+(bnV(a>Kh^|d2#qyrV;=!fAP;tXSmBmlR3rJ5inDPT73 z9rgId69S+uhSURNwNOI<xB;??U?y6IfM0LI6Rl%~#~r@J8)z<tN<WOl8VxZ{y#5gm zCU#R_3PIIAKv9!=Nbe!q07ou&Im2~oD1-jkhWj9~O|-Pb9n??*HO6NsF|tG+{+ttd zJQ=M_xFLNebfrGkRI1^y1C?_42RQ>U4#H@H{~qZ~(nUw5m~Pa=dHui*LrjVdade|E ze398n_enKLwZk9HKtey{p_j>ElO9j_ML*n;(23BaXY_bOCOR1+WkF&OE;8Ls)y1oJ z)ngHj2!J;FK^S^yf)K~MYNe*4(qvrYajkg>A^AZM2WsPK5;SXnq?o+`h)84o;D%nN z!nJxJff>V`ohO^(3o5YgMxXSB8`SYdQrdMxi+NH#<PeOrG=wmjf{i*So29oJ?SbIH zoxcK*jN@4lw7<#V=KN8tC-~wY32h0;=z$A0P}Hzut4CtbbE9{_gNw3t3Tr6^Adg;l z7WF7xyZ(`><7R0w4eCb#Dj|<T*3}{O|2Rhy`SA_u1_!SU`670%h^J-I#3+UOhcS1n z(8G3)3glRstKbn**ttr))6J_=(Al?RG<Q?HbVxe+n>P(+R~!F0n80EJ5s!gmAAPaz z^gM&$*x)s?g}9%H_yd}CaL$;(ogvr$AuPRC^eG#K1hssY;Ve1HmbvhQHU{{tgakki z+wjL~V+<VXF3!Q)eTc`jQ4d-`;~&rZF_8Zw#TLDTM8#`wsP+>=ay&9m5P@htsNjob zt{5Kjs7Euw(G3efnL~<E%0_EUJatg8AK{<`C3fiCHA82C^?2vwPL-jlTxcD}a7JrN zYf(L~1h1YMjI!)^y{GJFv+O8T|FPikR4$|NlVA=}Ma#U=0K8!x;*iHW(xm7;PjN7C zF5aB!L5W3>bCP9EwP7Nb#eLAC9@;qdXB)D#Y`}uouGy}wKl8ANMQm>V@E06v@vUAF z#?-VWRz2nvqFO)XS6}vp*p|92e^liOB0SQuqw`IA>?a&_IL7btjKD_h^4y16jI+9% z+Ht&wI^Lm&G-9!rME1(md8Kz^sMZpJBK8TuRd1W+@f0o|0)FJ^WkZn4#)Gy^px*cg z6>1@73>kbjGmgd@ywRJQFr**wXtnW5HFADI3^HVr%YP$sA$@~lAMLSt%u}LlVS;QO zVAd-)9TIek1q!xpi^!z{|4@rJKx;5e46GYKPO+cMCf!Skh8&<V&jWch9BVj+Nwq$m zb?iH(_2>n{vY4;8oeHj?KnFeOIu*1ZoZs>o4nq_I8DCVPpW8~4y(jh#GuDF}8_yAU z%&gmS_#`dA^7w4CuJ^jkMQ_lRgEdmVu)c-Scp}eyPC(<qdOV{S``8SsAu@M*xIJM` zGW|({{u<1@#%FWd)>0!9v35-Pm>+zH)3w@6a%^MSdR3O47Hj*vq}w=+AOt%;3Yx(* zWDU^}VL9sIb3JcfF+3sUKhRMLe-ueS6PeV6VL=amM4w4ilkacwG--$&1)KkP!z4hb z9tuGY(xNrvAQbyY|1niD1nz);3N?Q^VMG5=ed-Vn81@kE;0L)-K$Bu{*|RGUxDJI> zXypJw6k!wPun(8;I8XF|8G%=vc6pkXIiM0)DK=2ELk=)P4G>o<37A;);0;IDf-IvL zmm-1IH#zxZ9Gc(<xsgvmhF3VjAWw4%+29WivK<ql7csF9vEUb`;$%Y@5t{Q-Ip|{7 zQx4kZA-<w4C<8igV>N=sOJqiHHX$M;!VO>)Mq((1dG!%bAwo>ZYt}Ut)>VD~z!&Eh zAVJ57$c7EoP!FJx4gAm`1$TVa)eF;bDw4v78NrCt77}Ol5*Gm)zv2)6M-RexeExJy z2=Q5Z;YLoy{|*(WhMi~<sMlO$HwT#ocM+ipVKi@whF9YUa~zRyeOC{#avSpG8xpaF z*dTk-kVw;GixQDRUIu2V=r;PZ7;Qrjzpyrq=N)ZhW^e#9+lV1T5iL$-FK<$fDUnrA z5&+!CA8Yp-2owP7@Ghjs5n-rE!$^L*@)6IHG>yY+E-^!TaVqujZwUhquH%n<$al6u zKbc@j-|!R_u^3OG5NFgjQNf1vU?=Z@9yaw6@8V3Gk&)3Ckwc?)>gG{977bukE3W}o z0nmiu(2_Gaey;?OQAmHABM;}04F1p!Hl<W%!Vk1ST7PAU)kua<v3NLOBNe5QMW}Av zFa#-t|Bkj2Sdd@`?0_c}<cI4J4jF?7SVSC8*?}H75j%O6oM#PW7Y#^akF^GRwb(sv za#Ek@m%mmLs3#Bo;195{5A-mN7ttH(a0!&?8hUAqL5CUU<p$n1P@d>qi#G)6V|)&Q z8J{#&RaIsYaTb9R0N-GNna6xO!FB8q4#D6D-N#G$av*AUV5Eq2%Jz>x36v!<75YXC z`v7PJR}locQs+Pq3`THpX?kR+Z<zoG>c9=~Kup|NmK?c4HPQ}q5t5ML28-o@1>_K@ znVLUG9U!PTle7qw;10!8lj`;mOw*D%wN8E+OhLC<XSWfUfqLNJ52Mu@PNJU>ff>!S z|5n<NMSxk2LFW%}5-4KX4&R5F4a!CKlPyeCipp{bg^)h(0GRMFA_)Ow0!nY{Buwo$ zpqSYZo^>U5Mm)2*qOhT6X#q6A2QdN)ObVJnR5NWx(GurLf6rJC#$XKKFjpC2oX&HF z8pNEocX(3v4_8M~;ZP2V<{=U14}ow9>BB^aMGr&359AP8LiC4w=n%%%mTc)EO-dVT zCn?qyYXbCgc{OQszzpG#E*%0I16U6^2&8fJ8i6XPOH~ftFb;ml5Q7?i7V#R-NDt0{ z35fWRXv$sm@GQ0jE7#*K?---6!5u174;lkoh0<hdTB!;VarF}j$dqmk!8QIs{{_@Q z4ixi*$G52BrKq_&s41bSOF<8dpb6qoJe?|||KM^Dp{pSU4baf1DhGGBiaC6_E!Tk= z<UpVF*C71hc1i>eJE=I>zz+_@4}`?2YpNJ~;tpH{J0IzQZ8{v};14mxrDsPm>o5e{ zz!Wk#5#qp;rix%dS&Z<wUY&JElkpQt!Za^BhKm6i+pq*nU=5)1rwR0lG;uD%zz2Wu zE^|{8_<4(oB1<Zm4x6YE4Z@h?Fs`UluK7tApkZF;1EG*95fGC?#PS5)09iuVeEtwh zTuBkiA}s0ibIInh$i}ktK(G-}qYd#<6TzPW5DkK`3&$V`#~>+xqNDs%|CZFTh4r8h z`hX73pbX|vBq{Qv0l6S9afJ?Y2`EcQP8o*J_z#6ft}OUu6YGL)vN@75GVJgt2e(0A zx(#A_bT;7*&7cNh`b9GYC{JKvNSR^0`GLB!c7@Yf<sejVQxChL4f1z<blM$aMF?iO zEdd*?QnZi<11FDT43)qSBsjS{ITzBCG}mwq<e(0l8n<g(50JVJ^#qarI#~eu5Mj70 z>R1nz#10s_9q~}B-Gd=t^g7${K}Q#H|1d2c<Q<3S5b6M?U<A4UD!DyLf9&!RH4$9} zn?DZWn#2&BYDSFfa2yT64(ecX)vzqfDZGa>ehT3aclQr&*AM(K|5u9xEBr97<q*7f z+Y{?BcgHC(n_3ay`VZG&4A?MNrVCoUIW=3WVBD00Bcl$T3AhupQ#zmyVmfB@V?V5O zfFB|cAK48<P(u0&g_5fiYqwF=R}booBfqzzazGJILO`)r4g(Yp03<-prNOxq8asky zl>jDlwS|yq446P{IGUms(Vxw84*j4F&>ExVz(v{Mh2;Pat(swfd7t@N5g6LCfn_J` zfF3gY#!>ZUvie1pGh8qPKQD52Ro4#WzzsUESU`MiEt{jdnYA2&i=bf~e(;OIxT5hH z0K0&X5K%zvP)F@~ePm~Lc@|9j(<c7_C;QL~;Q&_(?2zg3{|~WHCUmvE``fR8mJYD+ zK-!=e&$|%UlVq)DCO(F?IRT`l!lrjMzQeq*`*$SdFfx&mRQ;%6Cl;FO<F~{05B38O z_)|e^2yw$z56|{3!*R?vmCONI&U3MLlO)LjP_U)<5JKEs5s{J5r702Xn)E;jnjlYk zr#%+LE=Ph2*+58BF&wCZ4zV!6t>Mp!V>`Com_?=$3V|Dj*&2pN%N-oQ#e1z<g3dp= zmp{gx3jq|q^*R2;EgErnpEQzqf~ru_RJAZMLow1+5iON;J%z&2;+sL{YRnm}e*rmg zV1+Y143cnXS#rQ!qU<4%vCrk8%kdD1O;{jI4Ae7I|5^WFr1c<3r&(I)l3g(Y%i&Oo zADy?S5)Zd54i)me4S}e*L6r5-4ZCyI4II*p!7%YFMbK*zQ-QpAkO{?usA&sWHyxJZ zU^-H%m13z$#HqB@6bQ{Gp2B#}%52x&BcS1MGqW%~nTyoQg;_|#k-dzF^ib4tmU71+ z#Ou|>TFYnX01AJGX#RVJvP2FJ1ZaHS!7X8=|9}bCkenA{r4K>T{@`75-P!`V*SJEw zeA&SG6#&n0Oz7g9G$>V6h1f!&*h5ggFFZzKNe|gOos&)3=gh0^a(zA|)w#<odn3B* zpl|u&6J{A;T&E6DA`Cid)fdEPN#l0OX-M?z|I0*alz3|qRor&cKo8xJm>U7tj?-(y zO%fc;+?5@d)*Y&Fz<@Sf8ACOa=n<daFa(6l!1Nm)Jf#NQa9`zoRmDtx&h3((<xzSR zXLmyw@StX!)n)8Z4%Xm1G>P8zKn!ybXKP2w3Pwoupepi!NQ1pl4SLJW`YaM`f&@1l z4H6H%APt9xCgs^I3-Q0G>`&xu*?X7FXI0sz%Xhy*4`5c6;L$B6{144Q1&qf{G%Dg^ zO26dm6a1=Qqs`)_^wZ<(l1&m!JtPP1$=)J&cAUMi4gn3U<bBsv4y|@2^bqL!;;34V z#)xL482rl9z^!wW6xlUlpb&qE#EBEV|6p;o4-bZ(AYI`dg2UFBSDuu3R4_mkBUyc| zL2D!rF=8fBp_wUU5vikt+L7tL)SGu**H;M}LXk&2Ry;NiPMkeXCUq(Ioq_vNIJp?c zO1&9I{?CeGvPYA$ZyAEvFb?k&01a}s7p^!ccnR@`)?Qu_TZm+mNQrp&>_L6J74&z+ z`R}^J7!iXIxT|3LJF$x)R5_?IlJk1i9fwHJ4Exo5(qajEKEW~E6hlxfuCnYtx!lc8 z*e_YX;m`@PW+jHRA{><)`dPnFk_#<+z8>`tb1)10@f68DxoF;~S6C0%kXq?(E5r?V zkl}Xg@KgGm5nG6Fvfb7TRf*FO{|icl4GgjDWH`VGtPZw>>3EG%F#K0bff@Di^)>PH zLH)v9^hj2vEAL8FVMd3qDl9ev_utKc{g)lvG4g(t=4+p}+YS$cFbf63j}ig%)}ZZL zwF`1U4~*YQuK}VpmYhItyu-LI57$my!VgC?4&AC?9ibEm-3wnYPbSHhXknanhY(bL z5zp8U`%nq*P*3r$(lAUF3fUl$^1sJuu9T(w`r$9$APAfA5~#9vXA96TxqATsJ1n;? zDWMSWs)HE+Np5(V7O}Xw^$*^V`zNK>A5FXqWjhODIO!P<87TQKe|FIj0Kq`s0-j1A z<sEVH_}8Z&YZv$h4-f$a{|+Qr(BMIY2?efO2M%04X}#c8!xqn<LV5Da)k{aKTgCtk z87dUn5L~)?vCz@O=I^4ygD$aQ>xZtAKZ+Sg!Xzm&W50d^uPMuyj~BXn0p#^7xs&Hp zs8M^Cloy~~JwsLS>_Ot|-8^>ebc!^{Fyp^}?ylB?6TqFjuu>5+j2Dj_)<gfs32Z0M z-=0VQ+`$a{Zt$cx^}Mx<3)87w$dM&a=Gn9<LCcpRk7Y=Y-amE!1kJLhPMv4W>jeHI z$T|S(0PN}olS9uM>vHAb!DFW`njd2D(0YEHI&)^q$s?Bpr;T1LY4IFZZrH7!F=Nfa zjiv6;-@aJsz_olS|23n-e(6B%s|T*6WXl=9feTP6**<jmdCBr;ox5@XrLwFrcj~dE zj&b~{hnhBosVAIr-c#)$hQjKLo<j=hM;yl3QI4*7*rBHuHQ3pPwRT>^!xDMgai_R~ z)RJeCJ=9sOu>f<_aYyQoGfuVRCPXNsaNvRPxPR(7W{z#N3E&@)3i6Ddp!~?C9(G&{ zE1Uob(IlR5!pbeT-nOw)o-BzIvY;T5<8jBG%#!CJbb9H>9f#<7Y9@N5iAA27T!JyR z^B(fkA8p8s5-Q^U(dM6C&Z)<rC<jgGJ*6}%CxCjELB}6#iYX=>dXl-O9&G+uM@>uL z%rT>k#G%KR{~`SOW*%?cp=JoH;9|$JA2Vuao_}=UMxA!rS#-Gx>yj;#H{>}{Ain_X z6(f1nVh1sL7OST!$JTUpTyigUbD=ghgB9G|>gi`VdVr;87CGu62R6+9L9HKato$d< z&;GHd9yw--tsFfA$j!8Vb6E#qOVib?TmVawsh(?+sfQnj>caLReo{h;987!4^Uy?H zf~=%*=;`It)8ZBPsW?SyjvwggsRo=PvC*cUWIpNdTX{;RxZ;P|+3lZi)M%z37yaSJ zA3PwbN1Szy7D!D6eSw3WZ*~h1MA>S2gPgqtdWV`P==sJig~EC(v?rcc7Th1vJ$mn> zfemTR|2Fk5=&X8X@xzbXUZbb3x>lWKj(@mJXi9agnS&U5-t`PEYXX?#N)ct=T;O2n zU`$_`=aQH#zTunDEO+UFg}r`q!&ab+&sk>U`KWWrp?aJ#rkp@2#XBm7%JHX8f5!Q5 z<#jUhhn{UZJ*PjH&~k_$f08+8JmZgVow5qqX~&y-4%y@Cc08tMS9?|E4DjgXafzFM zswPJq907E;9%!vY9GeQj+J-<6ZomyDZ{bEgp5T?cElX=3^4s{vC9xj`ZXh7hlZQUB zgk3aZ4)7>P(Hgg^!qux~2_r~GoTUzJEJ71uat&I-(XU;^hE?krjyKj24b!MeaI2e` z{{`iO7VTk!ANv3WKlsE#n0N*p<zON|s!|Umx&|Ti@W*)gafx)$V<Ym=Vr1k&kA2Xh z9?nZja-d|d00^TO>41kz66TU{oa7P#s9ibGVnjD0(H-yL1{JvRjb!nKf7TL*JN}rE zdQ8ez^}s_W?j%0SWRV=KQNzF5sH+2V;~h_V$2-39kGk=r9iPDnJ2v@9$z(B$fOOR# zWx1L%B4m~Yfmf2~#Tt6Zur#Pc3q0zf2||=(9Fa5#8Al?IdTir|K^cf_a^VMUs6%lA zVP*hsD2HQ^F_QQ)h%C*CL|O`{ehg_&Juo4ulo@YGu=*V~>d}jAj3YNS8{#@-|Kc22 zWTQRwnM_7JgAP#CqZ?#t6@`2PC~z?G8%_j=$_6r?cQBD2@#JSZ%~g`!oYD}1xLQUm zq%3Mk!F;}g5lDrzs|~$lS>&tV`Tju#U$iJi0cZxN-u4bl6~>hRP(v-~aW^?dDJ;fx zi=bH7BO*T4qtMf!;Ls%@bfLykdYT1jtZ@uESi?hg$;dJbhDCB_Rc7IUh8%$S58Gu) z7<15u=2(f#>Jg$5pm~koqFThM&eJ6uNh3J)i7<MsOCfb}h&*J`3r8ucX!K*q#p>j) z+{~0__1j1~dch2OkYln9O^ra-)v`#{LmTpl2SH?Vl2T0rRi%uQW&``T|FP_*9`qOj zH{dZ!#l-`G@~B!p;4<3RHDx#SXvP!%(Ma1eOIYHl2TtqZq5!<al!GxXCcC>9H6XB* z-R%rLn2HNx1b`nvT@@5n_gAal7J2D<ubav{9A?bH8bEoMUcDI>hLGy4s8fhb;L+B% zf`lFAxMp3md)Fsz)eoAW$7wQ!slQ@)X1A@ZKkjmlWSAFt$em}F(Bs*3bORgFZ45(x z2I6>xjG*f5?s()8i)pX~8xtf*i<=^kyF6o#d4xx6FYM1QDiMruEg_mbB;Ou~<;fPJ zZidv+$SJz8wE%oW08WHlDgP>Iefh^5CXtqR^iMfduC6bP>kjHd{~{2C>@K#zTMtpn z^mrBuKpn!cgV+%3Z&4<6Y{X2&FsHMBYA#5krCh#+jAI;|e6m0QoU|~9g>ns(<t}P7 z4zw`DtT_y|Lb!Nfw`M6fpoxYYpb?I$WHC#u;gaD#gBnav`O!%`PNp*rWrA?gI;pK) zH=iQKlgI-WNWsSD5`q?&Jn9_1*jRfgBSm{w0v-LBNpxWn>Y4NdjQmKHLYngr;gKUy z0R#54|B)<t451tBc#A>QQeA4$+mX2(2wE-#he@~vxH|GTb#eOcc{H%7R>2}v?);7M z_B$=&2ml-&fknVv?MYHWqE`Qi#a*`hh_d8i0G1ia2YDu8|F%3Q>aqk@Z#;^J+LU2k zLub}mBxS>O{s*e90cwJ@8X6$~<AgRxj%chQ0JkA#4V{k8N19XQ8w6LO_@SP3blbZL z0m(n;L~VYMqsj5Lx<A%~DsMj}BiH~3JeW9+nS^@hWqD}GKn#y=Z2TbSQDQg1$Wf`b z+obH6hd+Gr1Ux6JF;u1p95`|14oPs#Yjf^52AOuquo<WHm`92lpNV%fIyDxm2Z{cX zK=u-39`C3{cBvt&g?mU<bN^d;{Q(bhkmDQQ$juH(JHFpv^`RS4M?IiniA^wLsqi4@ zaXeG}Ml8ZMssc?oIzfp2vW6YjxF&u6;W2aFa1O^1|IR=v=W0KGpOtl)(m#@ZLoy1n z_Dzxf_u~O9z{>ZZ{IChCupybXi>M~z828vYc2XjF_&f5Ti~zj4OMtuWAh6AXmDr($ zeHaf|N{Dc%2N2tseWE=MTZfRU2RNvOe;@~gV7ywO0)JSH=fSNOaffCY0(lT6?$VKy z0-!w@2XUAOPU$jo=n$SbDS1$XUq}k}+6fd40AJ{bs*nd?r~(gT4e+D8?sADN8J2kf z3v!4Dc&H#+!m4lql85?-eh7zL5Cl!21V5OAXaJ4fs2R&(joXleVDN{gvj%JUA$7=- z?Ykz>h#A#kjl61veozP7`3JDF1_D}|0AN3Q|DY0UkRf>p4f#6`Alp3*61j0=iJ#H7 zcX%Sm@C=`E8EF`(kdrts!n*NDE4jcn2ON)<2pD5?H!1p=X@~{Y^1iv_qM1ksSV#x2 z0|#`PI$XNF1sMYN(UV%Ft)^)Pb|4jYi!j`=m465XNRWqc5H21;3$@S_Du9R1dkx6& zH*X*+T=<7~z(dz~31J8TZ5jx8aD!TC5s7=YquWA5*nu6W1GV^udJwK+q$Q~v$Zt!M z-KwyEXaqT^9(pL8Id~1Gz$K_dNE-?UKZu5Y2%Xvc2QPULc(evhSOj<ILzHWyfoLxq zf`<tcjwz{!Mj!-rsGe;?vdvM4aG-=m|ELE`447H!xJX2~ePWHD<hR=z3&LumJ_5iw zagS**1{Ev7I{TY?`UmXrKZ|0@j0l;RsRwv?LAtXTP{9VQ<Cq29J8+3R;n5DTlrK4f zvwC=hLO>Q@S(m}1t~UU^1^dFxU?2yo1%D7US4oz7@C7RPhjApq*ua{}va@qE!aLEk zxbOyn0L&sW3@B8C38|Fi+KIxThjDNNJfH?@$OIYi1$aOou^=(v3zFIk%cj_zXl%7; z;7QZy2V%&`e<3SanZtgd2U);A)7Tn?L?&`@Fl%r%u?ii8KtWX*7`?(0GC3wcP_3X? znstE0-mr#7*aUY$9sC;|ddP)2|DZ5Llo=lZwsldEYdDoh$rQ<Gmvp!UawCt&0Fidu z1dS;k<&cSgxCV0o2Y&cKs92YG_y-UZPy&UChZu)%m>sP%Mi}gidQbygptsaxllt)m zB%p@@>dmGorBf=Z>%u%U(y4zi%zEg&m+%FDKq?Tl3UNS3b<9u~p$0XehJ+j>ff#~n z7?!piJa}-PrtyV!*ur*bhA<EY&{R1vbQL+IFAWtw*Z`|-2#0rJzI!p8atH?=k`uK$ z!EjJcc+nFxJcc#chD|v?XwU{cbVcG^$q9?Zg`o#c@B`b3)B4#h&d~;Nf)~qBlZ{w} zf|&zKsEW{eQeb0<ZlDJX|BM&q*q%~3hmBGd*hCMN2!Qbjkc?<lQ*oDgsEQaxm+h$s z2(5_nfC*^g2YSeujnUNLGotcw5noV)e&B|;5WNEO2OOma^ZLU1TdEEG1<m9TU8Rg1 zRM9Q0A&P?vxoL+KrGl$TGbw8ae;|=~utAr&mqQ2y&<s3uu@LmJIK@~;=P4Fsf!0GC z)f|B@hoXuTtOva!htN<QGc=Q25GyD-p8J}YIS`|NiPP<~k}$zZaLPV7jj-pG*GAw; zBIy!MNJ$tWqfJ_aU4R!hxyf*lp(I&ILI{9InLQqpuX+GTKk+62X%AM76qayBczK9@ zfCXi$#cQJnn1uy*|KXGjR0!<>2YPS@Oy~z~n6aps32^|0bRa;zo4VVp9ykC!h=T`( zI3Is-154tN3`7ge#Dx-RBoATNsE8!OG|X-h%+0vH0C)x@@P|g~M4GGxEQz=oHJeDx zp2>*^ckqX1I80pSE)<=2Jd}?E$8Wh|oHLSfIGaKgvd+%VN|Ke8%t9)A+;L|+dxWg) zoyz{=?20pzoxLlhvg&?*|33dd&+~c4>+^ZPC5Ir&Sv_uRFUzV1pSmY-noSStjX3S2 z(hb<LC3vS}wwzCrVU*G=$jqUAX=pjI1w^c9nFy?hj)n{8C!hlh5(0HqJtzdX6tzf9 zx~x1w702%{rV?1lqry31AO5!V#&9ttE!OgbzvJ-ymW^L@)P`HdsZaDtF!42nq>*i0 z;A+rnt<*^0?;tbgj!t?8u+o}I?59HHT6~C1UeLRN?4ODn!vOIw@MG^wBm-^4`i7Ga z`*>ydqW}f902BPxIq|mv#6T14ci%`h4~ZfL1i*f`VE}B06ZD`1yRlx#GGvgu_Q_!z zb|u`}-|4pRkW>Zjq;BuftpZ4XTGxDYW>zHeN%;dDoETQGDS&u4TAnu_Pk3nM@N7Dv zh6_HIOthFF*Hg%<w<j6m&{=|zpln{*nJz>SsWKYsQGowzmYbY+g#dqV5DtCghxpE& z+azdEvQ8Z5lnL-}K*ibRoN@ziL+@`9PwE#>CU}sB1Yb;7Q`H049az{>6kWAwSoG(P z`<X$jR$O{aX^>Ut6QV6O;!RanwU`48R!ijbhX#ngj(nE4CPwtyC$`%VJC12KuQLW% za+)Fmmm!&fS&{FSPzFv3pdnJ&)>@GppXHbYXi*TS%jRnjyHY?13hKFPghVBdA7cap z099PL%x4arPWxbr8SOq7w+DPBL44r`E&KRe@-`nth^-eNo^bc6ssaVtVAc9OYauLI zb>$<oS<4-NN~szf!o7cR9M0{#59@H3@Z{N;s^AFHw+q->33#5D-JH1R&0K3;^RQqN zn1HHZZ&lE{^hg(ae=;V?9WKQDp3bI$$0*v&%h;bnI6ZNt<7^Ll1J?C_z;=Vz^)>Vg zI}s^~pp#aXr>b>FuO>g6fd=~Ht?Y>qzNx<pH(6{si+so00^;s2;x~6t1pm0Ot|*a0 zLz$Tv-GA?ItfFMpGc!2EIz-*n^Wz;uzm&{$WmRkW&dSWfiTM{3R1!?TAaXo9``L1? zy*tDxd*S$L9Ucy2x9Ig<yvC?E;=149tKsMz`v@x*^Rk49_#iwv1FzqK?n9WnpEi=1 z+`Q`Z)<`kb-T(T>O)~3|KMsgQBq^|xXgqB^WR~~!Bs&%f_!l4BDsLBP&y#(&(h>7D zEPN?{^+VI@_R5Y%XOqnH=r_HCHx?|EbW8K|p;#YF7+uH>o`0^}$vJ`b_Wgo4;F9Zg zk?CgCo>#EIF$2xZ4${hQLPT&Pv*alOlGtmQ>_qGP>Ay;k$vpgh|EvMq%cIS4A{l7> zxXV>0&*{PF1^*UVQKCJi?j0cp4BPYC%B4_-T0wRZ-fR)cHq{P|XTGfJ@`M&`_6|{) zBAhTXmU%+w5!>KJcdi;|k{CY?2SNoxm|uyrQBF!kc@FqPEg5S(%72!__NSq;8F6o) zCgwUQUAmTe=mXm@13xz5tO%jqspJfRb9JV%+>c<Z7;=-Zc(o&TB_R57L_z7bMTV%V zsH;jptQZ&?q-FjKE_h)n6#B`itsJJ?1zwO4XsKxYC2b*HoaN}kt>6H^QBCBU68=OD z)H4R_*_rjq77!mxT^Ebd3N4J(1|<F`XF6iB(ee+L=e#S*>F}bSydKFwFmceZgkAHh z<LeZDC$}Obk~wZm474ZMq2S(tto1}@-Q4`zbHZU|e|B^qoQ4$Wc$emA<sff3&a!55 zB}@1W+s115uL{EbVOafVxn&_t*B?I-C;v%f`_FyrABza4TS5;CU=Je3fA6?!+RyQu z*O`sWbiP|RYo*g1jN=HAR35-jR6WL_?B6t`oA$6a_!PKA4}>J7%)3sOVY?r6ySy+S zJ^lTC=O^B%8UCfq#gpyM)r$RrK3ml#&!o!&Qw%U>Ok``|yo5e`DvmEvHX)D-|K&gb z`>-h2o8ldG?V8C|_Txq2Cq*!YX_^LI<LUN&-?4n1Zsa#g^5=D@g$klOKq2Pp@3p({ zsdG$vcVjFJ??w)$0sv9_LITiv_RJI3l$fm!y+7v?n0kgM==#jDfRy+0LU5yuAY$Op zmCt;~#HYcy2c)$@(bu*O>2qXGPx|nBV9?`AnqKnfh`9PbX%#^e;xilgr_r>#m7haV z63+!Qi<}jDZ})`;F*I3f!K!Q~MLUf#5L2Bj-NPrhx6FLDwIcR+o#dg|p*7sne1fcl z*D1`InW!T3cC<V<ITF?uE7(MV#*2FzxfScCBn+rKrp?{YXFzZV(2r6j4Y)j>H#~+1 z0FwN+h}+@nuPR_(Tn1(1$=eDr+u*Gn4(=vbM*Abe3valTtZz6;=ZQVmuYJeu?7h*2 z^a=TeCR)^ozb}^Unvoy-7@yMf@AJvUze}v!o*zy-(0A1rw>|&$Te(tX#C9N>cP1oA zqsIADn#whmV0fL~4Z*+dpXv6izBa$$1S@w;HweDv19qm{{CP4c@Bi<*WZD-=fRgN| z$rgbRiN!iTzmVUO6@EVew3>W*cJ#++f%KTVMH7Ab$<k;KE1ut|T7Ija2%h=;a{W>6 z+g9)^B>MQrD_IZU#J^7WYUf=%##EjNdz#)*2n+*qA@`eKy}gyTQ$eLeePX=v!ivK# z_~VFG?a<D2g^P|-W`Xz4WCa11v@EG`QRhhejyhiGqc849{ut$z^E^{aHXt&f|Lm)- z+v=Cu6_F37n?6_hCEA@Fe3!oN`~bUoWX7oaHJqHKPcM69tg(>=9+Ahr{qq1Y{(0gy zw!rx(qdbD&r7)VUVa<Xs;#eS2@9<nEJw`Ne0*Pg)nJ~kOKnonB1gx6!l=si?n5)hW z{_MR*ZC{<#{1NlZ=<W~i8>7m5-kLNwg_1v8YJKx(3FmCCPc2EJPnSWWbut7QZJ*!j zO)>Bu6Bxl+9ZnZJUOHu8aa^XX5`}+7vLw5+ATAqWb5MuI@>i)0_i~j67+S5c>s@S% zPCKqnT#u>fH`?;kePEu#qx#}R*}UU}(WlwT`g8m_k;UomITb94ye*M8MieunrWf*d z1@CS;7(k^)REKi!AXSSIN=z@-*jMT0cRx+D%l|52F;F}Yo)*9L+d-3&_$&CB+i~@_ zf$>G<b2UkM_1hLt^DlNML+pBkZrOVRO<#%<wae51aI<hN^*`z{h^Xq8zm{x}vBb0) zdxpHqPU@sL9aUob`}4L_k(HK<(pvelLGI7NHv@dWzgU?xd53=LVkBO_wXig2019Pz zSeP>_{Ms@fkH-YHW!VQ$fn77=6iTx3Q^ySkuI(1Rl-C2)L5ENB+!eErB&W)Ma`qKx zaH<KUm0vL~<JvVyo><;{Za9%Gc6sE{)DeC@o<4)tNF*}628ox!t#j9(U10~vpT|$o zDNdYz*;89e!5ay!yW(%Jfrsu;)Hx+}kD~wl0vpJ!ou0C4^47L}3yeuR=2JcI)%m_u zpX62MZRdl>tFBU5jOQ-5fY+5YWqyvtimU6<$jY{|)YVsh_?f6WpY_&A!hMpQU>9TC z>#DRuVbSHI`rjBeNIEZe>SVgF%qpYVWXz(3Pr74_xte-|M@jjs5Wn4tHWtGa{URQ( z)XX(DzcJMkJ?W(Dz=Foh>j?0QMe=+c<W%To>r$Yh3iA|>5ro+aD?d#Nu=|!1WhYt1 zVr|{Ia)xhf^_V6Sbd&hkwuoq#1F@<xuwssGx~$yl^$1ezjVVj;^mHM&V+g%8o{nt= z!yG;~d7*i?)Y;${Q6w9V@J`HH2$_SB-ROp=XW=wh=0VI88r}GdCg?iKS9^Jgz@xGQ z#ePht4|Ej({JpSFk~8Zf;84{sQaad+`L}+E)Qd|9TFrUKXiYyuMZ7`GVCQlYpJ%ZU zK4_rW+axJWcQfj4Q;fCwM$$LiYkFk5Y|D0aMrBJJ_fJ=y^k#J=Awo#+R{?>uoKK%q z52gq#9_Ure(r)-z%%wP%mBMz+Tk0lsle%62;XcN|Z~F=G7fatWab1_K?|?e9nJ3B( zA8?EV>X;(oE7h27iL(2v?0#L=&Ko4wXisK=lidrA<im2nF_4Ecwkj~E^)l=jag!~c zUyeqzuc$^-YKejp9+5_R4sKjM^X24qYe)+1BHup*@HFl)Wn633kzG25Vk5`mLjA^g zX@^Y!D#`Q#uH_^)M_sI?A0m|ElpC44W{kehnbTRwCc;E-m~@={kDDKr(EH)TmMN>5 z9<hSf7j|O5l4RJ$2bd>46m;9>4@4JT@Hb8GPLHLhZ5%|mpTT%AW1Xg*c+sPmdU5FA zNt)-&ymS6KI+Z&-`pj=7O$4aDl8a0U3Mia$g@dbt?a!nMwbiukrXu~n1KELtsoZOD z;zA;j{jS*_Uu@+7XJWFd>RtVE`j#5uTFuYT(u#SWW<?p?CFdPn@D&arlhnbOPejWj zj+Qr!@*{UD+!GS`S`-F&7uZ=<dO+O2;Fnl;1t<Crz^rHCxw^YxuJ1TaAFiQ=kbkCi zK{Oa&Ly0|0kQxK`ny#GJZ9SbqSj<hoYkKKxRS$-k7~5k%$2z|za!=oj6A{evN_+@^ zJ}CovY{{Hj6CrggWeqFujN@LBx|j0rfKK+vNmzo*Ld)trsi0*o<Zk4i>drEZR}q#j zbn(d{zng{8?q~d3ul<zzESPEHJAqxVxR-xptNZVwQ1jcr9DJNiJjC8&p3iQpPu}iX z#iGCPR>l&_dYCwAus6kjkse>-z$E}LMO$N-uVN`o$&YQk-~aNq!Cr)kVgiBppEufw z>eCHyF6U8UP{TwG7rRMIs;v8Xeur)r1uCzgoV`jNN;McAeZlDy$wX_A!^N%2{(*(# ztEzotBG%cF`>V;mnZikNA;}3oiTTQ9W{8Y1FA*5uwwFMmJ8q_21K8`wy@vfxd~yzE z_SYTLlm9!d^H`hf{dm88!JR}e_#b2L;O*oeH?<;N`{o2#|A>n&!zMi0K0GP@Cf!4r zYpsvTpl4bZuf9Po^iQkg>D>pr)`~MxD+D+ryP}LPX;jPKbRJ<3p}i<RFM5aj{YSrj zpb}`xkf&0j>{kuJtj4W}&U0`VNSP=wuWiZN3UEMU>rw|c3Ic6bIoB*LY@Ki0KlhH| zF)#1ynU!AcX(e;*NsX&62{FE)2vph&NoS}YGCrn{;8rXksP1ig0ekS_1WKj+;!+%i zJy}cl1?;BZ#fp{B77chQ=R^l(ZI|~%E1u{aoJ;b13fIWSVYIOCnEte)osgfm1|0S8 zFe>a73AFo)KTmuUCp2HcWN%P8HYdm#`m}{<4^CXZbC@JG>WDmaWvFn!^>BXc8$VUI zRvhsD3V~|oC%py-<UJionxbhuTBhxi!O4<tTi32%PInHlDti>AHCsltOv;Hzj{8v@ z(SLQVwnN5|FM`Poo#n6$ajjhu5{;5w7_-9%RjC|rFoJ(s+dxZ(C&wjS`51JGgpX~q z8{Ib>n$$e-yr8e)uPJw{lEBs+(9B6N+7Q<dh!OPCc8%1OJkD42kJ38Q1f1V);e*{u zgUWnVmsw-*l)dyS61+&V*!Ch64o<k7TPgtbx=yrIr}ZTPxs{e+zO|m41&|X5tw#m@ z9?FZTaT*2PLRO7i-(4Z{6tYaO2G(42aEMdxh^*2JQiTB6d(d*#n&Jg`WfOzZZYC<1 z1-W1dhY!cAUTCn^=0|2809*${?poEQ+nGdiK+F)FEjl`+aaF?}uHGS?aIJ-gua;>0 z?~{;!cY%U?5wWkMqUw8pnE;iYaa>JF6Ss@3EDKI18M7&PU^m&y%kfSPUaG?~_Gn>d zY@iR@JNP*k^AV&d_Sr=XFCVO3u|GVR@Zg6R`Nv-vHrGt`2oLwQ-ENs_t1zjh^c~d@ zJp4$!ejsx{%*$t*bnEGJ{u#1e<fP?3SMx<hcKvZd29Nv8iiQ`2Eu0LAE~t6AGjd)< z)F{BOH>8UgT&<&AfW8x=%NEh2>Iarj1DCkHlFLnQTPuEFU=W;uFLg_#YJFc`@-ulL zn^G{HYAmJ2zk=h8Us2k!<+C3@!R86Z&?}jMnb}FbT1=_!mr%|cFcZ9@lwmt*NV(e4 zG4E@XH<(h*t9(58^<)q*gy)<DoiU(!LO3Kr$%;p*j$?RLc1Iod;WiH11Xrk%R`$yP zl0<)!&+U>mDf4^GAf<9jaaxhSo3?5ixk`#-{;tzQd9>~nrSKStmCx@pO@aK*k{axB zxUQLGYB=9_S@8&`n{H>ykiy9}>yoAu_>j!eQ}CWdr+Th=EmxBed534`zO5+V9WRT2 zHhAe{a-+S|iC6!BTVH*m2VJ&qVcRX^FO9~wsK-_e@}%%$C%dU23c0o+Av)d|psc~Q zk5`0TzR|fsJ^{b`bt@$+%d`_b96e<$_{oKy2J(E=Kesf>&mM+^_#K&;RuGsoXk9;( zsh(3gHQjQgb$_c1mGvgi^Vhs3B(&hF{5xGhmi81H_6mg)9wgsvMhO;@l!_ozmYUT^ zS*}92bSA;d;yB)5oRIUDci)uaG*MNMEPGCFlqnhPh*K5pjizOOzQ!25eg7@Oz@tD@ z+{OTF*~42iAhxW>;Fy-@06zB8RPD`_I2;`0i&2`?)T<;rR+#%|Whu%(6l}fNQS{gh z=~|i5YXV;L(RV4cmqlY%l&1Ss>z!>RqwVKMQF}R5JBY=Nav(L?$}^r3TOJ|N%Pw}P z`zT6VfmNqAoaBB^mXFj#q-##s4<GA6vGw_kt;G26mtSG@RXs_vk4v?dQdO2ed7p#% z#5GV1ge{xcM<`9yf-%|k9(J#vpVbsA<=(xnA#3u{wMn?me?x1?YP{MMlF*OIBVQM! zS$DV}LK?_Z0IO_)uVra^WEgaDRJ2DY%MEIFgoCvb2MQ5!WtR+3ltKDz+$Bc6Iwi9# z$2e725y*3T>j)3ea2=t~c)rQ*w;@SMY|vs-ioIcixnrcCnzp%{Jt$r9w0e*r8!yFR zzj~r+>aZ)pHX@K7D+kw*^1SkS&D1SYlj<e06)+6uld>z=TjxpC{evh+?`ccAYWg<B z@?oKm)V7{ZQ<6G1zfEFL>HXqxkh08u9Y3v2dplgBW=jRx9);s=ci@1kb%cv+$_O5F zUul`<6W;^3>{Vw>>D?L`QOF`Il*2g3*BMMDv}rCYr-8*wG>yJFfCKTWfNrCAUt5c~ zfixh&c9D8`%xV;AtRc$J8!YR&kX*FGb&24IBE732JB~%_=WM?@FtDW80^Lft9Nb$` zp@9lzE3qb%^@x71ny>tD9x`l7Q(!(noNBJ<V50fAC@?pgTvIUd8n@<BFc*<RgH;2w zMBP@q&Adbdkp37U>ql8C*Qa7lX0*lh<!wGZjpowU>lN}O-;G3eu+^;i;S~k(;s6H) zL2-!^{6JSy=X0yhc<q3+0pzX6+hR410B#QuV*s|w!JBB`d`qG$qPAl9i&?LEv*r!T zX!^OPFlM@8EP9S0t`x6h`5BP{N_K#MZ-Z)_6|7m9Xksn%&iGR`KI5;IM<@p4fl3y) zXu@B<-gK3C?bnVk8Ua2^d-SL}LY`8(o&UJPzhCmBx>T1Y?6r6}#&p{6evSPIrxy9! zMx0_dL6$<MPpv2uqTw6FGbCs$cr)nB{OFW%xkdsPTuT2-`yphKEW@fBFo_ozBu6yo zZvWep2h8_`iZ)n$rJDK}gt`gFUcaC$TII^;0AAW1$&gvnVy!U|*VH2UaGtI*U$Eak zg~5CONfe~ArdHm5Xcnk>=elj!CGA^GYbJ1VN7QY73hh+zJ_{KvWYW`1D4|P&+ggIT zWqO!(S@$pXt9d#J$naoIa9dFfQRiN_B44T=Bg|;Cm`|kaluiFA?i54!_h{&lvXH@8 zO$B>rO-CH}jI>x%0;kgjHyXJSj=xu~eKtG9!~g-_kD>t{^6_&gw|5I3<0TY?^e^^N z1~;-XG>2Q`S5~^e9B>*6_4}M?gbrmbMk9}PA^(jN&=CBDw67eq1A<A|p)+=MJzt6O z5_7i{pSU_zpgemwr5N!DJ_+Y5`hL4zhCw+E6KVGt;D<`j^W?exeV^MqR=+o(8GUmA zdGUM-OdpUt>QUJT|8bDk8W7+dBV+hJ+;t`;hg=iWo8#JwQuWhP`f?RNDTZFcDISAm z#1C=yO~yCU<Bq|XWbl$h<k?G`kTWfnH*l?Eu%K42oS=}lVeKV`#Jg-4yBZ;S#oG#M z;D}m18Letj4_WEeJCfyU8zI%gZ3IQXSY=9o4SHvn0V>$>>oufMwH$A8#4<qt)R+s( zqwaDk<CTSI3WfWtP_U+=--ibVZ`{LKl|_5@n&Za;ASLOBL9zyU8XyeimV}8q)}QQC zBu5pS(-jTn#=@=7J|om<0L;3!p4EC6q#1xG80&W*AU^rpYSA0fm{kKTR#|?+MW{-l z@j><2iJSY2I+O|Cent;_aN7G?3oq=cQCuWaG6stU#W^LCe?UhcsX{{KU6Sq_#f0K7 z2fkNI!oLEhc$VvNKS;d<l#w*hGWbWl7i>F1A$R|N8u6p>B?a&O6pY>KN<YdpbaHRr zFv*qZZ3%(8t)o)h@v1UCWwnciA5#U~nxoPdNaH4kE&Z4X->_k_ZBD+!mp&y|JfrF= z?6iBRNUSfCrFgmcj#GAC-?EUFL}9~G!pq0z^s@@h^mlHytl>WLX+?7Upd)NOq4rpb zoy{a=%ssfiFny0KX1pT?R)}=`jOTRL7^sgj<A>Hn;=Lfhr0Sq%zQdgLCe!qnJ(7=~ zys*!L4LBHZ@}+5NZST3jKj&Q?R?y(QnOlr%e6NmM4oJffkYpECdWl_R8FtMCNBu$B z)|Z-9W6*FJlN_#_*JC#?zbmwinvJg)OjRzJzR1GU14zk-z;`ZiEU8MdIpyqF!odIT zr2?*!Y`R;2X*|-&^UAJM;<WhpFTSOV)2V~W&t5bVgDeDOe9u3*LBJLAx8DwFDqB8W zW75+CqWi`#%lYT}|I&F>+^R2Vh26qm_Zw7=qG>JO3J|JZE#GRB&&fK2Q;m+t|H^ZE zqQK0MxJc{h#m*=`88F(<1}k>{2YUJ4?QP!UOHD-2&I{taDhS=K`Q$1^vj9@8p>4K5 z6d=r@V2Q7eZ`7hxSD<j>l()1e<QucTLq9I7bmP(Vrt*FiE&D)~k%Y=fO%eMkG#acB z-TyB0o_;~Ig`fTAq$^|y&%&5hO>@h;kbM0J%uxwBy51q^*7p#n@l(B|^xAj(^CSb^ zp{PoTTQGX93_hkN#nf=%j*I!_nAc$nJO>+Psv*+mAzI8sXTRC~Yai$y*S(VyPy z_of-sVAp3XG_&S<?&hy88gV$JD7SXwlFEHDnm$=hhQsAX3{!_DHS<%!2FJ7e#qxDa z9)N-#BPVjp&p$ijMv8m+iiD26CvLM7tkR+&MZoyIUfZ}E(d!0!H<r{<lR%kr{flO+ zipTzPU5G#Zh@=mhg}rCk_%_Ahzv${-)kzTZqz0^O77x^F_Xon+Wc*PVh`FQb29Gbb zi}^agdQUu>A20NT?QE@Ejk``U-~ToFw^-++vCOlb;dB8}W4j(4yEGwn^O1#u;y`tU z(|eSFVYX%rn`|Jfn;DLdtF!9MAV9_gXee1C(j<C29=MZyu4nAglLdS0xcB8+xpMr! z{*#|DBWtYT)^P~<y)3})br4G_&Algl>K(y|%W|IVrR`zU)SZ(!AqgIv_qZ=ZHlm{r z*vCH3&XqK7g93ryT8Hl3+2w7^bYc|A_+o_a(1hf~cx;|}KVE2K7_QQ}t;6kpKHZHU zu-<KZF~7rb@cOZxdxXSI?bPBSEBU}k&cD0&MvNsrD#4pIHb-Aoz2>-Re!dyu)Q+eM z`0_rC)#XD<f^O5B44$j6T~9A+rQuhqu0>AqZB{?t0dCgS3dZkqZBQcCc|+kjdnzUS zxFLzv_+3&j^P8fI{3oY{Wtn#9>av$_K;rOH0%*UC$H04^=1sr`!k$qqi*5<w&SOQ) z>qdIO-vwT;P|G8F$|MgnQ<FEj!+1CkI^Uk3l=3|AJEpGj`t<XO3_a^F9ALb?HACQj zR?VlC5$2LC5MJTBLYE)-JbTqBrMaYTSmW75biPwjgh=iYa*npUqqR^Z{J&$LjU4&u zX}<}}(wWjK&p<sGmnXpa69w|6`%132S;*VYrg6L!kDsKp3mVtuBU|Y6ZbmrViv))Z zc+GP>%AF22#dFFA-`B|n)b|(+mDoHbRzA1NVVZjU=aiV6Ub}}X&B;B5G3ril?{IsQ zhlE}qjlb#7lTGZd;PG0~tFHbjUTn_oCCcZJ;XTDMITxAU7|Y{-F7{(gmw5Q4z_Vm# zEm8kyOoThMAECqLIWh)I14zb1y?U`{W-070=0fFg@mTk%n)Lh#q+xaQ4uJ9b(pGMw zgo7(|hGmw4Z?gs6D<0j}KTFT5XZ=r1ry;9`r?QankME)d*LU(LNyOculm}ORU!W7U zY&tM1`@8{K<2Finl`rA6LHIKB^8<v#uxQoqohvl%>?`x9w_=mz;VTcbgO4goIXFH* z_wxQ5Z-H{6|I_<~=>k*He)w7lk-L9<X28ef3Ic;vK^AGmY91em%>Fl|*H98Tc(VBr zhkpCyJ0<FxpGVfl!9XV9`iTy^I-LJeM<c@Oj`XvSbF)&VXAai+Jw)oFwF}6e!2YU5 zKbZ^9X7(sItW}@k3|F7@K<y_4%p0~KRYV;q?Y9xq4(`S1Vzc<@9Z}?)>m<7;?vqlB zV>M5MW<UKnER*8$8PU4GYO6Y(%oFCniurk93sbU`MDQev9$v{;*0NN;%tM3IZJ@o^ zw2aYTUw>pPrsF=ftl}+NPQ>QEYL72sL-!cst~D74?(i{sO6dfSSAASt^3jacE$8V! z;JF(OZ$BH-lKpzdO#@a-idfqqs5t4+)vR@UDT_;aD)E}KPPE}kroy%}MTYz3TB@8; z=!f03M7gyj4!vStpwwqoEl3ifE7Ab-R7WuwmKbsF9r4H%scvyySF`dVH@`Ej(g?2l zNwAa9W1kOVUwzniY1Fu8mvpX`UcCR<_Vo&dowNOAc2pT&8xW$oLiBBSM!oMUx!b=y zWm3PwY0vDePZL8_Er%d|j~g*)cRdCFXT^Z>;=7h^aAn_HX)o%X?k$I-BBRF>0e<x+ z>@9GIL_DgxDH5|FqdV23t84p@C8{k#hu^mEh8vGo;G=9i{%(g}oZ4W)!}ET1=KIF( zX0(Q%_Ut6VOGqEBs|KsC#DV(v$f%4+Ow1AYwY%=5^z*0JK1_ZxVDKI0)i>Z-%W^gA zOcunY74x2}r5a2}+^%&7F-m++fb*L3Jtj#4T*vRKH~S3-6P$_^CDuT@Y~eS)-;(u^ zNj78|e_xzd%;li0Yfyx^^PZ}WQoTN8tZ`mwUUY=dOs`~>L-m-}9$lb^yP>iZW~j~) z9}J_SIJP`MhvwEZu_t%gJ?1$8m3)GAl`(owH0B)ca%?wjW&{=bBd!z$UlQvSd#Th~ zB-Cn=fl;0-A;57G_^u358wS8*#-0mo3<M96t}<*IgX0P;8i#&y#hk~Ibmax=@>2D# zN&2AtSo=7%v4gVk#(2LhIWccVT`bGE%{rU5sFU6+4QGDj9CIY6g{LL}#bld(gnt8E z(ozj&1t>!bk)tG{yrIVfT%^Ob9};k$B~-YxIzPfo3PP=RO`{coz#bavYF!=dFY?r6 z>6VI?6*WcK=Ut}u{Vs&TAC5ENOb%auhIgr?q$E1GM`C81M^#+80G8~Lmtoz#Cd>`= z+uJu@0oD5U%syrU#N+{_Xh|h+CJ5fs$wNsrTD<A%z3ii#0INlk(=H1a-m(R=e$HVQ z>fE=5bZ~ntv}<A+jJhquF=}o_P)Unm_0s}zFHwjO!QKmD!NmhOhAsv8${enIGI2vR zHm)#$VqK#7e!KbB^-#<BbGFD)_mLZ+{VT>e%GBladOKk@SFCLCAB=o+{bP3rR48kb z=uZ7rZlXrGxyUW(*R)p#Ohrilrqzi*N|9FGT+Ips&R1OGs%hblb*2wq-c*-_$~8)F zL>d-*mQxF0s(YM>r<29zzto5V`jPR$es|s@6sjG>yinVpx#ofpa<&zR_wZ^803mp! z+vnCyW)y_^yQ}!k&auj(-j`Y@HDrh1D1f{7TTle1$uPhBdUe(_G)i?)ss7m}j@^)a zVi8~(7!jK`k<kyt)ICcM7VthgCcLrG7qp8Z{U<H}knq}*Eo$?^9ToBPc}pdXEi-z~ zKVBz{QG(-eUjV_5XzUN2nug4Fm!or0YwNBXfqTe3*^FX3IDkku!u72B=9oh@kxvn@ zifghJp6=<+5jF+7d)A;tC8B2;Q#_--&3Y>4_r=74ka;@XrO)R-BqgY@J}m%okEixi zWikrm8+|MXZp!LrJ}iQ_fjPLpVD(2CgXl_(KVv8;g*7IP+o#XepzaTQ1%e-;60C&* zZ#8NEhDM;iO4ftaZ!+OLk`a;es;|k5bdNj^2#eOQL`P5UJ~8EFYDumDn~V>p1dX#C zOYm&KEvQ^<gtZ>87RMQ-;WVw$F6e>4U&MBl>2OOD&9Hp^mA>}gIu%TJ-%brAG(z6F zryxgN7X7U=-Vwf1b^}oR2PqJcQbgMf{E=8Rvh<-#Yx96rc$Uy}52VJ@#fR+~^r|jo z;g18X8;UhYbqz=J;3|0syM>0eHH)HNOx3=tbmfD(i`y4@j;o``fd{lWbpW-5x4)2A ze$Sylf>+cHv5e!{0S2uUqANww{{2ld&Kr(WVjwZ8;|Q*_SX!sGv2s4{Y9e>AQ(4Zp zW-CGxD4fe?PriM1ZH>fvdV8l6v6n%@yo<p5;yHsIJ(}o(<a9F2E7Tst1%jbyD-ACB zc=`qjwW%1KR;@##8y^77bG}l#M#c<xPimB(ZK+3umiJT&1B{GAEd~DbcLUr=mbxO& z(@!awcYy0qOnygSqp#Cvk7K9%QMMnC^f{QdOl}X4%QO=}u6N5zt(fm`=k>sa2`1_E zAYR(BER}DmYP}Ae21lKyWAu*n*#~#eX#^}*k~Qe00Lk180(Dz6n{2zLybS9z(HiVS zA7!<NWaXX1YH?934pOCjKfU#@g0`D~3rRzI<dx&c`f-jKKD-rL7-%u?jYAV<W<gt5 zj!hqre-73=g~XEAHTgrzrLTGG`7(or34>4WI<6=~ifovNIzuT{8q6`nqaujn>lh)? zxJDJll<b~Fl}Q{<t(TWm4`Z&EE?1SSJRn*(E>OdK^?f7GJlbJcGs;f@GUg=SGA=&K zEa5;az_1y2DiIyI^`gG~>JHg-_&VRtb%~$Mej7U1&Khy@z7l`Uq+qF1cWd)OAOPP9 zgvJ>F1c)O6D1bNU;s~4y0K?I`^#$E{ILj5A!TLfn5hb9XtJ_f27pV}>?&;G|JdlLZ zj794;mJFqe-l?=1YJ6>gmkl=zJ^=N1>4B_|%Ezt%1^|K1E5UkA<zvOVsaI@=n=0<$ zM1<LByF|NU*g+0mU7UbvH9mM4Gb{72ikUaA6P30f-hKPP6QIqJ_A<RN87+tKy_5ys zrHgn6TDs0(qOEQO`p|0ovAJP&fFzKrwX9h{x<_;Avf!lxSa&<H>HA$vaG&}|N1-aa zPpxlvzvvZWcw7f$NGg7aS*9$VrNzs|30p1Jnwe^>vTCrw;<6WyrYXe+uZ(O1rEFSY zvz$V`M_+IebcIxt#}tcNi`2k1cHK}`5gXvVf1S~Poqx}cZGCGTEO*s%{+;MdXd`@j z$1J3p?5*e|NJP+W>1k)nP*w}q<tTQ}BaqHdj<p9Ga>+L-c6?KUoEBCgS$FMNT((x? zr24lqI4-D+WLM?|-LVIdzd}XvYEZE?(v|xWG;DV9g?zWeK0`3{hALu|aG)~BdbqF= z0+V5CasPFye?+NZvU7&pMmEi}!oJH7AQ-5oM52sCF8tHbJ%Ceu%tn6j?*NC(;DF^m zHGPzOxmpx|perEedaG+ON##mK5s-do^L3Vs`>T8>Uqw<GC?a;Vtb|~-Q(juCPfBqK zZip(a@26h5>STqI>0?c52w1Ca|Gl$Y*9E=0SKrG<SFP4BT(#Huk!NV5nsUfNQw#KT z_{J9CQuXcK{PW#!@0SQyzc;UCczkc!Dy{n7y0_ux*0f(V6LrY~9!p?8-l+P~dH#F% z$A18r_<k4UvgZXyQ>1#ohyH0{Wd4CR+L;3qFs8{UlH2vQAN^wQU;slDKO7W%5xhDi zT2_5HEM8}G_(5tw{O3oR)Z7M?S}s#pGV>p_bH2t={pVCMHm{>GU6Gojal@N=j`X5h z62B(R?|J?DY_3%EYuxA^3Lj%ll=wYus2L3!@y7wnM?D{vN3l6YkKs`!sa}5;UJQ`b z0B|^U@{bn$Jj4VD;`Uaf7YR>zF@E!RS2Pp7q~yt(ekMUK!Rt}z@|;ta^iAJ1qGTXF zMiAq#5%Mb0WGUk8w)|H(CbVeF>ee^BWGj3O^R4}>SBs(3e)Y-z$+Lea_<O>2=Z7C} z{y6_R>_LN}4Ju0<2LktDua77%p2#uONc}XxF$F&Pce16*D~r;IW>RMB9eA+7mK#*7 zbhy1)r+Rub<8j9hzXM>By-9V$i-tx<lz^BHPvB`PfNJ5*fFknhti6Co0X;plYXj<A zlRuu`+{uIYX=6LH_XUGKMDQGuz;y>mcZ4|rKx>*Xh?UR~_~<YeN)%aswoj~X&?u+w zU6!TgJctJH=WQEVru?_AemU3M{)7a7%PNWj0NAyp{b1^XflML0EI5vldKxLfL40K) z?|gK$CU+~7o2fw;1Z@`n<$fg7fA(50G~`=ZEKPx+t`%PQX-r>-Pvm*`61!Y<zqW?3 zF-EyWFu_6*2QU$Qo&^zjew}BwuK;Qx17vFujh0aHPElCn>qQUg_p=+j9-kG7zZ$@@ zr|tVa7t~`s?LuH|*5huTI$?AabfF<$8H46_>=X6F7K%3{bU-<j6uiFP6aZrQ@wF}r z$ZFc8q2fhvD^(}2FRtH{hN>3+#*Bzmrs+c9QT^=hzdi=4(4_n^C{-yIp{my$C&lnL zIEmr-PzPGBFSNB1r9Q;;$)7uFTFjP-XU-S~S(%HCp}}XdqGO5LZdVaq!fL8Tp8)U( zrrf0>NK$mONk%FSZV8XsNp3R^^ed9K=e+^$8jL%g6dh}t<{?)YX*se4W$x*6|DEE% zO7&#svDz}6`}bXsK7_9x_lgKQ#Hdc!m!~+DDTV1zm28Qp*oQdCOT?sfxiLZ~ZA3)l z3d04OHJJgZaEUYk5aHSt(PnUU(Oj>gk#kBYmy6tIhx+jH`<pPJ<&GL$XJ+tvNn@5* zo*Mf;j)lF3#vHPK)%PG?UPhCEOjn~5fLRUjBo{qVs`k8_GR8v%6v{N&RCtWuGhjXX z_AKkIr#JEH{EF37BTSSZ*EDWL%by5s#lToFQV11*8t{`8$o_rV+`^#+j&0KI)+2*O z(&Rg(g<q1_Z?NH5n%;MO$96-euYNs#_oDMh&9&ekTwmk!05qS{A4a-fkO3)b@KLxR zFS|N;v@-Lx0!=>S2Lp#>(RVP><7-nzzrP|M9g}&G($PBNE6l0Ky~1oh1P|})!U<*S z;=&Jn<<{PEJlRS$iRFxUyZ#n=cC$|u=^Jglr1trp8t9{U1W3-5KK|rICFckBv@-Ga zD>^5`=KYQ7Z$7R|Sl=J!Pyx<9hyF+VvPEF3(!4Xg0Kz94LH*?U{Aq4PSLe;u>Q7Jd zZ{%;!Z^&=9j0R1;$))+bsl>=hA<D_*ZHsSe&vA^!hx+A-B)n1NYNdp3{Cq8&=ce(M zV?@6I$lJS&blmTT?Xfgf@_ll@^*-=(ZK7=T@}5gD!_NIjBX6}jF<KGf4)k{NWR8z& zd(!Zi(=LN74HHt@j<5J0yXcbZv)!Q5T0ygUZ{9T(=Y8{d+BUmb`tDr=!*{PZrTILk z=bTfY_8iN)Lw>MnwiS1Lmu{b1+$Y>@`+R%PCv5KPrreA7G<M%c7_2Y8*e971F$lS8 zdm8v<@|%~p4;=2z&#?d3+%GY55Py-cJTIQNref`EU$*l-p}v`lWa%lrR-G$tAKl{Q ztU|Iz^wJv1_mGp8AR_Ib;^iL2?FT+PEYghp0*d*jHf#cQQ2M+5$i5Y;#{;-wS-Ixv z&^kHid{isYi!e1|dHHTXO0+!{Zi>ONK*pcGty{o6`4eciI0A{t>iFV2diJTMizb4C z0kFe^p%CNaE;>65Cj|h776E&eQ~(LY^Hl-klOb!n!>qdCjcau$BTxVRe973cd5iIM zOlNVwM!jS4-jgaZ`e7K`k{Un@a~2tl0iXvvzP}hfTRi*sr;D+3pJ;r(!bLqEH10gi z96g_Z^X~+r_mktFByR4q5hh4L_xmjj=%Xg}Z0Us_H3zW*B-pEgxd#72r$+z%ZlnI) zPx|kC)0lcXp$g_e4W9lQ4gE(aNd5K)$QvF8i4H<z!hdIm(>90GPlq3gpyEVOiY%eG zbd1+B!|1w!>?T3S4k1&SsN<VK;l!YnGGLPk>g}HhO<csNON5P1#QI&R6($6k9KzuU z1fp<sK0vPh2$Ve#RRBa^wCC6XT=h7q@)r{@CMHYnkw>Vo{TH(Xz_WWO_V5U>^d*=N zuHMX2Pu`km320f4y6w-Ktiz;2p@;BAH5>|q8juhlh{gVu2d<`5xM!05LF+eB??oW; z@{zRCTqtjpeiwqrJJQ)P0=SO=c0p;W2e@a`x)aQRw}&)NjzHdeqBMWdWem#Gg2Rjw zgWzL<9MGBQqEaa#$<47^W&|U4K#?d-F$xAmU7Ube^k6jD0elgi&nY2o(x~Qof5pMr z{$tKn5fo1W4zV0N*&PGnqe(@@a#^C*H=$uDKoo`R{g)7BDTICUh31%Mz%uc7VGJw+ zD-g|l3(oY-71a!2dv1@oyaY54r@P!0uXZT4k>$Z3o@n?minWJO(u|TJfr{l(is2+s zVUpVQh`*M0=|EEO9kUT#Ui37AzZ})0b~(J9i-{wJ!WR`Sj{=lLu;EB%@&u@BB)B^Y zeDI>kpTK`VwbGOWNL?bq4w8SF5`-#3zzzPY_fh;LV3BL8t{4X^hrsqg>K%B%=~lc^ zcA9w%8;dANCq}H}Ub>wK;~_>6wHnJxO20pp?xMi`0|i*xXJkK=gl~f+O;BQ8q(|2? z$Cxu8wXp637}rRdp)*OdCc+mNWaJF{E`SJJN(V2~4*`%*nvt>hvr_czh<Ye*QAR2$ zd#Qloml|rCl%1}SU8LvWJ(vM9Wmrc6Iw;x2GdY*uA+yEke7c|y!=bKS&{%u=uLa2D z?VQf-J5-aLxMq;BNp8OzNPHhbRbxCt<@|S&Ta%VeRYOuK49@l-9TaRf0H%Y13Wq~i zF^mUP6UJ&p-bRczu?4wi!Z=#+G#G<OsYj%nAcE^bI{WmWwsSXIUZK<ScZcY|bG%CT zhV`4g(&?f<QbV2&y`tAwp198lXaxn^BeJ|9Sr|lcc-}GMW$8=-&#YW`3v#t9U-2?5 zxZvq!_X2oMKJRRi%0#BOC1bBQWV!_e3`d03Bd%C6igN<!c8b)lT+Q%?GG;>AVi9;L zxTihH(S+gOQu+gq5;Ix}JO-L*`AWDRBwp~E@ev45DyWaix}#W{efWG1#dzcmRs7?v zBm&>YFm7{{IqH}C1q%ODV_Y)%Key;C9NDv9*3(6Q-c?+nQ1&da-1)+$dVm<BQW)3n zGk)A={O6t3Etba}Tb>mw{IUYMhGIM@DDXWk&Q`3v-pIJW&yeL-QCV3D^sXp5t>jo? zOdLY)p(@{9sjSbbx^&2B7f|)SvZ~9SFJ-5yle4;CpU;H$b#H9dz-)C*a;0ZW<@lAn z5v!UBhn(!0$_f3NTKAg8Va^YnWh$pNYr~v#tu-}PwL4chmamlUp4KM&)K1dY9l2*^ z=vDv9sf#nsE>uJjD(e72Y)1tsFjqZvmz^3|Py3P$(N>Q<t4DD)Fe^2%S~su-HL$;I z;B0F^&o%IzHDI_J`IQ<4ts8}d8bx0=UTJF-pKFvnYm^+XmpW^>uJlHZ8uW%a4zUDa zl;>)kQ)B!`d847!1hdYkDP%C!Z(_g7I0ryhR5URL6~PV|K<bQHh__5ZkbDln+&;3y z>Ww8`y{Acj6X!eB2at{l0>lLS?v48B{%*IG9@qtYi9tEhy=Sq0pCW})k9*G;SAxf& z9=kS$?$%o=p%$!~W80d~hAyIuo<eGlH>f+Lya%c=R*SWywzcHWwd9|*6mYc`DYceZ zx0VLAmcMMRY-_EaYpp$Nt><cMRBCIoZhIHh*8H-qwXLmvuC4Q|t&6L@N2$Hnx*gd- zTV>z=><TS3f&+X&`<g^MOqcgs?a~KRlYoM#k4hc2G40@G=scCH#DD`}tq%k((=K1l zsZ>L00pL&|T+1HhQ$V}>va>h_+Ufcqy*sU^N$83{%9GT7s+1$_jbcIp%++GDl4-}4 zy29LO%?eOVXu!yBSBf6c3>6P51apd`K%U(gbdS+k7ngX?Mnx=09rjoaCcKyV>niG& zYcZ(dwS;nZkQxM1_!@iw>oTD&Ga-j5a6!5eb@jBRfZos(+J1EuwwpsYH?wM=wq&VS z2Mws+?+pl`rH}8kneVeZ@3TkuJ1X}(+w{8x_q*oyySMjy&i6k)@ApOz_$m+h*$g}n z9`Mf{2y7n+o*xK39|%Ve;*<v?Z3YR!gVDKzvDEg#`1!%a^Fb1NC`EZF&1NVgcql7( zD5rfWcYY}U{6dX1T%<g#=L!o}8%|j31a|cRr4V%{z2#`>IVCbI8TL#B)rz70%=G~) zK*q$Rf*U@xi%Zkcr;rVm?{tHxN<o}VfX?8L%oAKX_OS3JG_anljQ*2Kaa5Blswp~i zcK(KPS6sV4M6L@wiXNdj(i(}Q`u0YimyLMdfzRlUT8WM_X^Mag>GaRLkI@nz+dfn* z^}abDrHqe27vxNHDf9~z<X;MkdyE-7#%epp7Ba@3H^$j9hF%!s`8$T;9_Po73)+qg zbAM<<0bX|@l)cBL%qXBSTA$7F-_!<%MJXgOoB@cU1xfeGB=F6n0N?8wB0q33W5Bmi zfJ<Fa-2TM%Lt&Hpk49d6=gKG!<<FlZ=vwws)1oM|gwNH$rkpC&65SM~Arl0gc)ir| z{VG|m3ncL=&LxDm#|CwO=VQP=-81Z$BU5;sH|pNUFUN(wtkrZL64SrBIZC{HOHKNs z|4x&*XHu{;X|^*NAv0NdGdUeIxeGJ-e`gA~XN$12CAPDrA+zOqvy~mQ)eEz=e`o8t z=NhqdO}2CILgt$D=2|=E+85?J|IT%B&-Y;Gdu`|YL*@tb=7&4xKQ7FV{GF$8FN|Xs zCT$m{LKdd;7G^sZ<`)(gsec!ixEEKji)*%v8zGBZd5b$8i+c-;-~TS|bALU=em%1N z`a9(7ao*R{j<4qnU;q96deJWa_AOnR3$Sm3G&WegNKlA667g@LQ12~Ndg{x<%Wa7Y zcMd?k6sn)JtSGUl9*0z)W7uY(qZTkscP)V&T2@0=Kuky=iVkYG_!sc<ZXDu^$>dUA z(>Vr(tzE3nZo-VL0PNPZL)Uck*YrEr3>Vjo{;iqttedH<o7=5hgsxlWuUmDl+bpiz z{ad%^*>F_ZaJJiU3Egnb-*E5T@Lb$@{BOgXXY;H3vaiu>_IA3l67q%Q+H6SH5GRu6 zWfqX~-mh~3!~;;Lq9BBV)fFrv)@t#g^%Ag)VG*^qDzW@ljWJ0Q<)*N>ufDu;n{icb z?TXRjffQ<9ZSC22k-e_ms>N9;$*sEYGr@K{Z$fvQ^LJZ2cL&OmV7~2biS1g+#j*PB zg8YT9@9*sA7CeVGXKlAa?xSAjFMdESHmEE{&M}PTFZyAS6FfU$A9^4LxwgNx7Q-g* zHJi5$`=w?wx3ufY2aiN$MRd-5L=cbmmw@&R`y*`CE#F>sECDevh{LWM6Vg0xsXBQt zM|lr4It-*BFMdF8OQP(CkbfmP61Vp<;}5`fh)g<;sC+iXJS4=F{ueS7J=)J}gc9Zj z{McuZpk7-XGGW~Qo<$khdipV^fs`YEZ81Utbv<-%*7g8szrU7uD5cBbPT6kyP(-sx z=VAKIP6T<{**Y}5{lmM=MfxX4=j^?(#aXqZuM!Lp>4VjU?e+b4lb>=_B~jae)kM8t zQwy0N73y^vx&6Y%iFUlsb*La-RgNEQ?Xyf}Jlva$DE3Zf&x#}D*q=WUQ<+sq6DEvy zVRg_0<O&A$m$Y(Oy(*gnxg5S^*K)k3hWxtE@R!2)V;@;`4YjksH66}yO_j;jw!Y`_ zThq$@n3hA*K~s>zA&t*Lk|g7hWJ~_VynHyf{Q+uCs{Z>Da((Gcr4`wvUq$=l2x^Kv zp*}|C>!0>t+cw!@{NbJT^#PLjAId**Y41n+%np*f_2hwA1-X;0o%$BUbhI6dQr+1E z@YUHUJl}&7=$1wwgadY`q$4jZ0vd!%5*m>(NkB&=-PQiMM-Av(-b?(7?OA5)`WX_o zosmPn^KHaypBvEAbt{Sq(hq)n3|!;a2?hFHKl)S4-xhoBcbYm-?;2hqz598N9pG^* z;BVz{T<e=s<Hm=d@;j!#aglu=4bVgnNTXZcU!vNgbr{VGi1yZ@;CVTKlCRibC_5av ze=}j{pY5fYcQ(rakE@jef4;e6yTykRK3g@|O+LRmR8c&@^v(Uv9B7gu+{9Y`*$%a- zd#~&%KiTJCZ47@|$)-P_USynZh+^xL$;xLZ&aSAo4@e{4bk4IqbKkg>x8N63)28h` z^!Cr*%*=Oko57t$><-g6i(*1IVIluPP*B$K)r?(9p=bIAG3epO#%P`w^N1zk&vr$L ze4z9@VzPlfVhQ=<Y&j+saq|a{x&f^f<$16WMQH%^Y@+T~T-VbfPW@@e3f_NqM~u=q zN&e0L?%~2~!lmpfo3FT@aE;#*%8W;7r$5fsM+>uPRpp@XM7mW5TLijPkxL;zu>?@0 z+e^VzIEJNkHre>K+Hv=FfEd_cAYLlx{#Gxx|NfXbqePC$>*w@t0tnrIJ|a}z%wR)3 zBEZ-D@rYEn^FU7A%A|JcXI)RX7=TRSz}wgY9}&IG(|B*8jc5dMOz*)jJ##{Q1?(lD zu?5b_`>BFZ_>g@z)^N((R*$2}{%MSu)7@bmUX$KaW(zm4l$L3_K0q!UBY6ldl?P{e zTc<C1kG;f@>&rg@zVm;1{aB(=4uB4p{&hXQys)T9u>9nyRpV6nJs~d_W#Ozhkha2V z+ezskMKE#NtL!I(dtc<kt|hv?0_5tY7lxo4bc>&AJRP6<R_kWe6w7m-!RIL-A|`&| z>O7d6#Odpr=PJD@Srq4N-;^Qv42RFj`1PT;sMu0JhgT%oN^CLK-Si8Up90!aL;u57 zzmN*+jrk+W?xB%csAsdDEu^slUxIpREePd!KFJaa7h3zS2)MLkG-U68*FTZ(zb67f z>5Ak=g4k_yd6(Q)B~yl(CXpnuJV33U^sR?o0mT1aTQ{}vyNPo`Uy&bN*?8MH>9oZ| zc#Kdht`z%P>;8<7<^_+(Bh@M(;X0FuNv{R21pkPl^5HUp)3pE>mb3hcU(=E-0Jw3N zSq|Xh`oN9NP~z031mIE)&mB#8NwXij<`Vra{I!QvW~{i^_V9gOxUhUzo>Hs&cZY<i z>+KP3)AbN^yMH>r`1_O>TTcG}<Lk}8q5k9l@7b7*nX&I0LP#}aU&oB>X$T=%qOz3e zowaQk`@Ziq_O%+NLekjRgb+ewsgN|Xgk-++{d~{4uI~@mx&DIJIj{3P&+~dcZjbx@ z#<l8dPP0x7cGwWFy6m`bE0^?O1j>?SeY{{WZ~ZFUR@R3dlR5>$CxPuEMN>$&%u*Ym z>j*`ZizlX~5G-%H_e=!B?A~uI;|Cp<9%JmAuqVbzVmwUgicz3O>LnhKb5|UezmR+w zoOWl=^hCRS;W@x3n80kM^g>g+_(~ZHr_v?r?rfIaF&YbSSTck;f_!LAz44eI{<V40 zs@viCXHD|Fa;<$U17mfWro&3rxEN_-hN%A2N)KSFAr#k_eu81Bu!Th?9+tEwm?B84 zEv94H<&-MJB&pE<%({i|yfkl#3=}LAA;N&YR&Kr0lc`@$yMU7TPn9U9&$yfG3IMJs z8}Yq8<hRcTyiXYCc6-U%&goa=<8z@B3-;4u&SIvdZ;2As7Ks*Gr0Da-0UlxQ1W!lL zbLB;a6@pd-g5CWaX)@&=8H#x)bOs57{&(wmcI06p*$j;f`=%jWjvxuRdzz<HIUI;v zviRmk-h2{i_>dN>KI8!)tY3`>O<0+lU(K|4iWEnr^BEjzjfB)jW-Fzc5_I{A4>h05 z8t0qqS;dd#rpAi3o;1~X)t;1alOn3!tl(754q7`!O0Y;K)--9O=k?%F#qw0mr!5kJ zMo~3JQE-B0X&&v6BC!TAxxA*F?D^b79GMsUAy&pH7{5e(6WXtBe5W8-sr-C<4b)^M zr*yq!qCx)c*XtJAXFv9~$kbvAi<Dk=>eP8vU1QW3bD-?lvfV&g;|Nn-&_VJ^QMq$Z z38%cT>0F+foP2eyrt?-HGQ(nH^7T6oKmTCli|dWHP31dcsvV=WCG}6uAEHkGX%f9s zy1QifvEp?7|Bc=NZ1hG3LI3~JTf!-Zu+jfFdP~p>vy22Tb>odeuFHK3{~NtUc{+vt z-{|dQyuoqQPd;kT2VrG5*r6H@+EEQoY78-dRsVm`TY_M$q!s5aZt*uGR!ADK5ygHP zz5r*S=5&P)Ed$?rlkcR<|Dd;XmjOJmYj%cRpvxR1hPWPleV9-w){<rmC`i5df6!Yu zL6_(5f719AGk@eao@x^}uYAak@aRYB-jm@DdT4$ZQ|gyb|AXG%9(1^tEej5zDt708 z0)Mx%u(wh#?h>?o?w{_13tf6Mxit9r!n?MMJHViCDdv2>WI>OYm>GPvglEQioeBI$ zq`HEJkbT*{=a<O;L2o=0nV-&axTs$OI4bZvaaX%XFT}}LR+oBsaFx5+$wiO56PBNN zEhTAw+p|r;!wmE7MTh0b$mr3D(qvP)n&ot!2Rr~FXUIsYrClidim+Fy`I_w<WH#sN z60PtpSHQ`=QUDmT&@JLyyZWubzenMF;oZsAO1wv*RE3a}m*Ka^WX{@r0ar~CfS`kt z;5q)-;wkyN7cDodshOZPBYu$7%nc78QO}+#>cd)6bxE>$Z8fyW$)~n9KTMHO8^J>O z*1@~i6l=1+)z%rZUF2ke%QxFaML|3Xs~JFyPU`b+PXC*kLn@z@p7&T4C>ai1uS<RP z$xr82=HS(nn8xAwzdv90nv30P9v3V>{bt$e<j<yu8$Qpnb04~&E4Sgj3u5oM{J-eU z(jV|LG-vi5_gQhA7nH-flg=?(Zg)$Fc)uaiNbbZPd$q5mJLhqUy3c!*s&t=s_U{Bo z+yH_T3kMx#Pizix|JSHu4?H`BL&%dWpTFm3UA{Y{%{NXF`C~j+QLG0m5l{1kPm>0n zgMaRPI(61`d&)EC*6y@XFKK(`I{3sKT(6P`FJ$v6$+OJlw1mXe{XeYtDqc9qeL8#1 z&Tnra_Qcb@1sK*p1cdbxmUtL+>FM$L$^9o<Q`EQEJz(;g(+4Z1#E1D`tE-avzl|v8 z@=<8Lr~j@uei~*(oN+G1FSY*J`1^|v{Svakhf4*o*PeK$Yi{p0oOAb;$(aW~MPK`O zK;Re`GIKWA;64z}4<vx(-bnoYy;9}MGf&uNVDA>NxApAxR@(by5^*+0ps0Jl-u>!2 z$ssL=X%gb<yR~LP1@S%Sz>ycYO!9}f<uuz9fF%O2<c*FU&;b~n-#yk3mjxLt!q>7R zOf6szbg8c+LiLO_PiFGr^=f709RivcF!x8_RD0~f1yF@sxDv~Flu|0<PdsILmG|=> z{k>7#L&5DXdAZRT9vn76YFTo{xEjd;qYD-_AqQxcT`ILtt*^!=BNY0KKeNHvPAA6+ zVRk&&x#1CZNSev1(Qzpk006mhp18|A1C}01jJ0%`7?<lj(Sugif=xj%qcL+|tyA9p za9xq{7Y~O4gbM+wWYz3Gn|$6=zBkJhZ|6ME7jB2~<<dD%g_>D{o~1nE#{(evMAH0M z)h3+^+|LQh_nLsLx=2HAMqjMHusbAn>haRee!b3s=UC7l$LTIF{1fi20#EJqnZ9aK z69NzC>T1^+BOZW`)mG8V?Z<Lxq3}x~JODC8=B%zY%ZOi`w-CTxZHDr;dLQVQx50G< zP0?sMX^t0q)O7>ER3Mub`YSE-R~x^~9398<<slKX@albop8|kbp6)7;rCY@DSPG98 z9vG)?{_)hyUmC7k=M95vwTiw)RXy+pQb4adB}D@R<T=P7egHr{lOi(R*L~*5U&#LH zxhS>wwdU$s##quu?y*}Qj{rdtn9QB98%21hPd@f9^LOgK9{66CB_&oIP|yGv{%nXF zkY@w{;~A@Uy9B8K;Lm#*CgffP_Bh0<?KUJQDS4haIXz&L{XC|j{`wiQ=@OB|<E6H8 zTo79@Kw&FLE!Ge@U+whx(8f?5NV4;yA`Mx%PTqGIGT=8E3AbeABxaHPwN#uRA6hi^ z%KF_&vT*(;{kpk3>FI@=a;a6^yDi6g2mm&;`iU@tnFBKL9Y~kWI~oASoL?{)<FX5K zSDF7g8q|C;aw|LM?ar-VhGFH9oo_kse*Jv<p!1%~1}L`;Ts#!k|9PH+V%EBo_3ZxZ zlbC~tuix<)|GKBf<tl^$i{Hlqm0PH`H+4g>5JCUozX^<;c%g3K@a?e6^>acg8a><B z8sdEq=ioOKt*5wEjE2giRPZ?N>zYK-Wp&PG_%he^)Pi)huY<zi&x<7EJAhO!H9Zmg z3nYs>nP94CXS&va*`!L=$D0nymmOKQj#hUHz9ud!c!UnQwf$Grtn}^7;H`dduhI0^ zvz{kdT7#ESs??oEPuVkC1Kye-<vm)2023&*HybIFoXRPGTWcWs^j0?U$yWnb^FX<v zX_eTOHKW@i6ZQ6LH6=mUq&_=ITd~i1#7mB|NeRdd6<8_xFxUNcIkHdAv_$y%I)EQx zov^mUGewU$E*{RYy0?UV6#%(%0%46(HElww_(f#i!+sYuZ3*P&40!z)o8ZL%&hPx~ zsP&moK>1F5A3j=T@9!7DcMUq!iWwnx$bemF>JS=cM(fNjc#h=obz!5GX#l<<Y_yL0 zLZt5gJ<<+p-*9{4#Ho=}03()v1Ya%_BMs~ND*vc?$iwQt+|T#FX*|;!4t}~-{QdB| zF0|zX#cI0*J@?hfv}N!~64H$3#$jR_HX3EMQ*(K4#o)sZK2rAgQ>5qg4W=PL1w-b( z&j5Lv{GIAQjp6bFfQ7wuX1`ngY5DwbBjm%I`9H&d+W!9gMSi9OolM?EI@3WI)7FJm zNkEf^{zh_&?(zxN-hjpY@630t-_CvreT6J{art#nI${JyL&)F&G#Q4Hj%Y`E?nuYJ zUB7YR@66|;-KG!!4|;26kzx8wAX4}XvjfT|9nTI&bRJ{31mCPeZO8y|`T-<d2kQJR zZ2T7E@0Sz$tj)8y;BYeQaOJ|ggHQh(y?yyt^Qi5Uh5$emwhZQOC;vE0XC3`zu>itk zkR}=8K<0EH!xkQKwLiMU<`{cq5!!>Q6Bvv`xL`;)K>pE(7&)+15D@o(s{wfRchIAb zK+$TugRz_7@JH}~2j4!)3XTMc(!x$SP|Q0b5XvFansPdt7;!x1>Tf^wTsu8442S=N zr@ar%ZMd3w4VUm3#T)X(5cAkY4zLsmn~Rw}5pEuV6vY6PO)(e@fJ8?6^vV=q00C5t zoMx2yU4?hj82i0&Nk*uXLy%bq7_xxmbcbfUJ@Uf<G*_Y{HKl@LG1{>*8F)4y!ep>$ zVa^V*=`e}yKVgosv1SBl5C-sw1jArKu6t31ZXUj|F&QE86V@?YC6QWp;t&DA06M%j zHoj3_LWmY`o(|gW#ppAmUhXAqg#$R+<F7u40`Xk*+{A6E#4}T}uEODSLI6=FFs3?j zvPn2-CBlO@+_UNdC_GF*Bx%t>qAOPB$&Gk^hvcQE<l4<Bas2(XzU1G+VVfE$yCEri zxhV%tDTh-jM|&v%kyMaYD#S6BGc*;Jmx^dk<(f`KHK%y*rSj(Kr{iGp7{Fazny90e zcP=M;#(xq67^0=gIHt>mrpxE02fl#cq++ZX+&d(cqE?2sG|UQj<|K=GR|$)WAfZ+F zGc-EFfppZ78z<=!=01)42O!h3MtYrz1}$)X!T`odm|uXb^Lbec(#SzT);1mu24*{H zWqUeiUk}ap%FFg?&b~RF?YE!pFOqXdE9b6bPEcr0NM24@bI$$goQL~4WRctmt=ve* z-00BU*u32M=G?^T+~ob-RFS-Nt-MUfyzJ1t+`PQ}=Dfn`yyE>lsz`pRR(`o-er0Gr z+alv-h^h_Et)I@Pi4>gIf^9SNpYP`^lF<MB3tFcO_~0lQ4~oes2-`=`kx*C73jIW& z-kun`R^~P%V*s9`qlKZ1pq7|u78d;*S9C`N+TV<_V67J24uzZ~!$Iww{brb1vtplV zBoGHn$6^9-g&PVvTOw&dTEU<FYzh{(vhM?=75`h!o>0JyIZ_cV)bw0#h#}W1lbfq0 zdnc88G*Se_74x-}h|iQr9+Y53OQp3-Wt>Xo!b;`yOBGv6m1as$AC%%m%T%<>RGrGy z!^$-C%d}g{bZ5%+56bYO<%AaDN>X_x9%CF<PHZW+j2ApNfT^P)&V?bWM#{ImL|Uw2 zVI){09szViRADOYwNrvH=~yj{92QeXLRi<9d$gpOq*lJ?si<LAesZXSq^0HOrU{2C z-E2YByHyQTBWg*QNB)?9vY05v>P41AwYNE@fIURVV%U7<>Ogg4E+S+N;bIQ-!qfoW zprr@Ue^H#3QWY2CYcg_cfmp;TEzBc42O$+2gs)}O>k29&f1tKjJIa>b;J8*RM}@>7 zAO<ujRU4x>T9;9c2p0v^x*_W5R-gq=Z2%+)UpMs|5mk$LHexoU9hq-laZwauP6KJ< z!R+S8(zVk-8p2leX{2z4Z5X1QiD<z9<WfOF3{Jn)G(R_Jg(hZG@!3VwXFwdHg#kBC z1)atKv}!W0$Cq<j#71f(_G+OzBxnm2Iw#0BKtEq_N9H&+5JR4I(_v>ZkYXxw8Yq<E zCJb(fec~@}$MSiuCX6VhA`3|nDKe~uiKxIeg2SH`-4$mlVp`*0xcou3P?6DCa3BqF z`ZA(ds<8r#cy~}Yf~dE=e0#R02(*b_BcT{>Few~(Zw687Ut32-RQSJuEWC969C*Y) z6SdGxI(HBmg8$3LM-|pSA`}Zuj??qN0=vcOVh(H6S1fAO8-AAF@N5L}1lMTeMB_M# zDJW=qy_<ERA3Yj}G<1W_lF->YjpQHAzk7?G4i@cTP@hTYMSs`@26BA_#a_v<QN+X! zwv@a^vFNBTn4)MLB!+?B!l8lKl6pX8KBD!>VA1RdYJ-8ab8Gp>KrPcyJB(HnR!id; z^3`u9y514p#^5v~A-`hLOa8Bq0EN#m)m50cOJa9s*_0Lc2G7I!5`fxZa{s2jWB>U) zBUQb-_ijo6y-6=>c0@l<g#==XKKo~_)9J2pC5TzJND44VD(Rwf-lKD~Mo^2m)`LO% zq6pgO0CDF{yCG*5?;5u|t&PP*&6Bf4T2PAhCBF_jaIMz+_u9Adtv{Kl6egr>1l^hN zn(MIZLTg8!yQrb%Me4owO}Dn6)Jvvh==cbFk%>B@zVo!~afPFI&1&rGtrw?zmbB0t zBV3|}+(0Vo5P;snqlxuJ2MImN39mthPkfa~u3D{IOw=}&CzVAln#W?+8BLIqccAc| zM4dj6Y%y30{TTz;!NJXFeLM8l8IdC8y!NjN9j>9Tf4TL4*=||f&)mRb=9!$gnB7Bl z?Uh{J>#HsGvjf72tPMIEi0>sbkR7_{xqkZFo4&c?046hX2LRVjg|A@%^8mC&>(I_C z6xkX563-FNKwZ{FF{wq`_3x)%q9nuz$1yM<1NmzNHHSej?q{tid6KkHJ2Y+zsby3P zb!(_7_5KHnTI&+7rQ$D|t$>;4$`WuYfjntq(NNRyc6SWt8}AOGmO-BL7ZXmRd7aR| zMmXIW$bW7fTuS{CMRvQbMYFWlXdJlb5WUD^pm+C2;4Nd3&Rt(dP}=~wia%@?Kgy&P zYd-l1=<dBR{qcx_yx;~KXJlM(><2PiOdpu<iUYVTU+K?rT^Qkf$$0zOzeKdKzxDpa zwakfGv;K7)S~(PUl+Zg_S2UY9;l*t=3r8`S^eAlmAr?K4Ltm&V8o2+7u|2wgDe59Y z1DT&TQVSTkuIQvs;6wBh3B~ra+#+$j9GQ&xhrU!lW~(=SO{Vx;9s9(hQfX~{(|zlt zPv<Oq%9Bjfb*H-iqP75VQ(XH74!!I@{Nk2*W#PMJKyS+x=s2EzK-$VAW>1X|JwvwW zT|wVzh4!C+vw@=zKQZ!a9lXqXf@)UiwFAKQMS6CyXua0Cin*R(-?j}>$z$9+;?{g< zVfWfC<6Givqgv}cb3TI%xy3-2aIq1`1pUF6)uo=3h287yNSGenjs$&AMGX!Xaf!d; zNMs;wKa_Jd?*O<H^%e$ypwg~PiVhR}>fbH-kBpF^rU3XF1NASdhdDBI;wgT1e{`{V z5hMvabA%rF(K)bMd2N3H==M<{9;uC=Z}ctTm}x#c-6Nu%Ifw1};ym{D-)A7LNY1LT zo>5O<tN)Ono}kmJcOE?sfZk#trHkHk4IpaRm#)QYQSafPwy(-A=y4|WN5YJ|()6F^ z3|~`3iyND{A!}H5X(LZ2{=P@y%((BRLZaziiwx9(PS^YMg;H=1Iu750L6rM9%QQ0% z?y>t+VACfVa<eOb4<Fyf#NGu%Qn27ssz^Dlny;Dht)O5Vi>#<av1qNAAFf{6D1JnX z=EXruX)OVtQ$_Ttqj1y~meEAw@ReMTIF$hgj{e(+QU^eFRmeYxE`-9XZ_X3*Ow<nP zr>`Vn@GpwPYT%<;H)yi~A=L;!OhM=uzi*xR?Z$4LM{d(v7a2p$)YXCgYLIoEfO-ws zaGA?{cy_<7(HADmjfOni(7Hn9JBf*6aJH?)b2R@t_GA&%#;vcv`u0Jg>uQtzgU4?I zAO)<IpBJd$X~pN9(?i;AD9{zuf#n;859nLmsPAt(#b(5n0I)|?s5TQELXShQ_I$P2 z-eGV@lOdILsGoS0gwoezYn%a8u(5yj>hvbm`}_Sv?zaziqUmVmqsZXDB^nlxlWt&X zIw-6UY~lun##exve^Cdy*IbY)0Qg;Tw8yPs-INmTGs~?tHP*F=5*Mxjc0)!b6C(!j z9!Hq{Nb%$9R`@selZ5mc;iPY{KVVQ@E>tG@wM;=>ExrPA67eh&RyZYIWV%~O75QiS z+d={DHH7NcLzkl`M^_o29jE>%6rcO~rV3xJc9|<|1Q_VnxGxGYO!)UDKV^jVv!zn0 zxDSpxbN<kWK0PWj_5Hy@_vwOX1xr8N9?QHz{HaAIl0fdXSLIm5!5Kt3mIaWiwIu^8 zVUk9<qy<7Ww}gJAu=S!*yuc}!E{A}*o<N}HSlOSSpId`ojyKkvdp6%1x;_;y!_E#H z=d0bC@5;OQ-Ktpc!I3UZMbhwco$0Ey-7-Y_N}2In#g{&I0J~@PRvh_uKkT1gks3oX ze|>3rwBGje-uEA#PwoJ_;xc-N9~<Pl{G9JDxb(}V4f$gNiOr}!eI-y1GIH&Q!Z@JL zrQvEtZS6#FJ*?7v;?majVO6cC2|^d--uNA@P2AzDv~LRgJlh|sp-QuyDPrCF(o=N# z&-r%XR1FfqH5!X6&UZSsqlo_&!Is&~NL&fq2viwN`kUaSrWH0f*}SfI<uK&;*Uji- z-=9iqO6hQ|hMlYB_q<q%E9ia9`hFvCsi&qf3Nf+gT_qMYLy*_~C+JBt<n+#nDc)Y& z@8uPr|0t_Cw01m}2sMC=mITsgyu`BB;G~y9GyBm+Vf5cgMVK4q4L$D(pR2{fj?!e} zv}p>J{8B|a-9)jJu3u+UoE5*fJX+hV6a@Ni_7(}U3{@;ny*`YS3^~{z<UQ6L$}1Xf zyP$G@v+KaO{&`!?_oC1>Q^HHYp-7Cl+MneYAELFTp~GRZ*2ghEE1M=PasPa{8`j|1 z&mS+6dJeuF3u{$|z=?aIHibdX9lSQyCPe{HLm1&NB)nIa%O4vpghIt_ZhS?QfAHrT zx3RoNE*HC`Cs5a)<R$xRYAy`<WGwhj$yvTfM<P&3?*-*oGeup}u=22FsVd3fZ}9T? z^Cow{OGF+$SHBXt<CD?&F4p^a9DRj{outKZQ$?*OzkZU+i{9~)@MbL-7ryg^OT&n- zR-ux?J!uN69DggCuI7jRS0fqZfCS7d-rwpK^NGni(MWMt?lVpJ^p8vCg=sA`M{$N3 zm9N;#b6%2s>09%S1j2u2;#s-gW$~6r-ZzQ^dKO_F0L-@I6?SObf>j*W=YFF&xO%$G z%XP)wtgyOQ?r+IGyQ?PaVX?-g+4Whcp>wq2a^~YakblKZkFTM3Oo9&UdXGI7*p&rj zXBJ!B?%t`qQQdgn<6F|Je)s;Ohn4y;i`s@lg<swO>Mv+TFg8u(N?7@ki1T*lEk*w2 zNvj(lZamXmDfxmsxD{}a=5WJIit8oT#QRG|Cg4?(|1Hz%>Q14?hkq*rremwxTyu`Z z8dof*%<_+o{hQX3Izn~S9?V6S_Yrr_E7yt|e&LB8{+5AKt#4jaF<|L^m4kgA`qXZ< zTT4O)-bdb8pK>N1R=wkF?hr`dO!br@V)|(v0;L#^!siWfk+(juE-wLw4YfP)y!y4* zs$2M4(;4ctnx(Ur$j1cr->65KO!ZD*F8lI`)bHCQ0YVtc)4?$QVs)u-88b>Of&}%l zed5xv|0&qhlc*>SC)|ze)wJoZ7l^NrSYpOlXiL}dXhS4%9qs}@Be)|NB*hQPvBXG7 z*Y_1^;TP3JXaw!;iCaq&On-RtK(#Sp45ogB?bTeIM4g^2J;n-|(kV4HCfnVKJPijV z#ygm{uGi_?q#>?LZl&79O7lmGL`g)D*oEUD@sr+WTDX2QC((5E>&owS)eTRWJY90H z*peV*Zl}f>R%L5hj~E{U(f)wr{FV3RR3A^r1E$DWNtRnU6ebOlUTIHmSpiGpF_HS2 z(!>!j=$ETG*lCH6Ma%H_2F8REf-Ml87gDbIO<K@`*E1KBmR-NNXH{?*r4+W<vw1Ye z<px+1ro)VtBNj%k9!ddDYQ`c?heaklCG!U6w!_vi@mE*aNdP5I&AyJ;?@uwUJ|H9w zugwVMvKta1H8&)hMpMd@JpAByz0Zl7q&|4RePa{v_VlRarJ*uK<UOMcb)81Rn!c>H zJs%Fen+g)YYX{XF3FmO2f;m*NfMRBsjGQteZtbe%iGu{~ws!9Nf5g<WgDUGC1V1d? zNcL2IOwXNxq}N%Mk2TC@UCu}gZj5?}9pa2w!t=~X)$(vS9><=cr#im(dxh3!0(j>! z(b|zxaM=|+$6Zpm#)=_G)wJEWHxD;vLlOOqKcQ#8ESr~loOJ(q+102Ye06!(&W(pe zR#rERhu$p{k4Rkbe*;onp8%n4+#;l~3-tmMWulSro|6&4$5&df3L3%KxEl+>GU=Q? zArzV1RF{tN*TS*Y#A9n@7!el^XD`2tfk-g`;g!VyYI=np{J0!sWZi;pgY}qSOpzI& zlh)kKGMG+9ZiK0mpXz!~+#KN~VqV?Z!kTEb@c@=M0F=LDQ3;_KGJh-<Zbqg^Dj{Hz zsRZn4$!8LIwNEUCJNl;dBKSZoKpatg?Hqaksz%>JNBY;H$LYVBlzU+MyS=OCKVXHL zd;JTo*F#T+)W*m%$qUz7JO;j`#$0%_nGoJu+Lk{N&gskmDjc?dfHid9hmXZ;wKZkF z2gE#j-k0)_d0cPN%|vYtw~7;AfRU@aW%^_^f^QxdSMm0?eBb&hXME`{+clqg;9hYu zO1rvj(p+cOkXu4`Rbp-7nBnA7oIXw(%IgKR<5_?wt8|qv|43Cp=(UI*TyH;HlAuff zo^&Gw%xefEVia{^T^SL6&}q)DKG2W1JseJtYB*2ZTtq%>a+L796UZ_;@AtUrc#%K5 z!YX#b_8}iw^f7zez7#`dNn`?efNl`OR9*mISGZJ!-_U=&Hsc}mSg9l6Qu5K_oU>;q zrcn<pw)-<lJt}J6_)2eliD#^KL&3Ram>PjM<o6TP0?E`V!{NY(cDm!zLfK5nRemeP zQotfM$RQRzCI%Q)j=T$pPxQFT6a?S&5VO0}JKK_!P<znlKMhkN@WP$*bNmy-T5K!1 z43i#KcaA<h)yocx{CU0w30Kt>GrdkIp^cP@5=76Po5guZRs~4)+nQE8gCs*+yTugS zZGzRqw*U}B%>BM>LX|EGms92$_eAFdRyCg!3a~oLjhUG)mJiPC_6G9FnGl`{Y{V`3 z&%41l^rE<p|FJ@_7Y#oW9B7!%<K>H|AE*&MZ3VsGcZ&TC;klBp9D5!@g;?}-DRcc1 z@~d9b5P1A=YGfkCyrB!D;^3hF#r<_|%%d|GA;ToMV2oR%wN{VrxqaAGP~z2X?77g` z`R3;dd2wkNu?!;CnMU!S4%eQ7c)P{D%RTw)jmnYNi9eLgBmmrdLC`rP3O5x_1RO8- zew#y$VRYbEr=)(58Wd{B5>_Hxl`Er#<Kt@L%-~#Ouo#Me7J$lW>QB*}3TF#B++*=! zsnC{u?of+%>p0=jz37i=BKZrPMVpchIFTvej#W(5UriXrpI?W_wHMoP3D6cxGX!-J zWHMi|KwRW<cSYCgDDvPdS7sE<vg-Cqc6030Q_JZi)iG(fB!%s$*P%(b8VV5NG6t<l z2ZK_P4u<URkkXSJHV%eyE1mh6vM+H+2RPvNUUn!c#i=h+(=9^Xi(<mywB8mB%6%T{ zVI%`I3SveZ7K*s0#>|3`rPm}mBqm?Sz|P1#Mb5@2xj|##F@D0(?2v3HawLErj)y^9 z$uacWbjRQ4PKFicHlG_WhzSdSdTz*Az?mcNGu+3lvmQ|V+yVNlpbl0KHN`>HMt~Y2 zk;IaOfGN(K;=Rzgghn8oux%U=3*|1$mR&d5q;vhZ9CwPZ*PS0xeihmqmmp{+!+Jz5 zajFI@j)WU9U){4dCY$v}u5&TWWU^ADWT+w=*7@GyaN$tB^w}hluDI~Aqz`VmjXmgX zdM1tvQlvqyYx2NFp#DtVt4e3{l#G+T(!*fTK+Rkn4D8AjyiFH@UNqmzrG9looe~j5 zEs2FpMXT?}xOzov!y+`<u?=!`QfEdmQuytb#9{wHVXDQu=S{ScQq6sO4FqobS#ZX5 zpk<spdOS`+I^_`@5X^{qWD9j>v|t%vJpJuE|8oKNOgo0+-QoOgnFFpN>8|<ZL*tfn zur|Hstio`3D9-ePA@$K-yNNKturE4DQ&LYRW^|})tUUIOC(%#qEvs!iYH*s<+puE_ zZZbcc1U-mLYvfMj9}2`|hq%S@ZE|E=fK2HSdnIT~d}^z$)d!5Qk6HN%9xG8^=pF1? znoJLKJn89d+-_kqV=ON?;jGrE=p(OaJvumRC~^R9q?vKyPh@OT?m0?LOlILga0v9a zgTj~T^PsofJ`r43;m44kF@d?S$^+Q`B+iU#KKDJ2bbN;&t!_1qboHP&RM;r%P&At^ z`rUHWq`!k>l+Ne*fzyJJ9Rdxbaw?QW$lxH?VfCRf@&<8eI(77BVm~Dnemex}S1v*` z6i@X^56mB3Aw%h29F(bnLenvh&0{yGHEV%tK@R5x^|)C?DoBk^xsJ6C#@64eLAEHp z7ith|WM*rSz^)E4G_5kr-*rme=+4Fwo|)LuE{i-SZwNNV-y<%lX;_9Dq30F-C?p0X z71I@Os<hL6@;5Y2`KA0^G+sEusc-ytVRomJ4dE^F`=O0fv-OI2rBM`jFbqm^PWy2` z;)Eu|m5RJrck+E9(%X<4B0Oj#0b*YPxBaD1hgPkPc9)7!1u|mDLjFtQaCT|Om^8>@ zj{_%V{!qME9+c(R*WwgH;U((T^T_zvS($^9E{4Y7L*ZIl79V*bS8+-7&8+&v7`r;C zPijO>7fy5Q*qx|Lhw^Q{c1C8?CKj79H};xX=26jfUgWv4Tpahi`H~oa;lbPTktdiO zLTj9%Q#9C>DGy+xx^%3?q4*^+q^@H==N3mH60Bc+9^NHte3;N+q$YLcbb!~}HzjYf zWJwm!C%P@f((mQ?^5r<gl=KQsnYvneRAf*{g>$O84=Kj7$iDnv>h)N}mi0{KW|15` z#(yM#jTuF(20?GexSg+dDc7JbaMD8{YHqKC$q5qS=Ni;fL@VMy$`osNTd0q}Sqmu` zgOg3D8R~l%?1w(f+11Yr3wN3!HRzO}i=x7!Jaq!jA*I<qF!Du=@ryE<vH!Yn?pv!> z^Ep$av#?M<uk;q$tVdV}9RoFs0JGY5+QvvzqZ273saX*Wnb5DXQ^IiTZR-qt1d;ra zu96@Wp0-dS+rAegw+Z!1b^dj)?H9>$QPx$ZlzVg!>c7Hy{1&uNG=lwjADXBsrMWq6 z&?$W|Y$f_#2m~u^bz8Go@%WeHC1y@G^K0aoGhzB~YB-3gAVoUI9eJS;;TRL?xAspY z$L_V>uC@&{6|EC-69b-ISnR3^h}*el?MerWOi|3J1>5(}uTLDCVG7ddQTkaY>hkh| z-0oW#_RUt^iQqyeLXD)M%3Co(xJc~~kSR9$UJYaUq!i7IJNu1oL@H0r`U0nSKJ={X z7ob`oS<7)NN;@{^JT{ueH_e$*CS4cW1{mQl&x^SOfL3NLoRUj1gU{xrUot$GNveqX zeFzP4<7`Z1YtUlenU-S|OIT#iW41Amy4`duJvVtwLIdM!eQ^zakys{=V@Ta2%#xnH zQ0~j7`P8^DFJzb|L=grE1Tb#ZEIUrd4mD0(&X)fCACFHiq-NG?g%2LMC^8D<5;+~I z$F}$ErG&sPI|Y49Nc|KW9`nl!`T$|7EkZSY^4aLF%^O*Peq7~Mz|#?dL{oj(N5Ju( zd*1?|e)X#4_V~v=5Z(r0Mrq`RYrDmr@J?%K^3dPxI2;s@VrGU-QB3;8D;osHJikX> zk9~Hy=(s!@9u>)wfq@*UoC9f4O)Xb`S;5P>Vwbx!0AA7Swov84k<cQ~X#3Teit>w6 zMZpd|j&&TGArX2_M7QXSd9&41n_iU-qQ|+(`ahw^1LGoHR?DKlfd#*$Ru=;LATnN8 zS1!j1!Yw83`F6Ep!*F>LGO;CDJUZvrXgx;LI&Kc(&;aJ~P<amtc`t`NXvf-j)f#l4 zgYp-A!u61d$aJ-aZ@z`3`Og(l)oVSL)C|HNM|CFV%ak{!2Ho#Z6(~URaRXlWx3|4o zFVJ+$e9w10>iyUq@bo{VX@+d_SKgu2_<w4JkL0~VL-aqqS^xAZ4*XDqg-HnRi^PS1 zh>TC~$iggjd%pfDDgTiSJPz_`$}lSW=W;PD7{x8{1A6SR3D+0JA^9~A`xU*3vDb{c zG1X4cg!~65kFb;Aa<}8XYG|4TO*|HkPdVZxA!*I|9yis+(zwoyZ`=@`l5$HEXjuEb z`zwZqhxK~~Pq|vFM@sZv7rd1=Du~B88rFMps=2+%$j;t8`h~o)>K<P@nt<fGcQT9_ zrQURd<{P7MFK+)8j}-u_84_7^H>UJDkt-(vU}F3Alt`W%JOrB?_tdM|3)%wu!5P5S zHS(-B0lr+kDU<RxCdnd<6azXC3}ZyASVd^$x`dE_pm~fh;3KY^vNMgpaXGL&Ju!9f zc~+1Yr)hPBA~`aM6!(_v_a>~ZY!7Hk&1vS@(slK#NQVB`{^5E(_}<lMSYC{v<IQ2s zC^``$g1ZtN!d*1FW%^|+`-m41zxpHcnTh6cQ1H32N$xrlN0~gQ%nBv*&fWUVZCh5x z#FOXUzAm4QEjk}+z_sqarB+^Aq4b0-H{%2C{sfBH_;A0^aN2GkiwBSFX3vVJSdT=( zn2^z$5+_!mGVAK)_g<R)<DVxp=QfhR&nGd65E=aAs<iT>;@$spE?G?TSp13!q(-lB zUegHf{xOWaNaA><7@^&ldLM}F*8TIyHP%hTIA}%n-F}qJRJZ|ya|aVgA4y#BP-a~W z;V{w!ma~_XRf5TncZZI8FMp0cu^$7zL}5kh%g!bWo{dn4k?pCKev^ASu7S?qm|tS) zkE(B|L*EDqjU@ho?*?$lxW$*M%-xCEFLjMo&YG@`^KzY{-258}Nagd3l^o@W7x8Gg z)EC(~l@neaeFt#64Ei@Z`_siuXfZD|L_Wqxeo2vb=X2*B#4Lh!ndANm+CqD@KlXt3 z>0Wilbd3U%zZmM;7b)ZRUuF77y5Z(ya=aZNtOrK6UO9O7<!?VU=(51=d&q8+G1I++ zC?SRIvEy%xy`thC1KeP`5rF8YRfqk-H((7D#vEAmyXm~p$UCFsa+}-vSPs@J6_9SM za)g)ig)0vRZvRs(NWj-vb)X^$7*3%8CGCo^M7Pi@4)K?0QQ1&VNZRfKD=<8G{P+>u z-4!!-HG(kJxWNdG(0mY0tvq*zbDx%Y(TnqD?C$pWhj)cSGHkO$LxN=hv5L=I+v}jW zFOwq?LMlq#IQNq_&umtGE}94_M3s=UwuJD-tufLj=}O+eWd<@8FFn7x`dfA=SLMc7 zz4w;faG`ea@2=*J6C>0guhK47CFeiG8Sde?E}a3W+0@u`kSY`_YHF)YSJT5ybE@s? zoh!^&Hg9}r^!fDs){os&vrTutk3G@(eQdrpjMd=r{le_KhyRX5W;Qv|jjT{QsF3&C z+JxCf_Po<)VojiwPxx}))ow-nS%3KE%&A)ks%zu5mtOc4Imwe!v8(M{lgaZ2t|`|c z${n!W(^pE26v{0_7d8jV;)`(QzWfRe>>XXm>Vfv|`poP9er^1dU8jB>2w&IvQ1I^2 z&ix4y>(b#;w{}-<bgEj3XMe3j(wJQp%mEmyW^c@(Z&{muQE0+axV87Nk@8VO1-cLV z<vv{48oHQxvY4O82>M{Vy-&HN6=W~pX)P3Q)V%_vUc2g8fe7T82|1puwbta}WGEYH z51?Iv+3LMYly+5!<qs!dWckDUWXi<BL&`wNMd{;bBTFn4csWuL*I2c=V?!Fy-yw4O z-nGrw^9{rKFX;Xlr&udgh}T#s7eh$BkW*9|5fjd--3g0sz3Nz0Q@)sY(qnQd#X#t} zmO@3AQ<(P^zoX+-r=Mj0HdiQ(4Xe5zJMP|BQ>865Bp=w8K3e*?nP3HAhD0hnZC-0R z`Al}d8l$&ezjXmnJQ;eky39$$67Z&V@n&7`^+tppSG$K?;ai_Kr(Vyk?eUp1^ko?e z`%;&05K1e>0M92*LmV}L__b4ScV_P04w`%bv9=#S_<P3gd+ABum(OUtzh3Ssw&FUu zU)Z?-CTJEJ4{L=JX?ZB$R^?uavb)qSzQOWpyK4_TMxIF4wW<uVcCU*qH>oLv4G`9y zPkIk({b=1P|Jrc8im)-TOain(nCL?M?^e~1=RbR0>Cw=#wKQ#)D}VOU(f933U#y{` zs1?eNc$wz#-vjj-?_RqLL)!mrd;#t0mFjbWpWj}ohUZQ1&OP}1FZfCq@Z`ESS?r<a zqL!H;S-zXRmE5|@Q=s`Z>*M?P=P%_&F$S~m9citkKQMkz*gka7T&bxmelemv0k&Ew zdZw@Qllu!|+VTm6l%m@%CoZ%0lHD%<s`7iJO1U}TJKe2p!3`eV=$s7t7d(GXcX#@S zsnxhHw@B;mLc#~^p3bV6-~LkFJN=-d*QY;*e0pJE@GmR*lJ){?=f^u%-oep;0lR}K z=TAH2#sD7{#OIaKzuI+^(Lp-kmv4s`FO%mfSdO#R?c8^06v;y@j40p1lTM42)0IM8 ztnLtaPK!D{J~3+~+$oel68x&xPPaZ9|A6C%n11GY+TE#iEN5DT&~uDdM>rL7B;#-- z44v}%ibf89xY3R<(VSV}4}g#*s(kw+tA+7MyVzS-JYz6mhm<?I91_6Po{MWzJ&L<1 zwqw`ilw>&aPAm8h9qb{jFeTI)NfFMUx)K2hX$xZ#dG}#tmEqBphJV(N4q5~?5IoW6 zMHi2e_eIve^`+uK=g0@5DcVO3NCBk<U@xqf>yL&c>)|-@*g?pEK7N$jUDh;n;e~+4 zT3RHox=Qk1h>>pBXmZM)jTCJks<qrM6hu7}9x}?Qdx%5&I-i#S7Jlk4-%Ru2r%3*- zHqxetb3dXJAO4{9YOc7);m140wuED}tMN%eL*PsvelyZdHPov>N>RJdw>?x#@*O-8 zH9FP9u6!~%5mqk7c4mop8m8PD0Sm5B-~Z!$t)JS+2DfYl_VOqy;4WA)hWcHD!Ot74 z{h!2(k{I1ZwbZcGrDM+*9;14<(18vV%yVk5=8<8nF@#<K>@wCHVM}b7l%jE+UX``c zq_E}g#C3`-?lA)y+C&NdUD|`0YDjYLW~Ix7<(cTIltgQccd!*bzW?q{<#-JNMHhta z2`h$mWoCEpW8IG%tN;;r$0-sFOp+JAA*CanQaSx2L1)G~#kD$I;?=^OPEP|$?T{ex z(?8~#?*U)PB$55|UxpfQPu9=>UA2=NCBEj)T_q<Y{*Up+<A+p|3mq&rg%wl}I+5fs ztN3#I9@MStpvyGvr3AB@L!A0KxlNT%W&>lQ=Z{M+mi%~Z(9(@I9&p(pvMT|dR^<Mb z$Jx@kOtR-6T-_)m*&?yCX=kfObHy5|cDN)K@WaBaR~aP{@?1i|NAB0aT7t%*2lb_Y zr@?H136~Quku_4yHYa6vgax>;);|gvoK8bMjO9F&^3{Y;$V0wz)%3xGh6#<Ml4vK@ z-S7vVCVC7;0^(AJjKOMx<}wc~H~BcgPPpzETXN<*PDHhbn7HsR#>~~09aFgY<pP~& z!i8(%2E3h9FFha$K+}w0B+{-!>#uA}<w;t6^X@om#+U;4;p3za8Y}G46`d&VIs15) zU6<m#CnZ{wC?)jo_t%|UY9i^&y&(sssbTA2!4#Fcr0LDMu%;5h?Gaq?Em6Sx>(ZDt ztcfl|%J^|JvBS1HMrF_t?Ncq~V)pUH9-cQh3>Wr#9s6GAFcld_`WO~B?xMG1opNjY z>alHq#20!y+M#?&f^dpezpG@)kjpSWGhzodKPKCp&bT(t-qq2Y*-ReVB|>MJ-$MWN zzADKkVt`XW4H)h%kM`Vyujn@DCJv_DmG5Z#vE5s;bUm>t@7mam&UEsR64aF2q{Mni z$HvnggJ`T~fA3BI>nxsF69?UAP3|VDlQeGGr^g+Zt9xx8mwNAhy(IY&*Q1g6rl#mb zx#V>0IY7FOzUI;>_ZsPXZMf>MFw3iGZmXRuN7go>P40cN@9RxwNgn{52@*zGU{zzK z*N?<KxbI&+rrv0sVooh<n$moJ4-81Yi|cA`JQ=E2ja#-ec_5KHw{g7QPpm#A{fU)# z59X+ydu&-O+`g{&H0v7;<)DHy^p$Bjn3`G*+Xh$RL2=sqCCLudGI2EeSRq;0&8rlx z{(%3<<Fl8SqjWKnEc{8;M=GzS9EzubUJ$9N%}b1$6SQpA6Q>$mYCaN~--glNyH5jE zOd%Z^FQMkW6s^eX+nw#=-}Fd}A}}JeamB98S1+H-Htf)z?_sWb!-$QhmOua0lvs>` zgQ(8FZ6F?F+sva!caY`&u)jU5i3O_dfvpTlr0sLZ;=bt5_3YP7Y9~^3N3w2mWV><D z$^BpgBvpHacw8xB)iN!x94kvAXqDTDUQ1E+?lcG)FI$&n%3Ly_6VzL+uIYVdiq9MH z6R`MCBIjAA=>1M9agb_%0>{D?@~D8$h&j!xkU$puTYp8<p_6Shh?1GPs07m3%-++r zHz+46tyAW+#)|hT9qk=wh0z4Z;V7>@1Fm-U+{vK*3=+9Zx36>k0mYz|BD^ztJ$zOZ zyQqCQyv|`3v!AKfL=-l^IBlBIt_C737wtk40(QXKwgg=-aJ~roNT$djv2>GR_w(j_ zSarM3{Z5_w0+&S22AZh2smrl|5`t338B)6|M$m=M$CiTNTIUY>-fMdiajK#&uu%gC zikjxQTUXAA7Dbs%QTUBfR53c!MNyRQlaL(tX$SXAMCd|tZzehuGHvxzCogI)n$lSw ziyUMXy~tIr;v<=S10|4bB$!)pR5iL&RGf0=YRX8Bu)(s>rL4%&9fJ0r(5}4njh#;Q z#*5ASi@_3QxKx4ca50y9TgE;?FO&Z?=cF<)LFJ*eADt>9dQPy1OXD2n#MKWM@aD7O zowA-pqP{apK9g|w1Mg@u>Lo?vuv5%|pyxI9$NHF=tjJ~!@tD9g_zAxrta#FHzIK#& zmIT!CADzIISfK1Ql_KQ!CJk0F-XopTsu6<mX!$!%N=$HqM2=DDgs3b;em!}NJLOUq zzuunX#WsrST&ZcIsLY{Z)DtmcVz~xHGDYFy=SHF*3FvtGxF2m!bcCoi#3D_PQrH`v zx|)^G_8u>6Q*_<3?3>F7LpFMaM3t#aS~jTk3GknNu*RV<HaYT~e)x&E;3Zi|#9Odh z6HtvtGz)hDK*}~}J@4~ad>$og^1FCRe^Hf8GQ%KU<a2}MmgmTkIsJ0FUPJ@HWu?uz zw((?+wQp`H5g%);xPI5|u=L(=8{mMMT&tmhOqP#buFZ9VM|;iz_WbAePFMK3=~I!R z5hsZ2moJ1`8H|IK);oVNscZ~p>M6Gpa>-GTBC1=o-~5eWEBnlvvT+L=aMZc}#7-W_ z5%Shh&ZtB)NJ_7qp)}MU^Upl2MA}H8!jy6D!h;Cea-v7*@cR-LK^t$KeXVG#NMtKf zRD7KWAbs78JYhg@Pt?vm0}_#87y?2V9`?CKA|3S6l=q{QV_u*@>2EU<6mbX2uRO?S z)x2X$5#mZ9T`ob!a=G{-R+}w%@&aq(&AB=0&jciPQ!}rj+8@Uik}|tEu6v)#og4<j z3kws=4$d8ge+Z}A=?Oa|^#~PqWgMf+KG|k3hKgA~F`Q{$oN??_9%;WNUl3Y4sxhBr zb(N?kOi^B!IloCIxKX}HB!7T7$T18J)+>+4r*pJ*F8>tPlW}};%Bb=P%)1A=b=M_o zipv&rtbTgs<>6$0bZza^TGe*(8MW*)*+r!aVuEU!4H7J$PX3eT>ppsWYgXDPbuuXg z=ZN`#vOfVIC2c4-6>QJ8o2h=Slo}A-Gvzah%QCcl{BoRl78@S15dC&IS!lpl5&l`V z#)nWJuI9huuwjK;w%7Ec<ogi*N?ARu0L$M5Cp>{@=Ax8_a_PfX*VU>-nG`p5Z}TCF z4ppFWa)!X@9xqyv`pxlRtx{B#qODqb{dbgF`MOT|Slc=N2F!%?-H2nOz5p-&-%p6v z5V9Nwr0butu)g+i^yWz3l<9W2hxKe;==8dqV2C3~k_jH)sWjuiaaOlo+n@O4XJI9G zDIo-G=Jr(*@2*d{vDLL!|Ed!&Nm_+>ihF?#7_2qocK7@K_S2ZbhIR#wX6c!sq};D# z2IDtJ-xgh3l_0ux-kun4?WZuhFFOWgQT%4i+Ss<RaKEwaUy2Z!b;C^A>tqSOr{4A! zr!Um2<m>cJPPX~E2^45lj2cdu>xq{K@n$_2c|5gY{!;;BdT4dN)j`j}siXgt8Lo=Z zbY{gZJ0PO)eIp-7DWq@|EIvgr7@q+K@W@OV8pO)>$2pM&K+E~Agtz4eunzT|D3ZQ> znKu!(d&OJOs9}fSbR4Wa1f(ZDd+Iz`xsLiQ3@P<fG84Dg8cEN8YsL3<4R``_O2Me) zRpHm!ZwJ?YzQm-#&OmHLKOVoI<DM?7C&QX=%<kGQ{j8~!vGC*r>DtB9Lv>uiqZ&aq z+D$~Rc`wDC&eB_siqi>C+#CV8&a;?K^{y|FVF>c^jh8!M%`PzNaTk0HW!ehXYYjgm z>{425)UWVWCiBaKwd1x!o3-a}8*l+fc<sRjbKnmVB@4A<{KE#c`V~oWVjuUA!si>` zI0lE?m8hq=p0Hgap12jF{xVqKwm|#J<@3y8gLNST%o;j@f6G=@1DC5A>G>-@a_M<t zYxkILZnAZ5WN#V;RVech;F!!QzBT~PikeEh{(G={R%new!|X+Q;2^Ebf|^g$T_>J_ zEZ7&_1cn=FkAMvBgV(F&Vm69rpRlaJ9mj*-c24H4BL>0ni(voBnT@$<eT5rKuR7n? zgr8|5rZ(ju?j_%xwfEcMUpV}rYVU{}s@a!|4I7F$=0#C6I__8h>D>ayFcXn~4J=>I zr_N6tvKP~%)h{dEUH12A(*|qa1+R}gAGy)SyodnH*)35kaB{xbda_EAs`*svG`FE( z?{~Z1jJNylKsiX^`dH2ZMM_;r|HJUjL$F`BE2_Om(0J>#*Y|UOqKvbAFHDcS4}&D? zpO|#2CX)vZXlb?!-S(@Z4I4zI`YDh0UuGfiA5Vgf^(N12WXu+W<t&p85`9pAyPwt= znwLB?cTWFRlv%C3qb+|Eu+F+6bOpJhhY8^p)ysritEU8xQ~pU!TognpP7>RTeli&6 zM9<h6l)GVmW*x&&-W}N5UqF->a-DKm(Xj1%DRRlyF2W#p(K7O?65ZN=N5#G74E=YF zJnQ|1dMNK9*oenM;8>up={%<1!&Ki3ONF?^QVeEAH2Ti$-o26alTe?<%++?iRMlX_ zW1|`Cr)vD!A{u<+p7r`7Vy$07u8^WlJ9`l8s4Xw(F(=`p4{;;fot9;Iq<JlcZxCkh z#(c}PsXeaKXM6j{aXq@3V*8f|is$vjBii$}R<REMb+qs2!<~;?ks^s%al*b}c&d`u z+2HNvdI`M{rKkBQooyCHP5$!5P``?%xSRD)t6qwflh@ZKuNg$zo>f5Smw@GUyFI3T zY2!Z)Mk3b3zBvqQe(1uP`dbU+<_mqjYwiq_gF9g@f1H;!O6C@Q8khzaKsf@V%f_NR zCskHfNGtKeM{AmEedhrTd($s}ocxHwC{CX9jyPC^ns@>A&xK#Ov4dh_$NTf7t|EiI z+RlbQW-Fe6WgCT0KRpM9G^y@uvs3thY~2tltu}JELSxxjTy()uPX0#Meyq8gqFVLk zTVW^>USe5PfYC)*%J=LPK5L;<Gw<BPFbn7Oq88eNG%C6-XfLnZpYKcHpqqWqsVVE~ z-|o=D@lNS#N}XX50bZTW;Nc_AGJ`2&%dWlt`Y*0rHwd}*zX>6M6U3JHZ<tMWYKfJW zEul9(ip5FagA?4+E_aHrs6QrRr0hJh>SbR)gPYD?Qt2ZY$OkWlLrQ9OR^1<)x8`2` zNz}yn#wJ9Xj0YN+?tWi4l$$!6`rODBKkz=l^~uQ(%fh*4AvqKYf>dOUzxhV{Sutzn z8IswZeOgf3-{8|+S*D@NCmts=z5f?s=lRd(<A&|TN~{dj7D;TiYmbuHqjr^6)uu*` zs#SY$F{`DBy;l`g?bqJauA*vFRAZ~sJf7e42R!fZ&;9cH-1l{z=W)o4OGSKhkWby= zmfc8~uQ}eEWzfn?G98K}nUlaZT-kp6dVU`!K&({MGE+^^`1R(`lryV;c)vsaHq4#( z?i4Af{4EQ*Ypn}&i+kN73mOA#rPG`NB9hLmKZ!s7i}VobRb57PG?8m8>8(ipAw?NR z^v4IMM6r}VdRQTSHw{Ose1etGFwqTDl|Ah)gy6Yb$V|f{3_jyOwvsi{%zWm#<?~x- zzwcIba^!#XM6*lPwPJ2Pe%sl~o;C5{U&s#C7tJ%NQ(MocXI0Bp_sq(vp4@p8!bOv{ zyQk$@`h2SNQ|I$yMO?erx7)k%-@H#Fy?CH1HPm7_YfL0alzhhzXQLWR{_Q&QLA}*` z+u4R$lk?Qay`fM{41-*{eb@^=qkPHArVSl`!u%|omI3=nHpS+UE8qAJocr#=dj<1~ z{0ZFerR$f?v2R;_<vcX9<Zr&SsvrEE{9FEvn9J@wC-3<FLwcdS`}3$tJHLkI8aZN3 zFvG_bL`MiQWoVM|{K;H(C@@x$@_ufI)l~OWYTR=-9k-Ri(vQ7RHt7oV^N7D@zcW5~ zWL^JZd(?zzkHCvQ8WX7JY_YvOS?&2cVyWZ?e=tJbk!wGkC1A9y$Rdi6i#T2W^SDOA zWxSB!Q^B=8?%Xp&^W)Q_^WT*3y$oI-Gb-l?1?*MZA?O*#-pIdr&QbNQMT`DpG_5j3 z@AZ4TW~rCIjmJBHFX^32hcAFUxq+QPr-s=RRe{^yyV_fC02cz~dEwp)J0%mHlVt_E zQ$NcwmBx4O$+-P99_I`+*W+V!T4E_L2u>$<MPWR<*=}yd-qgm3Y%=b+#uq73d|@8o zqwTkZnuW@IRjNOldAscGb%pzFmD`k0u26%mfXtC$y+HXZqp`zbNt3}la`p$K8N2v$ zw!mG1ZO(wqjPiU>66Yw~i*D3GYlQjbHmCcQYbsK`ma-FikHmU=Fyq3GkG1|n(0j~) zh3Z%1^K^mO0(uPH`(~?Mxm$T@YJD-B=8Q9jx})8Tny9{@k}6D~<9ATMZG!f}8+$iZ zS{*}D-FR8wws>i@0Y`TxLT>;Q!5Wxv*&_G07Z0M7*@X{qM0DUmP~G{b+e<Fwf#oBj zJ?!za>aWKhC@Mdva>|vi9IMs${zrV8l^fb$x!o1seOL}xmYnh&jqu*BKsay2ZG8qH zX;o4lcek5i-_KB%r>S3ki+dQXJd5KDRKb+z2dWP1v4uE)E3@{Lr_wg1vC-zs2e3;v zaA#joPD}CvM`-fMm}V&Q%=bQMr1J!vWII&mC2JylxA0E+4XZ{BPjG>dm8HP!^r5#_ zk9M_mw9fpuhu>2iIi+ekV_ypUwVU=Z`E7l8kCbiIU#hC<#>b&M;N>|6wfswt@jO>x zUWZKv+HFouYlNU|r2a1Zy7No`LtWrTPIU2y8ixTP9sbD*(LjbTOt~RbKpu{XEAb#6 z*hdS#*H5uz0~4m#lVu3w9-`OjVDVSVTDI2{-~10<nQ9mEy!%;>N+_NjY_czsfUWkH zFgia=^R~Rovjw}sYp(<Q;eX~v<ab|}mtHdFyq&NU_}51FeCdXMGO^C~JL0SE)PtKP zR3zI77u}nUL#X#n8t~9?%6py(8w)E(Fc=SPdK*F2XYIVbSO;~x;gA<Is!GZ8eL{1% z?vM%f+r){98=G@i%~g+cT%f63VPnkMN-e5w5jxa78Fz2~nFDCZAViHn@5R+H^LPcQ zK4BiV=1jpp0cIscoufkSH`r^uZ!Hx?l$>U9-^oo=m*`Jx0L4?Wf6^UL_<UF;#5nkn z^$LVcH%xqJ-%b0OnK-DqVlJTjvxMWvO%P;$72;QtEI9spKpANRdSN+)R8=u$?&BWt z?NE(4S<&!?q|>X%N1~5+;s_L#ZL?SFfp2nDxmd+PSgk0#;B@)}62nyYQ5z=Sa8SQq z6W?KNF+zm_Enzp5H~yA~dA^20DQ-3PtVAU1MMS2QL|KJkQ>p9+H_EtY8buM|I8^+l zX5^GnYEC#Q+o53rp=m0$>T&UXnm1OaN%T2+VHK&|F83x84Cp{vE|x3%GzId=beaS% zz-N_iWw1;tpkg&dOCGAWFbfG(bCO^AlgK+XnX3DFU4WtzH0@HB0cbwTT3~sszl0fS zA?M*6>2Y2oj`u>S;C7Vn8Z_3uQ8yj)JNl0(JJBvOkf=#j`Vg?nzd&Zl%|2A9_1FkS zY)lS>6~UiyffaVr5&=o?^5wpPVW-XGeV%&Jf_ghf7;LK4-7m>2)_5(mi{`)+5)Pts zo}Nm#!ObRCElZs3eu8uPJELec<;NJgZm)90-J^VFK~Q`*N~`m(nvs4L=+4Yae$>B6 zR?`cJ?HDhE78wbyVd>t#m<gH}nPbR*&V{5LMf_Qpwh<cy;XV>EsQ+LgB&H%#ez|2~ ziAM@B3F{Sa7KivQY12ni#m+TJ^wdqMI*}I-locBB-Fg!ZD=3T|)^Nq88b;Zz77mom zV2QYBSY!<lS*~(cQt;XIm^m;I{QQVJURDTgv%31*#iHr0w~(3R^}HCIjU;cEmXV{d zLR0?Yk9B~SFGoe6hO_B<YH%kS@EbW0Q#Dl>2rFh<oLJvEYSHi<Z7Y<WI}q6HHxj&v z;CQg0FLM<R(i&8CdS1dOvjdM)HIL7DfEstitx!M1^l^>`gM7cEI+n=ZBV2B>A<J-l zNBlZxc4v>md^oi%Sy+YH-J{Pr#dz-tE*nnju<g%`X{YJyN`oCV-8nzav!l4G!q##u zc6#7XyWM3EC;CI#@M*8+`Pkngd+F9o=rTJZUwoX`zok^cuRMxoeFsxpe^&lIlen=V zeudKm2)=tOuWp>2s;wz{*2r~BH@oTQM1SH_jr2Tz5Zic9uiP9^Q63APA5V;yv_28! zuM}4!YQ+d$!Bf2LnX^##e)@F07+=#r!Ka4SfMMQ&4BmHRw#)a7)(>d|X~J3QR*jWb zaPgsGeCcF(2f(t>hwzE?XT*z}tvkvgQB_P3JiS|>o1T^D?0h@(ERyEiA)UH<F-M4& zO>uc`7R!`o%r5ee@;q0p-I9a&fH|p>JWmsERWwJznQFyfxGHH66G9aY$?F~1tqYMt zq*&304q~7>LfubJJgK{7>mFpk2ndQ6j}dnx{WT_0!Ue5ru_>7>tO*z-s-UU{zS-Eb zY)R&!%uh6VnwZK(dR&rER5XPKy#xdEOMa06W983)RKwPGw#?bZ60?ScDRniSm$x4% zP>2rYb@VQmNj~VyG0&><;DzBjIbZz)#y$jW7M8PXsgbCR@Li#mlbm8R+D|B=6G;*O z+Wh8}=Pz)c+`Py4f}<|-M;<$g{fwAbw|G~Ct>5JNya9j=1pVVvr`6y(&AAL9#l5=m z$DMBf94x2A$N$B8+BsyzrJJXBz2GjdzPTfv@Tf%-Y-w$^B5S%fyMZ#jnjaaW3;KZs zUTDAP?Zzt<n@ZPOC#HUXoFxgxE~vV%V*5^(K$N9Od>Dbg2=5`ztg>OhAoKf|#`yp- z6dO8X{JS<DmtB@QTKvw5RBb5!AV+kY4LE`1!$URUUCeR|O7in6XB4z6{|jnf2sYox zahKnNw}>U*dUXjUIfJ3i!6R0}s}{Dachz9h7=A4rg>D3PZckst6{*8pr52?}APZIb zWza(U1WEZh^Jy*X>Wk(GyYy=7H5-K^ThV8!d4na!&GF5$ymDmZ2<Ay7iJ&2P)!-6y z*KKS{MDLQuKF(J|;tEBctjBG7PjwAt9ukdO_$^*Xi!fKSXzN!A`bF2?6<v}nCuuie z9nK--8f;vILD%1xRQqa({V)|x6*clWB}$g0oYB1Eh)5HWU17+#T=u=J$TpooJ7~k! zruLs!#0f(juXJT-2^oYJXmfQF+qJ1^*g(m5bIv5NrgygcuE1$_INbWas62}!341+< zXBR2;If|_%QE@^?aPa?{Nze}UAr+D4L6J_qSQ(B-YiCPtD%aR3fNg164-Iu<W6ebD zvIld<1?*0KPyBOb?8k6;YDXb9^hfd1Gn$E(W!P~W_GVO<Cl+B{gV&iXylUjhAzLW= zLSDbUXm5MKjyCfl{Z8`pON=-rAOGgez<D<x{j$nyA9yKAC)*W<gGpa8zfW*lPywvr zdAFMk6LAu<O6d(%jN{_}7hW>I%5l~8*ij2aG#;+KiphS1I$kQ~JnKB|2#>Zs`l2Sz z9)W>ehFe?5#>%fTZy`U=;JHR4AQ4@xjJ6U6Ye?7F&XDe!uq0GW90y$^mt2wXRT!ch zgJibjiHlR#iGif7a;FKH)S#Gqhm@LZCq5sbfqQPO_Uu;`n7L=%bbAg$z0y?&-6Ayo z-6#%2Otkbqy}|)!k}x0$M5l|B`#{eQsb{!9A}oA({~w<D7AaY4b?m=-DwpstGnB6x z)HD9s4Bc=b+i<KB28euWv5R6vn=!|f1A6U<vt!jVK_VDtD#Fx^+`^CM10FU-BGyp6 zB{flGd;I2O%9Y_aZfLiwuCdQHl*IQLw3N1Smq5f$WSz$CuN!tIXb1Mf8e&bj!DzqR z4xW9^mTAKpl5Kt6-R<RT`rodJQP8t%0=XY@OV-|2(?ip@JKRL#-94I7PBILA|I@gB z;M>o(yn_?pHE1vsc)GcrqLyD6X+4RsXpEo%&rZ1MPFK&|JvQAnX3|dPy6_1Vf<#jh z<}w^%3*@-6iEaCZB74DZZNu68s{#=v|IdbD$vU%0Sf64??0l*;$zEz99Q#;6f$<#= zHUm+CS4fDk3qiGvk~cMRPa=0j`bPP!BCH?QM`_d!?S$X<NMQU{_qZ2>sIWe(>m}M_ zX)n99Kc~}*mLd=t2sQg@qM92=^RA7f^S~A0g)s>IJd!J4@ZU~2J65$9o5by<52*<k z1=|{$oji2TkjT)7$ltNI)z`iTuqry~Y$y1tMah1zoDZZU;e4@Z8_j8J!^zL(TF1p# z=fpA&G+(h3bVDQZ-|<M4GQ9&bPR$f(U{xuyOd0kVFq0YcC>RxfXo^N>ql{w>&*GMt zDSvv_xy2EL5&3}0c<3n@$SeNJO?V5BSZlKMEakF7Ur5+whEaJ^)Ulj-kL|dDA^n_n zIG+uEo6#gTtg6v6DIKA3sLVkRbHLr-P|fc(UzVjl=0SN=Kd@iJsO@J<*1o&MN`9`- z*P@$tapD?RMG`gAl`p$ki-tR`y}g->g*O0*LDZIgxy+`D=XVn?nvqmJwfAfMixS<; zK58zkXvw^7xnGi0<q_IDKJ_{zPY%cknI+EPdWjYw!`W*738Xkklz(P5-MDHbaBH*; z<JlH{5D{x_Uylg!aPd<e3bI)>6$Ib_ezK?hS13=0I*zqIj$I(rvNiibS!l&Ng&dyK zlhKC~9lBh|xX{RT5Y0Xxz5*WO^v<RrdO#e3_gFn1f{s4_vtbN-%1A@w7w4>(4>lal zw){2cvCZW%d5rSEQ#IG6^h^N#+t&ERFa^2E;aGe30X4raDdX;HU=`K~p^7N$Vs6J{ ztfGX8=8*{I#2o+ir@UMMH8Zg=VZa2QX#;bJ9lu)+q$ik0G4P;|wqYb)oP+p_i#wJi zU9cow5?ZX)-H0Id1Q_Z1-Q-rp7Rqv|kg-in{g6~uW*yct`uAUW*#;g4L4h*R%9hkj zwj%<|O^6$2)gUT#yr04y2<es`H)YVFM6)8|e~fGBD0ds!^2b=47$~9@QE=R?06AfJ zLW2&Mpg4Do*4-i(`s4NPB^3KsVeT0rcLfzRKO76V&BMyb0h1B<DI(JZxn-E-y-tQX zTcw+NW?H-^|A^$YF1B$OQ#eR+YtuQ_Fr1Sj!VWYP4EsvCol(sDGn0WQ)VDf{sJN5a z#D(_%%5V6ZTSAH+ONE$GVg84S_u}D?Y2f?}%wAaK^hCPkJ_7=u`sLy|-<;QmWg%w5 zf+ErG-fMhO22;Mw4I(|Pk~VP02#%A?5Y=L?VH?~NY#0z1vNwmiTJzxirnHsN9Jg+! zmZl^z!1-)I8u%4DKDs5nvAb)-q;kab{ij4>1cFt{;B4a!SCp)x86OM3{hC@6_xc@M z88Oc)OspK@q7oq_cJEeS#eOzVN*W@4HHe`&M@k2=LTB+p>=f_}F%Zt?S@_^<K;XD~ z@-4|RhK%f<fDaX&oEpuXGb>CTUpY>8Cl@w3-q?f>vj}W#QnmrBl)-|;4W8iO@Un^C zvzdMlp?KB}Oh#|B&n}+j=1ay@CY9+B@Ej#g$vRL5UC~HE9xmXeUOpVTuUFap`M_1U z?5t?uUW%s^`yBqo3UGkV9JYYEliHg%v&wuG#;j9O&`QzIFB;3~LUG#<>3zhWy_%Tm zfRB4as^nP?><Osw<(AGt0P3ZtwvE-X2Ju3ql?q;E^&E5=LbQv|ZjlS@0-^Rm8-gsh ziPX8(6SH{!C_M=g6i!t!&$f)u{bs|yf)d!=;?RG=vGr!HJ)4a&kV77=@P_dEX=U>h z+dFO2AooBy-)=FKjR}XsgW_<=)M=N@qKdTTyU<8hBNO3&zKp~x74aLRH)D5&fq>*5 zFvOw3>YL47$yN6FVqE&EdOd@i1%)+nmCousGI-(HbF_t%KX0IgX$V`JS)A!z2n zu6Ow6yFT08>SC0ey}(nyO5oU;aK#lK=074pMJMnN4@2UI7P{`=N=V;DeeQEaMEzl! z0siOuo6kYogfqOZ(l5w^YG{G{b3q{@P^a|pq3WI0bE+x11t7wb(P2>`(H!kgrjDR! zMgDBXbFfY;DK=0{J`V%?A*naD6tXrk)hn(2tM7HTvpBRKG1P`@d{?c(Y;q&)ZiX?N zzWO~LvlO93HM+BU48Qd~t{C+SK9*_*kKe5sKiLIW6Nx@=^|BJNvp`oHlA!S2yjnk# z=`yZ}T~070h#0Xry)>rjbGQ7l%jwJfduN<m`1D;2s7=frVV^~j!FELVrD(#qu!WQG z7PVxv;FLhi)Zcg)OCQy0$s(VH2<($lDAu>_si{Pw)j3QpSHGeV2M-_wK3{^ZQudCP z|8tX&HMGN96~t$Dic@m}pG-+!&j<tC4Bl`6I0!A`1bk8H{GeD7&Er$UOd6k~8S!1R zm-9s6+kxaO?7B4_q+~p1f*PCmU>77eE7wg<nS<Iqk~gaEZj&j_&v<%QU?-Sy;?`@` zXT9E!=dUwzbQg<pAAi#^NyO(<V0E&KgqYUji7An;$+y$rkBHtyv(F(}leqTP%6jDf z_RtngV~y-tL2)oQByY%!N&KenLkRengkpL1GD@13duzp=11Ssa3U)PYKs;n+L-_q^ zyTdi!96&RIl&<Ne(iyuoAW_67>BHX28f*GFA&tKL{df{b`?^Acw*mjg>;Lc<Xz$f@ z7$h?xZpbcs7jq$7#+b+Hy1sQjrAfX0mx2?6sEgvFL1*l^Jzm;E`l0~@Yr47Bu<mtV zesskSkg~8V)?4}2_?GR~3iCz;4RGzpe*h9{h-93hbyzett+Y=C4&NJ325O=<^cb%R zWEObZG?%)j7EPSH&gCgzmdzmPnRF$p#pSmLo}#Hr_}(E#0jubQD@w_ViTJ&_p^OL3 z%hKjQ#Y7b4C0zh+^OyK)(^NtAfYY<ds;|GCjVkR)qu3vw>=?P7PJ~wt)LVY?KODZB z)!JYw7y6HTc#jQG^}S2AukQG~4k047(fi)c&&YnV2-i0mc~XXu@%x=(R`=>>vhuUv z%kY#cv;2<$50}Qj5BB06r~Rl$dMXb%>0E$YlYdEn7TA5kCBFKn=^po=@2>-dyUg$0 zl+avKm45BX#~=Mu&n8^AAxHDm8zZ2>PjSXd-ZbO}AyDOztAeAiSsWwdrM$`~B<zol zQ>1|NpiCRfU+GgSw>~uYi=SLY5~uw&S5Ke{lQnRC*`o$}RQOh~?27z~vudh%e;6qw z?mc-JTKOcbDOLGLTkE*&iRJTTotR3kn_4qa$|~_HEL~rAo>00L2kb@DY65#BnNl}P zdA=wdT)i9MIt}Av4%Qf&hA7S4L<bd0g~`4t?yE!$$p6R_DAih=Db^4s&d`Io_mcVU z8xcB>#~l2@17omtT;zP1ALeXZc~lYJ>8Vv4IepWKSxuD>ve`zdj#<d7$s9{ES>$1p zH4S7J+hz(38U8&_;_T{Nr#CwNeraX+VIjIeSFE;p99u~-QT2);oj!&0L)7sCc75hu zzlhA_9V?@H1lNG{3Q~$VFTekK81}?8nO;}=Iw&%^GU(|sRCH&CG&SmI9;}=6<cM<3 zi0dfwjpDqsNou@BsjJm1$6usWs@ErxqHRV-{V57-Gk3_O2;Gr$uMYgVzQD$=Ox_fP z%^j0TZ8RL0_xODSYa>rCOvInFEw_#r++kg7Qovsy*C_hjVzMaStymrLj>zgCQ});q zNYT#I;Xac2*SWeN<5NkqA-^e>Xrv@%%g0iB(sA|#FxNpLJ=0eAODv>UdM#Fm+F{Ur zPPVZaq7>poGUd7(MW4huDSJ;ih@q+Y9#`U3#-j!LReMiG=12vU(nj;_h`g73^<3r? zjW{`_^%CAM%HPRWh|d6om08a&e>hFDV&FBmh~_K89(UY&sfmHm-G@xCyUb10HlLqF znSIH9tIon;Pxm!rGy6cXbwOD?mQrNir_02^``^T|+MQiRM#W<rCiMqDe`H=kC$oun zDxVnfUTg5~noCzItTt{@EBrE*&DO{0Bi8(5MQ050xEDG)M^rS5-nO(lqc#w4me`1g zPMil%BVd0%K$M)DaqquZxt|Sv(FNP2Ta4lncDJ((31?7;xA%~{4H|*=B>3)6vDgo3 z<f!J!)Q($;C~JDXVbd~EPeKppCs~l@ZV_5A9Kz8681Wyr5wJap;9TX`1T$5j-3GZ> zrd85vQ;J@N5KD@g{sLl|$M|@jTat?6w8segJks7*>y)1>K*PM{)uLHth;9`UrH;uw zfO9z_W1duj-9%G%%hmW_MXYE(Ays3!o+In_$aCH@(on<58{tt&7t--vV6&T&AIrv_ z7-Sw{1E<3f5Gz~rl_r4wFr|C<%e(wWGAs<8^A1q7?s5!uo#}zTsfd+7vDJ);Yq<M_ z8>M&^Uh7^H`T823Iv>Z^LS@0l908!Dt;NTycW}wL>}{&l*wD(c7h?yw=OP7rA>O!k z0~`xN_9_j64(0*`!w~_?kqjXx5zN_(iOLmgsnr*%Y-Abf99>3GThqoOI`{)A5?m6! zQ8V#P-AE!6(-f3J3ipb^YdNbTTziL^Ay2c>SSci2WlLy-BTq;TIcKAz9ik<cq(j3V zWJE2?o}O_x(iUkl4H;oa-_*-{y>oP?K8lsI$!q2RyZiuqQ~?xgF)9&cLZ@_svowDP zAQg7;-EaqIMj3F7;yh)hw~8HPQtavFsLYt<dwm_*RU3s3LXtNOt29?JVF+<bb{_1? zBS{mI9Q~tisx;^}@uplU6q_0t6~!y~%^@#=1fpw$)}+Q5=OK?pLrqCIpi0K>f5nr{ zY23;{*HhTtv}CK2$YK{Bw7ji&+WUM*#Sf3-Of0DMx4%!7|HGLU%!N0f&D!cx69cSJ z5EOgOQ4=Eih6sCRm`ZXqr~9SLieq;II;-bVJEJ?Uphb@$#`kc#boMFB-Z39)umdM> zGm1856m+U{nH)7}$eyt#KQ-Fm{etTWm={-2q&Q1aOyZMFpB?pA-@HFJ=%`ExK=})5 zy&>z?mw3_ycACqGl^lxZEyQHJtEdqy9Mn)cAyGD=>`iWy>X)u)605per~3(uW&5g| zUp&L5o>3g@UK(E%J-f%b0`?3jBuVii-2U)(-61HY=xt~lK2*X)<aHXw-6uiiAI~{R z<c1F|ht-F4eiTyN|6|ln`$5buV`%j)K$hiAL?wsGJ9XtwQZw>eS;1xtEh17(+S%m( z0q1o?KWiZds_WIOF1Rt2s*x^}s<w`1;gwu8b*ycyBt`hl_lfLGWUy1vHKmsdDK*@J z0Kd`3{>2Z_2t?$DZeSrYH-LF?V=_volG_cVDZ0~@%4zVX7Tryu+~gGxzrQJT($;%- zCQU>}^ABer&_{G)Rg}Bd&c<X_Q|Jr>b*K5#OkT_8(`w9P1i^4@6oM4%G_t46U9z6i zhGqQ=C#}0;y9X>3l=7s5iaPyLS~u6$rsK$rCoh6s^IO|rd3A>1`bCnS^~2I1Seu*d zDiV=Vyhp#F;LVPh5EunybD+(0Fr1}%p(RGse+9JZ1b+i)k(VWMyNd=Sazr_keSB<u ziuB##%dZ>|*@C5nUamVahfL^suf{&M-(gNR?-uF~m+I(9eD!lpQ{~(!C4pq0ZVO#k z*?*L}9-}4_o(<|8pG*ua=}BU5X;Hq&DvCGA;do9Jg%a{h3#3p-{t6r5A?>97%-zrA z5eAAKl<%N&U*`-5lPP@m8k^>}KT~ZS9gIHC*qz_Z1`<S_jDMtCLBXQ9y;y|^6v!QR z&^jJ9%U)>Y(>;M`XOIXHxzGW5b;R%*Yx~XyM4W1z6kEJ^sg!RP_o4mCde7;+CoVz@ zXE(aa!kKLHJvI{(?7H+kw8>h+dj=ZVrL=>iG48qbSCfdK3a15TL9TFU&8|DANa`Um z2r2pF1p=g@ljdKTQ97S;y|{R-xb&tcTR^rHu8ZBynAXvj=O_$>BLtSIW0NA-XI7x( z4`jbf+_O63D>@<DHDnD+lQcDfK1hG6Dh_LcKM!Tn-#LWuBGq6QwjpBFm=n81k_Q4_ zZXIaObSBp*g4-M*nj%J1*2^|z0(^=?jm+p>H@s-^mYpmVx>bZU-l6kG3SX-*C6OAq z!e~|^jB>3Z0Zxw$x3st3iO7(Iu}H{oH_)6G(x#O>&4{3#B|twRsbe(J&{8$Me&{?b zz>A5;-H7rU2ze16M$-(z*_haFLKkt&MkGYD@TiDoL#U@1rJ|kgiFLqlz{@a6MOcNv zKY(8hK46>P+`1VS+I>sbnl~;ya6~-O7;}5cP{OPU&3S}SF@qA}&}4OF5Rk>&$gR2@ z*@l9$*-O*)M}JIDFk<8h43}V%pthYyxXzl%0qI>T9%PhidiXOn&e07H$nG~h-6*6T z#zH>enKqI1z(UIBD(2UC+TBijAri>I1!_sgVFd?y6~=72ik8JfeyqR*GtfjNEm<k; z<1^?%4CD_5Y7-QvqXzxGr4iH>jF^Wk7dpNsIR9$MaOeu4j|64Itdfc;#;k)>hjdAR zEEKDmY5}l!PCj%to*r3z>TyJInLg%GOolQFh8+xyAwXP=Vbf+X2(Q7Rwez;D^mkc{ zjGkbk3Yr!xY{PQP?2m_}5z0Fa_3Y=X2Y+Or{ed#2qbjG6i(f4VTP#jGX@X9DKJ}u& zbbtjzc}WcF2N$*A6i-eu#0h?{szUTJh8k#%acr{x+ldZ3Oo<HFfT&a7OGAHGf#%|9 zh=#QDFla@r)KfL+z^Q++oZ{gj#I}e+deC5BMfbW$`ACJ<v=DLwbsQAuFz|{hKXs7@ zdlTSV(#KFYYyi15rDxd7blIDPJ9NXEznv^;fnR!m0=hau83KbC$fz8g=w+%<ZhG3% zHbUH3XzYs9{5Oc<LcB?)5n(P}bVMV_V7mT3iLwKQCzTP@y8-^i6e5h58B>EC8ktXs znI4ideTsx!i^=agA}~d2n`>b!Fvw{q!+NJ&3^-NT7)pF~>-z*_V<ANJ5<@OuL@h4T zfTKOZr3+FOG-{wu4XKk*kW#J^r;YsY$KEsX?4}dU@h5LSso#r2VGFY&fntVkX!hVq z&eE@*zFrK+$otU^+Bz<5BtsBH%<H{#gfPlyzz~vVbn~i$RIkF@E}StY=Ep|Jm==h) z7R|y0<oUdig&nham29Ok1J9v##;MPQq=4}mjp{Ir7$)W|$isC6ttN+>8bQXbX}*gY zDnt;~Lh=5ukPnGSnr?MSd5+g`g_EPtt+KY;eroIohR|9d))JgAY7Sjiflk^zc8u{E znT`G_0Hq$fYs3RJozScnXRg_S{OF{eHey{SE4UV?{|jU+Kj9&nG#}-*)6s<9<&MEh zR#>&a?dg{dqjIPGMk(iH!0IPMY@l{Egpy!YS5?4oajqO#o>M}lF^Sl_tXmVqFu)yJ z@;KT)m{<-V{(MI)0&|PU8@*EqzK1n}i<dreygTscS-|!~a}!~yW1$<!=B^k-4&)uH z#dHG-6&<_*f<m4FGE)vQj|FSvcIC8QMqH{x<yB~jDsOA)Ua(B-?i-PR2Jmt_6PwY% za77H%e@DuN-W9h>SE>PdnWGm0quI)AI(4}{G*}%2w6D~lJP8W|O2EkFTN)%R7FM9u zJ1@Km&<~Ex%_j{60r=I#okzL|=^^`BL)uLh4IMh>Zb9g?Ovq0|N<SEN%Tr9Bl-E-R zBacbi&<IblzdRF%(C=`oX{|e<5k??W*2y8-buO!k&A06t?~KAD=v5{E-H=NSsbAw2 zr3IDOv~EC|u=|bG`OjsfGWA!*LQYK?js{!jR$6%{p#o(-&s^)D2;O?kX5k~IAMuxq z=HtiNkND7cGViJU4s_a#rW&Fy)jea4<tZKubVCmTTqcKUIt&TfY|zRGBD#eV@^z-g zd>v}P!TrLf<I}9wHyv8|ohRkM`*}0>^%GQXcR|YcK26N>{Jl?o1Cdtw2<u9}f87nE zFRmp{I3`t_;dl&^--o0K6bwyK7Lm3ARlr9#1LUylmw&xcBYubh;tHdEXU&*=3*D9A z=3h*!2Z9<f(dJ9528N6Na}*4C0Ef~PaC<|BV2~?s%I_;-h(TGX+VjHO0fCd8n*fO3 z9IfqkpY_8#1W!4)bgOS#j7Qz<6FrnyO^-+ASYELA3R2&)A)$QMP;)TBy7!0gQDOvE zt~)jJ$s;yS@pjICLoZx__KfM&iDHm03Ht65hJF7*&Dh&hPPBvxBGRV;{;v6>)zJ-x zwRigv;w+>3c1D_uj)xQ;5Jf4ny%WdmW$AgyF!4Tvk|szt&HXEm2A7k4!(=M7ja2Tg zw#U#Ly<mAJCb@V^2$(rmNh30b;(ho~9w_E$QaQ$+X3)M$y;u3ll%@DS-^2Z+taAp) z!UXbGqux6)p$)yPTjIe`6S_7G^i3hjz1V{Ds3`I@6zi(q91{Ey8N=A<zOKle*8;mQ z3ArZ}@OKod*V4JIQuaw;0+hfld@1sCu9ww)fB-8VHGH>j_%up~iP{c)XT=l3WG^sg zyh9Jw?$JC2+*veKqNmEuSi_AOl4q~>{xXM7AVHIbkcZES#t9TGlV&f1oco;byjS_; zl~nyXU>Xdac#6pEUXg^Ew}SEaQ%J?l#ez9G$KEi4dp3cP?}d<0NLqplH*7Q4Hds^J z?ABjHO363R0<N*}JK~;&JS&I7b$5oYVc?fAfq1of%wsNK7)a$QWw^EOEhEJEdd6J` z-Hqwe-{CT=oj!i2Py~%91xrZhO;w#VdX#3y==%U?ATt3*+rlh5&B|a5b|VzRiDFAh zN(@9gvHmceOW#sdxO!2bM`0o42hum)X>dX?eI3?sum%0j@!9$aGDaXfYG64a_-u^X zsvEIFJ|HM$zUN+xsfT+Tz*wAY=nj;Imc$_PD@5gA4GC7+A74_t!OLbY1REY+K+_8; zZ&AKD`{gpSx!7wAoqf})L+$Bzryy|xoU8((g5bDp5OOhc`!J@>&c*DHuq{vOd$t1n z_f|O-1U`_6H5zINTQvJ5CxK5NH5*G%X!|yeMOUsu*H<8+y2#VV>n%rjSeI^QCyh|t zu)R%^mWy^1rsnXtrS*t)0|_PQGS!}Ka`1v)sYCVnV(9;EaGN@79X^nxv$lQ?pTkiL zih*d}(;c|8d5*$=OW&%qsE5(fwGwE_uvH!ha=%(2zbWEFfz@B{b8bBc=g?|1p+-CC z&=ie3Nz1jQ`m`Pmq&y9f))TKd8eaN$M9_Prc-41-wr<r`7~bHVFOaQ3szjD}GwlL5 z3+vF8<8%~%yu|;S*OC}a!iw3aIxNd0@d@bPVvlAf9o`8A*!aSoX!aYanh*gVgo$*5 z-M(^&Xa-z+)FxTGhoyJuEy1X5?(;9sZuXN-TA&K8^kc<>XSXkpX@TRkRj#<Bm$#!! zeX{$6nk<)E@jeSM**UQW!PSk!f6I@xmg<@;lI*yql@8{PgiZ<1uJP^#o1etq%+iTI zAL4>ik$Zp?m#suzY}OUNY7e|2cx7;)wLeDk)}!mYSZ3nIVRwptBe@!E@?~W4;1}!e zZ&3-x(A}NZD8=&3B06FrT)LbXBVK<j``>UBh7j;cT5}b8ZAh!}n39Y<L9}>rh3?Se z2{RFp0F0*m7DKz<Dc13jv;LKVVUEGt3N4TTE_!QrSvP#^%h{7MGfnZ=oyRD@b>$Y> z?q`GI_fFNFXAULt1}6YoS8K*+%yYI68N^v-M|;;o-=8ghK0RIVs;s}Psuz~@s&3vy zb5{_e4gUI{6ke}Dw>>FyJE2rlw4B25eR0Tt|6N9^Jw(>)<VfH(>P|%;Us{ARj1I!; z79Ww0(hgNqbgR&>P0$jKCs(a8lH$~v6W|Xj^pqB<$<u#qR8i7vAVE(WKCa03q0Jxm zT1ujcf9n043ZWwa*v=Bsrf2TU6F?N@EfM?qiB;7&IFEjb`Q%z(;(YV0u9L_QzNbHT zX6@SaZIm*Bva{VheUz-0sV++2ObjeP1|Eq$wEQ}~tzU?VraJxhyrS24dH0WwtroLR z0JqWH;#vHcWFFmTlIc87bN_h)=WX^a>X!ZsolDuIDnH;<3e?;jFMTw_|2WBugb+_3 zTmR#8D6xOC9Lk~WIlpn8SOpWd8cgFcsJk$Dto&l(WOI+a>bKRW+<)Yr*s{^rcZ^G- zDCx==WgKnnzZS`)a(v9pq)&l#K05bUX<towD^qXvRtz{bYA5Xs<CXIU|EgjVVeim* zUi0Vq-!Jxt&0M6NFWHGpR{<yBcsO-u67!vN!jA#J0tjB-^HihWgwJ66{P$Gus0@&L ze@r42vJj(mzO3pjc}8OX`%}mzMmK-)A7)4x_*;UYnlNL;2Y~YY9Vqnjtakbo(n7iN z+9~H-86xl>%87k%1z(;==l5`+hGXc@wlq;i@<=N|>j+fG^YdwwcALgjzwp}*uA#<B zFj=E!!mxr4AGffMVeT`Hh{TdMSi1z^8b;^D=CzD6%9FXqjOecTPaESKyPM<k{Zk@9 zcnp;0S)P{$R##9udZv;+aD^onuf)`SCqK<O$yL0+jB32ZJ8XFD%MTLEIQA&PC=g;# zP>lh#2fK7c5#31$pnSh&Z2~sHTOFL&u)jx}r^2b{eE*&CuWf1Us(@gZ<tkS9zW->u za2Ht@kgw}wbEOoE6WwJUBBRrdAM?mWY3|$a1nx;w*!8*r+ItW_`Tb*DCaBJT&Eh^j z-|W}<55U^%6YjA860;G+^cVd3k=~oeDEMtNzPSc=l5(pUI=A_nB=^lP@<h6h+KIS% zpftPt`}?mg@)+e=@<aIS%s5P$NTwevt{=_FUo+08zQv76RX=gpJQg*3bp3(4Hk;Ji z+#;%}PXn!`%F(Rms~0@L5jA==Z)r@PbbAIcy2}R$SrYIai<)rwTj;%Ewu6*nS<`gE zPD46ti62MP`BeONMo-PWNSK{C0=_~zm!mGfz2sP?gLZmF3;OIdMo!fPvX4w_u%Y~V z@-9%st9Lb4-t*zQe9u0k%Jbfk-kc!=9kV`tiSvd$^1jPNRi3X$FwgxK+qPPkYeC$K z!7uCqx7jwkSgKzr65k^5&lu2}XQ6aaAMsuZv<fI1Qt)HE$7h@JGYE^pwfAeA=-L0g zs(v{Nxkhl-8zTSoa4f2rrmPsH8h+67p&Baq-Ywo9Hz<IjQ{$|f;>HXluOsbmFUAUG z$c*vyGC$BU-4gSYqN}B4ix)`WrXxv-Dv37-;vR$<`U^$XG`N6Ro@gVO0G@3yE-|%1 z;xeOgCWOR6HrN|9-`lOmmq3ovw@*@BO5+8iqd1K8%$FFAp-=D$kx=m`fVTOR7&Y>6 z>uL~mY^N`}BNFjhqKM@sf7&753+;CW>$MzIh+^K<DXzRv@4L#Dk=&<!1KG<qD=qa% z^0=Rr1m0>W#U0!ij3-}s)Yk2#+5$|EdH-gxi=hqoT<zxAlnd?<Y@#(<t3_qfgf(QY z!kh_PKDj<|Mm}pP+l{=B=_@IO*Co@G#z;~AU@S*Ip1$eBDknn+n5i5L_fkPqx{Hx1 zbz?>>G{`_fc7qBhZ7^ptB-oRX5qdePYAg~(H(&^rt(lCAYokMbSh2%y5n*8(GsUb_ zloU!Dl4-c`;~>h_a{d4o_7p`h6U?h0!`GBl{nj``^II&|f7PfxYL`)R;U2(w6*tyP z5*#_bt(pq1SK%h3%R(<gNW><h^{{xbYn%k!b~>g5D6!^g17p7E1GHh#cZCI1V+<1& z<Rt-PhJx4yLQ*mXNCa-tjlC=<iB=&LP=-HI-GGJpQ*=U~Mr(;}?7-+`DNqyOZyc)G zFtc_^rE7*)swJzrfrY9rpH<_et@+LSlzQW$)CZ+U8*xJDUbyl8qh)0J*Qgx362)Jd zZ%9f~qj20Wgl1huZ}I9zjTWZR{)|yKVhclAL(q_U4HiygYGQOv3kr9U>juY;hzs^I zwVyu0+IK<|=?04^jX;VEhYKn$;wVUPul{?Tk-G747!cX@X6M8AwhC(|U=FDge5xMB zW8Xpbx+j5=B$aL6qu`8mPX=WSb<eS9<Oatm_m5-`XU`dcJ`G@Ryq6Q`9MleAKy$AP zYQcKQ`d`t292&#aE5gl@q5_iQC|Y4>ByDGL0}s<hK%<t9TzDB9)D+nPE^8Zo(8F5Q zB-S)KBpKa-|F6fl(&NbuBkP&E+yOdb0CvwFru!yZ98pcN0PqJ?n);N8Uz&1E6iv); z&oo{-iNxiG1nVcu>Xv_FVagrnt<$s`*djO_6+<kB3(CeMuI<VRGPU+?VbtZ>{d7#3 zBN2r(x1Hm`>)x{C?58=ixJcvF$Y>gmE!k#!QcvqBZZ4tuon`7sFx-My5-_a=x~<!~ z9Y-kUbT@Q2xx<te+WT~9%)CzT$s)un$r1QvWgva5f=4isi{AJ|o!kZZ9lt*||9i(o ziDoj~r}JJF4Ui3@<DVAVaG_dslK0Tt%Q33CuD_tn=8~Q633jQI)$cwKwe~I5GVCVg zi)&SlGKY$(+TFuHB$aJWb^+R`R?YHjXu?U>j0~9LXz;OBq@Fg5jq#}WDT8vNSO-J8 z#%W4z&3q2;L|1!%AzxDe0p=+n3*i7xY`D%<n<2!s)%->UAJHm?bioq&qAE{Jw9>dD zN!N}#WSB9&X7t$HdzWnuqCs)5(qcORqqd)*@f3-<4ZNO_A5nI}8vXof)KNZbNEv{F zYUlE7Iw*FHhVquQ{%h464QBv@_JHP3gwL7H9C}5|VS%TI*4w9N$lE=RzOu_aer6uc zCd2sCcP(+7#~$3l)`_j^On$1_%cgU69(%yLBoav~9G0XZa`U(QQ@WScb^ZX&PxnJd z)t(Xx4%=gk=>Nsr%i8fWj57uP^1oQgM06uZRlkj>buzDyu|+PtzE67K)LwE?3*?Q$ ze)PuOMDWZ(!=GEY<Me#l=RJvS*fnGR2flfH*D%Is5u)%HYRkSyc3L_YlgWUejKZK7 z70Vn&irtZM6&DmP%<}ftV0ZxdNn|5nKE@%9+LxI&VUPZqr=;;~hS1Km)k!*cN>Ix# zt(XAlF$<JAmn(WA-qZQr=+D%6Wb6$S@1FpQo|-xU%wWt~@ZqKMpeM65yjCjylNS&) zJaqRbrZ5Cva9f-jOaclp>|lP=)DTeE0Z*l1VEkf1!>*$gJ;9h{p0P580b0JZ8OF+@ z;r$aOEHC3EOTc^Saik?Rj-BDEgNnmi^wfGqN<TBiy;;TKh369Tx|8V&Z&<}>sDygs zy3%-D;icdXdOenOSK`xjj>}q(RX7c>#AXF?Y*(^qoqZ*c$tKwF#3D{csP~>u9sN&` ze?!Iq0b&vrw=qE*OH!h+j}-Od7nV~i<nMc+_TEI5Ludb09wAlVO-<OPw<xR~AR8OZ z%)lcA3ScRYf347U12cYFX|=&a<iG7O+7G}fyL4*A9rata$ARN1ye_cbYEo`ObQ!q2 z!@x{Z6f79U5#Y(}JD7A^;ME@tN7J_|xOO+!TC%j|0QY6z3(FowaR!y%p8l6$r9T-` zc-2TDVXysaKRFomLvnrvK0hq+KB|92uA-?*D?@RpxhEqtN-EQBXfP+C@B{sFC!>{6 zR-%t~-l+ClrTwC}`$PT5v>5~leu(z9=@3*rA@@YPR8k9IGn}M1T$(iOy{=tZqf_0X zQzO|IF{)FyuTy_DTs;#X1^}S`kdfO1fB+#NfDsT%Li+zPsxniz3=TFH52PYh6WFzz zN`^A{O{y%1rnqUC#UBpmX}>EQ%awh;yEOF9HYtZP9DBu5+#e56cfHylYOb6vH!Rk9 zt24W*8zXlUAG;{3`dV+@lfa=XU7Riah$IJ2Qqtd9@aRc*^j~9<iE7~fTy3u3(<eD% z#|LA#Whs)FLdNn0M%o(J2XI`G%@O1yDku_zHevr6$L(<?k~|Bc56wTPD@-0-OAx4C z!&NByV}w6S|5^k(Znu15Yd!eUk~PX(+unA#K9~`!mS}d8vu%}M5OCMA-Dh{M+U`fl zr;onBzx5~+nV7#P*@_NNS3mh;6@1)~^?vZ{TKnhgzZb`QKfe6;-;GI)f`289?C9L; zC79R$O;FYgqkd<Y2LI~+GpaH>R;<Rb`|hm9B4ha1;vD#$*Ww-I;N+NxK5%llSU>-I zlH}a~jH(suDT-%1>!~Uf0vk9rI(VNeKW`<ssXo~Rd2r3!)ktz?)2EwR=8pd}s{Y)3 zWgR2nn9Y>=bnCTqS>@InCr8h&oExL6Qw~B5uMRj8uH4So3owd-B7!=*Kv9e?JNP)> zs-2=Fk>RdloQB}fl1wv~pQVvh!{HQpzPmrm3u6R#%Oh=Fb}K8&5(M$7a{)0-b%#WO zy_!28w)$8k$%eZqI?i_Y>N_cJ?>F=^y6!g)B62YlQQiriTI38WFfiP*VgLP*WA(3= zUfWL0TVSE)UfV`~)Ld<tOVw`se#_p$$1LgUu6I)jC;KY&=6@^N31@qvr7PVD_8-WY zlG1`&k5+&nmi^&hJuponuf`GS+ZX_)m}jT<A4jpn0VHv^w%TgrDPf3T)90Wd+!l5; zA~vw^+Q-;op+Z73`xj0ER?Ag+&*?98JTYX8!@RZfZ|v(7kok3jY29Kysrzc?emZOJ zRC_x2Kcnj7<Ao}YXod(a%p^tOvAUwB0tPS_A$)$*!~GOK3Cz7ZSvFWC3YONXfkgaU zn4PVGd>L2bFw*m?@3M<ZKb8)QBOizyP3m<lpnv4a1Rwn1Y;*gwQ}WWaiw~=U>+B~# zWCwitpHa1edd3$>?_(+TGcq+#uI4SMz<VZ~YV7Z!nsVR;cL2MZ$M|Gjvf%=$(#yYJ zn8=cYe&@vAzB(u48f_|Ed<A`X6dEK!iB2kfduO9{8zIxO)wBPRaV?_$zZ!4>UTpJ} z+PYU3Ndol`GdXMjdU{l<1YCeVuczvSbE6U^GMz)2)zS*4c-q?o2$4t{o3EcYNhzH> zk*OnESG+1b@ODD<$?@YU39TOPQv(;s^Fl~QX$N-RhAVg{a)B5#51;>2^U!Q@wU=<F zpg2p22Om9Z_pay_q^h<-6k<@GMhSNr3Z2w^^3*KP<+;{U!p*L7ext#C(k&n*cD-Wu z&{;8=rz^H!s+aeMnH8dNX-U5m8Q(X3ZIHWLb6*e4#Jn^(xDj*^$`OU<=F=W>4OSt` z>t?~4KS*2naL<peqJ;lb|7{jQVc}#w2bW$@1+A=GW<yfx(gx2bfS3xhwV6l6uX4m{ z>*!Tm5+lixgQNxPbHBPPMtaAJVaKu<fApYfahdj*%fsV0^P`S<=}rMk|Kr>hnsV6z zZG8`lmE3RBW%6Gu_0?i@J;sx^&5OjM0p|EnlcuTMvv?vf<nmns;JRFeRA(ZbwYd<i zRDq=*o`@uwA$3crP@A6lLOtV#XLhg9xHD`NWmc*07g4ULDVVMJHXJOy60Y-Lcq+U7 zq*N@qQqM_e`pv>gne5ojL&MYgmy%SE!JXk+Ix|&a;d1&>IA{LmnLf3O%6l(%or|bu z%LQkvO!}%!-wn^!8J|{Jf8RCxZ()|^{(G#`siA49&RmP_Y^`<l?FU1w_}dJpbx#7) zRVGMcK1ZOaZm&IZ5W0gK7VB*Qs_a`cjm-Dcku|3BxY^T^eCyVkYs&moqaw)mt#9r0 zow3Cv6aO7^@whI<ihH##4@MT|+I`=D38-~*(p_92E}XTrjnzK$8(CaP0X28N)tPE5 zB;zT>Py+euykCthZONa1m`JYkDcAkJ`|!Mdeyq;7b>#cLH;~qB@QLTZNBZWHE*d@+ zAb5^C0^WT7=^$A&X#4h$%c)nNxduIgPji3#T{!>mAFWszNN9zG{-TpYUo3*DW`*L8 z`G0%080sk;#d!L8x5T%IApWEX)|yxUAt8-%ntHa^F-Wp&hx(TWmTQb3FZ#q%8k3y# z)>#)X`njw`X}qlw)OHsGg20*pea{H!x_>{PV_5pDQG1^4^IpT0rp$7^O~FThhRw&D zvRg+tMPB|Hv36`s3CN>B=34M(u{6alzO-j4ZX*tPIs&44^tR<yzYQ8~dE{$aZ{Pj< z=ZmSYDA)x@O7-_*G!CNuX7bU-DapeTuDItJi+Vrd#peBPArhJ7kALdFd^3eI_n@(| z-YMk0oZ+&NOiR9cO81||l<qUBl&=avO(*$Yq?SsB!Kl^a$gn=Yf2Xw$_x5d%WxDO9 z-zyo7?Wa_<PxeTkRoe(V*$rIu1Y4_dTGqtgMRtQz5aBI<0S9MAvSjKzJ@vI?&n${% zyGx{10c!-x-%@{<83S4p7RR==Og=7LiHIk#blr`3^>_ZiacM3_D>4`}eueDoF<9*| zA?#7dG~upC#&G!WlqdFs6Cpm?*Z15l6BS3ch|&@KE@I*Fdnn)=h!j{qEbgve*jAkL zpBB|H5+eruB$P8+<Rs{*i0#vGQHl&)ar`9S2TzUs;rFq;*4{|0XebbH(fG&x0G`<m zUS#a+LMc8kh_xn>5<SW|?Tq7N!Yl^D{(cnIKWBBaT)y|^uWEjsW94z~5Yk#rpl*Dl z-9w2?gI|5=G%W5_r2i*ALJMMT8T2}}b5UdPcaJ;bJcRAvu}H{y;d<@)6elCKk<;mq z*Q0S7KH_uSDJ?ZU*Do|GmJU<Dh;pfQQ9c$cnnPM&frmNH(H)Nut3aQQctXy3U;q2_ z`kvDF+|f8Tur)#7>~k@F!JqiZM{CHINMegoQoxx6652kmE)ZcvW1#Z#4<WRv&{ZXH zXYof<<*QGPuk!##H9!E>%1fHUP~g`WMTH<PLo!efpzGCh)R}K^Cm@cGYB4+PwHcX4 zA*kJutb;KWAsZ@cjTnDmaPAa%sS(!KADTo61;ho9_&pUYr!F=OIOy{i<_k?Kqz-Oy zjBowF(!x@Le*lt-Yr>h6Ih5c?;b0bV<`*&DY99_F2Z%*edD8rM9<JVCyU+9T2h)?w ztmxDMM}Ge(rdM7LF%-^7E4@J<eSa^(!3fixmtvq$iEZa>zEA;aw;?{~CYcy}b2n{g ziYK0YuI7R6&R%*kfZJdI$;}`n`qTU$w(k9($@u>t_-12s+U8WwHs>T!j&nBW;~YYg zoDz~yj+L-6<a|m(&gMKq5*l+#%DE&t6Qbr+NcP?PbGY5UKYad%YuD?x>-Bs*A9vUx z;puNema#{P(c^Oa__+9p^%gJAQ2&2Si6y*=WvYoq#2aQI3?<0e6kdXZ@%?h%Cl%69 znpG2aZ#@Zf^m*C#q-FX^$KjJM-XwCE|I<MauK@47X}=NWsI>vYwZo)Q-sJJNSfVO0 ze-vCd7!TlO-(*S-QchmrO<7V+SzJ$=I80v2P1$Tq*=kDxIf9g2z4Nk@4(<6y#z1<m z+|;&IDv|H_F!hu-?VoBIz$A_84OWUulUZQ4kp{qg7^bLfy+!QPMG)FxD)?L)<Lh+( zFX>DP=_l){NVN>Qs4Dy}oo<#&zs`{Qk|DE^A;6d6ryw+FoH`tGW{sxnhJKx?@g-C1 zC{yPPSnms1HjNbs06a!AC#|!`AQ+wH@9OYn+o)yRUCjojF<I!iT}{Y#x|;2Bl<mrw z<Ib18wy3Y{6LW)Pe7+<nYU+PQ)hb43GNUW?`uQl<zyPKLDjN#`5Qt=zBr_NVfZdTI za-vWFTU5PwB)+$UJmaYgvti0U5>MO6vetQ;^1q^Lz}3uKSMvlHk+LM_eJYzQlGP6o zwGqH%l*U9*6R{0=-geGLW#_)t0HV_;k9?$m=05nv0=tnbgP#stavSrD0I*ZQa~x0p zxLN`GBEOM5)PuxeL}nNzF#uc{Mi;>LG*@4HSH{Wk!u6{N`vq{UPcB_o{b0iO4FNHt z%J}9M9;y}m@L_aVV2ovEKSeTcZ7@2fDGq17fI8*9^(k~B7dH7Y#Humjy)UgkD>~zw z_v1^UJGQW)(HIhK%CuO_s9*;|m7I+zSy6JbmuFh$1DNAV<bCtZ&i;R*>Wm+a3P+5U zs?$YPbeX<W8J$x#&MPyei>fnamd9mS{&E|1xt&wFeMGrqUb$0yx${i9%W=6Ye}y}` z!qch3E26?Xufn&z!f&R+|F|N6zcL72dEcorB%(4buQH;&^5INn<Z)#bKQRVP#5)n= zB8c&M#Kd-D5^aW<a!gF)ugXAIWjR&lL{#PGRpqr;<<q+qj;o6Jt4q+;Wlq%<5!J-J z>gx9D+L`M5<7yIrO%uAN*{P;AqNXjcroFwUW2UC-xQ5JM+k>v{b*k-;s2$9!9cr%~ zo~iwKTsz8NH;%5GbgKIlQ8%4eH`87>J5x7zT(`hqzl5$|ajIX7s9(>k-)yhnnyLTk zM0`lCH?3CPbt)51LkwPNQ1fN+c4aWtX$aA20HGKg5P*uJ2E_={9~nf5D+Im36z)pr zqDd;7ER{%vjVpu>!9GBO;Q{~)oksahmU=QvbrH*+B;xTX2}p&66@heg7(s4LwMaw_ zjl?3VULf_LN%=gB_X5zH)Wk0U2rq)z6@eJ6S(F3-D$idY`mkWHk$_~-jxWSthYlt~ z{K+8D7>m@`X3GbKm4FuRTg<ZZi1TCyp9if#B!f*6Ye^bQO#sVTfmZTW79g1g``~3c zmZf!61JcL<9EC(<!DM-sIxI`@?N=4yO%*yUDrT=5kS%TU%)n7*&=_-H6jU0CtCN3~ zbS-`t2?wKCYSLJ$04-ScR;KsOVFCbcN47pPbG8F(?I_EO2c%-N)DN!hDmAal5G;_t zEcHdKeN<dhlqyypbeRMy9A#;he_cg-^GCV8v<C5m1k>Dvp8{YX7MM$DNS5jVmd5kA zQUqHB5^U%SmKg1NR0Jt6Vr{^(B-|#on{^I*b(TFq{3wE**1%Sx*r%zuRs>sn8U*VK z(H-rQhyp)yh43HZw5M6huy5<0yw$FF%TWCG_<3h3E8Sa#&64RzVh=qBM4ysp4v=+S z!Prqq1A=Ace0M39QabwT(UX_=pLEBEbOOn+EdX4P4Ze%)nRo5^ISOk+vNAM+=vJj3 z5*&|YDWtLtoX2&OnYjhK%H-efv9@aXc^zMats>w%$lfg-*en%(iiOiP($_j{X$bHY zDwAITgzl40B4AAdY|0vMADw3@C$TgHG~Ivy(rwnSl=i&eX!bu+=bjFGD;=i^fVg8J zT??$IbZ`}k*j`{SLv)qPzgF#Fsjg{PVeL<l?JqTht&r)QBK(&;oJxg;QJLV+nOg#S zrDkD!qwL=RJq3b*gy)p1j-kZiZXa2g|14}P02-^qsEUBbVOg~w_IyRc=CQr2SUANQ z&M?L@xD}|y*1IeZo4p2aqeA`VL2-1PlMLUMfB%j8c9R6tlZ8t-!)IAxiydvt`EL!( z>1gFh4-$GA3vt7;O3l(AX74;126XKdcJ2i!wEsYiRx<T!oxth$KYxeWdPxu)1UN1Y zwngs$Cr^i30kpJEd7%k~&hEdonz71?5uiNm*crY(%I1#%tEVw{kw*TJ*s0X<O9hki zcP0+kKFkO79>~LAM?tP2!1PbQeY)nm05h(m*OX3}7kKYuVc5ElI0V>@3Y{#1(d6Ou zM325RoJOWMXHW1JjJZ8>yIcoL)_|u`nSALuD;4&SPRowM<k-uA3sXAzoyp0cLkm8i z_3A&MvR~bXy>^9O0YF-G;HLpS%SCixb?k?H`#qrvFTeg-)=ysfof$&TbOqQ-6TYv* z-d4n9g`Ad<g)IT#@PBZ@3ve%U_)bx$i3NN=ZDe<0s^Q<&bK66Eqp(R5T{4Aqjl#P+ z*u`aM`;tEsY2Usnu=j$~CqE=Rcxkk+%EKh`neSp5;{rbHk=V<we-6Grmnj4<eem&W z0ka(z5{K=1G2H3phuFU`@tfU~o)Y+B!FZ?W-G0DFz7L&{u~KfAMV`n7o!{{99Sga# z@2%K-2QT!3E$0~)XLw=GTBfkS!}GaYqhB>XYiTUq&_uXCT6%H74#dLeu&h?23qPm} zn^X#`+oF!?A~<kSInse1)=G1RFmJQcs0+W4bIj>ujQ&fKg)3q=`?sj<v+w8As9y;d ztI)tzv$|FN*x9mc@L75I&opLZD$@rt-7tm47a$TXRtyTi8>X!7;%EJ|;0Ft=nm<_! zl0I_ME+8cQ5E1p?jpn{b&KZ}QeYr39?E!)*?&HKZU{=9$*(-8Q0=AhBGsqN%XKT`b z^WRJW%tl-6dx+VBl-Z_~S)lxnR=FQwg&(Dso3re*!_M#~B*;N%D#oREi!?aUHT%MH z?oGYvlM^~_3)@TrhaqRSk+6cFl=mOEKGd6@V~5ji=w(+Zdp+!P;W%64cG$P=5Bu<M z3xjkOI<5%DUa)?%{^za2)vZ%~n(NO4da5u0`W3LfLjJ}Y{p+~vmlb|i<|jO+h^b|? zf1Pdi(&+}vFY{05e{Nc^Nm{U<VyVp9h*yz6TIzqCZ7}`5y?TI!n2_1&sPwR3=Q1t% zm(&dmzwGYSf9(Er<ur|%Mt!%B+<THtEpgeqGg*4q0`8Asy1fMxby?l?-@nt_sp<QD zKZ^A-meo&l<jjY+UtN}Lei@#U;r_Es!K6=8g8LvBguckGTZ1-voBbe-`AQn|niiZZ zx&OD;{`=G4Np=S;{>-^^@Vz3KE?W<(<Ikg!8lqYGF)Mso2mV!u@d38yD-}lXwaXis z{V`XgYQ_Q(DnHPHjSK(66!dz2{OurIoB9{m@V87WZ@%RNn1H1pRj~Y@r99fp29Imn zi(Ub-Y~e_7d%#<Zyz!q!3vY{<y2!9o1ibyl@e^825|yO_3o?j;wmo?{KobG16fMYF zu>(m{4@TCLEmyiX8T_%}V8EMFbCxQ^vEFgF5&QPR!i2-WezL{tonOBJ96Ad+F^ug0 zm#CUc-<WbQH?3oMy_rR?5wa-Mf5s`H9`bYM-(LfX%#J&!b5of{0pI>3s_xqH*{x$s z43dQnWYS?T0QYC9jTCprRLcg_XO|c+ZO}#4PPwGBR)rmpSJtO$xGHXF2L3$#H*sY9 zbEF~ozeLrBZVfx{X;+1JGRCzJ*hLIyN1to^hOiynR=F$N{VMyyTXxrHmu7nlG#@k7 zogEbsLj%|aJ7o5KKVAFwx<<;}=t9T}t^eq9*wvT*!*!2nOu{Ec(lHv)HI5RDRX&d# zUYj5nxHa8$Fxp!6$7)tRhoKUZtFChVA5rxTOMvIX3n|Uh=|zgW>$$yyfz&#cUy_2D z*|iV0Qh*4iGJ*<7?d3&X#<Lplz{?CeFsSAhNep(x+nc5oavFW>IUO}E&1vdkriZ6a zcBE<>dsr`G&fdU}A<@Uj(LI2LCkjR##0O6bLN?!(B|6awRiT{I9iP54!JbVfOnU(s zHG%DbCe!*k&Vd(?XQP%y9<Obr7ZhM0nrWOL(dR;|dt*J|>XuyVJ&ND;tDZ;9S&MOn zFtpuy2@HSFri+G1a9>;+XC>1>0x2XE;7C|j(PpFHeLw(NMJ*QzoGHFV8S0<heF1#L z0GBqgGMEy-VrL?eZELBp%3}h)<W|JPK%7bdxVTANxxwmQB{VG@h~p1#=S!22xH`Mx zaO=e*=&NYgz9DXVyYN*Waj?t^9A_AAz~gP(H}dfg1GBzR_-yzsba<{(uygo#c2`*+ z&^k|z!?kdOr@V;p*rG^K#Z${rM$;Ujz|G>gM9j&TeG!GvS989^T+G>*dcb&Go@J|p zmf*gAKOM+%U2n%2naV=R#pW#Vea9#f8<U0dD{u})Uf0&tY##i&vdVqMc&smtj@y*; zME7pL9t}R>`~ExvR$M~k3!cdsXy1ZO*7`JT^bVUvfZbQK><!1tQ<0a{j<T=V|BJ9R zr9JyTpb1<2uAQ)WQ^Ei3v)M1bfJhF5Z2QEj()e@}lmwuH(f#PI(AAOwjPFbozTl4I zjLDbK=i4ShV+FIXUAP;MVzaCn)+x~Iyi%)TQ-%#evi}}hgE-qIG6^~nA^gDwZQfGC zlow2j90J#j&-JH?&U$qmUS5ut0yuklo&RoA{ynn0;DMe(l$X9PkomfkPv7#-d-=65 zo^N{N_*-We^Xm_O{V8-0cXVg=jmS%nM%6B*+bzHiJ-=9L{-(wUzb?NN&6x$1;1z0H zH++1xBo1M2n7IGUofgB(@?O1FH}%Fafb#$`dMasH4R0M)x%cd=I=vmrXt3x^!;=EY zb#LKN6LWefOh~(VuXN+^W2m~msC!bIegs|uu+_#aPSt_?hKT|kOx(lg+zUeK4Hr34 zIP~mda&52$vh$rg{|={eJx>C^F|=2^7MPs9flYqPXXf|`RUK3m0CzhvQe9}&zWi-0 z&G^VAtU^q|Q@50*>yUsRvW7iOUP<eE=b=HOqhOvrLQ4QH^{o3QHX)2Ilc)g;wrH>~ zTcBULIg7EA1mfzM0MsWnkDJ~$aA&sSGs_60PdyMb_cO7#JFIyTQ==jw_|jaxgxO}< zb7>BpEU0-J0HWr|01NT772<qur0H86SKG3B0TkhdzS7h0ks{{R3&mVun3M|6D9g+7 zysG7Pmc<$$!+i>tUUu0j4ZS}md5POibFh)1GD=T=95SgK7sE~ixsnfhz4aYe<c9jp zqwN;@r`jm6`(9b1j2%)+HGF{n=-ZwbW6zmC86y~ZE^)NbuSBKjxzovR#I3QsPf2ab z{%x5hCzpL}Sc6P?VqOY&jdqJ|j-|LZQ4&lG;xB-x)sHhoul<vWlS^Do(301Kb5em$ zQ!IGyGP*1Y)#F`3JG}m+3*m8%78s|GWz5}JZv-$PBcq>m+kl9=Etb{;W9+jlU=*ll zmA)(RWNPgCJ`xh+ry0^jig>uhzMJXRDSey6K3<Re3ulcSZ#UF(y&Iwf=z)b`V~_#v zEwB16h`B`T{Xj^oXRhm9Xi8`G;(p54i)2zl0zV6Zb=iGYDSU^n&h9#(Mw(8sJEPL@ z*w3`PR<ch%bfllz@~>3?7HsVO@0?;|Pz)Cqpoj3f79+~52M<RW_*$#WU#F^Yj~>RU z_BJNpIe~CKSRkOy#V55*YA;Qa4dg1)nU98)p%24Y1mYFo-Y0`-0e7RxW0XQj(R%f| zkkEWaub6*_hj6fQjK<fo6sZzkR3^vhw4QpCH5da|lGbJ3FCu6q$<|g)#Tt#$zE54L z9Tu}VW1xiP1q70D0>)$<`qUPFT5#5D4na_nU4@6@mq{%D^z&|7FVdSp;m;3K3A7#d zU?NU%g{+Wr=R}D|q}FBra7<OCJ9X&GO2-4q!EO!HR97+zt}CY}bo_VRTHc)#n2W#4 zXN^ehU^$OM87MIT;L}MM_Oz2Y<hed=!B928%sz+o_eFMj9^xgdKD_uQ@~ga`9)ec& zJa}b?-5s(z8XuRQXeQAiB~vRr3+NSi2yB$w<QwZYvwxD%oFKnN_k2mBsklHQfS16q z>(>4HDjC#0xif)eR!Uz7Ch$2XfBGJLptmrd8tEA~AI$VS#JrcC7Pza6FiE>3<O%%V z9=rEt-Zj1@eOs~X^=(<<t~u1uMyiLE24JU%piJS5(j)?5E!4ij7zGwsPERwqCR@iI z`Qq9$q<qJ?gOUM5GH?T}!}>n(uIvNE3WqmxmkQDNWGxT`cp%(XY^ad+o=HpoGvf7N zf6foxEzMQWCSfVNY2;vw=gx*~o3Wlir0&f?jmEM;moXjDi6jiNSexc;B=6+rWF6Kk z)_`Q>H%G*lPrIGFPaNei2S8t4dC%S8#CVQuoh-xaZnbqh@I7Sdd;GPN?Sq+l;@d?_ z*H`okD{sRKL^tR;`kG6yv_I*eHO&8EsbKgiZ2Df=(uc=1f7#MRakVb)cv}d-UG+#~ z+IAx~5Y~-2aW%?+-aXQV)8}dAXXLO)#%f>(|AribxXcldny?ve-P^Hp0a7J=Zw*po zWfL?Otg(-0zi5*~AS#!D%yI#!3va2ZBI#@)hjHv<otGCi3z4i^jVU_3F-C`wP(a#a z)y9NU?x3PZKv9hRU>1}c61ffu$kqB1o_%!*AAP9x3j`KH#P>hYpr{Fo@iO?vCk2w) zz`gNT1XzRD34vjdNPy(o2kjA2VB-J~e;5cu2KnYfro9P)Z7(&|&;w{4MicQ0cjn-> z<Vq(=-+;!*G`$2&gN6)3hBfN$AqXZ&2m$oaPIn+2`g}h;vhBiRw=M&v!%}~-0`Bs~ z7aj37FXBa^pn%-!P-G*Ism`JsDjv%*fNps7LzgXI;qf3CBacTe0CiNsh1CQuK0?5> zh(c}8j<nEgN97bwiPT+28E;T{2Be=K-F9C82QvtBSh0;{{h`C5Dz01HowIcfh-%}I z;e)D1=R4>M=%+<%g)w>~${0{jJjRn7-y~&9SNXd`g1rfmhpB;4_-54@)djp0QZWL7 z3VzmPEeQ9SOd5`8dG6R3w)rYh8gkCgDE>JFW6WSY{@j~8{<@&9Z9ulIcQ#r)1`rQ& zpT$IzaJVwbhH*wQRiM>q>=Y0}oAo9^+y}nNBQg%r4BTC{@8~QC<7+yVg^0U_ct_V+ ze_;m}Tq{BE*skLV5snnga6IpO<~tGZ_-{W^Y3d85GJ$}`Sv!4Kjtrv77+e&WifdJ3 zQnL+j5dc8ovX1wiHBQDC4I3x)4dn#~h}?+63qf&;hu|MQ64Kz*LeJ#fd_x>B<oOQ7 zBuw)MFJaTI)%qbnd@;_phH&Sw;$D-|^@kJ=?mUNRf%BYDRp8rb*O=&0M*a0DQFVc* zr9%$wwZ3JB#qUk)_6O&p2^M_NU}7vftW$lE5$=%?h}Cb^NMebx@ZpZ18RU;BdXHX@ z1FXkI3iQcgko~!Qv|uXJv2O32dcg)OKn?%g8XFUX9gHplUDt`>Q;ki`8Ui3y2(GRA zcFKQ?<MGk_PLzbmL%g|hj64x^Yqb3?5)xdj_gN$H%;Lux;=7183x5R9E7HKz<^($W zt3=9cRhRskAw<7peZ&l?KtRckSf^s3$~qvEBR1zje$qnHM^B^Vb^VAmLTDP9F9YH$ zjrTX}sa@uF7bA4wt;$?WKj1CuC;1q9CCrRt&<k-n-fy0=v5tfjVgo_O>jcro(QRk5 zL_VmWH<ObSBd9Miix0}x#^YR-tr#DL9Ly;@iZ5QU+~zBcA*qi1;LaiIU^jd3Qe!oB z+H{DqG#XXZKaEi1+smVraAE4jOC&iY401yn&tFcY9ZEJCcY!<;Vx#doVT3aRRdE0& zn_MBu7O}d#Y(N^`QYQu)h2I07{W8Xq-KK|D>f1JnpQj89ezndyjH5-d`(ou(!Ze+| z2^Yha6PGm9I-zsdlx<PuN{WyY6mP$2SoY?rwd|EJ;yW*1hR5F8))7|tqO$YV<@P|n z3g%qOIYx0P$O_OQ`QW*?DYKPDuVB9RW7Qm0E)nCfdSxnOXE@|H{)u_XRN}%%8wp6q zds`($#@$UrE{-R&wgXRIW?2R$gs-c{8ruw5$2v7t)LnY+AWdKC26{bYj0_a4moA`1 zQ|*7%#)}1t1a@jiddDGk8GM%G28qe+s86BUP{G=#ThPX^LHI03#_nz$uuA8%AS>q% zp?b_v?8``;j;Z(c*nAJc>kHtvlEJd8<M=C89c_+0eb9Rk34v55e{RTXb&M1l=cLLS ze@-WBO8Q!M?p?>EI(0k>!TDpFdqnpO5CuVogKn`t2}_H=!kqAmkH2IrR@AXSUWl>E z*~b4ue4xBUJJtRPxzV%g<=+~DKiv#1iq`X%AZ$7{SU}M?3H}S*E-ZK{d9Y+Y;Vu@1 z=bI{&tpaW^h3hcfASvDCF~B1j;l9~d6k@UKXG^<rHl&YIUuAI9lkMJ4w8I+5II57l zlEUw#uJ8p2CM-rO7k`Uf|F-us&ifmvY=VccIKn&5Dy`<@wqZsIAt<bT<I%fDogCZc zw5wO3egLMej>Id>&nUWhX2<8BciyBro?G{JN_HIy5QW?@W|ca`-x}rbe#FYXSYNne z8GWe#gBn-8On#LM37U2o%619oB|J91Ze6tyOJtfjhQfUt1f>}=!(+Q1G<`v(&VRGC zWuA*IBCw{2-=)rr8^>4-GEE;60(l!*3~wZDKEJlzIcJ-3wtgfcjZqmI^CE&ZG~>*U z!I##$Se1B)=haWK0El0k=u-hc&G={`B50O9wpM5H1n8bU6`waPN^_I9P%-}ea<u2q zefRyP=P%n{wiXcl$RH)}KGxrayeNWB`9d@{{c)HW=Bw3gW}82h|2iN}D=pgi$5W~2 z6<}+(Bnw5=5Ls)XCnhX}JL_U?L`Hu5w#xIYe>$pF<0O9Cac;UnVrn3v)8MuU@YJK# zkii6Vy_;$`6BLdKjGRNG=#m&?G(+<<S7;nM?0n`%L)Z4Vv&;qCJ9d;S#aH)4eZ%m| z>q?hwh~%xsGItpRXGqN7)XN7;Uh5DpldpyBEBG+J$A?Uh!*J$dH~opGuwYqk6vRLG zbKJ7>v5nUhUy*`8=jgfF#6fZ3gDZhOAaPZ^61$X&1Z(g|X&P@HY-oeq!Jpt9g%>Br zm>*UQPBU59d<u?)=1ezfSbj$7*Pi4mB+o_5gyGPG4QO+b8Ypj_9#;|IJ6L)BpW2mc zYjGHo!y=1Rc)L{(6C*1(@0&fYi~D7Z##PIkj912zQ<CfsGo82ZYzd`ZsR_=yZj z{l-F-#~|YbLxR-H(tMZ2la}c)HK<@|p=GfW_fBjLI~Z6&82J}ByayX#@MMngDzGMt zHr?VmVv^E`lePzm6B(ZqpKlWjy;%KfT;c~wDNgcuF%p9mDQ2XLK}w!J<cS3Yps%m1 z`$h|xD2To49d)*epF^iJdYDXOA;!G_<wyr4(4?Ks9NjDV&{7sQ1O_%`=P;a<H_p6> z$v+<g|B^Y>x)n>l$tp|;M-VQ|V1LA4-ijmuuJYfgnl|<S!PDPqQte;rWqYHoS2GG< z#{&tGhD_J`Zfw}0THAh7OG1j`Fi}3nMNC-!(l>&Vv*)XvVJjEQv&QaKGKEV0&RPiE zn3U_Bt~vd2@f%mzXp_hh;qHB2FX_g^{-kInWEjW9oiM^n?>N1p7;(96+H_q0V8<W9 zG>Xu-4Y`WHtyA&qO|p|s;naC$Z;%&Nl&D(`-?WoRhXgIuMjSGl>BPtoaaq3!0d4R1 zdNc)JHO9n2yC1Tuvr0t(u9^U<-y{{$IIZXgI%}O9lbI{SelveW=gWv(@e4Ps(dF?D zf(p6v7ADlVy!(}xFBXc8Ni;$4{}^P_hT=Z&F$U%mA4eG^wBBo7G5%5(U+HGST^)Db zW0{Wy5ZwL3%FW_=pu+4IAO;Z!2w#=78Zdck`>HTY=6wn_4u>H=w~;IS_=SrhEAM0) zuY-I)(4S#-!Uqlw{x-35Ns_0{KK^34mnj?g4Q7gA<#WZm4nC1q&7)K!Y4F8JJjcxK zXhukM{8whJkcJD_C2c~3e|7wdXS+}wrvr@<M=)LA`f>c5M`%_g7^!+Ok6<DHK_v?B zk0pfVHa<nN{(HB3Ps-<&u;0aR4z$n(NN7=s6EQ}a%y@L<{Hboq_Q-}CrL%RMDt&s_ zmkJ4w+Ic<}>T&BZG}#M#CuH{@Jd9ULd>Z6`$T@1@8x&akuN>l!jH?XsD?Ek+A3(yq z^>2F|<-FbNY4MDw@1*~OV2Cl#=Wn~)9^E+i<ZD2Jw9A}1iQkhwDi5kzq4GBt>xK_| z778T<9j3ZX3~0K_KG&$Wt4bD$XvGBJ<N?%gU*dk>pLu!q1ZVtUld02!&VG*?og*`D zweO}IW?u1dzt|Hi#Y-P-#+q;wbW#oXVc)t%PIe-Xa_{PkJiK`W3X%!iia@59JEZAO z@jLT^`ErB4ueEzo6h@>1X`^Q!3XMD?--5dDiB3BFd+Au4*}(Z+knl2$$#7Z+V+?5u zBdERY%qO1CE&tmxf;xuM_m8xYzBsATnXRJBx+4f_{reO7LDJO_b=y7pn+fR8r$@Az zyN{q3t^1T0ru?X)zrpblKqgLEZz{6qKccGNblUaKkmobv?<RlEYX>f!HeUO_Q)={o zi>l6im&g`r=+H<%X)9sF(520Pd%@Bs1%7**k3dd)KJRQwBHci*&KV0`-BL}w{bx^V z@CE3u-i6!0WoQ0dR6QeOoUai+bUl>1<`BN!`>w_T&S_JA(AN3LcWCk)&AK!ZCDT+2 zYk9KV)BRrkso&yop31$STSu4IGoBhvup>V;YeZCUG<y8`SfC!Z5BRM1>F14CpDHmb zcICcPGFOV7Hpa7!m_!4BYahfu=UwjzbNy@~a{H;u|A?vuiid^3659TExL9Z4-g+#~ zt{kTL_@Muv-S)qtYTMHLo#PY5gXjC?jppxdnV)sI{`uRh{}EN$V$Zth(H>qNQD4!C z(HEK{FQ=+6tVpDWR;~}c5WdX4m>}1h#QD*e_(;hCuk>G{s=wD~y!r*tMUCylmnh*m z(lY$Uf&M_j-Ll*gR;f$e(eZMn!!|?bLD`rQtM+%xr71MGL^a80H}fXNVwn3tspu8? zvw-x`NnBa9d4`^|5Eu5#kaW50#*of+El9<)SpEp<5~UKpj2P(Ao~6dwkC!d;?<G#; zg_Nx?C4j@IpNGyjxV|<$A3Zd|Uz||gE>lw%q3jSHo=r*9ppwPTsb`PBWH)@FWRlNu zDQtI0y5#t1=v*ynm))1KVne2R%v62b{OQ$CwxvwnT&d50tsJ{N+<W9D8fdVvDAi7` zs*zPW$TGapu`{IJfd4dPYpJH?^<+kSIUbXWZoau^skw5(Mee>^P{ML9kKdXgSH^vf zC9*=%HYHqf{0&`HeVNEHh@ve&9TYu(f8}=T_?Z<ITCi8EBL~9c+@=iZXzi;^i6ST^ zTqk-<VN{p(!di*Q)WE7kg*#YOy;`%xP;$FtVpk`Z$@Rt63e~Nu-pEfHqi$7YqRs%( zl=U%xOiicq*J4y|=GYCJc&GbyN2P_@T^-T-7q*)xE`7RnWM4n*n8T2-OD@ney*!=! zieGc2Ra0#>`=0Vl{BGJGo==aCC~(b#^$(%yd(Cf-Y$cUz-&3yezZr6?h!Xm{r2d#V zlR>=NrT(k4M#<?muh8_m1Fd;E`9@ds4*uf7@I+RfVuI#qWV|^x=|!DjWLg3cJkYj$ zdZ?v!wECHQR|i#Nf9V)pwe}QSeZ<)>JlnCSkw8;QZyGvZI4JM@Li!9K|J}z2q|1yH zekrXz1yVGu*<?0O<>~IB$NBQ*cvJ>f`?2D8k=OT_U%OTi+&lEn0;S!EuCKIhrQhqT z-8KXa?~(b&NpURQXM8I5GS^+jjZdSDm}sMNfoWooFBVTrBTzuq6(CDU0ELTrH}T(2 zD$h~X^+P{m-vup_cV)5b?e?X!7(DRo?rXaqJNFV>L@)TfBlLs)VkM;mAxK>i72aDX z8&s`H9i$Nq*NZ#ESM-GT6iWEHg1|8(B)}VKki)Rha)k~8Ms$cvUVx}5@~lYBQ3*&& z8vd|sz*qX5D?kGQP!|-3NiKBj<d@0P`Wkn9!QJMP_o~cN`WOjM7oVb)MU7?FQ9}Dj zLN_9ulWTeb`IrO}GRLOb63tQ=!w2MER(&W6%s`8a5>(c^*)hm&#C4ymGx{;6BE0x) zU;ss+J4e<YFkl7Z7*yV?8VTe1Ah*g#I3xx_RSxxp9#1%H<h%ogGA+PCM<8ytOID{S zn84z+l;Pz(qD9=TFi^OW0|WMn46*y{mN%hW%NSupT9W_ROcv!>V&W2v=4eOs>6^Hj zB=0s?*1OM-n69PX0T&62W#eyj1U5%Y6Uyb3phzY?NQ}H94Cq}ZE_K`jaGb1k`RDsg zlKZ@lT)A+xPLJ4$b$fI!%}5RC+NT$fn8LN`CT8VJoP*jVUyW{Qi0rg(Krq>*)%_CL z!^$Xajxu>U-w_lHJnzizZgN(&xtK*aY1%&B!Fsxcm-XblH|D{M5(CJM;Ul99ajwv+ zWRUQXo0~37Ob1@8!vaLa=*A<Wq;<xvo_)IkAd1c`a-LOm9XE;5V0is_ABWzHhiJld zV~rG(uL1-5Y=8K?Q|aGB)_9*|-QW|n=6=<&7A)XXzs8Z2MiA2VH56K)69YOPAy7U> zev)sRG-5@iW^l`X<op6qAT%auIR|~3o<K**gxW`ib<I5!ui*90t|YDKx+o|w9QKzJ z#pUBM!#T_c5&+s)ECGE<0k4riYErd+@r8>*w7Eu`9V6dYp6pdkj=i>l*w@3_v)$)! zfKkx=1-STBpVakzAT!5A;g)CU<@sFi2(7M5IUi!WT>dSKEsipIpb>HZ7P3-G#$!n* z;%>dQfgkKYUdmrS;RI>d^BYAP2w9F2Aj|iWJSorQw)o!Ya-o}ov=mFMnld--O5Ms_ zlQ@#dC0dL{JZTz0Q5QEK)7IA?;>{F^m~Uxz*`>m8tsJ?{QJ^OE7I)3<pzP*QdR_e0 z$<{6<xm6nkR?9IZXU$58A;8n&$r4X4Y=03dw5l@S{^euN6Gzym#JpHv?!U}rwjQjY z1s{V>34oT;1fS@<mHG9{E?`w>g;&O!aiJoZSNBb-GhV|kfkNh>SF&CI`RG00#XQQb zNJ;ZM+8YcUmj{85PrfJEsBUmKvXX6&F6>|{6;OSx0pR_pWUZtk-r`aIElIhc^i0-_ z2Kk<YO;^IXR(ChC$FF-|I<QE-FM^{6n}2_T?iHy2O{_**O7@IKb8=(2onDHLWJcab zC%Uf{4(=~9)b3Z|W@6C>zuT(ngVk<*v$AMd{X~)b-I&?A<)y7YGg1G$<z?r#|6}#p zWw}4ECpv$Iyj7putN+uv*ZC`wroI5Wc-YO=MUB(eSmJ6p?7Q5xlk!+&MeO3yJKL_^ zoVOZlw95@gAMSPS71FDPF&B^Jj~IXc<$p8~8N(4JX;<zDo1H=$!E;DB!F4;Y{F_#( z>$4ocuevm#KmhDcxot0(UP4{#QcA?=vd|mI0c?3O{f!Wt*z4bcnm<+9eGmq5fm)F! zTgoXBC-gA~FX4Uw{Cgp}RQMBuN%JsbH7%)D;9wfB#ehw?pCu+(B&!u2nAM-Ae;drK zGN{9=2v8WrsfV$u*Uks)51`X9nota27NF=z`STB_JW5d#2Wcl!l=k&B@8f<POnWyM z?ib9xBT-a`nS>89myy7XX56`(U#zBC3<c>xDCYR2@Ol(Tn+lRG11Z~qRGoXYCTW-} z#<2Kk{8MhWdynG(XzEkh7zI6hv`2CLlY08I$eeGz%A+8ZV$Az#16OulW7&5qvoF*h zf|R)_>RT9DKaeUOJ_{~V5lZ%L!|fm#)ut1F@#(ve<JPg=u9G;Fpq?REXF?ywn)fsa z#omLbs2_IA;!`9Kff{L`nH4zT%vsea4BA-_8iUb{f=L%)07THIvc)LilnZY*Tdu8o zz&oU*{>fIinCyTCmV!tEsn{)MGul7x1S!%PM<Pa-i1Fo}N9RJ6!DKaA41h{e$-@1+ zKv5euQ6&#<X%<_W8wq@35In&k+koo$EKGBpIy6DZGX^a`piZXgUg#)Qk3z9T>TAkV z1oc6Bg70p{@@hlDXl}MHonEa`I*&<db)FCZz{m&#Dj^KcUUHD*2OFx2$nSzw1mT(s z(GqDm)eeyU?zDEBJ76V7c^_BGwi0ErjBwFIbAwg0FzDVMtrLngXK7SyUsYTGu4a$$ zBu=FbcM+-EJ&M!DmjusR+Z=<`whW9@=$zUz=;J(^*l#aL5!9gwG3uy#_lP#T+vl0; z&oC;V;4X_(goYTEy)hbgdMfUiGgT<76FgiKs8oyD7z7C}Fo4jmn520D??n}IKN<_- zxexMN_lQ48*N|V99gP0lh%?)DJ$;yCdz#IbOcRwf$6#jCwWlStw=fd>xa*NiRy{+k zdV1E8D{swv1V(Wxvn9tnW`>g#w;(($0|cAIfb0qJZtM=Hn42yYW==SyAV~8Bb1UYP zPZUL^3?wuBPQ+k9dKZI^>d{JCdb+-7`EYQGt^#+I))7G})K&Gk5~E2A`Y@%3d#tLr z@}m5Qt3Q{munVTYMH2Qwe9ArAc#v%2S;OghHF1p08L+K84&p-5<}SO&F`c7ns;Nlf zB4I#GWOcfcjV+sBk<>l>ApehI9r8ux1cw4MWN;Hx|KXG-ae`ZVw}*w**zl70(y)4r z$|&ZNGe&0Vy~V!wrF@Jw6{BZJEAiG{G`Z6&U>+0Dh0BV>X$vxl&A3K}WVp;4(m`93 zR-Dm85ZgxrS0ZoHI8G1@(hxVF8150=TDJJzqx%~a=)#WPXVBcoXl7xIj76>5mem1t zoGukKN1wZNYqNPc3hUqA>eF_t!n#(K+5naE?bPv$=m34ql^79OvCB*>Im~Y7VsOf{ z87ho`m(F_H0PikopBvpnCLauuZ5Vg=^2tL6!7yT$q<(1}7td_vyrYFC)>Fe-rUEUh z8L+9`Cax=(Bse^0B8-3Hm393$2;IxT<xcUzgU|hDxNKZLd$?g~?DOXSVktNDidOf< z6G}akXXY`bfj_k@k%rS=k3xG(=N#v5>h?-0>M0iSb|I5;vhbT%1Px6}l_xP0MIg=T zn=@(E8mgdHU)-1Y8cXAiSTFB*rd8RcX#3{#rG?zPC)MS!UfCROP4MlUymRXRp_nnM zY4MIkoHAVk#$#e`dg^YSyUAOt6^_3yBa6<eXcgtGnwwW5;jSN--C$lYGTzW$=n(*9 zIDjSm25}d$x`u5S>68~2iMrY(%s!axa)^;^(>1iakfY#0fAjMl=g}mPHe0V~^U9Dg z*dZh7<IjwcPZX^v22Etu2}iGVHAsjbCEV_7)h%P(i0LrhxKGBY+7;Q%RcOhXXnOWc zCgQ}DX)>L9dbnUl&x)IF26QABqe_x|X%q8J4(!lcD<a!12N<67%J4s==#Ar){rb+n zqlDDsIOp8%%hh+%Rah*Dlh^!B1b!t$WI7QivQ!A>&*mqA8hY<!evA{~m9RJb5nv&z zugHKRVK)7XQ<wlhF4gGm$D)pO#fE!0vv6qW($S{PAQ7i6?%kc`XuUWQ@*8B~i^F}o z>)kkVPfs7I6QhmYI5Ms3o-W;y1?%(1pgKU&lEb&-VS-5@Kl7UC6mw1dMbth;8Nt|a z34g=fA0CGjL13!-U6kFDjrOHw>F0SFdl$E7%s7s@zUYt3IQ19`Y6q!|;$T=BC_$9- z^(n=`{>}`MNo^El@X7S)lm)&Av?py+eOToy?kIMsi*f1ITQFOzO+^Lwh!)97lqn>d ztSN7wi~8N8MaHP{%6?K^S4%@?#NZ&0d9XK0lj9)upEC@lV&ZA%^tOZ<MY|u?RdLi| z618;2UcsZY=ej2;f?you9|gU`*c&7q+7W~rWYDCO*n`pV9+H+D1x>FFum?4lGl{#K zYR>w|q__)vO{_aXu#qL$NeoJ`2W@`=dz@SpM42jNPd%m}6jR0C-qN^F(YDjoO$K?f zUG(lIzBi<N<HSoIVziU$sse6mH*YJ;E^B9@j@mu9*Ep0NZ%Z7~Kz%(fuF)8kT9B+K zMzg5I_Apza$qK|!>LY)_(AeTKTeqtpQFj#cmxCgJfB7(1-eH_ld<tsFy}OaXyZO6F zEaH-uf^^T8*<8j=)uNXoE9(ZUT%+~n3aTJ3OQLSGVavFucGA+HpWs0@10*kl=0lt+ zmwxFnNd8ivhu6*0j}+}Fe|fhJDZO6fBZ_9|v!%G4M`;%;eT!to^vy)UhU7sL5Su<- zZzU1Pz7wXOK^D81E3)9K-<baxmYyC)<}IeQ4U<(d6*gT}qTitKh&I)I$o=M&=S4rm zO?G~p3mrg>B#QlseBegahY(69tmM$?m(f|UVO9WN5Up1`4Fr$$(7wghQxdF93?4hv z8?oalaJsE+XP|Kix_)=U8Qg~j-_wr&IdlrXl32FWhRd;$5cj*dU&!=OxccBHHdVnv zvv%iaUV~v`%gS1XMwX%s>y~zygkpfc%8iU0ZDkk!U^JY6>&i1~8e=XF;;si>vI0)2 zqx~<G)i#>e?BKav%|7U+tv9e#itvM1Oq*`IW{%{Y9pvS__wwGqxTde1^4O;o<&Ijj z5M|9Y#mlYt*u(W<6Bs3B@dW34*c5k7PmnZm%}1rqQn1nz(^IEms<*Cu1KeZW)Bk9G z3E>Co$}s+Ua)~Ewv47KTBl6~O-o-<vs14ZfwOX2$wl_$^ThGj0Kc=p+@^oL~k?6WO zQDa}8@Txy#9G9Qt^~{~SHYC7By~0(XS4!`K%6e4fS^W2&^Ga!yDgNGzZ=zFbF1XZN zX;K&5F)&43kojfl+xs}BVc^Miun|~C{!mxZQ^u(^*+acoYW&;<*~KvNtT#D0#5hGp znckYhgFWTABHSZ(Xx1eP-fNv#VT+Cnx^pV1q$b$d;q<`@8mrO!qhI-0OTxU*q6D%S zt{TS7$blCeOnAx$c8F^dS<x%>XH4qCzzbQjJjO*fe9E}q#BkLkjwv#iP!bQak2Svg zf9m0i=Ngphg-dKAc;U)?_|MhA+iAD@9?_0bQFiK{%~8chh2x<6H%Kqk-2p{As`4I& zUyU@kVg$+3gUwsYw`5``My;@w8uxFZlSH2i;)_-SE@UpK5*_@0aAHqwHL*DU{O?35 z{VEXSknj7t+$)Udr<~!f^MlB|Wo66eH7mzGlh2r8nagi)1ZzK(Y4OkxasoXKMoI>O zl_%1CW$#>4#W<gt8fi;?1@Bcny`w?J_5Qs)m^G&XCL@L&Oq6@axpxyqnNhD6QD8ky zKmER=*m-V7(U88@$5ZGekecI5L&;%QCV=TYmsZQYInIu55jOH9PLex&l=V};YyX)B zyrMfsQxzmR2<l6jK^KXlqx3ZOX&v!?59PLd?U5s5U_I^Wk=)D^^z@K?;iH*r$#u<( ziS?21L+j@SOOW$%c7LuMga`dKFY$PN@nfaPPsYO$F)1mQ&Lh2ENoDcW0IiaB;gw#O zmQ1{_qL%i$xHcXaWc+H@&cIU6?f3g8D_zT4c&tQ+?##%Wc)iX#-eJp3P2XlM%`HXa zf7ajqHc*9csb!C~5)7*DFz8ShCoTY92Ll-fGY3+xcLv-G`G>1SpbYS572Hq$jO1yk zz1*xSJsTz58J7%g{Az#E!|drrxBe`(OfQSP9|3EVRTGlt`7DiYW}!ZU+5rn*4D{69 zXGOnx^5T}-e~GG%UU#Z8X>M;qW+$=q+f5P5Gu6fJ+m1ijHN$u(PQ_GKo~wtlm3uvO z_+=sa`t)RV3Y{C^Mv3ET`unOWUF7zYGd{Kha@z(WpJLwae73s&I>=7Nspe0k@S6+? z(BxMMf=e5v!3{U3`aI-Lj{pv~dW&1|{WE$`*As~gvtwTx)1@3-a+O{E4;DOaq%1?! z1NZL-*xoveT8NmBBi;Mszibxx@L!(r>-<L#{wN7t+Phcl(y8{cE8D{;WA5$yZg69T z$U$w>n#lMh#-iZPN|dDF%-j?CngZ#SbAayZ-J};0^{?07uqyOIrN}YviK=DXEY>|d zSDR%n7H~&MwcMD@trzO^r5&3HH>?!v$-dz>tr7NLZ+b8L)PD2*+pwkA2o%q?B%7gU zrn@8j+Cj`F^cV7&pdDAMW|(qEa&K5v=I>uA!P{%9hIJF>HUoJ|C2s34GGy~@tb}Z9 zN3E*4$4P~rA2%S+wQh`a<ljAg$CMS>41|y_AJk6TAYKfcph7?5Kxc#c(-i=cBTh!B zA46k{FWP6VrG+C_s%}C3lV;)XA|{Ek1$T3sp+jcTHyg$KQm&Q?-=?370^!QlHbP-% z#yp<~Pb=6K=2dSI3Y|};<6bt$WlzA}_1ZHFHE@qo&&N&Qj5o=T$o~HM8Sgmtg{Q_z zMak`(yIUfW-X@TI%qmS&`WvnkA7~W%P`BsB-IH*_xIVkqL5GfTxKX}9pZc$K&CRMS zeSw>9PlSW!lz11j#XN&b12%m;IU<IRDqjShDaH#2pYHs*s_Ql8r8DVQz561ft;Mk5 z);tUOZ9rRgl92vY`+AMaJ03YJ$D6>~vSSi@`*LK&7b!u%j@l~WfEB(WY(Raz)6d^t z_h9Jj?@;ZP$+e~bt-=-@A4hs{KAzz?kO*5Z_KN?NRLH#b`dp=N&}{~)M^4}*b5ub< z%#K)IWY^>wv+@ty%q{=opJ8;;$4`t3BJhEaE?r!%KT%@g5p5K{6CWP;th7J+3MzcR z%STAkZ1)xs&`dLtMn&F`*&s%qZZH<KEbkco`30v`)r4&B7$iro`3&q8-ro|)&{Xsf z9{BM)3>+AGsZYAUUxc74k9(Z0PGy%DGc1KDuJ^u7)~E0X#rJzAg|KO>N(<9+bIq&o zKl6^o-O~3M*lO$34K7QH!dp-8tN`;PR7*KS7chdZjhc4=UM^Z=SsM99tn2T3MJ2`% zn&=hy9Y?Bx+POuJJ8c(3o0mmmp?K|%F_`1(dfav{L{sa`+xoCl;V=?deFmk?rm!M( z^4GHCcWhdQw5MaMo;&kpUU~s1L$D<)L=(vs6}Yf+`K9XzRb##EW>Trhm?K4bJnQLG z-BOFwtF+~vx%Cnji4}nZ`GHI0x@YKpO(H!}141e`l&A8{g5QV`$&bYs{nouDwR=DR zlFfZ<{Lx0g0zIcby91X|#0Y7W6j~@7bUC#xiY)6I&ud&USE%-jplbumEA;x<-eref z<bVo4gNf6ozvDk|<ZI=OoG%}G;ETD%uTLE5wZJ5)!XsBuak^wltRw)M_?hw5RT&}1 za^Ze?Lrs!(aukE)nXj0y+WODZIgUW8yX&!vXJT8*2A8D;M6-&$2ZtXT+PM8JGP+DR z8XwM3rD&>f&WF0GO;I~SA9#DT+oIp!==3PKn-+_nk48xbmkaNELzb0?EHX)A{E<+m zaN6)eY9Q~pzzeql^ky-$UY18Hf4NE9f)D3KzNErGJMi`x8Lq-<PGMX-lV+j=-0Kle z_#}!^(Y{=y#!^xGg!ki2ntNvHFifbENYG8<wNF{Yqn6T)kZe1!AaIe-)_dm6!JSko zEJo=39fG#tQ{~+Is~QI$1N~HY`M5)zXImKl;^vrRcT=tS@=8W@hLf=x7<5}+j9uyb z5G8if<IKH)K{R6MO3LKDGp9S|dX!D6g<8ssw_>?^WR83vaSs9A^qUqBU%?&0Q7U40 zm=j3dsb=vwk$GfprhLoHueus>U!4ol6(yw^X&8HVA17X+@141RiIJ&k5bw$m8b|E# zvQRJ-!)scUa+hs9d9#IEpvBa3-EHKm@jdhJeykby7(*lr%*+A&d+Or{=M)b{XH}&y zr{ADw70}kcnxnwP2&B!0EdZNqJ21s1zf}02W1vM8XDaV!oQhpHlj?nstSf7+@=^KX zPatAE@^i5Q)ts~GM23biePu)%c2nWnv1*WXy@cmh?PHZQroPGLS0;-XlnF<vy>5I% z*(}LMIwf@n(|*^^ep>bpX@tGDx#?(K;Hw(-{HfcRSV1nUf5G(_y<hiB{d~*!42P`Y z+tpdV$Ib)ke}IXt!sSv67Q5Ey0v_%e**i_F5<i96H)Ow#pO^SbQGIysT><U1^o%by zL3^QFTH+hg^}^y^&COdjDI3tIG!jUBbCEq{rCRt`(aTzoiF#}MG_g|VIBgq(((Nn^ z?9Ftlvfkk3+WcPlKoEbSUwHFWK-pD+{#Hx!*OAADGRcJ=M)zsare#s34{U)D?IuD> z<oazH9kncNh@m{m<)&CCa6pO$_%aCa`7&}zzSXP`VL3)&AD!d1Z|=xZsTH&P6=r$g zyxN{8VOA*jQBTUuSS2rAnZ>O4E75?=8o61hImXxaXIL}Ydc=J4qiqvz{e|82E&1m3 zOlWE&TK1l<qrx*a`_6PTv!n4^!I{nT>ixxEas;1=6bl<+7Z%}RQg>-LY}5|5-JzpN zCCnZB0Zfvo991zjPS16Z2nt!n@O#n}J~cyuT|=8KvEu~27QeuX`*Nugrxf-UsPjhw zbMMSaF|NB&1InWP$&WjV&vb5a#VN0*+$DNI+ditjJ$d<byrFt+GK@ia9#u^e`6n8_ zGllkMdMQaa^q%de#>Q3%Yejw+v2&<Y?q|H#J|V6MSNP)>zxENJ$X}dVI~Oq-A1Utp z<?_r@pH{zaz`sv6s4_9TFUj@ViK4N>MbkzA5>P&BD~#<Izx-n8N~(MWL73ECi>MbK zNAaDQ3h#=!#H9vF|5|nzy=Yh??CfhSx;En{x@x+{zN9O-lp;V|N1-b)ACfHgewGNt zxhD8qJtW5qw{PXu5`~F?mZ+71_>snd7~y7oh~CmkE!eC_SHY(L#wQd%KVG;b8pcbE zX}v3{=V7@i{%JfFl_<mev&Y$Y(5#+Br}zX{-1yxW)x~d~g4qbX)xsaU8<N~3Ok-(f z-3>8%fXbK`AAwv&QZl)<G5{Et23Q~wB~1@ahl`cUk$f)&EIB3V`Sw2?wLE`c&tr3u zIa2rIAc4QfeJ^Tsp8n5#Ertnm{;<N!{^2m%I5oFkc0XpcF^TE^Cs&yCV#C7ue<zf* zRyWZQ29)P_)1c@Z$H1{k|GTPs0xJu=T{5J0=D%oEB`wCxpsQc$<W3H^q>7x|<j3=3 zAH_RdQ9^^=mxo9>XUc_lNrJVkxrgN?pXgX0>ePlE%OW|Um%M6RA~?empRpLqy?nqF z=r5{3vMY<1#v>h5os46t&W(`OEi@f5okk_b4^~^Q8uq(E54#hwgXg=VjnTW6k__Ch zQSO_8XZnV69>(c<xt#^0M0-bFlbBeZn<}iyS;*sHC()cx-H^gEnfANv`8!p)RV^LN zX38Ft2X{kSyA>T7qSBz&qeCJY-F)#|()_!-`G)KqSk8H>wEZA&$$NS=0KNUk)7wqt zlcdD0WY0OcFxVR9Cn*#W&1-Lf5aDoR;gqG__PPEMH)B|CQs2WQ!r5{hXXq!M;~bMT z2Xu!mBC<@4RLh0)2P^$YuEhabptcf50aBbEW~S~+D?kAS&k(G;5Wa%{Ddg4qqEHS} zIkfm5X~{>g(lW`$h{?n`D0*r*RokyZ*wc+&u{&Ma54q|E-B^^)za@xcFmf#+G)4bE zvhKnwsyBQa{mc+E49v`?dtd-*6hx(U=>7r*p`etsNOue!5<^JG(2bOoC@GDkNC<); zt%M+;z?}J=^R9K?cfJ3@-fOS*?EAi+>+`Ozd+pW%PnUMbl;R~NfRPWAUzfOotOVDE zY7Q497h{;Vx>FfSq?8a~3b)I@Q){isN-H7OcHuuBYA1_Q&U1rZi|u$`kBQx|L|=6S z5Dc10=VO`%dWFEW*Td-&`r)AKMy11z=keYds=8O*s9PauZVGMFc)Q2DT>3rP#6MPi zsShyyF~C!|n+^~7-1z^B^O-h<&<TQBvlH*tsoNA<AkRQG#V8pQ8(!l=QHgHWIm~^v zL!RnQ9@z621WA73>(b^J_E{UZSdz-D=|9`A5!frN#UnV_O}wg+nkwakeP<gjNbS0n z?9hA1sh9t3L)IY#PKXYG7tIEM_1;^cce;_qy&~j;*J_owu)tTo@0pRfCOS)Ah9Zj# z3-%5bZH4J;PDM-wipbRd>^qO_&y-pGH@ILJW?F>f_ZdtNhQop1E!@pZFeJels+6M^ z-;4>F;dQ=i`(L$%5K{qd?18k3=X(uujyv&E+>e;dc;2*XKU32(FponL4Qe!t9-y0^ zBRhGyD{k|fZg5Rda?U(3?@}z8+T!w9^SQVwBQ!1>mQ-w~n_+(Vr^zzFI268PfhPT6 z;&G(hSXu2fPdP8?!Gr$0|1osj6#~jGRYUvq(+w%2U3Tv?!f{?a*9W`VV2Vt~R;=0e zTiiFOzkobfYLxgwA0?(}@WxwPKC(Agx5%MHvu%Y$GE^0oa7p*#s}(H_V9I61-r;uo zp9*S*!Oo%@*)}}vGtR{zUg=s4Yxp0@%EGI47gh*?9T}SYU3(%r4o#wHS1_O@@oywE zwABJN{mPcU^hVgB5ktQ$gaF;ee1ZQq8yR@IX@Oo*M7R_z5C>`goIQ6503#Fl#qN}# zxiP?pFqhkUB*zpk|I+Gc+$>B>nXJTSJsc=?O;mwgn^6&$hQQTrH9n`=nk1lIQp0Sf z+_zT^pQrJqrWp5!Ki@5&hlS|OfO}$L7EK5h;aK!_3ogoyvk6slGLVDqCqtJ)sk+x( zve(&{>bce@-c&c6y=(Nbpkz){<ZLZKC~H3qb{_Dn)?0}15sUbwG!m`k7%+d0f2M`A z73Tbd>4(erkH#-$XB81a1ze%yl!@VF1EHIdIJWy${mFa^PC)QZ!EgDb`zi+-vtPcA zDg}C<`t$i%Y~KXM{@^rs44LKTSSeVx9`F!Sw4W&oCF&ZRwC!{CSwAvyAIn+)@2;o) zhNkXT2*6Zu3+Q3%FR&78HRo@25U!Ovn$WLX<*-m{tfbdv!|PvIC}+GCrWw~s9E}bp z6S_dXfiq&h(lhy0-?cmOcOYx+w}?9}m)}U$vL)**$I5klzhe`2|8=qTjQOL%Lc{0Z zIR|YGS6oP}t>#?iJ&5`5zsJ8D&Y}%Y;(FmqYI>E|nH-~sQQ;QH;k5p4{2*ENm*0=2 z!#@lEDKg$EurVLIHr)LWHuT6s&0Ri<%eVh;6S%du6d$5$QRv8t1#7=;kbKdDcxOdN zx~YDlh&K2syImRWn8_6yiaiyHh&!R<7SDLb!%3u$<w&5(JU^-z9?WVjy*1?>Afz_3 zMNPL%Ko?V`|6mp{<S|Mp{Ss*%>@FhFXXOHEMY}*k0uw!?BcJ}eh3;6ruAh<q*>KN` z=a%e4dZnIcI$=+`R+Im&xfe!+t9#vjV|i1abu!#nVkZP(>)zHWZ1#EU-WSs{Y=2uM zk^6;^blPc3Md-|ISOIb>x<?xw)WTV#B($?i*RcBHVXUp#4#$cjCqGiKD}+-?H;YXC z{RaVwr`6~?igcoibfDK<bT7u*y)8BMb6H#R8<_-R%SJ3qzL>}6&Kt=eoylDEUf*Gg z)v&}saQaJe>>Ut8ItPyk)_{vX?P@UkmaQ%EB7!ek(Sw2a`jrK9+%=Bc^K|%>aC7&! z*a(|qC9=<aAn^t17j@_i3nW^wV%-`U4t7*)*GMcyi<U>rg%92o({cR%90D?3ba-JS zeM#8lIsyo>8FDSD`Eaew3Ko8SF-|OoQ;Qt`tne;DN~_=$zq#?6*v&;5#fB#!&#*`u zMan<T@w9E%c50H1-z?CC-MK5>xK(icf%j}rnqT7;`gn!*uZ6sIu`^Yh^M&HcGH4-I zK(|gj<tKZZ=RjOHL%|L>1bf0Wh!=d~S@7zkzoAabK6~f96v(hh`<NZmrG_@_LE#v^ zaw5>F;y)ddp7cvsJQiaOQx#ZvDM*}JO{w=HLr``AJe;5jQ3)l`TSfGpRjyP0bob1H zItvbxicKO7eAB%A6r%$;c%_<T$1$u~XRRBueJ?a6YRMP^!Quf~Y&4^pJR`X+Q?h2N zio1^YnGC_MgW7nIe<XpmwA9GF5VQXP&A*Dcu&}yC%k#d+ikezsod>-F7WGuIKxX5} zd!w0TIRq8yo%y~B3xS+73Jrb>=(>Bn4fPQGiushzuU@#wv)J=5Osa<Qe9Brk%itcG z?Zsk|-ox^?P|JgAOZ~gx``B>1faXFt{0-0PwXP~IFOGqV`S$mG{fZX;`qod#%nhc% zOnu#4US2~X*EEJ>+4)B}i5ms%A25Lz82S|)+xp(z^X)k<aw@@*xe(4Lk(DuDFtS)z zz6w?Wmzc3rbJ^A~Xy9t2gUgr(Km7p?vbugP!0SHu9kl!%GH8`slmRjWoT_b!zY4in z@9BfFArNwORAfb*g<R!dG`n<l)aJF7rgxk41b$jEF=@L_f4-mGlKM;Qz^Q}(2yRLQ zt9r<Rrb3vyFh4)YJNSR)^2&);zDwE@8CzjEb2Q&XZtY)T24vr5$?S4L3V<t2>|QwM zh9cU*0%je;vHbO(V83?O7~KKZYLJHhi&M;n1sx5Be%6emdQ8x^P;oH_eP;usFrI$Y zBh#bo;Z7}XJ-|Rb{Ho3WehV7y9e&8N0b;|pQGZ^gHZ$RqZ@N90zTe1m$VJ}gd&or) z2jNQ|-wi_>uH6(5QnujFovMv6XjUEW<!WZBX)3%cOvO00DhdDWhu@<+TeT^MiX=eL ze+o7YUZnW<NXbGS><bJ37C0uJzcQkn{Zsg5Ia{uw;`WRKYPMCF`b4@~aBB~@^sF~@ zk91)WOjQYb8=83b43ap{frMaP{`4?^#dZ(&yqew+yD8GZKz3B3e!Y0`I*;1(^@mp? z(6-$gcaUXTj^FGYMY&NT`hD<D^$@1{fJ?#7y|Cs9Gj~ycJcpbgDaW3p=1hd$u4Ml8 z3>PdcBWz7%eGz}hQIs};dPSXH%Zmt55(a9Y)`i?MsdS>cSus_jBR8B<_Ve3Y$E&}u zMZO%beGWP)o!#Z%|27@RoUiuYrgmAk+9daG1RLQ?o8ML5Q>W~toQ}Awi%F~OV<Bmm ziyay5KPQEjaX##F8)r@XEx{TAlkNkb%yFZ7i@sHxj<Dk3pM#jsXAhstxq=}IZUVJt z8v~q-Hfa}c{(}a6Umku}HIpmnxih2hF7WPYjqp|Ti$A&NOU=PPcQ4rmZb%-)>wWyZ z_Gb$yCJZuX+v>=@{~OmxmeV4pM_&-k^KsaJ=u=jy>RR*@b~wrvUh{=XVR6t^$N0mG zQ+j=3A0H|IEo|~2k)v^@7b$;WdORgNd8VkNMNB<m58-#~TX}HeM5Zl!)g@^TvXc0* zXndSAt*rp=Yh+dr^n9RqbMv@&{1NNe*_`y@acIK5UBM>fCl|%^SlNY(henB-ClQD{ z+f9Pw<_38h{3g39cm7jo?Q&g`6a6SXd+&S4njW_f{?@1Ht`fD!_Ochh5pLE`8T8~u zeW63VI41ZtKkl~QNU2Nt)mQh1&O^iRtyR+}Ms{_p>5-0i^ovh8p8wI4I(BMM=B&N% zIw<F0?~#}Je0kWQ;Bdly{iU9o$|_qoh;dC@L6KMeR$oM8H2-XQ?|*TvwW&$`sTWpb z5*|%t#2O_p8HdHNA*PRXx<R9EDJ`dBGXN%^d_qj&gRb_9<s8tA5<K>3Lu;GOx@*c_ zd>s*q2~1K>#9uK`Cd90rkx|S33S3MzUzm~96_u5ZjK8y&6Go-5gj=h!Jg!v#?r^OC zSWoUJL%TsiPW^Pky$>u#<8u2>9<<t3pC$Y5taE>P>bDuVm_GVTqJKqgQuQyYB<(*Y z7@xz^$4{!6-GB5jQO6I2<sLT(2q@rJR&C_K`VXKSJ2;1LzPkB3D{)77$xo5Ck&IaB z?lafXZ1@oS?7fAFlm`ksgUSP<tH<<WZ(6T2Ar%}sipKQEE2r&VU@M9c*HR~n5)4-L zJ&19#i0f&YA&$mYSzi;TmY8BVPajapUV6mvJ%zi*=qeDbCB^S}?MEQ)oqJ91`stO( zd|vvNP%$I5V(yl3&+N}5*Nm0w6ohDGaOdgQCaDt7`L|t%xh|?Vbid1ezfc~d{|eO1 zn-vQ|p$Z|ErL0Ann@`#yv2y_@Nvzv(>?iog_E!?*4%WJk^rO)((URmrt)g;Pp##!e zhg9+h%0Ww8k=4$I?XDflUNdsf{LWO6;pNY7Sj40SoME_oO87yG<?7$(4h!t$Mck$f zjUyoDB#hI-ea902;;#i_GAZHO4o?00MP0m)t02!RY=Gl>D(3y$i3pQbI*Z6nWDv0; z>YDnnu|lm%;X8nzGu_S@)N0h?w-?4FDLTI=@0Rp(hK%!ltER$-sPrm^NX?@zwP&O1 z{UxR<%6z`c{L8cQ3^i-^Ur7T$q+;c^t1z0TkBn~}lW<z2?xmMxLh(8|bF?We7`J2b zJcxdT%6W`)-FP7X&X&4~+b-428MHW$CpYLq3BkKJM()U{d1B3vw(p7Hvo=75i;+jW z;nY;_SXSqeTOp5NQP|qv{@;(T^B%WaN;jRUFWyp#y)@Unx1|^-BQ4-oZ8fl}Lx&5B zc8i-NUr&L6iX2(2EM#{${|4RW{qZQ2YwvhKjg23*7s#6uf2dn9T%c}zOiRq-Y}0sF zm>lOgQKW$@n0&b<IcQuR#uXM~qWF4B4{;gB{>R<KU$&*G%xO%{p-c6XVQUM;6fY2Y zpe{@n-2nbusUMhWBhPLBz(iObakSDe*I|(}=0X_)cA2-HS$X9(YNfbqY_2e)PwnMX zhUVA41}7Fswsr3(N}UWopj2=7v*Qu?#k0i!nU?-VS6HrWYE<MLSoPj|DCe^abx}?~ z9=^#U+E=hBZkukEo}cz+d-~8uLGX<<a#g1Axtz$W;g5c|Ebrzxit_y%PVyU6e$+G< zb#Kp(C!B$j>0cfEKEqUf@cMO-!>!4{3Cxr;%SS;S%%~i;K2f=L?UpW4@%o+FNosp? zbMfuIn)?7xryqGCP&_|>KQ1&USo8tscNcXvV>j^~>q4%Ef-fHXa%R7R_|h7yBiOwD zCaUj+d^kAUxBp<#EM@%weWkG}_Z7@`8&|_gD-nA!C-H1`P&rbaw$3-R;jt1&E&7!m z`F1EzzFUGWFWGmvs`S5VjmmIzSVR<;>|u4@Oi{<JtDGPvS`^jo;%rsLL61O4-|cW^ zcE+ohR^m!XQv;`t{zY}sDc2ix3jI=|V0DF0Ni@D+!+E_fj^rrA=9|xK#P_2~lQN6< zV(APDXO-mc@#?e9xHa~pK}tb_(oHtHnT}jqsKU&_s~}iZJyohYv7qNDK8Q5AJE?mq z(=eOvr*8#wqcG3m>{a?`R~8V!SS7mcD(U4ChJH(cC}^E9QDTIFqqE2|HD3!qV+iW% zAkqoxLo1ua2NeC)iDwG5Y^hskaf1zPa6sa@v-@0T{tn&)NQU!VWb|>eA;@MI@JS83 zmXT}FCdw>5@<%yl!mch)?a5=uTU8vDj)g-D$v=3QYPBy(qsWT_1eO{fDm)Lpv8=%p z(Fe4Hx76gVZ&?k<msp*Y_sLv+O@FX>T{xpvO(E-5dKqp;w@D-F1bx15mn|guyKbKT z@9JmooCTc})4lr$%)Pjb8LmRK(#Y3(_l07=>JZ;oqVI`^iG{PgX#YWSH~cS>6@Tdj zK6uOW1(Or3uNcbAbggKL99l%##n~WYC)2KhN_JZp-YJJ-zs=*j(bgP}(Q5kA!%5eh zi`?jvIDS5*!*z~XQW3YHWzJQ!_@~ZGX(cVuY@dGz>_<sgg~@AZ@wo)E?$dqzVb;&( zPU~XK!7x>>p4WJHP|0~mB|^(twA9s2T~=tL>HetsS;&&IC9gv4UaU;ls>HzWy9@lU z)t4}?(JzU-+L|&8MtKK_F?m(xlk&*P-E5DUMwdHfr&aPn{GNVWIIcaHZ{&%m2`IWo z^qa8+)3Hb>HX`6gtS{W{<^}R62<s-`!U{$Sg%E*KMx-SrYlJdMp7ai|L>$+_Qq2)T z0L^;?A6;hsRU>{qK00?SthflX(a)(shddGYO}l0sghi=JaL2kb{wPGi8t5`w0^X<d z{4l!F$)j=3gSw@9_r?q_^WhB=+}H+nmzt#ZW^h5bGMKtav=t#c!d$r~B_rK!M)X~e zv4LzY%tWmEg}z>dfYt^D2Q?om^}b;?M)T4;=y%=2y$Hvn-zfhBn7Y&rgVzoW<Q(`f zcE>pK9vnb2$)0;UbtP$oVYhA`@xZ~TD{c+iRL)LHjyRs1`{uB7sAp1<ZR<^E@%!Eb z;?OpI1~Wb_+;bD=4C?$lJZc3m9ao4@bTLL3`Xq_`$@vCUs*YO7AQ&&;OEu*qcBXd1 zr}ZI8z_E^6L_$CKI4Vwpsir?_w~moYl6h_d^-S6(&Fj(b#I*<a)fZE)Rnke!llyS0 zS}golIB&Soej3AflSPF&V8bF*2P}VLPSX!Up3<RAATL@4QL+zEBYXk_X&!txA2w}J z3KzI<ZX%8kC}%M^{Xqt+1{T}aTiUC^36W9zAS!>5;I9Em%?Jw@eQG@ElataWfpLM! zoC90NLah2PvC+cT!g*zArPmmHB^u!gm^*i9Z=rNOIY%?b*d4EXJQ2^F6h8nUKHiiT znA2)+h!SX2J)fm=ccDSd61kJtRFYFdH<e^PzgUS2KK7@l%T|SfBf`W|9dd8V`1jJE zhQqhbZCa+7!;(lvgVbAC)QXF%kpXIcf_j_4EIrR)L!Pk4ogl`*x)2tB9vaZz63<$n zxYCNa{nnp%-srH`0<I=(d>YBuATmv>NQL1Qwn}E^&r%p91&&h|p{SDy8s!626b{-F zne?8A!@<qGl?n8_5lRSm%oo%lC{lC_8Il|GM@;#wVxa>Eq3^_@+AGjG24trMuY6MI zvs8d)PKp{6e=|MF@;Ql*mMtNBm`6_s7B~J;C)A({6RbCrmgbeXMeRNz#oLgb#pe<0 z>U!)(`_c&2fG5%@X(TOKG2KsM+Bt|iZg6$?pyF=vAD8wRilF)g%A|4#ibxK9Fo{|M zxkqbCG4OG$<H(l)wYNnqi6^K>yr^l{pgWtWQ>$mLRM{^IB##fM#bOK-ZX3G0TY$x> zoI)M{JVH6IPzN?RIMXskxZe3vZzN;KBXM6gOck}D&!VN7`$`{RZ)Gk0EV^$ExT?n+ zAL3qH`K;UP|EL3~q5;0F&_+h?S#v}>ueADaCK_5~atQ(-7UtitwN~Nb-|IRgPHLp| z3;XW>qYjm>kGfciuuh_7c$D{PT4M!|T$@N25b$P(BcI;6cG^?GRRDNKAqfPgc1HDw zes>wxiJX}Sl(%Emi`t|j=#(4UpJdM<_r)D<3tP%ZJJi{uwGVF{G}!AAkREOhSDVOV zD~_&p<dwJst}ykojdt%3`556zkV;{>5xsjI^%Xad*?MW?TjboKh(dvwSG(CgMZt$c z)lO^=w~eJwXC2nkLKS9#UpVgh)t9uk*v)My&!n$=iUaRW8Ey9)9>)kJX|W1*miJha zuKOzXwmgGs=5q+&gKp#nw^n(m)VB#$;Sl)z?Kd3s@*|(G5zi`J=8%6sqt*|M^&=uS zFxny((LbX&jzCl)EBAOz_+?_5dyWwfII^z*yYm)p4#VxVNu(79RcdV#(UbE;Qk!5x zd?wnRvuh!$$@hHXh+a6Umek*#_BNltK>CIH8%E7)ZVQt=eVO=`&~<YJkU^?b2n(vG zdsd9J|6bEq$s*w)GR-KzMUc2KSD3zUV}L=_*U8QK@XA=Ssd(`)r`%84u{N!uvoGWo zNJsXs(ClF=pDVd+=~KN7M;Llp_V;NM31lySSM!%LOuuD2s)OQJP^6wl8Wo`<mm-f| zHL%({gAD$!2h?&6rChESAD#$F`17R|BVkqsGbe(->I|%;kOp$rA_g7&4bo#rWl3Q` zrbSthi~2(bq+eMc=b!g4MreDrJFXc9?&3qwD|lyDkm*)})zozFaH`vE+|%!fW*QQm zGq-t24aLg-rKf#-wYIO9HCTv%_%{~NQ(DG-ZFa%id=ZCCK@!;~2UNlOBovG0+$Eq_ z{f5c_-!Zp-&`c)FWROIaIfW3fsFvdOu$*IaCsHtN)2PxX$)PF4h_TsNa5iZ8kdh=S zUROq)NZumbs$?|~oTDv~>UQ{+#i+*sN?s8?C<ai|R+opUffeX{zjFw6r*yRu_aR;B zHRz~#NG=w(I3a5zE2TssJHQRgnn0ECDjQ*1nG3p}7rJpX-qo@*sEuKJDUsc8?iOKy z5L18Zr^N4Dp^k#es7bJ#;E}`T$ZRZC#)RJ^nBB=4iv$FDj6-$+L{N5*gM|FUlLKfG zExYbcv(TE|hZV|Ok|?qY%3JPEw2M*A$&4p0ba!4eG?1g-9*}>NKy~UMWc5+~%?=Z@ zb|)aHuXK__08hWtiv@hHdF6xk6%=DMa4ZhZnvi<Z*X&rW`9`J>EfMAtKy&Mm>Zuk- z=a%3%9wuLRns65~DFPL#;}zGz6H&w>40eyWKge&{%FNqtCgnMz%{?7qnjm~XS-5@B zJN>Q!zn?FawX`MENthQuuhQ%_IC#ps5E%U8y5*u_qh`rA+Uj$H+`*CUA0XbwGEaYI z=2H~f1sYpj%$I?VtIu>QHf=iK*X4V(9A1*|OAU`!ZWl`s-|1e`4j%T6kG=y(inwIu zf2nVa`$)HNfXTvBGoF=2sCOKEWjNY3Z+Znt&Y^B+yx?w1`}xFD_mb|?1^2FwI_-ce zypB?P0(LP$zgLG?b291Y;YBIL-)8~!{$>{Q6k%>}@8_n<3xKK|A$pk!);ug(vG9{F z#)Jr$lP+rA`-mSnsaGF)h2F)B#JB#KxR%tKH+f5w)EjwT#@hKu-`gVio!YFzU(~Eq zql<31>4S$yz!(@yp}q59{MJX<qoRczs@d3qFYyWX-&>YA)h_|$0SJ-20?j|bnaY(c zkA3xjPRd&8t#(--cRdb%{KRaLds+@T4^y24b$!kxQcEz1nT6A>5|}eF^WVP++NfxV zP}m}rMtQxYHwZK%E9p1(8n&VXE&%EpDV8uMP__$V4KHB5vAkt0Xk*Ai;GTA_6j?DT z^q=M=a=#DnkKeS@|8_r=VBxXMjf!%C85zCa7qeBEV$C;rSPXU?&vBn~2ztLjqd}@6 zUc$5gYG$`!d!~Z?A<qA@n^%uVxpY!w-)WsY<cAGHb?gW^3xL{4E$1{pR*Hd_QXD4_ zk?-*N+E~~-JW}D1M&a-U=_&~`YxwcXcNR-NNF~c9(Dtv6<{!vr4v2w3r=#i<&Av+% zpQ1|3J}wSktKUS)p4!`Ks=ewCl)wFc&xOc1k~<Q6h}3i9*pMe5cX??0RH|!{UFjE6 zft)H*99c@)tF;=uSch~Gr|LgOe$gp^!a;k|MWa2VE%lFSZ36MWm<62uz4h1LMmBXQ z7Bx^uNvw08jZZP2W@e*9Dm_3>ic`mPL*43NL3NZou=RM`X%kHS1t`F<(8Z|y`H>5w z>(sR$Ak@#p?LIU=b0bwWEu92oh2_ypsy9hiVFC9;sGcd_t@OA%(02ET{;kzoh~HmH zFyWoNDngyH@9Xm5HRJ3dPSk4y=9<`)cYF?Ftn5e08~-WPHG+Q0@Re7Vwp?`l7VTtM zQ>%L}`kZH~@?|Tlav5O8zyNopiJu_CCdHrdv?8eMwR9ShVKyxNSmXlUj#h`q?mM%r z{WhN@VhHczG{o2WIWb>DuJg-2RoP>|T_yI+;!KwyO3lTqHq9OyHj*?Q1;Cp8`qcE; zA)1JOSDc-ykxd@M@E=rW7yqLEO_5FpqhjgGuniZxo2lbxO&C4$T@=uOdtuu7Ejbp& z0)nM{Ishhcjc4S^=?hpSI1K3exK(W(%&~83ku1N0^&=lZi6!%^=I?f@qrTu+(2{34 z!O#6AYo^8!%JfIW7d!m$+m9w_te`q2-_G>OpoS^5m0_M9Zw`bTYks!u?U}zF3z8>O zTlN5GEIk`VXO@3~0Wdic$!9#VLh5e$A5m2tq~NzVV={6rI*(szuczLs<<pvM6qjlO zgXRsiyx(fiNl}aTf6{hHR5Iy4yQzZ5`}IRI=zq(4zBeN%4+Qb+dI=m+!xvOY_ItkR zQ}(@-zf4Q~76OJv+Gj+%v*zkb$X@?48xJN11)1#_EO&aII8>asAg=fM9Fo_XX-x5| zyZ#DL_33?M_Re!}?z+vz$>uxn^{daJYp72}pq~&I2BFj<IoFe$ZRY~Na=+)BaYAa; zopZ3!bTt$(8!<7J&>+u!=dX(`qjP(Oob=Z5c>eepIjOyNf3qD=`{1j!)9V@eCh^nG zM8h}C?LqRp6qoObF8_RwiNnl$Ly5~Jfpf9%wfV)c<9@plO4VN!7E3^tmg)+Zac~?* z$kSKX+g-0nouy<JMVnQ}Qx3Lh&&qODPEuEBR2M{fZ;aEswV;Rj_RKkD!*N<=42Rdu z!N+{BWjIJB^D9qTo*yZ{lIsSU=tBjsSO|)ROlTj;(`L`?=euqtS*5G82?^x1WN=g} ziBW}@^QU>4gh?biC^>TJLndO;M>!mWGN0iWn%RDzG)vWk7%HL!oW5F@bGV#UY-TxL zbw@TP4nL?;e7Rvi#_OZMPzrbWj=6E;!vdQS+OO4Mk3Hpr;Sqnrb!!2DmBw*XKAA-; zHaCCaFp7=H`PhGevm`RB7HxC)T%a@9i=!b&P(TOvU#HrmG$G&q3R|tchf25pi^P|B z5rSvVqgZa{rwj-M3xoBlvsB(P@zM5HHm3Vsxo)ue0;WtDNwU|mc`v&Z8>9&9z5*P6 z;qw@n=Hrx2@wRfp0K4h@kjM>P&F@>eFZyM4>wP8f!15@wSJgSa*&e>CQt?#q$qVKd zD$eg(-!8X~AjKLIWnhQA8Gdu~^|VSm2GAC(lpnfQg;b#$i!yAPy=<OyVA<~lw4q!1 z8EkAa@<C_dif?W%u@vYaP%iU4e|C>%S#WY&DcWfm!9D$aH!!NYqRwFVr(;A`0%!0J z6>l6dxIAPHAN-*WkCt|_Fp-QBdoeANgzsVbRruO$H{Tm_Fu<8UeFT%rcpj?LfC;Ej z=Qx>FV#dtQRM;}fG!@v=%Ir`<XKp79oo^G8N;-~w6H5iQOa8fL<#qVCG`BdJ&}oah zknfOMZrcxkapaE(k>KDFIjQrHL2&KtVC;NUp7EcMP4<>|-VGu<&%Z&jd5}Tsi^%ng zvRv;SSKgH1Q7iN>=|0Rd1{=JEW8aY;)#IV4Z&9dyJOp`4ams^=*4gBW4H<MJEoQu$ zic}m3YOouTofY-HY?FB9TQl8=7o#C8KmQJ-I$McG1ibWQGBtF1>P>b}{HN_8wHXmP z6xkWB@gMh6ccj>8L0rIkFY949r9vDZmCuh?=yTRZjp$I7Z_y=ObsFljcHO9&R)mjD zWuZh4IKla>@0GIeBjU3DD;v&8_I)2Eu_Lk=?BE*vK`RS6`?N5c>8HTyKbZR0O+5I$ zvOXyWCiPb$VVri7+czd&wr4f!zi?&F%esD1a@qvH08841EoeeqdG-w^iKL)dU2PgX z^^5W~j5G&)K5gnoh)bCIR5XR)Xh?!Pp_helmJsl#`_;~|iq$9A2M@5%<J?;(xj-os zY%l1_U-I>`Mt&dY{mRoFb}V98;HoTkwTkHDD@D)fE89h45#CL`Nn55gEVjgLfh2La zeDuuc?JJ9D>_rhLVwijA?0!noWs%kqP<VSMB-ho>lJ-h}0C+}K_I2+dUpF>h-peA? zMEs}EWier>Z!_`b7K(jng+eyxK26Tub&ig5a;{>?gWy<L(&vkzgp4Fq-~_LeX%n~p zuP}t0X%XG_0rXD)YN9$5xg9_?W;)j$&l6w9xl9<~O~z9R&#ZA?vDiNe=B<~CnGv~) zrsK=QB7CFQ_&JZ$!W&dkc1`+EUV<}(Y9^H&X`;O;?LSR~?ilv>ZE!V;V+BlGr<@gL zxo?aaeTs99v9Ck0gCrk#@6;y-){Xg?-2TF`RQ%r0TA6iY@bQ<01vJsuRGDjfE9TL^ zLyn@s*WCBE@uo9%GNid8`U<ZjriG(!{}A>TUvgbZB{{V<QV-3?Ga!3&lG0|dm&@-p zl$Rou?nRr*wd>Q%qvp1V#S5!?NyYRDYm=oTop^M2#z%?oa?c7a!qmUDMoLu7#rw?k z@!D^z-}Aef@U76XU6-vgrAeUNdXJZ5u5MEFwqV-yb!D#n723omi3C><E6m~+yTS}1 zlD(T3owPPAjZ{XlSTJ|WA%{3_JK`BaH>xyz$ZiFFPH^Uq_FLtSY9>fTSzUx(1J3dA zL`8@a`ATQUg`lXf=^ei=!w;sEPi2c;<Fzx^y4EMqrhhWi0)vQcPTwZb;_82=DpRev z{_0cmyClVbka&b4`j7)(eXBxh*DMat`lZ<TY&DGj3+60T=f~?qO^?G~vCv2JZ*U|1 z>_qNU*S?ZZn~?N$(GvU+=MmCFvofp*u5j?u`go?SeC=n|=f8)8FMZ<_6AsJSHU`x} z$KVKQavTaA-P=Hw9C=HAmCBRQAF<MX?U<A|e7AAuNg*$a=A4(_0tRUsIY5NKl#uRo z5rX><Qhv^ap|ffSnyCs)oHrLSqb#s{wSN<xQ+dT^c2_8$sWJGf%)Q>2^zQW*dO1Cu z%`$3E*#gmbwUJkz0OKeVLH&bi%jN0q9zH{ig$aaX<#ggW5UEHoD5i)ner7QBEu30O zHzhp>JwuIE=qiZ+wMB8=g%;Lv+lZcbDSEmy#Pbt<#Xaf5BTQXEyP_XC3XRd!lp^vN zu-wGllr!7&@I)oj@UWf~2g+5E#mu{>Iu<#p@40ie-fMzZ6bGxullhK4Wh;E2un_PR z;d~}L=z8W5qR$-}xBD#Z*XxM!rBy8h=y&QV{(;Tdo}SkMRkuaXP6n%f7cpx{YXtv& z<eqm!V_km7EMLRFb9p_>gl6dZ4c}JAA7bpCf%}0({}t%7Psq`C2l2rH>jKZt_uuUw z<q`w7)QM+b-7Al4f&=$#pZ#0h3_5*Jygb68FV+OSgU`o;gO1CdUGCZj|63vkoeey@ z`dt=$`7@Z*aPW-yZ!?&9Nel+jV8I+%h$xm!9!su+r7*=(I$@y!SXdmEDhCVqkba>} zM^lYO6xR+qen1@4zn6}tqUuJ8DpIp4(l>F_iNYAP6`4iZ7<T1C%{#(iu>alSyaft^ z`~ZVsL=YK_L!*w+9R{NpHXW=h=#2t+wQ@A-c|Hm~ptFS4)$<M{qLo8Agc|sUQurSf znpQOY7)oRkYR?&J;2+Dr0rfkiYb+bj$A-Z<wVKK&i!{iLh3IkWAZE?~u{hsWs)`sk zIxG#pt@`o?*%F{R$WT4sXjkT}InrFS*y56sCKg?Co$0!1*VfWV%bRbVI5KLqPHWw2 zZ#2Eg)6v$$l^gg@ClmITh94stH{@8QeH)m>tdw4%b=&{P;?$(p8Eb#L`=!omBv1EU z^Uqmu{~kwnTg(2pt_tUR%jXT)>so~>R9z8mzc(iGwG;mflx5?$%ee9K!;<gm&Pv%U zB1$i)<NRoAyh?98=>5Mx2jkiywG@sA|6_3`3X)I@j6jaQG6GVFT?v8kN3Vp!?`RN0 z1p2sF!*A=@t>P$dmKTI^IB!`*aR&)nM)M`uS;h$Fm0L#9!3D_y+qn8~B#RT4!{`|? ztBfMog7y9{ixVCbil^_v^-$}4An?&hFbMrfeQ5aqTbw4(5rQ2oMe){Y_BM|_PfnlV znEYZ&Qn>kWSP*Q~7X+c;1A3@sF6P$rag@Sag#XRryt8AMLI=U9INSb@#rbeskQ}ak zcX%sNrUS4A7pG}CK)4UK%gU;6w(TU|?I9j)R_0u>_9lr{53koW4lnGGEY8K^kQ<SI zSW5@_tEyGAW`*|%*g{~Zym&UoHjle$LV!k0{-01amI+=GetVs*7su$fSe(46w*B+n z0snAC@uisK{`)hY87G9ZjSwb<YS858+quex{cdbC;h^U~x;7W;*1OdQ?GmDK2On8@ zN7p-)iZNCnxTE5PtY!ZYtUE$Nv&i0382dXkBZ}g-YEu5YA5FXQcflpqms~uCQ}Cf_ z7&>K(7T42Y=oF5=-6#5c`tTEVQCxr%9q1*GZOz-DtmUl3R7T-Zx7?D#VcY6wohH3} zPI^6qlN$YavdI^_lc7Ld-A{K!U>eb}Pq2$6Njce`*;zV?EY`Q5_KDQ5v%qWlG$+(b z?6l%}*E<86Kc$>zDT8WY1qXs&*bCbU1(!l~)Lro@D4_j&saK@LeTR~_^}<pGMeFrT zu8!lCYyVmwbFfLA(lPdIwXS(3^17>KUfX<_`cOwI-G;e}h!@MD)Py?3*Kx;B1K+!d z<?yv0mu@jv0Y$7^XoD13d@e5|1n#~)yg1FDWwAU<+~yw;x`r!apcnjneE+uer^{c4 z`RoxFM_p70GWJFiTOnwcB&b|mC@oexr0I@vJJXqyrx$FAdg|mI(_LX7TkcSzjfQf~ z;MP6G#^n?J3CJ~uHPlB~7noT2=niEeB3LmQ|If)HD&Lg{1t_znn&ZRXUh*)1hT%{U zmF^|iDxi34na_h3$HB4{t)au44l9;sojr(mk=I(6eJ=fEsfGmvgkPuAP;s)?j#u1C z3-<%bO4+^g7nBCmWbu>I)EJPLV>cxtQ-mI}#@y{gDJ5-iFQ|eVPiUIz*T=s3`0+5c ze2;4Af|vZw(#r^M$4C&!Jjx-X@_G5N;)zn5#)r>1|7BjzvZF583zI>A)irhor6lM+ zYk{efcqqGrestH{sg#aU{?~J`a0wbcZexuS>49y$jVIiJ@%O4IsZ<B^{pOR!9m7q- zlN&5P2h4pF%E<pFh!8mj$%pG%eK(Fl6cB|(mcF_OG4cVi2wxX(gPpWmQ;kU_S5Z(Y z!=UNl&}70!|2=*=fsQR-bx=lX+Gi{lvV5-Y+2&#@;S+Ltb^`e?SL9(s@*@OfW#pQ| zv_Hj*?zW)tT7J!kd5pT11R6deEeags<6-&3A=a$*g8GDQ(SBLo$^j}GR|t1k1yZ>} z<(0|HYMC*iJ6z4hKMb6G7vgsDt*k{Z|DBLF$7NN>mipwpnPRLpj*Fe&$T`AM!(YM4 zviEaU71N#CqT(+D2U_zF3>jhOJEn#$e)koc%^?`r>-)h{lapCY`Yp++1HvPZr6Dfr zU@iUsWpOq)!{`ctgR?Itq;jZ<LGV6Ag)ql-+B~RBvN*LD*KW2b_TB#F{{LE>E$su0 zDXfo2macSd1hnuEQGBY)%$Y46TMBRdre8hf5-ebAWatuo4vx2#4?}kuzX_Uu_wDNF z|FSrz<(^&>ETDcWZRjm<AzdHN53(7oi<BB&Mf#uh+5ls;b07pr5X1%tVL1q{;Wu$1 z2=A>#)=&6I!1k<&`%`^__vjk>-`M~b*?^DwYQY+DMnhX#mmF`D4hsK0<Q4P(S)AS$ zeSP9!$^LFi`g?0I5%X@^gae8W7mJ&o5(z0)qZ@bLofF4g5*l+hNfzhg`6pxiLGtOS zZM^I%%_3>}pVJj*qNT*d@<+*4R+4p)z)Brw_}heK4A4A1pURkBV18_xsF-0+F=`G5 z>3|Rt(u$(-X>rC6m)3RO{ry~*FvOgrAE{Uk8V$ooXhvXSc#Rc5ry_ABRwRp)eUZD5 z^*3#f_=at?1#o=UN87=jIcWTEZthcaeWy8vKy)|!+tU!foe=6fqS+)c?zryl*e@>; znH%P<3k_s-p^Q#yH~OfWv%dWN74$E==-CQ2bDayhM7AHbUx>FYdEu|2jPq3+XX)qM zXxA9YsPDGU(*4=Ihhk2qbBIpqk8;=DqO~v9IEm`MgHr#wr8#n}aR;9div2oztt`K> zW7syTyL=e2`{P^YRVXuFCkK?ey7io8L@fmEQQDa8`k(h(_M-nzDo-=n4aeJO%N{3s zI^{MH&!VtfihmkX%(yKCqUXmF{?xrQ`|0@d-Qvf)__x!_zh0tnOXFx<TbbFu|Ed4- z&xF&q{mWm0r~l?opZc_OJv|5(2>4DBeAa*C=}~BBz&tzGd8^*?{%c~u=1-*Wfd7Z% ztWCLvFWr7#b!)qIiSPGp_5Lj^Uj1nufB(yS{NM7wtJ5yjhl41+i|_2jvq8NNN9p4i z8*;?+iNp`bWqOx8Pl$i##y|XN8NdAHPyDxn>Li{G=v^IU6EC*(I{$tdzxwlzczKZ6 zd9kTS{JTiJIvel2Ivpoo{Ue#&EI5cXj@%eW>4Sr1;NYz|nmHWu3<t1;&`F0d7>6+V zgs^0Uu(gJea_s1{5N?)G9_dg%<4}H|P{E8);nq;mxzOupq2erIH>JaF8He5R36stU zBjr2g=fduug<)C3m88Q}jKkG@!Zk9&wOYe<=EDCw3)g3fxGx>?&^W@-C&D-*;&E$) z>0HFqvj}sRNK0uFvKeXP6KR(b>ChVKG#BZ77U{wg<t82FVI1Yf!r<W&b>R&!n*i<; zqKLK-91E_h4o;>Bcfx`xCnd>}I7^A*(MJPOWEeP@JDLm(y~_;*6Ugz>!4Y=wL_wgS zoIIEt@WoQxGAB>&iXp?q<hBM?9l)!*;E+{#v>o8(0#usABhO-YjG_YuqiW6J_st>I z#(*9-pmhL$1B(4H7(^J1YLW(gHK1NAlpZUT0a&temf%Src%?Xi#sZ>s5K340r@8nI zqv-c6@dSF1N*CmqKatXcynO;*48-ne1Vylb2zKxaJiKNC4w0auum=RhfxoSZ3j=<X z;JEH`_^Kc<S`O55#|94KcLw0A<<yF)0NFO2z9Q-KfZriN!tGGxv~aiuwJ(T5{yFeb zA6|R_=W7c*Ch8;CNlwrqJi;8{HHSeJ;YIo+_%A_fK5&%)lyJkD?E!KjKs_^cc+*c+ z0^W#?AsK}w0I0+~1w8TUVNAdQ2n8ufMkG;^g`|;Bz6Kw_%~<gPg9(??X(KJjwF6*( z1$BZ29{U1S0KP&$9c-W8@13kLiQ1h=w~zr`sM0O%Gx|62<cA1`0_3iXcdAgDr%>jg zx|a|Y?G>pwa0rN#iOU-bu!f@6a6Vu>b(jmV&ke|HdXshg39)8@#j`48GOIT|Aq7Z^ zZW;;$B*S6$ZdZ0q9o%_7`~9Y0Z3~jvmGXue^c?`Xx&S*}DEg3Wr?%IhD*T0r+kQXv zk=`vS%_cyw0P=(z6%3_a9?JerpVzAHH8F%d>Pmr4(vYtrZB6nZtGRH+%r%qTW2%52 z6CerzT~2s|#Zg31j%`eup$x$2S1_@i8|_PIKSddP11IL$Q>-BNSYS{ylU$K-Wd6E# zsGz<q8(Kga(uMGlLaky^Pt%hJxBbNZvISxR*>>cw?ZQR@RGbOm0DyMHvzM?)5FDi- z3@~OD-pc}NYzZoC{v=_KJc%5SMQ&>X53))=84-TfA=KGGcszj*o@1a@I`t)svOD_) zv~2pc6f#Lkg5G|0A*r&m+w99G2S~33Rr$rc@!T&n#s^0fE*~#Lo?y%DzN9~mDolU} z3TPtJe1XNTbfS1^I$PkrcsBR|wq21N&sI6Y>~*k$BARFZ6bELwbAGPmR|*F@w^Tq5 zDg9*uOLedPwlaIast-m4zbGJ32pOnVJ<ME8*v?xgRPV^3zKa(-vX+l7__q&v*M7-c z#silmI<YHTQMO?IufMfXo*Emd`7y=IiFA^}xTlXA-^umytL?PSA)}=PbECdgBwvet zGb~k2BMd~qD<Q7}jM+dJSk$t3t^D6yD!Bl~taNVK`eF6VRcs|#A9~T1LB!RtJP8mw zM=c#7qsx%Q3FOa}N?z@Nc9S$J2~^GBhL1$4S^?iT@9b;uum>DsQM<9g$U-BZ2<n)- z3~G`0ysS~>iGP$ZfX8|t>LY(FG<CJqLBI_H6}5EiQFQjf$e2<HEv$H_(pWC)Z${Fw zfY((UL2egm;qdmOFsfRh8Eg*wDpZ}O6=m)l{B)omGD)CoZ}B`!|Gnwyqy_9xy!GB< zpsdGlM&&>bYc7ZKaKo)((#gAJ*>NV+Ju=xDPoi8wFfcYTo^*~90WJv1`zwB6|0o;* zn({sU@D%xVh0>7?w0uyZ=NQ=uO32Lw+Rn)DbwTwoK;)|+;h_d1j#`;eOfmy;j*-2> z$=h=|V2~#m+x`$l4(W!J5*>p+`FS(RdD#v51*Eq>i7t#DfOi`MaT<Ucf$VT3i1ZtT zsLXSH70Htc#3@7luoTDtp8QhxqGM~_5l7Yv7q?Y>Fqh6!>`Q`MK)nc*$4_E$teGoO zb>y@SP!14MG_o1@9+i|!PTRpQ3LG3D9@atqjB56<naTc<3YBeChZ;EiD~Lrx?h2ew zC#Yz<jkJcRq^)+6eg(%Q%C9h}o0FNR1sU&>mh^8f{n`ZncH6=d$icD2I3UdjkN+3= z&p!<u`_WA!9gK&QVN%HqV8JW>WCh(DEe-eCdYlJyy8prN0U+yRc>6?)tLVT?)CV!y z#-Bq?FYTyDi6%f72@?fCg;;oT*J}+SQfmXv&IF>?e!yufD^wmZHHmKAirv{n?7I}7 zVCy^t2VKt7N^uE9mXTWHp+zHDh)YehXjE)<ci`fyV)>wC2bjm-M#+FEZ(C{u%_M?V z>eX40{Z8IZr~VgnMR!b~0UT-XqkG&I{ly-W!_R{v@#MF5UZp)ou6AWa1EAy%_?@^Q zk5kn2zgSBFFMC-yq@ei+bJpH=6}YS0J31Q-R6!)jUQ!K#apS84UM7w}?U#2R8OhI0 zP~Xg}LMBijvGCOBi8b54i>~@(0JWo0wj=(rX5|Ch&%pl2ABtswD2{gbvqqC$gyzJX zG@^Z)dBqrFsO$4~)=%+|mVV9dgMKICNQeUPz!bTnKXJv<|22Ks#y6$ntM@n31{DC! zh|d(kk#W9L4FazU2WJ!y{ivy-t66U`vi%-seyi9%(HCh2nKLzApC3!rYMQ0kb98iy zG8~&{x?sJR4iLHy1z@(Q!OUcCGXSxJRAg(a;{H-MkWjBPa`zDS_5e1}K0%o@oW%)R z>neFE*tWxsj4%ac;lnNIGfy>N)$h?ucD;eFE|9H~8%t0cV#)ipf#k>DKVE(8${Y@6 z{v5Lz9-N-MXbvckOr0Febd<rH1c#JXy=*U0>r9|b0MthS6zj;y3esp4%P)w8{JX*> z6I2nk%nfV!)*aTm0~hb13s1!b)VbqCpoZF?Js>y^FpC3R2n|I$C~v9i9^c|N5Eaa# z$12K8Yk0oLWbV3dIC3bXS!<$8$SX2%4q5T_*=DW<^c$U`8o46;=Oy4VfLy^RBWqgK z|Dv{X0pim5I!SH39zN)sJiVQtd7$x}6Lnyo9AyS{ocBI#Df-6k#c~}8#CL$PR4?g4 z+Sh5PO@L_ck5}?#<+8QWQB<Wdo-4WxIXa<4anujF+V;#59ra8Zxk)N;S`q%+zzBrF zJmHuh@FP%%awN>)0U?vTkJZ4XcrBtm<r|?2Y@TOlv;+pop~Tf`$F?7olRvH*zpWKm z5E`DRFj)58+`4Sey3)^W`?*RodJE0RO?`nM8o-?cs=bbniLmt#!b_DofQ3MA{fDwF z`#Q==!o@c5b;YyBq3?EUZQMNNBis;)S}l*AeGDzHHfmf693fYvN%{IZbuO`{jzg;p zIyVSyi;n*<DGFxr4H{D7{|TTR?V_+qE>b{wZ&L3i0C#g|NaF3<PUz%Uzsu^XN0)x@ zMv!l)eHxg{k5=Z%4ay<)sfFgLV`sx=qg1b1pl!yTG~F9dyLWdHbG{;gDko@UGXH*i znz)8HA}g<Gtg%^O#t!*IVXX9V=0P&-7mH381f%RhT!HHe0Y#ue`thz-D%Ac8ve}{P zl?d>#iyREVTD~^y4VQ!>d!|N1mZ?x5<AKQ7BHjGe&Wh~4gA|I95{34od{~>T4q(9r zx~&Iz5)d}^MG{WGx;3{SR432oyl2rFryN24Wm{vkt586LoW-ZV%OcNToi;FgH9rPE z>UxRmR*Deg$t)nqePGCGZ1RBp%|OaAP{sT$e@Y>1y>2;U8CQSZ3!XF2C;L70rT@hO z>dQ6(D)I9Tce<OxA94viS$8rSrt!5!pL|UEhwDIwQ~CD^gs{m8lEv#-%iDf|u-3KJ zDTU$~LD^8vq_Cu!pN}M>ev9Yl7EX*%5)DY6*k57vHx|lJBx|X?_op|=fMafC9@p2J z{C<uKxY!Ng3m3>DKgJpO&aj<!wQ~7?TAU%oE7nx?+7;2zBZ#qehQXRz0;fU{IqUs( zjpS=mwQ|y*@-@@M%szylyDrK4vXFJq&xzusbC_Q+kuzf-c0VXHrC4#Bh{y6kLZ~>{ z9taO+-d<&VC{U+`2W3H;icVcPWP-2e>Z@cP{e0Z~VyU6Vr1tAP=-XEcAB~CpR*>Mg zD+-Q`A9CI-ftRK%spgdrA&)3Px9|~NyrMp^4%0$C-2ECzH66#<GhGr1N^y|>g-$8P zM7cAP^U0q<za!$#Yx>rPyyDR1xiLy~$IsDB$Ud@Ipl-RV3Cf5P)xuAAF@kl-%h4+u zI6kn)TefRouel!et$nN#+CS|8UG}>wNB?G*^D+8I$DIF+7?e1c-CG3ZaNal^VA8e` z56=qz@86g}-&vTrQh3%h_3eLKj|WpjbSCkVAsVzA$w~~u6t@7mRDJ#nO5uG>%m=nD z+S~2)kzAp6vTs@$yw_cu8$XQ<z6H%q)~oYkit&W?gkJrEO*)7!w^<LpY9vT$Qk7st z{<vgBFp)-R$cH?1;6_OD$a+kuVP#d``Y$rc|76T6W6*vMfB8Y)%N!aS(wY7)|0z<? zM~(ab_ph9&-Or@0%J`^<S8xRMSaEVv70M{2p0&~@q8GAoSds>sp&_t`JUym*@W{xl zyz*s_39`V~Mp&D0JY{v;=<VKK3}H=H*p(3}!#5}yt|b#OhcK9VRP5PbZ;(S;ifG1T zAlo7!zpq2WZ)`eW)APEW3Eu_@v)!!a@WqJ=YPx*mthgI`HBX7fGd!=B2<KZ$?$xGk zKrI_yRt`O3S*5o_g)d5+@Pu$JkDG-=a!0c_&8ptekCwV_pGzs@Cv1!?l8pXlRA_BT z2$r!aFa14ixyj|lcT*a4ThxAI4Fesn(nt#qswmCW7mH?h`|P?UFBeGJz8%*u6fGa$ zHCaJq_#{p4N`S#)wdO2x?+kr<01dqn=ld4Xb+@A1=1Fl@vxH;`Zn5-VQQXH5sQoYx zx^jm54gBRSC^EsF)OM5h+i(1?EcOY0?IC|>OV;k@yx^qvlE%bX)^z-iTbWl|3*P|` zq&}kIf<@9n=I*E7*YX|Z9ad1cyOrm$T)^!XeU;)hLNrk4%%!T_tQ-nd|G=HQ-d2_4 zvm)cj{~r9vWH^MT-cP%Vibv)=JRmP-Nw)Xz0H<qDeabk<t*s*Oe7Im!H0C|jD5!IW zc`H3?fwl}S1rC_L*n-}1rO`9Xa%0YRk;DTYWiJCoCPBJxXkSDzhhnDsJ$O&{>i{w$ zhosCaWxjHek|j;_w{jCud3RzRLm#G)9kX=y|5SC~|5X2h|NjpT=h(;I>)5jQ=5TP# zY$qXmBzts7g)<!cn30i9_AI12I5uTQNQg4h3sIE#_<Y`<%Xj<(&tINDJjdn!xZdV7 zLgFfQEmlT<nb~*$7@8LT4n-U;&vdgMTlhXd-pGoCH_VqE2=1*<s5e6ydBxfy+$9k$ z?6#DKC{J^WHfKpI-=XKDH=#dKyf0kT1r%w___k1pn`;n&HkhR1e(N?5<09|eAp`e& zKo#t3K~4w|4K4n-=63?lskc@L4&fGYs}LiIz6;J8l*~Lid_sTQKEdxE`TUXWM~y2X z5)FCS0DB?|qR_nQJ+QYV@ok&HF^+bt5d!n-iW0OJh94K__}sn_9{{Y@$jSX-gGD-$ z+-Di3+oXJ8FKh^lQ2|KFtH7G?7Zs)%jUpQBgd~ZEf~lNqB5sQer2e8`L&cZe7$2Kd zk}YCop3UN7@JirP)t1gnp(g296^$it&x>!A@w{sU5!j>t8V(KSGCZxl+H!x52_nId zy>B!o7<<!3H!@!H7$pBMkH#k^QhOg&Y7~9_U6?*s#TzDRUc1YZWPe;8+nB7E?Um|) zrz=uZF?~3$*!fw$1G>k>Z|%2B=pZ$wcp!xe-?U})Et$s2+t>fbd$nej%Qnad?CEW` z(bus7xo^Z|+1z<*n$&$$=;xV9_;5mY?4zh$O?skSBTnwsfOqUHD_+)VfPrW4XM@jf z5|vF3q<Gr4>7lFlRd(aK%Ba<$wwLFOVILRZrf$VUyCEr!WJ8ANv*fm}v;ZHD9^S>M zWWi>Krj;!lm|5&S9R{X63Xjf?q~<!`!X*j=jLGB}wfu|9@63#uv@BOMUKYpK5zEb) z9Ffp%OXla9+J+N~YNqd6r4<={yVTL^$A+RmA)q^t42MQ!oifYlus0oQ<bL<ULpJqu z<<wt|zx@y-b_x?Tjx**6=KN6d4>hO$D0}P=RYw+ukYr@v@_L!jsesRE(j!nJ%NpN1 zD>hy~=VPE5X0r3edczH@7pftlb5kKr@_CA7c!P5jN#(y$v-`cU%{2{r_!FJI!krCA zbe$034Z`Y6&6R({!8kHg_rauh2^~w^yI*|!`u<JKvsKU9HZAN{o3kS3Y60EGvR%c; zh7t8|wye~r<hi7@xPQC8Fp_kX9h5ep+pyC4v?aB%@S~{XBf`1uV_;%UyRhWRr}oP< z!%Pn<RpSVoK?55>`lr0*$zCq-9EDnujIi1T1CG%3%n>~ntPFb~<UNh|)6;I+*#Xnc zu4>15^}M9~C#Q3_i>joL8<RA-eIf3_bWw*p)R{jG81jmZWcd!dT=RGiXzo0f9To=j z_a#Ww8{B&!x0x=U#{!_NEm;0${2L~MEAQ+4V`11^K&-bR_>1L?y|B9fCgfocNc2N1 zPtbAkJ>iV2p52vo(0efD#s&nH=2hWL4N&eJN>2*qvb#eUugd(rjIxMlL!kDT!$-Jg z;tBi_*^_BHs^30cF}z!Hnb8rmegmF!3Vg5tP=FH_573ti`ZdEkiPepaWdu5e?z7d} zvC>)fRj@9fohQ3mog`i6?8)vX1!{MBpvBlMJV{jQd+7HKzZZ}`;>qu`b5HLlhdod$ z)?D6hUbawF7m8U^%w(p%{rt;=ACFt^@vA6qN;_*A-3e!v>o?UQs<{m(Iw7+5gqXr! z4c-oW&sf6u_I!!CLs()1q&@$op||t5O52T;Ky$J*%J8+*lI91f_lY^r@KSfl9b#`I zgc?b-S8zjB?;OiJdT}`wNZ~JY!TpRCaZB*)Foms=1bG=JJIm)k6X~x%$&qV{bDId> zysP`0rZ%On5%XQ=&7(gZ_5W7Xz|HqZv~I%_!W>#RpI#~#pY*ppx^(*R6LkKz0LGeF zhI>W8UwS6PnZaJSu%CV^w)DTfQK-9J*K^rH>~hW;9n^^_0EOV$!g%n@`WhL8-2NHL zG+F?C0@1$pZErV`BT})*pdO%KS;btsItTu%^$HMAp%qWA6-sf<UQ2|rI?5aTL-&i= zEAT>_S)nq#t9Z8V40I@&(Xo!5gu!lQlAYavtV{EbLe6g%ut#gAumLm&flg3Q{0^bK za%$I;#^}oB4k}Y*t25(O!SQ~GIsk!I0*)VpfVIxh3Gs<+tz?PdF3-&Y4R6wT1#K?A z#-KHed$Wm97LSI&)kZS_f|R~Og_{8+>&TXZO`PqVHWr^Y!HI{l;?)JgkOY|qmZ4kP zvOmkEf~_kbPeb)s!Hn@~2@r$pfstgN0h=~<q>joOuIKD+{9u+Tnv9QJqo~OcU(tFE z9ROLZhtNnec7IJIFkMbk>}%j~xV_X*vKmEiu|RvQxyR6`JlK*K3_0hRMi_@HkHoPy zMb!zOJmr7DqL+On#qVyED1rEF4jZ>+h?^h5P1e(h6nmxd-5aNXO`@;R028C-Qklrn zj1vi(=OBy$ejALH+tZ<!#Ee=0?}VoWo<b<pNB|6gf-`^YK2LB*WX_x3=*_!g))`3{ zP0;U`T!oj@0fq^R5GJj|<*}N$_9!9`<oHb@f{Velsw$Kmt&i@LqO^0zIwJCogs{HE z>urs8E!_M)+2AVY^*<930tueRr<j`J+0#a2l)-P!Ctf%5%=$y<jzEu)ycvfWK31?( zDCLrEKGozz$JWHi3Ev|`Jwt#=Z`_bWo!%dA{F)slF=6t3pNKCM>nVsW7sM`drBIJz z6nZBxp-R&jOP#x~rD0?;M;1Sp(q<>|RNgw)vlB}|tE=8*X4mzOL;#bk^^~0;*3p_c zmBtrF_ipE;^fDH^A_9K)g&&PqXjeAhJ$cvLUli|QnE*y}xdZzH-j%O+$$C)Q0;n<? zoBqqa*;-hP!m~NKV<o6@U$yb4E?9d(>|OuYKE?0Jw>kf6TL`nJ^k{?C1uef;jeBUM zXtz~=R-UHi%e9!Gb*$5K1Pj~XQ<x!%37iQFE*eKHV7q=EH_|k_19U}^^O6_uxs)~~ zkAb-3Wsd~KB4+p(@}w%E39Xb|mi-BMW_Nj@@MyNv^dx3}1^|Ex<juO=;uhA)k0Ghw z*dWOz6C0CfB`NJ3+NgK5!E&^Kn-Yo41!PyQc)_Eebmt1M<@4+={WJ0k)D#ciH^P9% zOAy&)W`{ZUZz=CJMCVxpL`t5jWdO21Xn@r^rVX(3i*-<{baM={FctC!u`vG+m2_WX zf<+}c{17y{GH+Xwe)WJ_e~5NOdBHKAWvQJ-DRSW!{q=s&O#2_0vXS0-+hP68EIYKR zjYL(lyx^wtVY<vXOM*tpvPg(_-V6JI=<b+ZpjPs<(|_p0%kHsk_oN<3-95_1=O`AJ z1F&32`X23KWDvFLh6;gG!qH(76~xgw(~$2DiWYK+S#ZLRb`{`34FioPpB5wkQJaY- zPtYJye8^B8qb$G@7K>a$Eh(ifU8T6D*4ZOd7myjm#k5aLZl{_PDYgm!kj_3c=>^Da znU8rsAM>L=KEZx0$op7W{qbqn$D*NI@V{^U_YkF1A48tc&ExHi?K3|KF<&E#8Qjyu z5vq6XKVHr;$w1#2(+Dl1mg5>2hcsE9%Z&7l0sSL%W{Gug|8_>w#NQOeM{4RllqPc- zrB#mT>-6sgfT>V_U$ql)NFfl9Db;Fs&dJ1L+KxcN4(N_G#ay^{FipHaCm2=+YWnwz zM2-d2;XDx;k*!&aU&NwA1xChS|19X-s-sk=QG6Ex4sy?V<eu~Nc*%`NHCTe`-VRkH zIDRtf^-qbUSbc%*&<VBv@~a~zaPz+;LwVr+0#K+mhYL(A*dUp#1glZky~bx>L4l1# zCbw_#s&hM+YcV)H1f}wn#QKA>c)_SymS)PnZYW-R&h43KFOr((WQGcTYi0YNqhe*E zDA^r60d!feba7XEh#uex1_VlUB!ngv!1OCBK{ltLzJ1(df7iQ30{(w+aysC{pyKuM z93aE3&cM!4c^S%JWMonDKf`o}L_9T4XS@xljbJFYrWiO*QZ#MrK+u<jW+tA|pM2^& z+t}znc4c=|2tqP=5#?36N*gTI(n8bUUi6vg;G;)VLw4o?xbd_8XPJ^W(kL}*vXa^@ zXhVtA)@8a$;o4Ur31YX;`B!XfAQw0x{nd8bRiOk;&Ed>%{yhn;S&=(9k90k%M>*9- z_<upu&UK(i7h_F2x6nn&?N2G|jyQ$dz;qs-u>GVDJoLg=R1wIG)qk%-mp)PGcD-6! z+XAF+fz942DMeX7J5W&{Wy7D-yRpMwiS$!q!a(;0LAp#J-g&vQi4J{ESj7sqqfACm zaI4&KLx(Qjr!J`->Ivr|8h2FpHxZV(UK-RDMiY{RmT(%ueL?=&YNiZG_AU~6(oHsS zbm>}m7akb{3MW$c$m3mAw@Tbu9#$kpF!}XN&{AZ)+(uFi&f(49Nrgg~>jJBcFV&X~ zz#;KISDGE*;4{C9pIinI|2BnhK5L55TOij!`7g_2<L5XBc1^>t?T=9uF8+1X2HxQ| zZ~X}rfvvbCNKq6x={ia?&Fu}3;22^KSPbk25U`$#J65kdit0!h`9|h9y`KpbqSUle z`T-luFF$^?K@+KNiQNYNT3=s)h5-<02wO6tKu2P~M~f;!0(5=NR9z_=A<XqeyBp_~ zCChLR0dh~gSsw_3AMF*bFV7S~v^Leb<G@;kz=|B7G-L+VEnpzH6iZkz*1rqy;7Evn z`tp?hezafxmv1UuVBy;t4Z0Yp8G{Ov^!5R`Qc(@}AO}gE<T<R*PY-Y#rSE3JU;UK7 ztuCvcB&$2pSP|1oJ@(+G{ySfxiDv&AkjRcM@k?=$DmbWM@AGJ<v@G*2K_JVk&hLqP z7%I{2;O4{NzG667BoKdR@WsXo_7RafH~wz-@U!iufW*U{ZBLfR66T(o_Ls7FT@rYM zs?OweqJ;<^TK?Sip{lbCWIM*gqPYvGql|^TzHj6Yf3;%_C@u7QN~N%V-5KwF>ib{- zH*L%iD`75lbo*z<i>_aI+q*ixJk01quMuv|-|1B6VgjCl;NLpyXn#xtuJIfeCPqsW z9Zy-qubFu($5&T3b?2GM5?V*LJ+`2R`MzQ@*FC-RU|e0&Y;RY*)=>hI`YN<N2$rf6 z!KI3o5X7PMhTXs_WgOI{udu#a6IS5#L7JCt4&sJK<yLv$%0NLxD)J|79s0TJG=ei( z{`^)_?%ew5y2RH=^9o`5#WKvVvdo@y&Q;DFwyx@KgF631O?$qfm?-8U05-P!OZon@ zYI&W2nd>`4a{b|VCtii~O1*72DW0AGw-MWk@jdiT663r2J@o2L%k0DcS8jq&+VxLt z`aS~?2MU!)QR;XD$Q=xUoex!6X&afPO?R52CgJeIpCt-SY<#TJh-KM?j-?oZ0Zd|e z%d)*c*|bfT49PLAYo)7OgkQ=}6so^gx9CTq3krn}H^Kt%1{$(nNgYy_jQKq@rwyS7 zVb~OJVecm*zPiX4IO+Ym-z@#0CP{Q8=<;EPoBU6kh2xfbnnYrLsh}9yA5aC^XGX`9 z9o);5k!4XYZOd$jK9uw+3Y?1k<k!?PX7{Y$8{Bu>{q9dqm|rT>(Y^YHyzK(?cDzuF z`b1K9NF=T?LCu`crV)9Vv@C|YYw}g+-dQ#w08oWHbyzDG22GkV{AvJs6ri2Hd0+w6 z!#HU#d0ZJ0cL|l%?EykLRG6e#Xa9mZLhyaazcS)#v8ilYT+tOF4K(w(es+BCc5!$- zXgWmxqTl^B;P7ELX1TiRNnj8b;RuLaeDe1BK_0&M-QO!ZI#`0dJ4W7bzUyI*vtK>q zymLaY+bFIN@sIs0>-`~olR3jPC%i8z@nLh^t6r3ZC_ZZQ^JC5zq0?D)pv#1Km&HSL zY%7)beK`pihFgcAw|Z(~>;aEMK~WmuST{T$51y6^kNW?$ICl<(NO)#GT&3T%Gc4wq z?iUZ@{pNuCf0veY>n6A3(?y-y@9iFoPG-L*Z{$JBiM=b<y#E!$G3Tn4_}w}91~@}} zw#w`YgMF>M%M?0%O+)7_)7u_*`gMy&|9JB$;J<=wnOFA0Fv7`jxx<ob{EH&83@W_% zwDekEETgXBX2`l;^z~${FSgay`l>)c<;|!4GX;xi2MVMJmumdmx1f<zyWdAXjzqEw z%0qSr#k=@@#}==~*)A)B?%x2bCFHitJqoAV9|tQQU(nm*ZMXdvU-Z4FSfS_R7HsPe zp^gy%)@q;q_kDS8w%8&hG`_r+0%`Y+YinT4fI7d0Hd|yDuzlC|bLrF5-Ui(3y^!Q* zfA!bzRq=WNJq({bq`nJs1KcGTX55q(^-Ydgg54*$dwmosN#rvyc8AqIXDNpn=Al_) zH<->G04uFO8S(s29Wq_W=6`a;{yX`3GhEUt(m}^03O;93u7cq=Q<O?xRul0V@HFp= z8GL5Gr9U?P$oww#97>e=Bs2DkK8sUdo#)_w4zGj;M_vTwP`8iUlKh|rpf?8o{xNd^ zkU{;<=^Q=mRH$<~^vgV0yaLg+&0t{Y@q4<QgMS>Nt&-ir84M2ST&_%x)g-v*Fwa{d zjhU;a@?LRCj#Onc!HZ#6CluML|5|^3t(9;3W#b#=rjg^ns1Plp!%d&GW^+|gUmqB^ ztWLOjJfDA~i!q3MxvDT9=%ZC)_0p<(^pnPPSkxzMU>81Gahk9%@)4{7SVp{arJ}xT z+xNwa-J>?>$DUX3CD-mPz_%r32Fs=Z+Ers-DoDsPYLIrAZQ_R=hD!CWoHiIOhX`l# zX{$;jY~&$}oX)B3_ke<{;}Z30-Yfk)+r~z=$dF{Yb`}BHwsVwQ>5cy|Qn{MVBpy|1 z_MXPq`*bF^0E>7j<ps)s9k%Yn^^57dMoh|I4bednEVAePz|0Re3rg(TYmPy8@<opg zr%_%{o2-krkvV(%+pP$9op9~cUn{a2QI@VhlJEPgE8XmTN+32X@9UDaI;elGZX2EI zlsmU&T(VXp9SPZaeSNRR`@1BjtC<R5Sx9-1eaFyUacd-ie?=X%f1^vqyQG%U`<s4z zex!_R+4_s9k?w#TE5NkC(gR{&#iOns6Tefo&$K$RJ8#jhocyP^f4D*psgLTk>L|xf zKU!j1m7)i3s8+vwd$nx{q}BNZbmTPMVd9u>q=4N>E?Ue_Wc#;06e*|hNzFb9Vw?b% zrK15@PtPe*iAiuCo~3B#VhOTXLcqSp=<N&ZOlOq?0fw!zdZ4gGERh0U2qTQfz04{i zZeqc0=Bv3C&mMalD_wHhW)^@3lj`1KZXA_sE#2?;tA>jvdd!!*y@0m^rv&{2?Euka z?NElVI$O8+%u7`v2B`1ChSXGSFPD_j)7w&42F|d~1p1efK#@y8(l{r%{){?>ELEK8 z?VSzA-6d+#)1A?pt?uk-i!nj=jY>mBm=Y#(LP(I>8%0Dw4mE7DQ*4vj7y2`x(ZL*F zsfoSht(8{^hgp#JGX{gZtje*I6)|-8CT?#f%0I56bML>grhmD~{XJC5uB?C-uA431 zbCIm5Gce{Pot^1J=gktaVrjf2KH@8D!mIKWB%|<=;H;e{IGaFm-bY?B9AC++8P6Qj z>7yTYLE%;7P5sUam|Z6_3-z!C-8dM?IGbV=4voxU98-p{TSW@;SJ9PLkiSKy(^d}5 z;*}Q@nq^!kjQ=~M)!a)+e_J<W$qr-GOWP&Ho<OUacPpG`pXa=Ls3a3Nkf~{@!G1>@ zR-@iCp|>VDA*Bh|1P7L?GuV!8r~UWrM)?Q<Kcn-c{4laGtWpBRoZhtdT+fosFIzKF z^()hrFt0bCy(EhYXRmvOfJB?Q4m*x7rWl+{``jj5WcJ2W$QA*A!g;haJU`^@AcSM4 z*S?TqYU5(F_mBa5^7<APMS7vv>h5~oYRBAE2BIGQ1uatrwj?6hh4L(Ei9}46%cxh1 z1Fw}^Q_NIyUalaK*0by`^HMkl64W}w8jP74^p3U?YLIl&#BJqVklA}gCR6IIlV$8C zQ<%*{{rqhtGTWXD)ndFF@3t#00IpA_g_CXE7WkDeu$5*L8MCKV$_>!R%J$LTnu<|S zgy;b)k-KrUhrlh~b!KlS*I2v}@V=V4?}=B=bD8j!CmDU&jm}e(e*K*&o|wiOr>p3C z(xZuT=bPMvTulF3vZ@wb_!xlf?Tw>%h}CyeAx_0tk(M^sG~mx4-uwqUynho}@J0Tl z7dHR6VR7F-hvuVlrDA02JWZ<81n)7ZjY_8d*G0=t`J(dN{MlQouev`;3wFBBVd{*t zv^yoTb!4q!I?hrE<{S3}FX})t?J(hzb`f<xt{u(REaa!Nd*jqI7CqlrO%luOT+%&F z?1d7Nxao)aq-n-k$Aor=m+$3}t>fY!_Sjq7bn=UkNy_SpF$MV>=Q2c_A!x%z*;S1B z!ZnNmJFQu|wG;BgIm<S!7KJS56iCP8D&J70;xj34$Ci|_M{fE4@<07}*-fu-fQ=1C zDlO+ov**gM<iT0#z(l^Md<doRr_VC|Rcmg`{)SPxLS|bHd5Di_?q71OYTy0RkBmJ% z-$d1C>^$gtgPkqA#hM<@yC*FCFIU!FhG~#rL@7DQsfbCjDXh~tneNsU<$gb7u5yi2 z>(a2^N!ov}-CI&#_>|rR=5PfQ<dhl|c)BJIhUKHYwRy76ZFg)K`;nFWn9<$NyKIiz zxfI-GvHLf6qw~6O+FCJYPc6%0WQslf1gf<0WprW$!ENtWF_TwWZxk7V01Gid$&@Hw zzImIKxc&+zbHJl=hJXA>(fNQRqj|ylMKG4HtmJ%3nR_3wdTg}n$l`HTMVA$O=<7UZ z)@5)K9o5kK&0K(o0rkXtW%RbAJO`_NAlGIkhoOj4TubKQSKUMX7>wXt#k&<9k-@sH zWX*>A;75s!_lxESQTacI^-3W(54TL^x%)l;`+E&H#s5015_^LX*W<Ur8QP~J-!y;6 zmnSqPjFyX!c5uvQJx!|>i-w*1JYiibQ>&VUY&<r+Fj76C7%?LGi8y}t&w`!N!_p{v z9@20|p}!gd0S4pqM3}?LA~4DcV2$2wrBJ8)@CD{(U}5a<y)Z~bP|^d9w?3P@B=`5D z`_reNxR=nS*aJr2(|sK$TnwsBnvBMzeyz@2Y(gjV!N)~_s{U7K?J`cX=3G7H<=Q&* z&uX|v6{6V)$UhHUMtGEu8D2N+S+NTnu6Pb9xDs809)1w4x%{t(R_D+P)i=~zJnYoX zVApK}xG0h~8cMcs*EUTvAR+**<L8GZ4?}a};MASqOatCgoY76T0g|rZBtO|E`I|Ha z#1uwlDw>{}Q^+&KdL+OfC!!6C#pE7`vG$PGUaXV7oLQ^WE;J!gc#cxJ>nBSzp=tjt zhRp+AS25v4L#NJ>xp_nR(FDEer-DB)+x=MSwowLd%oUa;wKF;54Cd76nJAH+E@C)h z0o3WEYZWoC=cH1#wv!zIrc5DC)3E8VC37-!3x_L$v~Q9b0YjjS7X%utf0`QN15Wol zTEvmOK91g5hXqaJhsNf$BF(S!Z+bvVYl5J~8D}jS;!C8f#Xal6U1uY0*ZQ=<34gQ% zb%EBQq1-sW14vXV0bBJLC7F`++y_)7ZXbxUl&b)vPR7;ZflN~HmcI8cV6fP=8;3Io zboN`Pp?ygrhG|%B__7TYs4;KY*EZ@+m*i?K8dYUgWRVOMf>W0AnmC$!iBQv87EL03 zC>MBdHg2s{(`*3V&o;gPG}T{VLthhW>5n9d#Y3JcnAac%e{^A95DVdTbm|2zEz?Gt zf=_GvD1M1h4d5vbC-3CSOh!a)C(~WQT>TOHP=UZcib+a<mQKI-Y6_<;9cq5mj}0y} zPf^!qc$)xrJgf*xnZqkU@DM|+$Gk!4P(Y}cDV}*c3w^q4rHvntIUs*Ilp^4tC{HC` zAxNhQjE_w79r<Up_KD8L2a`@$V@_w<>9Fk};S4xQRAVLNPuc$}*~qqE7Lqq(^%)|> z4d`iaS$$2jv>4F8ht}KrU{#PKN(ba!B_Z1}JSZdk1W<C5vuy0=%IdT*NAolbFIh@` z;Z+hgA6|$x9(6VTb3wuTi8Nmb+$*ULAr4MVldH!W(kIx#r$-$Mrqn{$Dg(q{`5WKj z2dYAZQZ+03k#I8GrOKYG$~5mZ9y+5I7fLN6#V;LL4ltfd@eTmKApE`mP9Me4F3E{7 zcwNQ?C=XI;08<+mStROeWeA<D7@(slor+5e5MrgeWxK=%v!F6185WJf>K~G-i^tpb z#Z%*|(nzCP1=MaePN6`_xh?;B&h+AAV0o_Lc??`nutMPi8z+XioJSKR=j{Ik*yGXa z5<I9ZAeN9UQ6b<n%rr(H06;v0_4TXc2l4$Be%5Q&eQ4(DapSUg;kFhW0dU`{_va)8 zA3KmQZOCjB?p~O_f_1TsPvXrNWOlAi^e+GJlj)wuldKC$H7q)e%gw&bY~Er#=_}Bg zcSvoU;aSubO*3Y=A=~J7)w|d;!;lhdr{qQbv_Z(E<=*`0>tTpNC?8xt<$k}UrLwX0 z*&sin%BTFZ!5OJ`!1Oqvcr@mT8HVD0E`H<~t{2ZwOP<MW6nMc0&yJgR()S7RCxrne zxtRzs#QS4T6K!?6Ovy5Hm%`F@oX4lN=f$I$KZcH8m%i&AFHfU*D?Jx+hGqywe~~f5 zo-`Pq<+!8`eVTvvJf8GaS=b|H(DFNMBGgc85)H0SJ))<?_zPkx0?C;$f`pO6V+;j1 zuug{*AUy!88NX{mbN{Z1J*4zk_n7E+^i8D6H(n!6m&A>)7>zB0dyF5f*V|;t^wra$ z@E2Eu4|XxeRd<(!jEi?^&Vr=VTxXEs2&FQ|$B8uWxiTxgQvyB=Ce&nV#RuthqxFjS z`zwqs>rBo*!o|-Lw1A=>e8ASDa@#nJ$Fx~|;zw*Rq4~9}&KVg@$`o=s|Gu77?%$kc z|IT+9lU2N3N(YyY1kS3!%~dP*+6EP<03vw0htqd&H!kTBTqGnZ_p-n0dr$IQU|)WO z8*fZXS$-I1g$G$%SF;Ntz=MM829FBYJREHTUB2i2AUWk4ic2S|2+CF4Q=ZnCt__dt zO=o^CHAw{6fhmo3iVYRzKXT+Rr8Uia%9Oh(hlV~xI-j6#NRccpf^j|Uv8>bj@mB+u z{&gYU#@AsQW^IStahz>3K$JIb5aCmE(Oh3=cJ*jtzn-TqG|)hv2Ky-OEi16nKg`Wu z0CvLcd+6!jD)`o_Y(1W#v|`a5V8xIPcS5w_H~l=fz&FG&VkD-?8r-9$8wp>5vW_O2 zjut_aP4LhbwOMb~Q-1OROFeoLzxIIE^rqoXVAC3Wsvq4FW13j703*Vl^cua9*i!5M zBBu}6OB>=7rlFT?&5ULGBtvonGYFk1R%9EcwAOTG5Joup9}r0LS9gxT0;4Xh;>CDk zbgj+;FoWxewld~Fq1%imB(<Z#=q8}VH1@!u-lfh^?8<lrS0dk-jw`q-o}8snb1@C$ zg_{sX?EueM3X6H{hYo|nVCxAwPGA|Myev2(xn0ckz!A_0)0n3LKl$OC#;k$ax1wW) z!O;Q*RLL>>XP12Ls1aEPIjPhGOCd^n9-!V1&eJUq`j1lP(0{<6WOqa^vq7SFFa(eW zl;g9!dcT-cfPCjEq`w=s$AF#v!A1FS9bN;304ec@(#Qaxu^km}?i9M&)L-7jVCjSX z$R~B_dIl}3jX10xu~;I8{xUuiR*Y9EGwaNz)Uyox=}nb9Iq5xZ<h4HjDWihvm^ESu zxSTtvI&CNo#FHlinQMVoRO<qgtGxlVrhx2h1LXWD1#A7)k(ETrM>_1lkB<vsgOIX& z?w?H@9%REp2a_Xddu>6(tqrc|7gQOUS`rFZf68I3M(=v(pVMJ_xZ%R1&W2zdAD@iH zX#ZS~!yOu*pzqaxPr~n1CW)YjtyZ&`QcwPC?%b(*@8|DhGQ+9-aDR8*LOD}y#~1qH z5uVe_*vgRPPLSb7M@a-Vt2_aoPy#}kQ;j<Zb7Iy-Ek$(%5zi8{+vd^n22_vE?uny< zLsede{8KgL!RX~aQ{Q;DKc!MYp2=f})1E;0A3$A9?S^z-1Qjzg_o|(jMw1;I>#QsL z(#eKfkBGmxNl9y>G0EKNp2EFvlQC0o*1*Ld`0Ve}6-M`FqFy&z_x7HE2{6(kQBynd zdAh4VV90pMKu<yghI%Sj*DtQd7;SHqvUET8R`Gi(B9s@c-v@52&apem)=o<^#ux3x zPlaJwkTy?lv4(3g`KosrJ()7ks=bBcz!Vgr#(+KAjp;VhL!Z*9OW-ONX-ejyE#}jQ zCoVjG|Jk!9pI9~-U)CE%Y>=BupJ$it1dG8NnMtu95kkO$|DsBsi(|t(@4>(Z(ymz6 z0W@#7ZDH<Sv$_nS$jI3k^%a)tLL5Y&edCpZqLzQF31n)MBpe0{?YL(&+!L$60IRhg z7*5{PK2w%&9)vdxuhU~Rc#Sa2AkWCbYmOW3-VRT9vC3-slTE<fK>_Wnq75t-kS7#u z1(Fgs5NEvO8FAhdfXq|^d<Ah^C+Lr@OL-9-bJIUjpe$*<V6<>wgZ8qk%Ud~ksZ}ZR zuN9r6W*K?z%%raOq;<>n>l(e7D0ND5#H`?NUt@%JvrOTuz?!n8Dx0LpRu&C-upz~8 zNDqZJYv2cFl2*KoZx#K`3fwHy%U2%t)@PaaX~sTtMyCPYArh(Yha4WBjiT;7<9Ox> z0HOs8z8@7(x;92wMN*XLSXjEFBLr=3*`@R}c@d#$vs0aMOL6lnBl}_C!Y6}_)`NtC z9N1*<L*5oqYR4=_D=HqK#LIH4)hk*frVo0nmVMoKzR~Kga07)fhRHPIYpv+H#JTwp zbN*&OBN=S4x41GhT(OL<Vh|qO<IWcb@d>9u5M(VbhJ^9saE8Bbk(c`NXiZL6IHKBe zz5il72Y#=qR(PoFT%HLOAL~M=_vXotmwyQZrHyLD!2F>4xRDAtR9qMS_X}zDI$3UU zXqy(1g5ptsbmYN=nb)V+Z@fM7<MT@Zh(fv-cUac<m`=zzSKY?#^&{~9^9HpnFOy6G zu9Ou{_bTmZLDBIX@i2a~CvqNE-fBw3Zq)HWUV};I+Q@w}Man}zLV0iWfqli+`N0M( z97H*sJ1!?=5JkUj<jNI)<<<?jU1`dumESlYzD*9HFFRO=20FcuUOme!=>mk47klrh z=+9+bmFA~QKzP+L92DR!No2h`+V9Jdmp0Rf{*L2|Caiz*rei<(KOfzthC46w$aAdn zpK=Que&D|Y@>f$NYKQ4i5F$VdFYfkBT|YBj<XpOAOSNWy4z=<H6Q0}s_v@d+sU~Ix z_29#3Yw0s%o*3g2-O`K2rp8^~s+W@b>fu+Lz9Y_A0S+1O%4s?;Ra*a>#&Jn~7kE3a z1=hcSYz7dIN##DpfawYo#mx01KZS+8=YIVph-V;?o;K3739WdN&UfEGM}~B4_Pycx z7v~HAxA<innwR&huJ+AevvC+6R);n_+aMOGT%-}qjI&>>=)5A+$I>&3w^`nCYMPdU zIEu1vpvEZ(q!1!gi*_DyM$8D)N|waGg-L7VNo(Ex+8?!^@NMA8AkcpVAi@$cir<SI zkqaM~I~JYa3ixKkmj!8hsrOJAB5KN{7+Epu8(!C<hM_5Y2YCR;%i&0YveGc+bHAck zY3#g1!6mG*(nOs58=qEKk!ZXqgY$_bYFILfA7v~<JM&0ZlZEH!Qn9S^7idK-uQS)* zul;B`voLjACwuB9w5JAm;_<Ja5f<yv%G4XUy}oIeOlSjs>M>0Wuq_?(Ft061zj1zg zg`kb6F@s%I?3P8>G1b4_<)5nNee+}9j?W`%e$lgS$tI}@5KcGJOZ)s_q1|RN;J6G! zfookF+xduBy_Ga+S3!-<^(o9E_WL#n`dlhWuKw8o$>goE*@_k>wc5UIOGG0|YAyp7 zM^eY2NT?AL_lQQAL56=#A$;XamJ;pvfDAzCr9^Ak<wvu(j?Xi+;!`8p($y`iZPQAp z$74EbUCFNl-F@VBVjTy|td@vgDGY=dg~vT;e_X8abp<=uZ-#&m<%|^ci^vf^6t2?i zR4mr;gGw!m@_0TJ#3uTIvoD?#T=p!kf6d%q%c|u{?eP{@<a%P&h+53b1k2rTPm%uo zZThO3>mbj+gH~v8Om=_ey-AA6k>13uZ_t@FhM88RF}L_%r#lVb%ch}Mc7jj)U^{;+ z#Ca6XoqB9^0C(rfG8wyMMQ@Ky4s<IDUF21>U{Ka}{wigZKSCZmL-9zG5)6Y1aQ#A^ zz2I{C;yB^1BaqH!rj@K`G{71$>mg*3ZwTA6@eoA{J1sK98J|vi2~!6q(OQ0MxgeOC z>uDhL^d$^MW4CTI#t7Zo%;CVqrD|u#R)oM&eaF)jtbdV?fZ_z|diP4du+$-4oM$N$ zP9ogI0Pl8<0Ou0>)6F9n_#v|lD3X`H`h0PUSh&&SCJGFyFsc800U}qK{O)%0)fdmv z8Aku&DYd0|K~rKD+$hCIbhpm9wx&(jiGEc6orn1s!Kmz{NH3Ab%_m~jiJY(Rg(JEU zlXliyss-M4R;Mt0ucyK2b$gfhsDN80OHwwqq&mafbe!XFyEKcKlGxpHJ5AZ6nyoN` z$TBfapqztg<pd)r^%2iqrJkeWNSi;e%nqM7MHDp7;Qd$V)feV+SWC7f;|dLRM%x&6 zd+f3zrr8#<!<*hWQt+&a__Ha5(|c))cyc^gRNvar)?oiG@?Y7M*wRrMZx);vy}D!Q zx|kEJ?H%<UQnlzCLuiO&6wORD*0{8h4qs=fZbozcwc2A!sN0r0E%=~(^<X(Gow}Nz zc7u5f=dX~bJTDhQGi5G1kW*kxl0T)@msztBzTqQU*KNLs+BwQevaf9n@ivirnPUGq zE5{WBaY(E|FLeB16Vf&UYuhVoe>sYR4sNY$>i4sSu2u!b%9zhxc$nhKhT6Qy$W_2q zGj+`DF=`@C>?^&u@ZA)ZbN8NB)j@Og!t=WlH?rY$IE1^t2oLT#$j0=z?}OQvfVLzH zoZK)o+JNS%DOA|<TY#kb`6hyK%wjIud?Jb}$7=Gym$^5%QOVNn+smzirY+2A0A!^& zM#4m?a$oaR*?q(y$?V$}Ecc!Wy9kZS&DfZ^mC1r#LE7gg9@6$#w}x5kTZZL_jbCgq zzF@xDAYPxX-k3@dpYJF=%D(aFl+A=J(82Zx$}F1l0b#SusGQ>##PS^Lu_y@$4PUt# zg4A%veU}0JSvM3V2hhiQXUpDp2)py)NXBy#B|7-2IBKh{@sWtIOU3szeP{$PuJz;w zNKz91tL~G4oDH!#3lz*yj`P*t5=q=nHq)hi-*<+Z2=@Z5hYJ}-_`Jtck(sEsXQh`S z{kwvKQ#=&!cl_nPb>~za#5tmvBcN!~D5PtrJ>P$Qls~vP`NM=-EHf^pM8p%^j$`r? z?l!$6&Hri|jx=cCHmqhhAnOL^e-7kx{Eh6q?Y3_=e$;buWe-m_eNM&ZbL5O$QiCpQ zgL(fL6z3ZoH~g~!MVh30B#=zP-Y?;k0zLUW1u%S1j?z%3%m+?Ql7_@8ZgMR}2KW)Y z(%VwS@84{m^MuA|cUXpqw}M*1PW%m%WOMD=V(!S)2eYSk#nKnEjSj9Nq%RK<!hPAk ziJ5;S<M0#$kcu?4bOR6hIpliH_JJ#A_4O#GSkt&F6HOwcVgC=TNkOD%Qj%0o4GXY$ z(>OA{5`M_ch0<f)dh&SwhX-ozyv|Q~>vxzD&jzwQDg|^ZNO}6n49Hae`}gxC>S_U; zCzZk*26}SpK_e}P<bG~9Nu=qYolb96!t@J{o=mo@8eo?D!b+(Hv91<=x?`*kEZAfW zs$1P}m0?T9M6F4!p<r95?ngg16X!8PDdsaJAK=*~ha`;;<)&G7bS+lfueH-2Q){J} z-FsJC4V6^PmHJr9oKaAEQY4Jz+9#=z9sqk@Kljs0MN7;46u15%!JzR$^?Fxt$QSH# zsYTc}esto={ZIwc9J86((P!xlRsgBx)%pBlRwz?)%h9H>D_H%D-lDQI4cmjuh%Y`; z`Fn%4dKq^KVEy|2ldQ>bsRh<PQCvheY3IFXr^qAeK|8oKFT7Gf40wU@z7T;b4VN3c zVDx9Hpv%wCrw7cOgTw$o$}ec3@;+jt8$4It8$8{qDUqP8ACtRV8<O1{9~nXs(Pok0 zofy_F!GQ{=DoU*ZkJG)~+VF8NH#()|LB6NKya?J+bzfe>K2=T<zk5yEqb~!xiAB)E z)Ecqm==XueiM(`%rMAY7B7|0HI;i*bH--WHNd+IT5#94vX=l$ANUOspS+Yb5Kb;ZH z4POy%7-dF+FZdqKerS&DW&{ldln%?!Ek!S9ObatuQcrvjNn8+1ca9~eU`*s%>Swu$ z6IvDoKoWj2he1n)00Z%M67=Dd2ZB_0ca_Oj6E`F!$b|Y*D8!+ht-@?Rc>cb6{!uHg z;|;;I1Htu;9M-Xi<DNbca<;RCnk(y#oxL&P%Y^Too;>`XAcz6`=*D<_TbKIHB(cQM zW??|EyPPta(1rW(06_?tB!}95Hp~>mI>IXmjcA53yNdF$R|v0(Fk3)GQ#@!+VO*t~ zyx?PPK~K(Hm_SKl7xD{t=BSkX@ncy7`q>1_(Di~JOk&ybT8j7d)I%PAV1hP^b2e`9 z2_-s(g8>xrK<EJDrh>?GsvU9wmx!kT5iIf>#C0sh`%8%VoyR44S$DP~7ex&ZtBG>6 zk-z|qn|z(0VUvB?iuV#`ZA|Nqq7c8|P~ltdll{fgSPBrm(TCeMXcXc^xO4czD2a+$ zv1CHOVBCu0fLS5t;*Hv?+&cbz*k{2_ZV{|t>PBj8Ie$vISR6ASG?mxb;4!BG7pk0p zn#{B=n_PiT;v4hZ3%ISIk}0_$r|$-bQZ{{&0n7@@v6U^n7qFrkVbn>6InGvc{idiv zE*VAz?IU}wjg~s~;EfC4^e&_D7iJM719|4Gr_ez+!|caB*kjt{=KJ}G2W9F5JY``T zj6S96P#zR48K)%nD?znD0q|!=e;`!*K9FyKMJSvk)zEUlP=4+n2u-Ww^32pa@Lw0J zc=X1rA-bPi)8nT1cr528NZ9lFnNrBG0q+l^CtJR}vgC(i19C|oSDgvcK5e|;F>*^7 zDR6)YDM2bt5^%NF&oe8;r}zbWmcV;fey1XpZw>ynyWc?3i|4FAz1hg|PXhPshE(LY z7bjJ)-*@vHllW~9)d^n|rU#(khVk9r3S|n%X`KhSqbJ&59*AI590$zbWx_=ul1Jvs zhhFTDp-SLs)t1~c?_9$gr3QD?@nz+Z(a71{S!N9>$qO>J%;2pL<>yF0)1^+UJj6{O z&wPm?Yt%dIk;<(|20n%$5oU<!`i+BbyN*98%zO(`@@@JTop$?>f2|u9I8)7J6MHPe zp|ZgRLnDQZy3?ra7|`W-FdFH*;5c$*8P(;qPjGtJWyv98kM2TlOc_ZHBlDte6?Waq zWUwh=D^xIe?@-z0?A76*YX$u=?`*ectBJqeufir;X+5Y?=$>=ay31w3;TzP8ePqLh z5h@7ye-*VefFb}#b_4J~iW*%!<pdE;rYiA&6*VRX45F=KD3w#vjLzD<as*AMiKCMb z-x@)4+10xg+6dxu<h{m=O*?9)iqs?aR>%IoiduqI1#sH-P!ROQq|)s5t`ISaP5}7m zkkCI!)#B1m1N^HJpH%NX5niX+budgz@vxZd%Zp~$%sX#T8cKwbPuGgtG(;UKzcGko z5tnsAhOIwWrOH1#?rxuva|AlK8N5vU_TGm){{Jd!b`5S*y{G=lKJJxFI$Ej+D=#7j zWe3HGKbA^;QlqcGjl<^ibIgZ|7gIT8U1|`|tX}t??k_zz`S|YPgZ}^42UD*EZocU| z|G6`Grzg?p;e%g4z6|<h`lS9lb^0DM*7EGppDO^B#QOa|2Tuya!Q>9c9ON3mhr)(S zgf=j&`C&LLn{C|&jyHN|BS{b^v56PS_uovG2*+<=$?j#Xr)u-n8F3)hVVHFFwK}g1 z?H@Z{ncA8{Tj_?H{qQV<Wll;abJek}94lk$?dyz(>2{u@Z}N7&bM)Bu6E__7*8*oT zF6=}3nwXqavhUky5U)Rh3>5ZG(ys)yc1@nfeGL#V;da;eqryaEVdXpksXD4K)$yIm z3}c$zs%%HI-RgYbl--)A(c`<dr8t_sx;#&JDJp*Xax8~`{q9{0_xP(LN-kxh={FGX z`k#d6zOT#s&2Ok^zqfYJYSc9kbDK-Fj;Zc{@0d2eanL#M7<kR0`8FK9n5kLzZD_&0 z%3^OQJrZk{u6{*U4n;xwft0)iVjnecC=tklYz?N``?deyTL4J<kVr%QbdM`Hxk29G z&w;}}h!f&6)6Op<-*0mM<3?ETJLWw|2~9$AT?g&Ka^46}ZDY6*mC^=pH*M-GBM#T@ zT{6-QHTcmG=j~9ow;Eog1TgfBCaVqVFL<3H7P(F}^GfIL_d-EIUE@hLe~vj6ZqN-+ zsysV7EOwfUaRgEb2@;mcw*v#`odnVoC?PJP31y5-W-lq(53eTrS0TvI{$>k~hp^B3 zBTXpcEu{qcMfzyI=7+(5EM6>3xP`VY-xFZ%r+guMsX!&UWP|6^b+PW6=k2yZ@Y{L| z4p3G<vl?9g9;=V$;a-2*y+dr6KX%KOTWwuZ`~B|V1;76z+c%T4a{tPp7dE4(*wxEM zQ1hLTWC(i|0rU%76`BC%a?u|YdF!wD@9*JAh;+vqjy+y`D9OBe%4z6f!z*SFo;Uh_ zjq6im<jS0sjDqWAE(lmua%B#s*aj8YdOa3WmcR#hPoPT7q~JJ&UDrEle^dU4k>qj% zWDwqt#SD9>r7kTfjwog7Gx`vVa(;wvPzW_L(y*`VmtTGDWT&ADj)O>WQz@_au3%ds z!FUSs;Fq$j&NEOMTEHFWvw9ij5f_&pmuc`qAGJtX1o(XQy%kEIJCvNhJ9JQlA4$xL zxz<-gDOkm9@FJf2z-BuGl0U!*tWU=A`o=OF$2o*eGa)tLDf!~Bq`n4XP#Ur=o{Mps z=^gzR?(J<Cp0IL^fdm<cKo$3bc3FbKx&iytPUY;Te6m{D^-*--fI$2PP7s%!l{&de zBXka}275pDStlzd6?FInD3Vc10LW`JAdtGO!Z6|a>G@h>ZMh=edS!7MP9Wz-4lwAl z42Trhk<oT<aC8$X73vkJna+MZA!?V?B<o*UsIZY}ebg64(a{Zl#t~2FzmL*`det>& zf-{s4`$cj?)g@S=cv>NG`olW1PhsRVOx3V5_&S9^6_K6<7+5)`p3KMMuw>l^dLBT- z$SL_8UwFJS(|8s@|0Z67ln2h0r}iW<IkA@w7|n>onOF@tqY?d|QGoZTd<ca=cM&Dt zxnZGgKE*e}1;8%}8J%L4w<#D<aAKS0^ku2_TMYorI|2eXucwR@9|QvQ(X9UK!R<<) zMfI%Ttw~~9<F@xp07h0C^hXU&_T~QLu^+aqZ42}J0vwOnEFXMq5GF(DgA!;Q>6Q+H zUn<HlD23L$mwf0<8kYzZp#3;{6^*6->}lsCGw~r}Z2GQm$Mp#7Ry-m81)$7DB#<)7 zv?Zf4W9kp5VPN3Uu+U`cE6ZuO+*_TlF~47})3=~T_CH;juJ^GJ^noITwNo?q(3jAb zxNqj4|757$`qb6(==a3u%Rj&0dOR!)?%*kq5u5`hYUL$zOs-RDo%Pp|yMiQ%FKMm2 zV<7MTA4N@&p$%_xv2Nd#;sSg@*VAZC1#K0il*PBD`B{A7UO5|9wMxjiPv^yP!udan zn#C5B=X?}l)t;S4=fw_;mz6hfyFEKD|GsKxTznRq|8jC$_QCmtyKEMFrS!IBra5iY zIb#n=7;>2Ve-yO{8yfgGO-7_(6SSlF_vAO-XQX%0!AzwebH8c*J)g#ZRVpJZ*)i7o zGZT~CStUND(xLljw&2mv3W}f|iwA$^Nb@&Sr%C?SMStdpIwBe!>8TRprluP+R4Tou z?&{CQE>t%EY`Ww64e<TxV&t#WrU=V#cUWHOzbcJtr+B^ZwLh{{?-t$iIB4J3>A})m zest?|zJog>^+x$tb^#2YdiF(s=eKoV_Ab7bFKGY!=`i0#ZPW6<*c;yj_Trgzc7zCz z&;EYCWFLLQNFEwb8}}J3fCA85W}?MiHt6oF5B!}v#DUf~F5FN<3Jgby=Gq%<FV%-7 z`Hxcdinl1`zoCZBn~w>P<F?rzYm8F_A7=%wuB$xmo`_fr!!^Wxg?>|?W;Dn|5zxH* LNE3YkK<j@2ph4=} literal 0 HcmV?d00001 diff --git a/images/demo_MPC_velocity01.gif b/images/demo_MPC_velocity01.gif new file mode 100644 index 0000000000000000000000000000000000000000..a944fc448fee63fb3254de89f8d17eb66fe1e0d4 GIT binary patch literal 214623 zcmV)OK(@a}Nk%w1VSoZ_0`~zh00000{{R^n874FDH-q6ggWx%X;5milI-ol{gWNlW z-#dliJ%igmfYU#T<Uv=ILqfJgb+$u*+C)xXL}rsna;QpWiA!2<OM0|UUUp7md`@D1 zPhE6RV0lk#kx*lQQDl5lWPVd)dsAe7Q)GTqWq(tiR8(YsRaE~~VRcwn>RM`lTWyV8 zTfSUnsa$7vU2B40US3~fXl1BoYHDq2bAxYg$8UCnZ;Y{Wcjj__j&pbZb9jJriKTRf zsdajTb$_FEo^^I~b9RsZd3k(!jo*5H$$N#7e71dljGKRbe}8>}fPjR7kD-Eshk}}^ zgMx&EhKz%VkA#SYg@uTQgocKOhK7uUhlPcQg@=cRhlrA(iGhBJh>3}eyNZa0iinVl zhlP!d<Bp7vj+Fk9hk%iew2_a*lbxxQl+BfMYL%3nm6_d_m6(^Lxt+M3ozb42p8lVk zoS&W1pq{#+pWvc=cA~4dqQ9b~r?8~Oq@|;zrm)hdj)14D=&G~7th4^Ftgx}Nv9ZOo zv(&S+s-w2G*|x*gxVG@Px4F7!X}!qmzFAwoySu*3+rOEXzudpT7Zt%uOToqd!O8l= z!o<Ve@W$W!#^L<N;s3|t{Kw<`$L0RW#>mLe!^z_Q$>aXX<NwLz{>kM2%HhV!<owIx z`pmw#%;o;g-~P^bdCttz&dvVL+4Iif_0ZPN(Cg6Al$O!W%F@-@)1ji%>;BZ}`PuK@ z+SlXS-sszCXx+`g-P``&)70bK)#Lu-<am1I-|gk6spahT=9HD@@BZhvv*+*U=-%J# zzQFBKRPF5V?(FXF?C<dz8S(S}@&54i{rL9o=l1^o_xADl{rUOe#`)mS`RCR7`1tzy z{`>m&`}+L+;>-Nx%KZKP{o=>{<I4U0`~Cg?{&{!)n412qt^UZw{^G~};?Mr$$NuBW z{^QI3=gj`?+Wzn9{`dF(`~Lp>|Ni{`{{8j-{rdj>{Qmv^{{8;`{{H_P9REW^|5aH3 z)7Ag||Ns8}A^!_bMO0HmK~P09E-(WD0000X`2+=I0096j00000fC6g*00{p8169)I z&)z?O2oow?$grWqhY%x5oJg^v#fum-YTU^2p}c>=#w=mtgi4i@RiL0;$+D%(moQ_> zoJq5$&6_xL>fFh*r_Y~2gSw<b#R-!<@(Olb%CxD|r%<Cx)p+k8GB8B4P|-?MsMoJx z!-^d%R;$^qXwPO@%a(20v~AnIjVo8}R=R8F;<ambuU@=x*LM0R&R)KJ_wF5D%($`R z$B-jSo=my2<;$2eYu?Pcv**YEo{b@*#fp`@R7|U0&APSg*RW&Do=v;9?c2C>>)y?~ z_iEH_UlRqMr8RM)!tV|*&iZ(2*K+R~=ZgAuu7CFIC7#E<yZ7(l!;AkPPrkhQ^XSv7 zU(de1`}gp}bNh!YEAx{?yOQ0{zrX+gHJNtOY6DsU;DKW?^G`hSHR#}j5Jo8BgcQ0r zUm`?w!BR<37>MA9AciO+PF8e?l7J(on3ICvBz6yX+f^vzj5OA0<BjC`!;KtEpk-1P zUj!-SkVF<~<dH}wspOJOHtFP(P(~@`lvFaQ1r{o1sZ%ox;^^g<V1_B?dGYv@%^FK| z;iD5b+`vPdZo(<&oOIS{=bd=wsb`#f_UY%JfCeh)poG5pW}9hFaoS#tHtOi3kVY!$ zq<C@J;+U9bs_CW<W@jdvrJWST5*ln^>Zz!vs_Lq&rpiGI8F2p~>#VfaYU{1Grtqo; z8hp^|ufPT??6AZZYwWSerpiMUSYUyome9h)Wp<oaYwfkzCT3<EOO)2^s34SZ!nh}t zATGJ+rmOC{<C;6}2OeM$fxH;VTfw~e+Dq@f^yWJ+zyJP=!3Q6dFoL`6Camzn3^(lX z!w^R-F}voLpuw`uIvefAE={Z5i`a%N^2ju5n+><#VlnCl29MzK%P_|*^UN`a5P}FN zSm1#J2lVXo0X+XK^w2~P&9es<h#-Q^G&k*Z(>62x^wd;WZS~byTV28j7(44>O<8b^ zpvN(iZ1&k`vu85OR(wlp)Nscw_uO>Dt+dV#FrdKReE0wD_uqj3ZGZs`Fn~19Bh;<< z;vu*kLd6D;>p0_-S8n;`m}d^R%NFw>MY95~Mbi>uALwz~sHd*Fc-t-!w%ZzLp84G# zED-qZxZ_^<;U~ym`3D_jut5jqzU=$)$R{s5=Ug+3<w+x9p~XvKkCDh2DwW>f>8p3| zz1d}+>3S8gx14p=Hjhg|?Fr=W{`-YnkaX{jpYQb6Fx=tDA2k$gzWo3Upa2JWFs^;B zSx^{5Cps~PlZfttRan9pa4`lfgslpq!(iAhsJ)+X?|UE&A*WjRI+c;?e*~=A%|xIx z+r96Fx7(csP9TEBrEqd3=ztsUa0E0QA_eAZoYenrNW>xzuml_ES``#1h(ItfB_~ly z^~NBFSya%0Sj?UjJLnVcl}&_T4C9PECBBqJ;RhmUneys}GrSo9hH&KD;ADuiHOkFp zI#@vnfN+Qx6wHo*45T1C=R7EMLJ&)Uf*>l<hDrot7KzZ%7%G7aWE=x~a#+PH8ZibX z1R@cMn8hAA$i<x~NQ|gVWsOKkJ`;v(h()v+&erFEINEZK43OWrV41?lX<!A1SVa@k zSU)2g^O)x&Bm!TtheYl{7HyzLCFIbEJrJQ0jcCIjDA)x^I<XQ$NCY(mA%{-10Scrn z<xLb64+g37o$zcBE8X_WV#acXZnPyFaf$!5UD`8+=3-e5ns5jafZ(6VOsGO<rc5kA zL6pvvMHM?ahE5)m2xI6)MUR1tULXTQf>=crm@oznsneAI=+0DD%F>p)^rbMZ$URzT z#wFBKkao-2&fcg`IPR`s^b=&_bijfMuwWJjHCN(r%G9P>4vAfZLL~$N1w}SO4zEC9 z7L;(&F<3F9ZJ?qYh>(a%C}Dah<q13E$=0^6=TqHkn+apb%Nxp4rw-t0PhUt!`Wf*A z8gPRfnt%pAykKh!O{`*H)=(@k(TP;-#TBZc1uZP0ta}gyGD^CNK<ptAf*@-rx|Pnf z+T@gOO|5EKce3%(vjlbR<;_k&%f0`;5SO|<!7&X6gFhT15iCd}3KvUUBU+3IQGkN< ztf0V3V6P2{_*xaZkcd^Rq7z+!LK`}<ibyhH4}n0ZX;He`@~(Dm-J(MIU@1r%wom~H zh_8I-OW*q1x4wIe-wcClN5^d~1HwD#<eW<20>_PWNldP@rZ*DtGU0hBVS*B(7d8o3 zH47IWFL}+&VYklHm9RyqY-j0#qM7)_C_dW!Vhd1ll>h|AjWIHz>O9l5MT0D%3uU{I z1ubl_v>L97g1*?{B8&0E;Hp@=Ajjk;JNe1y(wV#>K;<f1`N~+%vX<vng8f4I%V0*B zn8QrwGMo9#XioE&+jTML>E!>%7<3?zgFKUIrPRoH79o0Tx&dD$>sT7dK=1}F=t2|v z(1uPlqC3E7SpE6YkdCyZC;ey7;rLl}1`wCTfgO9m2xNH<HQLAss^?Jw3WQ3vs#neG zR=fJuuntrWdW7jrkFC=&BC@D=ovoR+_DTf`QWu6z>|z`H*vL+{vX{;5W;^@Y(2lmW zr%ml@TU*&d(!vxJ)f!v>hio9zHLu6LDU*T9L(RfZe%8(IcDwuC@Q$~<=S}Z=+xy=5 z&bPkz&2M^Ru-o4LHg^7zYfzK>;F>abx1J|GVRxZQ5RbUTCr<H-Tm0e<4^nIbzP*7X z{NvX`Zx`em1t!4Y<S747xyo10@|L^&<uH%A%x6yXn%n&5IM2DxW4?lAWsu{V#<hz; zPV_PDndD38Gr^Y5^rk!g=}?b4!9t(`rCI&zSkJoFx6bve+f3?U54+gMPWG~!{p@DH zm=rQtYoLpT8UDCb(dUjSBrm~#YR)_4#-+2uHQ?_I0KDKE5O~55zVL`Yyy6Z2cMkwn z?~sqY<R?%0Bp$HsIF8BB_cP}Z!QGv7551Sro0``ecy4Vh@y`~}Gu9u#^{{Wf>|a0o z*wdc&u9qPVWf$Vp`~LKtQ#<GumBG%hBzrAEzEG5}qR)%|`8Ogpt=(3z7^hFC2hgi+ z^{L-Fiuiu9ld=E!jS1DuLxBlUNF+*zz4?`7p`tF~u}r!!J>#R~{U*(l^P$gw8QtR> zG=+54S6p|6HwCbLd-YQ#ur%K%Gf|@fFrZZ9H-QAyP|Vc^7&rz##sq;72xsL$J|;R{ zfD4@<UK*qY64fm&(PL8Ofj$<38q{MObP|am2TX8d?e`!1*MB@XA$Iox4Twy##6mlT zfIZb$EareY)C88G106726c~kCBYarE1gn4yv)~JrfKFBQ1^1VJ<C6tU5K=0LVG}kB zHkeLfvjjwNNM|Kst`jyYkw_baPG|*1a%g{V=MSLQgMJtvN9Q(=V|}xwGudZ^afDkd z7KAW^L`VPN2*aQQ8UTe-Sc%~0IS3?5Ou&8#6bR?E7TUE3a-boWwFj#}TH4it$iO3a zh(Vng2)N*ZRiI6B5H?*<QhUHH+0_PtU{YDo29h)edKeZv_=m>W9tu}e8lYPQScp4A z0ElQyKQ#gjST#t523z0=N6-Nuz>JpojhA>p57h}BI6Vo(42_@!*(C>+unMve2y3wf zc_0f+pat4h3A3;Y%)pBGw?vIF3$nlrfj|U%Pzka?j@pF`jc{FZaDIWXk4!LKv(N?v zd5W#*A1q>U$GDN_@qYm*h?J*hd{<)H7me^^IP;TcB5+hdkO3k2k}w&QkkdSw=nJdh zTu}ee1xwHfX4M5;H4BRr5?HVVfk2NwSyoV>1!#DKC{c>5FqDTR1gij)oq!BfFb2!e z2v7iCN{|w(&`e>|2!b#MjgSaRFpOXEK^(c3<^fkV^+)yddn4%p2WXNoq+c|&RCO~s z2a^IUpp8!mGru>O{l!>q<}6UaOkJr#N>Enn$W_SD39`@#JVunVkS0p7NN0tHD(FB< zV2V|EQL;dStDu!_U`16GXI1c(-NFQI&<lc~Q6?C4)G`m^#+JAVR~kZngc&vNMUr-T zmxl8J)QCAHkO45@2s)4f#Hp9P`JBn4OeOM_Oo>64)stK$2tq&wy%<6Bh?!+Y1W^C5 z3TfDspZN+BMvhV$2tuF*;q{stLQ1STJ=Swb@p)_6F;g+MpZwXM{`sE|fgP=58q`OL z33Yu27@T~ClHNBpHe)ep0Ew&M1~tTp;8=-U6IBr9W7f%&>bR8)RGO7pl=Y}x3nUB6 zP@WEyK$WmS0!feu*<IRYMKO31tXY|IKtZZ$IzsnpxcQ^D>1*d!poExud8MEysY?}V zjUaFYX0QclFic5!p_bS=;wT5$gCg4Xi76omO=OQ4MnzJjT}`wH4U}WA7zhotm7bMd zT`-C{hNZ|yMfr!Ho(80N>K%5s0TyaRL+D0&6R3qVs0yGr^d+c;Q>gGYUx@!os0?5` z3?KoHSDbyCI2Hq77a%-SN~Kb0f#^p{7-oWEs02zNUKsXZD>`AM;}X+Ds-?Py6BcKv z$`TPtO0)VQYMG}%`jM_wsYFzOs)u62I;=&r01I$9ONu_`f_I$StcKY&HnxJGT3H;l zc|BHHFmbIMib2?lMbheiXekzUR&ct?ks^n5gE)Q#;{oj2uI~D-@EWi3I<M{eVgh8K z&RV61=`{u7c4UEC<(j7-rj!2jM>0uf;^%dbbFd8CunzlV29z<<<*y0y58v<^7@M&g zyRjVGu^#)eoWZLV#suhBvgdcQCY!P-yRs_VvMl?uE*rBjJF_xdvo!yEvo@QvIJ>ht z+p|2ovx!ty=$DjJpj=hp8%Ue9N_!gs8?d-}bOc&iVNh9ATeVhuwOE_ATD!Ge+qGW% zwO|{zVmr2ETefDqwQO-B6HBqgcxO)gw7$kIVG}w$mN9mFw|JYkdb_uL+qZuEw}2bC zf;+f`TeyaMxWjiFY`Y)q)Q4}ok>Mk^C}9#LTe+5dxtN=|n!CB2+qs_mxu6@mqC2{z zTe_xux|M4bn+pXdvAF%wxR0BgtyMxRQ!uu>HMo1bx|_SaySu*IyTJRq!W+EAJG{nQ zyvTdJ%A35*yS&cZyus@-R+j=I&;d$grTyx<Z|AnLyOz8<Dh2<eG$1g(<XgVxd%ozK zzUsTa?AyNX`@ZlSzw$f3^jp92dp9L8uL-6o+DjH((!H`Pxvw=b1YE!de832tzzV#; z6JstZ@B$Qo0Y!rW6tJCbb09M4ZFUC090^xpb0takup)f02Lom3qGTnkWK6cOBizDa zHcJ=~G<u@|1aJTqP{AV?f|Rnu5cH}s$iqM!#Fa8|<jTR&M@A?!1+e3*`TDDkvw#^O zL~$84Admr>x&a5H0h!92FlNQVV=$ZA#8%TdFx+~4LjVp?0Tv(xV9+6$2Nq!}2wX~M z<EoKH{CvrXbm1~!(Amd#R6sD$1Tf&754wO);09>00w4ddk~`D`8~|HMAXqREF1_c+ zz$XF_EWxjL#%YYhZDR#hdqLMK%AyQ{)N0BcM75yU2EmYyXr;<&m8*9QeR*tpVoY3* z69O=B2)Phku+@kifChgs%oN&Ne{ctfa0D071j9VcFffTse9JWRIAweQ@U=H+e8X() zHCC_$q?)QqaD!qfUZfK?uF8}WR;noB&8xaq*z|!}z|K3$MH@WJe%LxAS3c6bSU}|l zhcFAl)jN%t0f*286QBc&kODg32q!QBcfbb|zz1$H0V}Ww%lXUu3_xT|TbkTA*<8V3 zAU)HS2%Qi~Vbe&Rum>q2iX_#YWZ9y7pb~q~35@@w67?wvJQmND;L2;^M4U9w+EdTB zY0n@RK0`WJ_?po-R53ju1&&Yy&^$ROK+tFqrH-J`hp+{Lbq5iB2T^(m7ah$?%~%U4 z0ujtJ9^J{?Y>#Cn2-xJBB~8-SRMJY&1{CxKI}J*Epae4wO6HU%Ze0n9fKE!V)9N^e zg3Xf`8PpyJppO06kR91fA*4${ph!K|3iY5Fa0H7`1H=?Wk3-dm5TRJ@2E)wNf8ftP z6xNuXHRhr;XKl^xL&Iro0X)DQ4>eX@u-8=t1w<g&L{Lt9AeI;uQd$WGjadmqumo~C zNmn=vNm<zG=#y7CmB?_PT*M+EyWQN~-QNHG-Qb-W0C+O>h;)<K+6r}?3(W#R^kT~x z+F4x#kC*`qT>~|62V5=DHE;t@9o6WqH6`!@X5G=8tj!}=B8myhOi)Ewz*S~x1>J>) z9kScl)JcvB%BCUM!wub9zy$B?lLrZ2dr%rnTjH)!j6{vcaT`~rH^r80$rZx_ThIzR z5P=y$Sj;)qe}D!h&;wV^-z>lasqN5i00RhJ15fDUFYZ*B9Kk))H$bDtY^=oN*^9%y z;I9x?Zm0!q@CrDMK^4_Vp(O|m)JWVSN>C68uRz#4ogqswRkKK$KrJ>Xp5mexxoM)u zmAvGA>@wl|2eXh1vv3Dme8?A2F*^ScOq~D(B9H=4U|oFh%tAg3j*tWfv*&!yRMg1P zXg%8>J>?G72BRraRluFI&<l+a(l*+V)3pk|Fbj-CQjO3HK)H_AeTq5>THRuzxWG(v zE;h};hjz|?NIZR){olrAE-Y|z%TAo-qFayC0V}ZV0(JsHz5<i@gv*Z6$Uer@IN%3B z0P|G<3!u$lpu|Oci&+ZhC1tAgw?P%v?ii--D;n?hM_G56lNH5$9Te<kGVJ{Ky(iS| z#{>e4+yV8YG>u4gHFPi|P<49@TjNXcSVP7G9yG?<GY)_O50D{BEFfDXhg;+lRTc6n zVe+Y&dHtC3CspSFKX)G7N+JL3!Zcs=Hh=SI_5vKucz;KD9zX#Z@*CD_d}#}=;0mg0 z7_R!qhyL*Lp%;jARVtJ=^;BQ=R)6(aUo1;Ez16EU)SE+?$gfAcwqc?4z%J}gPj?<! zMo6~;JNNc*ANO)U_jF(PcJFdOP-A4@zaG@1X%BMJ7b;^PBw<kahJW~opZJQu_>AB9 zj{o?OANi6$`IKMzmVfz}zxZDe244VdW1qcz-}klo_eDoj&tn=KVg*j1`mDeDuHX8w z|N62Y`?Np%wqN_WfBU+h`@FyVzTf-6|NFup{KP-}#=rNWFBGy&`s0?2r*8!q7yZ&d z{nTIm)?Xx^pZs6}ZbSdg{6z-!RKNuGeFOVl{^WoD=5OEWfBx*h-{}AT?f?GfAOG?X z|L(v3^MC(sg8%#9{{T_rhCqTh1{xH2uwcQ14HqJWs8C`;iVzuAoG8(u#f=*uVyyVk zVT~nGuwbcD#fp`bEnU8Z8B^v=nl)|S#3{4cKYRA>{k%6%=uo0XjUGjsROwQtO`Sf4 z8dd64s#UEHz4y&uwlzz%SUDMGiG~ej&6@r2A%%zxDLRNq;kLtvvvuv>#hX{}UcP<( z{skOZ@L<A#HSma%1<T5ujU7LR9C_x>o>whj#++I6X3m|X{@mL2YuFzkN}ND_qQq&{ zB_h0r{Tf3B5v~7GufDxn_io<3b?46QTljF?t%)D!9US>`<;$H9Z~k0(^yM9RfT@Bd zOBTu9y?_5s*`8<e<;|Z*pB`$w&`Y?V>@v1Q2>SI$jQC)|frA755B!%Pf(=9vu08`p zxNo=n4y>;?2I)(Xw+BOTa6$?te6Y6#GsKX=3Mc&Vzz{v`P{a~R+zrIuHn=W3@M_}D zvF%=@5hiB-Q7=awcjU3hrm|{pG%Uo@0Kxl4fN+G>7+~N(1^zoAKoM%Q@W>-4v~oi% zv)s~33yt*B!y`)wGs5}qOU*bk6U_3;2ixqD%Qxj@uuUxwgmcb3lPrNnDNb4`#u*_S zbVlx=cx?X(L~G0`Mw@Po$45ygrL<Dbwraz@?1q$YLo4%>fB^#xP~gb}8i-)Z6TW1% zRaaky^+6Ce_@GEntpuS1C09%90|ZYHf!4I{jI~%}k43glB@g>k3n-YFk%>jO6I9Td z7DY4*DB2LDiz>LI)=+A{tzwK-67edfa9bKz-EqS$v|V^x%GObtAdS>gefQ;;Um&x| zR7fI?G%&&hL^U9R1P)jL)f7-mHe!ic9kT-+{+NZ28a9}Z;1Vq6LkA7WY~qkr+*siR z7V>c9kRvFZIA)n+PS8&*mZ$`mHk4?imr52@mtA|=U1AShUYTW&L$hc@i=byRw3Aho zaN7SRYlF7eQERn+X*(#!s3bmeXTrB%v(H95y?+A+i&N9e#IJ;dM^%_%R8<AjPQCZ$ zyKle$M$$+!ML6UM9nkorgN_sYpoT+=5qSg0lepN83EcQYha?VRA%!ym2R(GrM<=}m zX0=eFmumKaLXK>3QKE}6x`@%+l(ZNc^+bA+Lyk@Yfr9BVo}Rr6Z?iDocGLsuM2XsG zcQpCnzlHu=<EywnrQ(A}KKrkck)w^_hj!`4w9iLBeak=t*sHb&hWi7#5w5%82-aGa zbp7`qoxT?w(SZm`mVwh$EDvsQ#1Y7%14qC>1b5)W1o+^F4AcOC1Y8sUG`K+yTFL)( zJdlDGmLQ8pbRrKVTt(|vF^fcuK?#BoL>1&vi7{|*JE#*xC5XU;HmqW2tLOz4QqqM$ z%;FWekOL7afs9$qLJn0Bp&*)vyDA7`7OU7p7gX4bPP73ET@b_y1p$RdAY&DQkcAJc zu!j}4Pzi}(V$!r13}oOU5m3M#yr=~!_4Uz@e@qId+!vN5ye)7^$`6xDRVurs>IL$f zStOHnANj4o5okCBCOM!R`jp@UE3n`ZHej(#{^1Umo8TWXsRIlWOOmgIrQlAtgjGl} z5x<iK6UHEjK)fOlN&uS__b|5Gy|EHZ(1I46s05=ehKI5U#2(tv1tqMa5o7;g;}~wn zyd}`Cb%NNP7qK{oKs15~dzb|;ec`)Cv>|D1>=`dvD1=JTP!6-G;TVu8KJAe0ANc}g zKn03ELB7Xr84R4k5XMOR)h2%(gy;r6xq?Hi;SQQC0SG=2xR0@*6*|~}26T|gJCsy{ zdAP$C4#CRR_$^6E;@?a2wn3Pdj#*exf-Led24u8>jaU#wFJ{pUK`fzMy~qRAUZT5W zc0mih*qJ-S(2^pC4GJR+1QB}XttBuIndPd4P@CaJC%Pv-duYZidXbAZ{H_W*Yr`wr zunb)E0vCaxXCjEu1*k4z4ETfsN@&8zffm-V`eF}PG(|{T*-3tLBh~+t6yPw3MbxtU zON%9SaDmNbU<5E=0f8u#0nJ`u0}MRD1>6w930^?6t#p&J!X#Td;i<L-vs0X0S<~4z z$YvwVVkfZa!&zvt5{XcP3IzeKZ{6^PI#hxjR#C%yh9P)Y#X>p9u!P?UL7z43YA3p> zgho`tue0zXREaPKIVd3ztI&=d#_+o?_@WKc?HP63phV>UHLAUE;q>%KEz02Num?tP zj@Xx}F1&9E9E+a?Lbb>z*$;m+y=;d4h8sSl^bc;(KnBoohYZMX14(ehF#gbl4mb`C zPvFBAF7SjuJOPs|P#nQR00JKOn74uJv5)gcpCI%2$3!l2O_Bc`<RkAm$rxU;X$}*G zFf3sfzdS2GWx-235<w2K*h3={0TbOJBM`!bLhE|rt*^mQm_%5`850q<EG!|6vFmCj z&KwLcR-zGsIBs-1!OJcVx(m4oAAko9=sXCa6O90-&SKYzL<r)E<ZDTR6TE3om!~}j z6${5YmN)q+QUUd&>_auY>f90xSS+~1A>8nSJ^>*K80-Kh|Imn8TkH>&ctQ$xjD||^ z;RYjPb+R)&rH@?)3s4Az7q!K$)^)<#?cKv3bSa1$YK;lLyEe4i%;vUQTWL8pV;8S0 zhd@B93edK;aKF|FStNqZdoXub<)DQYj^U2w4#cyw%>@524zCJrsKoEwtrMOY_$Qr) zc*Loa*sgeskn-ydYCzS1Q!}Xmlf55xq%(4omz<OH$-o6Nuz?YrKm#Mgc*-}Bff9Ri z<{H?j%T;ax5tzp0KL>iyrE?fCV1Wxzm_im<a#d|9!RdHRGj}xAH7Gbex!iG@rkd__ zWODbHP6OAo9K{5ylWPe|FltJwesyWx3?*J!I}@}cEveJ%><eeOJ^u0VdGKB0e+Rr# z7CcB!VSG(|DnWms1f>9tfItXUcI0=pD+M*j@Sf}yYm|g>-5yd;v9)b)X}en}SLwF) z$<ha@04SEI3+&0HqPQ@f1=ts=YTv3o>T2l~t@Z!D_P9?bxM&~y8{QE3;=;Y4f?tyY z^WE=(hyLH$CmIKfnl-7>O$BDN{Rqs4Hn&Mr_{Bed@|WNI=SP3~v48!H?<P&ZQGfj9 zKY#kyKm4X6f=L#$lGZbdCfbrF?(x3?%(R9Risy^I1dKR}>!wYKf*%kTy6Ba%NQ(~W z0J-3RxNwVJNs9>Nzz+n$5EQ`?B*79i!4pKm6jZ?#WWg46!4NEq8lW=4VhjSL3A!UD z8>|sc>${*(z#oh_L29s*aF!o1!Xre&Bs{_!P{Jm3!Y72nD3rn}q{1q+!YjnWEY!j+ zbV4407S_{2sA;aJ2}2sW5v@2t9|XcRM6mzF$`tNkj4b$qIi$lnw8J~Z!#vc(J><ha z^us>{#6T3pK_tXNG(<nt0vhDMGGxR?tO9262Y_P3Nj$K@gTvO_j+LN-P2|K*>_m5Q z#84E)Q6$BhsKFX6#Z+VzNMsL6bVb9OzNu5XL_CRFw8dM*f@D&~UF5}H^u=EU#!QRE zS0qM(>Ip#-m?c<&WrTrcbjD|7Mo>ybR1C&yw8m@1#%#2aVJyaO?4x7k3TUZ5`SFzr z>6H$EfiBoTZDhxGbjNpOL{{|1c|;#@%oHkcF!{L^51Nk>NP!x_M`|2EOtYHVBS?5e z$b?i#oRCL)bV#%*s7;9v`B4qM0ha&O5P@_QtU<}a#?T{r`M+loEOvRfg*3^NM9FPz z#fM}`OBuXm#JGgA5&~g?k@?4fw1PAP$;em&CRl>BqaNFV3GNt!X@UvaNy(&CN`w@T zmUPNWK}H8NBm<ce(`Wz*&;bg#N&Xvy8p0mvsXc00zL@BO`|2Ho8-r__o-u@?u3`o` zSU4?U0(=9SrL@bt1V-_2J~e#GzATSe9KwT2kouSs3h;sbkbnyKN9~}dN+_yr0W7PN zyDT6(CFn>Il7nSvBHn=(x*HU(8y76%y((aWbIPTI#LLuF%`$9CzjVzU36feIm=kck z$2)-+Xn_5201vQ$6o7#*umb<o88k)NDlOQ9K!~<9YlA!}gl@B%qDdj6@|r#9mT&o@ z<CL~{6HTYl0&t46bXm>t6wfehKE8a-^W2QV3rw-7jSXM{7T~!TFihRV01$YA7F!8w zqO|04Cx5fHGvb+qdo<^~ouWa8Mred55}`z327~K@Tk3>Lkb~>OBBgq-PB5be9M28q z&==85A4EX(6j7@97wRLVwTJ)-D1r#E&)nP(5AXofKu2|KOyoK^04uLRaE})X1_WIO zIRMXZDVk$2x9b`Ms8UX3I4&i19w-n^>_IOgKqI{C&?>dkoM_Dv)zZs&Ne6?A2%t|4 zpildh9}xgZE2vT8EUy2w9JDHUAtm)Q0u@p=Lc44!7xYTAF$jhTl~4-Z1Eb=rBtoO9 zyV626)R<_^5Z%&6eTs-ABm$uT5715BWPuocycyLFB^b_a=>;&TI<U#AIU|CuY6HBh zv!61Qqw*ri!~!qVHf<42<Z&V)IH4dt)LS*woyZDC<<*Ic%8M%j5m*5i-46^{ffVq$ zV6A}$a~9u;Gid69PM8H*=!8As8L3$X8d}S?L{*pYFS&crIO~K7<&N#Fg7=bzT*#%{ z!_{`JQuDzI^X%1mMG8md6b%3t5wL&?*pEu(vDKiEj8sP}n6_+Fnk+C_xGdN`kkghZ z${f@JqvVb*$hQCNJU9Y1*fwz2jkVIUq1TUH3O8IVw?PmJS%C_ufENIP74SI<*-CX; zyR`eso(#LEBcDU*8p?c$v)fiXl{(Pm*q|Lxcm>&_J&G<RBoIK7eq`ByJrkEr$3<M1 z=Hke9k%^(PTB^;OYMEN0_1e@VTB8-)H2l?jZIB(Syw=!Cf&ALGbzATV+p!(nvK5PD z)r}RHjx&ARz2#f)Fds>j+mE%!CBVmN%*ixE+-I2rX-V9iREe-0u*j9%$)()NwcN|a z+|1S7&E?$A_1w<|-Ov@?(Vg5gl-I!R)mZ!r{#(SBVBNlj-PjEef2a)9HQFF)y<AKt zKx9|h_1*v9EkM1q-P={H21|*YT!J59f*<%v=1tz_O<td50wDt4>h)b7RMg=eQM!Gw z6r9o4wchY`TOQP2dbQWOg+KCJjhA&q)D++Mtw!=K-(D3$iChATguK)XR*fvfcY)vk zWk>m)-z`<o>T9Vj!AOma!{39V@2ESD1mFk`Mgbn+5e3Y)nMmE>oAm|A{j0OGle(;Z zj4s%zZI$2??nOvM!wTlr^S$50o0EXm$QS{%IQ^PH&=#SImqIB>><I*Q6h7MHTK7fa zB8J<4Vqr!_TDS4MFWE}D1hhm*gz`E#UjT#P<PNe^l$1C-wBuqy@yx)Qk*ng_EUr@{ zMq~d1Y{(?mQq^@Ze08ah(MbIi1TSWtF*pXbYPWN}HbiNJRUo0VTrS#!wj^qV;v$!F z!=m6}9(5z)G=^k`<VH5$QWpjRidovNoHki-A}#tJ<ixf?O9UTU0$-?vJP@;c$}Z$O zqjT!1Jf$=k5>!#1E)$OATXqaq^oM!yhhFyOUk2u27Up3l=3+MHV@Bp=R_0}9=4N*0 zXNKlz4rZPZLaEH(Hc8-twE`Y`uVr$lEU?TsVulrBhEhc@Az-6>BBM@#0%%$<JcXhn zYJ_(quVq-FW3X6U*5{niWlFZ-dk`diWUNv95`XMqmKYvjLL*MyE-QGWRp=dtg#!O4 zIwv2hw|crIYxS?#NeMX+gli%%h?ava+UJtS(n<E`^Bi1(zE^@)78xE`CIF{4xUX5j zf-!i7v&^%iY^NpY1#a^yLCA(i5b8$ImLv5d?4jwl3RN0vgLa})la}h2P+@?U=Bvi) ztk&wS=IXBY>Sd;8#Y#p);v1+PSg;bRoJJIM!iA#hf<x|wKyVgZs3Td}8GM@^$CSJI zLdzBE1+{!@Tu7QcBHh9^?88Rv#8&LZW^BpL(v&{WvZaDf=^K~T+jpY^=}|k{6H2FQ ziKOXDg3aM~i<g#29&LG#Ih^X%o(!HC56DK(AaOv-&XWb%Uv(tIvB?^ego6KGu+}l` z+W+fF)+X-Y^@-DkZHHXqC{O|runjdS4i3g`cY$Ded6z`6*wW7Jt`*_pUhT(D?!K&F z(!e<il)w(83t_?3?vTz$_U`w#i4P6$r*vcZU;-GZff~T?{MK*&-f#TA0d0;92!`(h zhYU^o>I7Ht1!wREcW`9}XvGSbT)aaq2m?I4@GsEX#^&%2_wWw~@emhr(UtG{Zb{YE z4vwrr0^jfvckvg8@fer!8PD7ssa+F4@d&Rtl@RTeI0*v>a&06m9M5rN<Z)0ua@S>D z@D1`NZ$ytJ@|N@mZU9oDbn+|5MktT+hm41RFefW#ODq@jU5wi;pU3~7=yKSBq913= z*B$dWfAW6<Tr>AZy`zRPAc8Mo^GsxNIQMe`%mR3Q@Ifc^LO1k7N9KR>2V?*PBG3Y- z5=+RX@kyujO1Jb&PwZqWb2_hcdx(d82nIYKRmPPTCNTA@dKOfd7DZY0RA+TnhxJ#N zbyuhLR=4$7uXS9%^;zHbT<3LN2lihVc3&s<UN`n&FLq=<_F-T4WM_6|hxTWec4w#d zX76<+AOZ^J^lrQdy&LC1SOYK+_i-opayR#LNB4AB_jPCYc6ax8hxd4w_j#xHdbjs` z$M<~KcXnTcKq#<$0Qi6x_<<+*f;aesNBD$S_=RWqhIjafhxq@9m-vaN_=Nunz59o) zScZ+~_>TAZj|cgX7x|GV`I0yJlSlcKSNWA^`IdM2mxuY7m-(45`E1AsZQpipj0bTL zhkN*kp9lJ&7y6+m`l2`bqeuFrSNf%A`lfgKr-%Bem-?xv`l`43t5^DO!1<i-#-6YT zafpYo7yGd%`?5Ftvq$^1SNpYR`?h!cw}<<<m;1S=`?|OLyT|*yS9_t@dan2Tzn|Z} z2mHY&e4`co!bkkX-_jD#Ud4C($8X6shWyE={Jxa@%E$c7@5am5{Lc6MALRVc7yZ$P zxX>s4(?|V*GX2zN{nkI9W<Y7zm;KrA7sf|!+Q<FeFAx9Q*Zto2eewYB-xvPjzl`7~ z{^Ljfrzr8{Xa43#3gdVFKl1wNf9>c;UFf&|eF1o&==SmO2ZQ&A?oY$)|5zKZe)9Jh zA3VnI9|wELhIfGf_=o>*m<NFG<r_zTM%D8Crxfl7h<X0<eY2PCojYvUz^QBK5S&73 z@3L{rm+#*{i{r-4>*(<#$dDpOk}PTRB+8U3SF&vB@+HieGH22h$?RW8e>!*a?CJ9- z(4azx5-n=<DAJ@#mojbY^k_$W7{4LJc1<0+b?ex1?aH+wI*8aLQrsx;-qW;d*RpNv z_AT7Fa-ZI;Y4<MPyn6TY-Fxqzz<=D{VY3#lVY~ls;TAJ)>~$ShvC`-bv}dp5-@ckR zbMEZ<Gw7N(<ApA5`ZVg(e=YipN4Q%zu8n8YW(@nQx^CX2!NaJLW9s0-hZ8S;w{Fh4 z%9k^5?)>@Aoc~_Ou5JB#IN9N1Q-fzwp1kDH$CEE_{yci4$kVfL@BTf}srl+rvle?D z_Wakic55dw-#8cv1RsF~8h9Xj$QidFgAJMnUOw6+)J<-R>31P*?5qPDZ~u&AnS&vU zI3kI5HS>>Dna!hOi7mP)qD6oG_02f+AhQ*QIo8INR@Y#&jXeNjCgY1m8hPY!CrV`z zlTAALB$QD~IVF`<T6rawS!%f@mtA`KWt9Km36@Sf?C5xAhTeD+4mR%S1m0?3$~h;U zb=r9+o_XrIr<6+Kge0JWs&<cM<K#mRHr}YC9h!|YrsjV%UM47|m0Bv3pO<R7sa@dt z!;Mw#ENZ5sr5>hEIMmql%{Mx6`YNoKDmf{OvDzA|jQ4C*k2K(TMXIT2^0<yd^7vy} zt+y(>EQ6Uc`|PWK1xT2$j0Wo{JKd}Ujx^N#BM*qsiaTy;&XRksk+}-i&NUiprPZ~j z_J~bA{s<H<y7}r$lezo)+n}^HN)t{y@fysShP(j?-oFhyd=fLQJv?!6e-%0%HsNdq z?7`T&drdpz_yZ?k6r0>|#PQgBGRyy+1^j6`)mhuI$B=dF&xiIT+cM9~rra~odlf1$ zIu*`LGn%mRmyWl_;u|#7ul^i0)iPNI9-<oG#xc?!t3&KN1QA*_*_Nifa@lE<q++4@ z5a!LsM|XWDkL-9u??0}py?2q#NX$3j9_1R<KUOs)_uOZ`%j0DB<QzEU4o)38;D6~< z4?Nyj=vCtJHgt_U8BspEaW`4UC+exIzB=o94oy$5_;pTmSE<&sQR}(uzB})|`|jkd zD(*}=%NDOHFgUW$PIE)pg#9@2(T6tc@6}s>J@!tvP3@@5cZ?s%-*`AqoY|XyKKkk7 zIji()2k6c<aC_giR*jQia{K@J^TodYQU8Tvs8BUO=BWd8`S8c!`lrB}1g~VnTj0Ki z_K$k>M`Ht|8Gf>*DvLm{gP20mq&jo4!wcDo?bhV>(hJWYfyGztG+_^_eT$5$xq z+Si;1pccxohaVXYX?)nQfWa<#H|!XX!T~aFjPHR$6d@3w_^;RXs(VL7BDd(V5hqF! zf(q)QzP6Vr0bbEyDtt%YVnie`dhm;EJXhNgrKU1skR3j<$4)r7BK*Bke{SsKvn+G5 zge*pBvU?XI6RF5WGP045e5CRg<BfJ$V}pju2eSAGNa;m!lh0C-_}~XO#L-b$?!tz* zfWt*kMovKpdL=AlITZhaz^@$}vQR1GwIR@XNS40*B{0hqLsmY^AO8?#+_;v@QgH<y zx4R!P^VhFv!iq)yNXXYXx6Es4upTs8B{lcvr*MHYoG%ij<BkckuWf9b@#5At<^e99 zY0{j4^ONxEX-_2O>U|4gCn?>Dq2@{BTOHBkJ_CnOeI~S0_fY33YbVe~$;KN#(py6# zH_eP{>Y58l=0us<6=#w#gd9!VLQlG>Ypzo(0Szg3c(fZWLQkb-Yv7P<Y9w^}lb!8^ zsiT_rJRT-A9!3o!)F!7>L5WdgF9qs;-o;C3W>jJr5s=D)<~O7+HBfQPm=&SgsCC>8 z8!L*6NzEA#oG|~Rt;|>})VA7HO0|s|*f^Xrkr)neWMv)b_-j}qnL>6@<CzV;hxm}u z1|cw32xCA-KDf#<rOx$8uglm^2TP`eD5SIQXb0Q`doXr@;~nBC={_%#jWNW428^Xa z45B~{;P6bYl?7Cxz5%<hbq+S|I0rCvA>85WLKy0pqiE&DpUKFhrqQ%aVqF^uK~R?n zG?>LdBx^Ft-quJPDPm?1Hm`F?!Wrg0uX!Uuj^oO2wCreJD$ChL#MUDp$dG{&8j*-b zGy)1S=tVxb(KGILmqf<<t~Agg(eJIp8rUF5B%Gm-eNdRf`Y^9G&|wX4XsBa3e23$R z%0_klLmU6maD)tg5QsaVK@d@h0d~0|Uv!y{o&|nU!0NFLm*zECWVJ>+_z{VHkfX>( zCWm>=!QS>7>~rn_(2PBJ-~id97{mAkDh}}i9<aCuZqUJh^C6CT1SuaUqn`TGtmZXa zNnQ2OCe7634j~h{$o#PLg_W$PH6g7V*ce***eqx~?aCg{uth00kqK1Hq6RW>!VhY| z1Q}en7~iPJGY7ppG;6xkS-PsH^^{{1E|_LOrZYKoQH~?$nUZ_<aBkYc#4X+<)VAi5 z#s2Y)VW6TEs6d4%IAM!Fz%~ZPrhyx3;fh*d8ZEb09ZvT+IyL6Xm>BugH@IO;odhg_ zxBCB$RNSF0GV1bO-k9@{Q%wwa5aZ5C2JNe9=Z(Um)`$JP-#@aU>`?GK6rvDCC^+GW zKQLhoe{cjR626IHJVP9rHnYRVNh^kyEnpkj2u8HgjAl@y7Pk2JFowa6c!-bIfppx5 zAevkslNH_j;D;LefDKp_`NGCnGX2ysnQve+tunm$IO_3_Y2+f||Nb{9Kp~1vprRH{ zI7BT_!HH4?`x3Q4(Lo{JuwmwJg4q}b)iHqyER+2c{|-hm@@5ujLH8SWZAjO=VGVRk zLJ?{>#TX`_4q_yE$t!o%yL3(u$3;1R|HC6UdX4m?GydPGu!IgAQ43CN0^mwtc+dYS zHmhI;b4XHoM$t3D@1+0w*Nx|dCK!%Mv~a#D7%>#07;-H{GNv8r*o7h_QFmRKLk<9l zfjexzWIh{AD_C*IHh6yR)-#_dBpiCtMPYizCmrCZa6}I*k#K$=T@<c(#_F3d7p_z8 ze?#Z>(fb{WQm~)u>Hh>MP%#W`<Re!Ux0JMWJFp%Li$d*a$1d~%7pOucM1nr3*Bbx; z089Wn07Hgt81Z=+o1~J6El|L8M82UyDp((|i9+@LTPV~5A2fk0Y@fd!ohhJ#wwc_& z08u`vO|A%%t~~=NU;+rL9}cSD4Sqr>JOc==UEzty(1eSQRY$PEMt=aH0LuRXDOdwA zTv#OV!yYK$0@8yzK;Yb<%2;@a{oNn&<O-`u1<`SW^r1r1=^zN!f*U+REu0|0oggP< z!Z1ujK>(o_D$5`7jf$9sKkS?IxnK7M;?aGe2Yw$WVHB){O9{mc|HTwn_@5G%!6WR# z|NY-Nm_s>OLmN=x0=k1cSc3pPm5vA%t02_Rjf1h&LMn8i2P&N)hJr0T!5y?=D=uEJ z86wJ|%%6;op;*Q=Tv-RkAN=JYF^0k!#vdwVL(c`Fi^!l<U_&~<o#HIU|LwvfaDg1` z!e@b&sHg)axx*%M;sm?{C3Tp4fluf_95X_WPM}CWJVOc=<LJ4fE%g7uA)tc4ouM(h z;<9DL+WAW!?v3S;**_>7u(99bQJ+F8B=;R%E~H&9a!L&1kvhQ(npER8_5mgS-yA85 zH)>-zDxd)T9${ERc+H+gVZ$!=5L#f`Gq^%2kYOt>BnYBHD;&Wh)Iui6Bq2&4C_Dqt z`5cX{q#l+GrtMk^-e5z{<3dtjLw27sBGo#MNK^gYY-9_;P?8*|K{mF-XHAl9*v%w4 znC}UIS^B~<<N`HhgEfE*2DMx!O{GAVjAiWG2{xrGVwoc(fh7cDPl`h7O+zLDWOhLg z+Z3cLfWir)p&&NqAi5&J%^`}A%&WxFCt77=^v5S|Wmo>6H<tfeLulg|2tYju0RZd) zG8Doo>_S^IS+EQX$e;)dc98MxnqxZVCx~DYa00Nop&)X?_g&g-o=YbM4s;EJCiogF z&LmzoCn1JHKZeIV{3HGm3d+&LHYCqW{hu{t<VGS!b|}+2P|`JY!YfEaB>;c`yu)f* zgEfEy(rCrq0LfY0A@LO2p}}85HfL_$0UP4uK2qPmk)bPCnqln=`ISwf6@x8Qo^w8E zQ!eEvfL~6*%C6KyV(^%DWD7fRXCbJ;7;Gd*Mj&mFl`mMsG{{0BxWfbhz$u()Sdge0 zv4b^aLlfC&^sJRZ-sOXqLM@;{vhiSmGGr*2LM;$P1w#KzN=X~g?BOLvNGX`YAgUjP zI_Fb{LM}{$y-??+WRgx`Q<)%PA$6!Vd}xSPA}-|zWLSeQ?7}IWf;9-j?_t9(NMqNS z$u^A7U@DM`e9H7W=i>QV6Z}CfRNfmdB)|DuMVyX0;^?MqRM}wKFWR6yR;r~wr6?FF zB5q1Q{R2ImsC$A#nPg>|azP(>LM6&*e#qS}oP&EB!!gi6A{+xP{2yjAQ#fqHGs&ge z*n>FiS|+5QJbvKgC4nPIojy{jV)~mVJVTJ&1H<IYLU|j{G|6AoLzTHgu(4m2c5CCc z;;(5#L7*J90?KNL4>QPt5(t4B2!Td=Xw02LC6@onn!4vM_(DCTCKq7gTY?U@(i*Qq z&2I?ZG`Ipjb{}32A}TBbUzUQ|F{gn3+rkMZ$|dQoI7`5ii}8HQCIBMDdMltF9V&c6 zGl*H4Wvp?a#cH({4HR1$lxZ21fxNoIab*X#fCEEZ;V#g^YL-DEfL462gOA82RrODt zbVMzr;KL?tEr#GB^Z-oqC{6yG98xUG0?LwJEwhkNJ^Z331mdNJEir<iC<KFGV(X-s zqM)o5GPqVDyzL$cK@4z#%zEYF91J+Pr+ccyDX0OE&5?L*h&%l2{b+5=7|%PV;ID~o z9M*z=+Cs1<D-IrACKTud4X3#H$wgch=XU?D=YB5ehOX$2F6ox8>7H&zVA9ZO>(qJd zZN4t-l5K&`2Wwax>fSEy=C0?84=&IE5hTLf_5p1D?Eh7ZMZVMCsslFk!Oyzp><Mi< zxZ?rYuI^T^^<FRbX0Jt{$S+pjuf=ZCHLe@Dfh`1F?EahO*4O4{FZ;GH>Mm)|bfJvo zLot{_<ssx7imlk{<G-b#&J0b3uI)eg0)FjR8N8OfYEEo4VySqfJM`_}+U#q7%-~k6 zP?n#JJl{*k<UAH5|B6CA@<A<7o#Zm6_Zg@jsV%eER@z`%giKxj>aPs<8zE}KG5|=? zT1q_RL+=s+e*rHS#6SWs4`fUd^CtfagAMHk=g&qAL@{WquvTjKwL%g=of{To_h~AV z=nH`b&4upT*CH&)jxn)*!Z3uP;R?rEF@q4uz!<ba8<auIQew?6kEou)%j!npwu4I2 zQyQO)@zk1KiZRpbC109CLozM;UY(=b%Gp#+ju{$E%H#}Ja=&$7mhS1M{6izifU$k@ zBY5WgjOX$`f;%`by(&=!|8en@43xTG2@_+|<>nzAf#L$F2P<Z#)&l)$^0;(ylM)JI zO5J{vF~}YraDrb%YKqGILoXx(bv1%4OcIZE4sN)^E~tSoG{o_i%GX>2h|!h;(b}Yn z0{%kizvbp1Ji+1)>C_@!vo8N*BX7#th+ldPNG-gfQd;u<errDth&=;Et#K~4W+=HW zj}iZD9S4h00m$+Nv@cl%wifKRdTcE3ASwW9EeL5WcW@|-Y&N7^?LxFtoQQS>^Xb4N zEH5iR%kT#p=?=5<a2ORghyyoJg{`6x0CE8xA9SNMv~w}>htRLVnzP4Z@f$YXpw<GV ziY+Q&f-*1jFJ~9pKut;gB9<AmRx2dZsbJyGvxulm&y9or@s{_<R4LP}PwU7v)5ABd zk@O5s9~$iXS#)#q8!B8v6$9I!KByTwE777$g7VB&+kz=ja!Xe-A!5QXjI}rmiu|%3 zrgcO7sA|q(vo_mlD)0YX&d9XG$aT_+aivxtDAWSOO5P?I<7hKpD46lMa;cJnkY~S& z2E*j}-ZpMW@h4as0Ncvdc+^7Aj(oZU^8&3%ZOdfTo8ejKJNlX}-gYL`!qd9KCdedi z2WD@RO9RcerRWjQDcj;Dwo5N7LW05^X17Gjh_MtA1JevT>@*$Us&()PIM7=T$2Fn+ z>N7Ci4R-Y8ZbB`rGZg!`M+4@0+t|4bcFSN~J)pv2=Qf1LF8jryEkwh7aCdO5-2}zV z{P2kK_Q4}ygQ%DaSLiBi<F_vkL$F3Tz^Nhmu6S-^H-c+72r1$c?@Pd(PBvf}i}(0# zQaHt8uBP<Uq5S`oC^ED<V0L`VcWvB}AA>a{>&m5d098P$zirW3cW!TjEi}O_TKR38 zcaT4JZ0{+C^OLUR%r`s()nTfSuQ@1WX&qkDt>hLxyu*<j%(=-yC|kB8j^|WaY~_^s zLt(@;*g_n7V1&Cu73*Y#%lL_}FbKtO2Iq{|t~sR(;_MEH3P%fCKvY;Ij;QVePZtc6 zFUGr|12)jZ4&8X*Ttr|TLodvNBRImMExIV|<suL>gfsemJG!4gj83HZPO=|UZZ#Qq z-|WUiqgSTm6nPQrapyDyafi5BV@OwYgEZ9Ft`pCv1Og3E8l~|iD>|os{#z|L!VxfC z<qf+cS8cC5GEoBm&93~zOD^Zf5_`8Adof^AM<n}@qlI;5=%~|cl4mm|>iKmv(}C*G zTFF9dDS^YwEgB%JD<bMgbHXKDLSOzt6I?=40$ee3H3%N~m^a91P)(r~EFjwZ#E&t) zW8Jtwm)nfdD7!-;^a0IMySsEl=#VRvlTAM4K@7A(BM1VE$p8~z0x0lc!am*;+<?>H zK+EdDUUPywH)mv8ZO>OqaaJo12gwr?a+P9P)BRf1MIGfmcgQYsw`KiKt;(fQ!(Y|8 zHv?c97=v2t2W-AWJ;Xz~k`7}1!yd$d91Oi1pn=hky-_EfgPPqXycngm?BmBk4Ol{= zf&B+o--J5<_D}|mlL|5ve|*Gt-{TzuACSK3F9I2UaL6VqDhSCuWO{lJA;x4=sm&;~ z*SuN>l!u?XuK2R_0KVYs7ZdP+4Di4o9D*fW0w>f$*-Py8$$$``0UG218vFnl<iQWf z0HNC8V@7Ph#WQ+~%hm(({HiW^<2K`EnGVPR`^NzL%fJh;vo7N{ziFy<j(o~u5{BxA z!9OoRw6msWS37Uv5GGW}jvYdF-KfzUH*VfMd-f`3)VPsjM~@#th7>uHWJ#0p{soHB zrqLZVNoWXZa^y&oCT{*5T7-!cs#=R=@VMi~<qb4<q{zrqE0ZXvPoY8$rRiC|ixW*| z)w-4ct43!3x`q`ymh8NH_w4<v<tnNuP;cSBb@~>SCMGh3Fj2zfhh7>l{?y_$H*R6M zPfelv_AQ>-du1U<4te(5IC|LDsav;BVQ0^uK`XR|txz9>-qeK-w~pO4clGS~^CwT9 zWZSoKm*keOQw$n>nbe4Zrq(4#hyI}1Qu9a?G=JRC;6Zd~jiX0o+^O{ms$s&RKxO;( z4`Xigk-s)Rzn;CuvsdNSG8O8n;kZsiefmkm`p`Q=|43rES~ls<zQaU8#ixJ3Qm?%S zv&zS+f7(fBGu1H6FdT5&@r9sv)Jg3#hSWg^8*1zs=OWr5Y|+J%{`n>l8hrCj3QH3I z<D`~ad~(GRN1$6y1{!`iVhg_h!%jQy+&U00R4}RPDvDmLlA~tGi%qsIx$M%*FTo5` z%rVI<)66i*8%LW`Q2B(uw%~MYKOu;6!%m{MxPUlJLg~}bIO#*hl0_CdW|@5cY3$5J z8Ew>2G3Oa4pUc2utsxCDb%>qJ+$qf<&O-CXn}{T3@X=FIO;y!ZyS#_IV{kd-5JxVt zg}Y4(EG1B%c044eEu;|Qg)RO|O1q}we5y}VYSAX2d035B+C{Ov$jWQGdN0K_b$!#% zZ~vUD7DuGB^S^Vq7_g^L*k$)HPT=LF6iwWy;jftT$i^QBv8|Fee_WlXoo-hD%hcf2 z))7dJQw;Kqp>SGz%^up$>eu2b<B4q=TND&!lefMF#i@8}IphT*{&)fiKJ3gxNmK?C z1>A6#t>vF_&Z_w07pnzp=bu5kirYR3JFvbv>vSWDB-S`$I7}|-X-6J;R1g)JGeLz9 z--Hl?2pSVf6zCSYl$4%#tnmiagH^jQoY6cLwKIk?!-k%T$IhEQ*q(8vl$ecnYLk*> zAYu+6%q=#%tBWoSzfhR<hf2L6?3wbswN<l}Zj)_m@I_)e>W(CY&_M|yVi4j8DYke5 z4LA7ULnlitxkQv5i+MtZHS)M45jj@6+(ii`bq5=@A7&dvbvj)5Q-!+!=_W*K>X}C# z*@VwttcmQ&r|+0M7aSGPYXHIrG|+H;iyLGJ4E$vKbj9Y$wKuP4opr9?#mtBHcII&9 z1iI-Eg(kgA*BXxVhoQJZIY%f`6q2xoExZmpQg~e>@*smTFi3ywk(52^;SPc^<WkD} z45vzS5OhQjA$5C4_h>`0$8?Z}9yts5@(~TTDC>WZL&YZ05Q7-VK!`FRVhoNj3-JB# zO-^w|RVstC8P>2Y)hbW^sMsF<ZH{P73S0nVVy>F}rwK|aMlFhwMoT!t5<7B*C1jNx zIq)ELLRdl~RMG}<_#=zvG21%^rjCP{@G~J2NEsN`4n-QI8|}FN$YUgg#Xk1&J>GK# z_?!faK3$>~d}zWNz%T|;igFK@K!wN}cb})Yq8L`e$|T8hzbV3UJrWWc7vGdgA8z6< z52V2jjt~VJ=;;YKNJ0;WumffG00&R#0Urp(iD>Aq4M%Cj9yACR2~|Xrw9Lv`Xd|h2 zxFa(qBxGm2(GEGNp%9OF#3@4L4r<)&kva1w6^W-JOJdSKeJaJ^E@6XOl)@DX;+RiD zQK0(R2P(FZ68Fk;Ppw!{q7S+y=e(FnP_U^I!l3~Tjwr+-kO2^Ykkuk|#EC`7$`Q#- z<`HxtgBnah3Rgf~AnfstZdSA_Y59jc+yM>|C68?+Qb#)f9zi1^3b7BbsYgC$$x|v; zvKR$@pJA3|3QQD%5}epXy!w=iPi!ugjuV_MzEMx9Y9&1x+38xtV#{rjb)mWx1t&6L z3OJ%c2QTo#9RA=4`Rxc^f+3lXre+CBkO2rVSgH`laEutq5UwQAStRdKs-FgxdC?=7 z@|fqL7@V#QHl=|t@)3`T$mXq;#oSrca>=VYt`wN4g%P?6uTo@GqpB1|DTXl(^5iV4 zuI&gj_GMh#Y_VG)V<LDonb(2xVF*KrLlGP?jFj>uUfuPsR}1TkLwNEAX24QCwn3Y1 zDt9Z_BM(qRM8boSs2#hANg;&LhemKA2A%i^H)2@-8}?p~xb;wrDc~g)aLuceLm<#U zW%gVqI#(1?ng%zEJ7BLQSHqCGsD!(iA7-J#4LcaZBx*5>DWFuhcl~ahdJ?Z=_@fwr z5Cb5jfvEHfxFYNAut!$pkN1*OsB6m<^L7yfcD6wXjVMD5WRVYUVED(vOG{M~Tvtto zf|J)3%;p9I;^#W$pH-<cNRZ2~Gjrvl22y3sGQox&kO8rra6}K<xQS3)4V7B<ty3^D zjC{O<9`Trj82msDA=l%2Yxam-xrr!$jI%-^(i90XooRH`HztBeL?If{h5r6S9BOv- z&ffEnY4|NF&MgHe7g2;SleM=DjWDwogS}J#XC%$L)(ZbNfr>7^xx%+QL=Nb@BTMM$ z5J|YiZh5QGsD$Df-^hnH=s^#E96Hhd5C=C{o8eurR>=RzHc+v_4s@)W-4J6(I@D3A zbzs9C$PfYz3LywV1cC@L=!KMhJ+?~r?W+c&Phu`ngk{TXx3#vl6N^z9%I><?0nf@+ zzJUr;7~EU7bwv@1kkY@w3l%A2wZq}kMW<*(r`^LgY`86C0JqlBXVEpZ5JeAa02Qd? z6k$BwL1+Wl19(FMX$-2MXo~}F;IdWl=3dQJuWn+u&@HQ7>BGwLywcabp4QjF&ME`1 z#m&+6NgO2L2gB-iFttdTf`(n|$AJR>71!I+&A5?mdmNe-^`M8d(h_#T5B^IPxd?+0 z#UKXJ10H8%&|>m29%}3X3rgU^666pJd)$NYo%j6byJX88I-Q4ltpyGMK_IF}8|8f# zg)O4-4baaXRTN!1Nw^nVj&m{-X&}Rns4lO;fI>eEB+%8REedA+qtS+k4L1y2j5^Ta z8UEk~*KgmEi>NhH5_%TD;vwX0P~#c%6kGN$CY$c{4Jx=~mLGoa)vCANJ7=8+Y_NZ7 z+oK;Oxv#2%O@WjA0QC%O{<f?XYT<PTs!v)EDzq+&BnkTdffdp~7F1-%_|GvoLT9!w zqBJ5N!p~IZ!PGLaMTl$t{D$HG$c&TtK-L%z+UU=$I6)JNVH&2y;%txREbatVZHMq< ztZKmziXao%Zp-El6^Nx4nk0OZg_VZOo-%?q;z3{JAr8b~82n)ys>d;Oumn2-1i{b? zFGd_J>2GkUjR3&~!E6bcFj?fH6vU&Rx=^|HPYg8zhuDu3mIW0u!3*M#>i&ie`vetA zVG9By2Ky`%f{XjygY*0$+y0>#<^U1QP4+5+MeHyWJ4jnLCRa8Gpo)MeNDmR=!U1hY z9_CQPEJqXF3N7+s)tmwqE`bk=K<#wvZy0dP2JsS-;1HN12Js^kYS3CnLJPHl52!B- z^NAIiQFvsd9>if9hJh#loJbaPVA+C?^-#{AppBKFDj(>_*K$zY(C<CIK^mJvelo!b zGNAx_BBOlB5|Y3X_^I{iV;U+03ODc`YU3hggB9jL^Q=w1o~0QL@@F`47@EQq*yIw7 zAZh@S6yGcq;KdcD!Ih*42eSl!$Z_c=q8{pD8lE8lJ4xymF2>@7?kqtEOv&}yaFyl< zvo5P34NptxVH^J88E&i+p{gSf@+aA&!0O=}o*~#wVQ|hM4hZCuUa~3iY7tXJQfPA5 z>d+2P5Cv=Dy1WZ!9u5?2VG)kNl>E#|9I%xlB^*WK9_Ycq48ahz0loeKVDu3v=@LS` z?-|&HS=c}+;|2Nu8n8Q9&MJH?;J)G~rvxO6p#_0YUXV{&N~Q-2YAnA<6f6=Wwc;Yc z4G_pcU${X_>hd!mL|eRvA!~sR{GhuUP9jS&!Vqv8RAlpf^2gfhCnsVX@*xci5Zazg zE<&M`wty}CXTproDKr5p^KT?*11_Jz3l?D>w!wNpGdkJhB3@B1;~-uFQOvXxy5c9| zrt<a*vl$BvCo4fIAB-#QN@i-|4xYePa!Kxfs}umw1GPd@wt*h*0h;3BK5tGs{j)4? zXdDnT)&xVgQd2b%Bol058pL4>Q*pq;(;#c}9}vM1@_|4Y(=Yq1H|=CQB-5<o$7VEe zD|BXG62%YyD3Qbdb4ABOLSzFcZwosa6G0KgDKg<1?$1GEv%_Xn46hO{JHZcBO}mEA z;ned9+`vPPbd{n(K#$WTz)2pm%^wWG4Bk@PP;p0DbW1TTIq4xEiXjbBLH=fxMpG^n zTJtqCFg$6mO~H;H{$UdQpdOrM8VJ$3B&?yHfDddz!6d9>iqi(;Qd;hT8~%Y8=D<+F z%}p7#Q62SBA$3c{ArjNz8H#}?$Z9*avn(fMP$TtIw<JACF#AsMskGq?-clUKqZpp; zLu=F(nt%@k!&O&vbLR6wKVnL5G7`-|9{ypTvXo1O^&>LJAH3ih<Y5|{NE?CC#TFDK z2NOL1H&RR2%;p}^9-g66{h=Df;U2)$778R6C({*ru@;&rJt<Q}an*)qNL%26#>8M1 zvXIeuY*_6T!$9&M{(u$afg7@c5H<8K<-)>1k{Hp?azHg<y#yrvK^xMb805h=UlSc8 zOkB+>K`h}27J(_=GjQO=q4J>~91-l$%O14B4<;cCXG39Gwq;%RQ)vSyQ8pg5fkEWM zObg@SY-U1UHd1BD4)gU4ieW!R)>|Vl8x-n8p8^#eAuJguU`2*1tO7P|Lqe`c@AOj( zq4QpaH8~CJ4<-S<=;3<)k5-oyub#CYo^<J|lK)<mLJ{HGFl;fbZ7p)qVjrhB@5~ba zY@sP8(}`?`K5qjppphHm0cBN|TDkThY2!;#mQMd+YC92dB=T{7YZ`12HrG`Zr<KZ< z?itAw5x$`s>R~o2BKJ0iN!(DAP@&lpLz6m(tP~U<sdjK@sB!NGn&yFeFmZ9E6Lj^J z682LfCiWRLp(#5DWGFM@1Z*NUcfeLL1Fr`sS%D4c6eJt*B1H0P;_fi~#O<0uLDKVT zPyuth2SP3){808DR8?_(*ADITP}6{BLGoWD=R!51d+9Gz7c{MUw*-H7M12i-v-KJL zPS-dRQHo*XwCr)(kv#{BFd7FcOd;ZmmblhKHuTOA=-~dabZy_)M`s8w5j7tFvW>WC zqkI03a{qGAJ^>X1vpk|T`vSOH+tp|_xE`M244&a1v{rx}qkAZJf+MW>h@-jeLw0LW z9J=Q_b0a`OQc@<tdjD%4W;lecGPCjlClS?EqBtWh!X7q;2%)zAWCmpUF<8a0N1u1C z0!(Hn!DK<mb2029zCjycMrM))6%^1VrwwufS0?9jxpGE>xtI?8!SA*fi&-%_adH^u zARhcKE{O}aD&re!;dqyo3Ayowoh41Al8$Nk{DAn>9Qhv%0TIMjhBz`n(_+;qa)LL3 zAq|mx-*YZRfe5P&gkGtQp|q0IqGl0w9R7=s7`c%n_E6{GdeWkjjrJq|Evf8ODK5zB z6Z%(%d(xNLtKya}zzmER&fp*3vS>vjr|y_Q4&yDP1{IpX7c&8GZM1)3LvSI)e)WzQ z=-^6C_n5u#lo1sk%q_rx>=mEkoh5jo;!Z(4c^bmcdEM91xY^gDlsd<OhqH|!(^8A4 z;Zk4NEfQp<_&^8#peMcsDqh$%sk0~hB`v@WQOD!@__?36P?_i9zv%UU>)0OR0Zf@P zZ{IV-W;d;5!=W{?8C2BQtX3Z2@((EC5lh#YGx{nb@hB67#9jcThD2kZ)<#7EM|l}7 ztHfGwG9U0+K))2KWBT?;cn&~vY~|sKThSh(@fpZh*urIV=q?ohFyR5^@S#sFq64lr z^8pe3pkc8$E4U{bwV`SbVMvJJYlJ`swm_jXp|Xo1_86m-u_e_|0#R!kz|#8mrdOF? znw&@CBgMFH^{`{4A`@DZLC>;3H4(5+?IWWvk}q0~O(KQYuNd4w2Bg3xegF-m!*=u| zjTU2a40dN6nXKs`t=u}a11?{S;S3U4+qPmH&hZ=0hz~2fvMCZ3YH%9R;&j0}6Weyp zaMxISxPEoJBq$@TBt#Hmz!1TJ2ln7(Y+<|wa~${xgPA*q(&DYVI7XaUx;tz(rZf$L zVP3g{Via$q(+G{y2p_+JUOzLv&+KjMfEDgR8yXZq4VAwCSz-_5KoDp^3E;t&UJ0)I zMQ0lKkgpr35q!XA!@xRRoXLYL0#v)r8Sy40Dgpc_HN4956;W6Dtq)u)3^fsAU<?`| z5h@`NWIzdaqcXCHrIi^`X3no`oQk~kAMSt^vM{>IVj|ES&9(Vpv&7eM_aDrl`lb}E z#R4T}!LgNq2vBDaA}`CMGTWS69_#^2znr~p{2w~JVfjclT>Q(6T*G1((OKczK+?-W z;vN#=qkMw~B8!x%DEAE2v;XV73;muZVlBm-6^56_OMN3AUAa!V73RR)w2jWof<c&} z7kptBkf9oUhL#NZQ0YL>&Ains>K-m!(hb|RjlCoPUfsB29M0vu*li<n74N8NiSu?E zQA3v1n;py_QQO8`9wK6&zunn8SF@E1Cp%moYPN}QgO9)v1fj*&X=p|4ZdX}>4)P%) zy#3s>=Paa*K@z=Y^8up)-YYy^!>ko9Wu4aZ!5<pE9A`-V>|r+$VG`z{8fIh26aKYM zcZ+$I6@0kX*Zi2-*wVpVO25<$ia{+U!rn`;l^yXW?Ll|7@ZUfFXZ$%JeK;;LOO($& zLVt|7CUp`JfoA*qC#@Bn`~h*dA>4LeZ>)BvOZdO&dFm^I=sV0y{oxtRz=WxtF6|jk zp~)WZQ|Gn*TGkr+qP||&p4Wc;$4=ShSzhh`#q)OW0qWsC?)&9M$$Adbf{BUR@3;OR zthHyuj(X>yVf|6@A>T_(CEWcXYim97F+cO8Wggnz?_5;#LBCB!waN~U8?;qTSrnqw zH)Y>`;tk(+M;lQGe^6h4BfjF~JLr_52_E=U=08(5-u&#-zVB<_JbJ!Ci5K?~JbDe? zslzlL1bqwbbv96OeYt@ji~m6)UDPKv`>%vN5dVgy%33Qz8~ou6c!BvC@jpv6-2cJy z8GXsUUo5=#A7)_=^jR+Fzap$i`2k{{z<~q{8a#+Fp~8ao>ixqt$KN)3_xvrqh%uwa zjT}3695+s$NPm7NNfhZZrOK5oTe^Jz+0vgsdjI^?k>{_TxP19w`uqtrXwYW=?Ag0_ zPpDFlAnDc9=0#h)hV$ety^8gxOquj(@>w)*qCcxy%bGolmY~Rn|Ncyh*L5t?v~=s* z6-d<Hzq#}H-WAGITRudH{%y1B_pjo#^6r(Cm~WiG#EUCiP788d&9~Z&Uj7VPW!|Gn z`<4#Pk}Xti4J%Sc4f`U}*|SB){Tgo~%GkVncf?sQU)#638{gwO`Lyrlck}L5&RnC+ zdi4D9X*IRp?&#bT$`okz@iu?ZyPJ>gkK4avX(r8Mt)1-o`DmN@`&OR5L7uk%@k$d9 zeEQ9Ylt{K!_mw@xAva)yXCY<(luVixlSVM<*^``u8V1FTKk;lh5MMkQrHwyn@RAcw z41&lUgW<WiO=L*%^csscVniEKAc0iRglUwxjXf6KNaRZP#WQ4)4dpXS9fs8dQjyUe zXb*1N)Kis|T6$EVJeu(`2ax}4Nv1{}e#jz&T+sv7Sk#eMCT|ehgOhl0niglAw1Fp2 zkN+5QMrY&6muH~_ohc=W{}5(al!l^4+ihSK_h_L;_2)-n;{;i0r}H3Mq*3E&6R0@x zc^VpDAC@!^Hx;2ure01BM_qME!Wt*2Hrl3{A%^5bDXxq0b>KZ#+A1uFI*yaxKh$_J z$x~D%n`ejkDfyHa)16BH?PZseG|4^NIJ#Vy0vRRhI1J9|S)MZ4W)FqW<c1}o-D)`+ zUo~<!SF?yr;w8EFDu&c_2rfeJcX+0H4@e^M#FI?_`~z`h<9zdtqx-U`Zdd;-lEyPV z3OR6`qp`S_L%{&ZY001&I8RC9ZU<XD@#tkwLpnE9jL16sGjYS;=y^|nfB*uIm-Nu= za*_GwHy^M0(7{VST`}EsT_QDga9B&*s~CC530D*~#n@s?E@-RmN-4IuqINOG3^PqV z_Rv_-ts6!xk#>I|0vAnUXN_-Bq;0sCe`)+9AmNpPRG?!fag*g=AStX@J@Cx^b||8J z4vHw8aPs-*q-T=<i7BQGQ%p7!Tiou3GTEcvGiNL!k6`&=?Kq1kgD8?_Y@mqd#=W1l zrgaDhTbE2A={3$XZ>RD}CY+#BdiL6jf(rJbV4{gDwJcNj-QyS^-KAds!^#}bD9!uv zApX7~TfETWCAaebHRr1C*@Gs#AZ23nXvW*N7m84TVu1{7-~vBaic(}Rg2V7x#_Fe+ zPOxEK+n9&m_GhEfv<rQ(=@LCOL$z^qC1ZF4AzF-L!s-}e4h^A4K0dgVW$9%a!$5^8 zBKW!PCD4IH1VsWNC_zy?P!yZsL<J`%FoNI^HTmF1kLm!puwZB&D{>)-m@y`SY-NmO zETb9Eh{iPks&S3eQCvQ>F)=pEagKDXqaE*v$2`(eB>$Mi9OCg0Zro6hX*|gD{_%}r zsBRP6YosGV7rN3d@pGC$#WKFplZ(aiA0F}`AwM}s&1ho|tH>WHPl?J@s&bXAEF%~< zBr0J2V-CCsN$k9smK^2ng!Z@}Yv=)zbwQ0I@t70FFlLxqxB`ifY^F1{#|cxQf*Rw{ zi#Vu}4Qg_7VRg~hZ1BdGRh*$1UiuK^hKWo4yi!AJp$RX}U>IbjvzxW)Q$5rJrf&pt za4-Sn#QyouV&o!$M|`G1pUH{T)#4kK=mHd&u!J$lA|C+^O?n!Fh&pH^e<C5_JkPVv zR*KaBjB(5f3ab{Ek*aj1ELCM>Ja#``7$%kT03<U4A%`}|VGpZF<R-d@3Q(Zp6Gbel zQIE>N?g=#!GKc{Up6b+D{NqC{wd0kv!3IRAkRC!RX;r@p*08p8odYUZP87$uoS|!r zA0=3Icp(Pt6z7&5u_+W{fLFZIfDg9t+~`Jk(7-<Oh^PRA4B8-wKm=k8G1$XYEwiI> zuw@orkm;4~LD#l^5s~;QjYln`uV&HGmTP6JX7BP3huotMtN_-W_7oy?B1NB-h`|!} zfZI06KnKeV1z-gWTm*&!6`P2H4A78>L^NU#F_6P^J`0pCR&io}@B@;rbd=1V)<IzZ zw3&nKx44N^1cvC`?p3-pk$fcRYGB)ldIS-JHZ-CUiO2&DZqNz|E^(5<4Qv7<Xk0Y7 zVGM#`u5&Nbl&8!A5Hq1i<;;5{FhZ9%exjPy>a|t~(`8QJi5VLl!VR)aSRn6>ZzBG% z2Q=I_znmbb0*&b67|VFZG$!Z*|67UxZ$StJZf+O}c8|$cb|&B8r-pr3l;>oKIVMDF zXRvhS%24Tk`LG99{h{52AO(={T|*-7@B=E)pa!`Zor^zL<20-J%%b>jE!H3dA<#ey zTTns_1cAu%W+gp9o5LLRqM0Q}c|*?eq*zZ`6gbjycX~OrqaO`v@^Hf+aK**{KeADe zJJ$3cjfepg(13;{&_D)9a77c>jOtVq^m9#g#0&C@S15Eh((<52FVoP924^hNyzaHH z<>;Ide}*l&SX@^~HfSl!<An8i25bL8j}T`WAvU!$UYi<&CfGuBY(}cLzm4Wv{NV^G z2K66uF*Jch@w|Dv(m(hR2g_#6o5?10lIgRSlR`T_!mjsEJadm@*P#xzdX+|U_K-G6 zK?-14LmrOc22_;7#r*B>BPY3uS{y<Lhp2_eYk>+UPU9PNG7eVK)ewIKLks|W(pda` zBj>bh+M!8sG0xzR#=*QYIm>h(<It5!lh+_3%7@*efi_ftT<MO0__ksHTu_T2^b;Dd z0Uv77L`I@cd_`F|P>_;xEB*rzWO(1P{n5ppJBWVfA(1}_!)HCK-7E*H2QQ3(q9Emn z=%u-vG8qYqPkgTyi_ifYYQYJ?M_uZUyfM``{s+V-QHh{1g)OvUntp2}hH#w(Jg8HT zo0)d*Yfm!0nUiu-X@k9_w~SHLqm4S?;u{S)3g6FlH)^O(;zIOoEoK36?6uf)l>auk zDL-6C=zy=kU0?)1feE@rXo@Xa)~pO626E~o9vz)c>q}qc?wIw2e=@|A;`e>J_$eQ8 z0Qx<#Y+AnT&=uH=;1WZT2~=3Z@JcPd@sA%0R9AR+FglD>eA(mw3dK+qX$KR+p%eeG z3`6i1=}|N=lYSbaE8TG*q#_TJB~KS9Kn-Ix9mEQFXBZwtEXH9J%7i_Tls)+ed~RS0 zqytI+hg6@Ff0h7oh{p-~#X#9(3bn9+JrNZ0FlqGw2x4G%HY6D!_(h#0ewbwsaKtF% z(u7VJg3qHMoHPf2P!usT79Chk_V5kU@ClUnNSsg$I*10Ovk8&Jcs2M5`j-S~AaSEp zacBq%msBwfm=fc_4Ky(cMgTDMKn=lR6fJ~>`f()lp%?P-4`<*rGNE~k$P%#SCyU|- z)DTGVU@>FJL!MJqE@nMC_yn~uL^fztXeJ7-kOWU)3#3#33N1)PrNariFmh0GK61AZ z7v&#xU<ex(Bqf&^m1v270Y;eAhs(%}&FGBJ2#wK5Y!Pu;V-t<nh>h8(joZkL-RO<q z2#(HpAnYRstN?A?up@Re4Yq&@G+0#GQwx_+hnP@0K;(Zm2t=FE1Y00YaQKd;lYmAS zOyM{dnjsH{KnCXce&NWF4e5{%36T*gk=mGn+;MDYAX84^b;tN1rLlo=;6BinF?Ul8 zZ6irWl|XaY3a?0i#FvUT_&I0j3Qf=i^hZ?RmOw$c7cG$wv?m<0Kn8%|5DoDm#>kPN zQIWmTWMDFdt-*^&d2;q34)Tx>lRyTu&?gS&56blaTg@ayD!Gq8C3r5_U!mp-KjdGb zAWed_62UVu#pVZ6VMSvkXizyH*5X-DxnbW_Mfq?dsZ}{fX_swjAoakB+R%Q|(39FA zai%kTG}e2g<BCtPOv8s}HFjgGCJMIT21j5CE!bwLwm?2K4EZ1qhf@%`#1}FlcE}(G z@iq@V;z3(;g@eh6h7%q4@D1Xi9xL-Cwz(JvG7=NPK4$<35SR&V7F4C+ZKd;5m#_s} za0x>d3igLo1Qk@M(3zHC3&~l7Hz+!pU<-Alix;sQf&^`3S2duAc0>rArAJ<ZnM1l+ z6v1H#iy#pW#zpxcpYOR5v{7Y|K@Bot2wrgi2_BaTF_wqhGlw%-lb{n+29-dZc?6D7 z3z*P77MBapKzpZ`9FC$M(1r+NP#A_89C75I8uB!CSs4YRPtDK?jbI2zfD6wMWXaK= zDasLZG8SBA3r0``lu!$$un7vfiV$iFThIj489GOmilHEGI$)tcq>6CJ2?<Dh=cG&O z28iPzq9pnZRyLGS=7&1U9U`<vIr<ZTgbYLw15MRbZ9olGW)J6Nrf5MMR$({APz!)C z1UTSvrl1Kf`C_#gn#1J^O8S{J_>xdZP_@7ZQYvv(%3nHJr?p8Ci|M8G00?OS2#`n* z*`SPNdZ*pt93|ydyv8S<C<ig11Z}|o17P5$mCzIInX12rtGViETvQB};BkPk1AL%{ zrck6u<$^+03R{o_mmms6HB=2$P#Jd!H_&l3c#p>iL8c%`jYdX2sUGz34xRd`R+bH7 zq^swOuIUPFxXCc;l4R7t1u`HAd5{E-&;~IO2<TF({Bs=NFr=H1ahWg#IUub6N_?Y8 zd<}{QJ>aXKaFaz;b%#(2mU*qsSvsnt4fsJC1;Py>iVJZ-28e(Y(S|N+y041CcJ%b2 zUYc6jz^5fi1T=65M*xhi8VGiirh0j@E)h$$K&+g=owXpaLr}1#fC)y*Ujf)XXyBP3 z_i-QBJsP)sv3Qb{3S+aFvDMW7CBk73z7PjuzzZ7{ZS#;}JBxuo#;?o5n$4h0sFMko z@B=j91wfDmIMrB>WwK_g5Ob0b&%m6H8MK!$1i`9?7fO$ZTBuOR3AV7Xj&KNk;0BN@ zxt5@Ok>`$%s%kHWW}i?DwD%N}HHDS11My}xp~_8qd$!)?djG&frC<u&gFQaP1TVk> zK=1=-00#J)XEcYpFaaU;@D0y!xV8wiws4_CFa%!UtB8jQnaO5KiwbM-0yF??GGM(t zzyp5}ay>Y4nLA^p^9ghViPQlmLAg<eQItB{yS~v~6_ra3BUy+v3=SJa%sHBQAOlbJ zRMxu+fwYV3dlgz3yauTMJ=n7er4WyC@TY))z^FL9+oK7!APCm01X6GWS8%~@`U5{D zRAhNjZ1y>rfC<l#5AWa$ejo-3c_2svz!5ek?#pgC3ctzZ3ZoN2sVJFAkiSA81V8Wx zw(tyH$1LsH!awmm!21jY>_8FPM87%&MNkBe(7>CJ3G_>ObGQXEKm<I126y1adB6i& z{FzD&o)l+94$G__hYF662V_77lwhOKwlrf{#4G|v6Pb;Xr7q7<W+&-ls#6PIa0bfj z2n|{b+;=(ciN}k~$c^mCcr3t4%&0E*tfJGz@d&I#@C1%fxTv5Bn{c#q2xn^`1vSvc zZomUfKm$VXnM8H}nP~>C4hud{dk9dx1CyYb6LTdG^T@sI%fAfF!OV@_g{P$<z{Ai? z36ybwPy|m9c|ZjU(Kik0lD7aH$poA|8Cp8N1+ax{2?}fjY;Xt%>T#u@38Ik2TQIXV zum(S%1NKz|pUF(l1bvwB2@(8pi@*mxumeK?2$aydz;Z!#tR-Yc7l))w*;7<hR|J00 z1It8tl9`JeNzf@_Oi5g|qxrCr1PV>mjtEKygWCgc;0M?9W-_484@U#<>;|jc%7nT= zZkq{5tF%w6&p6P}{v5Q6JI$9`(NdC(>bnvHX%vZchGzW7KSc>Rzy@w$3kH}#sK9j) z^V2W!y91p6(L%M+4#Wu_?ah`D(mT)tk@^B#kOyD<#ZNVzK?Itj@U$M6ag^W(Y|sNa zfV_ZUp&s{FPNYvhUDYvXdU^SE)<~xgQIg4Aok7S3Y=8q63Wsc+G2QpqLp_FAy`avt z*MH@4us{i9-~%qO%0S=)UVsBWU<PAm38rufB8&-_u-cyhvhBy%I#2`1O9q#a*LrQk zqZ7WE<kyouKlk=R^83Jz^j|Y*1a5GOrch9$2?`uqWx%}>7k$ogXgb?FI<?TMNpJ^Z zPz3!f1~!ntI?w~;4Fu$^1316}WB{`MoC%h&3C642dp)rkx(UPJ+tn=H&B3mNtxF&= zF^66Mo!v`BIoYSpYzSD_K+YKqJx$U3tz}YZ*;c#YqVrd%@CW((13xeYO5ou_5Ccgt zv6=nRweSlj-qk&r*?(2vq+>*xfZtW7-w;k0GRH|G#W#A9NbP8k`vqe-SPKo!u&8jb zR_Y2Qd^dxnu1n73c*GM$5xfdb;bb{Ft)OCW`ld}q15V%wLj|w^iwRA%*Vfa6K-G9~ z2;;uZH%-pwZSLk{RA^a&F8`3w+nl(W>AI*u2}ZyMXh5}6{y718x-^~<Mg0vKTI3YY zK%Ub*j(Z4?4(a04X5ZP-WZu;_hPjw-I%!@MGfwDd5$9OJ7SA9}QeNO{8H7c^2aS#Y zcqfT~#XwPt`00CV%=zH6rmpCV&OJ`6bO<~;N`;d#cIKZma@F+Uv+f(At`t1-4}5H` zYbH&XPy~O_1dWNfOB956g6tWgBeu@m-n(W<6gmYc=0OGS&RgUYWD0_@?G4f)yz3G> z!VNw&=@q-^YFP_$Py}djb%0mlpA&>10`KiU5dKgMubb$(ZpM^OsZySbKv)aHMDXU3 zlrE7NM!`d5eCjynTMeBA^4w<sE()_Kbf`J;2Jt-kaM<>4wYZ+^$7iW5dh)$d@jzkN zi~3ABMtDWg)V46O&ZG&@ZSpf;5O*^T5N+K_pY&W;azxJ^HO~@`l8Amw<OzTO>ZTw* zs@?;R@aO)QJ)scvB=_4yuS5C3L)OFaFR%9Brp>M}a{n-pPQM&b-x54h4?IMV#+Q>n zRRnHe20rWJM&(07FZTx_mEUmiS-tj)e^e3FV&iEyg&!S9LVYTsg@#?jX_;{-`~-(U zT=niqgD>{SzU^9g5A!~GO0W6{<@lOV3=WQ|l8+k6IFWpt4V&<~iVv*=o(Vx-2OmFq zM<x2{BFx2a{KpTG8FTBp&-l%+(5NsCJ$b3fPyN+z{nx*Zc<G^=r<z4Q4Am{61Fq*h z@8_v++{0xG9GWh&k2iWzl7YYa@vl9VDuhkw>9YS4Da#T=XYlj~5TXSC4kTDGR47xf zY87#V!%;0xp$ZlR1qzj>XW#PKo7d6fN01>!jwD&q<Vln%Rjy>&(q+nf_d43kH_g^2 zP7`(R<k{2bPlKUcJ=+-b<x!+bl`du4)ag@~&Hm-1TGi@RtXZkXv}bReHdLlig+e8& z;#st351KMnis2bfu5zZOYZ2qOuH(jO<=fZqU%-I{4<=mL@ZrNT_2&CFtyrmnbtO-x zT-kEnfuV*?t5<I^V$h*Qk0xE(^l8*urFM1tdD^f{p-PoHD3Ed}P@8H^GV+8EL{6Y= zryVZpZdapFl`m)B+<D049T}sdEiv+C?Af&o7l^4CXV2rFk0)RM-u!vyt2s9H=g;21 zXRc_^wtR4QCR9b(G_iy#=XJ@9%LqA{&@=Er1eMck9)F6F>%Z+HlrTV1OsPdL0u$75 zLk>GsO1;+h%BL1r2*Pe4OpIW|4O<|iY`BXCv?n?bYqU{A4DER>69^~tF+zbji7TUe zZZz^pBokCGIT}~uil%I4I|w`bEc62hBOclWz{z67YsLbT6m!g`a-8Ow|IGSvO)4eQ zjI;HcBy&zW>m&)prP}K%pJ6l+Wy;IevScAI+=wep%S0*VnQ8J8&rV1qC5fuNYBA+c zHZz^fKH5<E2CsTplXO&4lVs)}Ia`Y9)A!<o3@D0rE5f(`T1rW?C;L#zXPgX6^|el_ z-kZi1?$m_!SY&~6rI>%Z0`pgBqdoA{c;Zp&(@#USrNkaByRQ~Dib%qe*@mNVty<=Z zDNJeGy)mYG#5og_gRIl^-eNP^%u#py^;bD+twkyxfBrG}A8is663`b1%A^(}7;2GA zx&%V^n{iV8cjE*1Dn=~s@MY6tR4kh2n`Rf}cx9GV3K%Jrxj_aOUvj~P6aON@t+KVm zn#2c(T6~pZ;{KHF!i?E%d1>dUnkOE|E-4ulqD9^=v!U?Xm1(ZK_K4bn|7oTT8e}k= z1~)FvY-h;?1s8}kN|DRn$p~7OF^#>}`=}hp`39B$E!Vah$bqJ5)T^ZTR{Y;nk@EYW zKw_Xl2_=Xq`;S^OF?Ul?+PVY>9Q>$d6WTVfc%Zux&wFv!M~aEkaXPb!M-vA>5p`x& zSGslHNd@~Tf4I>?hCLcd<c=|9Kx1@dbpynPC;Gb;)~vx?z4zYNEzll}$EigV>XH@z zSc#_Lm8N{KSHIL#uP-ThENCbs5kc<QLWV7Bp_lEtMZsht8{DB5wWCbAL}3f?v}b(_ zB#B=1B0F2qj$*benm~rK5qZdifg7~bYW@MdY*c{;d1wS0l<))PL8KJisamnNbO{$^ zX>{G{pIHznDh}pQB%c~!StytmPDu$BnloJgsNAPRBqGRzOxoQ?m=wI>6)z845P}ST za0pHekUnYo1X-wKAwaNT4x6w9qAFuCO$-BNx=SMOwD-n)yyqLm2!-Y*Xf=UI$vXp5 zjELI!M-DBqKu1&;%JvWgA?V--On3ne#&Cor@S%*TK*cAv1d30T<r0?QBr0&=f<<uR zRTisPDQiOz?`-5*fMlQo8T5~0=uZ@70hB3ic}rZDvLZpsgekt0j|{R>n1O5-ss`D_ zk;Fr6ZID3>WIzKNpurWb_(Kwy@B}Q@qLP_(L=$fC%^T<d1}|vBB1T8I+u#NjhU+6C zhq<xjI8ZzW(?+dgvr9E;iXha<q~SXMq8E3*Q=m-opr~+Y61`~T8?&gyA^zY9N@md( zjz9w>?@-2CSmFnggJwr*5Ca`p!W8wYk8C`pN`NABpi5&ShW_!5XJ|8%Eu7FPsk5bh z)dO|`U1?9FQp}DJQhWB$DVk7GiyoE&Cr7o!ADW;8G#ug(G9UsP_J9UAtf2;NAc71q zN5j(z#6mCCo=>qCllF85rv4F#57|UXQE09h(a=b+tfx}5=Jh3l4Cn*vF^yaZ$$(@L zMMScQ3W^>9g-p1E8}4w2B>dnGNAPMb(1{t`eXu<|)vLSuxTk!C$}#@Y1Sm=|wcAw$ zuA9KmT&J-s2X19uouzG3n&A)sqqIl2yX9?f-2)$2l!cNNIpsmRcvM%QL2^gff@5#6 zg~?X-6Q--6C|vPcd-ztn+vRR|z58A8hF84fC2x7ndtUSIiZKQ|6H+;miPOT>XmmN{ zeKc2#?`VWI{-6qa{rg`42Ux%ZCUAibJYHt_LtrjJ>xhE;pHt#9NdKEE5v0HaA~2x_ zdB_80F{e4Tn39yD_{6?eS=;qJP>#<ihLAGx;!tct6D~T-Cq9u0OyH~--<gKNbc<pj zJ0-yjeu*+IMZmKZL^php0b|`Th95w;!<Dt;=7vKb@4!iAK~|rNsdA=g#8jIQ!H+hN z%84Btjw+qmGMC+qlp!DgWlvxk3;)6zidrz)$&Yn|W0{bGM6flVbtzXVwDFBNa`w$D z%aKm0@+rfe$#9KPbFl8wy_u|M(VKRef?blMd_3b4RI|=bb_t3+H<{0meXNHwcgmh9 z1XV%BE2mio$3Et$D+Y5GQNz<_C(hQ^!w$)9iL4Sc!Df0C;m&(&F;yNs0S(fA!V|PA zgF|GFdbKd7u!-F@?a3C7@|0&EX^rbzfBVgGZi!3dQ&{Q}*E&M-pA?*VZ?nZ921y7k zSd)x8qM*-d>TV;t34U;q+!oPHblpAVNt0oX4;7X`-WV)y@h#+`Kjhm?s6K;mkcV8L zcv?wUbm|~mC2KbSlw>)}A%d(-6yr<&(4fd|e)A-f93|ST$3I9E?=$KIlWii)r>25) zq$iz$OFCx5pTr<bMMT2mLl!<|EsvBcTIpNoy04f{>xTDD8>gju*%kFFTLc`~U1xjS z|0R{eh+RrM%Vpi|j!R00;u8oo;yqIHcfbc;@Pj9O;SGOy#3x?yix<4kPx2%_f$WDx ztIa25-Yd6fUh~m%JVIlqQ`oHS?xQEYN#~(Tt#4lStKZP6x+30S{dE|n2D&~ABI_9) zSogc<eeZq$d*BCO_`@fD@s0oA#<4`jfK5~BoljEk81RB8W_|UoZ>kTfq@6VhuIQid z{5(SDO_;y`e)-MMp_getj@&Pc*<pnif*cxU=cj-D5tMu<t$$df{NZqfboJD;KLH#- zm-&Zkfr)j2xbCaHdkK=bI2pttKna|{rocaSNjD712L~~u{wpkf0gtt#KoK0lllUF= z)2W|ZHuvL++Sr7XiK7rCK^dIEj=+=Eft~l*z!glEW%-nR@HQF@!Wr}+utN!&(7_$# z2?+}Y1QLgO2tXl>!qp=}^`nWO^S<w^J9(oH2-Gww{6Z1@I+S=ISdxn*^a+Wu5PxtW zFl<8#q{5QZKr>{(AIS_`hz4GXK{wpP>k}jdw89d>!Ys5UieMBrdlWuQMDr6vjp?JF zL&7uv+zH(4H7Ha>OFTF@+`09;LOPTXyLpCY38qUNMb;ZKf5<=43dBy-j<)ilj7S+o zBt=<tJ9b01*wGRBxTC8vhzjAhUh~3P492ai#gs@kKUu}gD2NXfm6Q@jXG}U`9K-YZ zhS`I#L4-b1+7k1jL?C=dZ$!9ge7rcS2WqS`vzxmAdxmPThYTXWZ+u6BGerggul_o{ zXUIF+qdIwutMBN!y*NIA3`l_-NP;X#gFHxtOvvvtHkL?^d;p74I>WJglwN~Ji$pj^ z#6Vv0xd$O7!kMs+%P!nXw~H*vAj`;-_$=U}H}^}!TEH9XGfA1`w9ZS3uCR$M*`lid zE0!$73sIa&prpxW0Y+(z7st@YV(CT32)3YXN;jiIp^77j>mopDKcQoxQp>VKtVE~m z${eymlDt58DMJqA8HwnnV%Qq73`?(UOF+s*ailfbQ8teZv56=d{Mg0_bW6VMteQlL z40<&05sO)>vs$9P7c;Sx%AlX@OUE203w()ogb!Qrld&KrvXBTD%LH3U%SU0j#|%x# zG{9qP$o2b_$FNMRoTXBDv9udFJrqsZOd=C>oQ$E0dKw}-dNCoXg^WNc2ja@v98RW* z%%z|Sm?{P_+c8G5E8!$g=;WI8V~R_Ak4NjVHG92Nj85+Sqv>o4p3|vM8HdvU>`wFK zAmfCJ963++Y$HFsK&6PMq$#WRtk3m<OZ&{vO?%Jh)KC9hx}ogP{~XW-LP-KWP@j5F z1YOXc`b!3V(6<CC2%S*K^fU^+P(YGL4Bb#2Vn`1C&<!%SQ&dP2Em0FaQ4~#46<tvl zHLq|4Q5a>N7mZOG^%@PWQ5^Le^=MHZ?NJ~7Q6LRcAq7$g%~2!u7Y`azC0$Y`ZBi$F zQYh6f^<X?Itx_w!QY_6<E!|Qs?NTpA4gO@yBOTK^DN-^$(^4@|G+onCF;g~u(>ZA$ zzxz@;ty4R_Q#{R6J>642J&g2(Q$Veg?<5abnoxHP)aOXP-t)02ZB$49{jUC6(MWw% zN~P4=d<s!45@)H0c#wxe{m)JHRGLGyIZ3GWfzZY&&!yOlBB_ZqI~i5g&r|#ddU%I- zpa-wOtufJye~<?O?aMz!3fUs6X@~}MAO><sR&vM%s^A9yWD;)p2WlXLA=m*j@CACn zm@z>aPk@GRIK5LnQ2bO1VabPnhy`=7)pvl0ekg}>$cB92235*WPu&LiID=x)26^Cx zG~k7Q5Qhx<Ri((FYRHEffP-EgIB}Iwrnt$1MFwJ^27i#WNb3h;I0tz+nR#f;FN_Cn zh*k2a2YY>nG<XJhs8xEX2QMIsdZ34zvylvnhI=ppH~=PvCD4NZ`iJ&lRP$mGZTN?N z5Qg{AhDU?6Z-573=!JYJ*nH60N_|@JVvuM(n2#ON;Y-<PID=;ho|d&&UZ4Y7rH6xz z)M~hggB6E(m{h1;TOutc(ufJe@ds&$g^Zns?VN|3oCbLC2Vv+3agbSoOO4%nojxtx z!MKNLZH7)*gIO>baY(%Ouvb5rgnQ72&Y+2(tpis0ha#C%F0~dUK!SXThW0RA(>+}( z9aop=ipGcsT0jP<nFjgn2*W|zUib%jy;-DKmv7((Zm0)mrMZ_4x%Qw3df){yhyz}T z12JF*?g>}t$e_;nhg_J0c-RJ)WlZD!2QSdq&fr)Lp$cXHf&(O|2ASnA==Dz`6fmOg z+i$1`{?e}2&4<3NiS^5e^XiCGgqo>n+I;X>2AM~;JxIK@S6rBbrtP_5n1f<ySyA;p zda&0t2nNm-$>O!wMc{*Z*arAT$awgMH$VbtsD_<&+5tY{6?Ic_Y>a=v23pVte-eo& znY37thTct@*n|#;;}veu2zc0qb2x`&IESVk2YDsRvl3IJ$e`_AS%2W*ZI}mMI0JvM z+#+#~wE72Ln1d=lsPFZMl8uLY0N(_O33(6)IDi9BFhKNO*!S4o0x=xdg<W<+Cf2oE zX`lsoh~bvl*&hCfcSr<sFb8sQ*K&9SVdyb#h{g5)kq2&&2W@zc_ZWwNr~_UIErN+) zf1rdvc;Yc0Ua05{Z2)6`72CVTTYDJg$&H8Xtr4n_hkQumSNPvHCeRx_ie~+XWH1JQ zC=x~n3E9%uexQYafCsgV%XxgQcc6uGIEPUNvtoFMb0CI(fEtkXn%9$uo=aKIT`=Kf zVtUAjMVJGTHRVtl<$nFwZ*7k0J>Y-9URQb&Pu*fiZk7(wp0tGnLV$#9kd9Lo*qNMB zl#s2)2$fiP2g5n2hBKUhFotBHGz4T2AMAx@hKDoe26*U<zw(E6?S+Y*h66c38!29T z&;~vb13*Zy?*-+fFk@||hkr1GXSj#Uy@%re)nYcNho6nfrC{Q1$cH(Y1$ju>PX%Xt zn1fsx>Q64?b;%$^dxKwq>Qhu`{k-Lun1*W5Wn-8$mX_g58wYs!24gsf#z?eu3!bSk zhjh(Y{c1<#qzYj;2i&D<sNgweGMG^Dkd63<WiWzC;Dt#rgI0j#qEKR!h}KE)gLi&e z>HX<57zS;=VyFP;td(9<{s^BIXFiYz4&K-r(J82Y18DHnX8cd9RtdYR-B`#5?vY(F zH5_h8THO7Ht_F#T^#^!(gk*r>F8oE&>anEN5s;2v1^eh=@C93VT#d-Sjv0sTonU`( zhj*}tmDOhE?&&A~hko4^QL$_-PJ?&<#?{(ZifBayM9^t_7KyINAgy)a@jj0XdR(a1 zgImZh-L2~4&Ocf+Ie*yYUY>{fOt)3Rn0JVUu(sRnWFnh3V(KLZX>eq5c-*Q0t*XF_ ze~4?&9m#HFFkuUx#xRF+D1<;D24YBtzjAGW4hh-n2z%9Bgb@c4E(SWV;*AYJcu`>R z?u>Jbqq*)^dk}{r6xJW)aac}gQ&ySq{8>Msgn7u`6d&kQ)d;AD1W0%qnh@9g=9}1w zhl5UNBsPimu-j#ZhnJ#lkU*=cJ%>kthj@VD)q&e@;Bt7FhfnFx89v%VFo%9<T6n+) za}b7?(pC6=X;?Y~dobRv;0AyHn1nh&7(rj+p|)2#*j(fFY>!}KoSy41mrO!$1#<3e zlW1CgMHsp^koe9As3rtbkcYHQU-P?WND*kKlS-`C>S;K%`D}^SUFLU~SiDV+t{`1_ zI0a*<Tf9igb*Wu<cwrb8l}d!$*Gd3kK%Tz_YOV?2jfRsMW=bn{sCeZ_Kk8Pv2kga| z2>u7H{c)Z~X1{s{FR0=O4~fRk2RbO_4rU5)z6U;7ghMZqQ^xF}c3G_rEy-Sr7551G z47P!j?_Z#DR@aCpw>6Y`sUUCDp?rzF&4<_hhm*;emez)N80Njb;d@~9sl|nh^;m{y z7md-2M@|NFxZz($iuQ=sa{%<<|H;EoG3KD930Qv$ll$&e-jmqDU_Q9s%RY)zPi)*x z?~l0Pd@uw<2ydHa3X=8*Gw9Tmwe*kBi^l#3KUjs&>rXwYhHQ}6m-mQ)lk#7PYJVW% zeZM|`pavBtleiCwn>1Hq-eZi}bd+G|cL0WSIGLtBm}f8sT6hOXUg!LqG+Nm6I%Wz6 z&jtf;d{kzqVXg_+4q4#+2lIaC-AY*v(puvsV_US>Ip77XQ~FEqcWuyyGsuR}e{TfL zWmc#Ic06{kPOF}q;_%L4mLRJ4FqlOyiGj;%(f$QI;D+<PZ_Pt1dH9D}7zBDC80GJv ziT^aPzVLGho`5y%{l@rw|9}T`hy`O92J*j!awvJpZwc65W@>1R_)PX`;B|O#b9V9J ze3*HJ;eMou)-)&vfRJZz9>Id#{!Oa$k6XTc1s_6;NKl@<di3(~O7m}9J$v^g&a-Dv z+rK%i{>8iZ5hP2HBIV`t!z$i3iY*C>6Gt*lF^m5E-3<EB-?o3$1j+G4)aK1<|K9w9 z_U2o(pF*!<&8l@P*REc<`jhw16C`L98-7izwqUb=_Wlu6nf2SZdGKhx(>Cp)T(AD( zar5^s8M(sba@ETh@0&xdDk=WV<}aDKZ`|Up+}iNx!C3wLX+sN9<+N$>X!ZM6dhJb$ z^y>X9cE%pZdGZMU|MZ!rnLm+TT^BX9h$g+CeKG$O_m3Bwg}&FS9QW_cGkf)pOH`S2 zC$E3Sfu<cdu3ph#VkWWrgNQsmrVlsEs|KqP)j_wo$pg=NKmY#z`EM4FRMcFj-+u>! z)RsukVds)PrA>B9JkxxW-*aDyln*!J5!BE>me~eVV_lW@4Qlz6cA-#xi8M_#|0I)4 zY161kP>ZI$^T>pI%_EwBKhd+zJ%$*v5k0m=H%^fM@G;yr^oZ9WOOI8wjXl)mBa)ON zStXA)XK3?{bzdb(4?X{|LWe(QayaEZ6u~x$AN6QcPd#MbBhs0?)Ipa&|M)S9J=GXE zk4o@WLrNv}|Gn~0em)`?sic$c7a%lv9FxyakW%`ef*z?9YEU=&gPK39g#_wWhvp-m zNOVoZjjUoe)DWvdg?djzH^zevEvnHt5LUU~n4>)Kl%~>iwYEA=VCM+4P^7soc}6ku zusKedd(t7#lU5m;8B3e3x!fG%Xp>=MT80XoKSUbo-mswpc~O(zK{-xDtf~ZLJ<psW zo}E%=Wu{nOJY&(5^~})<dG%1lDx#ze@=rB`!19+roOar=#~(wq*+0MFQ4gUT=R+{a zUVXaiJ=6Tt4=w+|quR=AjiaGF#+(C~%A+pykEx-J2-2z3z!M8K@#r;ep0TAN4>u~p z*`7bv|Ju{uZCo9M2qOQaE9|~+Rs>ryX5cGtR|cD*P1$No1ZPoc1e1@QUkO~)9jvVR z8f?#)VI9O<cc^K6islo|eAUF`&(AkQ9=Tc#!9?+(_Y^AmS1oHrS3Uml91o#nKdw1Q z;|LZ@er;~0+GNI{7%WKr9-U7zr^u76xB%uOjz6p@blGTm(uQX6Vb#b|)uAD55!??k z6<8YGiJewF#?$6_=>^&Ok0Wz_oB37#%I2jwgKKk7phOwB(!`5?^UNF2G|sW<_v0TF z<^RB<hd<TKLwot_3Nui`m4-Af7VnTpT?UvH(oExZz{(Y_h*uhJJOUobnuf~yLKl1Z z|3iU#Ngiu{Qj|KJL?G2;(LVr&yy^u7PO!<v9QyXWf+))#FhSuz#1XOGt%!Iek(0Er zBCz7n&`98N88_}>63}FcAkuN6h%hs;idBOdcrXjf9O%U_7DOZm!C3DeRWvZ(q=4~= z$5lM|jej767E<G&sL&{pDBXiGp81FDj5r?9okMDvncYgnb3JJN<4*d*ArQOrs*+F- zB(9;xKj^><CEbZ|LLrYo9H9_ud}mZTMAIBL@<W%YBpd&jo?F@&D(CqFVP<OIAU6q{ zVWgpNm;(|en>3FnG39;VAe0_%0YdxPF_|8t-HY(>iwcQmduS}+R!C)xWB`kV|H_o& zINl;NnzgBep-R>}RHwTN-iRBq&>)4hB~79DtA$=*59T5w9y8^G5`XYkzEmcf+!V!< zYbsDna%CrZfT=gCa?Cxt7mRZqRFef2qCe)q3%e~5D**Ke9ZvEZ)ZMc<t(e2ZY*V<f zB&uSn)B`N?QN?Y-)MJ~OM>CD7(3rMFjcgRkb4nAB3~un9UxZ*jXn~E~@u-#{QO#*m zgQ^M=WE!El9a5E=7U1M#q*>G2*t!R>w@Fla@}P%3o)NY2T&Iqb9BWY;Mw}bA#5LR+ z2Qb4LS8pN24<kWlOYZrvGk7VYG871yxG^|Zp;S@B{0B=N#aEm{RxN!2|4KD31&wc@ zOsHT~qgF&h5}Em<W=W0gLrN1fTEwn!EoqTI5D5=Fx{@vdR3JC#$R8kCsiPJNB}*j3 z2437F9*>3ISbwLGbfq;Y^+FRJlqfzoVYQ?9%4lB~X{Rqygh7oQo=O5Er;%hREM?P% zKTx=)c*p~>hpR-a{s9R>^pLdj{ZD}Maf?CF@1^r42sO1LFhJ(cQ2Py6&Jq*4y)5)} z<C%v7f8w~-jRPM45XL!9g&EBnZA}67C|4!2Kj4|tt`hOAKUisx;WF}||7c!fwtH7Q znU%bE(~1n^K^?b%YI`cNlfI~vEsC6_cccWHb<~?um-^!uZ}>+v{{o2N0Ymwujynb( zqEWvy%2%gXu~i=Pp}>?-aK9o!T{#Ua+i>w^B@o($F_6lxtk~)w<@85AcFM@Fz-c62 z0NacsBAUc}6|EI?UOsqY5%F+&qT)FSPXq$j?1*YPX&6T~Ql{Cw{R3XL5iv*{noEv| z2QuO{6F0!5jn@q1ebY!UEbzeO07g01^9oQkJVA<Tm@&$q((%hM>#M5XS-v+KhcR}6 zRP0RlRNp9PgejCKm-$o}y#U)cw8a`YVdPv>OE5%mTggk#^0^Q3v~#z&D;?&;Yu>81 zW;FB<uQ^JaK_QR#48c$8vIMvJXc(OdS`cr~VHRT@+!Y-q|Bp*Cqc~`mHN#tCDNJdq zi%?b&TzLARy<9VP_?|Ca;87~4j_oHo^Ehhe(MOlLPG+eM_HXbSDD=uZL_x~OBIZDw z_Ozx-`MB4>#2vSaKy4o1INzfqLXmCcgNORXO4YpNg_{?>AaZ?%7eM1YMtU0&hIrVf z440@%;5r`BC}y2|gyn{#-Rys<h8~cCS&0vr;;t+WJRb3m9mzU}5&Y(BD<l!u`9c^Q zjCoL0b7B#m{HiXW1bQDUSAX!Lxn@$XhF2MkL=G-1A)SX8v~lW8UZrZF>AdsO>*Alk zhK<&;h)FFDlka{*N>!65QNB}fc?hWOiV<Midw<fA|KUL#)xaEzw@GnkAs_iFd85pZ z6-`|wKl;+2KJ}|_ed^!H9@4g$-<frzq)~%`biDrb3BnN9`U(2vPyUVvM;)J_O!~?K z+jNRyovusYUjTEIo$z1%G8ILW+?@YWU%g~iDLo1Ctsj>)#6i4V6P?)q2@xdagY79_ zLw$}mq(Q=1U|1+l#lVR#3<BfC-vXN838G*Ms^AK;;Pm~(Ew~y0m0%0fAPZ95_J{<b zP}pCn7Q-1{(!fJCjMl3}*o2(}isZ+W)e?owSv}B&5=z~`#ltwvQ@DvzXu#VxY+Sgw zhCfV#z17KKo!(Gr*gd3)5^)+t$PGua!fw?Q|5qFxn)tyybQ8BZ2-pDDYuwOvm4rtH z8AW_ug)k76Sy?;~p6~6K$iU#M!QFmQ+;gZ1i`c^(;l&!|N|=$>o0*(H$c#O}Lq0Un z@-aj&2*ZxB3nt!#tAL7B#X~GegFl=Z6dsYe>=vS(UAT-{w)ulNsG@eATlzdvCaGct z3C!oLn77meY^5S5RnoO&i)L}z-*|!4XqSR5$s+IpZ6u>R*@!(9V`vZ&(xD6>QjEdb zmmV;Vh!h_p#uT|Y#UPLZN-&GAxdmK2SFV&sJv3j6z)-CHgijemFNj?Oy+vuf16~N- zXsLy1k>b&yqALNEJ*Y>you0RO0e)Bn|Hrf+Xl$T3e8(29mN%ByMP(j5(HYnn0g+W) zSL6o7%)#Y}gB^BT8NTGe$xE`m#xR_L)g^{Yt(PEH12yQuF9aDBvf~%IBV)mWW8ETY zaZXT71EHKkGVoF2HJoaA9EBxLdVND^oW@ZpWLhjA()fejJ(X9;%|9H1A@mJMMq!ZH z!yMp31$J0Oc-1u4Rn*xfodAlU2#L?x<?r}GSg;#fvQ;IuVO_O^{>=tht(BQ*;4_p> zs2vUn%0o>t<x!&DPrTz&E?wO5;8jq_UAzM~Gz}tpgh8SPg_ss;dP!KS1y%ymIGBc5 zHdJv~Qre{9L>#6*A!F;=Wl<c$|9U7USB#mt>>@<6&&!2|upFY%jn$cqRJ^32XXVvW zq~Rp3QZDqHc%T$4SY|Zj10LK$W@;wG{lqs=85gbNHZenJ3Pr1w6JQ9~QTo(7l!G}m z1Jd+^XPk=mjA3Uz2qy{yH}qXs(9U&L9b@!kNa_%nY+6LrixY8YpMgc+P@UD)B}*J9 zPxwO}cH>sK#&rM=KLO{6jl{csP1!AG<?);oqRx8ZT73A!d!d9;p63^B3N_46uEpAW zHjXGo&^egHG&o@c9p%w*!#O;{9>jt$<i$Dt2UgO8G>9J*w&Xov$xG~J7>OiL%tJ{& zL`YE`)0AGznF)pV+lfNw|7*;HHh9527|hl@=S*H#MUf<%LWCGy%`=3ATM|V71;eN1 zOJY?_<A_E7SPZPG#l{SiIOOQfAj*A_V0$VPZ`fIN=@4q51nV4Si)f2ITt@EDQh$&J zp|IJp1!#s9#dn2`UWO@O`oY)yWmh4mJP=)%T4PZxf+75pzh&5xID);^)wx+!40%h^ zv4Tr^DsgoWF4Pc5;9Ihh+mm=_e1IoPga!W$g2@DsrD8^Q`OZI(YY#C-q~1jA;b`Fi z;vo1!T{I$SW-6r7UEK|yOy=E6h{_tJ$}ZhXf6$$=@T1GbAtLwzk%7u%<&bp92K@;O ztK8}OY=fRY5C-}~|AvOoT?NUz5GOrgP7b|On7t7%%z@Ojigr;6KKW+GLR$NUhM`@A z*C`4K{)JRP1M2YJmZc0V63WPU0usOhHROXlTH3MpUPFk((3We`0tFNz3L(70?t!Zv z0jW?VOER<>Kdvhn^#v-j3Lb53M9{?=aVnBtXmNNAXsC<PVn#^GL!;@T>9rs3z2Am* z#ocJ2{n@P=Rs>m@!86=L+;(Hg>Z`6mUM@||CH93})q@#y$DGa^J%q*?@IprZL}hBL zKXAi<R0v=W4?)mHe*D59ya6P@0vx~r9xMZrH7g=E;Ge()G8_Xkw1wt2WqkT1H0Z%G z_)fe!qQ*>A|7qmIRH`bvu2rP47G>DYnQa9hQir4Ehv(u(<<-F|5XI+!M-E-=PQC`9 z+7d~agm*kzOJdhec_~Zwo8@6%M)if+Xaug_$@i-0LLf@EHcrjz!7{|2*|`$sz{D$* zZd5WxHT(kVn&+ed#jJpc^s+|3Tn{t60URVkBMbr_48kw`#neiflKDe4ykXdy&Qr34 zPpuQORNJZ^C9L9&oW(*zg$oMvrbUp1ENKm_&fauJXo%1okz6mu8mD0DP|O{j7Y?Qh zr5T#GRV&y~SiJ-hV`u1%6-H=87=Gs<Xbeid0wLg@@5a?%xECQngJQ%-*!=<|ctYoD za1b>F|7?_Nx%$b6F4BSQ4<Wz-Ed0XB)B`EJ!Rnqc42O$~kqlKF)9pf*2!q7l(E^<@ zukkLE1-Xq;<&NKFg$&Iw2cA+8*~v(N3FOkDlAMV}WsR5`=4<f68St4X6PJ+4$vuSO zwMFN0bc?mdF)oT~iA56AMKSP<L{501ebmHHT+b{JLOP<Dk%6ZmGH*QaqK$rLrMTNa zWWy@-0_v_pTPy^6=_*$^@K_MS9g7Y(tWiExg8|PgRy2eb5&|S>uDXD*=1`o2!81IY z+&zTOCq`U6<8wai^FH%)Kl}4P19U(OG(QV3*3xDK4Rmgt2@Ta=LX+>lc~k(w^W>QU z|3-eKL*w&nm{nNx-#*`|MJ3WMVRSy5No<_KZtZhO+`|S6L_)ttWcHf}&JP#;g*e<7 zd){+DQ%;iMS2RSggZ+a~Rs*Ks+DQ9z<3KaedO{`KLM{-39=rh|ypcG>o>A{J0=X9? zi1YoTjI2}xA$WpmY|K9-^zfzgUvP<4tMyvP^R5+cH_9gBF>>Ujlfc5}O>C4W4Il$M zYd)|-DN(UP9fU5IGu|i(CDD!DB$u5^ZY(`RwluI1&4aa6gfcEyDYJ+7PVdZFORRbz zrg*S}MMFJ6Mc3(1V;saA7*kAE54q&T{9slZ+f&Y9mOP-Y9g{V=it{fJ!XQw?|2PO& zvqZKRzrqLxnUqxn+m&ZCgG5qdj6E1)gE}IPRb#58$U)v~56(5EBuV3ND%q@~Li@uk z)WOXuV+GX<z-R+nWf!^y%0`r`VK0dvtO8m|38vvfd57E9ipQb>3M)uWnB5bvZk;S| z&w$sT;Gh&}@6tR#gE%<Tao<FMd;?kd&<r-l^8EuTNOf?t#@PM?G{EDFNDViPEjJ`> z|Fi`gY2sI4^)H~~$@Cxs`NO5O#S1%JV<bm4%uirEA3eTB*A}kp?1C^HO`UExf2iX5 z6{+vI)Arz2iCx~n`0-}9)m&2falRk+Mz%wlGRr<6dE~?QWOmLn6gM@*{~P@^r2(jw z|AXUB7X$BDQ4Fhz#s^UopQF?$B#4f756@1MOl6riBf-bm-NJ>ZajyKuFp=FBGoYq4 z&e;8eZTvVxk;{uf1-jMBdq8?M+_V`zj%W;1X>;*(zXc>lAg@#@1Br=rC%L4&$~;Iz zEc}HkD(pQVICb>fLoVa9&OtuNa!H>dN3;rmqg6h{*fT<3l5o-)3`49IdzBYNo7mz! zKn+YJ31+-SG2{{h<ye5`O(!YDli0>kA46#G^n3k}pL2S5{R4Rt?QEwtU66VjGfRHx z?lIIuV5lOi4BbJ%I5k*Csh@U$j73?1df_sQVWsn;-h{fKlo?Ac{~<?~TaOLht<z$d z?W;F3D?+lAQXXdy!<u>pkEwUIED0a5f|&s8T3lB?P;S<ow?xm9uIB^@_qUQ11;Py6 z2j7G5Fo&ojxejY#e(x4~nLE0>)P@tn|G1_9db)8lcN97WBtSxNB|6#UM5B8r?}>+> zEXJk$!T}#p#3`A@be)u-MUpKUq~b0hO8k{IoR-lmC(2RHNHWKFJcVHG1fj5N*aNqJ zsD(B!Uxsh|vQ0KP=6>*D7Q&5d7!REget7h^nb?DHyw%oFgk&h)&<84=+yf0S__-@! zSV%=Ryj@7H9j4%Pj^kdSR|UbdgrCGm+kJ!F-%-vWnUW3N|DbE$I55T-k%BmfsE2hr zc+Ti!K|RzWnQU(sN|bY7Fa(7q(jx1<$J{3^=*3;Hl@|W>DZ31Bo(b?sKEz;869K5S zkIg-iQa-dY-;V#UzrSRKN=W5Xa}_6-z%;&!l?(&KKQGVd(VHi)8lGd({Q1k5&)>XX zZ}NSUCvV=od-pPSocA!^KUjMH#rrnSW6F*X{UL<pDPKH)<4~%!nepL9dH+Ze@)zx% zzl}FHvg8)+Wj=Wh^WAj%5u!YCw+2DGXb-Esn-4EW`=(IoL!$S%%7gYMS~Pn?IX-p! z7H(X*8JU%|x$)aHc=lqwn>G#W(7A&N7dCttu}7>K|GCMF)$iZ9z#H4%q)E>ot2zI) z)vK3L@Y|wF<<YCB?Tog3p1J+2!|LD3nxPXn^sFt-Gk>0GZtQ(eoNL&U?a?MonQXqx zpP!l8U5{o%)Bl?L+lHBK+>N*W&EfSAv%F{ufii6gP0zAv4Rco37}Q_2e|T=i2JQZ4 z!)n>yKx^DywB-DWC!b^Rh-N98#7YS{nwFa8A3`7*5J0z(W67*Hs1awWjV2RpG@8co zXQY3)`Hi;G&O-|t_L@oz#u!toE1q~%!V5xVX!+-_#bo>u$RLHBho*Y|ImeiIxVi7G zi|F}BGtN9SOecBj*(M)E{`lv*e}*~ZpL#fy|Hrt*F1qrcGnNVSvy^U2vzU6Y15&|! zuxhOiUgjBdBYL*+#}Gv1oO7^?u$;sXd$f@!o`e<(3PXQ9fux#?7W4?iYG4_p8ks8G ziZuBo%!ivx;bO@jXz*C(8yDYt=$lqkO|P1Hn2PHmuKu|NkAI@E6<4LWQI(li<uMgg zrFa^|S6h)C656Ngdg`x#k})Qqzsii3+ityWwI5n`ixs1{?)=9)i+n^(&Q?>S=N)ug zDUDDd&%|sIL+sh6o{K#4%*!<HDahX+MI7f%M6GM-Oe5*|&a{H(GV~ur{NQXrN6TZ0 zz)7=N>e=W*8U&VTJbm$1rTqB?k7}w3|7tJ_M<oztxI`X@DyxpIIpx*}Atj%e@pCHE zP5-f!=Z-Ft4-!J`k>{JFy`6d<8f|3o9&KrnCZ6A@{u=BUH~K4|N8W))+o3&bSerC? zk@KE%4LkGcEd4ODm^0$(tY5i<ywaal>fq9#avSysmpR6{jwT>|8|NW$?%`#QmawA9 zo`3T8ha0xkcB`Rn{y`MuM#+N|qWI2g@z#{YS{aXR)XMJEsH)KenV4FCN@RNstfupA zLH}u<L4c+?*oMBLraz>GPqv|G{?X$Yh@SOGoP2&R>H4stwOS>trupWbSmc2xujjpA zpMAybAv>8<{7L(*+ww^R;)W30|46zg`Iv+kX(&cKu%kY9;VlgWq{l_7gr<jmLr(fL z*ulo(r+j#!F%euCA`oFYtrUiBXOPD@7&V?pnI~0eG1=}`qAUshLmb~2Os1&PDHeii zX@j^0f_6q2mi%KP6`2di@<B2L(Jnw6kqIeCf;^jCBztf8g{#`ft!DgVT^)(lTCO#q zlVq`qVO*bw?2#9Hyn`0-&<0@a(Y@^$=^1J0OaUo#oaA6-KzukuGvu+24;rvAwmFSI z212kAiijT6_(vLY@f?^XMliV|O+mVo3wqJyPkxvLXC_0KBGn@vUeHEM;$gy#g~}f! z<6g~BRSj|UM}|0&n(K0<|DS(I@gQKdiLQ9{6Vwf{mW?9BD@t-htdR?LNBJdGp3)wN zu<RQzGp4OtBSq`YQj9RVV&+tm7kK!C7X8Q?AhTJ{snzH)74e%>0G5k15Kdxd@`pX* z0UvI}4O)W1%CY>wiW>RIN%e^1qNWs)AxTGcl=wp*J@Yhqh;mAYk<MwnFv0<u5_KTa z9whQ14wYa?9Gfy(59Jb?e?S5f2#IHY;**dmP7^Nt^GEjZ@Qby?1uNN;&`g;mmrT7x zRyTrAHF9<`a|UUf|LEp7>;aFyr0;V_m1?wNRS$n4Nghjb%i(e{hk0CQr7_~hl8_iJ zOpb1Fe9K5cH>XyE|3b?%^3aACtm7HcwPG{Zc_d-Z^d~+n;vev+hY6)A$&fS+hVkT> z31vl2T3%!#E^CPJFjS98^{so_xkpHtXd*xcg{HqaNM@Z<rE07$K{b(OOR7N%W+82= zGD_-F|A7o)<YgL;jqPp^Q`M^qgGYb_STNoR)^+msDT0jSO!g@ctc+5Vds@s}hxA;3 zyoOENxCb3zbDe|Ctu%i!gdzL^4|+JNu(e#-8)Bo_)UhmRLNN@6qM?Ui^sB7UOVt}( z85G^_GIi)(=0~Fv(m@OercKJKKj<S4>aNx$p0G%Qkqeh?7N;%ZTMsRKA&>FNx56Qo z(b%RDk4L}*|9!dr976Lk2V7LJZz3KZ;6zEBH>ze1u$j|?|8|<uU5sDUIfFm6q05O` zNp#~4?0FTEUQ`9~o*fy@v6>biDgv`5`Ph^=jG7XxXcVy?jS*J}xT&YXv@FpWgfFH6 zGHk*{J|!ZliV)Htt58_RH%TgTH0)G(#AAHph-#h*Jr)hiLm0hy9~(U)7=$h|7^|tr ze~${HdjQT5i--r~5Qdp&h_E0Tne3qFn>snANjIYFr=>pV$r1UZApgKCc;KP2jJ{V7 z)KD!{qW29w`~qpDZ8T+CNew(eV=WK)kbr(N9%yjrQ!~uf(im)0k`9~9tCJp694kpw zt*#m_|C+Mtj=?%%7uq99^%057_YJgt5#8~2OI8*=k8t5Oi-Ng~=;n|MNjFa3^SB(s z{5W3g(BqQ<`zmw<J<nGEs7eLNheGF}jd_UDyvjLu`0Q~RdUOth^r$s?TokE6ydvC8 z!B9SKA&3>m3ONB<ZL0pE%AGA}%Ey|N$!NB5qP^%F%lbyClD43r_k?raelvkHHO#fB zTsh+idWkx>GfIniw(p76H;rMA_|`GtVZTY#>XDDW^a#VWxr`!REa|IPI&N0-%&ZHt z?|=MtP#xj1<1RhvXLvy-f&)*z0txHS%rzczGG)o5qUAww2<k2IM<qz1GoK4pSFVk3 z|LY{#kh5e%99p^j@E`|Y{~~8Jwu<5}T7`2`V~xIMKAF*%MXG3vJtbGXn${r*PHcF% zleiZ?Ufi9JWSj$Sx|FGD;`j_Uh27E5S&A11_2@dRqOPOnma?CA4_2I^4s!@fMBjdp z($wP{bG1i7Y#sTZoTXAXPn`;7<@&j(Xua`$&waR(56#CPMj}Zmgy|LPPijJf8IG;X zsH83ALl0o#Xk4!~9`GMfPxx$t83rUJV#OcI$HPkO0z=RvrXe5N?cI*c{GKF$q$I|~ zj&1D0J1WRY7AQBK<GZFN;f8?~JY#`Suu!ao9@-`bNA861uNsa)5AIBoj%6g`{{vVc zDJaZBhiZh!8lqGva7=&%RiZ&vR){vzEGZW7FqY<|2%#isqc!jV0!7d%GH~}u%vw$X zA*O*1#ZI3V4IXIW_W}*<mhT@{P_2d!K2&WI_9meIZg1qo2ZKc4NF{U7&vRbyDP&63 z5P>r^##x%8p6;P@9#DwhV`O0A9>Q%AeX8+Zfe?6TK``VSekUHTEl4`$g$_vomxer& zEg#Ac|AJ_CjBXi{urcaTC7MA4GeX1WVQbV##mY|@+lSBIC*0y^ep&_WM9uKp$}^bJ zoMg&KD2If|&L1Yh5acQwCGjvCL_`=RY6Or0GlC|<4G{`a8!(F7;%)+A|DhtHqoryp z%W}~inQs1~p?R!MK#oO+l+Yh##OO$bB%+M}AYxYrVH?ctMgHqTqN2Wz!J|+p8hYs! zZ!ZLi(MH}%H9RoIn(+c-B_F6E7SM(couXA(VQ{3PO)l^%giIUaK^%N6y0+m4MbJ?4 zA-c3-8*cGdBuFGkBHTuVKyE<~Y-sexB6{qBWGLiC%3>lsLxO~azNja?jIoUJ0kLG_ zAK`+vCWRYhqPeQ!6)45cP_k<LA!;(Bs^Y;Mk^#_cBr4%@8}DK3z^NayrKd82J8}#> zw9gLX?n=g??f50=&fpoea__{>HZ&&<GDaZ~@^QvtSMb0Q*P@<C|E5y#%tA7Z%Xoqi z;)|qO1Er)wmbfxh!Vu~lBp>MGXkIfhP-P_tk^^Nz5N<&;%aYJU@;xphBx2$BzCj!L zGMgaBs;;FZPC_N@2fKRk0wYdz_<#}yr5-5fN+xYG!;Wq~ZA4f`vRY>->;XNFp-nsw z52#^1NHclXYv}GnKU4)8K62>}V+-+9+~Tf4j;%w4v$WtN8uEbxccvkJA=el}J_GKG z7DQXnNEw5VISGx7#;1Jp;RM~p#|+atL(t>?&<y^88s4EE#%o_DtrX?$OoZ%MI!mjd zhd_Rlb(l~Oh-W7D(_GqU{;0<QDFhduQa`=rPmD(?29C8}|Dw$vbS_$@%4$U;c7?r& zjyW$(!{Q-+KG4W6RK_%n8-&3Z<kBKMR0w%N23xey-e@NTNaDOhPFfHst%N${C@JlN zmRO4vJmFX7K|YKJhK3@)3WH-L1rm-(EJ{g-xXhsT@<~Nv5Q3&SddEhuY|K;!n#yAy z?v&^pHP5hg(fq+|T(V2OG{iLQ9`22PIs#zwCLgY2D+Muh{y~$hLm=Qm?)EAKZ9}{8 zPDU|e6)}=m9Li<*k=w#k+M?$d1i^-oiC6xiR-BYjNrSN5Y(Wp?D}Q9M6oQ_zYI-0r zYIs!aKsD&Fffmk3>Xy?~y$3nGi5t$2(cS}KKJDNT{}cMaE+78zGNEKMoa>JW6uA&; zyI8><n5Z6tF<AA(rH<wwkT5?TPFE45EUE!P>*H#e1`?#pM?G~cIxoVGhAob+AyZFV zAwnlnkx@ee3+IxVgz>_P<f_bJjdpKc!>%=uq()-pUyS5S>J?dClwRQE9`FZ-Mg%VH zAvl&{819s2RU!><p<k+jWYSVvHR~RgLq7x(8r0?Cprw@(aD^V?9_?dDbkjh1=(PAt z44d)7eB)i;0cu7=>E@Ph>(*}X7H{)bZ}*mO`_^y8=NrPsi>UF9V3gDR7I70-aUbmu z0EiB_B!(bIaVM8@_jV&X=O36>mLw@7f&;NK|0FFKuX2@c>KbxDYD*6gb#(DorX27V zo=$a+O>|dRy^3{;#A8!NQ)i)qc6)bpFYGV;K~+_(X5$Sxf;SeVflRH@f|QJ3;F2af z2M}za80aNdQPLzd7xv~4E$U%YzJVfP(^kwgDxhHyjv?hZwxp6HB$|+iqQO8QPkp8G zCu$C8FyiD=u2e%3ixw>(!U^9ntaxRtJv8hedI7l5Zr}2u4rYO&08RuWsU?DeQT{<( z!;bb!<Z4`x%%m0;7_2^a27*iWBECU1mx32F(OaercA_Ev{$Wx^bAAErhggPl#Ni;9 z!bfI!w_f%iHq@g8tr`dTOW()c_~ISR|LE!bq#piiMT?^jV@}}a$sbV<U@I(xM>aV& zH&l295}p#2I2YoWEgH-$8zKY}j)tjt*e#Z@QP#{Nq_Es9H2{;NEL7zf{Nev#t7Yr( zij?!7lELfl>57T?s7mD=fD0ZRB)sh5`symIgt2K&wRBB{cg7(e>;Vpt;1}`}7PWBx z@Y5dn0~$z(jWx@1oHG6<BAV<qNXp_LUV&KvRm{Bfib5|;`l15W)sVyH4u{UqOd^i` zL|*10qI$U*v)DwQ<w9Jh8p_CPhD0zrr^<$@NkP(U1I(p%q9-_TQ0rJXsX-5JVIWVr z!s;S;uO(aJ6`2dofDxESnw0tI|0)pM87?b%MxCOBJEf2Z<IDWv7UX~s-e4LW)SP9` zPiqbW5%hyM@mnk+A0`44EboHHl}Fs|#9We>?U`zfPA}pCUMK4Bh%AEonWK>lpM~ln z4`!o5<&L2N4q&0g*3G2-`Dq}v8d!#+rI_y&B!=>}YAu=}1ldlA<e*Pld^<vX@*$DK zWG0yJ3=~BX$)u){T8xz0N@*!sw)&N?a@r~atYxXC3)Exb&ld*4pc9f2+rsF=x{vvC zP5yxy(uf<n)~aPpc~pbLrm-OYPD*-ktnb=;usWJ|iyLC8ia3U-Hu)B0xS|DHE{1^) z!zrEv8?x8hBl2P%oa!Bd|E4uK=xBD*vM>8<uzG*X$(08i=(G$DDk36|8nUzD9)zJE zlq45PTgEWQ9uOJ0@}X_was7T0x5F-KHicA1n=j)dUu9yrg(Q)M!6liBU8{PGaStyn z?i^y_9HwCyyucC{=x4(Sx!3g{vOy2@fK*1fxuHTFDE6_}+bw9J7viBq<s$L4V%OfH zX)hv@y=9X7+aqcOx$t5f;Nc&z!5HMB66oL=j2T+8YJ|obz{7@7UeS{pLrr5OB#>bc zkU=_aVt3)fB;I?z5L+&kr&Zt^xe#Q0GCZ>%BDW?}098^t9VEPkMCwSeP6lMc?F3bj z>mtTM8&soI?g5LG{|XAh(n&Ix9+ZQp=j~|(oZgJ&w5P^M!i0>j*CwvquAwDdW5Ngh zAu@#cCOktXj)vX_Ge#~#%->4t_?y3JgUxqY#dnJtCV3LGh7Qj`5zYb7)F)QxJDjp5 zb7Dilzou>aK^W><C1b<HJ>sm4AsOZY&tr=d=V7dtVvJ|-8Eha8=ta2W;>zp#(x7A} zt6WHC@E<a5)99hl5B7=9FOG_#@6PG4Z{o1b@X=eSB@9ewEHp-<V^>l)<;1*3;C$F} z9ct=4wyp?R^rs=BU4o+hFXG`HB%vJUCnBO9Sd3hG?8F}W!7p;FeBMDWx1HP3{n?@2 z8rj`eq+QzS|MG|X;ht0@k=Me4;Un51N6g8A7<RkO+a2Bqp5P1K;13?*(;eLnD%vqZ z^4z`Q7k(ZJq8`Mc1+K$1xZPIRT=L%Cf@5tC7D3Eg6*j~ib{#(67arc1g5lGh<qIAN z^MMzF0oGjo4Bo~btZLv(gE}DKJA!Q6-#y`np6DYY=x(7tlvB)+TqqQq5Q5-gg$UYH zUgbs2R{jCrGgmDB0UBTd^mYOkJQM35KHW2SlM%w(Iil#-p6%P-?cW~m<G$#pg}TC3 zB{l9SRKwlm0T|4oQN(;2szEg%g&V3N=m=yPSf$$gff3HZ7M9i_?ta%GC-7rsd@681 zRLmi`{~>s#ZjIcVCWb-RIPo6JK^K+*8KyyUb0uoHAsDCu7|P+ErXd@$At&&f$F?CG z_~mr3M05&$8$_oh!h{+`ry%Ts5?r9>jimT97x-HvBXmC-xYGr4!xx@}8>E36gyIo{ zAM1@d_^Et4y`Nv~q#m+?8jK_)_Jv>SA#=hXWU1j8ij3l2U=E4_8C<=8_vs&`0U&(w za>2_VJ!;#w{j)c(p~Hs|BTAeY@!mau*_z4oH;*GXZvOmj{Ksu$HAqN~{mYgupG$`! z<AnstG2TaiF8$fu*wG(1nH=Xe%Z4*vK0-5=9m}>+UPF#LnNfR#<li@+Aphl~$hE82 z|F2-fiXBU~?8IgZ?WvtMEg!8@@!qLomhYS@e&m|@tLG0`xqQ{`AtSd>)wyZW%;{1_ zjx9H0lKLT@CQaWyN#*{Xq9yO$qki0`efy^EAF_SQ%9UeOZX7pq{0y^I%x@p9Z{;NM z<CiR3y?TrD*^8F1T%_8PW1WkKO%=6yr)ozk2X7c`Rp!`Qv}m?_S&Jd-{R5;zMI3tc zco{)~V%9%-hS;AeR!<rk6*eZ(dsh#U3xDs>lT97$8KO--O~jEy3#_0=NqJ-hSdR?@ zpy0wY@;n2<4nB!P&3!EZLQg$AsDQ!_x%eZFJ>!g{5E&4t07!|w<im;$D3HMn|2@x~ z!5##`{Nn<9HVlK_BoNf`k2~+!<3fcl{KJb6+Q?IfAM!9$;s65#<IjyJGV{-h+uh^c zMBL5u(mc_?VnS8&{Gx{mCXg}>G;hE$0}{7X<4F+E{PM;t)$kP0H_gzAgr0CvlMfOz z%m7I>{-A^a0(kgC2%RPn0!=*sAYno@g&uV&0-of92O<9)^G2Vum~iO~`EUb=2{RBv zsXQA6wdR??1}p5a!=k0uTGPlwOf2v8qlh%`=t7J+z^F0}H~#=*PCe1Uqe?mbn4^j| z&Ysf`F~)qu4K|V-R!lzFD3eS-?#M%nD&M@LNHYJh#g;$kv<nO{{pgZR|31kGQ;sgw z=zGpN)qX>aF8!RNNI#>Qqs+B!DOT}wikKshv(1#-4=}{QbFVq8)vL`n<JglXvBJ7! zQHu)kG6x_n81j!1aqt3&7u*cQ3NK;+!p#{r#1RJs%jEOVA}!QI4Lv*q62}9q$O8cc zlK>*dHumts2hV)`2E-1$;Gzwv_tmpaK71I#3M(z}q74K=#{q;q=(Pw^4m;oth=1}F z!$%x8oZ(L#M({Gp1H8cVK;K3H{!9yV0O-y?Ed-6rKX~g^gc$LhA%^4-6r)WGN#_8B zLG-}<>#%Ay<dRy|WP=0}Qo|7h9Kyr$3!Q`z@<ud-q?9K#)jTCn|24OC3I`G>5i$-b zgxq=zG(ivo%kQ?%01HZx<nzs@&_pB8`sR}Y%``~pG0iPO7#{>A<5x9Eu6lySPkN=h zt<da%2uvUXjm408d}A8%poT8Wft?8M<AVE$1w0PqmwZGc8~dt@BD7&Kc*G+cCX5F> z6mghokV_Hocm`X9@d$Y6s~_6%*EGiAEM=+UAF43MJIJAoedyzb(ufBwG)N3$sE~zh zu~<DqV~=tGBOf{eqB-*6ENVCl9{y+|JYr#)3!3m{`7o0LiN&jxJPic{@Pj{EfCzcS z11)$1Nk)EFA@&SoBUGb@JFo_U3PFGs^>6`};<1cxh$9Xy|A1o}>>&>zU<n@d5XV0d zVFQf#V-7~Bhdf*`34getYgDTTdMK$4e*o<tTpP$Ucm_u!z(Wj1_{Zy55f6gE0}wVi zp)2c9k9Y8=1(d*KJ@EF7c!)s^^)SL2{_zZg#A5&^8UQrW!<U&M&?4dxM>YO&y?=xX z0kSgRFT&TpWr)KQk$S@~LXwl|;qMp1gGT-IDJulr0(`JI$rZk#2jE2`d@g~-4B97; zqaYy~*YZdG?iYkxtn(N7xSl`sa4G~Gqfj9U${I&X(vpHjFUMlhIO1^+axCl|ooN?5 z`q7Je$V6M*c*Y8Q5f6)zP!aHu$1#>+#}&448qSJg|1qXPj2db~5j@plPk~AdRmcN7 zzz_yJEY>VVFvDK4$VL;j;jkz&LMPL>hZSw6MR)<VgvufYH&l_bcO)aIF!QEK#o`iP z(L*7Iu)#AnhX{Lw=pWmd#h0q)4`le_XJU8;FBU-!nJnTz)Tl=sQ~-}>tb!LpnuOIx z)QT1i;~6%X!#_-E2*CYyJT{OAQPSXrc+7*8x1EGMF6&ypv=V50J6hfdk_}wiLkwwn z+bKthNMOpNG)7P@lbo~&*XFSv$km1s=#U{_9#R`^)5eJA;gpf?&K~2`XsD17DEY1P zpC*CCrI7FoN{&V()C&SW0hK2>$Wx&f&0juH{}PXaej^%4AcQ^gp-^f>15`*crzY$7 z4}iiV2rALT8>&H-UqFKt&G<$~_DbRslh|1QNE2J!!3bd#)i35C1}&!ej|t{u8e^Om zF|ODT?1(EF{(uKO7}3If`K1xQm`5^v9GM*YYaGddVO3XX4s*nUWs)$aj}^g0VC0L) zW>sNZAZ83<B#{{8h%qBdrV3%0gApkchPK4@4u3q*#AflULMUMaKmY;)e)z{T0l@|@ zfY%0o0E7_$VUIc(0TGbXi$4%|wMq0@(X4P%VfRxHUR)Xia}ZAMx@XhR`9^GQB9 z>1P}8VwAe|PdvEkk5)EK8xNQSFCgIQ|3tSSl#tUJ*WxkkRAb8qY50dR#bJb`HKNl^ zLj(lK01roN4Fb8)ZXCqcIrLnFq&FJ}rPSNJ<h?<Eq;Q`+qA>^);1dbdn1=MIH-lRU z?-z@@9wcrB3w^?&c>^sdH=vQLgwEij4JAc_^>7S-T(5g3uxR~|f`ocxuXzY3Af7kQ z@nA8qA#2H(F!})xww#O{<oJm_{9%rBj01v0<OeY@_KkDs!lfcn;mjYXje9_Bf?6qu zGWg*P$%sZY@Dj#5%wY_8j2s>)$4ixL&JTUWf*Zz2h6+b6nto_i9&Dk8G4SGxxWr;N z%#sH(@S=<@PNN*;0LD4&T;7g{|0PZ0nS=^<fC6M>NDL=hhCl4l3cmZ{Q2B_%4sy_- z5%Ho9vmOy5PUN$A%z+oGq{lcXK{yn+jT_k@0}9em4D_%f4)qv^c*v6j-D-mkyog6D z>VQdlkhe5`n1nXcz>8wc0Un;_yU*k?haa&59=!jOlCWinMbNGu&k%ib^MQ*Uln4<d z*{t<7!iyZJfDBbqi(YA#CVQCk9@m>5G>~GxXvpap>Tc5@paG3R1hiNFsKzn$@C#Dt zVf~~~4SEtO)ld)PGhf+23WM+s)u0Ekpgy<of2Hzakpc_%@C*NA0_Ro_#}Fwq00)$$ zCkgfq_aJ_1WOpc-f?n})|7s!}H}*c$z!4lX4GSR>>SKNz!500Z6IGH!!Z8x^))Da# zgZ<JGFyk-}G!1G|C14j4F$jY$1VJ0bE6WlZ*OG&3aTVim74k3+{nAR>;Dv1Qa^KJ| z{vs1D^gvA^596nT50NJ7f*$Ar7$brnV<Jj+SP$Qj5A;xb=2s6ZHzM{x4}(Y#|L_}o zK@S%Z5`BnC@=y<0G$Mf0A|tYg<M4>{Fl(3ih(UD^gs4Ugu@^yA4`B2guJsS}fJO2E z4~Jxj=JyXWK`92YBKZI~;z5Y=unmM*I|f0D@GuYDFe0i{f+3MR3IvDIpka$b5(_2{ zQX>-npcSJ5DzGRu|EuK^IT4KwRf{;WVCIx!`5+$E&^*-Oh2dmQ_CSlpNJ-ZC5A$#j z;^0V{G!NfsPV}f13+9IUxQ}PC5bih+SxAERU|TH`5Ak4A^{^tx!VzjgioY=rF{46y zC}Q&fh%M3(2APrna1OD6a?${HSHT?&VGs2Hkbp>v18Eff5DQjh4C^Lu14&-;K$7{0 zkq60A>G%^RX-5v3dahwp_AnZ4$d3@=4`#wEFEbi1qYW!!M@tzq;_wl6G!FM*M>63O z<Isb)r4zQrD;7Z-U^#fKR1#{zD-F>i&s7qm!42PFM<ro1YQznKvk@gB58R*)+VC6s zU<hKc180DF|J!g8W=URk=@Lq*E^EkyX!#LLsfSBxCMLK>+4v3mlwhCoJ`7k5GC`9I zCLHOwVBcVj1vDC@IU4y8PSpTXzkmn7GYHXOQ==hHM(Idc*&>-4kLg$q;-r+iSq-K6 z5ovXTL^+%&h!!L$7K7Ok-jtj&`4EG7kuBJkF*bA0B^+R}7F>j8<{%PXNSrBHCd*lO z5W$>mB%WMBp3O-SWpb9|V26l624qkWztJM#DV!5wf@#7l=viVSQIFf`O+!f*=d}@X zl3=<?PX^?j3c8?WfflyqhW-FSU}t{HX`fsXq3VNl47#BlnrDDB514chkk}$rX`vlD z5xTjD|0I@<Wq3O$`l2w}5DvPJ2Kf`vNfy5W4?Y>AJPM;0!7Czxm!shnH`=4$S%M8& z4cO8^M%tvr$qZsyp&JLCAwi!e8W#F#o=&=@!x<9n8E$D3pj>KF%qga0dZr_V47Ea( zX8INDiKcL>k6?NaRvM=r2cTDKr+PXpolq+!`Hp$Ir-C}D!;&UeTBm?YsNg1?ZK|k_ z+7*Ey59Sn7lv=5lda0P2shYZ}oZ6|L`l+BAs-iloq*|(`da9?IjoFB*tlFxs`l_%R ztFk()v|6j3ng^AT4Ii<qyt=Ep`m3PVtG*hnz$&c7daT9@ti>v<${MW6daSzotj#K| zp2$kA%gU_PimlUXt;YHh%^I!T+O6N(t<XxY<I1hz+N<ZPt=Y<}>#DBhimu`suk3oQ z@Vc$_YOeH}uk(tp_v)<j+OGhcuj%Tp`)aWMI;;untp}^H?dq`h3b6x=u*bRtF+c-d zkg*!Ou^ij69{aH%8?quhvLsuwCVR3do3bjqvMk%OF8i`D8?!Pyvou??HhZ%;o3lFW zu>k=9A^8LaWB>sGEC2uz05}3u0ssjA00RgdNU)&6g9sBUT*$DY!-o(fN}NcsqQ#3C zGiuz(v7^V2ASZSSNwTELlPFWFT*<Pf%a<@2%8E&|rp=o;bL!m5v*(hYK!XY$O0=la zqYSG+fr7ND)2BsClz@3cWeBKPvufSS6{ZN47$O9ay7ENTu4vP$U7J&b+qZDz%AHGB zgTNGbGo;AS0WaPFd-wJQoL8{l!WlSlsLQyq<HwLAOP)-*vfKc6*=pX*xwGe{QL=m< zO*-h8)2LIcUd_6->({Vj%brcUw(Z-vbL)0py0`D0Re}p2PQ1AB<H(aMU(UR_^XJf` zOP@|1xj@msvukI0I!u`D;8S}4KOMfjd5|jtq+hSTJ^T0W<HMgXe}(<~`19-E&%eKY z`2f-<V1NV;XkdW|9;je~46<hscIQPXVM8EPXyJtzW~kwY99DQ&2Y`W?f`}xBXyS+` zmWbktDhANui!jD0<BT-cXrql2=BVRCX1&zFKtBc$<d6apDP)mI9;u{}JF=8nlTb!! z(*Xie8Gw~oR;lHcTV}~6msT1yf|MO?K<1ffrm5zdY_{p<n{dV{=bUubY3H4I=BekN zeD>+*pMVA`=%9oaYUrVeCaUP7j5g}%qmV`_>7<laYU!nzW~%9?oObHzr=W%^>Zqia zYU-(|rrO(2tOn5PtFFfX3hS)0)=KNGw&sfKuDbTh>#x2B3+%AM7EA0;s#-eLvST&N z?6b~B3+=ShR!i-*)@F<Cw%T^f?YG{B3+}k$j`hJ*$x3S0y6m>=?z`~DEAPDY)@$#* z_~xtczWnz4fd}bAI>HDc6m0Op2q&!Y!VEX;@WT*C%<#Yi7hG`&6cdcG#u9hz@y8$| z9KZ)6{I$?X0jI2131=lVW_DCApn%FW*F4Zy0XPuA%r^JjGtWK;E%eYt7j5*>NGGlI z(oCZYV$)DZE%nq?S8esxSZA&E)?9b(_19pBE%w-Cmu>dhXs50A+HAM&_S<mBE%)4X z*KPORc<0UNES)U>0ioVBKmFz`+W=m)nQtm#&@0Fq?zmBnR1&}{OSJL$<w5Py1}+87 z(hKIG<FrZuUr0{S7fgh%dQ3{Z66@-)<0MDwvDXe07EC~)h3&kr6h-gA2QU2a#20V; z@yI8y{PN5<@BH)7M=$;K)C<K__1I_cd@r*EaJ}}+FOho}Re*2)`RJ$bxcKU~@BaJn z$1nf<^w)3y{rKmv|Ni{<@BjY*44?o9NWcOb@PG(RpaMUmh4L-XZdLf(10C0if|SpJ z6CB%246+A<2%>Qr1e+k5QIJ*0fd~WXMe1bnlRPK^We~w&2#W^7gpBSWpQ|B4#_+uv zLM;#jVG1?>4$?h?n2sQo;GqwdhKnK|Bo7YZo<Tk*!6gz63ttE#L3W3Q7;bTQR<xQ7 z!$`(5n(>TiOrsjt$i_Ch@r`hdqa5c*$2!{aj(E(Y9{0${KKk*GfDEJ{2T9068uE~c zOr#<g$;d`J@{y2?q$DRv$x2%Cl6RYjCO4@`OlpdgoD2XcN7+eH&cl<BDkUjb*~w9& zl2M^#r7UN8%2yJ~AGpk=E_cbxUiLBo{;*}BT1m@d&Qc(y6y}|b$;@WfQkizbB`|$S z&1zbcm(ZNkHMhylYi2V}&J3qBznLa+np2#}+$1^4l#h10^PTXFr#$CL&w9FZolrWb zKGBK)&wTFlpT_K`gaAs=aSHT21x@HN4;mhYI+T>Ad?rJG^U#VybfUhos75b}(a~)5 zqoC~QXFy6)iHcM+B?ak8*`msnZgiz<31viGT2Yv)g{B|1>00c`)1LbDr$5yxS8(c5 zp>E}#KuxMrms(GwYK5pIbt+V#T2!eTg{mpFs#CC9Qmqz+t6BBxP{3MMvG#<lVKpmH z(27&F=7g<bO{QC40#~TcH6|^sYfVjgSDXa1n}7|hU<Vt_zUoA;Dm5%!pNZI)D%K^9 zeQ8J^yOPM}l&_S9tYsaV*_v$DqMg<3XE__%lZ^JVr8Vto_nKOhtTv&dOlNCL^4f?0 zifRo9;RgC@%i2rb;~wKkh!e7rk9(Yt0F6L$zqht6l?-rU4|}8!xv=$A3<_d}0KDQK z0r+k9pqpGz@j!mujqa#^AOrO=^}Og!uTN(S67{<Gz3yf2N5ZR6`Fe!D;<YbF@C#7= zdW5h54zPf|>EHeGcb^5uh%0A$V16dJB6)2vGasxG3G-8~6po069h~6`Z#bMCzQ~6` z9O8+Lc*5!|u|-ZCP!*e)#m#iFhGASx8B2u56Sgr#a4bt5-<Zce_OU~-`;Q_U`N&94 zvXYm~<R&}$$xRLbl7+luAaj(;46$;Gv0P;>%aqFv@v=$5tPn4gIU)m2vzh~Y<}UNN z|IG^#^OxaV5IJv|&RM20o*e?@JwGJE4feB}Pb}y^kGRl3wlJb+3{qTn6;r5KprSdo ziGpw<6a<{~re5#^1djH%puR^tLp|q3=ef4>kcXqMoT)KPaI@{yWjkAHY6yR}xxZbo zBS8TQhhUl@_xQ$kHk)f!D{>Q}5CtbVfr@5F+R_AZL@)$WSnaI&+62aw3{ZH58Vm%A zQA_qF#x0Ofm^&2cMz<&g0t0~vApm>O#;{}g*-SY?20XZf8+0&-J2Y(zQINqJGQkj3 zfC3Y>$kA#!_3QxfApl<BgBuD`3xX5v2ec!|77&sNP6PlIwLn7v#&Cx}OenGu|IJjd z1wsQK0KpAUK*JMoI}nQx&EH87h$RGKax_>@3P%Wl6a?~w0Ng<b0m%6s5<!q^gJ-ms z;&lK#UfzLBS0FmbMbfqq12oiv*|lhPDNNxCODw_>0r-Qy(SSmM{Gbs683T5;TOPR1 zR8yNkMJtf*YJ-$wXh0u`6KWuXO4Q=;h)?|CK@M_TY&-yN0Cxb|P>*}inxdA?R4GDH ziy}~>;SFE+(5_B{@=ibpP3Qp*dcb<s^T7{*m^$JyVT(J&fCj&Vp==`rR!T|zAf>oO zE%;D`gjZS=sQ84<k}Z&RyFwt1Km*}vK!)lA!V!*GgxMWI2{H`f`#ZqF|LYI$iZN7O z2Gga6b4yJcK%*5>rTF_mk{t?B>>Loq4}koCO|#zz022aH3yZ)8MNkAea0sT5aEE6Q zif0Lw0Dft(2%O*umCy;D;0xK{5AiTryoXhi5`X^Je5jBKMPLaYcWEJrD!jIWpnz@y zVGC0?2RRS`WB`BxU<t|h37Q}f4JQ!Gh6<Zd3bt@~n-B*>fCD8M5BXpZ<1h}P_Jo!< zW*OC1m?bIc_G_k)fJQ(G0dRc$mn>IUbALw(MKA;ik$eH5ZanydoRDm#uxxO63$<_w zaZr7|kPrW`4d37o&DC5OrX4a>Rv##T^cM=k#|C8Zb(PkJDRYI%|CfNM;08MY2mr_l zl_n5JaEWPHf1==mn|OuE28WyA3bp_ZybuRsU<m(U5A?8ye#n7!_h^|C3c)vg`L_uk z*MBV-3JLfLY>)$hkZ@fXe*qwjrVweJm~P3ojLT>cp#X=}Ko9@G3xGfdzJQ0@plYx9 zhx3+9y)`NESBS@W2}Uq=9#;yYmx85og_;0zi%<k)ux#UYe4=oPk0%gUn2+g35WKc* zf0qyA@D9>=iei8a-;jsCq$Aj-OPdmZrH~0m&~Yb7Gt7r@u0RG6IdvvDb)v9x1hIem zn2!WOe+1D^<3JDeP!GI725j&Q0l*FOP;A^dP?Hr)1QBGG|H6C%k$^?u2Lj;=j2JM) z7y!Zt2sq#eU+06(CVC6Oj84gv2ayi}u!Qp<4=AaUVlWBuKo8vD4>Bo*Pd8=}b`Y)v zmXG3w=qL&a$Odunbw9|7s?uxdwh0MHe8RVLC)kl6DUA3S3M}}SE0_?^kPpHp5X}`2 z(Wni8a0but5A+ZZ@}Nm{$9`)9i<H8QwMYp#pokn90P0vOqEHH&P;onuh$q;FpGgp! zC=tpx5KWkB{;-PiP!9pX3u3Sc_D~P>uxgi=J*Lox$#{%p*m3&jaq0$@r@{%YPzz+Z z2%HI=smX&L`4GHTk5efSP1tn)fRe!!2XR0R{*Vp!|L~PFSv_ONc{V_t@#l#;i7J~Q ze14Dvl)wo)*L=}A5IxusItdC5XAh%hT-kLGxP+4TV4JLPlJy`DP*|SO!)vCn3AK<0 zfS{bFfQ~d{3AKQKNhyrY$PgAf5vEWOO(>b5hD)hdIOE_4dw^Z_;19+&J?Ms^Y?+jQ z_l2S|Yx9tu0Wc2PPz=PEaPo(a(|HhlnGwzvpwu=Hztx2P@C_|G33X6p++Yv5)Py*S zJ@E&jWH^j}SBR$aTd6h=O85;$zy`)gjHNK724Qn6k!tm@4b$iayzmW=DNX-5J>L)w zp8$lYK!%m}cc_4zr2?i_Ne}Wc2b53?4jBOJ|7N2H!KNxfsM}x<&rk=4kee;)52;3X z(K8O(fC{DX3AJDYJ9mr*r>3GpcmE&`u{j64Fb%l?oE-`jsg|3u>7A?CmAF)F%fqQV z`VY0RoL(@Y#0ZzEl4>bA4`~n#|1b?OC=h9isy7j811gQUFbDsjn^a1o&C`T^7y!j! z3t|wA9v5l*cq*Dy4=wr+u9}C{Pz*cBs1)I-B|)v>nGdYM2F$t*2^yJ}DLf>qNhtXb z?^p{#_;Kx-D(d<V%bJI@DQtl%s65e51TnC@zy`eF57h7v4B0%m1gEKR2Dzwz5?d<c zkPqDO4~XCg{~(_B5Dx_5m(r>e6e|$-|B#aGnhXChrSiaFW?4HVs;>Dk3~5jd$k%Lr zi7J|84{*8)eqayPz_ENd5Sy2@JrQaG5t;O`4ef-etT+#vs-RKmCWLCU04gZRx|?Y* zr(}0&UYaU!N(psP589xv*NI(es1@Sy5BV?$f8Y<gDNTP>Ji64Pt~w67#i%7qD&o+z zexRH6Fb*!NPSenuPw`vLC5@~Qr5ae3VjEj)g1O@fYJd{7a7qWPz_j!b0LOT&sb-aw z>IIOgt|RKXs#XkIfvn)!3fPL0O~|Wl;;W?#w*CO8n_CY~N}C0du%P0tRC=hzu$8sS zgyXQOQt1kdD-@x2vhWZ9oBIzv|7#DYM43=RsGEAWd!k8h3a7lAoAh9L0)YuL`zg5e zrvGpTxgZbxnrb&mxt<6W>r1eFP^e*gXRE_WEy@dX;1BsA4x_uH&6mBJ@|pnvr;~sP z@t_T>IGHgSg<#tisz#gND-ZvvYmP&ru@(;;dj`cI5AmR*0}-MUJSj^nzBxJ$_K>ox zPzQi34yksfn}MwC+q=8T!1-`W!n-4)i?soo#A-r!|Jj5%O9vUd4fLR+${PTmFvFJe zTLVg|XAr`bN4iM5qrvqM@)s1^6`t|%z2oo=-@vOsOD6nVCz^z#^<WQmkg*zU!xZbE z0<oH!LU+HVuJUld#o(Bl|B9nETM?#Ebe^db_G-Vp8vrPIz6@#}PzZ%}OegAVm2k=j zhETj$JPsJvtfgYVm4FEOV8sRe8yY(g-<wMXoXK%h!(eN?e&7#NdZY(Yn4qFbANvnb z`VZQWo7~zFOv$`A5x|SU2U}Uh<QpYrTgGI24?_G8?aQ5I?5lHZDd}1d|L_cHP`8Ha zuN+Zz0)cjdyb}Vt4gTQ9d5p>5JR#NW#AyPiy!;Qxi^KNtx}SS0+3W?+puhD{m1e6E zih~sEn-AMu#K5a2o%|*UTo3I;(7G7_0Nu04TD<vy2#8?Jxf#(KQFJsnbwzOx*-#I& zynz8*&k_RAa6+gl|2Ym+?3hI?)2C9ua9Rv!fYY@M(+(jB8;1ro&}l`nzWz|jm+Y^$ zJRuX!Cfs_+|A4VOyNV|Ix~j6b&k)9dOQn41%iz&Ys<sVn9HsKGjRsu4=quI4tDEw0 z)2=MGOq{9!ic4MT2a~X~U^~qh0e3VI0NHR90sPRsxz=dINo5@XbubD3pbcJ`E`(~o z*E$aTT9r>-5eqE`c#9Op>%E+-)|m}9pKQO2U<mgx*XN5Wgv!-tpbcql!$MsV<;4t6 z@mpKF)N^3T=S<Rx-NATG%zhxI<5|bel`e4V2du!$nmXDQ!8uT|r1>D8D{IV?`>$kE z+N=A_g__kV|D&7#P}x?zY9%3+xoef;TnD(Yv;Qo%&W$yoRJ{D`2Qd2$M;g_mLU;8` zx34`8>iXWl5o!y|uDl?X*i34(O*Ndv)6-}Mq>M{7i_gJaOYrOmA$`pMP}fR~&44S; zbD*<%4B<zN-Br_4`b-b@pbd1;!u%?rbu8hVV!rZVzY5HXnF@tbQmw5zr}O}}2u|AZ zty|o%w*L?hx&+{qLU*tUxYBsjDJe}=xZ&8D59)dkbFkid{L)Cy7QPDO4Yf%pp5iO6 zzd6m(UcM<how6XE50LG25<TOUN8s3{YC-Ka3od2ZVAWk&Gj7_V^56y9(9}@QCVhUt z&ybro|D0<QLa2kTaGQjzbUWsA&FA(@#oI{_`QYYl@}>@rtpgF8Qd?wL6Kk|g!uCMq z+yIa?1JDDR29MobI_)N9&ChiJOb$$*3BDP+gx}q`Ndp?ni-4GAo-#OkvPCNoCp+S2 z9wmi62lwsNh^-y4uGQsHY{jPLh#(Is+uo}_<8W#ShG5W*KGPg-ymep?tJvOtogK^G zevj_${{Zf!{F)q{E@WM(<g5+;J;u=lxI>J$hrRAW!%3u`vXj8F+_2FBttz6c!E?Y0 z#+>1+T_@<S!60qf*!9v-^U_-z@1s24X5QAxlAHe!3~7*u@2jbMlEdFn2eZ(!QairU z|1LBHpAV^q?TAb2HuLNMK*e-Qn;UH>kUkFV3h~>3%^Dx&H2>}$5ALlz>^0L)8hr4) zEX*2R?{h+TQk>qiz{|2t;x@xc&DDf03eu0gqrlt9BhQ5Qz?kX^<pAC8Xp**v{P20G z(O+pa#m4ieUBRXN!{#m70=k`W`pm_fsen@G>b<HXzDhL1N!BiE|4<G7u(G_IwaD&- zBG1~O#+`sZ<Ez`jeB#9&uEH3d@)XNTrXowfMe3{T@i?tZIx6>}qQT0o?aqs~9<9K5 z_}?Lw>z*P@y0zxq@VnSd?KHEn!*B+d{>pzc*<7o@>bjdvJhn<7Dl&zm!n~bQ|K{{f zE#uwZ@pI4$&5!kf(p(>_l5BwPzAy7zjw!1YT-c7X8g4Vl`VT&BTv<%}bP~V-!D~*v zdi3VWyLT_ZJca=rK7<%i;zWuSEndW!QR7CA9X(!T$S|Qle*w1rGi2x=J$eZty8IYZ z=1iJ3ZQhJ%&mKc=_v*0v$Bkq|oJEZuHJWf-zHRjc`uj&P<kWdctzN~N6(rS!3`uhP zhX_$VZaQ^pMVnUbT8ISy4LcLG-q5OS?cVK}FW<Ov^|tvF=(pZMs&&ue-N;a{#Hn59 z@#Tvcabbq?{INu-lBGO(hb4ao9hx(}lXF`6+eVLMXx5(-CbXQbo}Wqb|Nc^DsFP^x zhzS=5SPh(H$%XTRJKW71DQ>d=!Xom=jq_`T%B^2VO7CB>GxM|&JdRzwRnDC4&8@TQ zU$&ja8&}8v?VE9m&vM!e@Xw#T@ka|Q9VY;Lv@t`a)Hv%eK?OM?$g(tw@hcyHl3TFC zk2oW#pmF~BiK%<!3CX>>SW_suZ?dV#lmKjjs2BnDvur{OJHl<Gcml}gL3y-6FaVfl z1hT);PFjQy+vw>rNF^_#&LNUm$|pU!0st|@5fRhvv2m)~2BJ(h;e?Y-BHCmVQNnZx zm51udFUch-!tKd_o}r@{d8kpXydU4>6Ew~Uy622%`~mbH3j0LV|DiwYx#u4~Ci!QZ z4{?)BB>1R#D3gau;gnN|JdNm+PgZPZp??BAR7u?UYmOTov+>8C^7u=%R=h|$X%atn zoXS>T9~uok^-ij)p;XuE@tXi@2|!a+P~lV*X+;U8T5GSZHcd4{`6LyG^1;v7!Z<sL zPCN1J(am4iMJmI3wE4%2XYQHHAL@=}cfsEZg6gM8KXj~Dwe)hc7ELnY#Gz~hz_#H~ z6b?mNP8Sw6fNAmpslvkaitZn2*sv3xSosQW&wNj|iL`$lG33bbP_7j-DXaPCp5bm@ zOD8s`2>@DA0stjwP!`rm+MpdW8k7LUbO>JH<OvYCD;2z%|0K(D6=N8A;Gst%=U@h# zri2QTN6>h{v-cj)!VYq5BspZo9%}Zwmn!6@&WO6#l>OGBwU?GQtDggS#-5Ut#q=Tg zd|W&&qH26?F?m#8#1L)bK{7_p_%fMo&oScbBv$J14mMgH>il!@sC!a7DNhR6?zC(% zg_FRuigpuM0=O{%CLU6+zxTY7r=EXwjfa~CV<buM##M*jN#g$Ux3hnuPn2x9?K!FH zmuFHtTtOn@*_2YIofa$fAO0gq@AcBopOhx2=QoGG#y)?>=5Y(INbBVczVtVq(YQ`M z?7@w|JOYzuRDmL&h?ppjrj}9!U<?)c+hh{x6|mHU{|tawluoR6x&cCuIs_};U+4f7 zmheS^B}@=ZwD+h;?L{w^qSQkK=r@YQAWiAZ$^?T3s)_6+Y7$AEQIg{r)}dxVbl^p# zGN+SSB@u?68%+Rsk%oVKrykQW6yC1bpC|pr534ZAKQ<T>^F$;O52=AeY&W>uVZ~D_ za>yMdq7%Mka4j1Q%6ixkMd=VnQ6wB=^k4#(IRIrGR1{GnE3~M1*yATAF<h}^x5J5u z!;liOL@hM+5Ta!T6-sl66nGGbhvcJ2Becr~OOlO$u%ZceYRar6ImZ5_0X3Ox-t%@T z9t>T^fHmA8Cn3TRz6GES4$;9BymY%#TE%E;{|W#P95ROAIV2v#nU%V-GOqGq#u0TW z2t5o3%VCz#FaB6zRO;2vB}rv_lCq3&a3+&VSR@n^TuUgh=@1#*=QG}WTF3qo2SC&# z9^&{1BI%jGCuwmG<In~b5%QXeDu|EcklC=*m`si|lb{i)R?+}^m7tBvA!x|MLt0S} zBZjj)SlQr6E~B40Py%!645t-4nlHz|s}7Wis0b${#-U<oQH}bEU#PUkjF60PYX|@s zqyUjx1nrbS6dXisfeIGYqJjbnfL`Ro8NCQKCdoVqh-i6?L1L0|x@_v_5<<m)2#Rdw zv0q-T<Gj{ca#(|zN9+n?kv{%|XUw8V|4PAnl`%Qw5K9ZdB`|>rhZN%*dI7Cj>=7B9 zz_l{+fG8`>5XJ7L?Ph)y?7D{Zk0Q+@mp6^=g4`94dukG{`{N77kTyp&S%Q>FJ4(=| zr3r{|;u5p4#42Vn-RWY(9oNkUJeCqnw<ac;?m~%?3L-0=m=27&g<0$3aRwf-X@syv zZ)<eQ5_|Ze6Y~6RL=JTcR7h4@m>4K#k&6@Miei)j$ipn8D+^idg24~oMLW6yj%!>4 zyW7ZzbL`Pwi@^0PVBwG-KEw@uRxQ3T%gunE!;P}6^TZX}?Ly-)7l`KfZk;RT&mfDm zpP}z21$Koal(2_aJXjV*Hu5WW|KW>vghL(P@P;+6(GF?61H|?Kt%PVq8T0&OFDK!} zYK`f=9&z}^OR`5q`}&N(mRXo*22B$Sau0!=Cr`%eRfz7&A7$C%VG>!GanXPZYVmj` zJ`R8@TG0t5$YB?~U@)W`ENKQm+8gQ!M>yEA>2-hu9M=72KICIkjjSq0Zo!3)w((6e zOBBwD@{Mr+5e#28MS4woHHq%g*6=xm8vhW;hU$Uk*G$EQi7j?rQeiEK2(7;^MOpwL zIFkuV%N3T8g(tYsh9k>@(v<f0gQe_^OqW~Jown|kArjdAy@z8YIh%~H#-@jiklnei z6<<_lnw3zgO1Q>%XkcQx{|E_W7^neQ7>9@KW;0tNsBq~(Z85l>1-NL`3WX`6TVyVb zLDCL3GK3ji<Xv3D8|&CKl-GgsO?Sh(+0e_DI64u?k?b=5pc5<dK^pwPB$(gIhnWMO zAOrzBF5eN3(1$J=l2F4bWWa?sQUk6mS6#RdamD#8610Q`z_?pL1)2t|5o@7B!9@<k z7#{rXwMTjvB=^P2&7J8@r~K2{VAD5_7!j*m9aqMi1sPazk8GS4zDq|`AML?NUJ&Xa z-$VR$8bz7_aHEkcNpqIoGq!M9oFYb(2n7FpacP;N72O^~8A5Jkkgq<{a-Tb=*O6&; zr~@1C&`Wu%V_M*F|3jUCAj3Crd)~;eE5-Zqf*0{xeDQqLEp^xfxY$G)$D}z;qo2qS zE4YbTSRx5MLt4<PIgx6C0u{J$1cTeag>Fk4(vU7Pq~G3PlFI@dbH{(m)8UP7NCO_H z(max~t?g(6R)~iKAr5h3zCQ7a%Qy){Fa&#G342*Us__SXtED=~Fk%S_UegKT>Mw_* zh-fh|RLF&hSSgFJHcN1@URb|QP%_v1xcD<NNE<hn!@rf&L3S`Xm~);GX(FdXi8^=& zc$k}|2)dc8Kv?^bpLzx}XfM_Hq$MP#6auz1Xgq4ziDOf|X&45;`59E&Ix(DxIx0g^ z;1nctK_%z}|8SeX)^okq+XZY;2OPw|xtl%f(guHshXmRyuwVv;;t^X*8!G&j+{lkw z+7)rI41hC4U4sZ*0X8!51*Tw=Fxo4}vW4?OA4IbVGdaOD*$71&IXU2hQ$VsvbG_B0 zG$k{+y1T>J>jrcHhbr3(dnt@@P@dxv16H7)(NelctPq7@h5)DpFPMW~m>Y&G4q;Rd z6!Hr%s{=oP3b3e*7kLKS`6r>_MvPz@hu8w+nzjI-rU<f~Tu8rOC<GyB1aMouN2|1t zYr7?@!&tOOOzQ?M<Taa9jd9=uKqwri6OeELI%lkvB?tf?ih+Wfs=81ngS3mK=$=WK z1N+#9|AU|s>vIM4;l^&vK2RtH&ubQ-fr#5N1yhK>b!<o0Q$;v*$8cM_+JilN#KU#C zy}eK>-kP;DK!mvfi%6V8h+LA>aRMTUf;A8V)af1J5K5<_hj?IxGYAH<;G1x9h5k}0 zp^2<ND+Lu96Ez7(h53}TvV~T7v~^4bwhK3qlSh$jFp+~YnvBKS>jrQ5wWSCEc%cVG z5S0J9x2AlP^S}`(pn*RCf<)-20N8_n=tIC%4(i~KcglyJA_#8S3x{w8$?C|C9Kljh zt`&KL?^6>{;S^Cp$6gQwArJ(2d`VSoyBd5jZ%Bu5m_517KX$lDZO{&0I0Kc4l>MNH z|6p{?>i_~XNQ6ds2z&U3T@x<h98RPVt&@m{IiQ1QunmZSAVS;B?Igp6`NoGpg<9~u zSLlUA5Q0LO!PbPyRiw1H>xOigN!!%4ma8ynpa*S812%Yuc%X*h_{-;15N*iDhZqwb zc!3(2gC&TmNMx(415nA>EBuHzR!9S65H1LEHqmpKYk`P`2^@-Z2shw^JKzI1_=7*F zghn_|^^`x>oV1n<w<5C!Z0LsCw9QQ`w<v3ecQ^$x;Dv7z3h8-JCBY+d%(wuMf)oG( zG>9XI5QP2MkBu5qf%}l+xl1tsgn2-bt}DNx*-&he2;~CF06+s8cmarrfix8Y{~{o= zw}j1*Ys*z^No-gLa+6QGV+U(s2Y1+oGl+v`I1<ZHD!(DfDP0h2IV&HE2w6C!jdD&y zJqldWj!EdnT5yFi@lbN?#7za!iO{0}fPyOs0BM>6Z6X3URkF5}zt{XY_oF`so6(cI z)0ImHc4!A{*aI_2hG(#bcDT$vdsIlZ3xOIH$!Y}_AOeQeFVs;&VYQ33*#>)f1~Fg* zPUyZmQX1~mRvzoRh;RckC4v|b0#A@Z2unpcT+dhSwmD=68<op$=!SMshdMZeMtBBv zum*I<$9hn_!*f>N=u(IHgj!$&K=_02>zN%Jj$r-Qq9BQ=5Vbhi0Y0b&|1n9LFU8mh z`k5_=h(ACBAy5K`=!B7*zivy#bVb>dtu$<KG910bx&w!HXopT{gHs3wY{1u*!_9XH z0LWn2h7G7tD9uo?0ZcdohhP>{=+rC$+Rs>wVW?O#D1uNz1v9}uPUTebi<nx#Du;*y zG7SJCkb?ja0vOzdRdCH$1-DftS(t=JSG+WP+%#)Yhjv&6Ge`qgm_=(yhxeSlYrqC^ zNW!0OTC}K^uB-(>NCQgHfm`5&OsJ!10GGo34AR0FOW*`spadMK)><eNqB$CE_0nnq zlPyrxhgbqR7+V_fg!WX$b6w9=1h<o&!`gFMb7O~Ys9R(JgGOQp|8?M7cy-xMlZI^| zEy^8_Au@$pzyV4~gNNXRhXK((WGduE3wo2IP|5_U1%z7g+)Uumhu}{CLWMO@RyUA? zJ=lY15`s#2-H?Mv_DnLigjJSx*Ot@WcDM#PFoR&|hg&VTx?>00vq^Wj#f5z{>y-@i zxr7|B1Rdy^ZrvXRRtv{~h)W0)PAG+9poAeXg6{QP(OaoaEih3)1=HPvJ8%Ox$OAM` zU9vp|7iGnkq+KMFLwBgdy6f9`Z3kZ{1TjE_e%L=uqe*z(S6m}p3XX}D8dxmlgQX#~ zi0D)$Mhwp4I_|554lV)^-UOFQK_0`n3Nl}gb%Q(DgY<0!{~8!q7$sSiRo6F8S1Hrk z+~wg@=mR4NVs{7!aJXH$#m&1+Vk(viX*pa|7!@42gd=Dl+rd6TcG>{IggFWTFbR|H z^I$G^scI4$Y2m&AxPXWF0U{uRqznMnlfRQ?yOK>?wr$CFXxI0Y*Sp2Sc-`Y#?c=!& z2W-GQS#dQ-4kA#v9mMs60HB1U#VlXu4fBDRh^gA}?BEafUQ~cwjO$V}ga{f)NNf%O zC1`{hW=Yv~)0gZ8kdv}rz12B5gE`=ZbkNsskiA=$+gjvTS-T!&MvFSS1m?YjH2BtL zBSU*ei_Y;($udW4)nY&hr4V))Yc|G8NQ6WXgi~lk|2M5PHSD&utzn9mg;nTPcQ}PJ zI0Han1$NF?caF~+ZC9HF<OBw2JE8=y1A+iJtBh&sqfopafw*gVmQc`OET)7aC;~EY zglNtLO`#TuW0+@Alkl_z@_f72J7pSPOV^C*^&Dph3j{IfMP2~je3iXBH8&kx2MZfE zUJK-!zKFyPfJ5j3W{KX4K!tin>#HCRi#r-=36o6-Pfmyfpyq>2h~`hwggSbbFbOg_ zbzL@gOIGxST_^-T@PY#2g=VmZ%C5bWb62n~H=XT<lQ`bFMvBArOim~QN=Sl59zTfa zWzepP4C~N83*U$lljTj^A;^I(wuD>oUQzf2|4iT%tjvX3cujP5Lsm_)UciN2*o8(w zgB%cpEieRk=m&g72Xv@CA`ajI*6jJrLkyES)=n;^;l4#6W(XEA@UGy+315l$&@f5p z#4Um$7y>tNg!hKzOZWs_KwDK-%lBnP@@#B7u7eyff;w0PR<MR$_}%KRz3rAuP74PM z`&EBM?~X8q-6?`YNCPye*eQkxk*si|NbQHqYb-_u;2VM+7y>k?Z|^OJ;C5p<jkI0> zaAeqpQ?O$;FoGQ*13BmfT;K)eJ_Tf$J$QETBJS)jlF|?#<iXMFOE7{<Xs(NZHYSgW z<HZj@!#IYPVordTFewFBum$hs1U`s^{}dmBCwPKEsDxASg*S)uIG6J`$MI7rgfb|D z9nkY3*n>&{@^OAkB}0ZM%iSXf>)f@^j2x}KvvQAcg<6OMHsAvsnB+ohbhN;aXNcqx zXK(bOWHG_wiuD6N;DaGR0X<iPGT?$M-~ukdf>wX^R_B5)h=LtZ0X;8-H)w=hzy(}r zY>g&4I>c^6m(SX}$ww;GOXrC5(UdI?fIp~Ma#VJ-$cJjEAWp9crSWnN&frZb1@Ene zVQ2+kNQ6SbgF+AlbXWIuXZLi+g<$CQUXXWBK-WqWH*AnqVxQFrcL%+5o@wU@RCwt{ zINGoS_^XJ}X;7A#{)i7nL%h!5|5=DXU+4vjuXuT<_>8~!Y?H${OvP8|hHI!teV5NV z<v;e|9F{(Kh|oBKed2FLla*f!F8>Hl@pAo^@l~w%^(@&IZ3jCgd9aQ$`^3o&YgU;T z->j>kMd$(O%?Qpy`ckV4`1k}b{V`N}1tcr7t-oj`i*b~t@z`CmcCf>sr^!t-_PeC; zl@|r>1B3wJgC_`pB8__JR8CFrI-2(g6YhomR#{bcO|OSvZ{7tQuEWeW`?(xzclZah zsC$$W+EUOIHi&~~uXG6lW)F7=sDFIM+B;Hnh%df4$>MsqYd?*K<M?ICZo9#gPJDZu zGI3Dy&KF-)GI&5ZTCD?`|9_@^nZS^Gw)C4YVc~w!d8BIAdr8$F=U$L9*>nBZpF0V2 zIt4`fLaqfrc-{bT+(ym_ap?WvRQV=X7_&oL*d*>Zh11n9xt}+3=#RaWwoj-z>y|c! zF)4yccL?wm{qO$>$ODJ~0tXT-XwYCNQMgvgYS^nG#E82bMua%g;wy{pyoFo0E*!{^ zB1e)eX;LIRb{?_4%lGY`y?gf#(yVFoCeEBXck=A%^CwW7r7jua<E2#4q)L}EZR+$X z)TlN^Q5BVI)vJpUA8O6m@ZzqA5XH*s71o<Kl^##BZOhi9$7}BX<*O_8F5bL)@qz;N zDF7gWhfoC&1!^zi|HO(HGcFh^Kq;h4Ib9t~(Q?JInZbVb)ede-kZZ$rE1i;^Taj=- zjy$dQ8n$}%WHzpC`*zd6Mc4>5B`Q=xQMiW_FTU8GJ%Ut|R;4_vp;uX2E$@oH6|;1A z=vaGf=N(%+ciz*j3!PdtT$3q1qTW_-+&JU%=iiQu>QVsSh3WI}??0(4%LUb(E6-J@ znO9`Vl95;pUU$(e>v*G%Iv#n`&Mv1IV~mCxTGI|%qn)RoS{_j-&3p0vw<3S>KvfGM zICv32Et@<RKwm8CxFc~g$%I@0!+atfj)(O`6(^#&V##zEQKS`D3rd%jMcANKAzId` z;tZEvaw&;1{~&t9+K3~qwwgNVNJ9^NwDI^Re|_bMlPduf;l&x8><1j2efo)*O!Lem zP%WlFCZ~}&0auk(mPjY1W|v_%=|k3FqfT1vz(!6aUV0hHK4O+x(wT5khz&LWsQ4$V zjHOVJfHmDHkPnCi;0h<G^c8EXz52S7pzr~iTmYItR?4nKPQ@rEuC#L9S6*p#k%CVm z(~df*vD1w;?(739Kjefvt~2_aqmDHkkvS@QXNJR4KI8b~kDI^R3se_PWfDLfMhJvd zWcLa@@IitK)aE$TOcTIgO1a{SMbUl*t!1x>)yszyf`k@2?R>irIU$S850~eH6C%6q zmb#8y|NqESFTpYA6i7j6l%mO;IAwy05k<IRi_Ad_EzrF7{9{ngH8Dz+vzJ9zEyWgj zmTfv9o#rv9A?q@7x#y<aQOYH)=M8NC&^y!6X&1Cd0C^BW#6Y|r1e__Rph5`{I0OK+ zvTFM+Fe<?DIgsG9!YWEBs6^)=#Ze--U^kbRr&c%Vu!A+oA%`n2m)2N=DcE73v@JX- z{{43%OnGo?ou|A0Yd#D&tP@qhp`v(3VNL9KlUn(5O*`nA$6iX9lcR_lYA_OVx#nPt zvgjtQ0}hJuA_wH_L(8C4jRAy$X!havxi3M38^mY;s4P@bwHHs>Svr=Z7Sd?oV6%@i z|B~pUh9bywuFvPbwyx+|jUDQsUOm1s4(y39X4~7_PhKDpN1%c#Noybm=|il6{N;9Y zx}9=<Be+}`$U2vq&O<PEDRqz}B^UaPE+WCdkf}lux&TJk(3L3yl1d$GlE(r!n8AA; z0xB0AA`<x%nc4}ie8J%aWgOwY_caM3*0=^oTvNbqT&^9bu!ACE;Ea9jLm84dqa?~j zp%4v_fGIiEHq6GrB=!m^AnXYm0>FbY2&NR9pd%oQ)25>hBvIxo46|(UoJU29EM_Uo z@4Ruc`H6&!-udDc22l=Abtw{&D2F;gG&vrUWF^$F$2fe1wm`D7m9D&tpz0zM|6vhQ zAecx9BAF;4RG1<&(0WBAIZ~3+T(S>kD1@cjVGVJOiySpH2fEzh4r_E{l%!nGyXc|7 zIleM&cW}c&$k)wr?j?4siktTy6N)8@FftCZ7$eJKsWEw@8z|XU7f;a#E+Eq#YxIUR zz2hBs^q~;#@P#|*Aq{JwgNvl3A3Ip`jc){?mgE%L4+3z5i*mFvf-)LG2=lK})a{QX zT_i+ak(Fy)5iP2LizU6d&wf(qBkQ2h8Y$$CU8untyLg8XD)ElbrROB8aZ6m>;gYkh zvZDe+!y4cw5FI$Rs)?z`P4pB1682)HumRC$MuQf#*wZ_^nCXYsfevtl|HC|3S_ig5 zS<qe3V*&v1#Za?FNwJ-VEpJqZTwDSZtETM;GWbI+#7Wr2F2!I0*q~h~Dv)o`0~^3g z2Z;3Q8W(nhBW6V_Hq?5a3+<u|r+7yU03d)_OtYGP?d#~&f(@kxk+Es3;1O-B+k?PN zAjnZAL6YMSaVQiVtTE3$xAj?mwv>gbS<gDK(T6_JBekmS#ZcM0*W_-ORO{$QJB-$* zrtY@9=JgxQt|vr-*d+k<fJa-2M-p&=W4U`smn7MRnw<(k8rD_qE2c?SdlK+M^+4r0 z&+DfLZm$UnelSf`>7%m|L?-Punq@s=n#+acvt`)BF1(}Hwr;k>|0SMYJGih5833Tg zs`UjuK3BlYT@9|2GqGz7j9_j;_)nZLT#ti%6ItG49RGNSc-jFT%YnqKkKlqF(gmWE zMK6?s*aZz-?BYhW*12J`P&*DRtn~`{KUz(nNXx9|oW#RyyC}pX9#IHmOvuSl4skp1 z$wRpQ^uGew0~G@CjfIX_bUKF5n&D)aL^IkZ^9n=^A}#4c?DWZfz;p0m8@BaesICAI zga8Ea4`%qH7szO78(Rol*ML{d32rp3W6dI&eB&R;paBiqFor99fd*=jLm4ieWS52n z$Hq1>pWPvZMEoPmZMepqcOhdE<9NpNgD!aOk)qzpy4&71{|-0uv5FX2p%H~Rg&c$s z17Uk-tPiChhOm(jK?LFz0GI$ar0qE`r%c1?a5cBTE%1Rah8zEQMGUHt2tkxV2sDTR zo-rlNcXN6d?mz|?gzyf#79y|w9u;)GBO62$yyPZNjKRm9g+??&4suWf4MP0!cNg2I zyD&z~0|9_N#Ml~pUI%6?dh($Y{Vuhhg$$Gsh(Hu#54aBT#Az-PZ+Px=z-GoWq=7M? z6L2MSA#c&cE_R=|h#FalfedgR={`tK>L#%UIMl(@M)ZOf(gt1hlB%k)^S$pn@kg73 zAqOrfK?z*A@0HvxJ#}E?5o*x)*SgNKxug>8e!u+X|No)+Y*6DF)SyQ_wbfm>uf!T$ zIE4<Q{^jVtWAB)MJ?sMz4{rD)A4c<sJAkKYQWBdaA1Xv2yyMWWziS)uiaqi%ACH%O zBOjHOui{@CN?$xav(bBFHWg^$*d@RFMMus!DEkg-TRZwX1%BJR?u{SHgU8-~|G@L1 zss+}g9R$9oh~7;hWvby6!XG`gUEA(`MD^4b{2d^{xyd*<A2x&zdYGR&fEW7Z831xu za&?1yz(;!_AP08aZxxyNO~~#=Uq>8N85o0=l*qc|pQ@!pH^2j%7+?p^;J3-2JA_uM zDc<=7Ulvs$U!_F0nGOvOp|`<@LZO3Z`QXnf|I_K&A9TGG3zArQu!KGM0})<ftj*Fm z$VNM)L#8Mp@3jN)d4m@gnp^x8s;El9VIdnrm^=WH^I?%0Djug@gK5PTa>dqqP!Bz< z(i*lQAQF~Lyx|*KAw5vTc90-R0Mr<M#(7}d3&vm|PGXO}A#&8iKiuFyy%f!Lhc(<G zTaAc@wFAA3*&k9ODms-G(!(@K$o(naC<31~R80;-p{Be;J<JP*r6MmbmMXyq7gp2c zL?I7_hLV*5Eo?+B7MpBQLp|if8}_0!GL}r}qCe2XJA5HAlG07N!zq-3x}2d(fWte) zAaG41I+BwrMPmTi;5Dd(BHk3$9g{nR|Ke)}p$2l_DW)SoX3!wY!@L;b_*oO_eU}%N zL0aV?biqsI^`k?+k}Ay$Ap#`s0najC-+I_#GUA=|ghM%w*FHX^NM?`b5rpOeV>S*W zcU<IijiWcJ!C0kQc|?xp$wNh1)JWze9ciJ3Wg-p^&y9g0iGak(9FupL#HqA|iiD(2 zHf8u|p|-WdH3X$ljtF>t<A-$QN6Mg6c4ZP_k3fpx2)dDy6_owGqTbDhgn1=f(h(v0 z1Cmu!9`2bsc%vNvk9TOx^x$GX_yaq(C1CpFJxF9-<iia{A6)f8l<mSUbd3GHLresw zWV$6q&dYn*Uq{R(U%dt6?Si`D|C$;IL5Pi9Lr$h?iccY0A<?j68Lo>KQJefAr80dc z4LDp3a6wB*7E_)kZ^n!&AxHCJqy1@Di3Ol$cGxMzfEu*HuN8vBAp`dXz;5;?bqdTx z0;ls)LpyZDN9@%TjzsTyk*^g37nqh3#DFi@-gH(cd)~{u_!cVtgK%OCak4|`&5u}R z%7r8+7YKqJv_T`BCv<W{dlqO0`Gb67<2#5LTa^YEZI+49mp9%f%QZqGD1i(hg8~^S zhrSLwYG8uC!-9GTI+Q4Vm1rorgNQ1W!*RhEd;t{501+_5Ke$MT-ssS5UvSxjJhYj7 z)&n+DgNP0(J<x+}xWqqn|AM;7K%@zQEC3#kM(N+Y;g}r^h!&>i9pCZ|W<CUiEOde_ ztOAXyrj(Yc%uM7Py2)><S4`Xkkp%#PYMz{$DV+)pd|09oLFM&~mqEmXpW0}h25PIc zS78=rHR_^3Y@dWlm=z8tnF=bTT4!ZGszCf@q+Y7pwAXt|r;k+X%UB+!hN`HJDyf#L zsh%pTrmCv0Dyz1ttG+6%#;UB&Dy`P4t==lG=BlplDzEmcul_2q2CJ|RE3p=<u^ub3 zCabb8E3-DMvpy@d8ib{K>ZabRpg2~v8bn=GE3a~Ewid*^+yg}k(LA8dw6dzfBu6xI z!=QZYKn!M^8N@$S|KY2(D)<QmJp=$>p6jw|p+9iLH{?P9l*2%nLoq~ypBCzR1|m0b z1E}tWpsb=h!~q!y1hdJ8w=(Ns5@-O>LNW}*JDdYCoC7yZLp;m_zdFSS`khS7tDMS1 zxNRU}0Es-*gYlWcByfW^JOd)sfqMxAwmxe=&;nf$gf_f`InV+;5NJN!L(ncoYO0r~ zrmVmjO&n2!AT)yJIqbVWtjhAJKg1Ct<Sb>)1uM|OKe$H#*yOWv-#7g0K#YStXhS^o zLjb_TKTK4{0)@;1=Qr3W+Y;S9*z7+9!w^gYAc(;#j6)nT#^A=0AsB)@Yy&+QjW+y4 z8t{TYU{$mZ|Ls7m>_E%|HYlyakXcY1>O2sroT^GZ=;Fc(*}TLNFU$cv0OT{&0VT}C zHc%~8ykWi;!x^~D=i21#a$mb9tHI=h-Oj55Iab8_gEoxA&<<|+J#A0?NEL?Lk@Z49 zlv+hi14x~mJ%~f$&Vf9nt$X}~A1v;H@$OQ%i8lDd85Dzykeoo|10om#kkZ563M+6D zQa;2(bQVNDOhYxugD~{MJpgQFCPlm$95o~YIg~@lQ1B|qAAx#pqsc>&27nhl!!^2B zJ%pPV6oWnFD`Ln-0N}zLgzYnOpXPl-J*2@iV3h_3t3TWv+pgg^nCv|W!#VuJG&t|^ z?gXvL|6eDN1IfmN!uSI`m;*2@Lq5>n>#9w}b}C-TguzXMAB62h(!)O#LmK#{`$0vK z=0h3`!{%}>d|s{}Ou{_mE2RSKM-dA=!~#4707Y3ZK`hK2)80e{E>A>kMP)-QoC7?p zF+9M7Hq=@@2tz*<a22Ob9VhAyFU1)=!yeCrWp0B%%)u<wtT^O_pkN{^)PX%{g9?W( z%KpRb!fgKr>)Q_UJoGSJDs3YVR!_{)JLK^Ym#dFV!#BVKEntH@C`=LwicQvWEH$mu z7I9K+sul79psp<kW8yQMLD=%|96!b71^_D@O`1OQywHR3ZPgmP?`;r*$rA7Y=OoPh z|AREFZH0lVo6w#)Btz=bOHa(hI9%>7Ji<H7EkIuDwT9o(&_X{5aid-`Q}FR{7_`A{ z?fKdRL@x#R*(5!Tvuwm~9k7D7o$OPn>0mxX8mMyD5{+uQG93iKHo$2&D@HSi?m$38 za>#68PJ=%vw2JWaO$5s{<byFhDL0J6MHhsi7~IF&q&D=WKN$2!32{CU^E<>tBR4H6 zUu&QowPI|wd-=mLAj2_iE+@AmSMS6djxy1(Yu8$4J%}+Gx9L-qvM2MwBE*AxSZXQP z!yD2t8&7gnkS{^F$XPq&73=ZnIx)~fGjH94!o<TJzk|ZeD`OV~+URsL7z6h`|22FV zH1_r|WIqBtG%;QTi@f~p^0Di+;>NZ5<v-NH89<dGY~e<K>iZ5RxLUTOzSk$?!WQzi zAVVz&(}Om6!5hlPxpuTae01!@vTfjGTLvwB<S`I8H!DY&k8rY1ze6mHgN?e$)A~rQ zC4)J9Llr)CyBc(7*YZ@$Lq7;Z-pb4UzH>jft18t+F0L-%`SfBmv+u@HD~N&F_yZuM zLHl9vOh1J<c(pYb=|3z2A51PipzLj@tHGVJJ-mcP19LsQ2rs0;KWIZ4%SX6P=0wed z>Gp)e$U`zDgThQhpdj_N+Hz+1FihLT6*qAL+XFH?g?ihb(G0^X%)%?I|3WmFtUuSQ zUYK^ReRz#h?mQR*BJ8g^_k>*s_dwJIascG~R(4WE_2n}6?qa#87O6aB@;|Kdt{U_} z==5YQ3{QOaFn<FOgElZ<agP53HpId(H!(%R3{)q1J<LNaxC6{GxC6(FQ3Gr~m;*6b z=qa4SAu}=fDS1?EpP*bW8}PzEh{L>uIV;GmGL!jFx9fY-Lp)^i8rQQy$I%-@FHZl& z_94eVG{YDNKyBYds?@<M9F1Bxg=eD;oAU%ASRs8QVC!Bw+T3wAEZ;BhCUVS+!n^}5 zyu-gXuR+(vI2hbARC|wF<9uVcpw!xX&x4KHZ&1|nk#jd9_o$yD|1BPuZi?T<sk5{T zM`Jx?bNIo;I0MDJ7+j)?cmSaLRvV2;`vX@d#c@NfA*3xg8w9pu74RmgbNfV~Pb5!3 zLpx$&Edh2G-vgD#FEPtrG|-D@&x1}o`at(MdmVcK9JWp;a6KrD$1nEW<^wYjLq9-o z!&U>``ont@=*d>OQq;wN+rt@fdXWNST`z(Q4`$6T_vbeDf5!tI@B(G!db)G+HS%vJ zyO-7zglP-JH}k><)jTU3bj2IQFF?Z^NLB~p^f!=tP}pcBOIBg)w$Yd@cfWiin>@-- z!#`v;!s|5M*My)b3_QHUBQP<X14Xb0b;s6jkMF%O5ABPu|9w+zYVlq!k6!aUWb+Bv zHemC0amPcxp6frJF(vQ;JWwt@pDxG`w>)?OH(Yb<)5I$KK{&tkTwm*-!f8%&AHp() zwx?16#JjAMS3Lal-6}L)aDzQ?Lz`uT$4<XEyzQr+VxZT>$r{5sEMMM3JTN0EHN=9o zb1XqDAUp^)$<p5813Svj?LTb#J&f|52Y|!A@jq}aKm-VI@18(|2N4n^SWn<0KJo<0 zlQ(Z3LWA_`*?VRt9zA*zErt|n(4IYc`B>HY$4wwXkrX9n<TYoUwt5Ul<~&G|qQ80E z{soQaPolztI*}$-x|C^Cr%$0qbz04z)RD=i1(;UV|EbFWApK37hOL~jcSHYuOZKQ= z*sVk%J}o&-Tf9f_<cal)lwwPTV*Ls0<<_4+uj9rUq}4C$z<YhIS}aMB;=gQZp8d1u zwQ#+E#m@NC=5udSiiiWy`$vbDKaZ#r-jgV=s=qnB5=Rzj?;q_ttp3#lIkKl~df(1u zj?8o3J%8eO2g4PtWB_{=b!XSUoqKoh%fxlJ`;O&PqxsP1>pR;VxjcJf(K7e$+q7@j zu^aWflc!ONV&&<FmineCEhpv(%4em2j5#MBZfHYnvU?B{E1q{Afk!Wey!#3wdID%= zj(WBUpfL1e5-yEl?tu<Ar3gZ-9(w%oLZW{H|Bw(rfzT7Eu#+ZHX&cCxVh+8M5Ie&r zoO(3K$b1Bv(H}oniHpdmP8-LgILPSI5PLk52)!$b>(I<I(M%H|d7udZn)1}N3cbQ= z^5-9BnmHz$leqZ?F$0^T=$mig`GyvE<oSj+rv&}x&RF2lCO4uEN-!U8{5eOMl>psN zB6_y5hc$V^j7uO;{}GYI0I+K+rT}Id?xp_j;q93;;>qVnQ<oxWxPMro!=DmcO{yM$ zW~sxTZ9d|)$ay}cXB;|!lP4ZT5V@4OIJxcCTQmQGMGvlYLk}o}xFJ(FiQ<XppA#WW z56bMu;pQGqFD>dQ81E5lp1a}^Yd<H8|Ai-(vjX^r-0nWD=NTnQWhkzOxzWapjy~c^ zDdvFkW0H8Zsg5{kN!?~OUh=_6R#!{@XO31}6VBO?3XACBZ$Ol)xNQExHXm)MG5HK$ z{wej_qmfP;DjXvtXwZ4!5vV?q&y2@Rg2c*4uz$q*XWj$nL60D9@-Ziw=i(t*KUU`{ zEbDVlv0C9`w_C^`UefSqPkFq8NuF)|LF8j?)J=*WZT|7%8JrxOwJ?wJq2v#FsA-nb zc@RU@jAuxtabb&mg{Yp<(jdB?L7}3E#D9WGBOhjGtk{fkZpx^n!j;Zl_cYP78WKYO zsphNHo9lO)c;E(^;N6?@N-S<L|8#3YK>Nnr(PL<d`mwOTCb+P|xQR!YbF`X%`|K!U z$zy-4ZrmXBzR3q~f4CXPuzi*COvHOi)HkPv=pnxmZKEF0TANa21gkXIV@WU4i9}2` z2|xT}N&G=d=scngIurwA6X8ZauvIkLbc%T;G@(>1Wf7}UO-_r^#tEb1G(!Djd|?>~ zQc#qatsE?1jS&fDNH&yr1Ryw=!=G-9VzN0@%Y0rDhdBPRB7fY3gaUyKkyat3W|5FN z_PCTi&QOehh@&tp{NFu}WD*b};vXeSidQ}rfRxyScJ-)YNC;9Apdey`AKVOu^6@aD zRHt|_G~^+BwXcQs#(~cg|45(S5sSKfgKdahiiG|V$$Z4)Pv?uxZtO7)90|i7@Tf|Y zL{gIKWQG>kkQzjAce#@M<6-%L&Xr2?sS+7t5%FNwz>)$u))dV{IT_PDZgP?kZljY* zIc7<CR=VDJ<&FoL(La)-8GBrgAw)StYI62Cdf0;xi<k$qYGz4wuG4}(3P3ah@C%|K z29-^bP^LB&vLmu{Rsh<XePU^lLDj=x)Tl^64>A`~_Cgr>u+Kz1^`Xz0p^YA*rgLKU z4_?s0m!4Bf&FWE%yg_N3Isqbj#38_Z$m1r@TF9|(6*8PulWnlMhan8nMmze1ZX@Z8 z$#AMuiS&g=8~s}W|24)>rK%Gm$k2nLK4+eLd~h-UpeZ|<Q=fWZNQY)bNJ;ARk5eQ= zE7S0*NKgYMe;n+E?aYop%E^^<TBN1^2;&sz`an_vYYsn4=FBYOH;*I^LZ!N@iHrj* zI<(PpOQ8s;{NV^gbk0N@Yny9?HVl8<j(fbZ7aLlGRD>d=o=Y_?cS<9?0H{_fbNR-F zvZoCno;Eg(GGz^qm!sTRk$YInhk*W}AwRkAhYFDqK7$LJV@3v5)GC^^a<evx?2(P> z>S<u-@kGS=ffDxM24~L*8BmcE7c6DmQgkUQ+!&TaBQXj_;<1s=0k*iG(&!vSL&fdg zWV@4CR?SLE|62hcZCe4zhc5=vrtB0bdC#y;Nk?nRZ4oLK)bI!D90M7rjRPM4sOo4= z(!Dbt#9(-#Bt&&nGg_X3fh`?LE;Y&qFm;lqh)WLRMw=y26~quEYV1c7J4}z{6)6pi zhdh!4qLqQIBxGCSKPqyR9D0TqCPLgFk#Y=i6r{8R_HtyZp@&;gQags~M_kT2;JH-e z9}IQqR`|9(<^YDF#v^i4=3=bfg;QH$qb~XcOOTKROYj7@LU1hvcL)@RQmj~Mixj80 z1P?8xxEH6mmQvhG(F#!7;#R|@rR4DK*|X=&Id|^Now<L+T5HzxzR&Y>=%0DWCeETA z>pwt9Xfx+8K$osnSfy))&q>y^GNqD8LqoAXNVh6?GyhVB)No0cN6Ymdou96QntMgV zuM^!dPg~^v-jH6>nPP}wqgzF*-@McA9}ut3?m*NEVarJ&|G9CnYuj=kSD|F}7_ccr z<+lDPDQOaRx3<yLmfSY6%h+fu2`{F}Gu6_qtIW2V0Jv-pZZmaeNoq3Owz9zW9S)kw z&NHTH%|J`XwIffGYKr6cri!Vs>=r=YoVz(G6jP&)2?gFzRdwh}|M4xtz1zVM#e{?J z2^f3Ds-r454qI_8i7j}#DznztVcNd)R<2!9$-72_e@6c(q~2d&;I?ACEp;1+h;+dG zY;<}BinueSC980>a<-DgHs9=9&>EIE-DooQWbUy4CH}=)aTC9_Ha&^aXRdv-^G|sL zQV~J7h3L?>fIn!DAwWn$zEASU5Y_&j2M>ujB0)<8?59#C2lDBQ8(nJnoXI>s_#rtN zZ%Xlk2SJ*olQ2kQ8963~Y#D$umORuEa1xZE8MH}T4JnS3Ot|aKTTB+5KUjEWnNb(S zW*Z@=7K?CdoVMqG6Qu6qD-XXO%HiO>Pxl$JSUx~Q71Anj&oPNRi*8%f<n=dr)qFN4 zXof`WRe+uXWrX;HZ890LOGCJ1O2OnU9eox<bwC!wg@NDiV<XUF^&K&~%5>JI=Wmx~ z*2EJul@R+ap1vzEM=KsRZQm*duNZ_k-&I|;sdD<M7ew=LHE`tReQzi$EZQT!UTVoz zSZbK_>H(W8x7g+Cx{^0rE_4+y>`0_=Lg2xfb2MI}1DqTb22}1`B<b1~RJ>*b-4CWv zux;5fa&qx1j>B}skEkSueJ%r6I3IPv6C6(|uQ|t>^dGOK!!e#xygQAP+-1f1;i_z_ z%eWc|R4BQFZJ)-Z7FB^3E!=-gXjpFra-^s-X$*#org#PPBM+UVR!V=Yk+hfck=GBv zY-UPX_RU1L#-{G^z_w+2Db73Z_iQ;ZrFjM&zH_PC%y;@Jh{yGc)bhAsq(~xD7;t5H z{LFqGWY&8@M^&+T4Ng-0*rG|S7pOJ@(pyngzbfH$LUU4W-r#b+%S5X805&%Alhd0@ z2+Jc+f_3s$o0*E7y!37)dZt+q5mZde_qR&SP_rnc8taB??vqkUca6_FF7R8`$h!4I zS`zJWRVK>=np$AthG4u4w@H8ra*yje8~9!`TI3RS?}s`QEd^$Ug#5-DgnW(d7)P!v zI)_!0j-6x{69-J1pqLE()2@#QCnyuQ`K%u9i0*8YI9yGr|I6lj6tp$o4N1p%Hcnw% zDAId7F%aJ<;Xfv*m5lH;IAnMgIfjui`>~#sak>@tByAY!)Xz4FW=a80P;9aksaf=* zpHv7qc8k+NN3|y3Zu^!x{%}MJP_cKwxC|&(>_OG#(Qgj>;Ws^9Dr()DUqlO0a@CVt znQ>i1PU=deQbYlr6L*T1QUT=Q>Sv7<*Y<UO1|ESQFZiup<%I?~53el<0Ly|2zXl)2 zFID7q0NCu?=jqCF*v~#u!uB-^BU<Z$@jUM{!63(s_fzk<Y;b3~nEruD{w%>T7`uMd z%J&`uGjn~dnCr=>k=p^<m<h_TlSbP=pu?{zzlY95?r<n`OJOvB>wN$EzG|tx<UNX; zYZFgfs==bI2F2inMpjLKXmI3~FuSWuX8tk=crhm0vb^!az6PyQ3zT_w^v8FY9#z7U zR;Rvp^fA}v=Pw{zWeGBzZzH}&;G28V6_7a=Xw+D4#n-PeF&Ci~eItVVu9kb~B@K7J zsOpRI*Th2dk$qRyC-iS=xY9!gUrNNRXOqrQrD$BDApu5jCTCWbws>ah&v*uEseW+! zM&b3!K?xveRf#wi!=st8dy!nM#{eiD8vZpB=00ezGx)T5P#Ally|l@iPa5H?a|b3N zlg7i@8znR)dBZe`tB^sE!jUONz2;9mc>x)uVI#DLi({xifQlwAg`}*R3-Mb`<n&P3 zS_r`7p2uXYQTfhp|4EwM_oQ$VK<K)1=KFGciE_2U9xNpev&JD)DzxMHWnn}sS^K$> zmi|{$qvT&wE@ooWW4sPRkXE3E!Ut44mk@5969t5#fK1VA2ozeMh_<9{d5~7hgpd>< zM)NDdNW|v^4WXsFrE`X0ASD5CtqCwitDTbhuvy-NIRMq3IsGB1dXAK+u+JEO-<8aW zHj+z;pF-c5dw*=_%+bjE=KT}Fo&M|9pZFl*oI}UQ-7U)B8C!faF%P-q>!DS?6WrfT znN?#Ey@|``q?Wht((e483iEU~EwdcQS(?GoV{x$XsCS)c`|v23lH-fUdBw{T`w>P2 z0ezigvyJLF(yZA)4=l!i3lH_vlK|*4vtTG7t<X`MX#meYO3B-$i|f4y3CeR#byoDF z_%Ol#KqPa<2sxs<;p_V^7tYmNeMa%Yn=E?ITkTRvZT6Sy!6RX$Z3V3>dY1Uh-T#_c z2}_~=Ak9zWUM56ErN70oRoqjT!S1}~ZAWqUs{~IS1rr6@lYOv-%oFGO?0N{Dgfi-J zx3gO5A?JgB`mb21LJ1uO5c)Ne!NPL`b0!Ezvot%Y906IbJ(_UU)UCJ*m$v4wk;u1< zf;G;W_O+Jml14nG3r<nIBjtjg6dI*eGrt<#Lh6{~0_I2@nCFU3>eJ~Hb)2Dy<F$U8 zK5_93k4KHw$PHCCrZ|UEO^z8^ClR>dGB02YpnW>WY3~RtAMn)ar(e;P*uHDDrW)kp z_|)^GP>++q4^^gP09~=8a5UHT_B(A5Lfc*4o$_R#j0?-F#&&qigm|@z*e_<zI`QhK z5YUN&Y0cJWN88Q02J7RWkdz@PI@HyDEPo0JxsOvn+Vit;`!*&agyiCkM?(trx5|g8 zd3Xid2l*pOz^mf6C9w?xc-et8##02NM+Hl96wUZkLGKMnFOWrf)YvjPP|(BZwx%it zFz69))NqvbpeD3*RlH{q;Mgfc!zF;{VnM#-fcy|Vbc8uP*DfAVreVtTlJgi~_&1`8 z4G(lzkM_vc3jVi7Wpdvq_k~<M%@>E%r=OrZ@fGe=>ZH0OE~cfjOdpy$wK>l99#W-n z>2X=|0pXGLyj|%5Y{v40XqyXigAO1xJc=_falv5WbjUHC2(c2H!^<FlF|Cm38Z=(? zt|AGM3=HHqvlbZ}76g`uPkU9_nqw>CV>~PeG6R2dhN*HkA-%X41qaL=O1Ib<K4@l? zW=z!{?<c&uT>V?DpSc^wD$3_X1Ac0l`dFV|dT8Ux#Rr!#zAeJovXB$suhfpTL=;9d z_liahsM*p@nkHpNuC8XkpdDl%6?J`NI?7{7f}QMn+jmLx^amLWxZeo9ken;6rh2Xk zp#?qWiMoSSqsdP0bdwzd=EUGkwGD)u+Y0^oAI<GD-R-__XozB4MT-RRsJn&bAXDC` zfkxdgQGV!s-{ha*nzEshq*XlkJFy`_P6jvDSCnX?L>8_6wkGtzhem|2sBFcwTb*`H z`|#G}`KPmR8=j50T+k|$T3V$yPP><jWp5QSbi(rk6Xr&au6kxS^9MB|%E_Q8y4C7h zykYpYvZ?lDUOAzpdda%$#!Ye_fHGby87|SCxEGSSQ>w|zF+JR~|5s_Kz@N)+BLSkN z?LxumTXHU4M<P)^<+3)x?L8wayXUX8{eqlC`x3zKitqxzYX5eU?!wqMe3utH{_5?M zcgKBJIp!9l4LrZ@3xume4_of<2;LN-M!QDA+M{?eb;N+O`(D!pR1D%MCpG#>I%oNk z_G+Qu&mG-98<6pG#)CO9{N*`Z4MnR-^yB74L`Rx;P81!#<jSXks1%LE)en7dQFH>= z16oZQ7B%sMoHb3>HHw`1)Z7p3_$~Sss#Y`J_zE)dxxvanCOjM?=g6vo3mhzJRleVy zdqf>)vAE5D&?m7@V*5rBupik5fZ}p3Gisw`GN-0#qG9&^i^b7|<=p}QZAFB-5J0=J zWu4O-t<7@A!N!ZkwySfvu^y^w$B?p{gS?;Iwa%n@tW&|86h)im(kVLNICcH;H5Clk z)X0v1Fg9#0HJDvIWLCO5R{o@Q6Br}*$&<he@)$hbYC=6=lc?chxr&160Ljj#mS0+- zn{KcS{6Ie9&FUhdBUlWnruyE@n<Bm%=KP~tlN`unRyLt^u2!ZoOZ9M!?AB+b@CUI+ z{+>NP7lXsrq!#`E-YjkrABb?fGWtzE<Q2eW<(Z&*J*NEE5~WCaA2Zm{a&=sANf?qr zWmtu%)Y*Dfn-0{4id+caBAKg7qlm054;pBE66D=u7y#$5Rz7?rcY+m%B`CgM^dAid z$Fcq@RrYK}n*aDllJYJ2tys`HC`#Q`XNW_l(l5Ga*^b1U?ON{HxN+g{|3uxaGS8wS zn2q5SLLF1OIQD!LZVvs)?5o9J>R9>Qyd!tW)Xc3y+*g6${{_pkFI>5x=kV#op*uS2 zILOKVh%^<~er>j;r%!IfL@kLdQ4D7H)WZMvhs7G2X0O|`u$)>6t?|qB<!}6)Ei)Fq zWAX*bh{w(AO7|cgs%c#Algzo>%Gv#lQyTp#5kL!`9!3>()Wstf09k&1EmQ9vyXm!) z|B;E_4i~OfSTR{Nmnq!uQzI364J0BN;!l1H)UEFp^rZd%Qv2HbcE)q*0rQWX;r)GP zwb<9D95wyEaom)(ByqY{?H;b;b>#$xBHNS!NuytP>q%EXg0%&7!N1{uG2FA&`T)(Z zNbO3ksw=shzj@o_{sGqPBcsTuS(Mzp3kQM^H)cNvOzSHJpX^*5A^M!eC9m3N)xi=Q z<$zO|lZMreNF~C>Vf7?&oAQZX^ch*a$d0kSv{lUIFt<m;*1IT3*S~qv??pYy>hx2r zvcJ~EZoaR0cf{XXJ@E`kL4J-{ak8ktD*Z6%CsL$RrEdJ^k-UYlQS?%8L1waS!`Ihg zfB!&=y_aQ!npPJ7e(YGlRz!dv{O!P}-%MX`4Mw{+xU9!OB=7yF-hcB!4oK*jCd*Pe z_=POJUC;;4o5{fF%`(g1POtA@or^r#&hYsfPpZzX92EHb_We7gttp>n0Mbe`uAb)Z zw~Zr<7EXjF<$qoOnn7%3*r_4LfCu+R{ohpY7rrhkA0fWi^CY|-nWr-PE0cDQgjUBP z3N*Z#E<XOF5@AKwG)%NKgnYP_esef~6)N4y%(dio%ERwqh`1?}$a!+TckTtu&z@%P zp>dgyY!r7jc6kcdC{elgUD1z%{|&xnlV=Q?Q`+#^<kqqKrw-=13VX_9DE?Iz_AHcg z(^&dq<$xM*Q_pZKVoE&di}}T6^r-9yI~NW;gD1^4cW@sh3Gx@-M|LR`zsB8))crqk z%KqaqHI6XhIL=9SP(A;O^9kNc=gdsuOGlgxJzZ0hX0LgUzrrD>nU~I=E>@i3kbROK z7;V<r$Nrzb<e!Wk(P-cNb2P0o9n@qReBsS9=j;+3?2tlS@p-Fq_Q*B87VQ6NPOoF- zU^@4z)%r&ur7k70P8Bk|4&{kmcIMT;QO#@YKU$}Y(@$k$tyfy3IZV0@PDDm#CF@py z@)?lZcIzX7PCf+S`X!A4zmK)Obf&9fZ3ptCr9P{;>2RlUKD`|LY6^KHbP(HeD3l%( z`A)r3rN4X@en0GE=Ax#DlDeA-v2ksb5N>!5zw^OY6XyJFxp~bLvq$;umdP+_D#xhZ zvCpeOj%Q{{zxO_v8tt0Ur+TCPEx*YLY6d|AcFo<qBO7jH8cW-0-DEJ^q%#Qo5-Q}9 zDZWi3MLQ?E>V%2nO20+Jtk@{AScm;Bc&HTCcnG^WB%hUzPF^^g-3U*s@liT9Xf;&! zZ!CQ;n|pCWG+`O6l9E*;pgtB<3VoRe3(gwE-mvEy;Wi5Q*-C@`9$j(#>3U%Cw8-=j z@Vnj!h$0W1JN3RUi1M}t5adX^7#=r$24UZ>1*98ax&EsIE#Pt^?iAw=-H!~E)?Gf% z{E2QD%0tJu=3|CGhdqtA3lkCn=D`SaFu;AYIwaUG<I|rtRO5`U@Wo8wEh@FjP`hLU z->3<_8aQNcB`pTD`UUj>2)Xm`uE^Djsd{NS;n{{W^LzN6JFWaLBZgvvNfRlI4Yr<# zfy)qBks^4y0OEdM42o!CtApDFt6Xx+eHo-4RcaMsJ*`$l{2BFP@y%FtcXnkk$uAnv zNe?3isj||RB-}if)eLcO6ub6F={5&mMrTss4-P&DldVDB&89hQl$ceo#OuQnhtq8` za1B4WL?asAZlU^hq*1GhVXa1@(osof_)l#RCKujWIY()p_~*;7oo@zelnUP&m*vl* zRB&^r)unI|!n9YK$?RI(Vu{O33{sWsezYF<RU2Jpmx_f_0(h@xMndvenTb0YVMelV zZ{6nx{CS%k(%Urd%$sbc+696ZJgLkwXi&bON(pt4OwSsM@g%|$)TYMALxUs$=vWHr z1&s<B2<44n1KW<ZIfCbmu+f<HIBT(wB9C}83Nu(i-xO_Z<#~KJoMB!yt4nOsp@k?` z(VZyfkKi8Pbf)decCd0;Pp4Z{XFay%piDihz4gJF<JA+8^qvV<#Eh9F|Cd4=qr+6U z{8c$aAhk%HGr^Nh9V)n?r$y~M{ZH-?@vw0;m+2F`{#Pg1hw4(@`*bZqW`p#F*%Y0{ zPC`{0!T{%b3aOp|^Vm8v78SBwJIi&blxA67h3X57oy-)Mp+O<;FICRuS<e6_l;YOA zWvXfjY>V<o!8EC)k*$){u!R`4q8!p)``lh-e>cIWm?6t49F4-JdRD{*h3rh_Gf%vm z7sX;pP@k?5Az0$JQSzw9ir%=;MHwBTiaAP2Al>~^4K~|3@d-9x?nBU$L=nlyLod;3 z5j`dP{YM~?V?Y*&mfZFTrPVJ({Z08|=MJ)o<!C_-+DOLT8@$Wywdd2KAn<~>`~;-W zZo1(2rB%FuZB+e-I7p*B3JNS<yTgHRwm9YGK)YxGCR}TNv5+b7(x>ZbT+C&YGeL=i zIwr(cLIVwn5#7z)cO!4#KPi<8Bt*vYrPdJGKWcLXO(fj?=VWyyw21w7uJz#0f!Ko~ zIiA$p&2~-#Vz+};tEfr{FEu_$cEh!Om+*r;6jrF<*rZ(1XEv&(aKK3rWd;zN;`%15 zu^GD#@opD1u~Hw4I1b_<XM|-9epmG7-Bvux_oRX>X1jlhslAAlBsM)jrzM(Rr`}D? zmABW8VurX__s>V98fE#|ZtqO#|4Mtljl%k*oC*u)mHL4!p3cX{5e_3~lI2NTbq&a- zrX{9TTvN;wH4k0hymXODgHRWRRo-+=)KVU?)%i3eeDnK+ZsDo<gsqpeFP9OEDn69v zFl>QuZDCG~sqVSC%)$II#o{bol?+H8u5h}d$&zICyF_V&^HFguLYS^wp^l65bI;iq zCOW5*H0O4)_mAe3PLL{Q<F5`LjfeNm6}ZixaMp=h7?$$7t3?JbdG(K3C7Le4a_Dbg zZ^4=_GdAyB|IvJS=H4}%Gyg0srv6k&M~_1M7Z-1^0N!VGB$;@9!Xdk*tSqroW75i4 z9pkc+yzot1Xk>0S*JM(Dl}c;x`OnvK?oY)>`DF1i8F$G5_v3$cntdgtb4$AvUCE&} zOyBXR82BrCND94tP*UI?CeRSn#U#zKMBpphV2Yke{?P2y=8{bs@cm==_U4*N28X<` zKbX2$<xM-r!rhX$->{~~8_KZh8k6GISnVaz<;oc=E9VRzZHdnb>TC!s>}0Rv&61}5 z4rKn;nbe@XxYqjg_|!4yz%w`h9ycWm-N?THnBUUi9?*n8CQ>sm;;Z(l0F9lB_Upf- zjUC1}UZaTFgMSO=Hmy?+n9FlhO`n^?=lC)1ZYp_AcYP0t&^On6WH_a>1F6Srwy`(} z#D^tnOYviAD5e7TjQ|~=7f)WLUpt}ZoejS$0qdG|HeORbdZbqUL5vJeEj%mB6c|y& z&-dk4h;)^950gU03-upx79z%s7NpONhXJ%>$uh;f6ZnEDJR)WV=Hfu~XsF>w*iRYX zQ(UyAuc0TC+Aal-)Db#(3-Vk$COFDB(Z!=k1M<-{6y!)#QW<mhTv0!k=By85A)c@} z#KCK7TvQ@{iwCCFnUE9<UoG{0=yuC?fx()K*6s;r{uJVJPPdYv@2;tHT?=U-(6eUZ z3b9lVKk*|?*xx(A=1u7qI}rO8__H%+UvV0bK4L%-h?RHsVb~G$d5L3vCqfVn?)$(t zKERlgEp@|@!O+xrp@cpUY|geRX!?Rf#e^kD&9Y~ef4LafQp^zh$yt09VbsBHFr0h_ zG8z<5kUSK;kT&F{XU>)gU9Uncm9eXx1@ZCwS!U>T3@hxS15<olBocV<M2V0Fn7I!? z)^L%+4BQGPmO>@zQ?p^YrZPtfFjGF7ZLA9eW%`K)J+Vn+U<O(dAkACp|9J>hi<9tn zab)dEx{TFzj`1XmhPyvu7C(k6nRvJkB;_4&7?4ovWiaETo<bM-*9dfPP%v*TcHjWM zyB*m&{KVuFd&eeilY>MG*|X4dc#i{-qD#WC&>7AnpCFA++b_m75(pCG*Q>FCl$&(s z>KLjm-}e$SE71(&RT(c2yd<xY9_z%1?)r+%&k8M~FrykV*M%1k@nxLw@AVK8aC)PO zg!`fHBGxN5h+ckGJtmTHF=t%55KQU^-z&XYE*Iz|h&W^bY)flmOu~eC`0>^Li~<ak zj&!Ie&mIMd7RG_g=mB6sXm)iBe-zVvr0xnCDl!LwfI~7n*m)(XWB2p5Hu*`~lzNNV zKLa6y>Os1l%+|B8P$q~Km|Aev%~$}j{rq`zmr2{Uh)AN=w6~mnEGwZaV<v<1D)RpK zT^36LBR!ui8XvlWU<;HSG4Q>Q?HP=o-pYA2fnG%%+`A8P_k~^uFTPE(Yh#6>V`jwI zY{n<Tw-}zXdcqDQtb!sz_Ks3DZLpv@9#7S$AL1C@cCMKWxUP6$j5m$>i+llpc)$t8 z)eMjI9HKrdmxsmQJRpL<gY%RCVcRLt(SunCK;K}&0%UpN62|j$bm}3TLpz8FY2!L; zh@H6=ai^FJ4mq3Q2_cBsj1{3vN=)@CtDZ9&<YxJ^FrB_o|J}tuTWay3o7Y2C**cEV z{RxB!lVQ@s>~a-Eh|4S%S1MS=<@!<R)#T~!JboG?fh*x-96*vy+>p6`kTDiF0~7@; zWVhf|9gTFi)rfI&+NfvJ&;&SC)v*XvBE~;feWslmv&cskAXOTY);4i3%-6-zr&b35 z@|4zobd=sHVeT#wbx*zSH#t%zBQIDy`8A8b(*T>odg|Ata%pqfZ~M>~a?zV1Dx-3w zN|p7WC+<Y+zSNUZ-QTAV=%<oja6J)v(W8NRX71)^BO9L^IX7N)5<u&{+HhRqjQ(H? z5pE(GeEFCp%tWDy`7dG~AZ73Yu3giFu60q%XgtZP<@&DoWwu`6ZS#${{2^5dqHpgQ zn8YRE;mv$4^0h5A6rzgMcRZLYuP?-^ze1{h_B8RUKj9PC(r^8@S8t%-x*>V9a2txd zr{N&fY{W`zi%@IbhpFCPXGzs;M3+$eHbEB3+rq_5)1N)Yt!jPWWZ6Ri6k&iKha_%Q zWt}npcc>R3)SRI}>eGEH!({m8N(ZVRY=}-6iGj`IXuBJeZ#_@Q?l$=n6^DufYZ2N* zd|WB|AtxA`(~dS)e}p7fij)Lo=hH1p4bAw>wzXetn9;e}qS2xVOY!cE@}r-E0WOO% zhcldq4sDx*e5A7^WC!$-SfTgc%^~ntT0;TCwJklvwvpc(x~S<YZ_&=fAWv*`fqgXY zAE8TFFN!%ml@cnv2@+I7{WTeO_b+730fuVUbCP>m6ws5TihbJ1^H`Na#vyMQ%j?KQ z1pLu|)e}PDan=Jif#T5=M&Em5bOZCz1xo;ks)IfVP9~bcT4@D~i6jd=pl-mi&%H{> z6!siwgmeLENDnZM`lwA9poW0`T;@35=tFiO_B#^!i=1wwxR+wq12{_c7)=q0VUREO zk?Es8GlBlbur|bk$)bkB&=f!z2sBIL<dA3jhaz1Mw#W={a>}W8ff;MUkOmDWRM3s+ zP+vIo<vp15-^ww4m>i9tvH`3YOM8iHCpK#I=Jo69Hyz#UdzX#1X9Ng&)7Q6x>!o@~ zNNv2l#bj0c$fHQ)0pOz<Z&El7%J$)=B21HKqAU#dC`<<!NhUWpERcN3_<Bo&J`m=M z7v^!HKkGM34yB*R-dbW&@~<#A(9B$h*^rCVo~_colO0+1i&%NV2#gjoG!ZTCaYQ+$ zf}>g%@A2YQ(H5Gp3-jjsoocqR$<;7@6c8nMz(d}z_yLFR`{DB_X@J}j320%DsmjPP zF+xRQIG^S*KEXUEfv!79bQfEZAJn#W3sS~lxXqy?K<LSg-g7m6`h<$h4-Wj_>0-+v z54Fo!KD4m2%QkP&o2l92`q}DJ#!P~t?b0YMYt=Nk`30Boo8Z|p+i1R&`m(y3y%xE& zW4E$eldDUk3kF5b`WWTr?ud*^#T)O9As<X`#4jke{+}R>!v7Z#Chh+OVc1{(?;uR& zbkTo<Feb6qX+pOr{sY3`%Jd5K+G;-3{uc;y?S=j~7h1R2@*fc9ZF~KHgD@R0zq|@M z+WYdhqv6||NK$GJgU-g)K|H;%{p9}!!fd|Hmb~|0Ak1{JdNPM$ckAx|GYIqb-K&n@ z-}*xD&C>k`gvrSv!%c;C9c|4N>8Be#?mpRDXt*~$_4w7<ua!5+M5u9ik6)}&KC0*v zjs0&B=8f{dzo$p*-x}Vi5Q$gh;FU-cCY_ZiimaKhAvuXC5-?0lU^SM(;(tJxfSuI@ zRJ=fG0<8^>B<6WR@mi8d`_9_`fH3Q+a@QbCn$j8)ODWhhgJZBNc6TurCi7MUQ;X|n zkpkKJBC#Mgj~B+wWBw%1fFj<T&#})iB)9FOJzR~YX^yq&-P(hfzzDMaguF)qTUx4y z#Xh42{-+m<=s@sLLQ$+I#UN+kl=V(&<}PlaI64Uy$t|KYvGW3-*yjoeG@Gc#+Byh% zI<kN_cxd2!@_RMW9*vt=7C9m_0Nm8<`Mth#tLFR5p3}YW4gckZ4l&*P(KN<a`=fbM z=KGJ9c5~p3`<!wY{S@=A$xdR=u;}{hY5e{A_O=f=PrKJ<WwXMhKgC76ntX6G(f4mS z&IqmQW$JLB4hY*8hw;wo0-7=6a~k@OX5-$J6kzz&6Tc>E0SYJfEI5GY%@nGyC%H`C z(D;2+)c`<`_r{o7c=Z9dX$)|Pi})Y8Pb2KSxzu8eE{DiSN>(X2G3ApV={SVZNB8+t z*dpgZ)*)j|T$$c$oDn<Nhj#ae!j8Sr%agcj_T`@b1y;MCObDDo#`}+w2&szq)Vhz? zvTdopFfn?)+V%e$c1HYp_AL@5dcG2icyPXo=YM&=meSH4uuf1J(#Sx(X1&<VcDtGp zd7WQ*@h$iV`Xx4$tQp3jZ<aB<Ui9}%@OQ$!n*_$jPgevw)aSy$U)^WF{{Fv!FqRMh zU4t-h=)NyK)wer~;pbI6FYUG?pvZFG;JCEJTof+iPX7*L6EQ6_BC7#(4^SFxH1M;1 zTVvMK#-!hn^2gNHi>gT$1U<4yF!^ruCdn9zWa{@L3SBZadu>&%`X9EEXz(_6;3ekK zjDh)#8lu-SF3uy?|Bm-6rJK$m%hG<l+++!D;MgF?pZx?ZO(~3+pfkk9a)8${D5ZNo zHpHiJkcdkuWvJ8{7P2`=vYISq>KGdq4LL}5peaL+{{IESWKWj!$&Qa3g&aODrg<Tt ztvg|wdze{e@IuIPe8Qr8PV9cri`!e`>0u%+Y|WFr4cCAf{pmnfckK192os<O5}VbZ zqR;UNMjGWk$T9vXS)AN72B!5?w7t{SR>Op#UaW@72aiZ~mb`0!&jnbfiR2>zO!`*D z(eE(m2rMsVnGQWIJfEyoJ{u=ahyOV$0zj&;AibGrmg8cuVU-$UVkTbUy1JWMrNOT^ zn`CobihQ^8duug4^wK$PYzP9$Wd_JB-YU~{RO@ud5DW!07%>0%^zN7TtIr))$h{VH zxxU*IeX05gIMXi=Nt}Oosd`fiMp8~omt?#nUa9apg_L~YEe<YS^UP$0l+>FvYGHtZ za`h<<zOhoppbnQGxvQ@Uq{1O%D@!S>?;ffe#k8&!f>a0TD=;v2um%XJuLi*H^5J6F z8WYU#0bq*LQF2c34u^OZ<vk_W$pJX2YMd>*1ce}3B!w|-4E|?`(kyJPm28pBz*3PQ z^*EsMv%}Y$y(Z8^V&^eT3>95U(pMSvo{QenW)SWa8LyAgU?>5Ins?aTe6HY9rGy$Q zBtb0zic6aWO8em`0hpkfY%6Kg5SOSA<pWx2ihE;&>@4CicZ!)V65s%~Ff#sz#+iY| za2*!IR5MFARP*INLjQ|??_ib_eG?m4jI{49w-rg<oh37Xr;ia;*;@G@c05~9qr=<* zU9RuXLO#zXa8#rtik}HDJm<m7H?u+>g8}nnniA(qO9$wg#zrXS3_>^7InE+EeaTI! z!EQ2ue7U*@7O!l05j+$k|GXq2s~{DT(uw31vN*w>M16;7`Uytxot(V%LL=iQ3h_8$ z5?t(ytY~7>n<x)KBdRGtWE)-NpC8m#4zYkA4&X@IR%poeoA4nseGWE`7p!I)VAN1= zAcOb$hoy+>WGL+QsKsX2xol1_fPjsv?52*1Pag!o&1xiL1{9FWSgE}&#T}!aL<sI? zVof4^W4xZL32YBb8FWW}JwUSV8bq2`kaWfJUnWzTIIzqEaW8L#_b2Mtv4Fz+$l~Np zQXV$WbAF`-n5lay8G?%Iw`j3~7?W7dLCN|))iYOe-yiZnB2nsXM@o)M79;T_j1KW` zH}q5!(a4f7Z9yYa?T*m2KkCazgaoDH(On!{CqoW~gm=Z7N{SRzk#M_JV1Ym?fn^<k zPrNOunjdBrJeo_N->4}A%!om6lyaOdTn9R6pHQhVj=5WPf_*lz_O*ZIJQ?G7A1Dbt zr6yb8N8lZ~Z^EAYwT$F9lEneh@p5eIoF~`x?<LTDJ2>o9xPyA{Q?}pl;z{U%jYF^b zCn+tx^M3-t^@5#(zkADU3&k1nA9wqcBypu2#F==dU#saOiqqqyizi$>xRmP}X+taU zP)%Yr$!5qAY%L1zi>o)P{`>m(^|(&m8(nC~Wen8KVOV7c4vpAYA3Z|_{vL^X8`oLN zFe3eH_F-ADk4hLS>9!<a%F3hqvYth+f{sl}-#>54BnvQ{I!f)U>25=gv@MnK#B^T! z_umeB+w&{}M>S27UY89}Jn!@#oqx^BlsE7qe5`-On0DV!|2E36nUXN#LRMvUEDO8B zL6^6obp+Bu4D>T9;Ltl18xY!EDUY?Vop1E;3$Qvv0OCd{^BP_8n?B7zm!p}`)Awct z2#_WQc4}sm9T16B4FS%CBwB*-fB<KHpVYvpHfR08NXmisdtO+I3mKO;z=xobFrm{& z9(Q9XfWZ);Z&9&#o2Gv1r;u+epa>ZB6bnt&4!0s#>_Gr_o>Pjn-^;|2wPB+7+pX{) zShI_*#jL2ODIW7?7#(7uSgnAW*q}NTMbADIJ{Hs(8!aCvKg<tXB?dgE{}}Hr>$b1q z)kVQNyzNJ}YQ|d;{*lq2($R&k#22{YhdqU=SV9+3&?OA0SsO|RauIM>?Ai8fH=`=X zJgV}h)FM#&yWQT_ifhimHw(ZnV33{)9|4e8b|7p~<MEs}+(sbTSsQZP2XS!#JL*8; z+EHB{cvy#AvsKE{KIJzu3wr=K%QZwwE+sq&N;mpA5=Vxy48$aOQO;UL52v6Up^k`v zrz;@kGsp!tWu4+t$~+#3flT)qE{#z5cpL4P$96~EI_-lH8>ze^T~5wnspR&vAUaze z2oXzZi=(;fdknIUUpr5o$3WT~Vm(JQ#u%x7B3aSIVUs3J%GUvo`3}ai)vyxpL{^h9 z+iR)=0~$m@;Q~HQ=c!mLxz>%;-VgD=vn(_cSz9yxn5{u18PvZ=Y@p)erd4n%Yv_Jo z(lw)Dzzn#;#>*!XZsbIr?9(J;)5Q~fx0zB~R8yQ0wskAdmih?Z{0ylbki?EGm=!ej zQ&19Ko-QGNeucCb2?#(u9tdLP+=MQ9Q!HIeFZ&Qy_s4X=B;ErkvKn%4Jo9uW`$2FR z;Rwpf3q2t~{Q=<ZW5Z9wthq=4yefAZo41C6RYX3swx(Yf@VQ2CYUF7IFQ6*mw8WzX zXhL=bmU15FS&hhSnhkP90P4r61&P7&WEn=w9xz8&I>u}$)mTpLZWg^20n1<T*d*L! z964<bdOGviPs?qalC^a_UvDuhZQDLBC%t^zQYRpvFDkpnnkIQSH?2eNu<uzH3~&aE z8XRTq2+SrH7ac}soWgRbJ?=dkF=GlW#biV+pA{QWrqj7a!2*jO`49*|mxFWYwPI4A z7_>4(NgQWE`)3ewlz2cC5nI}Uc);l%?F+s&#cTCyoDM5Pd$FH)uj{eyQo=d~QYshu zH8Hyf18Ot3{nchv;l|qG_5#mL;ARPM0lSa|*p&kAyxF2NSD>xR$@c1kq>P4cZX;w^ znClS$*OmOH4|zGbtY1WYJaC`JegzsA0z2Kun+w2<XQEPU=#<a%-{m|x!Bj=f`w=mq zo<2WEZT)Ys2dcR&%0V&5`!s(0G*2e7AIb-GD3s6w10P_-N#ruo)^u9IwO2cZ&$cVs z$)AY?OAUc@fml#;2V~hQ{`{O}T>$1-3Asi_*196)_A*IIY9SegQ=8=|ldyt`(Bo^A zrZ^jpEcnj+yyg81NulQ_7il{anVdqQOMB^UInZCyG|!k>lLUOItjZOUwhugDpK@Wx zpgZ%Hu&sF4(<J!1T$<x(<zZiHst1AbFXGMwf+9J)9s`o+j~^F;Vfk{e&REbD`B#0^ zZUkr%bImzXC>c$iSW-;c<@%DWDay~Ysd*<gA}4!#=GIAHDB^GGQTLO#Lda7G`~@t# zB*`yryp{BT#$SuIjkk6h3;oI13KfqeL%-ms3jTgf0|*Tjm@T{>;5VR5HnI*ttLqo< zLU~yO1m40xLafKwCw`IC>o8jvceu5DhOZn<Cg&lrFI11!h211<Q3x7E8GzSmh-NXD zr$!{{=sPKZzIs5@t6`;MEZ>r{@ebg+^8$AG-OY=KF9_FwR(<N{P`;A<Wo^m`Sn<(C z+M`;;=|xkJPbkIP?28rhX;{25b5++tfjxCDy=*tK|27cDzn4&P9X;f|f-kZFfF5{b z;$oL^DB`m)Lb>uKa3A^zRrppAHkrrDnw&kR2zAgeWfvEByG!{)7Uo4=MwLi6q5CAv z0UR$^YL{fb`HJcHE5sNBwArKP0tKx)e>DV3pWX#!!l3_zUa}m33fn*u-gih=)6+(R z8oTI*6$2_f@w2-9eZoC~Q7_y6)Kv=A-%#ppHt8Ymx3}<jP+r1b`NJT!bnBgQPO_l> zmAsVk7jtj>FewOSexJ4dl56JZU(IW|WtLWr(&Lp%S8Q#)+Z)bREPH&3(rUU=#{k_< zCg^f#Xsv+63w-5}>NLr!l3i2>gE9)W^UNA4_d~95G~Rz9^rIt&VIl=d8Fj=J(Eg5J z1-`9&wZKWPqFAtlA5Pk|F?tjDy3QL!>0bL*zo=iWr!_JA8g*g)J_x=TtX9>RJ0Gr| z>}Ox4?p&ePgts|&jKR*cIKGec&RyRg$iBkRntbo=wPWR|DM}n2K?4oE6t4voXuJb> z4GYo#(K^UA9z-4PsN}Pn&APD_lDQnR?j1&~g^$+JuLt#BIMfJIrZaUuc|$k-fH_;4 zk5<_NR_Dbsd^Rz)7&1G~^u8<q%Atm;b7*~Mp#5<2Yhn<=W<0|><(mPk+zWit571FD z<aO7yxk=cg#H8A4zjajaN$yngTuGY{^!w+*FZfWKM8dbE`21aRS7N;W^baQA+#rQq z3MHKYY-QcZ4<_`;tbGaoDl+4R4W6r}nV|o^1a9iM2Nk|q{V3`cab~=j#Yc`Y$1Ydc z=ptX}Hh#`#^p$v>(->88?W~F$Laq{Wg`xC!z#ACO(bxBtUNSY~GcE`edWHdGtI#w% zs9#?ey|#5glb@U%sJ<~<05Z8664q?TpL#a=o#kVEXGi}m9xwk+kg^>~)fKSn_tYHJ z0|TsK_0wMs-~Pu$mCE#KuTQsrp5n**nv(pc5Q>M1NvgLIq=wK@{n}-R7CFWlpV=j6 zxaovofbji6<=bqs!#P)dpLCb<LL5Jf>w_Hl<9Q!{@>2b5N%VOSUH*jq$C{Mg)CK6C z(<>aLHn?A3<_`-<&zrFh<GZIo`_^M|^8RvrN!*j9>}9Hef%|hLkg|w8XnY^&xncZ) zNW<gOM4cO7xF%Nm9idA}V8t<r?f9s881#Zrez5|oBRuI?8lnEdr<L-}H*~5OT}kmH zXUe7_JY)Gqh$Vb1)VsQi<m%JWKJ;hZd+NgVR(Qpn$Y_F9QmOE)Z&T~*f6#*!^8Op~ z2i4y!BxWXVe8d^0B=oRq+0l6HXYJpdTYrZzsVggfy8+|x<qhX;d`F>oKlv0;g*9qC zgS9=lUqfH{wdg0}TT)C97IcBBF7@O|(kU?PS{4WmJti)*CO&}PVxzguVf)ZJndK#d z5ubat0#d9JwaZ;vW@npbD+_r&fTZk7@A=%@6sO=ebN2IHyyKVnMle4sfJgb;2Bhmi zt~5S;@M}E_hfqr*BET{kxk9yuR`?{B+|~9KPrJOHxII4>z8873wCP{2iy_ihCv+^Y zgbukg+O$2H^S$;lo50UJ_3*{C$H-98_+cz)8W8Z>HlXz-E1D_*M*Ga_$1)sId~MlK zBrm3{`bAD|(vR($+GoH)HKzABy~BC1GQ&)TPYiw{xmf{~J&%{=zK@X&zT%)0zYXg_ zOp6$Oxhqbqb7Qaj_NOo5Q13lxp*)nLZf%FQYncdxGEK#>@qYJXeZ~r<llk>-S|o3J zGPG6?hIz;+k&-PyJE{1aCC_jpi;cNT^j)&U0g2B#w)2<`4s~!}AU6pn6Sqbx&}LCF z*(PR8_H8xajIWzQIfE(-b#3Vcm>*R`fcxJN(<9_}=v5#~FLWT3j>hFkz+hy&a(pO% z4<p-)G1r+&nY_(mpKjv*{<8Oc#=-6vS<t)2%5O_=eIC&DAPRnwLxnqRX2G{SUf5}! znkc%xvPN%I=1<h``gw%2IR{dVE9MudAh|=K(++<ftxn`s{)){8?bWxDteWL%`Hw$@ zWj7kNHPXaB)YtsR@V<J?A2WH)q6PnEwIIG*oa=53Hez1+^75K<4Dp(LluADgdbBuX z$Y}Z4qT}*MplRJbM()4R2F?-XpXdGk-vA~Jg*}o>y_EUSy}!N={l7sN*wN<EcEeYh z(9E67&)2EW7~l#iWVT?kr5V3IqN;JX#!N7w3MWs-Xtpy`Osko=6x`|_X_!x<^fz$! zn?a2^fA}$?;p-b+|6k)R2pNES^BJAZe}ORV_ub;_o<rfKVM|w<{&|+a?b~U(d`^zi zZ2`fwmK?6*vSo&$z+Q69UC&#QWzRHyXhIkS1m2ZO$zNuP^>scBA{v_4opav|AugOB zjCL2kc?BcVSB@0ep8dkpSbwB0ewW-1INlhK8MnPStg&)_c;q$)(_0_gejJ<g*xvT% z(b`R~ALrs4<w}f-5bS+BXCGj*JgxU>N!S+S=I8v;cZK)tuR76YJ1?^LxErygVhS%g zo|Tt9c$Lmp`Ws96-C027)z%+=)`(_$Oc#kCCGQZ<TQTXWfkBiQKp@LohiR5?NB|vt zxws{&@TaUo0pI<ZR*N%YqqZGD#-)=N92pAJ;SHvj5DA{M;w$QB>!xn{e7v;(3P6%m z#ZZI;l0P%XnurJ#jTyL%r;+_lV3r9=6si+$Fl#YVynC2B60!A1ixu#j%&cME>PS0J zvasZUD9pjV@lxBhxLAO}M6QJ4<`+@YveKXsJBeu)YdGmt=2p`$IW1C6X<W8vw+AXX zUSHbc_2r-K9I0G5jraiFUgPMkYL<tk+$7)(Q#vtj83r@HvK`KNfj`pH_V02*FIjAJ z)KMW6Hkr4q-@KMA$+*f$8<`zRWU})YW@*(@FQRnF%QE;W+7MgOs+0L5%T#0tFiG79 zN!Z91Q{;U7)J@o84_Q?hiW3gHo%q2(p#1*2;EuS@PJX9zlG>lQAKeD1J<L7l>-WSG z55dLp7J5xmfbd(NcS~->!Zu1GHjeiD)^+|Qq{&}7zT*SGK9TbvElL%8a}y5NE`0a{ zjw5>1ayFk9S?mz_UpygIV)kf7&PhZ{vvv1VCWxqRHp2zg+rQ!Ts)x~Nwk5U1gkH*5 zZkrQ_4{H^yE<m@lc3vwSkVYN3$$g}{rF3{s5~*FNOOm`TH&|yU*r3JL{TZG8&-|qz z-U%<jfq(q|>2t}T@zHx}yp`;-KKER_Syytkx=zhL|8s+@uLUo6+lT(H@=Cx33Q$hS z!A<5mFBJBE0#32(C3d|gV3nAhn0vK$Ye>G;!8EO}fhUSJ=UowVNY|5-r&IJCp`vHn zh3RSOx?VYS&7;4TU;sfK4f@$U<~!M&1RE*L^#@_vIc@OGromm|+c~Mf($pJ{-%S%^ znBWA%9XP;#(vf2cyka(VsOm4yqsjxfSJHa%CJfi;VRoT&^9MW?uu#hNCyC>M@&Qa4 zb4^8zk&zM|p}#$}WvA)JEv_(9<Z)z*Cr*w`*M+Ol1zyO%#DvJ~3eCiRZjR^lH1lfB zs^1M>3IW2#_>NB!aSmL7<RCErj!t*G069Yma!uW{Khe~TPoSbPE@NVVds!)&wT_w1 zb8ohu_Q^pE3Eg!g7@i_k%%l9Vx|}yE6Xm(=3=hL!_pDm9aDUSIAhXOa22oUEC8bvW zq4>|`pR^zU%fPo6XL1G}QX0@Wv-mE}lrqpiVL2E8_YkzxdOiu8SkS9d63eued#g|h z*0-F3S!k|0eTF^cGalzRljnGz65#(f&<;;>a34)y8^3pgD|C{+*jUh?G8<tWw&Ic( z+@0{7s^a)?4ieo1JbM#6nqP8U@!L)y9iFw%8SabpM6sAqw!O_9<jy?!BU6kVE*F0Z zi#zd6tg|MYWXQ)_kSIzpB)E_;X30gfQt0Z0pB@QRRB2+5#Ai}XHAMbgXtS-MpqU1~ z9FF4r+OGwR(ieuIPtUdAy9Y^CfAxqsJJ+%5^wC;~<yE4+5aOmDkrGW)XZ@RBc$beH zUg;HWU_NW0q<WB;#|MP8mYcb5<TB$#xTQE%y*dIkW)cl*G15ZuL}n}1p1tg6o-Tr( zmb?gyP=*>5l`q(qxpt9K{3k1DF<#Ilhwd${8Q11<7Mrk|g8qkr5Q*V2Tn#^!CC@5l zpN8J&5TOO#O(zym6D5)16+AoT9`cUHc+6zT68IvuRfGZktAbl>mS?xS*$J$)g*IB? z80EwN6xHJRI5-_E(6BN7otGq%!oZzRaQ<yQ?n!eZpO<5nGH()2<Y+qV{d&)iCdP?$ z<x6VMh6-_CoyEOOwbAbM)$M0+&E10($uQEq+*jUphf*(Z&FS!Vn{KI-F?>WE#6Ajh z;YaZ{zfIk-U?^I-PoKL&B~HFD8bL#jE6{w;VCxbS5;DRGBOXA>GlXi;?R@juA@ZSP z-{WywACQ7>@(Tv<IQYu8H0{Y`=idDgP^JXjv7II3rhA)?%(!=VhCpVy!!s55(w<-< zZp2l4;w%gwQ^`_|*L8VtE4F&c$|3QtJ_*LsZzo+YNXABMa0hc7X_QF$Y_d5vrxw~Z z{stBO8MGw9km;+b;oz0A!#>RPK#t_I5dBS?`6Yu2q?YoK&!Vy$zwXY5<rugL;bj3| z&ez&U(#{eu?H)ZD7&kJvX5$jOq;w5zlwN3UO>r*jIZHTC9a9jbV}M6dGB&oy-jHw{ z<D`F~k<&OVMK(8Ne@2ldQ#~u$-nbzYNV{a3IvPlF-b-|H&;Cm6o!1b*uP4dCZBk|J z5;%h7U@(bmsFs<~I=tNDmMdk--jONP49~PvT1Ppt?P8Bynm&p|LxyoUH|q=Y8{A=! zp+dIY=QCt>sEKMB;}29_K2Y1$Bv#SgR+~}0sY!7c_n#0Q`i-|a@4VudOHhF~u8K+1 zzn6dc`I3hJDskCI!)`OX{-YUQ9f}34F-s^N2xSyn7f1NbhWO!Wvd_4>Ki!m#q)&Xc zgYynqC>!|V^dXvkjiK@$&osTy#BmngYn%P3@2!`AKHcDU2?e))!rx*R+X0w{lt1R3 zKUAbvH<jT_i2}7R+U?zHOAS_1r<r#&)Q}q$f4EKT*xRGQ(rpO0n0z}C$g3JgKk&w@ zHY*<edYNK$-V?gVNzt@km7yY(5$`k<!?OMKwZL<oF2EQH?rIgoJpg@K_pj_{;01L+ z(DwH%{0Kwv&wrZBq3eK7639((WH&Q?Eq&5PZIn8aeK)ul&_W|7jt^aFvwuY^xJYFb z%|gT{Jp(86?7lj=h2SMbDaw&3?8E{?@Fj<gdPmr=xH7XEkajld{Z3GDQ<^XxfiW6y zK`NUxCd?dzx51Lz4J2;N1C;@yDmGY7YB=aJ{sbr5C`et0W7YsiI#o5#4YIrkC+6Dr z4|!1FbxJvlft-M7k>VJ96_e-g0B=(ru_^a@IA8ezAz@>$m5MT5t+Xv@4nNMCksS<< z>bf2^C)M{RV?U4C`u@V^mWC!96;_BsOj1#Rhnhc_C&Ifx9ar$4Dw6SuB5Zv?`jY9! z=R}xzhoLvgb^T1t8!sM&H}pxQB^$QBph}wPkhF@8IPV=K%>(?Q2-@XMu#!&I7i5#n zLlgs<$6iqjsBo-ADI&`aki(jpBQ~`(hRFDb3vD`5ISo0f5!qZOChYj#A;_O0t9<0z z+MB~<Fbl57=bXh#YP4NWA}}Xr7e`>eU>RvluwUly^hj3m2J;FO3*)1OQPF^NpiwdJ zs@iA<t316pAA70nPr|D==Ltk>ofuyF6z@#1Ow#CB6Agan28+XJf_I$9Si;mj$_R(X zbP+<M15L69nam8K?5|M5%CK9cu<2mR>ku%9+*raGDF*?_<&alkpw^hjVAL4rz7OIP zdesPr5iY1baW&CT*)5!2P})d6?_s&iTw3uemdiVa&x%Yxo0n681$Hz+smk|pCYKeR z%j^iAS{t=~JD3B`AdkjhQxF`uJQjyM@$nW9DTCcv#CmQnsk&HRW8%Z}^bo+aai`RW z*zUc1Z-)*L;*@dvRpb&5G5i8tfu_}df}@jRrMgnWI|A{asg($Q<0CWUie)r8VBJ7p zJP8$mV+N=IBk4CtBL4LqTQ#W0$&C-E==}ueM_gMr_?VhY37{i)y2iT(uS)UpSQ`Nn zl^vjEBy+gDXu|HqUYKrGD=4TKf<=)&n}NbYY2^QO7l!fsPrd^<kjTQ2Xr#d|Wk$J| zELMUqTLaN}kp591UIE3qW>OHluVfm<cG#L*8;S=z$NadU?1%z`TQT5guw-=NSod(q zO8f~booBM)^$&g7&T9(8B#IKC-zk1Iq(F@ARp=hctQ)Kw>rjEkj2}YhL-ksGZ_u7( z8}1wYXPSQporFvXbI|9yQO}kLQZ6Q~Do!Z#0~?~I2tD9%)scjKeOU+Q{*B2S((_IV zd{von;)AM;2rF_m#WXKib;v6T0nKN!F*IhyWX&|#$ed~Ndnxm+^P4#KVDAEzVu&YF zvdmjYs|{c3%`bEGR`(qTheO^!$@$gESk}0SOOJVTSd82ZMQ~&S{Zs4{miPY)xIjn0 zRB6N@3xGHX%_8E<RP7Y97zvO-1TsK|$5;lKLZHm6x{BZ{b$mS?_<>?2N-4-QB&5** zv(YroAC+*^P<;jsbFx!KRavzYJVlD83jjdq&O)k);~GzFH4u8J27f39rBc*O*aSYB zQDzm90FwyKc!K2#02*K(CU6Ada=vBtsiUyQX~>G!h}Jkj6xJ9z=cqo+TuE}Z6MjJv zL@0s^6*d2f@I!|!5UvafYM6~l5CcGHARlxuz3L|&{4t~0iHbXfm0ej!u!LHmBW3kh z0h^ReD28buSWq=s4I5FYveqZV*gH8=H^2c)NVSWF2+I`Ipv4V2(Xe`$1S0_1LBg?q zvN4mDCz?8nngPPD<%C+ev9_662As7_K&XP9R!rjt2mRS0W!fdt(*WRu->OXzQo*-P z4X_Z=5!%xtnA%Oiv0p6C!xWJRG78Qpg-w7NPOvLeBV1`rRxyFMS{Q~ykX9F@77l7# z>%!X!xjN(ngd%tXL!hM{?A%dGn8v6DN*DsEtp#ARsXe+3%ji#~^cTc@SAUH&_X6Bd zum%5HxP&zL*lCTqO<9PP+uUnC-TJt?u#;Nn0oS`Ss^v8h{J@K^y@b}CS}~y`(J7?j zd_K78*JWKqQNV=kw1ry$gdE5LK(I{Kum|IP!sJas>Xnehy`zbB16%M@i%3cPl@P|I zo9s0LGI&`a#DurO)J$byKPpTS!34f~-9Z?F9T);isD)y{v@hF2w4>kU0$>7>4DC$P zTnb?zskvdGlv2Qi0cL|C7=k}I;7o{M5s}%k)x6^TgiG*=2C@V<fMGxQTCt0U(69-v zOsfx0j_)~P<<N;sFoFPh0#ryf(>03EXyW>)hiMpweq`aVEd@WQU^iHV1_DA&=w1Ku z#bLp^IzajaVlrbwi~}Rs0Wv7#o!W$9h=!D;LnS7%ELIK_b=3ec1g7vMi@;()UXHAa zjOuwHh0I`1h=Uy{f+FAp<ZGZ($OK|S%m$t{?tNoTFk^c<geTa69f$);_}ZO<piQ`0 z0rg{RRpi{r&H!KoHY<fNxd_jg<>hEX$at})tCR+!1VDgc95@6a9%W1b+&3mBO!%?t ziC|)K=22eVQnuhB0E7eHsbD&@(}KXdOt5h#=W;e@1?%O#2#TFRg+(ZWhbV>8q=-aL zXIT_y@}LNPT4hTx<_hisKJWt!Ugc4SpsST&Ypw-A@Pj1Hfg;f6eQh8Jsucf)6fPk{ z!TF74N~-6!2(p)D12?Ewb(80fUJg1uD@=%)!VQ2**@PgZTv(U{7#;#0(1Gn#Dn9@O zN(nii04hrG1Eoq*9q0iVCId=v1iI;FxeB=uafN5VQRL0&A|vUv(2O9%UpMfAQa~vh zo9gBGhzS}8F7DoBDNM^yNE0EXNVWt^ScD-U1DWmt9}sF5=m8+0X&oSHx4wk6wgoeu zXqb9n;sS+;G_WQ;=fg(qa_(xi_}l>SgLf`uvi`-zb_=E{i?9&q)5;&nNLFN7;Bu4b zrbz2w$lyW31eE54^QDwbKt9s$=81-&l)744GvAw?w*ignKc;M}Af5ku3V=Fr9+|<- z-A)TO3X8ii>~r3om7eTf4!JW!>xte3Ia=+BM(tb%GD$fTCA48t0IDX$Y^cs{pe1gO zurE=7Vln6;p5W5*wu&abiy5JYccAb3uJ0TP04CcVJK8_^!oR`YKT>?4HU<*_7YZ>c z(_R|6ViCJ%5QoCX=<z0R_s)n?KoLK{0aXMh3Ll#$bkb~~Z*0H@cJKyu00$FShZI)_ zZxHc!(47F72CNIl9PI7~zArZZPe%M#+MQ8R$YXhn3lx-a3FL5&0IDMJ0yp4<`y1&Z zzX+HtFlrF-Za@ciSch<6hi=gFZeWLS@CI+ta&<rl5toK{_zC}h4Wbx(V6fy&Qe?;+ z$66ojF{MC-X-H1C9de>_@{9<PBqAbQvf@2gv=*!fDZd7GKy)le^ezvFMt5{Y$MO_E zab)NPqeU}t<HJ=ABI0c0PJT$S1E>hp+&q_RL5~Q_NFqNlf+v^-#sd@SHT8)Y2PQN0 zbyx>>NQXz)^<Cd}Z)gW==!92bn-%ucGzUhN-i+G)vD#I3+x-N>?qE{a?O30PKL3e# z9wch7h_c9#bU1WGPlrV3^+#WHMlbhn@CIMlg;kgZqiyeuh~~l4-Qa3MY?F4kRpekv z3!czZA5c;s3UpJi%W-%IY*2?=w{nCZ_l0+KEw^=Sum=BGkcCwccBad}apP{V%-tj$ zFq3nYdnYo)aSQ6S)5lY_(wq!7aDh2ET0PYE*nAjzkOpwLa)!5gTj%w4@b*`bc!}?Y zOPD2<4n}zGbY|c9%sYx_0P;Qtd5WCQ*jx)I*&rN5%`bfjQp>9a!hu4b3<ZRBfxicv zaEEKKb)2{Pvw!q3R|jm^1)i6Mb#JME`Cdo8`ZXro%Gd-~hz5E4DxcllQKuy7oKARD zv03Cwm(+rY(9Ol$h{*s18-TBu53R7z2bl+lDo=Q{*ZgoO`*moCbm#?%e}!F;g;{6? zV-ZGA7P)Ci)9{Y)z@Nolo2aKJ{K;pdrS-r<I353oXxAoZRDaP<8*oOXeR(OthHGet z&M*7TcXYEScW_T}wx4)eaC=L~%i_zt9*cJ~p{4I_>VwD!FN<ZsAE@cvpxU=nmO%q0 z_<=m?-+7%BIl2TNxT65@bIErI5t0ULNQYYoh;ZT9v0JxJAi{(Q4JKr`(BMIV-n@15 zCF|lYS*vDg5)~i-C{Q0qjtpt?B+8T_MTsg^3KgnPp{7l%XYby<c{+FU?CJ9-(4azl zk}PWUDAJ@#mojbY^eNP+Qj<3N$YUzWG^IX<3W@bA*sx;9k}Zq#<Jkc6{JFyxZXLn6 z>=e?iYd0amgxIcKl=bT3tX7)>ur#XjFk=6fD>K!aHqPF-aX2SW9y$~!Pt2Ed{-msv zWZJT#N0TmX`YET8p+cQ*?fNzBsFCY!yXLK+Lx*>F^OoBUoUe?sdiAyBilt(a0amYG z&ipy_=g3)RGF2?!x5$>abMJ0BHu&)3p~e6U<KrSuoI({I@BTgfsP-U_qbJRpy1cyi z^M4B$cRStmBAhI{%reV#Bq6q-NvokE3MREYlaD_Y`lFL(-f6gDP@x6jVSFKqI3i)q zk$57Crs0%NJ~+)c&Oh$hmfu|c*|?irbL~akU&I-gAV>@z#u6%_WFpEi)8u1Mg_&{2 zA(T;i2x5v=rihAIZG7}cEvZ@gC7AzXRcH@2-P{(@jcL|pkbdg4vtwTe0x4ulM2eCL zC&f(jO+4AL$f8bwMmZ>yk)=hYSbyddCZpqJ(kP^n9_1o^^kCx+L~3fPkX#L|gN-l5 zU1W(ZpOj?MM+?Ff$|rah^Nf=6$P<r084`NyhLY;KYXDCq^@&%!3LEA)`Ly+xew!*= z7eNN?72JW3zQodMhrQ%dCYhijAx-&2cA<sgiaRd3<(hjgy5t7n&wKy;Gc3GH)j&i5 zJfLw0Nt>`1FTW$odQXhkbh<3To;JHqJJ<N)ODnDfz=<ZxrD~E(nqa~SD#hrjq&>KL z{PAb7Rrt|-EcSb{8)N){Mjrq8j^yRZF^d=OKk&4Z4x2R=TyTzat>Y#(#~k%&05El_ zF-_krS&yMlg8a01;Z-Ori}T4mtP*Z0weQtki|kK5(x~%avO6y;mqXrw<BdA>y!+9j zAMHugp83?nbg|<=y*Gza`y=aoR(q}M6h&zrzzYG?LiFH`m&GDZvRaDiz-FHv7esKS z)6S>V-2KtJfs0NbPPJ-gE8nUAWEzXIj%knU{s@k!<0QTyM6V>FfqU(}lLh%b0mO(+ zL6#do5N-k)H1;*v)br1xp3PGsWu=>ry6PIry1hKyy%zhSlc5#7?<igpfDGl4q`oVg zcvL?8PBm>ZTi0;j4nhC;_q;#<{rms_{_q!$07(OH<7-{_=0TZ%IW2qLnGg54hoJ_p zZZwJ-SpXDOJ@Um5MTbMm`#LB>q);j{_SlA*a(28G`bQwlbH_jAK@vd)Djz(dp#!@U zxd=MxI~I%^1{F2JFKr8ELp<VBX7i42<cNh%d`mdGkq&rJ$aFcpqK3jFD<oP86oWwp z#<(cPN!?>M(nv=WpSVJTs6!pt*al?ggT*;+XN-2dBOb>W8B2BJKX?HkAOk7LxCn$G zQiKaO+%XS%$Weh5q$4Efk;h3=GJY%?$2a(hCN;7!bL{8_HRuz`QC6^$raa}<a59bn zyu&Si<fIyZCJq03FsWpUx+N}ismopRvX{R6Q)GOJ%3%_dU#c7)6m3*CSoUWf=(q+9 z^+rml?GPvdkmOgkSj=s56E>8}$3Na-n@!?~kj&B<LYDc&ZnT3N0chGZJr+BlaBqB0 zv7R=&sn30m#vb*+1~$glpUQCxorN?gCub=SaQ-7*4t*#@BN|cAy^Wt1y=ZLG;;w}0 zrZ?uKi#pZ0M%-ZI9rkEZWqKmPcy35mI*A?iIJlIlt%Y3}y(vyfDAW0Hbdv-<=ueSX zwxAlXS>f=8^8(OFpRAOg+f!Xrhf+1z)%0~vfvHV%s@1K21aSAbR7Zo_Gms*bsK@){ zCkyB;pX~pTflhVn)7mNz><J}YT)it^qmmXGCTwi_F{?<Kxu1i*5i-HkOp|&dJ?q7k zu2I4v4uN952~H3ywE~Sy^QzfOQif#z2v9PCicrB83}Gd;$2XXoz`9;&Cyu?<d`|aB zN4|8fP6G?=Hmh4Z0uLwus7E@yfyTdnl(amnQS+deK}BiDwNA@WYhO#Ke{^h-ww3I2 zZ@b&=aus+Lss}Z|QQU*t#jM8NkLSGA+t~_5x`Wb;OFQJW=7x;B_PuEd#{pil{V}lY z7%o}K8rYGl10A!>PHfq$*zEGnR*rSBb|V$O+}^js;h7CJ_?u3Gq~pAnW1}0X@ej$6 zkEQ>7voMM;s!IKa7r-0-?|?n5Ox!@Tq8~Bw)B2Uq6!SQvWn?iEhnhwi7mOn9v<Jzm zi(`-t3!k>_F_c|1Cg8Rsv_f?;k$Dyl&qe0OOUBhm>I<G7N4d;aqKrNMfej{}Gs~81 z<AEQe<ZFI8O7X#<J)g2eGxK>gD~elBV_e!y`KO~rWk(xJ>a9k)x6a&IpbS5hSu%F@ z$w^`C^(L(p1U8Mreg5>N?=doeta-TOwOlv)h#Pdor5jH)NR3yimeo4i&LgR3RB){n z2u9k|OCd9;gMCj?vx_an8?xmL@+N@#!W*|hDmL2T4FanJny~BgNE%&hqJ$bMz*heX zo`o&$@jx(~<Am{Om1Pj5o<kLq*vGr$tqc6DZH4NXNIL34zNKo9*4}|D)G*7sDu#R9 z2KVM<{DDjk3))5uVWKtm5ea8dyy6s>ggK;*sTHmR9PhxJ;6lco*v%)VK8a~mY5G=w zS1@F{9*fD=Wg#I-+9;hpIL@U~!hBEz8!9B2C)wc*+Zco5``8CRke+mXM1madn8>t0 zJQr}x65AWvVPd1|<k&Hgd)SMrPn7cQu&^jxzOHo6)83S{yr@2Ip;5zklesot!y4Ww zhcom+j=l4p9L{L^(<j35Ptk+EI^;~bd~(TgBsN@Sw-9A}l31ZMil%D6d=mfj!AFLt zTTSecwrz-!_r8-u7vzvQIo>4r<00}L-f~yC(*=7A&7NirMOW?3m3wi?9P_?ESz0h@ zpPa@0E(hxdHmqTH(d(TY{NQ`io8At)N8NY_N#sAiadYlG{&h43UTsTmp#*>5hCLB~ z*ePu#T%Y~-23Mj`&BnZ0`a&Jd-@7gtp$lM;gXyV<di9AGc{yA-K$BW*kdyV0BR$w` zL72+@1lT#!_@qV5y~oW}TEV&B@9j`MzyofOle&e&F1UjyFhe^qU;e3q3M#_sNgn_f z6mgXoI_U>R*n|lonWT9gu{D=mC6?j&L}Y+ZN(~B0n4PA9M_SNS25SEx=B35m+)VN9 z2g2+EJxl-%R0A<Y!ak@V|0#kR_?-(<gn-qEe~}^PtOGj*Ks^{m1V!59?Zg9)5*tQP zd{9QXj2#pDo{I!b6dGSaw8JjELks{w8N7oe#DFq5A2}!jBk;rDIUV&mQL1IbNgbh= z#n%LJ5Bky8c9`6P#g}G)TULz-*8NSS<smA*Q$Dm(8}(s-;S4)a;UEHl4w%ElRa_)! zVJ@CSJHUcKdDM-x+Q)U;q&e0~#o=~fqI1=j0t(!j5nF{+U@Bf-%tg*USPD4MNWrv& zI~2k-%pw5vK|kmNIqJhcID;fGf;qI2H*n5ib>55BNXJn_;mQA6o{@x;T$60Qp=DH4 zP^^@f*_<W12bC~T_)Me0C80kEpV(-lva|yr_JI)i0yqLd7tq5woP+XN!z1(oL_!^Z zG+d704As>mNno2%w3mVn3MPgbHVNdHv>!qWTg=H2J-mZ(p<6RW1VrvaA8<h-oB};m zBmgJ@J#3^pSOXXAg0xi`3lY{fEZR-T6qVrE9L^+GKBKJE13iotFb+^ea)BIJ10V__ z0GuTN2mk<#0X5)<HMm1ZUP=JkTR6OtR6>Qw(NQW5WLEN7@I6L7BuvA>MXL4WBZwvS zsY4(Rq5ufM1V}?JAVW1UgWXLZ7o38$4Mcz`OS7=U8{Pk)SX@!R$YfuB+A)cfp%qkN z0^(uz0aHrb*ihjFOaMKoWiPx!Bb>r6SOYtNLpv0LN3I^HVA(l^6r$Co>&Y2d<fX?z zSZO{dqr6Bay`4Hagkf@lYq|qO=7*b%pdcUvHOK(~2!T7Cf<{_HHdfnZX69y=Q()1Z zJKW`0h*@)HSG=GkbgG>yWs)?213I{x^8CkYawK++U^}#tn{-2Wx<fsjLLy*8V}gqE ztxd;uqeu3U6FEyX2~KEo+jrDaeuik3tXKy^q=^dE=S|-uC_#1}Xd4}9vrJ!boWd!% z0}T-3QQ`+gOrIKHCOj_7*qjzhb!hrUO(_`@Rr3F(h(g(lz(_n;!!GPXGE^owq=P$f zq!P5jYa-}Gr~~q#A(T$(ZpwlT_yRSY1A-bvH&|$Z7?dj(6s$!PX(~nfc^Tyu1y3xg zo}LJc#KS){gB;L+pvHh26aqvNsFu130P4>{83Z~Ys5KbFG5o`TC|~BFL&B`*FPaS- zAys@T=TtCfP}r#t<wUkA>4^TA=){~f?kS)7=^n%Y4Jd&S2!X7g!XuQy80><Z+}r-- z3`B6LHP9$6Y-HxF!&}lqAIyloeaffKX;ajxOOBA}xT>&~PBu6J4HSYP6ha}CK@12% zA7JKo-iA3HOxdXEMjC5wAdEGX0cL`Oy}AF<r*ddn<Rz)*tK&Rgf<ddb>K3*t0SyE~ zBjl>B_JMY?=aq@pz!1_#VhW)V1X%*7HQ)>gZVHH9Lvq?HUfH2dwd%hzsi<WG5e#f2 z$N?8{K@1dvJNT*@64$|uA&$IB8PLMhU96_Ck+WjQJ>Z~bc`Vh$O~{rRwl2ZICPE?< z!WhKBBLq}L^r2VU#X5LHdD_9HcxkdBA3Y$L&+=&%1#Q1r-q3#9TF5~R5J47%K^V|L z3}B|0!mJs(XS&ISH@vH%I;GiM-!?SOmx%4y{_Sb_X)tI(`ow^&%0U}hnG+cjHk?8k z+*@jT-f<QdsE!97_8#D7?rEeMHO&8lMy!H0T&-X=OSRQ(%WmA|97LQYm^11W+ze?` z#9TBA?MOTx*lI5BmW8{xOFmRXc>So<{Y-hPK|9{t&UD-`%9+1@g<Tzm?JgAU=C1Tk z1-o#A^>TwvK;bLJ($uy?8L;fz_80IDAeWJtC<-LBV%7OhFZ(X%HQm@Zgi}Ca?I6{! zIU$VW@@80_>;JGxJHSIdu!y^01;{eR0FT50x32=11_WJWLym4ixRD*OY&O1WfHKkD zP>NVw?gDqPc&r#b&_k+Ou%-y_DX0Ni&SjdYsq?I1&D|FVdvIPs+PbhJ&N@*$_JN_Q zaPh_IKimWG5HRf)a8XDj5jX!%49oCtvB*uLuJsXGLLguMPTLI^l&5HH04uQ;%M9Du z!<FjK_*$_-WDZ^Y3^w$^Be;XS4iq{$3q90>>7ZB=-`Xi|aZb$@J-CCaoto4_@k6w0 zUVy{!Mq-*YOGy?>0&`a)C$b&yR%BojZLE!X!C)B61w`tww6R&5q{B791ASDO;4EQM zh;k!uQxL0#KeQ5DMDAU56e}wPAaa2<xLOs{#YC`^?A+k;#>|wUs(b`a4DXetmGVVZ z2t$s|&&i!1Hxp8!u^QL%7_S2s=Yy=^r*4VP9HSjE^ONkFPMYcQE3XMOm$4h|f*RD{ z)ABL$Bw8rR&Qxw%^!EQwFO!Bg&GQR0&^BKb;4sNQ<S~ZAQukuAJZ|rrl%!hR<57_E z;Otm7k43+dPebRkDe1(8e1slP^3KFEQ?ku&q}oB*pgkr9MVlf*qsX4o*&H`-Z860z zkHihmjxS4eF&Q&|qQf{7%tW|@GjHlS`EaJWuFT={3zLXFmvlngRQnaRUJ+YM!;hHh zt4vd1+&qsSC$1U^vN_iu*2-X_(Zk<x>?o7;sTQGFGsVk^-S(vFN5m9XD0Lpq9!W5= zOeX~%OM^{gG=B(ZLbQV%AguB7#{cTuU6~9v9r0G_L}bLnJbX?7aKj@%wM1*vn1qwG z5wx0g!!>ZS7#9B;AeI4B^7IwMP&|``LNkTm7De+`i8e(vYL6l+*@RJigF6i~?uwf0 z%!+F#Q6_Ce8-+8DuoHqFX!Qv%8do-1bv0zP#`0oNQ@ckS0xZDP!!$%g01(4SkV7u~ zgCs>B;Fg>`aOFGD5;t5AQUK2dv5WkIHh-i;I<yfYctH;AKpMAV@wkIIzous51v|k5 zJxJq0PQ?Xwo1{$``JD32HFu(n_E4`K`2_eK?cp?hL@b!YNWeos2!k=~Nh7sJo{rlN zg)lFO!48l?FEsX2TgW}wggdnN)D{}fve8=>0v+%|Gc>~-(1CCRpoKnNf7K-nee!9P z_FR9%H2nVqG7tkij3Q0!!bhwUbs@M*7U@oqtvrM<Js5%*JcB<JLmIHcKfqA}NyTi~ zOpwKx#I{2s7{WXBgYvz@D#*b*peNLIHdEGHkPXlqgEeXBL^Y5^pUkyqO+!}wgEoA_ zav_<l89J@Jq*%mW^X7J$ffG0U!z9$fh=uS!)WIzH12=RGR?LIa<T0|$EuvY&JDkEA zJcBhnYEr&~8LUD&tc{saZAT_7M4EAO%Jpfy%{SCBF>CNgV1tR%S=%-FNEo_k;L>vK z643&2nmt1rXaiT$!!|6`9PmOW$wNpx1q6LYD`n%<5?@@jQ81W6KVSnou=;<of*Hj6 zL<s+HAqYVkltCZJ!E4geJL!38Y|$G)Lp9i#OizOhA%i^71ZH8A8^*&s5ovcc`&N4O z9JIm-(Zg2e1DAhw*NXW!aHV#F1KGp{8oebQ7=nzbdx612AQS>TtU9Ki0^1s{;i|za zyz#cXMq0c<07S#T&vk`xLp~&fG5AB0L%Kf@`9JgnE#w1D#B^9g)VfS`n7IaZO*$)B z`Zk0MZODTm7=k}+13icZBG<#y`PDkR(KW0=GxS3%x)3^?yBY98y4y6kmVvmUYzzp( zKe*F-zyYAsS%m+CG{l0!D^<pmgly-7F&y-VKsHnKqk`p;^e}!|Ku|uUK`|`$NZ<d> zLY=`ga3yQc5QVsl*!L!lsDsBnf|{?ocm=4H8Uh`-yHe6Xt^%dm?m^xce%~Y9XBavy zNCP}XIPHv#Hpl}lAOoR4{ikyxPIP)h-Hl?`*5^CU_DuRXjJM>2#l!ytFVKNJczt}y zia6xMB=`ZL8#cG&O$TacK|Crin0r5PG;aJ?fdvB?yhAV`D;I3*9sp&m+CD&V3owvi zL4yYoCRDhPVMB)xAx4xqkzz%Q7aQKY$L-(1c<|&gv}bQxfO!R{*@HOmq{(?2^X0Qw z@7uqB)0%zDr;{5?jT$iq6*|<Pzk&7sQKR>7n?HFz?*-K;FXXm=d??kU7l8k2(V{cu zoq6`JUOk`|scIaT@1MVS?$o&pWXK)1ZtB?OWtXlUI&1IFBztEK9G4h{8VRZ-C&r$C z@rF8N$#UQuSc9UCEJ!(WXV0HOhaNh)CA^dGHn%*;a-_BZ{fK>&$T{uLX>6I9qxGmz zxn%MFakE!+vP;p&F~%HNlwLh;hP<4?HEvryr=5!i_*X1|KiAg1Ql;0_ks*2X=usUy z^4>ptHsP6Rmd=_waQE?p^ZTwB7<ky;X(NU<_9zgG7zB9?xr2(TCZB?2T2R6XDXj1! zjbsZT8DmPChO>o6`bL|Oda=i~fj(r2xOt|T<{w{(AtsrAzJbRab7KEF=bLHb@rR|D zQtT|n6l=4PAg}zP#~vFdk>{B@Ch=#RAT83UsHXgwq@a=13t%fJy|8B+dd3;&!k-2L zYAaUe2;d!h+=)}pIp2ZjjDhS~g@zdT<dcYC?8(qVoeJvG$U_lLbV16dfhU%1R1)f} zg;-LrD31Oqr<`}>nI@WPcAQ2U-QLmWw&8q4jx^E+GSosV{n6^5KUk5+o#yyx1)j3z zF$yD=%96*ZXXFv5QmT**z`1zlV5K7}Bg!s-NdvIwjAG^y#~!v~>b6_15HZ9bj%3-R zjdSxrCLhQwEQ(Nq{s~FZdFicJB5Hx#(4TnTeTdoz@r*Pz<+}g#=RFtSq2-)Tr{RX1 zkiOxjsD8>BtH%{t{dLuip#riv2{mHr(ti-~<0h@*iN}j)w37BB=C<O+i~z>Gjw^X! zMT(a+n7YRvYBTx?$(Wd{r<gPD(WWe!Mrzs~@r*vhD4VFJx?l>=633u#*ah0&ufhJB z$9htW$m@rW&4-(Okcp+Ao8pl-&3jsmC*gN?%=j~oS1nV~qJ$NzEH3ZaIk<eraTTLG zoNd)0WaSA~EVAlR+@Y?#0?HnV5kVwgf)#2ijbI33H-LBqs&|k801n&r*H`lFtZ#He zhL(_~i3(bSer!FTSg`Sx_m-e4DjI+Kp~a?Zz7ZC}ZXf?n7#@GV`DyowLVn5mmmC%c zrhKS^YC@{&vC0rbn4;&KamM>+j#lj1^-RC(dBzKyYvYW$ZStXm6?@QAB#1x`bFJz~ zF-*6Rr7gk`@u-gFf^t2AK!tn-frM&cm%$7YEGE@Mk@n8SnS0QpANc^4+=7<9g201a zPWzzK=D`tP2m>A>DvI9%fWxA+NFL{)g$YYSJPcmsSZm=1aHzJgGL=b!ojJ=^v~dP) z!~;EkTguS@NRJg&geBqtm=f<nrJ`-e4F5on%OuhzpU7qzX$T3~5Hb>%4I>TgqKalf zqc?+O%^*fO$=Ng*NP6|iJ$RH#7*8^dcf=w?9s>WNWG2(1e4L{Y{%8>%)q}{9+{PHf z;2QJ%*b>m)j2qubhB+SdGd&VfdusbfK8DeVM0Da)BPkPAMj0AB0*6iBVULxxF^@Vp zOCH~_M-vrtmNrqUC9U~K8hAk#&+zYjOt~6D)Uy>|k!_2493nQ0^&n{c0uPW8m>|(P zui{Z-8B9awy^@g(vH|iTI)TSO&S8vBafyH$xuh^o!MfYz1CT$VTa98t4WB(NSsEiv zG$u)ma+sqR#vq3|>gJ=5E$Srx7$#XrBcAO@O&cS5XG7$%4U-^*G-cw*BupldZ$>0V z{t(LmBNqUe20&?W^bE%mGL>Ql01pIFiAw)+nNFo1Y8Hd2Mt2TLnRRufRMWZ#6K6WS zEs<mz@<_%h{J}h%{Bj(a5=K7)r4t-3#Gfg7$0IB`4K#9bGPYbxFNA>&dAt&Q=OBhO zO!bY)&@(w-ywv2PVw`!D#UE*ShGtBf)z!3QD*<qXAK*Awmwa!p#Ylrc#vwkmoW~wV zbBb1;64ZMzrz24P40{}wx{WcUbv|9{Z7W0>dDz1fkcdXyk~$HVjH4#DgNHVBa!kpx zbRK0=%Q&W&3}O7E8j+pJZTj&D8lBK7C_KnnF6EC?s*N<kWe8`SOSgOoLl|9cQ7N-w zH)1@tCs-wHMV^bE0JLHb<<p`+Vj}+@{w;zJ=Sj~~mYb0A_@kOCO$cd>QoehfVHioO z$68kc!bo*4tnqkcLdsM=U-|0349VV3v_my<_~Ra~f|fm=$~xT67*TJaMvQ|p%72is zBh~xaRm}tuyKYjEG9qrn;-L+j;8hx^^HG_+RS<)I?}qnq)IDQT;s>83A1sliF;2ma z7HMRY#7bBIE@=;}h9)~I^`99HVny$GVIKNrF(MoCA*)OdsjYKKOW9`?0?(sn!lOt` zlpKI!7);9p;U7U%+Gt9R>mS;X!y4MKjNr6IqaQp-C1gX0SqPTKrIrx8+6fv(GIAi_ zFm#oO%e5ZH!WZM9S}!D;vKIe!*Sikc^*K%vj~1;m!w1VpKZF6@9T}xeMRCm{{qc`A zFQ|S2ct(U(Gu*P?!w<EJholWc4?l~;wh0lB7Fj`u^wE_yS_?*-;Fw_JXa^T_@N)=( z!;NM=gBNr_;Flbt6KcEx8X+;SsS$3GqCf)=)Nrj(%Jl7XOt-5z!*i8v6AgL1qa4IQ z0~#dyj<^D@*Fn2f0EkgS!D{cMFAS8DZO1Q14kXKT)A)u$MeNZm_8&VNM>bfzQkS@^ z=b!D#%O>J6;0SKs6LA?O)IFw$WK+p2YgNf{iXLsyA(~5h1{;_W0Bz~KAP!IX*+KK5 zLCEISbd8C`cwD{2g8TowEf$t{suc}tWFs23=7vxq2+3_Fk1WCppS)d8WO&fx9Z7ce zU=vG~wYklN8{HeBN!Fxs7}BamVQd<jLAhwPou=~$a6YmmB@9=@9`7SPb0_6Kf~@u; zF|kSjqUjo|^qXdX{;)x&u?(~iUnpGi2Q2j9kK?_*^t5A}@|gD&gAN5v65}h`wgoWG zH)NEOBw?tewL8(O#gz(^$HPE7j<X0AGK-W+_Q;-e#Qi)UY;e}*l{+^9Uu6+eIxx8X z;Tfc;ELLlG&f@KQZVsG6{o+rnyrh24phvtU=oF%N211Jv0U;WVG|J~67>H)-VIJh+ zM4CjU<b|H@jrjjm5N+lmL;?U32!XnsLWMBGAB-Ux0A~6`gMb>UA_!(jSm+UI$dPpC z_dbX;Fhs5@Y6S7mYuZY@jA0zcEU{Y7Ax7dK1Tb>U;^IUmNn(Z$9O%CcaPAVzvM_5o znD24UV;fZFVOk~)RZBbAM9R=aMPjArv}2FRup!Ds>%2f7%mjS8A^^M~hgz%Y4B~iJ za1kMCA!1_nAi|*P<`GcCHFPjEcrfsSW^P>SAIu>cNW$=T>zvAlb-Ij25Q>FPNDt3~ ziGIf&OvR);<J=U@4E&GwCa5KX#ipJi9^wu0lqC<3Vx`2dCC<$s<{%i@r*g1vvI;^V zIwt@ghUNd3Yf>KVAT&`ATf-kZr_%K7nY!*~cIS9jM^G5?9GNQ`I^q_rgLXs<d+tFe zlE)w50TO9!Ev`(>5~mq+5h`?Iyo7@k5u!}qV;*a0rRa_!B#aLhfr@hRgKkM4s^K59 z<oph9_Uul?#KO=3Nq>@L8|)!m{7bW#30RDx7$66k0<0?T%_y?*2v5Q~qDULgsJoP< zwOR-32B9PJ0r>(T#u5@8XKWs-f#H5Zc(yMRfy_FL;T(kRkIHbyh%6tz%95H#dkX3& zoXh=?D?&tqtK@<4-~m)9a3~Dr&91KQG^6L(KulipNPNX`ss#}n0*-QF4#dPPI_+|_ zFaZC8;j@C#svaW5SmzKBp?sj~EeisU8Vo!*W9eAtW)K1v8X-e&p{Rs1Ge2avZb1(O zVibciht%&LyeJkLPhP5!Ue+(MXa^n~g&K-U`Yx^%y)1V~NX$~=$F{81TrGJ_$knJ2 z80*p=1kgkXFgO8CBcI_O$|7jQBOi9Er}9jQxFjEL%5fU;0`q}QG7Am`(<M+#8^XlF zB=b9+(b4{a!h9u2NX#S<>>zfsJ8mH}>GLe^=os+ew=f9YvL{2Zffj!9DiaPvxP~gt zq4FMSNLEFz@<|(N$j7F$HNSy`Oh^_(vrs}JQbvR|1d?dH@E^F&3+-_sqACB1%|!qF zAxj*{BFJ+bc*Q&+B6Z+0BE$pt6i_-hi!=!$LqqVJD&eV6&DFe<J`*k^2;mi~;Us<u zBdWm$ad2)1^d|)C%4i~Ywx{k|^LM17Q!1i*`hj&G^c^w6i(u*y7vkLRffD{8r4H;& z<pq{5&?3r0$vTHR_)!mG#vi!OjQ;CFjY=T5OdP~vEpYE2jOAl+2!+axAmTFsq9Fio zp;v~KND~eZjzRkXRU%ph9w?DvE)n5)=&R7ok*I_;b`7uMDk(vPB&5+a=V3=4jwn== zE{CT%XR<kI^&tKs7t#PD`j9y9r>7K?AjpOn&Y;q&MTDYqHw~gAaCJJHa~S{b#7mZy znG6CJ5Ta|Ul~RZAsgS`#iccl}!64HM?O1|#QpPlQ<a?sb6hov@5-J|VLGB`g$ZT*I zyki_l5+gn;$W|56Jc<`i&`m3A4yL2BB*H_r&auv83t3QWSiujZQGhIBS}8)M8k3;B z<!rR*AV}dy2SRJGlUo;&Dxg6Rj$y^ZHFeJ6AIvdIp#r;TfgY!gGfXuAn(`xP=S~x1 zM?NAJ#xghkR9eg=OaKlNsfA8W#=&-{%{n3&0Hz9$g&wHEeP$u07L}Q@VIYX<hWr&G zq(vKgwY3QASiIz!D$LUig7X5X*BTX49p`&URs}DU4u#9~PO&D=YF+=-NI1jBYj%wm zkfGA9vSXMgZx+c^<O;wDYFpzdP#VPsozg?Hk0_qO4CE!fsD%b?jTaQ~X3Di%^f5c4 zrXWT%A?)gGCt*!h>U1&kN5o+cP%`~+sKlt{5LK!u07+q^#yG(vdqT{o8fP*M0zV&> zAZl)I&+Z?7;SJ1`B2ok%-pX`z^Xxp7cK+c%8D?W@ZW^A7gcznvN=&rmDtWBTz8sgW z?2cysp~3nzeG8_2Rz?eJgIZXE9twwNgq3GggF~_K4{OFD=*QZ;ARZiU{=W7hG|L3v zley-U8#Aye?yM9cBx?sE#?%o~J7Od*QhCuSCgLF<AORBMp-KNI7<yX*3ZvF<mkJ2| zfyb<rZ`OwJXrg&64jxM)0BE7fWQv9RsO`w}oy-S)ssl<B!YGCp<M?R~cmaS)u7LW8 zfgEy)5;!6%D@@X4Qe7<#5GVxsmm=cDgI7=wU|~{CEU{j=gve4TW%eKH@$pEbHUB|f z7nha1_aAma7)(eg422=hxR3g+wf1!&l#Gc}a5fgpIr5=dI%1Fy0wnz>QhXSjm?bdJ zD<=OzT9c$a6~clSVh~{AdBr&4{$UVEA&f18Rr108>cPX%k;wkR7<OR<bz*zIp-J%y zh{V)i5D8R%HfU)uB5>$S&Y*&XPJQ1a+WwH6(hv*J;AQ_U!j`tP4uWGyp(cv5A#&Oj zg&nORj44yiR;5I;IS{Y)7NRnHL>_ul52&kGM%hTj7k(iE8Uo-b0kMiFLSn}2nDAKz zVKpA&jsaVcs}@Pwa+sA`(@86hpv;n|M7IGsRLMR{Az7!IykuA>3u;WOryO}0vrs!S zwe(04nh^p${=p0u%}d-APZk1O4T2N~;X%Hbw(iYk4;eXlkX|4MLp|fSL=&Tt_Y}1u zADS|!`Wfvc5qUfb9z-*=h|(YS_QGzO1vwPEl%*a`(QFXuO8$WrsQE-bH6iAdA}2vi zO3`nM7#F@F(o$JcMJx@5K?_4SHBK%X=Th75mZkp#z>TT_mr@WabOtYXiy0RJVef$S zNZ}yn^FjVt4RLWG!j2lWp(sQaMuQ^oy2N!;^O7k@9#Uo=JWNvgxEgK&GrGfd`7j@> z!!!ZWPt)lM!Hl|ubj(g68R9CeGt7wVL2!Fa{ooOKJ4a9qYIkD7q(;g+2*y6;WhTv} zM>iV{+s9!2L2Kaeo65v0QcuZ#B6*dvP#o}szDLPmN=i<m<w%b*TPISMfutdc<N)Rk z1_BQR0TQ60dAxFzaGM1UN;Be-YeKkjha0Fca&znOEXvCiajew_)f7WhUi82h{462y z2zh2!uPxi3T{HmB>SSujA0}>J5XXp1k2C)?L#}o~pUwn51Av<QQHVe+(B^@Q8&-D_ zNu%#XX|$*gC!&J7I_eHgk2Hd85{J)(C%-2mLtN#=z$YI*3XZ%cV?_B(2O=}_S}-33 zzFCKQpn(wH;COmu%H;Ws2|ONUbRbH}em~~9AJQenVIs337m(o?)Fl9DC%`E}UXK)& z70y@k;S|onHBzEJ7iv>!p%?0*Zt|F6L>wd9DgZb&Xg9kyB$^i*Fm(Q*4pt!_a(8Vv z2ZG~;pU$K#{^2jvr<+owIqso25%#ikY9QzU$+1qFrKqwYVyZtD$0QOGkhIDbLN@k_ z8uZ{7)+MQcx&n7%YDfnckYUbqP;LKr$5nQ^#ec-r{(;LIp%Dfl5#9h2J|_pmJRweY z8Je`My=)+a@E~Uz?TCxT%z+rrAsL9l9QFz_id}%AD=gne&2m*CsE!c5<i9L}ztYE5 zoT=L!sNN@QtgnTN6w{(b;|xNYSha}2Aj6YILNpD+&-`H)9F;3ZJgd%CM3`3(n88@m zZ|Bs5vFRBJ;DAx_fP@ccu0O*cnimp;T{(V14?H1BPq+$&#~+}<C_1_VxonZTq=SbK zbA0(7guxhKle;L^p;*MjjlmaD8=R<*IcZ`hRXXGI!AHEnLDxJe3fWm!ok2cwR?50< z4~a{-!Leq-;}wEr3;{78TMz#?!yp88Av%H(5Lvg9g5Uy1ZS&z|?fIAdG`;raA7J4P z2;mndav=WU76<{9je^W1d6IK+5cA;}^xzie)nQO)TVOCB<~8CIBEW$D4XWW$PaY#C z&W*1g9b065VD;OBVjLF97v~|$A!1h*Fn}k*Jw}9)&%Piife*SSGAO&N=b+MT0;O)| zStDa>q3ItScYjVATl6b~77k^jAu6JOf~4{I*jZv4o3@@N0ALy#wC4Pt>hEYC4`x9@ z(%m5dXY%!6BF%}f03ralZ=?o&3xF`8!i5Y2hzkIT&_8be{58C|@ZP;|(*pRT)i0k% zc^FHYJc%-;N`@Nk+0*|hjv~pGG+Ww37!M>(h4M(!v#9VM(3A7#A*@$Vn?FQ|{%un@ zZd`zE^$ZzuT2JUsmiKznv&U;rK6yw>)}tryjJAXtw>B&qAm1cE|Ek3c&=&8#qVxWR z4KU6nT$4Q)0-bsBV8(kFi{{H$k=s8)kS6jqs`s%!dDRBJ`bSb@-kpv`&Ls2;;kR!^ zUHaozZL&wUdojCx9Dp-4JkY)kjhoLUH;59eA-sID;zGo36UKW-3m(FXqnlg5u2M8( z;6b<Nt#19X%jxa{tW7w$q(<ckan1SHy=2k673&2kcE+DJq}B7Cc^1G~6{Xi)ecSwV z#xVXM71eQkH5mT@D|Nt!9Yc?i#7Y28$%EN^_gwgogi{r!7gy8$rcynFz(S!(>2U_j zAOYOPkcYEPqsK4sMTOf|ZTTaPNU*GS*<+>k6iq|msWjMT;;c9$VB-*o&_9EaqL_p7 z@fGBXW5q|)YWegMz&uG-h-R8<s+pHd(|iLDJdeD?(RgnCG09Cdm8RS_j47y4MPG%L zlz=GuD3m|+Y~!DT;yi>NW<4>=)HwUuS0RD^oH5&C_DuB89IX8F(snDsSB$9voSBeI z@%&SeNbD^cXgtOpQw@p8MXDhwdd%q0JVx4<olvj7GKg{VM5R$_a9K1NDgNBWny~p$ ziPB?|K{EeHT`#fMV?x#7@e5+uUL+2yQqqc%o!=OD$~oLjGtEumu8D8H`eI~cJW2_3 z&Wt>Yq!K*{dGQQTQJvcmgjFJ92&N1DGnYNvRCKR(Mb&elBYtp953{NUh|n3uNUSD= z_LzJZ%9>g9Od8q*$L>nR8W+H7aaFn4MH+1j$vyQ9+^n@OMYS0;gWxKUKabVS@0T&! z6U{#rUHzEIt8JE~FZtZnBf}OFj8HYZK@(5YUCCn;TwnhK%dgo!cI`akeDlUH)O|>H zu>njYopj3*yKmu!=eu68|Ma6FMgBm|kiiH6+T6zW4ReN5KOL4&9U10JqCf8aLk~S# zB}D&XPyeBuCVT%Z!iSy+<#m={W=w?^b8a1~P(HWlVP8Juuv=s{Z$R_Xu3Qx*4m8J; zH0(|@8J}~R^IYwZV1x$<&FoIs-CR8RtQbw&J&~x;c=7OlQS=(#G6>q&J$rcl_8YEI zRPe+CPi<mfRF8uI2u(^cnZ#U@4{fMLUxi7EKfJJ(-0@^4|8Rtc4(E>yX%2k|IglY1 zF%QY@<R^y7NJ4@YDE6I*B;W7^By#n=EqSCG79qvgw6hb7Ktm6>x=T?wsF2dEuORlI zq3%%96ZXW&K1KoJMRrp@?xe&MIXj}?s&@`y1OOf)`QQD%2u2g3E?(#HVnZ~zpXUGM zMH`_SRXx%c0E4lD4hu0OQEZcxf24sI|G<=;6!MQ*)B#i5tK2+__9}$j<T5>}oyq2L z7AK+vGpw7PLgKNTW%vdt)hP<n{P7DsL<1Ta>s$LE^N&!zODK?wl-nrt4RPGV9yU73 zT?XNcZ=@|_Q7cMCVneR3R78?`afxv#Gdt0oBpQTxg>TUGk&xtOCcF%zHLt0VX~d%+ zw4j$qzQ-=`yk{$(42(Uz5`eJi$0d@Z123e)t29lDVsyDwk09g^cjlvXrNj<_W;O?2 z1c*Q+!4GHrVa`@I<UD0-h&;sS!d%HiJf&)lJ+u`7WJ)F<P}7KJ;t>rz9Ap0+&@-h; zERv67h!Sjc!<O=la<*q$k6~1j$2VR<2yWa3d-odFW4@7(U%Vk7G(1$sfRdyZS?3?` z*y4$>3Du}7(jITphCJppj)PchC9If(#`uzu1DVVv_Mk^So}m`0)PtCA@ufd5HkW^B zLwgGm>oex@$23`VqH}p`RQ?*63{Gffv@E1b7K9?k^r%HmTOMZKb-ZdB_97OE1}qwp zkKwrQA_L3Kt)jHqw^-{j>x;;{>}b8!^rU;s=#&&|G>@&_rJ2fd3A<K%Jat_s8OF$x z^`r`1F!CiH!!gD=<WbSdG9*;IAc^d3#uu*~2oa4K$5V_VAw5}fe%Jq7&{@wQJUjhx zCcH>P5S6<VL<;sF=3GrwF2;uDnlp!o(w(Yo8ly6?4?^OA-!{^wQ0tK-8u=iXQHB-H zjeLV7q=1Ars)pW%;0BW-rQvH&x|slwf)FZf3}(z00Qr4KRag7R@9t65>kv2q$oR)W zdXm@R${2sM^hZC4kwE{^M4(ct5K@Mb21N<vAMyQ1JWvbWs0ipkN<9%h@*yF)mZe1b z`iB>|v7eBs^&e;rP(6@blZ8a%DP>ZUGC31~V}xv`5!Mo{y2XuJ`m8Gfs75s+yDWI7 z#G|r`hDz<iB+L+453txwj8Ae8icqFSOX^8%B9dY39E29{u<8Fa<UHd{<7+VA;Ku&o z5x{D>g{_msj8a79lzil34&R^(soOe_Ml#AOPC>{_TtX7_g67a`GFU**GPH3R%rA7X zuE9E7k|!f1ABw?QLz2Xs+)x%;1rbLzX1TBk9|@FrAZkBFI~|+4aKX(9mz7{KqgK+j z8N5lGodVq004&lZK#d5f)Oe3+<b#|3fXACS6ktsYTqQj<MluLSSCpjTWVs1en<F(W zuhgR$Y50f5&A`XfWgE;g?BG9Wy^UilgpFt5h3u+{Z-gxBb$^h@Q=+nRJ}g2W{B-!9 z*Om|_Hx#xAq0CU8Hp{}U?@G+}5XvcQ(`GK@UPb$n^X&hOA~5^X#CWg=H(IHYhjwO2 z&Mg(xfNqg*5Tec}`9_N#&RMCz=Nv|M*udY8roqsQ8~rE*d@j9`TzDkp?6FRt{6Psb zRAuJ!5XV}#tEPGos&pLWa&8Rv>gF_Zt=jOyZyX6Ar1X6!l{{%e#6h?pnXTPyhHk@= zp@&>u_#)z?j6KBBlYqywOk0n%NpKCyH+&-+_J|?DAtMjV4kFfwm-j#3urs%>WNQJS z#ovAl_vowX8{?2pEa<dg<qqZ_dY{SWVJ(z;*kcl6Km;eLj6W}&Wg%tBMUby+I9vxH z4bQO0T8&>`{p^jt4Ec?2zZp01p(|VUDlQ~#*Wv#U(eMp=a0{S;68=yPNrF7B;}6iF zQk~ZjE@5^X<`As06E9<78j@!hQ4O~cVqY~K(hv(Y!fVp!f-8}2abaBYFdW*489;%9 z$c7U6GY*f!4NWsMb;EIihHLiVITMjr{~&Ylad?G;6iVR-lMoNNb0AR|Yb}@(op&bx z2S^fT8r^dYGDS|9K@pH<L?r=Z5v3ZwHELDjB}Zmhc@Z0VV`$F>gL*a_Em#etfDprh z9sZCE$<PrmNQl<KgY{rz!oUqzR~vH{Ict(N`9KxoR}om4Da2QWc`{eBb07f_3_vl2 zE73@PQE}%nQU76ou{SbXaTV}D4_jCgE@uB5MZtVR^$)P8gQs*p+*W7%*ANwv8rhH# zB10Mv5*Q|?2VbLnuGAODpa<P!NDXmqvsY)HKnfIrC<*}&v>**Ml1zmNjwZopmqZKL zz(O3Na6y57HK9zv!AhcWFQFJUqeyWuCOh<?4fMxJtC%ka^B+I~7HM!6n}b6;cn=LC zIf#HMT!=bb*Kj`dHREGL)leEANH9smLz^*CedBhJ)-&w5Y-3SGY36M71__?<B_U}> zn089Gwkik#4e=I=ih&q`A&=oWaQ6a;r;v*Zkp{s)Fa?=jtEe4C*@$|DSN5P}_V5f| zAP<|^AogHTUPg>-!h<X42dkhB^g#a&O1KD9sAWfIW(`sg@L>i7!z!yNJ^}CwE*U7% zaA$hsd!`2*(_#-e)o`cuDuhNVBqEllG#Ew^4Wv*BI5RA@R1s%Gk+gwzt9T|iK}}>6 zd}$U9rt+5!AsxnG4w*GmIO&;4#5RHRCQ)}ts?uaPnQ2ks6522a!ElSybTLek8~o9Z z_yQsS5DXPZ4fMbbYC#qlh-j)3YtmK^&bEpc5lT_A90A}9$+Cvw(Pz#RliyQQ{go{1 zqb6ik4?#jM_F_^A@n-n|di-dRaA6d7h&m*pR0$WHJh(m}ArhAOnc&E0<>V3YsTbIy z9A{-7`#7IRLK2KZ2dq$5A_V^*qcTm0iFOA07)T)x2vQ96@DEJ!l<!8KC_zFyQxB}d zJ}Pw(MpX&0P(E`RXz5`lopB4a)E#XR4^MIn(QrLIB6|*UFF|5&-pGtW!k6&?AyQYG z>_G^mKvLR+8*rlsJ2DQTbrP!Ce9|$WPr9V=bPmSALg+a$iUg$?Q9G^h9wB!V`ayq& zVn0t9BJY79&%k)amm&v<5FA<~&`=FLWJ<s&N^E!?r1cN>26`Q0Ex`B&ueTSQCM*H) zJF-|vKyqjD_Dz2Xf&LJHaF|TTWJ9Hr65p^L=Q0gKnWf=4VhYhzQt>8IF&Lu}kWB`q zSx0j}@eF3*aw60WXW;)6AvvQoAt(pJ2Yw(1hF~$9!>9|vP<Vk6gw{J!^DEIXD;Me_ zeBq}P;UFIJDvM@Bvzi<bxFUtIBzxE`cOf#;iaH1(N-zo>Q9%)J(14i1t??iXz3>~T zxv5gsCVHX`w15nv6)qE(AML6oUUq6G=Vbw42nuO1ql&C<krxe$j{yJ(1S&a~xfQ>< zqO&v^kf5AD696kxL=`!P!!j*9G*V4tQ7|bEboe-Y6L*AzEJh}8lsX$I`V<I-hsD?< zoiPgzI9_#@BO;-x!AUQ25+{R*uRr@Y|G-;{;Zk_DUeq|BiE|)FND|b55VHV^3yLN# zaTc2dR%<d3I6D6_LSYoQfCu>+f#hO)YBEtcg)^&>tliaDTXDPK@t_Hs;O<WGBEj9I zKxuI=Zo#$1NpLAn(c+~=in}`$YtfeA?oK7cJ7?CMn>ly$5A2)lwRZON?BDl8@q_C9 zZ}ivpi}@D-`Zarpguc%ME9K``Dxz6oM(tz+HhzB@@xNC*=f-P%@kn6l_tsd*#*T=a znpytDM5neN&sBh^?4z6pk!nD(l&faQ>x|mtT*!MQky9ggc?lgN)tKOtyV8MHSii-f z+2q9{NmvHWIwPn>E>*fs(jx=>loX}-&H^TSwgzBYJLKtSCbao&Qi{Z3Ya=1J1Ou+X zH#TL_M>(I+z_Sy6IYGtwwq2cR;2S9It#u$rX~%;XRgt8Zs|j&3MogV5F-a4%Uvc?% zdf3(g^ZEj#7hcWdrO-o)MgV~IA_k=wq8@UuFJg#JEfHzPEW$FX+<IbD_V3(7{h@t5 zUc1Z_9IuFX?g^PdKrHOKlwX3EQ^;}qIe$L-9d=YA?OoR8Wa5;V7Q+0+<2k=Dr*2kB z*N1DR*bKCw$*>SrTsc!RViRoDCD+DRD|nR}E-DH9DS;``JhLW}3S_28=%dnt{vnYI zxM(nzl7FV^61Vc1hX?kd1oAF`XcizVA;O~4&b@dwa9o-D013lDd+|yUj??$F^GG9S zBGmMu@arFrDAEj!8Inqcz??}HFTes44MwiRR`{>hQotQn_?DfJdwGFWiX;oB;vp++ zoqC~_nFeDXFxo5CbgV>V918L*?bTK*du%LlQrBSq5<JBv8?DH=&X^E1K(Y?NsqIa1 zo|En_(&i);J9wSvjs_0O98LeDoI7XmJr6R3G?{6sa@&w&qhRuplQ0n-dv4E=j#Onw z(;_f(V8WVw`++z_$Vab+mNSmLQE=KO6WpKs98WZ7q&HYys*b%+Gsvpq4#0J~#vRt0 zvmzihhhIip|2!_pF)6F906&SInJPXEbZvz_#Q28sL)pt8_)ccT!^OSS5ka$Z#IIu6 zTZuxTWG>`PE%Tr`XMIwCA{M3Z)KPIj-&qn+7x6T?AF4NO6F9iEPbj)G^TI?}Zb(}v zV~So7KmYQrv4)uK)AN7F7n>xF;4A4AMoT8^N&kct1Wf=B^W}Ufh@giNRN6?jfiq^g zAY9eQ{kGn^{W|e>O9~bJu~d)Vu5qEzI7J%^EM{GCUJvTUX$y!(^ua(`m&A71!|Uoa zxt`#kiUf?<S>-e{&n{Tf`ocED^wG}o7GLUEnyaRv>+{@d1>@i;b2OFxfYcGO%sA3L z@1wn=T@o%2pHDFY;=D*S?a^%)tab2w{a!jcdIeo|8MGnL2Y(7Nv)}|s^W?M3Vm*tR zapD@Hc_wZ7yChdERV^}wm33Cyg(l6Bc|tLjfLsL^5zq~~fEdq3`gN@GA?l}z06MD> zlrHeA07?D{DhKq#30Aq<%a%T6u7C!>8-)W8J3phpQx&E*_?Zd$8ivqE_j&Z<>op_b z7NL8<m7o&&I$I~~p1;T;NUvyJahLd>mWdAV9^5TWx(Xv9XPr6-ZX(nced|U^?uicr z0IT-49=w>Enf2qCp7Dl2cXw%l^0?Ec(2H||^La}T#;}3UtimNbe0;E`QV;DW#==ra zE3#0w<CzovDoaSZj_oRZfa61Wi_qp8>yRk%uNHYJl1LZ{`#XI1x8Gx4f&)oPU-|5D z3C`gak6FCydY$p5y02S&x*~64AHR=fz39oK?}JTKtXYAB0Ea=5qX9{DdPE-IAqGZC zhrC}<{B3v7j%<H&7E|h&926L9UezUvZ+!(~kXpXZy{FC|R5-9WWm0}`EH{*vWyDI9 zL;W2P6jFn9o@2=vvUvbJ1zmPJrA!w432v;y!>0A7p6*YRBb0IO%Ekdx65K+L>HIBH zm+bhWdslYVht)+|g{$(Zmr!|1)clG@PMc()-%^0ec%$IgBHbXsb?h~UkM|m64yLeE zP^QmBcZTGD`yA|owod$FOgV{YzykVkrFG^`T&QFfpbHUndYP$lxMP3r+z7cGyLhg` zNY_Vjb`I(jBiNK<(ikgvZh6X>+}+c?WmQTi=63QNhR58J6wPvlo-gwQ{~D$m4^u!9 z4@1BmU(_z7Z}<@j<?a1fN&FO-1U&$pM2QCT+S{9XBEme#P3P_X__`It-M}GO<@N}9 z5Bghl<NE^f@KqV^MKN)5r#Iy4^!e6!;4rH7J{lE~%||xs9-0JhG<)&DAE1^P`j9&; zklFKqvG-8O@V1-vaf6ZvgZL3?{&*Hb`w3Ob^7c*MYgzYDXg{dz)yX5fwWm<#BZj}y zTY})WZ^ZcFQ}`PpH}CP;!-e!Mi7#eM2)p(<nEH3+1;imt%%lKMzy(L~5_dS>&sz3L zSlM$AZjhWZy(Mw$1f-e&BBdcDjR>$i69_EE#X|!pU=+lL6WxD<pkYAJFj3eu8Lr5_ z$aU=Dr-X_%z=?26y3}ZPQ#pZ3#Nq>IidMW8Xx(n@)}ts+md5RTMa|PfGaJ-4RBAlG ztDR66A$1Hr&*}jLmE%OcBAS--yoB-Dtu)$o19rN#KeErf2}?Rl$4+tJ4`a?-pB5*p z)TEjGiXNP1H*sC9XistE6cuznxte+BDC+X8#lsSlFqGhP4D4t~z6Zihk0^Ce49Deq z_deu2Q<((KJ@)tNvbUDE6IZ!8dF@u4lcIIfQH$Qn24K*h*#Ps5X(oILUCNvD@#-u) zfUcWV?L`spY7*hfCkYtkq__-WZQ_AsnB$>9S9v%=h|`9lb}Hnle_op=CyhqRjHBC9 z()GzVo^au+yw3j*RJ^71Rc+~)IGC*qvkDSzx5x_;w_iMtDZ~Ll0}83+E^{*viw<1Q z&oC*438AOL8>zSeGywTQ(CbcIIcOX}y^8)0TZlOfD!MibmUBJEBX`7RK5G~quBseK zVEuYpPKB<kr^-GSH$oo_Bbh5+K!>J$I_1nIE_Nz^RHe4rR9DFkZ{&hAc%k<~SiWx> zdly+S(}JjkvC_Vdl>^4)8O_eAhZ#1yiM)XEyTqd@EwH>P?6~Ow&hg088g>2#Kiy(Q zDX|rgqTdUb^`HAeRRSvEMG<d`u%8_!Eohk%gtdln((SXM0*#c_@*4l-IMABXQI9mg zIo}*+sQf2*zz}NRPxgtCL4TaS>vSO|uf5!Wo4&F!a7@_nr~bU?#&MOySn&SF(|~`s z?}(ecrCOCfs5$(gkS)BLL-J1o4TwI#==iqS`OVWpG?ZZ+ZqS8Kr$%2SS~kiW`X^l5 z+7qeB`8`yGC!j3|Sq1+Zj2UxT6tKH7ycNVr6ZnycA$Q_aL95`Dv{k~G7cJ9W9vm8n z3^$l+qnr+?!eyX_(*&mXKhU_R5L#(I?G7Fo16zr%kr|)ock=>Rl|c@9+&%%0e+(o+ zM{KJR*z2PPAGpJuIX{iMHXL<xZKrsQ>wo_;$Ctq+-gy?gbUK|z&UujHUp{)CK>3ZP zctp@<?bVROj`)^^tSx@|D9+s<?-@mkw?1<yGF2u{EI#w=FaUt*0Tb&D01dzc0Du9Z z=%(lZ5DI_+qE)La>Wc)CaGQ<R6%W86EE*rw>Pv>=DW5y9jn;o0NoM3YH708)9edCD zvf6B{p==^cz;>KxIXb7;EHR2TckJu`)zmm&SfaH<Tn7g$|65ZF*J?2PIsRXo+Bog= z^Ngkc($xH(r2}*`4TwhHsIUH)rk3?Fv-|&>rWT3Epz|M1ZS?&!%jwRxtG$_znuR)D z?KekDUtQLxyE^X9kOT23h8NwP4_Ev1pDe$1cm2LQ-<l|V(IeAWj*&mp^sOfpKtzW? zu7_cgJ6Z*z(^n!xa53w8BOtkpR#BvBV%E`=_LUnkwEss_+eENtI&Q{3H9`LeP3?An zD_IWv>DN>uciK)>W3Spy(-Ljlvc#I28zVLmciMUV)zy0^(}K%-=9!--*RDZ^F!Kzz zW~1P4?u*3mgj|fNIlMd{g&VAQzPnX>1tGTwdxc@x-1|jQ<j(uW2=?mzk_6Gi{f{Xs z+y|xUuY<NtGwrLn%Cg;8_K9_&Xk`^C62+ud@lRbJ^-7tQDy3J=sFh0c&?fmowFYMD zPjXfTx&LoXZARtUN#nw6my@O?`%fo{-fqD=U+}_RblH9pa;atSoN}r?=km>SM|{Mt zgDXV%%;_@QcOR8>UE3?B)B-P_A-YBR1o`E4TjNvuF~4zsQNS1DxfmohbiEj&bf~!) zru9F*7-59-T#mA4xn7QOR@7XM^RygaP6&+fTullux?W8|_iC=DrS6WezR3Z3uV<7f z+^%QUI6hy`X^EX&&+Dr4-Yggxy4`#?a`=4n!_5EWX3+}Hd%N@|%k6gAvEuXXifhZs z?J8`9_ioK+(e3VMz~1M(|3Om|JH6jZA>sWdmD=+fB;WOi<i*aXAx7P9BTRt_S+q$- z@x4;JD=h#&$OkT`SM<e%3k}LVK!DN3*WvPrql7__B=vmi^z#@@m3J_2Se^X?={AU? z43Q?~Qi&<|`?{K`2j}*a2m|gN63+kceml$K-@|@I?Z3z4ma~7q&qw%Cf36ojP=D|D zYEl3G+?}CN0Q@2VP^}kTgPpWkPWcLdv==*0opjZ^2(u>=d;Ox9z`r$;hJA@#%yk2V zfo2VOcP;@rOp0_eRs=+yNAO}I3H9YRjB_0%=`jHWa>z(|QUt56)~6u!97O=C0ND;0 z)McF0)W-rgfHXNL;OJH1gs?Dd3S3NobYsTU5BL29*o-);X0LCyAsAGogWe_cB`K4X z07hKQz;ZbdIYw_(J}Ankv|R~skHip%MDd`@W0Asr!t-G^B)Pqq>_SX&D%6AI81j*) zlSawG**Y(?o~oVbx_G9o=z%HQZvdhjqZHwr>6K<60(7}ZDd^M5;mT+pyVyAG5QU&T z1X3;v7R8w$5AwfGf2NU&!y>>RKc}e7?Ho03VDHJejT=U2r8`WE&jgU1=_8#-!nJ1R zG86w4$WM;qPl;5gSCE3xHRUz*NW+QYu5Tn9qU3yIN^;Qdqv%~cQ8==sPwOU1^k<^h zIDF&_MA?V|NDLrK7=}*vXH7}koCqL^%}DbQV8C@G4tWWk1)Vn*aGr{fQZotUKW=X` z$5}-(>Gl(;g8-}y<I_i;4dj`<m{f7PQHrC)sl`Ufb9A|OP25BJJ2^Ejf`(X=d--%V z(!Hc^;H<KdH<1ZuF}iB59G2JSC(FOv?3{v8v^?k}P1~64F{xm81PgtpRK6aC$Tz^7 zG_ax^{mFvb$M(2Q;*!cCX7sr409_x(cGprH8k`@sCM8wroDrC`dUytAHk9l4aOo81 z_BLwnAWZcNP98lxIZPx4ywM^F!rAqolyl}%m6Nq*iabiVIB;&j0id*Mq&Y}TredY| z^3z3Pg5RxAB=rasWb-n(;br)ls|8mzFs^KRG&Lv8kv8Fc!9)o{R;FvqRhkRYixR8R zzELFH6d;)TXG{O@X_P_ACViA!LYl=H;UOk3sh2LSJg%%Jp|~-qRl1QoN&~v?mVlgl z`7kB?b$%&E1e9^yqF+rJ*-lzrR{H#vw6GFO4LpW(R6bgH+xt;|>A-*%P(qF$Q|A0$ zjmQBPllr}yqIjDiA)$Zv3r;>Ys3OsbNnJR>FW=}pHI0w3cm1SI2t^`+RHOrTZ%<M7 zDW08H>IoSO;2Q*k`JZ00$9<%ijEsAM76+jK%X`$Y3OmMS_lhNTty<gd=zhlcz;%;W z`RT@JyX#|~?KnpT#_J-uEW{cSv|vkvf_mrP2^*SbM|`^fjK#41!G!gYTxITAG`ntU zEFDZD-jq#P-Z>Qq@u9Ijms3TBAs;N4veCbG4wpXO*peQ~V$4P=p{wH|n0qOMR$c7P zEeF*&_p%y)xVS4QITCTY^UYpy4pTK+C%bWGeU-gE&Xkf|(5<^)u8RKUp7ELaql5`# zo<OvnJnkyiCu*k3dralc>|_rJD-DWMg}Pw_>^>+mHTwB|kFs8uiIQJW8R#rSJ7hB| z^5OkM8D{mvxPh2GD?^8haA~|e+`&h34vFH+&u#Nr3%L%aE*BWOyq<{FR9fqSdI`%O z5J(&7{z)aFYEU@Ug9U;<Alpux#)lfcLW2zkjS^d=P)|n}?lI<=-J5RcgFK?u@|cLe zamc4|r`*peYO;#8WwQR=k~ooISmBIL-ICkekG<*>$Q}8JDkc!^^(OH-ZCAkLx6&=@ z-+IFUn)QBr4S18e529#EOAl5LWtE_ID(bMV{c}(~fid?@O;Io|b)v3Ci5^`&WSKYl zHqHMxJ<aR(40Kw+&fFHwyYm6`Vz?buj!s+BZZLHLQL?pb1e_-)riViRdYGnj0Mw!% za_5eq5KErMFm8@7_W-+n*r2MsYe9X(sfAoBv^HVX0~MzUch43TXD>6(vN!RZEIt%d zH-S37Irx~BdTlYh6Tm5~Ai$7+7kLM%FnBRB0{KS)!?**l!(g=RZ~xW#KLK3J=L8ey zui|%tufhz14RH|Xfj4sE-;lW2PzcTf?y@0KBOIb;=f~oJov8{&>-8fUWxd`DTS0=? zbqVmrd;=DlFR`2uVW1}t=1de~(gGp!mu60PHK>3b0*TVM_*J2V>J*_pyR2t>VDt)t z3pwyP8NhQe^s2}@SPb6*0$z{<kC&Oj?!19a{urLpD~m)z+5b^&P$`aLl!4@XEU^@p zo4t{jNXOTPVLk}va@0rbCv~g1f*{rijP9vU6&*pq<ks#(d~p-1I_lp+{uDMbV4?tj zM}nPTk!w~Gub>)&HWKrO;4LKBLKojq6~ZS5X`YF)$g&DrK+qM(r1)V^KmcpKE~#Ry zYRU<ybKn!^v#JX=2YGNAF;6>!;?Dy`5kY80L2jiUKu?WCA8Bn}X~9h5RFM6b7J@pC zU?uce02Jq<*X^drnrTsG%kCYAjl@)dFG>K%8wu7hieR8LM2<q>en2H3i|v3!($s(| z${<Wbvj`|_QYJW50O!1p;JU~foyaO+(352@RLvJm4h4QYk8UqdsLC>^&4yGgn3c^0 z(uW&(qM(Eh6ySIPAPSkf?g!>;@p_iUVlS3_)9T`t4bEtG_!}T0=opyR>PBW1t+?!m zwI78!8_c=k1zmoP78|uzp5RRG9tmZcemdxm1D9quyaI$L`P=<5O3QC@N!fj(WTI}Z zQqm}h%B++j#zY)}X`fWV3j$z=Uc6gK>;)S_S)Ju|1>3tY(4AFsq?1GkCnV^HyHhqI zB?iw43HAV`f%T;Cu=TWi)#1Cu&T8NrHQ><sJ8HjF=w`wbC3bd~N;3@UhB8laf_v}4 zE#mQ!I7C4{ki60e?$m$|qwt5PMT(X0N2n8&IUW$0_aJA_wx5VOn*|UhTt6pRL7ju0 zdhtR*A0GB0cu;-JJ{8wNJ6^%Jr>&qE#>DeQ7x&nhVE??e^LI*FUV>g3msP2@yQ!sA zM7QSzipmgKUC65+#2Qu6cLF)G;(6<w;mHrok^y;KqKW^q4Tw|Cy>pm)#0WQ2z%38p zt-2^0B1t7o(hD}QHw6EUO6I~rpi4IP`uV%2y?nmQVh#0zCpCy_IG_9??oB<GLKyZZ zVUiRzaL69kSxbH?CCgR{_(lwPS(Kj`n8|;MD0l$-^y10}Caa7S1q%o$36StrSbw(y z*C2tnjNp0oI2jG*-{QdYbNB_8yZ<2~f5+?M99*Ldyb&ny<_6>B5IvwSxdk^8lB_D{ zp?OJd%rp`}E<Xg-W7*7IFbau<Rb@uqTuEDOBZw9Orv`Xi6`WEAXE-xAiv$0TWtu-$ zkO5;;M9WtmBIvDEgyhJ}xk<|J!Km}M!A>dff<7`wyjSA>kZtnu0?vZG4ed<9E}?uM zBv|wr`5ybQnmenImH5+U@5jm(V@79|o*WxjtAb6r>OgDXU<n*w#<-BG8WyiAuGiqr zx+;3d;FMiZOmAZPUYVP9u&5ERRnGn-u2`Isd72Wx;jr)@B)!?0Ikv@xkrK9=nXt=E zIqwiz_=q1?S&5IAOeU0Vm|JG*9Q%qoUiSceQ53h^CQgA%S&ni9XKAG5?qp-eGX(?d zH9+ux$c(7in4UmCR2?XU5$v%KW_9_>$X)pFY5sT~h)StZTK<aXRfU;tV~$%y4=PW+ z$7kaJ9|e?$qlMgYer=-!q?=^^jLiTNfBIT&o$ky6x(oG%B(`Nz>KTIx_Zx}Ezfz?& zOh0Bmu2hLC)I_Trpuw<Zog(8mypqWQw~KBJW6@7>?F30kpv0%yT$T~#gnw4pNRB*5 zO-knpw-^B&S)AZ86NxOxOf2T=#n>t|U9hN0{WGEV*OEBzQqq@lDO*iy22v2egHqT# zd@vPSh$m_Tj=WGa_)asC|Bzo|ieti_!A2xHcqLm}P@mpyT78tdY*{!5htz>6u|rcX zVo{K|)fBMX*w@Za^n4tJ(<Uv8G=@9D;ATVc3OjfO>2<J7Ic)^|q+9+=Gyf)!-Yuwu zFDt=Z194a9^7`qTy#&BV%FkRO%%Ae2ju@N+x?9A*Fs{{!d70gwhkn%s-kv{gIjB;r z>VNJzHU+6qJYyKoD0?tb|Fg<+XBxix^f;gZ$F*ALR8i(|Mc#&i;8ukm9SJwHeK7*S z^%O_@+hWgWpOt_q(c}I}!=KVN94SPBHGq`gE)^zu^q1MenUup<&srP<%%~pl9m3LX z<$?)#DD}jfxs4;&AG^*3<Eh1Q&{7;Pd^2WHzdv53<ot{4j<3sJfHvk)QIVU)qIzTO zCCAW^URpVk@oRLE>WzI=Vd^=Z5n3!i#G4%iDpYHzI#gochk@3M*jP35PObgII#QJ+ z#)^-_`KczJ)_PY(Y!gjX|AN3yVR%N)u@rIkwcPYWV{u_F<F@L7@(LqQ7G$eH$|@t_ z)ehBJIf1t>zAdz_wT2#GjBg4_{P{THjc+NE4R+AQxBrw^VC~0=+lCdG>T*ms4aMii z0k=Fk$O$d^IIT4TDOfnv)1$bdauIqT#@8>Bjd9;C!%94PShI2bx1FXx&{DtQ0q+F* z>X>H2OzF|gyUy+iE+GZyHRJhYAwN-C5gBV#Z(U=Z1n|jP^YPZI1pm_JI7y^ngM5o( zDiivpn42$5zlj(n7Fy>y)n#+g_5<9SQ(nJa33G!|F3?w6r!>!49Z!~~+N|9UDIO=v z5lnd{(CL^?A&}!Y5*>1v#iFhwhJRAgbbAYCM^>%C-YIyj`;D?wy}(3TOPnBo0i0wN za7x93bpHaXC{g!AJF|BDzq;xNU4rQR>4kciV26=(UGQJ^Ze@iLl-0<ET*a%_k&I$% z6fi$d<7<9?)51j_OBVJy%=eCR)F*%HG9>H0E==Bu+AZ$;T`!)GZh5kHk6RZdT$;q0 z1^{vK+LI*ob*_~uaa@5s<y)4h>uCYL$aWJiiQL~V8(MU^(T=xPF3SQ-Vu)V{e_0r~ zBmbpzqX$oxha1QzG=@*DiUs7vOws<~?RlnA6DttGgVQ{T$J$fX;g?Xr7f2mRW!XV) zX>pEE2AyR;T4~kWK&cWq3D{$CAuXg?%sG2d6k*<nt+lh|nMeI6CXhX8i0)_FnBVx% zO=9IkwiMCJE${J#5u;aA)U9zP_PXV?1p{${0!l=KeOY)V4$b)wjYw`*Frm{yu<!A2 zYAl%owEOqUNlh5tG?B*0W(V+lIqbo`RKdqaP4w88;`JdvsYmi1A9{f`=Z@2~Z(X}6 z+r0(kJR8GS;fNn=-%wMtS9LDWbZ|bI@6~O1tz~A*9yB-oUCrjB6jUY+xD8!{VWXLD z;=8auqu6#++itFR$zg*jHLYkS_0zv2?;JeXI$uP0_!cW#t&X*<6w!0=EHNXU=D1=l zFXYRW?=R&qlx8zy(&0gUEx0ZBfrixWI+vwH{|JJsXbc}i@lL>JZzpQ0j~tlx@g6H* zj}XMhfZhRq1lrGZ{@aTG^%ekKSxXsg3V$ylKA8S@`Z|~r4lER8s($?p?DI6{o++$N zVl5yGsU|?A+0)#Av8EsoQ>q@BxIYaDH<h_?Ls8)GJiLc$&X#`hUtQ}@mF#ONw#E)# zj}%GFlz~k1o<dRDK6#V4I@$!?ANDKUeko{ulR9x!y4$D&et4GKMrG0FOm`*pjf&c@ z`^gkN`sc_59-r-6$X5r$oGS_3b{U=f2ti;s-(wO`vSuNbQWltld#AG~rsLC<Qc3@% z#W$b!zD}k{w8bPr+EM3YqTh>@9xdOa+N)FZV&-!WG&bGCR{Mu0Gbw|=v<cQwhxkyf zecw2}C9n=isUHZF1bQMJLr=!uyxWwrS-;V`wCh>dn+QTn@vAgl)#4-icZ<W~Ou0<8 z6Z;T(Ls+EY|A^*{v_5%{b+FZw+NY9*eK})~wJ|o{^JfxFR9z99oND}p>+VeMXpa54 zoo4;Qc~*jI5r2Dl-)rr+zzBXz*;aeHjDuDxc;FdZA4#$Fa3)s4HRbi3ptV{$G0L3w zPk!H7JP44QY#Ii*+9hIj)Gbzs!lDw5QWLP0iMYL7j?32DQc0qdeuqh=U(gwJ^KXZF z;E<uq<AI#sY-z?yEmy?t*I>@eJ)HvSxBogRuAdsdEC+7CM;vB5-EL0Dep9_VG^iF! zbf0h-o#}DA{_}wMsDCUE7krNG#wifSrB_njoe?J*CLN5^_E$5A9k3W=ImFJ2XLxSa zA5Fk8Om)2~R-#=Pcu}GK0UD}HWI3F0&&RCv4?B|$@2YIFmx_RxKsVW{98j!a7t@vc zMK8D$)yZR`?!o%AzRVVdO>YL>D0(12`%BSV$ng5I4m;(U|Gm#4W+bt6uCI$>PnT-s zE<z$OO#ic`p_rM}x?w4bIDdAxZAU5cy6fXep(X0P2-S^c6jP)@d{I&~G@Obk`AeR_ zTR8>kdqy96j4{~(7gk6tGJ^^x%U4GQjTZ)`1gRvbqZh$x>Y^H+2G*8Q7Zo`mlL$sC z8#x3grtP+8U8>50PF_%F+DLzoXzpxjjM>pFNBi(bOhG8XI+Ehceolp2Om|+rI)4u) z2@@MSWh9UuM7`G|u(*a(o7y@COcic;*n5uX?k9PXYoLfAVP9_KVsP6pege?|OtGkf zpxvDPXL1bDq$<uJ?owij<|UReDdwGY_Tv=pm?Vee<=raW#Or<f2s1%`QeC+NAC}wW zjTo>{fL;^5Cn0UckWnbsk2*HTB^Dw^d}GD=Z3BYl<yw_-l>(dH>l(iOQ$fy}S%t0F zECy@1$nS>YiAly}sKDq%b=EcZu+#uvP~FSCvKEUx>}ob<sx`T-Xj$f5HHl!Rzs`dJ z3U7xC-Gmlio3gycyOZ*if4KUrNUgxuRXm)dR?x9~VVh)MG^b79PTT#hINXrFRWo8~ ze2MpEb_!Y|i&fD8ZWMM&yq(wC11^1Nxp|pRFy%1$cSH@_Xp`qg+(rbY`~3!LeNrN+ zq2Tqt5i5NV`_10QuMqaUon~Dw<+Tvo044xc6s*HBu$EU+tL<O7YJtOU_Fw@9$)xB( zy;$}AXO?o1)g(X^twjJ*Y~XVyQB$f)%bQHw={|MDTSmILvKd99IRoopGA)sZjZ7`O z8d$%_FIJ?{hc|$CCYc^PJ*!U{_hSIl!aT50bjLHWpn;GHte)Sj>p^G4u7UKWu6#5W zKP?V2&BTb;ku@vd<Fehe5hpA|{B(1f{)XMA=k4utGokcmd<+Yc{sP(x>d=3wY>DdI zRWAXTeS&vnbzw+F#)_2&IlXink|wz*Y(9J3%Y8y75_PL&dzR#n_mL<HpSrpJAQA9t zqB6^i$O-ayMOD-@jDYos3<EEDh|FvmKPp9qc2gIBQCgGUT93+cGEJWOi<8ZljX{iX z0Ok+Z5)sJ5h#@9BErhI|<@f=}KR6Q?kWeW!k!J%(dPM=C@-NXU`wV0#a1(@C=`VV% zX_K;OdCX6l*6~WnZuZ$K^ms_Yn3!0ny75{F^k~dkeR~xfI{VpZzK44tb}d=@dz_&- zl)#wupA_uQH?{$wdR<EM=i^rpc3auN3@i#;aFEt!z%6B(^!A40Sq?0@1^*>CjZvJ| z0y6<$UDPv~)TikSK3^Iwjvn`Nx0@~o{duc3=~X%l-78ODTGSCE|6Ff;Na-kpv?d6l z^PCVSK}7aWiZ$8jir~wi0s8k)McT%CV$W^cRG$eJz8k9Yhc0}wtn*$fvkhFG4<xS> zUDRdxF~-m&UQ*9l0iiQ!gsxHxC39hLj*A9nd!kv^P6P(St!g5t#vWVxwJG5E?sLBg z4hdRzj5?AEu2<$r-}x{t<BMCR?^p}sF~VHQeXa5P@9wjdD4<Abc%pllV#$UTTx@05 zz{lWw^-?dk$ghix&^3$?)~u_^%@<^HDQHx>hw*e25py0=wj>L`^-pC|ahyXwQhFC1 zq>$fI*q$!b3OG*;(mLW%uojb5B2!cfQo-d!*!;%>tSFJWSpuJ$NV=?(VY>mMBzK=5 zU-j%%p)<vVuC0nR_*h4WAhIx<eaQQ@nK>m<2`072r|-HU&VWa%)L88ik^J9-9L*zf z60~Q}mg`iPVzM|?|9)@N4$5$$M}Tn8nE=HsYO=fm*|CkKIR~vVc9I>&mzj&5J6$yr zoQH(Y3${;p=z&^gah|&C*SwB;xY7P)qEpC`>9WWhd>o<rUw);D5l)&g7i&B@%3@GW zk(!}%VCmlLR@HnGERGOBlrlu9m)bLywSqb8@9szXh5Z_d9~+621&c%cziK3AtP^W& zqCXrSRqpa^eE@{{5Q;?e>c|UEnA9ng>fmLCy+>(TvAMiyF(4Xx8q=F$?^%H|9b+j* zHUy$gmL~Yp=rOr^v0r=IbbzX`aOnJ#L*HysFP;y_Jr6dX>R+1HwHuLG@J#g6I%E)Y z|D`q<M`1|a&&t)1AYVWl#@rE?p3G;bwni)g%K$P})Qrtf=inGDZIXL(DiBec$2ktF ze*XFBRoz!3Em{{go2PcHvT2?Dw+n;j7t&R1hGs=_HIOdT4lc1Un<%r$qKJHx)7!03 zsiqTwpTA@&ZGcHB3Jfb!^&@-Vls}zt{k*+h+FMnP3ZNB&PS#X62=RmMm=yJsHKpjX zIYg<xS`3z$B^bKq)C=b@V;;!<fyl3pm_r4>!JvVi`u3l!E&CR2QJ=QPv(T7|wLc}3 zE&^0&N9*Fc5Eweb1}W~pTiw_hc3&0t4z{^%AegoRkZec){a+_KZc|gg#A<a+OHJ`) zTf@MvXzB_;9ZCOQswG_2_IN6tS$|sIrZ;%wJb5<B3Gu~_sPk4k&}Q43U`jZEPfPZt z1)fib_0KS*60enZmu{VNSP2#L^v=J$3hP#Kx${0|IsJuV?;85K{TQ+R4?g`J(CQzK zwX&dlpP(w$5c3Ds@3p_|qhJ#Ltc%SreE52>O3YgKZzCyU<YF{SrG2peW<GsYsPh|{ z{>vNQWo_{aS9>7>%x4uzVtc}i`woRLCgExqThQC<rzq^~>Bbh78k?2NtKpljSKSt& zN7y5GWcl9`>^7}$=Lz8K>{-;YjKcipYk$7Ldov|`sDHK8A`2}KXdyC!fi!|k?_Tz; z$9}FS+`3!u%=-Q{E)Ak$(;1!$C94P8!$gI%u>j*)S}BDKSM4~Za`}Mh7fYC0oLCJV zQHlZ`vzi?yP-)7QPQYlCHALd>rTkKFOG^nR{&|FEE1%*f$e>lW=)C$P4#2rLM(V1E zftBBHKjujsak7f_;FK%G!M&|a2m)~NpGOk1NE(dFX)Sd>+wMjLaJ^*gFzLmVp^RXD zvU2J$=Ov||<JEDP_K74UqGS))L}6&Z#`+Ul<?{hVv3X@Bc%qva{hLQM6B^xV=tP<( z`G1LlZj`{FA_<38G+Jb&MQ;BO&K6fZ9?#-l;XidhvOjT6h($rLWRa2djIs@q14NiD zSaHJNtp{ES<KvTH(bk0<;)x-U9fhMk{*28s3qxC`Ko*1YSjD2F><Ykrj4>dJ2__(W z9yxQ+ukVPb)f=UiGOSS2tBV+Ra*Zc&9ZuN5pfze?YQ@xK9C{v7e5AlrXFKGhl+Zq3 zAn_!9z)C1KMO&?&k;-F}{cbY<BM&fx!}EYcs|~c8jCRxrhdL~x(x@koh#nBZ%ou6c z7zM13w%J!WtXD(DFQ~*BNNPTTJd_d8-f+MYT0{}1<~<gX7W1)$aulaP6hhcHO1)J8 z%M%|!4#RBZ0*B2bOnivxI-8`n6yNf6T4Kog_Hqu(i5BLFopB~PK?h9kqqUGx4Y-PQ z`{A=R(n0`C&AKQUzUr4wOwrMCraBFLPV~f&n6uWx$2J5%xy3VC1w<0Y+LYLI9r2#d zDN*c;HKJh|P?k?{X8QwxRuihl*Rm3}@a>~7DIc?Th~jG<Yi3eap5(UoQ6f4B47r(N zsL?2WB_QS)jeI|xc4=}FU%ugYbc`C0>{xSV6ligqvOQh9ARt$4Ff4R7$~Zl-0K)Je z7DYe{Rm?hW5d}xn7`OM-A|}R#*$~X6PO`2<>7O^6v|{PAcIbopAT`s6Jjzwun8$-U z*b=Oh!3`)x$FkCk<e4)3ui>4~<tHhHLhG8Kc+=*Xy@P|;{t<<i>eEdo)9nE<5kb^k ziUaymUD~aa6T-R~Yf-X~?QS#zX|`!sMezZ;)7NH0tk)pTD-3eR=MfqW6Rk<1Fkrbp z{Bc25;+aCGuCmU-i?e{VkkKrb_!-Z!I{h~v0Gef3`2*B!b&2O6rvnpTRRcft&ydk_ z6l9Nupj9Vae3+E0@{?;VQqtSn8gX%ykh3NE8Zi3{RvMa(ZMf9={N<RY&-Bk#1P*2_ zisOAtx5Qjt@W&{t$y~KOKz0<a07eqN-eBtxbfAg*`-mk=|1B<n7b~65ZajD<!zln; ztM@Y&^$SlY1bT38VAKT2e7<?Ga4~qECBN&k5)1kV!_-mpel5EP11^hY@O$#BuN-!e zfDSDNi4qpe3KzCuw1N81*p^b9d`XUMn~IN4vpV@5#*ql)USZ9AgAN}&EyNJv@2D){ z1j_tx*7HrTP84HIfi(?4TXPZ<-^t?a7#rAvhL84BqbZM*EuQkn5^^CQ`oe~QkfNb^ zMto6P8H9_D2{xi#f)r+Q&O$%xyZ%)5IUfqEDWybP+<6!hW@0sPoMIR<WK1kZwHUlc z>{mEt<5^AOPkPShw$cR>B$4(m!Gd$yGJ1;Ucn2v5gRK%uT;L>ZM#ZGfb3%l}GrHGC zMl5>Z63#iNIxM3Osn{-~6;grk^WW$K4O5Iv5Jnn&e~ofM#;MVXQk0P~Gum00(bMu+ z6usdFkZO7|{1T%CKZw-7JmZ0DY!5lylF{XZrDeF&^4~-L;f>DPfrP6iqTh}tNeIIp z?VQSNlWHtN?cNp=o7Wt~uM&`$=I!`))o^z;c;n|6*3bJD-kKgFOzSU-(*Pz_$F!3Z zjr5-l?6vWXHCU-)P3G&^`V%vhMlqOsS8AsCbobeed@zqmSNoy$;bm*60sLlZmv#@R z4)(H{l6itjfB`5YZoQ##k&|_?OjC>!W4#YYqb}?SU0@|KF1D8;2r{`&rUAeQ%4}iF z=z&#;lggwrwxp}%@jvW;ea1!d&68{814RD`opZPcUu>*?$1<BcM=ZuKc4z$h3q=oV z!qHK~c=uBR*0x@GZ{ftLbwQ@#VWd~OZIti3{_mJDsd!Yurph%^_#+#_C=WY$t{uZ- zh_cA=v^bU~Ae>AsB5(T_(S-bQFShlSIUZkU$zY5>;ycy>5~fW}M+N`;0CcOwvM5oa z`}s5ZzFl9S#VI?+(?*t=j{w7d;}9C9G5Y0vY{R1nZb~C#akYVZi>XoLRiV+q?$2vu z;+CD5y6)g8=1n7R{%TR*i!my!EEcv}dI8DW*yJluiWtWchD3-!-z&mYILq>#pX#oB z-A!fKszJ6>iMC4S3Pe@#W`&xs;Wi)kHDBO|IYJoEhU$4le@UWSrP$Fck|(juglikW zZYv!rW}G!uG}Ry<uc0o`!cNl0HoORACHV^XROT7r#fofS=ZJ6cQrc1Yo*KraWK3?1 zw2mNE!^D|P@Vtln3rJWJE)4nr!PZ}VUhnzZ@A>)dp$QRoS{dk1M%n)uLyXeZ*zww| zErpWSn>zEkVkc3LVwlQoa3<ju1NOpB?7V&qSw@!sjWR{q_*oWy-m<aM1g&9e*9k{~ zzUaFlmLFN)2CW#9?^nrTsQikM9K{g2G%U8_@GO4;Z~o@)$p3+CbiHU_yLms>YC%q& zKv&3Vk816`MGg_~EDS1<i`_3ZP|5UTJO31E=~H|92u_>=#aZ!Wy~^MG`LRUQxfS-5 zEXVl7m5;JnrX}3-w09QCtY_5u5=?Dhb&AX+E3{ldq>Vyw2P!a4==1Pg`s5-xKmg$- zbmYNeql&YIyNig$>Neg!5`okH%NSC>o2gC5N~l(nO%y)1){k_7#+cj^xc2uFMG5d^ zY=5~kcBxXBT#Pwc$~;*vKUrx$S#*a#p;J>4KvaAy(B*W=t@wE3on`ogX}(U5!YxiR z*3sN8&aXD~h@}W*N^A5mcA5LJ`J@$V`m0IC(=)=g5PkRl*8GcIoH-fyz4ADFi-}<D zq`&HiG1I4;n*4Lbn|{#*=h$a$&pmFYV;{y|Aye>@>P5;5wjY|mUa!3NzyJEJ9QW@J z4^-y)0b*9@$5)At6a3_pDTPV%c^Cmoq=s9+Rs|naaohkn#xcAY2p|>`-NHc0%PRxF zIdfMyzZ&=>Lf)}0NA5-<dqD>DnsmGnBA1~A{_^A0^VjuaE##KZIAbuAaJqk^ID~(z zZimr-$+LLLyLZXA=Oy>B$M|AI_(I#-^cCu>2(~pNwhbpxgdc8>ScV3BA)Cy|ePMk! z7aKAQMz75U*FTci!u=tgkCUDrb=a?9F-nHlO39cuPYRlVSN|vDw35q#QE!sMS2BfJ zeDjEz+bc|=q#l}Uq>_v)CtOX<=dG^qE5mDVU3k-Hq)g2+&rtlG-=68njoFi?_F^w6 z_V`6h-3S$&D9~3y%*US*t~LYovbweB0KSD`tKMNlS5M59Wc&q^1i<v}Z9bbxi0kR( zG;IGlN`I?b8rx=g)usG~ndzJ4sJB*r<}g1;ez>aGmfUwY*Gi69_A}noTLzS$HpSsT zdy{Z*fF%|3gU}tmKD#GGK>-XzJ=tMzEd2r<{N4rJI*P3}z4|V*Eo&pW-uBNwj3FSJ z!$0y{?5@mxu|+`s;~dh|nUQqCwj#g_5EI0KZ4dXe)&)|p_K;3Jhh_8A^IyzBN>VHK zNrA~9`TeVI?xIxBirL>}dOTQ$JK>}{<?uRGY23a=0!4JAiS2HcYW-cpd<P8pU5kL7 zzx+H^AEAWzQ4~m^|BlX{Uv<mxYRh~{sa*G!jpu|52!DTd-55$vOsVWJKgJlPEWadR z(8M_RmfHHe(BD#p!Fh^JRh$Q%6wX~EZMZ$|pVx<a<BhElm?FASc?_5UM7aM9TulI8 zkX4<uIMmp3^&uvHyvGNX$9SK_=r(N_^sQDPo%w1#;o;vv4Q%w}B`1b50?lCtsE!1_ z00001XfC=jOBMA^SdS!A)v}WIGe6#f`0ppO;;Mk}bUb#nDgGVw5<2&ei1T;*Il^Do zMLwg9^47&xS%<4UDG=zkx-Ws#Gzz{O<U+3d=S+jqhn?o$SsrU$!Dymh$NLv7qbW># zsXYH%Q{y&la6P!RQ%@Cgn5%KRVxRu--<lennD^0htu^#!?ulnhqU%8DQ~B90e)(A? zV~1(nQT>Hh+-rvzhgJ=o*HpPtq~mr3IedC8O<aj`y5sxR$$xNpawNt%))N6F;d3=| z97X~Dt(oJsOrI!L{_HoO8ZXmb^h@q)@^&D|D{8<Ps@Lpz&AZ(U<7)p6*W0r0YH*nM zYZE-*SZfciUOV|Mc8-+n*|9x7;d1_d++OA~GA(59PtwPGU9OWa;!&)Of#`!ut}av& z*?e-~uRmQmT%0FAeaCrvceyuT%RgVx<+1h4x`Y0g+p7$xXyZ^4@sSkyj#kA?06JTP z2Fn6$UR&%Jf`eZ9WX;<`rH*Kr9>KI}#}NB`h@v-EILClFp0^$PQsqAJ{Ws$iPS%W< zI#^57d~eNukV)<v+{{Rvgph*(83Jg%^a}<J@jO4wY&W8-%p(cj(FH-5;yB~(pER|r zHTK<jv0~x!xHo>{a~jZk1NIM|(^;ufXfrQoZ1we)2%v^H0XY$(3O5XjM*%E$EP+cb zcmVWH?>NB@qxY}9UTI*xlD=V#{sk9|e&7mr9CxzU693GlpT(7{v0M4MJ%}<$@ZY>n zG)Qk568-M6b%f92vq(nqkK;?QP_!Be1|as{hCl*|?_6bi6sDM1UQ5-?T)F)2!8zBx z!Q_4Q+LNXhdq4JdDSbkFc*d*Ut6tTf<Yyd<a<`TDIM<IT(LRw5Mpe#6$mfrQO?mFi zRn0g@Y}Gm&5vJ9agc!c;ZDgi@3NmS?)RHAJER|ipNIA2q)-GzNo78nwx=wMS=Cl|w zr7QlJI`tB&o1R1O%|8izI}}+fSMBojaaL85<+;#l#ra%4OCkAJSoh-3*Gk&Ajk7@e z*BAF73f5qe)Rz=rBBx9DDYx*XuZ2s7(+>e=-in}&8gFaqRcV_!j>NzcR|b*4b$SZ^ zcp@9oXX(k(C{|)cd?5k)NV;Fg{Y{I8p1TB7vn3x1CE%wKXIy@yHY~d^)dg)y4W_26 zU;Z6@(5lZg+822ikAK}hh0=6Op3x4G07R5VXJTmG8kv;v-O^`OYco0CJSrfKY!gHd zKj^C%_9&dqWT09zzj^#a$jUtI<b}#S9(?MN`F)aA`~IG8=xp|n(0Bg1zo@RGo}MB7 z=ZcXKVm$;}H50a>qlF~oQdF~khfyUL^n*CN;zZn@&Tw2GZnRgn=qbSVD<byzmRJ~( zSm)Rp{GwWCw1+J28Oxw`48-xN{7RdQEeORr*j4U}G263n{W?qdZ1h7Fm8%%tF%sK_ zqq;{t!6OJ`?0CU|yA)^Fpxu^<+<d1$gcc+0`C26HI3#j5p9cYvSCeF}95^YSX1JBZ z{psg7D6Uh_#$=F-3&$2N)}2J?ciNC+a8(4{vjhmG4AA4&1GhIIO!f&Nhc6C^V_J3g zx}M`AbAlo|L%Yd729$B`Sqgf)v&mt9;)$`UG(3s)A&Fm^widz&P)F&fsmIP5l6A9i zRW(&Q>*x7N<5wy!Wqa>wY1inEj3|hkldLPb?F4_fjytuFGb|TvP!7*vTd+aAb5=Ll zzI*Z?8}DVo21+H5pN?te&Slqj(B+-04H3`H$DY@Kk1MObK_3Q!Hz7djW9v2#nK>@Q zSmYZJH@(k4Mf!(Pprqb`y8rEDlu)1TbM@%Pm(wpJ*=cuV6g5iLW6z4u_RD#h`pIix zOp-q<-}DCE69zNt<mYR#D}S|{eRWaxF{m;5g)+Cn!ze=K6aZf(r5<E%v(5S&?v#OK z)^VN@P7))q(>ZINC&%)wwD{|+nxdcV#^Vs)OiL;1SBz~5K+UEd?=wkX+kRhr^WE2q zfL8dd+HgS1N9D9PM*QVU%1EiFk4s~^d@0f5hvoDyB%eR&+#SCEqS4$Ck~#~8-p(=M z{9uyOkBs<2Ql}ZANc}z6MVRRm@8i;Z!<V;i00C2QfTKNAq<-~5$=rgf)c2a+APup~ zn?w&+PG~ij-LIfW-tlR8Tishe-MI0>BTUh<WKXz>;*lw>bQxU^^_SqJJc0eRmd>*= z;>2I_6Vv45wq5~BVxFrhnkIE32?VtPEG`zJZoWPLPSjQCbCW{_R2q+?aUJ~nqAlqB zxUYw>MgFCN0~gex58uy1pVwG_?7d(Zke<+N!IQ2!ZI(s3nLCP+e&PysMJV>P2~-+& ztaWaZI8OhB#f)4eYKf?J&papflh<tLPCTKz&ers{?&PHnO&`{J*N{oC@!{YXqH9A} zRT6g==r8p`s`B|a6(MX|HhAn<RftfoqW*&9LqmJB7K}>c^^T@USvRrDN&HynHo^S# znA5Ol!h$-o!Y^|$d8vV4*-YNGlZ9cu$W)2$(;g%zFgdilQB|m9E2z?c`bSxU2>CIA z52uMq9GR*<wabS3ONp_$NxJ8Pye>&d4$n|uEr<L$GT!;|8gY}6tRp5FspOpRM`+G9 z4xe4)4{8c;_M5DTYLd*KR35|PuUaP?Dij?nOD9~YUFE->$DS?DQ%k)~RyjeAe2U+h z%F0xUQcq4+uI~ye%xr3|)KA~KT+plKP=A&PrepCePW5qzOGiy@Mvgs&**}>!ybthr z_i{~{<_KK%X>$v&IB79gKFRH9azE5H?-Q|qE9gN|VYfTCfGkwJWiTCvez(Ha(j`9a zo#Y(@=}i5G3yjtx@HlT9Wr$lw{7(CFUH1HMh}4*+_9@Ue`(?gaL)l5un$${pzyKY* zfDOty_$BVmVX>D&n>joCY4un0P?}&>Dz4Vtf{rcQSL&{2v7Zhpio5*8-kq$k@)--h zyf-r-WH#W|2T3BI=?i^^hfQ@)<EQOwy<NN$LLCtdQJwLhM}&U9qn8lzN8~?|L#@4a zHCDsRx}bCI)r9ihE<=&7+veK8d){Z3ys;k5IQZg+9)bBTOH9~;r05hjau|(7@cr7f zy`4q(UtfYO?jE&#rPopkk2ocSJlx>?|M_!$Z4I$;je@hi__F%7=kL)#<3ghQUk;Y& ze%cF*+m;t}4C~Em-JDiTX5kRwe#${P=05{x23p%sR)c5}h72R7O3@R@RIXm|_<ay- zn!$%GLx17t(vsQJ8LuRt0pH^Y2uPj@6hS+af>vI5)uw@~TzGA+<wB%9v1~f%RAi?| z`Oq0DxnK@e`{pARH5R5=Xr+jcqrk$7QeX~|$1h?KgC^p?F0}ZGe12dRC`}s8gtdvE zt^Su$bb-#7V3NpBWd)%~Ls>{%Q+)Xl0gt7s*;wd|Hr?~I(6d^2v8+RE%@nxI@VRRi zojV%bJ-|4Ju`O+|$*4#%6NWzn02DJU6q$1#6p!EN5O|G|=rJ+qkZ@p`Wd0dY!C(A{ z1+ZlsmNmc-nvCF|j1b1`l~r14Rr;l(#mM`kgja!4TL8(^T@*5E1Gu;0!(HODXH<iH z)Y;$UzuaUmH~##cT5T|rA_$CrnZ)XD0TO@jxy&SL!orq|5dAVf$jhSo)KzvflKQ|R zF|J<Z7R9hxL|gqs$b55f%9ijEg?)W7$QJkU�v;f}Znm%PNX~mWt(HYoUDex6q;F zKiYJ1<jOXK1958@@}jJ|ttsykFu;7YbOp4CK@2enF@kgPjj|ck;uX?~d6j8M3bZOq zt|+V(DGQl9)GgIT!ewEK<@d;i4|qJo^Ff2GVrneWc2VE1hY~lKJ{U1+-$rRv&kH|+ zB0fqiy^*q781}q7FD5}EGm3(UKFBeEVNg+eW<Y9GQK?Ja?M>7IM3bpALVt3g|1C}T zhOPAGs`M$7MG33NHqlMsoc@<l;Wv>25Jg#6Or~56Yn@0Nn;o^J$fudy^SZw0j*3!s z3WQRTQm%^9gSIA*tI!1$hR9$zB|w4hkIl+bq|_*zc_WK$KY9Kr#yc%V8PI@uz&Bw` zIYG=`F-Huyh-8TaHiqG3X{iA!$4IF^NZIp#sy_pwGZ-#jyXLw^%YkToj*)kD3Ur*& zvZcHIf3TvJ6;+`IF725whcS4s6=gcN-AWKPD#iS3+hXTi0V|mI_lk6N5weH@MYjQ2 zt36qxy<f{wCl?hAS`ku?1NjU8!ASIH2Bd|}t$SmjtjLgeueOJFT}vFK@D~+hzlmW2 zUg0XrR+8Lbzln|mOS>upbkQTLD~&GpXpsss3z5+5eN`SSAq6XygzvJH5ljLVOg|z; z6EK+X(Y!MkFn3X$)^cwEjD2ECks+`5%^wE1STS;nfa-(0!mvnz&OO_e{eUz~>DCe| zsYrc;_<Y@L3daE>cMkK0!T-hEeFZfYux|oSNT{jw&_n3G_m<Fm6A%y)2)zl2NRt+t zfK(|0BE4GZqM*`yl_DS_O*%*u0TGsOXLn|IXD|MHv-deOXL3%GlV{%d`FSv6d`Cff zGoY9k>$!t!<;FQ)G_h+PI6yooP`Ap~piAY1AQ}(i<L*%j==SOaot=PqM{kDU)D(?T zGE)Q4mFQYubt$tPhci$(h6uApcqqMXSex?4^M>%@b?3HGK2w{&?82akWL&vb_j{Sz zfr5%WMX@wt$i5){7{w$)?p&AT0?4d7x$X<Gk1{Nn(@<&Y9w3M7r#Yu*5<w+D(t)=+ zTe~8)pyR#cpmx1_`DIsrxq(%BcR_C#gJM^K-^O#wYfU`g>f1L|I-Df>+yt>u*UF3P zPptexp#%r-ZNohi9XfanSH23TD%Gow6mh{ycu&q7UN%qX%3`gAbwUc!79nd#N1LbS zs)I8rv(u?c$(5jzTCL>M6*QaXEt&OsvBsEhU7?#OZyO~@(ks*6C4=gc3$0Wc1~Icf zCF9!dag08TpH=~MaCUb|092VTK}v!`ViQhUvjm0%qUsfrUiYrn@~!SGs4hB&ovw?) zhCeI^obaXV*Nt?PRMr-Zv`3b(nsq(V=NvhOn`#?~Te>Ml+&17{m+g*{JnQnACeQiA zF-$^rbCOCYycpv>{W{e|@AcVr0|ns?P1)-THQba^DmZ+x!UM@Pmj#w-<mVdaGsyxc zP;K%j5uBxk?FBvY|2oI__axK0C6T1!<Ek-{Rppdl6~>7adDmCg?QK0vm>C3(wOy3; zJDD$CY^*kzZvdu10b^8&?5jPU9E`|RM-r9SQ94zwC->~UPSdE+8aEHi8o~L9Z=F2$ zbo-65`OW3pkUjBUr^73!c5CH!$@!>lyHC~4l^hfGDspNtwtF<8R+_6lC$_;JejW?W z-aAnq%K06l-9o(%uUV5bRRmQndw(s|?>MikG5QEu75LnJQ?595AK+j8uO8{`%BR>( zr0BUWxhBxnWVo{X>lgDIZ-;23^6R@Vb*+hxqt{;4a2(*A=c@|p-TU0Rk2}e_CU7y! zy=u#v38$MW<*=A7uZ%Qx`abnF62L;N)n-9=gxnP8S){x@vRP2fP<wIMJ6g-u7xrs3 z`5g3lvGjA$kk`U)Y``jI1sEt&U)FTXdx0;!04LT>Kn)St)4Ox4cZ{YGY=WJ1-<Ds| z5g2B5dJ5j?Eb!efh*X*4Q=2FEeIu?AR_}vV<2@CFyg1Yxwh(OV(##Ro23sn3cPVia z<RUPoV)?rMWQHG#B@JORjdci)J<VS9cjX<EBsIHBHL=pj`FYTwHBVJSm&COw9mk8y z_dASzSu!t;%PU`T?(hx0xbD_3_r6)#Rv!U}m*Yf-T`TuVL^GnHw|EU!(liT68MH9x zn7iWnQ4_yKF%L>0RlCBse_qI&*!3UFXphLy5O~a@wBAM)^%DN*HUN3VxN{R#y6Y+v z##Xo8lzh|}9n}VYNBeWTFoGk7{J!P54#->*boG4Cw@n(0xq0CPrNDh9-)Ih0lyoJp z-ZwF7>btBN4o%99%F55aXl_vydGdZClAd}J)>vl<{i@gw5^5uqU;G^Cpj=@kviuMK z*vXD|7U6`;48NThdaIrWCX%jo$UmaF?z&kdONDdEO)jgnR7>}FdpPSVzH(c@{I;F% z!jp6v^ku!RKZO3h?vgOu$r*JlFjp)26gh#D8h(D56jsac6z!>6row#Ra#h{p&+8nr zE+utBPWzS;^lRgln(%m(n0B=yQp+$)O-`~)#RnuUQ%{r!R_DL@`S9`+c6p%evUb$T zob)s2^sT`-;o+wp(k=`qBtT$TZN9PI(9G9-NL^v5i{f3Ch0J{^A9cwkpcL~9DS<ph zqS4O0XpQ7fZ5T+0(5<rIEdEGaf4xgGM@_D<BFbf3i{IH7*#+2Hmq(nfYcy!R`Kg78 z(OqY^#rY`@;{^Ko*H7`v;GYyBmRg)||FJLxs0;_*@wR^;Q(^I%k?F2d{FA^PH)Z1} zw#sIc(9H+muDc7v)TEG|g0lh!i=F7%Eq9OT=5-&y!n*yW`VKr>^p~HatRzwauY3ZE zc>wC*Hk^UGD7F(sPj0@JyENjZ;t6;iNxV@=iil{JQlO<#jYL-Nsf8CoX&eYi!884G zJ;6k2kvz1x53W8v)*s%EiYj(gdGTt#F*SWhf1ygr^MNzZS3%8X&6Zt~rZdFf9YINX zgU)pUXw(A|Dg_~bwYSu4JCr0r-Ejp?ie_q|SzwDF1cxg%@n;}uS2f9gS_5*F!Ea&3 zVM6?jTD|QV^*<<6cJvgQAf~8l362sxxwT!r1_5c99;h<D@>~0Nte8(a&&s=U<|A6{ z>Pdbr|J3ZY3X(%KZ-~UGKJ{1h#|(Erw(o0?qkD_v>HPx&@5!}nZm2AEvc8I%*t>YQ zxhJ4+8N*7bW;vN0H@GTx=^!Bvo2syCB`E55J?Q$WI29z(tt#%>?chAGWIQ{?>kPjI zTA?_5$0YPiI8ZL9OF_R&;)Eba29h@8S^-PlRpt(;2)qo1aQ1c0nC_MSP%lUFFcWX? z?J8jU-x%erJW>Ja%*kqD{c7H*zSs>U%7~u(0%Gb03UuS1dvgar0`som0A!K|SEEeE z)E*GQ_*3uDA!*6PCyF$0C82*LcSU8OC@CnnM1HZksghQFii6+0)t@(iMuS_PM@Qej z=HsJNmO*XHJp+m7ugL%H@$gntUT{gEUJd+Ott7eeEd(5M=)zn>T^`5uVrjiaM&NF` zhv;ym-sdnoeGlQYPq+Sjj9_F5KZ;}@5BtzcX(&lpAjoUXm#Sd9n6L!d{`+*l_f!C0 z{SsB?U)6U=Y6d$&Vq^qKnlmp`kV64TYWJ<kuN6(yh8&sNg0AIGuY_(p=Xkjs*7Yy< z{l!MN!`+GP?EATj;Xw5N(A3V4+=gW0zJ9*{XMZG*)WlIe7?|*)?$MVYYKhbu32Sr! z%Hr^&-8q4Cs#3+EljiTo#ZT`j1q<E#bixo}t8C$a<)tU@%cmzYw#o7$xAFRCi?0OF zd1Rp9B1Y{HeUb65$+{8n*@gu0KGXYd>!ZW<>DKJ~fTS=Eiyeg=(dEy;w%%j<ofmDs z96G9t5GqGQ!og@yvC}B?>zhZnryjhBRhxom6>f<xuWq-w|2T?CdjEh&WB&Mv7<ukB z|M}LyibkF^RY|}5>QYbC#;<SfLFEvw6P>q<pIvOXy-H;6?{%*nxBSzaoM7#rzq94m zHt4@KG&lL~-)aLdztYQbql(AcM$9a>=Y~h_0&lmgwDJJ5H)|-9qYeFy?>8AX<iqQa z67m9j|8DSRGbZuo#@P*2v~Fq(PIOa~e<SDkVmHAN;ktgfAxh)MIox<3eXSZx7X;r; zt<4wQ*?ZwP7(~kIRnAB8nxTToE%*M)lQ^+Oto&~C2hsYCmu^R5+|PrS+(uu9aITEJ z40D}3%Jc1?GN|vg9vpmWu`cS~)sHUTWevI_A7ZOoD;}2a*RAFO*sPyvVc2-Yy+-9M ztjFKXwH5C_m*^d+XwO0^8CBQr%8kEWz&J>XzpVe;m*lX<=flYyq_fIq;_+&F=8mtI zsWdZtBxk{WbqDdU_Ci#A6^b7nE2lQ*1?#Y0>H@Ls-abPcvpVdn>v<1`&tsXQhV%AD z9G*Wk?YG<(bDeO<FL1wf{J>&Z;j6dM%O-DW#TRkPxvj(MYpjcB^`f|5`>ND`<lCLH zyZPQ_*cmbU1TAtkwbSZLWapF|+RV_$bxHEHvcQE1>pu5^^J<IDcHOdOsj2cwe?hAa zXXfk;Ha2IHy-2piEwD8r_jPbrEIv<b@kt*#RcC6l;C{CljYIjn!L2;c-Xda#lvwIN z!fDv3y%(0np2?WamdH3dw=ky$gIk9QlQ+-)Px{v$_RVt_n1{=|btkBcTTLfZ2r}#| z{u&s-Ctp>?DOBGZ<Wp4VeiAod2u$%+2_HqvRm|<D%f5vA=31>MpueuaymLSn!6c5L zw?3Wwo1i&yho&dvG~a2E)F8am-}}$Uz(lRR@%+Sr5ktKA7@POyHRU>UQ1xM-f5NMM zSe_*+mwRD$$Gxh3C(u80v7N7U<E6$~tyb$_bh#^ENJ6A*e)yY;L|3oNDst@E4%M4r z#c1<qKsF7iJ(&i>put1FsiJk!th41!&%+Guednyt%U-F3M~7OHyODACLe(_SW$j2w zIjD#<elcI63=55AX=|Idu<P2rN|FxkB&<+h=U`HyM)uUuP)GMC4Wyb`97zBgAs#yY zW$i1IB*`;8>(}Zf8|d#O$ziaVcS)j(BprSK-9y%u+EE4)3)z1I<ye7R1Jc{e)Z<Qu zF{^+<6=wVR&p<B$XsMb&4iRM#HqMOEdI&{ZMoQ9~n)X!vI$vdlJ^2n8E9yH}#8J|a zQTvY|b|`Dl(U6_**}kfS|8jRaK^hj0HgKD)T~SZ|nX}N1VfyWwT%f#F7&1GA$Ux0* zjP?m88Sn6)q6)d*t&my_<8g-hgZ`Vod|r)%%HbtLI+nh1DsDd`xD(@~+aj_)sY}2v z)$-AIXepC~{4ljB_5I=^QpZYad`{!W!R28JzR_EUyL&<DTs%9a@JSS4IuqBMmgIOd zh*AH1wa^)q7e=PWbkMJ*^xTngNF6WLx@4keB$snG)g5ULomL695<_uwDP7BgM4(*g zHvKrp>zppZHDKRkFAYw;i7mrF8mZx?KY4ziS!`U_-|XkFsXq+EM(+&bDXr6-1OjDA z+M&7T`NW1|4QR0B3`X$vX^-UjnZZ7*yhXfZAL~M48J5)#%k%hVls2$C&8Dg&Te2^( zuCP}&qDQc^kUx20Ghgi2X*%sc0`0?iiiI<&q`GI&=i+Ol)>Cn0YK|M}W4qt16Vg7N zGW+BJH=XYEol#Af6`{mlSA=2wCMh5G<x;YD3tq90j#g*BBltd(O)>enn6)YXO0r)d zBrhj4Uk!DKky^8xKkb*GkQIs8JyV*v{726@*x2NYN6x5t`XV22Ju>xF?ymUcLpN>z z!4og+SoWfu<bc&HA6dxSOq+`0=TcM^wpIRl9k(#&^f{KXm%%1|R`&5W0+BXlc53xB za4MjMmOIIVC?bhq*&_Pq?+Xn%!3MK+0^MwCU&b1hLQ?$Gkmgc5e-4LS9<DehBaR|Z zZFO<I09PJgQ#P$6DlLjzj_?+;HCy$1KCj`Trn_xJJDn>Ze14X3p5~-#UcRR-)#i#c zq2$z<(iW>4euTNk#wOBC=G(-!bdDdAN)iEJ%bhtRl@b{GJC+D}mubtYB+^{o=eK`q zI7^2!SZ0r!H0!5Ps2ECom-Np_x^=lKh0@!(3#NG~obp`lel<tvOkW(JowCh)aKEyL zI?0qeM|^CaOhD4#@I!Q*e_7Bs<A=9JrLRRxl78%^7Jy5YXGS@&DMj=tmOIu@S~M`z z5fV1av8(b%tx;|Rq&xh2dzUQ(_DMw;+KQ(o_xPgO+oLOWT=JRQa=!`xF#bMklk@dc zp%EtDj%OjBJ4KK9i-4Pku97K6(`BZIJp&7t0hIClyScM$*J<8l)WbrShWs6~;%}FO ze8AND{r{@p7I|(rWavlFS-#LF|N6@7^?tO`=fIm#q|~o%3N$W$k3ILw_r0FT5c<lP zEFJwidtFeA{f@4j30FN?z|mBxkWQBb-CR+Yc1$U=){)b6cKUrfGL>v)a*<6@cvU~; ziq1Ld3qP0IQszo-6NdUI=voS|Lh`j_%^U4zr#F5{g=M#&H3lvU`6WDH-i(=qn*wIa z8`q><r9XDaDFRxv@#n$@bdUG!D!X7JXVKqvbo>@V7*f0{zhi2Jp`ncva^aPfdf_?U zU(Quu1SxhwX$4w0EfeYD$2?a(54GNE`uVrlm?LW2{~q8&5rl3v_G0pj#*yC}sx1e- zD;Tq;&RhO3Y(AAf@a4iY<9BQFhS}7tifsp))Z=P*gQ_0)Pr@`VTHE{Bj>Wil`Bc#% z=W(-KkYC%Yo9uy+N{hnA6dUbk)hVK-VU2>1!0>bFO<j_%0Fp==8mF-%IHx%A;tIRW z+F0idnDr`hfzf?1s{$RYrghy6E<NeAxx{_B1nQ8$MNmU^Cq%h#hIygo##i<XNWqMp zD#s}HPnyXBm%y4f?BINj2(v2xcA>XVv2dk#!_wwUa9<dW9>!YTgp~-C7cIvd746-7 z5#W*>;4RV(WIO;c`m8CSMa2cX*jj!v?E>+#h<~w(uSYoz6bDL&k;K1>x^J41P4%*~ zjC2?6-AZ4Vj+0~DiwiHjDlat*6ZCI+KKV=2?E>vs+>Ir_yUrF{t9%9b1;o;Cqh%<z zH;>pKS#q;oq?&{dvkpf%Rt{nuDKLeqL+dzLRZ-!IYS0ZyvQor=E@rp_hU;sciO1QD z`dF6lUMz94RW8G>mpsiDeXNFK&o4SSoYj^ElU$SaJaX`d`ObR0My%+Rc<xo!*nPIP z(trCM5T((uUG05O<EN*ul9M{whE-3tapl`&)82zzZN*5$x|L0J)366?St7SLQBJNH zp9LicNh)4=aOUVfGc?Ajg|OpXJM2(CwaABYE_Px3$zkLdzrW0eE_w*YA&KmecI=NX zw-hny!mmVl9;9!1`i+l*IP}Vsx{DaQJM2GI?C!%c3py=mRaUuO#ieBy)*^-EFK8Hl zh-)%kV2Ov18*45;qH&CGtMgGj?pE$9-Cn0a4nLs480FHBRvDA;9v-kr;A?l|V<zPr zgJCQZ>960!xmkL1kcf(;90^}J{C>5%#aQwDZ1d8r&nRl;%+?_-7AkaL$Iz}P_<DjZ z42ZbFMXHxk$3VIzJ6hLz?%(OjZ$yeeMe^PQNk2>b)X628QYT##3H=ilOwvJL@K!i& z%p{-#^`WGKqP9~IJW*U~<6J3sgd<LYAdZV+v{6y7j@B&huf?j8CQ@@(J9XYv(g*mk zu0+<+kqkYn8#^nlOWOYI3Ch=es!o@*EFZ;{eBa_~nVeLRuaHCKn;YjNen#ygs;GoP zpH-$ScBUl&9Sx_h|0+kY6Z*?rQ3prf$K_n^$7ByUq(Y8-V*6bRB9Th~ax#0lSgM79 z#HH)%NTe-J{mmiQ3hscUPCi6HyEhi??PkP`S=_CDLo=cI%qTM$hx(wUX%zcn<-S7Q zMrp8HC2J>l!of)x1~5Ceops17{FAjnQhudNFqYraud9}9UD$4nesU$sHWFFg!G7eR zu`*n}Y2R50`M3gPM0Zf52V`zVTkRGFUjgYB0p!j%rHlZ&`XVl$ZXRVHmPk&;${R$6 zn$9~CsW^$Xmyp_`#7y}xcuz9^IM6J&*GgIIO%;){9Y^_eXZlPDsE_Ljl2U_o&o|w* zLTE(5j%}mpR86r5{CFqF7+v;a?0($9xC8ly!GqI7egM)B<vPimC>lD<7Fe`=y;f5% zE(92dW0J|Vk6d^n95K0Fx&AxzB$0EolS<>5n>i->T^#dxy`y~j%@88Uq``8c!RQc; zvj@_J0qL-kqkbGzdZlBXgok!O#_HAhFd)?;fDZjk|Di^CScgb^!mT?~To*W0-VrRQ ztJnd^6sV^6fk?U(hoYJY(dIPNFh*VAc;cmQfCS1jfX+SDHen4R%U_qh%fdsA>id;& zAKa}%YRpR4@9h%xgNlNLqEF>32G5%;3L}{o0m6=Sm@kIRB+InhMK4P|(Ca6#9Cp|9 zD6{G!>KpH-+rGyRZ^Ukotc;w{2Zy8i*phJw=!~BONa)it{n8TZx}d^p&p|`>7}gDp zwr=E`7>Xgn2BWLcCh1+0qHMkEVpCA!+ipzL#74hY=&qL?o|4;59yK9j(06~^t(2Cp zqv-($-pNr^XYIy~7$Xh`J!%aF)NM@v{bM4uyMu%=Hfn~XR#7m%-0UX<?;4vD_h<fM zxk``-m;j4w&?9|HLt^jzA=S*e(s7%;V9CME%tW2J7*u1AL<2dPH$<ZKz0&|xG{jl~ zU-iz{=uWWAh26ms>Z~mtb0<qE^=`f=)EIOm(vO}u?mo|anwYBYx+7FO)Ac;!C!1OG zYX`!s`DoVw4nR7AF<G=$mw$4t14*}h-@%2)U5d@Q2!6f5quSe1;W^m9RCzbtq!!AB zqT&*8G*J2Ejn||%EPmAs?(t5zox2h#k2%CSf;b%czvT#FUO6d7{*q>YGxkB??&|i% zia*~KF1V*?Ki=#S=laNzjICZJm!RakE8wVY$HQl{`zOVW>vW7$QLiKDYYSZ<iS=<@ zM?Pv9$SIkp2+Q^4ojC0(pAC%n^Bq)=Ix3hwQ=k07XJ?z1(huol=%2l;snZ-a4`QV? z5*u-bE2<ykRdI}u1U_}~PJy<iqunpM5xGu}_*zKzii`)q4oO^i{T!x+abZ>m6d-kt zvy=VmQNrIq&9!AFGf5d6BG-6Lp{WDZ4Cj1xgYI?GxzwQayU@;=LWW9`4wo~q=iZII z2cSENl|#L@!npC#mc$~sC5L8=B_}&YslG%}M+;@XgO_Xsv(sGw8B%e<yT_6+(1)mK zrc!pg=5#pdNO%-mk4oPn>&6}}mz|U)de35$I%AGimsd86ibf40OgT$cpR=atZ9zDW zbP|rL1StEm%FIj@-vyvCPpSf3jJUZpy4ltPm=<!vVD!GTCu}+Purj@;5BY@F*b9>F znGY-oa=$IFiX>{5rK`lBJ#_hXRYb)1+OZqQ9Py;|hd!&L-#u`S0+)l)>M-l}8=I;T z@PsO3td$u%k~6h4CbWXNKa%;PDAO8aa(&(@zNyQUx-R!%i?hJny+<BnR<S4VJi&Ze zMP*nmG{mDxLHUV~2M$U!;~{r*<a2N~Pmnoth^p!)m~ZE3`W15(F2jm(%zoyWQ96WA zg+F@3T6MDeyz}wfvlo8Beq$V2-ODIj^>=T)?|rg=ne{V^&5hN@&?MJ4)>^fuL|S;< z`WrWb>6EwyB4eDh%7*4+-3JDvo~w6DDCX4M{}WZWjwT`1bF$=)ndVhARxKr`srL{q zJ=7d?%u$U<&{Rape@=!s0*z}ma917u<*E)x(g1i9KqohSL5KO(-{d=R#Qw4x=OpHn zl%ijU#_)W+R(6e-R?2ko3pvJ**Ofc~Z+i!^aj7iRw|pyXq02RIzD*@KBiL4q@u8R& z_C7Xd4YFCb-f~~TV9Rk*Udj2=87V+)D&GOZ(Bl4y^jmW>YAsq$`_T0YU2yJYBvs+c z<16Pi$zI+I44Y^xM%>jo;iB1l1<bc1Vxxw{HtZI1$U3Iuq%vxXaEP3u^dtqo$_nSg zjdaRhS`aq4AzK0Eq>&)c_KM<FgC~D=k>RaCv*wm}U}@j6BH!V4_4}6=qT-BeMd!5- zZI?959m*`<%PSlKDfw|647_Z)r>#uqQz;mjKZCC>)8}jZNlvFP0=yqDml-zOpWW${ zj3{QkR8y07e3a2LJl)B4E$eRO>>4{>tl_vfjwk3}7BPk~j_Sq*A^X^?+1XBJUmfyz z19~;+F6>C;7(d~no!1o@g;+%f1upF&?<0K~zJecP7`^qHGTv&aNXab%eFGj%lCSEF zF4I_7B{*pLnX*v&aeVmQU_jCRU0Ot-8ie77z9><<_PZO|h$lDc34o|~^RQwHD;}&w zMmoo{ZfbE!`myVj4tIRW{>t2@I@vVIJi~|iRx?lZD3pPtbJ&J6nKP_hWb}G7aZ%ww zzkzN`z(J!02YZf#8eDyNev23uM(A{w4U1<?U5hB-0*qqW2lltIc^pUViE)b-{2D9c z!c`wue`q`Bx`LIi`--@)9OJ3Abe(?s#ru;!1Z9oBbu2D=s`D#XrBY%pZ0wipOL+-4 z?}kpTHm)1n&B1wAEodxz`A6RukdcD(#o2mx=L`66O`UtJhD?mrhuc9loY6IG6c}De z*v{9fmxaVHA9xge3u_V*Fg#+na3*elz;(P1RN(J6zf)dY0%~NR92XH#e8%_X?+QCO z3A500Al5`#QlRm#h)R2T?);r~0ne?b)@a2Pt4_5P82xyjkV8Yx5$r2ZCxM16GT2h_ z=^YFs&Es@H=S!uK<8@+Ll-*K`?-5a|yroyc=g@Pcbz8hxN$*o;h2YCTpIn^VVdG;D zOJwO_rr@0qq1RhSiyvbSuYOaX-nVWG62EtG{72jg5OlQd^*5W_@>6)nmrDg#q;p>k zaC_iCxvPq=5~cg!I5HD}_n*=LLDyd|n<WmxRQXybyiB%GP`}{N(I%&gJ3_Nn)_Aea z{gkBRg5HRu=jG=EaQtb8gI@Sibw{<Nf7xgEi36-e-gv?HtVEgXkYh;Y8bDQPCc13n z$8-YyjSS>2v)K8jFy!ym+1}k(u|LXTp8piyAN_Q83Y(<+HK7pn!%*}0*)J=A*9npF zL%tIiK=AcV4&28daT@$P@XsfO2g@xbVceO_{fzcK4!@C@KL%5Qz?{P*mEZoi&BMn6 zm&c_4#WY`kQ9YT;$dPXR7elFWIDTrRPW;$1)$tlhG$3>F^Z1_T>vL)Ysry*`itpDt zx=hE+AX5i5;}J5dFuLb~Gm41=9B{q@vka65O<84{;vx2!M2h}(GhPaaRV8yEH5stU zcHVoIBzEP~RhI2s@WeT`ms2fI?^>Io&`Q0mXGF0r-j_rG*4g8DADxh4WO+WEWuk~E z&>1s{MIDVvpK~#`V`7IJU`oCp9Jd0n4xG1iud!6^GSdJj6OYqPUx>s0>#1?C=+vVz zna8Z08M3F6<s+5UO;uE(H^WL!%Fi@PNX1L$V{YqBBaaeffoGsyTm<V0jmAXz6EDpJ z!1T3I-dAUccZ<@z#8bn6oK!~dm8GjVs>tqAWatCGWTZ&Ll+Nt4i7CyE0-)AsGq`=z z47Y4`t_uWLxMaLt@#%O+g3^g)HAl@K*2dvNrseE0k^5^8JT>!J2&CzvF}$x-SV;?O zG+pOzQ9n8NInGl=Rja2dUM&>I$xd80?C2g*F^nYsY1#P^w~&7dN%)bFxaa)~>Xfdc zsQUEb4FBk@@6B~>5~DKXQ71;ibRA4naimO6H%-5zRThkMXdxd!iz~=H_gN78STt!} zg#jaRecbDi^L}}}5tD@~g`{gk<7`HtC;?;i$o}M(<apre?g!Jmq&1ILTNKA0abBri zTht3uHl1w!2n`v+`+K~2{ouzMAxTt{iHC9T(_dkl!ruIh94!_0;XVv`=g)6L>K_$% z?)Tl77-LS9OeoZF#@D2(xY6Lpq&sKuV-ha?Y8LIEt)5VZ9h%`SrR3i_uewY#-&xn< z{Y#x9D@(<N7(0xWmu1uigpe}25Vwm}4c&9ACd5tUl%d~6!W^<BIZV?Wknz6Xeho)= z2obl_!=Cp}P#iTPs*UBui?o$4CsJH|SD8+iOe@}~J)N82^|~{t1<71{FAQ@GzVX=D zQJR^-G#mh~I&BKPAENzV7b5<QRH=6Y9UdLSE}mdpB}fm@B91UY4#fZU!Pm201KkKk ze#P6eM40H>O;qq1G#dGZws&dyu?p_F8J$BD0Hw*y+O~|d)=1Fxr0~<FvQ&(Jn3T$1 z<2`)<=A(Px>Dj>n$P-L<4LI)APxvBpcZ)*N0hnT#Jo=R3xtg$c6H>$*9COnvtl`L) z`9^<}bxf3?$RCp$e$dJHt}XZeY)Qk3@itGy;GinWQMZV7DQ1HY|5yFi^V`T`Z=IR} zv^KE5uc;KhaL^}%pzlshjd$uFc&TS6Miw%@i!P+0Few&`pM5Wo)hk%85n&3`4(wDf z9bCoPf?<!A{hsj$%}EmZWZZ8rkyUxZttRq;s_2;q^MH1*T9B4NTchT+ZWB3|rp~+O z^qW3JQpWz<+o=VosqRH0&vT?vlF9oA>9|a)vFrm)iQol&j@%FeP()l@=`zNchuT!x zRw6za?QJeNpT8Q<Ie<TXV_-A*T(PkGc}W>HXZrK_XN4wh)F#dk(vqNW4RfUv{P);8 zW&3VH9bON0JbWv3ZvSvU4Q3XGXKuWVPj(G9u@-i8`)vZr+{DNyUUaiP`OwGgV~+`* zT}8&8aVcHQ8l}Fff3(Xqf~)RgbPeS$Lb=6D8yyvd2(GiTw!WO+l;IV3qt=n9Sia9H zF2V4798-$!-W27vatx9JoMSVUqBJ@5FS6b`<6bK{h|z7kf0e1c{un3v!71O?i=Gp$ zJ0xn7ow}R9%mjB>{C1(qYH{=Fo;o9CX%rXpZRUI}*u|lW)ycXaTP<Zo(JpQo*jUs3 zR;Wx+&*|t1=jMg8ww=M|F7FvaiP@Q_$ZMd2tcY=*rdz#-h1#KSsGH$2!TBRnGrYT5 zjb;eN(Qid|o^GG)=A+ia*fEmiLS7tnQiF0U9PTDcO_T%tj2W+Xin|wuJ3Ye-EfmF_ zuTQnE1xG)QKK~^f{DnKDg(sjmom=12?CBjShS96TOU;f$i!cY}_j+T)d>34Dx2NuQ z^>GzT=AE=q*<Mzx{9)ktl9GxXpL7*($)_;!r?)!sv59mE*Hz3gttZ9-OsArtuqyi$ z`By7!|K1lB;V{(M7led=)kfikRkwe{i?Q3z7z389Uet*l>RJV7!L3%b=%h50bQx(L zUPZ>;nL3z4Kj&a28(0`*IT9oKr<uMuNVTXa4tP7;)YKcj+a;Shmm@ryA@+2oL`jmZ zb2G-(u7)yqdV^J6_0bo2z_YdURTgS_g7kr=nCI)g^3D^duyCP@JoZ$6p@sCAh?534 zi4E3?9Ig6Dy3P@-&V69c47<tSH-l}<sMIF`BgjtWiwVltNzH%W9z?x+Ae#NY<U#!q zi&CoJ$PG%!Ybf@2?N;`X`k+S<Ok`aY-qyr(M|~{@mUJzeSlnnZBw+7_aDl*-1l2f+ zhWf-6sd@Y+H{+x_Oka620Q8)l<#;&~8l-30t+UqYgKJ+GjJ-y=#ZhQ?stP4~v&UBi zAFOlzWBSr<7#KTv>VaSpkfBa_?}^qBIIryDWbEN-`xAT5qK;IgxN<Hkmqs#}w`r4Z z#r#3%iU@Y=Wm;^M&jG5`|Jriy%d^HAUIUI(YC#sdf4~`6bS?U(9d!6=xoZL<^o*7P zGi3YAq8l&y_Na<XkqYF|U!owkA*yMjtMyQ8NQrIrj8tIzAjPv3$7EViwf-PT5>yw* zx}|0}^mA?1wWQ#(1W)<q@m;$<G;0qD<KJWLK%Z-<!zyChm$rq3!Qwb9saySQ4dOx1 zs8?dI+{pN)f{j;((Tkl7XlL)76?pd$@d*tLRO4W-e9R^(bp=37+OgzN%L<k~ZUpnL zOK56M*&0hoK3NtR_NDbcVL6P|0FI+3qrH5kc;9T0PZUZ_o4}$1AZraSLle}QKuX$U z>S;Uk3HnGjlaL}RSYVO(L$KH6bQCEiVlS3y`CV+u3G@&P=|>7k#8Y-12nw}`Xw<>3 z4xo-m($ZeMZ)LPbyx$ZOSGs~o1(5$MLDn=fPhiDw{s}R;MB1*Hj~-#T>lr5iMwb$S zpM4|9TLNy}B#Dw(4@=>L1G2nQ;cfhN{M0n<&m)9=eKcJWOU$DOqZP1Q+z-8J;}VyI z4}BEkTP%TgW@EGfqax3%6DHzA33?vik#vjwDKl4km$G!DRtpw1Q5@JAG0({e3G^To zVjEDVQj`D(Q^Zn5=ytq`Dm!BmJ^s2;-G0p@^|tLzHFj)c?3i8n5&IJ|dyHj0*VF;# zYj2c-D&<c}?XlnH7)zc%U%BD~wdIe^qkJHpeId?i2$xLMF&KibNLD&TbdL*#@TMfw zJ?O+5twuZ*n~OrJ)AUGZ<YXy#P?@48Py{ODf+er_mJv1?2)agXwgF}jC%eSxgi|{% zT|Qc~Gr{9j`$6u+23N%F__d}nFivQTV3<XPJwoI?V>nRNj72%(%9E8X3=iu#$U0!* zzEIV&hxO@_19d9LH<zncvLZ(CcDx<YBr;kQVy!As0pcBS5p8Q`0Aj`6z*#1T#(^{` zc6_=hNf`HpcgR=6hX*ougC1lxXPx_{q;6!<9J1`2z@BhAyvoc_JQ2)H(|)%MA&fsv z+T!ZSLU2;+|C^A+tea^BN%LnUu#g%Zm2lh}xLrJv@D@dAn@r7d<A%`zFk(_$7_CxM z#DJQ6qh??TcTN;vSeK4aT#K$5QRq`&-iEq_30c&61mg=zovw$u1Iw%v#*|f<C{_;m zv7?`A4k}|(<XzS^%$`1W^*8$6CX1Kai=2SKqDBhyG&Y2MqPHCNev!1pF+^LGjQ9aJ z`UrN7rO=Kbt;HZNqlIo)dd`8#J+rtU6dU|DhD9Af0%-C!xf$2ggihO8ajr!^=9Y=w z5#Ey&AMxQh{*)i=G;-941s_Ns8cr3-jXR|t8<&-D;Fvsj6*q~lJCt~er8vsS{@jt9 z*9G%5g8`}@4<q$4rKJ+w)RU<&I-CUVYm%?-3-ELH^He&oNR-VyW%W4%i+3mIr#+*j zm2fmq=CB`(#8Dm^L<1m@{_<CWNPgGn!GpJn*$KbV%*tOGrzKf=BP;W(?}i3r!Wy-s zbmd3Wu0vxoxvQKJ>Od7*GA3G_-tYjQVQ)lZ3~6w?`p2?I^D;5IDATrt>RfH6yBP=; z4Pk{tBUqZ!5M$hr$UFU!;&0~t>L@gwsztJ>Q5ry_^8@}>QT~RGsDnt{Wd>p#>!(G) zEqqYDintr({`y<y1H{9(Xcy&=)IR4FLDOj^mJM0f5|a6cn99h|wK=ZKTa^Yg>A%s? zPsWOa{Iv^{3W}-{_F^<D!Ot0L?lP&XRa>PBsJ|6l<`^v|jmDDQrp*psMW7hseslTK z@zwii@XLQu__u5;m*`fDCCdRfnjIl(MM1Sb=ERUj1CRKUoN&Xx_=myyrXd)h`lD*| zYZG>lCMF!@WBa|kL$|*K>;2(t4$)vL4{R>(VvvfiGrZ&H5n>8*WIsex-(i0z9!p;` z+i3p)nVkKO4c8pmdbdKirIA`YuBIh}Ju|UJDrvJt)jCs<;eDnDrMG)aR%`KdNI^1P z)8|NR1Vs38>HD%8=1Cvk@|x@{YWkPoC|mofe)=O7kbpL<sbxl~tzZ3lFfVtl!KdX9 z)gdOCZg4-owh>CU*Bzw3NWQ8(X4XdhIj`^$pw*eGSq?(3eLyKnl+*Xkb;7t}v6b0Z zl?0PPIW-Oyh$KQ4MXBcnZspV+)EX$0RxpUcD8QsE3bp`>!V3tacw~jNkMyUG>$a^s ztu2&@Ta!`8oFvoywZ|vMxOOV#0Eom=IUxf4bm#MmDf9AQVe69ifkH@1`#W8J*6%oS zK_J=tA<773E;$bIYpKn0wNnHL+s86Rq>{bg!L=Yu-yJ|)F&#{yCi{8{{4I#*{Pn;i zL`ESIu#l+3xRZ3^Gt(iwZADn(QbF()Rbxm2{lw=k(H>uI5e6|b&0#7DY`2F%hHl#{ znJHDA6nh(e8@);8b*XAqo(0^qPZ)$}s?#L_B5a^R@w|czCSmW6sVK}UAGY;=#Pz4- zOVKvyo)QHuq!!QDw(>8_<pxV1*-=edrLlAbv1He$?^4ahHB{zvSA@=+U<a9t6RRbM z2JbKrG$jqae>Jr1AaK8R=reS<BZ)FuaJa{FxKDo&pENu)Jlx?aFajN!@Em3o9GUhU zxwum?mw#8XYXn$0GPf}DeRpKlreZn&?vLG(bw#7iSEFnCqkFrfKift&n8yy1M(4&y z|0s^_*o^&U9$WPsy-pgtdNl@oJa&FLM)G}(;`IpGzme13QTV^ntNd~B$MIvEiS^KN znvWBVFDB-=#;LxKqrOiZ+l+HQp7<X6WyR);Aj<^Zzj5Y&Uszctp|EjLr3q=FG07K` z-<XmA3-<!K;a)h2%>T>W3nj@m&Hv857$wVbBdsu)D2MHZ|H-{5%?Y%lqB5UB?+!Lr z{dev~sYQKgs>ZUx{rljwTXtj(SbR&j`PJMF_ae;P8cm)BFel<Q*L(Noduw1^*vQbk zw?97r|K?ua<!}w1{fB$e+KXPYtlL?=He@d*T>d>f-jT`gWTzGQOKfREPV^MZ00Q!2 zBO;*I{vA#bNnUnMfl#bfG_|uOB^1Qs7afaE4(J2}4=7ijJTEdCr}J*{B~1|ZJMCj5 znn0~S&7Ah>OXObJ<Zu+MwZj9veOk0(r~fKB?fDehk!+%_$cU#pf^JTBXfppOtbnVr zDk<2OulybcC7ViSML|PE=9av*p6Aocw~_BZ<F@f4@c-mqC@O<uSLmXiGg;<rmb8B) zP7gB14l+UhY0T(JG177wqcg1&?vN12%*}>?UyI+qX>nJLu55XK9mzmfLj~?Jp%yEO zF|W;%RwaWS=4b)#fD1uY<%XxaHXnyEl+_=jH2Kx*sT!lO{mwHQl@p`fPJl;_OPjbj z@Ig1b0rUjS7+0I>`0jgFEwGuK%Sz`1(9?>XO(qm_{~d?t+<4nlxId1BF8<(cnKN8{ ziJXY%q@(+s<R+MdxY(F<GydPWmm2!pL#%3t^%@dgH{45vYU1&WNH7()GKi)gNuy^L zxj7mfD`i64hGB6T0kMoA4LIdk_NZuaUQ+Q*<<EL<`;n!^3EttEZ^YJbTK^Zgmjc!Z zQzqr|8S)p8ji(dBwVH9tde5}KlK!N5ADF|_ne;X9wu~ma-iHYg0U9VW#$-yC%B>gO z<LMJjr<=OKT8ccAReb`T(q@wHgMSxLfvmk!%V~W$E?D5V^J=y87O4iE_3pIE%02bB z|4tVk{rdO+%)KxkM3Cth64BpqFY*VG$fQCrk9G%z^+6PBxR6AqzXKk8KtMx_$h5RO zsd5jZdG(7ZZufW6eK?2_O)7%AXm>HrAH>QI7r`I(cd=d^#9^Vu$m=-mZVcmLytaNZ zRd#<jxBTG~<D_C54~gWMq*c~iG{ZYY5s;8sj>PCHGm#_8h!8u<q=yrll0;}wBvb%k zhQ;4gri@T)iy#FBl`sRTwIcfqNosg|WlqUZj4d5>(QS#ms_Y3-%tW;LOX`?w(?o!z zU;5*;H7>D%Y*Wkhj6!G`ua?fBY3|XpO8qka+XI6ZAC59>lgb2LbcU?wkFr{Z%Y+{d z4B1{BWw%dRDqo2q!oeAQ;)Rje>gWXgzB;)sWha(%YdFXCO|J0!J~TNd-d(Kd`E0Zf zrWXTZh4SSKx^-ipJrVIQ2m7gzVPRm?L_K|1>TiGhq#+L1PXG}TSTQ6Sw<=|thAf62 zc-FU=9GU1x-c9H4-%t0!7~~YNf!NdU=O&FZf=^&`f&IPT*C|s(EY{3>FAVFzj1l_C zQo3tSGTBV>FQ0?bF}CP00q(WY3&cxgrlRy}3CpFKr-tZb-c^Qoaj`tFaEfZyd}>p3 znlXMx&&6Czu>KL_e+wf?fj>JCjA^7!GlUQ$rGA6A$5ALKIrV8bm=`IYqzLCE!Pi#* zF^=rt@2}Pp=>e-&(*k&GfMqKX4fQ6x$)kNRZI5U_JQzC`E!#<*Cti-{P#po-6*o)@ zlJV<C8bw0!Il<pO)yW2tSa2bk5N$lKIJ>s*b!8Su@hmUqZXUre^0b+|s+2R)ctEP0 zu7$yklc)Xtldw-&P)GHBt!E*(bgnEuunc&4U%%JfE#OSQ`+Hvp%oO1j|CKZ9`$o{$ zp~bS3rjHDV#W*|2z0}!T=(1VY$4u!dn<NpeS3PgJHa`4_%MoMG1rtX?7Leht0q7p> zYOdcyOL6&9Fkn2X48ML_khUfIkPJ%;T1wdQn`LL?Ci5`5M27TtH3P{+6J7LI8NZ$N z%8u408-XVyQy=wF0C#yJlaPthS)J-|fCH#D_9ypyG|qeiD{L~)11YsMUFu-9wfh-e z`DTdxJqvy6#gecH!!VfK6+a=EYJ0YF9q36HuX>H!kR{BH297oq{2AU*{(C+a0dFiM zHP}>Tx)_f)Y%Hc9+0<0Hm`F`-Eaic%i{HxaFmII1A@mL5EY80$ROO2}6%yD>tX>ek z?=Y(V?POc6J*}MPE)qW8XQS@dBU*$r4xgJf`crD!*W;uag!u`m{F7yux@C<wP1NnB z896(Vs;n^BbHDR<es;9Exs};LaY%ObpHw`ekv&Cm2wRi8?`QBYZAExUHzmls=|$!o z$y2!~wDuJW2_{m~yNj+-T<S=i4UOUDwL%+eT4Arvg%k_sMvtNG4o1zMmXD<X{>V;6 zy|f>~qz?t_tG5b{KklXHU9Rz78@(UAJ$jVYdihf{<^8aW;c@Oa=2rM<1H)%uPsw8& z^l#Cvk%w~+Z2YBZTAJ%E42r&MaQ_>yW{HpLQ1nSweDP6yR#k|EF`>$c^WA|Ln9;rG zNrK18)@_yhtj*}7IKgkbznwZEGnc7PNF%6|{DVVEJ{67czoUvPoM_;SqG)ZPryb#b zuR7CC5JS&&s~dJAs#zo2LLT=C#QdgoJczSKh4neW0I$f?$$P%d!tn7M78AqZ!EZr= zk9^X0JeEx{*%AN)bCdpC#!s}VtZJ=(;{j1d4lTdVc<tKF^G!NJ387a5c5EN?X6oQk zwFDLmc-(16$K(A+tAByxVb|$ZY!LxDKQ4bF+J85(!O{1^>3d~kE?2`TJR%7H_CD90 zR;4`E8b^}=P!VE<Bo&45r6t(83x2)=zE=wo!-8y(kyN~3F*JB)9JX8wU%8Ek%)*}_ zK>@~OF$ZKA-YA+D$Z{W?NgMyQFCqpBax#wM)Q+-2f_jmF#lk3ZS^QoF9C&cEKof=0 zj^g1(GPV$y%O4BP-prmwam<niVxyew2zyH~viNA8<_HxO=&>=G6B6v+PK>D}5sQdg zM21=R+kYj6@A**B_7kg)liGt~90Mspby14(kN41|v?u~*mek#tOx-xvJU&)X^YL<F z9MFywuL*LxK8SZ}CuTE`oIwJ%ePZ1E;oHWKL6n5qgD4`h2sSQB<^C{fX=i0#WGgy6 zraeK`m~6igo*fwH7HFHVjjWo5LoLHLzQXshkjKU`=Cd%O$hf^}I7v}r9x7~M16JQ3 zvDi*b>>7h|O$b5(rXEGlyTmNE-!${U7F?f7WIdgW5C1j`pKT{@L?&jtCP7KUX8WJ4 z=fp2A!7B<$HnQXQweiO-@G;Aqw?6T#0)HHs{0Ei%x1T`FmpF?g?B+QBBZJTSPy`r1 zIV5vDdl$A~NpfTI%)NWu?;6eeByF!R%px8JN=tAJNCX-`aY4DT^C5Q+(u3$S0xig5 zu3cUBYvVuFCeD6!>dhhC)bjzyVPEN8wj<JkwHf?wF3$bwcS+!2lf+dXBz^|Y(C@sn z1k)XO#&PaguZ>)<fSb)Z8M`?d2R+t0cl^tfWl5fLw>gpdd6deW({4o4y>hswRkp=C zVMf$h6Lqr+h$MfHS8jnY&%yuP&XUcFmmYxMb8~tmhujCi4H&XjEW=#R9r<OEyn)a2 z2jFy12y!ii7^{0svZ+9H=BGjukZ(-db3BAMQx*RtwlYk;IlO8!m#8kILI=O*nr4HB zHew+}_8Ib;k1hJ)y=d}uB>5=vMRg(khTM_M#!o$h&HBK{wxEBJ<QGfOv}-%~v?%Nc z+FzzT@)Hu!3wSYz1XN?;7fAB81K4D$@k0yzTqS&__Qm)BBA}3Dtq^+RhL{vZ*hUvH zucz&d!<S|YMzQcZJ19u^<)Kd@#UNoR0=`{aFmv$oF&43)^YTg*M(T{;Ooi()0LGE9 zUxj27eB=Xm@O9CG)1U%5O$52q%Y$*mG6VSl01$+}c>#?3gP9ziKj8#EU<dt&1^{YF zkFc<5G-6L0?<@(o4%PtL6?BP0jTy^+U|}~}5>EpDD7E~^7;)eO?E?UO7|T|%<u2Cv zb3WuB0AjcuYEMxSl8Tr^B3J|P&i=(WAjc3A`k11^>xR3zDSF>>#$UC=Lgp)oM1e$T z$aN}=$r<lFb<f!m@oW$Z@TmfblAK^+Ls-~YE$rI3g1Nlh{X^Ao1e9o;{60Tm%9y-H z6f%r9b)~4fN=3wffHokZ!$=SSO*R(+9ciypm%d4QphvaPrxDPn001=>F_Mb-5m73& zZnvUa)h7z+7llj!${Or$PO&PT5iy0lISST~g*|P5HMadmGRy3!(0=6rHj)bYHV$1M zgb^+r4@Kb-)^BQjp#F@k9RbSL{78x+*c=u%mkOIdfN{h+A0E_w&ti$8c=Nr-S%v2@ zZ(cnmn4B^ZPkP7IvGlFcsn^|863{geW}e`j|D_BlO7@rpBA!^bR9)XURd;CY?JEsy zuXd5FX)w@htT!W{9IpySx|E8N8GUmyt#K(u;)6*bA#||PaWW-R=V`!AU{`O^teFYG z2hKEw#5TMCb@be64j_4VFR$4q&-mVuOQ|ur0;DNQp(XlGOKeC>d|pdJYfI9%mgK)J zsZ8(F72ZF)^FAx&eWBS+y6M8g1jY2aoZH#DI-3{gx#Z=!;6m^sc?|4{@88s51DBfW z6P>Lf&hLzyf&$7UBOBiiAsOad3%gr=rOCP{Ke$@dhg!g@^6(FaoQFd23*&9=3LmHL zd~7mnEs|(t^L;5eQ5DPn(fInXmBIJJBWp(7U)Y!j{c9$eT4Ear2j#PeL)br20uc{m zXr0&Wt#uJ60xq3QR&WziP!Vh*69jChkk=(A!jb$MM+V%X{0R8Oz}}X8Xh*h0P6LEc z=)Q^*gUv7iejXsco5MlOfCOXYLg6!_iN=Kx<VFN?z!;fu&`B}TxiH>IJ^{T+F03c+ zU3{y1uw)%ucspW=cyWjVj)Rdzb`#s%w%K8X(2fv$u)ZfHz>{iGfuR-&CdG9qLP)hk zAmlhQPzS8{Fa3II&qNuF2#EN8S_f<=qZNby8>dV<K)Ad@DlYUo`o8eBL&lH49Z9vG zJCLI&DglWBNUl3t1M*1z<sr8ekYlM-6%bl(JERaJ0FnP87y!Gm5{PhQUPzdE9)jym zvy&jQMF8oLgd{@(`j9Q*6J9?fx)cPF!%K*~ZwPlz%0p}ytONR*2@;}@{7~Bnjx6m* z0($ZXttRfd=^}-&NF8D_3)%r-VRz^&No>UkO&W<Uvi>#&<p?vNZKsEh8|fA?s=quC z7(#g;KuVs5NJS0;+k3Ugk(r9f&*P|0;}=%|DA6JGXVOP%6ODue_`yvzQ3!IqkfN@= zw?P0Y7TVi+0IyU;{&qvoGE+}@+M4H&l8cp*9`+Mcl5Ve6lh}iROV+4JGTKA<F94qR z`s3K2VcJsTdgX6pM81XO9h1aBNTDJ!Qele0emoF}_=7~aM31UeK!}zRL7qsbkdpHV z7`+!<X0~??3%~Rk)BZaROzi<t-u3oGeu^0Vv^4FfNk_;<MA)_SMnG<Q+KK9*B$2~6 zu~;Uvr-Da2X{0@g38JcJlxq16PLIS%2+4~CWFQe`OaOU7ntEnH|4^&42W6($9BBCy zSWG)Gu~hp2^4AkVrG%WnL#I9DO&qB~eWy!14{^GLSo#Ztg~Da^y?<ssxI!ZclCVE~ z{@Qsxy`0~i9Fdd8<pTP37&?bZtmY5VQKM!1a|OhYLgNDf;^Y8P&+Pg8y4EOO5ZS;2 zz|jM^AKLsWv^q)szWmgI{f_s6-7IM0LmSf^3Hv8o|K5}K&$&?lYp&O-9Wd^@F4`>K zAbWF!AaW&ji5REpe`@ESH9xdR&o)$k&vAiV46$m5I0PWbDQY0>F!DnU9WH+sWq5EI zWWc9)qU}A}5SbgI>B;ZFa))lQ)!>KEybKE-RbUUMM08zvnF>|91sC^mBjn#8c_5Tn zTkjXv1DXfWTX$!Gnlm&C@S}E^r{|=~!~<K$C91>M5K7o@BtoU4&BbwPRaAS$7-rNu zm%eOYvonOieOD9cfTWeP(v7$tt}qCH*CyU1_N{%u3W!NY#<71wsw~VLzoraZqz)XV ze7&$_mA6Stvz23y_-~ZmcQo7a|M2~gh{Q^$+MC+7_a-(~O4Vv>)ut2`+7g1qj!~OZ zqtuGpsx6{K?NYmH*KF;gDwpr?zV7?J?sKklU)Oa`{>Yy>pL5>llh5<@et#ZRYlI^D z|FN0@0N1aO<o{(gV~vHR*1yIk(`lnPjQ+pX%%u>?N`?SX%RbB$rvD$1<S|;qbkYB+ zX0+t0kipSN(Qkk|K${v-`R&Q72ddaxsY{jrsb+8Q4>Z@zwU`36<c<HUnjLO^A83(8 zh+1DzahbN_mjL$}#2yT`*01#8_)Q8;+up4WWXpOl46+_9jT9jgPK?SLH^(b1s~!xs zH*HVhT?Ptoy>H%~Yqh1WmT7PK{iBmt@bchBYrxg%NbV~n`OKY#tjHwA>_z+W)^wfs z2wlnlizGigIh-3Wd06*R{qLV&D}+~?-+3PYysBoTv*J%zL@ii&5d{kGv;gou&)|uo zQXnp(sr9d1Vz?+vr#^+-|AQolwf?w5k~hAZX-Z4s;>qwEueBtbAuEY8lPo21Aww}M z$!aHt)8yo2tSFo=*mD(Uz!WEtro$Fglp^T~Sj(`o_FQ{u<5szr>F{)OEz2=hWIfw8 z({nw?qr7rG*QfdazncBekYumTvTV1vo8|d-r7=tev7%cQrI}t^hNke<9<8dvt*xrl zIMQgB0e;eJyQXzrMYx7WFEXaKbFwW;>-N<_K^!Hhs=9y`6}t0obiuY8a$kdew<%~+ zYLxqy<MwXL%_M(qKm^MBR~vJih50p)`C^Ioy<U?s-VjI+rsH(I3QiMIVPE?Z0IWtp z|IGeP<rm*$+v}c+AN2)<2+-7P*-QBZG~Rh245#4<Qrr2=BUYttM((*M01?FeZz0J| ze>lH4M3TQKD*0;8PP=7f4#EXZXinh*G8=rx$HaiU0rHcof##!>HlkPPw25hkA-`|> z_rMR1Ui2Z_CXL!-3}5<59}b`sGOKm%9w458di&agZSfC=K`lR++>hbkfolTSm+yzC zims|~pY~Cx@din<Jy(;4v-$0j0oU_eG?t;ZMt<-b%oXE$JK~}kI9vPYfit97R^Sn3 zm(b_;zlq!!r6ys~#%s4HhI_&eCfr${A5XjgPpesYk!|(wk4~l+=a>H%lKf`99`lWS zmmYEnxG-8FH`L0q8sdo*`LAlWs8;)bP|fhVmd}boRihfLSJmv}c8@kF5<$^h6RY0w zkezgbk7ohXqjbfG>4C!3mlTfIO#~dTH;z*9>+i?g48CS+A%2z!+fQ($DPid|?3Kyg zPxLS?VVffMDzxt>`6rfe{50%SncYuD4wi8JA@*sU@28+>N_i-ah&pTsIIL+YA9FuZ zU*#YbmslzwWYlkLcaWAnSSqO4-)|On@PAg#Xv(E9MuX05huK8aa+$3DK{u7doYBN` zxi>~bUUrAM(}U#-E&W4&VTXB(G;fspjE0}&9_DYDzEPR#AAZ_?Sg@D)M(wB3NZ9OQ z;pyNTjVo$xB>epF6@a!vi_&;BitVTfa;rjz`O9dmidE|2UZ48q{;1R#514$@T0}JL zhM-jv7&sHHqpN+#%0EamPD$kDRX~fnaEc%s)xK$ESEgAV57rT$*4EjF=Kgxa08G^e z`24iwkhkE`g>=$_oT)7ZR`1L3M7_T>Z#@Xmi8)*B)wZJtSO|b<Z)bOF1@XW+S9zbW zP<0Aw(bF4<FEf$tVJLE>sSRjA*L_|PS-=OizrIISK<PcT<>&#v9{{Cfdv>7T`$=Jj zx}_Loq*fsyT6y#q)pvV>mIOVjY9Y8BOjcu_-mcxH0BSVei-MhMwedqrnQ|()Xp^;O z0VG3SC_=tK$IC)#2wX%DtTzCxOQ+E1TEBBQH1uh6zZaQ*m#6lTp|Q58!?jHE>vyle zHJ4^X@!ND)&aKpHnX&=yO?NkfQVF!tq98#5XP8czFjTJ|YE{%t?ZZO24slk!hinSd z#6?~6*ds5RT<)aQ|13DFipz1HpdERs&CX$>W9iTWN!X~qspfrkRimyIL-Y=`*wD}( zEwJRMHq3e+EhpX$BU9QFl!}atBBH<+SRLl5tA7hoe03lZy%!c1Ag#e8Lcw*2QToq# zfYLIZ5i%0Cwdic3)Xk94D#IEp70ub|L@%=dx((%<061o_t+W>1GpQd#XLpmjSqeQx z)a*Z)XLpw-@E`z0JQ~4R!gTTvUqqi6cXI{BAYB`vtx_Lfy9PviOMFhDIB-dGd(EU* z8)Hbp?mQKo`{qF~Mb-)qYJ&~#;=B6k;QQ2CG)tqoZdJnO7Kxr#if9uFL##<aoZVhA zq-hb9r=8egoM3g$M=B~6=$HTiX!E2AiU=DT`$j%L?W}bpL`ru-O=(ufPO=Shzi|K* z*n1diz|HuVYM#V@tzTbF>sBQd{j{^;1FWuzYcCW`!4r^OrwdPFnJ*Fn^RwvplhJjN zHJi!_<itY#kekEiAhQYb+PT?oeLd4%%%8a*0>OIeA{MI$;LgbtQfr^OzwfWeB6j$e zM996FS-)b=4xV&6JrPE;I1T_`f5COVJZ=W(^Je8~eSgHwx4d)_L_}>XlVLZr#7dQh zgD0Z~F$LihA7mLdeE)hFn)Nx{^Y;6yXj%Xd(LAMk9kIssJalmA{^6@ij$hz?@lPgW z!3vDUy|*M<`Y>FmHPO=X-wRD0|2i@5(=P1l>x;vcTszzG|2$S$TC@$nSjM=k5Xk^~ zZ-7N}rrG!TYO!FkulU63*!QhuovIXTTs}@&uV>AxFiO>&Cvfj89mNpMT`OvXr|zlz zGpk$6&lm5~bC=y+I99Vc02WHrh+;3esCzVT3!5tN=(%o4k^?V4Hl2RIIx48Cqvk;0 z<+s8;>-a&lbqTf{s~J@uqSx*{;x^nu*CTkBTHq&Tm-VxXtH)DCcq>H^LnMma0`{Bo z#fUlVhzB+q0{cU$m16*>)(`EDrFy-H(hm#?xd(SvwA6#U+$;0qvxW~Tz)5=aBwXkU zj+WF(6$pqp!@*ctw2*&18t;X+goNQ-9^PjL==nbuBSLv>g1DH&B!vT^EcAbHq3}~! zLMP>=7VNq(Ow~|J)E#z$yHb&Zx1T=y@kZ`M5%y;h*1SlSkAv#_L-X-aA8?d3iyhCH z%jF{MY!CK878<??o5jIgPCYcRk%#8ABtW1jX*$A_MgBzS-uX`olsSej3qxHT$2f+` zxuSgCAy?4K(PEG~QuE#hMC8=zA9K_bgo9{S=*b>zM2beQIm#y%m5+tr%%*>36G_5> z2|Tbl$M}<w7h5GyUYv$!j3S$vpVl<Q7G=Zy;FK?gd@PCZUPbyIJ@kq>>;w+$Cfckx zM%Lfc>^X+b@4>3fDM{uuZAGqM*A+#ll2-P@!yR3#m7;0sW8NFmFF@i+oz(7oFo*0= zeCv}<bja<##Bg)i!5+=6$$$^SimJ$%E*$u5FP0k|#ZaGgy&nCL1#s+-4tIpj?!ic- znBzm_jt%8WXUw=1%@?8InubImNtu!i2P^s<Jvx0&v<1y%2)oi!UuWAaR$z%r8ef!N zT&a365txiEO*v0cnN(PsN5rvt+K4|mNe?!TdOR}?=MkY7$PRsR#TOUR9!ODkXhnW& ziQTxC@oi5xSS#{=Hf(nE?q6_#@k)@x1}t!t>aa70e9V$+->(9dy+Yyal0&~(LHmFQ z23Aa9qzGO|<O~ui5w<Y1KNzpIXxqvsOxToaRGPgA+!Yh3*_<sHW50Tw%`}FAvjA#v z=sENFcx3z!gu}g7s&F{0Z3fdrk$ZU@f9M!_Pl-D4ip@5Uzx@*?dpEWE%tbvIqORpR zVZ>lxNqf0Si3MQANFrG)==5|z`Yirs&*wBO@~I{?yx%jjM+p~f?qKhkeDFD&$_e?H z2{0E&Pa^_5F;5FdQE%D6R-qbSY|}d9vY2dA4vU_V7eh(Pay@1FM}UY2aF~Pes|-(= zI#X1t5<JK8PBZ$YU}SNl4X({I5<07nID=swA=FgG>NeD#?sDE0PaIBR5uH>hn|O2P za7I03USFJ<(rc#3kl!JNdx}NSO?6Kr7?~6$3IO92ef8%LZPKyFE$d7*%ludmm=d&* z3|9!OM?)$@q4dt@o_E@j3=4*lB=e#(JngYolmgYW8gz*0ADC|z%#Rhew+F+tzF~*R zdvE0ZCiPJV0wQ%p)6N`|$*=a2DBK~pkW}_!a6e1BVN2ug4`cL5KEbFv3&Xw6Xs<YF z?O6<id>X$I{6s$Ln-DC>n6jEJI~<F(IES~dWeG%vFt^8Cc2axp!N}u_61?6<Ze=dF zJ&8Aj3n;-!@XY6|a^BeVKtSm%PpnBLrqd2y;aDnKoPXL%b?N`=VDI&Zaa{6RHL|_p zdA$6Aah`8Tp7wbWRX;plfw9!Hs&j*aV(RH7Pi%*XB55m)1gJAJ$oFBXIr56o5qT-R zNfB@Zo^f6SEDn{oWo)#q?#nG)JPo5XQShCvsG`Ca+C~hp)sv^zgxi!=vjKki2hxyu z>BjL{RP_`qY}bOeC<~-sz}sreR2&Ye<eg5#8??aH?X>+yg*V>A0Tr^$RQO9=%;jGG zS!X%F6O@Expx%O!{K40-MdIvD#^X4}Y&6OPCSli@pN>O#!ivJmD?RD49&njGpoUZA zwnz2h6b7#15I&Akm`+C7CAw3$;1CWAVKCR+cP~8|NXyr(Ps6e1&_68q62ufywlF1Z zwbv$oCqBRNEc|tLU4|!vT#<s@`#SOZq95>x5qR;7(`JvqvWT4GK>suc;ks|>na6;) zhdl4vROxHqr)%@l0dv5YI9jteb$xTPv7*hvomBm8F9mGcy&%uLThT|PEbwQ?$P{k| z=_18Y_G{}~u*!rtU$;LP49Jqs!=rMj?G0i5ZEwcCi}CKYWO#_m%<C#uhL0%fk5Y^; zgk#NwK5m|W{QFFHt0LJi$IZ+gf57(1*0#y(jK&iH+nkLN*!SQwV$5NNopn<C>><ZY z8eyigFAQmm>_Hu<x2*|XNn-W3$FOkJhk1Mxd2#)`AtQfiJK5;Re3OrL?jg9U#$cXi z&HT`FZ^E8Y;d&T4X!NZ)WzXy4Cx13!%O*Lm`q4M-Wd$la?OU6P#%WR1_5CGX$D=Qo z&9kqc;s-2xg+tL&w(*B}^oMrYD`R}|6c!3dCmW3kYtM73u7HuYTTdL(;Zo3(PTDi- z_rdeA_NU>`7a={_ZxZIZd9TIJOIZX<K~Ze5g!y-ci8Uwgut9d3A=|VJ6~6Bxu!p8) z;`v0`m0IdKsz2~-=KL?ZhjsTnz$<yVzz%Nbje=@GI^yquJmRB5HuZx}>K>0oeX-9r zgf!1wnAuO80S<tA{>Ss;G}vi)pcHl9V4L&%G%3We>X}Cm3n2MRCUWa-ZLT`BvU8NO zx88>@brUvrk64;8Al^_!lA;b??24!En6_-XN2E;9O62L_{}bA+JUv*EI7A~Gv46#0 z<G`-QX%M5)k0o8otgubxu^Y?9<j~F(W`I1+;7^@gdy-9BAc}gnGse%J;QPGGB|FU> zSA|op5#&oChQa2}Vf*k5XYuj%Cv7At8s|=`*~P{~$1a-tU(=EOBvf4+blj4m<nv<3 z%l<xr4^oKG?uYq#x1V)=Ybbf`1sib$U&3J_?32xQiMC2tci>So+ME7awKry<fdIVU z_TX$op;;VcX{JVDfS+rtz-Wlp=EdYbUo5>(hLlL-r;8~a{yO_JSeyCuvA9Ks51*T9 z-ftq<<OAAbP%6S9qo^GMHiG%KzUij=R10h<+W6cBAl`DHz5As71Q*ji6NBZHL^Ai2 z@HAB_FIt{OKC@HTRH{7mtiGN5<OcFaGz$z%l7jBTzl3Dr*f?(@?@d+YfsYjP$NtU| z4?j%SjCe{#9`Pic;3_O->c1=hAQer!6?_}zt0b>aWc7mBog(Q5TW8Rj6x%tkm0ld- zo8H9VKy1o`pp_XSSyaDn)_S3b{K4tw_?v4}><i=FrdP8AuwBzj@9NJ=@6gVz$%(Ys zZLi6;58}GJ#lICNZzUA9&@7(j=O-jVyhZ4iM@Q}*)ZI3CA1mtMw|kSswm=$%xGxsi z1%J_67=^LVx+IkytJ8UR++f*)1-|$s;3p9&R)XCNn%6@A`mWA)5$*}6Da;Ku^t<7n zbN7-5yEoN8|4d9EJM&CxD%O1N$@TFYq}sKQGaY*^FHd)GygCinro}oIthMTl7w<xR zq&{YR7`ND&iC0Sy=?8bf)0tSR9_Zv<SE36trztO7vankyf1S8JjSb(UVelQvES$DG z3oog87s4ethl34NXE|dxx|}1Ws%hP{N*rupD~p5gE*JLuW77IFdmRMt?m+T4KWY|k zl<JJDw?n-D(cb#E`XTgNozRM|#5;F}Sk;1ebB>YT7e7m%>}-3$u#1#OgZ-~GcI{{z zTvgwWg$ll4fjOHr8z=p$bMBo$rCqVf_J*_pdJCCD>UZZq>aeZ5rezY6>)ONii@)aF zzX`sj8e2g7YgV?N(+liVSp}{B?nGkP82vEFNKv-Tv@7~h5b%kC-DW!+p0D%w9qjM= zA|Y)v7nWF)B^tNo!S_-xbXXv?{^WVRcT|r0CkEDYnjm;#EHwDU;dnV6_elvCgd5jU zS$uy^__H`mwYe-9wZ$krQ)YG*Y7a?;g0>GCoKO3ZVWWcF#UT%yLSY)v&3%#<rPkZ3 zDdrs;@+v;hx&x^k(jM)~&4c^hpp=F`H+W%3e_#P{%3oglrJoL`$1#lZu*BNCl)U9& zZ$Zk<3TfN;t;D13O=c&fTJ<#8kI@Qyt)aFyv?%L|(?bpK>_KXip;#iV6b<Zn@#2JL z1*0T*+W>arcqmX={r*z8k7SnEfTRrEqZwxXFx63=efxXnd<p0bcJ=CwX&l|v6nqIz z_Z>&~wUcI7l6G&8mc+9JaJs#CMSIYId9o#6X-83VYDBYGEbGQ!zxg1;(EQ3qp19nX zK6=cq9&rgN6lZZ<_!7!;|6>o!iXqBe>IzAQS{7@^sFP+^PGC9A)(02gs#;Rl?v$GZ zYQ(Vp2T8tL^Wa7M6PFLZq`{*w3>~M^)1B^u-N{?xt^QjRM(O%Bg*s8>^$VX90=(6I zxoyACJ-z*4yyNaQ&T0#mpIo1>{d@HH56ry4-C+Brk8$h1+i-z;1bEkf{_1dze~wWI zEr;#X?a2c5?el8e`Y96L2+iF2<5K{+q5=))Jl|g0k;GKj%g1@@gW`9oB65VZoHs_d zWwL(OPjhI^Zj3bu-F9><|2Fi>;1$<n!n0osFLtwr^R|N@J;Ibc{N&Rf?DwO6pttb( zrL>3KBFa*-^}}UoZ$in&SxwOaL(m3Th~^#Wx`l4Bl;mQsMRH*T4KMm-Nl!n9=iuta zn0m|)bzwar_)sBM*#)w`ns<XyHGR`ZbEyTherN-&8pmj}LO}cSqhzveXq|w_KkYkM zw6XSq#ErGcL{=F<oPj_Xxs-8>$jG3~E%~WN<Ika7-hFJolZNZ8-lI@=1MU}tb=8d> zIdz);rJ?SfX?(7hr24ehbD?bI<x0x#E*Z3RobDSwBKL0rel+v5j|1);iuZgr?^xc} zyUxd2R<B<$zOYHj8T@6o!Fu{2@YaZ5H?I|Mq`t}V+oZ%<!B>K$RD=95qPGPV#%oMq zIswE$<PP2F|Cu8T-%n<H25-kqyez%Z;=ugfs-nQJHdK<;r`<wmgy&~j%fckewJ*;v zY{;OfVDK}vHEClXlB#(zQ(idMTL5>Iw>a3H4ZBn>wM_2eHNO$Sx!&qBs<D%l`^`%Z zSg6{+HTK};&!KM`&8PAe0x1u5pd!8(`)G#R^_<2VvF>IKZqF{e)=ZEWXSK=!CKT<S zZ>r9N^8uw6eIz#IMuvX1n(tcfZ3i@C&<~x6ckXiU3(Gw$R<>-`xQP%Kw%tmN%J`yy z)_x3^=KA6d)bEe<^7EnkzBYaYScGSOgqzRtx9}(P?cV(nAod^cPSvf9dSG9%C1K0` zZ|JNubu;&VD*X1b85-(v&;NMo6qAg*ObzNtvglI}@y9F-ar#WlySxnQ+>Gt(Psz%f zTphae^U)q7$vOnx+@0y0y2bn4VUybOMOX>XBPpCpyta*EnZi@QXUBP$Q?EjogZlK- z_vN_GR(2^Go0ivfh{X{F`bOnkrAlKWKkdN`^XCs3Zla%~`5-DpkM@HUTO1iZse)2* zHL~;NbTY|`3dGy@`sAj!%@9p5vaf*8{nOuFgV2VyEMEy=_0T^t=hSn|ar<kA@fdSa zxPYNKRxnnHh<@5sVtpc5s?M!Y?{Mt+vTATKIULFV;Mm29>BBl3o8IGRUi^z26=Ugz zN~wJLQii>PU)z$f{KA9T1dc-OT;EZ1H`ksO(qOBBm0pe9cYn&~2XFLrjE8Twp7kmY zgS83Q4Rph8^Z+<M7N-4uKA(B40!{`hjpuv3@HL-7%+u)3yZ#ipcNSE2r`<ZuPZXA} z2-OPhl(C@S{+-%XiaT8xIk+&FdV;-(q)hd#{bibfY!>95W!y_)i|mnT3(N3h+Azlz zuYQtYarJ{0V?XO(Yyh1}Jj=VmH&7hc+@66L*L9Ij<%W!72!NLM&dpnwB`iUP1lgTb zZT~Y#ZtiF|E&HA{BxIF+zNk-?Bdg@xf4o>jhFW2s9u~oaOTC?!hRtov13)}DOrzb9 zJw}3lL2Il*!ef4|+GS`tOMk$157QCED8>=a)n#H(#nnEZ(WK8gy=VBTV|pZ~SeMsc zTj+{!j*l=W*p<w?d@@d}^wulCcH^~2_vKi6bg7~LFHoiFXEwHo9)7?eM2nAY4B`;9 ztS`Fi>EM)}`C_O{@lpEh6*njKtk;R@5{@yr{toY$8^G(9>nMapHux5$mzkiqNH#av zIc~5BfTfYzwB|@5>o3Q}we_@WbgCo8uYE1%rVTlTmlS<38vLKn6G860U@fb4)j_i1 zuV#w23$a&QIMfW;$)&(zW8It^ov+<PXOmxngFV_Tzm7gN!Vs}n8&BW4ikQ>i=H)`u z1dR4JZSW>{7xs7D+42pmx`x#kc+KF5)8?M<njaRODn2$cxQ~!GBhVXg89gG%ToiXD z2@6zj11W^b&Ews5!K?vrpk&WLQt~W+3r-y$CO^okEwBueLw51wmoooOhrBtl?Nj`e zn(`QDnWDArV2~ILeqf&d+DgSgHjgPjR|$0ORfV1gmw2p|e>B&;u*Z=UiDQOVaYi)A zUI#FWqZHWy(1_q3hno(LXMO;)e`ce_c7$0J(R)h-XA^F3bjfD0=sr_9nT}OpjOU(u z&6Lc8hzpnL?Wi?$kqUlNRMTAy@Zh5Y&*;#4jYc!7MYZkEzH`_lBzrgVYsnDq2gz^1 ztakvcx8pIdrgS;c(NUvPGv)vpdX(MtG7K?IcH=~OVXT?)T~u$Avqt@Q0Fej4b9pSn zb${7VRnE}wOz=K&=3y6hs{2O)i=x@V`kk&ey*JI!0!1fxja5fT!lJGmc_%G$mW|M+ zAM!wHA|3#V1WQ9u3{>^hK8tUr1AJ#}JG!buc)WRpoK8Ia2I5I(;TZOnX+x4vQYkkG zMX9v3f0dc3{GO>^Ym&l>l`nm^_?Kh52@bu>;NxX^#S2SiBSh_-sBMp;Zla==K5(-M zu-bXw$=0_o|K+r_=7FYp-pZ;TZbV=v5RIRd8%A-yhFVO|FepuT!Idni&8!NpHDmQ3 z0C5JjlBJWpl+Ub8cd1N}T@+-C(P9p~)V4M&Y=^0B?iS)>|EyU8p4v<6>`FsrE+XsM zF0z`&(lKltoOAR`0m2#q(D*5G_yZPl9&x9iw~A7)<@xK$ov(ep!K|?Js?RV=FR~Yb z?1Wh<#)v%Nr4IXTKM)Y|Xkc3Vo~Pq&E?13wb#r!@7LHWR4Aj}(&7v*oafI%dGwBJ- z)bC!kWja0V#Y7DkiuQgu3s~e2r8+F^SBVN^6S8||jEl-@(E0lNjTjYjJ)ddjG|o+A zgsskBSi`y*ihsXPmPd`6ym;~#rIFHW73|kLG>Q<ED()S6Q66Kcw)Qvr&SEn!O2gPg zzAC-J%D%}HC1k<S^y^S7&QLxV5_3x{#>z2Lr6T5*l*Zv4g>ClBlNFJ*nbhFZcjlE$ z=`0#7s!)RijPvv-;&iO}c)XJ>)x3A2s+5+1YbVCMBd(#r#1YMlRa1Q*vsne{P-%fp zbjM{k(CboYOarK_x@h}j?mDV^V{iOJX+QVIkc_FXfo2PLc%a;jKnEUpIC&+Yr>z&y zh($)Cm6~o7qtmJ=EcbvF{Ad$@m8um`85(=nQh@rINbJnVn~k~{xVnWFg%yBY(olPg z8elF=_%;_~P*o>?lnTJV$}CQea1^<m&G%x(*ir#hdSZ$!(}11|J6nmd)BsKhiUk17 zHE%N2qOdpA))bC{HZ}~1QJ4wG+*y=1HI*_q?{K<8Roi=fqag<QvOKCFYMW@g4QZKt zisrePmN`MId=B&?+g;PbAPA*DE@4bqrRNMPQydH6!KuK32$tC2r<A@}%6Ma_h;1{W zit6FB77RQl!CT${5dA1o%@iL)60KHI&ePwz7UKn?P#%bOvZ=56LYWh)=cj9gG1cJl zCg&Cgn<`=72F3)=$K2nGd1_<ubca4~LqsAB^UeaR`-L+rOz#<-(#-B{2s|}%0xTP< zw@CF_TeTOf1QKtHu`2>86d7uDMq9s+F~zroX|&OM#4YOn$EVP4<Nl`7UeKJpi6ITG zE&k3l{GGRQo)2w-sa`&^_<pfL3{-a0A|72tiOj}Cc%=Q#jd6q%_tGezsP?~~2I-(X zoja9G7J(w-<T6FkRRlx*K~RjqfLBK+?O1G5x^9=tz|B=@b17w}ikRDrI8!-_do~|3 z5v(8PO|o&?Tu#jVl|3ZFSYeuQW!xCpy5h>Cx#^9HEo)@*)uOmpl;?M3NTCWz;TTGu z0NpwTad~$nI7Hu@i+lu%9xiPk*)iO9?d0<AJfVrXBSqnR8rx+vbS{ULh`!B}4Q!<D zniT(ZX!2>bT@e|CZ9v9n?3;K_x5vzJ>?(8D?9r{@g>;Dxk~0)n`lBaa_TVqbv=ww~ z&)n2Qi<=P5@ELS#TKAx#!J1!HkvO<7PF|bep5WT^HXXawGnSGeYl#&CH;rU)DEqsT zSx!qFo2r>hX-*!3$!<1xOPN3I1pDA?d873vM083|V|&l(LjQx-qLp~ioPcOeEi?iT zGSTY2-ZV(M<!Y(WBs&nKVk1Ri;15*f0ou%wDRz<>w}P;Z(F0W$a&NI5HN&(^7KNwn z+-v$tAWg*zifo75Xd;DyhqiYo_=J6QSeQwMRb<mMzN-}jdBNp78mng*t=c)xdxe`; zSX!%F8X)hQ6j@roh`ORjI6J?o1p^g`(Hg$`_okyYX(tkdhn#N?f#Xf}zW180f~;(! zdn#h?z8_hwf|?O2Oe(B=AZe{DG{F!6D<Aw1)U44nzIIkQQ>)@P1oaqi>cU~E;cubo zh;}HO;#>qOETW&Up-mU3D!ugw8`|A{Cf}wHj0sGjYlbmMa3hBhzm@gq9GoW*Eucj~ zYPaeiYlyK{Lim15H{GQXJC|7y?&e@L`{@|}VvEP`N@T`I-<ej3s8M<AJ*nWUmQ$u; z0<ejqwP{zg-lEZqzA<r2m){;IkQ6$tS2h{{jZC9c$vhD|F*m(BBeMj^Fiv1&yL0Qw zeR}b=SPz;Blsv`Y9O(LmoxU!G_T7<qsmUgFYaJ7L@a&rsJtO77TN<NeZKiYRMd@8T z^%ncDma8I5*{UIs>(5NBHZ2t1vto3~^L04X8(nnkYSfg)=BOJXMW5%rIELO@j>O=E z+KxLVIOgp3$P6e<3=$z$omWSptW29Emy{ANsNzS0<9B&e;zYprh{T4b4(AUeq)1Mi zm-*JsdMeBJ?J-B(qu+aJjieYHKuk8#6{W)-93PCDz^4O7BgQH3D!NjPUkTd9MO|cG z+0Zkq^($+JU)1ffd*6@b7yfXXtTm08b|}etMCk<0dVV*wY@jglSDkuUb!dZm{2A<t zD0<fTT~RtNQy4tsx-b~C2uXH4dofL^A7g@wM4&Qrm6{~Po6LzeE$_2-XdMsnupn$g zgoiXLkndqV{&B_h;jP=ya;KuQMfPE{TNM<Fj%4-_3Nw!(>}fAUW0Ic@W;w_1nj0m$ zqOqvrKH+WC>a#_*^5y8EIKpSA(G_Vk4;3bVtM(b9=lu~(57>2-UeLFU#59vyx!F?3 zXM4K<GvYfSTD~&Y6X!bQJSyA!^HCFb^23wwI8!9$+nnoiW-e69PLDfd<5FGVc2H&g z_E%*tV#5}1v$F$+T(nCbemy2%NpRIN>o6sPQ!NM#W^jBcb;{m?zI72vT4O?f+W4cH z?eMByG9-%@rH2O~47)T7A=`uC8QE2FK6Bk<-jGFF#Ykt<RYMylm!{)K_QR{GvQ4$7 z!0FOSt_H|18(YZq^-$=%_!zV2Vp4!d@*QI}PwSs=aZXly%XU&4*{vT~EhrhDmWhib zgk1_QAk9sizlH)N_=e_!1vm0rTb1_!a<nLlASmT)$`Cx?u3j3c!GrQKl9I7aOt=tp z?xN-;v60e@ovha9+3xX}aLcQpL^@K(4KutDoPX~ubF3ZHKS4|fZ|2299Q31UZSaT> zanG_@9yhmOj5C&PDcd~WfMiOZ*f)9fZoc8_@+FY**x+A%fX3M7(>J*5v@^Os+Z1}b znhD4cKxJMnum-dH#z=sMc@ry_M}o~frkSr(uh5DtV-1j6{XJi5Tt(}`weiw}3*E1b zTCjr;CBR#dY?QSqIX{(`+?Cp$nL8+FOS3(cY{m2{A#RLn>;BBvN^0f}vyupH=m&7o zQp09H*i-WqCDsL9Jb(E-o8JG_XOu3}UkMxIZ$q(MK?0zxzFls_{w3()r{8qG$4GE7 zij`XJPXhcYO%aY12kwj3KQZYKvQfUz3`@JMejz?G0*BK5ru+P*@xRM{9S(Ey!fVmf z(G?X55qoZc+HJ?B*R@2Cqu$>+sn!VqeL*Q~RPYw|w9MSAprdW#j$84lAFXjiV|@GX zi&%d`y`Q5T_FpU%Zd6k9TF^^NqCLFN(RSq$7wgND4p9t9o{2WWLAHCTqO{@_<`r*> zX8oZC1W&umD(`a$Wwm5Ns6SyJ!!cMq`wUloZ}TfwX5Yv7*jblHoFPx-i}MgDMMZO+ ziq7Vdq}{K$>#!e2(^AY&E8N-oG2cQDWNu$0edeD9wBmqr5RgxLhE!gdd6sP9W6w?c zsg2kmn`B)TcG*9HETLp#p;32fQ9?FoHe4hk+cR6ZT49{_RAUb$l%>AJ7iL(xad~Kp zNv7rkvZ7iX8^w*TTUDMiM~+($*s_iZGG}^H#)-y7%=zBRI_@>cTT5x7S%BEZ<x2mh zF~iNUaCLhNy=04D+GM5?`)_UUoh*9Tq2X3<Rej>MsAN*Gdi9i#7bZh`d;>T884+#~ z8;6gWLq-5GoB59d`>5fS<<G~T0t<pPpqL;-3@uGjKuZY9Lg9u8ZRLHgFlp>NVP=*m ztez+w<)=SrMdnBpLvqb-!Rpg#q$X)pXT3v*F}ek5wORC;EJMey4};;I+Kcrz%=V8v zPEb4x6!E|L^AtwOVo$&S6Z$7T>kKm^q^#%#uucpTjvg%vVh^D-D?7<y4inHG2=Q0X zucLc0bMhAday^y$MqFZX);S#+9g|qn`6zP(@#Jv2rD{68jeo!B)p`Bxl%#2);LTgs z%ZUcUpk@r@@m?5qHdXi$-Mf~*O#2wt&Gcl7({4N(;PFh&@vp&R6hMgrje1tqxm)<< zFqnlgRrKtA*2S@5C`T9Uc_i;=VIX??tl)7AU^<4aFTU<)s?_h6&bW*IdoN6t<AU~g zd{Q*;w#4g0P(zZ@8dx%3B#5LY1#y9(o<dN5EdT66Y3Cf11t0!f{S^No%QpnYfi=dw z-<vG>jn-Kt{|+OU$A^#hCG<N{x+t=fbvdsIMXW3+7wurfk^`_=FW!1kcftS?i{$c1 zGyoYb1}B$S!me|LXHjB<rx*UQyN@hfb<_WjBx4zb?o@m1^YtdODgJjPna?2YKS;81 zD)exT{m;mE`KR06W7S5ot3&=fuFZ3L{9sxMvWbi(9dxmL?2hpyjpO+Gpx<umKbIW; zrEeK_El+m0j>V?&&V6Y&|4MJSK0m^%zc{boHS<^hMnticn4+F;P424AH1C>v9`z=r z3yp{`ldc41S-+iA>DBb;?Xm6knz<i&97|6FL*h+}V`9u`?T}kmIXb)Kd$*?Uxw_@4 zPC<iy{`Oy;Zx1>Awfi^Zam1x#?8<<|&)(^!b_%7ka@>2&?rhs!*?PtTp!U(%2Y;+X zhjOOyGw+kwmCld0rWziPs8%gCeGX~<ke#EU>XXvyIJI3<ph)`n#!PkixaC@iK%~Jn z)vLQF%)~}yl`H1D9g;Ve)i`6+^|%o|^YG-~w<N1g#@D?PzbZ<S6}QB7Ekh=hTc}ar zLlwV9eTE*Hnb>-s^5e9rlwEBpSu-b9$%ZE~bd_WIr{rH`EG0x#DZBDV#$-4RVZKXK za6KeVwT?45LC*{Yay{R+3Fg7e^it%+zA_K%QeTZ|<sW76PQ_>4{08@Jpg<*MOl`z0 zzEX<BI4Vv|AZ+qdja5X-em%N-TYb89vfvi%rtp-+qoXA=)x{2QYJiyYcyh*W=`}!< z(z+qL!o;a;a`elscCoq-X`h`memh><2r&J4>KQz8i;}K7?zNYT>U73FMB!NhRa&}g z+*yjIo7sj~>r%YxFFkS2Gg|dMn}nith5j{;AdCt-ePUxII!V5$=IL(8m!aN!ihF8a zaGf7%&!oDcx5ETYmOHF!R035tU#m7k#<-Qf?@`lRZQC?cGdEUjBvqT$mL$u~ffh%! zNmTDIWCp#-sfCpC*Qa?@ck{EC<GF{oMGEBW^TeMD5T440OzmO42XCqVJBktK1YPsJ z)^hC;tDM=-q2A!FXr8P$5bY90#S>L;^ml*Dkx=vZ{}kqvLI)U3yltBob&$rMN%7)- z>zOLo1GP_PcE5s>9b-8eo#vBNFHfxx2h&HsTuzioBt*;zXGuOis`o-cy+HSdRUV%e z8^q3)Zhd7agevdU5BR07LX9+1G`njzCUv$^>D6A-QgcmMoi~9p#V;JLIW9HC$}VWG z1$(dWe6x>GM>PGArEC9MbWJ)gTRy=oa-?mXPjycI6W!TD1}|k~<D=3rx1?E@>21>V z_NR#XLw_Z@@_DD6O;aIG`NKpuury~9eI4?4{nWQ|`FG$aiQx||ugg<?mAMSSqs<O8 zS68KBxwbCMHw19QwSgL-e#zhnCq@OW@?0CIo~VcR7{#6m2G{`}Lj~mhwd@3Ym=Ouq zDT-tR3*D#*NQ&xT;*6|Db50J9L~V{Ug%Vc@H=js5*!Jr)qn`A<8ZCl3I4_KRT*)x2 z7xb4UH^07#5q@gJkA5U$!+cm_pzwKxn<(YX%VhykhVX**R_u%onX{hCk?Z+aV`*7? zbTVcFQZhSSb6ZnWY)7@ANy56^i3~utHmv-EJLYZ&46WBJ`mH=&4Fz7krXvLj4{^mv zo6bp94%~nDlby5|Lz8i3Jtr0m#~!7O*<rt!@os6_z3Z(KXE0$=uj4!uCf+>k8}NN1 zE3;3el!#Iu)ECf!miS=$vP-V(z2n#FCxFi%C=b1PPP9;^K`Fei9C?vjmNE#BqWLHl zEA7AwPPW3hF`Q|wAcdlyAO$|GhiV5wdNbKqh4f|ZGButq3rU{}(^?VKYJ19U@9f8% ztscq7O}b__4H{_3i;m~K?n!xB(IX<dl+e_AaNF!+?u9FZ(zaILV_GK>t3nKIu1r&< z{eGW3GlP2ADB6a)ZCOm!S?H<mzRI}BT0Ks*QNR8cS7M;3-FPm21c<cA?)ML@=))?G zY<3gl{c4&3H#9DZy<RECFsKM&vTR~##?z)c*a@f8C8aiM<a!EaQFT#x3s=TCm&K`c zT9`DmH8&InV^^7USOji<^P#%6W>&tE{Lh@J+PkCr4oSMWA-uWS>lRU)?uqiNxM4|N zXJUUjKc#HuR#O&j#=kv`!JJH1`K*bd+7pARR~phUjq6S6^z=ldyA{;1B?gX?v-A53 z$4^fxDCM)isjisc%l%Z~qPX`m_ZzC@{qftEU~2t^f5URo2lze{n(NZKmA5TE-C(L{ z-NSw~^2zO49?)_XdvJLN`6^oZtI|elsj~C8PRd`y@z{0lQidvR(%hFvF_zUMRjmS@ zyNmwT27l%-9RsNg_}@>+74Xoi*1oHU7PUkH7%jRaZnr5V;F{N$nd+~-_yXExu!0S@ zWoQD9txr8Rkk;nxq&6t3%xs?5Rw8o4`|u*m(OO|mv|$GA^Zh|=dJnUd`>MRuN7=+r zSsiQNTWye+vhO7-k|8avL$S@J{)X>sCBIP)Hg2+3&ElD-zv^RtEbbS}e)v=^uqu_Y z|2-kalzxq4`{4#rqRFo3>&z-nEjL`AnU>$~i^z>$x_PgV)ilX(Qn)g)+$$u<36?Fv zJlWe^=+E?IVMWfSifNTPs}wtYqaajh%iqe*<Jpd{{coPqn<RV1uK_EP12)MH{|X`j z6OQcVDb}L=EG;X(>g{W28G_xH{Iqn}Qm1Aum%OJ<Au_nkixutzjnkdMHJDN{!Og6# zX$#NhY`s<Hm6}hh+7s;=9mwJLj!sLRy!xv?cU4_|wOxX#JFQzEgT<Z7_!bq3D+4Qq z2>iwPn<Hw1DYOLkir;!*97Bs_dA_cX$!pOullNLd20x1|`g@M=43;D=Cw41jCcHSR z5!&JD=9L-GOP+Z%{)SW6VXu8~NI3F)>b745D~{}f4nUi|bwUvkyzb3$PNvQQ^ZGjn ze1(s0ZQ`2K5_&Bz@su;T$-~KjErSAx?0WxQswI!Im85YgNG5Z%e_O&D`(xUjaD$6; z8t`~h@*v;~cW(16)08&3&!1m{ToY0Lt`+>@9T(y?i{5ME+cQ2XO-^sQ_OX<u&yNG@ zBssX0GF->+FC?YM&Cq>x9NR%tEtS=T^3I=van}OR7N1G+ikCRZG2Kb@rh5O^SH}cj zN=El9{6ShArMYVCK-n@bT<AOe+MZL7ra$`h458)^Bv0l(yMMJ|%|WA+AR?zLengN% zacGR$)ph;|h2nariErsytao)2IxIIB2dq64REe2?hsY$a&{}^JTOyE*X<n0vPy==D ziaQ=d`V>K(nnwsgHc(9*q;`Z*z7jr<90AFs1hsi!nC-w(XyJ8VN{l*N<Z3^HB6sNm zgTFDS%Sh1KBWLG9X!P7Y2-fp3dMOEt;(_Q8KLgii&~(-*U1tPk2tm<*QcjH^w@OgP z0c9=_^3Q?sn_qHH37Qa-A=igJyP)guOoot&GdZ_!pCvHG5~$6%bUO$-s|YrlE3X&0 z9z${W-&L~h5>V2)F&L?2-pldDZ0yWYb5sXl<!Da<s98f_eb>Ao$n`uBk4>1E0DfD{ z{(wiTO0lS5ZC>0oE|SOM%P90JXb@Ktps+nLCWZs7r8ZB9h;uqBjrsjydBp<(xDsm@ zc@AzyuX6OrnF7@yXh|AJSTc#)&nP9<cHogT6)L}*A7nNJ$40gyhHRYQ@9U{L#tSNd z<QJV0SG;a3k2=!HSioNW$_&mYbN3}sACPmpPCH7`Dt8abJqN0F68LF&>5`pmK>)QK zXU$dg&9sEGGlC+>1eI+oKyT7o1Ch)oW9=bhVbM{|&sE>UmPBoO89=)R0XD<Q`hA zZ~>%dbKp(ZWn(MUM0UygGod^Y8mC<XHpzEAz8i{~9!>C>ej%u8fJ_$6C_W;@pA*zt zUv`67@4g^DvdVkwh@i$tJ?H>(@)XNgAY6U>j{+!F@7e`9tm#77#Rj#dygt)i=QLU9 z)$w_B?<*QsxJLP%gkClO%z1~-B%bNdgbTn5t>y^4iGReETXyhy=9j7EIg6lLwYFvl zTHXe6RoGZTz<W>*@BK_Z&Jh(KlaoZ}IUg4UaY?gOTj~O>Bqe0S5nKIXk#8?jy~5OU z9SjazcaEM^>;bCvL>Y7au#}1Rk1pq=LTj2+)W;<_nY;4IWJ8+=1eyq<*<Gqf2qy;O z?Q(Q62vU{NmEdU_AXDyRq^ssHs5?r~M3x%9)@3tWS6hs2n@6yz0n1B;kb<Uc=U1>X zTG9-SQ2{LlAk>H}&&&{a^F8Vs2l48rH@>E*1jVxA$yHj@eCe)6cifSN0~MyT)cv}> zWjq>PBsX0TU~S`KXMWF?G^pIc_&>_;DH&g@V`keA>yAeu)&z`<zD~xf_yPewT&inm z1{+2@xDiyjK#5`Wf1&0x!iBQ6L{%1GgdI@DhF#?dC{x`fyC<Szs8=|MD=@y3UFvwv zZHD3XM)Y$IJ{}!_KO#RC<n^T($=a{Uh+sPf+HBo(@o~t`)w9d!Q@%vpf9;lgKBA6V z6TiG#y^{lp*7^HP{4$0r)9Wlp2&v~OW_Y63Xe4hnS{`6}J9_YJr(l#t<myx|odW2t zmaZxorH~)_l4`~<KaP1(KSTngZcb1eB$EIE+#h&V9(+-36_$Yj$u9YV^`lQZNGqBw z2pQt4oWDpJJhtT@FrV1pdS>Fk>mKno*DMIAQbf4@^-hR*NwDzf)F8B1-CLK4Rx$;t zcko={)}OwjpXBI@849YZL|5N(eH!bmzOil7<J}&mXFUj%{Nf70i6W2*_BWRJI|zAn zb0P5qoNI_3k>wW)n7&pt?`Y)SMzp}tS6?=SEWlfFf+cB!CQj?2l5TdWQna!)NPQJ; z07iX5xtX}>S|gWe^+8wf8D?VyKGGF&ohD57It)CCQ8hz5XgC_R-_&b$(QrhFUmzGh zt{XTkw0L1#&KRWicW-<FbGD&b7j-m2I~2AARV#ANPT(syn&Vv>)DEd^^z{Ce*#=^x zX4UbF)qfCQf?gV^wECBDn9m$b>}KqmKq7AKx`ge-iX;divWiyAUz#u1Wn<_yncW7E zKh|q3QST^GV<AYK5>(5Va_J?G^~F?|Ys29BuPZ;#mjOxYF-?_-h^Ve{rnj$R2;#?R zRTP=zp2))<qAXc{@+qBs=dV7e$B23UyQW^Oe4ut~UF&QYPX8UH{EDn|9?8?i$;&$H zPJ_AmZk`E*{NnJo@=J0VJg#DMFjGiKu=20SWBU)T;vHy(PH%lHNvaje*wgL#rNmn} z$hbl`Kh0M1!cVikAr6)()SbBqxG^h>v1~22*wOfP65+E9sb|tGx`hJ8@}QJTsIE#T zS}jOSy;`F8$@-NFPM-h-r|ZdUp|^!aG%Y0ST=g^r2omDaP@zpdz>Mmb8=;x2dZqqU zC2?o}5bA@RZvL1iTc8?BTLz@HK8xoEqgfe6Z*}e!>9JAKk2d@8?`cRQTz53HwWSxq z2VOl>l{8{|U3zxXx&m|5=Ut+S1O+V6?RC$LUG##+Tf5ZyI#YrZ572&1jD0*g^k$v7 z5J3cgBUb~&N!f6m79)_-BVU&AKnl)jA>ntR)2&alGP}+uKp5v^+|V24Kkb(AIg~&m zuKz@^<$e?3?j=1D<YVc68Xqlec|!tOMTPK?$|prqgHa2yAVngu#UCwZ50cjfuHVH6 zIxR?<d{IAH5^rBs{jv+4T2o?tETi@K64IaxYqXBGmU;vF;Ax{OPI<2eD3-0QSqj8Q zN#3)l<sFoIr4tx1KOiwp#;*i4RYeQfAfWd=0HcvE`XF~fyq%SqfiAJz*1M&!?{22w zOK|6GuD5z%^qEBrw;tiy1Ko359^Q^_*VivsSsa5zib^Xs6(@kEZ22cXx@_$wM#+1c z9_U5EH&Wb_diRcWulX4*e*OLAH)b!17X+aE2tR*KINfq9_A{VsA}AZ`2=p|{>ULk@ z^sEP6e2(unR6w657d4B1sZ~p8-Hu+(CYfklnf8$7JCe~m)|-JUo|(b>S1Vl86)slV z1;=Ug6W{uqjvQ;~@{i_9Uc9sW$H0s7G<ySGisa@%SGGViSsp&HO-9FeU-8XA`}Sj9 zg41!Wz`eX4OYqpAwr~3uie4r?BWZCH8I)W?aVxbthCf~HtFdm%waE(nzN=SbN`!zR zIlnNuCJt!&htM8=tm|C0RW9zKU$1MrR+@XDW7lK6O0c4nBDTF_9k(NfKDB!vY(V@) z9lIk-1gc@z)HY-XR6yc1-I`iJak*~fWHrlny6p#YUO1m$#ZFANwB+wVgL%56_2kgu zEB7Z!%d$>0=#+M0Rdci~{*r{`4Ajf?ymNPS5pbfUmkt^r-sQ?8lf)xrd-Z!+ZgRGw z<tGvp{h`vGjiM|-WgJ>ViJ)99mdn+9_nvNaxi;<BYPY^6rR)*~ht<cby6S2OHX9M) zXVFeUu57Nh|Ev#gP_nC=fD-0h0UeR<oM0|F#E6;kK(+@U2!9jyOPHbX<wr!|075Q^ zA9ug7tldLnUO>$dXwQ^yp97_$eth2yt!aqX{6)sbsAF0fhI*_w6uc{&O{RwXf)QVq zRWMY!SXBmKlO2GMV%jv0v?Jbj=lntEnW53OiTXX1(P3TcExv^*zi<J9Vxy6|vCWLI z9N{N7h~E$)z{5wDq({`bC4HCeZQZrH8K;$!XpgG9(LIQBX`s!xLYd@m<*$5d8LllJ z=f~|UN=Oy;pNI<P!TtL7?`#Af^{A^4M}E}XH*PJ}KZDXiCM-n>xrqNr$czX%7AM|L zLS;&mbx)tdDNxsrE^M>@_vypd-M0_X+L~5}Dh{_ARM8ryiy|FB(^qK8IvVP)$V)RU z^CjBlJ<t1y_qv_$#oP`MKJPU18<xnB1_IGbInKI%2t&I{n{)IR|H(M(Zbd6#c9gaB zW6PEcaxPsU^KauN3Y2s{;^wfAn+xc8vMu%+T1pDh)m9<d?ppY@yZ=2<ZEuPF6+#?N zkdiyw)gWaVdffhgj+QR!P(Upy5mi*S0v%_DjWeTDDh9bHB;4uP9|^2r1jLn41ix;A zqXyy6&W4{eTDh}PARh=Q(!N?_ny0{d#hxZ0zT`ovCcc{+X_x8S6FiG%RU-)BS&cO% zYJz|gx$4A`{nZU;^M_Rm7g_4jI88MI>z?;HH4=eEDu6n9a5{O4-!yUEJRAXA22@(B z146e8)g$T``u{%tz0eW*e<R75%M0!3kYpRwgWs7qW$*nO;}87z&U0L0=wV0LS^2Gj zKff&AMa=gmxwIZ~>0+)&ngwl02@xKjMHjFO)#ZM8cKOkB0F%Vjk$sX6K4r}yc~1e3 zd4`uL>bVf1mk0k!{tVx@57`?1u-&v?ARjb6{{gL^!lmq<ng|8#K_2J?d?R0_!b!i@ zs<YYs*T6iIpny;O0A4hb>ePJTxzkUrCD||;dc0+He31B9qkxth{76_@s3igmpBayp z7kc>YIn&UbHH?2U4$rnW;09a%^mU}zAWNelEO?vgCzO%aWaN_vOC5$;v*2e-3DG0& zGB&g-xKQKg=hCNUHq~k#gE@cyND8(f_b+&bUp?Nb6e@q7XtbW^`H|I2ICeH+SUcAF z;3s3*>m2>p4UMU9xa}^SezAu-v!}ccy9`}VM7GjHWU3!92-id`*iskDB1!$!dezQh zeJsxB^fV~-RZlQq1Ztq7Fw{`oqPdWKwD*;Y&AvPPCP%li+<ZRTU%1XZJ<YhEPdtfd z;)x1^{iD>A3a+pV&qv8&v4I}Vao{!)fFb1UjkeG&8mm!l=nFqF%*UB)3>9C*C&sq; zbn#gR{Cpl9hgYLG_JEx@Pd2}cfjFKh9@*b{Oi9WZz3QE4Uo}jru|7-0V!&ACvnO_= z+;3N%@J3p<1ZuNoi`x6RFc9Yrz3PMdH`?<TmA$V55)&|8&aq@#_JGw>gIvIYa!C$6 zg(9;`>M^2+J8YHpjYZMme`D;fzoLrze}PW{L(UmGhnb;!Xe6Y&2BZX(R1lF61Ef>B zMM|W*y9Mc#R6s=<1cMY%U@p)1u4mnQf4l#|IcKkR_S$>BKkrvEPZnrqW%I3HA%}BT zAosyK`y+Jwte(#f;bI6-y<##L^h<2g6!hzo7yi%?;PXF_w5F}jjb956s_gbZ;%w3{ z794kYvx##wm+PJ}dyx##Y2cOPUZP`@!;|wLfDAl(3q~)K+szm{Nm%SEGb3()x+^!f zRd|sRp_g9e<;)Uzk<N+o$f)4uVcbjNc^jbXDjDP&Z>OR4=yZ5{6f~(qDNDlsVlW0o z?$?5i#UE*^k45$gito#3IarQJ{UPIcQLX2|7}&o$hYEf_K7>%Cj&RR6ha)L<wo7l` zKAz_DA8xbi!QOcqH9EH42U=+}`JMhegqLSXBJ^<b>u==~R-e`bC)B!aR#!#px?P)j zQAf8wI=qw+N0j439cLjQfonfJ4CHuhya;hn)6eN3y(=aaSbuvf{ZR{BUyk;S2i47W z47Ic845ZdaB93HB0AzOEQsT0LkoAM=GG}5ktfobt#|UIA3ib)lZm6+_$0UCV!p2`H zLlJWp<GV_X@AqZ21i(QNq>{Yv=jXXW+6O5HW-YZd`_9aVx$27Ee<=IuM4l*l<}~Kg zC%DIkK0O8C`KjD-7HW?a<XI7!S4k00t(=}npXs$fM669cQKHgzgJK`KgGk}I3<J(Y zQL!{^`#&C1HK2770*|?5YgL41Z_Lh9rPbD}kq8)Ps=kVUkK;K|XL*IB%zi?Qw0J^{ zjSMD42JIKAXdBc^eA^F4<%6YlqT_i9O7P|OX6<M=%;$IRfZWPD7cqp3`zTj?uGmgt zf(XsCzyFflhP!be2t%DjMl-DSzRu=#yYso01WTb@!WE?<{@scg)DI65n+s*`RU-a- zWu#uSq2|_^uF6{kE!natv5nt{%9x+itvRn#ROSug_}&lR1_YneV8Yc57=zS^&~f?4 z+uYNSDdg209uh7VUfiS|Ic0o;eE|OSatkT%v(NcvKhI9y4L%m2QOJu=j^bOzsBM|f z2^8`<;v{c<$jv5I?~@5d^+Ky%aU6`0L?ZEAzBp4(2z)75W4HDRbM1l<#}9jMb3$iW z{)aCP(wiZZ84K!6zWd?g)8{0@yS53k`m{QNluEcQ5Rw$d2b#Cw>`sToC_Cd_lN@)f z3_qfL)Et0XIHk2*S^|p;yoTodZa6iJW@}{s24ioe$xcdwWf$>XRF$2WK`(7lnTh<r z$6=U_gXVERLzI!A25$BHfWtACaXb<Xf+Zy=?kflRHpa92Bq2Q4;svNyH9+-$61;I? z&7oH23eWah%LY@^W5=%55HQZ;`~+1x@-jM-*C0x5JqNkyWK&ns-nO>NxHnRr%SxT{ z>e_7)o!(OX&AIGZOM$J-w|Y?jgvO9NOnZFePLFLL+Is<tG56ek>K#SURF%;1P#Q^g zyGm;Ew$^trTpbkMsEgHr6(B+BAcf9a##|kqxTUk9bod$TgG<rC)iRBcre~kGJt9!y zbA!^xB;pGwQ|$c-8ntdua{1bm4h8NxGnoPsN9#{RrZM{YcZVpC1m|+exgsC!93{Mn z<zO$TVB?FM=S%a8RBV&~eSJ_&2+Zzd>|#dQ<;{NnO9Vo?TUIYya&-sR=2MYAy!EWL zH`ZYs!qiY2Ve4%dX}=(ybk{TT@*;0e!rEgr_UmW&TaFPz%S`tS>x|p423Wm~H>S=( zhBqxlUj~9tx{Wf8U(s{O^qZ`;qg+d^Vp#X~WHb>#%E=Sf!a90F+Z5^s<~ygTSlsU~ z9;{bfcIH%_Xg6MWE|#iCekR-sm`shdX{P&<YtsgNazydN$(kbMOu5obe^}-$G{kp< zWAA5Ukso$oWmj1uA&Ui!2T)dHp|7lWr|jOE78xk)=nIzhcVNFA?WZ%c=EYq65s$4t zsKQ*8#_m{PUE*8KYo8}R*Lygt-c6?8?)PH`SEzoRXR7J6P)4Pk7IopfCd02<{e<|8 zefV<FBY7bI5j=^xHFr>IribJ*&dKHhJmTWwatGw-iQJpf3od|qJkueP{LVV0I2Wdz zyI+s$3t`EOwD<`6B7^1V*c+I>ngf-durTWWd$N`^^(SPOFvPeTA)lQ0_VWy7d?Tx- z{FZN8yt(nc!yR|ww~Rqfg&34w;BL$5tD#4+rq~@hV&TWDM0Z;Ye;1vTa9sh&HR1v3 zCo4qa5A@ztOw`4fkwkl$dm2nU8%XyWCYt+n6S)oKb8Y+o`yFifMq+DSC9L}dw+=>p zznAiIkX%Ifg{Z(0y{x$1)l1ypYoOP{`lq>S*t=A@mQ{7)_7uavBrSPyw%M45d%X(7 z_@e~d!d{((O8d^U2hu*?t<Ro?b@tNR^@?%yEC^=AZ(L&SZMylBonvS%s<7RC5+Uvo zJ`dUB7+ht3l$+2(u^nr2FC#tY>$B=Qd#n$&J(r&dFQIu&^;e$R6{mc4q0JN3J+VIh zV%LKlyS;cFgI(w2jh{)`1&oJ-CkC9L&If3VB3bV!6jrEVC(lu56g8g9m@O>65=Qqc z_lnr?7_veimVZPcDA%3Ge0a_J=BXRkLT*G*oUG9A7*HO>@ZQJLTX0hK?!WDSxVU1+ z#j6hy2+<sLHCqWr2Ry=F1k?M0`6G5@8~YzytSVB62d@cA-i(cJEj|1=5V~tihYS5n z7AYz}4!`vh-a9b6EAkMvMmf(r{ZTvmFEQ9lv#k5OfN@pb1~<cwy98?umMogdct>_? z74^|UQFiPGdYfUj*7r#nJ{^omPHMYyL5*XW2xN{U*`-4s+q~C~>!4koWs&PnL?p#p z3N;@k$6AdAr0`;lmFvCoa(|y$Xn6qFlTI~VGA9COL8Jy08&4Hzef>q&19vOcZ6Bp! zL)DhFy~*m<7`J8?g5uRw6Pb$=Ah|Y`8y6w(-SfjFo+Ww3m*-mRGYufD)u7DsV5&qA z7Y5AyrMzIFZs<&y`*odcE`)g*#9Y41g_-2-#-NVN*)L#Y_encEUTWs|M*PLVzK)G< zRjcIJjKS5|#X~i_?Eqx{q8nE!&RKFf3~)Lm7q5ODK@@`HRf$lSUK&FbaR?suW(|Tp zn8RO7^tm<f@Zp7J|JGoUnEWpSDuiEZu7mx4j9NM#Y5_N$e=^&tp~{%yt91Q#594>J zI3W8WU@AD6+BO&v76&CN=f#$y0|mJiwidQl74^I@83I_Dm&5p5AIa8{?Soy|N#0@% zsuar~|K2ogP`O&ghp~UNbp7FB@VLx}JDgtF$^17|c-h)v_E>{aDGF@JOWhe``C4aI zYHG>JhhGkP@p?n--m68ec}vlek@Zw=S_etaf|bj)?eQ=rKRW<kF01wH8kG*szQ<gy ztSVC~zGmmG<HQ>_q^ObTz}heM$3gMXPTuM$32hJf1rO&K6<ydd#DeJ^CU|Md`3^R9 z9jO6*D%3cKg6J>ySMKi!em`Ys_Sso6755R2zarH|AIeB*zmW~qsqCkzS$D~yc^85` zq{lSqsolQHTSoJ!^I<hM)hcv$78&33sQ$FUz7$aMl7*<T%7dvVu^?;-b8Q?S^N|nP zfDc4zq~A^>Q=PT4Qu)SD<uE73OgsAfc??@4H|~1KvN}}n?xM74&!}Q+49ap#H&1Eb zv$yK0F<_l{2IWD&Q=WMW{S)EG@$+rR-w?OAx!<c^Q{WyEe6;`*a)en=&Kl7x?{K@5 zzl=it=uK?ArOBRPum#pE=6AJ5$nRiKiQn~Obv6=@K6B^0qkd_X2Z!cj9Kxu(4Pp&1 zlt<*n1M^qe;dY_~+7SHXdlaXA?3s3S9(FBPn8%3{62aT-nP95r9vay^YWY=4cyGrq z+V1+kSu_N(hGDj*qbd+8ET{b$re9P2U7Av$7^h;Mk4SqW#*wGuvW%gR)_0+p)e$$P zE0~;{Txr<XL^Ez5snp=zrajK`?{)}NF5OdvY}%g((LH(fr?8fBEAMqKhh8E4G#`_? z^NO5YfCE&+w2V&iE7eF?Wmi*mtP<y-U1PrhGvQ~%M(9Y<y|evx*Ms|NONCrl%0q6e zw@=ELuW{xLagJ7Z59amIAT!DdZcwx5!*Qspe=JW4R-yPerWxV`s9*pDW8Nd+cCqs= z9d9i!h_Hob9LzJt(A`neQ+PdT=b<c-_T4m0N2gV6Fk8*$!j5{kvTSfYpy$>McMXEU zO(G|l$|Y6Xn~vr+)m}7Mhpf_Wzz+C=lWpt^I|eZuXnAxOKTI@|Kl^3ee?oapb_XcG zq*`ZyuTtVQG4U$+T9SP?J0KS$;mnO~TfaML@7k6BG{u~Cht4GBz;GMv0yJqmdGRos zqKwrgBAj6B8~_1q6jx-6;F8Lr_4gOE(JdEW8sQqny7$h^&_0@jI7tj{C&C8Iiu&Pf zB5}Xee9JeMt3xp_LP<|29xac^tg50xB6C46m3|fazf4Zb>D6ZajyvFD*RlgPTIvY# z_JEe1GBgb9*dR(aIt*LGO@;s~EA)VaiB`Y7Etm>zr=}$N<ls;ooFKQmO7S^-RDMD# znSr_4Ffmtk;AW|<h_KP0n68f;j0X%I^g8bfAF0(X@Lmb;!~4<nXY3Okc3ge(vO;fq zu+|Z)<eJqL-EnuQ#oVzjle@8Rucn8+uQx42oq@dBVXP!1NI=90Ux=l=DIm}slA88v z0;id<&M4?OM+)ZRU~CHO!ZOe4w8R=RJ<vsrl06E=ip?)b$-Lw`VI01|F!!&DL9Z{c zZpDqdM5z|2ev@=?)u`H6_m;A77k|%gn~~8j^|PA?>!-|km-0+_l+j?-hM-Yc<-OOO zU(=bc8J#DZL{-QB-e8uqRbqde$yxACZKd>|do)FQ`WgJ}kRxHc^ardKb63sNoNM}I zJn7hUeO;u0TMVUlu;IH`E&E*X>5vg(C%Qu!EbI6F)_wZ+^&7FFe66}pzPh;#!tA9O zCmRb{4^5McV8hXU!O`<wzcjvUGu?9S<vZ$cSH>vU$1HP=v~{j;2gP-N$BQyL|1)t_ zNYikwJJS-J%X~AD9$v>I%8#*tn3PeY49d(SctyrqI}b5`B^Cv?#y#HG$hLmxGI6}K z6C7Me;~}sA))1!NnR}<(Uf|;nJL-?Rrt`&<$Vs=5r1^%|^6M0hWCn!4w7lMUcip=F zQJ1%|FW=_TQG<L-SD_qFp0)KuUy<fX5!#J4)a%xR4gI9VszO5u$_U$DL;GEWT9vxJ zJj&JLbQX@}@$1AskwESFM;BiDLc5yjcom9Q^g7~3T7_wD-&xV6qt2S|j&+z*DP)Q` zDqNp?UfS6s9@tm}Q&DsG6Nej!+0#=~GF9lHENbvTkw;pH(z3ciz85ItfwWm)&Cj7C zIW5cD=S4kS1$nE#$ed9Ik<8_J7#Y{c#P8X)f=|nPEtHSiTZpM0G4J#_eMomBL+!;b zdh<F?6oD)(dWakBt0FMT=JG_eo^efQit(8pAz7B^0%Lb-C`x#sDf<q?cU54kSyTS7 zwmThP{i*PeWnL*+Q8@*%9XG;l$-!n<Mj-Ex@sS-_;2t0M`*c0SX5Xjmn<VYftr~wZ z-R;@N8wH}%vs0h}a0PgTZ!f94m)kR0?YCMTLD}2CIec@1`_3W>54Lf=7gaAY_Mz_X z13~uY`)TvI-{pr!Jb=JtTG>A^w+xQmPdv>V+oyXRd6mb0Sn}@RGplwr_7ddw!cwI+ z-MzZ_4b=mSv(wj@dnlEP<>Kg=>#{3?l<lxAR`?@Df7|QQ53jkUrbE){FO>xgE0bEM zL_r@u8v3T{9Wd+%v7|GaeAr7D;Wi5Bovjqz#H}$L2Xzw&vzi?$5&?F=PREqqXI)+y z_Egg@eHIQ|21K`?9oEZLJfB&<mqyE4NFY&}ipCbjdd6GGlErLN$jy|ji~?S@Lc@95 zg6Zu)$LK=ua6kK^#U$7H)1E<juG9|IA7X2up#4rrk{4QpE0C_v^qo_XuicTNz|@FB zD!0Mk>+>*VW;TOc*`WIcqN=DhWmXwYqPp~u@Womv-<trH&prt(S}q+TUdp$G8|C)s zh*xzfWhvsI{IK1KJO_mw>40EwY^$y%uROL;BWhS+ay7A~u>XU@8jHc|^5s}#Rj4Mt z>a?BxnC|u6q@Fro2xepa_$rV3qDN<3vxDK&4Z@DIHe={pr#JCur1n)DJwNi=-pV=o zQO*d^{S=2H8OwTFKUS6Z+UJ;YPB$>;uW}QhODqpn>9g;P2VfI_vp-fw)C$$>(sGpB zHM-{&W)%kc)mLBi9ouzt$&@<%{_$Oe`&9BB<Uxvf_-eELgI$JDuJm@+Q4IYt)acvg zi!h^mdQr?|uL>9@o*m1VrtLHB22p_W4*E66`0m(j{m3T6N{kM<&!9ta#_P9{N=u}n zRO#+=ebdFEHvIS6UqGH43^VoB4$kq9fmQAX1;fahDR6FII(-h;Oj%$8IX$7Y(2cR} z58p%-K9}FCgj27!2ESY0_?PDXrOOvXBHT&f-A~K$o!%m{SWM29_nCL2TxvdA>kSvU zBuYFN37QVSktOR-Ch4M_cG<13+L~N6S7qH{JpQ7_uG4#ay!S}@XZe8N-8V}OB|_{~ z0ax9Nj!P2X8bC|CO+u|W2Za}>Idz$u3CjlAfqcSx&cDBjiyXFIHb~dr?egoLIs2?3 zf>|GwZW<ih-psf^n0fgi>z3f%t~bU+pJtzFd>#hP!<oCz4p10l8r9Jl`W1`cr3?%P z@)10iogjDB?s2CKpfK=DD}5YETxyBu;RWfVHjlhk5O7pwUM9)u5jelQ+D6yIt##7< zX^o50Hi*bn8W7soD>3ne2x~3*uzRKu%q-pgL#eGE61C1e{d49Ok8|#lv@~erZK4cf zpxZ<!gidoz%D{-zm*oY17G}tM?H?vYvp-5nz{Jco=qm_@Yb{wVU96J`T#cLEjfQ39 zQA$RSc%e)Jh*rXlp+Y4^%2yO(Q!j|awMNl<KU49q(BT#nilP5Ojn(2ul8vT1jZ(B+ zBKj9p<~NQ8MHne1woRS}c=1Tc8EHBD{hK(NP`nqwk(GG5@@h&c9XZDqngcoeC~<zQ zstelJJDM<P^dEI`pndFRsG-p$JLN;$O`|LS1;3L}fSz7A#6e#zl$wjubA6Ehvr@=j z!8F}4q4=CNZNXrQI8j4bWB!QnHb~=2Jc|9Ts7bbB1T4|Pir*y^P=B}C$0&F|de&8$ z;SD{A4;*<5WsV~P#h^O<Vbpr^NHJXywP(1wd@`{TU+32dlL>(wJ&vh<p^38(BHku6 z6GgN<^Y;QyW}+W!Wn6JkJau0zC=cQLpm$^zyXl}O_Dv?7!RbNbb(~9-ij8BUr&)|7 z@zxAYk9ZqVE>qRX*)2V0yCx}tk%nedEPKoa^usIYBcZv<tdPbWRJ7YqI&W`@qlCer z?+iG9g5wE;gtt<tbxpS!r(r&qDiN!DqIdFcIBir}st^4~3Lj<K!SxT;=hmBs<4Nw5 zKI#HR1Nw^L7bzdV5l;^i3O@ZQWt0d~8=F{Zh<*UQXD`rTJhUiA;`}J;?vocZp9@75 zDvXXjwEwJoJF3=q(O<2Ta`wNF<mjI++4XKA@7mlqdQJB?6%XmMH}c`hbURc^1dJJe z7zAGsOB}%w)FE$F<6kSbCjYp)ymG(UWYMXLa`B8-oIwkQWLFBQ>#~nFlQ0C%1=F3^ zl7z=gkeFSBYESAQ?fhVcWt4?J{>W>0O<XDj9?p{PL$t2rkl6AwR^s?Z#1b)<x#~#; zk8QrS7yV8u(*Y;Q`%L{E>oDVBqc)=U?B%8FvxG-yP(*DIne@)7qFL84V+Z4~v~^?h zQIJTCqpNOY^C`lCknJG5?>X0>Zz`b5wD<JMF|AR(aYEpVFgw?rF7ujQhvx;LTBkED z^(#11@q$B(PuZN6MN%W0lT#F|#H@_Bs8=v5lx6enQ|w1pP=G~6evJ%e86+1E(S`AZ zw1z(^O-;BmEwuW!|FWC+spk0t!0Z*{SU{bh<7YA*<^CY|Jp>eGPJ3NwI69|Pj6_&! zaiD&<m<VS?O%R3Gg<PRuRi{23^pOz<&Gmd#N+;Gn-h_!feUe+!ldSou5W}K7x{jON z&v*gyN(~H-RnIp25T-VUNb%5T^)FM2W&9oejs?!0Qo^;fF@#p}xx0S#IB6m=1o*Ze zsfhNH3W1Fi@cCh*PpOk{bn!W%4nWfi#<vq)fDpfdq<bo)oQcl;BFt8w^Hj6Kr(9L; zNqp;}>%bRLXOTTEGqj^H*uIVj4j5}#o)16D{3u_n!G(*sAYqfxN_f6eK-G}=(&o?k zr0;cHFhoAoW#@pN|6m}@s_GNP9ucLwX}`ls?ic0!yjdH@P4zo`_iyUVOvmC&oxW&~ z3JIp87@rZz$Ya#G`h%HXqc%8vXOp=<mA#EnTlYBUHHb`Xpr{gambe<uxKt}MnIC=T zrl=RAnCwZ`=yzaz(MTdPWje8V=o-McL?N=1n9xrPearQQyF#LXG7yl6&O9fXsb`*> zB`ri55%l%I7}-kYFW3s$`AZRE3>%TLDZgp-kTjY)=nzL{FSj0L_;HImKq@><?IK*^ zqZRYuxCc=F#L47B6!D|q-45mxBeNhDnMlT<bc<t9f+u!0ARg*k7c^Au*v5BwpRqCR zhN>%Mg+xtI%!}sHd<zf^5A=X)fpPt9I)yeRQ_#>(MiO~4ds?FzZg#zFt15Kz@&~aY zmH9;T@(odgkVq(EC~{EiBUyn@;{*RI8U5fJCz~MA19md3MUR@ieKjw+`D{jn>}>WH zU<5}A?!8nf4t}jN@6cuuCjLg)o=NRYS**71Wg@`3Xm~pYm9m(ruoG0^GQ!a;WaLQz z;fHUX2>08uT&I9d_z(&ARJ%ZjBof8mv85p}2RNyhIXyLBLfcR}LmV**0+Qbi59cAQ z9MaKPTLxb^$ei!jzkNGX<;Us3K$d@87tTK#qxXxw5L;Z3?43}y8ejcE%EWq1l|-o! ztf@>EldRom>U`-ywPalFRIRs{9Vv!EDZ`XoY2O}MZ_vBfzP$J2pr(D3Pbuin%V%q; zicGJcb9U{D`?5>3MZ#WV=h5mMwW_<NGS6MPMl^?YQW9r7!HQph>Bz$vgYKpIZ8|W) z<zZ+2p-QLh>!_hrv+4(HZXBo-P`_fM9m3Oba?v^uSxavR_r({WLauz~m<ejYBR!Fu z-btE6$3UEmYeO19Dm%@-nH~5Ag1Cx5RB~hUdZ{Sit<R0y9KQ)19M0TYdo^5mGCK`| z>v+mYM`oiVsh{`fj~)G#%kH%o5uPkBOn!4OUes^s_nA8D??rD*^N`yk*%;KguBs@r zibc&voy&ngMp@(N`#+Pun$FcCTN-|e%d<WdztB(3=Y8~AvFlClsPY0queWEye;ix7 zN51=hqfQUnrVlBNQ0n%7*2J>xxTYI%Ly&Xz`_MVcJZebJxwqP~-0SO-G<=#lIZ;m` zM?xZGOkS+i$A@z(#-=86_SsQg^5zFj&Xl>IW+a6LgBK;W>o-7QDwQC(a70dD$GR<b zo9GO2UD3l7`dmAY#Gs%4#3|r!-V@)x7i4RGn@)gxlBzi^2wDjI%?rl1-mp5Q+|Q*< z6Q>;LH&ieSu&vW)P!8Ew7O+(g`A<pbifLsn_C{j}NuExuIhTVIEu@zc0Va=1vFW6t zQ50pno(b#2AP7Yvd!J|_&ElskqUaR=&2T0@M&E!#gnC-gUA24Ap^*3kf82t%r;Ppn zp$%IyEeBZbKw4o*Q&W9C{0C3qb@6{pB2-Q5x|GS^I*C|QOxnkc2YpK|c7bbt1xZ}| zke8a0;K8nafRrVoq+ShLJ}?%Bh`*MCcZ2jFDqBz(3C4j556|D<?CPZ+!QS<7en}i` zMI##75veaDN+}|(WS&QzwaFEiem^+fIq}w=rCK;j4ac}9`DBKt=ROn1_EV&Hu;i*t zSSqmT>0vIxCf+1IdKScYOnGQbiBrYU*m+{iA|4r`$h9JlZrz>7DHfIb|5noP*>Qrc zA>L1sYbWt5nNX-6#FP)js;P<-&zkcc8fOxr1$)Wh#)#Sw>D?yry>&Gx2KOcD#<r>l z*;Ag|(rkVMTu;v!Y*+PA2T`<=Ks4lDsZ6+49(VII3Rp0j;p{=RSwPbq;(adVKHeJ? zW%pK<?>9&k@Iox|Fu{Wjo-G(;9nqVo-oYcEKt%}@x9QwDIBD({(sa<EJKxj1Jfa*I zhkq7jBVVMmU<8qn=<XO(pP-*$lU^BMSZaEVLZPXf&r$C^s9eMSv_?$K4je)<9@E}X zX~mP!i^T=`AOmmsUn$*{cEI$ABAS~itc`W6La^zKiswNTp&-hp{)D;~v9kljUq+kT zM=6zul$)H25m8}v8wkjpfb@ebOG(i=Gk%OH$-VikfebH_I+}S88A7f!Uuq`akp@9b z?v3a6yOqAfZLom^@t<T6BM~;=>5h<;=lfAZM%2Y5i7odicIjRWX6R>1#<E4AdBs$~ zwPfdbY~*%MhgOp58e-amA_UD%0KL@QA>6n<4G=si!aOo-VL5SmZx19bb5_*Y=jF3h zLK%rfiZOh)$&_8w@b6rv9i=Xh8{aO%lq=Q{U1$pWdg{q1Qn#MJ;aPgLP^>glMsg6E z@V4Glz*C)PT8Y>acZ*ABzBXk#@s`6UbEZ$p-H$Ecb|J6t=L@!q7alShY8Ny#@$X=j zeys7%)k<=yq}`VFw>f{L|BQSr>9tqC@wfBb2PeplDB%(#(!XLs5D4qa0r4D;Y8nTZ zE2I5+!+)<1<0YE!*lxm0UBYJ1U#^BYNF@G%6HtjRt)CY<GIM=Mhlo8@G9}II3=cmC zktQbI=rU4w;E$Pj%qq_H%#nfNTPq>vDu}WXhcq-V>$Nb|$fM*rrFy!`*wP+j!^Clo zU3d)f=je!6l#v`8Q6C38yOGk};il4y)az6(dp~f?OO!hBeRxl%x=f^W)mb3PD$&kP zRlrB3>H8QFPrpyQ-sg0MQ{|qWrZUfs4N%%_otxEjC3szlXCVXO4=o@6YpmIBkLsKk z2BXtaJo1W8wSvP2J={^BpXifQ*D(mxtlr?IanY&8GlXu)_Hdh?l#;kK@I&^T=4!)- zj%({r{MU7WyHoN>i}eA6lsArRc{dSjQ!IZhP*bOT-(ONs_elTK%9wpwE}5l&-jn~@ z0nn~P5mhuwc-<GAt6F}+#;-<zyMsu-bCp6=DhJZgA8z<-$~9eyQztZtbEe$hdeJ-% zvpb4xI>NKLB4M4W$idNqQ>AA2y_P`VYRGzv$gXEgkBU24EA0XN66YD!VdCTo%m&xT zli%PBr6B#+@@=FnHH&7pmL+@4WC^FrWapeKV11vwQe`eo`(e9-m`oLUM|M`-KPGW2 z=8k_)JKX=ZwN!+(?R8vY&<+1+<6^`L{&dWqHc4_c5&GKy&2&Djf5;<OF!Yas)CcI* z78seL{?bf$kZ9Slpk*aWk}W3iA8#3Nkb(m|(UkhVU6%6{cSA~N$*CW_00wotgt_T* z{=AkeAiHLIF7bf#M?xwcria$^nmHq1VxcyoL!`r~f9}2Mh=gmPrQXfc>OBB<9|B*E zDAp?=f%~*lLA~WqOWaw!YD!34jMVACB*uR_&&RIc77djE1S;Tn4k$@k(e1gEZD};U zPv6Usz#B^Hp~3GyTLHWtK<}%ED$e5d>OBi#Ad&-e^SWdl3w3C15YhC&a2QP08mXxb z*!Th59<)1reR*=g*wkaN2h{@%-MUAQK8BJ^g+l4tAKG^q)&dr$B=iMCG(<^hL<iof z00(<;qE-L9q9ix*toDL*DnIDtIEa6Dm~<)Mj0=W^fv5?1(gQ9W7c;ffk<7I@B$rWe zyK|5nOK71}CRchq?Dmg#wimt+q98J&BF6NR80By6w}WjdW^#v!l_~r?b$TM<fn}7; z@<4z`H@rR|2>m|G6VL!ap0y^Pw(ehv$-Nj}YbpaaFzS^r)J8<TcSWId)1&w1j0tqq zkF&=PPC7eufl{&Sy^69QK#WX@UE@oeJ%|lkeuF&vgP?KP^mVrj1@w&y*0~FeqX@~S zu~!Eo6Q`ild{TI%Q?0hE>e#<JZtEmy5Dw8MHNEKgLg0a7&KLTPd6uyKFrr&k_S%5^ zlo~h)1`}lwTbvxS6zE<HU&8CdxwZ6H9l(hcw@(Uol4)ZX*wiNKH)6BTna34f378HH zaF$OgbubtzizY!b!;+?s_U8=WFdb$w9iG0__hh=PD+HMUlF7AFV1!kazU6BgcF$oJ zsANe&Z0@kVU9#rCklWoCv(F@SBIu>|klNoyDDC?0j2@1Xtd5HfP5$YlbU2Xdv8Cup z;j^Dne6Ap1ca*8c7Y;|7lD(&V(!uw<of<aNn!iW;Vvo+LhdjNLuA^N<ujp~L#o}Gj zXmp<7-LL^iYvA3R1@inGKzow<DXrXePHBheZRLh$Chg{jtTduLi$!0pz%%W|e7#?9 z%(0>Ge=#}k_(Fd8W}<8P_a)ss0V+8tc3;RUeRcUy)wh2W-`>npWUR-$|J?QsYOq3- zLsRLrLR!5-?)Dfmxq_ftMGCLd7_9#L%Eo{K6%?;B#Xn>VSY_#6MJ=yhhvgWrR#{PN z-0^Dy)oWjr)&?uqM1<FP4A#WsABrun2~e$z$FED>T^Cwj7wuk?`n4u&u%ThFA@*xs zgK9%dc!Tpgdn&x9{A*R`YC~{x-5_TZ-@U=ty=f7!Dd)Ck62EGEb4zb|lQn0<^6r*% zz}EenYi@TpT~XWCS6iy6Ev~CgX4L<y`2Zj($nF1c1DiwaNK!zF0~4iEZaq?8H1-<j zFq*C1P^=%?3VG7@Ujv&>C$*$9|G%0~3EgX@H#$w_^A#2~Dx{!$+H}=-pnenoF|gyg zbQa{n;{A&)9_yoT1n@9D3M8a3&L>3Z>wgUFh|;{;)xJm?fxDH;wq!$0#*RDtXP%&u zWImgS>^8A&3RW2$O27TTnvbk!&|v8QXg+@icyGJzEl(WATx&j|<m?8Wtq1GFDFWA; zPutP<Q~|@bewXYp|3bsVZ<AgBNAu}C|Br!fL%3t>wzt1-c+AEfd-0EH@895ucY*Ke zz#v}RAQ+XiZ7>{FY8xUTv9l5iXz;Fv(MqMSgp=QoT#aCUHoW>06#-w1gfbuJ1oB#v zypI-a-dT&m4f3u>$3OMRh~rx+U5}IBT3C<2NlfYp5~qK#k)*|4wvntSma&#{d187C z3N>O1dSyYDy7|iT*~sQ=E0slRSNpUF_q9misrNw-o6EMcT;G4cpY2)w;JVb-zEL^H z@6Y$`w?V}G*R&A*|E>AtlgsmeFHGfcR06-cUtU&7A+r($2CKDyFD-=V^nj5dh!zwE z03c}5Ac0>Xm4p=!MmOzG?^bsHd0_)7(Xbt%46D>p0+VvC?A4D`rB!Ca@QEWZkVn1% zn6#%{so~2rUm(Mx$OQs|jN4bX>=ZvVBcc(+LO~mrheJ?W9Bqiz?$%f-y&0TV-N>Kl z$7^LQEo%^*M{i}gW1nn)l%1yVX$YLJ(00G{l(@E}yW7%kzyczQ3>xN4aD6<&`?m7& zs9?>H$74cr%6)<q(%HIPk}`Qm*IWI?;fI?fl*dyl4Eo2@8VnQtGn}F0b(ISzS?X>m z^G7H17EV<sAFZFqNz&h$n$n%vhv2obD){Ldf5Voa*E7M+dFqU}K0P}9>b+fcy6ksK zc=H@|53cOB2>CG`jwYDYzxwjn_vhJqqNecqMyld3;F;Ud3wtxMQ)(zE1di@ed;_c3 zM1!?V%ZClpe}vIPe6oGY*t7SQNn7@cIxIVX|MLCaLlE}c??+s>LbeF#!PX=|XcA@` zwQpcJJH>|C$pT5@<)5YJA1+UqUm~u~)?OQ4oo|&ST>XUv<J04wksd3bSlfyE7T=a( zdr!)7{QKIIqR0i2X!SstfuIL=y|Amq1cfiQbk|ucVf)%(N<UB#WbA(o?Cy&Xp;vpk z|242#f4oh#=m7+6m7kq{HaVgC-v%~E&mB^34|t@$?KRvDWhMxF$Tdag!n|El?=eCm z_+X$2(Q(?#`uD-i)+-PirBE~ofLmMlKmwQ;Rp*iu8-J*y9o67LGg>TiM7CBiuqvGt z!+>5?694I6C1MGW5GoH4(}&>!df6cPW=BEHC3z2ANr_XP`ykM*O-YrrjfDgTGI5c; z76G`z0|q8jo~B+un$Ih0*bj(yqRMf!ckLM;C(I>yg6y$5;7966)ci!1T5L+;EHYaE zAr|6xQ)37(J1V3-u4AK;3l=oP3l$b>iIKi131eM@lYo0A92`bMErLky>@aM_YENc_ z^@On0ZmPywBuXSdCMVXm0F`S4niOGip>>?xlrsb({?wzlk9t3`VUp`OZEracYjZG@ z)f0(dD5C>CLRlayaQfDIsei1)(&wg$I)zlZp&@LkPo~J|sRWa#zxOMYIq+b#deJtC zp~FhirNL%H8sJi}2owk*C+;bRwe_)WF@YH2{rSz)+sctEh5_aA#rRE99rBRbU=I*R z(zaI>x)Pz7SVz1<9c$D6Ao1Gwj5gA*Fq}IK0j*$pmd1jZ;P$!+ceh9(t9@jQZKglV z?qvnGl}h(UnKhxvN}Drwl@?|?9#w0>w5`GHa)}ziN=g>djd`VK_6zEmG-<R_v62QF z-yCWCB8Uqfx8Wc_1_x8%VE3GeiY6Bc@6{k?vRbsYIHHn8Gd#<`N4m-0mc3-p@#i#= zig7Q#<N$dow^kl`f#<{D`1N8w5luc3df#m5_Q~+pkrQ1u9>rtP+qrcw;l(Gp<)e0n zuHSJYe%k`y{?0t_{xMM#Fn=`iKEPZLTa^$*qPOx_sjvsG?4d#?ZyO@vjV2@32}6k4 zk<eIR=py#R89MDkd1bQA{)yzfB+gRv6cS6L>y+^0YqTZaXrcIn7<2h`noo=sl4+tb zc0cUdjw}YGi0cy`P&l%Zw+-FsK2Uz9w}B#fWArBZk_%$jLe9+l4at5fOHF}Cf56A+ z&wGg7&_w@y7{(2gqirTF01945g01miJ~C<EM41mhVNVAevX91<Z+^>|e0+8E_EOL} z7}*|HL#mYVme)$+-?q(TgP&Pnw33`PZedT`j}=DJzw5oLpKWSFmC`{*@Z_+$GqD0D zLj{+v%FL1~vlAwxIE~x0OY`OTpO!qV+BM**7mewzFF1#We4yWW4c_S?ca!dsBb{2D z5Y}oWHCA%^#B2!u_gx9!uHTVslEsBPX?`p8=&>qG(DoI(O0mK(Q1$0PC~1X71SQuy zUNiKP3Y@Sq!@z0a*;uIm^v%B^y%r^@FU)5kj;BLezJ#&y`^D1Hv2PM%x{5>wFFz`+ zybcRq2ycTt81H%xWfA06Uc(a}$6y8&Sl;F45z~BqphC9J^Y0{|nb#0GaIbHRs>iFb z`AZPX6poyYQ+5N)SniPikRxqxFrWe$M&)-$r)+00XBJE4sDPmK-Ne>Ny2u%$V<IkA z^&*u2z`W7j5C$20a)1B0dkWR|9{Nv8k7*;R9J>KGU1n^+_VBP!eY8R&xEeyLCZbdS zZ25=0lq=mZEE52Ai(jA_{CBSZ6z5}dGha7}{o7aBUOZtB`wC+4{~oB2SVgNw|9C2D zkHwwk<{y%pk+h8k!kZmc*a~Tca|q{A0IsUw>S#-&d-vAc3zwSZ<3XOTeEsTYOW#UF zhcDzl#QY^u%|%MpE?N+<R~|2Eel#Mz-!Lj~RAt42<v@Q@_>^;8{Bed!N&bz<U&P5^ zp(C+X3>w0m2=1hHJ3H{u0})|O1Lu3SI*1=qBzZb|ij)zlMD=U9h^jLT`|bYmV`KDZ zUvL{43ZCH!87uMQvH(N|f=-QGI|uKB@nCOJfDQnm5;f}oxWJM^ac3bn((&@}FnRCW zaB!$+vHN1Pg|;`lJRVr@4{5K1G2@lH!hlzvru00DCz^`3fTtlmyna>Gqz5JqLQ3yL zZ7qO%tuU9Ahz_KrCH{_EBocQV?#0MrqC~V{C;iO%Uff6T^|_bN86zx}Bn>1YBh#_^ zrU0(TCyH<ud07{tmh5qKD=N`DYJW8(y)|mC*9g2X0vGpwItX+V(G1XnN`|A#&wzml zp3|)-zc2tEA1zoHRN)=NWarL-#yOh6P_}@B=yeNXOdTUNnuE^NDW<hGmK?0R>&WB= zgW902#9sjo+eofF*l*9c@r5`_I|dq>c-_I<RnLJ^C=u2{_K2QZ4g+64izlt~fE>gS zCozB^&<#dVNKYKZ$iHU?d8`SH!V|t~iSE4w(1{SqsR(k>7)US$*w(yI3rQ~XR2P>B z%Sa*%PCz0lDC=PJrAgQ}YRAGvLlZz;l9<%)DY`C54fm9TDFq6Kfa*QiK#ySr47rgL zU~EKswL@J~3p?jcsqnrnix-J|ayyWbrfr%CP2;P^loBiPe5nQKZ$(}V(-~<elDC+n z6T{U#Us*-PII3~9%cMEC(Nd?UxsuZ06JI@IdM$y8e0=*gN>uY%#%uAqNZnePB9Q!o zDgAn(y&IjveA1c0(XL33$i;Mq>F9W-4B7*cj#l?%p9}z#z>*Z5zL-H4oRq_qnSUcw zDp<CV>D4DL8hfA2;0$WmG_h|_=Ccg=91a<W243NaEBLao86;G7-VmfG<bbGSBx~qI zg#7t!NQ$0n6!QHd(CeJtSYm)kf2!D<F>`*$*iI+m^_ypWbo6S9w+Q{d%MV`1z@eNG zDeA9s_=z(&ZzMlnm%ui$|GtrKpZ?MWxO?s+4N-o5!k4_1XB~6)HtxGh&jK4PGncGA zmtrZG>TfQ<oJTF2M{Ai!|00huGmp7Fk98>z^*0aAoR5{w=d{e{ev!|cna|&zFSwL1 z{5K!RTp%V}AYoY`^`bx~vp}}JKz^y<=HCJ(=0X+OLN&`mjTePlnT0y-g?dYc27e2$ zt!rc1qH8SA>_w49W|3ukk@Zs1-M>Y)%*FPy#g3N6_g@q{XI`_^#jZ=mZhwnCm`fhZ zmOQa6dG?~jJG10Pdx_stNx<KdAm-8#+0wvFMA)uCh;62tN9ij97D_aI2aH1;^^_*$ zKS|UmOE!+Me_58jRF?C%ESI@FU$(r^vb^|3d1+>Od3$-~QhD{?@>=GKdfAFb%Zla~ z6|I>S?d=tvOBLOJD|(nK-^*6^TUHLfs2t9$9Br>0U#gt^TRFvC<=}&FrXzd1g3QMO zF)Q#k07O_p%q-Dl1(C(zfjjf2G)OX-kt2AYQm~!qrV=p6Y`UlexZ$2zt-!=;i8Ihh z2>_%5Dv03+PWb_WNV1bmGo?RX#;c{8wISq^Mw`r_w5b{jE})vJOyF+~B$(JRh*(4# z$Of6NyBLz&kwQg{oD*T@wok}CvxIfD!2tA~WW6%s9>4&41q~)E#Q|w6zOd;q(ab8Z z+B-$I4PXzL5gsa^+em6eo^4y#G}QoGEroj`P80Ksa82)s$Vhbo(d$bb-3Ibt(hM}2 z4GUCd1(tl4pAV4j@&mcJJCY!nYi?D{egmmpvlk2KwFfY<kKk`7&BBv45Vd#+0O|Wp zFy$r+@bz>#nZE!~k!w7UZUqN5VWLT4qV?IhHW#ioxrac52T{yagBA-&{vnWZop%C} zW%rQwtyBrMlg>xCLJwMqr>{>>HH)JSJu$TziS3Z!`fC;X%SyF?PNxJ>i?bCVg9n;$ zKyeV@A<&+0dkw*Lg7Md&6=I!$qsr9H&(7@v_p}l?+sT6Kn`}G4Q!s_Bs$BuVIi~q; z7Laz0#N!Yva#TDntsMV4@vmATtKB5X4kV@>9!ts*1AQ(BT+`<fnfW_%a(@zm5585z zb{$(C4RqGP5laX0IPq*y+aVgkUfx06+r`Rp9n|juClY_QA|I@1ced(+=8;l}zJmqV zN8%eHb_m`tdHi}ngaDcR4=G{RYmTg!G`LT|uRHl6S<}83@dZ*hJ9k|dSS0I%gWI1v zB4|2E1zAC}0su!$ZQSP$I=coMir%Zl0czQn_`P=be|K_xyNOoGAk*CdrtQP$n%SOy z=)tv81NtV=OG$`s`h%vTO6o^Tw&3*)IjqQvrW$fr21rhNZRFcZb1A_}2$F-Y<nm$U zXdAIzYcly@2FH+r9v~|SybfyAtQZ2X3@{&bS#(fFSdyr?B5DNl)W<s^tfuSN0ULZP z7*D1p*cQps5^ptx4DMUs@5*-t+WioZ1>Y32cEiC<O{`=C7lu}@W0$*RuP8=HdPe|c z_ctrx0O(z{np|e;=DC=3x9+wuYi-qg_rn!w@oy5m(x2XuYvKEz*od61a?%Jk4zU{@ zSZRMTK1EWAgx^8r>XCHrBaU%p1YGZD!K@y6DtFiG!LRocTxBG2??1@{&Hp|S1)HzC zB8v#wh_yt-5{_gHjp&JO!c1gYSRp>+ffhV~Q;_3-)8yXy{xW+Cifmy*POUJ5XnyoV zE@w-$XCR`aPxq&Zm8S_3y@c8+se`VlY=q3G+!G~$=n;8DMK!a$)%iYRV5R$TY?RDs zkUDAZn!$#%m8HDM?78>^o|<36BOYE-q$@SqvZ*fn0Uv?}@o_-fcq_dxGC6ZDx&0%v z6>uz{nfw>=1>G9Z(|>|P9OQO-%FS-1BCd3SKe#!F=i*0!$#rXTCvs}ROGJ`B0GY_V zB?LUJ{rK=rlZpO2JXddm5Rfede5h?F1-HBs0v3)x3LXp|;}Ky(*TVJuA|Y<Rfo`Gt zXVri$S$gcJZ2_|8hxK6KlfVJu=~TPP<x=7Kr&KhcI!>99)zmB4vQyO`{0R7l9=ww4 z?HdDzvd2sJzey+{-YNi>Uo(USKX)qtu|N77*-Zb&4PWK9eZviJU+d!Iq_Z*RGZ)lC zLYd3fh?uE)h%&-c4=Db!9QRdfRbURBJFV*Xex2n5Rq&{gX!mc{FZ9(D;DB@z1>g|f zm+jx{#|B!JL!|r8?H+DGg5f`9r%n=^{Hi+1f}72)$x<$n#e$=~T_4>kmR-*`>MjxK za){4UU*z4sK$AWUHhv{uojt1kvV<mk@w1yoeUmn6@knW*O9&Vv_@^iT{q*ujl3wMU zu0l7%k9R)>cD~m4^PxbhU0*G-cF66%Gb5)m4S-zM)i~{qNcr`kDl=6-z(p81=;)J9 zLVQM3E%{}L`Sk|)Tf@63iS&V*oDNFSEp+hrla<XgAq3*OTtXNSW9{#8-KFRqdOG)| zSfShH*XDEiYvruQOn?R+*S117-g`4mEuh698}a1ID*5l|RW9XBHSlMDmAsDl#U-)} z1-e$wXf8hcJorg}b86bn>i3U5ur2&c?f0r2q>3-i&FT&E!1V06g)u7p?bx=L*+1wo zKSgl0IMMDC^v7kFjYmw~oR@py)*Iebrazaz9sflBvY@#l<ZPC(9jGmS=loe6GDgB1 z>lJnPfS|Upx%7h_0|hf}oT8_6*+4wjzxK~2F*Xb7EZya9R$)JhO0Vc;L=f(Js}%;R zJwFiN@Kfs(s|E;TUPZv^H}LH)jf^4?fG556^E>vz;nhP#$Y(Nw((1!+x5aCaT>xk( zk@BFM8f}9h5<;vgox=F$X(&dA6v}uy4+Gwwd}E_tw>^@;^e!d-QF<5qru#ULV&OFV zq?za(>@m!Cb7rmMmql<B-MdYV<<n5!US0WKUe~>=pamhD6Lit`N9)z=27+^?e<pd9 zy6i)0HPO12ZM=ei!*9BNK_h6{dv~e+-Ot-5UENb7xLrKpMXW4+2^m`~7VKT$`?qN_ zdof0N>keW$>%3pFpji<S*)?}`we<F_nYSB)<t`ftDbk}9LPUvDOUJLOL{R=8%}3>8 zTLe_?_j&hg%5$R)tz<6!9NHW1%Stcc@8VRMZrxY*IrpA8;BnjR@)h^Lf-#%$>bxSp zeMz3^p52+K`sQZ%?%Z3Az|Um&S<*#pOsa`X>I;jJubV5apng9y&3;-|J5LkWYT`Mp z+MoWEishMHmg&a*)~FhKVryM2Pe5s8w_+z-!I}IKtmlqn!I3|jHU!SEC#d7dyXRRg zB}{T6*cc=PypLTzQbI{e%^RO;FA@{>h;pT$|8ZNUGmZbObN(bK_Kh!lg7t@^o=28R zF&no(i%VDW>njc|%l*{}Jt#d9{3`zMtXkfb#KMsmb^qN453`7jX4bc*Uq2Hj<vpls z0)<}PeJ9d0G00brdej+N!Z!uW{tru&cRzQCv9MP7)f1LdDz`+-kv1|#d2NBS3*3%8 zKxbUmKuP+SyOYKyth^hvmAK8ms~0A!8FiQ<0P-B4Imq4JLb_H+6z`7rp<hcxm6TPI zq2n5e|7zrL9xcXe3sH_D_|oieMRf>qx$d&7MzT2fihgp{l0uUwQ))_irHbB6-vu{J z3LRJ{<>I!P9vdhlN4K-mfIL+~R&n}YuPJojI_ZZ$D->P^v;9b(AaUXbCpj**uQTnw zK?U1Vq<ln@bGW_5LEW~C>09`NG$?Lf)U;kS2+r0qloM#*Bso-Oi519kCtjkmU{jcQ zDHu|Jpow|~p``CuY|!Ivaart7M9aT2Jy8kC^b}koZJGDv7e$01zM>uOHO|;tJ$|M4 z{Hg0H+UNJZnYqeJ>iLhf3KgesH_zzs8ot9S8_fxjQaU>!N@8>TJXO5K+CeI<TY9is zm4(A0DAkywTkP3fqw)IcujY$dx;9DB(JeQ$6I;r&ujvA`Kbp-}mYDK<ThGm$PP30m zHibUOrDw*bQe~<H!>EM`yP(PbIORegM;fcZw?u~W6#^zB{h^X(q#weVyAZoVmr*=# zUwH04WNjImtZpFPGy1gS>l3Xj-L-$e>PO-QWtoZ3UHYtj8i%nPj+&c|pAJ681~rIx zeQ1)G%W1v;3Dt~r`*J^2@sIBhxB16nZf%Kwr{7Lqjkg>fY>mvJedoR~jRv>gX!0^Q z-!3nC%J5*<_4Ch;+RyItDlS@!SJ^k8a{J7T*47XfiMd@40vgVIZ*uLFK2k#%9&VEJ z9M;{i#4H=`5xtsd9RD+_QxjAb5fT*w(;3^Ia%>L{5(e#BeRFO+lzim8$!-~puGcB3 z3mlI__h_T7!n{(`fGEOqCe8$%py$eF_n@c~8O&3D3*~Hoz=Y|a#xKE75uoUw4+YLi zg11OimO*3UKX)`hAM2=|(S|XBhlvMuGy#UXGMDyb;PbCRRa!8aZjoo+&NHone?fiB zJHQ$+0H^Zs4vk&0rBc4%GSKoM40V`JZoF1fCr6=1<+7^bpfyJeeJrZ<n-MMr38H!m z6J=fHh0D=q#Crs(vN<~@d09lX-(ZU8`&{5Sl?((a%HInl3Dz_|?4=z&N8XqvW0&gj z)G|XoMpwDs1HG@KlHm%!wXcj0wf0t$Dvl<B-i9K>LUd$Mg?h!6iLVQl6GgDbY2;Bw zD$OdQRwI2j%!H9S>fh?nP><d;rQ0LD(KlEfmtTr}Inn^BFa_NYGGg2FC{nS#p^K%j zOWK{9Kf77dC;4DgzB4Fpeya9mh#oXsHbzxwY*DJt4*It8n(crD89J$OW`5ln1O)yv zE%F&^u95AeT1)W-<k_RM_enobN&`x^>MBiEJKo)El&-C+R24g#asbnZC^d1`gfK@9 znR}UhV#lGY9Sl5DqBOe`>)I52E_#w2<z?O@%rGAfEHrmGW?v%m%%p(c^d9!QjRq}} zw7c|vjz<)RRyO0iXPI;q=Rns_F$mgFQy2RHDs(`fnUGi*r6gF#zbrlFeU(1R(EP@3 zjq~1^2BB+fZEknu<OaT@Tvo~w`L^D;faTt(`IZ)@d19U2FCAw5VrJ+hPFU}daaD;b zFX_<_wXC$CtJm={P$m^86BV7Swyf{)Q*Twa?-ZMXANybbFUIcrujx2$^!^wFMvrdT zV01XTVT?}c2I-I*h&n=rZNTVG5$Wy_#3Dut2#QFF0|8MG0Z~EJ9j@z~b6@v~`|-H{ zg6~h?@Ai0qKJVwt_On=atA}Us*lB$Z7~VX<F{?v9?!$uK!M|sGy1KIIWK-W!{3^E^ z6YZPb>CDIu(vxZ?#TjB-g#r28Rqw|Gi$;7@6*&L2+)ko@nJB?pW60p+K6zW%=4+4r zPiU@g9=FrTTVt!^qlvJ3A5U^#gQyoj7)o`(UQwOej<{oU_e8CvCt68L7?mcga~X;! z0NK9@WJ+|8K)|~-iZ}l<gbVhNm;xsR-f>S#y(TA)N7p9_=#_WGU-RR&d+UwRef`b) zu40odh%`=l-aS(!A$4sG$LFAL_V%~i_JWCi^%s6PxA~s}Sa{!5JTBeY+i&yUSt1kc z^UTdFQ37#`!hotHg{%;ZiaCpE`h+1gz_Yq+y8B%1-SN2M;ef^9fP#Sg7<JJP`W|K; zCe=*MYj$O4&M|j<d6k){s+nc?SBN{EhU$uXyJ+6TQ1$#Gqi<S9XS>)?N7=O2p4tz+ zyC0Qe`PWKbI=VWPtW^^g%Nrw00zY;Q45eIIP^dRLIF<~cytwimK+?PW#G!p@Y)H>N zMQOuEV*G^Fz%t(MSN8!MAQ-r&G9DSCu$e}t&#LioQ#a5ns41v-TwSMIpEjF(OTa;6 zT2gp?)zY{Veip>3{9L2U@rvX8GDbwW!OmX9)%f}@sR9x(Mq6~kdnx+68s-vU)%37~ zL9bqD8}=}TVVM<5_FD(ps7H}@mpVk1;A?xPl`S6Mmn=lzt1$x@X@RD*^CwtJZ&-#@ zBTMyL`c)kkme(OOQ5%<&Igp+a>Y;pb@nq%~3OZ3nI(bOi1SyM@ApVMcvYp9C{MaV{ z1NlceD|GMZNb%cL*ZT8Y8^qOGY8d4o_E#?_J_smWkpMIJAt4bnE=tv`HVyT6U5@?6 z>jFp^Ktl1ew|2x@4bR@7aQ=O45V;y!%4K&Uad5sN^Mgi%W`r3C_zh@%eVP*KuX?vx z`t3$d%&!WsB|0oSLr3l|t=?E><V@Ub5FhL*w>Oolar}k*2D=q_h!=>a<Vx^{vW7(k zF~zt`d<d{N-z=vy<vpWIfL-RZUHa0`%HG!~FF>d)OS%A!H83zB>?mW-_r;{M6mI@; zB3fq{rxR$Vav8T-eaUp~MoV;@X6dAM>Cr<#309Io+b<19f&oDZjM>x33uF_PTf6m1 z@-1%pF@ku8D@~^@9oxB%d=2N}7RUY@SvEgHD7{)~V-4U;l#tNpOrOMefj5^R2!H_v z3cbKBCR@580b-V%2$-xg05XRTBsMlU0riL_I`EUO$n;9Ksfqyzn>+&Fnx}nluPb+X z<RO|eEoeB!OCM^ERGwiHP^5AiN(6K!*@FS*P_V-)V+2BOc(B@7i=`G*S>!f?btaam zVP)V1UNAt#onZg;DV78(kV-PVpX|Fy&ww`|La5v%2#M*VfXhOTHT)JvN7GOA7Vb*k z2v-~=CDfVgij7`6Lbp^6h=Txm<G{QbV~L&eQZ~;#d$U6d<ZTd5PTb&Y$dpX;aUxpu z){(~YKuQGR3bhC;o&=Wc>A!nggoWrH_ly8c3{sqXEvyL&aPTob72<MmCo-`#|Hu|S z38)+<yRZufxM#9zqAvHJ3ArPXSXm%H*!_q>+D6+XaRhht?3b(NBTZV>#u_aNu-%Y} zJwMn?f^grR5IjFj&|(U^NH8~{a#kXQRMy?j$hbuh2qjVP^R>n8vu~x+$CfYynjVUd zXqTMQs#a1s70BbfMj307SacF2Xc|hJ#Ivs;gc);g>2fJaviu{n0d0?V6?*~gQ(tNK zZK^m*V73GdgvikDh!BJZ5)&n;`qPIJkF@cKB+CKAX??H_a<Z2{d!3ESzzxqlKV<=( zsmFJ35T4_f>x|V2vCDLWwrSmJ0$2$u6^7Y#0tGK2aX}hfqeVz#NU#J@oly3WrHB?3 ziRS$K6xhosQ-Y}rl%V04Ig}<*>s+({xe(VxV^ER{ASuyqCf_-qv<IcVq%^|q>0u{9 zHiTJydvH7d+{fh+YAvv{pA{_1YL+CK$!D2!Abw?qI<}EZL5&bOPyGzTP@$FTqSWgH z1<S(;3I;C?D2=B<y7p%#SvSUihGz2I$MH^T?-)p8@4xa0N{Ly|Jo+tp69TvDDtMNV z>i$M~4V@8rmh3u!w<QcAKBD9p<_vqaT%K6q=85>mBxt5}0{h&wfw6^FdJfT=STc#n zOgVYYIU$Ws8YQkfH~e_R>P3;)t(AoH(zF=Bn-778Yb{9pV2d1UGB$w<i=@Cp?eKfu zv-Yo2OH#(w#>D*7(F_0qz^G+{xxoF)a|SBx<kb^r8hA^}y@9^(!m^xpHGvY;X?9>L z0dNw#Ep~v)9Qr!ZI?+q!mF=GWn4h{*82D($PP;Ds*LC1!xRaD&i3g9sdd&m#sAD@* zFcQ3Or3G>Ggq$;+Dh6x}el3os^u37_MiN{PhGDW)SZS(^Z4hM}*shVvNL0b0Fk_o2 zFVKnKcE8Li&YsACKiW>ONIZL<M*n<rNjaA>bGa}BLv4Qs(wCl0kub4n9K%6h3;t34 z`INw^B*E!m6ZSU4`TbN9w-GbL(~BeOU_wsB0IR2;Ao*HhQ6hJ;B|$&Q-sIl<cjmK} zt_Fj_Ux!zE38#NR;fl)#h!ueK1Ym$VBFOnyqhjb8A+c(?rpY)i)Dmq^ND2cNG#lDO z-z8|hPB(dFA(0%69x2SsxKg8RXQF|1Rx({D-qv{caj4;Tr?S{=uHb0J5erq6z-WFM zs+>PfBU8J<gHcC-U=48Ydzq9-aG{IoHqsFK+*QpbmANzY3;=Z<5_Lmlx>bT_4}9IG z0Iz83RxKOlyJfZOpJv0b&b3H=H(1|920_`Mp6PNe#ghKJKGk~*CF?W%#NP$xO{w9s z^!#I29eC?2s`rhLyA1g~zPET3y^(hU+q&ktlPOkQlh=ydgP+kq@X(Dl#Rpj!+%Peo zc0G`gyKl*RZ1VPF-^Rn78Qjo&kxXU3q2y>YC%Vn1Z+q#to^5=$q_>#G%W17%B`CkC z>jFQPicnj;K-Zy>3UOLRUkpF|d!Q$9e|G)OP~sl7>&<LTvu!M(;`8YT>RmdsWx&Cy z!kG+#aZx3FUQHc-S*YoJcay|i1dbB8njdD7PPEsEXYu=!g{9i$te~~Gw!KmVjw{f= z#ivJCB^pXv)w;1MSV7APC0s>F+6fS@f)yhct)iDn%<7#tE0f=mt_g*EQMbxZ_#`SK zsq7@yQ|1Rg^sNc6u0~$KCB=LRXic+D09n70>cc7HEATb$To)6wQH8^6k`R})0gw&a zolXTjZb?Ta0;UYefxX^ruk(duQ7B1J>E0#iBB*qdZ3XiC;!EqG>WFCP2K^<!lp}yS zB8l}b_=B&j6pZA%p6AOmWT|t_QEMd)-5PJrSLvOH8KKrIOZhYD;?S<XUO-qZ+)Npe zj};(<UgwWL@qv^YmmuXmmX^4=3C9`W%bzRm9I&>dMI^g)58!DKkY(#+up-kZp#3pE zF0GHBP*<JRz1NPycJsAEroOt+vId4xIpr;HC0T&yI#Zkj@;%P`VyxUvbO^+maX=&0 z>>WZN0d~tWGY&&@8{GOy+lw41+>w3cm7wCRlru$SNZ|4_sQE+vyfnQdVFxhK9Ei=m zfSYDK_q0N{;)Vuwr~<4LlsTJ(L%A13by#i<HL%~5FM8x@R76;}v?}7;F^(=&xA=@s zP;ICDvTvxQ!~IM%$25Hzg~QSU9y8r;yh_0%EFwcF=ALNqbm5cM&o%<@gn~&2Z(mb% zhmdw3JQ9xxqFJ`iM2m$)X?Z70BujahUkzsdxXQYRFL^i@f_p2k$pqjTm`x=4r=97> zFiB(4G$Gsz(58Lh%WHR8>qeLC1bXn&N?>d?_*ITZab-#vdc%J)H~h$;%Ek0mxGiO! zV{)T)$`OY~!5)BCjyzZN_0{h5_5(s2vh=93#ff#BEtm$*r|QhJ@!^*D$GQR``rzx! zyY07_4b#Mjv$UTkABxEiCZQh<0E7#eSl_tSxc>{E59>w7Hn`lXpRuC*?D;LGy=B|c zqau7dqB)|w$mVtWKL0{%JwNOBuMw6TbhptGneKV->hH&^%~I<6^+4fYi$s^^SO^^b z4-3!=Oluv-g8*{QO(YFG|2-4U<{ar$>T4O`lcP$B|A?fhV(_TONM&$>2d1u44Q`jr zc*iI*AUS)jMD+RK(ffLW4mW|P;}~#Me?=fouy`UfeE`8S2L0we$4!Wqc(yrmm<j>m z_i(7A`Y6#Z@*hR|cVkfj^)z~4wjSt5<qlv07)pM!^hPY*Rg2Cz_Zvb??D{NSvuQU{ z&ule?2q+0kxn-kgTWR6T12sMKI=|2oM8Vf=Y5LQ;$!hHa*>s@^D%6e<rsBq`$LYVQ z=_**UOcvlwzSDGT_=rxCKj#lY9ZpQ;2gxg11$&bKM6{VGSfD@J?@v?#;gid|?Fo}< z?|TIC`xADJAr$%FM98g<{b2dyaNh}wmC5YETY-6iu0w@(G0JNutUzB<+wHQI%7M+z z(Ocv;X1{}5PR8)__7K>C&sQBAoSK}s6TM5sukU{=4pAx(ZV@mKuW1FU#xo}b{Th-J zqH90VAj@uLS(9%^wYKd4R8L?20obFw4Ag}LDd+{(4aN54OrRfHV>(+f3O~h>e1yr_ zAB3~_->71SL+ZAs4^$H7^2xMQg;v^b=l`fI;sD(Q$6HvapRdG?jVMgam#shhl&RMv zHKYmSm1mVNo_q}|1_vKwoCvVrKQ)W@{%U^a4m_3UXmn@Bv_AB(-zxBpNrC#s(nNp_ zSZnJVUU}=n(TyR>%TF9)>FWPvr3YMW;;WE9cL$kMW`5SsJUSvk+gZ|MsvxzI-+ztt zd*W>PK0g6>@<xZNoHioix736fM*jSJR%Fv8eHZ{XQMkB;`D($Hin6A>Hs3NurtN5< zA-{X}`%Q;>p!wJ6lpA<vfcm6vMFT;Eq1_mp#<#>@`Rnha7jK@CzVC*b)u{&OhsWm4 ze+#<(r7}pB>SG66_P?JXR!nRp@TXinQ24qo0mj-nq#00v=*0T|I(g^Ve-(^S0S{7x zBQ{5<B!Z5hBX~M`Ci{VK7?HqA(;jyw_d)gEFZlmj^O-J?a_SEKd?HGWQTX)!iE6kz z;PwXekgn3|!BDcSq-zKl(sK9#f~$R$bLioV`19*>ZP$NDEw%n<&FAfoMVZPA9(I&I zVc6K6iMq`!#|t3WyWTXafhf0ay!Pwl>;A7Rq#>-soHV!|%1Fk^PebwPZzbM6*&Mt{ z?-haAohehjad>d<W!X(bFWTCov_CY6TOPb=fnGC;E7pC}9(JK}xK0;21<q-#WW{eR znm(V-^6<bDrLSmvE=Z1J6>i#fg#Xp}Sr?*C7xtCWeOR07o=&fZI^faE?hvb2hyS$y zoV^Q%$V&u$Z328HL=^t{?iJ+}bHmm0fJ00OODi?tb?rxz%{*7?SBLUoY6p8k3-)1A zUYtPe8H^y2>oA47a3FGFme9v0fDaBk?sgR0idJ#3Rg6fM%5OVsaSA2dc}*QEZshG- zNi|GrR_6hWk*-tv4p}y4>Z0*v&{1|Fd9mgiK%6y(3rFUV|MkkU+a^Y=EZB#7Cy_c; zgegUranebX)b)1T96{ZgS$HxjQdpKqry+68dex3u6Z2sAEs{jbIwWVo+4MT{fT&jE ziN8K5+29yS*mPnSop4USqHz0F76o!evZZa1H#bq?FAqTbAYQ%6apLRZ1ozF&>DR&j zb3diJ##q-jRL|K#QZ>epaF#+Jl><YfzH7NucCB1DZ?x#n%xBi7sH~Zb%=@chA4%1= zT&+4I=TCZcJRP@dsrt6ZziAg6T;WS`%8G=2Wx%wXp#E|VsjAIBL5!-I`Pb`_WXi%r z<|1PtdYCf!qDGeFI${#0$h~A_T4)^UIN21EkwfNfQ9`s)wMi+=D(_P_>ZzK(w0_}q zUJS{XvEhWKsPNrU3hy>e^0%FO{IpQRNM3AyN;}(rU4>RZL+PDI#CWfsZl7<6A3Eku zmL{FH0BZ%e)cvM+kuSd%TPUyi`WGKqFF6eQp31ANNIw3Pt!2HbrMi_GBI<VkbAkDh z`9Hl~TYa?4<G!uZkmt5>@0p&+Y!`fM*~V1e1Bq!-fS;)Ew>5ws>G^epm7{2C402Up zYwa)}v|s#-GgcmFV2Z4-d1B?ET^N3I7;UPbS*S><tNnvo_HVXs@mmpe@puQkKpDJJ z`ugfS`+GXS)w6plET^CAKm8@exNWJ*oXcddMozqT2c8^OPu4wp+NYBrY3TIzi;Kn} zJ}(V3D)6f$Wey-Qyu>qkl_Dp(qa?7fifSm{l*0HA|4Gg*w7!VweJCA=I7caR%)*d% z=)lu9SIpal>C2uo_(eg^VqIrS+4p>llSrQ1(I1l!r!Tpwcf);NA7Sc$UZ*Z~WxhJ^ zOe5q^6yCyT@>RDg%L;p>S4i+|yL4p`6zBUHy4h~jS={@`lV>~_G_F3*82&QO=X+5h zBvoEKE5FIY<542pjG+N0T5G$dAn6$ZA)b6$Ipkm45zS@@)90a`+JrPs>D^?)(%I2y z6x}3#d%vTm-#u<6cAm?}yUmBk6CRFxkB}{2=ed1P;MQLEX1p~+>!FozafK4u96k^! zyt(JBH+eeks-WnW@o`+M;78rW)YWUDGM0M$!H_g0waCH#B%)J7fb3zY(u5+MmNm^? zdaDi-pM90vVv29dn3>f0P3yCo)JN97fxbeR@M671<NfQzZYfRrZ+lPPROprZN}H)P zaT#M9spG@YCMZu239sqFJz`rXXhpZOZZD3SJ?*5?u6%v9HF^XRtrn=ibJJSNJDC5& z*@XY#f*hQ;R^X<qao)1+EBvH<DaMYVMrWIeo!Kl$cuZUFMcT`_G&Lz;r|o>39Xbte z7)?h_-1SmhKxZ(+_D$UM;;+v{zbE^uyj;)!;v;6+W-aPY-6gH;`Z)7_*bfKCG#d2< zCAPSXQL|;Jpw=%{h_NfKFm&nzDvg)rX<@72Is&XmpO*8Ocf0$J|67~CEP9rP;y3-@ zm%RM~WL5-`1UPI(xZ0At@5$H;$8S;b9Sk$hJtqqN`<|kL{#}rSKkdPpIcNb9nOpUy zD&3}z=4mcDAS=~2DwxBu{mNLL-e+G56Dib}F2;@Pq7F$5=4P3E!k_(d@b5t#+SjE; zUwP-I`NY#7v%X%&K~v(MDWrw|ddqTb=EqceGnI;2fzO^}+mnt7iG54|u#j`R4J^q! zA~V_)Cm}7Q7bRnA71v$`6fGfZ*;UTqZ!h8v&Tg=HP6fe2dE(Bd!tL>$S~3<+yVOu# zR<YF5+SLAxBWKtYBY@fCrUZ8P>V3F+Mh;=He;h&#^FE%`8#dp}K~D8hbQVQ~xckj| zolU@bi~~MK=F9SJH~ly|tbbJGq_c}=oWdk4qaODF%7q1>a8{JHOKmc8SBNV1_;y5w zFOL9mxLkTBbZ&mvP=sjK25v3wP*ij!NedcN)5ct@<9fgj@5&t$OUTP-+Km?1J!3P| zpZ=b0ty?Fk;Yo-$?*{AetGCd8?&~=3-m)kL@ogRO-XGKuj0pN}LbD*Mp)~mcjlTj2 zauIy>)Gs?i3j&)cB2RX*m4^^Wt=bs2PZ@N1Q|ptI;?hK=u4fOtdB-xfQ@UFWMP3Uy zc2Www-njwzSE{P^8+294g3l%VeQrbp5qnEJO8daM#%n@TwMueT`%C0YU}g;bV@2ML zltQO#b#Rj{U`m@UC3HfmNddnTIHe<ydw&x2bhOQFLR+{n;-!cSue!-6Ejy+APW;0D z$=vrvZ39rVt;kRO^VMbcVRsZev}n>f|4Qi3VEwLO&&qIGPg`?-64(wD{;3&|M0*s2 zaE|gt1l_~J=oe3)?15Ko6zUgPU2C&s7~U<;<oUm2aBbt7CCHF5i8j&pcwu*8j`kNe z0cqJi!wM(ZA+qG1-E3K5fWkF!b(eGYi?wHp5Y3ZM^Gqy4e11)<Cq)<Bv|NES34Pp| zgbGTzc0i$W{1PHrc|<%b)^ZT~G3kZ@gZz53ul%!@590u@=L4pTK^t`)&wo5_|DD7h zwoGikuxWCHxF^)IMiHFT(;9_Bz<RVw7+uC`bVk_P{t(q;N0j3rV`lzy5o%>H=bZ|J zd7KtT$lD-a?+m3fzxt!e0IhBPb9kEe^8-DLQKispm85bs$kiBx6F3?f$hpL*^)))L zF_b4kz<LaqM2rBax{B?F_d?kYzriH6DnEyksX-Wv7deqP!gSTd9z~D(pz&4!WkK0r zXdrfnj8iGMj_P}RGbew$3!i9WXz7<{kEi$hL$7aOpbHwhj9}2Jc>cpvs+6M`z=^yC zdN6jZ3qMYr3TaB^{&SgfuJwL%!AvUymwgb)I7fhTgrv7znC!4&d#10&4MpW(^>Toz zr(Tqg44RLYRFTzs1|%l~s8~Dk+4g8!DX&T*i+nIaa~{Qj9_9w?!N6D-D5VkRU6zFF zzcA1S`>5Rv$V`jl$IT?W_k|gHAQ>fWcV~sDQMH+$nTe%-{M)4l%h4>v=qCUtbv;qK zYWSRks0LVaa9=qI%fA}>=HPGIjRc%#C5($5*r5bunNN@woAI2oFzHR130@bIBNH_R zi58+Dg^FRsLA9|-w${42HYZ4u0b9sl@#)<6>7CK22gLQy50sWDwGK?6f(C1|c@E37 zMPA%gVsKT!0<y?J8{(5x>iz&c<#V&(W3;|z$rgtaO2i%|-0Pzg<a_FoI?`$n*};w4 zEUewcd#;NBwyqf;Ehzy7)OYkf+w66zE=7*&(nxnbxUjt|6$%AX@8vX}H*p#>Gl?QL zZyOI8Qc_9L%X;y$P`}a|Vif2c2{lMLTc#bZqEusNQFk4^@EGR46dQ>{tbU_f^P@$r z+>Ccu5_A0YYTw!TEZK)o(Tf?x%}}2t8d&Zz=vDEUBo*k!ulbbm%$blqwaTppY+=pi z`6}*?>Jp$}b`YyrerS%TGMd}=)^32Mq1$6;K+vct3)gK9G1Hl<o%bL?UV}3@?yCS% zlc28*2Qm^9Zq!%FK&xv+#j>j2&j4V|Y53D#0qwgWpYcLtaJGG~M@^<6C#`53VFhKa zZ^*i)M1o?T8-ThhPzZO;oz<wzS49j2o5F3-7W@CfDS8UOJKr_M3}?;r%WYVGvkttx z1V4U`5|2iSPGXT&PX8qRaACB8JHD&l>D?A1{#peQhnu(S>ShXN0=@{=XxD#1@1Xo} zg-C27uTy3_D5iPM@^ei@5|x~fNc$as3&L2OXNkp(mx3kPf6X$<f!`quhKJoOQK_BQ zMZOai6L#=66`j@}aGp{m;?}*>nW&d^hp3IB@JE2n%ngp1uMPbk>81Q8SgU$eP>}vx z$GpfS?RZ|L^TwmrX(ceJjPr6B$}%U=guYdyS1Dn7x}Fou6eJ@BiWO9~mr_OFe>guH zO4OG(Gtgnj)#i$yK9;x!UDX2DI$Ny5;l(+g4}}A$RL8$0M%(VBj^|o_G5rINxK2{# zcZupFnG@L5b2Cad9@b{D&Am0K|4k|F?2v}Vr%SP$&g+#%t!TrSE3@*cY;11x?iO_d zQL?@$C1A=Ph2lVkyi|=g;tNIi!&3wt-`D(Oo2>859;`Qnvy9~L`tm;O=z$knq%9OA zJx>|?JJ@pB75$b%`mzE)5DZw<t4Vv~e}q-aZEj$yejo_i_=5usdez8tiSXjH-;enF z$>`r<%D8Kk8HD@GQ*Vl-a^ZKWn)cDNfQ|Y~n})8Wi=vtlCEmY38|{u>h7L@=d`Z!8 z2W*cNmKelkfnu{jF~Yu?MwBvu%KO|t^&X_<sSqdo087rxj#=tU*B03B=jFLw*%e$k zO6*;f!S}C|1GHCp_o_O7e{L$WN7U+-1_YWOO!CYJ=ZG1+xeH2cVxRMLXr~CDTsn|} zV6#hQ^dF3<1406wy{G=@EBGy&Iv+BgkQ-!}8lrY!d)36-K0G>B)%LZA!{MnSXB1}Y zA56TMtej<n*tur0#LTXJRd(5#R0C!EuWzXVO6*KsUHe|A`O7>J{;}`awwhtW>CsS8 z3n=h8x2(x>TOax}`-4QJ!*Utwy3Wk-Y?9xn6JTci8x!=XKNPq*z*?m3V3p-!DA%sH zm$>f|USCJYnacUGSGH9U{B(%j(poI#*zpQjzxipQkXhxZFdjzA{L%c%Ek?BZHKn%J zD8H6|vq2|mwH`+&-01!B_j)+kTolYDwAQ}X!fAlOdZzJy6N3pekdsas!oTu@4K`Xf z!alhDh%lSi_YS%QtFn#vGCWer`7zJ==+ANWCnG$7chBbK43J6oiJKlVjjf1vHGKN3 zA`nwJaZd^_)R<<RgZQgZ)-_FFRJ8l1gt&&ZXsG_IwcPS4H|a?@F=4Qh9KK}U+VT)Z z^$-fY*bOpc2>EFk!f#B}<;WTl#dCFnj(BTOGYBuzj5;)9BNxr{5M*H!W!`&WcRuwD zRD4=xFMQA7eH0$k*2#6BD6^ROuNp5R=OB?H59o?Aft=h_bJ7M)`A4D$jEL_`K(aDz zs~poty`h4vL8gD-Oq6%u{^{*yD8@9{rH}e7$mh2v@9vH1hTo$iw#pk1QL_Fnx`pks zn<ROa<i7z1noY6>9gu|=n&tvfHw>a>Hd&!&fDSq1Z%>?i7QB`Thh5jK#}?W`CQ1>$ zS)C>pDJotp3Pj2mtf!`n{Fu~^Xh_|hg-zaxgXvRJ=&8is9X|Bt48u$P-6R9~S_(rp zKT-S94>pG{slP9nbe(23)pHPvXOn{_-;Mb@et9c07il6h$&Z|<A;(*!EbJ!|OSZng zHNteKUO!xNZEFUzpmg_z+UxYZluU*eEtjJW*td0a8np9?JQtrwwmIG@pC<B`sQwxQ zO4keq|3H=Up%`Aue>~0c8SiYPdk(Qz6$(EVjq)zhYaaTV?HQq(j#HZIH5@5;h><Yi zuBCS}lyf$95+L`D9yuDz-KZH)SvB2NI?6ZUFYPTOHUTTk5>>qZD0`<6i?j;A{Ak^M z{7$Pz;MnS+voX=!P1$VGQP~=L=U=MYy=cM=a3Ypp-LzHgV{-Q;f%#jAd*Anw9Qra` zrZu#){}iv|w0z?s(WF~8JyH@?5Khdq6S;l*_rXmR#ESQ7UEB>J7Xsxm3M-D5*}jXP zBaYf`W@^JZ{QC{OC*7}*fLzy=&DOCB>3F3X)vy_TbXSS>D@EJ>38ls>A&)?E5rPHC zBrdQtKF%N_uGb8y$iav)38nlTIjNK;pmIeD-Z*{h1%BJ1c7II87+S4I(#r+`V2jG; zLzsqW^7ak4;Hp~~6D?rp&3=arcn|NgZG407;V)wuRG%5>6ok}$4pJH_NGc{C$r(g{ zmoT3+Dv4OK?K^d1=F`c?NauE$x<~1dLZ$;!GI{Vyc-e>mI%W=|5#lY4K7rqPpesrP zu3tp5yd{LT>wi_KeO}Plv3@Aj`4}}noC^yUEE+H^u(&^j%`*q7HeAoXkyIFu%O0i> ztUOL1A-X^7Ye))^=16|HtYA<nO>uQ1`V+i@>*(@>-NEV8(jwo|Q|}qrk_dTUA;ou7 z2;a@F-{{MFHO+2qCy1*UZy(@jo0~M}I>sZzZ6o)sli{^_K}L93YwxI9YV%sJ?sDu6 zGLd~LILfsD*Ru-~gE2e!gX5@!pL*Bbdc>@}Z{KW<tML{AQJ1c48Bpre4vufV9P4w7 z=nV>*$|#jcSByh<_^<Db!sAymBu^bNLIumSox$s7l`UECB%i!H3=w<ROx_ahj_Iy# zSCZv`Lr}fu#AYH+jeqpTi>B&FC$D{EADh0p_wQ-E`=-0$sJ36bE`us@62xYf5BPSB z=A8A}$}CJN-k-(ZV171ZFcx`*xCH-6C^pD2z4kMxue0|-?G8601@z{XbJsq93}gDv z?z8SwekJg?l_$3rBAU%FKQxA;!ohuNGvhXQcu(()+WrL^DkwX1I_*kjYzmvinUMYT z+>4ld0&)Ns{*sT(mgAiKHs>F%eTW>KTLW3Gi+qb`BHok8;U%gpvm{dk1cGoL4}#6u zON&IK8Kl^oq?Z*&di9>Fn?Q9Jn7QD{M<youHq@6#j&Yd$$CrWdpani$$rSA{uG@Wm z{-VLsaZKbX?q1&A7=g5a3@*p`GF@blK|+gz^UGr=FGnp?z0+rDI0L0+NhBn8C)+I{ z;sX$FKak@+nmoUK{<8R$_elH+_iB$**Ouyaj9PLi!P3t(U)-jip-Fyo9KQlwe{%cC za|H7Sc$V*C=RX<qoqbo43t3@QtPm&W;BsZ?MbeMMbGv5tkHoYeU;dU~-v5zY$gyAy zf8c5<I1X^M99K;3-Bj(f`?%xA33b(K6944jOK@y@@q}WiJ523z5*zM8x%~Fb?#Lxg z{j->X){k=e9v}HYBgp};H$lJLsR{lARZBA&AvzTkvkzU~l=W-KirwrsT&DGZUR0ig zn5eFbp!vXSx%u>Eai0gLj!oxA`H9#UBX#hq$_sH9DLnOxkIrYNbE)Xx&xDWhcP;aO z@d942^xIROj!Kr_Jv#U{cSUJjJ7Ii$xFOLPHuA6KYVAJjh+!3G8T{o6CC3+r{zk!g z22}DM%<M5ek3x9$((}@!_FvGa;R-M47)(+3Hq3HGI@vW$wDX}S;!o22$gc?o;dkk> z^<7QMb4OuZzdu8XGrmDum3xY^4{xOT<xQqpm>*^&9eC5}ZB9o`YKXOU=ZrGgp(c?Z zxmUAvH>1Bdw5-<WMYTl4uBFKofb&!C!|hg?%7Ro*<eT^!WY~?Tj_mgMF<U2ARw|_# z#zPb_3ih@Akk1MYH2Wfo0Ld3G5kgjqE%|(kks^gAN|9~^qS&W}Ng+wqjPEwNVzI9T zBj;GVYa8v;#Ce?oaeY<p9IK7Ch0UAxQrBd)zl&E^>i>`>7qxwBu)Ce^Sj#|8oRWEA z|Lm(cH_mnMp?g`iSbbdOSJQe|p+fP@!0XT2cpU}OIMi-@I=60qj3u+OO@w|=qVKtW zz4;Bi^4~&@zPjZNrk-=oRY|vq6gZ@Jeugqly<*F7YC^T|oO;8J-XpXklHt*!9m9QB zg5U$t7=!d4C#tjJKHF9R-|xIu(|R027!LbHr<8tq#vYk#CZ_BG8Owa4saE&U?}u^u zlS9+9+F#(8E3hZP`Hw<-J}Q>{^qGdV4!HW#BLA$KOk>$5+>NfztH(_4Fw3u1H7~wT zw+()L!Ql$;s)DsPO{D)TdjgC3$FnVybk;uUUHC6HsWIw!%ZYz!!!WggCI2^K+>e}u zu5kIvx&CuaeS-HFYB-GcIEnp5=j#`=SN9Iru1lG#rY-g?pM5kW|1Rf!Y0g_)5%kEy ztlz)PVLGO6rq(3%b?AO70wbv3_w)UV>S=r4+6&pU;X?gloncawDPLH|2Z+^X-Y>r7 zoG-c`Lf$tr1(pmLn!<=a>-K&e3Bj$0_xNMn@X>*+sHQO|YK!Rs6E0nr>$^~fstqvx zk8E|N9lij?MH^n$><D7Gclkv@xgf5KPfh|hLn;i|0Oqy2AYeJ8Gruze^W^@H$vpTt z=?yQ+!(?3X<taA`iKf(L4_`24o0<UjPr`&|H-*+og?4jD!!CnQ{`b}hu#zandy6$; zZ(e7N!7o>I41D!z9@7gFKb2JA8+apLL)@aj>l3!EJf-Q$S7*5MMB<>k+M&cOb2{~b zTzQa41$2y7y_%2W8Kt1w@yp3xZX*YcWW=}gbb2RRzT$E{z8sn5D1QGJ4Cgyo+Tbmw z%cz2voPkf;#gxB<53^e`F>mV2bUU4*`lIc1M58IK>qrlS&Lt(>@nk0ev&E$xV-4GN z+5UdFPeyq>?}1%NhJDU({yMVbfm`G|RHF^Ej?9RlV*ZkkR8nDVP>u9I_BnZ-e2wI% zn|$Btk;-_9T>thR!L74Z-0o*$On8zt?u>@JskZcG{KrC{)j4^eZjKuky%n-;!tdO- z*nRir>wd`BVuVYFm0kDbVYS%^b4*20=#4A=C9BG0fx0O?Bqc0gBtRLCFC|Cs2sb`; zqq6Z)t-NgIvZTIN9XuIrny(g;Y5VL#v&>W8%GPFTiu3NgF4@J~?44BQVY<6O0F)~# zhL-Ll!dL-%e|&N~4^p?brn~H;w(occ@B7+(7f6HVRb<Q3zT!N|_!ns+_AqWb2k-Kz z-F-KaVYtRBjx{rodZ<SL*ov-I$a;VW71*UVYwz+@h)V9T>-2@n+|=jxH<}E$`ty}| z7Da79@a7JEn-O`Z!Fo2dN0khnQ49Z)LsVgHkX=~3O4M-It4O}yu8`_R^szi7B|25* zPI<dxSGlOZ4*a;&c1JNkJ8~W;Oc<bNl-(h-8!SH3!RMN(3IIR!<gh>LC}>A*kT~#K zFOiuDwkoK7!`CyPYZP%A&UGXGm>GRvx~e2Cu^qQRX^>P}7NaXABP5Q9%<G_=bP4MC z!ZOU}m8YF@d{y^3KLMtpvhf*O^PHu}R4$@3jVbo6C!Dse91phNn*;79LPpd4YhJ;! z1ix%fKLPuQND0oX8Szi?2)z?X-n<t4E}pgY@*a9XeRdIWh+gsiSnHjSrY>k8?WfSm z$7aKDj-CddCoVEV?=N0K!CD+Kpc%Y^XLFjd3QOUNU-D1q&~nNYqO1J*fUBtd)X?Im z(|T9+8$pIzk0^>{Z=6c-vEln>l$>nILX$!tPj`}$Pxou+Yz5~r`U{Sn#YsakQa}+Y z{qP0tI^ve>Lu%ziSIIZ1YkWy6CeYk1J&ET?k+h2T0=4Gq>rZ1b!4~I9T2b#6!z`tz zX&+Om%83Z%M4jrbz&_b;zx>MLgZTh7uCjL?W^e4Zct%fQs&f#@qxlO|@5AxIAJZ3B z_*6`gGac;Od`y>Z#D$tK889W;nBjDbBG((&rq^7ukI@oJK>moq#X9w?4GrC*-XAad z_skV4=!oQle!D4}C*h2#>j|b?So|HIB?Z1+w;8LLNY<m~2yJ<8N0TdT!b|~PwEeES z2VDib%pzQAYF}X-f(qN#x&MyHAIv_dXzvk!JW|MhANxyFf5hXbKi9ZmEKi*E^w!N; zi&~jY*|{9Cz=DdX@IHRllrqo0_vJcA5hMRDa?C<=9^I)p^`JqdV_6xsXGD*&%vr%h zysWPt8oVjG2ssS+1{pruo{GEEIL;Nd`Jh<mu3W9;alch{Duj-=pW7hF;$OQ<3rM!* zvAaREg4=Ru-B0@5F<+F(#<~-WY_ViKz;mG@UO(c^M2Esjn5qJoq~JelA)43sGS_gK z_k8H}9KFPAb(X=heyCOx_|~3?);|=#f@w6jL~JdJdmxeTb?ZOp(3Sz*7nz(jVpU(a zk!*(9(jsGbEl9qA@@#JIKKbr&@nvTAQDWY7b*TzsvA$0JUzMP67<J%5MC-J~zp9y~ z?NzVlC);ouZxO*oVzMjlAAhyb_1)yNt2AvgHxU7#y7}(Y7U2xxt)F6zUUO2lKxQ$K zW;xIXCzc&CLTQM)G=cAx3!k>nTU*SoZb9h%>EFVGQ3J2&Ld-s}`tS^n2tA_k1R|pF z1PObiie9<*O36(7XlV;dNtsVOg7R}1gisVco71lI8G2TW+SU~~!QBMkfC(veu-eFT z^nF?kfNb-ljAG{;t(nE_Bgd`UIUQ2jp<lxUMd&&hVI;3B8j&9*+LEjhE@=6TZaE&0 zX6X#bzt%0GjA=4C*+!B-m&b;1uQQS_M9O?`n5%yHAT;H2lbbZKVEgolf31l(H6qV- zkLFIUey6d(=Ul;v<8RiZ{;RYSGhKr8qMUzOZXf2JTC`Odh3)|rU?0(r^S)4yJbl0k zOw`s?ZCl7HSD&?w$t~kS_!UW$ofSf&NwSY9mXbTKN=W=Q9IeNW`*<`cE&5|F#D0s# z)(TFCV&TT}nE*fS>9bTCz-RP$>W6oHBt-YUx!HwToE6lR()A}HVr<=t++$)tzw+4l z*rHG@2gCfqUBW*pqy)AE?+;ra(8%;33U-~OvI@(Zk4P0(OLL&Ox~rgw>#!UcU^xnQ zqQLY`5=JiT79SKA=0ou%`HH+IanG{8AZ`llD}087<y6H*t*W@>Y~ie;s00`%>9Ump z<zcP4oD?dU1G(9&#XimpZX^m$!kNUpVU7|^r(dYdfk0;pQMM8AR;A7#07MGwaeBz< zh>$-P7Q_JOI${1mB-hF4ShXn6jCZ)8uN2P+*SIl{vjkw$Tm7T8S*<V)s}IXzBI1J? z?h9$n0LvA9Rn6Xu)hi5!9fk=>(~5VC#MOH$pte{Eude%~@m9Of4a=%yIr*BqR04Q= zH|6a8dBvF3BXb39vjoe5NXC(a%Uwo>>(T*6%Bou_Ta5~`=@NZCvdb)7Kg4Ec^34d{ zL~@A*FRL)WIZA^=STlc9@(CQ#Ic~sHEl3&`ti|$use&4@?@nW7AzRwpi3pehYL89j zsEz5eB_xz=+B&NuP|Xjh$%HOsEgtix>m!61yy#fW#(H(;u9!@mS}Z78zKyn=C@@<& zwcI@Y22r&7+-v2O0sN|T^@shpr_opco?cy%gaQDta}bpufC3;x4}bvRK>PpSI2ohh z=v!%|urT(2!^x)ed_%vi|4*DO>GAc(g_{44lS%4}S=E^RCr(ytU5prJt)ycUrKofl zFn=UNgup`65@<(S*Di4~S8WPKU^0MnZ$!oh)&AiUClg;s4*YkVYy;Yf8)6WE>NAnl z61FF^q_0)9KE{1w=iyBMFPtn>4d6T6`5!o$rZ9(e-;Mq8<+}d=D^8aBt-|VoaN+*{ z9Vh!G*J<|S*AdIle<z~P|7M-WefSU|WCS1s{)zuTI2m{p%b@Z<a55~7<0VeU`TxSn zxGVJzj{~big=!nO{s&HWH^&hm-0C2bsj^G>n5Fu&u_jw<l^ftH|6e$nRLoZXlVb<A z{}U&peG_ttlZhG8|DQNnMqohg|2Ix{hweXdGS*sT?IlhYTwUzR3#h-JEY)24pomwp zv8KLRD!%^K;Fp%pL-Nv>)~==N((Vji)5!M6Vx*Ri$9H4)JNq6PE>TR1-IwW_QE@Az znKzPdqhToYYVBEOEi+8@;8q^#CkeC54Qv;M9QHSxo$Ea+^GP)11f_~bIG@giL_9m& zXo-0K=Wsv5*#gOOGz8@0M+}k0*1wI=sm>gYG8r=*6MxH5jE#Axj>*+IIu93edV?y* zCgH`QCsPs)ttZnm{jJ@TT>%u|#`)cB3^_ggHV@~tejR*&g`|-^o!6y7_C7HZYCC;x zq5AdojWx|z>j@=uvm_S_ze}9Vl?LF@XvKYc)7j~^gU{Q{@Jl=_q+|aUAYy{?*Lu`D z%U|zreaci_5B)`c|L8+Phqm=KJdO3)X0mwJ*;bnB+}X!0W2W=%JSVI3om3hGDpR-? zS&9@r2v%85yPmj)40#70`O?~d_<O%|Lhj<A_g(nK*MU#%7l%)ORa|7=kyT2X4a{#3 zaubJl{5hFX{r2bkyz!O4rwcTd@ooK?;eV>%d5*pNMZz)v))$fJjo%V4$hN+QS=vn~ z20<2+I9x-&1zp%ZXwe<q6T=s6hM2x2C*zAC(Gf77$~lTXb^uVV63BUZb5*Hc`+}!g z_HU0Fh3cdpPyytz|N9mAs91fGahpk-G?ZhpjZ6f4-*v8hNX7P+lhxM$UYXrB!_YGt z>{%d;7c3Y?=EOk$1FLecT4g96$cr-d^N8g!VOLznr^xs~RTyS~Hii(m!f`tE^Ft<4 z;W|MRJ!rLv2|M!^wdy(y5I;b9xt0PJfLl9K%U5&Jz6N(BE?6{3zhU9D!Lc$SVE6XC z0qmy6GLGVRft$lK+x;}1e-^HydS3~+kRAgPkd)C=wR&`>5Zfharv9HrJx>foHsfnv zXMAb_L)1j#VmDL<Iw`PDdMNE^q;dsvNer;+AuJN5yDY>km->oawt<;k7@!`0ITbeq zC^VJOJMWe#R^~h=OxOoh8kjzCVFjfvxq0iM5Lo53ya$6k^+-A|aRkB6dK>?W1}H(! z;oCu*@H*4$8K7muZ6_$WF#wi9$Xxrn;#Hb>2}@qDI^4|FR90;^DMdQA#Cjy?#dc7I zg?Nqx$csvtW16{|B$rXYXmCo4oaANgMl46yUzs(zLv5S1wR5T?K+nhCN&;2$_BEPl zH{0e<FV<=FHCf+jwy!aJ+vM8U?EI|Rv1j^iTWnv8m$t{%xZigF%CmHWEL&WCf9LcG z6WeHALR@JT-X#wG5WlT$;`zDRG3nrK`<=`XFGiq~te1DIj%-V5I0P`RpaN5E9QNgt zUYRz!)m_}z>Q583k`(O-dsr75ps(pV>*Ls6Vc3Q=i(8!%#`o6mv|fj4x-F5Xm-=WD z+rpg8%__tkyWXw@>FFFTTwe6LF|;#Dtu%y_u*hqjYMWzLD1M4FK*CVv{%4O~zW<7q z!@Otgzzl0{e7oEK<dZ;0Y~PcOpUtYz4jHe+zq?RJ3>XJ2T!MfMw@q+Qzun=QBI!z> z$lhqbVYFdsf@SO`;gm3Cn`~ej7JhFa6JnUHq64o^*ks~uA7T3`=X>Bb{KwXql3JFa z6%vi5<vOyGOYTZHRrBSUI2+=#dO6TZAYte028B2~GgZ~LxrA!RY37b{BP<~BH4M~` zcM`6w;LoNhiuuby00F%Kc*4+qKS?OK+5#z0=Lh;=zCd>s3LM9y$r*!FCp`OH2~uwA zs*+YFbVC-LN-0XP7wd1p%@UA;-PgG;6-=c?);XT`K)M%6;HMIpz&bDV(4x%;wrIqJ zt`L5PX0tYR?`dux7!E0D@3lSAy04#>Fu(N1o92W>ZOpGn>E}u>6lyvR+RfK+b;ino z@>0Ctm<wYYK`i##`orf}WQCk5Bvm1=Rq2R~{&cr&ENm?=hZEv#-XoJGVK0J&d>EHF z!C)Q4$T+{o^k*idAh0tjSivtLwFvy&<!?^BlL2Q8H>CnNFAtrsDfK67cF>wPfgZj& zNn1t#Xmc5zq*gj%CKpwGWy4R*cYW0G)-00SBgdh4lY}L&40U|4`vwRiW$`$3mFiEY z6p=S+gVaFusI;PYVe1L)`w_2jR=$<}R(nQ)?_b^VJY8ah(|J3O$XI*wjdxzzOsJx# zKSYBibnE4T=lUY+N7!k5VSpsU3m`R2vu^vzD66Z%c@_ED-cGv)vx+=d>J$%rvRmYL zJ#b7GY5i|GpWeCz`{3JQ@y%ny4785P_Ddhqaoz3k#yGwl{mDrBIIRgN88dDev7L4M z`FBc5zK?-5QHh9bD0kzK2PmqT4!jsUr#SgNnpt~8_0_M(5#XHJ7ScC8%+6aE6+QRC z-vfV;VG2$JUp3NW_CGv}_V*YUX-59+7LR$jCXA4yg-$5@;~qla_+#hh$i-QaNjfSV zla`UwcT<u57e8L4&BU&D?SqMA+Qe%I4F+e$_rf>j4^j6(!&H<k)C}Cz>46EXV6Ivt zDw_mK?vg~_fkf_Q%3G?5P;M?8bRsu_g1<3QjF2eAjg<-FsO1D0Cs0Z{W0ll!0${4i zMXUyfqnQiG6NKYa!}+l2YahGiKEjza#!{dYk!m<3fl{pmXS~dMk%V_#hO8+-bk1<@ z1WG0nz|ae;jkXA^k@vMu`WksnTHe%pfi~w>5;_P1Kf|j*DLlCWUdxoe&Jg%*hzm0C z&LoRr7byCtStNH#Vs8@9GJr=7L`kknv_nt<ZD>=yOsQ<ZA=Xqk8(4qjgHtesD|<Mx zpcGv&xSWK{QKPEmBv5vR$$F<!B_=-%O40!*UpoWco}}sXqSc1txG_}L*18X%;LG(4 z;DWIyTOzOv%V3j~ND7-)OF!o_K@buF$ti{q01X-(UP)7wgVhFPTq%LHHbTs-vtE~E zG3wch7ACHkKxjx{Z2+Ldi<ToHJ@prMW)HPDz>*IKjn!wNO|VOQ1Xm#KRR92hpwIHc zI_2PiU3BA)5HA}``OUD85;^A+S#Q;FfL&^CG}x^&hd!A0vAwQ?qgHf3>!Ca~doK;| zV;ukEB*{I%RT4mh49$bn0<sYF2G&&ez66R&P!V?~&#@bdCm%YA7bj5U%!4!~0TrbD z`5iW+rUKSR0-rO5#^ZcI4!95sQpFYeowME`BxX2cD-d~fk^loJD9oBU+_@<FoF&>( z*A7Bui>5L~Q{7!DMp@H(0RUl_f5efD6Z7EId9d7P>zn5#T)9aBII4O@s=GX?PLLAc zP7ryX8h`{9A}ExQlxBe3oR~7`0u>4ZK0l(fCeZ_+fEjD*I!TCAYS{oS%YVpcLm(w6 z_%W1{ZJr*5EXhQIcuMb2r?QCVP$)xzTnGx=d0GGzv{DHgA1GfvhlJ)+$a4YN5cI?3 zA%;w}eE;JIt1Gg_MS3u6V2}-vshCCqS+?i$kP+rixu83*PQmX*l~eTKXH)t6YF}h8 z1+76QMOh{Lf+>Y{!b|5spnN!;Mip}+Um#^Vds!77jC1VPEs%U}77u``p{jwlnvw-9 zlvd668zN#>Egx)}4+qa$Uy@T%G!z^$m7s1yl3Z+(?@>n6QZ}V`DAp?%WW$=cTulL` ziJGr@C_&TXRmM0B!salF=`m7tUbAa}2(E&|atf??u^s48H#&}rMhL<bGKPWlcwKL* zr~1TG&vR3`nk{A<D{h8?SRbWaP+d{9qw1)vc9-`Lv@1LohS*9q+%7WRCPxM28?zk3 zXv`BTIVdXAq-?z+frT`zF|kdWY92yJZlIpn@~0-C21J=8^h^}e#0zLEtE-PKQ=rV% zq*CZAt6UqoN9?&ra1aJ!T5hh$0|`n)%~i=#5P|&GDcAqP$zE%;ExNWX#kMV%wXF`e zt*^Fi{B9%hwr^>)Z@aed#<uU3wSO6GKUi%){M~-U+i{}Naq8OfGq&TbtmF4!$Dh@X zf4@5be4RkePLNwCbzCR-eka|NPKLEkri)GpUl*%p7rR>*XIvNe{Vv`oUHofZf)`y- zzHVX7Zn#^wSX{Tn{cfoz-7;(4au?kQz8(e59woOP6>?mU+Wj7lCp}tgJvtXXNWNZ_ zX0L%;uMs`>F}gP`iuo6UsYMBLf?zglk@$&(B<8S6m{Il|F`H`krL$53BkM2r`jST| z{hml(MN@vi^(b`hQTW9pG+%#|W`DF>|E;)w%>Dk@C;jnj{dX_=6Zi(Onge*Zf#kRW z!u^4?Cj%L416daXIed@vG#?kZJuZrSyi~?aMlk<Nc>G5GA@CU82w<ruJ+{{?pn!rX zhiO@CE(Lhnnvg;Bs#=aJN}vsWDfEeM<fV=S!6GibqbFS6bgeB<^mD=1FiNc<6NvYt z@fP+;ZosAO*7@_Pzjy5$L$f|KtwcZV#c$?k<Pb;^1TgXv^5~_F7ayPmLdR(Hl=_%? zSA*3<9P;RhmQjyV3lOfpGe{4k+t?RUs=R!BoySGncL=kCIm<L3;3@#bbE!&nQXRg8 z?CiJKL0NRs)J*YVT?HUzXf3@B!|MWwMS90D9HM3%v3omE0RlK`>G;eCkd?8KM;NoU zLT-Q_X&q5!R#yMk7!0+Bcp<1m?q3^4Kw{7|fnPexz35frhi@BEij)ij+@4lj5B`z1 zy5#NX_yIFR9d+nY<}up71eUcN=HFkQ-M=)+l!twuc9x^ZB&p~)>Bp8XxV+;hFs&2! zhG`p*#^d=Xv09UO_sQh=NkaK#8u{sD#`<K|pUE8lsXVQz0{5w+_^Fcesj{b2<?B-w zS`tc#QRZJ$y52R>7Sl@d9<uSY4H?tzS_0g^rxm?T%cWl;s^TAMv3W^TsvnO$UT1wq zq8~_L_-~BeWmHsQ`!4W-8D@r@A*C5YL_$&+$)QtPK)RF=5L6VU8M;eFr9mVWkS>P~ ziJ?JiNNI*nnZx^@bJqHQI3LdU{cW%H?6vRfxv$?i?)R@I8sRHgmtVht0jB?|AImy0 zB0Df<IWXZjFqJ;=r)gkzc3}Q$0LMDGBs;ibIk@IG=q3Z(Y#Llohi~-{?##lkvGx0w zLnnSiXKuW@+C%5Dea&0V|4QjDe0#-g8{Pbdh8x=?M7><z^}fu<iW@wylIc~@m#oK- zrej(pIWZRS-zl=q#6(z0uQnhj!*AK%@e*2J5p^JSORAgRO&{NDH`*rzofaZF_!mHr zRP(6p+^GD&(Zc?!Q*8Zr{e~Pk*$dVooo6soL3p0;7%|cKdOFNm5Poh;PGmdAOi5NY z`+W)kdkP2ap}dv+VI~8Vg|=jx1LJ#t8prTdw->31aFhe4Fd!$HddAqk7L0h9e53r` zGOh|}K;{!S2ATU_zyO#4OzD#U8Zw^3NB<^5jr=u*wNOkSN@Lf{-yOP55_6I<l?@+k z<|G7Bz8df`W&=2HlM#82<qG|{pGfSFqnd|P{Wa~<`}gP2{Lf4OfNb0!;?@bgIgqMU zX~*+V?BrM(8(ACMk2|vM^Vw9#cg8vFG)-*{vFVc$&D69~0i6VC2oaVHQ8>p>{e0YY zW`1&(gOj90t8>P`WE&GOMoHsjtVJX;8r?_EH0Qj9SokitFv|vbF5%S~y+BO8Fz~mz zzHFYQLYsJSMAE&OUNE?xlE!02EnT(cmF(h|Cep&7n;HO`zbvDLw!bO`o8HY)H&P6+ zey6dr8p^gJ|Ek|&3K~NVG}LB~uJt#A7CS&*t$S>PosFb+{SD&s%K?5vUp-p`ucj5{ z2Va*iOUkbrTd$e~teR!6nzyW4&aYZuuiCP&`H5lm<_E>fNveZL8IzX&_Tv@>F$$C; z)OJfNB@@4Q)`lrYN`<IJJliT_{*LrFG47KF-5aRZUxN~oet{O7g{_C?GiVIu2Q6?o zVlR;F00?e1<ctN^xoya2K)C0JXw`8<L5;^v80W;cd#S|lgNFA@*KV2_D?H%eZE@#K zH9l<E3X3kT=F!l5YZ&(JHu>!i>+P=jUeE7TJsCp@aL^4~(cC=h3I{ZbOpe42h3SKd zf*=&oo#BCP@Guoo_V$@2n8FN>1B^jEhQi>0Z~D-0xLx8!s*$+)9l>1^&Pkxx&c4p% z(md5h%M?*Icz<wDp?UW_eHX-uCz_+0Lck|6qyK~^{c)7P1BPnc@x;Rmvi`fWbCmJ} zRQt`-#sRy`SwpZNQw)KltQ-IepZ$O72gC%ggKq0X$-qP5XA^P*W5)92F9JqMwujHR z$;GlkBp;!p);lZgL(YPr7Xc(A<YNigQKtwBEN;|U2Zk5fB^scdg#-HH4(%0A9BodX z2A())ow)uwaa%a?Ae?w|oW4*vePwg{I`Gsd>-62PQ<LC5)W02>oqYz_!8ygD6x-Ym zj`Wa<O2TG{`Pb3Eemqe&{=A8bhcGIn0N=LV>o6QYw`>C$P=bjr?rERr8cqng!*w2B z>~Bwl7Gc42Lz%F#P&nYJ+~q&Z%aEPXdu2br4V>o?Q~rVjmdbznBMwUr$W0S2#RcYi ze)0Rj0j7IDl>mQ>46kHjaK9PaQwVJr!>GKj(m~`5q}Y(O6Gnd1S~)m-1@t1hQwtd` zxtlKnB_OEG_^T#_?;eQ2-(xQU)F|BlyPV9rBh6sBE5Z^a>Duw1ax$8|IRTC0k=kS- ztCmnEqcxq+_uc0^J{kSh&6N9ZIoUcklmFKf?$5>>h6NAbzTWH*%rq*dtv@G6t!E*F z@00|Pu$XL{Robzva-aR!Hm`A?YYBUnG=``)17^p4G2OFn@kjU3LSyc=J`JGcP)j!x z?Q|w$u1Ga~m@V5FBV^N+{@|YVK!#i(IHPJGhyD66OYPr*o9jfG)vs_iixanLe!}h1 zt_+J)kNIYQ0+`+M%yX$Tjzc}u^8CfxK!!pDyVb?3&G9mu?o6x8*SmAgfe;SsE1!ea zfh_eb>woV~cIJLXaM)b?T^#Q$bZ6NR0<Qo4n=BOs_+E3vTcpA1-%un2DG-rh8cPwS zQ$Ufr5_zvLF90gMQmzbB0EwzltMgQ-(CVp(s?wV}R;b>x2^Cdia>}nzV|m^os?PRi zr9zz}5G2-9so|od!M)rDEGep6+}60$nyZEg+}!WJmrv{`_B(&OGD092%%ra^`kqWb z-R}sB%kp7n{W*|jM&pcmp8M*jZq|Wf3A;1J!HBMc_Y08$03P`?T>+NSOAtU8M7w8F zQg_0Bj~?N8gHW8EH_qM|SvIqpILY|!RB%ICiGi}}`+P9{!|L%kBxTSeQ>U-cfxyj* zZg%x2U#ll0UmV|`iqr@W7qd%Hm3;i<<CB`lPFZnB28W+xV=^arymyU17E~0CoVBr% z&aRXTt+TwiKU!08LqKI~MDnLYGwnczova=ie~vTxw}R<&0`G+t#s^om3Pb?RDn8Hz z_xOCvkrxg*EqHmHJAqIp5etULHx1~#cPTX1V2Rn4TW1YTPICVI;#Dw&(}i51@JS`z zT){#JU_WFz7#R-?c|w+(f-s@@)5UIm2F)gs=d$jJ%n^$I#`sW%e2ft4Ko<gvLIc9X z9m6FUBERU#wQD<uGHUj0p}RI9xfMg#>P~2UuF)D`d(Ej7{2<I0Q3_AGllc^R%&-<( z%H|9}6Z<16y(Y!DOoH8X`#|Vym+eIWFS|y99Bl*fU<g0EGjlz8E^9C#{_g#XZkU)a z;%Nb0A&2{{kbjPkP5~c7Bl&0kIl$Ba<Vy(aQH@=V8x)~T1O$YR_VIofT>oIo8My&i z3*(~{UP}6qyCB2{#R2SXB3Y_C%1<cFx?!$*h7#|9RKWocpvi!F6K8NWE(}-$4i4=@ zq3Oa%Ic)4XW8H&v5JN#WD$I*9lk^?>(LNASsC|6O#u9=0009;`pjHgk31g**>O{@A z*4F~;QTBk2i4brzIyi=XFX$G+9+@a168ct#B8Z&Vt|e>=17nI}MbJ<eAQ8DjD$G3y z;vj`!9q!;$7AVb8M51qoE@!GTrEJxcmVihPMC^#IQa>{Bxy~|6CvBHZzg=uF2F<$C z!=iY?ndrmF&2)u^%G!U68K@Rauw{)=NWT@7B{#^PY|y&MRTH^Qn$P^NEljd0tvR4q znZ<1?OF92(;>(9RzNEcGWW-nsu7iB<9WIURe8!}SVe~7s*|Or=<ol4THgj?PNc`-G zR`1tU`;fLi3F0TPz^gp_jf?PurUFXIM=mc92sf#<h9p&!kG30euR002Se!$qp3oQt zMv6v)a^(G2ZwotfxfZ*^cOr40h%n=aR9rfks!_zDE!`KKVt?=$klpOTZKdtto<;y~ z&W3Sv^;Jc0hNp76i$RP6%s#>Is{K<NYqyDnI^4GhD8!!8E!Sim_pZM^Fa1xd`Mp24 zd|us6CufR~TQV@RHE_%%QB0IOC>jb*<py*i_!I%rdR8PsEbl)@D=!)hdBx_j?-%Mn zIHW<kWA2(}mW~xIEy83q9ph#-T%}+3!mGj!5jx^+;vu&XZ>t_5o*hBH+zV^TUlB8X z@>N5=Lv$oqMcMb7k>0kO=+5`hBE9#?u|`O<gE*~+%RKQ)ad}f?$-l$*LeCK;YVR-j z`l<4(qVAUENzC+(%I8<Z8gkXlXMR*<gqo7}j=P7o=}&h_a+Ue-D2Dvb@Y9)4Z6cw{ z^b`0J^gnVo0Du}GO>Fl6k+U%xr~nv=*_!#N5uolAJ|p|>-2aIHg|UGf&R_ogrWalr zK*pw3^?!1<Kc1wc-}G;CHvUJz@e=A1RB%Xj$>a}PUv^J~QAcFC^JuZv@7GIF|3!eb zPu=w>sG*sRX0^gr!Oyi*%PkVi7ygR?_1AgLbSHA#T)}bZ)!%92&*uBzDn|pdj3WPc z&Xz9+UdMBSo(%psXKSq4nW=j@$)0u_Mc?~h1c=o=b-pu2;M>L5w`ptGJnbyq=7!^~ zsjts^{|5pTP=9`CP^}wW*&=s&y1U$-CHzbN-{r~S^1_c_3IxJ62^1GZ%%Fh_+Rpig z3sG^&Az>ggBgzS-)^)ZEV>B#W3}bovUj%4sF%pr?XCK9vS(qCoSTMB|eXk4Z5N3)( zlAw`mh0F1+!5u6KD6nRdCb>DUqYfwh?F|BC--!Ye$uiweH8jy&eQ)&C<;jPKuQygd zBJY)>0QT$%-cRId51xK<s;qzd*}d%nZ`!K~m%kZ4Yej$m4+6yBqxfG0$k>Dg-k%dI zx#_GIMV7Bf>Llm7@iom{g-1i$Epg*pcKBzwCi?)f3YaL7XS298{GB4HRt<rFtF&su zb*s$n>jNx=r!#u%2j-v<1%S{oY*+N`nhDyp@NRAY>@@)IRE=p#wpkMyles1n`Izt2 z;$C;E0G7q<zSpm)G43{O^M`dd;_W#X8%?U7?KLYuDBNqI3JBi&sY}8dgaN_aJX@h0 zrJijR!rPwha0NlH4mv$IuTDmr(wln=Oe-n?4)oRYN}l)Wo4vf>Vh{TGYx@s=-|MD0 z>=&E7vAZSz#vTqzpZ32jZUSeUL%84>qu}}Yt7i`XJ7-fDIvz6?J_&|snaZ?5HDB)> zPufNZolH4?bU&GPPH8@#(5z&uvGw>SbUOQLa?bk+mtPlL`|&BE3`a(MGd#f&ZL8MR ztkcT~0y~nQC<1JIwoX^pc1V=Kw_bUM)ZALpm?$SPK%KAm4hLhMH20v=6~vEGp$z%m zx|Wo{f5R#nR{DIGyGcUHN`GakS9(w(TW58s<Ad*hW*&57AZ9-ajv$s1+Fw`4c?+Cy zj<*!X%J~oO31HDv9~a*50bB9vhqA4BWq@?HxnFz&T9hPo?Jw*RZ3IQW^1dHFlG`j> z3K69n2o3GyOh#1+A?+F7*b+fOmC*n<A}`W@T!ryhqK<QCPiBh6pK1tVN?UD1t(zkF z&((Qk`Y5O^Jcpw75fM2aBPHIy_|wo+iR}XaST=GIMu>oxioo|HHFR=mKK69*O7BPM z$L7*~)9B<k-;a*Cpk$zqY!!M(t-%3Tq@m*yk{-yV)kf*62IO@LC+~vE&#gZ`t)P5g zH5^wVkc|Q#-@eVbLeG{5HN|Ua^xQPi5t((;{6X{x7FHzoS=a!u@E~TN=rGwo$}FA+ ziI0!$xyrwUu?B#8T~=4PVi=*k-o~xMh-8Ef<1JOkVXy)iLH<T?^+&O3<KXQMc!~;? z0&|Dwc2k=zE7KEz<c6>ny8s-Tqmxf#fE<@ldjBRFEht4J=EPMJ!2uwGzGy2Ed##N~ zReV$fN^W?x2_@GFBHnH)QfS@g2QVOmtCSFgw53leng-e5V5^3S=cGs3(1(Rew?2R4 zM|^ug97UykC;C0VaWL6U*Bkw2n1KLKLM|dKS{)dqfKHXL=6rb9fVd%%9p3Tv_M;*l zcdnbUGKy0wqe#~&c{q5C4#EhBf<2^-LqPWd58^g-KYph9K*sY8LgWf~=gD1Q?#+Ej z*F&B7ZY*2tm>1nttdntJ{6*foP^weWjA^L{fYd1Ul<P5x<2U}kg!}FjM$AxI3>S2? zv#c@J5PnJ>RNdvBdtV4@91}E|$6!(fCRIWF5$Tbov**-~bh`E8?Nnlbx9<nOP1MoN z0zP|3Is3AO)15xUrg`r|#<O+_1_Ppe0$FGk`Se;YxDwPtlOIy@{;v5j*_c-LA}rLO z-$RBo(w(^@p~sob6|JpjsWx7X+UZ~fdXnZFJ}MfNgHjhZn*X4=1&o+d(s*hR%r23F z_yM@5w4!ZYp>+J6217(n_CkjZX=hFHHeYgU=J5xH<E9KmB!FL3R=}*Pyhjk~MA|=A zrt}^`ukl>b#Lk?|cM1{jU3!O#D-r;=YvAA&HV~fug`R4ca(}pQ=c|>-t)fVV?Am7p zRW7rUJJyO7d}m;_BuS7*0*n|d>CIj|q<guVq<D?@v7wl5Q+m*+7$58>zzG_+f6zHH zGD97H3*d_EthFg9FHYo5bf9n~w7GoWgWk(~G~e~0@42R7u5@-M|H7w++2VePGypA( zp&AJM{yf?E5jxKN7N@yw9?Cv_{gcPQJCXH}EYc<Y`{2qE9eTw)g?EWhC>$+=*HuDj z?dSMWv}5E0M+MY|OChhGBj7Y0-|XVB1`8$##hh*BP?1FISZ#*JL9!o3X&a%l2IRpR z&$(##wW4E*I)B$J2{f?=In(A(zzfs>prkkp{`^0{qK@jHa-GbGcL)ipP!5*hm=*Sw ziErNzY$*?V1%5V0RWkG>aR?>e>!&3TXYUa_5ovittrC|SAg(xn@%(N9W-^2V!=8#~ z2{fJk#C3*HmA&3i{&Ka#N6@S9GaWqm(0H{fl2G68q<i>z=4uT&R6qD;@G$f8>Msh` zfQ`^S%4PYtuA$d3@^SE}K<3|uenP|8H{Ii6i+`JDLk$zPgU8=}|83dA8mGE-Pb$Cs z+jiD#{4+UtQq%Zv$1|aE_OI?~!_2>3pP|P2)4|i0%YS=8uqGTt@2rjG8Xu|Gv~+9e ztV`y4KQW<c<&NHYpT+e-+ECM))X<Fye|?w@YhG8^yBPU$eN<@LC%cxEfW{&K2H9Om z!@$DliD@SvlUo&^?%U7aDxQUk?#S&fUMjffBAjnDu1?W}C6?kZMDP&qOi{|e7FiAP zIF-A^h-f=mW!6byIs!j&x&JO0$FT@A79#e%0t9jW3tLhFC=n4ZW(e13L%*(1hX~h~ zHxwIV5HT_cWEKSW34*2tk=;xar-G=?g5Zq7G{|5&vtS0F;G3LH{7xV<l)-ZU-OY#$ zW=HxF6FfH_Y_{*p=|f$J2;pO-PvsG#RRlIj!M|bygnQ^--Uj(4qTBYhEV6w!SJ9Y# zpf(;TMF*(Csj(Kqv+)56Qsn8l5DgwOeINKATEHz4t()cz>$5P>Vwj#YytSO-90wEW zrZ`~$EO)D9>ytZ5!rvr@fh$N~Gm?G6kmle?bFdNqW@MjHa0K+_aS%<Ex11>-{0&AM z>jZZv@WBfKWNGCAdVfje5fMZprqzk0tIBRb&KtJI-2g8;^Aal5WpxliR*lkh@PxE- z!^>*lDXGg?i@^2D!JyWtro-@}P`E=V_<K1N9R#-UBr(DOrOQeB3ax9!;WLlm9e-b1 z_c(y4fkgV~)s)Cl2e_CgNDmKEE(b30#jEOrq&$HGFQJbMeKXS_6OrL3Sl<Vy5y3vB zNF0PH+g$#sd|?opWRdO;jwBKX`GA7o4AcBjq(LGeWh~H7pCVNvbn?}!)NKDkd?fL3 zXwzr}i6U^qCvGwlT%%8(u225j2mMhb;Pzwk4*;lR5Ks~Ue{|oPm>MP{6$c_1Bz-CO zH!f7j#YBDggi4E~IwwK{anJ&Nvh?y)6DZkN1etby>X+<j$OhzQgF_Vmj)MuXAmS%| zC*&)hl<6*f^`nAAkJZ*+unZjX5eJOXC*O)7Gnz^bn2NB0zBhPGUT6zN0YFi3im{;Z z14NAEX@pT!l9p!RT6+>vHffqZMUe{l_6AfF_0)=wEGOubcm1bNZ$HXBrYKDWrvPBb z7)mT-ocPDoEPYT>RSI!VS|4|KHZCj&YgLT`E2BuaYXj7=R%v%b_D)0F9;A1WhI{bB z!f_;}B2)`_%4OVpF{iX!k3m70fP*_B$od%lsfh1zK&n0nWbk2y5CM16OmBOebTcCE z#8ckr5S?&HxIXN-obp`6SNslHaqnlKXjp8$tdk2_cQ?4cH(*6QY(_n>@-Do6BcT26 zm#^6HgAEuV2>LXe@*G1s=#nLL8Y+d%kbax-<x@t5@|RCIvKkSP7a~yRJavgFic&P) zzbB_qgz6mYcjy8eLV#1?fEldcc~HQ;k6AGo((gr|-h8?rrjfaKi;P5*R1E;#aw6p^ zN+PmNhVO?~MP*gvVGHntL(dzm12zPQWZ+@PsGD3ST<{GVrj-He^AGUJ-yzO`QAajB zPGapL{Zki0?e+1yKE*lq-3k8d!8wcofZ8K+3hH0@6Vg(Pva?j9zsf}kV_je<Ew}?C z+1vwC)gV&hVD!(sA%%Dlkh6#)IA!#V!iv8Ts0f?E!J0%Me{5ktiVI%7a|(5Vf5m4P z;tF;k=@eQIjsXEgB4Hq+Y$6Q!0Vay1H^sM)_KW8S>Lk*3IN$?wVf(Fw8xUqpA6DU- zGpi5V_j#fDm@H8%;D#!y6pzcXC97qENSXy~_JtdhQFl*%CBO?yYTupO791tQ+Hc5i zTi6jU-IdJMMGKymO*;BG<Ck<`d68`3`gfP01R`w4i;aNU$&{H#Kgc+9$4~Qui+@~x zF4%cY@gRu&pq%okysY-Z>EJHh@J~ruZ^|LzPA>P$5>2fSaSZ|E^;smrKW`0Z9KS6i z67kdUg&n{Fho1_(QKZ-9lv<aS*(T%>wm|8kR45PGS5(D#eQM{Q5HkLB;38BGOJ*)Z zJ@>Y1L8S8XqUO-H@(2$Lz>*qV!rCLs3P0IjMOV$3Q=R~zs)-Rd(a}L|cHd!MwJq6h zAJ_|(%yhSgf-{qL_#H7(?Tz1Y(0e2FKvMBA@2aXdAF8S@VDb7Op0|DxB?_JTiEbFM zQD15bb18(giYBSvQvi02f*skyyvZ95(w>%lESSN=O7$T;j{`nWXXX8T7c5P+jCn`A zpTTsu5iZ(D7u;Bhgv~V66Z9da1VDopdCUh3n_w-tszuXJeF#CHe9ooxkXZ(65xGzf z&CvSLcmYqPBV%Ww#uhbSk~Qy~!>qF@4Q{L$euo*d<{2%@E*S_RD7-$XXkT0Uq?g<U zSJc^1K`#i`j-&xx)y!GIuJtKgL`tf)s!LQWi7lH-FfBWzRjVoGVP+IWB9y%KB{e1R zYHTZAQUQv!1M)kM$hJ*efNJ%N{W+d8d=nCYfc?Q#kx74~E|G2e0&~HTALClosoM^- z%ML`c4n!y_waQ(J+q~}k@mkzul#mnztVtlI6Q8=4*Vswka)M|`je#pQl0NdI4z2$| z6jUF4(=Nnca*fEs611(RU18^d0QY`!&wk1Sc)~5RZ-Ig`ho4}9BBV|i@DX!(0Bav} zaJUjHfKqJNXTQaITb9Ha8+x+;@ovv|@A1|kB2Bb)Ob>KV6TF&C77a0w8*;?C`M zU~32EV(0QE3>*uM1T<VDV1HRGZ>HAa(vT)NY^J<yoE1>!M0RK@-(*`BR#)ckThT;O z0jfX|*^+(grv?bZUHGY{6K`H@KUA<G;%nnhFS#nBSFo{czzH5)C);!hd#X=yifLqi zSMl!|JXIrLKb_i|BIBT_F`yhO&{#$)XmYHRwN*lSfT7f4=^+t<L)c{6ox0swTYgFx z-u?GEpP<ud<U+04)XymhpXqDNcvjmvGbC_{>9By!%8afa4&S6uFKuB<k{#&SfTbq* zHFBJPv2*YXjN3232~Qy_JrGlB)PAdW=>jI~R)7|SImdqPl76tyIKg-Y`zcjO?e&4$ zf1FdtkDam`$zPuRyHA6~u-3Jg0Ec)XCaE`J4njSCIuD*(z|8u|EiVQrE82Ivn`&5^ zYQNOSSPeY9q<D#^a4H@Xt1hdOg_M;ys>Ow$Vry%o18N}O^2D=%oDHWqSp7xrUM*>? zHoQLuF3LiEYwnNDX03rQtW@OY3rg84XH;^PhZ7iZWt$>Nnwi)f&v*FT?OUGjU;L1u z33o6iw<oQbE{f5S`5q)YB+J%y6a{^cnY}DEyf;8@o%qL2dO#yXvDFiN1403VyL6`p zi4w!6E=iZ2>IdG|pYOoU2Ab_GVGLvg*(|Mestwb4SRMS2fkl>o2@YmAewsXUj)Ejx zsTT^~@Q(2N8bE0g_;LhUmdLzN&b$z1cjp#Krzd7ELm#_^sfZr1+pOeN$txfofcewh zEhm97FOv-W-ffxQ6oT)s_Y?mfAi@lh-ftt=LSJIPR>=BxxX(?dlzi_m;}4GE<Xa|d zdAD9hZG9sQ{k!?Nlt-~Hkam6zXNCm9Tbbn2JfF!kQZByIrx5V1(vPElOF#hk#Np?7 z`=6$>h^Eo%f%)5RV1bx|i0|4RF?lbuE1RCdmV@S>mneAoF1lgJFn&e+c1t9Rl|FHe z=-8!G#CIM!(r`dG_HxA{|HrMCg~Iu~Qqw$fp|vL3iJ3$DQokx+7KX$Asr$RdCqdAC zrh?zP8m>)^C-4$CS!{sr_A2efAI~=Jn1b<mnudErW<u~o^2L+HP63&guPZ|@e?#0b zvq$(&>jvDpxZf(cg$P4g98ZHT+?E)|`Oh>TWmCQsq4>C4xoWNYmK^`;vdcRYbMal# z4-Q*0$>OgFm$Ji?G?$g=taie0&d6<>{Khd9tTQ{$=})Hf*<U6?)pA}L4UsV2b6xx( zMTtvd&)|ld10}v210I6kR0xkg3)o+E`0VYus%|lxH^@+)Sq~EZHP=rT2=5Y-nKJ`5 zcg8?p;VBGaHuP+;2ESw<XVlizQn+BMYPWaXlMXlKsSb)L_eDqp01d3L!3P;Cn&izA z(wOkX{i+ODSlZs-7MU2!Ci3P+i-dZw=O=$=rq4Zhj^Jr8aZm`wo^dMdmM*1}2<bI; zUF>0HqC$_>o>ZU$)vdu%+^uakDppF}7GlmUtksfT#u=CKz-SZYiEZ0zf2C7lj%Sv_ z09)7RW>y3Fjh$Xf7ZD2S-C^DQ#t#>;I8U%aY=`BioB=}7<@xeLZ5+E%)=axp7WFns zuK$7h?&&G+oRCfFt)D>v;A5<=NI}!Un*n^rMsHF%U{Mc;3M8UnuX56}0GN1hkH@^h zFDRgCVgJq9)Z+ise#2z=Uj*oLI`SUJ{dYqnIv45**3AH7z5koDy&VKf@6F3)sm8fd z+~jPkZx7bpFS|G6f4w{Y%-;F=(U!?~_Ae%Rr$YvxoepZof8N5dW553=XY(C>YT3Z@ zem<kNqPV6oVB7uhj<8KjLl`B;+5-uW+IIxN`Q64i>(Ttk|Kx0sf2ucWi%R-4V-j<I z9e2geq?_Nj3Ld+55qIdx()mnE5ctuR(J0hB+E8CfiDg21qJ8(q7w=P*H|4ZsC<x#6 zT>GW!65adzL?~;?uQn$TBAjgQQ`Uy|NYxcyNVmKmw7$);@WAiw?De$riu#x7cMDx} z?}brBkd8jtC6SA6`M@>Y6Uj4ZD7JD`cSem<n!?MK_w73wVWpd#ElC_GPFyA`oavRo z`&P-ZLf}2mrPBv4=2G|%hUa4x_gU4MJvsp4%w!UUJ~`YRpNMBfdo#ihx?2K!BJ;9; zk`W(dwo)03X$wh-iwMVc81Q9<von9o78;_^><jb}%~SldvN0?p@wfjjW%T;Wa2J|N zM^8ukx+sF3XFva?$out*2!gb9w5EZc5=Yppl6$^Qd<HFD+e2A5#n}>V{0hxZZO^Zh zc;oqsD!*w7$~+m*Qzka6coffje2^>u_*@(ddE)NH>H*JCiCuB5gbY%>Rh8ua+%zRT z9kVp{ay;~&caMbl18>QuRtn}#iBH#y-0^_*oPtbWXz^VOZy??wxoTpdrztM93Sx@7 z6GK0br_thLzf9Z@c|VD5aAH3*8J8Nd9s9#;hi=%03b_)dpPEK^vqal?VGp<|-LHCi zIRcxM&+KKV^ET}xA0$)pYh9=I+ou?5^Obk`Oot>F^FRG=JM?t-RXqK|qv`HAn#vzm zsK3PK)dl=le_;vB(@zPRNiu@<8{(_`e`B4T#irE&=#t~?qw7!HrizE-f5g6LP;`-N zE$x5Yu9)GiS{#P9&+KMBs8mn)%6-8nRC9T+v?UGxN&2b7o|@(F`4E}qWiQwppVhY+ zF9zmOkhrE2{x40_v8uRwr}`WOOisH12)OL7Sv__(Z!6*dd0Zw|6VWz#ZM*!*r|WXa zdG3u{Uq3ps?aN7gXleILzXS#ToYCUmJ6#eCQGeMl`NT6X7&b&BsZ6^3>(24_lh01x z)wNn)Wz;Rku<(7^kNArDU~d%w3ue}lop8M45ldlg_hn4I$(zB~KnF4P!en}OM996L z$E>N4Oz!IC?VPi10_yQ0NANZ}-76CPtc*MIq48PL$vzilOHa2_RSHwf6ScQAS8+eu z+G4~zIC+_M7EwwXg<;U*=T*t0s>tJyeiYo4z0+M%RX^Dft*b2H;bB+LI-WJkt{C*W zn%qHBob1@5^mzG0$WTfL=WdVR8#1;s_L@$#>;U_g3rQ!wx=dHpjuia3Q(--lzOW;b zA_dzeTbGnDiu@6mpkoL}LzCb70euOD%4~r5osP%$qE=osVjb{^Fyq@I$;RwFL#chs zE`!`ozD(IQt=;WoT(l+mT5?yz6!M9kcV$cZD~uoX^YnV@wMq2YZjUBLP2J&ygp%Ju zf%tbl<2)V_h(Z~8MPV;UvSs4A3X<1z;)DeInb!dk1j}ja=iVOVP1#fRGzTA4So6Uj zP$YcGuim@qIMO(Is>p6DCip@Pk&DJOc7=9O>AH5rM!%-D^<=TPYrX})=m>JlHquuv z@vW6&JG(VJ$kLOG4q43PkUP>|i9xftKK^|HXXbJX3cj_mu7=bhrg~+&%vL@F1#vza ze%tE7qC%v?>S&1i<Z_z~-1?2ryd$4%B9HN9r1InS3JpNO&p>f^>if>35FbVrwmX{Y zYLOqxG;;-b1d=rYPwm3((mHL?V_J939Gl6mmy7L@Hh?<ngzW6!WwwtD#WC1~nDRWH zZBI7>V9d)TCP2cl>q<lEv*CBA@>ckHp?dpg8U>&Gsz2$gx@{gW!sI4Ed?gm#P-+&= zXI1U+mp<M1v3Br`WKiWIz~lL31(iSbBW_FbG8BL)@(rJ(GOcTjkfb8wBHN^zcv@}z zDv5#Wg?`P?W4Po5hWu41nr#kA>M2ZYx%8Ag%BO6^w(d2LdU_81fd-tro732l=&s14 zM>{Hx_99d9JB_$7xX`*MypQ>I<?j2t>LHE{Vf~9RzCT?n(Brw$@Y@(sqJHFAr|{kq zeJh8dx;Qa5AwZ|5wm9^|!W6L*?|GgS{t$9|1g;UCB&nIDpZf$Yn9yQvno!WZe5;7S zm`?kww}!l>>#>dODAOBW9$Kn0xlC$^m_D}%{?JSGjyXKg*}*d)1893E*-9;*5!K^% z5ZA#H`zjmQjJv-(yzNzE@0=nUdlN5faz&?v|8;%RIHV0}fJ!GW`q9xY2l$)deswab z@9E>k*`;Sr1Kt>^FwHvxyuvm6Ls=MwdU^Ai+4cSG8P5x+d#>I$ztiEO3_xc27JD&o z(GMkkpc?iuY+7P~*!Dqps-gmoJ30K93p?>ZmhV5uMVuU&iS)hwOa|tjM>=qg6auwL zdKm9Ur;YpqOGdi>#sX{|YQ0QeG&Lh>rY`y{n-J}}D+UR!mPy>qHDSCf+z$z8<OWA2 z9B3Qk1#=}=nLp4y{V-xT`UZk)y&--yuSk+KSH2jWFuG-D-G`ZjQ9p3hs(nCQbhIot zJTLT4Htuvj@>%b<FlcDOGkNt_Hq*W&M-Ty7-S<9%j&H3fP(n+z(RyjQ40>5xoXuCT zK%%HMnXH2Btcs}sOWC>Jlef9+ci=g~#i9?RBPz-Z;|$Yh5jlJkd`FMz>atXJiOy7b z<qe|Evx%uyMTnW)L{oT4LFOjBEEA7A;-1rq0^%@2VuPE<NSl8=v-%PO9k$X|CqB;L zPab`X@)t@DtGnL6pozlC2dRJM==5qkZ;vFRIRQ&FwIX)1#<|5HeuA~;aU!_$&6juw z2i9#~rdZTfr@3=h4po0z&!zp7Xh3A<(bt9O5m@fUSmQi{mW>K^bRrt*8A4l~wmYmn z`*K0KXW>?>D#AJE<&j}aFH<+^H<YseKzA$kP-2v`=M6_dVt{-wVpN}7ClhN1N&%A8 zU4kaj%@zRAzCZ{P5Na;+i*lAWv;EhJHVwmJxOY(L$#3!Gv^#HoAS#PtNL!$!ZJ1?U z*tby`oiosgI9a_mCI<Bj8jB(Ii{*qX&6I>O&7!C%f-aG@P+%*R2`!0%KId!6_(E=c z5Ea!Eq5mb8fey_I2vy|^W2*Y9gHV2?ESFI(kGKThAPWSGp3p-9B?~i<0%HgpCYTEV z(k>)1MJnA;8oFo7DdLe;8abc&I(TQ3P$H3PBG3n(5xqZueU@oW_KCcn3b*0R(uDtF zV<eV016jb8jS*EkSkOaEXhtLojU`eKk~6~rrK{SxvO!ut4RYJ<lvm320wl)R@aJ_A z^ZV66<ql{L(E}e@bYieN2Hfk~=6K1USk8WT1Z)a#*Dl0xO$D>r0_8nJEv7>Ee5H-y z-CkE99SlfJBFu0qB;H3FeHJWLhbHS+WA!0M^@M&~zPZHQ`G_3AmRhVo)v5Z97k2Q) z&MnD;EGUUAh{v{_ZXNhWUsy#}-Y)i|c~m$-Y6YZ&Ri<nLX?ddW6e{b!LMP3Fw1Y^r zQJS8D;ok(p?az8*88u(G64Cbrb0L7NW}(`3q2^Vg77_{uiH#6exj>#OQ<fel2@UvT zbw*Sdz!MUwrN!i+l(-%@wbA~N?`97ibc4Dj@t_m?)sp-|l30INgc32|Ov@9A9Mgjs z>w=i^Xk(3rZ@;y&RzlhQ8n+zeOdE5JsjCVdsdw{&0cP5<X-ZMsa#<SnH8Y*uRiM&R zRZ5<A?Ygg;o<RAjF839nyaq8kjd&<EL=>TO+cT_2rcFU5tVVkv-nMx{r(TCK{JEI` zW|lfYBC?eNpql>>c7*E4(}>r=5IR>v4e^?#e*Md1T9gvM%uzrzjtE@`j6*6-8rNr2 zXraq>w{#x3RED{xMZ5_vn{%WFN<gX1Kw7pB_B$dYVx&5Gs#0<XH@B1x038=q+BeG| z0G~m>&F=c&k>V6VTcg@am!Xz*HRv<0V~Qk05fTKRh_WgyrY@X%c3`=kw26nbu{6wE zB9gl<I3_#z294SjK+W_+H&qNK$N?ebVkF1#_cC|Yr-D>P6k;*q9?rtY6uc+oQ6#dY z6F-Myks$!HkaY^cjjCmg8Qj_)+I}^1=e<k;i^{DhNe#>D^*nWtZOd67>Gz9~-cfCj zjntKb2Hjk0MhA^ZgpCk3Q;Lm_q^@&E0QEA)iQ4jv!`Q}1aEy^tX%!ld^miS|j3kOf z7@_${{LNAH4-F<`N5zX8&C`GksGFPR(C3jVf2#Bo6Zt7RqbMl>RFpw72qSU-#!ZJ& zRjV;Ixs;SIKsR6?eJ6=JGV--ZBu&2IZyDY=TRDz_DBlh!+ZoYc%bpseQTyYexHQg3 z^ob;H)c_<&Q#Fjn${;pP|GB=2vV@9pa(;Y}%+^?xl%NrsajcbfjC(y)!EM0aeZ*lk z(j{%++3kc;@}N6NbPG`HH6`G&NTiI>Bl)j+hErp{b5S*U@^R&%o8l7^l%#EGd_LY( zfgMl_dn2RHNW$y7v3qf4nnhA=o?$`v$!?EhTvSc%ADK!#8HtTF+<s|B?1kpmAGsYS zv*{c5Xe!Ja(fVGl;M6rf<YvkX!V;QVVvu+1W(FHs2Ww_Pher3k==51-BePbaH=Vx7 zV59V7%G={aGIO9@tNV3ZVWx>;R?d)s>OV<e=mPn|GldN9TNygI4|vdPZAwg}IP*La zm>JXf1<(isrJ5RGM*!<2&u}A+I|GflYCk@(sShUf$!xZc!B(in^PQn2+;|avEHjto zoQ8tf*RgmE*qd>-e;{VCF3)9sibi#O?9tr#Dyb=7_;YA%X7B8tGm5quYLQ0bf4>AP zWbvTBkPw;{Zs*gU`fPS7!y*IT9aC5H{bFF+oxDi}%?np~e;-;TZH7+M|4W~=2Vxn! zKfhOInKji1jbqyxphPr+sJ~9dW9NqM+cc&@thG~l%I3$b7f^CgH6b!xI5O>>&3NG; z+V%m%KfRQ#Fv7pc*0ejZ2y6U+Zk-0^S-T~uE4Fd8guQS+Y7R<VU>k=+q>_Z4$r{iP zBvF~f>0#v)d>)}S^eXS$Rl3AiFBz{RVvGG3>zri}heX1R22_%dv5kv?v=wi>8WB_( zG$NoQw0UgZR}+z?4hzX_IM2m^&5XZ&#Bi`S9;)ACfi4dRlurmy1*sXb3!G5u(l`*> zvyBwkNJBx(?K%zz<uk|$GWl|V-=<}(vx&4v(wo)gI-h9;2FK90$t$51MKwpC);<7+ z2%!;HW3hDm;fm(#v>I{%EDdN;?x?lqC=nG|s&8qKZkal;tSh<7kYt%K1u{l<Qp>HH zs?qWxBk62y#V4RD*dWz)d$YAC3>zUaJ?Kp23N723wdB)v6xt9Qil2i9+#G4Fs}3KY zLN!BW5yV`D_DSnD44xR5lcz8*wCI_BIz9w-z4nqFey5JqSOZ9|(eMy3cB=CC?RC7O zToj9b&-l;PO`#|6PMjKi=rf=u)nBb+6GsBoobO9IC82<vL2Xx73s3K@6G98t$C1Qr z&^5pr8sO=W043r0zMj}cAtf>r%dnBckSMOY@t!Ktlgi{n_{LvkD5K9tOda})Cn_L* zBV%nNvmk{T@W?kgSQ({|CF$A#aPguH;^iyKd%am(XprKu_N`#^J1Q(OW8!Ljqj=3V zb87iJc&nUYtAcl{QgZ93+E$gxR`t`Zn%7&k;ahdQ2}(Yodq`+u>Q>Dz8o&p-!ETIf zyP7<nG2@@fl|TELtki0~C0|E;&j-YFKk_xyp;LEDDch~S=H_9vR`Yi4F7Ua=_Mqg} zJN{6k@@*@m+px*bcz|nP?s%`fp##8SBH-CnfqTV-k;vfA%-Sa5ry(SQEJ%25r*h)1 zxg7KsyGL=$)C%v`z*CRP8h7vVoxhT<$A8=%@^-f;cHe>{Hs(DtTXy#t_V#)A4kY&u z)%K1|_Ku(KoxI*V(cU@zuy^iZtXTdG;}L-`c<$f<=86m!7Ks#r0)EZ!1@4B%mb?AC zhqq>suwhIffo-6Q9zjo?6bd{;!}G`qP7)J%s#81+vJbztPkm>fMrxl{eV@*BpWbPo z;m!W7h<(P7`%K^VnQQl1y7yTp_u2mLfAZR8m$F}$hd$T$L<n1CY?hr#zNiI|Q9cvH zP8eZMc1!Ex)`Yxb@CBr5H#k<Q(%C-O9%-%XR1N0E4nrlOI5GFt7qMT1&ym+rMIB_y z`w3poWYdoBHOQNDSYJ+0>G=|#Hm|h#Lu$t>@?d<;8&8M|HB(aK_QU-MSA2w?Jk(wz zJS1j80V05<0+|2v;)jvVJ8+j4R$yt!b?Jbp#HcEP2lXD&AkMqy$cQYmpe!-4Ju>21 z43s5+2fOy-**e%;<IXdoQ0i@PkGV&(#$oG4L>ur<DUuQk1*o7v9zI}qRH)_fSJ!7- zs+$n=#PCY7NT7ej3pm&#E!+j`t+5Gq^Mt%{hAf_t+%I?Qt$dULAPY9j4@81}G!kto zyzjY^87hEO3M1b5K#~?oB&YIGm)iA`ae%s9LZnmEb0ox0Kjv;9-p(HK%oE~Jj+Ted zT!DAdjQ27bKZ#yIY!GNRY{9$iaGAb|nxJS+Jo*|-^@20@F)kte`Id_a?ethYe+9h_ z-|0&m+qi|Z*Xy7Mn6O7kpo-6%Zy>kiNz(Hd3HLvt8%Dqig`sqd@sIYRazt+5tU?qU zz#bAw{CFGrD)8CrW80Dk)zL7jJI}d$h+n@!l1Tf2U+F`9vVrD_-mw~YR@kFLJ&$eS zpWk}M1ty-PiO3?Cqk<x$71BUIVLl~Lz-PUT*n}<hLb_Num)vQD$K=abrnfB~l?M1g zo|S_c#L;0z#-5&s3DBxfd|+|g{GUG21V2=$R!_uTQvcGrPZE66GqzvF*AHLyK68l7 zYGjOd$@Z~3gZS9;)TpO>>O<nQfXW&X!h_eZp<r>1h-bJL5z=mv(LKqSAJT9}59G(@ z9*8hsxDV!*04%B*#bRw+S5in{2#5rPZ~k8d=$6<GUiu#d=#F8j^FCKsEHj&-0P^{K zTLRJ2!!I8aOn$lEmii9@^hD|P_E=H-2Pz8TSJIP3Kf%I5qAu&iKECxr00C(NMc*^6 zAJ!G(*Im=(c!PZH!0YYl%hUdtCikPy_N&Z6EN1USCM(^yPK0Lbg#M{snbFK6Qwarg zjdyMkpct|79Q3V723f*0<!KVs>35Dar|4Ff?aL(Fai_ygY6@)Cykua2Nf`ZKJ@$$E zYvh8s<N89)yF-1ORm*a!62MVc9QpR86du=RbrIL|WvlA>fivf2ciAa^9aBaEpcS0b z_XhvCpO>=zx!ODRzNB1V@!<6GNtJxr={QGo#er;yW3SBhPw|5;FYw#y7DXq<R6W-b zdgJ#>B+PXPG$mK6o|>h<c$~ss2bZ2EVQTavn$3ew7qEk~S5w$yq|-&tVLPIkre3w{ zN-MMFTUmV>=hl;VlI2d2YoZ@BHvMzf-pzC3d6*T#>~#p^3SY^4XiDI$dMN8cXO!;5 z?plBQqm|N;K_cP$h`S$2@DtZHvM%n`M{d4a9%K#Ar)7^M5e**{w>{#flb(C^a@haq z$|#oUI<k``f(UPtVCtgN`94+9JB*v9X^h(@`N-`sfg=O^gg%J<bq#OP*Fk!e0$l4T zE0m6ln?m-se`;ZoYad8g<|#f|S89vzXz=b+jc}?srmz!;z<yzvv(2d=!ync<KU$XL z9NnWNlk|V1WNhIRdGsbzBe$K639`o@6lOhXhrZD%iW$m2y8T$7`Iu`ACZtUw5?2j# z8E26_WpvP$AD())rL)<T($74Uo)<3_OHUWCJA!&@59kD=Vif1ciV};7JWs~`($9NR zW%u1>)Byzh0ZCz1UH6*;gv#LwENkid?+>#3g69b@ccgiA6|odFDEa*r+Jn}IGnWY> ze^(q#R0(nIl(KC{$uOyfDwUF8Tk^lOY>|)i2D?dz?Vt{PV1TXxxLVv=DdT?i3Qs`3 zFYNg;&!1bSe?XpUqWipLKfRU<-NGgBPQFY~AmP1;Qz$(PW(pCGI@FWP<XIwjyPj39 zesUa@&(D+CpZ7}MUgqD0YScX;nNe~{Up>tQve6-_VK;C5&Vpy&dj)x6q?$01EbFP_ zd{8@;@Kca&+>A=Kkv<d2Kc=9LDceWZfVzL;97?r^CUMRw`AlzrO%ArdmnD>obsHKr z&VNiGoX|PE$7OpQG38})f^YtTsmjXL-A0ZQZBWVv<JqunuEM0EPHup?%WuQiiY+ny zo9rB)^Z`|CtR79fPMv&UiGoE|Ut_G4d!O0SMH1C#pKXMgOTWy~7)8dch=;#3x{JcF zNp((x#o8=x;M#<>@@$#O1=kfW>+>Eut;|Bu016|eSSIO1<?wjOqRBGNx4LeveIFY( zAJKSsJ`qmMka*B?TGDesoU=!;x?tfxZQRx0djyeikz{41@Q!w;P3e^ebH)rGv*BAI z2nf$_15)Yl-C-ou27q#}IPdbjchDT&>4M3o5KA;CNOQD+)h@CeyBxB*%o14R1tUn~ zxt^rCW~tO2Bs@h%i#u+Z+DyGn)g4xqtc!&L$~5YH^pyqA@onPBJ6Ta!60a9cyh=+I z+D~VdlSKAElfXs<sajxf`ZiPr4c}L(yjV>{`QDKYuK6C=N_{WI!kp{%X(s@|&Gc5s zbgP{1*6W~lwpS<>>BzRGFq}OFR53{^?Hh=hP6Z176d|yelLzn&lS)R<x~?ZBoCiPs z+<nuqeO&>S?^hOd`MjjWcs~{}yUZs<G@w8c48?jDu%F<<3@sZJLuEZ}NIt3VloySK zrLS@PU<^fmuB`g#cn`2pzNUOl+kewm!Pcgs@^a~1*AbCN;|o<m3^GG)L<neu?FK8$ zi{ymovq0CsP>i)!azY^Pw+bC`JX5kAm(A^!utKc}rjX%;i10i<hOf>5KIw3SI2{FJ zMfeo{8**B<oucp00Fq1f;aTV!#p765ou{UN2t!^m!v;CiFERN+&|Sa-^h5d0w~4v; zs%vSYAQDHO6r)i0dkUP35|%PaGeTwc=Y<fdWQX_{9U%<O>#7RFxbPRLXx24om(UBZ z*np$F#wtv>!U1Re3~80n8^zwx<lppO#@rlx*<lhR_s8mFdBswarj#cu;uShwJjS(I zPT(&-mtQ&1c%P{g$SSL-c(nwyKcks_>C8tnBsjN&$=Kxc81%!Qu@inaLYzPmcGsxy z2uov)Fv`xmTK&o_>5t7nMGtG=sy#(46oNUelM*QH$7{=hyDWtUl(3pm*F%x6dsD;~ zOQO*Ndx>g1zd0#g5P9ANz{ZG&U;GQY5G!7TU2TbyM&n*n%iB@i{tG#jEk|j^4Mp8Z zpW*U|`n#OO44#o{sqqgd?y|lT*Wje_O7!VbW<AGv8oi!KEWoYHT5jQ$rOh8mV!(!J z?AR+r6Se#5-=9`IJF?I>H^<W?BE^!7UCn;wF-v|}x6kaiU&b6Bvi1og=X$Pjp$3Dk z?d%I?%;)b+dNTPR>U1~{zO=sCg3fikU3)occ{rS4=BaBCSV2&)s`6^yI{%a+UZF;H zS)p7-0%#@TQ)VGXfzW4$EKXRkYfMRELH=Zv(r3@_w3Su2&s)V$;6lnH#$C=&^M#TB z+Ih63IX+Fd-!Er+59e@9R2+F%gum<-I?_+L?bON9y}Q)H*WIoEXiEW)13L|xHMkys z<ypAdblU9`&g@kdpkp4DI6+F2EqgE%X@rY*C9(c$Ry867ojGkRQoV80!$>(&c(0*i zoajQ;LMbuy6uHjtYG2U97_?pQWK=#JHuS2s++B~&$a6aTYEC}vrg-fYZujbvYdc51 zI3l>iwk^W)Y2BF{gBVov&1|jZFz;P(5^TQG(WT|P?IS|L#ny+HnTNC<xnw0)G%iMt zFBT$A1@nnG>uH?Xzg~7#93~Am>kkO+J^;%0NKrx0FPJ5g4FJ-d5gmM8b9Q_h48++W z@}<-d#V?*H6CcC0K-KTJOOlL0B*yMg`lp}uj0C6+qLQn<9vx22zD3M((CQ7a%SkQQ z9$6)7Ug*NgHC&f(pPd0PO0b-~4P>*)Y;U+C_ECnN%HP|ze}x{t`v+`XY2Sq=d`q%c zK|sPVrkXzH)e<CZi!luDQ|9@kp}}F2L7E8?AnC-9-T)g#V<3_ZMA@YD0TlGhYjAlM zy(UUe(~Fi&YnAfsa(Sh1GSKet*2h}a=A_7>EJDDUi1Z1LDLxz?JJwW*{@3pQ*k;2x zhXc`O7>m9l!7S}FT(4%0I_4-)5DP}?sBbW+ohjeg6oCF|A}&NSHiEc@)!z&u)zK#7 z8TSIyF+|!fg#m6?>*kB#TGBwNc9Fw5+84d;Ql;JBdg2wa?J`(p*_GI+^q5DHRAT*E zf}nPVl@HndLn)EKVUVqI)u=+`P*M+&gbUQU5nZp7LcpZ`bW3cOQ}#=>QE`rG-UvVD zd<f~(Gd=^RW<LgCIT(}M5{X!uTBsIPmE~})La{?p)uG$X=pXf+Y%i>p0P%9OB$C(= zNgWMAHPCizy8?bObc!vi-g>wdD0@U;mLAMeqZs9(3!M~+QHqVe%7(1Qfustf*LL31 zbKU?1Kn(pS;kdEsw{$vk9Zplq0fjbKoGG%#oQoaZz0NCNSK76z$Ck^7)EyUO&7zhg zDeoG$NzgeGGQ#LcEG0ZhBgP``i_NRCehDk>LN*~Rd2sNhp~PNb3!~;rKDY81YZ$`H z?=3SZIQnTt%mW^@!nWn-RW9osOQTW~uLqWLjMRX~M$xMpqL$GLN-Ak#t4!s;FX);4 z>GG9|Cxul(INLlWrH^8~vwt3Q-otdqB@StR&yX8y<zG>Dt4hPLh3ZbMY`Jxct`ohl zV$Q}#D5RrBP-b+Cd9Q*7)?Ek><zh4G28I=y+PTk^OBrqRp`3*{4ZR8A_T5!DaSnA^ z_+`>i%s)29;kiiv#U~<KBKbu2Aq)xkL6y_V^N%}?bn<`oFtXsrcS**SOBw!Gb@%xX zSNJ#jei}xZF?wfa5S`IWlrefQ(OdLr5ke9~qW3n479x5J2_hmQqW3aH5)olW3nGGu z7BSmz@B6j)z0ad_9-jYUt!u68`mXhPzp*o~<hZ7N?tF7$9>%MEbd#2EF5Ug1p%Ldd zjdKw1oR%D+$|GVll3NR41+ILMas31=U6rcZR~^@*rLG!#U9(yzlp;ZU(hotJkglcP z{)o;W@Ey5wy+KDcJ&r9hUrJ#>!D`Vz*?2_|sz0ZtJ^^wmf3g{LWlZVGNy-g*i#1)= znRh^vK+dM-d_P-^&Uw(Fi~5M{1}t9FH0FFmEmCKku2NGKzm}m5MuC+ckUj5z8nYIL zvE#sAF50(yij>Dt=`tgF+)0ImSXJh=yu?+tuF3@M&n-OMA*@1m#`<bR2Gx>PHur&Q zx-ky@$68}noP}vOw6`d3j&VT1@sJwJiwzArEh&=yE!TzRe_(SK7hRG^`W*&7aS-Dd z!PEpVvF&tm6H?SbiK=Vi8(}w#t#RxIG3PN&>!6nWX0JpcrSS=P_D|MBN&Q&MWN85{ z^~M1S8=}(Llt>AfALOGIX--(zYKnzyMT%(oq-xkLT11MRpJ+LhS&i9waxQ}Jxj@cG zw9<yIXOB))qTHk`7kpkBn{xEk&Q)s#4d#{rqvnmXJ|*Fi6stGM=KRsu<Pd%0n`v?R zeo18wyrCS9m?TB%E!D8e@lzodjwe^0ps3Q6>v9Fb?aM`WP*rB}b>t76IE@|$XjaZ& zXD#j|pr2hdbp-;Ds?ucnqPsQ7qm{U0g>Qg2&`C&(?i<GsZD@(bf4A79oDgOAt!L&N z&~mR~8$ie7g#`lUzO0No&`t@xS1<{Z?#KE;cnq|}11K1V{6c-KUxre2pJ*wp+33tU zscOT%_moBj753DpQj}_kM4PW`COa&~Om)l`qvOXM;IZ2Eth4ih;)QX2)B2}CPy&;- zXWD&k3mJ4tsyanwI8ZU(KSbpl_Zmp7`iXc=dI`F6jFlYUYZc40HEvP3Xx;MtgP~r; zHxTc6e?%vQ`bnI!_KMzNW4=IYMrI{?!H;rD_;D;g;k-djP9Oxwug6hL;|!K?s*W7Y z6kUSaotN=s^ODpCZRZL{=a}qjj5t-n4i(gy={sT%?Ec)o;rD<!K-%ui*=B11O>$0E z@I*_^gM&A=qu26R0#e!JE+>!k^%lR5OdB-WCuS+5dCC`cigvdshmI+Fq`G=7kr*w4 zj>f<^2T!^^#98fbC8PX+T$$MmQRm_r&+9#<6y*ckZUL={iEP4SExrkHHC4nf5;oD* zw$TZ)Eu_#5_s9uw;^-|`8A-tHgrqZ|m=f*23wZz&OgeU8x-Y!V-SJfF6=zd`Az&@m zR9A~r#(QYy7U+KRhKR{_nW(dH{qjdDKc&gpo~0ZCaBonFw!rYOA@I%&rODBZhO4)_ zT;pay{Ly5u)t+twE`Bgv`x&sD|3p*5PX}ovre+?;GKHHIKgbGLvl{@fB|iHk8egH# zE`W<Cq9wS#r6-(uS?XvRu?7Lw*1p{hPVyN9f8kSzeW8QZ`}u`-dZGV;MO+7OU}ro* zS&0}ADc_Q*P6(o;ei=U^x~7P!66cTCk2I3i9~9slC|%N8kD!HouOAbjSkc)M81{YR zDg(K$3!{B0|0>shp`U&=r);C|NvaM`ocuGAkgy#jEp~qtspR1p_Oiac)P*#D&D|y| z7@2UsyIJIWg-t5%O25bsh56Z&K)FI|y8$nDZO-|5;IWiiS5gMG$RbO8`$+$h3(dxm zl}|@vd0m3=_4u1kzt7|$hz%-TJ=5j|eU|sX&krsi&Uk|HPqmN~B`lctJeJW<o1ZnF zyW5mg<Fi4P;r?^<?wQt$DUSDmeQon(IReN)TuN8fMg62#9SwtD)n-|;(K^v`ac>jQ z(zbU&bw=3f{{!<i$JTWCE3ge%U`xJf2a!yc`Qmka8bdeEay0BltC0|qozQ&GV5J#J z9RfGtB6QuNp9?EuOibfeF0ip9Cws*b#q5c{7|~DcUumTW5hRkX#SL`lJYmty)x#xu z2x;q~D8_@dw!}?{L52f2`^OjWT*nB^<`8ar2Z;ZRV_Pdt+`Ba~pQ9n(U>>uzyspoh zeaM{p!Dpy^X;5l5o=#lch4!PK-o&6Poh1(s7l+YZoe?eh#XcnaM4Df`bCXOjtF}RU zKbj`f=1_cXL@1`O#xL{t-}F_U8&_P|ktLjxntK7V*Fs2Nit$ckk;J2u&2O@GA*VPD zhfcyD$}3rdV>b$Sxaq!RymGPf7IK9fmYestiVxhQF(SQtrAg$uTP&`r8Y(z)Lz8Y+ zrfXIQkBFBB%UX4WAYo4B<YR3)9XUE&w++E>{I1#_$?mIB41xclHQ}#5`&V80?!|`4 zJkykCURaZn2fcCJPYoXZt_~z7M>EIAdMrn>qa>Tl+uQoM_vR9>gpwsoV4|q`0K=uK zfO~!rMCxIlt58;2I+Noq)!40=Lwzi#!B0Vj4<I&PaV>Q#roX-4YRwh61#svtAUAja zR?GEVMc9t@rII6S4B>dP^v5!9etM=)m077Ue}H#mX?D`nD}L*`VBBOdvu?l`Qy=AM zYnubW+AehF9%mmaEY00J9^;(-wA1GlnDW>D<rMO;$THrB-7Ro0S%xNXsclZG*El~v zpw8J}GxT-$M3TrdSxMvSz^oMl)dLh*#Mz#M#Cw3;0|yT8<MoMe6eLq9UeP`ajJJV& zZW>ht4b3!q!(`G|`FJ6>n)$sikT3CfGs3iOhH0K?{x#fMDoWB$+RzFzbU6B^b)k~^ z%&hf;MC=<&qi2G-!N1+bs1@2dsV$ioIY^dQS?;p_QBBcV_C75>XPGwrWjt*SIk&rn zg8HQBN|Zt;rLeI=CA?cSktR_d<Ig;-D0-wvK#WKrH$IkFb~d62q5i7{{;MT-qEj!$ z*<=D$Q^%nj?gryAs)X1Qi5IGY0~8<l`T8K<zVR|oyh=AZn5L8L+f-pxHw+6xOZ|)_ zPg;}|x%GdNmqtH5T8^A+bh40k{n_4sXFNKaSniH%!_PL~lfyVj=*6S|_18|AMm_|K zAYyM1T%n;y<#1b0e=c{NXwhKL;6;GMH}7i-+>Ot=Sr`Eu*^2qic5CsgZN6$7_i2g6 zY@ZsDf_py#>WheDG_&x4#0Z--v2Mn$8cPC#IHXc=HWs!%(9Gyp<>^tnh3W0LU+Asg z^icv~=T2W|lxjo)5mzn|AW~oCDah(=fp_8M=b^juje5WMUdV!Jc>|PkmfE9kfF@{> zndM#agbu+_<=dXR;U85sbJ%W?-bY@n>BOyVIjTmTUd&i^&Jnx97x5RlqIq9c<7^AO zt9|9kOYc4OkzdA-Gj?7Bf<V|b#cMxsaUU-jVh?|P)r!06J7na&%ca;F2Bcyw`B;DL z{!xudoX|wUd*9{rZ@K4o4voQkjC_)fx10NdSK<D@KbsYHMEo97{uz0|@pTHQ{^9CR zo#L*voL4RFwl74!e+I67d0y}q{wxY*EhJ}mtN6Wg@4*a{(CNMYn|~(uRCtM{`tg)o z!A_ndyuCz`ub*h~(|8oV`<regcrxJo^;^gYy%S9Id%x4Y==G;zyoS$J*3V<M`NCW6 zt8-0T86<k|)4fdU+!lD-{LJyNtoCu-0E19(r@n=0>11o`xJK04m>zE{9o-JsAgGLj zE4+rRywk%IZd{Lv7bs@njp7X#D)rq}HZF-GrmR1S5}#=9nIwXD%13WkRX>fCd0E@U z&eR~&oHXVCJkwr$A-OctuG|Be4j=Q;`*`8zl^NCc#z%J4U3M$|#_pR8ob=aDO!-X^ z#xpy7Gv+3DLXWJ-+f^LM_#MEzUdtrD!Z%q+ABk$K5f~h!%(`A?<umr{JVrOmV<3iZ zD4cH4NM>?lYg`9M#Dd^<E}Ec5pIznsy2zf$$>+tHGhj|OzB9V=-<~ws;cCC8E76*+ znwu|rugHp(+A$t5mV4eeW|OMrRS9@J<J0o}sh{`d!H@)#mW);?*a$uznIm1Z<PRkK z%hi8U`K?HZxajrDj6_ImRk^KEzfk1ueOX(myvCtN2x&S<;&++tkp-l$sUo_vCr^?d z%V&AXtKQrcu5sTz^ruCeuxwkE_pgm|G=~jvtg)~;U;9&A?8;G9T2{NJs8gkVPL-nw zJzamBTtRxp*a3~48|J;W(#~1QE>kC}4^5H96m-{bWL%H!Znvq<srEwEfBbpBYR#%- zhR?U{aCF^niX(|DYU9mq0{BUe0)U+q9$&k>-F2-vo{K#C^jjOp_h~?1<#!I*^U)6$ z-N3);Z|--6U74Id;il?}L=+8_s!ExBUb(Ru=FN|fnW(FjwT$xlc(}{qok>zAJ12{W zHwHRlq8@SxaQbw;HE#v|iZPPB{L|hiz;XT25uXnvX04!Qgr-F-IG)p!%hSN5pg4*W zCHT~DzK<_q0L&TJF{r6sEtf!`rze<?zJj(hW1g&V%l76iW0VSMbhLQ?2`6!zy3uj< z{?yLVw8&C;sU(qY79Cd~_r`_4hzJ=L$ldE#Yjb1NFh*;dzHz*h|AAYhv5)Vw#k@{i zaF*;|AMYU){sY9%QCAhi_NgI{nJi7MZR}%iZafm?Dx^x3)7C@p7ul2?lq)XAT903Q ztobk|$xmNEMuclZ^FR}(*0X}#-<)cxibeSJtiV7yNvl?Oa~<hGoSJ{h#_1<a%x^UN z?@COJnIu{=`}gk2??C~oEBj4!nXT8`XdKiSe`kgif_WFh($(tLUQc2-xcg416on5T zU(KFWm^{tZ=;})htNR|WN&^qM$gV$7nvrKa)svnzm-dcekV>+5x;)FJw@Ve_I(F3p zP=;#u3M5?l23%0wm3_w~*sQ_e`<O|w{*jk;970bvm23EvR!z<WD;KV>x<hL45cg3V zaTi*$nr%=tU)B1~Wneqc3UIm*z8o72nGdvA&a{O%PzkQ<Y1*(44fYFX#?a)sZz+y+ z@w1-R4ZkiEE{a&|Ph8uX(LDf80+{=07qTY@=k73stFF>5G_$XgX+jvHAp9^LPw(Xs zt6H|e)szzD360k5#2eVrcwWKMh;tH^;Ul34=zdOSEH2qzfTI2!eI2kDL|4LMCPI0t zE4T5IH4?PJMNncfm)t72wMk+HFZjE5&b}vGq@kAMpup=C%;8SLy3!4aGec12gf8Z) zCxXUqGTNeljO(8bF3!AST&4FASmkqWUDL<2N6RvM@Kc_mT+zqx;|ebqf|xNS#Fxr- zy6=1~v}Qrv!zGdDF^tDbqVly@iUjxF;Z!p-d=fTvvWs!ZZ*OjDm4Hgc&)n`^J^k{1 z!fR;!iIlE$OagD<mygqa{*fJYO+3Jm^vD4Ss_kXvfzui}%aQ2j(*6^Dl}D`THFssq zh<u%8?6nM?(w}(Bf6q0`_7nXOKjck|81#Ou+B5Kn%0Bh|tYAU&%@3_xF<++BjZS8} zQqhe0D=4Ds@;FP+QqEcbJjt$TRcj~E1KoR)RN8f>P+-mv@D@&d7<-K|N?4Q^QZ%dr z3}K5xf*3wHB&!kLJ}m(>qu5gSH1>LiIE&3hu(Vk2LCxWQZ!ZLqd1o$~5oRZc?kRsY z>+zZ*?Inv<X=$3S+ALiO(VK#EM!(fnN!i^XNn|jOSMW|ZkUpGw%i?o{go!z>vnqH> zM6;NLx|uX*k-6h`0JXsB*w9yibm}U1XZ~#vXtK#DefLmT9j4k*kEXh$&WjPBH+|`N zZ{YAJS_Zuj1DX=T3xgG<d)n&h?uzH4>n!+a-6(DQDR-SUzWdzf&Q_`tJEUGg(V}*> z&WdT}*;f<Cn>3f_i;whV2b`e>x-trE(P0F?uenD7)fNk1#C}b)e^1u4K6=s#NS1c4 zE_GW|&wcy=yis^%A2-|)k(DGqm3ZS7l}Cb@Ol}*s0LSrsP*-!l!}V#jRrO@c2Y0;8 z-ECM=^{8frH1tixYa-0TLjIg4*QADv9(8f3Z^fKpo6;|wQ|u5_RxwZSW-ms4K=r!f zviq;3!+q-dHMSI9=)1<xI)dSN2MY{}zeF$}J(V`p@Y!dsYY7)2k5DKTO&o9Aou_0j zNK;<j<#q{(SM(j5<W6S_pi^ObtSX{ER?1;gx2Dw{>pM4$Vgfv6pnWIQ%KDm4ENqwk zm-=7%Cd*Dyb;}*?9dpHHP729FuLqU(+>Lu}Y6V$dawm3#JSsU>>R;Yw;~!5iw<ZA& zPZ0OV4}%Lr`#cQp-JuSbxsgVps!Cl{@zT#fq(?b%jk$!NZg_k7XL_vv1-;&$CNG2| zaJ#LO;m_4jy=$|&s_s<pkCMitSGXz!zA@vTp(Rj&bSyG~%(%i^YW6yHx)K5{qzrIr z>}%20Azq+_1X2lmvBt4z09J=r;nyEB+I$T#8E_Ohwb-YzgPPGs>w5ZJ+1QY@F|$X+ zmUO#ut8AP%-WsqpCP5{o58PgDub0)uxgD)KA)EVC@sBd=c~>;Ky0D&wBH9-uj#k1& z2YmlLCN(qNA-Pd08dpMDsl2c{Lez9*Mz<kp7~}EQ8$RlnwKUp{NXRzdA%1p)#J94^ zHQ=_oq|ZA`E%S*wHP*Z5KnwC-yZD^+j&eZgWSwsSNbgxMw$r<wxW}}*>(EioM}s;; zHo7Ac=vh(k^68nst`rt-nH|0;xNuV)tK3I4OGJBjQC85zh;8^uuo+O5EPzp}1E>Sk zP|YorQ<HCn<_jzOX(!k+nN`61oEi;SV|AyX%v+H?X!ND50x=jyB76C|HUABniL7XD zXOgt6GJplT+%7Q)eLubJasvnI5*6uHrxreXNn4qpd?lXT15#p}F`O4DSbBOP-3%WK z$ndsDQkSRKh9-)B#kUVXbT^v?f))_)W;p4oH#f!1@rxkb_*JPnU=$iBMlrJ>`oeOJ zZT(}_8~vP6&fJ8BZnx~YzK?b*@}{0Ovvh+O1jlodRay3x={QanlRw@Sj()dFA~o4< z2&ksnmsNt)JkJGvV;x57;V&4aGDZ0GDa}f73SF2x?6)6fQkS@!-ocL|Ob_ZFR$5?m zu5F?O^K|vZMFHeMH$tl3gIz6ff(hp6Mr4EL2!Z1M60y4R^4)0S9Z~E`JS=EFow=Lx zW(7uUr-74G_^`neMOUX>!H9`3XX{#{I<5}sYn7+Ul2r#!>;>}HXbOstwwOz@RhY3m z&jjD~;GT8m$V~6(2zb9XIBoNjZ=<JHvVwPqWVWGc?oQ`;vFX`H;_8a#D!U=|u1X9P z&CJ;lc5#{ZmO?*I52;z_6PA{~DrApLMFbj*%m!M`d-*nytSf*M`FiRFlrK1&P(QAr z9O7pu8m@wgu!R;ma6b=`Qcfv|%2^f{Y*Y*fOV{)Y2ChkCS8ud$nIk|d5lLYJZ7B81 z)eB7)a`o1J7)r&|b7oG^a>tF~0trA+q@-?#Y?Jl~dbfw%Lb~0qk{EoPD!!IVQ&zg= zAi-#NCYjze`M><aXn!K4P95fcKk&c~;-miK=T&9{`ih^&bpr!VYkW%aTpdZ+SA8w2 z#%iQzkw;p?(TMxoI~+G~MyS4jo)sv)P%~dNhpDCj9IWhL&Hjm>c+&R6y@`Lb>_Q1G z@nTgdOxA>Lh_AF<15up_!SQA1u6p-19OR%(cLdQmSub}X4iTlA-_y}(zKwnEtaVL$ zp9yYpOOIc|w_+3ljjg2>5te3yfB^s9-!@+=p7rd!W7LMdiq)t=p}662`akxc6NqHq zSn+cpUzGWX4_doiUd(eW<=m}(lf<)A4x`51Mzb903;N`L@c886ypA&ez~KB*O9yoY zMGSKI0p{%fSw0lwh_}FSKQolw;h6FNXDN}{s>!e~$Ee|9AZ)=+lvfrH%)Btv%>5%I zp31D+Yj0~NlOD?q?G?<y8R_9}k9av++{KK<D#p7R9qO=MyX!YLl~@R-_5JC4#RUD@ zjklRlx2frHIJbhRR)XC@8Mb{n(JIemjyYtuJV$XJlur>df0eky|H|-3#c70rG%_k| zHtKyxZd~~*#dTol<BrA>Ruy-ub)6~{JdSR1RJ_|kxn|}WSV(e`+9m1G+T;TgU1Bfq z-MTTtekCA1qVCznfg1~?!fDve?RB3b(w%XN3DwYRRG|~#j+5M6dH;Ch`Q_D9mvr;o z!|cMRe<O}dRNQ&PH@na`TtCP$FeYxJDx__2(ekt2#j2IlK(O;||44XX%)K39Iq5wH zSu0t4gihlpu`pP>zyXSVstj)G&DBF^tdZ)lgMvli;WkzZ=Rf|fc}ATh1sfWjpg(O% zhK?S%AG1e_pmyuMXimwtzN(d`+wPpZTfOeWT252SlM)E!=}e6H!^&RwdM3{?)6nu* z3jToXzUQ*fz22oNgo&Ks&Pj5s@+jmqbByh{C!<BF8zZZBee>N%<hxD$YtiCHx?Fcx zo!-~+8`eN38_EXcP-~k`OSr&?Zr1y(u5aV8oH5LizfffZg1h`vh3&pvVp>F8=(vzF zJWl&cE|(sDk~7)0U%PLQxP}ZC>DDy0%!?f?T;7`!zb#<6I~2XF;QA(pAK9*+X6X#? zM~)!jbtCVEjZzq5>oR{DYfMJARcCc;dQ9tPypeZi@kMNwE0{K>^rKZjdKs=!OwnY^ zN-8Q&+$6S1F`7*XO8#Iu$9RdSItCpn8Wx=oDTS$}U!C9O>C_gfV#~YsMYaK*qSGiM zzQT(OOY2)5b5cSXThJp0Wd{-?w=41VeJ?VB`4IyXfqk;%dmSDa1wQshq52M47sXt< z0QbuB7^PIbicGD!xENa;Vy=<ptwpeQpWv=o+zn+Md5dqVmpuS1uNxaV8{NJXjtU%f zGBnB(e1-jsR@MILoO1h-B-?c^w9=<ZUhbQEe(M-@3iUU=T;c9=#j|>Vvy4)Oej1LR z?qCEc-BU_I*$#J)I>VUsqx^cMx(`Y){N7W+Ip>;~YPh?7@lEz_`x>5BOtdZ+=%j$9 zLKzh8&e+$zFrB$QVcA5<c=Dr1-Bt#|pfQ#dk^U-Lk*OkW{mOaoUBRS;30>KQPQ%r{ zsE4;2Zf!k&4Z0qtlJ^wF>(l#lqT-CV)$(hn{P(Fsa^MEvCh?vWoAE*Ucf5|{Y=9>I z54KKX^F-K(7~70QXVMGkTXDvCgEH4fcnlmcR<Rj!=EMm&Bb|BWuZT8!_7YH{k-}E$ z<CwPlolwO$Di^(o9uX9d+O&6|W+{(zgI_6Mu4X0=QXbQb$$6Y|%TO_bVlq7%I<J6= zHQsl9KVVh&K{j(kn7_<DD~ACn=%D;5?$xzV{kI|LC7`FD*AoUWfp?C(E`QtVgw8}C z^F7G`^1BOz?Dcw;dx)`)J>vZrFDbLW9zk|<pE00h?n!o|NF&}nwUT`~rss=APi6b? zAFkq_xQF<q7<4<V*G#CHZuAOq2j*#`6r?)HRfFa41}lGm;FR{^F8RC0{7kZ^^>X?Z zIZ%FlR;f+eX0ytr`0FjSLt>$f5sXD=))@}&qoub=JiI`?L!C~Il1DkK(sneK4YH^p zk{)Sm^y@-tmWoVcU^ECRv<9@|mGryd;^o)si>F}atnZsUQ|$ZUJF~-DsElS$j~lQU zniMLVjpYK+K<+ube06@)dR4_tRs_y1FJs6uxjs(yApbP*_uYw{3X-}@c?|1thxKu9 zrZM;7D_-5jvL#iA+*OINI}-3wruZ-kqU1W%(JqaW6`|9|#}mkR=w#;?&gKsHcDth5 z^(pRi`x7~i@D;X)3161xMr*6E=bOCbh84{RR~?q2O`|)l5DCI72UJ}WGx5jdQV;LL zR@tK)Qk3yF(f{lV<N@&{Zr-;-T|0{gTm?w0u%~DPH`Rq3in}hKqt8pE9Xl|8y}uDb zp8v{o81~TJFRFZamNfRc0yz5|o{*O9=T|ZODl<|tf!D%SaxQ=zhtaN@`3RQZ6aEQ2 z>u!jRSheunUows>8q!>ABm&>qx?b_WsjN`{`L~tNi?^=u9gR33|6-w@tOpX$56W|> zJZ{R$=|xtp`#zj~IOkY;F?zFfiFy}P@pr=c_k-V#gp>O=uXu5z&pC+ziOso*JHM{i zcJo~y&kTJ)`g~z8qAnK&U5>d#+W++MVcVB^^y;!@OK+k4k0^<HI2U#5vdir`OVqxa z*rRP+l<x&jW`fVAmx<W&GPC<O%zaKRVV~Z5)GN$LO~aeZc@=%#^ni{rzIukp8#x`v z1!5_?A9m;*{G6#zd_vFBH_DMZ=7{uya{$N)k(kz*7`>-~n>jssZOwFVS@NP*vd{|0 zSI&3E?)1g%%(KC>*VfPTv-hpFR@3>aYEVP3G{i%E+sB`pefV`E0T1g}|M$`Bs{`M~ zR@AYU_x5rWRGFXr<Eb9Nz4Sc*1ZG!F#+3IZ&~d3mLZvGPQkcaYx{|Y3+5$MPMobj` zS{lw~{0AHG$*LO569>;5k-yBY^n|ne4s~&al$yk=1fPY5Gr08SYNRRbeE!a3k<dBi zOB-ZXHB(RZJELD|*rTQR-GRlw21c8<ggiVly`7og0#XVZ=~tp{T+Ae6ZWpH=uU$=9 z=nfwo&za~Aqq64^2*4Ysxl)&BtWlV`ION;{I+otIMvKQSBk#iZPFpvh-eJkVTbJzT zl_iv*u&5Z}nHHC4Cgi#CTVN$3S5Mt&Gs0~z)g3gKrY6(Y`;mo*OJL4B0Jr}58Tx(T z-;J+c&!$a^hi?Dsv*S+r_HJGZARo7Y;G?@Zju>=z%%Cb1Fx%YPp}sd3HNs%-t13Sm z45q|Vg^)!KQ!S!`waEGaGYSSk6eR`2bwI?UBU)TUm&K&!`>vJ3`?RbSA8=P>9-(fI z)Ps0^7&vmxWvGjC5f~u{ZE9Sia0ek+7l|%N-~rw?=jN5ay{L)6OD|?JPd0PhC^CVh zc?5AYSHv^F>OkDFH1y4iVgSA&<Uvh-Ps-`4AL`$tn+dbS{c5Z+PI$5<Q=?5rr1ZgE zc$p_O+P!{HTE}_|WZEjEA7!c9XA20U$&1x}6%X14OmQL#1AKQbit=*oDO0qFnzsVa zW@;IWM)9%7`Wx5MDMz>PkInM#=3NIy>ftpWHjOpd4(r^tP5sls8Ev~q$hENgGom%E zK>6hwTbm50&I)~DiN&LwSO0p!^o=dn{FXPC(D6Ua!Ffk!x1OAKnyaTM6lZDda;V^y zR(jS7Y=5+NGPW>$1N*D(&0Wj7u2v*=UDc9fU~&NRUX*~%`{Kc(_$(vD*2^V$HCWZp zbS^jTlx~qxu^t^tDP@wQeK08TnR-TT0zGG6ORaXtRvs)(_t@0pOS+t?h^%MOtooJ! zeTapW?Uz~cYSlX~0`~u|tBdW1h3dFnHM#r6`)NkOpwElRyI%v}!|pBKo;JDn?e22M zy`_j>llPV%l3^WQ2rAPsQX*gA-M7h7Q(>!_aV&`c&TG;GghAH-FS5TQEtSJrNQPZ| zme#7#%j|E1)9C-q{@UJkyMnRhN2R#`7q6+I1#v|M<wFrbLx3~qY(cNCapC{sHJ@-& zR**to`Rn9R7J2R)wl{uxd71syQSv4}dlj@g_N4eW*!hJy2y1WYC7vsI?{b<U-W+e4 z4~Iil-EI$%066M<AJK1G*B>SRC;R&*WFrRc#A&KRc)2x|U{s<c9YNgwRQn%Z^FP_& zf{-7jotkm~#cM9!OJwGNT$v`IdJZ<GpIl8+cUB4cKB62X{NJ*_-CcW2pl1;Fw{PG5 zJ>FZrTwlnmY_E=g{8*lTe>;y1pcE!XLs)%?G0-b@#Q)7}y2V(T_qs%}d$adkM&TJK zlem_sR+7>A>?<h(6+Z5%;?FlLQZeo9t7$Ty^j9-vH+(8Hm3B8hvUqPpD_A&LN0(`U z$a>ElW63SgTyu31uSa55zUz5*-u3JGPBt9t1=kX(HwxYJ4K|9rYf?5I8_D>t6(7bR zznA=1_E)49D<b###^oKm{k<%jQPihAnfEac5TUTWS&7#b-Ku(IN%Ot>PZQ;}O9Y2A zy0+}D=yq*oqTzOZse7lTO+)*(s4mq2nbRN8I_2=p{q?NFv*)b`hGIDWu7+&qK34zB z?C+IlJFOE6m)YL}d8*6ouZ=%rOTXQ-pY4l=+KpJA$R4}bYx(0p-L!$(C2w}xX>T^C zsod5M>FvDC{*HU^X}&u-`tj>MfJ%JNkVY7Tr%2zwy4Oc%JA?&LGBG>!Gux`pgBZmE z_J_EiC0Gq3lNR%!OnO7RK77fSyr$~<`T?W)K%*_-QA@z@Ng?0z-&3kT(l2?<`<{aY zZ8o(~!me(0D8NW@^6-PH9_-JYrLD=Ik2W_lE_uy+lYc(DB*Bj6-KEs<OomsbWoI{P zcK#o{=J8U*F?sTM`5_hjgc!?adO}Jlz~6qyM1^pmZfu>D7|pW@JY6rm@%(h7#MZEt zBFiA~mtR#u;MrDP?enw$i`SIA>MJG3Ou<@l%v(5`Byy*4bWa)U-^(ths|j$nvv~Q7 z@bpz+Gp7?irkl@5@2NYLJ>uW7@0;vLL)=(z0U*c%sm(@w{i_@6>Z-Z+_t17dc?c{a zgV_HgAw~H8hqlaW7lXfAR*pPpDg%k!g~leEAyw=O9ugGs;uE)G*dtT;tM1@A7m)z@ z5kt`Tmt7mqm^fi=1A1-?#B=Vd;PZVKnj3XFrT~<ji5-O<E+omGIWZCI$(BQgpqX<g zMUwRcY@ujdaXQs#=#EhZ^Zq)J27v+yl~l046^td^+)vv$(`4?^*9}~+P4_Xb<orA` zq|mva5tLrZ{at@pWnn)vY+`jt9m&iPNpy^$6L2%c#9k5hj6Vmu>K&l<^W<wOf%ns} zM}z|1M7qo2to~SAUb3z@N;DtB3Cyrg0fd71jW%)2TBFTO#9v5y0Vu6ZeYt8nkb}d( z3lK4r7!x0phvKUCw;Sn2kH&`AE{=!}^^9OJjD>5ASN6N~5p0x1Y9<7fbFqg-d-n#l zx)o0E2#HWWbk8H~<YUZ`O>p6axC|(E7jipUBGf`8>Ld=XKuxYyP`$=qW?cIQ_c{iF zl@#HFe(QXc!*UPq2}b<G9?1<*2pf}dATJK`UhSiJ-o&RsD64<hD4(cj+rwg!kq#(s zGPm=v8k13Pe8cdAyO*1|4W=F|YW1PCwJImoDS2vc^+QF3C$&wiW`RxF94F*soq5v; zqXOPsJ&}0HYi?7uF96xgWE)(cj4(2)#4<R&YV?u+VQqwu<uoVxxMlpnwPNQa)2-#> zji0%|_(3lyi5igJIwz{D__vG)jS&)J*T1C>Ht%INyM64VC;-GVA{AP^<b7zm4CO{5 zJ|T?=(PGlYHr;1`o^cfENU47v8Ky+GRSMqp{xW74Lk`6uqDAz1M-1lFAh9U(pjcMO zxPwYXZfkg6lZPR}_DDyXVMT7lFU{X-P1Lp}K<y?#6!<NQ#*^CKN*_}vrVns9?o7MM z`?sU`YnpZedO+|6>#vA!>v!`WuzLxxyR5uaK)4AUJXv9+b67s~4rUpSPjS6oJ`SkF zKTlw}8B_Gb`gHJfuUx|3JxxUHnO}Q5B>a~@FvN|HHnfqa`?<F=tu0fWe4Bknunp|x z7s-)n8tpsMR@p|yOmk)7+rY-m2V+;oAd24lrne^wgFJ;d1AIJ0_VKbbpUX{r#<U;$ zCC3kVNzg&Z)!reQ9s<~9q<SYjFM6*RVkuB@MdW733|U)y?j^->W|1cQ^evwq8}$18 zl$?pMKb@rm%~y7U&Npl+b*$Zog^t1G{Cd55`%iOic{Dnip=E42_QTd;&mWg=SszpN zy;c|)FMq!E!1+Gj1Hy_LZFFVra>QHKaArQ>)o-LmLt}R$kZUC)w{CqKGSiR%2xMyo zPKV*GM@XqUqeempj8Jr2!u%b`K6U}aC_#msr^-%1KIDlGViXVpMjv52_ihAK1`A9) zY!acy{fzaDLt2ysYUX_LzgIBxf>Qa4t3mA7ip{r3Bfx8H86hxk?L^}J;W2Ya6Wf!! zG1=AtR~DPCZ^briv~_t(h~n|>G&!fW5ORRn|G%=oX7Ap<DUa|`MsXeZ{A;C=MsRRD z9rdNgU{^SzhcCd#FUE#s*Xnm;PB4Jqg;aae)~Ns`93_Oo8_?mFwa%YLDc5|_>KT;e z;Pc+PWCTJMLZE3(As(EK<ck(LhUmz;WxMjQ_vhcu{y%4bs}$)kg6QAhh{?aK`mzBM z=OXE2XexSQt}&Q{Td3)Ssq@QXL2fixPMA`V56Z9%8kg}qwm30q`h9am6e2){_<#`w z{!$yKzE9<MEuJYjP8Z5-K#2Ftb~VOAjQ2F9HgzlT34%(Yr}&2yGc=eJgdP&x5{ji@ zpz&dkq9#Gpf@mj*^ju*f;&KT25rho((&00lJyyHdeEF*uHE5qY7Me_fqA3L64&)46 z*h7x@V65bQ(4Zp1V_w}Klju*3g;>zy3PTG|5ZS`&mV0WBSg>AC{3ST$Xl`;=sZr#L zaKuyH>$wjMqBqt9V_h$aC`z+vN*{p1Zf+`w1dYNVY!LwC4oWJ9R3IK2jzL^Rhq~z_ zWcFe><RBE~;LAqTef)#>_vqWgLUk{(BLeH+SJ(f5Eh%PF>7^;j<_`>NHHz&JPoQdY zfb>^A)YYyuH9Zeu(kUQ@Bt0tV(lB+!Wrc<vaA)(XJOBa?hF<brl-YPtb{vf+Y_}kE zNil2p10;kUP)&&R(?<x7P}gCz%@_b*gR%{VsZTl*{#0rpNIB46*kM^{Ni%gd*)@mg zky8!G<|)t7E{Id%(A)J1RZh`M(+`yq(E}(Wj`z~deOTB;=%?)-fl>4=Y<bph^rMRK zRo6T)3cehj=ODteTM)UldD-@)r?8+u#K66%nd9x~{}3}k<@tUb0P<z?6G_jdpC9~& z31wff99A&h0h?B$8bl)6>LO#lFga}%g0ks@?Q-3lq0@HsqsN7+ZuBli^r!ep_RYe* zG8m9Zm23XMb+ky5^ziQ1BXa{pz#E#(k^IIlENpKczkYLB)++8kE$-nc`A_!OzGNu8 zWTdFXg)L|7OUZ$oKCmpa4D*C>t3<GuC8{iT!uN?73Y@F-Xpw{Q7x@klNX#V_F`D7i zbn3FdpEATYQ{bX6VP){oEk^Cj>hLJzn?JCGqNjW)_Yt9@i!TfWHt@U9e2_{RCyDkF z(;LRaI_t|gNDogjaC?z*zU(sg&T{UBa^ACYBxeO$r9!}=;z~q?@Z$>6&I<8`3dyqy z3}>Z`N~N4br9wod(&I`ossb!SQp@P$<;`SERF(3XaVwr)4O;Snm~AXgOU75d_oe+> z&-Cv~i8LnhT0~`&IgQaN<HOD3`*<ojbFd>#sl<MKe>m8WKj$h6a=~7L!?HLL9`>fx zr~?Cywu{Gv5wCi(RQB;e*BTj>ht3U^i4lmTu)5UFI!<y646^@NemjqWvvL{m7}QdP zaiC*ULAZz@jxhB?hIt@V)r-^mr=t3`W0k<@G+;D*+cl(yrr|a-{eBN@We<LcfVL6n z{t@89LiE@o(+nSk{Aj~A9xiLh1d0g^#Ui#4aK__G$&W7JVE8;9zFAiHtr^Z(kR_u7 z10uoJXSdPp*Nib{n+k|+B20QL%doD_TR5cs)KUiUApQ>IS`cIqT83h1l%#l|jYtXB zc?!0u<B*26`WawOs4_fg-|o?D_P}+l(}75JjWUH`8t>JllnoA>%M48&zPj-a9!z?$ z6i2heVQsvJ<@@3Ofdf$PS}N$%Y$2%5L3U)kP`UO3N&A)n`(|zxh{aCoBjTan^;kp) z_7ZGslD|XM^2o0QkAH&zP_qIUxvXW76mmb@9lyc}G}gvFIFYNBHH2JchvzCP?dhHW z;WgRz>9n`oZ~v%py!u+wj~0k;mU>LRdZ%vN=RdsWA-G;?A+I5|vMr)sS*$}sg?8h# zRly<tc~6ew*bDjXn`|u!A4kjQgb@ON5$(iUq+cp5I{}nk2W*DEDr=YN?BtJt$hp2y z<^=zWVDK3)PjdCY^8-=W{D$2yhb1N*64R=97C$T0i8+Iqer;8B0B_%=y46sr5*>#b zqq;QX%<iWus8FPyfpB|}x8%Z7AHY))bLvM%uL}^*`ReW;J%&6FdMhSMgD84OiE5P? zqdrcK+xt-=YL}D#_dS5S2c+5qaq5vfgC>+wf=RIJ_j^FnwJ*79+t>g@mtE7b=dx$e zOaAUwS<hPp;6+5;i?JSA2TGd7cCRvcw_)YJ928<f$vW}e_HPBs7$GK(fN@tYHTQ#n za7xumVsx+E<9;A=Kv8tyW*K}NJ0R;f0J7-U5U)@-Mi6@jR8;yEBl=98DtD2HZUWpW zpbkSfs2I@?#0*-L4Ec2pJ*q8NFziT8r6mmC&;MJYP1CEAN-KwjY(-R(%NoH9x8xkC z75)3=&MLc(;fmzPWukB3#zvKwh42+5JmA^uM`J_(hu1tGE#n@mP#vps8moyMt1B66 z=o)KW9D9B~)|{?Q0yKRQMSQ{{j2huTFyokoK~T%!rujG~f~F$?@vUcEGQyZjZ>VK) z;y4LTj2;3;H_Ath2Qa;k8J+-v9~U+t@;mR%1N!K4BbOVCmv`=M1;K3oj=;1=DNyv^ zy6&BX*L~s!{1%_&>4&8`-g~h?2O>?2#Z5-*O@hJ06u{~SZ19D2gtscD*rAfJM+-zY zC4L`aVS?drOkOI-I0P7H{&qcf28bl2zV3(d020J2HSSA&j|~5bod}DpBt^s8$QZ<f z=JX5PY?|H#W^q{Itd|Roh~=(4Y<`SurujP|F@v4S{!Bd_O*pEcYQ~0>@dZaR(90qy zIfynay0V!7&FqM2@U6VewZ1N+a%n06p=K2gX}}Eh0nU{l0kmE`^n~cj87xhnISjZ* zkQ@8#C4uM|_$;sT5o`gw_w7?2aY~tH-Xy#-@j+b`;8T*yM+1q<z^1y;fAdp|UrPUd zDf@OeubGCJT6xPg66}_(;6P8_qkrU-Td7h>?upyS7K9qkC!J?mPtKKp``Z2QYY)$2 zpW5Pp^WxBh#gQkAQ|Zu>2bI(Fi!x{TdxJWDpH<9uQWAbvtTpCD2T_8_!3`LiLNE~O z_l|jn_}SvkH>gFqQ7=rR;e*P_<FR2_(qG2!+^{eJ3>T4|8TLi^@wYMO7?sI+%)%_N z=W`eW)*(?@JoZ&$p`J4POByGvhJ(oZki=d};_N1IFOhh8JJ{zL;1}Y59<Y6Uf(l%e z%p8T$E-|olGalz7F7PXKVB(*cC5@O>2nw#^!uKI)1=w6jY4L%lyrB~TFnUZ!Yw@i$ z71n@-QFGFdBM}X*a3h)}=a{@qPKJIVhFuB7RRo|5@H`iZ2u8vvXVzPb7&=@>*)3KS zx|yo*wG<?3O)TOgVU^sm26h8oT8!rZ5IKig(%pP+Jb(?dIeoYv9NZhxV2;=$&_iYx z_awHcg5eb9w1&?S+BBc3v-5l&5~zA%P)C-f&Ad?|`0g-OFupV3%XYFW<o6gYynKYh zVuPYLV(>qWWl(=|+X8|<>n6DEqJ5FEST=~321uPNvdsdda;yJdKzg{2oi#YSd{WW} zW+IlOx9Ax*Da&c4G7+i{3sUgv^JdmvJxa(-Tr`pX2n#DVgaMu)K4yR@_gB)wD9QMr zAQT+1^pxJ>7YMjZaf@M>Zp|_VK)FwAw6Fq~hBBHUnD_wrXvp5)_ho!-!Otl|;3pb4 z5HN@q0_WSh0XMKmECBLS{25kVx2UA2DaqwDdreRoGsJY*+A?Cw8BT9*PiilH?VO!I z+pxjbxy}gu3M5YRP;Y8#FoY1nY<_!i3sS(=w_7(6B2N(?g(wX*5D8Pvh+7Q$d*6Zh z`P@K%ACvC|?;bY?(aK_(;-Vq^fgBG_XfGWBa@p?>h$GZYTsnZh2a8xQLu5s-rb{;U znfEs8(WRRr`pgk6Sj6lFQ~2p05Q$0w-mtKD2rl2F215Jo=&@T5N%Py>no9^EY!^@O z-rTsmNfk{1x$hASj98nakK$cHV@n7hGNpGEEn~)~mTwIAx_=fh(0`=L6HtR0shm7$ zVwlC!?c?dPr4S3|@N+DDo@|C_!R&&wYxj}Ai<fBmAFf?QKiw*2jaH@>Z3c@X=njx; zKn&e%=O4;_xTr6bc@hTLm+HCXHK&;ce5SAWCO~=ABYn)cij$6!@G3S}D$N)=2KZa{ z|73rG1E@wD46i0mkXBc#@K)7CArQ%MZnFmykCBCb%C-HlZeF32HpNvqU7-~&hZ_1& zbF=Jy_-aWaH<c8&H52^iH22hus1daY(#}%};_ht&$1S{^C;YGvJnisx<U($az0_YF zELQm0V9}QVUVN)~i`V@vaC7F__g|jxVve|H$GNa#z2P3iraGHur5bM_za^@;k+OYJ z`I?_sf5_a8o~0n0;YyBgx(xx8Nxe)yugcziP0UDB{UU#eTelm2@HgK~W#A(NRjRX+ zO07~bc_roM(%+M?1D&5A<7|HktdO2l4He&DtyLS})#-k#f2w*8__LPFeWU3svyt)3 zaPhY=-UK;*pSA;D0h$&7?b*hgx>!H+rtdNW$;Dvjesifn(MOrxF;!zJ>NmSnYTJ{p z$oX-1QHsJ*?6qfNfHRp~QEYuxj$SE?R{UPCFSqDSce(1ss6<j3bt~`KfJH#rEvLU5 z`bq7Y`r{w{#AS@74RGo2`jVMN^ph#M3`}Cj#B<xEzcbg5^)qU1qh(RIUz*TOhK5Yb z%?P|SCe(2a3r}S;Uz^ZY$>2ZK)O^C#Fs&ywD0j_7alP%DnFfXY-2SGcq1Cl<S}5S^ F{{YcGd5r)7 literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_cov_GMR01.gif b/images/demo_Riemannian_cov_GMR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..c0922128206d0d07df0b92360a5a127d361372e9 GIT binary patch literal 297109 zcmWhybyO4H7awav7%A;Qx*Xjw7|2K|aZ-*H5D<_Kfo+V&ks>7`C848Jr5hYdN{EDj zB4UE5?DzeB&VA?obKiUCyn8?AbKkorrk6D|-DZFr495UP03E<K#=*|U&aueD^_`dZ zOo)${kDp&ifR{&*pI4AyP*6ZnNC+v^df|eUnuxNcs3P{Fs<oI&wAgz|aWN?gDR~K# z2nmxYNz*7Pvlwa9C~31uY4b2?^LXhoIa!Nv*(=eq*0Boi<qGc<FMU-~G!Ia|)u?>y znX*4s<xEXAq(`G&OXEyiOWRP(t4xcuuKiC}$BC#rrmv^hq?h?w@4JD%Q<DCgq5hd6 zI<y!akG@=yV&XJnQe9(dK4N)hZROx*HDhxn+3w1ropp1U^;<ieTHC7~IG30GH+)*~ z4{zYt-Q5R<+^0M}9GyMfHa)-G^gZ+Uo1DJo;qTuN7)YDF?Us5w@Jn!*U&z#S$eYlR zUtxEW&q7lhLeC;1Y7(O&qGG0EW6t7YV-w@*JK}!E$Njk*_b=h@RD5CrF>z&$aF#?Q zd?J%m$$gFFqm<N%v~<_{^ama3XIYtfSy>sG6bdEhUUyD*L0;~Iy!`xpv)udnN%srx z-!E^t-@SByz34xb6ql4Vw3o(_N{gSAmsXXREkCL}t0=Fos;H^1sjq(FQ@vmFq_+M^ z-;*bkb#+!x>gz1(sjH0*Pa9WOTAEtg<~!Ryer&IdZhzk0+1Amyw$}Y(sYgezr>m#e z(yI6Q!E>kHmxcL#FZu@Zdj_Tl2J!g8{=vb)v*FUB;o+W<>K7wJBcp3;W1~064h|;X zOiqnfP5VvGjE=vWT&8vR(q@8bw1L-$+i%>X=3?H=y<V6*o1br)U&v}+piM6>Eic*F zEyvznu5En#xMroPb7kdhWwU#AWp#aZ{oUHTckA!oeO}-A{Q3RM{>`(q?Hg{}?{{{# zAMa9kc9-7oZTIi(?d^Y@_%!k1;OywLx6k3{gD;;CkIv4%1qOZlcJ}>f_1E#q>A&B9 z{+<0j{qy(q?C-z-<E*CkZ20VKeDdtwyR&aU&Q8wGPU&ZVPS5`DcXsxd{(t*-eD?3} z*?-PwAL)rC`py~s>lyve8U5cs`ak-A5TP?$8Qa@o46Kcn6i^@r001EJ8w~OMZ<hOS z0RB%C0GtlcwoJ7F4kZ(z=Y*Zds3I5yzn)a+9_kSkfl$0$A{Bgb_#P6ICTQARIi4$J zSLZz5Ts3)L%6ti+<g@-V>g?>__tBP`R}axdCLy!d+S$k0Tp5>%)+cXjtRI_|zMX>_ zox|xHO{KNfFS58k7iKYUZ*X|(^vYYen8AO!!>w&1X)^3^rOWS2byE8ML-LF0&(Lb8 zh))~6p7cXq3tsB-@NI5piBBhr?vrH32wKp4;yL5(!=Je(-L3m?YVGP>r@PxeEmA!u z%Pf1^Kd*G&`LrHaya8dpt(XU4<{^IF8q4mmysP6MvOA%S{KB+A2;LA>^H~gh)Dy9_ zqV7qD-TkNW>qwwM`PI|7Ug(Ft4rTQj*VyQD>(7%To~`$iPgi#$R_`AFj981`<BN2T z`|C!z5yLn$x)FCY+|eJ)YXNt@yT;z>7P6Z(`aWT$>)LwavRhbL+H@jdNbFw*kyWdA z-e)UQ<3sIMmd>v|4_}-cVgSP7jIIQ8z<tZXYl_P*cfPnut=+MiNqz`9pP>FOZ={V| zn2aY&e<<`U@cr<>r~1i<BLDXN55?~7`38(3C3jwB=zn;!TNe9kfA?X#8zm8<8Okwn zfqWKRdv5z2KZZjylz{*d#0TX=-@3Jx5c!<NrQq={`35Ee8|R74%fZ(B#{Aetzxu#_ zIum<I>w@2>#?B9QpPt^Hd4SQTm)~J4AL6-n&@?7dUle>2U^t`y>g>%Gq^YC&9xoNA zlp?4Yv?rE}bsv8eu|X)lkn6(Y{*<`>&%3`vzzku~*}HJ-%kz^D^|zlXiErJbM#{(@ z^?}d(qx=WFkPL{?a^)EfI>{CYBRcpQbgx<FU>Jo$-v>viZR3f8YRKz^Q5PJ7Fe-8< zU2Niu8S1i(Cq=FwhH^p>$Hbh<siPrck3POIIv?<37Tcj&bFOX4ZbsMIME>WT{k4Ff z^SGOhKNp-MKL1?AC(Hj@^1L7LYuQ~u(f}5k!^zg_Vnj2DI-i@}#LYoMj;;qs(1WMi zi6|z+^C2v+jaf%e6yY1Pw`EPvU%F$f@pzx7teHEW?Hg=oC1*Bi*fd$;bg%N=3g4Sw zm8?Je8#)e8Kg9_j3&8vLDpOxMYo+`~mQrRL*NH)|O~Iyp?ifbXP^W<ly>z$X3+#fT zCg4X)G*ij`2zLW8X*WXm%OfKSNKO-R#hN4jgnb~Qs^iPqpQGIChAge%7|BfP?z8`R zKIvUH;Bf@i@b62M6Os&(YXOuBtEZR-u|+d|VtvPd(#tV71)T9H8$FUpR6suiz3eX= zRdX<44K=yyP<y>&b98{GJ1F!{nt?p+YwOwa5m{sPLWl)fw=1k%pD5}Krc*-`IeZS> zY2WdT6i>rUk=ux*w7v`5)ZX2IDX1s@^>-}<(LnPGP?G|B)Ow8|k+hK!6Z4vRaco5G zqYPO&*0C=HJF4|I8>j7=bIzGMB=#UV#xrGXRf7Vu4ISXljYM;dQHMV2uyH><8RRPO z=-64t=QL_mfYHe0Px+T%xqBpu5PagU%}1Be?)CFmwnrSgzvX*Q0AQXzYzd6a0i9D- z3K8RzuBYGb_pwN%=-~&RB5Od!EQx7qTtsg&@;0U}XT~2-L<BW~L<+g!hA4A^&`)_H z<<&|(zb#X(CrDc9iRurwk+|;frAI@3e?K0#&aZtfJDIwf)jmh(0V&n!e+;%o->E@~ z@tKzIt)e@vq)H>QVWtO0ud6jkGm(xzDsGkBkUwO&$M^oqL*%(9Saztm_thtw1F5fR zOFLIAz0f)zrSr|#L<Mu7%2XL}%$dvP_k5CqKSrPP+fzwOWTSn#@KbOBdw;^dn*RqD zky&S7V>VyM&jqq>t8?g>n134mvmSr09ye;X&|LJh!N;=Rv1WpyTIA{z%glP`ucp)8 zZ+||GoUV60o>+Ww`tw=BxduGUd})CH7d6GQ!TtOsZZK!F@mEQ`r{v^ICfu*)!s!NY z^~vR#=wB`6=Nf%X%-_B)`qf%%+30s|^6f(RLaV&bu#>d;%3J!282}?HAuwWcW&QM5 zN8h=pLCNN;oBYR}W0p@t?oY0M&^qp-Wj+nfECxV^!rR-YpN8kRB^*W{_iUVd7CCCZ z{;lY^chB-!^y1|DukPdLN14xJcg^3OwjXz^u0Fkc{7DjWa{Lm&N=<-SYybsL`ruYn z!uhEUsP;)eB8y6rw0O_t6xqK%e98Iu<a^dndjm+;rW6y4O^)J|At|dSg0h^GThz%g z>chE&&*oeFZ|*ZN^)+SPneq_47cr`R7JQEzxs6OeKc=G)l5<bT^Mdm7*!%gf46Nk| zpwMf>xEZDFo*0+&qbHO2g6VvEPXaja_Y@<xrD#6GTjg04eLCQ-a>=yCuF|CDbnuHi zrTYyxb-rlMc=1pp=zqP@-+$A{?aIZBjeD1syJ`1+wLJWuv4_>?r!gOWDQuhCXKvx` zabs<(wRyY`7EAylu&Q9e@{bNZMe}v!wt5fUPuC}-=i35*Hr|Q*<nrlsv2`TuX|m;k zyTG5NF{}3G`?~%xjXuEo=hjx;X|LrE5pzpCKg-!R5@3;k7}!(#I!6C}4!ZBOx~+HI zDMAUn6SK0me^<SGOa6A)sKELOPekYO^zG<Bf8GJuI{RQ&M+5=q^;gg@t>@41M}8X3 z%ULJsFJt^7FZ|u)ebw1-C(m%ccVkQD<Yd$U^(Etz)7Ca!Pjlkkxj@4Gzw7eH$90b^ zU7-z&AJm|iX6~@wfcl(V=x6DsC0qTd5cs#(S*Zb;n*LGn@bA9WJ*~MKg`ahH|2{gr z(pnfS{Rl5lfL?(0jCpMQh$F5XI4yR+eKYf`t>^jYApJje)2lAUw~83LU8oF9z5DP> z$S<+4R0{Ot0#XHD401*EO<tQh8M#riCUm}Q`v&?KZ0K~QF1+`H`m5jYskI*9(w}$d z(1}d;$9-#!fGo(l$d|Hx%{BMhtDPRY58OUE>U{U~_4!x7*Z-7lDIj{beG!D9`vCZy zoI%~a3!w1t>&LWvcPI2;?eL(G4BX{?Tn9)%59iVcmLMZKGlJp)Jy`-2sJ`5oet8O^ z-Z(l`ryn!{NQa|0{>5K;dA$7c6tSXr45*D+9}akZEunZZObQj{aSRZ*X0F6D7NH;r zYhZdgV*v`vb2EW|FQ)8%Q2cq82{Z!`0L4?|fQV@DuLwyj<5mqoQVMXWP6!Ah#Ox9z zmt3Gn1XUj*3hSwfy?geP0Hk;T@dT+cqV8V&Jk*b2iIm$GBfy(<em9DZ7CaysqC#U} zsb#e1WnewhV8t7Wmq)&mO!AHl67uoZyv$s%0lruWwW2ZMQPAqe__JXEkOmAuLHkg5 zxi-Ld05F^i046|c(FE=UKs;{>JmGEveGklS9f9sk>6!=n(tv9>0rDtF9*z`(O`cax zO@tE(H{HT&+^h=Ia@t~o7t?MZr#<CO?~6!sGYMy>vfM?&9F71tmY~Xy7$+jasTvtg z*o+b0bYGk|*9IJS#0UjIgLqluknk`x1MSxhmW2QI&m>S-wyrS*&|u*kV9gXr8!EF9 z$KZ?13e<q~BjBmluv85Q0SQk;XGM*%*wNzPXr_ndFv13yqygzo$TH@Ihg0A<00|kM zwh$gu$D1u;9L#M^z8RTa2xD-qNw{zx^nL-7L`k>X0JtQ;3TTi#L<VnHj@?OAr3oV% zkn90Sjz$9Dct&}8N@mg$OpP%Yh-UDxh81tXCE?JpAi_K(FM!IJhXhz5;Ig=Qjs3hd zS{$$(hC`8{eFPu?oRt7D#^s_40XPZ_PXVwjQx22UIF<`IH50hUb3(cTukyw+6(%`% z_zB+u+yjBpfQ&Tt`vk_Iacp#fHG>tJ(E|mQ7z1c%rf6wGbe;g5`SLvQjH%XnCJ%gH z`M^BTj92%;1QaRDI$n<vd^I&Wj(RV0H`j^+$4fu>wR^*^9OjG9tnx{_^_vp7T>N_| zjX0ju5_!L!R~<ovM4@wB5aa~k?0)I{<AnegDx*A_0pG_Q1kdL>Dy&LLwgcp6Edv?p z=u#_bxTa5@epiH@bkPoDz@{X?c^~{l8W2axXQJl+OfG8TgF}(=%VPjv6x8=gvEFF$ zi>UH2qwJaAC9jhcT2F$9&ocxZ{dadT4><U4`G1Un%8ix_^Oth<<)f|Hf(lu((2RIA zL(TDxy=$-nG~)#7uGI!S3&Bjr=W^p=m(o(dU4Q&wA3U`IF9<4zBOewZ;e^8fauxRH zBqFWvF@cuCy-{J;m6wNy6QtZ($4T(FRewPx!hU4RZtzfQ;Fvmjb0qeFr`oM3<B17F z+7fVi5hxD;`%3u0tr@}`OW_nis96oMuqKqL=I&{Y)o(^CK&p3jW&*vAT%ekAH?5#* z_b!16>~*;Yjk*hRbh|cE;ClMx^t%fS;=aF3(x7Hk<bFWCL`K2+LWoJ2#I-PfSbfuJ zXka%WF0EeeNj<Qf3=EHxOaW{s*W;IKG|2@cW({gl6!kri0lx+#Xrs>)Z}^6X+1vWw zxAhkno<N!E)<0@l<LYcu5(Iw(+220eYA^pRQQyWN*7EV`7p>dQyMWN$yAQmdt?$Hv z$j{cgd=E`LoxGn}EkplldLL_fbVWU@N_pmVIl^qLkpjtnr`0rGQGPmdo42@$zo$uX zrAhct6Y@{fP08kglyD*KW|87%nVx33^d_m|rf(mTRPGmF_x28_j|Iu{1h7dqajmor zRfHCd`WtGu8acHZINjpA-fGs<YO&JVt(Fp(++tgdM>s|5#k36@dczX#kiu`0t8d<5 z_RW*H>85?tqsJ$ed^5ZnFdr5T4FcRY_hN|g4K;5MEpAWqZjZR->(kTW^~YOfG{{D~ z4erpUlirq6FIiMg4Xe4M0lWKGrta%vr_Ha<?BZwlZgtssKchHxg>~G~9gY78>#CgW zs&?wGjp?o{?r!Mme!9|4{nOo?eka|$vt1x^VZJf7rzb|qW9+n{PoQ@|yLZT`cO<5F zthjfgr*~?lcjiwoP2l<HCu)b&bLm3gvWcFzpDw1y_&tH%+Mxe=zA5Y9!1H2T`^AUi z7kfP~c2{0}TzN6@;l+V~|M0ID&EYSHykGuUxz(%o@<jW^S7!eY0x$nt#dz~MToCW% z*S50Kr(qb32)eu+dU-{qpU1hM+oGR8wqGElU+8bYpx}V8+yF9zovT4cYKnpL@qkoD zzl23UFZ-a9|A0blzrw))hsdBf%b-q)r6S9q*1@3K>Y%=Vzh1+jip7w6?2w2xkS)PU z=lrnkfh*+H0i7I*D;aj|9d=$FcFK)JQU=_0Mm(KIykkdvN=E!FMlRrifw4e|AYhQ( zXvhIj2yJnzVPvRvR4`#QO6Nb4jK;H!#W{}=r$&<G#^mS?18kIfmEykkp1$NyeR&xI z2o}!5l5x>TG8d3ym(U<QY~rEd1YQzY;y>mcizu1ms67~MIGCun;E3x*q-G36I&-u) z$i%-N%KGcl#yn2wDRy=oAMzi+IT9dJK0eVq)p{_#BNJ7vqu9|fQRhE-(PpwEV>)3K zQ6o6EmNC)wm;J5tq?aJaR_w&)`yp%pXAvebi?VeQqccX~Ezn<M1n*Zw$tlyTQ-5Ox z*1WvOrlx?6<1>G!E|mkTbtYr}GVF>8OZ=coA55n;&{)}LIV`8$E!bBwrsw@<xl3oy z>&|jN8bAPsVF`o>3;A}|jVDtNdcp{5_lZiMi5U9Hj9j;uXF+jA2bEE~6I}HCpWs~6 z*H_Fz08ZW!Q0bh!n>6&__$4IpwZ-K5i!iAM_0kQUU8C7m!ATi|*@a$?jj4HQ_65g( z4Ern$m7Rd}4Y+7wEe??14e736f)*g}CQ=!>Dan;ccx3{ldmdVekJeI;{{0pj<?^ii z>QX8^Kyi9$UA0B$+VGV-!>-QD1#!!TrOWP^Ifll$vPKSzwYe*eXeO8cUSKSxv{6Y6 z)PVvj>a%42x7;jG%V23^E@xSn0(j7%-=5S2)%9tr<)SyhVN{kye4G`MwcnaGu@A8F zo2_suKE4LPWxe)b1W>sF4sncFX!KpCKVLIiSc~6Xoqt|2*A76-&wZTcFZm1@*I79V zn1TG8f<K?A;{e6vz7<3oy9CANqtU4c9OR6-ue!7r=anw*3XgI)9FS?%ckba4qaA+T zNUDf*lAA|?rXe4CSX06Q&;Sbbo~ifTIjEslJ`0VhHGwIBmXd19XcrX6RK8gol=s$z z5tS7okA&wPG0H1+?3S*7(%r5J9*5lBW>tJAczr@PV^o}~RMf{H)}c;TW(2cuC^YF< z3a(&ZOu?<9vyczvH#XACYc}r}MB)mf3ZG;lANX3s4skG?H7p7Rxx)0o2oC;fTC=EL zN~w*0n*y;rV*J?wC<de!(&6A@6l59~AJDfF(%op@`O3(3zdAc|Ja(+;#ePZFNGS`j z!sVUp>L@ZuDc%~vGo)UG0F^3?yk%#g2C;B*jx@S{YF8NPEpd9Y46I<xY+J6s_%zp# z6<QBqX++o5ClroTU@$z~7r(c4EiFz9Qi-nA{8ebG2`$DmzDC`Bzg%xM&Qd^Se3+0b zkAUl?zT%J=FIYdUO5Ar5{_^PGRMpf#>tD3j&^vYni0*P3mB>E#n6aO#=PdjMW$@bi zpfLI^EDZ&<>Wc&Rm3l7Z$5B$=EGNrb!&o-J{noj7be5Erw~{U-08qnXeR%1l2$}$J zTaVjjEcn(Hfu>VZG$vqy*jJq1ori~qm+yYkqkrFN*xq59@6ypI+F%N?))O|;AOco8 ztU{>x(q`5l_VHsED4&?o3{qdf^uCoQ6vP7wFDxwfk$xcN18cR8_qufM1LNJDtX(ZD z0v-XM723S;Fqr^=;`*5VZXX9m9!9@|>1aVOGeWho0bRHBwci~c1s<6w{9sC<F%6A| z0yQ-8h91_+fU<Gxd#Sz@=0xYCta}_{rS&W*Na_+Wobn{x8Wu()sHE4k(N8JZyG18o z7b8yzami6jr_XLQE_Gztl{>90ou(E7xG2zQ)Zd~M%H{(=+wb>!)uhx{ed(9xGWAc7 zbiY99LerZ~h;_wFLqFtQKXZuPXNr>lug>`iRychdKmAdzlvL=g+1YSu>9wI$!{WID zU&|Cg6Fw100J6i;QVEF!2qT9KJ_sQKB(Sm@=A|Ss5J^B51eniu8=E5nk@1=Rc%v)k zoAV12pWO$GBGrKPp$B%mR%N<zXJCH&J?jeNcqXn$zyPe;vQ#gL|LRBkx~q+@{}LF6 z($A~(zTRV6_{7Z4qoJ`wDZr$#`OUWv%gld<A=vR(v4tbo9lL`6on=lk7^T9X6eV7G zFmf|joUhE^BIx26B*m1e)j7yxbFf6+oQ%C5;yzks?qSu{TxGM+=<<>*<n+t`Z5!Q1 z)Fr5o!KveU933j`d=j)dyjvEQ?Mz~3pMG$uW48Y!^keMj&FPqiq2-Tj&m$!LHJW|D z?My#3dH6!dFJCU;W%7j^XR)V06E_|BMZxg@KBVa|6q*4hMn!|zz=@!iDVcr(v||eo zLj1r`2bg}QZ}1*)3=D8X<iUzY?AmY<oys|kqA~Y1m3zAL2Smlod^anbE*Bkn^fAC> zXxXDeG2m||B5`6$W1`6_N~U7>b(&4Z({*geBx^i#%p_xU$_scn+yN;(gs$o&nbF>6 z3)xrB%_dM*WTvtDJJNTZ^J^_lR@z^Nl&_QpaY`|O{~95!4PfG}))+Qp6}pY_d9PL* zlM4YVi4br~5|E(;flrIZHj%hcU;vk`jY+^9RpW}W>eXBs^Gqw<8%e4T*LSyClt%o9 zRj;{3?6h6G5f4$rxy9|I6!56<?UtKy^0!~V`7lY%(YGe4AkpE=?_J@5j-7U=+b<#N z&cUPN9nN=N8LPX5EqZmhM7&E<cMXfU+U6Sb<!bgtd)kx7_q4!!7ZD6n108rG+vO7_ zhZUy)hvW-njm@$VflF@bm&mynUAfrH33x7`H-nv`M3-l-rS|OGTW1C}ZmBoOnjfxT zsqXUr$<a3lU{LGNyMJY+RnzCu=YR&F+%J(DuLt+NyM6ij9<%H{su{u20V!Yrfe&B# zz%U{02~_)l2j<v7&^c2yajIGL?)kjzh}%<i<Gx#P=xt6|IP5Vwop09XX4pc`)Qa~8 z4YHZU;!<RSDtKDw!?i=kCBHCcFiCZ)22ZQ+mN=&O9_ob7nn(&MLuCNK!l<dQyAR|4 z`u+=Bx>@r)eC772Zp2!|?(>Lu@i4u}_sNnkBDe0D=>2}zV>+11qfnCo+^e})7QJ6T zdKUe;aaZrpVaF@s*sm`o-^F|%)qffLqvK^S;aC4P{j(ptH*TDr?sw?N|2=;BGXCGQ zXK3aG6a;_bAq)#;+?MJ<LlurLeBZb%%aWL^V~t`v-;0E(;tW{bQFNl<YB@xg*ANkX zL=;nb&uCsaz!6AE661Qr=yo!|6COlT4HaPy>%<8Eq9yBt-4RI|Mxs1l$(Q{_gn><| zeyxGR&=M1%%K}=)A=`Hko&2e_(^w&VHvI<JgLhctvQoip#!Vv+{`t<!YVEU`w@Ds? zlbu>o^RrnILmt9EJ5BU{&E9(-VyZJ?!)n0#nv!hfDazf2y{z^+`yR<tOkC5{%;9y; z{UJ{Y)h<)3aE|OGu}W@ZO*7kq*LgKYUNTp^%pBTZ=RYHP$$4p-J1)E~=os=+2<tL; z{q_3(ORzU8Nz=l8<lx?@k+)KQmxZ_5n+LB*-YQj^mVORzoQCN`-fC@KmhIB7ir;~6 zY7A>yg%rFg*)_VUHQ!|w-u|Za3rX^@Q}asn!ke<=p__U?yIzf5fAf$I_CZ6mtO-1G z<uGHZ?vpNSvfA7uwj>`TaV?uPhq;RL!#<Z)yKS<V#2;ON_+pK<Y;y|cDkbBtnOyC* zEoh&sx|HN=;iY9)v@ln#KJ051MX)XVHCLk#@v~0Sn!CL}S8HPIXPe(`U#&L(<VupC zeU;YLI*0kXYr}pHZQXN`;q&!3Ah&SCS`N(x^9?tRZ)taQJGB4GslA<a%XvrZTKB?L zmw@40u0Ol4z4$f%EFR*Ihupddc~MCvR<Un$IoU_W-l9B{9i>}LF!aQaT@+67lIcLz z*F+9sS}qxwXtt&d2Xq;=%4Uy#QV<x6Y^W663|jN^%5iwRu+ZKyEPs6`+iCq*L1|CE ziD#Qn)>`1F*3HO(Pqsac@!&1aJRf6OBLTMf)?XKD%fZr8kKloSiQVlh{;t|FoCXu& z5?jN!M6?C27g{WYEq0PM!UgW#T>=Ty0Wk4C3e<oF*nUJc`J^TSw-@u^E2fhC=pw8p z6awEA1$v1?<lG$jd<`y-k?d>hYEX9EDyw)KX(zCPfGu|K<TFZP9@rUH@Jf{a-1H>& z<Tz*;vJ-rQZoOB`il+@QmH~#P;lXJ-lr7<3Copj}I>QZbsV#n0*KvK0CdNQ94Bt2f zs?62Yj98hUyaD~*K?`P8dbrhcjE3n@ceDzEZcVxPFSpOU*9t~q1ecV)w>O`#d5b;n zp^vq+|BB7j2NgM8Sa8?el-nzC3!X|3|E`G?`rw<>m7a6?d&%#NjXg(TyZ0Fk#goW{ za>4LF#2M+2ePwgk5aEB9@KdegJ@{(pA?L%+%SytlHv`28JkwQ1Pa_&xe1`_u<vtZ8 zU94L-sOFu`&xG-?`M3njVfa6sz!E_FTE682Bee;i{ft*KuV?`K^RVQI4j~qEoZ)zy zHM!g6+dck^8te}f<YSCu&YA6rus0?IBt0zkp)WICOPBZ+lp1jzyD<<r4E+MVL>0{N zqArK^mxIN9`k7t9kGT`esXEYuZ9S(40<?dy3nYe5xBZDbHAf`n*4T4iC=Wi%r(L8! ziD@ud4?g|d-&EDU-ufl8Qbw#)7`WlTChxd#p*l=RUCk;z)P!$j(HeXq6qzdRKOmer z?XIb`o`%<m7+B|SR5_)kc{yWlk&%$M`=8-*#r(W!){GhYZmD=rO}@%L5Q-+@XwHIQ z!2t-Ig4tgdB#0aZeNUfVBfniZ-Qw@1-Z>cg#74Z8{hi5VNA&*F;ct38ZO=gD9{DCl z`&dKvbh?Q;R}-UaVfXH0XH3rhUKZI!dhdsRnvtT;Y)C=RUxC3RqY+}_cQ2{I-?;Dy z*-AJ3?zM+}y*N_ueWuf@n=LKxo{b|tj(-;-PY3Te9{N5@WWs|%+%F4`^`E*i8n2#q zrQ()-z4~FMtD8K}A|Y~P;1H~Qs5RJ@LYDI&-@-x7%c=1jP~BQx*%q~i^q%+)hzY*W za|7+$Nj5$KFN#18H+3KOknsrc$qE>W1?lw>_4bHrK|r~nl6Y&VF#yVHLB=B?m~v8J zijw1!f_+fOK{T4zi8}cSx*Z}kquj{8B6{Ab`wQk0?!BIYW6LFum$kPbi{@Z+EJ^y4 zLOcL!Qch}ARAqD4H$kY<9fNv4{^{~WXz2!Fc0t`RW@sQ1e1#Xfby2UNxb5a%3+zwV z!;9?>0OG#vkZ~TyyjJ6|Sn{Zz(Hf}h?bLK$7UoZEsEA=Sd|Tlyt1tEADMGf=sAuTD zbrVl9qnwghXswY9$w)@*5^j}hFJ}DakCBzmOYym(uUZO@8+lGEVDALE#p_Uki%G|W z3Yd-N_!APBJ%+6^No#`~)t8Lk)2Dxbd95?aVgnQ#nT!TNi@s~F$Dl9(!$`ZKvRsS- zmK+Hu?Klm|4t6`FzzitRhb<VFEp<l(jAxsug&5PK5_Not(pah<wy&tC3+xXuK54tM z1iodC_T4a`BVy4a_Fyv{*c=5mIRSgu_OgE>i_48Cc(nX{ZKQ$GvacNAsUP5aJZ$QG z38(VxC-AX>qiOI)QpPQHagc^ukG8=Q$$_S7Xaq6vNy^9_+<((A#0C5B$Ry{X4|kds zHxxiUT`q6h!h901{TbZ6r74L^HfZfK6jO67oCs+!bH^lE)>4aoN-K*SH~iXbVp2iT zq9Lf{U~JKZUjsQx%d|4JAN;f;WxSBaa|e}thZhEz<awY{Ib@-4V_|W;Suqyf{gGpM zRtpvbm}ZkTwN!yc?j^^cn8Sadk)-xDE&2a4j*X@BV{|tgXR^3X=NJA?qg#9h*G&~T zD(P}X$*iA5&zrwYRJJNPsNfNpS_>75sZE}Luei7mJ=ugBdbEV#+Lj(e7VdOdo`79b z8kcgBdlisIktFHCg1|8i*Z;cPq)V;{aPU#`sB)WZi;`v@HHJd+|EnLcec5y)X_uq@ zLpsLS2V#2%-Dor^aZBBHtgT&4&A=LLKW4(14>iGp<c{tqwu1gM?LvY|(3N*RU9!b` z0*{scwkpAUppFRA6`I0v!&t1?fDt-r!EwT932V})Xm$ejLYsahJrjKnT?iGr!~2?- zXo@)%?fI+cJZ1X5#VQbI=(|B)$|f6G1CcZaAp}qyZYM%xKyH8>abT06SM)zWy1L(3 zt9$BU@-W7=AhS;E*6ruN%|VWxc7_MaHvy0<k*fMX25%#v*0toFi$jJ(N@hNw_J)ZM z9#C^iQ&D7hK3sh%k+C;pV2s5g{$zS1N7O!Jz|4POW?-_AYHAfazQi{?7|LkAA{x(| zEa%5K^Fy?z_|jr_@_tLpLI|UkJj{E~u$eRYO{KyoGxGdn2rx`2vM^b53)-g%kpzGY z(GWFlOBNLj=ETOa5Vn~1e76G3RQmiDLjKADxvJr12Bt61nd-Sj%4(qD@s@8mVI8+1 zwkZ&{xr))b3iZEThO)+5%Bpgh*RS4)2G@4U*+IpA4ncCs-fdtyW!r9+>6+dhu;CIB zdxX0;4RVZ3J~q2zj+y|oKpm-yOMZ~txL0!K=)fSbc_$Q;V5d=OA_BIBdQQS}2d@G^ z^wkl1FT`{MWDwM2Y&<D%?D(<XOzsa!g{p~FHSz_J6;U+oPfcH{gAOm2jeAVbCsA($ zTDSAuYY&RD9&5<AlN$!1mWtMUnwj#h8Bjsyea&f}Xgto$oJI=7ll8Db*`ve()m1($ zL9MT2&V6ZeMFTczBDNzMe1tA`n!far4E7`+Z$b8n)P#C9(Mqs@osw;kF8DD>?!;ES z94G?^$(#@t!(2pAMK}!{tN)w*Tf}82TFp)eU8@{o?9*J654GI`*-~B<t*E-TfUh9P z`5s+3k1mWj^rp4_<vb{c27+eJUEXOfK7pCzNMAA;m!#Fr#?<3!JkOn}4!k7Cz5=tP z?hrWnt%veeua*-(Lo3hjomfS+Nu^UyWrH`ZLUKKLjfMQN3b}8|FYW%5K$O~+&hIUi zg&6a%+r10>re<h}D}X$E&TN(=*)jo}^~u>bfd=^l^9TaEr9khmkTJSRIQX^TJ&-xh z&hFE=e2<0>GU)~Jndb)N)WeeZGhU9<{h%4V;HjSZI0?7Z88YbR@0)B;P83E0#n3>} zy+j2h$P%s*h*mvi9z0d<sLR!--!9fQL6Oo_JG?aH!KxTzYw+m`cHvKpSLD+N5U6XU zJNOng9t*Xh60n6ynDwOVSWlZ2lHwTDG6<~Krprn~r4NBjsI=HtOnvJ$j1Nf8!|C#K zC<>=^xMn6f36`T>u7J>-`Ut)hvbN5ojw+_8c&AD{NhO7b4bbxitZR$A$`t~i{c}W! zV^IKLW!2kVb2|gvdXzoc2%xin%ltp#L<f=D(!GRYQ74rop1lOVNP=u9Pyu-}<Ss!{ z%9$BUP@#gQ*ENn-6~woCmR9k~V(*OruSd7=nqmtX0&DZ>klnYW2izp$Qx97o{gc<L zITm0c9|j>5fxb|+msSlFK>;r!2x^6nhItsrJ)$Lm{6o;yrk&I$V1W0w*T$KFNpnJ; z$<mRoR5|<m>12#NnRB(R4gzHg^K}iM`~`n0%&aE-!u00QiUSsm^lt&x!Gf^_4(v^V zTFBj6*n&YzyvE4v)n>fUG@o`C^iD?vm&TXqu`52y%3R4&DRQ5f$eG)Di=d9XNaedH zFgq*=HNS^a1qZ|BXPKbN{*WvX`S~4i^;t5@RjAQ_QlDA+9K>0u+IF*&8i>bq5U;a= z$wo(hPP{MnlG<VsWN92Ma*XKE=_32R&+|yt7fx#5(lxU}FL>*lC7>Qwjd3>6BJN(N zPphhWtbpzIfT9$F4C-*}DNt-LQ5XraOi(~7*rp2_m~AAn|0UsTwNGrJ_g27rA<vIO zl`dwYs%8|-%ae|tZr`sW=@tTQthX`b+eYh2*dT(f4>`87uW?Ap)d$oZU{jTku?G+t zm3K6@JJhi2Evx&VKD~PM?@Hk6Wm5_S^nAxP5JcJ9(fLPGl(K0oT|!ge043F25g$}e zXzqGn|M@YfZ?Ctq=$I5zi=7;KtCBX(wObx~A>|Krg23*%E1o{&t5k+yhuu4B-|jf< z^6ddGAi#keWSFul*&AxhOH{!U^~$>s3PS2tN&ond-p0K8lSiKVN7AE$=mwn~rt1c5 zm0-z}*AfUj5$fJT<{feB9T9ZEPMDG{6=YkU6n7PjFBo*_3vsN)<riQsaJAXGu6qWN zLlO4pdCd3YT&=AkZY%q(Ea22i&2okHPLF3RzKx$;_07=omT_9|UHUQ;8#g)RjSCsn z(7Sx_{t#;NLe6uDN?V5&)h0t1vjMrl2E~^@pWyGfI}#{z80gvw`*;fDU=3$mJ-qq1 zExQUVRPM7}1yoGZcLjv6Oe&rDK_dRb^xwVn-fH)V*=_z8EV)wX*#|nVeDSfx+YCvz zqpX|Kq1Go}b}y9R<|M5IDi1y4hA=U(yzgVo3kVlUaf8fZA4vy!ki++g2t060AyArj zA|n;3iYEvzF~ob%@(6uL7ZT73&x&Iv0zZ(^eL$Vs)up@t=>kbD$ouc1F6d^G^wH9Z z)%LN2=jAN0EDd&W*ab39QY=qGZ@jS{Y4#QKy>cU(75c%A8Rq}v3jFrY*%bKZ*eKJN z7F4e_HcZc#3f4UV=LhQ5?qH_|gV!-M_EG}pCGW%%f);=%ZM|ROr0q!Ch0l+sW^Owq z*l5d-Hb1i-U|UC{-A&JtrH>Lrt#-%sLqa6J1^-GExsfFK>Q$;GiMR2q<sQgvPkYta z-K_5ezhsiJhU?3%KIg|IJsimaK*mLm8PVEUS;%xn+*-iRHB_6Al9!8i4NwT5<czT~ zl>B?F{Ufdfr(K?OT(94k{O3yfAU}wlb*Sm9k!08D%R3W+yW?gp1-((a)2gCgG(Xzj zt7rGF(f;3!)ef~E0fh@Pt~I?-D}&;w+W*Qjc(6mPvowx2(iHJ?;$O?0nPao(M4=1D zSh`F<en(I|x7uR4*$W{baC-de#s$a4!Y0os`3Ds_bhYemiGb@vUR+hur$4@AXI-)< zbBNb%*(jN)iIbhH8y+_sRmP5_OMa1YAom^l6PAA58pV4ETlv2YaaX!h^P<VCr}6Vj zfYpMr=Wp(sR)>H{MNriFXBFs&I%me_zIGLK3eri5)7K21D{N6`pKaUK>?N&BLGlfb zdn{9gq{Y*A#@P3saXwf!9h$VQ@Qmv>WA+|pr(PlCXqHaPEw^2X5uN5Rj^+8b-4brh zA?{be={H4CJRGZ^mc*xH*X(tlpL^nvc2MUaagMFdvK5}(DtnHv;95@L?8~1McjJCP zP}01`rq(H%26%&Wdkz0)D(bohS(V7bDe>N}GsR4D1>m#ELSb{+Ze#(g?8^dH@BvFw zn&}%8*+yDU4#DTqeNlNb?psc39%+$DrqACUc1d_#&6M#9T(go5%=d%DhGC6LVpAJp zXE9oovmKRer4hFB^WcVN9zxl+$w+#wb81>zt%fM}-URqs@<o~ILU*}t2*_DhYp)z! z7PTpDWMjx{kW_YKkH&4aNP9g}D8p~dd7D%EakBWe_SZ1ffu?w-kUG>5Z_ZN3or${L zwzHtV0_V)+{H^iE)~-*pIaNH5cCuKNo=4<<iW~lZPqcT(cv8P(qD5BOC2=nM;_6=y zE8SlS9z+8ZiLY#0AO2z(!!Bq-1f{bIxiT8We}!j?7yNxQk+Hcs#G;<=A7a@V|26!a zbTM4S-sbmR5t2}*Zx22Izq)nhX{VAW?0TzA0W{)n_Tqh&>RMG9=K$l!1<K9rOCM9I z)8Y4{6oI)WRd-dr)+O?e+_Am%&p*Q~*<7%RMr^iAvCGrNiv3`AZ51;lk>JdjA)bbd zej-E$T&xx+;QWLy*}IxDi|66^r&M29d=*?A`@E?dGQzDsDO}}@DSi3c-&jIkaaxAI z3z(BLHY#b3F}u)fokN|R)W}U0`!*YK<1W#B0Df^ka!AItK%@D1HcgQTlfGO$r6`?O z-i+Pm{JLqx?~(9GWWRDHahTUP;k{9NxIl$#8Ue66nkmDSb66Eec~DVUd~nrCBLerR zGRKrBPwcDtOoFv4LBr5o?)D4cDkPy$GDTQ(Qz}lj&pM|gF^nSm<VWpL1zda$FkDj> z{Y^9P;peR<82Neh+Q=dO_OG{fdBC*asq+?4!8IJCT0s%3HvB!KoiWk9;*^Xs++p-6 z$<#^W7?My^ES!vzWZyh7=?|Spe6)ab_lqt)&2wuopB-?XG8|Q`Ml=$r{V?LjsK(jX z)P=9NIhzViT)DtJfvw{l{nkr%1Y&Z>KI!U25LAeSAjj^T!*M>)+q@p?_#Yy?bgEf@ zxcE6fV=I-2o=iLEk(?AN22qY6gQUY{tQ$-`1eEWII=)XK%S&k_MrO{cd5ap8Brkuu zZfQ<v0?nWp7>)Xty&@N|5<VkreA>*)14G)58t%lPi|0_)9aTJTW?nt%>|rJDW%z?f zw`Nj@7IRvd=}o%H{#6^$w>Z&Ew6(im`pM9Wp@fRyPXmfXGbWsaVM;DMjW1`6v;j?i zcnW3>T0CMKt$aOsm|(#lhK3YnT$i%t6}{Y?y{JkBK$+VTF#@j<!hHZJg2By5{9{UB zg^B9iN!7(-Yw&NMucI$E6m4I>u@U+ZnyD~_j55+H!`$B{iv7)vT_w&+oKjL;UG1Y= z`-;EIMcXJd8o~@I5C3f31m`(^6@S@8G;sUDc%=x&EuA>4c1gX<u)sU`mM2uZ1W^aK z&9G-T;&xFPd1>T%<nmFAPg%-_m5_8KLq{03SIDr|9h#Y4C{AfSv$+>t=n<(bm%`nb zjWMaDbKukVE(dikTbj(hf71E{bmMHZ3=e-FXD^q=o+X;;N1af3I)SGej#04E6^(JB z2nWc6F|cr3ZKWep>T*A;QBlhI=#$zvOr$g;oHU|IqbTa2ul>r=cR9`p10G&eu$a9F z^MfZq_7rN%WwS@j`Fr+3*vaQ(&D3+Nk0As&NYGg4)#Fs8xly+pWV5rmVA8<qPTKd9 z<}gse**5#iKvz@N4+C9!3)+sKmPG;wG`CN~S%p!3+6jF4U~w*$Wc{O8si=lETBp)A zYBm`Mmk;S<z$7V<l3)9dvHJEI3fS+0J*;4EsMnbB=s{-Ymy9L8pqoFmGFH){U@V=T z+cw+ExtHUlg1dTe@5fsjxvD=h8ixX3`nG6;$G^9d8s_A-;wPVs-(w;`vc4PsuI`eC zYed)DreT{>;@?9`JeZ7bYwcu&M!MIs#Uh=o!kQQqpIVnzn(~Qvq&{&7!_kAlj+NOd zfeA-4J&q**tguYWqfOzT2$&``WI;9*&v97Dcw@r9%pu6cK~RNVz7ILm<5=;$#2xD9 zG3z0|@#&eti$zuVt<hzv$4vzYldF6c!ugi`8ib}<hDGf43P-i6a#8Sq?Ux)6h@nO5 z7>XXsIT4~et&>ieMSs=K#vR~0GQ|i10R>4i8X-B@lnenwd3N8<$qGe7deXhIHh6aX zfNJLNbHWO52hO=?a$CU#7E2zNT(^zzcc5gAOmU{X6<_oeVFt?&fi>eJDpzWk@~($Z zvzX6ad%;?BCC<yuw>+wa8??J&1kejSQ@SXAV0kHs#YQA5Jf%PU1fd%YQ#Z-8Glm}Q zstUf>m($!6-_G2ZNaxA&02mBo4a;8Lq<|e8Dn?qdBqWc>D*xjOR`Qrfrb`3k1$yL_ zhfw=J8LLpa^>Z7)9}kNP4-{wNDt2Vtvv1@qeQwum)0&|rNmek_Riya|l%u$L7QPC| zcYoxJvbb~Gy8lDnArrUmN4QMh*WvowqDx3cw%Id=d(l%K2xa`>b-JV<hpW_1iDV3u zc&D4Dm@CL8;UQcYC}JdU_V_#wC(W(p!u4pCk$H`h!V{L0Vdg}bN&A=lJEIo0A!SEw z^1dh{<0NC7`q6$sBdPZHi^;EigxlVg!>E5VMjO_^a+!~*D#Gm<!W6fh>_-{Xa+sC} zp9@%wka9yDiFded+=-E-QWNg?k-jG`l}oT=C48pTLH|<Fx!@s=@G#5ZgG9Z#By1tM zl17NeF&*=9$?zJkwVEiw36ocg2A3deM+SrQqp`~-LoWQoPYNz>Urh|!xU1_p62STh zz#<JW5J+I)$#dRc>gPq{QkMEvPn?o0uON?TM%YZLs#Fytx~0jmVN~LvkV;;f>7z96 zahC1Oto$nieQCmTtj8&)A4M+nMCVBZ5?S#=lzmgmXGXI)$C^;LWCo&0Xc_cl{}0N@ z8@We98KxKZhG0OL)T&V9Fy#AMsicpCLa@a@K7t1~RGC7cR=(B8ZkTTy%Ze4~puqFJ zmbTW+T7NO>Q+?$w{Vb$G{S=V6CvsJapy3bf)OCFH!vINvbBsR_hTFWeC(8aPtog}U zw(9EB$vU4msPnf>{D^SYR-}@bF52rpph%RZ4oVFP31*uOC#0bg44&>7M$2z8g_I}q zjh(~}Fa=x4@*2vaEW0~-*eMJbEjhfg20Yl;Z7y^tPXxJ0Bda6(qEE?~L`I(I9^Wa& z$x{&%&}z%TGaBrCzc*}J_=GS$e8EKId~{UuVeObGm_mZj<x6D}s7z{71F=)dD%@GI zy}%1t=LaH|A<Nv&)`pdN>_J0J0L5%RHwKa=1M%}l^6Cbc|GToC=@SY#Ce%oF&H!Cy zp?}v9DRuq#k4GvxiBe^SY!>2Ic^DCu12SA|!8QaTPuh!q-VnEBQ5MdOuY_{@wX(mA z^Hq;HcoPxM1QX}M%aA!qF3!<d!^#xKb(IQz-79jvGv*pBjtK+O2~36JAD%=46+81F zLJkI^vr6Sa-f^O-bG2!#=p~J-K_^3+h4dj^u(^y9SxEzknZmF(8E}+b<(NWi&kgDi z5gsd&6;j7Fcnwcxz5ffH;l6~21y)EyB0$SnS#E&u*QPa?M+p3WJzJueGNfOE@o|@E z`wO~svQ|4=tuh3Bz0WUUI;b3a9W?(|J;6)`eIxv14*IJhvXu~Y__pldti?|C9VPA` z)`q)HW~%lBtkesyXbz{A#WQmk`F;Sjx0lyg3V)Qa$*_1&*%+qun>K*m^kyFVlbN?g zJQoGa<-D%RtBzWB^1ucd2WU4%AHhSoa|7$f^@mN7=W0~&7zxyX?ASF^{+ai<LHE6C z4T+T7FD!@}1HQjMRH%A%Hb|+%=|IF>qE&aU_Pznz<s~jLeqZ-ANS$jKC0)p9PqQMk zDAuq$m@Oi3V21H+>NJ36Y@b8L$p-BZ%1og`PMn+liE|8RPgW#a6C7m>Za|jJ9_6uW z02hY`gstvLPzu9^;Uyc1W*J3AaHzas-ECHcs>4>T4ni$@K*=5xT{m8z@!?+kkYsGN zseQhF3UQW&a>b~kj$xx}YD}Lps4)l9!1Z6(HQ?x#&~!F`9JnnmER>2bQQ=*WM1x_C zHvF|DtKXBMtBfJ6NvvaDoTUOaVuQS5gPTb-=|Hz4-7+DcZRHmk3ac)Sst+YMiewuq zqfqms++(>{SvliKZ;^BsNzM6I8H~b-!L+jg`|4DH@yLv`6I*Pe@`04HRIc$bS>`u; zX8%}1(#n=mEqGIWXpTUZKrYE8-%;5Xt|fvDh0&>|31E=`&zXFHpaRbXdgSsN1*VjO zG+iGZTuzQXVo*ylLIFn-D;rWR%>4V@V+662ktQgOM4h(8{a!nwWj`+|Wx~`7wQ(<v z!UGu*tk~eXFkMLlujXhH41|gHu8Bp}OI(iqVy)6;Z=Z<QI%F>U{tVhD+#RTH6M1+x z&hK5y-U>i2t*TNjQsVN2HOf-U2X0EI!J<uU3)v>BZEC2*i`H9_3J+BYX>Nu_huloB z8!vJw5`Asy-0xL~5<(>;y7|;MK5VUJHjl}aTN2oU3|g_`dOrpw(=b2JRhNCH>91mB zgIJAF!|mb&y1eiO#GIWGm|Yz6&n4G3&PXYUD1N{kLQdq+=ofe96y+;;l+dr5q43mx zSRa{T+0LZ?!=PEvW*}g)Ad0ZPAT%6FkQdwwx;qrQ*I#Y@z&#X<I^yUon*zK~OkgPF zRK&0y++rK@IDKE>X>H5;x8TC&Ge3ynCAi^ap-EKL<Il7?(h@@^Ltqh_<x;C{@Adm3 zW5tGsm7F`nox_CD6K1+K@ZyX}rZel;;feQpTQLAu)130miDWSvkjYk1Moe~N-{|$x zK|7X?xt#BD;U@zkBa8JAFR)k1DFuOvl*I?vC|A#hh*YIjPBj2VANdpPo??yggNir? z?kxGM1${yQVsSLrZz#O$x#@);{hg}sedGz8f1mJw+c!N2dFWkQssrTNFB2LVmyjEH z?;AYD;4MmfMEc<++30#h<(Z7NhhR2SZKR>1hWEQprq3)*FW5bbz1;mLCe{GvVnxly z6s(c8VfzF~X9{!9*qlSmKz(UY2WPJSgJg-ekYL|>y2p-M8nVP<rm_j9&KM*P7=#6> z+yHeInrrrnDPdZour03NK+=M{T<^_!57H4CgP&Kg8Ep@#j*0Z5j5Lkh|C6DLCi>M0 z3HENC`<Bf{C>5eiLSog^FW)j{#XVW%pdfWIL;ldg+gz7TXar8Vkf^C`UNJ*z*%zhG zf%88S0{M;@-dK3j3=~jr>@48W{mhF17I`G+rIIZ?7K<!T6@J7BQ5p=A@{||ZSoFLm zcEF%IH^O+2=aSC1xS#Ceo|XHr)9U98>eeAqDuWlnR`2t+<FEuVK@hD7Cf#aqqHtBz zGwgN>B!L@hrP0roSCTuBt7F+OO1jhmaE9{ncC|`|WG0g$7w(u&sD=I4Z|G-H$y?$W z=i~zCloWEW8vHYOWy}EL%}C4_yjGB4a3{*Xuj@z#3_^I8URaU;TkD2rq$f&K#%_a0 zQElgh(WWy>m@5F{#ULwwMv96K>-vevn94KpP`*D37pe&Z&SIdqfQ&D#SFg$rY_u)w zoPgScFniM&uL<I1m7$(c;;{I_f8lCb0%7=!V1fgBbAy`54pWL@p`Z;|cD)fbR8|_U zbP#CTdxu)`SUiJGhFTzQk+1(3<mY6VC54fzoRTC-Xbl-6Wf^Rw46J=Hy1hhkA7B{v zyDbG;`m<T3(CG5iu{3Z_-x-8%1Y4a<sJ0p+r-&LsNOi8;Uz^Qi1~GaGhI-hiX+)ql zcG*^Ez1^9(ZiEWb8QxlsG=>9x8%deBnO*NOXpnDw{Qy?krT2;2Ku=AbxN8|Wd86(% zfCK&qPe8E0aziGyfz$jlV{n5s=mD6hgmy{;H`IathDDDzuP->k#?G58y;3C9g5|o* zQ)E&i(2Xkf(N%APT|8PcbVDMvfsiZpu7zL@-)Med!8C-ZI4v}v18t#LLLYE7PK+<3 z&`J_*0uVg$PM!`B46R}m%E4I#Y8A>SptQLWNJzs3Owr#;OT;xjfdo+D74X1c8$^)+ z9h1y}Af$65d~1pT1N3}C9wdSy*k>#(w%^^(q*%#fTSWD6$u(%&AFrif5yeRXxPS)* zH0Rk%hEgCHf_bP5Gk6x~g%*r+Or4VUSL|9aumdZ^9eLXJx#s_x1=&s1sNzPNOLB+M zu7FF7)ETZ&RYUZI2g&X|3=2A(gFCo`Y9dJ?=tDi^&^+7&I)vtgPy#RULM+2GGj!O4 z>&kqW12DvbG6aKro`h9ci#Viox$MpMN?s1#10;L_wJSjyTtc(JGcwl8<Ddc|b$o@x zBrmkHI4na8Ve1De!xlmbG%v$X!?I<5xFx7bG`~b5m=HO@L-O@=ieJn#kOMiKV=;#x z*l)NXh=V;W!zleS*dsA4GqcKEvr8=Dc%WkSb%cVy#L-;>Ck(J|-ArZB%nl3!Csd6X z2Ls_J!)8`ZD3K#AgnTe41JS@FY<vPK5PsobXVKU}N`(J}f_p?Tm;x)b0YZL_=r0Go z4aYv{cG^t@G`9j4yvs+t{_8)pAYk=VsM71>Mbz3W?8`5U#>b65oFrfYGIWQd+&=ep z5vlEdZ#aS;r2g*9YaieNK0bdEVSy6_!cOiW9yozSHwx^V5ir!jRx`!!heaO*NbzgS zypXg{_jyDdLnr7pnhMDbxo%(=Nd&L~Has~e(Jw#<5>!VJDrU?`C8}d6QJ_AGNHM!6 z?US8NmMAR}L<yL*iOibO5u!wi5FtjWq*R$w2o)tdbO?zhO_?%g$(YqlL~BzZRMK+R z6sk;GD@T+RU0b$vsIq0ruJvj2(`nP1!MYLi^o{>3*KOave&s66Q?hC}ZCaH^O3<}r zOsx_{h3a29d3W*Vy&Laew@ugn#nbCgUOa#QlF<Sz81KD%=>GYe*G(U}evtp&V_fcE zXL+3&<Bi9+b7{MI%grlo8ujYKoy*<p*N^l+e(&C)vu6*Uy}O+Mi33K9mbA|P43m~d z3zZ^Dq?8>l=MOk7M~N;{vcxNLJm9DjQTl{RyQN_N`oT-T?i46t(S(uJ#cmuqa)=ix zLd6RhFItuy>87sWHc`ZqR(MJ96G2EB@E>6EbA*;;c)^Ggz&cyY5=$1Lgp#8yQHGp( zyvaokGKfgA2O`L*1eVVFk%pH~7D>d$O^W|3O&nfO*`!8GKA8zLWq`3HkfRLTPn>_a z;l&Y4NGVSdM-19Wok$`PWfm<(=@QFb^r6I*iKHoWqF_*Qgp^<|3@Vv7m+^>{KxPc4 zrlpulMwx49p(Ghcq<ITZJfQ+ck#Hor<&|3$Wt7oHUy&r4q-<hl(5Iw9#S&>Oacdc; z1|_PMh(4j|Ql^-xuoX(U5%g52C~*RdJnE>`)?4iWqYhNAx${)0ECHjqpe{|OOh>Tz zWY4FD!bzH7Hko3RnaI4Rnrpzxh7BKPn861ho(MPGE1uxi2SuDK(2zwop+pczfI)?n zPYekJN=jC3<G@8eS@n}ZYV8A+V4nX<FhNx8Xh8=flvqinFutGyriC?Wh9;X(y`~L4 z6ba_yU#}shjthOg)G2A|_@viUmwGcCFofw!=B~cV$CFc>3FaV{p>h}0PhZXSywLQ@ z3%Sw^D_S(92~*mfcVL^R>B2-i%{!$FD@QP`u`Wkz?}*0BYjg@T#~jDzNqe4h>O1G0 zaoC=R?7c|4?;m+ilLtBAR=YcC<UZ?*8EJqEO|alRb}N~~;&BY`bI4hzm|=z~W*u+r zN$nosGOaO@PnZFXy3V>$rj<kt1V+HU%<1eJ|K{SwxVrEz?e%1W;bqBx#u+Cbe#qI4 z8(4DTy`O)~AqO+`W?K#HzWe{a8v4HZ?&euzcdrYcf7J1%%Tl`ZB^!S1@#h)?w*zL? z4@nX5AMkjYNPg496EK)XCaUSp!I`;;FH1V|GiB(B8>r~RIm#i4OgM^xkdlNo>|qI< zylNTD=);m6!Hb<0>l%1i#y=DxyPpy28aM)>VqAqMqR`?K^Oyn{`d}+N)M17*Y{L}# zagj2muw~NN#EkrOjiB6VfJLzcEd;TNV2}wYO_W9;Xu+lrA&3^hs0A%ru?kA0;uwfv zLlV9i#x5X&8^<dRH@I;PzD*B$=1ZeEUek^LK%^BtN)j_Jfdw5jj0zD814||*6N{Zi ze}j|JCeqLfpp@)WIJy4@Fvid+MiS~EmPo`TmvRuOY=RIm1B+KcIhGa-!x=cS)TvT+ zk>aqdhk;lf)|57ysbLLlvvis{{E<t&-Nlx$^yM#s*_eCWC2heJo7cj|%h42OG=j0E z)=I<7qSYpvN#i9vu(`e61jd@ksf`)ANf^ScaW#3%+Vo_pw`M|bnR~HM;Qm1luaTo^ zU~A@RxF)uH;?r>Z#HU@nNzKl<%^dT9+B@Wd4zIz@9sU>xZd`|^Pkh2-NaKt$65)vK z9EB7Z;!G<-Sf(A)ix#$1M4a^G$Yp3p9QH5=GO+L{nJP*W!NA8qf}ye$4zL?g?2Ixl z#6x4zqCx+7;>Z6~=oCRLNgREU-CKSJl?-+U3{%j<3~yD3K1`txo!NvT;x|B{IBTi@ zxJGz9Rwhe%BpHcdDk-8w3R=V>LCo<f>6GywM|@%vYGTGX)Kias*yA6Bg@-#-Q<vnG zV|iIara!%dOn3$cnr!UMZmtoCm&7EHeME*U93c^)R4W;+utdjxXsJ^+QX-SG#3mHU zN@Fo25XvA0Fml4PYiPn2zyQU}WF{6*7{eAb!59ZAp}|fGYJ^0oP+*K1UFjNay497g z+U9{awON<Ddby`Bxz<j-qz#+ykZdd?+sv+c?Yz@m=GA)1%*evhK5i>!ckxR%@yY|c zku8UL-2wj(!#HL%=*$~u`q3&yUSoFv<x4P5t10KuVo9TE9WRnQ+MFt)6`h%fIqLBU zNi2$il3)Zf>M@VwC88C*dXpm$#La(<$Hk455hY;r4_YKbDa`FzhdILyI{?GQPB9iQ z5;35rVxbLzz(cL<(1$btVRipth9W)@r)o(<5hdMSpPoYt4f28%iU?h5Tvw##h^G}5 z_KsyEQ&6+bna;_J3@`V>U7|JfYy7k@+1$a6X7qy4z39d~loumG9H<p_{DdR+ilJZ_ zB7aO_>nAvDR7b3AP;Yr%$NrJr)pq(C3o`3gXco$Ecw!j#*u+m*$&5+cLmZSKqRA*y zQgi?2m)E`awJ?9p>ttSc9>k<tu!BA9yEsO>$o_TOm@S)rI0hZ)a2zw)yWigkv@S#g zPB+9M4sNs#y1(g*g*MXWZaW4Z?Z|`<BoXg;XQCdN^9N+a0VI!{DT(DijDbGl5ne39 zIClAHASCiBkE|+boax3QBJz=51;RLQ_D3tG;Dj;MK@T@{0(T4poKJX2uB~`9kg1j- zQW#}k6s8^CCc8$%&6&MpWA=UTQtfKv+}XcOTRH5bn|KtoF5`GxW_a=H9;t43Z!XXT z4`NzFw1P8UGelYj=;>vQ+<l)YPIIAx3PBY1AD}n|a6cIhEVLsYu?Q;2C{faX0MP$b z#gayV?$&d?@15^`_xs-gA9%jovumGu4RwkJoN$YSAFx^WJ>~&eU}S<1lGsEz#(})u zJf<$Ey$D9mlTXrobxnOrN?pXs8D8jzVAjDg;6^8ok>dzji%7=H-`ovBWE=>xipAQR zW|zAqV_;-n3~J!%kL-obzvJAs;E^3|w@v>X*DlO!pl43RaC8wG4F+eZ^HEBhi6;N* z@PMxIcKvz8lARF;Ifn7uRBt06@M#C4#bM?VVu}`u7!WfyW&c*l5y}nv4DbLEFaZ^C z0U6M`3hXdoPH7si9vI6W(BW(#uh@>JFR(}%94{{n!>ronw(i3)aw(Viq8$HvWUtP{ zmPkX6pv2{@NpFCI9GC&ORAUDB0{cv(m*$JI8ZZcBspf`_G_=NRjzjxE>eV)3<VXRI zmc|lz#gJa-Njd`^>VqAeAR1;SAA|uExPctJq4DbIVua!#+M+Hv;}Zf%D4yc1DozOH za1QCP4(;#`u_oH?f;TD<9?oGm>_HD}2WgazoQ}=A*r{u>ZwPB6pBS;d@Gugi%b8Bl zYo>`wWG5JsfiI|IY7V0hlxR3CK@e{5F{+I-EFl_BAuOWdX0(AHI0N6z%uOW1sRH9@ zu0ar_;ZyYI8l<oQB{3L<aTtlQ7=P*7kTKer?eTuY5ozgbo=-1M!x{gl2^xV3Y>Y7* z`Hq~ZgZYBvPd;aMV#6_ZLku~IEI`2%5`mt^v37vL5R66OC?WJJ@gI1>5Jbu&`j0cT zu^;{M9|1BT1#%z*(w>y9FxV-XcB393%o0{X9QxrL!iF=XA&G$DC_ZS{%Ap^C0T1Si zCn(`F4w4{AvLsFNBvCRYRdN#jE14W;G<KsO{2_COt?GE86+H0eq|wSYp%zFGa8@!X zg>oo~vM7yG8`-Nq4strGDZXlFusmZVk8&!hvMR0eDzP%zsBs9{D=WS7E5R}>#d0jW z>jcg6EYUJ8)p9M_vMt^6E#WdQ<#I0RvM%lNF7Yxi^>Q!yvM>Mr@-G21Fa>ik39~Q_ z^Dya>EERJx8M84R^D!YaG9_~|Dbq2P@iH+pGc|KFIkPi8^D{v+G(~eXNwYLf^E6R2 zHC1ypS+g}=^EF{JHf3`*X|pzMQ#C6yH+6G2d9yct^EZJrIE8aKiL*G3^Ei<+IhAuc znX@^w5iy}NI;C?usk1t*^E$CJJGFB=xwAW|(>cL2JjHW7$+JAo^E}ZrJ=JqP*|R;} z^F84+KIL;h>9aoV^FHx2KlO7z`LjR$^FIMJKm~L_3A8{B^gt0bK^1gC8MHwiG%MjO zLM3!UDYQZ@^g=N-Lp5|mIkZDP^g}^3L`8H&Nwh>w^hEzrG(}Z(MOl<XAM{0GG)84~ zMrpK0ZS+QQG)HxGM|reIee_3xG)RSXNQtyajZ_G|Gf9<nNtv`so%BheG)kp(O6BrM zt@KK<G)uK~OS!a5z4S}LG)%>GOv$uN&GbysG)>iXP1&?f-Skc2G*0DoPU*Bx?UXpF zG*9((Px-V@{q#=(HBj^NP6<^^Z}U(QHBl9HQ5m&S9raNmHBu#YQYm#&3-wYlHB&Wp zQ#rL$J@r#THB?1)R7tf|P4!e!)i*Em@iH@2U3EXT%Wdpo94yfKUiDVt6M@cQZlcXT zI-~KBr`l{4SJRW{G&OCiEidlN=t^TAb~WeD;V}PV;Ss(760U(Z<Y8Ee^*oJrywoO_ zv~@@yqj$2E8RY?idWW%euG-vYHQZ)y+Vvlr!4#O`9BjjF-XZcHp$NRd3!vZ&dSM*g zVdt`In6}kC2kULZ<}mD|KE^@kiqtXct8a{MH|hg=-f0l`AyD?=9{xe+pvDy*K?}+N z4XB_Q?&cq$1`Xg~4a7hU)?f~r0A;1}V1+Xt-Uc1cp=cC}Vm<aQK6ZIJ!|0eX9(t#D z4pO}cwAzjqZgw`IASW`q;Sw$(7P!GS$RYFO^%39z5Hvv>?13M2mPr5s4#GeS-~bN9 z!JweV6oOz4%;06C01g_#AKZZ)l3@wv;AQ{M;AOV}4z$4?#Masj)@BE?RkO8l6F27w zHyN=pmW-}<o>ecjwls(~q0pi6gaZ;T0Yh|-G=jlwD<)dq<}NC?G~PAZPWNG#F<aS2 zas@*f6)M{n7ub|0T*cB>wbfRSt~9XE=zt@1&vpyYpb3Hj9iXNe9$^W#01AfS4Vr)# zkoO-h0S=&`48*_;)?f+Xz!{DQ5YV7+%|LwT;0Oey7vKPU&tQGezzf!ZZdF!T71wb6 zF<IqdHXhG@t8F)S^=)<oS*;BVS7UR|^$#;=ddR_mAGR-Ifohw<UVA5P{vj5$APl@< z3%&pjGH+MwA`HR+3a<AEzSbZ3;pqRmA#KqB4XU9t;31c`=N~q<8umdob~bH@u5YH# zbTKw|@1Y#!sT|A!bL|%aahDFSO@6(DRwZ{Fg4i+QwHtULh2H=T9>E#H)~Lb&4Yt62 z*T4(J0AR;~7Mh?8uy+mM)(Zeu9F}(u#J7Fd01(2!9)n<S#ejXa7Ya1N9@16}ynucC zRt%u`9}0Ge>DM23L%!J6E(*5TD)$|Lm9akdh25bVf<cB!mv`=?9WLP!nxF|N>>Qjm z^V}hAmtYObKnoxNWg!ZVx1f&K;0&PP5mZ?lme-73_6#aGY@w!lp<oM|7Y)MTgXAeV zx>gG+7!78}92&12XrXw!HXHw-hIcZr8_c2_ctIaB4{&(HUMbcbbgqbx(!U-{yJDj> zZUdq|ws)HW5}H5@d^rldpbU-xFaY5TqJVwP*o)r)Z7sNt&)|&301n=u5z@Dh*_V&! zKnn<(Z~eG^#Q+VEL2vukk6%`1uc3ws`9PhrXf~R<2IHfx(kVT0FV@HzAA_6!!5!QI zb#qB;yTKGRA%*ExkhiHDAOQ}vpq-oGYmw(LZn~E*xD1*g7E<~jdLa;&;Gg664CL8; zuAvFo*q{6O4Z=V*rnrm8_YCg%5wyX|=D2UoSPY`z3+k31df^eEAgje1n6Ke5x`7I` zAgH$>r@xl42-=wOI(q+C+8^xo9b`nzssS9#2pvqYz!DPAeyOAN0-S?QvBd_?Mnh}o zVL8mU36>y>lYt*pLwT2=493@%wKt&QK%)J5eP4DBR-lv*dZNW(4p!g@*tnrjdka?J z4Y0Sg*VhZo;0=yI3!=KA{~3>cXK>-H+Hy%nkGn;c+coe)=cZ>j=8PO1qcrZr+7Re# zrh9;O_AnHx+O%8dtZg;qf!s{P+7e4{P&%DGc7TUz&Uz!eOM}|%qoCkBzB3To)_ZzP zQD`HB2Z>2;Fr#^{u-g7<SAW(Y9HX53Mt&b7zsn)qR{CQ-*1P>d8cg94&h`;5;r@E3 zFU*#C`&OtmVI2Qdqn@F_mH9YrJA;;sAgtHd47>mh8i617K?~lXi`f@@y&w>JftJ0v zq0L|pf*=^Q0k&T@tK0Vs&;Ss$A$@VXj%D@|-oeJpppVTUwC5HQnj8vV`JiLG378=k z-u7kdSPbS`3rr#N#MqdZKns?D3eX@KIu>~X#~s9BAMRWnBAlCwjlBEj!wM>w)P~OP zE59{V&;eW-2mD<vs~k93ki|h7YM~W|gBF&d9qdMv;ot~*xo^FAuEQW6Oks>Y+q6yF zlvA6ISNorDAPC&}ptE-kqQC=A9Jtw+w$<0x&7cfcAhc~=thrjiG8!)s?Fut6FVN<P z<Dp<5FKz#L1DoVmS<|MOz*TYA6~FQ8C3lrzFSFY0!#?o4zrLnElJVyZeKd|3lB1`8 z0qceT{Jl3vN3zEs3aZ+GRou8?cjf^etnJ&tjln*{S^Wk!x&houL%`gLjnJVtW<$Xj zTs`WG#MuexWYr!J=!WSX-jVej%!UWyp&a00<NdsEV9v1nqTt1$;92<NNhcOi!GpB` z4M^dG93&XBxR>E}3%Hl4|Dh4SAg#OnkHY{E#$kE?IeWFbwV^-|w4n*m0IS)zkIR>q zOL=@t+l#xl5yID??YMpER&V3B%spLZ8vzii9JqBGn0=d}$5*%KU<r)i>A9Y7UA75U z;FbT6e0^Qk3(l5hz1WQPUgw)YmOCREG@+B1U<rbt2_WGSf<drXqu{|U<-skQkw@Jv z%N%4?!2YS`fbQGV=3UVYdOi#ZOGEM(59N=C9Il}ifH?@}8VcN53xc3x>UjycIOwnZ z?N^`)Ox@JAcMD|T2B3hV$$SlDU<7V}%wheXWk3d?K)3(6p@YB!44R?wS@^w}%yGMq z(V!Q~p@g6I@%T45IHRBnmf8ZNoHFCu(gs*NL%LhnhD)Qn8~3C!!_lixaUVnf0pgrM zbob;LJb13$zlHzKjk8x!-o1O}&M{o*&)mF;6XRXHXpZAOj|;Cglg4e~Idm-fHN5{8 zOOqyEDgVtwH*O&}Qkqt2LUj$@KXd=&{Sz1K5g<4+ul4&^aiKCeaDoJZ^GMp$aW0!_ zYSN_0RY2Lu{Tny$-!)QN!e~LW%2c<7=16jjwMkQ6W;NrL6YB4pv{<otUAx9`T+W5v zq%|`+SLHZ(7v*&mC+=cAhZo0P<91ElJ%;6o9%UAblqE~6f?ZSSujHynOTrdu5`<JN zhSK1mS+d2;nl)m!1aYLzUbVJf#0)=k#`&8gy&NqWZU#DZF=FOuIr65Am+acl2>-ri zjTtfJqt7XGB+MEw+qH9_0~S#8_R-fgF~S~q{COwC8`1Fx-5L#~x1NB|WjFta2TL4y zAbV!aF@y(22-hBaYe3Ne6xn6RopaHZ(F7!LG_l2qXRKi!6j}uFNHgvPLsbw(ECIz5 zL4<+EC&5I<&tbus(uygx1j9`;;CuvSlu!wEkvN|n#!WYAF_z3DkKnchk6{L(q9(Kf zr=A(Z!8lwH4K(o_h1$(g#0ob=fuM6`cyL1vKMYr*heOEl!w3!v=-d($)G&k@B$oJM z6f)fKXMG2%38EPEMHe7+<H6C$Kko>1kVN;);}J7d&83k@^AL57Bah4lPd~1vb&V;> zSX7Rw6K#1-FwIbQ4?)GA6WdXlEmUl&ra>7GK?cQR)IZ%kw(LK~%0vHBGt4yOZD#YV z)Q>&?z{89tvN{rrHvD7+)lsI<7DN+TJd%t}oGGJ)7EnO31r$Jb!w*r~d<k&EXu!eE zJnsB+2^>6@aYn#sgdvVU{LJGU6lct_#uib8(L^;1nbJfV*<mMe6Z()djwZmR2jdn? zzyV2Q%%JgG!aV}1Ol<sI@<<Ro23*9#tt=}}D>>?T6&$2Avt>8InE41AfOz>xERh|R zj7&WDyR{~<i1XAkIRf`@z)L&=iM4QOu|yPWuDL}Kty~jE7*IUNouk?D42Rz^vd1ZR zA2y%`apcLl#tPRxUZ0vl6c}iQ2d=Qic8GGihL7qYUY>JMtf2oMg4%H|r<`I;y6JlD znK8l$P;BbCnnUz?L#L360R;&pYzQNTVyx_e41Xss;F@K~u)-0Y-~D36J;L#Ym$wxG zu-iU90tZdqm}H8Xj>z=LBAS>YEZY7wbG0T*^;=uNSO;Qsz-zv^W}SRGXCX*^Xays{ z!JX9PyY49J2Ys3Yr?fMl6_CJyc6*?6wh(|H)Sw23BVBZ4fCCaN;du5DRG%tkJP+OA z2DejPbKn4odyMKFrE1AL4hDrNFpL~GL5D!z@sD17Aqr4{LoeL%4wkUwVU76B5W0pA zekjo*`&io}E}@ctcw`*3pbGdtkqn^_1XXIeL?R%OzDxfwV<Abj$Ul<OH=da-C*?TR z8_%?aA=nEQnTdx-Vj;0D1S|?mSlGiJCd9g}0b~^mf+og66hKg6Ja;n#6uy8AZ|oyw zDtiubE*Yw16yXhVs$LOeF^)udY;=#?!WSA5F%mUMJ4L(%&xn&I4|(B|y=cT2w&0w* zsb^$Hd_)mwwx&5~N()UOOuwQaoc(#hII(Dkii!{gL2^fAP$&Wnmq7}9<&Z<f3D^+e zAc%!!6J+~y)ESCk1T6sbaP?u&9Ng46*VVHDL7-;|U*rYYr4Dh;yMYXbFdqI~kWa0% zPv|^=C(U_KM-J*x=wtw?(y?a?9uScSAqa&P4uSukhzi*N82E!Zkf(Wr3SsXam7pyY zum&WcSVa>x0S49}JrzBJnhfgF<u%Ari-dv<WH5mdAd`Pgg+dTk5Iq?zVVVHTW>ul^ zpD%nNe}e4faOSXuqfTG~MHs>slsTf|EI|e%_yG%2aD$QB=S55Kzz|r#0!EFlQ)@6N z3}8Sh7&XX3c7;I-u-QTF$e;!|(5p{Lw}#z?5DFx0&l*OsyBesprxzN*4W{ZsF}wi~ z<CtNoei%eJc%ck{0K_@?F%Wbl5fE>16d;<A8J2MCAKVB6BmEPMmB@o1{Lls@{x+Pv zJwhA*cvm@q<b~)WEfKva2S0%5%OPZwn{EFIMsxphFyI7JQ#UikKin~nOQ7ki(P8E? z77~mgkTRIqdD{_{(F6xRh(u?20~)kJi?b#Ubl$lHB(|Wk&(Q}zfcU}#OSed7qQN{0 z{TTF=Nze)nX9Y#T@JEArVd9i7J7t)|5*o0C&1U#TU~Pa0)Kt9ftZWW9NZ!Xv$v+3m zpaB@&AM@rg2O01w3Jx5sg)ZvZPVr|AMGz?o59J&)G$5`~P}7pvprIlBX>^_o-AS?e zqMoiH2qUP0PfMqrfCg4|^MPIUmYkvBsO}6)D6=~&<e`w_U<7mKs0R5w*B9-M1%Tz? zgU<kkoEr8{iTxmB7d_I{^{381NCE#2LRf?-E6xl@Wx=Ica08_(6Ld~x>kv`^*B{WV zdPNO_K~q2iMnRzr*ty{4NbrM8!#b{q3t136@MuEsxuk12>R$;>Q{t2~2supwU@Ij% z=P=u?BxvCSF(iYxQcAx9#4HXb;ISp|NrRf5B?QYb0ukb_J>x;c8{7d~8XkltNo=AS zynvs~7^Eft(1L-40|iKkW@E)QMT#B89yIhq9Pi-AJsJTB^B{Z;Xwbqt-Z2hHT!&50 z%ME;eE6g>NAqopSZxh1f!C*E473h$p;~rZ*FTAoBa6l`&`>TaZd?9chQqvZ|QihL4 z2gZ^Uafe<cWt$=>JEz;!?;ihj(I^BcP!>}2-^^W}fR@#BN;c05YM|6JmnS=3SOE-b z!01E2XxeB8AVC)jLK57da}VCA3~&wh&L!|e9{2$aNH7G%$qqU+4#Hp4-a0X?AO#Ez z_tA@x(=`u%JBEh=LLb*WNi`PDM}`7sIVfT!e`tjf)u^C5T3HAe!Lz_LePo9)*%B)5 z42ufk2>BbSY<n8qCHzoZkv#(8R8$5qz`<YlJfYHM+xRf>bl&YVZ9*5n`EjM07%pdN z=Hq|`a*y<joXV%;Z(r_VA5NVnxc$Et|JzdqE1$G~d=VZGMr?Jf`U~Z`j{#Nscgnws zLFj2D(0ZU#1`Xg=DRBRJp@&m`CxAj1GC8GJ%GPBv#VA7OId9Me^H3`DCR_i|2w`w< zCT0pzv=R5<5+}zU^kGEf5D)WET*p;H80ZfE07P1_Sq=pSk1!6s@CZ`JAD;pU*3=xh zCm{C(3F?Jm3MB?%a9a-4QwM?{C`dY_qb5>TTNdb3k#ik$=2I)MJZPpJ93@v=M>?x_ z12Hx`0R?uP2V*To0!k=oH}Gwa_c?tfhj4`_%BDCpb_2}^c9>^RH?RWRhiUX7X~aQ5 zm3DR`5Mzq71q}duo_1Kc;~{HBXoS{(dZ;FKRcW9WZh@jElj4VevQl|Qe0b=9D`a~K z)gFAfc^zUxjfMY)4-{E(wPk=9hX@sDleQ?<mVav?DTcKn2!drbplua&Dc3hahgU&} zQw9@oSCV)G>-IV|aD0D-S;g}q0H}V)#zN)?fbchd)3^l^bZOTpe#0Xizvg${c#SDQ zC}ZXU=je{jXFxx&R?}yE%=dScH5^k$h|IS^kHTbqhga0+bWvuIc|`(=r6!PfY1QUV z6E#6JHFyrfWD}%i#p6LHRRg}5a^0Z?;~*_HBq|<=2J=xdaG(w4@DBE14-O}V^x<wu z<bnsYADkkBrS%U|n003WDl|u7un1Q1(NN{#9lix~{GldZ=wS`TWHP`eSQu8HXn|t* zgdhcMSl9m^P4<RdxL5)>XI@YQll5dWhHaP@k}tAC)E802W><LCc5fFl23dT7H<1f? zYz8D(&9hkPcb6m79(Tulm{=*B763!ge8?7QEH#MDcXng=ASTvqpyq>JW(IbJYW+7? z>VaAPn2@A1k0CUR9&%YjutAMhge$aWuE#)#wUh}`XE-p7T<0me$7r+2hjKZF7J_Ka zc6Nq_ID811jm3x%1bOxse?^cWl2wnFHUa6;clPLxz*kt(=Z*q70`FIk-N*uk!kyi@ zm_OiRekW|*XqIP?i08?eAO%9|H(8W;20<`EhUtW+cznV4cDIRahL(RHG(mT=Vlh=_ zfk*#2CFC7Kv4QeHZypE;#G!)Kg>kQS4^qe-Z=eOI!VmFaTm!frUH}KqU@QKXQPF{K zTF?k^FqBMrPaQUSN9TnN<se$OZvRP^oQZ{G=AXp4dNpN%*%1U_mz9b|Q-6bnVc9}@ zh&W`4Y8&z>EY*jW$&re4S&E2ufYNQ9I9Uo9IyohM6r>%NgKOBiXBxIZ)ybJ`DTn*m zpBy=6V``5L)F2`UY{utlfhB=w5Cvw311VscVFo&@M{Q<>Kqb<pem4Qlv3FYlfq+&| z_5^IHX(>>Or>2J?m^D2&<$JVgh?!#^+4gKxYC?v!hL-Xoz-Et1g*Y%GDbg2!f(ic} zjB1U-cBhdR1$~H)>gS1=<)`BL0|77r*qNR22dw-ke(R@x0YCu5x{vu80LGe~;1*<Z zD6Gtwg;21Ne^mn$P*G7yh=4bRx)Y^-(uku9YS0E*Va1FA<WP#DZmM%1O)w7UFb^7t z5U-V5nsPj#A}TF$4<xFnCYB83u%YRdVlxVqp>hvz00%u~Pbdlp9=c?wb11FTX443$ zmgNOQ1}IA=DUu3hp3)~ZaG-)$Y&1o8rW%T|Mp<AOiZlhQU3Uhcim|i!LC%JwC2}Ey za(G)-hrD{HQ|KYk*sCy5o4ja$&IfvAXLi}yfZ9Qy=V+&Z<%8-moyXUn31a_L+DB*` zNg_=4dyuJJ_R(2Ipnivij7v&<#RqOr)+t3$k!F^s^S3~L@}B}iJ1A9}CgfPIw>#QZ zsP#do6eOzJk({adqyV+Hg+f_VcY6CciI3Bz{0OF5*p}ECfFi<ao>q_6=~n0Ijx{g< z1uy~7dX0@004YEK1wfC_2?M}d03;xu*BAh@+nvJ3i1ewP>8Ohlgnp2Tr+B-NLb{(= zc4~O&dY7A~0u+pRIHlzQw~P{|Avp&}pcwvOuLdCy*QE^+t0`*$L+9`g1_4BXkdpMF zK&W(a<IoISSRyp}1{as2M;RS31O-V5hEWhAU`RS@mQu`99+HBmvy}gNi*<$>m3fpB ze6m-D!ZUePc(T>@c6b}X*5;`*J3+%}boL<wmbPYyq9#!=k9oDDb8@+{_ltd3w3(<l z$$5!qcLQ11wCMS?5!AVsxiX&jxyKfqX)*_%1(<l1iMNTh+Llm`xR7(`w)!`&jJRUJ z$fs>(vtoLW1LaVRs<(LxL7C;V{}fpxfLI%xAZO5bEDXXQQo1xnF|)&DUW%8NvL1wq ziK`Simqo4p33VcT!;A(68C0#}7XSq$o*^^<s_SfnJOHa(00dyV$MypQP{^y>$o3cj z1MtT@+*VtQj?!l+_B1Jkc$dAq9%BZaQfzdlW02Jrn!%LHmk0mAqZdMf_aGU?WE*6` zN~S5^L6QaG554RUEfEjaRAub(25;b!Y~+C|N;+F`3EI$b50PI8i=qAS4m2lcH>YsE zb#F%p9g}irOeqGd_k}_y2Bep<52l7@#+A28Q}p|?3v8+h0=G}AI?>y*3N^W4rgoFN zywe-Ch<hn<xQ`MHQ+B+4cr~`$QI|V>X?&)(hYX)J98mE2S2+8>8EJo?R>jqWS$M^K zaK(y|#f@z1i)*)x49R6j2F4cMu~fP{i<XC(vmW&Mr}4~p6y$dPw>z1Li(l-dbE`sV z=d;DTC_j*>4p;^m<fpJ1C?TWNB+QYK;sMKemztX$OK|^EU)rB<5Fvf&Y?RBk&pOF9 z5C8>0x}Xc6I54`gO8}Q#d}M9b1Yo<}NysE%Y5I7L&?p9R$+@2f1GZC%UV41n+O3*L z(g~R$Q40gyx}RaDXwi97u_(cFRs<+Jpq``4fMF05(GvbJ4hA;|&EXxC0h2C4bDHv@ z%T*5X;1d3oLKu2p;}8oS_E9g?OJN`$+*~m$5M?&Y9oSlB4>GBU)=~dCy{k6_a0neb zDrx@-wm5K+55{*jkdwb-I*ZaM`M1oai?PF9F(*~2XqIS=WoWXqQa2#GYWa(j<!mgF z(9Kh3hV@rJ(2&quy68Cp!TqV#dW`Bp%2Iomxw-$)2YJ{K6jzXWcJ+NAZB~4QCdHlU zXRu~gfV!Gy3$CTOq(#uAln7Z+0NycOyh8xSrB}Sz3Y!;cLczPAt|*pd_%S1JipyJs zgYs6x)_Y0KSkia2G&aIC>@fj#-`)AEf?bb~Ji2y0yAz<uZJn#fHvwx+0AEel10cJX zyl0w4X+^t!;O2D8ceVmrAH;cfjBTSG9ICcSS8eroD88C<Nag?x9hKe5#%&&=r3La( zf;EH=sKUM}CfZt14&(A#H*^W(>;;g}3j{Y0y?_R&%_*>ras8$;>((5A&<omd2}K}S zQ@A=o;35h&2OOqS@!TH`U^fS99~*mhGRyxS*eaO_B8K$49eg6jzvx*~SF-lxSrZP_ zi{x1m2xY@jW&jPr*gB|!M>@=Q&}RI7BiyDCbOr+ujrkcn;Vj7T$>r{}KnDq(IcZYu zSbSyHL5ozUm&ih4mS?zHh=GeKrTc9T8;E^40b)F(W+#BuxT>C41E5uR_LLzxl+x(z zW|Qh6A4`Y7sCm5S;%(+^z)poT>+bYi$9r0z&vu_oc2Wo~jE4Ar!YY?&=K=ifX}?;? z5M7UJy~vZS)+DgV1pb_myt@>w*I{M4EFi^1)l%m<0N1P?<93X*+&tJC%hlelCuPb{ z=!(Z_dU4(-kNT6a9S;++pa;=!ZxH`o-eC^EyyyJj8T~{eTL1|yNnGWC=~wsYS|BPw z)C-g3L7%d4{{SBxGIk*YDnUSNbLEI&LEDH@B4E`7$tQdLQI0&7Cl%8Gc%OJHaO%Dj zrlGFsXPG+%sgigvAo>eUwpqXj)bCQ=Cyn@67g7U#H`(!Adw`d+Q&$98jl<WLAq`I6 zi6sUDkmJtBi2Q}cUwy7vDss>$Y|xmHY7&=!mEWuwOgzhdZ@8bE$lY7UJi*i_N6+^n z3wEB5k)AgKmucO)(^2C=gajo6%;~t0vK}?|meC*Q695DEY~3FM-kSAT0z}4))wXPm zL9>dQd!>INudAM@xB~zXIB@^4fKd<z4iZq7OsHY7AdZIv0;CXV5aPiJ6A2Wk=&<0A z0R#x7IOtGdiU~t*koZB;A`B8Weyo`@L<S6k5C=|x;>C=aGiy8yVL>p(jhR5tEM2p( z<%BI_#4J4{HK<A)6TDEBYSm2B2{>*<;X2jooDnx<u32i;>e3=3YOsAfb?H_#Z|1!_ zcTV14dH3%1<@c{q7%^VnXc;$8FgkSd{-G(e#>*Ngm$dQYCpca|EtM0W$s6w-x^e%; zHQ7>zDrPw0$nDb>E65TtYjo>AQzRL=USWz{-mQB}kY?kwXxYj(=u$09v^5K|#W~kC zT7vX~vm~e)so-;$Y103wiI=x!*92*#C4JSZV&*JaZe5J{wpE)3fwBhZd#hF`Vh+2? z(yxdHg0jo3rND#2gDCu~t3fe}m|%o83hXMVEj*YYq5I-H>jn>C8p5aif`Vdz8W1{B zsi`oNfg%`E+M=!d*0^B=h)Cecz%|kuNG`exoa2TYU`SzvA+8H=4VzqyFh%$lN(e=& z;tOiWo^Z_a4DgD8@VYOl8Y;swvlK&ysFZ?_t2v4&!oM`(gQ9^c)qJxI4{GQV%mSA} zORXB_&{9jwWFUcs;nd7=3mGOjXoNt|n9l<qae|?SCV?_z1P@3kDJK$cgp|dD2zrPG z4?HBPql0jehyedsV;zVDi3YN$M~0dVf`p4oN`Zt@!PM~vU2h!=(A=CNi3O-Co$6N@ zMj-1@tAZS2gqaTI>I^7|{qxNck&MDDX~lRD3M#Wi4-G)h;ma?;{(|hCcewLzv46~g ztgm<e>E#P{=V+pt&E~n+AMT1sOpGvk5$7Iq$a&|UULKJFip0u5ZX9yvk>{LVE-7M( zC8B_02r3%+M;wsfXaZ%Li$KHWcWS#0im0}Lq6k2Gafh5ny5soaEsB7n7klK<E-IRI z^MXE?Z6l7U45Mh-9@}zj@U`g3(Pra0z{5|sAT(R<&8q%`xR)|QtMrV^WNze$8`I1U ziYBz^&)fg5=8$29Exw}AF8>;kp}B7bT_OMvVkDEM4j~U}x69|)B7gySoMZAiypUl4 z5{8KIr><y<LQxPE4DTvMCt$FvscM=LLonGk_Rg8+4o~nK$So5n0k^7CzZD{!`?W1r z*s#nPi#Q^~<&9;t-7KN>zzgHkw2Z`V!E=<Y5t!^=&BS>uwNlH1Ky}l(%+?%KQ3pZ@ zY8fY(ASWDZz<r6)ji7!IVS!52Vk;aB>q0dU9YqGBK!!v}H%kDPKv*!W5wPnu9{52{ zmQ(}UwdGemT9&ug5QQW`rF#pCQTck}Ht0ctNXN6(woarVy>%#Wb;1kIAXBfu^kp9W z7>EBes?)N5bmktA8Dc%ev4kcxp$zbNN66+OGJd?n9e{{V6JntaDpu@YB!fc`g0Qr4 zn4@A9`-i|TF$XQ6VGiP`hdu03F@CtC7l0^3835rj)uiSh+PFmAqVvap_#+-|Gz=R0 zriCWltc@2FM=YSYgp(Da32zXGJltWAMxdbxJ>eeTmXMr)nWraFJ3|zdCbWD};Y7Om z+!?mew|bz1JJl(Uab)mCahPIby<`g%s30-wc&9i_xurJ5v7B>#jxD+oL)v-)$u7~d zDoOj}%u*&5sYL;bjc7y=W)_7laL)@#>)RV-)`U^^<Yy?`BqWyr1yYJrlUgVOf587K zO}hOo2p)ifp{9Ac3=N?Hvt*W1Xo8?9oKHPlXn=RBw>Km7$4y_#4WtU{7BzhZ3WTGR z-p&vm>xhq|iqV2Q%OFuT-KL~z`ig)ERHqnuU{3fcQ=%5<C8l`oaU=K|x-1320kEJ3 z@e^M$NhGNnkibw_OB$y1$1S#e&J0TcRRB0QfFKNE2_EpOL`WwSpm?DO0r*f%Y7o&{ zeurBq5g^B?*}@^DU`gu(s_2v?7b<1TCP*pUd#G|G85owM54x6OgHnXW!SqW|kikr$ zCk8b10v`PMArSwC4u05!JDQ<lUj#D_dn}TWjp)S?D+U;U%%hF|=mu*2@sIx{Mn)d! zfZ0FX;f`?x7afU|ZOGbqk2dzBALOtjWXu6FMz--Bjd2WW8JWd4f($Z{nQeFf(U-oE z12x=u!yg-Aj(I4Ok@W~=6ql0=ZT#aM3L8f=ASox5!NFzzAO~vu@dhf$3BO(h<2(2< zk46CE1}Xbl5yIdycu1ybCqt*oqNojRxI<uoxJ?w$>9bd!W00}n+bFl7vLa}q5hDJF zeP<@%B?KX8Agiy;mIDQIYT**SXd@vP^T;NI;SC6LhdFwYi#N2#opWGqC+j;0E}~&M z<>iJw?r{w`qU;8@fufGJ(Te~>p~5Go=O0lv&Ej|g$2XP`x~Q3AKy3ekK)%aP6M8`z z$pU2yOKZZM(`7d_jHXU|?nR#!yA|`oLC`&g0vrJGQQtL72BL9P>XvYXC7?-fn89?q z+OmcY@rO6+fsza`)g0c?vJ47szzxKFVpyv=2r`Ib80bUK<ut*(jc_L*%1cgP!{H5K z&;qfOtOXg|bDdtOFghRCrynpbL_wKDpXz!UAVFazJehV#1-Cs7aTHuDK+l47SJOE) z?n`m1>_z3XgcXnpdW3cdKl<X2+a?m<`$kP_lsnse;~O>oXrsdPz3<zihQ-50cyz}B z-s$2yx&ohWaL<9<hJQD>7MHlbHU4mrXZ+#Q1+O3}KHPtBS2h1A|L(>Aam9bwakp(m zhirXI&K+mh<)(=_IU6yD<c!1K+eODc$mz}|e>b`U3*~ZxrVZ0f*BtUFS+UU&2K}bo zj`sKmJemQByuhmw+OS7IQrkv%_?)#t4=y<pNyKLCSdjAwF4x<b#eiM+;msvDXZTT$ zirakRxJ`LE{*lLCkaG?@c6&d9+m8gt5e~-wqKNlMVU-PGW`MZF%a%|Xgw8>nEp>-K zTB<wa1OXBlegwxhs-G<!AvG<1>2-?KvT?wnaC!nKa-R8yLwg}&+IYmd^fn*(N|A0< zLi8KJe3@{Y#S2SYPI_24pI$Vh2(6KKd<+KmQ6jW$W+4C25xO`8F{>=|%VF)X!;qKB zYa#3M<;Qf$iQ#y}!|qFG<Za`j;n`ZFk|8!>^R=rBgFoW1bSjR}0WlAdfr!!#@d1zB zFg4R*i`RROA|M<Znu@q71K@M4sW^@$xG6n(jUbpFmEtJ*fF#$b9&mXCs4I+r03sWd zhmq5*8{93D+rfG%Iv)%|Asj*?EJ7bdhl&d>k*Sx{+Bl2TK^_#O*$S>7L=FCnhll%% z(_$oip|QpYjC<I)f<r>n$U+<(2ju!UMzSNpm@Xyq2hKVN<vIsD`iFQhJemuxK(d#> zOF1MQIX-kkCp-t;`a?lf!YDk%aVR=Ngbd{Rm$v_NJN}ccCL{-jNiaBYwCqE>dDtb> z5hz^~2XxS|P-2&;v5X>UnZqlhAb5iep}^32C7}zB2~m*kfSF(j0?VSC?0ADz3WMb{ zkR_18`qIS}j1QTiqfkPR*XtpF7zddGkToa*Qy2$rfCM(7CJ{LUnbELjfCN_?wNI0o zHcBx55Ho<HtXLSNW;hHqaJ0z_8kmv7152dnQlmvYE_--JMeN6ZWI2Dh2LoFo5jzLq z;IJT&lPz;P)(Qhtq$QdVgDpTA^V76%DW)R;giUg+uUG;&=!U#7gY%h+pJ)pGDnSNu zlsS+w-8&w<aHl|9o@NP#afk=bDmuZ)NuB@PNuKOUpZrOn3`(IKN}?=EqZCR<48xI& z2QU<jdhtR+)WV#E3@=1Po&1ZcY&)rZj3gYnevk(?yazklxc)*d-Ezv2skk*FhpSA) zq&!Nv%t?Dehp{ZniczjBsu;3tyOGOFDWtjKvbcC~j6DK`Kk5b4x(9eDE@yxud>R4= zTd{vIJPDf_;#e6i00i5z#$eb!h!le*c(9ifvE_Kh*H{A0D6)*vAoW0wdVq(1kTT2A z6FKUKDx!{$nk+bIhV;@G;y{x%Ajfflhek>nTAH&XaGAnj7&N$z-&B`l(uQ}yw_b<^ zG!P{jI2kzTymFWaN%X^%8_aj`$Flzvj4SF38f%)}LWi~NEVRtaH9Aj!+&Gvyhh|7T z{A`AP@P~fGCiKIn8;GJWx-*gV5~+crYXFTmC{T`CgD4UQdpJGA8jmKxuqJShO2G>) z_=ihi7dI&oyhuDWm`xTmnBa=7&N4z3T~QWoQ5Stt6-7(5+{&qhLi3!5u$0QAR4y64 zhq)v=F*-}R1Vf^uQ5~gAEA!Fy{860b$)s#9A%)Q)M9ZWMqI0++CUT4+y`s5%N<r)k z<$^>JlML<xJVFF5c1$q2YZ@#(huadH>y#5m>xQN&40MPGqZ1{u(mX8?hsgx3`YWT$ zAP_I;n<N?{Rs=oNIfDnY2hRTx7)Vei81aJ4s<(?N8r+xzY4R9xI0th8JajORd-@7j zS{jRaxN;PZArLD}`l18lt<>0~D7t}tN{%aSJ4WgSUFEUK<gc<k#I=-48og1pv?DAf zy6vLTD_T}&UDmk_Qooe0K<by^G6&W8I!I^)NZ>pS^DXY^4~VoSl=-4I3Q6`^6G-TV zfB^(WgDKb$8gytWp5lrqSekiAhD>v;C4dBP;EqLOiml+6)4)k7Em(s+ScElLp0vTX z48k6rQNYkiqJ!8Yo!BAuNrt`HA!R}(P0@rk!pA_?Ds9RdUD${nQmPz8i|vbY7>C<p z!*WPU$N<1`&{ZzH(JTM*hjX|DNXS-hNR5FF!*aNXVY>m%TY_MKx{(<NQiKD$0<|EB z1vCuEd6=&1i<;wL2BC9|?1Ci7giKSdB68rYm%-E^fESRFhpIgX8pIf$1%xkhRH8cv zaWFg#)75UBmmnGkz_X*<3a*gdx+I-T!7bb*?NP&}SRdq4z+l!Y#M!m=Lh(9QEQN=1 zFg!aVB6~oGZg9+%IhiJK1+v4JMhZr1f&$Up3xPock@OV1h@#*kMPS?tw^;-7&<1i? zq?URf`0$t_yGGW0jja$(z5Q6@JznHZUgce0=51c*-9h(MQs_;>i&Ijxl)BiO2g{W? zAhK4%n<PSPR(Jm>2XR0K&4{me;9iO22CvnmMo29r++5kJ4FS7>teY1*3Yc?nhD+$* zUML50kcWJ`yL`hi<QgKuu*ZIp414qpd;`O=Ttw6=JH7xyj)k~k-B^+Z%D-S-lSSOZ z?NQ@3L?_Hr*&2sf*s=cA27F-K;3|w>fP|-2v%YaVD|)V2m=kTnG0hOjD+1o<xSY^L z%z6t|Eg(^55l!IIJ`?1MM$539d|oM@Vk)j;E52eZt{2B`TxSJYu~bics0XvNLCCNp zwdCGoeXSrJI_2Wgd!WQ-hy{2>FUV+PvqOj4xP)NfI&<L9nxjM-w8Q+%%X&$<>C(cX zedA^2E~@`jqnPyvwbfFoG-Ep4TqrC;$XLtQ0t`(SFPv;vN#<fuHd!jZ(SI<mzQC=T z16)N8E|igzmf{At3m8WH44Ekc$g~-Wxg&CzE_kqqxKSs*>C@?Yxp>fq?#P}q2m+df zhcNsH<<pS$NQQ***et$gY|dtF-eztt*oGBCh?Q6*JX0g(LD|AL&Io70z(c2u2Wwu> zmNhNu1)`8uT#gl1BD7~O{$^6{<`r#ABm_L|y5vY^$7T>k`HEh7C<l4qhG1xhhqgF{ z8E1SUq!^=*X1FbTyV90@BKNQis_6&dk{83Ef?%wh4ZTTy_GgxEX_tO!n2zZkY{TmH zLH_?d2f$ltnciucb_aQwT(T8lAcDhx=m+jHhj`dGz)%g`vWIRUxWi+(CA|ki0^L3p z%a-E@f3WD>U<;2dFhZPXo*rwmE^D(sYqU;lwN}`{sA(U}t?g20_|)hMUf6gjNNyOe ze)#3X-N%2(GKJ6rZK#LA9ND!#Y{X7%#a?X2Zfut}R`kMA!!5ghm<R9m2Y*2aH#X1l zZ3fCXXh-b}#~y9cE^X63ZPZTfjLq0g_GEm{<asbWm;*!Au5H`CZQRan-7f1pOrzcY zZQu@W;T~?{E^gyKZsbmG<z8;)Zf@s(Zs?9~>7H)tu5RnTZtTu(?cQ$g?r!h?Zt(vO zZ}A>)@-A=lK5z84L4;dx_HJ+YesB1WZ~2~Y`mS&LzHj`_Z~fkH{_b!8{%-&eZ~-51 z0xxg_KX3$3a0OrR{Z4NOe{cwoa0#Dq3a@Yrzi<rCa1GyZ4)1Ue|8NiwaS<PJ5-)KR zKXDXKaTQ;27H@GEe{mR(aT%X+8n1C1zi}MTaUI`r9`A7<|8XD>av>jbA}?|yKXN2b zawT7KCU0^le{v{~aw(s3Dz9=Yzj7?kaw24KF7I+L|8g)7b1@%tGB0y8KXWusb1>I( zHgEH?j!QU?b2*=LI<Ip(zjHj#b3Na4KJRls|8qbObU`0<LN9bYcXLEfbVdJPbVhG< zM}Krkk90|&bV{#uOTTnXzj8z0bWZPdPycjK4|P!=by6>NQ$O`V&vaE^byjb6SATU_ zk9Ap}by}}=TfcEs&vjkjbzbjvU;lMr4|ZYy^jj}>V?TCePj+PhT|lD0Uv_41c4ud4 zHIH^_pLS}mc5A<OY|nOW-*)?cc5nZ7a1VEJA9r#ucXK~?bWeA6Uw3wIcXxkxc#n5^ zpLcq%cYD8ge9w1%-*<lRcYptPfDd?qA9#W<c!NK9gim;dU-(()c87m>h@W<V+xCf% zc#E(2i|4<C!}f_Q@FG;)ekNlm6xny)=8}KuEY<05W>(0RX~rdM#=Rny-)_eL<zAld zEKq)VZPv+{&-u=3(zf)BNOsttgwIZ{7-l{CwNxW>K(D5+nDFvsQtzz%Yx=nMb$ft^ z{M-6~{Pm^RQeL;0a<EChKHOcGc}Cp2UmxeI|8>BdI&%n1Umv5f&v~#PbtJUh{DTLr z-+I6QW#ZI$jhFeKTx~GKhk8JK#ZP?3Uwp;K2gr|n$;XH2x}uof<~tN<7F#;>L~3r% z{Lk3G=(3~BWlGGChqdItwKV;m$LYZg<mfsu%U+|m6zeI@zc4O4{tM$JV*P9eeF5e_ zNS22?^nGl;TmTll%J<IF|NMB~{OF3`awxl*cV2Xu{-S0iZ}0|a;QsCZ|9<fI25oQ# z@-Kh$H-ClsW}^4bRA_(qe}DLIe?*vn`k#L;V1xTdgifdhYe0N}sP}K+zj@`#-IJ$q zA;X3aA3|h!58b(Q=+F`T_wHS{WU*o~3)arvyo?vmm5ZoyB};h+`}y-n&>Kxyz@FiB zrHy9BfBg>5o7Zw^%ZV1rkt6629=vPUV7a>1tsTFNNGYOANOUX1i}w=711giCwsFp4 zW%EUgSF^I?l=|aW4xPe_T<^;JI?*2AeguPpbBZloH*@4l4(!Kw;#a(m6^4x$Go!zF z%XraR%S>F)fBsySi}(2P!K4}Sp~h9KQ>|LSP~+=q5TVx5ThW#OJ7*80(s}!oc?=fp zn!Bn5D^fH!@2g$gEkjEtNRDQ%TD0=z`}QqgI_}-Sr&|Y}yZ7?x(kX8~^lMUc;P!!g zA0K}F`rzE#x34e$u~wfD0hr1rxP*g`Jp+-`m~#;^M-f5pxYG?Urd*<h7Lddej5NH& z0tXs!G*U}4`;bJ?f-C9u4{!g_1Whiev;y8*$=GrpcC^^y3QgV+MAwN7GWQoe?Ql~K zCYY$91}xGz(+pHe9w|*bOpP^<dOs@kRZ#O(M$kCgG!siLzEHCZHPpnCOf9XHNsT(F z0OO2X11Z-}KUg~Sm7UVL*9|w*+%nBH*l^R0G}u@Z=wRLdfHRM2iiw72MDY+*jyck- zwTUB?kkSe;nDK&&C7<xpN-*MZMo^@ZHgwNFru~CjIJl7V9~S_kLQ5^Aq=E<=h<rlI zYxoG{Sv+3V#;QD&4)l&Y`y|5)B!GMv3ojvEQlS>vR?`iHsy3)>mJ<;KjW@2u_?<1Z zu+t7Z@3!M^yzRytZ#nV0a}d7m>|>5N?Zl+uRteQpu)zl-Y%sA4*8>}|^&Dspe9MH= z$*+eXf(t%D35+LuNhxEBDO#YB?Qq(Zb>Kg)qO6Tau~-NRhTU|T?1>8c^iMgcn1UU5 znbGUcJ%0To&pz%3LrZtu#nOs7Di+OZiU+o%3?`NTs8Izb&@=;$*F1VQk2lc30*y4V z<dP&Tuv9Y;I!H;Xpg&IsLkcNvszXaM`s{<4XV31Vk2=<>V<t7M1Vhd^igk?Tmj47M z=q<P4b4`Kagro954P%Z^H`V}pOE}ncvvSnpDkKvyt&p;bC9Uwn3pevHOPN371Otqy zlx%_uDy2(?x;#by)6FOU0f@*dt-SX%pXQiz3@xhw_^TzWz*Era%KC%RHMLv<hlQ~K z6HLo?`V|w(*YI))Bo>+yi!}e}=9Sd<R7OrL#t?&@G3!*LUIW<?0Sh<|Z;WF)3iQST z8|b6QY$<{g+|sgyVnGQm%Nz$O7(D#p7js1aNEwGn#Xro^xE}@OX_qiXGp<pV6~!YS z{0PfA#$gYBykmF+8ON8B5e!INV;mf_*@9w%6nGHh83BZcJKj-{1u_LU3}j$W+L4T8 z5ThM$Q`SZJf|N?Y;u>Cq22va~j+Dg1QT9NJRlFvSr*L9AF~O38g7Ox1utFKx(8sgf zu|pn?;~jD-2OyIIIKeH$7q##Q59J{gkKJP)=D-IstkF5t@Wo(?VG2CtVGoG?<CC%? z3^K4`551tS9RK))-mcM^&x9p3p;^{g2+|GVP@){45m!(k2987Uq89O~(!ngXL4(n$ zB+jTsC?;XBpu{bb@i@md9ubUYh=Yg!7#SKr_yIj0mct(K(A<}_aSdjOtc1|KpDLe0 zjB2o>9Pqe`0$<`mn8YNX`qT?Q`-#6fqR5{D9VkHwx|m1?g&a)bpiJ%n4ssl{pb{16 zMeN9pM`&Xp5xfd-zG4re38kCPB1khHF%Cx}YoaRcrz+P$48EMBp1DECCuy3MehjT2 z&_fCXUFFhOp#!HY9cmZhajsnO$WiBr;6P$xr=Y|nD170|%AmmsXOJVPDIMxWD^itG z=;LjQ<Dp?DxX~H{l7~qFt2u<Y9ImRAFZ1X}IFLasoWdiG=CBiAV$zp>bTq3}wFfq) zQPa1=b*1O{2QV~&n5<kRD+FEt8CEVr5MGdiek)6?N_+W_P=w+z#dJqj@08HPEGw2A z<VQd1F^N>v!-SljXhr!kjz@%J97Bs?Q24PWkJ<yOu=K5Q{-KRWG$X5soh?Dx*p6Ye zV~x|1hX(rrRYxU=x!T<>ckfZKd(`3(=OES)yE_qd%;O!}2t+KjQJjh-)+@OA$0cHc z9LbuuLH&S-D%hd3p!$QecA5@6iop(~WHrAZ%N{f;F`bWYb)`rVCrv5=4RHWAvgTC? z5C2gMYLp|J=pENe<#CaC2vHp%o~eTQi4kjHqaOI>tXyL?7<?S2#r^z;BHm&V?OsHc zmT={a6<m+E9ODq<DA-*8W-AmMg2SPk)$vLG5sOQVgDJZyvP2_`j&6>_6_4nLAS1lp z0rQ9$@noPxbPQMFafK=7K*u4D@yT_b=pt3=1tj`$QWHPWG5$ENHmv)|6B#kh>+r`_ zc6pZoPbVJiP=z~s>gWXxm>d@N#+FB8L~<PI9`WGkiR_3DeUzeTJUro6$jXXr{DX&w zc8-?jQIEQ2ZnL9VPQj3oxp^EEORD??FvyXT1ySl6l=#Q0P-tr#-r*Rntp}dD(#v|3 zqhj+|vLhY0Z9)gvId<#^Brfp}eq6~p0p`)9<I#?*z&YNMx^|So5lVa9458zQ$0K^d z4?w4zC>2HVl>_<zRxBZ9(*KwzIh=FEco1V9KqaDM^b`+o<iZuu7-zt56V!e*xEtOG z7{wp+7HVW8y~uKm9ml~BeK^7$JoLw`N24WqP!f{|hoC$l77lBakkzB1R5u*KY+?Vy zR64_x9X~sXx$$M!wysB2qTSkR+dPu*ut)s%ZKXiprK0!XGb6EXo5R4PAN@rN{^ad; zXV*g<=6J2a5L$D*_~RYpppZDy=;d9@<1LVAMnNiaq9gvJ7!p4RqUC{<c8nsga9dCp z?a^SG*s0?Jr_05i!3l4qeezQ8a5Y%5ZQbUj<m=JdJkE3ub9~0^cz>}qAa?1;XbByZ z3`ad&g(ph?If5BS|4~fJkqBMl>65Q=Xu)KUmw6_+ge%MQm;aFqNE{ixnjcC<-*FC+ z?K{A#CrUzj^bBK27wm6eKVGh#RVfGe?sxf0RgT-?uW!F7<Z1>a7#+#O^N33+Py`7b zOC*{<oF6(Q(D)I>Rr~`dz{0CA;9W2f1TtIx4Moe{11so5TM5yE*wHz-16W~~^Q{L$ zHH=-=gZR-}B<Wtx1y|H9h$``dAn45PIR~YL%F==0)ZN1*gu>=foBUaut%<`u3_>VO zn+fWl9oa*_@q<M~R@Q|eauoyyHsC+7LorN==&|1y&L2W$Pb!3h2H_xAD2PR1$dS?9 z$~}hvp4pZ)4I!!FMW%JbD8x${{ni9R#Ddv_fr(W=30gdm12|ZiWVqpIT!dd--pF;2 z`gxoxory*yA_SeDJfuaeeW19J13q8_HsC`V6<`t813Y{pv&rBnw!}X;0`jp6r7VIg zH5*>knm{C(r9g}-w#2o~LzI<6^X*(1;?Ou;S>K@>B%+~SWK}Ob!om$v7}kZ(B;GpM zLjoZq7?PNq&6Yyk*&#>+u$|I&(at%P)HtMvmvLEQwH!tX5qvS%MZCp%h(q=mT6r;7 zZ~enM6hjnc*KAc@gE@mY#6yOeR~MB7*}wwm5hQ0RL`B3!DeS|{eVut#gcGrXI>eg) zJtmeH{R5&jj7D~sP*4&ucGqIjLT1qhmHmS>Si(Il7I$65)6|(bMO1eMnLLC7B48U# ze%YY0BYG)VMY+Rq1%nMO*KDy-H4p=~^`ka27dA%3wb?_I2_X}z1RNe$Gw9aWjZ4;j z#W<jY`}mnq=whDSgLA0@!wrp95(SzS*g7DXBGS}9zyc<m<vE;JzO9?4L4y!sp-Oa^ zFTk3tK@z3tgXz5kMew0nmITE3S~xD|3DS-y#+WEZCPWmE(aj>3_=7453lFlK4|c*G z_)9&ck+)%+Jvfv(03$TI#64ihs$C{a)Yg|^lyCjzLwrm*s6rPe$QeRqaH<6VUl_(~ z*_t^3+Q4W<_GHVeY$oN6m^J`W!*L~7Bw9Quo&vSqk4ywoxEmhI5pZ7R$4!TYHRWsu zlnKECCtRRpImTNYrn49x(_Nw>ogNVel%wFo=-|Url_gPViFegQDOuNlLWGbd186GC zKZt`N1dk;$nM3tlJ#-t~$yky-6Mg~-?fgSEX+tOFrgF~33i(-A0%%Spg?K2G7Yb*K zu7n!dgE<_+5#Cw*%|i`g6g)&B<8h~6%mccWlsKTnBO0hY3|KxE!@?PcvK-Mp;KWaC z&*t^R#koS+aGZPoh@M^CRe6J*6lq<c*F1og_dO$?R74X&WDU_=7?wo;T@gzp(V=sA z#VK{<G$;m8qNhvzLo!&x@TJl}oa7BEXO=)|Gj(QG(UD%n<T;E`YmL~6UPRvAmR6z^ zmbPF;&4YA`!ztk%qmhHVsX{qi#htilsj9@a)k7*+0y(ti=1J<{9bquiCs@{(5PhlR zDbzo#ovlXGr?o?Wy-LGz#UlPggEbl#`N-IC0yMxxh&s~g{ev&~f+n(M7=FdmsDm%W z!#gm>qqz!<U7f7v8?bp|fmG{5d<KtU*mFwC(<p*0-i1`z;vH0_xPqYK+yhmX1VV`@ zeO-bAdXTbcNj%s?GGG}$JmOtU$3Og!0$rnU>Qlr@?8H)R#aitD#0~^sj9Q(w7SX_k zJ~dS>o!dW@R5jv{?Obfij>Tj|jW)o6I8d9&hAha!#ljlHGX(33sO-+>)5=7eKC;MR ztn9@SL_Z*fk|2depe)Z?tX0q@CNSI5Qf$cb&<L7?_q_$vs_e`%5)b*p{D7rrq%36s z8#h=3KD@<Ocm~&MZNzp)YLM5Si0#f&3N5t44YqCGQi?Qe0<-O`?R;0AA(Pm$ZQgc9 z+}T4Y9Kw+m3(HDu$Tn5rkpnx5pVa0p%TnzV_JTXq&d2s_PaNq_F<jwZZs}I6skRxH zU__FM!(8DTSEvXi_}jmwUNq5Ph*5|=l-a{Fgs-YXJTRR9z-om>P)fwDQC4stO&OKv zK?5RMDxORjJXqCEfay?ZY_zI_iOJi{bwerWom*LN{N>!nESIuyNl74zpE;{SWaiR| zC!PoyFNoTS21VMX!Xd<{m*%Pd6^uEkCOEVzZGM?Mpu;1Wg4YFGk4B?Rl#~J%DdGVu zm!WRzIi)z-8a~KqEleFq4%9HF)9zMqMKMx6AlEq@OF9Z7py@`$wPywMQ&O<QDDZ`u z`IDFNMI*u#Ub-2k0x#LP!ly1|L2(#-mcm$h5Dm8&NuV4fWn)2I1UdABHPjx3f};z= zDLzaCH^|sTD%L-cLNL&e74Mih7@d>-gOnkZ6<<XE_C(*DZ5eH$gA?^aAfyZzYhy(X z&qsW!9ZS^0o}bYQ77~lGL`^Vbo-sJwnTGNc!V;QMR$`)FFEh%Ty|!6W76TyD#jT#8 zLijPx9xISw#DN^i8Yx7XCTdU|>9T$*7Pg!_6oNWb<2aBUvbNklK&1Eas7lo0?onF; zN0VIH!+zS8t)kLOP)ag<f`ZDMDgi?>9~(<t+dXL8cWGz~UYk4|0vN*swT)k`36bo| z&{o+lLX}019-{$zD&#T6<Y{stvmbGO)*-~2WsavR$u8%bDC%g5JBY(2fU#tZ;uDiY zI~Z873TwO_5kIV*unHYgOsO|$gN0q`+Z~Aiu_lO6o$9vzL*e{`J5<EEj$R<8#p$i7 zZr%e`b)qHV!#uTfyn2^CR8kCvBTE1u@O+`W+B7uV+CN~Z|KeLU_h7+54!su4qxPXR z?Wswf<J*lIpQ-N@0*MKQhdi;UJ6m-r`(U(HWie-CP>|yzh(o2y8>W7VAe2RQnx#Uh z(*MANsAd<Op;Ai`!@@ms>J`<wB&1gHZk7hsL86U7W|&!?#8UA?Dfp2Nzg<?4#6=q3 z&M8QPBt>0)BqiSumxRMKgc4hJX427upt9fII`jLch)f=X2DNlD5+^x;mg0!U2{lMi zG_qL7o1P7&HMtz^=5y+mQ8jQO0|nLpRi}>W3OCaV^)V3j3RY}WW$GgY5tq2iaJTJ< znwu)k?Zi4tKm6*u2`zN<EP|w2HPk~HVXW9v%6h(vJaBh+dj_srm{wJ{#MV%>)`D%F zLwaj15mTb)M(os01Me-zd)xPTd(eJ@qTg8T@QA}AL`{G*ttxFog6h)6ij#*;0;@JI zgInwd!=F8*tO}W%EMs`n76d=@pVz5v#ZHIXu>&A;Nr>Awa4!Trzt+N4Xq&~Pzy25U zCN_G-+9No_9G2X4%!8U$+CjS=q$$*|8r5&MnL=cmdDd>c$&II)_cK34)1jJ1s0jPn zkvRB+BH7lTG3Go_=1Nnx@CF6{u@ERYs)U38GgMNFIP~d@PTe7IFi@kWEjm-d)c8US zEHz;idap0;X+;;&mnqC|lsm**=;JyYIgG=&XVqIMQCq7Zls$9<JMJs{eMM!ALo-}L zIheAapQRS=WAJ`qP=r%>;D(NOMNruTUUzB2t{>Y;FPDDQ30;ImV&q<%@3xV{vw+pA znRH3y9K@WtxVXw(dE^jI%0DQ>vbiEQs*>F*vqVT=D5Qc0MJYw=)Huwfm8Y)WA(vYX zx}4I*a)0Qkb21de19Z((NkjU)Pbf})!kv%%I6#8=>@HLakw2U833(@fv4i6cDO4gw zIdCDWGlWAItAlkZMz7!hBKE`BNHifndf>gqNKY~tUaLQ3>$Nw0KL`qqE4tfhNvx=} za<CeuPy#n}J2tXn>0G(39Y~Z}I7s(sFHPkkh`P{K#g*N|R-U$FXsI^*(3hb#dNUf2 z+-$666${ckjDHeoZ%&z36v;xu(CfUU)K)pl^3I{zJm3UBCm0xh8afDIRey{sHzlVt zhq0~AmN$eQ1v^A;8(sz{55+?%cne{UOPafBco#jPPiD@syPmef-HJOlQVKI9^Jem5 zo&BP-r@9fwL&f+*tJa$0X!^M?h&SIuzlp;+F9c4(a50Dz+i~^O1NYOAp(M#5m{Lmo z483sH+BsZ85YgQKluuWGdFsJqBRz3pRdcd8SXem#GE~0Js99BbGDOpbyc0d|+qK*| zWMapsUYg$+%kM7=NycCV*9lPyDbReW3K?fO1kaZPy|OtrUK>v@Zo!=9_S;rD`c~mP zM@2N}2?K;Yf%3?agZJ;*I(y^d$wP;3U_^-%DOR+25o1P;8#!8>H?Lm5W0T&QvuE$# zJ%Jy`{WGNv<-?9MH9nljZ(Oig<ND2$DbJt3g6)X8gI5rpN}5Y67KDe+*t&n@Cf-B$ zPn;`n==%L+`c+=ahyBh$<5ciozlr0}Wy?m+oma4P$Bmn(kJZ1r{^kixIgcDZYvJ(y zo0oF#QpEEAKGw5`4V&S`5&e~;^sixJ%>v{7BX#ZH#E%C@{xgTp-e#sB?bZ8d?-00p z^*#!;iPO|he*EOB=J?RxKW(e()*k4zUomz^@A>on9D4MMf9KhQXYP*SlYZ~99QR1u z?%vWZ+MGA8*(G@Id_oL+uk*TM|H?g_On&-3rwG@bBbQbzuHx|~7iYZT=RN!`3eY;U z#384juH1WwH(%5t=P;!d#Auvz+}Xz$ea^9~ulMHpM=*R`%W%W|R{AF#Yi9fCzJIzQ z1+x}8>Wr6G=#!|idqSDSG<Z<bP{)B%N~xTC4mswZq?EGhopUZ}h9TbEOHxUz(CJH? zN9sENC&QEqvM0HAjtXkA`?%a_$vEYllg>Kryc5qQTl?pbZeBamrg+f1WE^wa%M;N= z=`?SgFty>!KBda}XPtD&F^4-vHQkh)f7qGtsQ<j|XFyk+`OhIKH(k|Enc^WQmt4Gw zM?!%*bVnXm_9^Z?R(-Y8oO?q2N2xebi!r1qe_dA2lji9MA7oVgQqFV!0VWoIRArW1 zvHnp8m4D7@)*f^IndF#x;_0^Ahb9dr75a?*(jQ01VJuR1R}EB~E63rdO#M1-r<i)m z`OhDH6}I!uxl(HFo=$2ZXT}U~A}1I^&Czzth7&}GC-71WFv4=|A%-2y-1IoYf<FEK zCsZ@ZISHCdyz$01DH|sFRcExKHPYhr@x`6Gkn}ibb1k&TKT-7zCo*}6MVdQj?GY@T zdZ^W~Gg6Ytk!p%6vt;8gTiZCc*%(`y%ZL9t<`8?DlvC<v9;xRX?vM^}o_EGEB^Y~l zixVkefLX}tqr+Z&vjFRX=bl<Z`KMw=FJZ<mj`uFss(&s?#-42l`Uhph^rpI>d%Q8I z7&X!I5~Z4NK50BI#~RQZPM|rdAc4qXs~TVQA~Ed6P8|B2a%f!g*}>2xmhB|}DhD5I z+NlS_I0gF05^<bkT%yjp4~;v={sHF@ac29Hac|MrnszBWOHWz4-wco+ztbcC=N&Cu z_QoIUc*a!7fsTYN3496EOk-&CKDD(6FkuqMIf9}<hx{XBrddou{Lv0oxT7G;3tLdg zp*&(#qaVE+NM~RHi>V|qB@w!r?ojiSb6Beu)$m7$jKjEdpaU-|Q_4q9<h*`NZE=5z z2R_2l419=CAY=QU1?4d*TJQpF0(soG4snjz*rP;YYm7MH(I?8KCPSyWL@c5N!|t3% z9Af$iaP;F1co4&N1)L%k`A8E6&Z8XJnN4^8BAiQ@17XqAk+JU43sazjg7WwuJlH{u zf2^)Kj3Z&Eo&k&$ipqEYzyvI2rb5QGj2xIa6_Q3Y4_1H!CwWs~UEHDntD=pAI`v2q zZIH;g#<as4_{g48I+F}qWKn^W;sr2DxRUC?V;&L%32nkiwZ`D%9_VTfH96xCNc4gq z_NZVI-}pOCXd`c95g5Vp7!gJG5uOoYO+Czou6e*CXX{FaDMoa<uu;ez_M#Cw$N|8p zOvM`!YM;PtG@pZ|#dqY;T>)$7F@j#Dg;SvpTlS$Vf7~#E-jPR$%u$z>po59QB-3`t z$-rPjlRL^hW;yuSnQnZdjf|P5lbpd1BfV2c47A5cW<yPuIBJd^+ZprDgARYaBT`qX z<Uc@&p+g}so<Y&-R=L_$uYMJ*Vg2eq$oh|<jKd$3NJT%)Rn`;##o`irnMZKSDptGR zb*ygn8+gRg9by%PbnG}-0qcra!`ij1W#u3{0ZUea>CRe-CF@}+3s%Yg<A`RN%4B!g zkD<B49X~W{Wl8H*&YtyN*{B6hS`wUjRF5$B!0Zu6TUy&{HL<g?Mr2M@*3O`U8=<-F zaKj3e%furnWStE-?f{NIotC(y&8^npR@BL!hZ~T{QevY^S<Z5{C2JHMS<e)}XUJ`? z-0kjqzZy@9P=_>==n12o+6%t;lWG+5TP$K>Rhbb?9QH6JIroDyq<oJY+R$BuD%!BI zpu;ReSqxg$L5*`%NtV7mPfJw0;arA;FkfP6@d&9~-o~l_Gn6RD9xd3JO@O8$jT!1B z_+b*-D6V0wNew*iV3N>%=^f;Vg((W9B@)Z?AH9HtT-$TRXRt#*J#_Ds7xYHizAspB ztP6PT5~<DQ>?Y%I1uia?p-xru9FW5*iT86*w2;ahu=rW6z&DnDI4GfHxv;SGF^_X( zMu9i{M@Qpw4wQVPdg_BBi3<s}ilyWq+}H&9`Z%dpVDX0niEoWh0@N18$y~ANba%|f z-+Nv4%kSYwy~Kpe3{9$aM@ed%aIC<E-P%r$DaRzbQ5|ZIBfH_bDy~^|)N?M+T<b7~ zb@D}QR>j8{KY~y^paBa50c~5(M%3-R;R;x6MZo<3`$vdC))#I2%3QjV$GH3&Bh+N- z+?qO(U<P@Zt0W^_?2h-o{*eqHCFLZDJVd;p8L)jL$|P!~k9qnf4zwEl;CND(HXy-` zhZm$DL}`bAA{23bQCT$8v<JG(@j!H>XB_Tm4<GOG5AZCnKIvEoI-a7`#cgt`p(2%8 zpy7@9C6L>>fCV&+B<ODBg;y4&(74snO2+&H8`kItH*MXWt64*R-H}IUfDsI2QV}bb zxCc!G&L=2Q-Hql-MJUb_4|;{kq*VM1PA(yhe*mnY{+Mb(r~-1odqm`&nA`*HVTx;D zubLJNFP8XGkXIQaWh@3?!U|FjJicmXceYvo0aI6N2Xmz#-hjrO1$_-){Em1Ee8@Zg zkqv6-<wd(~jg%Ma6Tx(2MOEaU_uN~VPfSW4Cpq6Brb+uczikqIqtHFzx)6A(>m1D> zay$Stt7i;wb$^!#d$}*x*}QEK{FseD{8sUPbf383^;|6Mfq8g%FjQOt3i_ps(Byyy zLl`CHx(ZAG!;-Zh?BQm#f*d}oC4Av6>Y}#%&$~k7ABKkfPQ)>=A#0k00qc)gm<Su5 zsJG<d6U0HdF3`3ng%p$lGpyquq~Q=st{z0NvXsj;daU@?Zy}Ov0bS6vYRf0CLA$6A zuu7+~aFD&U&zZgt90tK1X5=0k?%}lmhn#FB$(9WB(BV_e0h0i2@`Qqu28i$eA)`9a zf(YjyTmc%WqAt+E7o=f_?4ploi52>$An;+ASfuI@jT?f=E@Vp@aEhkl$<nY$9tKJ9 zC<pCYYMRV$o5HIX$^i@A$U7iG8~&xB;K3H!i3l$-Q|MzJo`hHqqZuHfAJ}5$>g*v5 z=pDjDFZk~I2neF84zQ|W*;c1hD#3+P#nTqaORi#+45KbUWFO8$mTpl&HtJt|p&hEK z9@=38mq!@!BTlYqFla-zdgMpqsWYx&(pWH?j^S|%@t?kAr$WI;;GrJ2tQic$%gD(l z`~d_Zp&7nJs*EA!atafPFis}_1zj-1THtCb8lu78q!ht%94^7)0LvEEf$v(;jgW$| z66zl+p$u)&^X_L<ybu%EiY<c3Z-Q|manW}=#211AkSGRfgehPa>Mu~L9-{G{JcAj& zj*r4_DrUnR`lR@54r$C|kZPe5?r9;o;S#iA);jXjyd*5bi;djQQ!Ht2nz0_i2h@-c zkl4asP^}J23UCMr9#kQZ6e>Z$XDIA}D+$UQ6l`~X%qg8wDP*f=#Kl^w;Vq!bJ<?J^ z6fhfTA;>7E83@BrM$HkYi2}jsDmKASsBBU`0W_8?J4&wo`p7!w0e!{+9u6WHh>RJD zazi$V9OmZ|<e^ahAsyKN0gRmRDT%N%;D$b^@*GD|>AnOfVj&pDVJM2hNFWJ5_^8c9 zGxX$aR_LrX$-*pF#~sEk8{{gULWt1fFqk-yE;Ca<U<4b!uN%Up5i89zuAwDM!^hx> zcVGh?m@PMo>>rWlhJqtK1f?@dC-I0-2+<Es+#xmsP#iR29FzyT+Vif?gW|LySSn>R za|%BVt5cK>X5!314Cp=sGzZm%9LUfchBHL`%sCYFuB?LmSV12OA{>yxF>H`R!-}k) zB}Vq-8gL4^J`}Ht$wv@Ltsv$GQIxC74qjk};w%n9Ulc|;#xTSI5*%(G7^?tt)VAtT zs0INXiY7gTZ9J|2368*{GZJDlKcbfusAZP2Kpm7Hd{gxVgg|8F9cpPG$|3dm=!RI2 z8uY;(`XTBnhC9KiA2xJ0`hgd`t~&cD(l!AdLhTs*!5bAQ;O1fNXjHq<DxN5WANs`^ z7=j&Gp&qiYG%>L;&?*!<K`#J@M4EFLm4YYS(SVdgz@!u>7pG;$ft~DO^uQsZevFUo zO!R8O8}7mvb|r7tbD_$#^@<ZZ9}P35hj~y$S_%U(bEHl!DD3Ql9MWg@X!QxV?jGPq zwtC?aVDBsW=qBKyGG!AO5E3bNmE}B6UxexyKH(Jog-yIwQ=sq?TmenE5-sS;T=N8# zO0{N?A}M<R<z4H9RdWX#+9CmG^<MMjA>3|gOo9SKquKt|PVPwq@xdH6K^zViVee#8 zUhI4hfe<e<V&z1}$^i-I0j@$(B_K9qZ{r@4^dD@29r%tbGS*j0GfvTm)$l<!>2Osa z;vaJ167-H328%1E)Pj&=6=4ArFvE2ENGzTcBE7*EmSKm;L|HXVHu1tBq$M>*OzyO9 zVY|T+41zPJtW#DYa6(~X*tCxTV>aI55S-y1t|WBaix|P99Uu>(9u*TGrd;?09Ks|N zw+5alq#x459Du=+R;OpV^-T(AfM^k6;)yy=WR%E(6;$pgFcm+%qn6qMm{g=XQp0Gw zgHKog5+9^tVnQ_xRpK9*VH5136Daj@j4z}_ZW3z2<?PEUOP3|;0d9*y9*%-^>6USq zL{FOm7hY&usfa@A1rpjJAuj1Z)S`18k0{6?X|=R;1;Si})|KD_q`Jg{yaNrZ!5ySU z8acOH=dB))0Ul668VZQYWFpd5fn#AQS)cC^kD(L10X(279s4LA4k8wELD_!JcP}v| z)Gic|p}$zOj{wRWAmLNmfuQ=%y@tXv+Cg`)t$n=^76ul>sH`}$;Te<>AE=LVTV$?e zYcOa5G%y9^0LdOKfw|0q1zp!q8z^ldfngQ6X8GYCVgVThh^m&f_k^^xLR2Is;SzfP z!7vh(h;8sDv>_Irp<t@2iNVS#>>(<?4Ib#Kio1%eWUJe#ApuX6i@TVtAnAM{PYw%^ ziJSN;P9*9yL2Kr(i@B<-%Ap@VAr*+k$LhGNwnH2S4jICujQyCde4-aF;mP2kGjP<9 zy{aCmqczB35C*~L(9&?*=8eiS6J&v^UI(5Q;~<`a7@UFVRJC&-!aBMwM1IFONHfq{ z!W~f7;Rq>{d9~$4bQ&zdG@iEVgpV2SAYK@vcuV&r;^Ghd0897+mfh$t66_IFA>8Pe zWq;)%9tR!dKojf;ldE}77{wb#!INXgo9{%n*kKe*IeyCdn^6NE;_MER@JQJInNCI| zO;urlv<Bkn`7f>}6WA!*_*qY6>l(V?NVO)Q>G_!L;Sc0MX1haV**OknVH9MO^8`9k zN^>lZ!W258AK(EDy_RCmVHCna!ftt~WN4f7Oo;Q#o#V_B-oZ%x&Q_nH8fJq`O4vC8 z2_GIIa16!oQsPUS%VZd%ebFJDa$yjdjLKw&9BhFY8nt-`_!2kzA2dM|=!1H%)+y#e z6{JFsbecR!#vh=;4V=sGyrcDquR|I_tSk3C{s9?e0krnFa~s1EvSygvc1g~s3)&(0 z-daJHE*9v3$pl+E{^w+k0ekX{s)<mQv1btE0A@nRmlrC8+94C3VH|w_u9&%+9H1c& z*r91MY04DP7X|_K5{9o44IZS}9EzqfTl=;6AjD|4Z0mOnj$!I(xO+ju9x%b6XNESW z%qrqg6&xXl5&N-QgyAkh4ldcZ6$r4{VY53MjQp-su0a#HP=e!0t$iUBh;B^58zk_d zl3-~ZX8U*Hcokj>dfZE>LZJ|jp&aPxvcab>#-SckfeenJHSWc@-v}R60f+Oicbofa zpTZR`Ary|mAf`LjBFY?$0T*OJ8@}7UP$?Otffx#Eam~9IeE}ADyH9O55V?UJDsg7W z_jk=@6>wn#Zw#fAM5rcVQm4+Sr|enkK^ruo5;`FXPuvwf<rz%>0T~9Y9v|7Tc;XUr z0ba_H$!)NpNGBZ5sVAmft5gRXYC#)Xr^+3<iaVpiG^<m@Tu84AADW>ZfT0$E5zU*} zTs|R2qNa_jm?jUw9VTJ?CUnZH<HvL15X!LywS0#tWgYmjCE|R_OLH{-!5xnw6pq4b zyLBk!5nCVvxA_RpM$a37(C^G;XuQE@@{GBCgE|BQ9)f3hBwUlyf)eI|0v*HeuA(%8 zwW+Nv7PR6J+F^cw_lKS=9F~j?6+Ery!CW9Qkm-rm^E;(KsglTn87`syba+eQOz1v+ zITAdX&`=+Ob1Swwft<x3qUHT`WiOn4acl%fVk7`V9r^zMffll*4+|B@#sL!6H#W#| z$KlB-{GoNiq<~J{*r9_uBFz-=A&|l09-4iE5#1cP0X)Qm+rtLVyp0@`jVy9K-Sojg zXC+la+3Mi*A24)8?#sP+gci^tMhv#%sfJ0;1xkW}nTB;s!2~?sVMg&uq~EV~yx|g@ zL7X=I?+o3J>*_q3VHF%>5`uwG#p#jT3?aWm8+zi-Vf2ell@lK1W!j3#L1xf&CC=6t zxvoA(MO5nkff_C(Z>Bs-{(%>;C`F#Akn1?E`-B|C;W7r|k;!V+;0_)}q9jhjkjd*m zVDX(zp&9zB?u~w&sv4>N#uR!%n8fxTYV+ka+3^7Xo*h<)Q%}-(d)6!pO5@^B@}Tx! zf~YJxA>3P9lU)iMWXmncfgiTFTgPtqP--ynfp4#Ni_m9+#$juHHuO*A6I%l{-=Wf7 zv4FBQ!CZmJ$i%J-exU;8JFY<+Dt0ysj^LSsZ{`XfioxM}*c7U<nLTDs4gwa=Vk=Na zbuPNb4PI02!Y$52U*WC$XW|*p<1u6wApYs|b?@D|bNBAaTgb4X!-o(fN}MR~-oJ8| z%#p(v4jVpl^AaYcNU|hJk@wJ{t5>hzu|f01*(1g5AG(nybLxDEa^X01mrVVG_wSH6 zfA;M4+{yH$$c5y{{Ug@xpSEU~#KD`V5@*x@uVBN99a}Lax_MS1jT>iA+##0r=7m&9 zwr;|CQn?YUCl%|zaSK(}wJS2-KUlE5dHeV5**|jL{P`P97Uwu|<XGu5=WQG(XynXw zrAs+1&U*H&;Tvbp9V>V94tgy;7TrH-pB{7cD0eAsrg!JD{1@t2xsSAX{fqZo>{6+w za@B)p@6ffON=Y}*iBfXZa>Uxb8>j7&HhWyrZC}rR{oQ`eAla*D&fcVB{^HJCIJ^DC ze*Hvs&ojZ;6IFRO`Q{%<DghW3CeV08PCx9}0#8&o^|v5J=b-ZrD*L$O4LX>>vYbkz zZ72~+Dz&BBIOMnnjy)-=n3G|_wDOPtIr!k?5l9N!=umJh-E$v2EM1eEdP0_j(?RA< zXHO@g%%@+IE8gQEIqVo?4?N}k14%O}DWoBmXxeDbKf%O;jy>kgbDuj~?UyD*-bMDz zI#H2Ro;V#cdFPN?_M=!Opv41Eh3!N&*`N`jr4K9blp_^1nDm2?c951O*KQw;^N%mt zptF`gc6Qp3VXa&j&so-l^UqwWG9*`07=benQQ}y#T&)ku^-niZ5>-nm=CCABs=!LM zj+bEmV@fY{0&DGdYhKcfP4oDZ$|SR%329XAgm)o1_QVp)IQ;M<n5rtZ>kT-c#S>sZ z#f0MzIoFnT&Og~ua}K)XK*I_DWB}HhP*QmL7|ur^RpZNF<H*%-n3hyk(Lb>!^$(|z z-ue$Xhm<3lMVq*KtxEG46wD=TDMhk4ELq$vIYjN*&#V8$cTvAUJ4cso+S=9<$@C>9 zu8;}!b5B(45c6ed=cqeQJnjm5XF~6i<BTib*t7Fg>|D6?ouX2sPKQZB<BB-m09fOo z45NdOY7o1#k1zYI)f>oz4vWgi3H^hOH3kL=scqlxC{LKAEc2_vX7S_BIHm+c4r=D~ za|k#!GdpNPQNe>RJCEJuGhk%}9g$?P$1eNqwAXI??YR5%&p)V=_sBTs<OilvZ`!ka z?#L&P`|h*;`|NVPm-mzZ?z}5+{q?XjZ;v;*Bo>c9M6HufRLob8{rSl6zNRnwyn{|Z z@Oa~jGar|4KKl624&XfY+>K8?19OLK=CKyu9WQ?fq@7`KbCLRmV;UcmO!*R+zypdZ z6sedM{Qdz99et02Aj}@`;-QT(k>eizsLv!a7^eG$5P!SFOF!CSi$;M&9@@}^HpbBp z>b>xXwsRdsSVlmsh@)F9sm^thVl9>AY#mSQmhS+Qo?101ew=UyIo=mOV>s?wFwz^} z)^d+{cmo!>*kV84H9D01qa**YM~C<^Dt%arIoC2wa=OAl|Ka0rlv~q%!ex<eY~p84 zJPSX@@d$BfLoW6IAWkTD#6(q*PAb<R#y>FAvT<ml89%9_5Jx!?mTAOlkVH)<YVnVn z0j^10Q_nw)fjWN0LsZ(@&)HNIOQ#u3LhmD2G1_6E6TT8lz<bA}C^ip%6znsmn;V)? zLKJLZ<1s!NRW|<NKCP)LOesrHY<$!sK!!{>aUoehLbu6Hl;csBq|2JHB9Dsg>L16L z1V8wfolad69o1MzJ0#RetHnc<q)ezoSmr)cG{YMQoen-H@s1*iZklEx$}pp{katKc z7Jt#@F>TbK!(ako0rG}CRMC!ja1>bQ5EU=7K@Q+KjU4oX#+%r<wR?!HW45`6s0Q+m zto6$upAZNC;XV}(W_*NJ=bX>TV4|#fgy|D1i|0cA6^l!h@mBV5N6GkED+h&*80;7r zNXCN|e!K&r3XSVRx}^<Mh{K)|?ZzSGQB{9FjU4{qhB0g?7qs*O68|`dwGv_&SYYBY zS|Z;wfbkf90jq$h*rwm)A)(Jqh^K>+3sH~}j!14*9{MQ7KimP@PW^)$hb%{McB7wN z+DNLk=tL{^6Q))KV{+EQr7P-@q4}8O5LKZL9wFtAr+K3t!#tN<E~7(K*;cNL^{G`J zaSz4HBPnr0u5fHNs672+9nTOdNaPX^pLy4>TXF?x7(%{v*rKvG>C|-3;hKFIBzXHG zhkVKZ@hWd(6q5cktvq7t4)z`7y|wzsH3lbJp9;r+=(+BOrh|@8q{2$<y-jY)aV>u! z1QNZNRVwe%iB!O4S)FPwxl}O}0d@Btkl0~!M~dB*p@Sdy=;~v@s={N;$EPuNu04#w zr#>w!EqAppk2jQ*&O*Z+S&ND}pld?|qwO5~pj0=@bQoA9t{;A7sz=U}keK?T7MiVC zt^5%tRMaFMcj4<jNE=BFw<neJKyE9QvY*!;a=DNSj_<Uwtb`1w7U1e@PaTAgE=|p{ zxCE(Dd+fR=ox?Df=tVhLCzo^BBcJ`Kk3G_alcYdqD&08OTt~eMP?|GMEi#Zd5ET#q z8leat@!04I(X1*_se>B-;KxB)^bdnQ4IMki5>D>2k#Lk2NJ6a`oGE54!-UgQ{Norl z3{)#f+M^sLGe=Jhld*qTQIX?l#v|-;P?ex&s_tOP4Ht)woUwy7midQ}-_c_r8k~B^ zBcPbbgpLmJ4j$;pCnb&N!h_S!et#7QF|<Oyv$zzMKD2o5CMXYbbOTY;K}+dQXSRxq ze0CG`hp4iVjh5L4EoJ=W37PkD+m#PMy1@oF{>Z$Bqm~sEGa%1<emi+=(h^R$UrVeR zmzXo%=dHwND8MS2dw`Q0?!J2Zc(+J(m63W%1IHb9Yd@DWeRrk12a_MOI{=CQ>aaFJ z)d9thK!p-<E#~PK5m|CvaKy2nuw>DiD)bl0u<Vx3xI{eO+FD+k<x6MGMc91Z@F&{i zCsS?@O3=eTe)TdQ(5M95<mP4npk%hzsK+1Y0z7_%`EsoDGkb=0$W2+eANJ@7jrbFK z_CRtTsR%_1E18mi@PZbI<o7&!{mF5lYBYj8#;z1+`KWwpm@q=&-+yP%%5$1>)8&RK z#(~1ZqVpb~L&~Z#iW7IOV;!TG2a2XEJ-NI~_k__R@L(`nghE_%4*hUm&v0(9SA5M8 zQ}5spuK^?KA%JJ(3}LfIttWbPaTjkCd&D&tD&bMSpbl|Fe2@|*yzpE9%as)V&<}Sb zdw&Cfl_3)T_Ya+L41~lG3p8Tzau)MY9@?M{?LtKFgh4wpZ4NjXIN>PJMIT$_4}Yga zR3uI3M>!j$F8$ztKsX&NRtuYRC6KZv#lQ~x!W_Y|CS&qNgAy<E@Jn&yG$<5c?LcF) zb|<CAE|XGI_S7^6@-^N-9p)z_wsAN#G8<u{HV8<A+fir909<!rH^|Tq_25&CI2gA= zAOCO%$s&de@pR>IQHduPbhJ8ub1U<ZPw!w3F&1FxfL@$2AsRSc>artHMM`{EL1Z@$ zvCs?R@I43gCFlTYZ0B}Y7eg`f4`ql=vBMQ&(hF~ui&$qo2J;X9i?MXy5nYZVjkL2C z<RCFghj1yy2_r%j#+Zw?5i6BAI~_6*4Rnrt_lcySF|Y%4^58I)xOChIJ062H!(l#; z^ADCF4hpf4Fqc^W&<m1h4zpuCBx4ThRy}){i*UCXla)e%<wIo`3vm&026;USbr&Sm zNbCny!+|vOL0&e}gy<4A8ev()hZaJ{iaq5-hv5nsvSX5=81rBZ)xZ~)b%|p!UD{T2 zelr(NV`aj)fg6$#Yod-IgF@~|ViDFWUe^$JaSskNdqO!F97c>RaZn9$Rg!~ftmbv| z012@mM?6&zCSx7DrIMEC9XK;sE)|p(MjkoFg<W}t+u?!#z3>S2U{4KUT=uYbr~zYl zLOvBz4wxY*T+=g`0Fg?_G;=5wB?4J=VP1Oz88C?^MA=~aP)`sBAS2=mCNh6#iD0~O ziwlMh{gqhW)t6#n7|cKlWfUxYg%8Mp4_iT-VUbFbv|Ea~5ICYERN02;5GE-04rVb| z!XXoupo5_!ZG}=gcGxG{VQNtVS3=Z);2ECcIiBQMo@QYfSOE`xC=%fH4}$~`<{6*z z8J>Lt3_lqazUP5Cqzx#fe;G2L07{;wNe&Q#E~9Zt@K7!_wM7BipyTNi;}B+)_n!%Y z6ea~(a_FEM`g%;|RM=)2qM{k*uolF(p(fg00>=ygn$mzFF&(`b7bkk6D>ez>kRRE> zA`(Ul2@<0x>J#FiLyAcxaS;l-6*@fXpj*NY&p;;_VuK2I2_TgoM>?hA>32Vd4(jrG zDmh*MkbI$0NtQ=^<e*flP)nc5P~=d3TxgvRVh)IcGynHj_E3kF#XEyCRK9QyS%VWc z=~$2zZKGIiKLS-m`46=)F-M7lO>$Mz09>{r9QJ?>;eZ}s+9a7M4@Loes<|rvKnX{o zoYN(5_OMUyl1isG2>f7Cz_}9$dS2rLVGSWFrr;*t>6fa)e~*x2aAj`Ca0g&zolx-) z>`)B%a4z}fpUpH5!C(sLa8TUG9t~nfumCpy<=|^#iZhI{4i_ReimD<bcn`jSYz5X3 z-q&oEpbcs?i0t8kyjf0!N<cBP52esI{341fVi?yz3DFlEHy92ecxx+p4{JiCnh6ng z1`Jk(Q4IADtFSKTAWC4>Er)Onz-N{V!l%Vkh5{mofpHcINq$mht34G<R@D!)YEL^V zr0xlZ<4{{mI2H)%4`mo2T7t3DMGj+9F-r4#94J}?SP6>3dJT9&b=VF8Vp&#L8naPA z64N)<$1Kqb4X^-Bb%K>I%c|^&9{qp}h!aWfRu-}34*x(6$VQm0BP8tBsLR!A=y4AC zFb&+$63nuy5rGr8A}Z#<iAD-CJ7Nj{VUl<#@?-yy3*<M0P8t`-a0olnaCBP|f%|ID zU<^m=dmZamym$#7BBf6uvWd44rAU5k1~Q4ciPR~V{y~?F;UzFqw*vdIjpv#Rq7whY z2_}L^8d6i{5V@7rpG~qB@lXnOv{_cWKmUN5Hc_b;YhgXoo3^n#!9qY41H3WCI#?1W zz~F-raTnzvd%X#;3zCWMIY|~35n&PxBL+{FCq?#<tJ60dLTV(nuq&R}lusk9#ZV4+ z`4B{;4fT+#Sfj3U_L0lOJkx~^xr)ELV-Yc@KID)Jh~So1_j2VkW9@J*3(Rwua|yw4 zH3+AVKXgFM6Cefy4b;(g5>#3LM1fXxXFnp>c8NGK?*Mf7^K<5k844_s@Q6U=^C{MZ z53?dRCM<I>QVpaq9{=KzSNDmI@TmvMJogY6)_^$w!on73Kf-YjiJLSOH<7So7?j{D z6v=bS)>W)Q#pQF7cK|wG%Xdy}7{#y-c^7hRr)=`}7xK`-0*pJ~=~HwR43K~iagwyA zdI+pko%AazZ+vO)OBZrcQ;)DMV0*P+5w-IJQFF1#P{Adt06#C~t!MELrGR^;+p+yn z4pOUm)ta=F!M12|IO{|>uQY-Zs15`)%IyJ8yx?`{TcQ?m7XI+I+v~l*fw5~cu~G%7 z5P`40@;!v;vC{JsUu(7h3jtmYJPCA$DnbGo{xGavmc2H3IggMGT7t}+>&b4Y4PU?w zp(IU0Y7c4`m-f2Kmq}p5S`HEdAdCDiKM@O!@D6xp7LBXF8S*cFS`G)=fg*8JfyiW@ z`K+{YDx|_pk=ziuCLxuOnySo%Hkfs!m0=cv&`VJ<sl`nP(Xpp%7~P<+7R$?b0S}<! zeb)My7FHykFbU|iEEydp$q{|)`g;6e50`KWe{s;foJ#$02h{1Z?m-vdF$(Q4P$xvr zD6t=lc6}LA&eaPPLQM|INfMS43X?>={$W<}P^NbYZKVWl=pYV|a1CawB2n?CQpl8< zoS;r^Dev>W3OCaKmjkO3(IJl2$*!lohqD@FB@sk<57a;lizH|F`VWFo6J5=^snpR| z?H{R>w;Ex{6k%145Q;*Qtnon~wb~G=6mf6C**)z%<D+g&sc8Oi35X?ISl!H}CWQ5N z*{qus?~ula7tn-qQ|F~g=W;eIQ%~Gr9;B+<zhQw{M8Xiq+*a#E{vbY~ajfle5c{MV zmm|%D!fXbkd4fpSLc=g`1VJHaTL&Q*()+X<QofGhs1%_RhVek_B+T-h5Mgo%8Ki1C z5hlr?qm$hnBs(6DtRL!{YxTk3Ls6VE?R|B)5862qB+Cy%xSq8gyPwQR!9awi%@FVV zEpTDWlo1vGGc*j`kT{z=5d{pTNhrxX0p68>QW;&L`yvkLpbFOzV8Hzl1r)9^g%D>O z5i0S5-tbG~y&#=q4cCMou>0MDs}6Ze6rb51|DXs;WfD`}Ka%Q}Pfi<O@(<2{n3445 z58)4np$J*E)G84srXbXBoh2fpc5#xD?2#w^Kn#2$AqF^7j~8#|5rF`l;dNmfpR1*p zJW>m@GxadBn?vGc(a4Ko48{;YTQuYnan9yZh2;GeBe5^L1{zGFVXwvxs!&XMy&Xh( zd$_0NTw^a&n^++`%*yMp`0%jEOA%`^4y;fOe<9>|-dhx=6M6PO9X;0sKGXH!4@ga% z@tn;661L2{EYB)o6M%OfnoHrzJ`bTV2r@UnwBaD<Wenrs4uY-i`*Bx~%r1jY=$`JR zfY%E}IO>Wn5(ubvc#-Qco6z?lA@zKRwv`Z;YYOX^+rS;I-rx*WYh&Wlgu7x7Z@irE z)9zTi5Mfe+AYp1w(Xn5WdeCq+8VKABGY@z3F!(JIYrzkbBFbh?7APIx15ObOqg~d- zd@#<s9ZM9czy?VZ7dt^`|L_UW7xMuKZ&1n_d%EI;GR+3EiIlzfS5tBOEV_a81PC3G z5~?&YC?Zuu57mH(RE>&AQv*^3F|^Pj^bP@$CLkak#L%l4P!Sb0^eUnvqN2IH?>XOf z?!9Z>AMRhU_g=}KJ@a{H=3$a$vVy*U6g4-rE{_`+LrrzP^p-RG6dxQ){l~NhNr>Dn z?31$P);J6QI>xKJ>UT$n-?=~s<i{lsIqJi$-`U5_`bWJN&vxrrfe!1i{RxZMA*o1R z!p+ef!LEB!O{W;Nop8Jl&JSnUvqV44CO*{`H{w)#qd(_MV)KA22Mq<*=&0_Fg-#z2 zJg-;R5~ubmb#>8ifd>0x`#b%mjvs$c*xj>dzMhD48ca+%`+ioKA|=qnih$$wpCWki z2S4hsA9s!w6uSM!!upiellQVJ0&fVYY5V2ba4wrkWCVF_Q&K=kOklf$?{E?K%f8iD zXEPW|Pkz&5s1tl|O}UyvqzXUsXX;h~UtbpK27@`p4c$o}yL=Y+GT)#1GTR;{aQw24 z@Ruv~maNfVeL+4<{m}WEdFeBEi1;i4q3OqOpRit)J-{x$@N#IFJx45F$s9Y<w4fQ5 za<4rhhO3Yfal%?0aq;O#{qo~~en^|t6)FbqG=A(n#=q4|p*CgaLt8c+TW-xY+B$BF zmpxo0Ro~EJ%s#h`S;_7DBRGHYj^o9KgzQYwnR>~uiiNAU3luK>SbB6zd7pXF_oJd- z!rSvzGlLHEb4Leme_R;P<4*pQog|_e_%JuZ$i(X7IroC@-^iNaEuGMr-uVP*S2Kh1 zz44dUThR)yC=oILKSECwZ~L8KIXrdaKII>^^G{40^wL>3WGr{vw*R<xaOCw*g$e#6 zh3&yD(JE0;@esPEp=f@&G`Dh6tb>VokT;S`dXTj}IV^xL|CVx=^Gw(0qTu}_6}cuG zJ~728R(?g14@1*X#255BS;uc%^+cinsHsJ3^B}u*zDeG%q5eme7pjYc?%jomu$}kz z=)L>TAtvX6-`(@|Yb(L-629`DUQIz=;j%(^^b>Y!8~(weM{<^|lWXJle+>!w|7%F- zD|BR|h|*?79v73!dn&}a$N0S~3~bhKiar>;ZvN0q`K!CZqy5|=6CXR*j9T9<_>HvZ z49VE;ntxU0!a@BGsIq3vQ)scoP)UY?!_8;0oxulR8;*{hbQu$$Np4>h&8aNCZR=y} zaZJh2*57O3K&tkMS$W1uZb1vJKNS)!JH1&sH(CD_w#3~|d#y>>HJ02RP|<6ysDHWC z5M$aZ*jOR%+FJ!}djN{GEVelaHu>19#%q##e`s#9&#tehyeJ>$via!Vzp7<wn5|69 z@dp8oAYpefl1p7frTym1;0rZF1qSs;VGGp<Un@=papk8K9C;U!C@C>Ce_kQm1DyAA zkbZBq*j(i>@C!HPczpTpR<2BD8BZv3Wn$&fq8iA5J<(&3{JkOf?rmQCN~u3SLL$C~ z`PPo`FYBw~xvgf?Zc(2$vNHp>kJ`BVT%C6{do;)8DYH=D11TQMy6q+Ev-0(k;DbEr zml8>5P2IX%<O+_7?@@bJBrdo9KrcVo2284>S;AK~C4A(6t==vXl3L9(X_D;x{Mjs~ zs`xr2_@;d|^6#<2o9yGBq$fz;Rf!8!^@=T8MWE76ztGplI_sarx#R)~Pe#N)w>%$S z4Iw&J<UHtV%-w0dJ8j(W!(4yzx%l`(a`6e5@PT~UKOcFtCa!X`)k=#wXbwfqUV0p2 zu_X2n9esAYufszDEEeSxeQM?U*(pvL*?k=3>`p@mxUo#~fMlYuJBjADHjy4#iyett zIi+T4fO+38!4boee;C$25jl1hAE2LbKGXtB4Ia|C4CW5TRYt))@^r`bk_|-rL@!Uy ztt=UHF)>O?N~tF3k|6Hk1CEe@BVs>Zw`sFv_6+!5Fd&bHf2zl&O7jakT@bn3D<&-v zDRzNZ`d^1!ih!P!ApZifw{eR5qiyM_OK?}b)&(xthA(bGk(Q@JuW|``mg9f!P;TNP z1;pTPm{)YlUZZ@IZ-IeW_YRZ@(X4+!VAozcV*0oywJn2yHu{0(*4V~z<rp@~vf7eY z++vfT^|SLX2@lbVVtE=5400~8KXlSqOnOkc;1sXQcchb})XlvY|HJ9JR%C?GwtJb7 zv`CB><rKAaZeIAb!?5T>aMrDVi$`9rL910vJIa~;i6qjHX6&-L*hz{giwRN&6egqt zD55L&P^FEMnl=ThtmIw10-deY#*;PZxkLsl4@(xUW7Q-PONFNFkA}De$|P6iqt$Rx z#@Q{d$0~;}_(t{R{EOYWyobhzP>eMKzD=lH6g3eaS(L|*P?HQsldKH`1(s_ci!ZF1 z$ZPR*-SexcIB^4Y^<Pi&)tWD<uWDec!oJ)OGajl7ZdGgjxX06&$iamZ5%-sa)I8XV zF7=9Yx;kTx@~J<eC$0$93A&1~H;pncQ;1C+o<~`cjqxXK;&kI1k`;2L6G=v~=ZXwD zJrAUbK#jXj@@}rG(PKsFb|@_6y4~w<nUVot-&&oT7JPfeLR?jfoBS`F(<?*3?a<$> zGoBuAnz0yPQu@;5Yy;}XLX9@dv@1%%4C<1A9~WK474CHXA;|q!bsL)^*ci&tjn?lz z@d71ij;bcx=jfj)ew5t*Pc_c5E&0(>($=|yHGvTK1pHjpYt67F$0fUH#~re<ETT`c zUMEAWdL~DkeN2>@CFRnmy8s?z<Fs$<eXxhW+&ey*;$iXd^4uiDaF(ZHIzG~7Nmpg) z<fW?{Ou;CrP^hJYFV|)fm*{Hqi3`p*<C5kp%`N`L#Fk2HaRx(mqYD?d5fL|tIi7vH zx%}svcs}}ML`vYgPYgp8=sr5@5`kI8>Kn)pQ3CvO4O_iuH^Ni2ue=s*L~&hb@L-Gu zDYoSzF)y?fU)G1N9r{^W{e`E+#8l=MC2rV^8=Mxi*1GDJ<){p6`KKv+yN+A@D|sEG z-P)?%2NBC4m>2}TcS?{S@I?DlD!l}+e^*T=b58G`(|6D9^5i*DAB_M0@2d=dcckoB zc_<<6cvAJ*th;OS@KbUDt6`$rwuu+ab-3=Y;{Go3RmsQfFhf%%)1=;sH~8Xj-@Aji zrKDCAiH$D##IXP58rRtM^P*pCzx1gc`&k(L?fscMIhO}~S|eW+YU-9fy$y4dfc_df zE&ZX4_Rx7`&*V(MkDA7AZ{6O*UFK{k$`B(ZFv~RVOhvfO36F^VBL&?o=t;g=CM}Va z<TnNsVTbW@g5);CQ>-@0&z7yfMEwN!3O~$q-X!*Jn#E`T4SIIoM`g)$y`D$AfM?XY z-BEWXC?@vwt#7wU24XcAO*H!(D&3GT)c%r<WV^PL2IWFdU&y#k4hUNfCO?!peU=NZ z{cm#G*;J(F#o*aCp7lhN@|*8I!bdwNIf=Aho^O)v-Y3$2FV+<;xjM(5bJyYADN}y8 zOc~N}4Ox3Odqi%(ZBSL;`ukt!`yVB9ht8>gjkCiWEdLyA@y-qPwe;#fLIt7}b|#-* z)aq2lHn_bo@JU=079F2-QqvKx626o8k*q#-0zDLlZtwkFNO^6neecOvO3vOs1l|s0 zh()!v9!70Bl<9%)tQfZ-Ej%{b&OOSQ0ns&}Bbsm=QE|Q+ka?vjBRn`?`dp6i8S6+& z01?`B3UZA|^(V%(bkc>oa1Yj^jj>=$a@50ha3)6wdsIxo&SBwJv@0ESI)_(SO&=6m z8DJ0Pcn`XU(++TlHY?~`eyF)WOzFH1wj{(HpM`E{_nzoF<xYk?8H*<F>t%jZL-EIm z7>F)bs$!%1+P}vf59PYD1NJ1ucmhx#dmT%qnA>d>J52QXeUJ?dvYOCmsLVCI2^sE# ze#fitRmPA2Xr4iok#LkPKKeQk6SUT6sHX1*gV@%CY-wOyB1B9L=VRY)eAsws55C|Y zb(z6}5DxSO*r1jLQ3f<nemaB%gO-W3E-h*W1f8>)iE7F(t$8|t$cTX_;%sr?t%T@< z>w|8u)p{yBCl?2A?;783gLt%2NTMblM9N)Piajn8YaeA26lETZvzv{%?;bO`2)WZg z6#9DT{*rNl5}dRKu|!2{w?(S7v8$7!uj6B`67hN@P}B7unQ+L>HIuNW;e=UZoOjH9 z;=pCH37!TrfpI7X9garW6&N5}LZpPK?wv}LkpAJE@u84@%{b8xK8qMj0*G=z@q<xZ zXQEx?qiy6tb~FQ08wK7)2^q)d`i+(=$7GB4N_t1zS4Jof(>$orPHo`JbXK%S8@Qhb zO2R-%^!Bj+_NGv?Pz&?sC5XnovEyBxHuOlEGT5I8xxnDi!$)<i4Y&&H+RYBN*pB7O zSd^<-xEz6!s1!HA+?5(V92)JkZ)!-4G$3+llR%a_l=~XVBv?$m^H@cfNzWF<gBfi{ z1L>io&N4V`sTBJlkRmO@hz6?cjJn(g@tJ{=Yqa}CUnJ<5-`=+{(}7ryM`{rxmr>E4 z03~!EqAwh6jfFIInyC6gZURG}okzEqCcf-W?0{Z=-J%57bi&lYcsxjBpIr?b?M9{S ziw^w~HDPw)eXz${fH+rXG!aJm2V$`J3Bavr_FG^_EQ?`jf7Uz*gd6TQ$e?&uQrI35 zSY-@gfPs9&0Dipuckt4+GWt9&`XU|7`$$C{2Qp(sT_X<r#YWpz9(IED*ufw~JcV;$ z67^;h@tJ^l1a_<hUuH&o$AT}DIW&Sm_%)Cvj$JM`+J1jh!YJClo}t)0r8F?5{Kf{k z3?`xtZDXx3#76rOCqwH&<}fom8b#<Y=mG|8!(<%Ke5LuqMl$K}%W|GrNwFtID-#Z7 zXjJVu$N_*TE}xhGY_0N!pgcEeygbPgwYH%ei#(!~?1IhgL3&saEy4zrY0TySn($&0 z0cQN;H?#q!>|n1gh*1`JkP-U1EuIA-;vlX7#1U<y_2!Ms-}92E36AnMmuX-VJji@M z%7l1ct#Z_{?TsB!jrweDojGk?3%1>lx=5e42Pn2}<NO!FlwCPnMwA%?1bzf20u&7A zv>zC9^|Ote|D}MWOK#DZoHO5s+?dvXW2gJf`o`J`9GSy}5p~As;;q`~yT_+)5N4up z%up^uJcxX)^g-7IZH?R+H&+=dqba;HJ5E!@ml3O<AQqw#<JD!av3uA{tY$vOIo+1Y z(S<P9au9CH9dOE5D0o-!LNI(^?Oj54qgi$4vuBSP4#-)(^hc+Cl^h8f@ABR`+(pN* zrN!^?6fQZv*O={bHHc|5V8zdjynhTfaFs5PtAuKEz-j5nulAvySQ=zLJC*7Gp}q6W zY}=VfK_A+h-z)q=C;Whh?K=)e<{R=SzLuWt%{<O9nC+i?qIEPs?bPg0^z3lv;a)uF z%|?~K@ybD!v)=i$6F+8$mS_8K#d=>q`Al1F;9~sCi!LLUb1z=Zdf$Zx*3b55*1mR` z`v9KnH;VE0I`wwhIqj*-?7*BspZY+O%O@k}`HPpCH{`}^XFo3Mu7Y(JTt03XUH&LG zH(L8~emUhi^`m#fNAFk8qCB6z7RG)y`qWn#yY<K=?a$oHq^G3#Pro?pc^-cHGw|u) z&8NT1S4uPw|B98rHb1dVQ&0Y4ontp<g6x=JHzp*2*u+i*CL}oonb2++TR#&u&E)*o zrj5j9EHcr8^E`)!QT2H~<9U9&c>%Y1!GL)o%Diya{E_l`k@BnDT$-ZOM6qq+ljeDe zu&YSH1xdLDDfI<u;{_SJ1zEQRxqyXZlm+>$1%>hj#g+x7!3E{%h2tv=DtikjAd6VR zMOC@Qlj@77j2G4H7Eik^ss}8dp)6`-Eozo8YPBqC4=(CVFY2x=p50qK2U$7}S<sVP z(pO(HFkUjWTQYK6G7eZWp)BF;=5ggqW-UwR$yZFLmn>J7toD}9LzW4G%hqx?ga?-{ z7%$t}Enjq7whLIkL}4x4XDvIFFFUp@I}I*7PcOTyEMMMRz5-bx3a(t0Te%jtY-7CQ zYPWL3ZN)8M<tAlCM194he8sb6#cOcIdwS*8%F6A%l{=7ClHjV3+~En|>RsbiKf6_b zx7C1v)j-N>P}XX2`Rcuv)sVr}(CM2F$tz)ds}CS+WWlv?xwQ!OwMgT&D7&?2H+RG2 z<`~LaY}Q&_`C5F-TEgI3;`Cb5%3AW?S_)*HD!861x1OfHo^HIJVYi;?wx0QMHJh@Y zleL~(zMj{zo<F!=Fzo?pp%v||7eh8^f*U1r8>Q+S4~;j<>^2^`ZIlOWR8Tf5vo@;A zH>z7U9uIEROiOLlu58rpZ9IW&)(dVn$Za;NZ$35NY_i*IcH3+T*raj60Lfn<uqyxn z%18hVB(X080E`8&!9?-(w4O*9pQ3H09u15HF#68;hSGrq;ZvTo!wnCIQZNSbqNa^y zBkA%Ns+~vDZe*))JB=2YJ}rNduW@%{cI0Wr`MgLeNBYjw%E^cLbVZlZCXY!2K+#g) zLt0-5@I9$9H`;u7Msw&;JAQ=!QB)jgGTCLUrS?NBY0+^B!`P6>Fl6(ij<r7d^qkD` zWeY^4W=7hn`TxFd#7;)Lg5K8?msNVZ3Z~eHmD--JzN8t9Eq9%X!o89_+?&CPivUe< z$wrY>sVdMWN$;}g;~lMEKG7pzc9A4M$CQ9H8Mio@dyo}jY-RF0(sx{Gvb3Yn#Iw$y zUzmI=tmYj(qJK>AL#G*P$^6I7F1RPAy5!%lo&E2dpS}o1E^Zxw<(XuVpgS`hCRfRf zK&h`C4mphF=cD-T+~=c(-74oPq5*63F&K*cLaa=d`$C+2dF4X9a?9F60(MY-F;Q*W zeKAR6rE)P@XK!sW1qV@Bq8bW%ET!VZKs_AXGV4p}-6N?`fCs%4h2yd{UFP5+t>4Hd zhAFt^xF&nJ<+>MDx#fA+Y03eX>awvo2tZ5JyN|0n=H9_ZHF5A4@QA@70p@T~>^=2I zxJ!tpvPcgZ#r0TUQOr<Tj@#%Zcmlt%Y(XAHQSpMRu&n^dQ5~;mjY!<saI(~AVbIxV zIdTSDba(aROI3oon|1VW?{Db!LA<sahUFe_HIA!qZarlfD}8QyZRhp5dB*MW=a$)k z&Cjh&iqdx5QkK_tyQ)gyO}z`ijtNS3#yHLQ+wTEX$G+g{SkW;yLIhYe<BU!4k7QX= zH%!RLzAF`OIAbWW`^OsPZd$N2fJjy)fU*&Om*7(O2_IGK4gE+?F9i(4WrbU3(|l!z z^#(a)U8f5Mj>5-B<iHBY&=c2=)O#X<wfS$8Qn~6E^=12i@^C;3x9r#n+^*bH_Fgj0 z5`Y?ncuPj?0vm8k<L*&Co-tY6wD+CYPp*$?mfO)KGFK6k?3p!L_6ppr-A#5_)A1l< zz{&aYd(k-MllmfF*wlF!G4D-g#tDB5y<7dVn@gF2Ry;i~8f?Gmg*+K(U#&d01Z354 z)OT#wK356Z0$*g}3SpY*zqdIdTmZHUdhTjTEe!PXeebbP#B-x(SVUwKfMYv;QTxub zu(l_EM}EwH52Wk;WT)dE&t-p_V{egT2eyF&&wqb*hKko__!;L~b^+V^>VpGli+glX z+XxH)jT^{$_yD$*q{BN*hiL7DqZ4VMWB49~<4%O|I1O@UxQFZBP9z3Z0yDuMcAM-( z$y<~lE)DkzcI-rB6H8Dx@qHricPJX;C0v2Sed51&VsNNZG%E(*FD3Fd7H?6?n?2kw zr}Z_CkXXuJfgezG{2FgRUMko+JfL##YXTAVQ23o4*RA8Eh<}x_I-@z%V1OyQN|LtR zo-Dl$>rdu4gRo}gdHo1w0=}VdP%=%r;qnXj=f~g*-n~h6u2$Gf7`)7-MwRFC(y1H{ zl!UVI5sro$>8TyFGG~8$*+m<J(Y7*N4o@Q0y;0^KYD~)f7e<dz8btY)sAkok=7pBe zLLo3FTJLzS06>m>L!Z<UJkoYNF8b*V7$^;<-S~GSO=%<@M_SJ{=;jTptc2|tOT|0H z>SH?HA*#<FcHdD~x;KBfB5o<T#6Ie&%u_T>sUVzXf%?pAHcnfO&uOrNoxUrb3Xs)K zNHGA-5-y_mjkr+-YN+Ba2L6JIMNYl+KJAAS6PwgOjv)IM@d2sC=(94OR6F}q=eoOw z<@*F|*i;QtCKD)FLqDrDMNp2|oc!Se$Y_&mK1a3_Df-<FNu1UfBwyffM4UA<ijWdW zx0)F|1M0N}{QM1&f2*P}qZtuy*o+Ec{Dsbri{bKb^kwcV>hYSsVSjU#0PA^te%vu5 z8!_*^q!DWew@C^y!{_-542yI1j)9t)x#}f1jOu($b=B<@E|ne*5HV;;VK$df!!cMK z8~Fi0Nq@3zMOj%fK9imN1llX@>eP#LVR0=z!E0kEf=Iw$M<1gaO^~m^f^SW`^7(@S z!LyoZD|VbjGp--w&l_uW*$$IGFrzWSlcMH^7u&;`u)Q%UvD~+ods{nP0y=3$e9aEz z?U+_T8ewMqOHTn>uh6LfX|CKwQ6Lry<UoNyVl4f1s<HvJ_i1>Bv^ZGjmNlR=m{c%n z63vg&I>65(yhb~P;!HI6hcoG1OX7aJq%?fZf?((V05-WH@utP1$cOzwjfsZj!0|=# zKl?*Cu10E%#gf#~U&DB-#<cA5B{}V1BZTC}j0%foMW<h*_7ja+t>eooA-~3mTu*a` zELKkD{~C9<dYbokd_}$U7wZKn`Dwwb#j4haUlTzSPm6wzub%z$>m`}1i3YV?(?9x~ z5o^^{D)eH_So`-RHMyzmnB}^e)9<OA?MC5~mSraaCMrLRDbf@K0ir}SZp!=X87Gxl zzPyUT5*Mn@40{6od2v;8FfP!^sPo?|rtxOsIAe?#5xF+qEoW1efJF;xOwNEtngjKp zd4<>XpzihV@!latx?Ive_fW2<Rrh`wKOKPZG1LVvz7SKz9|g_<bl8lpj2m+4gBz{2 z&Pwb{#CV6kGOnfb>jlWQMe>Zg<R1Na6WB?}aE?9|2rW#Kbie*}?w55NRavFh#=PK_ zN^je9-R_<T$0m^inriL1vlE8NX9#bMcIY60?wJ+oY(x{}Xn9!Ae#EdOZbx`nn?0^a z7TX}Y#~gxP2>mWL61k>`_`k6U08j$h*hK$_O$?L6=@Bq)5oZ`s(nmoY)lzQ5N%hBp zr5*c+iEMq*!l!*jO?_!296}euY~jG8u`KMRQP*FMa$~tlw@UkiPd$1OEntZ_9Y>@A z4-G8E1=`d+UX`1&=_Dx%D7>k<RBLymT0rs5A)D|NFmI`Gcxo=74AUZgrXzS3Mhneb z>*hLxzHiL^Z#IDxx6n8N0>KqKPUm9S$gmT(_#%t;#^te`Q(hm(+yBcZ62vV#c9(@T zWr74Y_Eiyl^4G?SEIV61e`veA`SC?(>z((CVMAF5rEOmq2cng(Oz5a@z15Tw-hZ#9 zzq2y))a%oP*Z`bQ(LI(WaXzeT>FwMrr3XbFRS`cC6vs0@rQLu3{D)1veEyup0w8Ul zyz6z3<&%F*3SACHO_45p|DF>piQ2aglDN$`y%GU_EPJ~69)?m`2;ZIDn}he3v=Jkh zp5aQvr3QnXLf9LYOAy%6LpA|o-+|t1TqegNG!M$95*98>7P-oNTa!T?WoPE-**g4O z$~>7zhsaf_trsFPaj%S$JH#}L($r`k;>oVpsxEVhw(MnQ-ku(rgKHjqHIe-^kkv2Y zOZ*mre6A4dnsDNMu6TSyPjE&-999lp7;iV~Oah|5i3B~M&g(0>#FE7B)Ys0?M9h*s ztL_~=t3{PgJIgxcqfOre*pHNeR(mC4(LC}(M!((Ga+f5-;c|urZ{2FgG!<omeALCc znsGa)e3&6dzZ8Zq<BeCEu+^83>g04PN;^S3IimX7am@MgOLhVqa37^s+qpkAXe?WQ zP{JNBBNuL3`PnQsqH6gE84d>M`ttd|6jzl2e(FiaIrh1us@=i=e1;`lL}%rXYKR15 z8;<v$WT@h99~|v695AaI8?VOn!q1#i%+K!5eTU(xAJ-;uC2m-py3O}N+hs6aFx0Q` z$C0jrcGKjay#(bxx7}AFzCi?=SKab^Gp^aU_TITy)b73aetiGR2ajS}gpVO6J91RN zM}N1R^po{D@Kcg8Fx^xxaC?6~R^sf38dc&{1i=o#Ixl2IQX)Lj@E_t90yrR?0}Y^m zuRcuR>R2n!w$j>ooD$ZtS^d07YqPQStoByZP~Gp(&7UTIf9ZsBcdZo(-8oqOmiL++ zO$P|<oAs@A_jaG0FYef7T)A?8udH($$Br7V`o#tnCfHiveDvhs@2%D^{|F|>FWM^0 zU1fWDY!VUm@6W;Gl$mQpHX;jxr?ZRHtHS&e*}>NkK<G8mKTosSk4npe?5Gj&E+$CT z{Sb-jBQZ-D$V+yKec}JGiFt?VLyt_yBZ0lx_<dV^-xKe;|FQ`-raoI<6dN5k!X^D* zHsKTd%j+Z0f7wK;GNj(xspvm!!aC+_dnp$O`~OiPz@ZA6V1LT?|572&m5c}+oCm-I z<nWUJPZiSmXe|50vdlc4?f<Bdm&Le9gjn@tirz^;!&YXrsp?e);h|ZfS+nBsIY8^G zrGpe4I423ZMsjbidH2-)Rkh1lz*?Dt!f}%DtLQ||hFkxG8@Q1GG5&02W?w9y(&ces zRYl+dGYeoWyB>=$Kl;CML;CnE7%d3A%M&{%oXBH91Ea3%{TDZGb=M=O)lerR=}11P zTeoG`A#M!&JGNnj{72)3Lyr|(J?r?fDR>Mr^uJU{U&0}7ba(ywzV_<zm6zSm{`}lo z94kKm{Qrp?|36iTEtesBGETXrtw_Qb*a7r#Fi=n8N#h-Ivd;F}^%UGcc~`0-mxpUA zUcAaRO^>}^$~GJp1?b;vbH5QvVk5`Mg63x=WiL^FUB1EoMxGGAm?XK9cWh-I$n_pn zI2MQ#eiWBzb*+tF5Sn*JL{D{g?M9FQtodefY?=^HvR2j^S!=jFb**fcGq0p9!_9F$ z8SGQNUO}TMZd8_Kc~;*-iso%pvp+)6i|XrGqt(?7qa6Uplis|?wY5_nk84nCj*n}e z33_cd3^#hB>w3F4yq_}8D&1;&ZRK^VdFJxtTP=)*dmF9FvRKALfEt2sUlEMj*58zR zUDvs&xVzo;^>@a$V~Pq5C}-|%PIhxx18g8Jlry#max4+s3q4a)--k3%{@TZH;{3H= z@MfZFKQb`1euyKohBPb@qx@}H?vBN`QMuO8ufr1ATfXC5GPDx_@aOS&<2rqG?@J7D z+z+P5r@PBAI+nCMWqhW#>6OK~<NmL04Q`!=nF@XOo5tOpJ8emfabdTVJ?J_;ZFs#_ zeM&DRDd0UOl(si}@%gPY)4nfj{b90(EFyh^9Ozfcfr+|xh#SZ1_7@V*Z0|2pO(yoC zqKR|iNckMvua#p3^}(>CconUg>nYtq>y*QJBq+SKZn6X&ius?Q%xc}A?XI8OA={z^ z744blpKkv;6!a;f-^QQs=%aYc#1EEUU3#Fgtai1yZKwavr)LYYIyjYvy6gv34oUw1 zg&Sd?)dv2aoe`^K9{k<^B%u#|mtWVm^Zxr47Nu1KRkM9(#hj+k_}Tp*6|#x^2+e!S z_TGo4xv_Y-H<8+Puzcsit3~mjT~PXm==uk|O)fBVcRikRQjqWC*+i~KbP-+<yR5t@ z=szmNW<t_;xM-GTcnWs3t3FV4jSS6(>CWBa4tpMQ4S7Gi?J%-PQMbi#+&@$y#`Pdg zyz#NdOKrmL3&NW6g<q71dSn;4qm*__Kq<q0+hW*+AP`;f+3?WWJSvAOwGZ=;5HZzU zj%>g$0)_Z=&W^81VgxZUNqb$v0BgzxeGI^#Iz;c8NTH!*_k1-ds#7vlJ9)Na-ZW!H z#jmM9BR|Rn+P9x8n@BhcyCMhe9kJT>Cav?)ura0<Bb*J$DBD6&#Z(TRvQlK_UD2c3 z`*;n(@AulbjO9y%E&JDbfd`9eC)l7C)_LhEqOrh9b0V96Kq+4>86s&;(3A0GgqfGE z{DZBr`g+;I`HEws!FkgC;wv_xOny8PAUyKf+e~NMDmOf)r8OE(L*|j9MSama=nOif z8GqgI=%sU>9oAX=FN(lsOaz<owfs-%l^bXT013T@*(1rfjRsE??bU-K_{#)JO<Gj? ziQd@Rxfyl$sXy!K5AJSVoi`()*kE+-Iy%utGKk>^$5n9aUickqW(VWit?AFlY*gm- ztM~dAw=Ln2#H$zCU=e&<&PyCh?gJ6Z%*#Xp0mCsf`=5Wm+_QD9#$Cp7tW1(2iC{_4 z@}*8x2JwjhGtc7?#i7W{s`dXAZ<?8yJF<LE`EHGqk<J))p8DzL+UU=Cr027Dtbv9W zr5b1RQ;%U?j>M<|R54Hwdw-{=&g-6eop1Ko?26XUc1BX2-&eb~4Xf;SS0|6<CUc!O zm)3R{WH_WU&*AYx2_MHYJuvqJTemLrPXF=kO6TTd5Dhw;00{sP(O3R{JM;X{8)-6Y z^9q|#+jBN!Y&f3|k>k`pozt#9QpjQ+?j+nJJpGXJV{D!?Wajx_PM<JU<%K_cf&Cnm z`f!0zBEl9UoLh@Sl1WMS89~n#yM3ZqV`SpMrS9)8nQi^e#R?@zHoVnIc3!$GSeQI) zX$PcgHj-WK-@w_|B6ZJRh1*!@0S4l6kN3e#VLyb=4dvN2-V;@JYk0>R>ieBpaKRsd z^p~=ayHkLz0*7nAg6+uVcXFMwSN?2m9;%Stk_-N89Q@{(<cW*Mc8^d#<Z#|AA3?(O zt!h1v_E#+Hrb;81H1I*~QIA7zVJArzWGp-`O7@R1PI6BdCbQcM0_^VAY;4XPu)fUZ zdbr`HL4N;hb}YaF0w`WPQo{6qU+XIhi>)NgZQ=yu*t`6_%rw~8uE;(OE4R4inSMt$ z&5V4JZL|16MrRv88sEi+{qlFPll|vJ>$9IpU+y0ReG&kIo^$VV-|Y%v1ToTj`HFTT zu%Yv?;QhWMey_p+qB!(rTiij(*W{3cMGSZQu!+^TwETl5dDi*%(MuEGvN{izu_^82 zH?6+seK=Urc-cM?IPtyc&%r8=yMqy9wOe}h?;8Gm$5i&jZn^f~bwWzV>k6wM)lPpm z>|b_Fw@&=13;DZA<nEjqvf69R|GVXWzVrRtiM^IcXYp@X*sQs4N(iiMJLqNS92?<h z*b6b>K};tTe1h7;Ck}`P{&9d5`wnu;h=bxxbVemp9_&99jc=Ver+&CjC!hN}IYxVl zjlt>T*Eh$a#%PSrZ-?v1eIKmq)ZJoBdH><zmpbidxC2S<;lM?{2>U20bstXi*Ckv5 zw0=u)T4H#U_@33TkR_Aiw8KI-%%c3z$1_sDxH36*W#dd(vuqfcBi=w{4h=#NGGYv2 zy>JK5vu7@I-!BPe{Q+<$n&Vfw4xWZ#-rnT>eGL7Uz`1}9WS$8_@{mD3Tpt3_%V_T3 zfe%36?hBfrnb0t?a4vv>$RLG{&^i4N^*k05M}>J1A_7R9>?NrD*N7iO{55ZbUkahd zF<f00WQ=v-0RS{mAzB!a{SNpInQIBh)mDM_sX*n|!^?2UITDZB47W&*#158Q`0YI= z71cvSH8WAVZ9G!|pfVH6p$G48MU9X+bIPIj$l!Yfs682a4+}0PagNlZuEPKp4xxG& zIt74P20WSsjjTt_65)L&h&UW#n>8K6F%J{tq2$px%yz(s^I2m6L?v<`(8+MN;4;GD zV<7XXuzY$ToCi6_L{-w@WlY4<4)-iGbe=6PwSs5cjnqhorBUI}W5KyJ^jJN5z&<ex zhrCZeyga3n2?`*GdQc%m24pG+5+odZw>0v*YS@D_!9Rt<U*F^_Bf=kJVCqEh`5n-u z9gsQ|)I>+U#c+=Az{~0b7l(NQ0^$1PxZM2|eIi`*H2QrIdU=?0svh-Cp7S9L1-4G? zp`!YkAQ}lFScRk=A}|4&kBJk`;SGldS)`^Q*#a|!;!zEuD;Okw|3BNcu<-OWGT04& zc%Rh!EG&8e28=P%y@X-+F`T0`)HoG&fgCz?6AEA<ld+-pbR>90Zt?9s?it>Be7KNg zF!fmQY#Yx{G8Yk^rNR~$w;HOpAG&xcTD}Jf&{6wngdLOPEFJ7khitBK+#;b~RHEME zkjXpTGQm9Wg=N1pQdmJbwir+z^};*hOpZy;cyi2WJ!+JZ7$gttA^ULXW%Q5`lRLQ| zsNBU0C>jI$h8|JOOg+{U?g9tWW4L}Y@>F~>3x|BdH4k+jn#JIpVjzm^;aNLyI-N5w z7d^^AP%y{{3|#d{y2>xaD-0-#fjT~nn$|>5Q6cO+DE7(pk5#BC1|*Q>o*RUX843(F z2`*YTg}-G+C|PHr=DAm~T#)QY$0I?F3cUYtA@(_eM<wq$Dui{lq8D)?^X^=Sxv3=@ zZ`vw1(Ssxe1>Rz~0&jAO28KvZW;VNL6;z<v6}deX&^$pw4yI`b(0ulu2dLEIj<{e< zd_I8Td`stCAl|E_!NO^<S`23wF-4I_Rx~@_XoPZh2jsj1I!nyn3Id<P!l%fbSyeFW z_Vfr-bTS5Xm7K%c2kQgCV*nT-7QWR)C!k?;Oh)>8;njPbi7?dkyTmOVY;uS5Q$1%d z26fl0q5?o<)R%CL@Xiqun)gGIBBk;kymQpbg?d^iYlKr7PY$ijpCThNXs`?%vJ!_V zBO|Iz;gy)U2WC`uNzSofX)ipgPb$De(Oj<hjOz&CP+86eC-RyhJa7no1x`8^97HR+ z4kWGSLWvmI=k+38pWuR<+{b<eeWm+M9pm-C8T_d=7;}${7R&RGaUb-RJL3!u;gh9c zhQ6r4%QCr_$As!KIKpv|Hfj(O0npKpr5j*k9`M73l@#ieh#k1DC;XchT2vn0m5XY^ zA!m<7OI3&4I-<V<B_PR^qxX3EwZi6b$Sfu-o(jvNLhP|%D`JxD8psL&#p6<3J9vB0 zT<Hw9ON_?PZOJNsK&BYZ5p0GL%L7{QIutpEo*v1jlEIGgIc8*V9UWEYh#s#;5z$Ef z^}<gh*+e2dC<oPE&qb`~^fRj{0uT;P6*L@diWn*969W+8t~kiy0L_pIJCt6t^}%y- zXr4bj;qsj2^ul~HV(2EUlz>RZAZ`(1*8xcQ4ty*dHkzII?>(Xm^KkV{%3H=^HUx70 z@WF^p`3faX7<j>00XD9>s=9gxgMM<4bF3oW3R%=egC%2{dq|uC0OZ-dq6=j3bWmsz zHc9Re-{KDU2o+k3P58^;>|r3rnYR~Wc)!Kv&(b30J4)r?RT=L>YlWV@JO&ek0WEZB z1PyVY0i_>eWBo91&L#MD9LRzI_N0UGIFJh(^;VIWf};+c0jKV?c4CpGXm|(~98X8m z(a3r;^jtkWgVE82Ll)!U|3(WzJ*EjX^c)!p>?9N_!BL5v+l0*OT%H9P^ui9jZwT3i z;cCJqDIEG72+&)Er2E(i8!vPQGe$NQHHAhRjY3qlIaETx-b{{STDI{RD$|^z^DaFi zx9RN;Obgu<Tg8z=;zY!?gC`+zj3%oO>4v$m`#@$76SYonwl}W`R77337__Hz5fQxG znhz5IkT!#3-3jbh(``creg44VhlPFjqC-+)H^$J(xITzvTozq6oC*nH)kA-N7=ECH zpw>M1!6It0DF7X*><sNUOUcyCQ19x9U?7Iyg}#q%ZzO}$m}x~J)vY^-s+wvY)0DUE zPmOER)s<mc_3&a`O6U8GsaWuJDx}*P`u<4fZXjQ?J@PE0(FIE>5k)RnqGlC?T7!8G zl?LDi_uB!t`~f%7;;-bQ!(cgc*{FCLtUYu%0SE6GB0KjMju4<lO!&<%&LS*$bEocu zB5wl?_Tnu<7X$WF2D2A}FJiz~2=FCpx>QdVM*}6k9{LnJNkxrxQlF<%q3=kX;cXpR zbYvD8adLDrMTrw}0Pn#K!>_`7=xJ4`j#_1SA{EZh677NY6h6y9hq%LuRM<*jSeX|1 zIy%Om0VM(;A`v<%oMev+-9Az+H3=EdMh(%Dbwk0v!EeqJU`%xCGdN^Ls8vw1+!P6r z0FW88-xduqW26{cOq*(FWHF%HdF54Os0;?;9wTvzfO2-Kxa?KYOKrCIN^K_~t)=J^ zlAMQ%DaZn}7IL`2jp0`S##8IGF;Ig0NQnGnA`WeE<RPR7NmfRaL)#xwA*rF0zc+_V zsn7XppNG&9Q&iY3QWc%tV4#_s?$P024{stpi6=ikt-zVTGgZA+P%HYXS_kpkbQ;vq zQTcelbL~|eX6h{l*7&%{9)Q@hFyp2U(Bj%8)P26ypA~kvY%OnaAhGYH88U#Dv;*f| z1A^ZJ5Mvt1qc%>T25Q;~EhfB&g$Ea-VM!sJFqMJYogT<MDohs@@SC&rNZuy^QAXrm zq`hn~L)bW@PgkK|oS{6}0YhCDGLADYGB|<=Be&Lbj_`Dvh@xIlIeEoCbdsJo=pxUk zAk=3<*JHrV^u!Q{+^eIgSpao+=3TB*2|$NdqFxmrO)p3Q&oeli649RaPhBf1I-bx7 z2Gqqq<It#P83!d|!J;8W!<Qn=#CZp`&<Y_ib=n(;xxVuZ@I8;dWE#{zssH-%a`x1m zKcD-59|wJMrcSd=bAvcT?GKv931R;Zfjt!AqBIjR*Zc|18CB1fKtzbAHcipt_T+9n zy_<TAk?sPvU~m|cK{j-dA%nvehYXs@68<_L&V+qJJq{<pLNEv|@vT2cM}Buc?-Ach zC3!TVk(FcwoeEnt&6py>{7FwrEs#ZuV`*Wd)mx(~?+V6iM^ot4$0wHXA&IY$fU_Xd z#k=r21Jakc@<#Z})x2k@3EuJ#S)&ZpV-nPq4%zq%Iz`AZ3Jyyqan72dZ`GyT`ka!x zmZE=n2`oB$bD^#R278w%!d)~~536O;KLm4D0|>O$U~w+Dd@(nT`tl=*XM3G-SQetr z5=CiJ!Br{@jS~zDDn|hw^#<TgAU`9%PfR5sG%s(Z0v~#;VDG3mD~YgLB6KCYysMVl zMTH;=VAsad$rGroolzR{Rl(+H1ex>RS~d6`iS{gA+Z1uD9^QpR1fW~!1<;N4xm)Dk zZs#K9%e<bSvbw0COG$6AUaNMr>=^>`9yL*aB;9m86kvSPr%hjBOzR)M>dXk&x%6=~ ztO*UfANJPI5?Qjve84#qq?H$(*Ia>v=|AD|r-z1`LbORkTVtSl@poFEI39)lY5T-+ zoe5F4PppPVVqt*zyM2()!DBS?5%GB{>F|g7OBWvzC|vyG1%6$RsAOSAYjFq)w!cgf zMrZ!51yB@HjDZ5@WAf~r_;S_nf;1cwe^AZA1M@yVH%^0|mp`1XScn`~4%!fHdgT_c zuMOk2vMxsf<ntNImi;-_i^j=fr^49jiATsJ@0$9nec<IpeP)F0g+b+9X&=_8r3Hle z?qrJY8S7Gc5T`(?QC#Wdy!;|QiI>gZM&?#-W8uXL#m*LYsi!waavC_Ee*Q3X=Y!6& zK|;VxRUY39HhQF@j7i1O!1%7CUeGjUo9f-#g-d2xiui8q)wdT^jrI7ht9DK+PAQK* z4T$4Ctz@&}l4)c#DqH(f&arZ9XF<!~^Q1?(dUI*BDOIf^h{ZOXwrkcZW7-<}{M+aJ z*6mA)Cw&A)_@%M!mTdL6A3@a>9OK=a+0s{uVmd^@@*b}8`JV0kw08~#Mbb}iAD-K_ z^Rh<yBzBj_T745wE9e!wPqvup7L@Vm!zB~-sR-E&tW=U)%e87n?Q0J~^y(ZQc^;NB zPg%Ynj3+_)YScTqJohLCFXaYYPp=@`Iy)_)k4h{Z6iHnRk5jB(3pW<IWvGvkyGM&m z_u{vf5p>k>9H8Pf(l$F@xcy3O#FvjNn=78?d-PP{r+l>F1xLwK9XAZ8B6*3U$`^Qu zh8@O&$^p`KtxjaVy4Ja5bFRL)q5^pyU?a~HqZib$#NzX);{l-}(PkWp>h<o|yCMf; z*NiNMItL%S_UiRRG6;Du<858j)<tXx4e*DB8l}q;DaIQR;KD9JN)OaPE6w-p5>cSL zwjFt)|2V*GMZ|oA>c(&_7=iLP+JbK6hjyDPi8y&n-4q8vbGsJ{Gkhp%;<0PU`ksH^ z5@IE<AIYdVY=`kKb?Z=&O`Fi^vv@ix-)WKRxr0d;v=lW>s?G`GiORAgltlBI)lGVo zR>_P+wO#W4^LfH4sPpMW!ta7%-k6Yu8z|e+vgLGzsi2Hb)oycX8<W<}WPZ}>k60l< z-D5>qsi^JFS&2H0jy0JMIOT}h*@iNK_lj2MSuzEH{0`0~?j!-OtWuJ*l*3+PMJ-RU z6jXG)HX<z;P+hoZ$amh*=lz`m0+_r4RJK-R9jk_r#X6`9Lr1-~^zc%lO<zfJu`_zB zLg78IOna$!*UiV(^DWF@Ruy=UI_%91WMq!WfUmmklKQWzJI!-HBvM}GEHbypZ!KOr zdA025`?Ss2>gu#iVPP}%R7$SudlHOWnI7xcsl_YOcfRP=<AjH9xp0UrCsX=I+!49< za*x!q2E&37=jF9L!+wvwye)$T1lgos<Jx9vH=13V>Ax^yyFr7Y#5V2Yu^@cL*P7;; zTZWT(WJ|Xy;%?AGrzewU=TB+~C0WR_gu*br3+$)#d-i2bbcLf%Rk}3?{|FcSP3O3& z82Kp7q5P!J4p?^ZHG(M5F3?nB_8v8_H3MT8o*ItB0aR_{*YNYtM+&#q1!3L=rWiBL zBQ6uJ&?zchfKHF(+r>Q7vbc&m&A}~vn}Wu|^tm%Qa7q9gRsGf5v<<*1dK1*jbbHSJ z4DJ=%<>QJ_h~R%w{qUN-Mq15!io6yr0<BWQCwMK2H<@W9^-sF15LTwugq^{3=*7BQ zcpatX<j-yeAPD`}?yRRil>1FX-ENaKp?J+M>gS9(e~X4)sO%pVOs6E~lnVOq&#q}z zXe!=NICZJl!i_Fdo;lFVQ_NbUNWJ#!I60t?E)(WgXXhE1eK&Gl;<1=SO%ES4{FTbk zHDd`(R;)DSIwC7iTyT(PZ2s;lDjc`;BZ$HU$b*l~;0GAS1JTE1u6odUVTyQ3rAz)c zxR!PhTGWAGOs4e6w`%ue0+O&QpGHMhI7JL!61!?)DAY${sz;>?Hibr_w=gkh1Q#>T z?v{y+k&VQu7<~o)H<d=qJiJsY)LvPd^wufAe^)PV9H_~4%1gW$$OE@iz7|vO1iBO< zpLD({`9^Ym{}+If=;N7aC6-?5^b3QGw=~r9-NIXG^oy#q>FH>Mh>LhpqSfpX+PVX= z+Q9*3i87mLQ~5mB{f!H163XnNm8OPD@(r!k%9Q9DP3rV+cC!g?SbYi?Els`}7bn}N zxcWyfcbCBF`1-gJx7uW^#V<~ROz%yfC?TM%G{^jMB;R#{qRP>?k)mHuW*e^cZ~+7n zwp1y>M>CPDXYb0o?TvMo4&T1mvzcI*lWY+{ps2?UpEQ#xt!q=T`dpM#F&DbUbJ4K0 z*glWvx<Iu6r-6}Fj%1SMfq*0eetvuxfEW-gL~uNnxEpDx5+2Ubu+ZN837IsaMy~{b zEgDc8=yfCNHT{0YCYYznE7)DF6yfgj;6z5EmaS_DpkWl>FZJpUt+L!*bKvwpRjxaK zQKwHhE}cBf64sXityCJ<_AXEv(a!xcy#V9Ti_n9(e{tpH*z9<>GGCkxC?cP=?AoZF zDx(e-j?3T&X|C_~`)-uS2^$zo={Dj#<QMq7<8%0O0-4z*4V<T*zK-~?Ba-O6G}-_l zTxS3WocOIq@<G39*<|0wzJ*lbMVSl6jWl-6lU`S-5+l?bF?OL5<mw|uYIxOtd*QUB z74otUR=H-pRqo1@q~24b+B{u~#wve(1~CByjXqT_c!+h~BJD$@A?WR~d->bPdP6R{ zU#seLdT+4W$RFcPy=L(-N?3f_3G1-pnk;-*YWQ}{gqCTk9Zv}&7EVdEaIm<XPcJJL z%8X@2cvnaw9bz99w8G-w{1|;}4pC3`i8+#pIJ+wueaiVmCiKen`+T`q-WZoAx-s;i zS7$2G^$cWOQ_e9SI7pUo-R7|39bHWNa<^_0cO~7uoM(K<@@~9tqBldOT^N*Jc;Nb+ zIgG83HI;o5$a&e-|H`Dd+r?T%gps|J;El%qeEt>>p+=AC5eH)pbsnQ*0f_;=FYXR& z_VN*5hsRbj!NLXTQ`%+WHWWGKvkgR;$vIK!rpim$1H8jIIm@$QexGq_M`GFIH;s6| z=JEJ8H)COX->>Wx8;gtXou$d0K6ZnG!MMd4k)*|@%qGv2TG!65ynkz@5#0<nMA{Ho z;=rn+^9e7Ii=5#HV}?<$a726A0P`98<Hy;X-G6SmYn|e4k+)Rxyc&aeGw;vsl`9^a zmFOlfb;h#h)n_u_CDWa&A{a4SWA}zr!TxDSvS?Nk5e<o6Ggp&71RqhxNVBw00`?#( zR_BK>G!YM(UW<yq5SM|LuwihgV#Fmm8eofY_6#=JefGa_4vt{-{s+YTRFryb^wN6z z5*=ZJj!M8&h;5Y6;f5kU2&_Y}X@+858B@ZCHdu?})XA2+-r*lypb!aO4r=papj1C7 ze%&~!ssy&J?~JfMGzDiYQ6Zeav`*wDrN*{h98U7pulR7a(|0rqnhT>bbXiI0I1ArL zw<C%uG=uvm)v$DStr`wpI=k6U38(;edAN~nG5RO5YoIelh8Ss;O0n0#nGp1f94NQR z9FiKUE~-=xHnL|<F<SyyhY9}cq?d|@75e1hNZ<er=mRfuRx1@PnQ%cPS_cbGBDL<e zLF_S+{R-We@3pM>s`Q5!=nYGyxT7u%Q*_X0l;%ahbSQp7JgJr{w6_NnHaJYyC_>Jy z_WPi(N9#P8kwK>_?p`ZRYJU>?Ft2+(b}0v4NtN)Zj5NzFTF=eEA9=X$0aG4^FV{yo zfeZ)MGUD1G=cF<-a>A{K^--zKx7{->9m-POqwVR%NqG^DWfH6hW3g(a<9VB9ht{FL zPBdqG=uE!gd3u&a0_5U8)CU7)8-YLCG3m0$xUGesAfN2Pl*n(gonf?9be!~Xr+8z; zjy9&<+~7TtkGhQpnUTZ{b`a4#u^o2{vrMB7;?J4lp0|7#p405JLn|GQgH}GoW-Wp@ z<@t!1ww!q`ZBR;X>X6nNhp8!LT(RXr21S4A;h>U;N=`TdC*|P|HrXjzVmtk#KF>1< zWIkJo|CZ;Ns+IgIGE?hlkVyU6{V0315pnIbfNDZ}d(TA?h`Jvt(kAhFD&huNbhR|q zgM;^SM4cFw!?|)SX$GWo7zx1-*2K$AI1Ijgr}Bc0k99c~Z!^qcz6NoGMfp3`PCXU& zV2bVKpOCL^wOpblR*r=l=w4=UEa{Zy030WKBXe^N3XX8-!SMg2dLB3r*#_5S2n$FI zb7TjZvGX+s(S#Z-UN)d~jf7*|+6*7=vx~tfCNoj(Yi9yKfO<PAb=WF!sTLLkzU@vY z5@W0@k2b_Y(#Lze-cfwkpuU)x6mxFfHW3z^fg3F5+)Vf*rC$0>xK(B2fs9tSPm?PH zI<lXA;(NB}9ET?r;(-PkF~K%#95OaJbp%2GNX}E~#Z)GIcGxWVltF864ljtTzD0|p zfrTP+HfEyKgUq)H57o@tB4f>!sm~vH*Rnc8xl2>ICEA*X#!?_^{84a)BQ6ML6~&$~ zo^+CWf(iMZs`a{;!+hrXTd9H0EsiGVXbDSbdg4*rG=&cdMsD^Xe%q91!MryrAuh9Q zQs}g4zidf|f<6!Rqx%t#X!Dd<uuUb{z`p$Eg371=i=s0Rhw6L4_?-oVF~+_PhOzJa zzRX~<mR(4UH6eS2N@Hd)WG7qFSR)dlRH_;4kR)0p^|dFdtfj*I{QkZF+~+y>oO|wl z&-;GfD24F*MN;ab4q8zEz1O$UvM#<*JS^k;qjDwv+q-r5azW(t{BH_r<=8#-R0z!q z$A<UT?F-3J7R5fF@=E{KzwH6Vy1v?Jx^7%au}&h9dP#UAxi&jtyM2!2o-F7(o0=9_ zWe;5Pk3Rknd<n^sgO%go&-7X)hjbv*T(0BGPa=xgy%t;q{}`iBWmesHW?`L5aiS2} z=|Wk-98?meS-W>DkSBtP(*Adx_%+9TBC`yc`>RO2yoXEf6ZFZytgyK3C++F;?Kkrn zH{;!)QAFfbxKsrUI<1v^d^N*Dl$@%ASy!4ef1?P*_Dnd^LEITexxAb680m6o<0jYH zaI$mx3}0|Zm?*jUl#`^=-D_j8JY9;9iFubyyUjGT0LC8FaW~)z<5iCN=h}2%oZ8?T z)$<dV?_Y?{-WwN53&}zfQry%1I#_0v1oq?=*)$kqn4HP6xXP&VnRw<kS8!ZZ>m3uq zB9?o%L(Qfsk#^-_GPi?oK8!Dd-Xkc=kHH=-W<`4IVyqBhNG$8?*C$_G9nH!~nBpgK zr{U4w{Feyi-&o4;xy)OlUi3uDRVqhvLFPjm%o<Sq_??qn#BmXunM{PrPo#mh!H$<H zVYDXC>mm&W9Kc>?2-=K5<h(~?vyP?2hYLYHWIR!Y)VmUaK*rT@`+i5+9OnHRS$N~e zLP=t}*YrIo{LPUh>cwmuxASS~<PVq|2$|2&6D6|<r{QtxZL1l*Ef6A`^4V4PNG4^z z+)%d!s@9VpO|)dvL<%C+;9oP2uabZLmGMa+S<uDIcJem0VD=-1HkEVG{h5~Z{C~tL zW)K8!pBF+e0s5wV0<*)8;$*%~GD_+f*3cym5LSl{t!28e{haVSBl*+C<{qOT&xx|T zw6k4sk;$1B%WHzbZoqDwZXpmzDB#)rA~%Dmq1?i!EQ&hUl$T|6+LI07e@pd6e+X;k z-<+w^`gealD4l?1J3T1(hmU$+O>`kj)ct~6l-Bc4qPEq`qfX4u=8ey28{toE5d6H{ zIkwN*vEU8A>JuY|Mr%P!H>r4~iRkvstJwD$Gnrv0*uP=ZcQ!M>4SxPM2y0O4-Py~$ z)RUQv%}k2rumdQXdtkd&wj=;ZYUdzrQ6nF`il1ZqKv1_X%D7r^o%aR|+66sDXpop? zuK=gJqcc*Gnd#T5>F4e9S2<!PC<7k~S<k1ZrRLHh7J|)B@25P<xFq9qW+wdwv&fE? zaiK@s8k-)y(eDh)_<A~{Y?=b0V4!0#$5^Os&r$xu)O%diI-<4ouwohMYyXUDLST=! ztB$0;uvjHiCZ1?dKuo=Z)Y>U*chCOPHdB3)p-Ss&y$Q0opXR~5*VRm}D5fsn6jHni zli8!^_JJoLcBZkKO#_Bay%`3?_7El;@Zg5~W0(8%#jUT@;L;iPoU%x2x*D}@@N1f+ zOwRC7Au_v7s)^lXfoedHc*X~{4kw#4Q7;OfeR}iw`{QT6(-fO_Cx61Hj@op*sGIc! z1m98aRLCAVN7lYv`^VSva{+}_(K(reJehA->TCx=Kjsclcy*~r>dPM)KI@f{xN9lx z9I<w6NqZbg?LV&0u}7D4d>iy%KTc0B&pf)gSq<Ajxbl6c{$vMIe`Q|X;7FeM5>Mqw z{R|63XC`=O9-KH5k{9p2pvvAT<NOhpOyx*KXF5y|x~6OB(4jYsGPBAFx6Y=6m)ZZN z^4%?{B+%PbKsR5~pk7Ssac}l3hnbNyHb*<Ct=-M?W9iuI0XYO^xkqlmo>5eJMpYOz zCy;WsJfjqqS@VwCA@uYQKK=b1o4;L#ML9`%;<iP2i5{42Q$CP0*IIgix@a|`zJgc9 zf)X8$Z6)3$-Z!hprL!ET&BnK}$D7vH60L#ucPD&;^Xg{5*kwe_WrP<72W~(ezH9q8 zu?tU?C@Z<_{d2vrn&GfYk|eab?H2Y0wn;G|mUD{-DMjIfumYrG#OnGh*u&Uw4^(Az zBf{BC07zs58*?@L-szI>2^8pG*W@hDtOE9^p6@r8Kg>;wT3|CyZu&Fn>tA}7sRbE& z$d9?E#Xq6`YA!z@5J>r|;k8H0Up~VUm0}W<GE?_B5`iyCP2Ms20snITQ-z#K)VfF# zKN@Iy0(~Q=$@}kN^sl2tS=-OJpVXrjk<^r#F!vksj+%Y5ESaY%%jhB?$`MD08ZyC# zdk`lhjvMV4Sz;X1wohIX!r3n}+0RcTouB4NJyH*MFC6N}HQyDw!VdgpPs*NzT@i^% zY|p%Cl$oj(b1BwN<{@VoObZ_iCH9jUZgt8?y?cKAlVdO=uuVlcyZNZEv`g0D;tOj4 z`K}3(xWPd~ukTh-%?dK&M9F$Fk#$J$@l}r6-_)yiP&chmNNx7-5tvC3hv(c!DOJ9Y zCh39GQfGveZq2hL$*?_P<8X3;7^2Ax>B|aD6u+cvsV@6j#5fRNW;DP7xNt<k&c0Gg zpOj&{R!+SRW~V&Oh{VeJHyxS3ARfR0n=kEDZ-#F{v3K>nDFbXjmoanm*B7nD2W-s- zO>3-N0jhzLnw=}=>ud7=+vf3+5dk?#$e4t34miif9MRuY+rw%g253sHX8cGZauEN6 zedQR4Pukm($~>RH@%0t#&P9%k)0r2`Ilh1AjNwR%;Q)RFz}FvK{TK5^M42NaI%bap zmb?k<tA@AJjLwdfoVHes_E80H6oHz;J8EUGmFoDfuf7hJ4HYT|O<nxLIjS1f<Ch#i zID9ksZIS$u5a;~xDv)$#{i^_04LDra7qD7Zn$)s=uJq@t>ls<w_vPv>zMd6&gi<pF z?v<!d$}S(D9UU*`M|H)}s!v1cV?naF&GBCQJ0r4>l9$#uryTQUjV>+z01;0jPWQ6X zM1)vonbA_j<e$GDefw87`zW8S;#{Jfor|nvi9t=#inDKR$RuD_{O(tfETKa5)152d zJkQN`%i9-quc_;XCSKKOF`8XybY>WwcJ%6QlvPV!bGgM2bCNJU-$nLG>RnKHv@l$( z8FSd{p1k(H)Apy-0rslJ>l$6#@x%XqZ@l2y&-`&ZV0&+o_X?o(s}Q@{dRv+ds4>e^ z4w=CO{Qh<KaU6@OSbf4=*?as_Z^708+^;=OR>Wcq>0mg1I)O*o=)irPa`bCCZl1fk z!RBWFb;Ax{ko%igzElm98>=U2Z=WuF)@>@{eSJc<Vra$ne64EamXnQ7VP9n~O9Xce z0sJXU4hzwL_TJfY+wK>l>Id^{p7GDB1jXtvf{EkT+TzIbICFJbKEqH2Ojh)R4?{Q9 z_PlKhW6_%)d_^bhgE@;{oet&{O^V_;CZ0#UBPr$GRqImTeCP36@><8=J4wH1-Dx+h z`u@776~4rL!$+hHRJS}_<4|kQ+AJ%-*G`%)mdR^fIH9OqL!pM>Rm0TE-=NkNW0_BH zGb6Wqw(}HBT=>}Y9XMZS7;J9nj^kU*RjByQy}Dv_m)2sX-WcViYwp2iPP)q7a(-_4 z!KVAUT75Qkqb9TAU_kyNs6DED^No0YK=%w6aBp>FEsiOaz8)7+7`n<!WpNE<wiqvj zkOoz=w%$otkUe+2%5_!vQJ$~TTsfoP!<bHu<*so<{HRqd{h=K60vPhHV}=ktWa zIq=7Nf|JTHJ@}PbFD)obzR9mnAa_lYNi+MsFW_uhrc^`bbAWZ!ng2qrsLoitO?s)2 zXB7Vc(=~QFIOt${(bfE*OE=kcHxZ`ODj#`J*eY|cO!PiuRA0w<cP_qDu1lWm{NG~i zaqg%0w5c`nT_KO1jwjW-atM<|x5R|;WSQBEg3+mFTO+E^&9+~@67ex!Ea`V%+Tgcw z!R@OzMa)tTevf00bap!z$mZifXHnDeLZgul{+ysK8cV>8m<tg#Vd?X)n6adqd4Vev zfxJm?FsQwz;pxPMhnLFx6^*~zKes3<zp50>_c9rwOPYsj?fuZThx7|3rKtcYW#sOf zUEJT>eM0x!(=~d1znIuc8&>qAqAP`PKjIK<d@Z=uz08$S92)Q)&{p_(3wkBqxYU?U zQfTCb8H$59X}~2xGsGYMH6ibaTOj$RAk+A-f~vMjhlHUlm1Gjsmj~^~am^s*edBWf zZ|p~VKqvWYsM=j<QJ3vow&l1&RsQ=08D>i|q4-<cGZ;%CQI`4Zy)}otV~E}5r9rGm zo{GcWY)?4aB#3IaoXlTB+o>0NulW4dJ~v^#f^R0AagF6A7bL)<u?Y_mG7ShgzAh%y zLrtgoI|!puXQrT2+&mVl(^)YNpQ5asp<UYS;~Vk0VSIQb%;kigTN+u>?N=U;E9$IT zF;jeNQ&y7(jG|cy4iL@0YnMFuZ~p34wAgNbb>*?kC84b0^u2Aq(zjExY=0Cj1@26w z>vYv1t|-}HR9<Jfb=3+#RXV17=XGv;SDn;>lAX26WMNTPy@I*2gZrJy>-W1FG_EK+ z1*=R|Om;OIJXJoCaA)e~R@ZHd17#Po%9|Sg?xthrDsIJh-ZbcRH=nqo;!&saw%M)w zj@MHaug*Jf@5Xnx_#dcv_p7|?DC%wvGgtMUy7R94KCAm~^c7XVMV0rDCcE1%JXQ7I zzVrU+R`<Qs162Y<b(+EdpgqG}El8kcdQj&<N8S~+5RB@F5w{2TOP{KR>9%}$8ULWO z`amt*T6N}i(Sxo=bM*-KmYKKrA9S}}QI85%{rF+>!Gi}+)uR(yK7QJI@bKAzdMsIW zcAo!X&ycxBd~wU{a^u^Cj{=ejb=TZ{a>>`epg+hrw0z3T*itm%luvy4ZF1wngU83# znXPwD<&C-Am;I7d6{fbp<u_0(5?{-kJa}Vr-<RUO|F%U$p!l?A9>yBIm09pNu276G zgeshsu9vul_`9(vJp<7BY3&sB<pt^JJFrylI{}4{)pJ=-vnS+Ci$tI2^-KRQnBWCX zAnX7uftP#3rYqVHvp2wq+$4(X8iRNE{1OiU>yMZn&{3y>fHOuAV2;Sn`=5P@>T&s) z`A~m5u$t66%z{}&z0|f>2#Qf8Z8DRU7Z>|Mc5!;)#)p=-P#M*XQ@vFdZ5{bnqc%?f ztL&&b+Pn@*Mid@J)9WK<$Y4QSM=|iSldcp)DhTig=pt=~2=rYB+=ZPkUP{Q0yS!It zIHr;EGwnVjLSx{}uj?tTsBZ^xABv>|HA^}99a2UiHmucS`j0z!f!+_tPsuSYcIFX} zy1k|R-;7w?k;x7Gx0o7i(S+mev_O_+P3Q5kB<}?qMf$w_OKls|w;|)B0|I?M3e9&0 zS54ECYUll8d!Pa61Ww$oK%Ph>S)^$Kb`t;tr;bX~S7O<<DS>l8SM6@s%u<+oeIsSh zm}1W+xS#b*)~)7+G;^v(Cby3q51PHzsuk9sy>pKEv)k^9!LcYEe1>$WaJJ>nKqc1E zSTwh4xRRB_ZsdaFjwMnu=Xdk2?#Lp2wM@{DwRsIrdQ0SolY~oxxZ-9PC9nR;GzDZr z)yr#LSg^6qTULz{wGiElYZ6!gHilf?fzZsLn{7fLe!bXu`g6&<9{zj$B0c|dN%WSi z+4QvvWalH<e+9?%Wq%@AL|x(IFbKc`qS<w+kEOi=`ozcQzNTZ$;OnQY@iaAd?Xeop zWf&J=5Wwdw;>sPf*M;u|Lb21qeNUv~Sm30*czS=_3%99Z6~Dq~JL>+$llK1WuKC$m zFv9t&jYi}1{foc?x9c=Xq!yb_+U}PGRtH6B?XkKgft<huyP1M?4!VTF{VTIiL?e*a z8SrfK%n{ICFHISsFYS_c)Bh8O(v<zYjrEY0E;gbR5Xu8$q%^JYl{1f#we^x3ltU&7 z@l|(mjIkAb2Kl!o*$8+0$UMr$@4vb-QFUSiVre$}!INS-Ksp4`r_yl(M?EXwt)VHn z2IC4b4=8E}4A9cV{8+Qao--&>$(3ZA26Y@mXdVxjDbep6*d34v2W3Q^^01%6j--ov z6^Y8i{@TH;?-r#pInt{7<;_ui2V^s*k6O7E?X8t5Ap;}ihZhy=xGNTt7_jc+i#O{t zV$$BG%@pr`M5(1Iz>gWC7!s{%BCR+v;>^TX8w?%S@aKjYt-9&vO$97yEvvfW9OG%) zX#pDJ`Jaz{U+1<SLBwecVbQAWK&p|QkANCZ6tFU|lO!LIjXbO+PLr!VD3=poEWhE- zh2i!7P{i|wuYStzXr0E}!LYlOtKkxPp8fIw=R17{W`J~J{gl9L5TAx09b~0zMp8DZ zz*p4@qgV{#F~(XJs08Q3r@`Q&eMVleQHWqDU!Yi&rty{Fa47@)P`p{3oo*l3gN_N} zDhD#%$;KD@KJg>x1*XButSRT9!dIJ2zasy!d@fQ>)guw$yj^Cvguu-?+t&A-{`{Q& z`F@E^qKBOP>q=tp$7QI0^KrR*vquZ#)y2CZ>HDW04xxb?*7_b$aY~xPK;Kh<=*Axc z2GeJl9H_Bs3kP|iyg#ES08gt%ihsiCiw$wgpy*P9f<gFJ|H6a+ZVT0j&YsewF<4?D z_yH>oHIPNyXNzjk;b|*NfU`+`rSB}`#D2d#4J7#HmPm*!P!OyO&@JB7BBDX>&a%>G zutT^kYtwZI^{9(O$W`glDce13vvprw0S$gW@9N$_t6swh#jWzG&yFbHXoJ|D-7<kc zGnN}<BR^|(0HQKMl75ZO(ZgxJyVa0|`^P4}YW`upB2A!;&Zji%HzZ{_o(5+E*q}g6 z3WLkY2b(&Ol6u?XbFHX%jjgDHTx{V>&J&k&j_do|Fk#YjIFT#xfobMaRtM+RvwY2* zSu1Zwt^W=Hfx*ljo*VQ}rp>nh^<2Ymkj=ZY?$T>)H^@9A+3*K6{2rMHchWGCj2gEV zFRV<fZxVaU3`lY<u3sHBN63wESWP>a4SW>Yr5LYQ3WP2V8fCQZ51Ll6`foN3yF6a9 ze1j|tWxuLdXGzF-`RL^p3w!}W`kx>dkaRXguL=J~78MSDH722McG^}j4UMj`+>`lH z<6p8&;A1wg4l1shTN&Hbn2j$t9IsLqWDqV;#CmbX$+bAI8RSst+DIKTJM_|cgQy-z zh*FEEG?@8I-D<2}lk@?`)8sEynq}jFK88pX?zT@LpU#^62871IA<LHs&h@=J{@J!( z380em4yIC+L+|x|nBE`UP``$=`+DhvHBYxdVT7G6)4HZ7UrlHjA~T>vvl4~Q@yih& z__rwdf#02;#qXa&CIPGG2Q0vVU=koWaAxICfJ|c~pPou!Dr<&k7F$<pi?za~todX7 z1O357lrJSg`55H8L+s3oxnC0=n~?&1zPTE5-lq^N#+%qYydgATHeJA2lU(f)dvTg_ zFGb=qXoBHS`P<8Mbl~R$0V=2*F%V$cqtHOJ+6B?&?I0lo{ebH&L<9qa1#3D{t2X;Q zh9XPk$$uK047>WKMu6S(<jVyRYB@v`+lQe_Dz}0S3+&CJLh#|>nQ|+w-u1)f2wec; z+*N4gG0>lUx9o9-(PaXU`BIz#IkMoc*<~NRAeXLQzdmK%vX?1YYo$h)T3NcI98L;m z$KmxD13Q!_QnENX$h%!-;k7wa{|GGUo8~cAw5?ME;eleczXDLgSiV3B{_MYU#m0QJ zd8K+;xRq|=FfTsvqt_sCEj<Wgw6eBPy?U3CG+7-mp2oqXt5>UD$o|YPnr2=KD#^OT z_!A_$K{85&sL0jep+~EWqyRt+v6Gg9*^#}}|G-4^q<Yb8@?VSe6R0ox16Hb4JZH<n z)~j#;3Xub_$boO_VL^NZ|8~y+J}iT=S%;5GgSTRlRK|0mg|)yS$Sj?=fau&4zyrsD zf^Xw(aF91x9*WfIFsYJrX&khcAAbheUY+q4PJ`Qko}@xccKeKaU*;M?#V<2{Td}8E z;0@lb9Q1MXK(M;7A|taCVLhzTU~lM$pyi+_s!?qJm1@bCua$7U>l_bWnybB-0R#A1 z=gbf_oE}+OYs8C6t{#9OK-fbA93RwIjY`ha+0@xMnyNU7euk97-NR@`2!E`opl>GD z>Tk`RDvQ&nC^1N#*p*MU!giky*wciyV*AeF1fi8}5$?;sV(RcT9cE@PfE7fx^Z5_x zL&X6>ko1%PUMW~-YW1slQ{d~G1pwL5lcH?aH^r6)?~(<kr-lFfiSauvz@+mi9qlqM zhO=7(o0=KjoAPg%Crf__Nd<*{j$CJ3IteDJe{Ny7T;OU7#xD5d2U==<p+6o449Lga z%3gTB`_00)20q8CyO3>r$v04Nr&<5x0J8iDH&n|pOXs}tjb(gp9TZac?gw<A4x0s< zGISxD4A>hipWnjj$d|r9m<;tsvkZR~2v+Olz=AM?Ul50cGA3ND)LLK843QMf`V>9> z6QMCw%t-Q3ylyN+(+rGi-{ik64T@pd1w^9NNUuNFn*I7FE{KD)V)=GXt)7l}u8xDi zK?o=M<LXGIzrkE{Se`D`AHVA0bbu4i;9OkxNueXBzoF={d<9sZfrd4<CEst`&N<jx z{)pnZDnCD8O~5XBHtQt=Ckn^){<1PQn>B_rjlxNG!Jibn1|wH^^^+4BZ+Dj8tQgPg zpa2%>gev6y2S0vYvI5kXVcz%7brS2>uVQwZPcWgvglt~bf5oB?I5mL03_`;{_AlR4 z(%h0jr76#O<0%Zr-30uOm07tox_Y_z({=!R+S*ygwF-v1Kgr<ovirR@{HnZ=;EGvx zn(I#q0h14jF(C21K*7Bq7Y%%N2bcYBHHcu-YT5cRP=;_+nt<1lnc}>rqV=Fym4$-e zYI^)TMobTw?px=t<Zh7BU^wvS#y@?Kpy0gww_vP^x=FC#iqQPvBMr;Npk9@wl%ZO9 zld8qlFKPb<g!Sm_GCv!@#HS0()LZeK`4K<8pn^GcByHgvDZaPy;msod=lDcE8y4<@ zqGpe8<;CB19Q#;Lk>uO2m$99|NoU};uZ>dC2C|(FQ^R=&ogv<0@FxKk|Ix+Ax~oX- zB7$lBdJH}QV0YI^g`ngEX1LV4;Yr3#8K14HalHs)o;9dxT>fkNOi~}f?J;oa-VgOr z06_<8MIN!=!#zF(0GDK*aK%P(KfnXZ>DOJ{?B686!!t*(jnP^>K|IJxu=R^QnrJ?y zX&j0Ar4Mf#{oH{2m&^2l^1g3KM}$2TJEbOiS5I0e@4#B!%LqWF84Le639=F$2<7`+ zi}oXBe(;+Ts}ga!xac-uwgE8-2OmiKHJros`dhs}AS*jnZMW&)lxBgnO6*-iYQK%^ z%guVL5v!l`t@s61KQ2>E8eI+*Cz##YMv6<KdVZ{V`SLwBM$`Y|1p|?yAh=-!vi^48 zL!&+r79#4S)+kl|ENx1B_ohR{^T9}@V94c#=BiOF<jvQ_FTqX!Bswk)tnA)6Gyrf3 z5w~l<f&MM8=|uCWF*qYPZr^3JN~r%x8Q`78ru<g5aHb;*c31xlnBC|!&VNMyZF96~ zmHe}L>R|f4Zx1$i(Soc4BxyCBeroKD<+0m%R+bO|1`veg>;MyZ??H-NN^?KGuD>TG zwN``)aGIHLzrlVmY_EOt9}k^)?mwbcgrNp|+9|~pJ~*S|Cu>o0s3orx%QZ_po%wnA z)C!(XhawMdYi|gzZh4s=>RDG<77-gD0Q~ad1IOP;BNK$2$-=c*Og3nK5$ow_!GvJv z$?^4lJy6q)zEcChYUlGmEsRH3_<Gv~z3k{0pq8^_kS`@TwaQj;6`rD(y6E4?aNPS` zcj4EK3(*GC=`qNje~-L;)#SnjdegQ?L%$!Zv4l%vt3d5xxncnLg<8kXJ-$jE4iFVY z7@89^B8uan?S+f<Tq5e2ptAM?3J7d!omVQ9v&Hx-T$okb7^@UIg}9$H9q&jk)j1=) zIfq9N*BX<VRM}(84q1`0pG7;4EmYJx*D&eYGOU$RvP*Z7Qf=IAraT6iZF()ZDlTSd zAiNn=f_W?C7dLT}lQ7N?SOfJ+{GoN_y8JJD(q9C{ye&T!QowvtxaRy2dlww4?b9II zZ<`jeueLIjE8~SLM#+-nS97Hz;4%)~tqgg&h&_Fy;zkiM{bOSdk>_(cP?idEzx;M$ zZTVA^A=3+ii(wr$Y;9uk5RS!Mfu(nBIS_WlmYRcrQ`Py-WIzijpyi~rUIu>5LzHA) z7K(&0W7`P!pX_VS8GNZk(6e5GOJr{4J8xN??X8cnY-$7-=`qMqJeI0Xz43!Xn0=ro zqg$^sm@>#!+}t?1^;jmG<HpBu6W|1EYzz-fJf6=a=S{wbh?XMT@D*LuVd?h<Yix*# z!(<L1ae^~f9oYK-%Tr(R?YC1KKHHc@y->`ocV2tVUZl=dl+~O&o)wy9T>9~afqNy$ zA!h*Y3n|btm^tnYlp6Kb=V6OAOzwrqt}D{KTROB0wXAdN<ehXEUsu?X9Pf?Mu(2e~ zv{_i2bhW_vozi2XB(@=1Qo+MYvsj^L5_|um>SPR1<DK`szcJk_MyHV$|A>z_p5+GB zx!TfFm6UWFS7>>4()#DlB6=P}oEoAGyQeyD1J=6^75DF?jp#f1YI8Z7x}7C{SNeC> z5Exc*ISH)v%^UZNE;Ij=|HYd9_F<x$^u4#&1r@FV`q=_HndfjR=EJ`wOzX6a;1acC z>zL@6dKa*lgkgV_y)Xfkoxit~>r{zm2x@422tYoCS*?_9-^jtdn`=R`^V7<Y_iYKv z@d2Tl%dltS;U;ixUjA9C((89hU>u6mH}4Vpb8$ywY3V6a3-&koPFBMB<{7DqiTN`} z6dPl%BLBVl%yX)Sqx{79$}~#*(`l}RtOPc;kSZ*@baS18xR37Z>mDYx3X)eP-y59e zb=-kJ538!uSrx`V?9NLSI*U(IUbb6!Q(<<${din$*29Egho{XlZZsdCLjx7EYGtxt zw|uDkMw{JAIGfX1AeB{ew)?k&gbWuBGns6&21+Wst0PW*X7whI>w#H!SibUq)Ax4U zUYM9}89z4nbQ4iu*LHd_)f77O^z-ptU4faTP;SUxS`L?o%5gTFPVl2_yXhh@)a{N! zeQ|(m*Hqz4wR7@txqPSSIkxLb*;sjU+T+rU()<x#idy0f`|hIld-|6sC1`dsRrvad zN7Gp!Q;95#p6lvb%kcS2*Ixk`B~9o=kd*S2xEYMtsqP@FxBa?ix~yqgFfbf1Ao(1K zrNrg*pOXwcRa)gCI3MyA<)mY8c67KQ&j971_)cgpF>+)Hd`h;f>2o??1RM1N*+PxH zdk4^vy+>I=CE6@I&pdFMOxH-<ZPVjEM6iKGkV1xB5;c-$Wbq64r2y5Dj~ydC$%U$( z!^TPFDFi)%d2+bkc>~A1ROs(Rv2neTK_Z~rs=5SiHtE^7OF7AX;cU&I6Q(i*?9_|x z*rh_?o88a8y1Gl}D9~K)m&pBerHU@D6m3whgRdt<N%Y=T(|-(<+qTf1KUDRp?1>Mh zlg4=jKJ#J}+7WI?JD(Az%M~$^!wyad_M6Pw$S+Vpf9KxoC|J?ga_$CEpmapeQf-d` zu)B2rhUR7p6a-9EDv3@<Y3j)l-1keDB~f~VWXVgsBW@=<e$&33mgTb(BnnHv50Tf} zUy!zCv46RlP*@M!Qnq6FDhk9EXzTq<$}~`r&1i|Epq2>Izyhd8Kk&8&D%n<GWka5b zW5XnnBx_^AwO)-HT&l#r>c-s`4*a}FrtHY6=H|jPY}|@YL31!dnNmC3FIT+l8IRDS z-d)ggAhfm+Fc+3Uf7l8&({a0Cg|E(d+@z%8$h|gB(-#@a*75!5Z|i(=`lL@zV98S9 zRJo8V%_H2~)0J~r=|Z<{GKWt`@vCR(K0QIn`$pF2ighy*x<e?$ojd(SqeU<lWEHP) zszB@_v*-b4LB;jsV^C(Vd&wv08;YWvy_m-v9rkk}oM+HZT*7Y(x8~4*T#JjpLNQAO ztfd@&$c5!%AG1DKK-Z^f-(^q#>i`6-+h|7yWr8u73wMuop=3UY{jG0h<IDB<TZkL3 z^%RrL&4k`>Zg6Vbw!7Waz^-=0pOaQZ0KIoH9^lB0a4-zmhX9xUt(kQNW}g=S$rFej zw){+F*ZgXa&P9L9W0xiOe{VeIoJHbTl5IMZiwrA}zs6H>5veK2I5Qt4jLD5>KmM+; z3y1b!r)N}8cE_K!O?KcqU3ZcK3I(^V{pZ>irTYeNr!%5cbn_zjak5}wc3-yt@tywu zUYi!@T;0`UVH8vME$*v-Z_+z``CA2e#C1ddjV8>0{bHDlHlTpwzIo`py2z@X(NbAJ zWV@X;^VJ@cBbxj8XOtWKE6vfqk@3Z!Kz2jr5UBV<T&E)Z7I($Vavhw|j>Br_7L*3C zDgEH#h<#w18I~<4de=!|D!klHjf+p;N5EDeIWNy_RBo|TxjJ=IVCIb9y}Z@G{A_ic z9#1@KlxH*&WDA*4FHKovFu-Ik=I$>_$Mi=84iee1JHZZd!2zW|(mWruH*g*@`Gscp z3k`cg_nUHDkRhS+|2eh4@&Ef$PPz&6tS?<9Q_zFwfw(w(P=!W#mQ|KAUPrUU7d^@q zh(8uoFeuxkOWN(@D!Q#`sL4zD`?SrufjXaND1W_8U50yUQc!rAgT=0A9e%b@SafJd z5a>(bu~Os_?CO%c-h-Ds9r4!3LNoVzJzJ@rwfpqcZVXRX^vhGPm9?Ki*lHtiGKVnP z4s%w7i4n?bUIIhzWY|8m^#LItCI9tk!_{;>jSY&0&b{`cs{XmDwZpDO;BS?9xPKf6 zT5xwNH%O!l(8P{`kVH;6tRe9gw_q*OqQuRa^z+T%Xh|veopythlQq8nZNn0QZo^NT zF23x0IaV^HS&b37C1JZH!`lf)3riXIO8_zsL-VNmrKQn%DFSJ{m!|nR4b`qf2m>QO z(?pu++|>&w_sG8l<$J;MR)S}pTSsmW08yW_)U+l##__hS`x#e!gNn^EZILf-lR_Xd zQSx$ZrSTla9<`HgecJrF2GHZ|Kb(Gzave1+dy2~qPOOB4L~O`fL9P-$*|lobGSB*s zX<bJ6sMu&E$^jZ`7E2Lm1io=^o&BP`3$OyW$YPUY+DWnX1_cpU!9D}6m<NF2eP!2) z5xviu+YZ*J+sE-%p>N??ThHLeYDgu1Yn3ChI`%t!MLyX^^NvP{O_OuKf|Y68xxOvZ z%rSMn*}5LsfC(Z87|;DM*3bPYD@;($qNh*rbblQ?w(i-)MvjXG;pfYub3CxRk1BbZ zL5tMV43BcFOR@bY;r&mNLMo0JiFO3v@<q=7NKlr;OVt%LY*c2^U_q*<L*o1Vp+zm< zkc=a}(Ef9p^yf5Y7jX42NrK6cvOB?D8UgA?$L<9cIs|dfVY!QPM^{MQM~3bcP8%YJ zQp&<<9f%$RqWEL2#f)UX0*<f>_JosWipC>heeR7v3bIMiwx*JCLQQ$Sl1H3q=oz-U zb`Ac9il|XeUDrU9pn3F2ly^1;=7z4k)33JT+Js4VXi|y&S=p*MJ@*oSnB`KCe)cn$ z`c`e_5oFRpdAw*@M0fK+yY;OBObEcMOIc)(YQey>()>pCp$of{V3`*&h?J4Wym}?C z#ag9B9NelV0!>|5h94t9r;BhdgTAcGLm{G3;DUP;Xa-}Q429_`oYPK?z}8)Uomi5t zWv+7zYIR!_V&wMa?gqDE(>EoctsH5GFqZ8a$hhKl9O0>D(e|w=Y*>z2<FLaEJl>RQ zvN;+`9&v`$eg>u|?J%S-?H4D|6^NRxahRjQqF!iy#&T2P$V#;C#Rc)g8WB>uT;75> z2*(|?>;n%n*J#si?NrU#u)4!{E{N@tpqokiq>OTt@jiwllq9P*P~~^j9T#&8=+B@f zPyjijS-HRoQW(WrQP!r;B?oP?VO4!Q$*vFW5RXAF`LwnEc+BC?Wp`OA4>Fh~w+BOh z_|k9HFE^oBiaZusJBenQqbctO6>K5z_tH&}TnkX9W-4~9Akrj)=!lf(nQFV#^CGE~ z04&{hA}H7?TJOBMMs|wGeEj9q%9uV73?(#W)!JH68m%7$0bE32gIllx_U9S0K>@%{ z-^U!aBEfSx&z|!`VdT?QZlM$dya_t4UlpmNwvNYThhz=J1&2>WBJ}X>_t(0DY-LM3 z7klC)7Q<Ps?0`nC^iE?gKt~C8Utb7x7^*?N>A-)caSqu@Eik0!aNMvV3>9q1Vn_mW z{Mi5+Ukk6KOHkoFM)ut0?h>Rq<Hh@G1d?ZGUF!fEJ^{28By^gPRsbRw^8Q>{pIjHg z$v3l;^>{%sua>ituGu?;kF9+c!f}B_V1sA)T4t*KfnRHSYiLKe?AH~@1lHxkT>v^{ zJ@|3ZkNE|)8PWa*--UM(p(kG0yR4phBmPBqe9k4B4Xm9D<$75uH7FO6u4SWMT^r%& z5oC$XNZs!%9p#;4j*rRqLB!(&PKEG9(;>e+d1D+oYg$6KtqemvESH3A#T&Ik1|cPy z>Zt>|;XgI18cm@XjimYycdT)C3fe*x2AHS~qtqK%J*jFoHQOSNN1iq1BiY!5FE6%P zxnxXUmv>WCIvxTx!(6|=t7(>R5%*oK(JDl_%@b=QuW+Wc_pG~G5Q0nVg2wr?@6d48 zXZoESr>|NFDXkx<i8u@i&DTxio0ykmk7d3IQOjT+AvF*w^O9EAmw?c-v9&NIL-*xX zIp6c#T-?a55R69JvswZ-jlfB76gy-{m%1y+8Nw*7u{Q|Y7nZqG0#PaMK673#D**++ z`5{!@d8i@m0on!s0EVuCB?lXZce~?{D^y~)7K&X+Kr+X|yD(YpQ34x@Kr@kb>4b-{ zoGzpULB)0SE@M8aw4uLp-iMKao*<3N;K5dWoA(*S9gi(0$M0w&v|3xy><s66ryEmW zkKkcuyLIhvKTE+4?i8dpn_ozxc|Tv(3ZY3`_oKys5_B*y%9}#pdL>rLCP%^eajtj7 z20;#~?68-Bh5|O66{N93;I=Uew`~m{3Q7Vyg)N@{)N6fOuFpb=5*BMsI$3Y36$RbV z7pS3q;>tyHW3<C{*tpbRuCLC-Vva@DE6oKx4$6#}R(#KXy98Ye;xD}N8SBX^ZRw4` zw592r7)nhmxL#Waf#!JD8IlV)sUAMb*$gK9cjBis>82&Axk9Em!}kW!YnXxB2}31D zVY;?uCjw*S{z#41@RbTErr?HWno#RCB0)9n59at&YI1+zr1lt+1#f-7hFx4-k?yJy zdoZ^U6prZ$j6SRpJ8_Y-JmWkW1kBY)VMT(BgF42wG36PjSzUL2&N8F`fFJex6$vdm zgp&xGXXkqHsum3wpO<b6-1LwI4Tf;W)+$$mbsQeH?!lr`7+%+ij!cJm<BO1MjqSAr zPMS4030wY@pwUaz%BFjjVYz`|jh>K?0Q%&uAF8r_+z)85QW|GT(4~7z@Ls@#i*#8& z{iNB<^Z<cvOa7EE^o|#xP_C~Ry`akLZ1tHw?IoKOaN%`GMg6I7uy7NT;y&k>&7h1q z7q>e1F_GUXE*AJ{Rrx^`e#{v#)*|EaCHbD(Py!$aIZQ44l^6jaUw}80!M(A<!A-Rw zT7?2pHG^<$g?M79B+QNYE`uo7MK;~i4_&cxVf{dQDq#C3$8-m_vct{<Xvnp_@Vd|x zOuPN?dkC$1c1$&R{21}E>pY?Azxmut>(XOsG81$mdW7M%DAeabdoRztm9%pa+vg?% zrN(N+x@u6!<nAwl555GVmKe*Eo6>he9()Kx6+Dvu8)%>S52f?y`iq)eCIdAqBQa8Q zZa=N(XWEj%xYPnuYAZjdG(@V^A$n+4iWw+{-96W?^w9ZZ*`*r3sPp;3H6n8%%pn=m zgFiL8|D=Zk5kM$s#@y&inzW!8Fo7*^=+_Ltz62BF=@V&&HHeMISv(om6la`2UY7Vb zSq+dWIjC_U8mPBj&jaXE>o}CSOoD(3iq%oyEx+MYbDgDi!hr%GyaBijeUR=kz7Q(L zvqJAaBLs9!-MZz;{drD&U1q?#4%X&*os8vfkHk#O@#wtMNA1U=_z|<MN&xNzUCFgg z0fe_bQ#O~VTy8%H_&i@l$M%gjmIbV!le%eW!xy`;;H%z2<$5-h8My?n2F(zFOQp7f zt+w_?7P&#bCL0Za>9y{L=g(1?`G8!CAGc0fjC_IS1eSY(#<xOqC%?aS4NcQbVKbvm zyyL9yayTzR0N0BzJtLi<0WFz?_c`aX!tX{Ns$4x>P%~X*yJme^rWSn-d`f%Cl^+t7 zof|D(bmhSvltUZFC~wgqZ;@qYW?;RDf*D^ptjQgpmy$crY`o&2m4`8kmfDw@O<O<> z1%5ORLM`-suqLB^@b*`H%6V-5F*D~%pQPkaICGyNS^r6TsK%k%wD3}($+f7tEVUSb zRs?Dn@%tS;TqDg@6+Kk(QQiWh^y&G(d#KKOnJyw1|HZ{2s`MzcSiYUl%2=xMBg$YQ z`U}1DJE)%nDJkfKn!Z%|<zV<np#AK8L7ANE@ap+bj5`|ppBS!Brd~_$#7OlzJd6<o z1P`U}*DoG|X3}@%q)@2&IZ{OiMyF3QUTEsX8K*qcB)d>VE#V4!K34VyY6vRL)5o3o zP$c}i?+s5Q5PI;RqAV-CTkJtSZ?nC;Mqu=U1^UK%oS5i&l`Bq<^B^|>xji<sQzWGU zpWz#C2wFT`0~OT=;D52QTr@Onm0A2dZq0dN=*7*&zJrh3>@&uF!+Z1ROdg5EcJd7r zVo(ddnlp|6p)X~wx=dzoXQAo@>U6?x>w3L!3u$<9`30Qrq^Eq(rPAtMgbAo_O^GIZ zd$<Y{R%t&#IC|P59&d-Ib@!iV_Y6MYf63Z^9UwJne&G)E(^JNS;R96OsmF`d0!^WP z!-aF@2Qwm`GoXe4dXrg)HKv&efS3e~gEly@pPy%P4I6vFh&0Q@RfAdy!xPoL<VCH+ z&NIAqeV2X<R(G<##023>RU*NnnUhj>H@IB4297$~`fjkWhu2PSeYT{CeF>DictQb4 zbW0xEzRlxSDC;69{2Gjv08)RZFnnrbbNiHliP;dNXnV2rGaj{`d-wQ=`u?k6t!)u( zXPnQ^8MCQ+*XNgFlB%0eO=%s|K1=TT_g;0ZRJSA&%<l23x>O-m`P%&Ya^VAiu7B0q z34e3S^b@XuC*3IDKkN6tQcJ7jsWt)vv*92u31YdDV`X^pG!K9_;<{aTcHnQ-^GjQR zQ<ZHrVekg}1*^+GT6UPk_7swI@`2Ai{{`lz_4{vb#R_<U>0OH#jn%6?Zs{9dBYZ64 zF2j%b2dB--6uo)gt4#D|8k?ANP!bN0i2)YyXHr9xM&ye_y{GtcfvqyC<=6CDhbmmn zjOmw8)ZjdmAI#u<i^DyPtz53Pz%kU#MHhSbZjUMKlG51_PaYg6_JncPPRMZ^E_pdy zQROT|8LC4MVT{en<U7t;kyUuz>u@Q|!E7+gtq}DA;%ps!KasaOAn#<6`R|ee1!rkj zHe!|velXu`vkHUoKG^-@WwkQ4J#PNgC2rRD;OQp9<fl_e5GnC|LxJfkRe;hg%MQx2 zI)b%*3QUO8%`-g&CZSQX<Be=+Ru3l6`_!~tpy<w{IvzA`BD7L8QZO(m9MF4L=5WfT zhBaaKyQF`?%O!_9T{yHS_*E#oz3nW&h=1*I^OYQofbrMlFR$!)HtUxh&&MnB-U9Qk zhq`|$x!7*bX)GvogSGT$!oDSt12A+I8gTY9#CAXhhlTiTM2X?<$d=y0Ml|pyqO<mz z{&hYZU6FI5!2ujz=f$0Ud*|~MQV&`SMBj9<PbX_@LPI7UG+!o8*>?`S#zKTz3+yh= z1fMT=5;i_xX4R&*VR?ls#o6+}<I~MckgS(QPk+_&7y|eQFBOVBY)gJ&@g{fcZu(wS z=6~aVQMtV={ntRDUDBh>5Jx4MKgDj_8wpy#a*2oPv6<fBJYx=lonr!$7unt!aemTe zMPLH49YaT7=9iKm&Ng)o1*1~V1Y6Gd@k2v<H@%>-%X^Cm%NthOr@mhj3LIV86y#;D z1&wu_5<5Ppi@@z~B-}VT%*Ll_y}Tc60OVr9c7I<|1@dzXSYo9{H5I87&hj#Up3P;S zR92jpJz!a;)tn>vxiJe78OTKV5&@3mw?l;&lIIn@*85IaD!3sM^=mm@3QFT??bjXK zhoo;5z4Vu(6wZO@PNpxAT!HQsEhRar<1{J2B_u<4!cJn5FqE7vES!#NQK+i$7Z@ls zzrArT%PFc>Ag=5AL9<PE{NhyZ<3tQVIv0}^%n5W*3lHL4uety6Jr3q*S7a?T*#S|D zb{SU33>wwrfhSa}X}O-J?l003kC=y1^+lb=p;wOzG|k#xQ~5cMMekp;H>;f2=u(q` zbtLgxss+`J2{O3beXRH@1M`!{$Y}@RP*i*;o04AI86Hkv{=wRGL`opH>80T-g5HRm zdc#K56l+c9W}Z&ynu2H=RL9H6_QmyJ`$Ou8WpstUymEu|FQbpffD&D0#ntXZRjmZ; zV%?)GPRVJM=yXP+KzxBNL0vi1jf<po)kEXb*2b`Y>qW8zR7v>hT-|aCi1XbD3@}yY zFqxIPsr4qbrroE%W38@Wh!9d^sK<Z37l}!yLZlY82Kk+q%k<aBSduH##p2G{lO=Z& z8`RD<J6;tW3=todKNF&OY~}UX)F<nR?K!Gtm8{Uk-s91%q)f{JzH5#fonm6zr%t?> zg6WxY`!CLM=x6@rjcbMR#JI4VJ<dSV!1NScIM`kBy?%mT$VK_uSNcyq>ECJnQqhic zCfr^{9BuB6Y^u|S#eYs34jpe#vi=ybI5cn*SVpBwyf`92=7muQrN9-VOE3Y7yj?i= zk2}-G3d6i(E`ioz%)sxY_c>Vw4I%+B*Ru&QK&fZhoLDlCeLCm(D?MFr)HO?_cO%{3 zdn!*;y)7>P+U%0b@A?qER;T1H`l~)qf*U3iH_v#jlO1yIElbVLxE9QNX``z;R4&uN zZm8h<de`k&AtSC<{}3fqsQeqXYU6CYj)d~2a!vYe@b&3wx$9q1%c^Rh5#KOSQ^WRi zI|}4xrkmzr%(+$Su-hoEw2by$2VkRj0)@V1A^BQmN_}E}U)VgkT9iIq%QOh;82Qhq ziL>Ya`zvO}!s+3QD*HX9@Xqu?c|Wl93Jn!kc5O*cHF?A-I{v?M%CzFeNU3boVI4`? z`R^w3GBh56>4~AjcxrsfxBdH$v6b^R(@VtA1zC~6zq3+&7Z`CD;`5m0-A_6SWz@o2 z9Ys}3$h(+C9VIJ)uGrksnOv1$;S^y~`*nFe-g5mc1S=km>93WF>W(FXLzE!8azA#W zFKBc(-+&dmx1_vP75Zq&{8!8pk_-3}*XZV*`_0Xi%VLvYXFEAi6hBrc@zO5C`!Fz% zE@qP!C~m9U*759)apx(wug=~D-_`H<#b0nNhnx|d%t@X7!hEFh@X@Q>ABioOKCNF6 z7x$FaQuWy*P5)?qM<3!PB@LrpG=eSB26@rtoF6WzsHE0MtlprS=A4gy*e{LPq&i++ z5IkA;e*E<}#|pt|*{|o#z%ROQxIN01t|>E`kwJ{+eHaspdGsOxv3*3p`1A>C;5ZQy z#`)1vDIU6w(=ZT%y}G<=qxtxCe%?-^q2X7jn8#DMScu)G?e8x=OCG<ym$%y*d1b*P z^WyV|h+pm3uB?Y>KKbw}?^jpLmG4n8Pd@&K_}%m3%8$f*Pd@$3``!EP%FoL`pZv!{ z?9sVXHz=CD^St?c1FET;IWfJ9(!76|j;UKE_j;E#^Z$%RrfygL?EPZN`*-46>Q24p z)346?f8VsE?zYA}{T9IcZ~8^*udaJfzsKbNoBfvhyZ7hQpI3SJ=eUpTcbd;O^YizY zRImOSi+Q$vi}zsF@#^0<_nz(E%Rg9;y!vnU=d<6>c@H<PUEN>OeE#QE{^3r`)r0kz z=l}lWW$nGVdbo4%`N7Y8*8aDvto@%yMF_k^kP;DMM`Q~pa!^@B&L$!^lgP75<b|d2 zDWwV6r3r<niBQwTn$jegX_BjH(lC;Y5(#5Rk`E^-Qc229BvmF!eU+pMBWo*>b?wOd z;pE)+QW|As)B9xm_hkO}PLB*Cn}3mchox+l<e5Sg2QP~0q?7X=<q>=O@Y_h#eB8;^ zxPP6B;X23u3yH8Ab~k(&V8)jb@Y^Qgft$o{0l(=O_)vt^?TD}``LKR>WM)ES2wqjl zU5)LSifg9lMJes{4Etl=X@f|PcLa_wf<2jX<kCLg=kC^thlXT~;IlsMWGbbl-&l=v zDs(Gra^na@Y_^*>gl9MIAx;MiKnEhAx<(vtGL_%5PFkKsbRWH$>%6unjAQW;4MW-b zeEQoHk<<8`!SI}jUs=zoZh7(9FTJyylQR7;X6cuOq;F@R?vpZ`Ja5L2cuC}$r^Dxo zJnyygmZ#zK0I*Bs-Hny{<-!|Q6v}hPk5?G`O&@uP<o!C&^N*Q-FrCjLxFoMeM+@d> zt?FGSMd9apD2xKLr2-0H&Lyk-xvr3CN`7;ONFGz_WX-Wn1^*RVAzK<RCX4sLh1Uo# za8$eJOChW;$^WrK94Zy>ALZ^ka<Mvv?2l{?wJdnP7Ml$eu&{^~n!m9zl^I&NC{V=q zn&%UpXEv6{Rr&gR;JT;%^^pgO#yWh|SQd;*XQ$3xC;Yh{m<8i1<T~RcKp43`OyJ$q zLPj(7*j<q*G3v3e$IO;_Saif-0pia@+1HJ-RI&0S=;l&8#lD~5?}1!$De!O7I|Par zusp@~71w<#p3o4CdTj35vUv}K{fzRt0fO0|h>{~V<p$^74bCHG>k&P%0|_5R^L&aG z?7HA4;=#*8A{YR?cY>>F;s}?<b(*vEWGrmXh4<Z7Y2G8f_z?q_kh16ygXBkuG|uu= z<?;_c(u-4iS;@R#1Chp$^f<P8M+p^Q?2m5Ei!bD>61!<N%+HE1Hr1(IOyIdiy!EHz zR@V{D7JI~Q<T|3fLL6vpCM?<ut@y1ZDabrxa1n9L(`=wPrW_2wb_M2W$S4<XX%KIC zJ;9=nZ==BTJ0SF}FZSo3lkawU-)q6YO&~O95bHpl_TO5anc5Al5@OPs3ugnDClGr^ zg^s}{e_goNXo$bD_4e8Ij(2$fwsUvQ@d|fTDLE7tCkd?p2rJ`T27zVu%7`p9&n6mC zpigVF=VFX-*JC+fxD-d|AxDyVYc{TTO>o^HaGvqy9tIGXxDd^B_U|--Z){q&e?s2s zSuC{k@?wnq92!`~@~>RrI=*#!;&nPIb>FnO*0p#)&+%S!%{mJFMou9%CU`YpS2!CW zcWM!9&GmOj>(^XZT$9L#$+t}=BmC$O#<n$vw<_^FMixh)&0rNopGs@D9n$dw)#nkW zH$`f_Deu*2-hKkC8H?DZ>61sRoY^ZpKu6`JO-K4jw+ioDo16VE$U`N>L3!K1Rm9*1 zoHfU@Hqc7mCCsOto^av33UKp6q<(N_8g22hTzDF2ybKR1behews~U8k`;Cj>vPTO6 zV^E^c^ALMSkbxoXovcsh$(XbL9M>w-49mJ8#Kk4&z$ZQz%OP%DvSw7Y8w<Y}3tu7J z<*dAGy5KJSjwb+sZDZwLc)90}^8LDx7zB6^wTd@q@;B&+{sOpNoY77eby-jf{yzY9 zK#IQs3u?d#&`|$j;6aZ+VidJd3huy=2&=FNs}20H519E8J0-5o^-~6M3)2u9I0a|E z`VYL|2(#vh&GbK<=(i?&XMTHy@*o~mMrCj_56KAthfoVe@l`fUsONEWMWG43;0mho z9)2aRZIeBaN}}E{it*471F=2*;1An#5aDGE>i`elP+&VskL&RdoB#{3PzeT9l!4{7 z{{XASBc(j`Q_JbI8RQGK;IoK0wWlhE^?(i5fDOnH4*ft5J^`I{_D$on42vKR00}_7 zW{b5L598AfpWsh`3tdtpUUvWv!wV1JJBm|t4@3qI8tS-Hdb0p4D*vDjkI)NARaI~m zuDUB&>=gf#0PqaNfTP~f9ZuCuEFo_EU@!B~4yv#YN0o%28d!+~la&Aq_?jO6s*^cF zFWEp1qZ=Ml6TEbbQ}cjC<xmRQP!w3xwrPVB>46W<YYo<b4?ne~LCavjO1?)i!&RzW z;*p#GFbSdXuxta0Ac_u;a0&lV554dRQGrI&IE|BdLDXrqF!_ry<qhWm5618e=n%o$ zIF0s#63{@q`{)c=dlGw+lFC?@<XH`@kf`JEQ>(})^92v1LJhuPWK4|30@TD*feh9V z8sRVvClQT!IE_p356s{QA{rHitQ1kf3zo1H^XemSS`YUy38~<YO)-s5u~Fq9v(@@p zSls_3_?T6X07~|736RhaW~5E#B#=CDYZ8$T#_(@JVN*3BU*Lfb?NAKW@Q&*AWLO-c z|G>u3;0@3K3t3ykjG4tcQcp(V3%;-qAfZ5fEHGxmu<F1-!;HyIj2HHR4A>AF*wD!R zgT`1K6{-nOo{Vmw{11mP3GP@AqU0r%m?N7OOi-LF#1adtu|18G%{gK(|L_dP@Q$wQ zsnn<t{$MX63YhVVjFLNz9AP#hiV2v2B<W$hP*F{Ctj=q;P9y9K?l2G46cOUw$MOIY z^WY1t@FdxD!8L)!C;=YKtHbpG5BLxc$gqy&@UPN{#p9z4n@|ws#?&kk6{HXhlDz*! zR53ooX%D$1&uf^t=wJ?qkPJ_9lJ-W&KXE|(fEBX5Il%-8rXa)xlh%eZ6c23-#2~#C zU2}=!sN?_-^-v7!U}YUmN0;c=_QJtJNfjdv*amd1=A<LKNH2lB55W|*HpeHank&VN z6jXB9(+Je_fDi4A4+eF^IvgI<>zU3>6{xTYRAJb57}M|A4_$c@)#RZeY}cbw%j^jN z@Nf^mjg^Hck2e<&d6^EyK-4>jt^Ycm-XIR?pbA2zPU^*|40b22YrD`uij+mou0YX# z4VOF-rSt-}`|u=>Y`yY;Brr`4yO1892)k_r)c;@&(=d`s^bhcS5<A6mJ}m#5|MRPq zFqawYC^2COB<nN-;g0{{42O_%^`NXaQ4c>mt)#7S>(rQh%v0$B2eEJuqI47I0L8;X z-bBpD=k!_sz?TLQ9`P93_JYjMAidWeYasWX<j@bvO}o$#UJHS*x!?`uaLaq;h4Lt+ ztUwLlETuWV+XrJK4SPxLxy#vIk0S9B)6mEOjSu#a!zbCm%=%zg@eicH$w>2Zpxh6k za0mVXr^&n2RfH-3kkHzoKuD6RmtYE2RYe0n=XaDIwvZ0(u#ff|xdTxS<ggCr3XrpX zqHQEN7IxB{nrbGE3IC?KA6gUfKox-u(}=<o43?_fn+*gD65&zbX!QT4;b0Bn024s% z5BSi$_z>fs{8zp9544cCM?s$eWS<89aZSVKGAqR=xrhszxZ_|BcQ6UZE=rtU6G%c9 z<Ddzqa1Sso<>;`#!O-JyrQ$czOz}Fw>j1Bec{Y(NH)agj_Am_TAe3qa<&J5EvrEzx zjS}&?*b0N>(!LUiQVI?$wt$A^cj>c;S_-~Ua_lYOHboA!j?}^i)b_y0+`x`wIPY#` zVgIlQv;dGZ7Z0H{4*f8kB^6$~eUuy#TCQ*jb&_hSiVlzv3q1YY;f@i_1d=YE4&>nJ z=|N6%{#?yuHsl}<=&%l|K%%N%@D#b-<nYGOfL8W~CqqsShLry}KyMQ`1rqPj%}!1b zyBfgX)J$d4yGwCzb$MWI)89iqy3O>a>}(B!g0V{vKo|KBn*i1Lm|!A7n!o_n!(+aY z1CaZi3Xkq(I|9mv*_G}{lo=7ZVhEDIO(gavjN^b0kl+gS08N3e5(n`Q?Jx}N5WcR~ z66)^2H~tUCfb=nmkzo%&1JUE&kPDRn<YaRXo$3#4><rU;<LzzU^s)~x%wkSabEG~> zRrL??O%;s~o#jLj&#R8RIu9lZ=GY)!tljW+Z(;u62v@yKt^aZ?k(}m`3X>o|^)R{# zag;3K51|qas$mbeWI#MW54%%IM%Cdy%_QVb!S?_V-pK#m>jwaUJcJ1q8f4fI06B8; z{;ebC?%%n84i75ic<-LQf3P@_^JdQ;I&|~q86@|Q6D)G@P;#WHQR2T+>fDt>2f(97 zgESL595;@fK34nujk~uJs78+}>xDxWt{%Fm^P>90XARp`t@ktvO&AZrKTD|onf3S7 zEk|?zHYNL4uB}_VQpf!}cIRKcdMXj()i}=|V0)7e0j>vN9$AehRsM@*YFtW`2GQ9w zM@}0YY4+mz^C*w7M~?#A5o701Ai;(;36nzyuV1=!;?~{`N;aWNiLfv|{73p8N|WBa zRf4q^qVJ&$>;5z6OWi+rnSnw_s8VIof7z0PC#?T4>r`v_&V@B7`ChnbRvnvsD%4-O z;+BHd<xSZCe*gm%@F|b#>F1b3bi)s|d!l2=Bb46xr<XvqX)G)T=i#TQM`AfA9>^Su zDz1NuStlNN9{On`?o9IuwSM}6=pS~9>1L^U3Sv>HnIsaY5@@{XM>~}uil-lFD#^tg z+h*eKyK&y}B^!6d8AqiR$KtLb-SjC1oPO~04<X6^fe#;iuw<|)d+@Qx8f(_dk|Ezl zLyMNW2BdSS!4&CcEj<mAiZ8#+F{#190)+4!LqnNFLUVlUjiLMgxdf7am~zUXsNxw% z95}c^hac?-6zi<Lx>1FlOwT!~r`R|mEJpv5$a#hscu4AvEC@&C$D3R@fu<jOAZiGu z(UJt`GJ6mzO(;tD+NTtKiW(=zQul<8L6am@$CtRyIki3)J(36;WB_xlp{V)+tg66P zOq8rj%TYv{JOkBtUw#Rb3ZHlS0tcQ8*E}`RBDJBTmw(=I5~UcsMd!0_R`SPL)HLen zABfs1hMjmIQVA-9GX@H!?<P{Eom|Pmxa50`{3l6gpgB@AbZ8QYxwTM&`B{G?lE=Dt z%JFVf5r3W&p-=hoQXO>0Sr4!C>WQyeVk2{moN%lOhhwCF{s*0Z(Aw{uei<bD8cY5e zH_&<hIpmmoc*5#!0i~)(o>VNE$DaRs{=v}XhWv>um`AjUXP#^kA{(A}dJ)7Z%wW|B z;(xrMaaDH&qL1XC<~$jpxYj8Kp4~Y88QG93At`Hzkb?)BB%y%^^}!kJE$V;3$%&jR z<rx_$rL`=IoNh|l=bv%>L7HR$48;fDe_$`HANa%p3v>p@{zn`|n8~+a^2_g6C2{6C zh7E3rZMLK1d_GH?N17RDaqj0aXB=)4(PkWeh(#<IQyoOm(GFFtqb^627j!nF5o0|> zNbDE}J2=KG0V0HBmB2*xe1^A&L<9gy5=Tk;!62GIX<FHsM^T1HE(bc~JMK_NDX#Gj z7qZ78lHrQi@KKHzkt}X#s>=UKKDR55_~Rdr;Klg%rI1PigB1M9+dKesk3)3gFM)ZC zi}VDcf1oZEhro|XLUfLENT?Td_+Lsy2LP1#!yV)3#Uiv}4~JRKA+*9zH7dw4)on*M zc=3lnNMet5tn79Dph;8!(2sa{qjq-Fqv{B9J6KdgbCyKSLIALr8tS7QRyvxNkmyNv zp~f8msG&RNfyO{4ttC_mhnvbqIEMTUAGGYp-|X?MXO-n2-MClX%y&#=4oE861IHlT z0T{u^qcjg9+c+T63vrY~cYDf;InL1wIJmMWFk^`~5U9Wiswq~cS%`yx5+kE{tQ{c? zrZk%}k7NnU8|4^MB^mz$F?&c7ND&!lCleB(e^{r5<|t2#y!aw0p<^H8xsp@fNGxPv z18^vOXnX8&7HmwT9phM+wiF@}COYwne2U8__5;KKsU$^XES4GFsVBXaBNSx3Vi(OL z7KwBN4!sCkwqkjla(wd<_i)>qR7Wdv)W~QC)X`f|Nf@l)XC1?E&Oi`ln#{-pbu_bC zKi>$kdqBe(!pg{V67noG&SP5o0G{C9c*=Hm6rwHMOE#33!xgPaC4ig8S0r*Uy&}gR z@X3+jFea4mDMB3ffN3%<ds(+^%pCIwMJg@=qGx^3F!W0XlXRF$$Bk-^%}89sJ{ZfE zu;Uq&T}dfT+M@rboKRQKcm~I4!$^B(g&gx>PDIp6yi=KDc9jsva51zaH2R|*zL+C9 zN(#d*CCwmxrN(g2nv!`;ua@u_T%uArMDfbV9>9gHIHqWpV<vHl;)n-)PxBGffujom zum^d4dei@`2yo^=$05K0xM(T_q4ev<dKl+VI>oU{v3LYYb7wM%JYyaAATNNR<rav^ zD1F3ehm2hIRz&reBtR<3*r;|K4*vrauCwlo6auC2_~LsNeWL?qb+U%d!x#E^2ik(j zkTP|pmgew>jzH)U$+U?oZhGYV>M0Rkv|@pn<#LxBvbbYRf;yXN<XZmmh)XaJFE?gf z!~Wq4I7t8Kg%7&NUVyO<a(vV=-ofr5fkGOR#Dg8S$efK2ijIEF?j^Q^$6aHG=yIqP zNW^lILe6oeYVg7z=YX(7V(6c}=))HP$m5^mG7W3g10VeG&Q()sDEI)TCuEU`GMZ@L zehCFXZ2N~i`tuaMnd1(}001=qOFomtWfGo+hwxGu7f?0h9;JQ@0MN*^dtA!Q{)7lT z{PD3|3CPcQnGrC0>sAGCW@eRehBwT?>gNFkBFPbn?fOZR<FP`NE^KIs@M4n1WrG?~ zdmc)VV>OMg<d<L7tDxqAI%`bBZDk`1ep*2nTzgsL{VJP5$`+VZbRv2LDO<^l6EaO) zVjTaQ^+-kvX^@u#ppa#YBRuSZIBl@H<t5+lKQtUhj&=Mj8Ik#23VC#-7d`3H@ht!b zT@dRQM~NNp$&4>DaiZhJ<SohMK!z^$LLP5Qz}w5vHG*`sr~TJN0f4B>k;kl;4I=nJ zmwaNR_O+K>%E)k&JnoKm{LlhVmEBj&VO~gi0Ff4-007||B6Nc=bP}Ps4^wAeoTBT= z<jMX=DpFBw!<f8mto}?g?&p}GuLSZ%@3>et1c_K&>FXu$_CHuttkn||?OLb3HvmwL z*$Sj=muJa8I2d%Eo1N*R4>~3=fe!el{gVKwMK+jM_QDyxEz*}hP|6lJbx`Bd9@qc- zN5fkcD#vK}Y8U!X&e0WYq$zGnKf2<@m+_6~pI>?d$D@21+EK9-NQj!I7!!LUlS~<h zOGq<4+a`?oIe6Qqb;>T1>9*CFC!e?&c?dCJ5th*~s@brvcz^~>Sdt@|HR0i_gi?kL zk-a{X6t{p9QBw-3IWIGr1~g$HlQAz5!98q9H7*(q7m<ioxHZe-2#J^rm1+pRxQALe zge^)i0MirBONCI_D26K%a=3(GsE3;<Bu9I!b>Wa+C<jux8<rr4evl^vT05(9wN&zm zd8-CvsE0O8tr+nJ;jp&|0ub4u8E-g;dqaq&IEQ_pE*vtl7xcH2fj)E)wTu5as*iXR zAXJlaqcdHq2V}4Ykl?6<@P}3q2mKqx^3j`lNRWRxl=xYRy|^Yoxi7WJnH1CpNVte2 z3L$uC2U}>FIWv{wX+(pt4HC<hZR#&?(5DmZv^A3lh!7TRxf`Y#2Y1l7r3fDG`Nd@{ z3V&b)Fv*ths0VDY3a>H=lV~bjDhvRa9%D0@v#^9e;WE@9n}0|IQS3DSyMxYH$8+2l zlmHBHSPWk>I9Y^<3fnC00KpfD$IYOuZ@L5=O06^;CSoX--x3fB48dG1hIV+36M`c| z8zD}R5f4(vMl?of-~=XVz<B(JiRu}WR2oN%6{DD_eMrPaQLOZcm-zo7C%nKOAatWO zsS8W6Hc~7~eHpBJum@DMsjT3TJ32!x!61?G2l}}*H7O(uR0Ve+iQze}3H&rVGZ))q z2NgjSI5I|kdIzXflv4p7AQ40-ff9Ep1#*}pMf5ZnghM9eD<P{GSlTPVNRKP|Ae+)l zh(ZVWa2HDyCP%mjH{=&u`v<l$yreOlVH+DM<iY*3qIwXALTQYq$cl3ihs0SA!ql^` zw5OwK22IG6#bJ;cX@@#&Lvj1Dr@%^bC<g>;heg6eB%v|P8xWM>hhOmqSMY{p6vCbm zwRl*|sC1~j;HznLhw3tm6?qr=c&rZ-qBa4-&@{`l5C=+lMWg>LPXLh$o9l#72qP{+ z8F?V7OV9?vc`dy3GsdAsZa4?$fz3Q)2VyXaiu@1UN*dPDFnB13bb}=0R1T9sNViy# zW`qXXh|3oG2c&428Wbe3jLxFChis^Y7E}|x3CCV)AVyT39O(*fkiU8wrcHQE@}Y@J zaVhe2xGQoLzzM=B+?Qa(N6vH%l-ZDGxCC)<9tZ7>XYr`Gp+z+d3#dYeb-*)$h>-!g zL`pHFnD{n!m=O&`j+q&WmZ+)#;lKs`$Q>c6Z*j>*w9Wr;A$<cL2g{0G%1IsCP>8yR zu28kb1OSOh2DNZJ^9<CaLCSfkg-)=d6!A!WB8O|R4AcMABOgmGe4>nCu&@uB5#Dl* z05w26?G=z%2V;<tyV=Q^fdzpW)tIC+?cloRh##<mzJEwlYD>)%C5%h^hicHVqCinA zqC0#D3{|vKK`FLyh`+&lA3psDKV8E3I;nq<hEJ#q7wHbpyoX6Rh8&ebWYU{^2!&dR zLPgz>ScnC&c(5KrF^oYOPq~C^KnEj5G#L>HV@L)QOH~bp!xcdZhKf>oc$L&D7U2*{ z<FMBk39$&BP-uKlbeNKVIK!oplpQS$75q>fVv4=mrTFtMhV!#TkqmTDGA>Hez>9_Z z5LA=J3&0?UP`E;M89IL;m1eLEhRVIn<G!gQwQ>J21#IF6<s%87lhT&Rx&Xnurzo3G zO^2!E4TuQX&ZsfX^DRthjv*ns(K`o$Q?ozQzTMN4TfGKfsMw4sIV<9Z^gx~Uqra_v zyzj$UTcT2fkceQ=GC)nHqcaV*X}q;Vj6pbtEm}Iust2a%gm1OE%bSOH&<0b81$ziR zq0PRu?YRA6SJWIjl7I)+fQXg|l<q59jyVSni;49so8V}U;cB@5n9nzp(4dvMvcV7Q zFtf&Wh|L|4<DrIHu!mj!y6`I2t0+0VOIz|A8@lU;!0}y!u()7oyn{Gd=4}YT=!bt~ z49AFy4G9KUzz2qU*e#*nafsQ9y404i1$O@^2Z(UY+U!)Z_y>;xAg3)p;TW4E{g0M_ z23O#ij2TWLQwJA%n|Y}T&HN8EdWUJ;hf5Qndzw>x=&;+`(d*=f_*;)Gfm@8@G8q*I zOVAA&;!Jl)5PpEB2TCSW^j2~(wji}8ZfKs<s!w-9863I<Y3K<jjTv%~CjiwKHmyuU znh0YEBe#l*e{cq82s#h~5HN~b7u$#ceut#M-FVxPyfR(90FPX~G}$|ka3J0ST;Tpa zuidqZ#f@OO_!InV-awTK&Nzob*av;o5C!}n!BF84X-fL}UU$V(d1@Iw8PJBHQYKj$ zS#k*p?H7PLN#%$+h~S5W(g#ixoag_nRsTREi%_1Z+0O$G$9niqyz(<2Mw9daN`{aK zQV_*1OCtQ(1a633{^E;6;EckA;(h^~-dSa1^NE9?pZ_u7dvzztXrW-ZgvHe%)ldZ< zZr>`s;q0?6kEtF5T1bI##(v_sB#A_ZFba2=7P9L_C*IBgK_h;c&cBq?_+wGT%4T;u zkFLN6Po@+{fKf6o&tNkLo@&pO*q=ub73bl>0hMD-xQqu&Lys{U`pjc(?v2XT$d<7# zFcOyX9pe9h7=JiPUGYeBL5HNEIK9&20FfGt7_xHUv8Eu0t{`4U)?zl5({qO4alwxZ zZsKH82>c+0Yd~eD>c23Gx&QwqA1DI}aTtVmAQ+X%jCnxZ|6yli7Orc6ged7}6{(S7 z&b2ATn1S$^+!RRS6bM&<h9-+&`Hkipi^h3CiaDyNHNENk;s+(JE?%9U9IR6c+=$1p z2XRObjU5aZt<iQqS&uN3PB?~gfGL!@2U@feO734qbfltygl3q}I)(_@>M9$~E`-o6 zh<FBIz*6gis(~^%efdLIaE3fPp?ip~eV~T@5$hwvXg@>;hN6aSh=`nK9JK}u6CG&4 zw1;p6lyUI~ao7Z-$v?VIhQae9gaD#zJx~zQILUzL1LLB%{fB1Y1>9wkM%JrcJ_l}q zgq(XYlt7(zc!n^EQDgsx>KP_6ip+}d$%Tk`=0N!ga!8Us{G`6p)rul)7}OJl8ZsOS zi@50;J!NaKELYAHOs7DIK9$?MX5Oasht8so47rD9s6`9IXWDKE{J17}z_pf$(%N|M z^UX_NGbC^Dhwjdt8p}iaEi0`CF+>|dOz><NR>5kh1-@iyNB)oRK!<F|hIc43abc4@ zz2tZUON@yNuOOD;kqBtD>&tRhX&{BVxk=uc8+ibch%Fz^yH;~x?oXnOG&6@Jg=6G` zl1oVJu;{jPFoty~7I$@O08<EK`CNf;IC5}?t4>CJ@rZsn2jdKq7*UB!BZum{<}S)) zV<zHh3y*Brkm3JfsviWnH)K<44a{(`2je*2f8d3|JMiX}sm@zZFV7g~hHz(#4)nzj zF8s^l8*!OH!(xshLbU94z!S<Lh<@;fwL(tyw(re=2R-y`^M&smqv8gcZo~ACl#x}@ zTCAMRVnV;FXNenZz=l-(GG&d{xn1%p{|9bpo9Hl!mM}0w`EtxkHh;L*78;(th=nev z<y?-z76JgoR_xk)26j+$h7ORTMigTaU!(9n#|Rl`fCbxmmCfGuJx9)kyH#GWJ{KbO zwib{GnFrR!T23*OI7#7VFBe478?UgdQ;}dL*Yu*y3X}N9n$k0)xP;iNV#NCIkN1aO zsKp-NZgT%X^HdCIe1~j%G9b(4P1+!cNP>kWDF=!y_&lWZfyc2af$x#oSpRipQ;|zn zD2`+=R=`PThdMyjwD_c45s9D$BiuM)a>rgvLBQx8zi14yHlLi13oEQVMA?f==!JKP z8(D1RBkPs#m<Lm626sgXh-fkr<5D(vkY|A^0031Pc2{CC&UR~1k|ei0<8@asRmg`3 zDH%*zr0*JkF@3dAUm#BHaFvc9oKqra6w`{p)Tl=SZHYjIA{BY&Jyvmm!Wz4A#EzbY z<|Lj3ig*~(JWoT^Q6x1KQ;UR2)e*=k*GL26FUo&>f)5mfU5=zz!KAQD0!m1y+Q;*h zPFDX=%eb;4Gx-{phRKro8~6yL;lT(~M&&LG?SJ?LQLLI+ZVWB&vOxidLfPfLs2_m% z=kFfDdjJj|ELadB!-MwFjr*7D(!X)?<dGw14_>i$83FWbC~{;&g#=69>(?(Mx^}Am zc_W7oz(#15VxsGZZYIf|2Y1@D=M9=GZ}9BRo0riYt9Sl_o<wMJszIMUFODOpkJY?) z=gwV3_YYaPdOfKwluGd7zi`;<)sr{x=RZf~{#nhdcQ4<*etQD7XYP==dqI<m`v<An zzj-?^LXIr?qR5l~nnCh+?qEiE{5odM`S&2@$p9u3%xLc)F?RoC8iwc16*Oo;caHxC zK(OCEa^N`GMmlfYxO1%Z0U(}qvgy;1bDtaM&R4g2=Y+$xR`ws%s?5L3Qz*|KK4d}9 zk)vy=8{XW1A;<d%jMqPO_mb8d2jEz!e{k=+#}|I^9CL_Z_SBOUM388Mjz9ktL>Xz4 z=~k6OJMm*rFPikDpHk%f)6O&SgqBur6i#?iYUIG<l0W2lGf+^_a3YROyjAsAU_%vk z)QbDC;txNMG3VTK&ixftaX|j_PH_&|quoPMr3l_+hqYx5Tu2f0k2sdZ<4=HNl3Au+ z_|;?2B(?aL;Be!_qD^B&S{WHb1no4>KiX)b%{cvh2mm|8cyuF`dP!KPJPH5x#^OKE ztYZ&LD$VANH!9&a+D^R11ROc{>=e;fO@5_lbA3e>-9NQt6OVH91cePg^9+<DLW)jE z&^++qqa8k~t@dS@W?GeKe9E-)PdWF&Iu1OYC}R#>%PmT*NN5fwjz4Jv;3{V0nB&h* z1leh1wRaYjCqK<lq#pnokpm1cufawpisr5e4?L~C2Gl<`!H6kOI-(O4kCy^E+&}72 zLylKqnR=>K3MEC{blte~YCYxQlb}LXMtoR5y}}jGTw*ap%0KZ~+p^2Kp{ZsnaG5pF zJ=~ZAuFdz9W+h1k`4f*lmozg@QW^bI4KXl%D(0BqRoR(6>8yiZdiVeQ>&icymFdrm z<j^M5PUbA^3&`i1D`9{YN5m>W8kZxhQ-_}2oQn6wQx7)W{Q9X_(rlva%Rb2ypERGW zEElY44sy)4ZVt{6e&eVqO-1$q@OCqrjAJsnN1A&UsOVG-i8$wk1mi#J*g~(F5>IxQ zG3>w-4^ZU5f=R$Ql1a9wjVYW>!|%|!D0pPDjgBwXnDZn6_=IE4uRDtr@!i(-+Hq3% z+!c(<<wPF7_zlI}NhfV8$jv3%yyF-;)}zhnJk6U@^gR5q1k8vrG5Vg*lkEf^t9yoE z?DHU-^vhPc;Y~&`0Smkkgly{Yg|c{Nw<3*+I7#z`KQtx|WZ?e;9{%VD=0*awTZIR2 zdJD(&x^#{2jjth)`3EJ+F%QKB1ssQP$9NzoKK#sT630Lg=H3>ISdc?O?>myj(1oFQ zXv1{l@P|^2VvK6k16~Ro%>^S9!GENK9XZ*_0bwyIGNtApo<c}Oe36ZR3~7nwIw8#7 zbPqR@qc{eE9t)F5x3t*_HTOA3uewnW0EvYbyg&!|V(7@1q3ItwL{QEC!Hi@W&3%c& zpxO|ku5mOYXYs(_rDg{YmYB#d@KedVx>1aHoRS<bf`u7BwZ$Z%;~f9O#7gWFA77|r zYj>L?29s13;=BV$`_LFSq^HY|$<S1~LI?C@b)Sv=BN+e6SlJ^Z6CX+>hFPlt#~uD* zj?aZpSG$78J!(;l=GlWEP9j<+iBz}vRR~Wran&W5fev_iqa7V7)H!acN)!naJ?nUe zIah=UXpp0zsYF#lKtxNteB~YgIF2ykhtItzDI(RN;H&sJD_GehDjrQC_OMYF0L<ks zmf!|AA8Au!{ewFR0>>cUF|B!C!$APZsn?2XRHFg_sYA^vUWOA&bnp;H@K8lNBn2X- z{^h7zJ?c{1<Dyuu#(^?nYJ2`dRzMMjB>(`QFZ3a<q;55?Tpdkul39v3!4x0Zkkwpr z$`HBEm8^}~STcT<)4Py@rXRJI*Zvx`e~@CELXH0je<Xz$qB_lGWDUwcoN<UY0l-Op z>fD0_;<UIP#IIe&YTklz35R{C98`^^YR4p|q8>!6cmdI%R+dw5{3C4rAZu>OYEevd z>nrZ?M=6#GqOHPJu6-eHh5iAg<V0j1dSxMX8w=Om0=BEvj2=EV)1iM@LLBi}>`mKC zQ3TCHhvk5aJjVeEX*g(SxI$7x^5oP@sJDvoFh*5BQlS%BZy*N|Xgl1Y8Z|!9mVfNa zrshE-OR1zB{%EVXPDn@hWOSqY=uptMTMw^6h$KF9j;`*3kL-EwE}ytYSz{QPyYPY* z%1X*zLXiqdp;LToIq@+jK}lL^!xVl3RPq0ciLU;|qaVRAg*V)Rzkl@B!L}@uX;8B@ zEHBL*DuI!w9%3JZ=0zdLorkM*38ajT!-Ce!O;nHu4qw1IDZSz@^-#zVMX9qM-H??H zu~v>&*f6Q?UG!)aB4#0OEvbC+lU$lyCv++49*<y*QbN?al}H%PCal&f?-3JnJfj*` z1rcx{1kK!R3LP{O2g1DM3o{SXRA{`1Myc^etMy78CymOXB6gB_)T1BT@tCsGTVqFF zBtF5=F-#SfienVog6S*>f>uTtcqHgD?aK9sF+DmqgA%|d6U#b`v9fWAnlGG$%!=G$ z4EBHuMzDYeJalqqI&=G9oXCg<M_T`pOnwe(_u@;P9kyY8RD@R1gKwWFbWcG75rjw) z;5CxfNJfKvG<SjYIrwoINZ4Z>q(ci@2q%xbJfatkNe?@Wu@M9BdMb?C%}Qc)#h}Q; zQouP%rUJAnp}4|E%GpXDEs{c(n*@2*`A1vJVKRSk?4&+{I$GrM5A6VIsNAqbq}^)} zaUjkxn6t+qz|jwO#+z6dNs~G3afl&?8#5J*x<PcF7q&e@8yg>>q~wv=oG)Z5V=g5- z;sLL24Bg*k0*Y)nVJU1H{8e0^C>Q0CQ2+ol;%z}jeL%W-X5qsgWLf(^q=AaEhdlOt zxl1a3Yz{r?-6A)n(DAII%S-?C!X5AU)I#-zb1s`IBlB43*3fY<@D<%XlqZTaypi&F zNW&Mz$t3)wu1kh(238~+wn0}KpS`9uKGz7`$GaJA^imNnp}hk?%);KmA?Tcka7O*j zfsR;EL^&wj!i|JF5l5d4-a4$qYq$*WNk+b9ge|bchj@cC(1txo-k2O+rC8sIWkWT* z$?jbmu_zbS>4TH#2{u?mP~?TNF-vx6j{s>?P03yjTE#dS$T`Hv5xq*6HBnC#6aY4c z>@1+|3=Hxq3QM#DF_c3&oI?ffTa-l~z)^|?dV>bxk#cyH_n`xm@B^&4#k5phG{Fzn zOkB78gCd~=%iI)vpcnspz=b3o!admEO{IoCghD9z!#gYs@VUc!6$t_MM8(_#(agkZ z5Q?NUU?53`*QgHb(93K%gGPiznNXf2cHlht!ai6B#O#-u5JY@T5IXR~`C&upA&RLa zMZfJ8Z^#&X*kCM*#AeMyk<~*vM8qY;f^V4?Qq9#~=u$6S!aJA)JODs3h|yJ%iFW~( zQ6Wt?5W_|w9V~c5ISkjcjRsS#gfm#)I2_V(z?nc`Rx=)6faubwNQ*t}Rb$lFNJy7% z{ewL8L-Ztwj4=ZZK2lNLg&M+zIn=@=;DuQ%)%d7ZJ^Vv~m{UY-+BrA~IeM2><kSwf zOME1vSYTs-kYoQ&!ALv|N*<8|jdX)d4CI*P)JAv%EaXDdy+bLu9Yc<zbbXh5s8(@o z1pqjhvS9-WwWDJpL^EDiV*tR!)dSgB0*&3DEQZ`pz(qM6g4@Lz@bLpbh{v3v#6jpF zX81!f{sS^*#66T_=Up7VHA+0h12WP}E;s|fnOT77Q&5l@G<c(kHJv|DrJ2-KTjh~D zhQpMI+VObNLfAt%Oap?5#f;&jO}$(i(g$3SLnrhH0Mv|4;fFsIh+q&0gMfvl{a|Gj zM0~gcGQfyEh)AKNgta(eWDEpLumda9!#ViFg?YnI{9B`qj!8NLEHqCSZel!?imtVc zs04{m?OFeVOd%Q8iJHwLHgsD#I2%$rXP`08F;ql7D4Ef~Tg3d#xtYVHWraXx(T&)P z_2dg{u)|6~12tNonH8t$0fni74K(BgkeI{6=vuju2^LmEn@CB)q*VDyQ$dKItl)!} zSb~PNp=A66H>gY;h5|UGBTRKt_~3^<=uo(f12;UvP>PEj_1@N<n}%G1Ia~@PW<^TC zTX<SYzSKiUtOkv!&W28yUg%R)S_*9#q&l!dljM?|VW;$w&YLiWK9IwU$%-zq;DMnK zpjpsi+ygxt<oYSgS2}0NK_>v*9fCxWHhkfA{?B6R)BV_&HpmG(6vGpO=hKL1qX-Z& zEa3k~a)MG6j6MO}j*!FeY{fgUVZseygt`ZDpaU(ukvB>YU&g2l9)@;-(141ABM1&+ zlA7T$XPflH9gqzPSzHVa$UhK<w_JkNIR+qYCQ6XeJZQrsJYwri%88=rcYMy8y2fi- zUTgw@sv1+n0f#~AgD<>;JM?Dv`DpU60ywzCi-8d79BHvV2Y7sr$dHUd0#2h&sVtUH zEg%~{C|Oi;=_igvp14Z=WJEI997{-P=P7At3{XGB1Hi~qnY5));LareL$3bAQS_&; z-sco$0|jl&>WyLbJZg&G$B?=dKKO$;ydE36*F^+Pdgag|L<E;Q(ty|<d%#I7bdLWf zt(c77hd-36>OcyNkOM23CaYS|PTU2*bk-zlM1NXKMgWI9%!99)lV*<Ky;5B@kV8F$ zLs=xzk^1Y|fa*caMX(v9A{}P5%3dVdBAhgXmSU{7lEfzkLo9g1fUN_(jBLb=899(C zImAQmFks6ROux|*h-5=B`5%WuZ3f8_kPN9?;KRzroeSz&I55M2217C&t^3^tDg;AL z6&XL&ojvfWgd$s-)IxuZL;ZLN&4Nx|aO*hq)1^>VIb?*$%AKMlg~=(P4Z*@Bu4T)B zhyy*yaSR8w^r+M+N51|8J~TsFTvG|ToRT`mb`9tzSPsG>Z7jy2E#ku^1Oxx+ER{o! zD?|9z+qeSN+5<6MgH^qZLuw?J6+=#4lrolyY6(!;nqZ-|M>EExU5>*$Y=t@KRWrEB zPP!xX=9G59?LYYK-a3-k+(j#F(>$cYBxGe!Jme!`Q{s|G{jkqmL>Fr9g<lEH5mgy6 zU<}e+Bt~W=9IcKqtb_yo!!^2$MZv;q90x?;g+qR?B}T+GP>^2nRRvd~PY^FtAzS;R zf>G{nEG9*_iNhqcgX9JS!trRv0>+P~TR=TSJH*l=DvBeL!xFZ`KZsR&w9MuT9EebZ zJ~)P+uB|zqL;JLq?ZQ-y{@H)(nO@CGWWleE6%GJML$drsC=5}*@~{6v7TN!11r_<G z#@-J(91+(><97~@=FSh6g)40cL{c!;i~IxFDpL<m@qL~np5a3>lm(Z}Ef=q_te69$ z#oY_rl#;+hQ;I|2HLlursOWS{ngm`qqyvj|WhJL#SYE{9`2#V~l&A0xv204ZRsu2N znI3`aC$r@-fu1_-8Tqx~e+KMW>}7K%tet!bNVJ{o7H;GaM4G@uIo!cK=$$#t*-^?S zn6k?}km)=u3o82$$#MpZbObyAhZG(mP9ab?aK)>H<)xa5a*@LoPlGq!hZY+rt7dV> zfKWG(0y(swCEFm`++969f}ifp=Jf?u*hAoP!%GBl%P4e8^hW>HGVecBLU637kLm=C zn8QAlLerhb>Gj>n3eXjUP(28*#**|wM8vXD0xB+AL3jxz2u4%>hXA)%{{2Ha^}-{p zgoJP%U-%bs95g#TgFC>(Mk5|tIHEW312Kq0J7hFETg#@L1C0QHGc-(Atk*>2^Fn*x zIk*D=u);osgLyoJPESnYL7kq}gY<O6>jktxQ|UeEQYzF!sS?LI2yp7^MOHvUF7#GJ zXYFzRlT55bEW|@b7tHZZUQVQ|D}Vzyu)^Em@FA1Q_xXa}yx8_Ua*v9|UWr5Cr1OEw z!%=JkIM|{Xwii&;gGMzaHe5nKn8TmtGHK{VQS-?-JOlqb0Dwg0ah*IhIv7JZw8PMa zu9*aei`IhW7?@^{Nr<(TP=a<a)2?>a0|*7fGSo*{+x7TRj6LwjMD#;BIIfdrr%V4s zEMNnqyasrO^KrgQM$}w#t0hxwie!63E*yg^WJB|0k}6AdRmeoH)&n!}<zCS3aP-4o zP21irnu^@TCUnCxd=_K^@=d`T+4z_)8U{?gGf@j~E^@={DB{cX40tdQa6JPp+@?`1 z_n7Dtx)OyubV7b+1)~7=E+2#d36GO*ICcl3P{WF{;lnE2V?4-rcnjHm9ONVjA@O+f z1*O?BwfB3sX-+gbga0SIT!Ss(H_@H8(d|=zgG2u(WJ3swV9l~?j>M}kOq>9N_a>3- zD(WRJu*o@rbIV-B9=F0VByK<s`6C6|J@}X_1fRQ%ID4W4*$~ZdyIP-nc`idni~GYm zv_d!Jf{g1o!Pqz~=tC#4Lq>3o6zlS@D$E4AMMd<Fm-k*8X@`=B#H%@Zd&Mw1=#VQg z2HdGKHj6~avWr<Nu@HZ9XK(~Nq$QbObx!m{1s+2u=z}=8v!y?-nXnB%*a9}VhDgqL zbLdK2V8bdT1Lkx&B#GHIgu*0P&QUb;_^jeT+^;D(Lr!eC4)+C!;KIJwclZpkdzJ$` ze8Mt7L)B&=bMMo6>cb@LgO+VEzL!Z-Fl7I(y3~{$)QW}sUTH!*aLuhV8d+`0AasH^ z#9{Y(uU-(>$UK57wB}WzuLFnIQf0&utHL@!ltnghaWR#p9K#^&gI9<}PomcTlF3Y} z-12xtM2uu!oIFE}3^F)E>gh?&iw}yyin@0KI9!K45WV<Nm%$9eBUJ6wzob@87gJ?K zILN|F!~}Jj2{|%EXSjnU(1NAp#LLShUdY2Zc*8%sgO-)mI~H#?w#QPig7m}(-jf8} zFO{B@ha<3s+k3ntK_@>9!XRjLm8UvqsuMm~f-3Y4MN@jQe7U1+f+k>CEF=6uSV}e= zLO<{-*Vwsw(>Sw4hw{h*J`hKfyP*HjK94mh0x&b$gieBi)Lnv@oj3`F9H2hSsMO|* zP8x*+A3THAoZ0Bl?f{ObDzJmyAN-rMJ~>Q6Cy;}K8BLP9xsSh#bd-Yhm_w)$`G>U_ zKFGo*NQxRye#9Q`JA{HC00g;u_0XXM0N`Fig$olNbodbBL3{Sd2~?$OTt$NsId=5O z5ahjw1?~L<ri$D-k1JUoEa=Z)MOTyh%_|r&q{5avA<C0CE@L)T^?=Tk$May$h7Kpr zBZtr0BYfoMA+>sS-n@GE?%W|~Zk)ZVV?7r1X%8MbIhx4Hv$-)TNU{ej;^VU}BRK&5 z=C)KS(qTb(|0n^Q=dEAAn|=Q~CMNgqP_2Lb&Z%^m6X8<E5q*+F%<9=xy=4DBoL3It zBV7HcZg%||w$+4a|G7d%4xU(tK6&@%J(gTXTfiuiyXP-<Pv5;qqKo&>S*LU3=K0f{ z9Kbk#wQBh@xA@@l<=7oo{MQW^zKqvfivNB2URHa+aQ!nkk3D&oS?d9qbjTiaCh|!? ztKyl*6j#PEC$sR}I|`|#JcCCScFL)!KnKTz@S$>QbLF3SG6bNYckJ;+9dD?sYPSaq zOo+d5tf_~p{8oDKy@O7xXA@xTV{ybFg@h=fg7|r7oLJa8a4{SSWN9hKys^iaXY#s- zuLfUplD8t!84Q+6GD82S9~=8xYMg(lp@y7ynsiaWg|fmY99i(mYAG`xauNWa6!I_@ zRQkD3&md<D5P(At`KO#hM_g*2=QJ^e91-8d(J#R6L8l^eMyZBI<FZW7y*{5@>YNY# zX;i1z7AkR`QjYm³Sl_96_Nd_6wCUUezOf#FuoPJhG#vXL=YjwzG<J{Dsc*u#R z3vwp96i%Kt<<AnS+<6OFtN1+ip2w;YWGnDu^K!6C{`ki@z%<Nu-EyA_r<8W!T}WIw zVVuXFRqQk;-f*!yD?qLe8K)jX<sI@mw7l_SkbmH*C#!i&-AT@Q+9AZ6wBjX?%ZMIp zMUxQKg)O1VoVx!*AFwzRw%&y5!iAVl$0~VPtti3f&Sjk)I>UnI;l~?I<e2iGrFgcg zqIOhyq@Htx){o}B`tgRGWE80f9;XVd>>YO|2`0FIfDG2R7vp;h8&&kZny04$AeON7 zN;0^>iM;z{l6ve(h(n_92G|~N23dHZyEPWis>Jx|C!A4C8K<1LNWS%;e*WQ_7fRr9 z2SfcT<Hwytjv2=r&P*Ne*}AM@WuMCYS-ZVk6M_jJN36joY`zU2z9l1(RvH?9lHJJe zmK=L(6g$^@n6W1xw?4DPyzwTPP1s>=H1aZX$DKh^DQfNJH(RJKY>d$-?6~T764H4H zLna)1=qCRf;qxX5B^+7VpO7Nf4`>WR4*wX)eXiFwC;`Su|6oTkE@6+%t!zs!f>1)V z=M7$10v_$qNWBg+oqx2W6RSgvmej`>_B~~GwbRZ3J(4vT{i9C5s}c2x*Tb>=;~(;X zPAozZ3futkAuv&*66f+5b{Jz7*q{m$v9m-g!UQ7!*qS$%!HZ{nE_~RT&OG#yLT7m6 zK2!w26|G1fB+i3Q*`P+l=E6oMI>dh5_yjhvp*A%V4JP)e$3KqoKWXR>i#~i#E=)0r zS;3=lYqTSBkOIVFJ!2i0n2P=WQ6M`W1UX3Dnlq~L33dR$Jo*XFJhI`6V`#%0{J`BL z3k3f}<AehnzF-HE>PSlf0MUNH00z+PA;eDl5Sg+8%wSw`30H)IR<_Do@zCLpeyk&t z%@_xX;1U~5bqPzO%!Mny=$Qfmg&f(ag+5>bjd<__Td*U~4ROg1UodJeJTu2Xg0Tu* z>Q8vd;g8@tQHx{HB0xroq_Yz8j(?b<7oj)?!N5bWOeJI-_b>)KF3}8%1QaP7a|t>o z0u5NO;~C{FU2L)f6m<B)m1lfs1LavS`(Yy-a?~FNZ#2z)(jpePtO-bynM{)QA{K>Y z)a_{cn}v2nFz_%&CND7=qSla0;MAToq~Q!=NQ)d~65lw^!5wh8!kvmiM+?_QIc)#v z!xsQ>Q#a=)tbNi)Mi}E4(FQ7yLr9|=n_yIqhKG)SbaWD_ppm*n$}xMzqaPdX=s$FG z)t*9bq-cQ#CfY%ZFLI4MEv1exj^PYvkb^H~8P`0^^$%-cBOBSM$6WiBHN%pE88{uB z{EFJ!oy;Q^y#U7@{$V2hDfF8>DM&o*Q4Dry;}YoDChoj>EA8dN8UK)*XA%h;(awXk z?r;TY<LST*{ezG8pq)D^Q`=HK$*`zk22>hHLm>?mGT;D*C2FEj;<fY~kI;rv86?fN zVXq|>@fa}<8w>kb7OUARNI&A?4NkP98pbG2Xy*ZxeXznC&VYqCAWJv`HCF$iTB(OM z!U5NE&^Dx5P0BwkQI7N;*S9(52o)a#iDvwRxaJrL7C+hD-&X1$#b`$}AVDi0zGjkE zL}EOk;R=0i_c6yz4p7`t3eRxDoh154l$ThbeX_V7tRP=ywA>OhOY$HdqJ%i0f{(2L zvCTsh+;BTN=aTs2sX=-pPy`H)MVaFs$9%JqJ7UX9N$nrGXfiww@<%AYS!`71ggCrW z43XJSeB{`Nm(L0fN&}IJQBDq??_p;ax5F3ia8sT=LS`aUGSQB}p*1F=V_$nDRUNg* zA;1xjfn=4iI8jJe`XLS_Yop0C<SAK@O&8Q^T7=Hk$f#Z;T6g#Y9NzyJFG*EfZCow) zAIQK)J$!Kucc3qKC&p1i215#P$Os=ngYeEcWDjsm;vkz4$KaY~IHPr#8<5b3p)H7| z%dqt!&zlE37@Ujf!eg(lG53W1A#TqU<3eHOwhIB1Cb+(%)bLQNxn0w-fdFmPM=J=h zkWC=Nazn6C`3E}o{cE>ng&f*2ML7OZPzCDM#B6=xKdM0tczELy*Z5J-Yc3Bj^}`>~ z0P{7!2#;wq#^h|O4Ky^ek)(6(O!3hQRKih@Z1`e2)M3e!gw>n#!~%{ut(twYw!wRN zC>4qY04;)%tfnE@Q1OWeI+}60a!djo?#N9;?!j^*Da14X@NEA-nEa1(WSrVnm&alZ zTji#0blWV0mP6%u4huu$9LtM~<>&G*dx!&Q;JpSviV|T6)!ak8XoWrSEjYgWoOnj# zeKS^Zr%*^HH}MetN~C0ubr|DwQMbqKdfrs#ppqQ?_=najf=zgctmVt@@IU1E7)-!I zZRCRZRsK~EeDn$(*`NiIGCKF)Bl|g|0Tti~&6K74u3{qgDY1Yk8Cqemk}dHfrE4xh z8|+~cszD$y2DxPHBkbiLFsZ^Gfg4uj>tYPq*vB7W0TX}-li-C+KyNI(<Q@Eh8nVGD z!0bzAuJSlA{bJ;I>Y*00fmY<MBSh~vo+B7&;UDk;r}Y2r$&fGklx6uKVI2D57&;*y z%AvA$u<in_OgzK-e8d|}As9kLb25l$NMigdAvo3{9dKi%)<^9g1Fpsl7T`~z%8dup z&L-&OcgjH@SfRt@j^?sTB>o{8K4A&Nq3w2PXb?sLkHH`Mff-1lAPz6kSj%XhBN>_j zAJ8F%%3&a~qUt*0h0K8%*rCG&OdO7*1nbHWA?P3O5KCHc9C!`}BLsrbLHtmpBEZaA zD&p*>i4W1C9&iaC>>&t;Fy5+79-f02q+toMfg79<3VRDiz`_(_p<(vn5C%d6X^$hU zV?v&R9XgK5#zB@|(F8fLBJMD1a>ncEYBP)^|MdUCexRWe;AQ$$Z%&ZW9L#}srh}<= zqS`#970PfRekXXIus{&TJBV$8D8WO%uUTM(_b!1O2;vyNvA)EyBcetX{^8vcq(6@D zD$LDh{(%$V?;oxYE#lBMjKm*k#~Wr57Ai##lM7eoqzT;tu7ILe43cx6;}gVT5pxeE zuMuLPg;>a;qr!sWMsWj)F(kuEZluK-sPG-m5H^qvCVug>PN*2{Ve#lO26ypWN<km& zVI1^v=S*xE&8sKjCLDr>cE}1AOU6Sifg2R49eRa24zL;h#vBeo6bH!?%mF4Ka72ve z9kf9NZ?PMQiz*Kcv#1Yz+JP93#2XrK9GL$EEkjSnR<aVH;U?Rm7~n9BW|9~G!58-7 zIkXO5_M#MDqbZ)ESL(qXJ}fx4i721uIV=Gw>15p;hAD~XRitnnG(npn>kzs@EAWI1 z(e5EQh&8-HHQRx7v_TWJp(fa|8M%am?%^iEjKrjh8^GrP$;uu6ffd^FEjghgd}1dp ziVp>%37^9kVulEVlYV~561w5&SWInlk+o)HFqWYcj_w~&K^o7FfR^napluwc!qC7m zK5kRlRuZLfLmL|J97K~;FcX}t4H(aX;*7C$u4*CJtQ+o0e^d|v5M$-`u=bX%)vQ4q z>LDIJ?A?a42x~4p&cgxW2p|i_A(Q`eMDWayn2aa{#F2!|NmI?2B7)UYh2la)9MGYo z4w2TzLe-SWN%!K*$j(DBsZ$J#F{lU~QY8=pz%5_T8&vL>+DO$l1J8`{8tjbqs3Dqm z!q%2ZBmzrq1n0H%$I{LV&jzCC8q`sFK?%!29*~34^n;4*N787;9Lga&0VdIG4V3Qa zA)NFv*5QlZ%{#TB(!%sA5-G|$35fb3ah!n@xCS>;u~W))Gk}8WY9Sslj{L&vm+;I= zugEoKwI(QMH-!jAJkQMrm5D@z8I(}S>Y-P{hF6(%XyoJ{df^cmWuHPJ6%@$(91|iY z>?JkKrJPf3#1la0?Kon>8&3Z-3qNojJfk&912Coo9i+h*1cG&3;f(e|2d$D1cg^!= zFt+?bNPUky|KS=0>srwaahk;^2I?LrK{6uM0i`b!HIWzXq4O}u0%s*2<`QA!qWsn& zShY~$26IW>3r9#IajMK4(7{89p&E(<7iYEuMT`C5jwrN_YmP%@GjlVVg7{{HMqpDN zWcIRZ4hc!&9!Au)+HNVi)opa-ADW@6&cRJmAr#<2KnABe5!Ope!VTdiO)kN~QkGdr z^C(PoA;MA|&?+8MCBrx+tgHiQO|j(C<n4~m8(<+9NbE*IlK$dj33<(L0&z0fu@n&z z6&S@H`XRkWG&2a3BQpP1#qx_*2T2?(A&Ag5IhM0Bwvki+VM=k4LoY8Oo@1&kCRJi~ zYsd3J*7oUgA#pnu9j2;NJ`ci#))%V5V&FmR#NjajSKh3%abZMr*X?O*P-RB*T$kfH z60(z?!(zRJYr7RNkgyr7X3r2)w7ut7lV9}h8(JWgB=i;_^p1d((4_ZXgixgmh)4$& zA)zF6LKP9|9ZRT!qS6US2N4kY(z^;Gz2tJn?~Z%Nd2wEze_)Si@BL!WXRWzDQ=^++ zf7zq`ocAWSCb~1vR@VFWhy5Lq?q+4dc$;OeHoe!)IxlomU{RVJmu`F=B=>oDT}_z| zHe!9*EmKrenTPalT|wrcR_v-{(SL{ZYj=5hJ>g5s;O>ptwXRS}Sp)EI7T!|UH4kn= z>+&Sa6P_|Y5z|4jZtW!n`}z84d4hR~t~+8mRjiUnc33ryEHH#<(@f65gXZgHutU2= zU^t(v@1gsQNX?$1k<fo(sEmFpIo|R54Cupvp6~WRezBGnp3^=5fyw~8GPr7QyQ=wR zXKT;a`zL<s0!3zt%>FU2x;dr7B*^obKXkQe`FE7%2MzF%IM-(kt;6p4b1#m_R^_3e zb!*?z+{vN9)|_alz8Bmn<+)BnlKU1Lpg92mPdedp?k;w`)LrUrxet-geAyI5bmG%R zSftS1Mmfepue-<V!r&>KiKTPbGx8m2;U@8VI>Xa>Sc7bP@ja4iRpFGcnlxb^2K505 z5EE~Bn%;1Jq!4LZi(wy_5hh~%?4?nlcsF-zHs2D+A5AQSAF|D%>=(?8Z!LB4EJobx z3V<z=EYKo?dg(X-Zx&{&s@PVm&IywG#vH(jxTf!lt>0h%svcEl^LS(SixeU`L(snA z<!Du)kF*m?O*v1|JjaH$-QM;r?3V&t^<sQ?pOn@ufu35+)(Z`z^j?QWC*7Xn!-)>c zFXb>NKj0&DvG>=*SRz_ZE&ATh9**-uz21C>E7Xr_<8|U~y~s;Q?F#Syf%j{|q=fGP z-97k~&&%xR7S58!x1aZuF!Z8B<bS`6B+E~m(VGh8T4_uTn-IKq<5@C$ED|d?m|mWp zCw0*s&62g%7<c1J;EWC_W1cs>zFF<P=n{$82cjlfJ0k3lo0E2zWF~*bSE#3UUi|S2 zhm;%abDt$82@Ih3PKrIOD+4Ag5%iCbJKyAk4r#X$u<(YAe#FXssdVLi!ZY2)YFla2 zN;&+Sq+mBsI2Tc;9z@ku&uOq(?91LHcFvQpiRYkj{XI6iLYC80z<=!p6S!S+*WcrL zm-~3$?|nuUwQ`;!ALW{|p3m0ydAgB1Pd%RWyrQdNXcd+j<!ziL;a;;XFdbzbLVubL z+MCyE$W@Ts?Ct33w|nMRF<56&_ghs2Z8^OG%g1xw;e37eOPR|qOhQPUc9%mcBA4-z z=pLF=YV*!`!ECA|>=S2#<AV2V!OG5>N^+tEKOm|vcl9mf(@O-p(eIQe^zPcy-N54V zqgLOPKs-W9l~9Wm@70v1Jb;}y!N!HvKj0LLRykm}4yB8TESZRJA5B%Zg$pzp`<F$? z2f5$wbHT!fha}7$TYQJhIeIN_Dep1F@=72KO)7Iu4u(SrW1Ohpg2l_1t@6cGCq)}Z zw``<!Ea)aTyA8hy{TDrekCGR8)`HaKvaOT{sFMI}e)EKw-#A3>vU?=ugcbkp<T9wc z`?V`{bs3qYtT2>w;$F&b#Q^|z-^6%?k~uqoxW@KXnAbJCRy1W>G=Ize6#L7Rf+OHH ze)>sl@F<8$B1FI2cN?lzsL#<Pwh_H|1G&Bl_|8X^O```PXkisXGD|$}+hgX*=Tsb( znz@jhJIDW`ePFq*s+0raa_42K+7)_Bq9K+2rU@%Q*~>CZ;!+dK==>D;W}$J=n)eQb zTfZkMxywBiCu5{z8ow`bNIx_t8=kv;FO@M8O3BrWW{w>5%PFiv!Lo^^%zDZbr{$xt zhCf9&2|24!pp^Z7oTcCJ7n8n+@DNz@pYTF8X60q~>Gw3NTD*u#vvpupx+jc)TM3dW zURuM_bmN^!t`kpe<V`%Cm>iBp?_8lbhscGMym$i^8?xr5%o#*ZHG|Qydn7$n>o@Pc ztYXw(sTYgO#a`U7A%P>}=JrQ7OKF#9;aHdILaxpoALv92`_%f6gCHOKe?KAD;9eom z59>ca-x6C@D-P3Lq`xN2ewA5hC|qGf3;7q2!rVhl@bk5K{Mol>@u%gSsD8lnj(ed3 zp(<9m?g?!J-nhy!O>S#@zC-%AyjxudY(ULEgNC)f)qr2Rb@QbNK0!mLE{V;BP9IG9 zuS1^2N1NRYa6-dv@0${4Fn~eKiGb%tJv|vOy(up~{~WUgpTD4_nNbfuxg6v)Y^*SR z4ANJ2svR%-6nFYMq5k`$#kQb>e`kCVhuqq^05fVy!vn_mF$WtXx3RZi3Q-#ynx2L& zb>HfdO@7W)LEK-6K~)85+KOW?pCX80bex^}_IN2BKexny*uuv+qXFNi6%UKllN`CI z>HH>()q{ynk8L8MuVlh`=z-pmzhUYzucgwhsh4=<%oYjknA4dx&jjZ`@^sigiycFM ze%pt>zcF=9J`xT1fSEYzcp}sDE%dQN{p6FQJ+9s9cicCDnb$22m>kc8*9=#FaRLE_ z57xHQ=~gJmiaH*PSg&mC{NPj$AEREm;*iKwtF#tgH7ka?e~Dg<>;cJL|06>wQ8s9s zr~?hdf0`a{twG|wg2-u<;YrOrF@5cF=IS!bapo?Y9ZeAN--Xsc9r3<cKt~*-K zPBY$({=QzbN=z5OIvi6a?p2N`f!aOI)Ulx+W@?x-GL#!gUeqg_?ktf_rB6E2LTk~t zEKLniayaH|o!4%WZJTwwMClT#G^*Z;kK=XsV6mH17ycb$t##GQ?}|D=oMq%#=52ch z-MMCS4~G1V%e%F+U{kG)(Xy{nB_?VoVP0Lu6`H7@6Uy&W{G0-Xt&8ed$~IqmfOE@_ zPgm7OG)PequiAkqhpSn#-R#`!d0#C%hQqNCjrr!E$Q~Bfy;AdZdskFR*XpX;jceXq z=9gSedBr)tdkPWt#CA~gj@F<>WrAPsR>tvC9Bm-z?6l_2?~<mh($3Z&0#)CUq#8;m zm#2<IwV9=<yqX4uJ-lu0ucIt0z4_aNGDRP}xZDCuHy8nS-u7nU3Tb46&o2S3%ober zc9WW9{XO}LS8Ud%YH6A(bFYLakG<`Wqkw6O2mkmjQ+6ow3OZ^>`6tTfE<?cg)mxBO zRXOmMP&LBvKS&VdR;ZKO$tj7M{lmGLxfEhfkJ~KB>%{yG5m(=;<cs#mK*N52|8Jo8 zxXCPvPET%BDZ^*C`Ey@xD^7>_`0$0|IttX-+7~!Ame;o~pRP1_Y8CPDSu_j8;3TIR zx0)U1WsU#|3x88v@6ERNmuQrlR-cTTJkF<h#B{M2$olB=Kd&SA<Y}h=PRzx!+msoI z>9CjmZqbQ!0p_Zx(nD{ghb7OfBeiMq2i3W5Qo32npXIKt>@L+S>fcUfm&Y=DR#ID! zVXwG%s}0kvaoQ~*m)gP`k=P;I2!?LyKmjI8peQa2ntVjYIg6M%K#>AC52%%Bx*Wog z$E}v@6kJt_x?ahikPsxT$NrM*SzWa<2G;A)j~vivkp%}A`uov1v7aGA<<!^tSm(3Y zV+ldvm&?PNeVIA8>MUg||J@Wr0(E`HCo(wBAIchuasWsEzPGdF=e$N>hq>E|{togh zzgg1#A%@8KOX%f>k}Mn?vxz4yNwR!`4m`{G`!WW$3Y8269sMO3s40*?+9o0?l_Z2S z75Y{f!pa>0oG<h-Hk0O~8holtni9b|tItZ$#(ecidGC4lJXH@#QY>7i2Bc<X?k!jF zlaW=BR7u{V^z2i$3I((8G-kKU!6jqS^bJ>J;oiJo58!-N+AG6?8!4j!PvVC0B!>*2 zM6je2%cYwME64&J)AGP=9OryF+n$dJ>-s^JaqkL`s7K+X@|*#-M4LN0IN^4QrCexX zxeVDHOsOrBW2}___C|?CaYrT%5^BoLFgPYNH~3Zgnk-H|`G?MUDPwfon|RJXdVab# zkgti6=nO~s{Hei|rC~guXa{9GAP}a_-F<g3N&i2>CN3Bk$F{eXOVklNgRE~)^W6SK z4RV~Ri8EnhX_v-Y@McLyblh^RTQIUS!laANjG)$N3vNp|jK^HROS>o(P<ZXeqBXw; zTYf_MFj0W5EKflBE6mOAoMfaq>5<I_*(C2TG-FGefO17(t%ahHHdoq_DGvH|1s?m} zCbTSIbMU9DzX3SHU%W`}_V}A?`V?1xp+pDESH7yphQVv@G5#w%%UN!zG4XoNT%VFu zWIY(;BiBPG@gkyEo3d@*6jeNQl=*Bgn8HrAs>>d_-U|z1db~E^VD{ph)B~f%*K5^9 zBc0{Wph&8qQ?i%Zm11`Ejc)=<rBn`P&D5*(I$oQEHS;SOs4fwg>Cg-#8X;v=R_ejX z*O8-K)3f@jzvH?8G0$?IY!y4c{LwJfxYohbr|0}^YUn|fuIw3!>ye07N&wZ2{6Qm- z<YHI)FiDiT)`t@$+D+qX01*^iqaO?iZY<DvYkq~$`-jrwsK26fUV!%-YfM5CJGQgb zhqfZ?%iQ&B=Qszc=#>0JJ{W?@@7I1x&+pFlYK%<aX_|KbHGd+rS)iC9<wmEDdqMvS z;96){&Wke45;YF26O7Moc*5zlsQ1p3u-X={aN5w;FsCgkwO!2VDED7vb2*!ybIk-H z>p%Sk@;dzbU(9vCusT|(MgQfvI!j@u<h%GM*dN$i{SDuV+iqJtxu||6xxy8N8Jw8M zRZh3}rcy9|h2u}nuz^k0O4eyP?6bI`-6-#^{qabB4L8qFArf%N^jQpX3-ia!sQb=` zGuX;fij@tp`}mw+$@A=8c!S;RkoXPm^1LAz*>*(z)`jG>Q=KXv3Bp<a!ZZa?Zn8bh zm2X-RcRwFEtD#6ETKpKab6cDJAmk$TDT(=FRvepVx)p$o4S(zuY5zg3?2*d(2Dp6> zaoU{`mHvx6J5V&rUcd+Z6VKI)DmGAW<_g-6h|+nO*e|qMWSIiO?v010_Xn57=)8PK zVn!v$-Mvs}`Ay8@E}LxLo5RO#!A_QvPrTkZgY_?o+CSc+^%HT-t=T%8(9uASBav=8 z<E==KzFmDqljT<<i)2d2Y`u2~T{Sh)4LNI({kOqQ<6m$TTu<9U_9BaR%<lrYi-X$c z;byc+A#V{6s`{16Rv@W5W*Xxn=FrSmX7O&1$cOr8Dqwy2DZ4*B3qF1M23Gi!e)7Kx z1MUBITP}m9jX3{Uyv(5fo8b_}qLgj*y@@tk=y9j8>>pAM)y@@%AJW5OtHoB@=WcKP zKi#_mj2DpzhcRQ$2&kE(`_{Z7uO{fhq)wd-F;pVr$qcYNe|bD))xX1)p9YH@L<nI> zq(3u?TvkVr<pf<;^Y1i1<D8(wx`MfEMA+Gwh<QscH2Q)x`TS+wYF*>Bsr+ImGc2q< zEJvNv)HSz{@83?<6)p>gXf;}&yuYPRCB8jCpTAH4Jyvqf6{<v@@P{E*;y`L**(jpg z+`Kzzt;B&X5`A?d^@T*`6i*M06n~jXHzzGM$sqA73x(07@6_Oew<$t+Z}E`|7$Tlc zerIN)r%l~tMICU?l+l*r1&-jR-X|=WOv!7g@cRCvqD_boJxv4Z*%^~#ct6|LIQ`bX z7zZCcXBT+8lhLZd97-bpLWeEW0F2*{f1nc@Oeyo(60)$*bb26zU4<~7GPg{4-nYAh z`X;uQ=Wm9F07(>-Cj%%w4C3~|gi>)L4Lw(0C+GZnz@>E5b13cSMg#^8`#TOAUWWC( z_XF(n9Aj-lvH~wPINdbChMG^%;g8dTt#7cg+%n$O6XJ8)2#0WvM_P2}`(T&|0}-vr z)u5dgoM9Qk%&i4JMQI+nYCL>S*KDDiem50Hrax%GbtVHju*keE^Q0A+7?l&4+Y8w& zNt&%zsG4P&k@N7k;n+)LQwoLR^;j;)Aq75)wRz6P2nL{B%BfuBl{6GsDSMosVVuBn zpWK1%?t{b$+(MI$I5y*bUdq=<9#?Dj%M!+)4eV*MI*F`Is6Lv_B?bOD&94S5qxt;8 zG71<u5Ft}Rh@Ptknw70<Pt;Uk*A52_cM7E3X86WN{oj4$W)qJ`nD!XlAT*C_kw6=u zkdr~h+LRl}RLaI9^T?^fVi%X3FlEZqf1kMlQe!Jz)s}H(kmEE6<p|>0vdH|7f_Q|x zJj$YLfv0XY<TkC#GSS=fy>L6x%$)7yQ2Z-nUYpf7#e6RaR3NXC=*#~c2!=C7yzmWO zLxuialBCXL{hGy;4|>@(XGZJ<aUVRtHOtn!|LWa)W^-$L%64l$-58q_o>cEB8#m4m z1ddPn(A-SE7nX`<-NiJPOj&(VZx14)W?4ecQU%<6<8ahmHW1Z5C{q_LhLwM_oj+F& zqEE0M#FQH4J>MoTBx;m0B~F0*QH+Ig_g2Rp!dH{1IFi~}F+l@5)WH%5wamFPkP8%b z1RC1%T%QS@W8qmeV9V_LT)J)Uo)}++NCZNRBVRP=p|q8o*fNJnLn_HmA>w(UQ3I<P z)-M19lM1DreW4)UrA#>iu7mTOtb0Ex1!-+3JgQ62uzmoPgGbmg{Ch5WGXCW4fbK}U z+1q7sWr^@6P8qbxaHiyEQjka3;2?+^Smg4M85LLeS8i^*@h?Ntmr7~<IQ`!H)6XM> zNUTo)YIAmW^Y%=^y#aXz{Bz5Yr<M?p<q(ZH@OmKCD!l&b6NU^?XrFXK_8{U|x`?9M zkBV9;dWDYIwZYqD?L}z`sRKZ~@@iD&z<)|0mD0-5yfsB#Alg>1^tejyRo;cxaLYQ& z6R1d<n0!OKGM{Jt;PKPbac#2~S?&(1b6t=hmf%f%?WTu-ZxHQFf!PIpN->7XVTRd1 zQr0J#`DBP~8$`F(S<-@)G7E*)kl`WhLZvG-Pa4?;f;{be8=P|dI`o-m&P&{=IUDKa zy_51JN;%Q)cLb@$CaU?F;!1Cjr>SgJmJCcS)l@%AqIr_*J!KT1TY$rROr?SzCVFQ7 z@V#^E5VGq^y9FrnNC5u~1g-4D*4tamcX<G$;J4#J@|JGUmx7#@574}#lX%82iK6sq zFtLS_E>~I<+gJVkoEJ|9lXv7JqJpid>$q#9iGg%4;gYltuO47;!<g~%g299c^S(9b zG*QTU5N*VgSh%iQC7OPsA={(W9Q#-8(-OFa>P>;YmcAZ%1*N0QUqc-R-jk;O%&cy| zEN~b{%~aDkrDwJepgZqTufUe<$%M>Wa2tGdSV=aIX-c~wMb=1bMZTwpSKek&X7KO; zV*_bNEFp#sP1|~){IX9<e2uRY3?ErZf0nu7^+B?s)Iz$<GhHp)4fN$D+V-Nsf<3IR zS*_8G`Bet4qbSg22y|wGt>2X<tf|7x$bEGQk^mKD%Id&o>aJ*b#TmB+ksyd;I(Df^ zszj)=z_$9nqYV*96`d3@;0BSEf#sFAr}x{8;8j&}k(AotQq*$?M}KYf#~VWD8{wpD zX;kz-NYxTG>-LwOEw@RI``L1S04Fd22kvKpB+WB3#)5ZHe0QuF>}hEx@qN-4w&OoU zFe!8+XgoBNDJzR^MT<9e&5f3x>nk3#o*dy!@7%caruv1cuUqLl0CLy6;QJ}06CaTA z0H$yNIbIV(Epv{nf^RspVXIYsDdofx>Q61Y8Bz9I08qn^q-SB3$obAzFUwrA9{BA9 z;tiTp!}Z*-F-DvIvj*MDl5J{EAJ7(@;~<ZR<^Ol2%<dUbHK$Gd5Z*EWt%91Kt5~|d zRk`#_kS4pFO5$)&x%;iHK*RT1SPLteY}eAAuMAdyrRJ<@?<BL`)?s_?#dG|ac`qx0 z2vus<k!w*Dv1wFVlzuP<Wq0Sh`*@hTXOk<BVSK95R;PR{7|BeWFqXxX<_SZ{jKI?x zbmuFqL2PlEg|wK62u$z<Kw3|wkbmXG#nZa?QbPl|+*b^xCG!wcjb)pB3<iebZ~3rM z1abc_(yxYe(j-)xZG0{pe7G0m;m)`Pf93iYYxHUC^3rP*uTJ@cJ#U4-lmt=-H!MXb zNbu@@#@j_7j7HqoA@hRUzJZRpGykxI49>BrSvjP<q$B>3mQB(Uk)Y@5kk*Xx6&eis z&claUF|ig4@fyKL30an1?+-qlnk>@=M_SYMjB6(@8<_8LX#S<@Ol~OGWyWc{BKy>( zO&FlnU)SMajsZU~iOI?ixM$#AWW>{Nlaqq5foV?&+cfOk12#n&@aMpe(v->xUT`dw zYtNp6dj;}0R=+{(Go^L2WogU)2_$F9eQ!>m*vYE1q8?7+tm_!SAII~9J^pX%5b?a% z4%jPN*E(b3@aeB`t#0ae5cIbNxE#Q~xGzvaNk2ia{9D6hB+N5tgRb$S{NJ;B8cQ=- z^!G+X_boi6a-43B{{7Ljk*p3XkG~5-4fOapGot3lS+{JiNPfEKxaulRnKzEpMSQmf zX&Z=X<H^p_xi;XZU6E?o7cvjDnMr9J;-MK5jwCa$dIFiS+D{I9YIZsq#RpmwEkXGj z8HaS487j8h;rdtcF|y@+XWi608iCQT#XQQWq}KZy1%qY!Q-sat`7O=-muUY0AQpl@ zY&0Wp+0Dl$fqxo+s{o+lko@W=(i<8d^gm7rTaNEq(3Ue5_rY2|0Vuztl7gfnkQ}ua ziEqme=BntE{*+Sxg0kE4qHi$LVx)J4OP8j1=$GtY)3bjfJZ{%0-}Lw4s}0zA^bI=E zMTdb4$=+t-4u;%Nf`6iJzerzc&|1p(_an}0lnuV(mevJV(0~VI4J6zxUXYq!ExlX0 z5C{!L-~vI%OGCMS^G-Uh?NI-G$*xCesbBm5xmM1)^M4aAg9Ix6k|l4$!@=rrt6wUx z4b#pq1Ky1_)NQUqR_Y-5idP^%wmkd>ZLdu1spynN@arM#ZwSz<B``dceVKbU%Y>S2 zY8iT)o(KTpI(OgiK*oY-{l{6(gOLrVkV9_svT!7sICvgPmCwW}%Km1^(Uoi^=)5s4 z5-o^T{;TT6cs#z}%*&Dfb>uh@JYE94D1S=&sK^;4Fe6Qu_;kg{5=?JJ{Trvp*~-9V z3C;;*a#7t+V!m}MO*d0=FuW*D{F}_v5GZ@UVIHQfzZCK7w$M8aJ;%EAOqWWX-LtQk zxO*>5d>?hJTN%*jTYykyvu}#%c@DUH@bq9QD<4bh9oHMsyq7kKk`*EaBhx?#4U`uM z&WYH&O`lFB9`-I1$`(y;e(N3gTdGc1BW3M92nm4Mo?m49!b-mGQ5H3J2~z#%t5KSw zqMAN5nwiWP{9GsF?B5sKW&R^L_y|gk#XT1h{Q=V2*_vt)Ig)W-0c(;{4(B}E%V_}F zq3}3K5@iRw%@%;=-hb^+PXI8TNa)Y@=oO>wmx`nRsV4uGa8WhLELM7SBIb6^n&I9R z54u&PW5}SPnS9i3-(&ZP$o=)PAiWh#c=TSY)pdUwr~Np*JCZmg`oVj;*f59X&s?_R zt%c^mqu~)IKkHrFx6YrUDSospwTIB8xWsxsf&pGrNXkn3j1{%V)Pi$wS6c}x1NN^g zjrGBcMu5NZ-p-F9T*}Ft*UlgQW&F1sXDa#C*r4g2>Z4IHO%=)vSo{0<S619t8L#TX z7YU`i)eO~bPd`WfngWI{8otM1#aiva91?bmOI_uu`@vIj6c<OUClF5AsMA;lp5#xB zUxJC#x#x-yu9f(omiAh90pgEJ4_Cfj+<)kBnu_dk$f-Z&Y13X>YwR-<#HU*66polt zi#NnwyY2B9@Nw>yEfPs#Mp7YrFUT{W3@Ht_N00Lk6vbfNgt>#6rp&r}kz)5@Pq~vQ zUPZFh`?r6^JMJMKIiV>EBKJVa6*<2T26!HIoDHzKU$bwvR0bsb6h;^gVhn$ZsE+Uj zU!y6xd=No;c&UM}Z>2e9j7;7>zSi`<^J4FCho|+rw4XHsA#uC3jK#2Dq{?V_zes-f zhH~n^mP%ugykvs6)aPM-P%{xIyPnl@YX4f1oW87<JBskalOb}a7W<|z+2j|y$0a*m zYoD~Z<n6xk<xQ@KQWF9l5wf2)O@<N7e$8dBUGcC-MdcI2Rba>0g^@G#1el92$7Yd# zz$*52kCeDi!zPhH0?0OMWfC3dcxX~n`P`i$!-OO^`@T$J!7zqd{HJ8%$C%hN0f9IE zHjIF%*QLLUp}#W2)c*71`&OiqeukZfA70jp1i;R)O7F5-s*5A?qk1PJrJYlU@3r{( z7Dj?WecV<J;*%{gHlRHN&xs`F*?@_`-5KQd<7%Nu`Ne;D^yS%Rxvl!z?$}f!Y~)?& z3_YbtOytPH&HVOb;Vnj$-mT^h4FO6<q!y=SU&vSmh{xYGYn!K!5cmFl@oB@zP;``b z%|~;KgDIhaA1?<U`Y+mqOsv6g(wp!iDU<+8UN>3eul~xzh0#Kw^;b{WR7?tEitK~& z-%s_dZ66c)3!)0qfp-`W?G=AyGWrnQj&@C-=h_rLPL;t7em_^*s*dp!?R!<s*5tJM z>KA(R>zGzqjX0-$a>j=z<j?HfBnQv(IsEv_@E=`8&IXDJpLl|~pA%nrb9~sZM24q) zpb=yak<ytBdgjZUU@6BUy2UQ&Y2v_S8|=-P45I`bBXq>3Co{sIJ>a%xq_qzqmq^$b z<X+Vnh`Z*MEG?-QpqR_L_nDmLQJ{!D@d-y}>RMVj(<(a=I*=s9P&se03RCAD2#C7f z7S}AsJzk>|wAL-&C8;m6bxL_zH6i^vRo^XK1*_7mM<?{cL-%A0ED5OQW&;N(#`EPT zGDLC_2U;f58r@mmTnC98$Qk;Otr;2b9HeW9l46hYsg!i=(%jhg<Sp6@ZH@HAqkZ^U z0=F=pF7i4#od?|In)CYU<QbRKgluiCQrBzC)UZzN&|Wgs?!N|_61iGAp@li0vN(`@ zViiyD?)dy{oZ5SPewfA%*6DnJsroKN<gw$T5p0T1JJILaOq0pVzD({tZj*;Y=ieM# z?NYS!Jz$T57aTt{fm}oq62<sZSe}xU2j$1{fTo%3e7X&T7D_qSYHZI_k06e0<vedS zDfyC)#S0`bJZVun4jT>P*?0eXCY4%R_8w&7D$>L`#J~D9*CdBst|A!^K(CO?ko8x@ z)!ZcVY3se^0;ALi+~qQ?3LZ68F-v6Zvz?SohuVs_^?Z3MZy07~0`1c7doN7omQ~Nu z8NQu5mRh@uoRvFzak{i%8KYs~7t&AlsuJ!@L3Ap56X`QBt9n8EHMQ75h+StF*NHS% zeY5~qbF^xlkJ3}pA$u$9AcVHG)|HRF4Qaewtv*K*3^%D!-##_nE~fXI!VSSH`u^0X z#tIq9okMJE$cp7fhb*(S^xjEq!Vk74ZF&!?cAS}RAHtatzg@w>1|~ksIW@erOc|yR z6C}<VC}9O8-IW6Sl8~Rt+#^A$DyUVja|f*0d4nC}ll8chHgeb<7D&6$q!6+DoRZ<y zL^oGnYt~@!jNiPQL1>#9N9F8*xfp}W8(bgvCJNJ5B9jrZ819p2pZK*3P1iEJRzpm< zYf~nd(X(P<@v~izXOgv@?^%N5(QH<flTF1dvu`~Q<K07>4-#Dsw$s7RCAPn1aE}Qr zu*Fbkx;eLuiBsx!AFouWf&;3D1{lrAczernOArz%*Tk@s8!IYX5Zvs+w3m-nTxx>Y zZjlvhJ4=v>GGxU-X<)zueVfPcg<h_N3ItoxUlas`W46kfent);VAf!x)MLX9`Es?o z)vx>Hj0G%wl$`0yjWeGupAnaU=aG(sZ%$V|R6b*p<iGvEhbFa$$`D-?le@rirW}ML zwE?XGH)`(kRS$f5sFqNyHeYtRh)?T2Kv-}l9A%ITNjh}!9P)YB$;7fs`aI?ph6nzQ ziG7(+dw~I=$i!I$5BEXJ3mq9~gdQv>Q6NElZ=Nno2{r)SXjE4Xz_Z<u_m%aP-1FD7 zD*W3=<nyvsb_zD;kP7l7tLg<LNe2CQ10sj#sna|lLfsZsaxdQfnZD?X$?0x#kl+<m zjC_<9$&^%r9x%SUvKM>V!%c>vzQ?dN==@^~dySCTrKP7WUy_}P6DJIOPRj^p`VbHs z`|H?%J~{D|XkD5X?y&=J=WjlH-tAqmBKJfJeSk5y?)hVGqT7R4HVexcdm?%&$J8ik z;ko#|?ULPb23?UN`9!`CZHnh9_VO1PL4hm%(A5d9Kvi<I*1z06Wn}&GY`QV+eB?!k z&r}_GbBw!qyVo9&NpXOkYsErG;2UGuy(3`4RcC+H+FEe1%1%EnnN_(Nv9j!vVE0X4 z+I}(w_5~J47cZtavTy*N&l2QL`Rwuz?$CHcPq_)a|0W>MVgj2_hpmfzZ5B~L{P=HC zXEBiSjnXbn$ZHnvQP$7CcmLUS&62VBL9uE&WnWXqbM}j^6jVR`7T+9m9!<SPfw*o+ zGG(iLaN#)o>&ItfO%N?lV@)z8gZkopG3f%&DFUONPo&Y}Rq7vn@f%K&_wr+KNhfvh zorw#q3sw9=8+Czeh7CV;|4K@5AZ3IPHkvBIFp@F?P9H3yao<;+v%EsEjJbPW=HY(+ zUUshb%No9vLiSo7dB@bySnN&+c1u=5Y`dLdSbgE}En|0kvNqp$6lK*M*JE6Y<e5T( zMJrpdmT*=k`|^t&ZAw4age{ABuT#p1n%pbjFM}(udTNq(5DIZ;8KXVgc&fK9xI&S? zJ?g1^2JC74>{yGfcz*+IzE6HUpjVH)m%<*ZA%Jy3#(VGgylX@F`0(qemZkd&`wRlZ zpp@S=81!>s0|!6>u|`B@VKkexnW}F5Qm@`Lky_sxYfHe~c>fy%3+;1W#*|c9W%d>E z=jLx=AGF0m>HAeBDD}rd_jD3nQE>|>y?%Bb56yVLeTp{w-mHCHWQvZNlkfyc=iRBi z&pxm&xOZZ<=suG29s(E*@3Rkud9=5|VS47J$xqrU^>vy?F8YI;lV0s7IE?GU-3w7U z$-dC{s^lq^TNwNnCP_8%K@H(S8zvwz;g$jL;Swf^d=Qsv0AMqGg9E1K0KE+`p01RR z2G}SA>>~m;3YuV`K`!M=rZYZx1DSJ08hW>3vMUTS1&lJ+Fd3>w4^K%A0D#ocq3Siv zgFuYaDVa%NVPZ2O+X>@k0Q9XPG9Jt&IG14TXEFCqF^?h*Jq#$lUBAAiHA;~%G&uW= zL?u*pV9Gm;Q-%ovc%XeJCQxLklXkeo-^d#Y^ul3mOVo`6<L}_fE#c&TRK^Fj+5Q%W z?|Tj2iWnvf4C2->flEO9e9Qw^j4Kt!<COfBCz+Imse%thAYy2gc2I%A5CFw`8N}<j znrKRs8_kki85nxwFgJnT2IqwNJ(H0NLUs<&7ipLmI`|@I)BsAM(-vE}VCXA7^45R! z6VvdYLW1`!!6kC2BXy`F6lix!hJ;cE_`m{O%{Far4h!>+*0_Nw;bG$73lr>Y2*%R_ z*c)X$8k#fPORgA51l|uEs`0c)xg_}R8)wCjtdft-?E!OgfL=(<Mn!_@X}qZgx%LeT z?8e-~WPEUt5Rh;Fp2-LhI93)qQ66f}t~MIj3H%~K83@G&K(XBG6WkP&aOTOI!Wq#L z<BFgXxN8MKS_#UVI+P^DC0aT7P&l;3BVB<mfmTzVlTyx;KAw}FR2W;hwH2P+c;B>u zBvsxS>u*4zV~~K*jn^uPR}PE+!b{-*wVqm=x^pz8{&N(GA{VQiL;^53Ya(kXTmcxQ zbOJJvLgr}F@ZqEsg|(RAlqtg6*fn9a%*4+ETkAIEZb4zHHf0XCR(n{O8%hD#A~$oj zaabZ!xFDwW))O3-D4aSI)F`H1j;v++rfqMw{l;44A%!(E!Qs?qNP@z;h1}-Nq~~e! z9aF12&W4`IguAok`hn!eZDfdNQwY-p4-23xZpKL0>Wzk-k(Zr-v!QE^mCe3|T;-Sl z<S0y+C|oFPjGe!`E>Xxnq_8R>f5Js!={)6600yQ_X^W8eSH!F6Qdj{nzy1v-Gf$<o z%%(D1du!Nwq)|B3P-xT5X{S+`0Z>i^JKwwZ0OVYr*W7bcOpN4|X-mA-EJc_F<q+*R z`Bw$*A{exqwUrNrO+Hfk*Y|J=fL&mMSt3QIyp0P0;0ge^NZZ(JV9x%1dtHe{sSzQ@ z@C5VIm$`-W$Z^U-`5%QhBhusKa?B1ku2wO3tt7pyBr6@;(i~$<F)zi&vOB&~OB%HY z6Y$97n6^p?V~(b37C#9pA`#Tcm#d<pi~cuY9N(+1BM7t-2PDz~*yuigaDqI=K7;<8 z_=#oZ*MUw_4~4;cIFnf?7hD;H=rb2aF7S^7DJOqYE|k_0D*KQXo&9~-M3RBdgkI!7 zy>7|H+8wO)MN+RC3%ZsvsFN~ci5f|xgX(ZW?e)Y1=!cybrx=(BNBDga%7r6fI^sWA z)@w-I!sZry^o`42<$|$|^SPw{ZWw#?)<igfGNR;-8*K5S#RYIZaMQ54r_OY5C4uSc z@J&dhwzmrYT}>ybs#9!_hEhzUah8X=XzBQH2?BJxGKNsMg4T@RA9)pm?odtc6kOcK zt_D)hh%ZxzmU}B<nT6hDjf+!(m${?0!9e$;*<xl1&3T#?SnFGEz2!KO&Iu6>pzRW9 znwnaN%5Ha=T*-aJ>l2^c%GC?X5QIAq%jyr#?oj^aECa<_E4O%&uDRU;hIlO7=g(9w z9{ucE)K2bdU8^$3uG|4%_=O}ncvs^5w52y(``bH(LO;7@Yf}8~U<z3?2=_F|TQh21 zGwxqAnOQRxS}bhWG6Sw#06%b+ds-^2-@yHBY}fC4uiHj5O<N1+3k9#+2b4dwZs9X@ zb(mRq-dJ}zUcVRM<)}yH7SK#C<n0<zjsgI9&&Vk}0RVsm0008yl4g+rsE7a(DwqMj zq$`e!4&0c9FV&8<B@mJh@MV1|Y`6Uu2o2=}8F1}n*o{wXFk8gB&S@~%BVH=z^`$5; zHgymx8M3o5*i=1MtPw}eWz@XYWB3X{J0xRJ0xP#DH+p6CKR&IuIU1I(iEjZCwB(#D z705R?YQy<!>zg0%`4p*gH1=O>(7<FpnI5pd{qGBkjE38!jUUs)atGE6Km{PdSf%7| zj%|(WU-NH2xE{<u*cdC(PT@BF(7ZiWV_oku@}Xt-JKp1Kk?F_QUq9MHb{9uJzW?)I zXB-WWSx4K!Dj{3^-e^br;pTX`ak1H_4@bMRO%MJX{q*tV&r(kck;nXV$Jyc5RQ<iN z&z~+%_E*0an}7Lyb#Z#Q``_4?o2W?uP-F>3&f>F#rV^@IiltT9T8e|}i7dx6+4?Le zuz3@B$Y`m0m$BU8B76XzJOlScfjq)8sc2CRA6BIGl#h%iRb(YarW>)Ej^GGIrD)8v z2>{et4A(NXgp?{WO~ADkIMeIXifj!9QN9!om&8sD(!e>3=cMSzxO{g$9dE7sW!sen zZf`*v1&{iH_g~(luIMC1dJn>j$nHYBicvtZt&(^azpc_lp}MWIRE3?ba-5!n4=Ae@ zfF=Rq3DrfkLO1|`zN4hOrXtU8r?#f5Zl~^b>&{L+zMm+z`?`51S&X_lxh|H%D|mjX zx}?mNl)9JY!CnJFsD7_;SYdasX<X0oHT5JPjYi9?_s7@Nw?cnNzF&NjvfC(>AE*VU zKjq-X(_7U4`ncaO{;pYg`oXQH<HeW$pO03)zH7WJT6*-QyP$-Wj!O7-VE3(@AO2v5 z#M;hY>Y9(PA2)!n5Bgy@1Hl7utVCmfFZjXV2L9^Te~0*ZI`+TH$rbvyla?=$zGKl( zJm^q8*=uTCS2o%EqRz_o2PD<=I<TiF;AI@L6KoSSO7+|S-#4W315!Xt2^>%DS@Bn& z_4g=DZbY8b@y{H2{j=^lEq<Dae!^Qi#ZCk9PtsGS;>4%7^Jzu2j{3arKRjI?DCh(V z)k4L)c|5YwiPX>d1KJxlgwg_;K_ThV|Anz$guaUtp8dUE<MB*tEf;Z3$;yzAN}`sk zD0;H-<Q7-xR_`^P#&jhsAz-<c_13Kx=L)O0RGu}NI<sPHt{v-bH(8j!)oO69jpf8U z<9uBZ#O1#=o`;O<ZQQYjBBLeuqG#5*hk<f84#>yDA8+ld>@U+Gt}g&Nc~k%th<^ID zljkYfFVe`C(@${!+|Kw(JwXZYuv;WtbpXKmxH{k}0}Xd#VHM+5_}8@tF=Vr&dZr)| zz)M0;Dy@5UY^&*g7C^!TC#WlL6+_<cV?_ugYee{W3MWIUC%t5R9kM5#HdGpbQryzw zO21kmy{9pG0~zFSRa+3VPtGS@(zzoT>;7;oW&WIlPT)j`B-9;KSnj%xTmOibfRg}c z-D5r^>H&%x9zH9yqw(z|7jBh_{qT~%@k6yf5k&40l2RccY&dA-@HZ=exI*ACLE)qC z-|P}vL7~j5SOM3vH1jC_Hi>O{RvmzK8twSLzwTFu`M-H>!<AAVVX*=>q`BsoJ@BDZ zF(#coorbls-gFxhDveGOC_qE5Sjp5^%er9Zwa`sxbHvwW>gD{Uw?ez<Xh1q+;TmnV z^3<SNXo2<1g;ZhH@1W7(XvTu$icO`lB%-<BaZ~Xaxt4^*Tr7);8!RsHzC!J`3H6%j ziz~}c60j>u((OQ%icq6RQ8tkpUQrIG*na7tK|{i11E}BX7m_GVVnOznLlSCY6mq#$ zeU0D>X`*_;LsNypwG{O=D78Dh0Jwiy8r41%vE$@p<xr?PQ#sp{JYQiIQ#yckd7W<A z(6_gwt|U}Gnu>2_C~Ryr0G&Q)K=2b((ayixp$@;eyvNlPk-6ry(xR$`aFha-7Qoe_ z*Wo|v@7-C#b>W|O?dUB?;HnLzT~GkU2TKz2&>E$9`Pbeulix<c@g!7Glotgw(Nm(F z+3(Yyw;gBUhriAIHb19(qYA2D6Vs;|(tl++z1g`N7aIP)BTY<8b=Pr)W$itsW<b!> zr%rDhkK5rBIi@@e4in1EN=i%w)sl+^>b3EY0Khwq#+N_$Z=!xTOm6`Q^_qXv-+%hW z^)8BYW$~yx;?tqzEv+46^u^!ryho-6s1ud{Fod{|%ROWOrc|t|+-Vos1s~6x3I&>< zcC(D)<3aAru|E0Tz_Y*v8Pyfq&1E<rSSHD`!=3rTEU)ke9I%33;^?`LRTynZj~HI% zzBnDw05{^WCTo10X9NSY#;oVVYeFh#gBIzHIn^fXVvc7+$kE2U_cx@*r)OVX!A<!C zCL6LZ&xU=>nhL%TZzy~`BaQ^7Hx+K0Y%2da8;u-oDmoe7ymN6jh5|R2P?~OOah{JS znl+cPj%?|voKN7=n=6D(w~ZXnC-X;}s}x7J&7M9{n1oV^-ZAwPI3xumNgqm4^ChAS zKTOkE0-qMr`%N_~^EM${w7uP+#?7RFFPJcvpZ>{~G~~>&I6YZc(-hbD_Zf#Z6Y!K; zAXkH@^ES81TV?pDT_Qg6Hoy~_ieWSk{y%vCV<AXPK7{(^ugq_<guK@cf@-xrg`;te zLMzX3VHYodk}b;vkTN(Vs%?7X+L+Hz4e^Agg85Ai1)$T;Prt@~i4@e|;x+t7a_lKf zCOol6<?XtGPWKNHqA*oIWmcdO4hCQuknQ|-6|9iavBCC1&y}x%GX9hl5T<dYQPD+P zXkEi{_IX$q*ce)FN8k>ed#ll}2@VF7@R)tKo@g39di(Th*A?<{cEIeo@#WQ?kNL;> z@1w`9AFqA|W_(=OG&}k5<LY<h*vG|_(UZ>?SAS49QKXbN7teXUpJ?8(!a8=^uX25W z%jj4WHa{D3y#AX%*0G^Db~gI-`mhA@X-nVyeDdY>zZ&yTJ9cB|Gas*y@EM=>?weoC z|F}MG8~gM-V(en^;`*c$@_8R?eo1&x3Ib5|d~R@wx{fTR_4bKI4F>|zk(%dcXzhOu z{}oFEmd+O-Ux-tE8c-SBy~}8&o-@0q=zla-=f4NWI9AMwAsMa{zwAP(T~S+?!UaTK zD8-Q?&&6{e7eLGw&PPHTdLRER&N~_y91{YEx&vZH56H+O8RP)~OE~bsQp_+(EV~E; z->lamD?lBOx@8yZWcw^cnw$;*KuE{#^8&#JaffbbL|dHdY}^gtOM@+53lXnl0DXW5 zG9u$w(H=%V+}CiZ?m(0&BEbfkU>li$%ujG=OK_S^a5+tIWy825FrG+^cO=FqALG}C z@t?&6oMHmmu)zpyC=weUiH*$1K54^7&0?cZu_(60SVUqxG7%G*n3$iK+?JR+o0v{K zO~kP!Wg(JskV$!wN%{Fn1#L-%vq?p#NhNH_Wr*YoWO7wxa!r16U0d?&+2psU$#}Mu zMnp<8GNm;#r7b_@Lt9G6Y|7`;luowPZbWJ?GPOT4m5`r0)RsCtn>u=$I?k3hiAbA9 zrp-jA&E}_RwmENh#utRU&a*KrMtYwFLMSs)WF+Z%EZ`v9bc$t~$^CeM>&+>J<y55~ zxk8rk)FIyB%|zc3-2Ik)Fu7ZX5f$V=-Y`<P^jurWW1$R+E?kxn<RB2tz@E<5{t)~k z6E>I0ea1qt$ly`R;*&`iID=kCW`Q%a#OAWt(R5O0P#e~4xihHr<1qOICFtHMt&n{- z`HO5)G)_Y)hw>m>r#5~)FlR3_N52-QK}8F+=e{V(v9Zt9cnn!B$pLPIHI%?s1c){$ zQ!)vn=?isI$~trn0|aK1^9IRp=NKiW+k<lM8)l!0K)0v>JLB2hNsvHMXw+P$B?y3E z$rn!Yh_TOpT$^wEILG}3BMHg>ugpmSlz@6t%>S;;8O5BCfjBK1T7IKKgNFZuGA~OF z8YczjN_z|y8a7ppyhQvjWu7gJE&3m2UNcc{kR1*a*sRtE8U26C{Qk8)V%@ynPzfH3 z<CoTthh;Np=~Btm|9Bs`I`qoeP5{VBrb)FYEgf$SV3D|Fu0d<lc92u>I61y=SRKIe z8|&3+x;l1pO0dTJXp#XzB_tgJh$l;9U$g&TW!_7AoBtoJhW7gWtw%J&xaCqG+Rl6b zqs+@KZaE?TZz}VeWehAFSqcD1uP!GFR8?a&sB>yok|kQVR#K$<MLeQF!#=BNh>e=n zbk*an)eH@w=o(Ik#dj^!K&W;t%S2&&E!#p*bUnw$)^|M@>0P^?=M=uZ{+vY$u#vAM zrM2<Gr>b@%Ch7IIP)d4-Xf^ibuy3`6aH@XStEl66Elsh@TIaNif4((l&NX%erKv@s zq|`WS&)AZ%7bvT=H17hdir2hd<HdPKy{M{+D$nlPQnMLdLCQ}SJN4&DM3jXCz{DXl zAHN~yA`Dd0OxJ+wtf9#Acl`Du+Sn=v8-_n9iUDeFg6Xu{xSKUvM!X;VYyt!}L0jiB zG_OcSIdr5nk7%cb070Y{Z`<~bPNXz9#nv8@F7?;{3H!FfVWRmRSoltZlrq(#i;N7l z-$Kc{fbW^%yTo@ga(4X5qQTV%ePT^&KWGPun@GPWU;h|L0O->OX&zdA#On$7I0Yt4 z-t!NMC|9<mQU1F?D@ef%05p$lLLP=r7(kfh0LHhREv88C;;W}k^dGipS=?4TnzmC( zvzW2L{yfsM7q&V6ZYQksRsGIIJ|*DMCK|gCI!1T$^ASIj;$p}N(Nu8}#b~1lh=kr5 zUkv7SiCj+X`P8<88n`-LO%uNJcr9H!Kyl?cs}yvzfM+z~M$<ASYHT&XIS;$03N_!U zACS7(YyKW^@vCj~?ZxkoliwGAIw@~m?)TnIP#h41-(CJ4R{V2$IIe%|>ff~8qpPFY z`|qxf7b5;#oh)H*U7xN!e{_AeRsHVzeDD3A>x=z?Tg1zM-yadLPB-5XuP;yj-25BT zmH;RXI!Sl**(n<0NLUG-@-3z4A?p$n3K>CPkqTzAE;u=Rd_p;(oKu@bTa#Ka=RrxY z38z1;w1fffkw2M;J%N-_?{5+gs>RgcgR#)jsg9G5OX%F~`9h@rO9#-=W}6@wve>v& zr4MVtZTBfits{Bi)N2U<fG$IVY!7-#i-WI#PZt`g4Di{9o7)hi%Cu-=CCIe3b1-aZ zCdo~v1`%fo1Nq2&dTW3-ZyB^tf*b_Ux|xQkukkRKHqfM#Sxuv9SovL;iIddxqJNl5 zNCK7-5~;FqWdIEhh#~GacSUx0J85)<1%+*qh0ZV1P7ablg4`2PmS!p)$(f*Jw5z4C zj%zH_6X_mRFgd7auS=LoGt-2$lZl*tO@vH|5En0tV<rKL-DRLD#iQYdh+eUJ*Q|gI z$+RW`&u24&P$_&r1L<;{qm<iF(kUsV;?h&APLw!eLEW1NC`k})1)-4BAwnV3Nn&5N z$&Mw;IRJ1ndQZ|++fGJ6WnwQ!1j)Eo>>$&lr$CXq6;brR&QwZys@pV^=8jg@ugE4g z)vrK+d(ET;QwLp&KSgl@(^~0UXaRtcLpBGgLDu-0phfD7Ec0+C-Z1~Q5Dsd<-5X}q zkU<S+mv$02+^q~@xGKTNJ94pKrX<Bg#eiM4c_GwWMOvFcYB~%1;IjOZd^;Z2qRf5g zw`ZDEuDL|swp}yn&8Jz^dDIPBRkQr9O=TvC`D7YziSV<tG>f^se^TVNkEb+_2Z8AR z_S#bm<d{=vF#b4<U)IQh|2XaED%S$uCt8tL$uN64^6y$YkS@KRe(Zq&NXMa(El{wR zzF<5Y8a&_ITr2-ZBj1fGyl$ZG?Svak6R8t!DX)_BAR#=m(jE<u;9bH04wuLmDR~`q z)1%zf9E$w8;uHsE7cI9`)0$3nU9M;~*wzAyCaYN-HdLD?ium#3Qb;W!6+RR|U(0Ir zzPx+`Ie^pQN5&O*1#IdZEQtBrt35dlH()l`a#Shwa?-v@4#c`QiPDu?k%LsA1lmeC zR5X6Z1z_<`%ikFHGwUz>^OltMxyGx|_5p6yq`0W!)80SSI)v57{3$8c$Q1H2Q|BtG zI7%&Yyp#ZC&l`eY`HT6u=2#*Nt8-DJj%H#MgFp{y`+g*}3+9bqO%`k56EHQvz}6yp z(QM>J?7@2XmLlN$YQc|a8m(A&?UmKyD5J#=C>1@s=m4&cMn34|y8u)caN9mAYq?O` zScl_bMS_h?Y_jq?AKzNrfVz%aX0*w!9dl5N#<dUE<L2LYi1-1e@nwk1)EdtL0Htyo z<bQ@D1KjC+`@s7X{eAu3er6yFq2-?yLfgv)n59&YmQP2Q^!%Wf*-^u={zB(_aFZS! zMfr8r$NH$~WN9vISd2iu_scM%Rqh7=OnFRM1(^85=|oL}rV#wS^a4x+ch^e&64VC< zDIO1~oYK=;={O-Qh{vbNOLQo|FWT@8IGAwP?6Ba+<pyG`eKcb9u;}7)Qv>p09BcNk zjPq*C!2HAH^U;4*Dp%VU86T#r&5r6EuXd1QA7<YFUr^?o+mWW@==7%@;P9e>%V(np ze_!GFzaO$(MGpsNhcr7LT`H07dUVq~18^RnX~t>vN@vT$1ZV-MSe9mKs4pINvP2)p zN?!JKam@3WQmKcdSL4~*mrYs?dos<!N6$`NW8n8sqlqSZs5nl5#>G#4&{63a$HAY) zE4ddp<!_Bx&Pd)%G7bR1Pn!H+NX5U8l$0n}$R!}0Kak9_GkSrN(O8-kfFngf;irmF zX&i&81(;a!c$z<2UIWS~!fvsI(z7C$uz=DK=!I+4w(QXFG)XlrW64Nkwl@U;KG35) zH3T3I0FT2hKUL|91~Q<z>7M{BP(KFZX87Z!w_>tNpD~W3!@J|>dPtR#&+2#+^ho2a zV&gZuVmF0>4hVL2IMk~%;r4O@sT<}fGnQ2|UZy+2KapD-|14;hjT->ixDO07U=$RI zS2#icZisrj9A(jll`V}^tj1Wl1MdSU$cXe91sMRMGuDE@6YC?Gd@8Un415vEkoy1d z^&U=5{PEZCra^!}LQy(~-X-)7A@p8Fni`5q7Z4EyzXlQ@GznEYp(7%MDosr2C~5$e zA|eO^A}Uz1=JGtxZ|>ZgJNNzpyF0tHJNr4G^FFTw2P~t~j|KntFPiPiLIyS^(+!-V zzn&zqmf}&L=`jb@Af#$YWoZiW_3lV`!sWK8$vwpXa+pwi$`R)ZVvmCP(k1$Wvt=1! zV+#_N0B~<RTiZYKjT~xa|Ju9coEK#NEv5l03Q4z-xcwt%#|HZyOLz<XcNueiyyPa| zh^F|}n~(+MbGcmZH)#Oj5<m}CY{~`eQ=r}ywuGY&9|~tb1+hfo`AI<u=ke+133%rn zPskH0%@gVWKP&S*v~a$Ze!h%%zFb1SLTSEIf4<66{>h*D7~uj9{Q@oT0-b~cJyvOf zL4SeKQh~|O0<3T$PQTE?yU;43(5AG|uD{S>snF?Xp^I>ln|{&J%G@)d$g8x-r@zQ= zsp#y_BD`>MfPQh1ckzXU;^5Na(Ej4^rQ*n+#ZkhyV)Sptdf$pmxD{V|>stS<q@`Q` z{k%mGE=kcZAsu;q2_@vxlFa^+><|gse2Mm~!6qtTlD$;cANd`Q{b^(Lf|<)ABBw_= zd#zEcC8qb%k^gLr!n+WMX~+da8B03+w`=K-b*?AhONwpzo_OZ)coV^9<@^4TEC2^i z=3W8H`}O&(;J_5-^0YADZGG<Wg0iQ!d?4@2#nQ^<X$kdvm8-V}`oC97Fc{I#yih}m zRa|COFjwRvq3VPy@+pmDbF1pBKEK$#n`~x08`w(TejZRt`CHq(t*z?0k?Nm$7X&%Z zuM^x^vsFs~az`gmR}aPCa)PQD!MjWOM=J%GTz@4)rvTuCOZABZ<QIA_FGs~;@}-HZ zd2Bv;Uu=z5!N3#ST7lV8=z5fn53k_0yr)rB|2irl9(4?N<RQBLH^gxN*-bWFJ-03H zTU4cC8Op-O1uWU%UWO_=Ugzz@E6E9zhG74nss=bxHBZ1D|1VWD#YCs2q5gkV4Tp~n z2i=Nv64*qH(efMqN7ej~-;e{Zm1Eet>%|EN)sV0pR_Xt@-w^t$#U+K5Dhw~S(NM5% zg5Lo2?h1kEGCaU=Or`z3wpWAkUv|fZJ=arHnt?y1`Nsi=WKXRtzXIQe!8O1UUNpBp zDvTS+dtvoaf7kZ^@*CthbYn)E#c_ZO_q`o#JDaMF3-{UxY#C4~?3JW#ZO#54zd`Rs zSqw`~#gPK}yy^_X(}93S#)FunlKB7e8{}ClG|AQvA7E-b7uqzsQj5ee!2r`A|9a&I zhsg}J=E33r@f$`MR{vjq!~a$_JL~D_G=(=uRzvWc428!3t!nz#!CYcd0Dxe|0}x$K zkByr;Z*~H2YO(ci<X}JRZRVQnD#+y7a`wyQTbfL77Mg-F8`<h3&9d2M2K^1i+6Icu zTmGN*wr-vId?=fJK8}N47Q)sqcPpZ*|9pk^lhSSQ$?xwj+HopGT>t~9&|qA;M5aqE z`S`9vO_s@Wb8Ug$!(ed9g|gcXurs^OSW1kYVskBzKuc3i{;uNf7Q2U`x0^;-J_^+k z*stxoeKBLQ)jWlGGpJZ0%FLb4DH`4}Dso4qbCS<~uY-BCcJF-5X{g#Y=T@%TJ016a zuTvH-dh*_egzw3|<@~I+ffXxJM*pX_u(rN;BVlTN4-B*e+x~nncLgWm_CauT6o7+^ z1rcZ?$Hl^vN7&M_XW+;2*p5+l`Ru5P<GM*5W5VVu>Jwa-viGM>IJZV8ov=s6Oe?3O zM%Xpxjk;!d+Z{0MY+r_=8Df5juS{;_<E~jVQA9V>`nO-~ys`D)uBQjQ_b<;$3L0Ua zpRNx7HfMI#Wds6U+WoW?tjkG&z`yK$e;GBY`eP+_A>zlY_@{qC?BdNV43i7mk2YH+ z2}T~SljTqTSgdaRaJbRPIrg2s@N{ItO7X>;30p;%p8Q;my5ZEnUGYHm*G|$MKo7XX zC8Nh)_9fe3ulkYdz=xg!lfjRbUm^$gI&Xc{e=3T{=zwqI+LD&R)gS*y)y#ic(dB06 z7-l4{d|A1^-|hatR893+9OA~|z}24&6FjzsO+}4$m*RBx-;t_8-v8EeQH{Z_GnITS z1_e1cjwM8jR{lFag?*fwC06O>yx(}5#)n<I&dyO_9jyI;#~}CuH=+jKa609g|5NnQ z|5L@FrsSjrn!V5qA&vnCc$X<jG{bW$Dy|vuARw4OX_bw&EDw;f8AKZo*DsM%7IL54 zuiW7GLl}U-=b`~sfJ_$%q|oKA@m@0!prfUN2mVIm$$^O{*g+`Ms#f)kDCo_<!#37` zi)feNyvfi2Aj?c>>vRx>2q?Q^7gO7Bk`bN=f+PTPsZBSnUlpF8n#kQTLyGc}uqXgH zFI10=Mw~yhMV@lY%)J5U_2byYkj*Fz&g1ZUxlK%lQ0v9(jrDa>fwMO1`LmSSJJjDI z>;y%Eq;!OfujL-5F%_-$A61}1E4g#b&u2b6UTcc$?2jsTN-`pde^bD~bqam<OIl`7 zkeX_AF)H{2rP_Q0Q^204<wq(#woaAx0a$>%Op4T{ibiaLhW@zlS1SCj?`x_8CE_D5 z&|63plR&d;1m{(7JZ`pn+h}?AYiC~OEcecS+>l+Bg$o2UVhX~;LC@fDaC8dR^BU^E zhq37EYclNmeeKD=3T3`Q*7egL_8b0sjMicXatz=zZ4o1EVp9wu`Po!HaBj1%iWkD@ zmn#VV2Fbe!peh$kHerS6;>Atts2Xyz3mBMGsYS0Y&!o738!<3I9)>%e2*#qEqTV^P z`{r*&e5H}ceRa6rxKwe_D%iWt`uOa<$FHNa?}vj>6&M~Rk<Q4^V^lK*4COfGd#l(i z)C>)qmy)OlUr-{m!KA!KSj$H%C<8#T!_K2lqP}A|A5Uuyb+WzLo%Lh%%)cj-Q=HIZ zzHiJiIh#Bp-<n(eXNy%cOvA$cl(9kfcW=uPofA-McQ|x?E@I&huMJ0Q=YHy^0IphV z^u&*0_8bDY!)!`)2@X(QBSAX#yz>Xt5}>7btwUqal2izwW=qusVJ7~&Pl=Qnj6v6F zUFW%cI4Z%TPPSHg!&h)PCg-G{86nqo{LvmBDk_fB9tse-=rpdkirJ2-2%Iev@>gH8 z(xo#qj>D<^f%}<}@fDy6$r9O!AzEQN_%<i>j^Z%qLVH`Qib`U?*Zk+sV#dmO)!foY zK~Fl{rz*D8>PlIULL(m*FC@JU81J8n9qy`XYG_q?>OGTa@}>W?%C=7V&nI!KpO4wE z<tXY=xr&eQZw3d1A7UcRbe(tQGDdHmkn;9iHUQYlF|;!72ji8hwtSdYsK=da&j3U1 zJLkmfJ)inK@94eKVt*zKYUK5-Jx#lsGD&cqS6I{<5db5w;YX8K&wIAqZu8TDi>9K> z<%Mxww%nMob1$DwupI*{0VFF8v=AGWpqD)}ap~4FVEnCnh{3O5a^~GCWW8XRJ>}EE z$Hbw(X|xAFBV<*$lU{>f>pFA&x1W4&+K#*b9^*t(leRe49(g){MEPH1)>Flen9o1j zbnd@XJ0teyG;5i+<Z})H+P4KF`q(smX2H0K=?$UDzU*)w;ApUHdt{yO>Nf+_zR1|1 zl{|c|()%k(<<&dK^Z}nHr`Q(x`-Wu?1qd+4Q|t48r_HzBQ<I&(KRv7f@k9Zzx#75; zuD>55a}!@~^IRQxbpK=ggTd7gPks#jxc=!sq|q8X>&FP!>ORRdX<6_=yx6<qgUr*0 zH@|-P(&;;_>DPjV>ac((i6-Dm_P^Wa&c9~M&wg!IyT0q({_928zi)SP@4r8f{Jr#Y z_<LW|{f`$P{DfoIe$d&6At}{~>_UY3Th7C0f-ON$OxJ!gbBDh+Ise`DW&K)wI{f|K z)4v}RS-;oVAF%$j#QytSUj66(qzRNQJL&D<4dw0_?DnWL>(@)xzd3f}e?Oky_+X9( z^F?`ZTcYlK0hP0ZUTi1wpu#>a5U#jh0?#J>(!E}*d*k`(BMMRS7u{rmzT}1U<l~FU z!p+I(62cR~YhsHxl;UqZ5G1JWr(lGLYI-`0O$5XaL2v5V0egzH&~>8{f<#Hm(;r0K zA@P|t>8Bt`a))RaPk`&)VBAY_3%;S+Y@iXJDn_}kv-qF>Vk(xAgwsns@*AuV0Tdo~ zQi~L^=7GhgMef`{p+Wj|gVRF96V%lAf?-@tPp>@rv&~6(n`^d0X)<sU34Yzm=0?Wi z^=5XE4vUUxW+vorv19Qtq6?U3EkVL7O;(RwzLQZoMXDi_&2|!_gHx}-iC6VVVvA(1 zsZ<eH(1{xS*0=O8$3p>X!lk|=Y{NBGG<!S-UcL>)FkxU6sFIM8K9v>Vl}aecRO`z; zQIgJuIv>XXyzp6{t&|6*vRC_3?(4D@?BC$Qu*Cq-z^LQ$hdGzxGnvhq@rRji2OP)M zVf9fcT62!L0C{gQ_s3O2#(F{m9XCVG{<o8+S_0A9zo~{NXxro*6nL8F<#HVa{SvZU zIcoLo&%^EjI#iC&O*eRt5LSIR#rjh|PEqDc2+!jAcVT=l;`2zbWPq6@pHSe#T1*I} za<nmF5keq$CajQL5LlA`sV`p;o(Euav99daG6g&(c^3LbQj4%uH2Z&e2s{|}AKuI( zBR`r9=1M3O=}$F}z5?fUbV=~n3Mn}EvzV%z6!L?FMBlh{J4H1ZjQ9x-?8?3{9V2R% zcdWnomUTgC{H-X(d<SyLpVO&Y`z4g0CD0nsdD|RLbcy^yK1YYUKqH={@A7A=q*lL7 zSqQAo1l?W_(3l6QQ~py?%&itKSLh(#KV9CNP~KNsKG0u2v{XL)vz#tmF`{2F=3UVn zk`^11_ArAy%u(L?vqDlm27v_$U@D*6R?e4JE`(Gr_gAha90{AsSFGvEb&jeH@2bs= zs;!L5z5c2<Ayqu|O0AU21KY~y-qp|btAB)4{?4fUl@a%cgZfXH%F3uV45(&buKsCD zHRP)fy%+b#yP8Ld%4JuLAV^<<Rf_ELCf5R!R{=KQ(!QMZ37;JG&o%68HRv+g6U()V zEr9a1XxZJ`WT`rDzB)yvS{2SvEzUZ*-DoY&OG+)Z?3ANp>*amww`6Nm`D#mW^_;YN zyU=<zRD(;VqElvrqEZ7ov*A-+gKtZ1X?_C-Q0vcmDezar>0kAyL~1_;HqNlsM*cD} zf7oz7vsARK3B{{in4;9#sdPi6`MOdw>7hcNhEnB-A{(eVi?yrtvY|OQv-wU#^JTZ& z7gL+AmEGoCzbq(t>4w)OE@q7`xK7|jO=D<FSy@YRzg5wX+fBb(0-IVo4es!Q?$GS+ z^p)K~_}>{?Zt3~l0tdCS``=+)YZ(u19aU;&i@r0R**fs6m0v^NxTzH(d3VO=?hCuS zoUXUWmQgF$?mi~nW*W3r$H^;zq4a&^7Pf8AM@+y4^o*nZlbugzNml(a-cLRSoh9vm z2HO9%v;!~OLBHF<zBK4y`}Z>1ehcmEG7a&Y#wFUp<J<nt4n=3S32{lp1AyqujsyTW zA=(L<?GRJ$l(O%X;ObN=XIFUC0rBrt9qa&ux=z}6YO)49)x$cKlu-(Ix=uXm(th7% z7=~g|I;?)Tvd~ED!ET3_-A=!|T||4_40}9$dpr|+yvlog27CNo_MH9QgBR@$FzgNT z?Y)rL8(iKSI@lZjvN!T~Z<Of07{hz9zW3r1@5PtjyEb?)>E*rue%~XA_N5s1k$n5o z68p&IeVK!O*)RKU{_dlQ_U9Y+7y9-WC-#?=_m>U!SG?@6`rS_z9pH{f*82`LCJr<x zqw4RV?r;H3i97%b`F3sK2X&xFd7$qR>TV*hoicLpH_}oR*<C(3=8K|p4Q&&6exQ)s z%%L6X5I-;S-x_j@)&{t69u;nF5P0l-hxl<kYb?>>r=sQShCGvrL;UOTSNq5V407uc zCl<v~i{fy?!ndN3J8SoO<^~SXLtx3F;lx2f$-%d459Xgefag76o8@_g=PZii{($1j z!lJsePzy}XtfTEM{BQz_qidfrNaIRGu>%+$aO(p-N#v_XsK+mdy2A#*W;_sAhJ-ru z#Y+T(&TSdS^96%!3*!|@8v5?SGyQvXI&nZ*V;FWYq|`bBo*lBZN6~(dLCrY2v0R0C z&LAu_hypu9gY?q55DdgL1+hTqDvaV`t#KvpGa~;m60uwgNqmD`z?$zQpCs~tI#Tb; zK=^Tgi$Yos@fsT)MasDW8ha+o4?c}SzQrKz{CHova52!_FWw_zu5?E~9%Toqr!Ple z3{JL{KiI+CH$?!i=v>oiZUznE8jfO65Lq;cF$ES%Wjh)dx1hoMnYL9ys7F);V+e7f z0{(%{6*0usMV&#baDF#LJpvwIp5gteJOo1w{iAfhQ0AQm0G12SKMZoyr8{UJW=w;e ziQ?G8BM<NJa{l2+L~}ke;;O~Kp1JUB?DHI};YcCC+9@2_0J9p;QO@K9n{h1wLlt63 z)*5mFgDP=A*(u*g8B5mxMt-y(Wnp<%F;5^h-6caDH?hp-eU8jEID0hrL)y4E8fHOw zWa9!mg=M?JVj`X&@j?Ai4{7rwLx?#%=P(w2$>=G1h`klhIYUQGU!-4u^T6@XGc5;R z7Me#~mFFnu<mJebL1Dg)LbCSR&tai%=y^9L<i9oU5yNpoe`I>ajJY@mKz$1AJI@+T z%n`Ut(H!|vT=P*}_oxduDbE;K&NMv7`#TJ;R(La>BUT&Lsf_9pMRbVHf;%4bua9}m zPK)L}aNR?cVK|$jI7gy5-Km^w0Pqh$+{AKppt%>KxZAFCH?P43l~E?*TnVUojU1>k z8m4*%=743hz59$lgqXOG2wFkp(b#8ZX1)w@J$i-E%hAc(<9&-7du=pW$W0fhp&w&) zOgi6P(oA}_kV8K)`(WqsGwFlHcEnP}(DcnSOI!z@%~XyuDrXao`!xp9L~%$40Y7Zq zA(E5rAC@~@*jLt&n;5tSdj1p|hBBECqTN4!@CYo4{QQ0;Qe|XW6h60Rd;BJ9hKg7K znE%~hn5Qk=Lope^%Q*sPCYFn}&r!ZMKNqzDm@uGuY+e}H1PK;_AAkRF7;d)2%35ZV zL>?vJH?O~P-~kr6`Cb?ey7B-!!0NSZ`iC6eRXl<Oa8l8Tmzb@WC~kZtXCap3!k_i? zeiIBdPdw@};4<CFggCgsyeY6#ObGYt-0&;NbIP+T+>a-7R%X!LQ!K=Y=<s?iihUi0 z7<F7huRn)^kl&f3#ts9Y@tcU*QSj{OS{U*h26^~?h>LgC`R}`un-3m}KKV|6BLC-= z*OSR@`m{hcPy0z;rhT{jEAGFj@wfX-&ySBq_K>yNs4dE4&OgXkbnX=w#wP7Obe5Y> z_5MH9^NGY^-$+!&P1K+-&tDhRCYooKXK1UEcN32cHAXGaxff`|ESLA8Gke`M4tVkh zfX+2Xfmf|@P$|ft``jaF1Qmn0pR@yY?G72=nx-Ny%y4DmkwGqxkWMd-J%9jIAF$** zF3BBm9^$JI$K$&@ClCwCdGi2ag=m5r6-Ow2Txdsgw6pd(F;Ch1(A*a)5I3ptayoa! z>i(GOWOLMMybF6Ap55v-8y*7-q&=Vg%{=+>F$Z!;+<$ZnH5@mD+QIN_P##-~?tO6j z@Cv<$;1%L`K#<lrX7{<nUw@B4a;nmJo?s`8#b++G!mnUC^whX3m~4S(4lMB7*Gyh` z13O|!V1a^2b()!`BIB78S^p-O_t{PEBE~A8p=-MLu?zr%bdK1oc#Zl4Aort&wkSga z!ylY0SO12+hpfMQyY_0~6>|Lv@3lRo(%u6W@Dh2Z+xQQ%V;J=i|4F#o^R5d#6~)m& zf#0P(&!BM>GC5saSEqP@H(1V6%0fOG-pK-ho=>j;D!iJqRgdQ8e9U}9L6p<r6Q7pp zSdL8UV%sb3IRIee9&=UYp5*3v@#qBr!meRcVB8`q?05+?Gdt1_O3K2P>bdjp@1T_u zZ-eJ_J$G!Z%W@BXz=`{}oP*cH;MZ<^0fO1Wgj`sW>gaT~cV}4H4(hg>rCpJVMY^Z| z+&Gd@YJfBue>b~O=zZ$$*;lfmnZtMnRHxEAs<iV$xy&nEmgn4(Z~L<s`Ni4Zx|r+r zIpZ1brIV2nO3&W8Ths7{@n5@3HDFu~Wsp&xKZn!2vSuj)`gQ_vXHiBf^!ap`jkhW= z?Ze^l{aIsZ@?6<$Z9SP!*1C)pTRf-`>8)(vef|;-Mn?f|E$!T~o--LuMJFq7yxf{| z*K)3_m<}qwCEsAsef(X}3rGgD#%3({gp#a%Zs_e~UWekVOHYD!TP+5BuH1TlCht45 zWm@qC8x)(@^s&Q+7qbhn6JqxIw<QubGqz8F+3g~zS+ToYQpsbkIXG@(v7M>}CoOAg zTvX^JE?H`bg1*5f($<&tux7tHQtM#UNMp)HMksbqe{x)C{c=#QvBgq@t?T!a5y8m% zJT@VF==%6bBvjHx*jB?|=I-gU{xSuVec`IYXI*N>@_AUcjk-R;8L77%8>7H*%-&8N zH~Mq9w6HQL*qtiOq2a>Pj#LR5O_xa`JWJQwTpJgY=C<3Ma<nT<<4G@cdBde-)i6?{ z?qD{~3$*85kSB_9@DT7732a%#wf55m+r#?fCGSgIty(K$-K<K(R;J9j6^qY%-amf_ zpyuyEWnAPdQbN+ojK6Ngnf`60PMm6#5S^l*2k2Y;z07OpRqu^$LWD!U`&jUr(H}V( zhR}h)Oszd36};h|O?bx!0FNszYdhkPVodzgo=2vHY-9*m#e?UBlNN>McrE}4f-~QJ znjWAM@>beo#|9!rmH~g0l%-M4k>)y*uo8Tmf6u9uIgG+$(1q)4h^^X?kNrEnAX$+{ z=je%JVYk+&S$swW$#J^hK2|ELt{#;O|C;85EDueoy0jcrc5vSI-|DJbzKz{Gt2X>? z<Ih<B?c3W`=2CrcI7GinUaa8f{gYn49?ZM5!Z+)0hqi;ZGzvREIIQJ%Z|ex+1$4yW zlgV#FEc2Y>>o$$01;J?)_p_!A+@8B;O=2-<!KusB=A755(+MD;#91Y}-aP)_?RqY` z7MHq&^H-Uqid4?e-a&aK(=RexEK1Lte!RFuEDSRexxtG+dBuT>M|7v<UVUkI=dMFg z$Ok?AF^Q1t9y&`w^`3(@V*<+n29sUGgBQY!(lBYBv4QAv@M<a{8ZL_8;}jeMi-Iq9 z$WWwMVa<wg%^_T8lUO)Ej-JBXj8<~%!60zWfJ|dy_TdUt9-M&=Z9B+lG)^~o%y@2F zk(Z6<-IQ~eF4nrngtTkl@jite;rSPp6S|g#O;B{yj59kH`SzlzeQ27W*wxYGoto$w z`uOh^sf@Uc+p0<XaMe9J*G#w4xj=t5wF(LwECqxFNjrd$J0$fP3*mXbDS4<FmxqEB zFMY>K0-eg>x`1$VrUp$+M5PBsNvlNADOesWln)aGH^9E-wK~S8M2jhEz%?Av+Tfm` ztTYKlCU%uyzj3MoTLp~kkQB3h`(+GfgMG9pw&a84bosk*sA{~skw%iF0*-YX%uA+2 zJG5PmgZ5>Cfb|l?kDDUSe6WJmxMThLDaxA<eY1BDa;;BkaIEd5lTi0K&Sq;^WiT0n zYXmk=B{Oy{eX<cB80&$^NsFt6s(n0~LZuUtV`I-T9Tc9Jc<D<i`*vYcaXFrFDPb1V z0$FiyZc8#5v29ZwIzz^k?Mw0PR=|Gj2NoG0N@d67O~~zGP#Pj6)zF|@J^+eGgzt`5 zVnzvig3jG?Fvjb|gwO$Elh%$ICf<g~FQ9IcjQOZ29Kfdg5d}KoGIv*SGX*I_A?48v zw8umJcpX7(<Zfnrom&cTHjsvS!<z*IS!o16H{T8qG*D(dXX&QZWMMd=j_^lZ@r9B( zg?x;#&FBD~M3;=N^&IVlrAPX=Ht$~9@`#L5lmasCP#5q-f%k6qgA)R#wt8UEp&fJO z0Drh$Hd3wp?YO`MeNu6cgK~wA6RFP<QYpEj0#Gf*eLBwgpwu`#`@n(<{T<vsb9Yk) ziRXbR5da#1?of3^2OZbU_|xOTt9VR>fyzz*9Xod2i{#CnU*qm@QS_mOkA0Gj!+DJe zp$Fh%txbi;UJ5A!3>U>N>LNrgs(`~%m{YjKB`1t<5}EKg!!N(1{?ps0#FtqXlB>c` zxh&ykz}f^tE8gtH(RA=eb9w`CnD?G1SgjaxN(jpO1(S7=<fa5Sw!)=yO_*;)4l}(p z1Ufik0K5=&@%d$=8h9clfcKw~4UhUA!CVD%-WyR6`?oVt1Fw<))<XQuc#5+lg}_bG zzS|P<{*RO#8I+*dhmxlyGcdBp{@e3;B#lZtkN-g8E4P74By><2i;~>4-)?zw5mP&q zhyi<lIn`iqvT=t%V8nH0Hu-lDWwF4}u2ZBk=_da6U>rL&hJ4*uIIqMQCvqzGLLjs@ zBWxcm(B!flOKH?9h>|v!^S!*h1vw%#GrAUs<aA1z#1q>5Pa#UX+M6!|UR+bI%me6# z5j%QBOyKOnAWZa1)~BEP(#X45m};%CAnU$ZO!EAd#S`xVjG=(bKoS&!8e1sSvE^SI zLO~PMOVqQk3~jVM*+keyk<akS=+Orzq-p!_-I8~Qap+?OH@L&`?vhf^ZOZTa_#Y%w z0`#=}*^e7V<Dr+#WoNBu^A!}HkiLMk^f{uekZqPpU#<0`M{axxUZNIXfQY2lVtxF{ zhiLViFPGnCJ+C_EIu<{nCC4;oi^<7y?R@ba{@JvogJZ)@_3GP_v%l)2IaF2zxua-5 zn@I%DPR=pDVlTDV8`9P0F{821fy*V;kWAP5Uzr7y3tsiS+2T`6Uk#5k&5ns}i*7l> zON+(JjD<HJGjJ1(eVcbefurp+tRUgVwNan_4?8+`DO%|j%NKNcUEkc?BygUKzx<NI z1`6%riKnMX_W2t>hf0eT>|hi8|Guyfh+#VuoEsYOJTdGHabHUpSHSvpTaHT-<>C19 zLUJ<u9vIDA9L$bGr6rM7iu7nRqecGYv<nz=f~{y+UYhA5NO8aQD}CTI8XTjkt1N;F z01>W?a<<yYA4PuKY;w94;f^SBY#u2j{={|u;d-fpP#cmXtuHYTS!Dyk#Osai*ExN; zl}^-?Uo-rt0rgmH^YlvfprxE1tyhlH&Mg?RO&RI!6jI)ST7iMN=IqO}#L~L{GEHzv zm%b$V0VY;oyzjwYEs5o2gY$q$0zm2!O6WXa+Ek26ZI`(V`3R?!VHpL*V@I49p}J^D z>r0H{;=rZfDjLnCWOAyb3uD?|{kj75kIf*eBDK7%{6JA^KE;r`Uwt5uC_i+RpMeaG z=G=d8c<s);(mpmDc+nr6(a$=t3ORLmY1ng-gs0@rEOYrpr%bttsCRWm>+3d8slXi+ z<uLb)9?EI-Y4Eh_w&bxzgxu@>E%9QR7%p@_3`NS9BK!NZg<#o!_)A-7op_ZGHKV8b z&vJ#(XqB2!WplKvdG<SdqB<S?-d9ha3GWb<Pu8oyoX2IIhjU-iQ{L+nUK^A$s3&3+ zPb1hct)?trKUrd^emVi7gd2{DZTG^adf7nTZP;<>322vjfKi6BVTXmr$t3mT8f!EO z3@2C8@eWCd47NAOBgbF;xKrW%zft#McPB3FXO4zq@m_-Wn0K!yYS|u=PNAT>ByQ^{ zY|FYBXqT}ojYyxJe3#i*n8#*@PL=T+k&DGCIN0Rg8OdIvDwib7U{%%+!6jy+m~67< z%%c*9rSTy&%N}Qu#}-!tK6BgLki>HfNHtV3@Q;GV(L_TI)v~f+c37C4UG8~(BvO;J z9u0AVvy1V`_D|ianPtb(k#VASPD93roR%+k(#7mk9PGe1XzY@8q;o170GU0emV-4i z4<6?)@>VHQ+hHR^0qbUnT_JKG&NeDz_4qfNGl64of4VBH;ykq2PYBwPV6|<Q60LkU zS`of##;rO4SrTPL>{S_4(=Y>R1~x^`%^VsAf<aRx^$@!^^SUOK)Uc_H_-=^IQR+L2 z6edIjNoDJ-nUU-vI}jmxW+hcICz3`|_}X`HM~3@vpAJpCzmJVighm4(Lr@*bC|S1- zoASX2O>V<AV8S;D>`ZWLA)Z#3c+*`WEt0NdiLa3EJbr<kDiH;_WIpy)f%AY;8-*Pf z5<Xtlr}zS4_J;-zMJu1SC~T+S?IkdN_}_A%r{35&X$-Kj8`b0CIF{sC3WH8mU$c|+ zpei<(S>sYq**xM-ebl?xNAE8ob*H${-H%@QqWAV%B(iyfzIZUPGI5j<B<2{E=1v_o z2oiyfx*D&fE%>u<`lf{e4k5KLHzCp|Xa^O8wA?hfINfMAmD;6V8eOJq`ixy!$V~9d z@!oRLima(cBUG|b`hWBi@ki(r!KpV0>CuPjmUNzmB+F<eBYLQYZ&2rtDULlb@%K+l z(^yzsu*0t3Ore(nyw2*V!JyQS?aoHyez+n{e?E7n>$?=$duc4L+^u4_%4wz4XrF39 z&Ptl@x*Sv&>tU@XUZByRmaB3+1Vidt={K=SgB|N}=6b|ZU+ZS<Ksd#1rWH?0*|9|h z7k>76lp1a?s+aba=x8i01rQ+edf>7yeQCTTJw?BaAMB{7V_L}eLj>+fg`To03vBTS za4U27V!voZa`tMEmYjSX3gh7yWpdt)*ad6jTXLb}(H4v_uY8BX`z`d`DkbivGSyuW zf6}~eGpYJ#2g!nFXYWF4-OMl{yOS@s889L5_;Fic*|SVYcWdg&edgzl`P0%XX+sdz zR+vG2Y0jQKdF|0~w>}z^YHghJ0Sve|L*me+8heNO<km}AIs0#<*uI<3I-%yM=}LZ* z9TmbY%Gn|OG;)q6vAF1kDNQIxige~y#5l8FELZi`iI(C`2U84V_41-=>E=vzyU)o+ zCG6<IbZ2yGtBUV(K-yU<<QTa1kH|5(I?@G&<6aIBVD=Te1Ka43d7zJjkpP>EO}Zb( zQ99A-LbKHAC<tfJX>BZ+(}6o)RWe)=mUMnF_L}HN4(S9V@j<lj<WG3m;?wKqO2mj; z4t<>p_tO?p&n>X228Xu@-tO<pz&D;jFwK)hg<?Fw&Uov-{dV5Ro-G`G(?Op+kFJf} zvDXNf#0<4-?ZD1sbvWFQB_EmNUPm9i$1OZ&9I+7G_e6T{B(R7Lh-S0f0db0zGe6VR znn|J>t3>*m?}yq*j+freDi_7!tQ*>s4)l9X4%V3SBs`rcBcNB>mtn|eFIkb2>Z>=l z==-h(A|J(X?N$Gw1?INzlBKwkn<bFfBXoQ8q_@cEP`JJl!B612pFy+VBV+Dl2oPw~ z`1H)V9Sps;%V|2B7BmHsS<zp{STJ#%JTDC%3+QT;a7^)&9eL+oMX)V~84B_<dZl4O z?~TuCllgC_U$%jX>b0w{m0#Oo520z=SqL44PriZ(7cj76AI{!_s2B&Q2@Iy0^qFou zln3p+c%nKHm2>mQw_|&KQXl=;yrv+R0u{HsZy)R>Q$%Pnvo*b-)$alfH*%J^8_AQ# zWe3fD&1KSaW-^J$V0KNgI{2qQN{uP*x3pWJJA#<)K4>#B@*0`T9g^;OIjFC&N6;j# zMi|xo29{OfDc-o0(;ei9dfnWYmZPBTC`5`S^hW(nb9pg44u$#R(~mB%3niFsJPDeD znJ&snMb*l`k(1d0I{{fk(V3T}NU`A6@TB}R*oS*~?smXLJ0@_&r|$eB$;hkV<L(L3 z&v1{$I*Cm|R|rG}Zr?GMGDsfq!KM-diNYw;k+VTJ?Kh8xRb1#WYa5S}I6q<x+@Wn# z&RmuuHZvceYepG$x0!*=7ma&l)N2~}qg-&JRkx*K<h%5X$+ZzJyH7<jPg06cCpm?O zh(ab#-3cCK*)*r!aP$t8BVTJi!o)b<>jYnJW>2COI!;*{bt$iQOl*8T`|<CppO#I2 z3uLce>%x&=5C0%~e>T|50EkKzs?lmWaM}--NQ#r#N{C1qLbcPamdf2~XHIu~ho8le z^2=^fL)iR;yqZ+JUIjpH^<-MLi$&`Bm;2I;FX%aExx)fn2n@)7W+Taj#ts-E5S?oJ z-2GseN&1?65@25;j#UfDi<84kJ&j6=;3+R(Ri1Bmi%AWb8k+EVBbLkaG%hVSUM6p( zvx5L@wn}L$-MzSe^xTPlK!C{Lan+de7fKJyIqTF;k}ve#v%b8sUI2B2vl~&NA-Gg* zyaCHp%vFBzz0TV}LxQ_W$`>tokR45D31BlaW@D(f=jiX*<lz+dQhcZ|vqS9w!)NzN zAzDdfYx<t!akwTY-R|z_e%ei!xUwJD(`F&Lokrs8oe<q1sY@;3yP8PXtBOBi1cODd zd9k_5CD`%z$JKTt&`(gR$0Aer)33R#;#{Vb6+lsh^lRw!G2uIh6jiYBP;i8XUKIQ^ zn0VGEt&8Kh#~RF1!CDGzw^?ouhVBN3<?d;bBgO^i3R3=_B8mfs-@7>enG5wZ(~b6} z`ZKPcLuZf~h~E{bkWj!%+DkX(gbtX$^SR33E~4iuDYCC1dwAIBU$@hs3C4!RT3dF* z^EMd&?fYW4Crr4DaOEbz0D&I;Y`>Z*ar3>ZT=SN=2}xV?oizW$cjF$mwXbF`;@K`@ zMdLlvz7_9YWK7qrHA*l^r?1aRtK0N0LE2%fAH4Y@Y#xF#xI%V*Xuo-SwdR@~J<a{4 zKKk*)`)g@h02tZpo95d$wCc+)PK@Ry8BrQ5^6agg!WB2akoHnMykPe6;g+hg4r$&* zk;_iUF&Dkk{kuINL9b^cF}u`M6F)BxCWMop<cM8v>&Gr`VJ!AQ?k>G1_}z#z<-G^X z>Q6EwgkQGazXH(GqX8gljj1do_GXyfJ_Kek8F%wjrP2I_<CiqFutXM~>)7d<c%U!6 zb43`R>^klPebVqX+bzHZ&2|x<)p}|<{BmO$IaO>5tQ~b}Ui5A#-G{gXnOxKKB$L9k z?+Yegxgzv_76MT=G@Cpy4k<}X^R(6u=yq_qZ)kVdnGRX2O>I8fdAq*%>~`Qq&SIUA zMwCi$6la$sAm<b=o3o^Ge!4`w>tJ((|AccJMMaTsvq+fSChI<dI2u12QkXk(^u1NY zJqi_Sq{iSyRNVE?UvERaG|xYZRI0OeFKhFE-RN{oF1-9y%gbR7(eaZdnwiD*{bTX` zb)A01YpB~&Z&m&JPL+J!scBW|y5;m^&W{aWH>{W!_qfcmZ{MFaTKm0l;5dTr_Q2_z z!;G?{XQOX>Wb}Ws(_bz;sr-o_d~w@J`D}_y-kBCH;d@$GfkqId(cjE4q9VJd@`As2 zNb%RCk)D>~YGIQ$!q;d%nXmE>>wX6pgdPJ_OjGywmhKNys$UO&@~DN(2p*Zg?deOQ z0V=?gwB*bStl{T(Jsv#2m-~EPbD>Y_vDLJnd4_cNSO8fX{EI>Iy>u$s0_lcIwm9Z( zW5dP=b?Tn7P$?~1aAat?Ka|K5=nV)+SM9ae6a`TP&uK5m*XeyhYd}P0jQz)rHlArd zHQM>}Wm;}wWidxeKvnv&?ACP<yIAmEJw(m!^A$&Qv5*3H32VVGFhh3#Spibv*N4gK zlK?el!{T7C$iaTb58@z2OR8b3zTV<$S#9B=0SD}KVA~dKPoy6D50Y!8vhsv#oiU=k zC04{~y&^%)X}t8*#j-1MWzFpXhTB_apmDY&P-cX?a>eBhN&MQT4ot|aKH2w#6FeqI zt9rjjK$9UhpK*Cc^|YI<WRA=$bYW;&UXB)cjqmE|?^=Z}E2Z*dvI`!81?T1*zAjok z^t+sS(*51VQ=YHGQ@1cPVgsjxE~>gap8W4CP$R%Q(%?@wq#WGpA%FjN8uM#ReKC_) zwD*k!W>{t^C&>Q`S*A8ZZu(+&e5<$Ii)MQ}ba!~CZ5T_qf5t)FseX1s$ZO4t5(%Gu zF(Hs~Jd;!6dQvT3;i|*r_%SJC>sNDgHGKT4w}2Yr)r}89B%am(PM>{2*w0VDwl|C8 zk}U$EW(JxL(@zb3b~=`W`Iijl#4IQjscB{=jbuq@l6`FjPr?0Qyn^4UHNKJ8864hD zJ=yn?hxZuGV|<1KNAall4VY~wUT<gP{n!pMQIj?QCwluR;iHO7W_^Qu8-y}d{@*)S ziDT#XzQSbrv|(>7-u`iSQcm;2ajG^ay&=oKrF<DujXKwp^R=bh{7FxWg37Fh9rzAH zw*4Q(32Ae<B)=ZI=+3JvB>gbkfP~pqsH>g1bVHl9;j^6Hul>qCPb!kPB`?p8uM}?a z3jQoVo5|r2h$2}|N#$6sJw%&bPMO&wup5h6Ame_Y%PC~!1jd@_&jcKwOQKe|{CTVR zm&;-)4MwmIQuSTov=bU`fMQfJ8dpJB^o3i^VTcU@pPyD*M!ekjPQ4X)zVnQ>pOzP- zx4{*W!F8O24RFA0WPIOUvH0WG8cA)oBxfw1{JzFT>Tj33Fb~&cQxKsXQGLo1Eahl< zd0`ZAN@4KQtB+F3^7tAacMRD)#+@Cr7J9*nX(0px<lJ^7QRWafseFpc34M73N!Q}b z9wS^n&%nTS7wEB0w!)Uwbi<{9^DiWLvssZ$FmhM;B`p({=^jqJHq!jGtT(?}rYb;u z9QVkrp220fAHbUupP}_{AI7k4=6rjH;)_}!n(EcbCh7~UGJCTWsR!A7<tYX_`527S zp2Uw5vhiBYz?`DBlLc;4|6}satDGHHZ`b4jg_`^L8KN-ZaHLQ|I%jisQ{pql+USqE z5q=CO%m^OW{&#@9JhPGTHr~phUL!k}wvn(+U_VE=Ds4x_@iy;Fny#7gc=fI02z+9E zWI{&9*TBoE1IH`MW^=-4r1+GUVQzxo6s~ANB5vA3HG{14{>{qp0x0&ASgRKBaDc?h z&ZtE_sC5X)63oP>=_&Y=J;PZRVhkoRVgi$@10T`pEybbx%=oQW;6mk8k}RsG^`fz| zHyHrp_)gs}^#VJU`B;d=MnPY_y~*j{+{#Cy60QB}+`o6;vd7EwPPudlQN0Q<MjdiJ z$99^uKzH3f2DFC-2Oxy({OB>|dQ!19e42C540x|JH@bk`GCEdNzGE`aPuchj^*c;j zj0@krslq=Mm1b2BLKq5-MBW+Ty4*gSsfdOmGaTw8W3<`ip>@%YwrnLP>L|-r9PeZa zsf+Xd5x+Bn77;vWfyh&EtaoE)dy&k0EoSMGzp9Z3VNAP1GN=4&a*cCoUU<SfM^8gs z#&6g8Q*MTci&09_tgEhRT0S*!yTb^n^(Y9vIpp!@^ENmOw7Dkwa<h8yyD^jAV9n+Z z_RGcY>WPci4VaN9vXHgQ-vF!<?x?Z{5hC$1soChESzh)FxVXSOcFV&WSAFhFYB6O~ z=8x2oIZhUJVjp&lo~$5a;x`f&A%MYWl~cf<(Gvm*!8!Fct~bUu#5NDv^)bmA9RBd* z%%gl;)uhv%{1gEIpZdo_y`$D@gpa;viLn7K-m2J`(Op&mMkKimUd(FdQ^xfUaas8N z5xzpIg_X7vw;RQlw|EgMF^5T0e^$dCK~IVJh4CqyA<7ju+B$531_JAGG+Uby{zXb= zAi?R;QCH=LT<bvQh3pMJ3)c}|x-?X2tX8;?np#rA+lWn%7Pm@zd8&5y(e3yEq36LZ z&XwSP!=DUcW4bB>t|KXjC${efX;`{+a9;74sZiy!lx$un)4C6=PI_C$ZYxY0<Xf%A zitq~sN9RdcS>?~5peW7^_7&;^j~9?48}NC#T5goriw=?XjDGF#3tOO60h%kSt1yTi zDNLM|08~KfYWwv?2G3gg6nMEpJfwv>)?jLUVb6unj43{0Viex=HufZr@Q<un>OOQU zZV)01T%muv)NaP6v8IF9D(2$bA#hwa>);-~%(q$MIw4iA$rrL?by;$F^Xbxt#P=hD zEUPX1e8OR=+-Gc8&d^b7dv>5$z3F6?@q?dFZ%IqU1c(DGrP~?wQHcX6-~bA(dpi2A znx}~U`(F4(U~xn2w}Wx*SO>4H>ZthdDK>3N3(xgMX`wr`Z}M8-E~b8~llV)s)@zN< za=?rXtT(gkM?Mhr*vBzPA9Y%>qPbnZNC_VRUr5iNhc9&Ui*J!9e-Un4ElHSu9W{#b zFeL~Z<`8dz==%HSMq^;~QDZe)K+F%PIrdsx23$&bl}KAGXO218xalt9R=g}tHb-@Z zX4M)-x8UiJ@0P>eP+ckx9W217P$7VJqGQYiv7>rg$D342!vH{BX4Dh~-r!|ToU}+$ z>my2qi^G@5*?yxfORkggX_H1N)0?oQ2(VfbSXKyr`7gzd>WKXYYU@sBi)PNi97Ta- zRj9x@5P)$ZJ@HP_pc6HiDa}7cWCg&YB%G2!fTRS(WX)WcOdL5JHS9Cj{EAbt2~b02 zm>d>KQE<xC5jjA}atueW;R1q3R$42|(5|7k!G<V!6LtJEXjI56<<$@=dBuwacUm8U zy}>Ye5K{sV@xuz{niR0I$4aAkUEK`Wa>p{tR-#r6ZT)v?>i|YIt1ykN(!5YN(kijf zQLRrghiC}vOicf36^8yBH6E+p>yrTdq_?Mt#zw+bcc1<kXSwTrJZlkM^}cl3;?P{b z+v!gc5qm*etBhzSvH8zz#l(?xP_$~)2LYBLhCI&iLZ1D(KP^vwGXfw}DsapFk8V_e zHKT}?B#~!Vs-$e##LhtR8KcIB5IN{gx(!)ikDwVp+Nif7|7X<5X4JLAX3QeR5F@Os zH9nbYC;n<gi;xD~1!we;w4f<^Q|F{yaETzUpb9R>a9jjhR0u9At<Okw8LLqlk%Qas ze=W7Te$LqAY{6r5qlX2ii;z5~gx!+OyV9e3gBTP-c3tc9n(J~@z-0KMg$-0Q-dtNR z8Pi%hWMRH+3{e*#-|w6FEK6*UNU<z&)T5YXd$Z<84)B7_W-WgLgkW{{&=kW>P)wz( z$ZhjyXY4gYr6UYrpPtJ_ZZ$@Jl(0O6m<~arhDVLRoj2;P(!6PY;0V=6%bU89ia`Wy zCyy?!u)^qK#ok8b1$n?I*Q(N7zwqoked@tmVZ*p5HF~381kBaz&D9a31~L#uJ+KU8 z^80}$CMm@}$J;2LC@SWc_GdeXf%_#J6wy*j5tk0Y^O%x};FI1>erzWQGg?s-ZUf8C z8AVzOU{yq}RUWr2I#)(@!(ynwD9ZeVEKcNEGCB#@%Ds8}t@Qi7z;ifxoQO=`RKW-1 z4I?9us-o2|E={rE+lH@}E{AeRyFm{tSt&0WTq_kg6AyF4Kjs)X*tQIo*#Z5pH^rkU zRi+>Gx*x`ClPp3CIX+{FEJ?}tfLIFQh*D>R=z{jI%oT%|qqQHZjF}n7j%NF1$9=zD z{ZEk^<8)@C%0wHjYfxv%%aPZ|Upr;1?G#7_hgPX8okMJ!Ys+to`IuHfc55Kt<Gl?X z##}}+&@MP-hx6}^1&mf8e0%iNO%EO?sCBBe53Zs=sZReZQO#oH54xxhHDa<UYxzv6 zHvB@3A4FX7{KX)goR+79%G0zm^J36u+ks`aj<C*0Z~g4R%LcpJXQj8#Z1{Lq8BX)$ z$)L-Z;0-r}Yuc8m$?xykd0c(ND$O}0>JLHm0dw`{kzqcFA(d!MCF(YN%eT0n?M{(x zE!sEQzE2febFlH<=itM_`M!FFt-vRkue8ZER?orp=w^S55zXwt`r_8<DwT&X8V&D; zJ?!0^4rnprs5f$jetrcv-7o$0*4va$G?XEV#)5?XQZ%(h&wZRX4&5+1G~acp_`CR& z!qIe)6Zk3C2{BF5n@RyvGwa8lC{AIQVxF*)U9|^PwA;>B?86%Voin=oG%g_5`0J?o zU!sQINP63%9F(|!Sa)TZM`e%xpu&0mD^@e!hW;G>O0hu7p~3iYbkb*~j-s+;)wbz$ z@~vmvTc@__>k_(K!gg0!)%CY|lD8U7yPfo9sA}XCz9(aPlu@dk1V)BfcCcwIQ)|2* zv{NgrTP3`C_T<}-AO6mc?Mx7@{?=i6L;$?-x$qR(Bybwl*^vk5RkEG<D#PQSxl#70 zDSRo~aYll^rMIW*a?o~oQ|)JQ`%kNnu@6Td`kbYUi0Gq(z-?*~|0ImY-D~u7Z{7CJ z6H~3AsXYGZ{_gD(NRH}GHUEX%{rUN0-Pursv^&_XlRy+vVZ_{&DZpm~;zNVv;~~#- zsQ#blBR;|uWm5F~s^)GIO}s!Fa;J4vw)I<YFUimlPccWMWZW;eVt-wF>A6wg*8Wjd z_)(~YWj3+<W<(C26>9#DziCU@B&W%6>8OSS^LdrFY1eV=wH)YDi<KEs)8YKC8Q;s@ zRlNzYs!+<&`F3g{-`Petg(ltx@j$+tLvEt?Tsp*Gt4nNmNYw3p{Md2gcS!Wax!E|U z$9y8ivUm0RAma^Fo6U+bP8L-~CnYA>0rXK3fri}0PPvy+CoXl$+e`4X_H_(WiybeT z{Dr7`fz^f}09wA^VB3N!i=mjy-{@3*t#NX@Gx9~}$sZcj0O5v*^F}MJ#mUnApT>VA zSE;FKYU*}rnrdndsvKHrYM<`XKBuX3u}kNYrtZ})-5Z*E>0Nrcn)<i8^s6-unz{_y zH4X1|89vZ7nq+kuJ=HW`=rVq-X|mmA@=4S5N0%u}6U*L>MQWJ|cAK5h!pV2z)U?cX zyUk6tEUddNoV6@ZcUzv*vbxx9bxF(mYPa<bEt~Xin_Mm1Tiv$RT6Rs{cI{gB_qy#L zXgN%FJ3Q5LT<CUut>v`c?es~@`A4@iOUs45#|5eFD%j(CLfcKg$4yP!UAM>GRNKS4 z$HQ6s)ajm6=d?X9_IO^>K7F<4^bKvV^d7HVZSPw>-qqSZO+7yC+P?RCd>?50P4@Ub z)jqS(bLO@7+3lXQpR~{Y=sCyI#<Tb0kvjf@z5XY30_1xG)N}%Mdjm~%f||4&M52RE ze>ZGDtG_p2<HORq7}m)ne~_~_k9#A_dgFdc<iy9g-q7D2wX2a~4|I};qy9`oLgy{? z%HIFeF4x(|X_jnUY}bi;wEt^Fr|XJ`Uez;YuBWG#Yz>A-2Zqg6uqlecke56ia#|n} zx|xtsn*N%^N?KIZz02Flx&_e^&bq$uUP0a^mzs9BefeN+82dwC;PtllsB|!>=!k<7 zai_u$ET+QX3pV55$ANpFG-rZR5<wzb;HdvjfY0e95Wij0RoX7}A&q8Soml3&diDBn zlyYL9JK=Coyu&I{zDc9JKIEB6AMw4=boR$lSpXY%1BA9vd|&vIw=nsrNKwdwA^3Gf z57D3qWrzr{^i$kHmcc}KGDCRA4252Q+!&{4dU!Tm$IY~GOIW?(p_*m3-bY+vaYM_J zQj^JenLGMGZ?D;%)M65Q^@3qxh`C6W<hibXbKM<can4ytzC<mhDsN~%Rq&z_JbL>p zP3ITJRMOyByIOHpOx-+`{H0XHw>115L?-x$Lg=XRka?lAg>ZPXU@L<UnxgZEA0Q<Q zV}6Q|86rc;$AzXXT0uYsLl~|1xayiPlO$ZhI8IO2BnUS-9qPF2@bC}1nz!r;?+Y}2 zw_V@)lCAfBPUYSCvu7SYG1(h6eEh?_w7<*=ijFm>SQv-_Sbm2w*{`FIuk~GjbZFuC z)MB4SoGZf#kr);w;HrbSretr;DMK*@h@JwqX|=TS6Y=tD=?DKySIer>U!DzXzeHn6 z^tGtfIvYJ|R0~%Nt<Cy;$fKxl)N#%YTKyW5S8-@zl&ARYwc-Co(Oot~(Y9d#9%2L7 zqElJAyL;(|B}7VGQd&wRRF+)28^k4~6a+;CM5RkQR0NTfkVX-ahkbc}!F;$s%*=J4 z=W$*1Dt6AurK&LaYBK0VKcivO?d+~+Zf7o4Mqg0yjzzN`>Piq(8Ya$le7kv4Dc(`w zS$6x|-Xewx3I|$&_pamkHs`hH)*4inPk4!hSPF^Sx?%)UxmF1P$lDdjcpbIgzbR6& zreX-|X8Lu`7se{Wtd?_^44~8$nb7{mNv12R2FS+zyzt1==}tGlk#p3msH&B|_MeU| zTX}PkgsK*OZX`?B<DaUej3@76+YBhW&ErIvpGd9QQOM)^ZwErnPj_xz?D01h-kC3d zrvfwur3@}>wDs^z#xVf^$9ka(K+cAVW*zFty4%exs5CXBGyXA*2iwhh*w2O`;{bY? zhLm+xNjfH^eF?Q?LRh)SulN%W9`2E?ecitzujId1hikvID*d2tc%$P}*^?qAT~#en z-q=F9z|)zxOuOnBO!DuEYd|dc4U6h4oy^uS@Cr~!flFhN0lQ}XyKlP6D#f6Ypaccd ziZXz{(xRC@v=U&<Pp-&g1!KcpT$0gk_Y+wq?9&DR{gJTAk#@>Vr^Fq6SF|$i@pNXb zW_%M44CPT^CP}w$0tc{5k^AOlHcxGbpFS?g_j7nHp11UNGrx54)%~L%b0P;s)en!5 z=O=?VCGe4Jh|o0<)p!=#d71JpHTu(#jEoTZG#$-2T{5%9xMOU>hUTasT%JmLvugWe za4LojINwi}lX0kIkdb1+hv)qMIwlgvd(;z=#(C38@o&)P$9PVN>hY4&&rQHqzb540 zhuEXlzrXLGZYlMEIm>kKUoNZdY^{cq2#9ZL2Ru`D5`=e`|26P*%WS@R`y<j{`QLu= z^Y+-~V*Rf0RjCvefVXd=F_M>o26zNhzVkNdoQz1cwU4Htvu`ZAqk5pI>`5c2v-3j) z0LZQy21_Jp1^XkE)mDp)ukvOYKev`?of80EA9!2r=~2oLtPIOOT^3wJOR0AZy>c?j zxe9%R?L1{xR4v|?1zKtcI24yLJMvO=)LJ=BjYY4hCWzj;Mbw+LHP-@9$uOl^Eh7^e zS`*uYPyQ`Z;MLDL)V8q4J2EDXdhPVE&Y<HH)J*yQu*AE!XDUMzZl0P?^K8P%aGeiL z!riFEh_;miEK`#|Xn_$)ik6S#%R<lvU%5&X(f%emD9?nlb^_lg;-0v~_^;!Z<iZ=? zpM&r|2W8*8{v(v0OM<#2+6Id5h_}Jc;i^A(n+MS=>qb90Li5hk)PFuoX?*daTBXS% ze3cYESY{02_wAybYe1+_A6&byVw{(Kr!*L$o;dSrHJssb7~kH<<**qU<I*E+>mApF zwv~Y!vFk;H*TZ_)LbMN{*I$(W>)Y1T3SJlX>3qxEN%--0)GoP`dcvNi^OYm@i(3W! zPct3#C!~-sdbLcyqN|bQW~JWt&M<_m9=UO84Q$#aMXV*$iXAvrQlXwq{<fOpwA-x1 z#c8qXwJ%vO_mbI^_+KP1hFh!G=A&x%^sAhp*jj_wAQhhaxJU1T;DYI4l`zpfdmb)f zx8CEI$-duK6K#{HV?v6;?0fnip0>Mv=1&$J%N`M?jJ!@#ye9G@it@pIj>v(ei4RdB zB>BP8mQgWZ=@$e#LWzIJ_B^p%YPu>(#Y=7|6mvb?Em2xrCa5}zZL&gO6j@ve1(Fkc zOcqrmsPJsp1?Wc$oe|oHm{vWyuD4gi<N1-a+y_=yo_Gz1y%eFX)=K=lXsWu`(N)(~ z^9ga7$2$8MH45b^Nc+2{d4kWiY+S3`7EKHL!R1^z@`^bekCG6e?5b_!g8Q31k6<4e zHz*9uq)~?fRcKvN6U}5&TV@gf)k3kj_5}^ma08i|Uz@UJ?;pmPu0{6oHFk4_wdruQ z5G|}lov*skH5?pt1X-IY9pE`P>*^UwRf`hub2ShgE@ZY5E-Z|dU2_*BBb8`6dY~R1 zPNIJ-C(0)B8~USOGFAh6Ul7y6v5N=d-*6_h#7q=0o385rD_ir^p`vV;vq@C%=vqin zYtPsV<2!$cm}-e2P<mCUeWIar)jigfLtzOarC!}ute7Y(4IpwjnrG>f_3`;twSIV7 zW}+zpElY$wx40(y84DJa?S>i?;r<l>NX#>u=^G9#^uw#)y_^jG1QRdYcO+>{9Td43 zkbw4U&C^a=V-tI;r_foQTMp`FsNUiQ!nzI8eB;@>(V&tTY#iUAzulEjCLOX`6!29z z|A#{~#2X|k^Lsr-;jEj(<T&fo;sHdV%|h2KD2waClzrFqm<h>0faA$@#v|seZYW() zaqeQgc3As};+GIOljW!*GHZaF5(JQ$ZgP!fuF5&Ca((E;awMp3aeZ(_-4Ey$)lvP3 z-KR%#J>E!9<*jf$rZ9|^wB$(bK{++9JmzC_yUD|7DDp$_Mg89l{}X_QhxTQB*!Z+N z&PzwfY&AYkwwz6TJArAEIC3*xhs_?U&0zU5VNAZ99k<d?>l;EVqthLlS;zy#NSO;( zS<0ijd4aEFR2N+9j{?GU?!u<iY&hKP`0j1oa%&R(`*08aq{<i7>XRJnxJG9~*|p%t zGp&!g+9qUBt;sZ%BI?AO-*r64UW@^K8{J1UQ^n9OHIa-Kx4?1}#befDu9=MJrVrq( zF}%nfC)d5>Vyg;H4{yem*nku9f9&1i_w1Dg7ni|2VT&fthAsfZpS+KYJ!E$eao?85 zU~3nvuO$Ua!Y}=EH4kA7`2ioo)ngdOwg%*~%c+c;yvj~g*@3c1l!5AMvWWVNSU5S< zC>M&TH8BviW6Pm%Qj&F&{$>>g0Cc`&vO`*iDE`bJTz$u-HO^!-54@i(I<7<H3QxQ( zUMBFFbfGPka~j+v<K7BAeHc0L(QuM1zcaN`nix2!@;tUc;(~BnF)1E4(iG44yodFV zCL#8+IrZqB4t;9rVDI(mG<`=i*M;yQw{hqOjs(*c8V=K8so<ugc86T!SRH88+qT!d z?9~KtZiYA8DF>d`q6-8q6=R={1RjF?AnjwC<Yf53v%w+;3u=jC+_NI=iAhOyq6LA9 zATcqpSW{<FvYnPK*wy{j)0STpNe)t!<+h1_<Zj~IlX^o|lg0^6B)3zglWCb<1QMww zt2}w`eoxM&W$j`5BuQ{+JcZUj{_$b#=aLB7c*tU3s&xTXJZSUZhICOc+y-#)qH21G zPbg((B(yIwbWg_n;AH*ka;1Lq)kVo0P8t#!E*qVp^8Me7O4}2jYOid_33MZI_z!M- zpC15QGUb}-&jT!Z@rL~$-xM^(FuF05s8uxsbgOh`K@xRKwSO0lqxUN>uk}&r8j!)f z17b)2-i103l2Pr9&x*<7ph5=GrVd}(1jCjgq6V6m30}Hd8R#)Q;uEtz;7~q+1Qf8p zbR*0<#84e2%u|xU5;oIB<Y|3|Z3xRH*LG~_8a$wDnxh4se)CDJ_Pek?CKnoj$JgBz zI1}BSz$Ty{xHyhNy7(rU#xgLP=szsQjr)IE*_*w16NP%1!j9Yce9zUJC$(PeJfyQq zRbhD-x4}x;*g5IPZ5i_(=90hu6za0dJKATI9cMq@L(@m3^`wM9uL_QN>Q~$q_`uMp zcp1vpy>CNv`hH8kcH0Ps1(QY%>uZJhE0#^ECrx~H<=rr{VU3%$G~eU)1HE@P%FGn_ zwZI6$%SDKcwK2Ka+V|uxiiG7yhkl`S6*aiw65@7Lr&y2EbFka<AYgLuu;)V|wS?O; z7#$FLW-KAevqO~VrXEA9??ULedatUI5#&o17%&0}ut9CrUG`w)6PLcc`-eypq@H0* zFQ5zEgE$UL=axqTbhKatbX~|ZdjlAxXMC@s|6!+Ko#k?rpwxG_9vMA6f-8&iYNz23 zfckwRNRONm1f6mNz@A6w{XxnJACTh_`ZP1d-k;f!7;R(T$}qJH#R?^3z}H`l)`JH2 z!4Roke8Ms%=|D^1GMdw=R=cUPzKZv+@CN#<oXWQMLGDNN(h8@#4?Ha9VIP`%F`9F6 zg|h|S#nEWuL3QoIIjk7nWit-T$C>@0c+<4ecQ&p9ko^PuBG&uRJ(#=)y8L?jFrA9d zQ1LBpt#8lWd8;ZGeCy;!a6iVI>Kfgu12TUzkav4<@8|c`=DNT(cTFP9<mt@uEQcnK zmV2A{w(5m;0skncq)ErvF6h;#!)|Ay@EHGosmEHNKbm&9$u_~C*MEnKahIMXz^__? z)ZhjMV5TCtgWYflcNm*S1=s*bU&AL#1`R$X$e#vmq*qQkaqm!yN(6M#%paq{I4GS| zF)7!umzeya$BR-}V!3RaH<<=ZM+=C*ut8|`14Jgc3!63%S5G4o^9<TWt5h$Bi7{BZ zQrEs~AFVpkV_gRhK+8GfLDDl!H@k%4<Pci`{6M(04+Dn!F`G*rF9yl+<orsPvM+3s zE#DEpdXwAYb6Nc0P<n{oGEAe#25%V^l>I0lPq`&6(TU?8h~_vB<dxpL_5&Ql;copE zEU~o0A%vCv1UKzjZ7KA=M>Ju-jAq5fglN$iETc0IUHF>}dK_K(YeCZ42#J_wIJtr3 zyFM~8Eg`DsZON8G9^xYLi2i)whu$hrz)S8}@n80pLK!mJIeh#~GbMU1qa^h}zC7(B zppmg5Q*{EXkQXCgOecTm7dq_a@AHpi0FImudUPsTgVI9Ync1^FmU3P`sm9{@b83l1 z{y;1%P32BV?v&9nWJ|P1l?X1KELc3;6ipT25-bUuVm#P1S<aLK?Jm6kCEaVrLgpvM z7)<HC!L4{#j+vfb-vyyZ6uLKaWP=#jqo+%eqAlp6(L(Cq45qssK-Fq(&Lu?`*<xcY zA|IFw>YRol1ZlY#A<(@dtPAKRy^<d#&k;n>y=ByiTj95)_B*#zw0`~dJ5qPo^u;Tn zO;%5-U9m&tsuL^MMl{)%@$%O-*+-nM*N^ffd#{PoTpOm0sRCUib&yd9j4UwJa=Mh8 z%^&j&1xM?}JobIT4@$(#=8#RS2IhMez*g}UppEyLQ<omb@pO~<L<Xgn-hJ{ZQBhv_ zDm_;woa(6NH1*_qun~qwM{Jabe2DSRs}E+C(8Y8C0UTUk3tX{J?{0m|E||Jzn@|3R z!n3?bM7Y7iJzi@ekY!$1%RV|E-D6#Gqv)3?wddN|90T8~lK_rC&_alaBlmngbv~Jb z&4-Qse)uR?;GuMnBT_t%dzb%Hk0>Mkt>!l945Pygd~CU2dB&1arY>JndP2(#9#hMG z;%zvm<eFo35_153E#qZHuKSuLID~Rk$Leo36SLI-hlLP{ZHvW=TNEBc+bcI2gQN7! z6Z^ae%LjoI(3kcU)?%L~@`ZRcdPw8s*MAHM1Xb2w_HLT#sXg=$9q;BmwGgm!^`{&B z<v}i3Rc}|neY<^<>2;mSIQduaacOiu;^UrZGWuu)D^W}9<aerACaZNdqakbcx+Ul2 zgBKtWd2hl5nG>~x86?<3A5|N@wq!bGI(0l*m3eY=HDSh^{ke<J6k{`kn0t>4*KbhN zVS(*y%tRc5K94(p-<WQ++IOdLzakpvQ+N>&9rFo24Kw!YS#axR+&+}9>W2l%>)-I% zQ^i=a=4@RA01S-2+pWK0pDlUrN#8|}@9(0eXBbJ9>4<P?bFM&U3L^HzCCu<l)D~xz z$1U^y7Yy4HL5Bb3YX()h%RCl}D9jYFT3*}lF~1*nXtKs5Z}WS|KQA+f5-}%VqZ2r$ zZ#48vG-Cbs>dr_QIXps><BV(OQj=q%LSa16g!&Hu5+LwHDp=ixQKFnVKVEw<y(s%L zk18%G8Ou*@5JmiKj7tqYsDSbYh5+*LhQ1OlQPFL>{!4x+4sb4F@-1h||8n{bAjCam zwhN+=|2wzqIHgc<GdHD~$2Y+GX}UJoJzkE<*zdpcYJZ6`6?Rm;$#vIq`j-b!n({Ti zL*P2fzp=@SOLe7(79P<#Ie$7um<rS1<0oCoLO+?QVfPWwe#@4nQ_>wN(V8$Y%j{gg z8TeXB|Jy!S0pc#t$%$Eyf(E_*=NqOUPo<GA<X}9do~_?RMVZ=}w^Va{<$lD1jS$w# zpJ(QX9|tc>wpNi*(HP90_|0qJ6(?jT!!<ME<{i2(X{ed8G%iW|<d=TwHY{LnB;7UT z;k_ob=I`<4pjwExUq3_V%2nN#u5I6>^%WI$1#Rm`hxWeB^N&Us$JsJX*3DGQ>2?Bh zSyVEXH5D?{+1}(ky9RU5?L73O7jFnzo+{SMz|t&=?gGT#%%~GBE2-uPiZir&Gm|Oo zRIftLis+uEd-dFcBW`^edKo%XJyNi>Yj<uj&!H37ky31SxA5QMmdTJxzB{iolczFG z<x-XJ-bGmatsUhZpG<mWFesy!)Bk`LP{ow_xmDA>J?Zghe&u%S<}0S)U)8xM;%={q zZ}L%wK&)DuWJn>33=Ke+U9NS=m^PodEWo2M^1Lz$+PO*uTpW)Tyk>;QNk-n7cG84! zBKku9*@-(vW9^t9N&ujeVJO{)ls-Hb6}>OG6{~2%buSPp8fwma)3AMH<=Q|wD?>oi zeeKL9SKHVB(1Iv<0-KZZ4%b7&Qn#)Zms8lE0{&t<BV=lQEP4m^H$G1r{?BSMx3Wk1 z`NI~ay7b|a_kz1yp?GAEE~)+8_|{EX?nb}BUGb&!yxghAteF@eTPeeNx3T?02ALaK z!gWEv^5Km#<;pzntGympFW>s}=ese_=fcCMwc{fn?cZP-{3i}$k;wLz(v*w3iAeVY zC6GK;g+*_e_u!r0-bUuRd;QCOoFl~8oQLEFjLgfd3d^kU0C_|_oID}L!CdVgK#gu4 z3ytwvc+6fv<u{v6rWCL;-}m<;L%3zs7F-4l_vLxf?YB>7h|bktRic>ZF&GvQ{)-m9 zulyrgJHi!F3-Uv`vLm&OW~a~*E7v~ts4U?^8S<qEx~q;V^w_cm0wfidFi9x^C;TS2 z4j|LLMN9ed(rJJ4NZG={{x_9cXFq?4<aK=Exz=KB?z@hbDpG?06?S7~`}yK)-~qec zM{fQ5%w}tOvbPlE@BYhnWl5H(eEoYBe>{oiUp8F$7J2lU8d>q{T(Z<me#fcl=V|NQ zeZx{qO!AvWgNqJ<R<=pRr4v=KVHE4{zVo}>>RArIr%dNE{)I4`j@tV^g+BOX%GhI* zE~L-g+=hMMI0K8FpMOl>3|wA_hS7mN|4rOgp{2l!TeQAG#)#)d^18J^wL&)gLwXN? zp|xa{Z-(YYrHhPZ|9E}_$){o;_ju>>j+n}wWlqN?no6pWTPgkJ#!CQ-doR(JDPQL& z4M)s}VP4FeWjay|*Y&j3JQ}#cB%Z^B3%bK>x`c+Age2XaD;@8#<wvHxYiR@iDdn!6 z3S0lorw$t5?j<gRzK=@_lk*qlAZ`?iy}|!L{wE^Fbel>dp0r8%^FAe75O1botQhR0 z|KtYqlzw%+cfrXiUOKGuzU+a=rf)wD<k9c00H=ux%YP^0fCEeP2l$-tn$#c+U^YRf zK71h=9i~;HwnUNH7V*TN3XG=J4`(fyepSL`uD{${fAe)@OFYf8cb*Cmbp81OZ0qO6 z_(9JW89BZyS`-{XWf_15IH*D6tWqd2z(P+1P!!9lm=p>hsAF*8GMfZo+r{F1l&Tla zLYB))I&|&JQ1Y;LVu+=6OJkQAi|eE!R;RMdeR}RYkLt<_T)P;v5;QOCdPLn%B#T3I zwFgs_2>n_Gjdz8U2Kwnd^-_(bu;NJ+he&`?&>QYTDeJ#flB#Kk@U3XD%M=q0<i0fx z#b(tD-x#kewh+^+5@F;1&w!<iLrPt4m4OPNzPeq$DcpHf_-m>IP#xv+idZh1vH-iN z&d~7=W)x`XWpTZHW&U1U6)40m2v}yKKud|z#S(gjppsZK<%)p-z-N@DU`y3&Iz}yv z&Ad6YZ}kg+u8=4!I`9=#;Lk=yNxjBo^!lCp?OS-A!4uhUQ;eL>;eBSoc;?4R0wg_J z9@xs0Xy%6Ig*z`dT66*Ov5=fQi}%hb!sK69Wy9!m8OnSszX{NWfyKdVT5wINE*)uV z>&ayLT|tyKJX*jllbjY+m8nZDOK!5-EUEc0cr>sVuG@pF@bWMz#8OMEeOiDjE=zW! z#G3PSi+15H@qzG0vTQuX90bE~`Pk4tQv25iv!%=E6s46J6$7Jkf(Hmdd*b2-*biVK z6KWTIPeCP_05%<yK;Fdc<uTf<Bl@+|6`{OFS+48rgPqER9c5Mbvu~u%7<j&5<3lN} zd6t6=S@W1mU~k~-Gi>&<Q^qXD&#SSlz_00LKcBz-bxcLKK4t5g+P08xX|suS@8Q20 zRoiO^u>D}wQ`em8@;59Zvjh}$K7TP%H^peRfs|+MHB*{r_jIUN*mCu*^HSoA!h=39 zW$*sAra)}XWwQCFhc8d*u|J~3=egH2Uc>5|G|?OS{9<adSn&EH72tCjG2j}R{J9Ww zJx<iYS2y4^$Nl~L=hLB1zreE`*T){{MUm%84WgvG@MY0utnQ_mU->q6GgLp>9lA=d zd-A{(7ZoO<yt{(5+VIRwsZ0vpZ<B=pC5F6*x*U@AR`Vr>d?BExq^XO%VN3TubrxPb zmEPClph(*KrggN>ExjpwpE73)_)&A|6kDX$3eo+|U!f;kcRiy?<4S)F;-6@=c25~N zX32*L>6MdrAvGMymeb`6vTgKGUuWqVfyUe9U3Blo1C!+c8(l*vCxN)I4937AbpP^# z0tuLkl8LtgnCTRi3m_oB!3EW7`<Em;twYNT7n}UB(MEB}^o}ta418_jiT!!6kqaN7 zFPV&LVoh69en1C35zWb!!IskoLu1X!6KL<;8<B5KD#EnJql2YT9_mH05aHM-E0kRn zFgkMve~d!>ke4DV92RLHjsM3B5rZ3cCx@M~mhG)8>bQQn3k1l~qy?C=bwrmSS`tPA zJZ_&I%|)w%ba!qAqRCaU3^oAM(2$3UEbT<cRfZ*xlndrHX2I(l912s0dva?xS%rLR zihI#LCXwJXF`sNb$hU~rH$JADAL2(HE)FK~(M=#rH(K7VJOjHY&iKCUMg3BRm`SQ= z)1n|0bgKHPj+H~GPF!)NWRe*~x%c;JE(R_(knGWy2w6?!yhDZyh0o_=5Q>@iRlPal zkM(!JmO_tMysw|M5!7}Ak>Uwlp>I10b>m!W(Ui``TatsS7hD-peS8)UljLZZn$gHU z3g93Bf(E1r3bWn?>xzS?ErCf2jz}p0rT?oqyVmRmHPHNTuo4JJLPHNDoPj=vfX_6F z*o=IARG!M^RLZ4Lmf4@!PowHV38T5aB#tC%E&ngpaUP!99Mvp^exdX!{f+~Iyi+|I zrL=MUIxAL25Axrz$g?en9Yk{c9c5}HBq&+eLth_hc_dH9@x!)mSc1BqJugrND5J$& zLeKy<QRIf-%54|G@Qy7-c4(e)0xMMv#M@HlFD{Pv)&o16C^oGIf6W34Ho?~nxtRB7 zyiiR^ZJf+1Ju79o3P$7^EEy$mmrqRg+N<GE-xw}rp_th26x8|3f9px(7eLodKzS_{ z6UNG6pMAzDGuN2Kt{i)8BDsUA<lx#epyMN`g`k;MC{qRVeu!qHGO)?bc}?jw#<k!p z9t@UH9W&O|r1iI#j$=RD>$pK$vGWQ2B9o8rqwwApVx0*he&fiOz@rH&*>rWaeSho% z4o51>ibR5dWg$w&MCmDuTGRj5uD|nK(l{d<uN_+BSe4zv43&S68tUad#f_*Mf$HwC zjc}}c2H1uCMuuR5IZhL4G?uzE?8wj(m$)X)Z_bEdM_KW8gIlUv&oiA;D+j(T-i;z8 zCpf|G7OZ`F95!&25tgg{p=M#|L#6=AgB(L+@=c3Dln&f>SjpK)KS5XA1rMdBMBL&q zKox&}S7lpNo))IB%9IEegEm1)^>d2n-D&)HSZ`R)9jSJ93&mqKX@Z;XTH0=WZbPrd za>9DqW61Eb3RU$0wvMFr+}Ax_ww$)Wwueb^J98`M;IXcOX_suayVeVZ@U+QVR;gd2 zJB)!T@bJ0kWXn4axAim(y$o+ygcEr%&N7pX2TV2rYQu9dCyzEw3N4pUPw+Y&RIysV z9+j+D>9#zJCh5<|ZRAdJ-BW4g7?u`Pf)cO_4=g)o@9DbvEXEwI5AETolxz_UVW*A^ za=kXe$dFlT{Ob2#c19ka*!SBKUcD|8Ld|~PGHZ`t&~KKPX1}y;JGGZ-ZGVk%`IFw@ zm?gBjF7e<%^m?FhoY2-8LBn6wEc&dnU)Miz<XLz+=*NTm3Y<ga5OTAl#LgdvQ!g+< z{+;3_$sgREsg+hqQ|`=2-r>VULYA&*-JQq%Smm4Fi0V!vez3l>KWBpuK(v3e2}r}) zlN{|xhL6Aq7Y~KqXE}#7+)ICmc2TNPWG)nH!}uW5Jar@@#K*&QMnnc;n=l;;Navmn z&e1AWYyR)SfTH@b#dS$p3eFQfPi^+Yuxhz9)yyj8$_;WVZQ6Wn318=<2k))|-lr8G zqE!dD?NRy~Y_#D0M;^S|wGyXWF`QzQnjD9RBE6zjp^Am&&qSwcFr}Q?cukQzRkM1} ztIcKJ-$n{CBef+iI{3r5^eT?(uzF^LB9lp!X6W$VYQ~o(Uom8k&9=A|2MtuDW`rdd z^3O67T1^W3PH9S!rD7KC3i1dm0K_)2VF5&tCqCLU;C}o~uqnWVmV)SMvdC0oGp1NK z=C1XVMOK#UT~*cKXiOEomS&UY;vZUjwDs8$D>lGC;T}42<)*HztcxasU*AVREKYa8 z*kCBmbSuu>K+r)}WwXoq`Df$mpkRKcczp;k!HZ0+aF$YFykhsZu*lz&$ca7^n)NU{ zTIO3es>R%9KMoPAaS`O*4CGV6Y^^H1n@Civo25MZ%et`^GvTb;nYx>ibZBxK5RzCC ze*X0KcS_(VFQTsswYjdb%-{;(sBfQIq<?~~HJQDCCDXA9(#C*-C567Ctb#L*1Wrg2 z7x53dRz#<pT(-4k(PYqDU!bp9oHn{(;lHJ=C1ppl7`Al0!e7!k1PHm@q-=|$&)`BF z<hV=civLhRd<#%cAp^bsou(jZDn6)u!pj5)i5+8@R&$lD&rIn<u{Yg9ifa-bra~MQ z%&u2woS+fST_T!T&XmCD2|5-$)&sEu`nMTsk7KxOrb9P_Oi?0ie6g$2=uOJhm(EeN zzeOOHA^~Xd>>$57D4x$NTOcW0XgKbO4~YUht9?SH|H0k=63=L3uE&o&yJ5P9zE3d~ z^k)*8MJMDam0{0?5@pS?=en)cE|lKpatoT|Dup~5GSTwNo8rBGGb!)zDJjoEDRdKX z)|C&|XEoIg4>@gOv^xs62z60sW&R3?m3}feUqP5ygffLuq*!p`iST0-Qt}T=D<6t# zJJd!|o&Ps&UAORVi>omfJYpd_d;)!k5gwaNd02(Qb0I)OQq|E6e<VdxKVSRkej|Vg zKVY<|5tOrkYRMe$(*Y59HAQ)M67NV0cDP5&1p;ZJg%7)sM~B#eLo+;}5(Po(*@P0L z5gSAmJLml9n{Hb;)43MiQQky&HzQ*!#^fkC+#ti_PT1=T%l`rp87_#`0MU!qs9%B6 zjgvH&0aRYrKErF&K@do@6f1QWjTx)$dw#@N6J?1M8vYxJl_#N{4pq>skKWy560FWf zQkT;Tmm8Mjs6FyNE8Tz3z!<|q=wu*ROd+ka7^dfOoo<3zE`rB$C}XcYeIe)PC*?}> ziP)ofpc>~Eo=88EN8KD3JZOyiVXQF{U%zHzHe9N%Uq&Fui3uRyNty@U!O}2<|3<US z22(Uo!y%#S>rHM)pG7y&3GXl<7<meBGiZNVnS?`ZOi~_2%lzBOCDD1`3UT=ZJa{@| z<CLY6aSYbaEEJ{{*;p>607E{vfmY6-U%N^zr5<OZL<Y6gdHGRAFEPt4=}81Zi@L<q zE)(hY++yy>PKNnuij{?%K{9XDYR-|Gbs4L&`K}fuCeJ$eutda#Byw#MmIhqmtI&zW zgo7@ID{GtA;zn<<I(5B{4e$N`D!C9;p#NlqqT<oUhbrN6lDd;o?<*DH<+@YWiOSTC zE5ePYUn<~7bwFmN<8VcV^8M}PMo?nj^@z$~eZl8473DjPYRZic3{_g&jk4zr#INO3 zZf>=2a`ypbG=zBr9b_Mf*q=m3bD>sI4QxLWNVuYdIMpQ#BkB{<q#QmgLz%*bX{`^3 zf`Qv8wj4&vcWA_s0n>}WY1&w!(VFytKqPVwUEb`qjtZh#N1Oz}JC7~Ka#Xk#%nByG zJu&K|o2JxL&g+s9y}?MGD}QyEA<lqQ$*A1K*zx+bIPaEWzN>?&+Q{n@YGAxhXwF)7 z>kzSYZerq${ArE6_k||2=?0HT)@7{9E^p{8g+Rs%==Ok_+253CIqXL-|GNRU#+iim zNy^Rv&0T9mqoCD0E^v)2@`Cu{-%k4znvQajj!NSWdbSGL;Z{p$^IUzVvF+EL^vnkV zCYv%S&2ZPRfL8%pc-K1bk0dfjixH2)OpvR^L6c}Gse0yNMLq4G)^TkS%ITlrd1s9d zTyM|sF;z$-e&BN>wwzyCB6fyucdmPsIJiaJX>@excp7P<{wFw(*^DF^F&Tpd{Vd=M z6<vNQV0%tDfkIMc*k|}rUooWQd(a0{b1ZVSpp<a+H=i-BQt25nh-NJrT8^flDc!8k zyV*y(ucdN6Ua0)GkocQe#h6^76OMoxSBaemr3;$1e9R{Ih{W6}e9Idg7#J)doV(0` z-0^fKcEoMe3E>Hd#$J=aHcV8z>pSCo4I{+kpWPO_`NvnB-*SOlTg9QW^EwKa6i79+ z43Buj=thQIJyi3+x!1mIm1ef6Xx4Ke>TVt~8~|b(GNNMvNfc7%t7KGblWNMM{n4UB zu_i<D7eunt7ta4WI%OYg6jTPD6=bk5CoLvzKSQ;izf~P+EX;0Ypl<DqD>tMaN#N+` zO3e#wGimEZO4lW}xss6g9Vq)hLzy?Sb%&5^cq=RxOhp9*5M2-4RZD#ao`gzcyM$kR z=N{8gWyTlXm~*d!jZKZl;Y7yfe8&tFo#jo&R;7X$V2s})$5vE3<e89o)fW=XF4un` zr-B8^16}X`v-O;WiiZn29tqMiQj%GN7Y{=o`wGH5qRzGHen5~%g5!|1NveiPnz2c^ zSpSR2))Fm(fAxL-WCU|7<C5L5vaj&1FYv`lxOw#Zxe%AtW$I;mk$;kJmUbt__NFD^ zGg4wRk`G(iJ8pjxy1pS9%ppG#nAm$V*&Cx6za`nbff|-lp1CqXjmKt9_hyMdjhP)^ z1bRN!t3{16kcMyOGCGnKV=rcJ!#_ETeR4JZBuLd$;`qs{;giqUC%?T<cDuuO#Xbj{ ze!l1T896rnJK}TX*yo3PpQEm|I>EohntqA*`$9<jlGN}eW$a7Z-j@vce3saJj_G`! z-+V#Zd{M)E$=Lkkz4<5bujOK2D^0&X_4`_r_O-6z>$9=14SQc-z!#du7G9Yyy!Kmo zleW;_u<&+l;oaWC2l!&Q*y0t++3&Y_rF9NBEPfnY9NSx*fPb43`!-|xZO-pXE&Vp% z@NHr2+qb=M-{DIuVoPhLOB;Smn`uki4NE`AmiG3R4&dL9#J-=He*f+F{ZHEWzYX92 zjeY-b?>h;;OeRiRrZ8Iu`7cA#m#G?;X~vh~`^!kg3a$7Gz1a$*{|a;Z3TxvE`}oSW z{S{8cDwp^wkJ&1p|EfUxs!-#q$oQ(*{;C9GO-g)C#%xW_e@!8MO{sBBWqeI-e@z3i zt|`8*ZMLrKzpkIYZrHePJiczaziy7$pePG}!PZ|?5N=|y(UQM$(|_o?N4DMmwBz-m z7d!QJJ68<)kBQM)7et76dUk`+mm3dTBgFbgWrJhHuFF0Ce8A>@Avbc(cjQJI=L?lB z$&O7AKhtvM#<1%{j9<qH*UM8M4P~m&<@%55r?%Rq&I;JgWsi5Ss!Xra?yT;ZKAq0n zsPEpwM%-{DMVQ$()->k5c8q&2+JEMraEe8y+di|o)!MZGbJ-}K!vi5%S83GYYI0QY z;r)wL*v}}Xp9*S?7FjAslDoy{#P{iYXIaV#bS`_oLs5SxHk%qp5b<7Hh$9^G#%?Za z>0Z0`TlNQV0FP|F8RX+#8F9TsEEI7#i9DRdEiJ<rV_jRSH$li3C>s|(elv-r4xyr< z3;U{_UFWnfy>HzPnV)R)Cn0#|oL6U&XIP}SGLFtW4|STLejgE)bU>ecMCNhK_vUb2 zvMEuV;HDV_4{iB`h<92zmP>2Y^HaTUlXm^I05j2TbKex6Uyu8Gg5+!+(EdnvaP;4J zQ`IxlW}Pd-_Tv84LO3|>!EMftL`f<D4?}Yv^WB*ZMl=dIA~tZyUzbP#N%Ip2`<sbe z?RvT!7H9fBdwuy}5=-Tcry8Gx-}sDEWvcgl_lMG83r;IEY8^3QeX!UCzaoG0HQ*~~ z#E(gwmnSl5;!j#soXPy@_0WVfJgiQVDiIIe!y<nyBg>ZJ5@L!207wB5_U#Z+;4SF& z<cO{wr<!VdZ9?sE67d;N<&C8(>{7$jpYVAJUScf2V&HS;@NP_(7~ymSzhlaBPF?Lr zfBJ5?i{?rdF2PV$0kB~-qHZUs@THmm<!dvI^BRHLujb(w0q{9YX(oUgyCl8SCYUX0 z#!)ejP)ts)^d|h_U82D5bGAL$E^7$h7+cWDB%SApyg{uR<_cK|>)cF#@*#7rrQcG2 z%;Pmqm~1_@W@d9D;dHm10^MLGsAG83?%B;3oI~MsNcmFg*`4l~6Rn6*Mv+?`sV#-C z9TbwU0YNsL;*PdWPt=0OXK^uL8YTfbZ`_7AM8at({A9LTw#ZUYxpuwFxi|EujiT>L zk0}iSxga|_(-AFG^ZR>y@cK|QUs^y@-=qIV<NFB6FZEZUr}FyO5_6BONjv>1MuAO6 zQ_*C+u{l1DqE-bxopt@s9;+0h*NQG5&izsgLjTw8Bamk2WD@$$xhI$OkyGQ5^|NO% zRm9^C%bnR9&)jFKU*Ntj#yY0?tKp}~VcSoF+REdZj0L&knY;{yYf9`5n)|X%?b`=R zw=SoWT1aeKo26vmwiB4GCNXPtRx#Z*1(GgQzGX4wCR;UK7fG8up?Y?N$KLj2KSj(+ zj|{Z4T&fzid#bV_Re=Lu0}S^<%k>`H*H7tl^1jlc;skb!HXlFis^eqSadQAM2bP`J zNQxmXrN!;B!vasz@biN&qV|ufIYJZ4H=ZoxvuVpGcK<?hjM$RXIXsDhdTfW1S=EoD zTD0^ly1@-QWl`dC5ROs*av10EPV?Zbl`c0Ur~mUJz1e^cDMBg9_+Y9<xSoZ4L@%=O zuTGA%fZ<c7`>HB8q~!5MHP^$AXJ3|2$i`8o-{0Ma;LTo7B^2P6pljL2+4GxE%6uQ5 z@;?7`0V(qy`uK55@7?e|XU1$T@7rC;x#=hTq!oAOhm)+EoKdIk(j~qR$~~BGdwUJ& zMb*ER<BG}`B^21GH?PzCe>_UX6<Si%mAZL)_0w5m$*S3dK2NtO_hA+Z1;%J9igaA| z6w~8JluUOx48)HHIZ=1#s9rzP`L|i*{Do_iCv!O(Qh4vtMI4jgXwi{lBBH*qbj_gI zi}~Km`8!WsNM6Srjai-gia{f+gn3oX9saz9E>_5su2z4mGE%vQy}%RiPeKCMmw<<C zN8vyIGrCFu-PryVQygDS*U=Z9!qNA!`;CP@ZTvvVEcJ-BRT8-mT*iOL3qDshOzRzL zO=^a4eijR6WRIMrH7a+UXA^CzPIq=S2{=z`tc&n?tsfjY!tr-LX6dhfiM~nT!Q<co zsTu+8zkl0H+{B~TiUZfT8~mPM#MVr;x6#&Egy@Lq3l9B@2Gg4nrzS&yt)H?C%|jZ# zFEjSDT(4i)E`*P_BIEk?{Qy)d(TD;)eWA;d<f$uZn;;a^U&#Tm*!Lmyd&rV_u4XNL za`yQmFej{-T@oQ@8I^MJd`~-3W>8U&0`SAE(td4%kThZ3l}{Ec@!M!{l<!SMc%Yf= zAGERDaWf(;j3S^-x#0ZA6z{`PZuaB9wmF@HCDg5^#{L$!k>-310LLmzO~iuEgJAKb zA%7l<$YRgcXcl<+B+t45gzJl@L{?Q_ddjaf2N)k>beKjsZDvFb_2+HWEFbeyqW;7M z1%qBf5I5Z7nro@c+nB;eG-KqD)$UPic;A}!??e-|=@>eTuT#QW%|pEDM@&DS9_V)4 zee$=If(G<eUf(iUyZiEGvCm=v$IKLCtFQ+m_|VmmO<GrGfR+VVJ-QBR)@O2_qJ<B~ zawb~gYRD6dwd=ZBTTj-b$axUJZY9HPn0`(nDLj*TtTK{<B1!$h5n}&wY)bN|J75*V z;?=^<3sM?<N}fcQ`2Y&we=$n{U9E}h*;zKj)D*F_DS@(-fmA|6in?oMPO25GCxXM; zI>p(u%bpC|MCR>?n|0x5+Hwy$HkF&s##DmD?%h@;XzEhP2Nm{e5bbK&8oZGQS-l0f zf9Y#~cGVyHFP3E&Kd5xhk0euG*QRjLm#UxYbVxXPT)|Pyxu&EX#!_#S%3!MDzn+@D zexnh_D8v&#t@!b3qV$+mR7Xdsu-cY_JuikwoaSGSRl^U|H}s(NCfmqOwjB644tJog zRERuU<NPsW-puxs%R^d{sd*BtfeR5LJx!mve|iWOjg!3wjLeCtZBUB34Q94nuA~2} z2X`&5^u9}YskSu<5xH1FOmd7VD7+SRDLkSg*Hvg&Z#EDOTN&>Wm#)$nrq=A(hKDWM z<bqZRDlJnmMaNan3q^t&PGlrkuz{`L77`70kP0tcyS^(p&{3^8B04{%L6MUnak+wU zvA@wPoHf*CNt;YbLWHq{Op{C>tj-Kzum9!IQ+c3RTrbZnXZ}iGC868u?EEuVtR+$H zVg-KlR|dx+7OiWbJua$D!F2eaYcgkysi3~y2u*V(PLw{~z45L#4Of{O_sPgn{j8=d zzl@=Ewp}C#Imbrrpk2IvX9Pg%;<yiu-(96`X07OrSgW;@0Wz_Bt@`Z6g&ue7w^4n3 z_ERZ(i|Mqh20<Zx?8_l9wT}}KR|__n@|OGbBUU{VJ_%k&$4scdFPyH+tX3n{?#I7c zkZY+9s;sl#@ZmgW_PVI!mF9i%fw$u)%*gHw7V%qU$eH@);a)4pxuEi*b2^$X0(}{l zWo->3I?ju$;G9`Qj$qobPk9`BXg#Gw*jmHGt-hb)&6Tv=S#ww(_N$?QxWa?Gmf}A- z2MhZ&s=Se{7w#AePQ@~2a;31^ifiWVY$dZJ4k)!smOYd$_KKqf?0K(e@!ryy{>oJL z4aycRw`ZuR9N<e^T0}ZA7_t<bDej7!cPAtLzpF01QmV5|VWiZpG%6GvLe9Z`-5Pro zhzvllqG~K#?M1oM^)VGzjCo4Fem{8)O4qJ^On|;GJHOYo_H)(0-GUV4`!iGAP__gN zQ5rw;d(yI5@|-xJ4xrPG7$4XDJB<H!+i&I#EeEd}GHFz7S~KYAT!6F%4vXyB2$%h7 z|0<SeLl<n^C6PI?R3-cB8+iu5sj<igCbhvWcZQ3(k|p2>?98wlIMt%fxIk-KuU*X5 zUFp~lAxl%aT%oy#7puB4_~%vPn*+nMUJk(Xl~&7is;wjU`ILUbuLcbVZZ<ZqOdrCP zTbUk-{&E*VOQQB%UO_fJ=yR>UlcJ;iyTDYUJ?Hj^u#X4P=a-B^{h)Tqo{>|M6kDax za6-HlokAVY0}Oc4nZJkzWzq~O@u6OtR2rZFJ1v87wIG@n3~U#ZqC!=E2JyPuUmElZ zn4)fNCRpPr{Lv_)GMm~zf>T#fU>M{PM#VUi9mu58ie%?;hCbZ}SF&kw^Y(-o<a~{k zE!&2mPoTfh>Ueu%cx{SNmq`5#Rbf-2e<BiQ)#Q++5^@;tkE+cb=`QDD^vM*J>r0T! z6<ze=Cmcdjh?M!Pxwn!aMz-{=hc8mP*flP+F}tZPBgsFxTJE|i<rqMX)*xnH379QV zASsLx;i}O}6dHJ2@y~*oA0wCCo!;iv9Q;ayE+)YdnsJDax02O;i%%Gr)SUdHylhoc z7~8Zu(<Dwo&|ZeqT4hIT#_FBv;$V6>$~Zj?2ZdwvE{<>q$W1#Ya8@BydY*h?Pq-H* zIlc9)DloxFvN3q!Wxka<fRfHQfw%vACzO>@j2R4mPUXE-uC0p6?}hl_mBbvVQY(qY zuGH?vA}O_*Zcs2DW)STL);CCCj!3l5O3>aSRO1pQ9GM;n5?tG2UBd{Xk%At_kf216 zq9<7GXPI`&TdP>g{}KtV4~nA%6H*Nb^?#`gE|TlLB*RyV1ZS^~opS2%+A4{r?#0{E zbj4JooWycgmU}qRy)WJOs}MI-UVncJuGTV;_)8caf?1Rs)rZvFk4RK<W4-@YKQFV_ zbW&SalpiRh)B$u_cyr7G2-QRFvwsO5VU%seYFZU4l^{q+VK<H?kzJL08pUw~2MNw( z{_K$0n9Up<mhi@?hvI_9q>yIl!RQbrQtl8OjH2cnroO-RHu-1T<LCW|=vR^0SM$+> zRx^}-L+{9_z*b%LuSR&L0I(~O`7l`T1I%!+1H$P7NedGW!AL#~{1Ay@$Y{zRSZ$6% zy=>$jw0aA%nIt^iN(jZ2gaVKjT1cQIi;aQcznNs{=*y#*+7C>+s!6q#Rp*dEsBt$> zrw;~15uDg%!05j9rkY4}2y8cRkJZMNl{!c;#84V!vTK?MpK1~2+9=0MbPKqzxp-=3 zgki(Ov0=*z^SK3wA4j7wx^tdF<YQxXhmV6i8FaV^fuo&PCy?8M@qw(6S8N)>u}@zg z#d~8*9PH~O&Im)EX`iPo7N@4deP2cN<^Sq?+ZfW8dq!jIsp)MmTz*I}^du~FU;FGu zeeFNO!!Hx(&(T`53C4mV9kP}LX!-^P{_27udRQrWYA8c8;Xy!i28;efs?3gKaFk?% z`>5eeiBu3ieu}j!W2;i*no@=Voa&!x;1@Hdr|3uuQ@NN|vZP*t(NbuBP7+rSe{F{~ z(`$lLTO6B9yTac@?=Y~#jv@(=e0|P41x<4?Ae8DnOA4U*Pe|M|lZ}Jpz3xc*A(|P; zRspb6Ds`H1FS~KS)oi{H0$<)RYgS6AlI=2<uvCVGJ7N_3^8K4A$?F8|jrmYn2~8Ya zXQKQKmf&E|kJy(V+hb^_-x8|MU^yvbyX};q2!hA67BL67!J)x&ZsIxX8>ZOlplmk0 z8YI}25Y%hM(`;yFpt?9qrFDxrxL&K<sJUwhaZge3wGts~L{pDCb^kBHw-y9G=f4## z<J0vrSduZ<kGf3|63#$SEcq0*3{Em?{%A>sDhI`qQX6AY)PY|nY+x!c$OxKE2Iw(H zyYs;%skz)l^T@XDqBcrDqO6K?qMtG3ZkO<zUYoa~pTF1@dw(f?7o!$5H1`m$;@e>u z&}MJGs`lzD#3rm!+s*nx@T_*gNas${^R9d!Nsw7b13n@vtgCFlT;7%u9x0jNJvw}U z_4R38XQ&|fLzrIBNLA!t{@1n1aYKl==mOz|w=NrIH^0qSZxCFbc39^?%5lAq+Qi!F zCT5cel)DKLk`n}sxzF!UjTbZk8br?e@mQ78%a%FvY??>NQlfrB`>=2%rh!P!{m5C# zp1sWW9Absn@rzK{J%fZ6nugi(sm7Xia)@}4WYtzMgt7RyWXFnkF$7^Z_IC2Lb74>$ zyxvuZxfOs9xW;EbmABM_SS7(QE7-8OTcFez5q+;0Hgx(wGNxeSPwXviSD$JRwKz6g zaQ5n6{u+%`oW!v}j5stNdm<yl;+)Wn3owy*Z5l7%Z_|@AQMM2VY$?q<4f9>jhO>^O zcTcl|6IyBosxAmVhw*>^6Kx-BNWd{g*2ZITSBH_j$s@Z25Koi%cAYJ}wb}l8HILPO zV0CW2Mu|`QSEbdTUJ{~0YDrcY#@dFJd%DTdyb{~<;hZ}LJ>06XQ%&@UPBlte>i@k; zJf!;~X4j^OqkVu|1C<6fQFcC~o+ABvYPIc(0?UP?uM~hdm*zJylEWUE9f2&xGN(yT zd-6R{#X;EYH*S)A*&-@06I~Q}4`&*>uwv?rX%GI5Iu<oY1;opVw_B+ty0}|N_B+P2 zETZ>o+MW_!iU+IWn?ApjKJ4Ui3^reUtkkapO(Dj=qm-BM&UaO$#LVl$ltm*Cp8}Uv zJ9Z7WXD~_k+JwX9$OZ<hQym~|F%$~tBYOjQC0g^n2`l6_pPmuk<z1mxLeC`B7R$Al z5HjF)k*_wm!PKi<FYSpF^S>SDwS+vRvk5q*?ta^wkEPCv+a|-@E4zua06wEB{?*WM zAa9M@t+ktt2p)%KSby9EY4S6VWkWJ!;ixM2c`+nBr+*18AhDKhN1=+C$`g*gHB{?K zrrf#wpDdOl^U-r{)mWL}Ldt-q$3LFkj!f-o&E@$)A@hYzj^Xd>bL*>+wx(%qo4T2v zt6<GQ{nfviNXwVvx!N8`iEj2WvQ3d;ZFM75{@ISQ9Q`l7I2^m=-z$m&y-EvlgF+<2 zMcrdy54NPPJxh!tf}Ajrx*sltXUQKtRpZmN{1NftZ6^3$rzA<n+dY!%1Np{V@%KHY z)4+V+0b0s?$cMBFAzz%n%c^;ws`h2R3$8TmnlcF7;sk6RZfU+;T3zwZRtY+c_hqR~ z*q<agWhClB_{6)HNS+zCDCp91MfR$U2ey_vs4h?@Au#dUWTUaZ6<gl*?eD4>?fFHA zY?ipN<Sgy&^5)79lC?|MnuEu|-kG{E>Qs*;Ux~kN8VI4G<WFSxpegA1cNe>j+xmgT z>IcEp0c{jfJRPfICbRFR%xdEU#lE(rgA7DBCK*!0zqm#9GTglN{$5x@qTfyJ;lRjA zww*H?u76dR)+rs+vbF%8>H#$B{0kf1JWK3rM<M7I(e=&cA!Y8as$u=CvwBG{WGQSX z>Wq?EYu7+N?U(4@nj8U(@tb?!)+GoLPy<JQoug)}5Roq+0a;FX%79dDIS|0IRGKO3 zHFXFH`uF}jNr&w&R@&@%W#Mg>{}#0KRy)7NmYbvpVQIe`NUHww=IOJE+!Mm1h$}cW zck6InpoB1ALEP%fcjHZXq^Phb$VDg2<v4LK6YJ=J>q#?eCj!10R@MD+`lTJ&yKNdS z3L@c^bq)lTq-A*AHW!K#&-qS}Q2X2Q&w4qlBFT^O0ZU<yO<fc^zV^~6<t)w}&1`-e z60-H<hu8GY?|F$+Y4d8-k(=!q<N)Q3+03nwt~LTX$j+0DbzakPfh$xu2|=<a%wJT~ z(IwSvbGjpW;~~_Uhc8NWXk0jrIE@OarZXKs{Lb;bPZ!Z2Np$rdd}XAmE#4ef_#!uA z8SG2yf}mLMkMW<#MJM_lgsb-6OE8#7#{N!F)aZ;(neDpg$$E}7_In87mf1_~?mg|N zsR~XcY@H~$Oytx=B)I2RVJy%6qE2;LrJK1$?5UFM{v<e_iT&DZuQ~!J-uh;wIWo4J zut}a31qn5~UlQ5X{)i>+q36eiY#DVQ&F;2M!r?oc7a@*L1b$_O{yVL*4~0XUK$De> z3k(We3*viB!}q+kEdS$8A-b|8ZEAS%$7%^qHcff@$skNsB=#LYTl@&Obz=V?0Bt~$ zzfokWcelSNncn?yP`9PLn%WXa2{`+Q?<RbG3B9OY&P{)(_8JFGXoh+)VR*X-mRy(E zKh?je8nFLCM0xNlZxB?0Ub*LYi*qPrI(5}{{w7|yhL8pSD97i0cL#Z(<L8=1)d`2z zF;9TFcMkvnf%E3!!)Fa&y?OTR5hVBzRkwc;Bg)IDapOjU9R0<!Bu*p2hx7i00%s1L zz>66L+WU8GQa^JU(V?3s4}dmP+79BpD0FDVmH^QG>!s=3If4TH`6K7;A2D|1uHN&P z(IdyMPVZfX_s`h6f8_4<!)Xs5G+4R3!Hb9Ur9ia($N_K#4W2!m2gi-uSIXSGap&p| zESQ)m<Hn93LvCEJo;iPq#7)i_^q;mz;>P)#7gX`wc=wWBItLV8KLF(Ztuwav>P5u1 z>(>7UdzKwB0N%*4R%_22G`)OBM=q)x09#kiyv0k4E~B}Btn|HOiCZY(eXRTyZVEs& zzHr#;sYb5&HsYZNCnF1I&tXi7;wb$?$G9%iWS{;Wc2RYy98(T(`mJZwV>s1g&pqZ0 z;?88N{WZ=b+GM3(as>HR7$n+^Gha~mphM0x?EKRgf)}av4?D&Hh}c8KxdNAp8wz!m zJ^esaiBvAh1K2yhh{F$4TPX$^VmQ5XPd3#2Q%*_q0iaMg4bG!rMDNvu3_g856wyE8 zSYnYy`>|KhR|DO1&Ofb4V-bny*wfHIcbGHbJh{~+(;*K&<kvjoG;@hK{qTe1P#yn{ z1IcHav3A#0#Bc-8RfieHUSe8?_0Nfx0wCR5-oWAvInf=(Vx-=9!wEFx*mG4z-LW!{ zJBBHmtFF72L|H$BfFt2*1r_SgI0qSZQ%-{dpouo`@Pku{Vm-4?KihHDmA3K-6jnRL zh=Y|sIQ7#HajwR5qpsw}L+W$U;bf3MzUY%*N8ANg>#dj`R30|?td{JyI|*gbJ(FP* z&Occ$Hs&V(#KV|I@%$rAD^U{skU95Ea!fo80pL|+T-thvKa-7T(4f~`q76UeuDGE< ze(__EDankJ@^bCiQV(rJL3I^6#I$1|UZKWAjx)KODjl+mEr?*b&~O5dH#`3d3Ya;A z-FhlVkZmLoX!`h4&O1yIv?o5;a09@6TB^*DHR1F_pP1Z~S&lzM4NOwV8<q3VC&@rO z-aHLfcbT3*zVr_`htxE4P7%iv%dva%n)Qd{KpHeT;t<n~rNC+RceZ{b$ss!M^s`Pn z<Vbl`q{Tr4or*{bRPI%J!J73y`mpkkJ5065tMSJxr|~?Yq!Oj%0Q}PoB*x04lSY#N z1;8WY#AAI}{TS1Zr7R8AcUNJNQw%%uoHgf+&eUiU=DUvS7CG?1BlbD|?BfeRfE|P` zX&Y3&_7R@Ag(DpJActrQc8_fh#UKEf%-j}c6pCHrViDt8Mkv;eO<4aACid7^$KC-l z0dD9Zbs~p34lxcr`6Xh^u-vc|rLuYauTbZB2g9yXj&`WR9lt?~z;x%0a;QRlKO2=R zU}2-5<w`B^aM#tGHYjrRk1$6fm}7AFK#hz;9_sLg@R(u}bSNYt0p!-E?!l#my)7{q zBt?|=RzCBcP9A}y1>qw0o|u4R5P53I{QmZya-d@pDyfrb=0UN_jRRW7%bF&d0UFV0 z=QZpo#y>!1zOM;Icjw^E{jPGAsd0i;%0d#k%ta1Y9Y{OXQAalZk)4<!FPFSh**H)V z3V)a*Q2L2pEXZ*z#n2^do#9@hTywvEs849E5efu3B9M#(PJRFJkc+fNl?x}*NkfW~ zN4wzXHhavfm%uY-82!e}agf6o(jZ{k$gwsB)(|lebl{%q(GP53;~&?m%N}Fl$S%sG zI-3xORz&!kLmZ=%drIAggae#V9AhQQ!XY|>afxx5BU-qO4E6@q3{%{LhuwnRx7c@< zX@12YV1W+NM#qwVw97fr5azC=Se$oBM<8y}2b6AkFNtySZ!Nh8@cv;We%T`&*2qi< z+vt~n0F;poqZluMaVk4vgkWAl-9{+JjQ^B_VD%8oO#VUD({bq@gE+?F>LDlqn8K3g zz#K)BleNk@6_Wy?*d_r`j%#k^lS9!RIW}3!0}-S+tP1~U%y8nlCJIzq=y=CJsF4k3 zB}tc}HC{dbk&0Brs$2x=<t1YAkIF#Bj!*#rRPGU?ypHD|X1Sj|hz3vH4rR8njV*0u zySMy!Y8?PDheRyWu5a27xV(Z2t6bHOGij}<fcXblbJR;;RKpyG0WLzU!3}_!$s)sD z?`#>P+mlGOPR$J*DR^;@4KfBQ6r%(~XB(!+xwRg{&DCuGF%FKU;x4+C?m0~1ih4v$ zy161Rp-gc(-Abi(&p3zB&U6tBd&3{bsD?97g40$(0~!(bu%dJe5>hb(I{uI@Kjx7Q zGUlwf1m4@;&fyMU>_Z;sh?H*efsA^fx4U9m*gyZw)5(hj4o-z@40{J$+}Q4<8)%J4 zozPK>Nd!2*Cxh@Ix-r4ha(5ouFx0V#t1Ak-A{ID>-kDCqj&+m+w(YI*dWV8xa<qe! zNqdbz0RRrB0jD)?F78480Sj1|Wx=-mM>cAC%+X?6R|jG1Az~%JUP7W744lhO#Ol)O z0JeRn>_#!#Av7ib?UQtg&Wr33J9c@)IagCxt}=3vt5gCS<*JaEYw^F!xrcz{poTJx zbznD^HzCy<jbe#nkbj<skOHA^9}!A1Qg8!eJ9&uX?hxRKCN()o3LNu*sX834nHvXY zSWlNV4sCqsX{NNrI;295+9oC=GQA3HY_b1ayj)ANFVzx`T3OvAs*AHvG7GwUO_Fi& zqZIp))<7I$p2@iJE4i5mw);Uyg3xyvQ@&&0@|fi<_lg|B2*tSzIl#%-V-mHf`9YRR zj(+$JN7&1uh3jUN%6w`%9jW$3f;NtCDN)sqhJ`&iOpc?<LoEQH+CM@JGtSaWyf)7? z*&n0A5&kJf^BL4VLOp7wcLgUKyM!ghL+}@&<2T%8xvXE}k4^UD)~xvl)qXSfams_S zuJSbj|3R;E0A{3yGbTEu;S0cE>NN@x2R=d*uYeB>P4J!S$t6MxaX^iO5eo(_FeVRj zg9FU<7?0@?Kc1M(WFE|w9S+5DA$$M8T2TiXPcI+Q3pvd+x&F>daHBGnbr{@~v?V+z zBAt3&&Dfae%DS{_Os}(59PwL;q%T~}ND^W7N^2iJKmVbS#Q}g~tqAvH`o57dSwe4I zE^Q}v4*!dANk7a)oz#QM;9EQ#M$pO3ocx72e2C7h767OZJg^axFkM6h%~Vu{DgD~i zoeE-66uD5JS)c>Vc%MEHPuZy;WSm_KHN>YiiZ+}B8-XB4REH_V0#p3jRa^rx>{bc# z-9BwZ3G&8ksm^uv$aMvu#a)G~n9g>wLO1LKV1!JvT?IdQM`0Y(YnX@I)KJSc#<dw4 z{P{yUSi+on8vw9gl$3;61jGN%4H?622$BF2<V3_(Ez>0#5Bs^vh3LmhnTS=q+8vqF zi<r_`Ku?dD1@Z`-^SO#nj0R_2M~tM~91_eqfChMp*X1;bHDE(bFkS??kv)uI=|#yV z=pRDapC0`KDO`g^a0xmb0yxkK$Ryij$iyI+5FznH^gx1v9n}Jk#yRxEg@ndRQH=VS z#l2kMMF<TsT!W-=$ke3>sihA0-9_OgnqL5b#>LADf+J&`T{(1Gek{v5bVJM37^$6( z+$F^&%!A!AP&Jf=G_hQ)4a`cx1JT4v`yin!5Zv)(glbXa+HDuTu#-+C8&mMlcL0!U zV3jp^p<sOx7*do;l!O0~;R8H8&E8nT_1zK0tYJCCmChL$K3ZH!I8LV>4NlaI^cWcX z?F#$F#3kecWvo=79g3_Z6=GdQJitS%3C%!^;L*q-j$F%Bz!Enh$t1$!QP$tZ{X;e2 z7$;)e!W_iYj9gTa9{Y_6e#A~=tRgo3gC)dC_te!n+yOY)4N-83OiaRL@ZvwX!X?C{ z^+b`htkyq#NF1FK&x}qDHe*Ccg{M5jZV`l=z>;(@BQ~M~)rf;PBqqiI&#fR^IAZ1i z*~5W#f-(#eP;|z#FwC~dOJ`JFKR6%wposLTq5^J&RQN+x%mW8fj5C<Z!U&{11kFES z0;IviYN3O7xWoVO%wQ$%psldN6oN)UG?_%AQw8GVK8fNyz{C5U90vUdejybGJq%ic zTqx`ua~vLys8B<c+2N>2wAAHh(jKp5Wjx*kBoQW{sRDD12#`pQSP13OB+a8OVlD*@ z0Q6>NmB?#!1CWu!42~z*Xhc&?WmR&?+^mP_xu1CzAjAAaH<XEXilw%=T;QO>S#rta zm;<ap1P9fLKfptoRbx)rLoC?k<@8lW+1o#~mQxW#Sdh|hKt*GMQe)g5jQq@N1lzyW zAXk(IWCF)#_R=*N+e2n%X2w+~&>YG*1j~p+_k3Pg7z|9p!`>8TF+?L2agfNIjwvP4 z=rB+(!UF#$SfBAUBJ}ttM4-b^vBEnTm2u7{Ie?u$+)7s3gD29~kw#}Q@)Ie}4VIwa z8geMhQB3}YMqSy%Avl8xrOd7{UOj|JCltsF0V*<F0s!RL9%kihfa<B_sEZT>WogL} z(#b!x8ix%QZ$g?;g5-t-%{=($G;P<7CFFue#`sl?FKA(e;zL1%iM6>A8YR#IWeHL+ zYKOX<1#$#eUCd$K16y^1StRQn2}Cf>B3@)fF9t&|{OOD?;9uCNUA_Zjp#v#N6GcfU zQ4kzA_~38o=4-f0aKIhG<Y#ke!%Fl60Nt2@U0Rf`pvo{(C!~U0;?Ouil9u+XtDb~5 zXoCN|)lFE`6jodxwUVY?6y`G==8pgXo7U<-V2iFi1@&=-oxa0LDBYSs+f}%O<EaBC z0>wYf4Jgv!7YXK%DhGL(2f#Q)LCr&02BAFs10}>m_0&}hfmGTkhq|#*EN;Rvkb|aX zk4>V7$k`CI2^Bfi<!g0|i@Z)?)<xLphFFlrf1;*;wh!`<$Ut!2)dfi}QRS~97D90a zVll-#xC1L#CYQuVX(cP%xKY*)ElJwiKhOd*tQ?R`>nHsKH=xyf_{nQMgd8G<IrPIU zHpO4GT{DmxREna^?j>NQORP+V$adXJ`KX5~$4a>fG4vyARF|+ZraQUM6g`?ZxWoUk z*;p+Yi+GqW!sgO@h=npt!kEoNVbI+<tfO|wEX|BVUOfvxTt%R*6`6)%@gT;vqzyYn zAHux`EWFA|#H`9DMp{Ug*X@rwPy;$}lN|2gJIsqdh@I}~?3HNB{~qsb)&n>Ei={L! zF9ZXCJO+OVPDPBUxqT+ECdXuuLn?Ga1apq@)zD00l0Vo(FZ?2CBve0CODAE)?AFEi zti#AgM-#pZ_aTptoI{UD1wR~{<5dFz$)v7qg^&G%#sN@2{mUqxs5siw&@zx=y-6^n ziemsUo7e{QT*JeV<l)RiTLn`QJJ7fGL&u2MYFP+~U=s4=Y%g5G!2X&z{Dc23utQWF z#X$XUWa!8~w!=7h!->HU!hK$*^sds>NYesFJXu;hAul)zM1vUGA;@Js+zKQ>ZjJry zM!f@GSrSKH1#hel$0Aj9_H9-;pNo`lNab$1h!c(|3u;OhK@99a)Iu$(2p=QHrBE6* zki%1<#lO($#Nv^%zQ@q!1p3iJMX1{z@xp7NXY6@eLwu3Nafv+y(k|}Ff#KE|voD4G zkF(6%YpgK-aI9CXEjp~jI#^1&JY4XWvM|yKIZ%yMq?2{%gE18+x>A#=ZG>S+;@~2L zFVhDKeMP^dk&B82DV$|gj%9}a$318aN+cMjaBd32CB_g?Ut-SjLWcjKbOt(HPGMGs z5Wy~4nW+PHN>!A|`=ruw=(4grgwi-sJRBQ82=3V&SRsQW$$*2oS!ujok~MNfhcuYw z)Yv8aAlfGF$C3!j>7+D`azDap#@GYZ)K0l%qB``0gQP5Cs4LlwgF9RWk}ZTXSL7~> z9vY?53(f~6&=%i@jFfa$g5K9duY?wJFfPsnJWNLQ+?!8K@2;o}&4lJSWb8e(Ej;LS z+=WwYq?Wm$SV|v_Uau`%q!J4WZ*pp3MVj(XZ<fuT1C^}JdAKN5!!oongqNsLS}YWc zA=Owa?Iu)2o$S>tdMdqbF|?%um|+}2a6`UP^CabjKja|;ZSViaw$CbxVp!ZmGy%sH z<pR@`!|iAbx!i*{h=X1{1Yq1lDYyenOR!8IPkHK|BBKmvtb#GE(b8>H4qZY$@Q@}w zLnbeFnabLx4b5uC-?{7*uVoHvv<oa;!y7Xfz3@Y$0${141Mu*JRv+;~>{TQKt>_^{ zmwd_0lw~TaqLctbEvyAPR0s2H<{FV|g9y(c?87+_(mXVSCSY7{YZ@j!EH=-FSX9L_ zlDFD!Z!xR|L3o2U)JRC3bHmZe6gh|2JcK)-f&pz2rUo6QWdo|(Q^F8!xAGH0q>*ae z!&kDQCCXahe8Otu<XXPA6F(3Dw3U=lj5Nf8J#-I6M+X02LxQ|@;3j4DVAJ!0=g9pi z-*LN(?!q};lnblq1zOm%FI+dyX18`5kH$=DM77y6{lsWCcTR|^X$G%gw{892YTrpt zOl<6bt2A^-hc4mNPuU2xT!*MCq_U<e*_h2$_zTg3V4*4?FE@BsXGw-W46a6uH2eo& zWO$WwIIm=c@<3FI00jVilsQxHee*+MR8Fi=Cp;w4tC2)kcn%Qt14qt-H#mb6RmP6f z=vq*XHe8)Q*y-~YIS*@ux>g$C#-l=<*TOjY$kkN^&3ZXxC)L^?mWNwHD-t@Co+xGn zUp$VKti?Z|Mpla!&AezZ%<Mk|T0gkMQhm+5GRFVUt?*h*b*|M8yqq)}?KwFFn?Ll! zQ2Bz62MD37;9v9uMwO^&6iPf?&XH=wXjB+TQKvr?Lp`zvRIVaUux&l!v2iH%@kkLB zH3$|4Pvo(Y*Je#t`$9Kp?-45y11Wf8GB^d%jcELXGH4K5X9UWYiN0g)vvI{z2Trh0 zN5mvUGlVX;E6JQBJH(cGSkQ624h&-j+BsM<IY5`jqq$>foj2qHQ0))dxI<dKday=3 z^o)@$>BQPh$T<~HKTnW7BuoJ!#Wm0ofV;P>Q4B5c0>1-NC`7OvW@>`~%R8)4Fjx*r zex7bW?>Nw1KR^q`8^cuZ@mGVP*XoXo$OixG<W%iY*0wmD*uF|`-I%dxzRBm3bmfc} zn}eIcsHj4Pi&YtL*_Op>gPFTHJ8&3MNLteo7oWw}d!+~fxDHkfN8o$IFqyWZw3k59 z2sBK_J9x(?URiVDKLB8&<4J=v0Yp7)-0;l<@b8~Lg$o%1@CN{5M2Qd)B9!+J8#a66 z;{D@=>R&l|6G=k!cd;C$fAIRv`!@-kJ$ndC)-0(oV#t4?j+r~>@7=gd4h>fPXVWIl zga76QjTP%3KbPH}k+XUfAx?)2|J}1%&RDp2R=qiM292dsq-%5bBL|KXw0Qo=%~O|c z9=fa#w<6Wb5U0O!<o5Y;$B!vKWcdH^A?(+W;?bNHU0TET&tAEIv}pZ{$JQiZ(SSco zBeilIfMtj5)vIR|sq1-n!1-$}wAna$4=aLBdX%5Nr}jpc1CVZ==eh?Ujs{%QD7ky< zjM+;I&6PKA_bNI!dhQ=ASpUd%ROd_QWZ&!AxA%STp5{=Y{+S#1&s49&=+MEJ_aDIj z{F7&#elBUoo_nk_rX8!$@dv(|0-O*)`1s=wo`2SP#vXFefd`tnym^d2_ei=2fXB!Y zCob9aL2sOK<}s)w{$?acMqj!aiyVBg2?rkl=8=g)3fY1WK9|C|tR9z=;pLvsKobyv zO~k>>r8{s;a2^y*j3~g4j+y^t9vOpr1c09aK+?-EZ7j2yOX?xVoPU6MhCB~XD)K)S zz4_-EJk6QM8&{wa#~}V9{4ydHo#DhAc<iZ@8hyHC)4l&7(o~*v&e^9FrsnYnA8TCG z3!Ma!lnB1ZT*?SD&06WqxGDMMv!i8BgXcbJCh^BLAr~cSM%V6{<d}Y}8|M*meln;{ zM&BGq8%Q|f=e}o>gJ;uQjV!5Ex5#Oy7?#NSCqxJP;m=$C;z36|tMZ~In}5z>6yJQ= zgKs8q4ykXPdoGEkB}MNE5P%Br;qN|3awEqda;@^PpJBlSuv-e*{7)}-s*6Xa5XB+q zF^k=^5S_;W@Fp&J;JN>YmwIEIkyS5C1R%zLe93089<jlvo_H?xR?~z>0vE}7`pIac zj!<DnGF#CB02OHf$k3ca$dPGkiHc@Vz=i)g=8%5Mk*ZppXEaz}h+>39o2#m+&Kruo zt(Y8d{CTFDIp@JnyOLLxHf66^hUPIDS<&Ymc?Qh1$TZzC>>WwNv8FW|*Bl%o{#^a% zaxVWtB^l3rBbvgFxcTHC*Z%1wl-8QOl%)TPeeIY|T&`yvNV*X+FLb^(aZz-{c_g)Y zI(mj3&jv(&c!=0kaU67t=_XHDFyZGMgWLTuJXoxHM`wNh>ALOo)t9K>J3_kez<%U0 zn9cf8L`Snr^dtY7+;Zwp@ksWIko|B3k7BgrI*=j<0NVy12<0s<0BF+Aa5N5oXzpU2 zLr2cK;foFS$QtFCod8J~Eu<(3b4~gOCB(5WFSUXf|LE1fBxOQ<-HU8TF-V-SwKnwS z>pz}Co>kzXt%((Gfc0Bb-sBM|d!Yjwm52w)Ak#MfK&WnU+1fk&;S0u{BYKP~+T^Ms zLxEVMB_=D0Oonv1dJt!HEnH6tOQ;ts@va|}xW<s0w3ge&BNU&Q#~ZbAi5Oi_jbHi? zj^K6<a=@b<#DIrY?oqMLk<d5PE5`xdf-YFROMsU|lIPIH39Go{AB(eB7}wWI6WL=P z{<7CN?D78yZ8V8pL`zslf^mtEpu=O1T;O_8=O=im0)giek0T$nzKZ?HP~(6HI%pxY zx?oTu20O=nuE7eyj3adRhzIl#ww5IQLou$YlOx1YMOzuC6~Sm7Izmy4N7kcT`kGN| z{&5I!qzVAdKvVJ(X`&gyPaBSe2Qj)KE~636D)#VLhsc2)tMEmADk6uWQpFE_u)-ZP z!={PKiH=&xOd!~hUqL0}s(zH}O_XTP>BtEn&D`;ghmgi2?ZKAYjja>$sK-6xB*PgU zO?~it7$j8zkGfS7b?nKTJ&aL}jgTW3&hQL5Jy%gv(y4ssbLChWb-Q^Sq8m7>hb`eT zH0b|vCr<OY(ldaOr(xO(b$N3KF_IY`O#DM{7;T$IIWZo1xPuk@2#SnGszLZ%^hF`< zM>yp%kD7ueN$_yveZ*mja%hDu|LF)bS^)rY*dr93I10Cnrq4mTW)R?T2R>bKiGDDa zr6!V*DVB;%x-1ZSSE)x+>tq)4tglro`$u7A=uuY4kg=__AO*)EkZ`<aQ3Z9CJ=_?y ze^_EJ#Jns3I`Ro|@Xj8c=!QAi*w~2BtRC_pTRk$=3`huuX6ifWKQ0jrM*^T7&nSn3 zpvN9h^#d5|7{|!8_)u>Fz;pHpk#_#kj>LK@zhu?$deDn3-f;tN{NRgoM02h<#pC}^ z##l$*&b6M=Y(*<qp{q`uF`nh9g;7}{RCu7Vz<qd=ds7o^O+4ijRboUVJ>?CF8v@#r z&;*^<xb8o$(V20A&9tBB$53lg3(P24UrI3+T7y!L{>li)>4Tps>H`l3<!LY8VG94s zRi}8JD{A>tNLBzK9<_DjxieFrLbmCVY}ltB)&Sa&e}fPo0qGyz*u++m>K7(A*&iLD zMd|F}FGR_NEehH0Ax?`9SD0cW32}11%7mX@l%r0-=$ko)iRl-EMsCCaEIG8;9~hJP zd|eS)U9tfq@N5{_K7Fk{25}5vHNzCzkc#vUb}NXu#J*GITb^=TG}JvLZyNuqO5I#B zo=fF6fQq`UUvc*1ckm;ZNP&;1Q0c{k{HPxNsdj+_s62dx1JcT1U9E`u4{>bb9{E1R zF<Ljf^xY1%vBL*B^tYcM;%ia&i3KvO!VX>YgOdB65Sxhjk76`0eB`Mly4O?kba^8l zJA-b*^cA3SoWr?`MaGoZ)bDvb8XxvZhLyz|Rio)e86c_0eA(M18+I!~9kPd(hI$E( z<M!$8S(J$%p=~@pRet<tOGK-|A?;|fin)v&e`Hc9XLw^CABFD4lU?`szIGm+I7T_} z@sy|p?|CEll0Rf<inlMcc@D~Y#-N9{?F1@sha(5brL%a<Mhh|)1;GD{qN4UnlZ4*) zII?Bz(KXNWi7f`3k&k}%4{5X_B<;CKXI(ROTFWMQ_<ED;j`0a|;A0$`Xa-Ymrmvgb zr?%jsj&(xLCz3xBP%Gv&G-Px?y1OZ5UL}V%QmGI7SkS%f$>m_)f!H#QL(zS#_Keh+ zByw1{F|{y-KQu$rn$GVZ!GQhJ4^fY%=S4z}MkdY$Ss(%uoZ%iG;zINVW%8mIx{mv7 zAvx5Aobm~2h{)sG!5aYQGZe+a0t980g&b<k8_b~^ssTst%I;S1+FomHCZQg*0U4me zha#j%7NseeB{$kZ6;>kTkmCLphLR#l0}BNj&Y|@54dbGvr=tI8fwF-bq5{IoiO9}@ zeCUNdq^$Hbr~++5^#%#x@Btm-$#lS`ysn{1?%?*~Yksb8J$4UwCSfD+!IthJ_pInb zhNM~?X&rQJk}A*nkc5b+iXFtk2rKDA+|WJPE*>WAPkiATf}%V=&qT&=^4#s;ex~#W zg#BzNNzfq^8{<jN$MU@9Xddk7T<<jgAr<Ju98e|z*=|z&Arw;KC=LW2f~WWxr2+pz z8y*3$7Al!MMC4GBl{Tm3_-X?o<uID>1{Wq}?7<sy0T!U4i@Kpq?u7-n@u$FH5Z<AX znBg2cG4MbzX@Y{cyn$Te;ScRExOnP-Hn1AwVO^9Eh}!?q9?k)9(1Bjw;T=4M<qirR zI1e5cBWN~8>}(=Qer`#E?h~-*WHf^mf&l==q&@(kry9r(`6whv%^rSH+U_uYY@{E4 z@jf=h2Zt%Ipif)I!5b<8aguO-B8+85=EoGvQ^Ka^2*e8gVR16C9?F4sCc<JCk}(v` zA7}w0ZH4ioN`^L}PV}yIGE5;AWKvj>KExr~auK<pQF#i98^)o3D5@!~4c8vYfZ72X zI1s{o&DuPtAIic|x-X;xW*b@1ti}W$szn^YuN)%>0QkWvV!<0cE+yR&6(cGwM=(3e zp&n;4Wg4+%=tVGh@r266E_`7g+F>zZiAWMs-ZuZT9uxx~`oR*oA<s@nBB3UCjH<QT zCP3KBpWuNTOrd&25)YN8TJnu~l*Saj1wL59FgGeDEi+#{rxCM*96svZ_Jk4@31j|& z8q@)tex?&!uqKSMA<=;n%AuLSM(i|$62PIKj^X{NGBnMhA6k*h;O5<oa|v@$6LLW; z%jFO6&o@f$<h%hEa-js<QkUTJ?4V&Dyl9)oG5qdwtYqRJ+~E+~fmve24&%%@Bmz!M z0Ug$1Thh!X0)xq}Z6*GJ7}#M1<Ki=1B0)_g(`vGdEJe5e;YIAhNARH|ROZ(z6f|f; z9*$BBTj5Hc(=R%L7ho?HCP9XngVFFsA=LlVpUUAWbYm&j2O;KxAH3lbtm@>hLNY3p zEAoULis2l(0Tbk+A2<|WvI51Z(HmYwD!O9T7$q<!$rq?I9Il}tQnS&1Zbqx*N?sE* zE^Q$qq9ZJ!PLQQ_*aIQxaZLEZ8Ei?!4nj(gA}AbY9;l-q+KMS|l*D`^Q8i>8%E1-h z&K&q5G&a>S0E=bT6r_R-PZc!TXldc-P(t16djxYFa$yzvL0fobR1niFF~n2((;4&x zJ_#q&LIfND0Hjjmf_&qkJ_V%O!8&PGmoBeZN(CRf0rnKpCjKMRCXGFXa#PYLHebRP z`wNVQawKyRTP}ea?18Ta>^qA|TnztH8Vp5JiuFrcr9+${JBp3?xD|4Q<UX<?8x#Xb zt`jt7L{g-zv)nXEyH)Huf)u3TtiS>Hob|Qd;SK=686W{421Q?q#|~*N7}#t>T*fNO z67@hsMb2UQLKSi95f#HlJF+9P2+mbk5I!`+pNdK)Pw^Qcf*;~x9GXEB>On){!5qFb zv_|3`r%79CvOG2iGUXvnkHH=i>yT3P?qXzexM4e~)hsWMyzWEFu3;0*hUF~qTVKN2 zSSx)7L?$$&72Sciunsbt!W&E>9LS|XAO@pu#esf{T*QGJFu@zjK_=D5a{yojF@YSW z6PLQCZP!94<IWevLCOk3UCsaL9_mEOnt>KFBVtR!+p3kkJfaq|rn($%VPDG}I@T4E z!7n-II86`4$U#Hh0UrMA1Iu<T9tdXFp&ksy8@NVz%rac8!cacSA6^l6cNW>sA&-s$ z+W14PB7%+}0y1t6WKV921olMeC|dNQ4|#1^?cp)i2SpTO1YrRjxEB007HmtQ9vV_8 zWx{+>q!de{G63#0%;99Xqq8m+WG>e|2)GsF!4yV@=32={uq76NAsmchiYSJAF{zT= zVnmFA8>9giBBgPi=^k#@8?X>J8E{ql;iIs1;=Gn5^g_{qffUTfOslegBSJ5LffvZZ zeKIz7UBe#^p>NR;k^cWz{BkibxZx7^DmmUo-*(u=AQza5p-`r(in^DF(E*h(0T%Qj z3U!uxlg&b2Fc)mAag7cl&gBuBfv>E>M!_=>;dflHI6Fq9Vw8Aal%*_S;TT{fx?=Z` ze1RRt_AgPf-~K_$aG|cG*FCt!O8kkv;!VG3WK5U^M{;pw3;3Y4VHL1}7*1GEF6LIK z$K;$L7r;S}JK01Y<Lta48}tF*EN~}-2u4{!T15ywL4$^|;Tr1dvt(~#^RE`bfj)#- z*=ny7T!9msA!t@OU*LluKu#Mr0Ur*C)+&i*0h28>id@nqXcc*LI-(lqG&Rb&?$|_V z#>DT25_J~xTrU4191cj1-3fDrwq@~VT!_J<V6J`F6_&N(7&w6%He!%{BWKF49e^(v z6WN=s70FiN8oB~J`9mU=Ar!#jQpu5zf$(Tt=MbDh6R1UD=XN8v?~R|qAHc4g1H@1I z!5I9Nl}UtrA?IeH!58*H(2lWyg(OW1<8sP`+TKHKmIN0{=NuF`cw4qux*@fW0UnfD zV*e-<OaTDGAz*^Xr{`#Jl6Ms@IB-)Ybz9b`ts;^_MCJG*p1mX<?m;}}lw{P|jFBWm z+_@JJVqw|@IFZD92j&?9_j1b`FrTTPuOS)o#-^DXDRN0WV8IorVS^I7D&6Kj=7t?& z1eP90btV6LNmfA`m}0OiYmoA;7CHf2+RCyV=c6SSB5LmrV4)IDMTWI5rMm$aaDhZu z)|3Trl&*puNP!u8Y~@-z^_I78j^P-V6?nQDJP+zVe8C!UMn-@%I~QiMtYH(dXL|G5 z=x!$zCZQGvNwqcBHQ?c@IpLP<@NsfCNmgbYLfIJhA#W7I=$w0l(V7^<105>wrC-xs z&;=8`$Q;VSxar!U2C35y;Sr!=CI+{&&jlMEp{{rva=yiTJ@_At!4zO&9z4Wq-8TVS znjCV+`(lI~th*!%tr~10v+H3TUwT4Z$R$ceDKphXaOV(U@Vt82wOnTsGyxX)0d~pC z8^-@Z7Dgc)DDO8TT3*<}5l~Q%H>`S~p%XMSMyR}cSm7DMVIzRLJyK;!EMX~$`MY1M z6D9!#>5Dxe?idE46R4$G$I2iE0~sE{81f`#WL(8<LdG;9Zd6csBVwAO$cxb79Ha!n zk!{QxoPW3U(jwzetRWNdL`!|c*5pjaETL|sqgC4mA++Po-QmMk&^NYe9`->M*ukNf z0#HvEI+#L6r-2e)!zDhQB=)Rz-~k-&pc7;VQpbvjQ-Kb0;gKREQXyhQtYH+o0bB5_ zRBx?~(b^Hh!5sdiH`<0F5TdQ1LCs}I$lg>*{h`om;TeF>f?%B_rc_3eff7pd*4_UD zP$MH~LV-4j{55cWjqD+MyMPlmg5QHZeWC+&1i|d^>@PNTJrE+?o`HoZ4AOBFOxo_s zapc$*eXJI;_T*p?yuo#r7ov3%a>*eaMxnw>8Lz5UqvBy52EoCh5mVIXKL(@MNj)d~ zJj8Dfl|~`6Il`^F*^}V`A8<hs{LjDJ!!^Lc3K$OeVjf>?XW3HW3!uRqrpX>z_`M@V z7BXQU+<~_tdO#kF9Lk{`1fd#Sk{(@|Q9uL$vY~>G3g>AGy7?g+MgiR~2*2569?k(D zWI-1EhN-)-SO6dtte`$Jr?w%2LCv8HJbb8rewynC+xXzRXl;(0dd5LlqwN2L73M@b zs;FkY<f=HK5XxkP4jki;yEVwc4>aNZ8kdS8!z${55Hi~;w9%_eXd?JyMFb&mH%wFR zq1OWzJi!(nYJW7BLzFP7J=o~|a3K>0V@NX6yz4>f!QuVzDe>3icKRU{#(;#?KFozD zE~zRLs@}pcY5Ajti27j@R;-n8I`{8kn;@c$Vg$b-=aBXx6Ce~I0HBixprFBn2o267 zS8o-idgaI^oH+5G#fum%7MwS)9)M6*{+X+1k0M2M=<Jmw*98_ocqmQEoOy6wKYV=f z)#G>&BY=!FDUu`iubQf%<j^6^c=4b-dFaORt7Yk3J&!@NYTe3Jrp5nx=E!kEMGl@n ze+HkbT}#m5*`f7DwW~L@YeBYbd)^}_PLnr#{bJgs$#LAgW4`9SL-};;xpD6P*<x33 z9DsQV@iw+Qube$xt^Qr^%JC{WIp9X_#5~v}N0tA;xe;d%ZR?=@hO#Sm4_;WOnl~Tx z+=|;j)*5dwy;tyYJXYY|jXNh?`Q5ev$k}UW3*X?c9dXGrJTG}yya_qN`{(LVJ##9% zz8yCR*1vdyttXt1Zxp-Z5+M{^bu^*WPe0yxQwcQi*pnXs!PPX+WApfO3_R0~rr(Af z8e|blios)wCg;TC4`cFJG+<i?lH(0Ls<Z>oQ0VkS(`G9^rK0~lD!Hf$G~@)PREH4C zQy2i*_+rjG=TL{;OyH3ui#6`dgVK)Ip~ux%@U4OiUF9*S)obv~Q%Gv|?3C7%w}Cie zH-Tt_*_C2ihmk*f{j*zHL+zMjiuWAo4LOzAmm4|e5or%(rGSIZMQpaFBXjp~gbzNl z;A0MEO$EheKdY=FQkYxeI3Pym_>;;VBB|t)Nv4kT&m*y1_F#t=4b@I2`qc9eqGJ9@ zU_}?T*w<e|W;x(S6B<TJHs*{&UZO-+YZprP%s9v(|1=oSnnh|>&^_o3g%2U&(3Mo3 zK?w`!Yvd@x&5Zt(CmNAQ9#hItuCnV@rSsr}4l&OtM(6*ZU2$2@BeHlzDp%`)lY}_& z#Aj_x{E*|y7|`_N;E>f0<xW4cj8fUA$^B`Op#N-QOSgUcD=DBc*<;Qf&UgdB$JQEj z=_vZx(-yTRafy#2$Y}cTdE)+bk4onJGf5KvShn;`PqhfZ7_exE4r|q-loUIJ=){qq z%WnDMKh7lb&w(kY&8)Qkbm9v+<E%z>&wS5>5<J@a@gh8NuUHUD{QMJ6CcxMXHdlrV z^ff=;XhR7*3-M%Ihkvto$T&gvvp2Dpjzcgx{5%->Rz_3OFgpK?PLW!NSs~4RYK5&7 zKjY-m#W7{^WUa^msFH~{(*`Ry0D^k+i7k8v*z^B-`rHA|i#!wgl{`NO4JhmPh*S^K z_`Gv<R;%x9v($G)Td#cn4AsRS{lp`?axM154&z{Ags@gCvj;hx;UBLJ>3;=*jV3x# zmNGrAZxHkwI`~03Q^>&^6%)+=hVqVotb-8E7)Ly;1hRJJ=x`~4hc}#|3U<V=Ug5i6 zspQe5Dor930=&oOJOwa(jN=)`_($p<rMw8KZ65!?2PLc_u=ByHEwDSr9cuB9a>&d& zPr+F44&jP-z{H8x8OnM}rj2pDLqIuN8G^iFi<kLEdit4^ddQKDN#v|SbiyK_z=Mx) zu)>AF0$*uXfsAk*M}}xTVFCpxwL`RH9BBVRq#WlVtv_(<9ch|Jq`t#0?W|)IU;0|% z6j`7e#bbq=s760#6d(iwfF%1kL@*dqk6T6XmI?XCasHtVO&mf_060!T&O*#$60;z> ze8)Z3!MF_R5`M-!W-#9d4`{&R8P5pb0f|(@f3PAI&F}_4ka#beJTqY7U<WJU;k0r_ zGn%CN2RAl>jd0lGiZeOOIsTD~NuZ*NJM54y{c%cDOd=KNz)H_J=ni72LK}ZU$UDzs zkY~yxLA3aUJKRwhzF8(4wSWcohVo1z)vJ%spvHR!BM*7DqMr9GX;vr-Pian5B!{Sl zGDKpRdex&Do!}OHN@6V}M#dP%xP<=*6L+tPQj{ytM36K7SdS43)2Y&oojv}s4_3GW zNYlinSY`5$TwG!j$M}amIASU-p|E1lSO+BJM8X-0YcmG&hc($@jObPCDNTBZJ365b zSU@8lL(EE)(n$<*Sm_*fa;0MbA&yO0BVG8E2}jBSfP>QF9_0wAev(7MULNBQ@W3Qd zLx#F`Oeq+K;Ro7`XdtPw!xl2?sP4W+SWb8&B^(i+9+}lgzM8`vgF)goECJKZK9Q6g z>BkLuF{-VANII8D1!~=q$>EWMyT!o9CA0y6#D;5mrBn$tFtH9}s6=(A0+_7y;R{&U z=YeC*Z$aYGk6vUq6^jz?dA0w9l8O-nACJ(+2yH2o{~72X(BMQn8p}#V&hRn+=teET z;R+1$Lm-N+)JVe74r6o!lWJ0y5w{YLe@G)3^{hvyLM$t^ZbBUYILjuL<0gDu0vvKs z%vFXJM#r|J80@%&H{3DAwG0?L9H}2PT+xmg#Y4B;Jcm2p(WtNTm&h~wN)oZ54qwm( zOInHAHC7Q0Y^>G7Yf4|XGJMcvlmx#r0TDmyaf!}eqg(cf$BsEEGJ6ms9GWPjc_k}B z^;Uu%#OM}$wX_*XW+NMhUC6kctKXj4gCC}F#W5yPH32`FEd~BZ3+LJo^P+EAP^=Mz zD^ZRZ9ja%K@kcd$u@C=F92P1i{1;g8femrcA{$kMq$UjqW|@@ZAGBZwHn5T6t*8Vu zhXBVXy77<PY40BA06;TvK@L{IXD5Sh4N19i=u3#h98FdvN8(Y<N|d-8*@0t+ro&NI zxZ|rLWUz9+;*W4lqpSYlN0YkpY+3-L&DGY*|4QSlRBYH1)zylgwE+om{Gl3U5gMLb zlPe>u0v~flod%&>O3_7lPxvWe`ea3oY*<s6ogQmRw`vM)q#_hmi`_x6x)JUCqZsYD zL<n12&Y)m*bGmFXEHD88WBi$<O~1`R<42Th+|AeW5UorO#F20y!yd<$j;!1=Q2;!3 zE6*lHGVo!IS|a~5>n2H4YzDy(OVB3AVds!V!;OqfkYf_5A<5f0MACIUqaBdI;7xPv zRJZH$DG_c5FrM)%qL|bl6xs(h$bkt=<Oc8h@t8mCVQ_M=VjsMdh}cc?>`!n58`coo z<+Vantm^VA_6S8M;$ew?q<bO*<=!gBF$rlfq&Bl3j4nxfjbhm260U$vQ=h&SUH0Q2 z_MLD_9@O@*Qt}_!P{)*im2>@~<k^qt1vn0I$VWMCMJ3O$^)C^NuL&GD?lMgA1Ag{F z48{>N8}bx|AuF{|3-7QXEuwFEw^m6s4d!rc$#ypPz-a#hJE$NH26rEDMsfcjMgL$4 z%}^%(;BEi6ktjo93YQ=?R0IzZH*kS+DCF=AbC+^MG+SyxDU#D55mppIG$;qsA%G<- zyY>&9kPDqBfi2h+_J9r3;7$6VcJISOwRa5=M--^{T=7MMwGayZP<-bAMib#C+VBYV z&<UOJ4_Bdq8<KzA;9jl}gPav-EN2p(V_)Q8fQRCPPG%4&(LuhT571Bv67eeS2SF$i zHA-g>gRl?Jw`sv)5pUrQ`eO@x77G%QM_~9r5m<U2#CbF_W6JRq(o!MUFb`jKggkU@ ztTzqh&<(!e4yza@?$T@?5<`|y58+@9|3E~DM1tTj3H1OBxX^8}b9^C&5&Lury-*L6 zKt=!cz)nQcBHnNh#y};H;0)++A_sITlJk8-xOw&<4oP7n9HNR!=nLS72?E4c&Impg zQ%~Ns57FWzG?5YifC}A!56Ey8mBNS<(N>xfCH2q`p^zF60Xve^7V}^aYiJM7FbR8B z50hdi7cmt6;CTHI3!Z2hdWc?mh7MAP36il6ND+>wHYuuj4uZuB<}h{jV~~wlE#NT@ z;s6QZKn|ay8iM$PI&=?%QV#3DiFYVO|CdOLBsxQZ3HDJ9kwzozn1J%YliqX;_P`1D z5py9nk!{9R{+5gXGl=FS4whgKbayFoI1?0i54CU%<^T+<Kn~`>f>F3>K>`WQ5Pbh{ zIArw*K;@zx&u|U>;FrgNBKWr#Wq}Tf_z%}$47uSAi>F7@@(;dH4SH1xHbReZb|dl- zHOSy*AeC$z7-E#Q3GmRCwS<NMC@dt{KL4-^%rK0v_7w1e4UphshmcSjIdX$BAAeX4 z|IiD)8E!AxG*Ch=DESXkDH-gbLWqJE@uiC2#bprYTkF`AImu&RLrKk`RP`_j;Ls6R zfiUso4Mov7{uK}8;hoEw7tC`gzNROUmLPD$Y0bG7(!vkE&<_4!U%vv2{~~6%hYnqZ zi=YE2k;99*R1TYP55&d|`0$pRg`W3-R^yNiqCyTUNDvU(oEp&^{Sbe#aR~ouvKpHf zg(b%wB%ySMaWLd)Amm_QTSW|ygeaoJpQ7oG{@@GZ0GXWdD;vonsWxr@Kwr`_4kLOH z8MX;Ylr;FDOA)DJY{48PcnI9K33lc*{U~4LAd=&7ku=DnU`ld2<PQmA5618x9A^%Y zB{>|JhBb0}zLtZg$fHB)pJ%8Ktnd!r@Kx9&pWn$zh0zR;aG{}KjjQ1<kI@g4!Ap-I zEgJHp!txe`0uAFZVd|no9a0$gpbyj#OjBp1gDGag_z&*zdU#VWbvhF*b`7CHY;Fmg z3W1*XP>u4mmK&&-QCJw<015a&4&cBlaVVTU#dTHIAh8gG$TgqUK@|T4dJi!IIxfi} z3y2P-&<^AfVF^M}gBhk2S4j1cB*~VAK{2ZsSD~*7XYNuO_5cop;12g-3e2!tSy34O za0xNU4~SO|XxbrS^my~IhD}0`0oa^^vZ?4$Vt9inSjrX)SQOdd4iT0!;}>j)x*>X2 zrlwG=!j~rZv}`MqiTw~G?y!c^B1)(@J85)-eBo>D@DIem4t+u-syM2wAQA)$qIlw5 zQDP6)fDO8Ih#WPsP4lGB1`M=74#XA?N`sRKL2;6pR`p;BRwQ(z<(&K=9nD}0<6sZ& za0s-4rlDyPc%mD|06YGLiwbKvEy9Gb;4wOit<iTxl%$~k<_`aZnlt=ms612}ZP^ci ziZ|q;6)naKwQv*lbfK~1qtfba>oID&6bz!0hyTJXgqI8T;17qul>@6EnmS=+p$(US zm>L+X2vJ)J;%nugPL(0C(ps^#kPYQ9sL+5x$<nbzqG#wJk|J9R9YHw1ihqS^XzfrA zsLKuUIV420i!5?VxnNlK8Y8*8pL%p8^raYy*eC2bItqymKBSr107J){Hcwg*&xQ)M zz?NP3F!w_e$LJ1G;|Q`6qDcBRSvj8d;11`2R<9&HX`2uqk`$%5R>2U1$#aR$IkyD* z55}+#?3bpTbRCvKU;f~?gqlG_bQ_ytC6|&k<zNnnNFo2@`fROmJAITcXGpccp|ng9 zHT|Sk-S7!jbUz`y5aa*}y}(`BCa|C>xfFqkT*nToz^db53bF9K3tPkwoEzdGQt<$3 zEg7_bLN~XIvANJ;c*L>3s~peNL7LDD+8__dFbExSPj2T_B_$D%CJ(q63(Rm1TP0Hy z@pQ#x5Ub=3u#gMpz)lnVE4qZo!%0k0gRbTfVG?m5mx&OCd=FPqNZ&^d>Y#g+cT7Z= z6)lDe$&f^CR;=Wd6<c+zRrC*}z-{ZB6$8aPB8d)>fmYpecN>C4>k(JE(F~9P0G8no zTQ^aKOvqoQOOBT<NTjU1XB&o5W{|N$9cCh5$QA!jbsU#MzU9EJ`v78jix6@5$;3v! z<W$HMp~uBkQc7_QKqr|P_iWKTdHOUf+VE@#^$&9@fLdpzMB#YwP_tw@55Anql@}D= zCqT|1Qh-AY-M~oC1k99|nZAH*&@g3^XUJg;o{Dh}n$Qdv8cQU587jjZ_*q3u+zcog zv^p#-i{!`7fS08xX<%#@S%eOTc!lQ>nRiOAl3WkuD=X+qLejgws63>71kPcCNF{NM z01!32zzgK^s~mY<<KUMfBwfegMPJjRYAQyhm>W?&q>+@qcwxjYvLMgqc-M%4si+n_ zU8)!>(SiHY$%Rf*yB>##4&gSgEk+7|R?YwT5JUXwE=|!=XcaY;B^nX=6e^Kml^Y82 zFjR9$F5l%r6pV{u>%=JCXfxsrUqv`K%f|PYBmCxXf?Cjp3fC3g6(Hgd%_}GIfUJ)? zAasI6kfy|@09zaZikTrSA7V-p?G5|HSJ{HrETtCR<O}M6HxUL7JPKk(Qz;46mh<Hc z6vUX9-H*d)2@7!*Ok@}^j1cT(xzEN6w2;HAEJ0vF4yij1QG}73!W!jmz|IL1aU~MH zqz(Om7StWqMd>2G1|RLUO1KTvZ4p@JyEES4*1cQH3^8rxa}N()YUAn;5{hFZlr%eW z(txcIQ4_jBw+Y5^KmG$1+%R6gat!|}>eyW?M)5!l6pT0ZJx=*;lAE^MD&Y;)yJScA zAHd=#FDWhVPzoGz;9vD#rhVGh^)+mB35&89htME;1J+qeE|Ogi@Hw7lL_$<6y#-M} z-r!qC2x+S%+yWlc?;sC{*ey1mGl3!yXr>pKQ4id(-AmfD<`CjfJQM#w3H7p7h2$Vu zO%a=g4xx|={tz|6Fy2=5-o&DYJ(o8CFlvpxGk<OuC08*>HzQHa4Yl!-*HK#oH01wq zWIY0fY6DnWW`+Gw53k!X32uX>5e`y&M(QwnPCBlXMG3894;CJ|qXXDr3R?eQJ)Q9n zpYUh)XWqQi44zoxq&8HFE)@S|VY50eEtPtPF`hnHjS~KVAg*vd&o<xR^4TlWB>UhC zBQzAg7AS&i<jsjhz3>R#Qs-#Z5plaB&o;;kCk_e5Wb&Ee_mqeUVkJig4_8L&OmkhY z7v`>D(Akrr_0SD+zM%1T=Xl-?Qd%+nz(loFjFe;!2UX~jiNk{S>?VO+x||&zF@ODV zZkn_qLlF=05F=qR4zU1RD6}F5Vh<~{(ui_oFpp){p%RgC=AZ)rc{;9x8!(quKIi~a zlw_c3iNixxw1@Q9cZC;vH-F%ucY1vvLGiJ%U<x5Of8sEaMdI>70uMU65aUqah;{AE z$%njM3F`RUk(P&fp(X#(y(F@-AVg8X>`pAfG@c!Q4}+fS^&T7&p5yS4I`wTn7`}_J z0}Z)gK4OG)w-!e<v`^qrmgBHOxqvK9$w#5gLB4Qe(}B|K+hWNu-tdv}ZsyNHVKJc# z0EBabBM+=CC~mu~8s@;IYNfB%!4aX3bR@OFQsL9NgKDOv(s=0)1K$s(HZ!@_Rr}Dg zMh_(9fR<`{8FZI7m{Dc`P%*-95-lbT|1?xF7P*)@h*<9{-OvfPzaF&kzD2%iU@;EC z5JG@+4*+qf+dq5u<jDh&P~k#`4H=Rn2cTUsc;vjn>u0LjIC=N(9RwLtq(g-s6~=?+ z${V?J{n!!vS1$kINRjg9%^T-08?|}w$o=C4?WakSMU5Usnp9~*kMaJ+y7Uj8xqqQj z*{gT6W=M}7&;0;kK%c)W#_k`0apNFqD>siQ$*mv(bnNQ&9xO}%`ay(8jN3nmYnL|k zdd^?FQaJ5-O9>60J#^>}lJs~JAGU7w$c-b%N}ss0AKSVOiL~55TCHN*>xT{7KXZN; z#w{3+Ung+&?D?BV$zMEwZvO)A8V_BwSmfl@vwi3ofY`o&KP2amow17K>;;Q8F5bMx zpXD{~7tb3kXDs2xGsX^L#ODk>9vo+HtS@(*(fz{&>mS_5?O)&f2c2+`L5?MNSmB4C zbIws}G+JWu$DD%yRI^8|dyw)jq??fY=a@m>;qaPIVmj)e#^&K?oJ*LA52HiGLB}2d z;_{EFdm#F!8)B++>XKN<dh5LmjUoy)XgIN`pMPG8DK78kA#0wU$a!a+f9U#0ICN^{ zvP-2PqUw^3&M~K-R6?=m949}6NS=0#X{SOf#T<tp8X3wEq`3O&=POuX@y8w<pLvEa za?t6=OZdi-(if@f@x~iYyoslu#(+zxAjzx=M^Gz$k)}#U=NYm;(f$dB7uMkUheC2( z!}B<M%mL?)evqST6LI1hsY{Qjilv!<=BdZZNu-fVMlS*I$Dj4q0VcxBxH;>l?mla* zpv1i4XEZ|p4MoQvF8gcDpKg4?iP3+K3{Xh_xVmSaekLoZtanOr$DOiFEowAWc)7<M zjIaqOD_9%K^Pmmux#yTku&U=DX-1TZ$a_vqQ4?*LTWk_#$bkm{Uip2_qd^OWXfz-H zIfqvv6Go_{3jxS>T}}+0XQK1k{LG`q`0<CDY=-^mPl9Y*Ht8<^VY=xsV@b0ha1ODo zAf}rY7i)i*hR7avY^iP>bm-)#>9H8nI&G|(ZPx6Ff;tq(YMwdlr?a_i_8cpDsV3P- zRpJfGdA7bA0JBA&Oq^md%f`{N{!u&fW|KOIw1MuCFC1$OI=m>X<}rur0{>|xm@L=U z+CQfMM}uS|Vr{D>lz%uZTy?%yTE`Yc%hH(Hu_T}TA3jrxbe^A{S;r!~z0AALY=(aP z9J&}|+P~E8>PKE|tU<1<d02Tz)O*A=y!Mm+A%&R$=lMr-+N*a6_{f<??w(H2<gl9& zc~y#^ceHtgHsXVt*qsA8N#mL~{$Y&dK?F+8xI{m0L%6H4EpiqlUqZ}w7g*fP8}k^A zUg7}}!>tX2;z9>M0N{&#u&ikMX^h#-r!*QSr7<2UOY6phoLaHQHtrG$pTIN`<%w-& z+(8GdU}hq8+{AEjyNh*zK{tpXYFsu+*FAiZ4FK5YZ_tn+&-@aX!MV>e<d}y(NFgf! zQo(E~|FFbp;$;srHc^RK<dDOVQ;*RAgBRDTiGRBC4;{_}D;*MDR-n|Se%$DT&!|S& z%%Y9#0dgx{>&KCb$G&P9!%+7~RE<LNI9~u@9t)Dsk^1DW-_)caKiM8uNZB{<#q3}j zM1?rkXAgW32p>1O<r49jl}TK~AEUE`IP5Vqw!{n}&45I)4q1yy%&s0y^im@&@()O! zk$nJ^iq9M~q_;SSW{p9IQ;fDAau9<Z#yeC$yfcn-xMLor*ate)#jbPSvWEY32pMrA z4pWT7l(w0gpgxzODt1y(IO@eEPH7Zj3h5`65Xz0n5s!(qV<q9b;!Q}2EPBTO0|0-b z8OdZ8nf7t-jOfq@E7CR2B_hQs$^1vW=7kJ={L(_r#ELySQ44b5>M5!!hdJ958JuXt z6qF<uMx-%`dmzUq{!EHL9O({s?oLJ8fCmx-36h!}NqHcfNI5Jrxf%(nEaxaC8|9(N zcw)7g2f0vW`e6-hbWd#AsKq~OiB*4;gA&P-S1<9wu%9}lKY3bMJ??M}YvyVoCGrh% z0(Qt_bRr(eablOWY7uyZ1!wor1|<9ekC){spv(k7(S&l2_1K~s4>is_&+(3bu<$bc z5RXc{!KX_B)VN4FQBwoRkJt6%5YFHSXxmtmW+e%E%DYK39wAs$1~Xy*;OPfqg7Qj` z#X}YCSPyLdBhqmkXdn98=sh^0A2q4hJ@IOvFImD5efXj*qZ(^lkdmWK<TPIBP^?dH zxgplx?^f6R$1+HfrO>oBUO1taKi*+T`G8{*ic=)>Gzt$@z$0w_Fhwj_CSZ{y(P)@K zt13o#s0`NVCg(thJLrQ%d%(jRu7JjHEw!cg;Pt}DAy~x9f(~l%B3-0PN<1t<kP5*A zAJ$lGyu8a|4ZZFkw2@FfsPc({ERv$~_=+na;X@fs4aA}4(#0Us4ppqyf%X6(H$Gw^ zH@=onAB5XO0kDojtz>-jWK=g;p|5d-N0Y;443UpJX@^u#9^>Hu#wB+3I(v9*9*eo2 z))M#+TO@BK?1P{_w*<e2$S)yn6W(E*;R=vN(Zt0-uQv?GJb%!0AFTLCm0ETs{gjWb z4Pn}ZR>QuYpu-pX_+8pwtv0qD#VOJ-&3ytinSyD1hHRVWG0K6QW|d>gyg9b*a5Ii( zXhJ)N6tg`9Qd9)qj;rmc4zQw<6KPKyYcI?aUedY}R@W$R|LE^H-jT$9_!!8#CY<%i z*DT~<xmk|`Y_GReV~03JL{do<FRj6iUp9>-lapWCIy?ygm;+H%p@pi<T$H@o1A?q6 zh=c}Fn|joH&O55kKlqW6jfCrJD8FD)%(jw1Z}TPVIlAQk^ag-xIIhv*eYn-WO=*CV zF&^Ux#w83&EPVXq5X<<qJx0c+Lp_5X=5XLY0O-A$FXXWq0<Slm0Sijmnw#wCQ_|S` z>v!nu9P%Lcp;*}vk)|db!(x_|H1iH&Dzzb_;l+f@5ifFZ8y{#~a8%9ijCU+%aN;=Z z+G8fj3y&if*^!NHB=p?q0@J?F`AIvTVI44`<Mn!*ZiNq0U1AdiFY`zbUj&a6n99^0 zm)VUsa*+#fxPu?X{Y!r$bC1RHG_3KF$FJdQ<f1r*7r-FL=I0R)ZZEU32>Z-TT0D<q z9Ks%>S--?4Y>qP@WI>le2IG*udAI|fgR?IA33iD87I;{Yo;U}M*ch=QC&(BdXOR?W zh!Kn6huryxmB^FFkp^@r3z2~a^0<gd<GK`-8PKtZ*BccM35CD{Erv=zTM!EeiU)1D zglpK6x>Ja|3$X7%6!Cxs>N7p#K?gzu0C%7*q-mv?`HKDuwgo{vXs861F^StVC1SA$ zzTyi$8I5OKxXN2Sl5mP;KtJ{CJZ!jz&wIZWgg1M*1F9$p0Eq`(*$>P6ixXKmjSw3S zlaNU`26vDdE@=#mAhf$kBC3ceeG0xZ42hqBn=M2m<S7X36D5TBhsOB_CTxlDnl(xh z!Z^FIp2D)Q;zL&02YUL5qi_&fV2KKu2X0gUB=0IGnt+%4a2OJynSW3Q&9fMfU>#?e zBQg62L6nLE^bfrFhjmCEb5Ii$0lQ16hpX}o`P+)3APREOhM-uC^=JoTK(9mbjhc9z zYJi?b6OZXjzag_L6<n4RF)0_ki9<>#>57ZEAU<{|1^}oIX?%ohFbE$6jys79@DPun zpcGj&4&*U060)$yaEfeDhjEx00I@=;AU}s#7*3IqgP;nb@rNYJ$CA90qqq-LPzJ<W z!-7F0qo_wQJA|L8!_goGWFg6};1Ygthm3FqpRyJJaF_@w2roIrW;6yxe2aNVEq^#X zxG=~HltiJp2@nDR2Feml^pD1P2LPb|27NGxkufp7gN2Q1BrQ}5rmBZ<zy^GP2d6xT zdC;*{<cKnKi2L9L(~$}8zz4Q;!(cSYz#NS;;l=y-I7xf0#-Iuvf{VeFoz~FF8aYIC zAQVCA!KR9)cep;1w2{Ch3Gj$5XPA_41Q~L`wTg&Jw^F!gTaa_;vGJfjcNj%@<T`mA z2R}5WB+8LP7>D|4BWwhT+$)BQX}}cO!RUBH`11~g{IMX52Zp?dbub3h=nJ$gijY_k z-r6F;x{13mE1Ee=;ONN3;xMP^F9m5W*D?yHpoCq?DekC;$#BEai<qIb4u%<x(xEVw zO3RrU9Bt4Ti>%79+C>R52)q3Mjhb;rcqoS?QVRgmn?U+Od8jUOz^H_1jL~q$a)1Y| ze8L4G#O>q=c@d8bBre1(nIrQ{-pI~)&<vb_vh^e#ap;QitcaqFm5REDa_9$SEQy%V z6^^^FMY#lRki{;#hclUqE#c3kFqw^7Aa<w-2PKPZSOs!02R^&SY)ni<xe;*SJ06wD ze-Out01aotBJW{^Zh*`1&^whlQQDj|ak`1r;tbrdnr^T^<glYHJqRIMl420LsvMzY z$c`-a(9poUEy*NU00(c-6nL75e&C1dd>0|)t>@uRc{z-S!w3&mOL5?-s*w?YPzPU# zhos_C0W*rxaD;()PjsmNhjSQJ4uii95z5D`$$vnFWY|wM{R^gol3sX(VyQ}Ep}$FZ z2Lm<AbV3Jrx(k!=htx8u3hT@oJqI8=R_k~P3A!QcJhSZVEq&0JgCMV<h!GD}3L`U~ zdf<k(?1zy=hpv1c7$r!C_y<aGii8-?xV$6pxJ4lu4duuZlNgQm45iO(BAjTqu}cUZ zB}@Zdyrp<jJ`qRSiVU(yEp5OJO9IYYRM;?b24~2rvvi8ExQn~95%$tCeQ-_GxC;|? zM{t!>)=RFr8<o!q9iD5VZ#A;UXbESu4t^DmYY@A%NYo|rh^=9lSDBePtF!H}kax5@ zvYOX<cs70Uh}U%g1!wRE*Th7DsyOm22>IwQgwP7O08W5KHgT{7r(mictJRZi2y#e; zYBErC_zGp9g_tNu1f@VamAma~i7hM$cX$yhQ&%Uwm~;Y*8`PAqTai)0M07$YatK8) zy%BWaM|9{=&MY!C6O3P5#izVPpn!(nFbNdJtd*U`a0mx{pwNWauq}d;jqEr$lA|N5 zhq;BVAQV0!ys<B%ENv4RI1&dTU5Mmjx9wuC#;DIps8k$n(!jkir#LU#;**<T6;0>` z%4@B)wY(?ou_NgQ8XHq*#0)02r5a_vnDU=;(I~i)SE{YqrNS?0>XUk$6#zg+MQV$3 zyUKNt3VHnh2csPaL}gv^1wswUNYI@#T#GHIz0{v^F9u8qH+{HD0o79UOM|(G-XvX5 zv{paW!-Y8DzBQ>WL=I#qnB**{O!<dYPzG}_(BTt@{VC!07`k3qGlOE`<NyaM^Ae9> zt>kmsp6G{I2!>Ia*zQ1yBCI|;xsiXE2wwD(1|(g&JBXjij{;^=*4q^FT%=6R2EmD8 zk|40V*^n;m6a&MoUQrkh`-iD12YaxRv2Y4f@YNN*%O*;ZTrh=};f^k<2Y)z((fCNf zWn2g9sJ_4r5bB54Stc@U2<8MbgNh>gkWM^iuGQ-@E9ozDc!vc^2#5#@D6!xB{SC8m ziiiUL66Tnddr*#B0TB3sHN%k!XJih+!LVv6pH@pbSYw(SDM99P8wKhn95K12V5?Nj zr;U>!>EpXfK{nx0l365}&pVqDR7FPf9mqMMeoME6aEfH07_*U&Bx9duUWo1Ov|~_< z>H!e9jfvDLXQewErs0(o3t_fGjvhr89JQUU3CHSqwX%r?SKx?<Q-}@nF<1bc^7%P@ zV`fAAigPi%aDJf}DLAEItE*u@WN3$;Q-~;J1r5V78BK=1{fefs4KI`zB|#h1ksPx* zpjt8H^9hE&t(cllXxD3EW=RO!D2F>37G<fnH)@(HS_fKqDEN^PI?*<110H-GmYlNx zha-7ZC0P(wAv8SZle?)N$mz8-N@;h9A-=#5{ZJBjW@V-E2<G~|oSl`bxC#Iki6>>P zu6kLK`iD#42Eq8&s)d=RKnEaWu5E;f>oT;2T?%qB9C4tJ`^c8VARgZEP)+GPPO%Iq z={3pQhZK2AP@X`BxHeRXiTC6}z7mu>!U}WnhdKP5!C@AAR=pFZz?<ML0K5!eMh>A0 zg$Gl{->9Oeg9tSNfD{S45xta)Y+Og{T1sIbbf_X5L}(jJmrb-f+bbGO$dUl5UTwsj zD(j^KY9n6*HcxyDlE6I8Q%idw82R|u_$#M{p}#?J2XYga(dcO`zT_sV5;{5mR;v*R zDw|lP5TXy_z$(ffdHDwjV$hFBPy1e8k7gGkJLN$2$LeegMtL48G3D4QJ`{{=8WJa` zfC|AfGSnDKi8V=qBL;D(B3Y!TM-Uby@(W=?C!i=caaxaWaqv}U2#j-_L*cMDJ;AEI zY~z^>l1tlJ3T?-za8_*yr)ULLxetwMG<K$2=)LPh;8_cCici=JMP+2*_|~t8g<N16 z{$Y-Yi5-Z+ruJCyL9>N%pm9V=kZ}M|dP1V&vfMvYiMn#6DD|;df$YCvFLLmOYA}bv zs$zEeTq4KN7^x6Ca;YYQk8}97DO3|iK4&eD3#L&GV|_zmT9_H`1TRzni~C3h)%IiH z<im5&gpJ5eS+$Z*NQFH@qwyvQZBk}n2(Kiz5MphTu4v$1k(sVpmrAe*9JPphs}7<N zk}>s#ibNtn{S%NW>=T#kfVl@c8I=v`kcYY9zfBoBOLRnm5+lm-#kKM+WgobKtt6QU zbXW;4Y4pa?r&sX@;6e<QXo(IUW1r%ab1bFKfW*^Yh|wUku`n>qX({O<342Uriw6Lk z>|@<V3ic|fIzNbdV3k_vgdHmGzu2a4F|?WS^GA5MODV%_@iB$ulT-eQQd<vx-|lRv zh9?t34UQDe%|1PuBQuKfao7hIf<^}E7xYn|6<*r*=_}i~SGMK<*Enp2W9YF7(jalz z1m!J6rWEYqQj0Fy^;&qHlwS&qhzECqr>s8+XbKbwo%ajRo)UC$oEL{;5QmD;wF&jV zdin>=ND=QQwtI*NO9yw0X*?a8ks~|zsVE5T>x$zh2DO4z8PTVwh>Dhpe8XPUKf6HG zKquNlD`J2#D|$lqGKVJXH5z+pd$**m&GhrWrbRMxy#X*2zI%lj4NJI&v9NtZy0ZAR zy$kQLc~FLvC;8B_Nn}yI=lGcv0U&L7-i5V|I!@#+Vtb?z_P?7k<-Rlk)dqyP78|)1 z;t?{F8LsJ29@c-3!DFE+*{IpH!l5_ubrnKQ0SJ5HtktXkhi;xcdE>^B^HuF1!-N1P zQk)p?A0=`A0Nm?%Z{ELw_3+J`hYnrGi3wM-Y?-hm0CD{$)%sWP-oK6)DV3X7@#jg9 z%`Q#+*s<WhPN5*yE1B{qRH*&#k@FT$RXcc9`}GStPn#xf<NBFIClP?lvlUNvB=-*% zEOO+Y$}LAMt6Y!wSe`rQ?w>Dp5KEry_YWE;Z{E0`jOzF?<j9gI7yUSI;UjHiy%q#_ zNZdSo_E=Vy`>)!%ao)&@{)dj=y<Voyjf43!ZQ8>9yg_qi)t_Fu@Y)d*Cl}pD$`qe2 zY^bl?xN`vf&D;2o6Et%2Jff91QM5^X*6@+^31H#>KYgg)EkyVfH|ePV%30D#F=uFz z<)5mQR}bDlwM;TkK>(O{5ihj-W6ny-RTh*&&1f>tK_?|7nmPB}VU9gbndjg{z?p`X zR^*)XkwX1k(#$!)-BXcX{v5{1aZ{ml96Q8RHCJ*V8hF__`;<Zsd*>vin>VgNvshQ? zP<EDH`Gr%DJtZZCo<k7T=3P`fiBnlg^YkNLK~+KpUxVEx^j|%b9MhqP_gNC6V;#x! zPcxACQ%-;X{d3GD1$n5Ja`)Uw4m@|27$raUXwu9$)LF<SnlRqOm0O&^@{c`*-Lo1w z&#WVti7$3HQD5`y<I6q_^&^j`y(z|+lRn!2dMjlel{AhvnSI0=m4{rzsXhHwRFyrp zJoArS)BOWLJoChI$zb#Fr)F9d!HSM(-Z+z3JOHruk84^H!_JMBImpsN@33OdJAGAV z&UM+HxEGgE3PeynAEA1VIs34(&pk#Wq%E3ULiJBKt^5;iN&Qs$4?f7?)33FrPE=Bd z0fy2~LAC+#4>z04=aPd#@pDcxv1r3jSsdGA4gjBp{GqK?{bLL}@oY8Ki~d~V3INh6 z{1ZrUu|^j;=&)l;IjeDX>#jliQjR;RmSqn-(7@u1RZTugsXQeWgv^xB{)k>J*=TvN zeBxMwGkEZbN1jvMVT&7>1lHruXN|`H3GF|hNb_(-EZK=CwdEv4ooMmEGl)Ak6DpZr z=lql7KZ_cA5I^Hwa?LounngC>%U$|uz2k^mtIp5R(ho!AAe>NN4EwTBZCm%#o6ch6 zIy~_|>1xh7*O(Gr#%2fWj6d+$6A$Y0kTcFdz^o(BYOCLKQ7@X<)BBkTqxBs;-sBQj zxa0b>=Rd@(!)aq6>I&pM1G}?Oe{R9`u$_+95qR_i8`uEZhfZ=4R_FsACpucfjz*D- zNW)}&%G*57As%i}DPt9J-ap&~0O?UrB@Fun02~J&$aEwq7l}nI#sRZQ*`psE>clbR z0T0D#OgVCChbrJv4!N+T9RIlg1TsuSJt&#Vf0*DD)3}Bes$2_mrs{}vx>1XFyn{Q1 ziHA2}!Hlp?YHatr7}}a58r;>U8ouyHdn9O)e@H_?;Q|vnD%K8zc<^>B<Osfs<rx5E zsE0=61u*7QzJy#P8Nv9-KM>-drhwxPHmOInsu-CTqQfxjFor$Kff7#6BXlqvN3@LP z$M{qRQ{=#o?N0K(s`z6a&j7$`%9p!tu!23kLz0r3CcNSivv`eMUbx6Lk(*3H8s?Cm zW8^Xqo(*v>+xdq)_@NC*h(mJ}c^^2#8P0Ex>>vIBqbtB>4t`jOBRBeosOYCQ2Zd8} z0^{OIo`s(o5%O8%EN4Cc3V1+k`IB7yc$PkLGS3igM4Ub9(m$?23PmPFS9!EX+Q_xg z_aWsF-5}Oa7-ll+jq`n!c~&XMVG37JshkrbmqAhy3V)bmYPfO>JB$H<tbqia^oj*b zr6V6^y#*G|nvO~U#4}h8k6iDV2Q}OlsfLoPAL)ZdE`CF<e?mr_1QO4b#MF=XxyB#& zWC&8B(#TIJ@}=auXjr4-P;gG?q3^4qXW#)6b5g{Jw4en!`1F%-8gWIn!KP0{Bcnrr zqeBgS=t(*Ck9DMmPh8sSWtuUYc*tm>44o@oM+ShZV5c=|!;vlOVVbDWhK_G!h(3uG zMrnA%9vUqsZgExrN^}fm9Oj4_fdEvCP~78YiL)L#h*ORd5e9VQc!W42g|kW}?u$u+ z1~lR^%%b%prxMeoWGZ?Oda1(~|9FR`Mys^Zv}9xRkRCR|QKbN$gdhI!g+AV~LkRv+ zl_~rOEn;y_Kpqbt*x;bQkmfggc$8C3Iodxq@zHEeW?LoE#wEC659)mIz5fWsOba=@ zi?E{@q2wV*dU1((oa2sB@n3efgRhCus~GI)hl_1>67)v(dQ6;(H^8AJTD2E4EJ4Uf zuz`>H;;XgYxSH!OH%DbS%*7Tp@RTyy!w5nJK*v~$2Ul`PV2~rnE-5TakwXy-h42{e znX&!82TykYG;J-;)og75d0Z~nl^o)zM0UyI6XeE&IPH)NWUKZMYA6GLVZw25oFUBm z<+jq3QJG3v8Z8>u0|3W31e_Ag&>se|A9?xQJj$`nZW<_n)Lo9udb1?aRHiN6ErwMo ztsJ)8;~oFV1~q(~FNH#*63@a-M{FAod_0xDulY4KAhO8*R>X*;7#2#v6c2oaL&@am z<5>zKj!A%nSZ9%k5jSzTB^KGp7S`q?7($%@mc+{gLf+|oq?64(qaQ|E$>Q>K56fPw zE&l*?)7m)^Bk~L$IbN4M`r>Q+vPZn%luKzlbvh}R?|${@#&`^*N`45eRe8Rg5m6Bg z#Nl!OB;(0jfB0M(0ENQMg;dK4SswGUUFIH;XvS1rqZjOjA{7e?ppQ-hpmRm?DUG?z zHnriC`Voq{Z4pOlo0JgKzymACd1%$pktK$Nsg(RsA1ugND@(KeF}e!f=nR6e4%tH) zlenbFzv+)3g3=yD+!g>rXNq9Z+SRE`9LEk*i6LH!P#|H4DssXn@J5A)7s*C8%#r7b z6owqK@<!f{99)Yv#o4|FHac8a`RcK9;SpZ9>dbbxZ@<So1o{)GMO^K|4U5`~+;^|q zGhKOb%^a4T51f5;k!R3(<1)Teo)!d|OvPBd-tlC=1?!`gT;w06*oVAc{7PuhZ{w%` zx=mWlCXVqO<S7ydOn!TZ@(6#_Qr4;mH^!sa+P|72W(%Rw-CTo!gd_9_OLzqUfQ4p& zM6HyBC{02D8eXovh|m0kjp-b=V9z5o!-DAAo~1>yX@xVST{&nSa@EjXd|ihvgxDR9 ziIm-RkOMd*Mkje-+ub1N9Yj3ziZ;~Bq)^E}ct$xCNFUA8<`6^Y{9Q-z1A8O`GO?5M z#fQSA#CD*=Km6GfeNKE-1w1^1EgYIRYy`}$o_OtBHV8(GQG_h*26k8l6w+I0*aJq9 zg|i)0c}W`?Mi3+YLo3u@>;XVMw1dSk#H75$?S0zJtPz)-6M*poI<VW}?HT<4JQp&A z;kC%#KOBN36-%*5p&WIX5!smEq1Zq4N_0tz4|bBNc>{Jh39r4x=HQwrtzCtA2OMD! zEBJz=)taHaMI~TQIp~E)oEr#Q2Dd3$=tbN(xB~zL21M|U5mAC4_KnNo!~U6yL{QsP z(A+WnmIUsJC9vE9ItkRp8#Cs_HvUN{%!2^79xpPK)D*)rfZ@&&#t}gRFxpNYx`cIo zjoNJ;qU_B4=wtm<jXU^)JMe=v{YZ8A8K6mz4dP(isSJjR1A7HfhnNF8FqUx@%{hoh z)2u@}Aj+w!%s&LfCCCszh)e3Ygj`%iv87!N@tPWbn?2k^I^=^m3|!Oy=*<U;S5W-J z!2H9%9Z4sl)2wNnc$EZsSPVSqS(BlIKKR0G^aU~MVS`+uC6vQMdEDLfL}eIaJ^aZe z%*;3xOGR9SM4e3kJqSAZS}(wXE4WTsTnmPnLn^QVHo#HBxnoo~;Lfl^vFJrmXrw7X zO4-mFAa#o~_=a{l2~HHo5lUMRIR+EW2Rd{^DX7D4<r^TK1lM?t8f=PQWeis83ON`U z2OUI3ydQo+M>6&mAKFLkp@YlGR~#B%|A9v)f&+&<jz6%(Kh#G&up22Ugf^^#HoU`1 z0@8&9;UUyRA?c<Z(S;GU!!WFa!+l$SkP<{R!z0APd7Xp}@=#m<kOQQpliHmpfW%X& z6y#;t!>W`+k=TYj>>VpY14PoIMBZRf_SRfT(orPhAvgm+)I+m<&N(&BGo(Wj&IPK) z!#Lnsg+yVI)lWPqBrH?{X}%)BUCJtM&M3^!Z!{PGedvw}WkLxRCy7RH<bv(M1FvyL zw_y@TIHy9?1}nJ3{s`4iW+QHp3?;M`HQob8MUpFyQtG*eo0tP@pk+!>kOi3!!juHe z{6j2kV2l03c6p^e9K#(PgH4=6#?+proTubmAcS%f0I<iSi~~NAr_$Mjw}8v*1Q1S? zn8eWJ>gAwB{DV4_f<Ej|MDU_V;Mng}f-A5FJP0GcxJ0u5RY_`+Ui+C!UmR36m={E> z>0ZQx5nTf+5Gf#;L_r*BZayl7SxQS8-z6oZJX}O8@WR6^5hwA3cf`W-tP`(As%Q9? zUU*`Z_yibDmMXBrKXgw&>>PQX19ZgY%5~<iRu3n=s`_-pq@9j%z*B0F!*B5#J7SMM zl)^vss8LP?#$|_$@@Idt-G4$twFGNH90MDKs!f!{IWYur6hk}A%B#p&)m*~Mlts2M zkz7ngB~-#{>?d`0#QT6AJLJPN$b~n!C9)Yxi@3wUIFOyy5N}ihCj3P?+)FR|!!%68 zvfZTNEd<8y1EE@`9*zt*groKmSV#N=HcSHtG0XA)j3qb>0wRb*L9nKtsU;~4+}@-~ zf3Ssg`~xI#Q*D4#!FdGrsFpb#!XWsKclc##l-bkx9gi3#KWJ00T!QAvY3|qqCIFg# zYFuz&kD?rhPom$IU=J+_>UlhnjGgH{gpy)-tXrJJC`Hhf9T*?go?IN{Q2LfhFe|z6 z0wpK|23l09T4NlxrT_VjTpYqU+=L_vXE)S=!^}rKV385I!zDaIFVN+#?kxa#h8m%4 zByz=Sz*9bO!?Bvw(Hdn*eA^?y0Z53FnRbV>RY#Ki%%n7Iauvf}9P3y?3-<g2FYH1C z^-i>ULs4~3M6PQw)ek$lg1i1w;7(FbOu`}mtXvYh1}&t+I<x~y;i+XTL|ANwh4P{m z!X$^ThR;AKbp@7Oqyttg2z8i;^|b_gJQ<<l%xJwA06;_9V#3ILB)MP%GGG*yh(@%w zi!XG;0q-MxAc!47g|1KxK9uZEGE2WC1skM7vYrI(RVDy@f;b#oF{VT>`dY6n&%|gH z<@FUqAOa$gixEYu-WDw69qU~5>yb<kI%q?d27~70jxWMOcI2<NV2bq?E3*g_(ism< z7!hDlgFEmg$El8m%!Aidf~5J(jXEkz6pOXoP2rjf43dL7>;f%-gm00{HBdr*AfNpe zmmFdPHhHMls!qprL!jJ@tNDW!mP0H5ID+|xEV;x2902S+Kw%C#k3CF+GrWW4d?=yJ z#}yXCNG^zWzy~ME1wTMXEI@)b%uM(#ELD&L%peB8DxA2K;61E^Dl7}LJTEi&0vN;5 z^sGc<cr7MK+MT+v_7+p**aHlWPuVnxMEFC<90MY-!AJeWGUP)#;6<}^=lhO>E2ARH zsG*Zwgfn<7vy>g5HEbBJ!zdW5H%L#kirzx_LpH33@C_EJkOM5JK{}1hKw#98Rf$Vf z%{fp5FWjQY$Sr*M73@VtM`XxIOt3`)KrI|XD$ol&3=UKnktNvfDv^c@;Rzf-%5)Zt zk3I%d22?6^ftUioU@|jB$b~)su){OVGIGR+Ed4_-K*A&B!dMm?hw`sJYKw@t1<z#h zT+|7^$V9kC+d|xD%G`tWr0o>*9Ca?`zHqK4K`}Lyf-)Rb$!vn{imLsE1U3}JG^grc z`VBe=2;Oz><Gd=l$c-fo3!XdzB=o{RV6uXhi6t1_CqwGq(&^@?!a96P7$!#~Zp?Z7 z12TNUu*?uG^5bimv2Q%Kot$5@v_noZgIjO|HAt^7MG|f_&Hs$9O*b<!8Om8+0$`6- zaJGcUHAN~M!X%`_H#5s(Y}rce$~>$Hz_^-xILSX~^^?M2?zY=`+ygs|!m@;O>a@pH zrk?5z7C@2<CSU?5G(*Y%R<LC#q9LM3Hq?YTsOz+~L_EasCnN&~LIsBSL$_JOH2Cl_ z03shjM!J1eIk*^Zgvk*tf>`{PolS-$q0*-X!+U}Bi^cFWEX!)NUI-FpFFe8}Z~~x# z$|%WgRRF+*U*W_?26|M3pzhB+a2AM2X2)WJ#7IY16W_$>#~6aiEvCn5uYx5w@zJ?( zloSxZ9K<<8M!oH%QoxCU-1U7vju%&uCYZusy9MyNu=4<bo6ydnwAVFV&uPrFJ0$gU zTlh!F1v$GbBYW1-(u~raGLYuWEC&`b5W`pxDs2cYZqN&2Y=tnwwu3k-=Rt=RYSacA zhy@R$!o<UGkqb5d3_~1bL%c)_I%1<S1B^dR%WcsH;GTsQ0!Wf@=!2Hsj4RGfHw`@a zHWx;cY03i^$p}N-Ln~y%^=#g9sCtT$Lo)yZATWb%nc6A$dDW0ZHr(-&`hz>57mn^6 zx_PlieZsIjT<l$jpiIIYOajpUhXA>-5yiJgJxhS2=s`e)hQBfcs>@{DPse}*8{A!| zEz|%3h!GDbiGJ;enroRcvNK2l5ya4V*2=Yri1o6=CZvz`T9u5d4zy^_SnorTpoIjw zovA2Y*T4dHJgB2ePqz<5hZsc<-48puMK<JtC}?WPS{xUH#6Y+e*GP|)>4iDa3&o7( zCa5qGGAwTYU-GlW0u@j}E!b8tPWlyD#!U!FLEr<qynGo_pj)IvF}Q=Gi}|RNO%A>T zIcNhM#M^nfM$(>xX=oH&gocOmB0ua8p#Fj=P=i)HqACF;I%q|)mDApl%2VucZb23o z>&j?(xkkAIH@HG02(>n#;uaf9aWV_juR}dJ10sZ}O*m;G%2<8<LoWDrBV5BaYZUMJ zgKc49vzUi-qX~By%1y3@IS|7rz=J<{19S2yxnR#YaDzHf!)aGZd+6C`z7xZg?8RV$ z8dxj#o{r%;St-cAI%vas5BfVeeYg~-<8-??bVD$Zf+cL_iq{D`n8Og(!)~WSIpDX& zXbv?0*?w9wj3azPD=5R|198ZrgAsLuhI0yMIqKZow8zf_dGtdl+=1<2(tE)>KzJkP zt=qbE>58%YM~+;-e)8l2kO+WbyoJsxVH#KO5}ai7{<%A6FWy9n{q8Z8$FA7Hb<o5O z{PzzYJbv@Uq1#uA+Prb&&hdjN@!q|mCXo^~DsP^-a`!M*0(TCbJbU)w*_-)q9zJf< zrXdSg?;bjIMU@ssS8nFDO_sF%Q&&peICAC8ol6Sf>b!pVkbw<{&m72qS8Ga)7tfrz znf2;<J%$L;p>E`|nuQo|GgW>wlfk(}?p!NJ(q@)3ixxo9qW0?HJcKAzDsGVL^#joV zxSYIk|JtcC25%rgey*27RIXg&QM2>rp&M83T}N*7%FScQa4S55n4-d>xjMN#v;5xu z)>q1xzIxAElKWRKp4sN|)S`<=4jL!$u)Jw!tA!Za%fJH>Oi)3I_UYvkNFa=*kzRh= z>Oh8AN~ay~?3o9g%ESSno}>mm?5YVb(FBr4g3+cOq+qE88feH_5UBwZTqhv_wn9f7 zZq%X17gp3Mk{<xZS#TV%@R4XBXrdCR#D9`HXP$lZDUy{|s8OdHagyAt8*XSJ<&#f% zVWt}@6|Co<W9~pCJIL$_XBuqqvByS#u1V$-OIjf%nQqt`uopPEVbjJ%0e~+56*hQu zlAIq8BF2_<*ja}-Z)Qrcol4a3#+!TWkw+XrzKBRcZ^~(BomYz?=AdiZ5ojWDc2Nf% zMi=cAno3}iZ>z5Cv<4e&m>h9IasK2+q9pa9hAu@9bO-<@u?Y;DvG$6rn`=@*WROEb zIp!F5HX?D#ZXk?nqH#9a<eCNRLC2h9Qc2~GP7q1unr<N5s+(fgL2yc5DQX6eT=bj> z9%x_z&lOj|gQimp4cy0<F45_S9DCYHM-_GoG;k}A|BLFsc@S<Hsfe6Kkeh3+fdr06 z77^`|Uc`ZCA8@$grkii2xu)o&rAcNTRfb{58)qb%8JrK<8045_06<#*nxe-Hx*K=e z5l5UxF1bVzIKFt~5@$G31Ct*oirJ)~>2|go0EW&R@4WNo#u--$Ne7%-cG<-cL%LK) zA7`}DrkS{}nOXA4C7MPSYr^S!Xo%HNgXYgc|2OZ*9mg`rQWV)m$gG)ZMUmGX0frZD z#1=>IySL7LYi5#xlZ|8QksN@aue}ABa3W8Ba*4+5rgm|Z0p=4!1QEm$TAI;>j$VfL zns2^c9{w75j$s24cAm*6A3;Vrh@Ez3gvJ@YL7y4)O0viWnz|*@#uPZ<Pz`2;?sIqx znlrpHqi(R{Ana2gE!ZKgYV0F&a%0r@Fz7W*sG%0lu-q+VaXBXcbpsx@>l!zXW;7Kt zLmH^i11drkv!H219lIbBGnyfdtm#mPLdzRYrUn+Ugb*x6J4P+ozy?1QqF?#|M>sMU z4x!nPW<~oPGnipBU}&Rn{}Kl;`mhNAuuz35G|6BFvk!cwq6=+EVkeG~j$u^eMR?oW z?eKWF1re`7U(iG|F!2X9{NWO9!-O}$AvPZdZEI!RS~Idyi&;>^9U+<s0@*PPRjh-B zDLmRDogub%v;#a*`2(mbp+^I$5&$I$pFEPm3yH{5mL{R)CmsQbOT>a3)sRLoc)^Qc z03#U11STqwiOg1@q7{}PhB2g3jap8GnAcFoAr3)_Rgi-Jo2cL>EsQD5U<$JuzzoKN zAn^!ObYfz_z}hU~IZdR{5&+^f<~_s7jCI(86_%iekg`DvQve_q00723ff0*ZBy^z# z1%ND&k&Jr^)10oT#3x!23tG@ZqZ|b%MT;p**~wBG**M)NVqpnD(E^LhP)0q234nVB zikmeh#VQ;@E@?z>FTg;?DpsM;SO8<8v{+~`>KW2t0+XY>XoV&$K?zM<LZacEs5!-1 zPp#6EtG1NLK~pgaTTmh&>97SYD#6ZJjB}zxHL6E}fy_#9A{htmYBgf<2uo;!7On8> zUuiKBaRNhj!Kj2OfI*9cr~(zf$Ocm38PBawmYy>IwI@hHTFg#xB7`6WCPjrwOko;y znWa_cpDe)(9U_&r!err)EMW>|GIN=kjcG8JvD0G&CWMH!#31sejAK~C8oVH;RfqXk z<<deEns@{-m=V&6x-_a7rLA&pNlW9dLKd|M1!XAF31V178JR7nWw8oO%1(BkTjfP8 zAhC){xZ#wzAgorC3fg5RGnoKjg)gL`4*(<siv>=GG`ayFO32o<$TTlSlc9`iD1#H6 z097&wnBmB|BYeC%hh6~S4}XwIBGf`kjR4ROd*}u!4w;8PuF|k6S!hZlPBCoIL5_P& z#33y1mB~64seg>bANw$JJa&u}8}G@+Gp@=1j2ZQgeXwlF2E$m8OU$NzU|B(|aoIl{ za<C4!_{PejNR3pi6&jm_W!9PqInc4<F)OGa<*<u(P(0@w&Dbok0rQsk(&O;iW5;@0 z$ex2d6F@uZ9QF7xWF+E`c|fKlEL%{C?y=>W_yb3C_OXZ>)hL!Fno1_tvqbb_kDo|d z9!s7v#*jj)Pn$#@y0P?u6qV-~j{`QdHc*vMy%+n~xf~xh%VHLz8KyMFDdljsvw3qM zvoyv)&qj7D&2sE=yh|_L262ax9qyzoX4~a($2*?AZ3L-X*x{bGImm78XHO*D$o{ZN z8uJcxr`y?k5%)y+{cLI@#XbO7%e<58qV9SxW-rA)$HF1b@Hr1WF#vG(v9Aqqep?*c zC^n0+cLjhC2Rz*-!Fa(XQt`&z8{83ZWwH;xZFo#)+x0%SL`Yt8VcV<O3GcUJT$z-b zz=PlJFo#4?{_>1-oaEzxH_+>?@qiyl;Eiz#yn}9_rH7B@<{*dH$6b<eZyYH{PkOd@ zmGgf88|fiGhrqM0^<bYGI?zc<QR+SqFVCItefRs{0Uvn551#OaH~irdpLoSDp7Djp zd*1b)WQpWmDUG-M<uRXm&2OIbo%j6bK_B`ro0`ie>9pukpL*4=p7pJF{p(>LzJLG# zA^8LaWB>pFEC2up0HXqn0RRa9009UbNU)$m0G$phT*$DYLxL6_N}NcsqQ#3CGiuz( zv7^V2AVZ2ANwTELlPEV%0s!LVp$HNRhN@&RMu{W<{0y{!A*IisK!XY$O0=laqezn~ zCCI_zAS)BeNU)%xU=j;f{*>6+bg9>`V8e<XOSY`pvjQ(%01!%Igf4%wmKX$}t3e4} z=mO|au#1H;e=Kl_h_<ld!-x|rUd$MzhKQdYCLEMQubhEX{<I?a;WB_65pt{?nB!21 z!3+sEUd_6->({VjKkQkM@4&SJX$u4qV=sV+A?ym25K~|W4IE<hwou|j@VbP111PRq zw)N}Svuodu5<^7dQ-?GEtXj~*2Es9$QrAG+LPQL@d#Xmwy}teX`15O*@17z24IdnY zfd&NX20%~b9XQZ{3GQ?td<N<#;e-@cXdzl^U8v!P9Cqm8haiS1;)o=cXyS<|rl{hI zEVk(4i!jD0<BT-cXyc7I=BVS2Jof10k1r~qzyb^~Z~y}UAgQF1NjAyklTSM7WRz4+ zDJ7LvW|`%cTtZpomtQ97C74T2NoJW#o>`=rW|GNfnrgl&rkZHdiKd)iE&$}7d`h%{ zo&qU=z@UT{YUrVeCaUP7j5g}%qmV`_>7<laYU!d02n1-KoOTL8rT{=7f(S8;S}Lig zri$vSr?#r9tE|5NDr>B?!fNZRx7Ld5uDbS`>#w{5>ua#Y4!bI;5f}ifr_6F1feI)< z8!ZacRx9nb)M9IGw%l&(t+wEH8}7H_mP_ur<ECq_y6CR!ZoBZZEAI)><{*Ip%Qma; zkI$lT!oL6qEbzbt7i{ps2q&!Y!VEX;@WT)<Yy!P1&|vY!7ehO-zX)%Pf(!TVD>A>* zQfu<bD5tFQ$}G3+^2;#CEc47X*K9M*6=RI?3nrLQa}E{=F!Inig8Hn_Hz%$1(o9o( zf(as=e1Zt{(%baaSeu-)&KAEAb<HjWP4w6|9v$)7Xs4|<y*?*FgbF^Nph6cf<lyw$ zc;}rh##N~Qaq$Z-+^sOR_6kk*;V&9pa@LGDzO)N}{87svNtp0LC!B;rh6?{W?m5mF zlK~AT7HbT4M9VIN`06Jr{`u>$yPQKRDnR~+2xI_0d+o9JzVg;Ikdcb$FYt`?%s>mR z005h@?)-?Z`z}4~IbfoK2!F5<b<bq{0r&La1207?062ol*QevVsaQfY^ZffoMGyY` zSgTN4<e1!EI~!_LPJis31D@~%@`q4-&1x+}VDj=s7Ci*2Ap%$c1K~%(i?}Xt7|h_> z{DlG&sNfHBNX6|?&^_L9OoJ$F*xoM2gtiET66cfK!l)HCd~pOx0!c$1(m)AC5Cw-7 z3?fGV<oCZK+N^UZ5Wx%n&;=3DfO0BWoDmxrK#Vbgd;=MT0iBjWlPz$97(oC*3}LvR z1fn1U0OIn5$i{~BYl?8BnG2G@iB8nb27fq4B|_o7p2ab1RlFD(5K$0I#E@evLtqU* z1ri?uAQ1pC0010#5lE(yB9<6PWZKBdg%I(Npk&$H;O4Wry?|~xKwv1B7D$U-aUcSS zr5q+fH4e&7Y#>=*lQ7Z(0Ep2dVC<wY3-ZQQ8Z%{2JDCW2hQ4Det(Cz`MJxdz03bL4 z3;)1G;JAn~MdA{O7*XFx2nB#ORz#P>Os7ElHL(=B^PPh`AvfVkPlNdpcvq~Z69n-8 z32}Ua5|e16-~#3`&~!vkI3yC03i2n5EWn%;VUj?Csm>ri3tHI9sJk>eEskQeTps0C zNW&G<j*1kd?;`0*P0G@bZmXmtU8zfF`cjcbQ3WqR0bE*84^jZ21-01As7wkjjfJeD zNWD%3TrjGpI`yegjjB|qO4X`b^{QCSs#dqk)vkKAsU5I^H@Y!}ShPR@vFJhvv}%J0 z8~{{8N~&BLvpgJ5ket38)Isoy*Mjg>uLk++FZ~MGz7j;R3n6D=2YXn>=9RGwQ7m8u zVpxYr_LqIFY+@Jd%LE9Z1>HF77#tyhDbNM56cxw;0I*tg&h@p3VZfheOItnv*%kl` zI6!S1dRyM^wzs(bEpCU~Tj3U0x3nd$a(~O*<^p#h=-d=@l}nK48f3b+)zome%h2Eo zS5pmTKmsaoRs&QZ7@rl#S%Iia2{JUUu#K-_gcMgWCg8sKy{|#?%isO-SHJ%K??L_x z;DQj?z693DfdedH11Ffl`5o|s9o*o7h;ab|utPhT;fM-M1OW{#r+i0D;`>m*0RW(Y zKs-E<7WknBM<NJ|9g+a}miWeHiNHGDxMPOs7yv(B$d7}pkRcbj$3!NGk%4?<COdh_ zP;T;)4HD&pRGG?1mU52=qT>fV003SthyxDbfG-Qg%v{d$KvIk2HW$VJ!)SK1Nge=! zP%(tfa?UgB;yjQ#*ZDp)AP5a!z!E+`B*c17v{Jsz=!G=8(F%FAqrpt+NlW@5myR^0 zA#LR}gW1aw__KzR%n%zZ`qV#>w4pc6YE5UFAgZo3tXaKkTDN*2v0inq(H!JjPbfeX zF*T}(T@q4*D9&HjF&>n>9h{ED5yXzRNXmTXBy-v!*Dgr54H9dObbBMY&_s}z-Dglg zAOhPyv#q(kZf)CI*X^D)r_G#$Ks&_PxHgC~q|I-R=t;%+UQr7m;A_|rdL)k22qcFx zg?=M0;2;9S9}HrJN|XS_+ChQ6N3sZy*dZuR5C|4F>F|Bcm_<bYc15TP-Wn7fyd!I5 zz$U^1(M>P|2oWp@5TpTsOb$d4B@g;n;tYX0cNr>n=FY}90@07y!L=MQfFoTCS)p6~ zD|$Jz4d~z*?w|l9G54uJ`jL?qAOM^p0S0BS&UUo;p%8MI!k5R;b?!L(-Va$`(>2md zJZGd0dlg6@wA=Q=Cxzv)339y~5+KBjm>>y|q(=5G6v`X^@+V0)vbO_qgM7g8k$j*= zWQ%t0V*d0=)v;~((t*~uJ_a2qL6|2UdepPs#wTYx!R=gh-uE8#k`%V>9WHzZP@wb$ zF~0H_vV4a$pZUi>enXzGkmp-J`pS=fk{rMQ?qeJP+^2y5in*WS?jz~=<VQd98Df4F zw}1O7Mt}UfKmYKL-}v_zKlsnz{_f{rAmIm2;zxffwtdDo5W+Wn4wqZ3#agSiTB`Mc z2OxnF=ztDLffy)(8rXmnc!3-UfgKovA{c@eIDs1YfF($Q7ifY9U;r&>05BMOFqi-> zxLP&lf(meh2cUPXm4gZ(c_Oxhk5>>rh=b*XgPDSaKe&TBScEpXgiiP=Q0RbyVuKK< zED#tdHTYIFHi7q*gXLs-3b=qBXkEZ{hRc<P(xrxMh=yzEhHV&!*>w=sbzNy_hjrLp zbBKr3MTdRJhkKZJN78{~h<YK$Ti|tdHWpX#)lf12mWYK|c&3JEkyweAc!`*piJG{H zoY;w;_=%vXA5KsU=pYZFc#6_S3#hn?tk{aKcsS_rin2J1v{;L_c#F80i@Laryx5Dr z_=~_8jKVmK#8`~Rc#O!HjLNu-%-D?1_>9mPjnX)c)L4zyc#YVYjoP@4+}MrY_>JHg zj^a3u<XDd8c#i0pj_SCM?AVU(_>S-xkMcN=^jMGfc#rs)kNUWe{Me8F_>TY?kODc7 z1X+*<Nh9)LiU+xn4B3z$F%IP5kP^ud;;?TM*&_FF4+=;IOmLAZVv(m83<Dtr2H_0J zkPIH_kVG&LZqN<NpgJiDkaQprBsmaOPz3}3Aq_AYlM~_(2C)lcc#{K>1vn`XEBTVI z<&!m{kRG9tLZOsoF$)IK49WnK3t^QaA$9{nZXwYP98nHsp_N9l0|2lLSoszFa3ZlV za}AMj>ZA(*5DgA-4QK(B46&0y;XWg=36uZ;hCmR5=MbiVmuJCq&cF?-pcKr&47?x_ z9p@7wNh44}mn-6yApr)=vk~904Xz=Tcc~PVWE6P-0Gd!3SSgoBQ4Ps(4QC`4J|`h4 zDG{-`5TYO(!9a2Z!3`wQm_3J^9MJ-gK$#lBnXF-#3!#@3aSI*6b6IH+JfIO{kOp6Y zoCblK!T<o@007&NokKwjmWdR)2>{>!Nf6Yz9cKvuvq=zkS(^Z0m$q;X!BC#pp$#WN zm=_@g1tFgo!JPo03&Vh%t@#zR;F$wKpa#JV=UEV|Aav9jm}Bt;Xz&Ga002q=cmR-~ zudxjFDG<yV4Ej(IQn?2OYMj!Lo{OQ1Lh+a*aScfM5OB#5ocRr>pbJz<7Lj0_0<jBH ziK9q?p&GHE0SXd*X%whH5Y-?NsOb~oDG&=c7Dh0kN&o<1upRnYmI`47K)Is;5D60^ zoMmwYQECz2ke$Ri5ZAe#191vo${jOz3(5%+V*mgaDi*cS3eDq}N8zK~F%BOQruDI* z3egM>VW9Pq1U}Fa%)p!^K?NKCQKkR@3j9eB(!iBwF$+3c5KvK~0<oA1QJ%^v2>|e> z88M_Ev7i|71OtJpW#I(E;HXIP1(?7N0uc+A@R}g;4*(F69uc7cz^EHSm!hDfcFCnV z3ILW$5F+_;0Kk^6aShD+5wY+Q_&E@MiV>iYqz91>YZ{ftd8q;+qJsJm(!dA>A*urL z3P$mlcA61SaHtAIopn@`Z~XUf*2y*mq#Y%x4lLTyts_K4#1RrII66caHBuOz!bky$ zAt5N@2x)a-0AdW4w1BSx7<>5rp7WgN&->ihIs0SReZ}Yf{=D8(NM$S0Dca3f;=&dH zupbGSMhQi$mhV@Ue@sEa`pbuRL`)@WE^f3+YBYllp(g=kUc)VD8+L%+4C$}X5diAQ zqG6Fu^X`qe#_^xV(H8)S8M)F}00m!Y1ohuhv_n53;x|zB5{3aE`0F^21_DM6pGm`x zk=tLjHJ{VLOQZ9uc$m{Wdp^t&lp-<JDxw(4S~L7DC)GCSR3o&l7}8(rV^}||ih_K? zXDXm^?kz@k=-;YB20X-+D&B|%(ODN!Rl~odHH%&onqF@*P!n>Z-v)SjLX{O4h!BS; zywhdrepbE7HN1{heJUAUSu7N;8nLhKs&XVexgSIRO<(|+5*^XER`_fRs$w3m2M>X` zcY!xhji2^(a8cTy2>wjeZEm466{2emeSs1VLZUR*L`py518MksR)iWWd|xBPo!u^6 z)s1#<fViMu<BQD#d-uiVXnbmc1w!2eyK!-K5WYJyjoY;%p8w@6d)TV!3Hbpw4!b9= z#ds>v^%~(Ys}ZsRIYotz0C%v4(7^lm<qg|Jtc6W@FgCT8Xeb!O1G}>DHVuS(=kQj< zn?iST^V0g@hS*6a=64;!x>U$|hfsnBp8O{GU6Vf>)dw}aSDHpxKi6VL=n=1c03o2d z*G1|h?~*lo$QvB2tRRCkh-&K%;bK0Y+h_DU7bLJdrdMHsj8GGLOgELO3<Ga;q_*Al ztgLl$VQr&?4wV%WBm2erA3&y{p{jTtN;5Etx8mJ)CY4#lLA)r{asoI5jF6FJtr5Pt z?9#q{uK0c(d=>rP-nF6qh7TP06!=Uj#?4RYcR>fPtxYN#--{m=j~lgeXEm`NNeDb- zsp9YAhjFrF7{h)T;gO^v%J+5~DDaMi0Mgu*F!Sn;i<)o|twzxur?Bu~pC$`r*d%pN zSV~k#ac5MvlD)SdWBHjd#wv_GTd4c$k@gtDU2nWNV^X?5|G#;>0req70Mo`wi{sXS zD)0B{5H!>V0qQ8muywDR@J#?c&YG0!pHK|!-LnIIOvR0=4E>y%gk@tC)g|A2CUmgI zWU~cD77U;d9-$VBYe^F#Q}?PeS{`t#Dk2H>(fAsC$yZnWyFZTs>M&#~u<<j#TMZKU z8@gpx__caGqyb~e|8&PVyIk5|>?==@&$}ySUjjx0Rb-^Fzx2`{f~=JA&p#4+E=>^k zk%PVX@l=f7^28p)Vax&x7g!%WPRQa^_KIVa^zfn$T$9Se-vzL~IkQwXY`YEiIRO0N znmr*G_URH1!wb^gS?hG6VtmV9iQPt1OeU?jjr%z20AYcM|3H6=*}(ao#Xkn-zTh2Y z-VAwMdRD*u47z~(%EtZ2F-ryf5AB8r5FUfG5p}M@|5y`l^UwFUwF$dtulgbV>ChrS zd<Q-q)RtSZ-UQ%ZK{s$-O88zWT=%PIVs^a%RdAE?T8J<W&&KJ^Nqpe8;wtktI1*pk z1Sh^e!ATweo__m3F1CXH3Y5Lu2mI#o0sOah!ZQAKtS<huJ|21Yov6Um7tLam5Agqh z{N#mVhy*hDrcfT~rI0|u+Kt<Pfj0oa6W_r7Vlw3n1qYh({4cn9Y&WQX4pxbJM8xm? zx5xXzJ0ZErVeEpOEP9KG2b%FR|76zz+*dq~t1q}^E2Oq+@Xr7JFLxZy^|@>u?kE0( ze_k8z%LgeB+)uh-?~SNk4~BK~$A7*b9b*=q%NJex7G2*iy8T<E$}D*pEP1&tdB-gI zmM>lETe|XgDd67{O=daBU^&EXIV@&5qI@~3Z#nwya?HPFy39(v!Ahdr3L|DEg<rms z*0+-Jb|v%Q3R7k^$6z(jZM7g~wWxfxq;IwC?P~eIRhG<JmBCt#+ge@BT7CIiW8YfS z+qIT|YiyZMcMLvtxP9u1`P5zh>0aNb-nXCr7G?LzWWHI)5wvkmGM{&h1efvebZ(A_ z)VytZ^7&#LY&0g-jf(f7e38rj0^TiCbG}@xguXI3@>~#@%Y=bsVZLopaOKwzeM&yO zub4m>@1MxmgD`Ir{>Q(snsTs>82oYKH)!^^WLemvAOPYUTxPCkw0+y}1_P5IdyT%` z>H^6uz`#?G#dX}1zO1>E>o9>$s2!L@!h4f9nlwN{hM<e&D?(2RyEG#^J{iwn-{tde z!euw*PT_r+-#j?$$pTQJIPj|ACi#?y43}^$_6r;bWa~5cknqRX!QW-R2_C}Rv0+*d z#dP0&#bp1uH4K6V{=n@L$JkI0+81;W$m9aSjkbAv<C~Bj1lqP9<pl9Kg*ShP--RFo z6qwuke^`~Dk%#c-Tk#t)TS-&jQSR%Y4KP50xU~AHp1>bv!!EP7FdKs3SXdh8t6(t* zWB1kn+m9x@Z_Ib!H(I`KyMgtxgp%HgDYi;yoFZ&+ZW*0AaxIqN)herq1J{1r)0VXk zw);K1umb?U(EXbR8oxnyko$*3pIpEXK9txx`A0PSgXf;VLi`2jgH!mTr+-O8e^67K zllGf09!fvUN*m517_)wsw0?URD{WHo&pZzN@v5`}ZF?yO4+O#hI>8MlV^Z`#tRbX3 zz=@+|6f;B)xD6HAeK5<E){og`4Slr8Q4~)T;K`0k03g#Sx+YT*&^V~}>PYcn9~&tg zp{2ON;lt!UqZ=iz#v3cUgC=>d_wtfVaawX_k4jE|a%vH`Q+;lK2QzY5_-XW)k}%e^ zq=91jQHh~1M)l{Ohjpg@40zOVoU-=jcHqHb**NSzv$F0=tpJpO=bxRrMWaK8BJXZg zv9CCZdLDRL^xxLzN=KFDp^m6PReG|5nU=ovxu2iY*ZE)bKPv{jt|b=x@sI7iI0A^n z_6oww%k~E??mM$j7}2>MvgZ8dM`__<8T!1trl@%LqwvtIMZtqeG&PkgcLRWEkCy%U zlNh`BY(z|&AM;O!|JQg_Cg=SIoF05o!iNZ4Gn9W|4XoU%_@}vcku@9?MIi&3B;U-m z4(CDis;K>?foCNvSyGG+y0I*7`P_R1pnkY*_!&y7zU<n+c02hP;a>Pi4o}?Tk@MTj zzPgEeHEknvT-s)pq*r%b-;b&xP3r@O_po&D*TJo2`wmM4v&>4^mnR1QWt%^ai}Hh< z^dGh)^$=eN9zLc2OK(L=;G2M>yew8qNo;-Vbt7NKV5H5b4DrP-sOxZil#;H=p-11R z5#niZvcKk|G+WB8U~{7qGt;9l^ggWGpFZ=S-tx^eKD94Q$Ww-J;M!7Khtq}a+~u<1 z@jso;o>`{H&R#6M*mc&Y!hdC-M`dl7%jMQLhh$va7Q4<}eF#178aSeO*ERU5>GAWS zGZ*ik4}X_*+%0ms_O9EtZ;y^&xc+PL?uA%BREru1-``D5z?o^eC++p_c2C~N(DF!C zs_XVhKQyf6dE@v}w`bM~n6_88`TicS+*4-S7xT|}_gpNzz|i(C_NnXfF1<Re?Q=7H zsmG@x7N+A{nY{m=Z*`WLj$dt|_dUN`6%3tA4Y%s<@h{zO9oD(re0S;I<<^HV-79S) z`|n?Ae`==d-#O!b-~aAAhHgO5a^3xa``?CjuRi#-bpPr@K1`3+4_E4?4dTr80w3-5 z=?xs&m#h~wrgW<}XyVX_Uhw1N%e}!*Pr&s<rp%QdggiTCt{?j1jL(D6nG4DKVRJsW z9)!)GvR?Z6a)e-R_{MhGhx^WQ`3Gkq%iJJxvCyY4a=9YeAZqp2t-h#Fts}dI)w|1m z*S<Z3pNQTVQF<8t-&6Aw*MH3TJiPwvUGj;T?d4k!V}5@dIT8E!*Yd+yK7aS7efNwK z0?GCN>6<SwC8`2-YC5wug$K$s_D6PDdhSNNgMaMB07c9E^PH{Zw6cqaK!*I8C7p#i zFU8i-2)4^dqHK>zQLFGhRSH;qq(ji&I75#{YzCNjye*n#3nn7AR6QC4d|4tgLlWSP zh3;2V2SDW$5({MF{G@=;6@ZwslwR4`Rg3pup`Eve00tJDLx=vUrb;A=;vS0(J8rBH zP2%78J|UP8UdqR>2+4GQRPOZTS)Q@WIP(pbL%#7mAsbvN-}v6{5he<K!>-h1&&CTu zulkK_8I2cra(vbIf_Osyy(Qusp+ihokds{EhxU?%M}|L7*~uZ3kNAcTqN3D<O;KK8 z-Axmh)A%!gMg`THLsQS94lBf#iLj!yndd;%v?u&OC3*_a8!51MXJp9`u{X|^Hm6~< zvU2+97_!U85e!t@6ll(D6U+f>`Y>ul?~$3HX(+g4$7C<vWeOLugUSXDoY61+VVRht zwx=857)t6Ky;dZ5<Lvixon`l|*v)21fLLd8TL~BKiU9ubR(Qu``;;?3NM(PNJT_4I zq)HljzTlO4_Rm_ZaY_1KVkg`tcnK#(7^_>nQ!Q~-#Xj=KbJy*f)u#Y7D?SY^v;DpD z`23^(xYy5I+dIsZdwd#W+45CMm(8_OQajxK)JvWITj1bu^znq2yv1^k(gSMXOPLqo zEYJ7(hSs3Rz21%SF*-JfKI$CozDH1#lk(wT*e&8nczCqR_QQ@8yPP02uE-ckTYBj` zJEvX`Y!~VG6cAu##)^H*xmI=ANKWKMy>EPFz5NF=<U8_on%bR~=VSQPso5o>v1IP) z_x|Dau8gJ^;lrD%XO0xVPS~Qg$@;+zqD0Oa1cno}^&6d1ywZaxIR-tPWJKqyW+gLb zM`M+O|BcOtUth;E(SErG^a(<}=HAm^i2;^DflQAMdBcCTSnY%T{Q&<Axvc)8{9a8n zOSvJb-{;4*Ix15?ytJ}ApK;NmT+H1jTT88M-AwzHvMqO-F$ko5ylj5@U6#$vX=I5a z(qBr%BJV?O-?)#8>9k!;<Z<l^IeXOK!W62ntnt}Gib7Clyy2b;<MHR8TVBF>d^}?s zt|E~a7<AJ4qKoNI`JURq#v=>UKw#2nu(U<M{EvnfX0gW)Uy|`=YLgq4a$%Gk)B~%n zBFc%Xh1H$BsZ;stLUEz|<sXc^(@F9scPC{0_7~RVikM)6(<Oh1nU}Y|T>W$YSvpK= zIVxT8($z6-`WUCWv0b$P*~#yk0s{YEt9%T4xBDmn00;;m0D=7f7rU2y;0dVe|B9G^ zGn>bWgJMJhEjDd8{17auS++uwGf9ISFsn%+R2gN8=vzq@Z^&6@?=#m_@7bss&Xc~- zh-n}wSm$a4-ZN2gsIkq0h$E!_pNM&WyrbdSElRc3O{>nv7q^}NCorY+_DnTO7;~P< z+7&T<pEaJJ=xUz7OZzZ>)B0}9oBI*-su1GO+wUII!Dtzq?*9=nAAAj^3>ZNK73G{$ zFxwi7qqzqzx43Etdp{{W8Y}ol{P60t9J|7|8L!$eJ!|s3pNZ8u>OWh3b-v|6N%+cK z&-Iam3q0!k52Lwi7oPO?{I`TRpacB^CI~_C7N5J+H%33#WJw|X5q$i$$WODa)w`{; zy%Aq#=EBYS*Z*$+{`M@Gxz7l6ee3s|U83EGH_Q9z?>3H8uP>^I8Ab4+vu=sdu3yv` zBudPk0X9Img+9;TON773wm6^qK9FdLP}HMx+@3!Ae<J2NZJKoI|B9Gon94_{iKySl zY>WL3A9HL}d)}idX2@EUoHJVic0hvup};k4b+M58ul57ntH5t5%eyYsyX0ca*b+S8 zj`*z-y}ro0tgAuXy7EhJ=c;ddz4u!#3wfzs&x(X8FILIrQH*k)Uld>ZUlFrb^Q(w7 zt1N77^%jev+ITA}h}z$vSAMCsvbt++?KUljPkvivXWw(F;bu-sZF<qqwNI@a*tr)) zY|+b~+a9eICx~dQiw)ih-Aw)5G5SP85nE|8w^H2}C9w)7AQeA%e=N9surNJ|{N>)~ z7WCP@C602*SjCTIOQl$@tYOEOpT8T*=Pc)v$f~^*#k<o%Rvt*auXwiRvYGnEkTANg z;h~t%9~Fe?5Z4kzz{r_H&MVk~@cBp7{0Ag1mz8rs(w=ImaZ&dKys+ku8&C9peGYb5 z?NSe!*zZCQLJ*j;BVJiyvT(#}!2_LDc7hl{5wM^dmhz2;)r?OhANV;d1V8X&?w^wq z90;n>+zdU>G(1$HUj63l#A#1CF7f7TzDxUnmhL275u~jFn@dq@*(%&S|7EKqssNuL z6+^qz0X>fq8mtaEQ69!Qz2~B(G9i&B*Wf14!h=iIzwUfukBEijcFY9){-STjOpwxM zsvn0-b2EOg4>@3Wk2;U4LURttk?_zq^Fx2XClfwx|7b0s8Y?9fl^p>}X{|wbXB{s8 zL7#W@a8x9O&^+E;(`>38d_HrP|M&D!w?F^>;BZEQ!5_$&E9@qz@89S)cV2E}zE3`- zo@H@7_qm-a{UOR_J>Iy@ZTpx-BTj40sbNzRE~|7KkFdFJDv+RM)UUmjtsLJwJx3`s z&+DVEGqh}6L-3=6GCS+ZaENpsKZkXEw?wF%=R8E@uv_IiQ<O=XY1m+kN2;4P=0s+u zX#41+15s`1)IU{XgBHUYC2bkLdestx7Ig=64&9)+R!e=bFxRje(ZQ|JAzez$(+CAo zTm%_X03SI&^)xNTre;<Z5U<mo)~pWv2$zi%w>-wk$-6SCAbEBS7hs=T9Ic>aygg<S zHLX$ov1b3#R4Yp3o%}l2MK9`{rIW{Ier;2&vj5yDLTXC<<jN2w>ekVT?#-OKpggdf z0y9H-vzV)}*JQV)ph|(R{@9BQ%FF@$y@N~5diHA(Ku@Ydg3I1wl#ao3P6pTImYK^U zbSAWg17i-WEMHmDf#&c}g-t&z`;@3eULJcK-u0~H_h;|Jx$hA%Igi{?P`bVV`Jsy0 ze^p{XP8*6*@tHDo0V0%6F+)vfg@x3}iL6@K?o2VOglnXJtXMnTvoF4vSErb-VjC{; ztYA~PPUG~djr+KL;NQG@@|y;W^v3Bt)X`f;`l=4e_Z)9lITFokEB>R)GJ`Ott_sjg z7Sa-rGD?0lotGOmn7X6_>CP`P@0Yj$*>p;6d<5{lZoB;&KVzZ;M2Xk1?4(E{oj-rD zQ*1wf2Z_fa6q49@Vv~oG_1w72&pSnro4nP2f`AZF;0VBh%K<HqOMZ5whN^$IN`Lk8 z-p|f~Y2b>F^}H(I3;=aLZVm{Sl(%OW+~r_fXadIYwT7_nQQMZG{Tt^Nb$<15^{s-> zAAhsr^6Q>!5YXM2-u=Pj*L_|-LA`GI&3ehN-VqfOnG_GGrj%XaYtz=~<=^>R`wwb< zf7}{#zv|WI!IR*BZ(8YaseB;o07M!%>xrD?!QSCr(P8XFrAYwpxHTZ!Mf!fQ*BzVw zd{F8i39O^%LCD=2+J7=I<qYP%XkpQy2*Zu>$W#F5LmQ&sWM{5k13KuoRd5nVK$r<Y z5yhisGC|o{y<Un+;$t>3LAjNmKPsQ=8F#L`Q?Q4_gb+DEgsG<S`lZKggvscMw{0ae zuiNw3+x*A0%=WTnn`NE(?I#gW+RJ}UE*t#beo7bYV8Lxyj3jrsDJMIs_C8)Q)7|~2 zGdpUOY*($$?MxRv>8LyYc=hD9oo6h;&U$m(HT%+?=k+H$8_zsmbGpCtf}Ppf<YW8E zWq#*n_mj?+@W-Fre(%h11iRSDwx2yDf6tDd?7CC<__Md}?>TN}SH~^eFPF~!el`1~ ztLyILF9Fwn&+`QDc8~byMNTHXKAxAX2dVlRcK_NNfb#3<*Fanx_xIbaC%>M)eG?G& zpXA%0PmcF}xgi)?T`jee@=N>QMpk4QSbBxJrTzT6U~ARy_x1#>2iZnfLtcBn*`#U# z<FcFCV2;##K5gX0<OVJ<;;4-5H`U?u%ed;T4@+84wIA(Be~ZYgmiollJ|Ppc9?SAv zFgpaF{Gi`eru%nQ=i&B=uM00~&^3~8s9Q&mEg;-pS4$SKhvbSja4rZVJV4btU@&!~ z{At;h&12&aBi-`4FR03F;8UK8w}ix!{_OiljGXwkkrmifCdDTv^R^8(E0%Bi1ZVZ$ zyWaA>F+D-j<yNBX4hQYGA|TSsO5Cq(m}<lxAjGkUjuy2c925WUVfel|A;bT<%)73f z7aRR`&VRGIcmCI(pLZX|Ui}q2adRug=j02YLlFTf;B|nPByX_s$BXiQPab|mKi)m{ z^icf5^p**qR9^A(;Tf549e1C9OWnL0#h3iHiI3hEV23_`CMQ<*aQLW{2F$yuPm;=p zClXOr0F1g@?q_1&aN()kuxWf4Knd<VBlZ=3758gb$q9_T6&ITv9{UTo;T>pP7`GPz zNSF(QeBytI(j@N2s~5!^PsMB2#~)0Imn;-9KO?A!h@YlmU2Y*V$*AUaTsj%aq3_zS zFlik0Bo~#&Muk!|$t*+%4{_NC(N7XAAR?~(ij$0>iFHdI_e}tsCnzZ=tib}m!*J`w zh>dmJA|6vpL~uChNHS`Yi%lg#0S;!2hz-RfX7HFv4*Dd1*J6vl&)&sCA*cCF%s3Ab zPfi)*U`xqJd9Ao}?%^BWg5_E`<1>M7$`NB6Ox6sx7mu0dg!khyGo&Cs2m1k@9D6G~ zB0Ts6{A$kK^xl;K<EiwVU+Eh!ua<44KSBTo$>Aq{#l<Y+IBY~I3(-tQ#{rn>b$Zxt ziby!N9)QhkC3jPy$7s+~Jn&&U^ffnOj0N|kB%j<u{!ofZAECjMX}^F#hDP`xJfn9d z_ybiiWrX&Im%w30H6UPq05Hwjt$xGP0L%nCma+R2qu6XJv<d*)N$6}mlDex`;?WUg zROWihuKJfpM$;mE^UQ@0XbWfV)$c0`+l0jveFFhLQILZVyFH4@q$2Z(i1$QnDiz5# zM}H;3oY`Op7V_gdG7Y$9>?~Nnj;vr}mXspm?gqrcga2&hQ+v_}#WFm%uTK1mdrwAE zS@2RaDvgYcoyEp;VKYQ*%NEj;PLEwdgaVkD2y8qFe2NA=!-1W`3sh3DEh#8JJbHc$ z>9CI6wL6tk5$HKoGd+Kw7H)~2TPjvCy0?J5oWut(3;>qLLQt6qrATZl6X6tbBb1j| zL&NrR3!9Va*NCW;`s{2H+KG&v#-m>-BRbYo#);TCX6WkP^FX2SNQ&_4a)jH9{3UpL zXGB4JVffN=+{|3WiC>DF{GVl^KGEIg!dfbVDYvi<DX4TVJe`XjBVF$$qo;k5u8P>+ z^@3(3P{7VROM%*Rp}JJ`ns0s@8P!Wi*{KLt5D}@g{75C-!4X>Aui#90iNw9i``sCe z@Q7(HDvygAry?DA5NA4+N`e*;E2hb)>-3}vBDRBy$RnfBNK7OfnNFvVke~)UaAG9X za1H!|gPF!BM$yV}$_VHB*t>JEnY+j^DpF}%a9@hx2b$nAHNe8KJm^e;6e=U{S8&Ws z&^UnUz@uZBV0}77p9BloooY-3z)Ec9V9BHC_}#c29wMD{tAvfqq^D#PQTLhI?QD20 zpN8d7lU#qL#X48FkDM6`k1o8F!Afn|<mIn3D#_-d#sbM3w7SlS&^PPR3VW+K%uqfN zr<;m;Iznq^BPZ6w-_t{%`ZS*14&U%eU%Ay#JRb9Dq~Wki(^5}XZejZI$N+#I+Tv1m zX?0fsMY6~Uo0Ql%UhE_Qw2`3ioKr)Ih^R<xEFOHC$O4#94Lss8CG9m6;ZM6U4FJsm zY`uOru>_e(M-|SZSicxGsg*0s4W3c#Z*>{0sJg-#>>^RHGW>ck9zo_oLYeUE6!=LJ zv}p`8PKDP~cNdP>cq%e`hn~ty9HV0!sNhAd8lyFEBp}#NEi2&@5i`mNBQZn=4U0=d zm6^k>SYQ)1$Zbp1dm{Vn+G)gm$Cstx-tq9?5@8`!ur3!2P@p#JbzZx3j|%S~qf_zd zF)F+nkG>v-jU%I=4agl5?4czcVAV@U-ja8ze!0>%gRfU>*adHAct}JO_ulLs34Y)# z!m(%?LPS5(iH<uLy`$AFRT6%8CU}unXQjmUg9AVDf$wS9*W56N<<<^v6|i1URzdWx z<7VM(?08b=4zh!TbpRkD=is;DrI}3DKQ7kE582FXEF8f;kq9b929|FLeq9fCy%Zp# zT#%&}`ICxE3>W-B7yL;Lxam@t=hI8Sb)CjXU}}^Qc~oR33)w|R46v~;cCb?b>=O$a z!KKtHW7AmeSqPw>ecz@YGs6aZks)ho5EC{ypMo{NggCdAVk?0trC}$ySOy82$Bt^I zwHHP_%*6NCs00?L$DCA){KtL()hz+5^`)~Ar4+a)72dzz6b3;2sPrf%%z+DYCPDw* z;^<nU05Up^gVr0vTqoXdoWLfNz#o-sOm=ovRB!_Y8&5^mo$Ze&-KgNgk6c2wkx|Y> z$gU*pp*KvXL#x8EJyF;eiTE3Z8E)DGw&;;lx7lK-G}<iI)&iBvLPSxK6L@rT0>qvS zu>fvausi)(NIm|wF2{)KW(s;&Np9w}4>cgyILVNr?Bd?~4i+XJkCxj({<w#k#A7mn z_zOGT!zIz#$-yO2!S|I%rd9)XA=cx{IC-gZ`MUwdx<R!rY=h*9yM-C@pNDy=8CD}# z*Ohv{?H?K43MgMm9m7nHJNL-ljaXzh#?D~nB*ri!r=y8TXEt(yjc~<aIxqFzyvxMB zLWM@&sNuq1%_f|27{1PdhXJsYR5%LRUqOd6NH;DQ=EzBe70^+wTTiCRy&%I97Z<^g zl!1qs$v-JEh-5+kt>C}w;a8O7YsN68_-TNRh~sfO0N^zj<xGXw0H|B*Sb&Hz4n#fT z19#%cDbu_t*$Iw{?sc>{TA$r%&+JUJf$3AQgW~m9BX2N>_vh*>LW&UA$+0tBxC0lI z994gf32)+}nw7B=q}w%?1J8>q{~{Q;<VyVAaA{Y;ow3jW6~uKaQhx%&;Ix~LVw6f? z{^UUi63m}g^%~LDypH_Z#K~)j8soyBtu(*pzz+VtV;c=UOoPAX%oa7kC&*Fm=)BVw z=sFV2j5zGbf>=>^y$DbpF36b$_h%u@w5w+DooBcEUtoeS?({?MHz~SCO1}=WwTLQo zhWk<aQrQS?l5p~Cu;F9Kx!dp%>TJ;};-vDJT-4E0d{-P5)yFPv=W|N$)9S0(^|cgi z9KBe#88fk-T#CnBM>qY04H!=q?`HjUlud@gL&j~IDztEG-T~!Wf{VPEE&az?w*tt^ z#W!`b&WF|=jBM<PXpB<|dV^dLej9gUZy+X_xAnJU>`HFyT4nXtJZ~nsaW?4pr6;Pc zRn2?RZFE!^5m~&B0%+*FMC3_c8hZ7<1F+jdki(pNh(ZoEQ*&mxu#-$!DEp(+7f1=6 ze%J->&%9+3^|5^pyEBIhRzZ{kc~{4<wO5|RaFJugm)Hk!HDeF{EJaw&_kZAEpD3|+ z{E&9rtm|BODHp|IVd}Xse-?b+0_l%O5Ah)L>)03k@xCblxCNj}@Msm?l#DM0lav&v zdSn_A`-F_tCyiP#Tdtx2eJb(^7v*Guj^MVZl2IMNhePA-(}f6w^lT~Zx2Y1y3@vCA zDT?nhKE_OYO`fk_36@!o$@3XectU&4!t~;^C#d5Uv{dvZcqsMt7#ZzPo_SUe7nz6o zkp^K1SWHXRxXOLGS7V9(`7^{WmOruvF9<LpCntvtctfX1;7QJ$k}WDqeXNa)yiP`T z0!SlLhY<}@*9-wzU^4(Pqtsp<V`h?|VaztWv9<Q1&lZKB|C{aiKXY&CQ%xuds)Gj7 zIMZ#cI$b>2gb3ZW$0SHSPvVzB^#Mo%Fy2f?#nG<kWT3R>qn>RstJtN%x^I*3W$$ee z459zmIDwfUkH1VFuO6qBUyAuf4T$x@6;8xWhU2V9!n+>?%&6m*$q}M!sq4I?mlHu| zJ~7mHOYiYrV^l%E8Eij&<E**hQ!YG_glgl3*Iq_sQg8F|F#wCxj1TH37aOf4@bQ>l z7N&U=-NHjXeS&_$YosSH&QKcr(t@o%;fz(Vi&Pv&NwAZL?&YC7xY+-wrKL<nJn=@- zR>2AJFhA0kYkpZer|MfYc9aRrSx4OkfYx<X4iTBTmE23IEg)jo&Ue+&+s7&6%WvQ^ zw<{c|gQ0u?2%`=HJV-t5Mx7uKN-LWr{hfWQ6L$8F>nJu<98Jax9Omurc{RuIaDSlm z<NRA7@XLkc7yB_*zY9t3dXfB(Zybv7WD>QbCe+$H?WBaPb7F=im~oP5-;wjk-qD<S z(`lyrfQR^GwqiiV&iXWDO_=UGQ1wIj=NI96=gu8gV?&B4VA$Jo-Ch{o*x?$ILNc7L zw#t{WD8h?_Z|7IJG#eavzkkI+&81YhQ&Si%a=<#y>MY@?bzZ$i^bb%<#|Y)PHT6|Z z@$?8m(W+Fcb2mI)obA+>mzuuSTJeB^{Gu_~WtB}dh*oYGfKJ-US=XrBT>=kh%9@t) z^Zf4^H+VET`2&-tFVgnniOJ6rhcp*yr7BSo+91v`eETVeZ|5DaRJQ%SlJ3Xr0=(2L zwKLIrh9^Ajl+3%A4$578ATqBLdg;7`rwI~J{QK(@xBrB!)Gi0h(IQZRsdH>$agP<q za!|-EzGtb#D`MeMalk*jC2?wbgZEA9OMxZh#NHm-04ia@H2cVRR$|`rtCi}bE(Vt1 z^t#z;uMFwkqrRG4*h(C-sb*FHb27d<NuxGiK1s+8(vvA_7>~Rn3jBN()Or>)VTSAR z4NMgF%R6f(?x*kv4n)4+zGWHs$9-j=BPP3UUodZhoqLkA?NgTMYiL@WIBu!TFQyKy zF7Gq>OIW_c;PskI<l=4XC2bGNDvBmW^amVBY?(_GGLo*mC}V|Dd66?xKA$LhPe_)5 zcTW@$5;j`nJ|;qbTO^7myt1#!vURb8(d`L;6b#g(M&03rFtO?zh8Ei<s#ZdVNjWp| z^Ib>Hg=K5=1F)&~xhBFrXi^`j-H6#EoWCDGm(#!=F!;WbV082ZGEr1N$K9;NNkM>| za|Y;EbT?C2081W)Rw@*b>Ak~3#&o|%o|CA+(gDAkZ4+&hSG)YkEJt~^*|{lXJo{9O z=M70yDS;PEa(v)$n)r||ZgeBM$Q`DWv)wF6`ff4E1eb<FGCaPpz4&|VDQzY=J&a$q zhP|sK7y*RhK^8zF*BuIkP->*@K~rBY8oLlo`kXB6hJ^GyBE8ej39Ktf09^!cNgyQW zzDNM5&BO`TYL`wi%!#W-D<tN{-<}YdUC8nRmETtBMc#PC3|zi#ldE4>w99q=Ijb3F z_mc+7a`6>loE3GDFvhD#-Tj!$`@{hav>aENU@`%Y5!|voc5ypVvEN9@8UVUC3jORL z=~U!JH5{p>6ep(S!UK;Ui4K0>{o_`|ftM?g%9Gcuq-2`{9U7O0uY4~DIFZ~BU^THv z`nGoxiIniWDoi8!i(q{0&K?%90SEl?Ca^Px>4j6xd~5^-q6o=G7&cucln_m&5mO+F zR{tLQe?!fB8iV3G{YdAPgab$VJC7hdj!?8ShyWf9aN~vlR6%6Cf2R6E$J8u{IcL}d ziBi5Eag3FOhS?m1eO_9$?mW0~>rT4GmDSKbt;(h+ayPuxJ;kSargA$1fR>`CcOLEe z37581s*Qr|WRamz^sXNcqhKXyZ=(567OU@EbuN=Sd?Lp^g?CoY87Rt;KcTTF5D||u z0%{4<>nXM_3Sw^tz>4<-=#hVnr8?*pM^qK85xXs;lPfTix9_p`xcA~S2-v|BasB5s z!4|vQ&Vj;gVSUzsuuB7oP?MUdY7vJh;nQs;3<7UtYZwze>l0)FP6k!%%5{HV<l%0C z41H%=p=|E-!LIL5EUx5=Pp%|rz0rI^{kUHYDOGH%rQCYixf+Wyo*fYSnRaGfKztfu z#^DX10Sn^;ZLA?Bv$~Yxg&X2CD`3%SnvL#|_w|!pu=~p(d3{$fu;`I4(*$wIK)n|v z;GY8U?T5QPKls*di0UzSgq3=Ncq!Q%0k+%k%{0Pa?=B{Or#G1%d5SQi44mE#WBC`o z$++6{#ML4W`bM30J%0+S922BA_+yC15@V<hYgRTqxur70HSXz#XShNvQM+)HZ07nI z&BW^BD}f?!MrYDYX59}qJDc*=trj3NUurY1^?%mAiBEOTQxi=R7?jhpNO$SpPbhUR zl-nE@Ggsfg=Y{dC5n)F!N#lE@4v=u5>Tuz3CM>iAG1N!3N<X%Hx|Ba%v4_JmSYpZ% z9{Qmb$vXS)S%ed8-dEsq01hi@IaWdoW*w%x=YUfk?s#OPU_BKA{8+wnQCAYEXMxq7 zrv=;O_P~CSJB6m=_tp*$sCY-*E+1NViaop@C%{WoQC_?#W@RD)s%#&j9>I3DAyrg2 z)ct<$ZvAV9xRxO8{oi@$iz-#Og)QFH9ogR$&m5LHh!&Grz9@Q<HEiRijs?0k#HX1D z0eq)<phEn}Kenyu9zMa6G)c!Uw)JZmv>^i=5n?ax5*^IU>W2Sp6^yY=qz&vy0U+|8 zla#As_3KboN+sw5k8vbp9BbXtPvEa7>){pktdxz#PcYKY%@$$8=y4qH`}y>90t#;5 z7tG=<ULNJWlrzo1h(syd?G0m#$bBcHEQp|^x7i5?hu)9pclmN643YYf1j!~dXnjT~ z)`?de8ZBUdVG~4Gp%_bquuS~o2qf>1`O&%6P?^RK<QIUrr|Yz@QFU_qWfMy$jeBO* zt^UYe?w?aV{m5~f@v^;1Ue`T~j2tRV&;c6WZSfpqTD^5z)kcV~9yA9>L#cMXMqnK9 zUnZ)IQG8vSe!;`@GKWC2$NpNZU-^>X3Y~EhdR{4qy$+a#%ns;@D-P@#+?qcInb`v% zz%4gzha3R1IHbP~_xv=3MACo>T~I7h*gq(!uH%}q>>f9GL<F!gL|xMAw~kb)o-<i! znL8V|=;xdvBeXGZ;y59ARUkiBMPUAws<1@|lrvCeeolS8(kjfEtMr*ShjDqonBs5v zdvdt!r?k(-uLnKMl5Gvltv-ASsoW&ClE?=?3Ik`l0XfIY)RiO1&UAmMm{&;GDcI<V zf*Aqk=zhq(4%x)e`jUi>f&<nz{k!WOG|p5|!JUgglavlyuzDLsv5=|$(IC;jiwQaA z%5S}7kRe)c{3Rcci%q*Z2wfAc&fC^HBOZD*$uoyAT$|oz-9BrasWx0tU#4OUlTTvu zr&yO?+m6Ot?9rBX#}V}^^%8!?DHdgCc-33JK7t&sxQb-hmRa(LjzZF^P5==QS#H*` zYS3<zwJiPcMJmjV3(hf2(sS7}z--y~yFsNg$(zXtp{U*6VdSLiyAvT{RG1_FfaXG1 zisoJyde)g|6*BCyhnhmNggzMr#GyXv<())RAiswuVqOm(r)ygw<R6TthtGAsL{^g{ z5?z?buT+Y?rKZ<$6Py>aPt`*$sfq0La<*|jqXg#XoM=me-XkVmsm{3{SHnMgR;6|Y zHq_11;Kb{ZGZtx}H=OQm00?T6lm{hjx<IKZ2}0fRWfBtKKr8?xq=sOKIwrmzl`|5^ zF{uZe`zkz7O)?-#Hs=sKdQ|_;W_6w|-IQxNrd99`q~Et8Ie?UE4^+#QOnPDu2_QCp zO3AuRJ-!(TDV~qJy@gU31^Mapxo{Kf$<RC+bJ)F2hq%vy#n93kP;k6gd+pYP*#vzu z(wy35i-+WBJ+dvjV*(s=BSKS(WnSHBo-JukiYq@8(LBN-E{sWZam70aja&fGV$eRK z07zY{B^M;>NN+K)fGtbx1|BeUSO<$27=}VPqKcjyh;F=Y#-{=U2I_~XD+xz<N#Cb? z@AT+FC-v^Q%h(G+{&{wNo>kEI-K|=JK=(x`MfzZQDc96W-;~NZHSHojOz~LeYcN=E zHZh<EqQfI80J}!@9K3v6|61HJ9^{;_fuluYadEoXRM$AM(23O-nI^3;X`rTp4!aEf z7R>RY3!02cQ>!4sOt|Sv+rDZDtq8QKj61e2KmwAfM6u|G!^f=(;I4ZQZ?|8jKq?!L z#Jj_qUa4+hI^5(U>9)1^a5l^o57#OdPsy>?%4t~ffcc0q9K;O!Wy>mNVM-QoAF;$! z76#o^m}ca0GgRiOl{obk6tzt5R$lx;8u+!LE<eLW+KmJuu?Cz-P=|FWv0nW^f8Sd0 zNq`M<%)Yw~fX(ZnH$2tN@sRNdoGTCP=TLNxB6cVb;!0uY)e8kJFe>FLs)CHW=ve{O z%nu$idfkIR`auPex?R2*4aU-$HsFPfCgT;rL@H~8r<f8QFBk!G^%c@k6LHHHfvSw# za>2FrNr!;iUpnMFtGF$cr6M=Z(Ii!81zeQ#^a$_9RIjD0Ku-335p|1Xmv!(rL}Gqp z=H?#ATjCxnE$QGEsfie`3UtcP#Tn9|=9l}5a_g5Q6HK|?hx6JLI?U?s5BK>h86n1b zfsj8(AW=;cgiGMrwDQCGGAo8f{5gAvSJMeP-Q&Df@IK+hV>DG&%i$xwaf==YB{#9Z z1VC4NGYhS>y-RV9D|@3$vYd&^>sls6?V)ubhup{@^9BtZo1g<A^AxBKK7QPx^)I<J z`CRF3A&}D+ghVMg7^=HBXRMq%CZMKG_&m1ved^3_WKk3LYJ-HemY{}dBkxlOPTq+y zh?1QX5LuLY<dNePoUUpKp;D9jR&vfK-0Gc8I7@@-)C<}2jvYA*i_W$;>B-LSuZW%9 z9Rs`Q%Q#)1bdWRgD_wKv*$KjQ{mwaU)yfK*;$X;49hnbFr{1V4`nJcNmoyg>x6-oq zV`I(5+xG=02BBbj{z-hY1uQ^}fm7&tmZ9Ih$@uK-_%&jBf2E|)bfUDFndkMY)>#30 zS&*jKkby6_N6S&o-QxLbo&`%??XS@J;FF){!3#Al?}c6DqZ-$)K&^nB!{?Rf(qs(S z45~8Z`PiKd_hH+e`d7Zt%<aSgJVc2ksJ_K|7r0NUNWnY0!IbjqQB~5;`x~dpNsjDz z)^<gO`;aA;rBoy^Us;qtWL^V$DZC5gPCq2{Mirbl$pF_j55#MXm4u!}5oKFCNl6Z~ zsm%1LfgTZ~2$;i)-Ngtr-)7Ky(1KPir9-ijdmJwW2HyV%_F?W7wPrkvI<AXVbD4!! zw@**pdwF@tjIT6W$_l}dDCr0PCYsPdM@^p{33Yje8eHiI-B}yHF2JxA17CF=>`Kx7 zb#@<#a?s8G;MKFJk^8U^ceJ4=LnNX2GD4xf-`es)Jb8^ll745xQTA@is1GD=#kbl? zo&G6j`g%Gs&#UY+H&Kt6STtz~l4QTU_Tb!6_RVPhva)!0vBb~H`9~<J0U?Qctb_}Y zqo*!gc{UsFPZ7{$4Xj;)Iu>WyuQFcV6Ldg82DnGV=aLQ)CeHi93|ZZ-SLBb#Ds3E= z3toijzpC4@X4oQ<B9iVHBa(Nn$=^zwrCsM3kdcnm>diM0xoKsaJG~=+;{PJ1$i9q= z-R1Gy5WZV?au5r040I=Gx{D_!Hl^^m6V;D<y}ODqE{jq3T|DNui=`OXKdG2Ra5yX9 zpC+e~BTa@<*~T@d&xK8Iew-Xu2)TK=*WmL9bq54jgSuckm^p<%>9X#0HswHgFSPE4 zj5Pv&87<AZB6ZI>@kZLkkOi1MaPBVz*jRXWj0O^SpXRm+bsadVoY>^j4PGakSmrwd zTjBz$aTFfdsWUO>{b|h4)4A%Ux1+lMakC~%4-JXLo0Fw69@FpW9GOKKO7|Gfq+^f( zJ57=^?Pl0!WI7`XE)&nU*B^1-0-3@(n<*b#SzuqWLe)4NLSf%M<$`T7olB!;3eSc3 zQRC|8OQn^l(5v|lG1|?n*E-AR-PpMYmi^5wX`ld%j4{p3k!)(pR0&>ys{0Cj5Nn7n z1-Ypn)U=y&@>F=>0<rFfU8KC*C1;CAIR4TdGF2$K1RQS<%=e<Erd@mHM2C#HmfE?t zPJZG({vCg+K0%|~$eIh$6Jr#G@Ibokj-RQpf=Xn${&_pd)lN5EW$N=aux3ge<*-xx zwyB9XNI@Xp${D&g04}DQeXWGvevs+;nPJa*Y18NQ`M;#g&X~7!6xuTPdv&$xB~Jzv z7Sug?*qw2aqPV{gq-GI+2?6VOWf-u*Zg`t?k1n)AaZxb-_|L4Cs`w_55MS0ABA7uq zYyT>dQ=DcG(dtTITP1qY7#`eN7QVj%pgV9G&XiL__K;Tn&tj=bPZhwYK6T_nHK;Z( z|JYC6M?&-{FKz2Tj@u6?x{@xDlXyjF)1vrC1LdVtRbG<`E~5}LXE%~p{YrL{_qv>e zR{F(mSa@*%KjTSH_vc5X1n=MX`vV!xwNh~szX0A&JZd6M;%G%qoJ6vZn{}K^(aRF= zPS8_!D-cf9z&jMUlAwB}cF*IW(UW{O(VUdD695j-b_8gNDu_%U4v0m)Eq24M^VO?o z(~lk$e>0)vS`V5Ub~DBWeC0;tedXeDk~ywCi{}d!c)5MOm5F@(vR7;G%h}46$UDBo zltdG*uhqJjE_roVmu)ew56LU9gRZ{HNfaGT40sM!O-*VZW6i%w6s-p@RT-1;^PV7( z0Rm<|F>bqSKe+|{q?IdjZh?w`A6ucDKeC42eD1Wu5N_T)gD$8Hh3End69jYH{!qJs zDcH62&MH`{!FXXK!GZLt<0KoL&U;v_?@^(zB$iYGqc1iR;Qa|?XQ<rj5vr8C31b|; z^?1`g|8mORC3NCpOPlT2iPu?>OOK8M+#H413Fo_E4u~Z+asT61d)f`*rt3vc#IIC) zMg|gY!j4l?%ObymT%pNliGz>IirHu;R&+71MQQWf4E9*6NseVqBGZ!MS4GjX&=4)S zZvS`DF^{Xin{0hy7oC$;W*N_1H}m019`(x7gMzHgq>n8bGb^y+e&}(w)PsU}*~h3; zzrPyi_d?eKN>BZFD#h1Y5Oc}op8hBdE~M5laMkAhg6U0U05#DEY|PjmI1^D6q?%u- zVjKWEe&>{NLLhsDqGWLuyyOekRn}tij_Ry1oOZty6_MU?(MIXYeXdE47V#C^715Wy zcfYUGVk#Q75dSrM@5=%KU%%K(I};uRb|4|D8Bq0lHDYR#ZMRm>I>%W`>ZPRiDP@@a zT0(rW&|BsF1MTl9*$i*7MD=%Rt-EezP9h(A7gCZx9Wy-ygg}@YdmULYt#Ik%51YbQ z(>WGk9c8Oh!~yOuh4ZRI_?2g^AA%WHVoE%)Ee)+7fw>1HAkVEhb<37G6|2;X{)K=N zR;PM63Vzh*?1Au<6Bo>VVF6l@`_NrOKnwo60FRfkyN5$TjI;ux+cfBU)eBY8+EaNL zXhJYEO;8#xKoMXWr&y>e$LSee^tF<<E-`c8Q21P@RC+vIW>VZ=iCZ=h6D9Z2H@9wg zN?gCApo~{M;~$1!?f<B{2hayB4C6aT1T{<5yLP+~K(mRcC(=mqz*&}4voAF5#f=v- zc2$50h;(@`VAt;bW$s1B*?oM+y?X?5>oUZ>yx|}I{(inD(d_*1pQ6Lif#Qx+lb;nM zjhN{-bU8Z~!DUV7ZW@fWJa_=ZOkM;gYM|#FeST_Qe9SJBvNTO402gXB9QNDd4q0<X z^Z%Q<k<)DwV3?a$pImU{%xA|)5NS75!W|&%=fa52H&69Gx4Lhpf<NGr=b~|I<r4n% zCA=ZT$%GhZa@y<T2*tInBOY}q>bc=d(~8e+BkECDQOgTa(jB{jK0{T`>KKjc6xZNK zFT@Yj@0Nfs=Xh<7tHEDvr70Y>s!BUN6J6z`76*|(OS;~nJRbl=&!EgFT|HCx_;<va zN`%d34-4CS2mr^Y)pyy&d_ZAfQq$k@qg-0StYNwe?&bSI%&Ac%XAey<go%qB@EcS0 zL)<~K^60V_4h7DemeL{sH4zW6yo7>`5blXW@T3~BqQ6VcNQugDPKsit^KNb$i@sYq zW|<t$iCS`R6U;4f9kfwrc<o2TPP6m(UGHJ#fcGHe0-3^2(EAB$FPaLfh?5q^Y0Wqd z#T(L@&WUM<B0m#Ssn=2mDwCrE#l~dbbPAjf_sft)sFWh&lN2_FZ-40hVFjW;*x2kJ z*`N8HfKa&{=WcF_8{SNnCeyQFgZ?%e4C%9VffV#@+Te57ij<}D&JM9CTg~z38Z-Oz zNQG8Nc>yw4gs=LPg3#*kFdR2!xDKaFt5oHT=B5F;DT4WonmblXDwRV7W#oXB{jzG+ zsEUzkZf@jpX@!iF&0jz6d1<QhK7~kqZkXoqVj7eosr{WyW%mb!Qs+%RlTu{LUkPMn zrD<)Y5?gNAOzbCFeXw?m`toD%-S{ttSm1GrP9c$(-Gf=o{X3W;|K`ejH*LO@X{p?g z=fO5NA!oDGbSt!`XOGrL3t{Scranm3Jg$%p312*CMd~dUvaeN)gA6I2e`#(lnfLlX z+<$y^@bLZ_bud};H6_RF`xrCw@v(A~{~jB@yOMBJ_A~F`4HZAi^k>6qXCaF(lXO^y zbivSc!fF0#$HmjQ(<}QDB<TdLNiidx4pL%@lz^;@x*R@n&!jp>q$nW;Wc-3_tgfDu zVgivDH<KXTZ|O(>$@3-jXT#*ZLt4*C)wo5I%`UINGyGIO=x<G>c$QVe?O9b<$7zD1 z94;eiu2L`zQ8oB^UEFU-K@^}se0>QOf7IiJ_fE{E_y(pNoaDfRG;iGe7?Py(m<ltH zPm=o#sBVeJQ@x&n74wKfmUiQIIVE{QR+>jF*5yu|6i?XiVuA+9ixTSzTv9Kbe%iD; zdvP^YmA;W`dc^!pyw>d50@)K=opOX%o(#1x&cp1LEV7C3E^r&4X}aR?vw5E(-}C~- zw_k5M>{*Of3=6CbfO@;W6`GNmW?~)HtFRFkiSlbC<+|^N@Xc|%zOPA#qV;oecMvAh z5X1V(NlmQ(XqJbd1yZ?F0C-yl659b_>K*QwPyi%L4!54ux-F8%w%8}}pO|ZHlIUZ^ zu*Mbot$aewNrd>2MmeO;NvhT$Z*<vsJs9gBR%2HnWMrwTIKo;aAflD!W(^GC`YQq$ z?KaDoEsUcqXRNUDk0F&OwQyqvqw8@i382F%Y0{qowKENAPWLvSNjVM(GiY)q7X4)z z9Uw7(_e{<A1LV7;YKeJNhBA;_Y2k%HJTEGDIP9qa*t7%{%qJ=e5pc1i{K0+yW=+(T z<I-ZDgJpOtMmOJ+G6QGj#p)@EvIbK<vFk?izun#3k9wzGo|G5$lJrsQa8Dy443YUs zChAAr?{{Y|hEA|-Nz*96Q6Zt}r<CNOGQ|^~_<=q1l({IU1@%|HPmmSeX1`l1Q&gA( z+CQ?*<XC$#`^D;2FUubkvLPTCH<I?&P|iqX45izq9Kdq>za$AANB3o<OT6iZ$%wWg zwYnJM-B$7kS~L{G?2K^6uWa|TBGb?H#`pcofgF&l&M@d0c+g*rt!!G9_$B>FsHJCk zf7OvBxtEoKf~7)=<o#H;A#<CtBJ6=-GSW?%ZP3gHr$zL`sWoy){&`pNn~)r(XL%b2 z1;o<9X&%CA*8QgE%AgWx3d9rO+|jA8&N^iTzxZ6P<vQDh^eU&AbGA*yOcSa?4n(b+ zf`#X)3P7LiMcW}c+)f#dST(rsA{`df2%ht~os;xOfQ7P|MG^Xd^h-9aIDzys&!S4W zH8;M1nGKV1IwNXMOCX79O5IiP)lw3cV|VaM^K0@LyH{!aN!rrkhT_%VRs$sk6o{CR z9f8_0aQ<Z5q-&G~G5{c2FGUyS{~w0V!yoEDj^p1O&f%Op4u`{;+0LGE=j@S@O*(sK zHqg4WcL<r~5RwX+r8-;oC`l?SR4Ou3KXpHk$M-+@em>vt=ka;JUe70^sYzFx7N0AI zAz;wnQ}eUwuv3HK#uY_KX|kv@HjU(ZktGqJz%qeU;~WJGvsb2Xe$)HcsiE*Xq>WUz zE^}e}l!Kd?=L|X)n<#ETYBx?Azk7mr#42j0?Pfw1=kS%Cn0NRz`~AG43&SM7g@biX zAsJU7w@kWxr!G?g3~*1786P%ouNxzIX@`EQ55Le~7)KH^txSK+n{Yg{NQ@pKd?o!; zaSuL{5c%o)^;6K!jp*&f_3uEc_Fxn;t~fF7J<81R$R0UzJjEExWSt&WnUAY4$E~>D zHazU%iYiF_^7qip(0HCbK;ehz4AF#O{+{#E8>HMF*FnQAGMlBg5xSFVrfdCL4rn6t ztX$oht)Yu%7l!e4FAdD97p2*(ok9bZeMm-rV*hLpS833|NBic-)F>Y8RpVqb)12Py zZ0F05KH}^6S;c149ouzr^USa~6z1UR>pZiRg3mXbo4H8l+isY?;vpju7{sk!R8Ky* zcDOIWBxsMCr{J>+`rfwousMZ93U31`vJ^TWWPRYdEU9*;R|=g$OpgCpm1ZbaB{)N2 z70=JD)8;M6LKi1J-I_|Va0&fakAJ7|j+h!<Dk*8&>1YlI;Up8Uoo7|mfL*~ji%KRK zn<w7f0ZXm*$Rfx^f0I}eZV*ttGC{p~Z1MIqScJNin_Hre8~CL&80gfC#hdfujQKXX z5)ej8M^hTPM#9$ou~gH%MYj+Qv#@fT;?EHI+|lK|0cWWRFMuiyXZGIqPm*fwsgnYW z0yG{+diN&v1jW7EQ}Fo`h_X+50XO>I+IvjnX_M)@<eDT#wYZ8$7wMn9Z!?AgNWKIz zVV?bCZhFl8?6LQ_<Yc-8;iU%@qK)W9z@enJEdG-{2<rsjPBUQ&H@gx<BrQ#<I4i~& zuS^6-*@683&PUnN&^T603Qcyqw`aIO96KU84U*CBc{;H2^w|nQTSTssci!CM+P0B= zP2q<_S~JRp3s2(3j5=YgkoC0qw^>8#qkHCw`O7rpJ+HOn9EZQ>**zA@p~=b?Nz)UX zAlrLoljl<<4(LDbNZaZRL-Yp88vvlY*heZR>v%FNbO1o_HbfUEtT)m(^*7P5rF!O` zr%rC4egOo?g#crTI)}cK-z3OIeLCushKqeV-4Z6^Yh(8Br-hAm%oDZe`wY`0b(#`Y z9Lak1i(|i?;x%q)6B0c=A;-vd!!$brP@$WVsMDFKmkZH3O0@mXYf>v=!sowR<Evi@ z(bcXX6_IT-`Vxt^r&ao-C42vbf$xdsngk_Dg?W6PHdXWkcaQPAJx@Rm8)+w551;S* zVL!<g%mq+LNQa3q0Ki6)3DBXJDv7;&puN{L5rE3mYB~%sJPy<Ma!aJ`->i3v3`>Hy zL4CQ7<n-6+{GZu`<_F1($Wz=E_BqU&lW7o1VlO|gpWm@ays=kNw-+O6Bo8nyrP~S1 z82J!Vkub20P9LGXm(-Zifa`~5K;8)?92}w4C}$~MLp!f4@iM(|XR-#xh`-UM%%X?X z?Z$OTQaWz9G*(dy`66DCzEN4-PQIMSf|U{Jy1ALqY$(Bvq=_?C&CSNU^3TJ;r|}Sj zB(nDTL=Edc^~D59ZBX|xSgihrBK5sS8rl6E*v1}A&}Nf!9laVP8Z!k(A<#f82`$`@ zX?5pV8b1p2@U*+(t!i<-WHBs>z5Uq$mn^v)0VQQ6@sAVbaS-kB{-mlUk9jxuq^z4V zMnauwI9U=F!+F=0$;X>3E{tP=sF-=m8sW8jC0c2h3=*UdK~nl;6;uK}OGJ^{Bd(o{ z&*C`@&XPQtC()Roz6Rz)fdD)lZBAn%%$>I#6^Jm!J<|DkkRMhWGCuWiT;y0Lea?%_ zVv~CoKhd#8GdQ1n)OeiS8O-eE0}vI4OTLCrs`VLj$2uLul!p48r23ZCI=Q>H6MgzJ zQhE(?dR1~d#gLO#eYMDnndut6Cxug8<)h~Y4G$A_#>o1N#FH3#0QHrU4V@A58);jd zx)5UMc}9OYq;@2cBv)hmZ%yB`W@e{h=IVXDYhQJ%`tJHPG#tbAze|{m^ga3#vb$N~ zznx%R#Z3H_%_9|Lq_x!7y_6=on4pm+an5|QKFC^&Fw}_4pgm&=8r!HhpG>w$JpJIb z=n}1PuO|Vd5YswnA69&`RYZ2ntbQ>^(hcmDQ%)zM^^YLhxIPss#6W%W^|;@ol>427 zi4D#}I_2b(X={&+!U%hL@p%c-K_8?X5=ySP<eyLRR80*3DSg;Er*(x4Ye|fIVz#4$ z<MASM-m{)qbBk0@lumQtnE6a{WKmuNSG3uRZjxfA?tXYn5=Fcu$&kNpk_5+K!#at& z>J8`|Xcso&S-X{K)|rh%vf(hqaDL1DU*hH-#9)bh5`N#X9_fD7=t(lCbF@XMXDS}U zv?Bza!+=2hQ9+3ys;Ui%<4U-fk%GLU^RPbb;KKaNp70n;s9*OWZ_}L?*(xqc>0D<H z=@G676vFI?KR}%>Arp*so$FMT<)!pU<r?APy;xW9@LTWiN1RGiMv9Vs+LZSOUSx%u z!0)X+(vfUhn8q>vfjfJrLW2@G@jX%5=XkqqxYhvaZWh`;|CfsT&=yn9lcuT&FYz_E z{es?h_#o*hxwF5gI^@RHBuj;Y@*SHSck@H;c}3n!kqh&08oBbNu4R>!6lvHZ$C}v$ zyCG-r#ItUsuTBK24^Z__!5;TIcjSM$`=p$$Os+nB8y5P7OVpU-DFM#m*TK$|<an|8 zfcvg)ZFRhC;`IAO?W9D!xe>cJ`Ak&bn^!q)1lt!!XHM*Zz2EbkqlkusEQjK)wZ;<r z;P!$5Np!wX6<}A~1{0Fro;(jB*!7AxRY(n2YeUJ(?qFqX#mGS8Nq}*3V$G-&qMP<r z_YVPm|I7IILa9sd&Fg(t&ACe+yq0pm{iU8|Stn7g5hAnJXA37A)Qo6NDJnZwg-_jm zoYix#kPq1M7c}qp4Lhr}2B<`vs5q1O`iTll&N?C|u*0Fl<#vQA)pK@SK?L+^?Zus7 zvSvR>1DH)N=+z5L(e{LB?Rk#wY)d3=-&;sLmK-@eSu{Kk`K|y_mSK{07*6w1kG{;) z@KjjI_?&brgK<ov-Y4-YDSR593@duQ6O~w4<wjCVEId_pP?G>F9{j!@&K>kXT8CA6 z7(2YVoCK0K-Zj1Y=QN&>vCH>4?;1(joUCPRu5hJv-9AB_kZ4~Os=wDq`75`}$p4fv zl64ofrjvQO`?hHJ=cY&#KG#5}et<iP95eOp&Dzb(8AVxzO3}e+Rcyk~m#P|`g=d4D zpx;Qc=gGl3X8Fr*I;E>D94hRO+K!*v-Zsxmk#!SoXFh6pi9$X0t36noN3udZe48YH zt$ID>)eHDC)wSwQCy?B0%)?Dvt71l<iKt=UQ{u*?bB(kBCRJN|F-w?z^g_-x{c-Uu z;oT%zUWWwT$p=!Eyf$3UT3adB>=lnRZ`eo(hrd&h8kO_j-KTWONkugIaCO+XJL!)h zW49!<B*EkQeVABVgLx=0Z={#y{L${6hwfm#WG@LD5gL(jw0HYPCyBpRz@=3{08f)B zz9S-XLO^Nmv@)4+`2JdJO6s{@!=pk^wkhfJeR^Yw27YAC%|x}%!X`~y;`cT#`Ph5$ z0rp_v+n!bY8MDx-!7E<`t<BTWpGmtmJ-y*)ITL6GF33+*nke7Luo{|2Q2vqR@t4TM zWaB$eQeQ6hFh*+KxA=nK;+z4wsj@L4{v=q0=3!pL>^XQYJ$hAo+#s|b*`fEn^)W*_ z&^5tt8@6QE%bx|}$vVf^D!?uIK}wq(<$OcD2K2=#=feY$;r^d5?}D<*7k5+=b*(`z zieD&O;M8p+jp0doH!v0}U4H+97nd%b{|Q}Gw@N~nwXY4X^(TV$;Ord<-6sT+_?a_r z$%aiayN;<VNdMYDIIZ)3x*6oF^%A-{etHyLUB^)Shp%-UBy}zSw21rFy30vTLg*d) z4-DfC7vyFxguEHAF>F^m{x#~=^brupTZX1Gl@O4Z5OgyvblYgLp*+A4rUh8~AGelC zjrgoY**(WHClEKBrnNb@G14wE)he+VogBlo)4RDWy;vnSED2;mv|7!@n2C+5wvFxO zY)suphVkwBeUGk7?-$5Q;f&?alXa5Dv701O%F8b$h^D{vp~$V{0f_Wkk0-mR@)&~s z!$b8&T9%v;zblEG$Xl}bu#kQGn^&J;FMRW7sVBTwRyt9(T-x-t2_Y9ej`|)cy2E%; zUK{ZzNMJ<D=aYVrkrc|Dx4x$*m_<Yz!eR&us3FCJgw9+f3qFWb2z3zhyz+x3(Ew${ z4W@30O^D>~-w`oZweGom_d?a1XYW6r{IK!NV^xFwawNU%@!fWb@cY)|+|TdbFg_(A zyz;`A^NvJkgLU}Vzm>}IOS>8<<@oV-=BoMDs%?IsPFmkkdxDs4%_pxe>nFZx3^m}2 z(db`Dkk*j+aE(^YI2A=gL>i44t$vk(cz#wl-WJI4l-o^%K*5lwa>BFrH4asYua+-P z8yZGF4bd}Fo#7Q8zK|FQP86fkc<ks>gvpfPb658`0O0S>9_~X~Fj+4ZKX2w0z45lD z7tus(IZ5NCCQedXV<;kRKVU=|tD>-ys_XTCDt)BCEohM5|4X-8AI_DqY;6q|GD8xF za(0eha>(Y_=-)hHUz-)E>NQ&QbLDU58ynBA>srG9#2%CTk*ZyuZcq5aN>qc#6x_f> ztI`(#(fl)yU!}Zi^8;?1I{C3Ov5)J<7+&{z*cb|r11^~?%x*Q90VB|>Az$|Ic|5(e zv;O+&t%$QPu7g<l^ot{xpUOZw`tKix>-XIdGc!Ou_WTt4$p=ilv@1$2{Q3Rw(?O0E z!!ckaugdRp!;3<uf&Ido`Qo#f-L2(6GoLt4#2!qTglPz2b>6H4!#DX5;-kgo-lcn< z$HJe2H_d^+iYqQ(nk;AjmOnAMXc)k7&wC<pvjp!o7NjFC_2aCT<(nKY34htvyObGN zK6~MHcY2agRZ*U4eSBl_at7<8Vme1`u|?9Y+NwWEW!LlVYj{(hi22_vd-7HiZDqbQ z)fyMhJv49)Ks~~}lDiqGC-ju5cdr^}+wxg@r{TZUGADy5GEd;(@45=({N;7QLoof5 zsDlBf-hyX<o+Qv%nGY+pi6z~==U<#Y!tHL1_UCUM%aAOyDYYMz2o7q77CJY^hX}kp z+?t&<1aUe}k=PVlCr1L#f7K}=eyLX*`qw;t2kS3rTYG)VV&Zn};^z~?(b6o`fl0|v zS&l^^uh3?nyH}?Nh0g3xNDQ3!Y<(=?`y@ca@nP4#C<U{e%>P@LXB-tE_-Bo0_TLW5 z@Sgk5Ua4e2><XJ`{^p>_<(kjc_d_+^=4us$n~l*6#TtrO_xSAT$Hjl5zTLhI^i4c) za<gG`E;!N|x_#}BSSoHdjJaZx`<h$quDVx)k#mnfGb%}jRs*WdxnASuXI-6Ok%T*2 zUhHp^_e;hfNAk(5l~B8jSTjmEP<LD}34Zu?y)0@l?nA{7QXTI0hRHdHp^Hf`?_3Xi zeCl?Lrg)%8)ii12_RbpJ{mG@1D{f}-KeG3ozJ*&)gkJvdNu%lw&;NF6XT#i6@*8yj zLlzs$pp8$CS^o#M_5o3c)XkpMSLcQd>kQSt8vE;~wi8*E%pc`f`h9bs{h52%m9yXe z)Wmt`3*Nr-gJz-bo<Lh{y{F8+e$&{!tCiQPlT^fSg1?c<?H}o~UP>(PG82^-*Rd)% znZL79YWxs{7pTL1h5_LSCfi^`d-TH(f4(+Pdj0p!e&wj9KJ)vN&9U7XewF5-j>VsQ zFYhSK?QzD8s|@<=<^9BteoeW>nSL#&$hH`*H5(?6?e=jtJaWF{HSj><;HE{rL3HW2 zV5B+`A{e4AA(Go~j4Rtl8M||%ty&ZK%PNz!30TCuieJ)LRkEA03Wt$jA8uuHs7bds z+qU(4;QMV9SsH6BhRjPdQC~s-o_Q|uBq>Ow`D~Q|7&t8(Vy~7!iNpHyKNdqP|9P@_ zVXR15Avz@lx5%YvI?!nY_u)y&ow1yV;yUfR!js&Tq_ghN<Jf5*!PWXwW3Lvjgv`%P zR$miCza22vG)=hJ%tUx8tYYCl=kjPeA1`2%>kHG)={xu>nf+^4LVa%(g^IJtnfh~= z;Xm=9qQuiX?Je9U@{8J9{k;oft<G@oNCqT||FL!=QR99}Z^)F|;O?4;e#<WzKfkU< z7qAINeo?&@!%?->n=f<fX4(6_b*&zOQ&BlL%Ri}a=uDTKy72I3#kcbtddmW~aT7Oh z@3(H8+$piW`u*mezk3^oAVE7CvY?VhW0Qm~wM$kipmSc>B#Q~!r=KdQ;%(bBQ7N_0 z4lk${-rqDM2|DEE6x2v*e73MJbtrsTa98odXDe^P(<KuHwHj@oZK6s~S9~w1JGuYa zmL}*(M;6wbXne6}=9N0$RVut^bK%Qrx}ej&Q-uvqZC{+4OPwBs7v4X!|HY+8(78FM zu+d-RtJ`#`bKAqh2j?z)^;i~k>6$2fc%kj<nVnLXXWt7SUETkB79`}_gDh%F*4Xks zj*bo}6*XsH*zy%SMjf0gYAI~n@>eNy8xJpfT(Q3uI4P(e@1EQ0$&nRADs#UI`=<K( zWr5dv+k?2@_jPxRSwo!4-pm-7wsw9?izw-O{&H)exKzM5@|uvYRB3-Ouw<rkH(+6L z<#qe(iqz%7orTM{ZzL4=XX@k(W?8APivGy;xe#w!@s^KA@&>i<MC;CtjgU)EqS`2t z|HPVTQG;!pk=C!)d6^o(kF4NNO{vuBX2t7C?46GboGz{Vd(>X25i28+v8_`{UR}PT z18Z3)el>Gl8*YY&G6-;a*N@37LCRhF*3oh=AD2~1X#W?Ks^j`9(<<wi==b8|MjCo8 zJ1a5R7{)albR{Q7VZQz4vrqF6eXVo0`y`IXU=mBmOS93NBQlLe@OfqWVa6|REf5q3 z2Bmp1mJvSMeSFWSIDRMC4$NG!FiXR&#f@1iTl!^P0-@BKzFC>QS8S#K7xwHnTO4lk z85H*%NWDHK4)>SoLqGBEc2z*>FMr<A3+K)>C03196uFyiW|_<E4i7u5!GQz-P;T^Q zu_;c(ju5{}Gh=%=BBsE&rKV&lq9A*Kb{}`nc8cbtAksVc$BAbP9uIfMULJOrw%R{X zAD!+jHeHX%jZj4n$&>`I5n1y<xo5(CE!CdupU-)|c}Ap}YpVFDv_Z+DJyc$+>vOi* z<o0MulztUFaOo$ymy+UnNdV;@3&8<BH^PB;n3bs%=~n8oyImX}fx3u~7t3)a)D<6W zXR+*xp9>L^{<uOu+ugi+5_)-3@^qi|#lD#A@J(OSpkw4+20l@=xM$vEn}`8&zw$2P z-^399JQydi3Je2)PyHWU5i0ZYyyk1qY(h9P3;A^-w8#D(-<?RIcjw;veriJybb<B< zQS-h`iS4BWy@uwjm)-)%>_{`Sg=tPcDOr8aqivf-`)t202;h6fs=t+kq>XpC7C!2V zcBzPSnLctl`?1Jp1s&NdzuJ3aYB2eo^&W57G9r)wdC-Q3DUXpj9EoI174`URX~6F8 zO5<B!V)4|XvvEckDGUq!xh~Vy1>}Bfy?gl<?1cSp*~hmD9sV9S2@eXGGE#;joK!+m z58NG~_RyDTqKg#HP;3Gsgpj16{T@P2GkO>i36Y5f0Wnw_B87;UtNhZBpBVYN#mHzI zA-xD1(;NZyh!FlrR(}hUJu6oqX$@Hn?^R3y^-TfDemZXvh2yxBYzJ8x<Pv9=E~5bu zx2hsvDJSxww`ghhVNH#2gBZ5KdwbX$wBPu|nRC4%0{&?A>zMSgNYiXqonQmWydICJ zqC!K@A+yeLCJ_J5E$tUEAeBVK81X<5&pyXkDyjq_!a2L~%>HeTOd@k(i!<kk=mA|w zH|$(eV<gJ@#aQ-pg?k^;n&5?2lRraW9MA=0>4MHpGXW3af&hDeBvO9~c8v;M2e?x! zVb>_g5ekq(<kpA+&;3A~Rq|9bmb#Y^OG}&|dV~wMYCX5SycEh7{muBobmdk>W>VCy ztV_GrsIB+xtOsU1U$sv`Yi#$5Himw)o{0B~(xZe+wpXVEm7PpNnsF>>WvU+ioOsyT zcr?cthi$_vmxMZ&AZ7T2N?--|5K&3w$O72ar#YsUdRrRV@IAa==&lT3DT58If*sMf z$lZUDcv~My$IpGZ0pX%*!6Oj16zFTMJm_!wTUm*=jpD2X{;f?Sx`BTo6wVPMB7p)m z_<4-*hKEp~3zHnq0IO*w!n#H31a*IL?AL^fcyP~oMm6YifLhh4BK2zsJUVPfo-J-# zcyU?Sa~T~z19$!*1j7F{ib7UWpw}v4Ayl~&0IPl!TchefLbQBy3%3Qgyo&>3y^^gT zB=E~xS#wI!@UtQZS&1WAiP@{fT0Q%-Y8Evk!8~kH7M4=#ks#=;e)~iFmcR8%S60Uz zoDdGyIUZ@mdQT263yO&eT(LHv9~ja#!Y%X&YgU_B2RbZ*k_FR>YimEoa|5ti4bZIO zzZs>y9c31tg*3L)jE${--Xg=*{4XWK^?9P7EORe%aGS2;Mj41j`_Y9hgxpVzM+9dr zl5_eI$ZPV;SS6?k&+!J&u1{gB<N<2K=X9&!B6I<3I<I;UhOn#rk~1hs&EQjv!Dk+Q z;M7a$4V6bUz7QIpIf-Wijl6zCXf^`6(D>JM2WGqj8;eGMn3NhKu=@e5=G1-Ne4|^$ z1L*>22Jz63%HlvIq1Cyq@}Ol5Zl*PjA6KWIgSg@~tNfpXLBwN&V4kJJ8R3HCcX*D) z84qt?+7G8dWm*w_oB#!Yr7*}A08Db4{nj3AO&M+uusTE|YcQ-S6z~Lt8N!h2pa9c1 zF#Qh{KXXpO$3uI~;9NE~$)n0BvdHFENWrnJT6uS5FLUI47$qlAdZ2x*2ZxXFQmW>s zWo>JshBT+*YT!UDo!4FL#D*AO4w0jh!UiP?^#aJqAH7dVJVki%G72m08@#lV_sQ}~ zD;_ZsBVy-$B+`Q!A>)D)gbuQz7^}7%Lv6*iCs?v}mlU0YzDp$x;trRES9)-A)yJtK z=`dq|U<rrLVP{q@S#?x`N*PPgNci(vj<+bwF15cQ6plp%cSI$5;}Orv>A%?X&~=97 zo5D?KleoOiJRwZr3GI|-wu#;Y+!zgqw+#UTWPHDixQmAr4?A1;1uuZOmnzvR@o;Ab zM4w`{`v_)^f5Rw*K8fTk0x-OL$H)zN!)Q+PpRCeL`?`5XnMAT1l?CI7@WZndpWien zU<slAH9C;9EgChQfh15J5~)Zf8nTOY;s-r=c-gi(U<;a$?_iO32ip_xnmnOXHEE76 zmGB}W?6?W)FvCtlvj+S`e7V7*?TASDZqB>+m*~hXg@J`ROZihQ2lzzHmS6;o?f?<N zT&m<>q>c2Z*svUYV60!Id{Wh{>dYUDobdin1jXRv7b)0UEKsmlP1Y^8eSy`ow-yhn zUv*R<n4u6-gkLA8mu>$mTtt|OYCv8b(S%%ELu|xMtkU_{qmGJbLL%Jk3-%m<7{VwT z(Lve&z~H#2`ZjA^a(W3j)bz%@Ep~wMM*8)5H)USXnWLx@uD;BDB})ifCE$}zFl@vn zWG#yP3f8I%_RSd_cDe8}+n|>-<DbKIk!7^O)H8qzRml%crLvp+gef@#;|xgnMR7Wj z+i3>TKkK7)k>iyu>1+h%I#Ej4@vk`pYTI(|gerIH66?YbA^%FV<OgtrTy<vonqX-U zZ7xx_9@0~@u3Ke#!A1O8+St{X{NBGVsH=PP0?QmZ47lYOqVs??63>!Agb~p&^^4S0 zVtOh=(y+i{pvm`<s{FCIGm;p#^8-e~vt;1eyDQ-ii~vIiOK*nMbWyklAG`Sys{@|J zk7$%y>E9g9_HYW~$AIJjoOWV-L50fykwRW7rpUjE33a{j@=c7urM#CNs<<0!i_3y| z+7kXEOYI&j3=eD{WQF3nqo^!0j`Kvcv0m%H4~MXsNcf;D>0Oh*SS$QhEY6>rNp?i| zk0bts<Ho*9tYf5%9!0%ieP-7i*;pM^RU2t*^pe;SO%qtkM@TZ^Zh3cAAgnQh_jPno zKSgnq_VFr&LWMFOe^CMc9>+^jB?4UmjjD$;*wx3le7Zm}U0@_pKwS)BfI{}J;o`Iq z^^{-z`{Ox8ShS+<eGN&_(tcJr$EoT0cDsL7yD)tsoixY3I?th^%B?j=5@L8xN6z1N z;#i0j38o8`ieUq^u%)CE1Gm2ChDE*Wc+vC~HyC6p`dBE)N3EYGV7-i1An~X#qkTv` z*Df*}n?R<3J`I_9;&5Ml+K<jyS}&5<>a?<;ifdu+Wdaxry!;y~_3PYUKOlUcE5QFC z0KLabp&VB?0BSgtLY3Tz-~jMGx5C+q7|(*lZZjXzgr59R-k@C#Jyc$$^M5)mUMj}t z(}T&qAt2oauf4$LObI_-$usI4;D!g1_Odh%$Wg@f4mD<mE6Mwur2yt@??v$9SV5=` zd;eh;XDd9((Vq@rT;kfD1Yi!)U`HJmYfWJDz+8DcCwmEgWdSoUem7XXYhzZ9`yDs8 zH#!Gj`Hld0z-M~n0qIJB9iORE(th8=xB1ZAf&#BU%(i-)O;+a&7LYfIwzPPQs61cz ziHoz^g+n|L+Xp!{kfU}HCM-Q93P!vTv{ln2X9QV?<bHisGe}#f4Wo*JZ~I0!*k}Ay z6G!RswURPg#ju`q{#cUGT92^LGB*>T%z|yYzr4X{)(BkFMN{2zTVmL>(>%F9q_uGZ zo?_Tmkf~%s-#an&-53YeG|jH%ibtSKV<l|7_gd#Nu2YQf%P%z4yZd3!vkYSBE&Pn> zwpsH-kl#|`)0iR_EYQ9U!^BGk{!aJc0={q+p0zbP6Fol4@U@BpUPnkjIAwXJ{kr0` z)np~}pRMt`3mitSup&Hri`M8eh3AV4N@STkcT(8Mw};P~?M6yd#L7$MZUOC+*f0F^ z6ACEsGOpTz-q8*UU)o=1&~}^~W)Gge)DM$?rPJr$(1pM#w*PgQ%M4U(cv0l{wBQXF zHavnaAe8ucC<^n*LwB;+h?z+AC@Z$q;A`2Lhs0x6WO^_Opo>pw$18L8aOR!8;9Z+Q z86WTbuP!`z@BSA6H}@F?{wZj?^ZF<eR<D;Cg}?c@m}LU{6h!?fi)q!+BZG*AXEfP; z`8pnRw?8h1X4(8*)8o8RU=(+&y~NSu{d_<Kv16#%5>ok?qyw;10drtU+2cb;DO4J` z(Z=`w<X<OIZ?v?)@1sLv!BIsFefA7pAf-wm?es|X74${j(~tBwfy&ThYZsUTSbkWw zcn%a{SoQJ1Aa=<D&&{kb>eDU?)LV@pA_`81XA6hNon)r{m3V<tETal-dG~xL;czD{ zuI-5EpXAF=G-0-SuU)(%l4CjusqYp~5R=~M%Gehsat6mMU~?z0rNs1?iD?gtVW<9b z#}5dogOIO;f&MJ-N9BhYJ@HHmoX~hpSdYCD;G95k;?UF6m3KY@zlOW_GZ~0T+v8() zzWfDv#uD!J``h0HQ6eDji-O26TBy0J{qMh`H;IRNhT_vijw=08qw8?hEcO}=_PiYQ zKpt};g2N18|4{iiE1Y{^zv|6oqMmr;@doT@<vjCq<H<i?4v`2mJiFJUuNKt5ui7$S z%v*pGSaQ%Fb6MD4@quian4;K2kZ&)y3g?NVdJ=e~T*uBY7OO%x$0!TC*!>1?<c$>E zvMxzrLM{BQ&1=EQw8u5WC_p~`A&QN{S%8O_zN)tmm=H`w@q%SqjPM*-EmM7Ku_oAQ znq+(V4nZ=xSClsjcSdc4(ktWx3{yc6GnYhfx5Yy-Qy9lXj||s-_x@2QK10*RPMWV= zmMF;l$Q;dYN(I1COH@*od7hA}V54?4G@DOb<uk)ANfjX|<KC{WWAQ01OUR=?)-Bq1 zfZEXdrkD*p*WxK4FAY#YOG8wU<bk^gF)rjM8w4Mntm@bA`_wCCk*dN+L~&~axiS&~ zM(+j5-Q5+X;@eAN8c4lI%gdKP0X#~~Vj{o>#Zcw|9*iBpCJVnc%`I|ukC}JMKCPK0 zk`oJBWY<D~Oj1SSE*e8rq0*)pWc*SOln2*tj4~}W17DZLpeR|aGsV5vRgK!`0hdq3 zd91fM*9JJ(yfypzDBk{ae5wkaZ;b4_UHagm06qn4RHBMB{1FtxcCj>Q6>0d4F?~yR zt#fx$$h~0NSnEetwZ(BV2b8MLB!XG-LHb||wSS&J;lLGxd<1ZdL1)2GlXlWIkNe=u z+*U;H%n&<cGz%tHla|6?{-NE72PkhSK&S?FncnwMk4$uMx!s(=YTp_^h|`Kix!!-C zO#ov84%r9HSm+w8ks?I&E5TEm1O~TP*mCk^&b1DfHpw%WnGj51<=r(iE&Nkhpkyw^ z^qAE`okpE|pd#eSp~%bNisp?<xg1q-SKdb<?NtM-2I`(adhPw|2JdK#r-QLY*>;g< zgfy*1kUQyO1cZX)XA^XkcbgbS-cve)vy6?ETuAD~I)fM&U6WWjU0Iwlfc7f}R1$YF zG!u|4>a{1c1iA%~`|qnDorG(mJVhMe?4cy7pBCW~!KtrN_B9-Cg>0$3cld2>G^Y3f zT$0mOm);A<hZ>eMcV3*j4Di2$<x?(Eq1KFcKhRcyo6$b0M*tWEz5B*T?y9G}Q7jGp z;eYXrkn^lIQENLvW818Ha73l!)?gXe*hQC!9&Kj7z=z=O-1#AN@E~QstK*F$2mRSn zO2j}i`S@a+AGld2VNT?HHEw=o;MPaZzI*HbeEn%@=`6P|m0Coc*;j46QtW?lYWo*7 z_sj=u0zBakK3fu}1tdt;;fU)(Wm^%2ahw(jtu17QzRC88KO$YP))9fj+_=^ru4_T7 z=#D=|%KhG4M4*>?>yTABgTSg53qtk;K?UdVDQd9|Z0-QPz7hqKBlfs?5y+S&R0{r3 z`mEPfFMAPQzSWoxBEd5R#-?&%oue+mQq~+mNl}ye%nC^0pPJ$yRN^>UdFFeYid>~6 zd%sfd#S|fq3Hch0_x)mI$k!O!P&~82(o1Xj^^<Nh6upT<yriTE(F(a8$I>I-{?v)9 z<8f}z(j)l!w;Y$}D5k^@Asl=?h{uaYBETz(MC!|Gei`Rh-WD?jNY~r5^(z&32Bg$X z^ULE9v#p)Spa9zH`{?1*CH<aOdWL!vD7!tAWnutS=RWA22p<*gS{v?|byohei*n~t zSPW`<e$e12WaIo@xN9a?9e~&69`jE3Vapn~?0^D(Sp?^*0H1npmR7cYLUg7TAkM=N zpea|rS$R!?3ATdilZH#7h-kczz&7c=YBz*<nA3k;qcm5EW(xovwqvib2VGGS2hq6I zQ1#6ZU<pZ9|0eK|CPhi6^0=C3(JMD>zUDbGGsrPAa8)>IupU;IkxAQhvjr7SUID6B zfPhx5?q#AGq<;Fi;y32Py?IN*6&W+fI#%&S9S|X$O@O0-UCv?Eqmsa-NaAbf4-b{d zQ|^G;3X4I&C#`>vIlT6&ECbNn`H?|T!<8uMkY^wy^N<z)!LH2gZy(0WmCUg*m88{8 zM|d3;@e3{~g25D|N}`c3S|`;b<bjig&O(2_tI`idk5*s&FlWe;5WV<-^*K7R4^{M5 zd0`+RSO6Rw&ys8!0JC~p?L&HUB3DjnT89T~DPh(npq~>BR~Z#?YVdhC^?C!($7AmH zv|~nek>Sh6Y_@8yddZ7?nbT&)SO^nJ8Omz(wv439il6lxSM*x<F|$hZ)ZM$)7`ss( z0OE^PTzxw1=SUi+uh788noY<}VxPLFJ){8JTY1BDzBTw{+}f%2?nlKxtdQ3~utM&) z=KGo~O%LdbKe6DGSJC5vWGqLkv^B=K|2{b~oo`ymFLfS}3=Lw(U+G>G7;g9?)O1pL zxAn^RZ}r!$KIV_ltnGqgZbMr5H^BXCfC;Q@r?2)~K}zvyw{P;hoLM(ZwQ?2yZn8>h zC-xzN=Su&{>)qIiyiil}diBc0l~J*1(4Vl^Qp&7x>f(&3`rXqHCT3${?8gGDrml+H zTz8Uc^O(jQipvKYb?0~Pmz@d!jZHRQ_WKGYhIg!L=$RZUz0`GJpV@R(F(=T*sr^Z) zQE4KhN0T$yw0JHOhF9`tiO?q76=;`vT)p28_c$Om7&B%TID9@XfJMY=?@GD);Xn4S z5mR_s#Ks>v34sONIxPx$pP1(*S@~1^%CQyoPK8DdLeK1rc%2iljWsdSz9HM#PPk<8 zc=-sILu<u7>t8P<i}QVFQrs^(T@ni<xK4M^ptWCg$i^p0U4pWS{ytRgw$<I}dF|f1 zS@7`cf6)6T!RPHKq-=Y8ti1F!u0CgB5g65c?FLG7vmd71>_hnXn2jXb95h{$6F`%t z-ZMwg1}WJWMWoig@a@@ib*h^|Y4V;eY6+{`4^_HP6SA+AINh(U7?#AIugu&yAj-GS zz<&~**=zt|v54Du{!;;!s|8(_-w><IaL`5nRO5!5oK$eV1AnorCZA6CIuIreB*&Fk zQ_o+mb5CP<hTMit?FA03N&0?C54z7@f7>|csndTJzn~=64T3G`ylG{8BQkB+UK#*7 zoT}y&3MzKQwfS-<JgO7@6wuqaP`D6pp8Ecv#Vwl0@MxL?=1{{nzAZ2K^L4J3IyhDA z)eO5cd_h)Nbw0Suig$p}_}yPp#@}x8>f`sKAKU%ecw@Tx6Ns9dD@HB*=Z^X2w-cG} zSxF%`YtFq>ff^E|h-x0H0p?Tv644<0{u=TB)+OjS?RsXl1YY}k=2?UJeFoLfvx`|D z@m{R*)BFC@1bl+qs|jooBN9lEN?9X=d8FiP&TU9aJ)JdU+*K)4iO8S6Vt(Ot_w2>~ zKBsjFJUTB(zYwfq<foyUyzYBhtI9yfNEqDWXjg>i53;-6u5vmNMUR1)tSEz_%HkKo zBgo<;hJ+-+U2Bjx*~xfG1ttB{LS5t3PQT>^HT}!8v5mh1b?zn~t_8B7{GI(Tht|d4 zNW=4)2)mnzyaEBwT?9yh5oHo6!Bzdb+Q{Y^>N+hd?Gj(;HtKSerg)M@1BQ8l!&O1a zN#v<R?C_2jxFZlg<EOll_LMdGP%_KKB<p!yva3m!%c0glQ1FB~VB&A@dVrHtHLwn} zzU6HgdEsoJUHI-SitCnY{cG~ZdGn8Ld?Q6tFIS{KM6xBfVQMK{B7Vo1KDK95$1QiM zz82M(NV$Ne^QI(Xm-zLIVB>nsS$_&<)&*@Nrtt9f^$%6bUtjTAxlrq*be(-niDc2* zqO-!XNwTZLf2O?{;yVBJ`W~#GzK5}OH?_W$=zXhC3(Df$Ta(|@>McnSLbt0JqE1aD zox0!03*hBIP!%9IF{p?jF(j7B9|>P2bosi)FK2MjMO^b#mwYWDXeOYfagntsJ%9e9 z+i;-g@acTl^eNgU?~<6XKGE3IT3I_5_6|}gnoY^_`LEt_uw|>Nc9=WEEU1wG0``>5 z;Q8+};nkQ^tCIXrqfaI6cwe^1hH8~)sTN&p&w5$xG&~$Q<eEjTjVHlk4Aw8-@(xsB zgUG59`u)Y5heHg_P5QVkR|hjL1ZaaKbc`L!eC$Qb_`Uac_-lqltLh~RJ1u+bFL!TT zE*Fr1w3I((6`qvMTG}lyEH2MD#>BK^H*Z=-gKXZuws-S`z4i_-NVcnU;>*{uV22A} z%!n*EiK{4%?M`S&wDfNup-AeDKl4UbVh|T_u4R&<n4hZ%g&F&x<?N#rV;I)v(M1c+ z`B=MLscTVDzk9PcTf7{rVngu-rEjjKU@oQ?Xs-H1MMd!|2Skbo=#)uNUJqMbc<hH@ zftU<PRzr0WPAS@RcK6e9W^_JR6%Qe9-KQF+Z@h&}-^y7Hi4^P!U%MxHe@;z9)8e8} z=2o*$22FHu$H7wrn1~WE*|+0ZiN95RImiuYPffddF_{5z<UdR{;*U!#wzH!U-Yt71 z&_WuW%7!mlWMS;MEgf!or+T64FM|jXe44SbXSKF1?B*hhNm-D`I*o7qhG#F9zYKgG zY*5x!Ubb-0nWfZq5c|9iA7m;#4Lxsm3!878(}d9sWH7G>*h4<HoL!n%u6(0ld+BVm zf1*FbMkoe5zESj2jBjBeEq5-fKc<mwr35n5IQrIaMh8EA@7|M+%QdCo?4I=gBwI;H zm7|1k@ZNd2MAZiG{q{chEuC<fE95H1hy@e2OW<0q<ovzq<Jm%#cT{9uJ8>8cbFXC4 zR?o#P0B%M^D|=xM6@~9ngpOW%Z-L>h{tW&)sk)+ok4ALt4msD4ue#0aJh@D`p)N&C z`=%r860GrOp~gO)KUWN85S^b+5_sQ*+wjx+OUH)s=?h(KkPgz{J#et2>N)l+7=H06 zs1ltjQvRrtV~Gw=Cq;dlsoCv)Xm7;Fb3gK?9}@;b@ioesu61FZq9H@e`h9h`ZylVZ z#2W;ENo&~1oG4B!j<ua|tENa9AleM%i+MM}E*2fP*W$d`gFS*i733r}%e$Ic<(&m~ zYwV*fRH=`>B?w1tI%Y=L@q2jCK$;|A5F(V-8+-3{@a35=nOwE;QD)h<I)mq3Ro)J$ z57SOD>##N(?qHCIfElmfwDSEBDV%P*tBa6MajciUHYU!@YtX6qmjf)>wxOWW^=|vz zlX5QUib>sPuQKmF)57cgq}*+=c4xC?SAoiCfj<AN-c|KXe1cgY2zik~a2VB%4`~X- zKRPBuyKln+0G3+><SGh*byTEHam3wak^-r)Yyj?VN8DyrCPgaTyb#GDCLcfm^+a3r zI73ZnQZ2HQ^@U3QcFLxpun7m@g*<n|;SdXB`uk|9xF~{)P`I?EM+dZR!!(Yh=6-n( zYgv6}zn%Y_S-jt4OWI@6zur1R=GIO=UfC9bcB&vvHLUp9L)jF*58iDq`2`$k4Ej(R zDc@R@RQX5cm{KR4PS-5>sm3w$l(q9zlEei=9&71g@YMi;x|zVZOXYA?iOSFSXmd&Z zyO%ug8L&A&{t%C{h6w0M$N_L)@oCgTPu)a<84t0(!ATvs=gv7o$QC*a6B|U1w&D9^ z<(HzIRJ&Z=Afqb0NzFPxF--K!(zM=A+|2K;*PlzMVadgO+I~Zt*&D^YDUzFMxB)3M zM?|g^e_LnS*xx>0Mp0sq6y2xBV`ind1fwVM=C;nRljrYKhLM^U2Z57cOXj~`UOOtk z)Oar|Ez8VbLZz!()2h{h$9v*&p0N<dNXV|OIo3{)Fa)|#;$&FO@<_}WxwegDPQkqy z^il$HJ@SRW9Zb1~bDM#%vJ>)(ypb;sfh4_nMr1LexG70P{3)^-v;3-*X`jc6d=<tl z7%1mblaqomcP5_};Py8zw|(Z$U;yv8Jf(@BXm_4-9t@mOwunHZx_vI@^o(d@5g+W! zEh`4DLked0I9MQ$=}|MQbpEvZ0-YdOEwaktC5gJ&oFU-6D#Wv7m2o8(Zf{2PJ9X`| zJ_TVE@15%ILr;-w{yu%%50ooErLj<8e0h)X$&4P2#>g01KdqY6K1hD9?s#9l+^Hq& zrtGDCb^KbC|Eh0CpsscK{fO$l{yAs<4e_#bhyCs=;wGmRCw$O>bg5&#E33!#Y2(h@ zo+rJIB)guX2aIkByb69J2GQ4)d^QV=B+{<;@m2_BH{r5h2Tx4ejH+5RfbElyXbr_t zRcDRuYY$U}LI%QF!dh<%*e|&%>M0Av%LS^;|90_=t+4h^G>1@8-m8&(H*x#kl^Pn3 zoD9)_Y8oaQ$NWda=#<{G4cz<ZfzP;1vPwc#RD5n;xCv%}Ury8r%Owjq{y8Idv8h>( z|8q2KpH&msy>d)*vNbAmGn!gsa53?+q$cP%0r{Q46*wb4PL%#N#Svr&C80R{5~iqA ztH0)5vbSMHU^v(L<Kg#=;dhcr6ZG&M;@OnAjUDvxzcpd*PmwcFVK9po<<qiX6FHB^ z*{|uO7c}5B(H7)Z`N>o(n=i;7YP81tyv1_Yi0B{;5RWeyh)!0OpWZlNs0JI?)s*c} z1{#qT1JU@+`*Y>*MDmYBC5iPGQK${Dk;8e20`Vn6-=tvi-1n%ud;SFI&O_cyO5E{s z8JSFo`|OPIgENM}%57_t?FM-XKm_p^dWNm79Na~}DJ)D^^Sp%0a__lG+kz~8ysBAr z{ZdLIOsZTDfI!qGa?y3ClQ-XG=*7r)>n?*8$CG>9q32tgkzsW+J@p#B?Bti@36m8H zB7dXI>+*Z}>EG>%BMI)%Q-PKF)n}ZialJI0mK_FPEq-(P<8|_bS-A&mo<L8blaa=< z^XaPWOCq0C;~ig#+<H^#7%G~9!}!FURV;XusH=dwr!LZH%;&Am&Hlzl5L<B^0WBis z`>6yEnrj9}n)KImh+C+~Y*&<RjmtcE?XkDfB2knF4&e+D3DO@7e7vh=BBTZq{=j^- z`mpl=8D{CI{Ogwdz6RfOF_G99Oia`9CC#JV<FF<NJbRn#O(62`JNPXCc;kZHWN>|3 zn%bozHz-^OQ=H$nx&Bd*n<y@}HRLBdWbzH<uPGNM6?yd&@;^J|uO+UZ3&@owuB9oL zfCNVN5^{Zt;{^;J)5HbmWIcJxsK<^=<kcseDd??AP7&zlN|ao<k1Ux6dj>Qu7x1{- z{Q>>=iIVf8iEG^kPx41KN$$ZQN75d4Flr>*Gl0#m>DV9*gLkul-U+%>jz$f|$H1Fy zRRis`&7PU#qt>iqlH7m;WL@~&ckf;cbvi33%*`hR3^9V-lhgoE9{tQT9SCJS4NdMw z>8ouFrU}~3HLAo6W+Ku8ClFASB!H0d8f$zj?n}%NvY#7s6ZZwDqYc-~-J&IkfB?A? z;|8Xf@F=>s2gRLMw?+$?B{aIK;E7{moaWY2AgPgTQQ3M+oI?`Jm?+O1qQLg*T>&6q z9kE08H8Rf#&B&!j^<|o7i-gpaYpaUQl?2Wqx@d|0d_ejDbedi20ZD}?<P}!6S*%x7 zawh-PDA*rUBx2e`rTO-kD~g0$n}ZTfhE;9CV`DAeSy>6F3T}xk?F9hf9t#BCu9E7^ zoez06%>MXGiHvF__S#o}PJoN-+C()!R>k2oq{DU`nCp~fHhcKPuAq4O;DKaO+S_hF zqeHPkIT0uYn}JmuLy=+J4t6pR#g8jN_tQ~j$Av3%nS^I}m`pZHpSe*8Rgi$IN|7qU zdIJD>o6!LSoA1;vxg(T-70>c7WUgxrPzpwxV%IN97>i1iQA+SO|L#}nn<V6!87vKC zq(!DF?%lNNDcJO=&Jz4P8>Aqh51GLO!+*S6G`44gZpQ({4P4B>-y7xE*YY-wGo!{E zcjAt8QgK?ZjW;GQFD4D$jv17FH6H!Fi&Z#gOsuXvYKz7y61SZdh_jw%+q)AzrgK8% z+Tvd7oooN>V{Tvn)4U;i{UB<nBIY}7SCr}Ueus7P`q*cwBCk$?R9wvB=ev1U@d9-s zr-b4lxu%04ild)ka1DRd;@XB2uo%TNd1-2`02e(4rFeKUNvXEFXP@y_xc|C$y1WXA zt1j_s1sc+&i(dPr%d}H{(l2M?;ebjdTs%!mp-hIIE5rOgz9(ZFPgI)>VyL7D=Evsr z<8xM4GSnN)eG;L#pzOsFXcN8O&n~!1r*i56><_RFrowVIgEOUC;fZd<ktrj0$5p@m zg=?Bu1Mfs1=C#XIg}c(z#Eh<lv?w}9!>a^MTcSDcA#rR}F?b`*H=)dUGa$h<UZ$oW zaFu^5)81;H@@x*9W+0=VyZw-v0PFLR2A29{su;?GKx%>M&#GRubz)bRkSBZP2(6pC zQm2*h^Gc>w>2ly5FQq&!I9Gy<5A<1WMi3pJFF{Xv!e6vJB%^B}bN>sJM>V;41fxKI zyQ<ljncDmF)I&7#shi)+hQ%9-eb9xV#uf+et(M}D%41XKO+V6q&EZW1H5sT!buFm$ zgm;e4!=qpHGGu^dDzBh+a|fF~9N%?|z^bAk20{V^nwSh10PO{FocF6~c|S~Jb~$8I zaz$F3SR+>HljcQ4{^yeG`nAi$?;QvRd11AeKg`}R?cc8JKe~sDw9L})y^!Oo$S!=a z<Zbv*QttXT%0_>U&MeoIQW6Pa_x!n?T6MHztn(5Ae8@M`moBV}D~6mdHsaCoajn;@ zfCvMq)zU5Wy%@TjO0oEg04J}k>ch`2FXB(r%lA$61ldzJv8jei$+Ezar9*K7rW2uI zuKEw+8LDe$xE^)G;oPY3Zs#1Ljow&^8MO(5_r0LbAkHnxv)j+J;RIDMqiG-+tJpqM zcrQ2g-j*LJsFxcoks==~2Isc__@}ffK_=a#FamBwU{OoO_Xn_fU_V^~K=8}KARy9w zOg}!4!)~TI=t_%(4m>U=nizu1a4aa3<h^03;ftiYZs0;*j!A9Tu&Kr-_D(dhr2CKi z$){(;vop;IU9tE}N*ILcp7Uc3LKvHPl$1@#`3f35K+`AoLx3G?XWDIV%`l$ju%gyG zicoJbsL66}k1t7LtS5%VMwY;&=fp0KcrXdC+QGbB=hVq=aF5;>8TdBQqe=v<Yl5=J z&6fb$G&j#@^Qvk}z*(%R1W?ls*e~e|sOMCQe{nb6sN{d}1Qj6}JE<aCb+YauATBoR zVe3jPQMEVrQMNc+!riCFrA|HZ*L|2Tr7C&G;=af)Y^v^E7DE9{kM4G+Xq;aY4ycz@ z3@RCQyhh;epr1&Rw71)q^HIx6Vo`+tJ{G)Sv{EJS!Fa7u$PE13^u;BZ-_IOV?%jUo z3F%tftAZ|zSN?1C_<WGw&9c%Se%a&tW|33Jf^+z)sZzAqt<F)YH<7pgGd3+{?@aEc zUx2us)*nxNx><a$%#QbAVD{*frIpju_4m)<rGKUW-5iSiohBQ7WN||qXQuzpQTB9H zh$mB~NRwTP>zt>!%-A1R!+20??9Vmsg-sJ|m0#YSYzQ|`i#5uJ&UyK@P0Xt;7Rk!U z6`3Fq>H{3cph`XtKy{)|O8N5u%g87I%o!955d>5wWR>K?*CJQ1?z+x)x^;BETc{HL zWZxPRO?J~)A}D!<7NSZVypkVVPbO4qy$gwC3+VkMh^p24SnAEfeQ%hdFc^@~#cTq( zNx-QH)i#|ZgfeF?jWXq+DiBN6mv=j!tfFCxM9^8DoT2-Nv{PE+=+ui@g%vqhPF(9= z4Gzk6mYBk)9FF&J*r(Mgt#*h$Bhf*>L60f@m8G@e{o>|w@?QD`(UYgozh*sS`w^4i z=2^QA6S$kkFIbzO@_Ye834nWqU|!JHx}x8v=fgo$4#8rA$dhxuNm{(0V;V=h-^dv8 zG|uo+lR=y&)H|-yGg^&^eLq$-*Z9hy{y4#rfVg~aNL{>2sIz4($$N^V^WT%pW~>h% zC=Evli<rpj>W8Cl9Y)A{MP&tgt_p1&4vK{vo4kkE1UX>(hqQm@CF0hY84Yy(f5snk zKax)=)*Y6^Lx-Y|f^F1=S-n+wU)ssG;DFAdR`t(0(UPkac&3TXXk?NYg2o<GJfzo( z=AZ_HI6q*A^rv=~juV@_3-zqJt$7^8;u+Wf0d+u%zkK>fFVg;oU}ys#&E*Hn&r$Ka zi}B-o=X>8xZpT2vNv3Z)BRLuY2RLxL7n*wT4NhDHQzrP!D-lD_8qow%@6DZW2*dFT zM<1eKKB8&?iWZ({ku`+A3>y*9SP&hATY?$@_A)6z%Mb?6-=GM)hlDmtMPX3>;~jI{ zqBs5ScR2=%x!Y=nqGg-OUTDJ<2P&ANJ6BIGm#GLVxJ$-J(tx_P4L-ok|Je0bP&a}O zL<aN87%pY-<@S$d1?6|##VF!JiUb-iab?Lf0nmgd2?78xg>kqO=yDTzAU;izqb<^w z(qR^9>4g~k2YZ16o%oj^cmpcXCsZ?o25`KaNer|=ov>g%!H}7SsF^wgKY=p{V|%UZ zV7-HInVLxp<Pj*mV2F;}K_2WuAN)Ze3__jLIp2!8m@C4N0~8}fLL*GVF^U^;AqN~n zrz*m)a1pOMViin@2LR}WUT}qQ0G4@h2LNaWX3>UmC<l442LQ+^ZHSY10K6Tlhj{QN zRY{s(2^UP6JAMEFd+?$A+M)s^uX&ic9c;oTWI{xwIB(jbDq^nW|GI~q1EdJlhI<H= z3LFBW5QlLf3X9N)CV&HNc!b;unJst(ZO}k4yOJg-tYQ+2B@o44paKe7i6HP5ppd0E zXo7!ehH^s;0N8>r=!G%tv|fl4LaGz-vIjI-IYfNMCPWiK#FTEKuuEtJ0}~@RfrBsz z5l#~aVd=)Z;F%z31VGpV0of8Wct7F6KV8zNy&;Js&;nU=C6tkYJYxu4T7p+J8G<N- zpJ=scvzI0i$cD(5TCxf#*q47eBb_Q8G~~i*#IJK8xkYq21LPxfxs!7EhpS6FH~<7M zbO&vCMfUiYC0GGy<A|8Kn3WNkIamRF+#875g88dKfLgzH|6GrjKr@0t3$Q`Ij0!@c zEJ~w1${=JpKN-TrC^^5Qxrl>Gs5C^XjLNuCl>dsNKWWB@YqBJ|2X`ntnvy~`0T&$d zIys7@c)%e!5kx8c6aLyFv<yT&ia8vLIdLJnd&s!sySTozxoUbO9m>jS^h0JGF#H+^ zewc@GKs#(K2X{b+MzAn1D2WLx!^uO9Ah?El&<04j0cL`{UT}wTFvq9^7)~4qc+rBW zv$1}#IzW&C>rpX0xjKI2$7V=F=rR<z#36gYN=*TPzwA4wR224_BJmmrZP}LLBL@Hz z2MJ6Sc_;^QaE7O=r4Jj2VE8g<g91(~iZZYc4+4Zs|FEUK0ktOZw2ZP2A8Q0H&>M<@ z0yyY}d=a>qc`$a{8!u2P&nyCyS_o+J2PuQ5Fqp73tQ6ivhnzD&=o-Q%R5_PBvOT&J z9&(dLxt6v=gCMv8ANw$(NSle^$0MN0XyZrGqmO7inAM{Xd#t5{!oLOjo-~^?f3z*6 zyipv@Q61H|y{ov3d$@?JN+AtWz!XlKQ%XbhE$$K{BaKTKiW?kiIi+k$nTsN&JVL#s z(u%{<j!RM_l}d?&I4;#oB>gxTnj@V%he0V7KME88;D*>Rr3QnQU5q+T%NA!jJZ3SJ zC&LqDfP}HLho<3&b7%%gXarDtG<cW?X$b-u|Clg$cnAN|1_~oPc>p|cK{+wq%i;V> z-~`UB%p-6C&N_)SO!<^E$|*J)hkmdZ!pN6>m<QYoPh2X4AP|R8nuE+)12oWre~1Ox z0}wHYf?*toM+kz&LYZLD6*Q2DiRheh3JO=+&s#kQPYVf+;50nJ(|R}uLfIiUbe41Q z(!Fy^;&j5jJ2JVPp|9(OZgrE(BN)xmx(Xu?-#G)HIXs&w2!iOb9-}DVxi)2i1AuiU zPGdI#>6k45z>Kod9er4cjaZ4DSc#odioMv2Wk8)1zInh^H;D&yLb_zQgi9EgctDeP za1$@WlP7|QMdBeb+RJwkPE_FsKGiNt|K%bgOG6%t2Xh!XmP5Hh>{Py+%BM8ar<4;1 zt<p7#hf=ZGuA?beAlYyjhm`d+y&(xSpq5TtQ7`a<FzAJjw3mTc*xZB%bjZCM7@9{> zO;;U)mih;hjLnf)gI(klJn=N$1B4hGK4-C6LbOPf1Jb@k+N3>Kkj1TXsFSPHJ)-D_ zd+3EPC|H^hMSXpquN}q*J02-n0#x)g6GWz1KnJbkHFt8mgvl6;U0v2~UDthG*p1yT zwaS*;Ie++*<od7XiU;8A762#*aIupyiWDM>oBR4hkc)?MfQPjtBX4b^-_)V2BwFD# z+#a>wqy0-TRg?*hA(*OAasU;6|LD)#XoB2Kl*!zZB8WS87~f0SJ#8h!#T18FFi>;w zqch@_Sn!n{YG3!%y|5LBelUkSDJ){_I>CHW-+CgU6-*zs%9)Gck83&XJ<^byB02dz zZCKoEc`#Y?B{%5>G}u?c2!do7hf%By!LZeF8V6JGPmKr);S=GWsMRLG)h|oOhLc?$ z?qMJPVIU6Tj$=x_#G&QoAu9dUy+lqey~@3;QZH4)y@R46HCiwAt-hn+i7VPL<>Ck4 zQUx8vc@QUiF;D=gyZ)5AX5n2~F*|Npm6-aIQhlPjTa-oufTU@#t(>BA2nJVZhQUHh z|GEc1N)sn;Vx-Jsiz{5i|CKp@SWI(x2lt&1gAqmQd@x!~y*EHQ6b6bYD1xm$hj+LW z&iknedxv*`2XR;?f1!ft`-jOKN+F(QTCQbVzGWS~QXQhNyv(@dI?5=TU5}&PAXdsd znIhpGIX>!#YiI_@MF;r;fSCFRko|`x=H9#eW!++=E2ZX!gk#=H3^CGXAU;~`UE&%# zqlMMhctB;(WIxDr2774d$c3gi*oQUIlr|v;XQt*c8s)2V3}@&sk9=RTz-5F^XoX&A zhHhwwMnWZAlt$6UB_`l)i77J0N{a<TY!1$c#<)#Y!avl=Tp2k`>={7lhltCfJXy>t zQWRAA*^jlk>10!D|Be-V2o*pux1RWDpZ;l}4r-wuYK_B7Lq<6{23g=D>e#)wm|EP4 z+Z1p#7wH9nMhT}0mJ^WOJ2YvOpDh%x8;5IP7N#z1vp#FIPU|1G*o{_e9UW4>bU8%P z)QAJlD|X_+ty16GShwzLzy52$4s5}8=(fgUV!mtdbvQ+tp}}r!$9`<cj%>-!WpqBo z%ARb@&TP%zY|ajB1@3In4sFpMZPG65ALY2hE^XCbZPspW*M4o-j&0eVZQ8DF+rDkw z&TZY^ZQkx}-~Mgj4sPKdZsIO(<34WWPHyF1Zsu-o=YDSJj&A9mZtAXX>%MO6&Tj4A zZtm`G@BVJ^{|;~Q9&hq4Z}UEH^iFT}UT^kpZ})z0_>OP+o^SfDZ~MM){LXLv-f#Zy zZ~y*p01t2hA8-OMa05SZ1W#}UUvLI*a0h>I2#;_HpKuDVa0|b149{>4-*67^a1Z}* z5D#$?A8`^daT7mr6i;y#UvU<1aTkAa7>{uopK%(maT~vJ9M5qb-*F!AaUcJ2AP;gO zA95luaw9)-Bu{cBUvegIawmUsD35X}pK>a%ax1@bEYET+-*PVRaxedKFb{JvA9FG< zb2C44G*5FiUvoBZb2oo;IFEBVpL05|b34CtJQr<U)@52w#4P=D%Er>v&T~R9N<V*C zUH<Gs|DW=3#yH+`u8G~2NJ<R)qOa+4I7nY=jU%p2sV3;+!A$qTM!#6xBIk!5^&Aa# zgmx}fZ)jAX>{f@^Qjhgh|Mch5F2%m)3;uH{wmGgu>>gA~G}%f+R!VDbLPbYyUEjDQ zVo+S?(O~}49b8&O-qBt^ZCftaCGO=LO?F&HIb+t8%g#}*d{}M=YM3teaTjKYCE}RF z_M-Im8;y35=EAtKca38&_Ua;i2Nr*K#&zdGVmC`x-9cdgt(Y6SK_L_-9cCYV#*HI( zM*5UYi^C^;STsV1ncMYlZ}=NELRAT;lQU$bR7xCLBqE$;tzOH!^P)0(*ed$ja5?m& z|4extO~kv4SOs;IEE4%2g!mj?6L4AhI2u!<G|N5u_$E}|M@D6*pV<M6E{vnEdZ-6{ zsQRn7daK6=uIKtyX%umXVtQA0X~rRPIV0pW<j<CO>s6FNaT9OwhTs*Ik-qpK?9?p{ zxp|o8ZMiR20a>H}`7x>o-zp-E4CaH^xW$Do<-L2pQ(iSPFRKoG9*m+(d3NQ}$bjeQ z&Br+4ocr6tcWK^YqWlwc;QMjmhs8D5vFE`>frm&kCpIKX39cfjp19vle9LYWH_`f4 z*_N5#{NY5(m-|C<A&0pCdp4$g9;`#QQ&}%U_|CWDIY9?Wc9Wb%Lo`I;W@zSS|LFc0 z>xU-hA%8H3R5*Y1M}I^}jP>UN0O$m1sCq;R6tRc*-@0A1cav-2g;-z)fN=M3V7zhw z4kAo=P#(jE4)2wNH}Ib}SLyPlTSqIFGjHU)_4}uAq{4gm(4mW`a-~X>CLO|rY0}@k zapbfGixo>9wVu4jo%=VB9{`agkH$<WGTb$8?dJXKXD^<=m=2F3^jEOxz;e7u@e(%? zfI+NQVg5sBZel%bojL)l7xEvubN8^~J?QV;Ij;L$K>`3MR<LB(+%0^WcO=AejvrH9 zj8Gl`dFTM#l?ShzG-uM(0DuJxo<EU%C1bsJj^9LWylU}kHg2H5cj*3||GirBE&zM> zCYlR}?b_^rzR~es%&>C9s^#QO>;{aMGN=c)E~kw8;J<R@CgQ_|Xnd+xrh?(CSMT1x zm$}bAj$d{=0F+V5eRRbu*1B~5Yk9+-J@6ox)OPrN=MOyBFmp{erO|cHWdO`G4^mdK zR}gFGjMI%TyX?}Fh&+WzO^6}7GY?7$nN*=U;Oqm=i{JntBRDsLqYpT#j28+n`22R8 zduNS=PEh~2bIm1yJaS1em%srCF9M~7(u5<u2c0+2tW%7C?6||uI-11dUq0-315!Vz zLG|54Zwgi6JXtnWp*HBK6QVk#kdlo$`|w1KFY0JBjy?5VnU_Pp{|#hLH`5#x&NPrt z<IX$(_~YAqSj9sdH?(}RNh`e2LJ3&cOcYr{bhh|UJ@_nx3L<ROQp<Rggc1%uLan%+ zl}Eah3?zV<(u_8}Bm+z=ONPM>ITR`;S*LJL<PT~Lp)?>l-Ke1kEV(S>3^dS)rUoY0 zNc7J+z8y**h5wAxOg1K}lMO9B`67)?an70BQNIZ#&NY(`H>ow&lmk^iCMjywwDMd- z%O;Mr5)1&JkOGW2w=t(3YV2K#4?d|(f=DRG+?dKHvW&;ZF|SrgCqur$GZ(e(F)W#H zX|jV+I<0i_3_I=gmrgP3K;z9n65T^&YV7^f&NY~*;R-C6|5RdbJLL={r-hSg7t>7B zYO|A``skxh+H3FQ&OUFyGmks`%#$;V@u-(~Jqh6hK;I%Cy5p>qh+|JZG5d=Udr&o_ zNtD5GW9V<<G}8zqP4=T=qFBb%DJ?#;)22t?nd99$&j29N<|MTUl{keZ6MHhjEW?jK z_zjuccbEF2&)e;_H=Emm?t*GOiYKSgqV`ls=``sfB(kK_ScA_w^JwaHLR$TE4Jn&^ z0!%k>UK7kFo1ij20M;s>n^5(HGae$T0AS9M{~S{?8?9j9E^5fJCKix@LnHKs4nxs| z9LTANDaIiWf8-7?of3y7H1UZGVo)q~OWvv|V;OX4{{<SDfCV(jVIBMo#2e0_+6b4% z7Y^cuFY{=Hi1gtOcc5b*`T&54sL>5`m}7(5LkOe5F{w$3Y#^_~hoo*1j(WsngIMYq zOghyKRG5kv-QdbWB4!Cnw1O(SS<F1l(GOtE>SRF7n?0b0ze&8qjP{V3JQxLlR^Ty@ zc+}w67K0zsWCTC!qL4?>5vFHcgctuXM^#|L7~bF~9{s?YxyCgR{CFc5-Eu_<?a`}+ zP%$R6*#|2`M5RKFV;tg0B`aH*N(sRbAzrJHED=|sRMz7+<p{+j_(6{BZHhwkIEOeM z(Tl<jgdg!R2SPa144sT4iaE>OL+-Jbbr1tg|KE9*Bntu$c%-Qv#b`%7@PikVphTI_ zaD^*8a}8-+!x^r~g*POL5;}2+AEeyJIJCi!I7X2lsYHj|^uY>!#L;f;V@T`pfsJMy zq#kMc<~;miEs<fv8tOsZ5E1eZM*zc3|0sxKxbhEifXXNxJWGZ4297%%gG%ZthdI<E z6n}sNSN1RmI{f#vdBo!!&3J@tx@Haq8mS!o5NJJ!`VW5G(}T-V2ueEjjAG=37r>}R zFo^MtrF{}?4!NgDD)FqI$`GhW{m7Oo0S<4#!>2Jkhd>17JJzJKbg2{ypgyq={Pe?L z+G(gYbY;^;2626_Y6~*dLm|$+XA{aW|7k&vSCoTvgBGpm&KQq^lGz*srWJBkJ<JJ2 zbBK%|hXBVsav6^-wQd}-&_pn5JG*48!W1TyVqO3Xk8!3+CFO{sIXn^%c(j8Z#bC#w zh~zN<;AcSIfCVQ%a*wH?<C{hK2z5QukA*cYODN$THEgJ^RBG-XG@0cr-IbTFkwZQH zID|N^+eVk*mtiL%s5!=AidaPR9SGX3JmL{Ia*P8K+Mp%t@(W#wWYZt@gbD~Ds9w5| zqa4PlhCR%g7nFP#8k|UzNdX{YZ<NE6$iYm0@ynrq1S1>eu*p>Abh{b<Lmj?&YFHoX zn~H{`v4`s)e!p8GhwADwEmkN(|864<OH`>ZmlcVX24V^Iv1rNo<ytC2Q9t$YLmv2f z;5YFR4|g0wD2D5!X9+6MOC%#DP`yWmqFR*M=){C5Y4J$@_>Xa7>P^3mN{?CG;_ryY zoS&4?AHCxYdd9WT9h9LvSh0_C6pn5x+O2oSagS_d;~lm^j+R~W<9~!hqxhJ|voNJO z7xe=l)9A*Kxr4kV--a2RwbEr3C!v9C!XWyU%vwT`3d5BHg#9{5g$(zPP}Bm!DxRi; zg{h54XaisqA;%@O5jROI1V8hr2I_30-T^b@9OY0NJB;C*XBpZh;r^vPpiv2rd=n*t z?292;oeNla!yWP1bE!=N|CE1pgB1cD$8#R&8}~vSEA@~_Cu%`jf-f0S1s=yGh$9cp zB?Kk6JV&v{0rFet7lq<%hfThF5R>qQFDPucJ#2!GHRa_uiLQ%^$svzQz`{6>#P2P~ zQE7eD<s4I;^f^e$<JG;~)Xe(_Hn0IRHXp>utrgCyiJb9-1O*km0DzRS5)@LYE6W-8 z%~}p|jHOlRE=0%PY$hQMc*&I{BA>^#2b$jGi5wlhxC8(kC=Wi*`ybUXMm@xlVR(>3 zEZOvq0&yO7bl$ul_^Ct*E!!*1e>Y8>JPy<q!k2$Y!xxCD&*AgS5R>b}7Y4@o*HKb4 zY=na@y<+f>&%s1&|5&eoYRB(EZqtgpmmVQpYXvjno%0R@;11weGuDYH(QX`~92?yr z@taK0e+>1c_ZavA=W&Txq-E(OvFJyB%MJ{aI(gqka642{GyKqAq1pO}h(Ge(u!2~J zc>^b5OZ+X_>&=EQWCJUyU&J|JE!kB5;LUpUOEncBR5$}9_=5vgpiF$<vcL;uInsBK zTWKi}`^?OtbQn26SUW(TMKPJ_{R1bN!vk5AKitOE2px+pL_@^ZKNytUoQ7C6L@K?5 zFFXiPh+ymFQeiRA!|jHJhzv5MNB?wGQBXqRyw-bk3O7)~NUfAr6wx6V&XApjvjsya zOkmu_5{q3%|1PAC$t_zHzFFkZgn=Z)NBjdZtiwl;!@1!HHnEjOg&{*Mj5mk_=S5ng zFw{MS9ywrwGyEYL)kFeT1A_fwcr^q<AlN>si_#@dOW6Z5JdqH|1f9*p6jmV=_F!kl z10~Fd1pNaud;(c);!(7eL><E+^uzXb7Tb}-B)lCwaMUeEor+vSFCa!EQbjXB0=#rq z2jNFM5JNvep3gbb`rJ-EZI}r<P0rv)3z47LIO08c1SdcPm7&9X6x}@ZPJfNV1InX9 zh~oN4pD!lPY?#6&sLOkZ8~_ZSKw(`>upe9*19N%U<=K}>a7}-(Ah_kBH=yHd5nM>D z6YeC>|5?<a0*+M9oJA@DKsMAuB_d83wiEz3VQ=JJ$o+#gV8hb1Vm5kIH;_U<Y+;sk z3MFs@7{;VSw3I~D!X%IugZX4@9S%4g0y=D;q8Q5g0YE&sN0AUzg*?eP#7zWc#a)m? z{b?6wu+KPfCA=-v2T7OJs7av}V5fwJNHiclR^mRr178?O(ftFcA=o%riz78+OSJ<j zb{I9aUM`ZNL@AVkbV@RiLU%}pR#-y97-I+J;y+ZJQGOgt&4WZ7Lnr_dFg@l$;0Lxr z%YLcIwXG6^;o>|P#51e|0N~I%K37C49x?obN2nJbuFpN-2Rf3&IO+~Lh(=lfW{uSZ z|2h~Hk|^OkA}6!8*0Y7eA_eCrvf4jDLNoA+YsQ4g36v%{3r%>WRZJr>L{mZ%Aw%E? zJIH1f@m9!Xo(f4r<ypzi#lrx0ggs42HQmNgSX%jYpeT`pIgk=bJ|;s6Q$274@IB#5 zvKUkdhg7hoRU`!000S?igv@Y_W+`S*-l9z%!rjHyWA!B40e~>}qG`5I(P0~%wPixw z(zR(r6h+lkq0>`}gfVEIEtSzfsOCtuM;HQDJe*j7fY*hD1OQY5UC5-0)<ll^!a2mH z;i+GRaEPP$!i>dZDES~NIu!5`6ky`lZ)B9Km?j=_%_lGePv!;Jkis&I)N6vx|4;sd z^!Wom#>7v))cSB{mJLO`Xu@t98ijPqe~km(90fWV$DeJ@A2w2F{t-N=f;-?}U}d98 z%%3x$qdm+;qK?&W@}Dbs*rq&HU1kG<k!W(x<8SPub84bh)LAz`0>haiIS$1=<it3b z13z@<oc_Z)tV2X#B!<$`cNoJptYDiBh=`3#Jg8W<*u$2%0$izB7`|9F_(COOs6+6D zK=jTqVPy)^5;oA9P{iOd{sTT})ZV;mHg?J;j1L`AMmK!ne6SP%sK-k!l534+OZ7u$ z(iAI#O^XN=09-;er6*PxiY7F}9KGmsG31}ILtNoky7dD)Ko?R?l?DET|7aAK%V7nG z`6wqy;?3C^RiOj#s6#5{WoH&1T~!)C;iZ-CWhz!r*F9&e-~%%J7@NtYKa@jbvd?04 z3N3P$2r>j_!jU;}rhz!tBm~1{PDKNXoNb)PI1to(-cmCJEK!8(#QuYFnV@>%g`e>u zyZ~m@+2nLdqNOJ6Si$Fsk%L9~BRa4~wk98`x>saMpK-LybrRG&$QFQoT-r9o-t|*p zER|fIA~*fnI?zSb4IleK*W&eqH(&-4f*AinSFa(;A(8_+658q@;5@KGH}EYso<&s6 z#=P`rR4T-&k*mnC;h@r)@8KRkY-y_M2ErxgP0~rHT-loDhDoeN|Cg1~irs5#!2?nT z5x-6qcKVlW&<#W)iX;u5JB-8sk=k--Wjw4LMmA!GnFBG1gXX<lBO0RS{X+}c!w_-~ z$Epy()lA6t;M4lTrI{Sc7M~&g12vRvCY~Yl^h2t-?zvVI_5c7CLJ@DF>pv_5DL{m~ zG-d^2DDXa8DqJQTI+wE{rM#M<$W|1K;^p5_h^J{nwqa`2RjklZ9td^TOx#Yc%4Tbp zZc21)(l{dE7GT-J!hGUfQdmY%v_mQEgZk2~JmzAEhC&(29q}<QBt#AyYS}&YgFaH{ z-|^XQt{jcADdQppa;ZW)WJQ*dr$}Iej)KiWaLou2FiE^#|I;a)I~cBh!C;F4AuFJ2 zBbLN3Wt3x8-$=BSaMZ)~XjwD;LoCpOx)fY~8J{8<V8*rGFpesV{G>T-XlwaYi`j`L zq!OJ$uMEAzwRM9%R7Ll>oHxkB>CEOIg4g_c!#t?wM*zTg;TMQ$o;PrwtL?G(?Tkd$ zQ$NsN558FH!At$(#p@BLFQi2N<=1Zrhaq!csbSCWb=~msMo?@*na-^YZbC8uXYzC@ z^UT9)A!{5LoO%QieW?eXNoA*80zcN^2jSORfM7d^>sF3aJDiogVZ}5yD*0uc$nhU1 z%!8U7aygQNJnb?vBVb+n!d(tAa^|8v9K#^IgL+66|E^x!0nyoWrsW_57%1irAySBW zo&)~%Y!tE@3*xBa+66vi-fvVF&QKc&UCr%uALd<3Htbkg1XDX6R84^5Yc^XyxTHvA z?J?ei$W+gPl5cbH?z*OEPa+(Yl>?^2#28MTH=om8zykmT<xqZ2BcjAw3|`II@y6~g z#{pQKO$ftWhR-e6Nhb%+!4*5G!s1peWekOncGvMd@<_}dIdC5SU9Wb~Wxn*R{WjA$ z?1L{nMN|Q%r50A^_=fHFAQL*2%w|S5Y6UE+lw@#CFnj`Mg-x9p<r~3+W4Y{=9t1Om zf*J-9o8?SUT!L)uRxG2#cl3e=$}?}c$C{kZ|9~XyQK)i1WRqn%;#nxrZ$g!I>ZP)# z2|D@%q&jFSk;6gV<ux}nY8X!2u2x(f&j4#H2r>s&DkOB|wrVUjLlB}j@Ixzmm*weQ z<`qS|bw{Cv-idvahk>4ijhHu(UI#%{e&Qt#GPi;36;2nP9D;WfK9N}dRBPQsVNr-< zr>YfM!c!tPRI4j)sA_3<^-^NRNtV$akk-dlwlGcgIzOEj<Dx(*iNI30zBSo3cBcYu zwJJ1Oyj6%Y4PcsB@BdtEky7j}79A<wP~o9QCg;n-?Pt!YhZ73$Xt#(w>`i3jjFrkL z(8l6o0>Bq;A!HgQ092e;M{s!MB2v<Y|Nc#7KVjSRlG^>wgMb+<2q8+ANdy2i>??y; z)|vzgt%EVlrdLK~cu7cL@0a?K<9D<WIl!{*%7aZTwm3Md$z}IEewIH>LMn7*c)15k zNXTpt1mJcM^BQd1YR*GU2t3%rp*lET5aMtZLw&qlNf($mFhfUJ6v27sFM(4obcFRX z1eDH3!cp&T5uAY_pntLg-`1~tFd^5K)?yGHs=cHEcFsRchb=yJOhTw4=`Lw&=-q+% zg|OW}xLt!ro#_IAQ#G@4Ji2sJ=T9?7SOb7+vUt1&g|0H3LdwZM`yVf3_dy(ry+PMx zhnGUkF+aF5b1cSQUBi?PRO{`f|KD((1^;e%bxPF{b!K11n3k!klr&bL>Bm1;uv2nB z(3f!>PHGEhJ$RZh)|@wE9#GkXPOOHlR@*;~Lon#pJ1lqi`NPUpb{pnlhSlHgU?WzN z12{CRB&jZjqC{zk7+u_<#A`>V;51Jbb)`#&1fOa&o#Kj)a2!YDyzlKfK+}X%kxOhX zF#vbK>p1`f$TNJE<R*tK|7hoC*+D!vH1q?3Cq&J;V>PJDgcM_2qJ%&k6yMHag5E=0 zJduY=JDs6gxmGkxaLtub(J(s%!i9FjS;f2_f<#eYR#!;Pkc>Z=Lw5?U)z;U^Ek;!h z@+FY<Et=3)FIW1pDMK8O|9LWKeSRFP&BF*iOZVYLwv>ahviAoqZ%Vjh$-Z_LBPme0 zjisSi2QmyfkgKj(JfdT7(~PS%^u~DV#m*+o`q0N`qe9TODfYb4@cL9RrBXixLnrXV zX)~C=j>983gB$_`0D%M1p_?~voVG{f<jpH6P@X)2{+_KPHx2+ge*-yo6j%`6KVt0Q z0f=}~BD#L@yuotjEndHZ5jmoaSWqT3PU6UEw0W}JKVSOz#q)R+X;P(2kN*2tFXSO` z_NY4b=g%s?aj{~Jn}_w^)s0stinTgVo5FDh%U*RF?_aug|HwIY$`rsof$-W98%GYn zSC6nT*&BHGuw8Ti|6D;M*UzfhapU%}+UIWEIRG00L>Al8>A8Q@sQnw~HmtvXkkR3@ zh7aF7ymtR}#)mCjY_MXl%KO)C)4zDUmGYMO?^8FEyiue3cPx~-pmvc)c1ji8A#>)? z=>=Qc-@C0{<$=XJ&|$Af_s-p`J&+tZd+hwi=SW*%e7)@A*RAc;y?ZKg%(v9e>&G5% za)HGgc>3v#tj_M4=bcjYG3_(Ns{3a#U)1?WG`mon=bvz_sV6oOnQQAidtAe(p5syz z%Qt37xu=}-I`XF+N`&JqLZ?CsC6ssIQt>n5HuI+*d&~jn4s+_M=e~cOYX%b2szmIc zd&c?al4jZy{|GT}0Dz~MZc5UTwz}3y=gj|7tIeK!bb<z^-8f?rwSM67#uWxND#*R7 z&^gB+cYN8W9KbrGPRB?kMQ@%d?U|&Or|LQAo_h+Sa2!aQ87Cfx(D|t*c{)949D5#V z=AU^wjc8VR`1z-pcGk>GucbN#2_0kD0r8-l(18mRSU{|mqfW1?3lmKIiDxENJ^d$} zTIS)-po3(+2UU}-bx$8w_~EBoS|=>g8UU!24X;(_!6zJSsN}U)dEf%3m4C`PX(^jJ z1BMsje(JQGc@8-S!Sf<IXv%mNwr5ICJDm_AQ?wz~R5mHR$CObIs<yw1$ngd+e`p#g zqWI9M|K=HV;%l#1dAxDP6>sd337zu_qRJa+a$apFanJd(T!a`}886Yw^;cbW-K*Cg zYkyi9rA|SlH#dt>0wAbQm=SJLu#p?vD3;}+YOy<x`Da(P!&P^&P>wN&oK8P72+UZ} z!RRQa0SM+2fAdxKA9jlI)6={nb*is>`necfd1m?tno3S4`c#R;{RyXjZsr6go>7_% zTVE#g3f{6^*Ae0-kNJcgs0j6xZ?(pm@OH|Zy*RIsE-5@7y*gbjzH;b08L$U+>{PUM zih+CO)c_!elfd3X3MYRu-<;=yg7Of=h6Eb9JK#HFbsTqCA!@Rfp*IX0vL!tTHe~RT z|A_L7HM2xHzEev7+{2AeEbC%FtH(dYF$s52<srVpn5AmbiFizDLcii0mP{i!rWAx9 z;%UYu#=#F$J&PRe$Q3;F(+@)xBz^JWiz?b-pX)t_C5?fGgCZCybI5}ejxklOP*;m= zT%>b)3z$5}VUEh|14Lu;ojs5dj!pHhS014p{<wjS*vQ6r?m5RNg5o;oB%?D@oZzOw zF$s#*gDqOr8v*YTl4DH5AB({qtNQVXUeu<CfxCxVI)X5f%q4wUJkLe`A*^$_EP==R zN3zHP4+8#<a-s8vH-h+>+eHL*?<>b-H1j%B#_JvwBau`Plr`S<;u7%q*VP2)|4I_6 zr+g=QmNyz{5tr?0iJhv83gH0{i{%GrJ#ilQ&|wdF+^KZ;X$LE;)Gcp)>uc*%+C8Yj z3#Da~Dpjo0q&fu;e^{e_*hI;1EMYK!DFs#k*n~J#c9PirBNdaFQavWb6nRbQA5hX% zVAMsTOT+?1llqj>G@%W9oRBlptD}bSRk?$Nq!@FNo6T}Yj;MLgpZBN>VT4mH_RV7` z=7^sMk-{o*2qhb)InB2q_M%N4u9hbeCOKgA8e<*~F491Szh1|qP1I9dvAahtLZPXC zc7&EFappe`(T#slWmQ^fhAGBj4s`V_DIo-aDS{CgUdga8HOyP(&a=yY|E%K~{qYG% z|1qGRd^A-Dy9ctARXLQL!yc7!2WCpC#8V#jD4nWXDxhYQa>OG{q@o;6K>E3H-6MqK zcmy|C$0?bei5SYUVWg19OJh{S9`=!(QFIuSKym~pEOACI%mI&wDh*rOnoP~2>baGn zu3Q&sPi3jpF3kv#r5>>dyJB_Chy(=~v>?YUlbctX1f><raA!j*)g()#q8}A&T~b`R zn1vxI9yTG7sJ7?2a@gab_DCO1dRfxW<rF0UScfql)U$%X1pt_Er|W#96S^F(F8c6A zIo@%Ob5z$O>?21uRJU82^3+85FvmQol1;4XbXAMNM*WKCS9t^l{}s}(-|I*r4YeJ_ z9$&J=+idHR-qNJI_UJ??!VAZPyyG9HaD|3D7S?wFV1x-1*U9{`-+!P?a*^_s%laaY z>q+jK0N^Avb{4^$>eV+So$pD$MB(rV#IT4}Gny~9m^*T4iw+q_L+w#woch)#3mwlt z+`$iZIY)8+(vKqHDG%g51^~vO3pt8~IZnXEAK#LrK&W!EAgV+lyS2<b9Q@I6LF6Re zVPZ->+B&f2r=r=E<Er{$qA3|fT|uz~H~t~8C7vXxq=4E#?ct6nUDYsn`Ey3_847zm z*mB((2R9&5!mm#1AOPqGEd8-Gw5o!I%FL-=4qXpolq1_M|NBSw5-DZe6%$Ze#_Gk! z7gJ=X87WH4%sbpsihWFGHLKz&Hn@S0z#I<Lpq3iAn43tp#)FK&bloyqf#&mZ*dE!T zOPA7oW6w>=AKBUGHPuoV&ZL=gSjosEwDDknh}5)a0-w1L(x{Qt##r-+2RUY&r*yqj zuQ+k^UnEDlpin~{{yp`YiOvyK9zq<I8YiemSPv8SOi4)r3#&$`jdy$nEJ2aWRVmum zNLLb9!vf4aAVX3{mq+2CSu`e`As<!&K*8o{uycUKoX>cqAV$hYHpC;C&Im+*J4*Y8 zY*R&l8;6|$NN?1oPNS1-B4KF1iXEe~nD#P-H_OdV|3Aq7psU=9D-1DD*~Ge8licth z)i6dqP!<`Fpyp)ocm_KfmA40RQXtEel#reYi(HiMF6iI~0EY4ojYNn|91_ZhzBH#2 zA){h?LcZWf^bdUKuO7p(N@t|e&K#Z6%CjuX0#gx+ZCURqb|;Q%oOG$TE%zU{;^10p z-T2LP=Ag04PvWM>LK2ltNc8I&VoWe%B_4zZPlki;rjH|5BrI}>L0l+}#^D|Ip%hfA zl!{IR1B1hwWD-=YVkV@)R$)|f<mPfp;J8aPUL{sEC?sAkeI~_N+#&4fLfksZH`pq% zdWA#`%=Sb>9aw=!EKb$VDsSdN!5&Lqq%9l(|3H;2>pWH^9&W>4N`>A2ffs;*9MY=@ zk>V$?OBodJVJhVxLV>X)O-IHMgC^k^-iQOWg5<0W4JRdp&OsAK#a8rVBv>dTOe|GS zE<Wai7_>}25+rjPM81a3XH=pePR14TVshBy9FUL|FvBa}X%TNl9elwwET%3-%rIyv z;5KSiTm(11XjX!P6bdG7UZ;$%Va1$;su-rStgE*kViv6=)6hXw{(?l{&9ZLdA4bSu z4q}*!!5+#%5y>fWjKP`WBO)L}Xs$;im?d!Xj1hw-XJUeVQqLEZ=9o56&0@zMj-eCE zLA<^~ckbcjg0U7isysx4D`1U@ws3h+{|5aO3LR+h<sL(H?gX$#D=FfmAId=|Hfc4S z#utVV&!Q?RFv5NI;mEwg3HxEhV&&5$NLFA(f2w9y;37F-4igIvC4veSz$PN7!XyS^ zADW5Km_iMkq=KFT9zNwCdLc^?WxQDK$TWsy;-ej&VKro<3oVO88u1z0L1tDWXo8`1 zUMo`O0WdlVTmWD)0KkYwX{I17DUL?4jBgS->>sQl9753{p$fztf?mAHVy5LEC_x-v za#G+T3poU01VZBkq7`lN#)5(kyM$G=VHLFDE1)t33j!;&p`jQ;D*J&x?29XrqO?Rp z?4S`YU_n_t%GPYmCT3+GHmNb{|4AND#}}$WrXo!oHBcqR;Sk=)Aw&ZwaRjHJ@ET9z zCNIGs!t!MP!DOIp@bKaw;9~2@!ANM1L0oGY@lGWY1Qxo%<I2GwvY|B0VOHR=D8&VJ zvSoXejx7I82k*zWkO3PYgI0dyfVglZ$?GSEgAx+vp59EnB1NheC_5+ytAH#P3I}k^ z$RM=B6uQC~6XzM=1~9HuT&^c1W>2KzLAH*QXZSNdFjGDPV=~-FAH?G^DC-?tN@>i& z7h(z{@aOtqgjYQ59c`(*st7VV1unRO6jtJ}B%&KWK@8VsGiqTHp28${(j9v%D2SvO zN#q)0VY-TpGh<FGVqsKF|EL`9;Z3$M94Dne)&Us&0UD1Zh`d2G)6+U>;!q|@S?Vz} z1j`)`MJ`kGloYEU*zimqA|85i9(v0QL#=1DVlg=nC_}3rfe|K??N;E*Ul`Olcc>8^ zMJWjK06C!>ykRvGh8iwp%x>%&&qp8r?tEb5H4FmaQ0by9GM!iy3kwF%9A-WLp%sF` zE}`Ndc1%;EEe%1;9Qr{jQi)aU0TRN&Q2BEnw5luKfggH8dI(fAIg`y~=#c0F9sZ;- z5YaFt$Wz=yCw|Fkgs@ESi%U5)J83~HIIteVAvesSM9(q>$8a&wNxndpV2J9J<Y6&L z!K&^<Af)7cj`YSr{}no9$sf?A85ZK|niVBJMLaGc80_I(sIwwsrCL}{DuJ>Xc%l$D zDTt8MK=o?>42)X-23x41iJBEnO-ZrJFco49l)wa5(DQ2M6iLV75|Y8$fKnCwp(bOn zZ2n8X_{$s^^k%m4L6;)7TEaQ?Vlm$59W?X9GEzD3!OA!Tf9eGvtnfRZXI*YXyi_q6 zMDkkc6)3Q<Up6fFs)|WAg-1!!S{7px7|WOt!VU?OSNIbEv`Q07NGhB08Hx5pPr_J* zg@uw8P#DCvIF@Hs;sA5T8_wlR)PWilk6AW!DKcXo1S>=<<rI(0#H#BjF6tk!;Y8x} zI9h?85bMND{}oliHBJDab8qd&mg^W=Ge>6b8c1lv{5IyqgRDX{D2!n)sx>lq5G2Tf zh63?VaK;;&>E`CNN2M}a@2bo+mLD9fV~g%%%P+<vZ5+hm65`TS<P<GaHW(1fgnFVK zoG}r}saI%r9oFG!5ab`6;Uzfdg8;WBelI3E<U%#q;*`R{b~V!m0w0>8Yr+<4H}XW9 z#3BA6#kMPV$5mhcAsJ`^YMihf4xt_jQ3mZPZlMEiC{!T`(?})dA++iewuQsqY8{Fx zBMfw>5_E*k!I=Q%C6JRpsp25L0hG`o8`Qz0PEc`~$yY7oeB_}XPO)e13}vlmZAt_i z9?CWy{{cEZ7cQ7#Yn3iLxYl&Dsa8-oM>k9>wwG~XH`#V|D+ab9zNCDwDq+ipAVoq~ z3XvRg!5O$LwdfXW1x6*%L1;FKDo$hX5H>lRw``OsmFg2*?IA53K^vYfQm^*U`g1&l zPb!_%8MAGIYeh5^2S&AQStT}yGeRXq${85sy_{nxT2OsNQEfQF!QMe4^uZnUmn`=O z;!JdaE@mUKPgCF0s*IK-#pO4G17ec#4q|29NOj;ABcGr~g_{9Dhv-a|LeHAvZ6~oN zg~bMmc-t<fF4%#;Rv7>gkWqIw3M0vxgr<f2;V(XPTd?SW34)P%_!4geHULA250n%y z|7LAmjh_Y>E`M__|A83}2wc~s6Z*8bj3<=>>JS<cRKkQDA}x@Lwu?QOV_tArVsM#v zaHrtHcCW{o001+Y)mr(|l|m<msRGD`!XbW#k536=-~k*4!5zT09umS7d<=^OXw~*e zD_kKMz}8LHVH_a2kI%{*zE@W=LMM1)lhucr9)ujgfpl8MAD+m;=!lN&_Z(;t0MtP< zB;q#u_psFRHGIrpf`j60+F3K{A1t9;LSpkIxQ|mw7NJ8r*!3TR!4!^VgCnI{L?cWB z;|0UPN_(!NkLP+4hZriUz;a<|`BX=K=1*KgKFIkVYWRi?P9M+3GX4gv(eaX$|5|q$ zk;80?Z^S{@)a+V>ibKdG6;AJ)sX8L+p&ZPCmHb4roWUL#dXIkxl*EDL5ELH1?JtHa zlMfZ_0F@zRYn-tt-sos1a>$PB;p!~o9C~KBQyO-<D?8xfpT}W@#NnZEm~sI|k+I~b z5rQ1xs+a_lRBJ_sunivcC3AR!pxYODoFRxR=4n>y&gSNwPT3!ZA|AZLA8e{27@H}m zg40~Xiq=IO9KnFAyGtX261Z!DpkrHt`BkeJ9a8t95ab*PhXSANbwJ4<NX{#2vKaV7 z+qe`Z4lU5M+tK9V-71=yo2mC+!nRE4eXKH0&3X}m4CpjF9>M|o_^EO>|MknP1;M9K ze`2F9q(RsA(v*CI8`|kE@94sVEsnp2f@9hq2I2kSAylqGBjzwE*jpSR!D0Dg6#m5a z()o8}2ms2L$89D{yX>QD6C1<X6<%UWXz+a|12wJttGi1aep%X<D;9!b95@fW7585| z=N$S0611Tql+kwWYl8ElWg4VmS6MGOp-}{zzEQ3*VjAvP!75pY2rDbnk4!qfgzRpE z!wmGmAL<;sI)X_=9D)NqSzFky#veW*h-(r^xkJk{e2xBrCFR4mLJxghN0R>m68>l& z60{vgJrZMia`F^zoFj7%%(L~{eRF{s5Ro6;M=Mwz&S483fNbv&|3WrgV@gU`Qr)pr zR8k(?*~zt5T@ec;UurbVFjG`G*+Keh$g!$4MKMdRRQz^*ruPyoy^>VOVO65t+3dgU zVZR!&PIN-shgZ*0A`qDq#|hSPPlM1A>z+Qal0xD?TjhE;bL3U<97xU}LPDBzmB8w; z96}4mkCz>D_jp7Hd!XSQHboyuK|I)<l!+Gr#>5xWrbMQJ!-x{XcW~ax5^NP%*Qg85 zuf`}yK^Zt?frw-~nrVV#(jV>s9Ih&+BMY}p=^!ROOl(kv)QTPZ6cC3xR|*vxVBwJr z94|Dfj>iGI>kS+=mp|d1@4UhuFn3C@H;z{Y02Ew+6}Vr%|1U;m&8iIJAO5m)3av+D z@>05?w*EmINQh%dl|nVE7p&AV>qATRSx55bG2dGrz9(<CG`vCQR9FHQT;U=@q8q4T z@mF4@yXzi8AybM89h9_?XC9YRP+lIX(q*QYdbcNRUu;h%9xCF7I{Cm(j>dUqHF&8p z&VhxprRjO=>9JKWSYaMk*&a;fszy<K6Wm*41R%`)qZRC5Ie7@>0a(bep~Hj_<&^^f zj2F6i<^H8QX3iYCdmtT(9EorqfO_=+91=&aA3SZ3#M$#_a->a>^XAF(SI*xh0RPP0 zV`uCfIdbUwA-o9yp}%`a{~2Q!6#%Ax<oqdQ$`zzP|9|Afae{`D-#%6V#*G7@b1T=8 z=+N<-myO!Lb0)E2`v(tX#Dq5gg4BsGTr+(01hy&|@2%se@&0`h*YFMidt8?`g}Axo zJe2l2g|b)AUb9R7*3Jvr^&Z=C|6(;8NA6#>b>qBc)#~;!0Iy)lwIenTp1gn1IAQ(j z7cj}c^5WWq=gk=`Z}8yF<K^q0+MK?_iw~a@^dx2EvTM7<t)9Hq_n`M~2(dZrOS99* zQ`L@~w|@PMw-8AEKt+y8v>5acEXpBOple*k1)y$YrAH1e`jqpXe4J^95J=4dr4In^ zxO2`w;q28HgaZC{PfqyYV+}s!C<Y8U2XW@x|6dceVi5oW9dZm`tc9mpd8M6a4m|Z} z1Bp0z!PnwK2*LADFqZ@cKsCkKqgzs%*+gJJ{{2%-HT|3j04!J)IVFJpjg{R$(sZX* zn7)As;)(jO^3OZu0H7CXY;ouul}jOHk3I8{gAX?0;A2j0t#tEGV^h)>87ax|6(l(4 zIA*A4DE)IxCv!IQh<9wcDW+>Cp>s(rLEZBVFjxhu)S-@zc~m>9_ydnXuv|sXJrC+A zl6(?+=?y2|sAZcksf`0(rr3`6&p#;L6G|=Ql%|a)_MGU?KLC97)k5ozwC=h8d^L_g zro@8IlI<7+&r#W;Tjn#*C<qIiK%wi{|F+v6<q9<Cti?(;^GK`i#1uQ!ZbNIGwU0^t zU;{uuGx?J#!k>vVqfu8XgD%A)JI1m<jqwu8XC@7@PiY7ntnFp>+;gf+|G;!ty4il! zS1ehUgAP$%7R+wTBO!d0t>L_r5hrX0nk_?dLNnbzykz5@xfdU-b6Vt_#g9An{G-=D zA?G~t(+y3G?zUPLc1=C^{^N)^N^PBPWXUABkU0Rz#MR61s=F;p030*OJN5LVjVa!l zw5@Nc-Gd)(^8oyhZui6swQo89N=!TP)HZON2+!><<L3f!)L8bwmQ6O~NGtg7Z{<Xq zsgp4IQcUxX8rW8YMf}gK_S8mH|LgxfXk<bKMzs#E8NIHxt0NI;;Opa{<4cBW(KITr z146hKru_V74NxHB8D8`C;DZc4+DUfJr4hMa0J-rAZXxat=0HhK!1ov=l_M0W>Ps_X z(XeZ^s5w@e;5fwb57AA{dN=VEQbgB1HlagV;t^qm#?cR7WWyY4DHQu0lM}U^<sEFR z2R86g4|04cJ{+P?M4A_)8THK)fcu?1A`=W!pz9va2t{MGvzcYB?>(R4+c73lkMhML z7QI^_i$VxQpqL^{ut~-`a&?c>-49u0@<u$S0;B~QtBuXE-$RB7$D>rjYufRJG^$k- z;2BaRAX(Huz;TFrz{4Kv|MAB;*0(%8EhRR+C<o$z@eBayhB;$=%ny%34t5a39J+a( zJQx^0kbDF=%JBw2SfP*JP4bE!VqPd&Aq~xW3~nJ35dP|6jc_pP9-GJ!3Pm+UgHVE7 zi#$X*6euO}kg7D_I){~dL9TJUCsTUj2ReGODsOa<9c%;<Q(Oa*sIcQ1@t_bi&{4%H zN$4Kt!~~nHR12|vr=D-D;W*AxA|B3YYV`{uL*#>`8MUn(r09tfBclw%`9m3ZI2%*e zha`VUj%}W622%7yo`0MM9^)v-R7gqB@vtU9|Ki?1oZ*ax04R_1*<*eBIFE&)V;t^a z#Xjy5szVx8B#P`t|05@Ins``im3mTVYnp=&ldg(`)i6f%s+Xyyv;-Z+XookR1&x37 zBQD{Q4mpa|4{z+l7vh-5Ic^!%x`xt4h+4=z&UX@G8uK5lBu^G0Wsj;l0<a`aVO{?r z4omQbPMzRZJuE07Bt>oz^MFS@P9qO*7Sf*Rn8!QDu?lVcrx?;8lZyiT8y7|88pW8$ zSQmy6v|<ZR=vY{K{NamkjP|LlWr{%edX0C)2pQq%$2=4%)wk4Dc=kZ9J^pcx0=5)* z*Vu%DwkTQ3BGRsPRpdMl0S*>IA{SH?Ph93<Qb_n`IBQ|ZUBd%Yb3S7oWf}{RJ`!B{ z+7(XZz?yg7{~=Vl-twpjzRYyRu@ZQo<BQ{%Y+L>!%IJg^9Zt$kJ?=}&Y}Ga?@ZgU; z<q^N@Iz~dsfko^3#1D_0@QTYrNPK-!4Rge3hw-RprW(2z0F*<!6c!*vc=8DVIJg#* z=<a8Qyr`T=)4}y>m>$Oy7k=;qCfZ=jN{=$-=eSd=07worG;7;zxsFW(WyL%AG1p~^ zM_M%g2R;OakAJ`iFkKenUr6K7e<Z_+6Pc)FDD#h6ghI(19hIJf)D3HWPMjuw%X$HD z8V$8$6z%{(T=MKPsCdI4q8sa2;&Ij&S6Du0h8scOG1mkqcv0r)$0UaIyjbKeC-SK< zT7&k8|8Z#J9na`SaDJDSco4&r<Zy*Ibkg63NC+L!sKin9;R{V}8ag<Qu{;{~k8S|z zxN}}EX0TNrdk~gR1&l|KPo0o^RP__gm@bkfo8uNiq{;WV13w~+AB|>ey(ZCwY1<Lj z==m_G%Zo}k!s-oZDBB*T&Q@H`l^p-<qZIS-$F(^v+=#(OkO063H+FbTAiCL#e<_VM zu+a}X0UCHq{09=-Hi=%sL$8TWlzc$q5%Q|#5zVl3v;AulC-rV0#4szBwsxR@496bO zAS*fwd%_(-=PPHf4YmJNW>*7mTd@Aetfy;=UO?$(>2l*u?q+ApLBbo_a0h>ER~vt~ z|Hw+kpo*9Qv^leFs~_e_4oj%b7KEjJZn9gu!KllY7=_#%A~Ri!`d*qr^@A5T>Pf{o zN3oy`q#yvOMJiB|5&_xGtYrF!G$Raj0Pv&llQ(?)9^njc5S(>KN&M`vuAjVD2U<CX zy@0mGUI$m)8`L((>kFoK@o+mEwUBd)Xq2<qHQ!>6GaWoSwwHleB+}UW$Gf`)0BMMa zcJKm<KxW+!ahO6IIT1cn5Ej~dj7uBiAc{-aEC1osb2#N7YTj@TEoXgi!8i%CR<Hnr zKzzRd6zbp$=kN}3(SKf-Enzon@lX%=@evAvQzz#Tt`u7Ph9BPG4q??g$1-157Z+Bt z4*%<b4%UGkRL5})QDyPO2^>@xm(pfXm1~)y5cA?~#uW~aCvMp?82ykUZ4(Q$Fb~Qk zgD95}8G#A~A$Gk)P2)jf_OO1(z$E=P4_((H>(v;h;0pC%N_>G(UA9w4VI{=C4&JaP z(4cN{F?8Q09mt_<<e(1JAQw7_aO)&hb2Sfr;tz$fL*;O1JLrdcmJsFPHrOy-t-uX- z*HxR63_wwHd|?kLxKN`qhxZU`p^ysyzzw~YW1jdJRW@4v#tuN?VDz+!t+5bu<#fdm zfX)Cd<zR5@_8dFqN@2zc)8-2$(rOcUNU-J)q1Z)`pbcN)i8?n!h(cAN^$z!73je_X z0QvGr2n9|HkskEaf;DAi<MtTsL=MxD9PsB0>Tp6Emxw>~7;Etk`v3s@fDg?ODbPiS z9_Vi9a4tyL56Vyww*-wnXkqt|5xkHf_CQ_`M|Jx6VTzK48j%W+^a$F}Mqj8{3&9WX z003XKG{ta+Czyu1w1#Fv6}gZLaugtVB~1LdEy-a{yE6~*(2gzzA?H9(1XT~sutTp1 zB8$Rq&9f+wk`j&}iQorLRmBUqut)#^4(L)?E%}7G1|jTq450u3+^~#uk&y=oLy*u6 z@30Q(kREw8CFST64Cf5Wri~*>kUM7}TH$cIu{-Dhfk|16*y2jWlNuHY5C4$HfpD3K z>!pgxP)bR+FDJN{3t=Vq<$~8iYHuVRQ0EHH@DJ)}E$xU?L$?;0c0M|^LkF@b`q&U3 z$X?-K4Jbhh(r_06WKACi64dnxAae+ovM8sRf-e?!p%4o5u$AM07hahs5MpKH@J0Xd zP9hmhR@6QwIThY8Fe|x@E_oFF5DyM_nc3hAqSc2kDT^l}4!%&2kb)TS5fbBAkWe*; zD59E@VJUfeK})#`Psv5*IBu-8KCA(GsW1uta2n!ZWy8r85n~Fu;128X429%`WVD9< z(1z6k3u9(**~W`}WS#yHlbERvr52xh*&^l94~#?|m!J)R>5R~!ZT}y}k;j<}0I&|m zz!yd#IJ=gh;{XdPc|pkHB{*sh>c}YVBbW>tobK=sw4_6kav*1^qwFOkD3MHn)qyz| zK;p0oA}UQ&H(3I*XIVH8sW5uYpb6s;4}l4bk_Lj~kPA)8g5_Wwrp8Pv_zwx{4$@G2 za_FJX#gEtN4VL*2yYmlax}?2=lX#&q`coS3(HzWq6N2#~_TZ%WKnfgWrsIK-xIhla zU>W8>8cRl%*ajj3ftBtM3#MQ#UWlhQ5iz9NL2Gn##FidXfnP89NGQr_je2bkcObNs zIaB$e<n|fxuto0R44ObAr^<s<IvD%b43IDn37Q@JvNZ@nfdA~!CCmU0NC8!8l@!rq z9X_fLX<{h2riczPSMI=D`XD1b6e^|JN^&J5#zYB|Dy35j7>(5rSP6JRi7gNT8^Y=g zmmn#pT7)mMtdC$1#;`^QCuB&We+wf={Lro<AtBhw3E*Hp`rr=g#-Lm=SMPwC>AF7> zwo@|5rOOo#$WRaAU|p0d9*uDgmQbJXu&G-57915Z{=i7(5DUp*s#8*Qt8fo($YvbN z6>HcJ>EMQ(P<sHfX#mBj&><oHkQ~^0KKtffzM3ti0S+0J45b=>ro%D^C^8eXT;kwf z_mv&&)v2Zz90cc)&;V4+cYRR<b`c5=wg4z=LAL60c>jHSVsZfhE<{Y5x-xW&I@@v% zGSVKO&~%#@9xSsHRT?>m0C>ofDJ-+KjpPcY8V~8WH5zvmt56Tcps*QNHcasq34;#n zKn%&o5^W?nc+*y}(3-T=J7Ftvce$ZX>K>h!c4K>b+v23npk3wAvXIMOMV1Pk03-nN z80g2h^-vD(a0ufthBXVK<lqdlFb-iAt%vIy#YYbJr42Ti6=D0gsrxc`6Hl<<3_+z2 z+?KV!gCzGb3E+?mmrxH~`C_}MZOuatq_|=1AXmUsAi4o8{@@DT;0>gSyzR3P)o~2u zPzvtw9TTQdHmeZ-Ky8OwdPVyx?>ZyZ1wiy#umAEO5SzdaTQsv%CphIM4jE+%vjL<^ zBoDpw2=y=(=x}fhiV)e8oW?K?l|UOId=u9eq48TmPun6#QKaXCvfYxwzwyKE_9Ez@ zuHirmObEfEv?z;U523&jLV>(DOL}(@ozfs-65A-wFuMGKN=N)EEn!LkV1wR(tWf(G z(g6<+2M*xi3%`Z6^jle3gbs(`49O4+<G?63*~B_^#Rx$T<AM*WKo!TrlHk-vZhLIX z=D-o>8&V5*$~K-D+!=bDXl$VlA!iM2!?sMSxY)oA*3b$*mZGo;5g9=W*MOBlv9DLS z71va~<Dd!6U=NAv#fkQF_>gx;;lCRU5&uU~t#o-TPod1Mgb?1)4GSYw|HK+c{DB`! z4cXAUV)Vaz3{_tEDD8j?36c@OlSuZk34wA9u$;~el|>6V4xJDVraE+bk`t6%tk2LN zi@7xbX2*D#6cviXAGW9OdklV(KKES6;#)Ec$(FNWXP%f?<me(bbPlqh4Q<FTntWSv zL~v~BA9K+nUolq4;0(fu!Qkc5kI})tAR{!>t2>s(g@FvHkXigCv8x3lut5slFvjLk zR4}a1laLFXus6yzps)!WtAGsaz!IN!&E(ie>0t~jtt&Lzk6-}}F-<LMaY95b60qUH zs#y<sQCBxP7>+U{xbQz!Wk~m6CI6cM4zm`%-&NBu;?%hyrp!370-_eHU=7CL4kj%) zFol?W>K`}NT!UIy+6)e`5Xc(hvlhK$S#%Gb;0m3f4Q+#nC;S{a;SK1p*abZ)N#SAg zP#~TJYQb=gp!F1E1q-2&4V^u%hN500;xSBO5_7zd<<Sk;U=6&WX(mUIC_Gu6APqvo zsTEye<<ZEU5DNn59y-Rao%LX`Kn#wJ6ui;ZaDpAhkPFU0*(d#Pp(R_|01K{QC!Q@h z<<lqOzz!&Z7wEjfbp0sxKnbmx*Dz-#01yoL8)#N1uKFAbnxF~ZV5~O1JbEQtq-6@v zAP;ZYkC1I3D(wpHP1Qn#DE}$yAFgl=_RUV%{Mqf3JB8K>mCy{8gUbIM$%D~Z<gg03 zpfAt--Y(fP=41@9zz~l_WpWWu-f$|}kUOA5Ni<Xw?%)e6ClA?6u;npwvcL?^y{JM7 zL{=gVNOlbUAYrm?zmw1joPZDIgV>u~L;rvamtYKHmC3EeOz8~|#NZ0B02Uv!)-(8G zx^WDgKn>?04yJnC?UNIH;tS!BT$;vTx%A~Q^60YgKie12dtGP%5DJ-=%N&9v_K*si zV1pEn%{q}5xF8Ea@rEsK69`-!#^4IMFye2z!O;jJ2rLe#GDzgW)Gn^0Un4oGz(X%0 zq>#Lb{YnnVunJm5I{!c(%p&6-pvDW~SmJ}a+SM@$zO5EYYU8h&Xx9={)esH}v^A&s z8ISS^?cgFe4!}S(UEuHuhmb>r44X(Y4-kF{lq^OBD`O9K2>}x*pfshw!F%v9>siCl zukLI~(N@vf3I626<Qg7Y#|n^w6}1ZL_+v7%aIvMM=~luEt&mYCA!PXs8mTY{oX|zb zZpOmg55b8GtMCltR@vE--u*xfz`zaeo!TZI5lO5Kr&0~xVJ*RqEyE)@oRC1k4fIbK zD5_!%J!H*-vlP~{4vWyhK$7faBs|bI2;FeOPo+HLG3CVs*NQ$8CV>*zkO|=6?$C|T z2_f&4aA-$<-T%ylB&IS5mB1vSbx5><4Wocxx^cvld?4$v3H`Cvg2NhvJ_%HT!E4_T zM-dMIV@!eKzY0<D7K$XY(7k00bMjy%*%b<iW9H1{;Gl5~fshN_(kK$k!PdYBYb0NS z!+Y~!45k1LTsHR(&Ec3j3Ei-7NT2lLku#(rqFr!kV+t>L^SFzXeZL+Kwoe;%_jQdT z4ua4ZP4T%mjWF85wHp(heoH$R4-~dQ98n>8;b$;BgbeJCdg%+;b(4Kxu_)wF2!}u# z08#JXz<&S?9z>W>Apn2=2KKY}4_p^c@y7LYSa9J+jt1|MBZn^yHhUl&HteWyAOMin z0+l3(4*$T)lr?F3BX`V?yLsr&t<+ev=DBhHY~iYhj@-<X{tTiN+K?bYfw(e(q$yOZ zL3r~3bb7b-U{i)oY1XSp4%`@6<^<l$x^>{Zf_&<+^g1)B*n|Vgc?0llkwJ0;$)+UR zG~+ye-q0Pp!}HwFy?iZSu4%8Hxqn^$)Wb(^-o1PBOrJJrx}$0Uq)B@X$0uCc(f2Sb zd`-7pn{NM5^UVz}r<{M}?Ac>|TDd&2q_I{5Fb?EBr?)-2o;R;vKUu1#mtL-QxjfRU zg%`T>4=uX9)=iTJ5K){JXyxi<hj0C0zkVR`VOd8ya$Ey%Bi63NDj7cJ0jah8tb0wK zdjITk=MHfGIZinUZDVPid02TSv;keyP^j^8LkpQq{xJs~d-U6AI{<<q2cCl-<Y+t% z??J~!m~w#S9eDmhhd{ARTPhqZ@ad{H7_T$vpKkiF#~<=YWG<x=-*e5Mex!5d4|v>} z49X|Z6iYMC{ODwyan7lYKpbnbjWquJ!-5@{(7f@UegNPDO?&zQ=Z<n(l*z$5<!tVw z!je&C9_fnYGdqD~dE~C+<m6B*PD!(;oPQRX1g$1vB&|mP`U4;bXN*%-P?+!`1e>%* zv@F%1q!EP0EBWL~B00=4&K@K6L()TEWV!XzPPZbk$9mvdWtFsmMJOo%ju{7@yZ@kd z*0op*vjUcX;E5HprPw(|8<v*BcBXC;v8P8y8;zE|dA#YTmh{{q$HRCB-sm`x2FXP| zD|O^cxjV<fr<id3X%Nlwm@5YWX#T0rx+?W4MYQ8m)A2x|UL&WTaBvZEPW?!W=O1ZE zvFDtN0m$;m<+3vfok5PV@4ohKQ?4Q7G<nt7XJIrtBvobt$>bwrzJ`<mJ4Q1*>Gbi% zoOgPZT0fBN;l>(#GQK$Mnohi@o_kio2EV1BT<;ELY6KvjhD*-*T{oP0(Pi<NvnQNP z>;qtEKL6py6n^~y`?tZBi*RdJ$RYC_f;U(69<Bd*B$j_hEAq-M`!?`2=l@b3<r<g- zCt98%DdEPSdDIr_bC5-|7rc^h;|73s&cXG`X#Yv3m4C{iyg(Cmv{ama4yol_rD5dK zv~m7H*q?aPMK(*2>fxiEyNVy&&i=&F#Ib(B-%#s$)M4eHcP3M9?p!_BE}T_Di;vRA zlRj~wqa6LP1TcsMJIk2HQrhAcTD*cggd|5t1j<+-U@<88oy>Xc7{#>UWijxOLmQfa z#&IG?!Gx47H{;kADfscVL~$-&1kxHh<S+>P{R2y=VPOSNb0>0ygAh#m4yvBjkAK*K z9mX+@l^D2?9(4s4#2HcA_$HRIwPO_cAXaOF2rkaZVilT^8_vckME~VH&>nZNgm#oR zMLL1!PX7P{ER4f5H1WqE|6#|iO0>2sfdn1hAjA#%w>`*=u6Jup$?EEX3tPY>JcHDd z>RdAuGpZ+z;j>g%tdNXi#RGMjELo3;IEG5h16?)rAe8=r4J_Qn9DO<yk0cTZagd`Q zS|lXNvL_Faz@s0&01Le6Xv5pQ1^^S<Avw&EA%<<Gd4*9@I7*_p@Fgy0eW=Fh;B(5F z$S)OxaK}4*D9kNBZ+zhx1vrQYNl)E_SeZaZ%Ca-e%bezc|A1r4Z1g0D^~W1Pa>p<A zcN;$ffL7M9q~xAQ8phS3UX^)Lc7}8eEN;qq8yep;N|BbL-2YBB^i*T>4DtwMpd}vM zw9W(3VS{7zLxM2PQ9B1ktS)q-MtrmkO8&8qCE17^n6yrhiera%#A8HAeV%eA;|>5! zViNZ7#wVFcLT7@843qeWJE#dvYYwqL{{SIU;Izy-5{Mk<a0E+i_R+0qtsloYgm65n zMX0WZm?>k2CH7$wiEfB9k6@NSYSY)8wo#7YI7BDTbsq=0=So_uhaCRUk9UlWgfqbg zA!Z{Qa{5(VQVIk+h}6OT5e9Sr2*p)nV!FZt$5HsehB5RpooY@_lm8G$CTuk!CuLMS z^?1h}lqbQ`Dui#Ew1;rK(S=l?LumTxhv9-Z!ZWGLssGLxMN^L&p1n!+90?6YC%oYe zsIYabaw&*B#?g#F3<3b1jYwj!RujcgY^cS!1U|wN7a08`9^P;UF@V93ctB;pHZkx& zvJnbxc*B^6>91nM!XSJAz!%y0$2m@dCLhkj9<oR*bq*6$#cT&Mt#IXwo+K5HX{Q;J zurGcW_YZyyRTjAL5M40Z5gKC%!M3QzwCIA<%S^Q&ov4K~vYL?<U&b#X2?s0mQ4+Io z?7{p!i4P@`iDuxV9(v<bLpC~zR`>%RGUiK$X$$~<%y$r>5DkIlLT7tCLlxKnfH}T= zn}=W(7Q|S`TQj^BIkV&)@#qAF0W;+Ho+&%_X#Yki{xH~0^){-1g~vUfv5re<;~o59 z?QNn9m})!&&9|8<IXaOISU@8l??cCPQJT1LOd}iFfCmkmyFV$(!WuVatX~~FA;`7@ z94>Ni>aN3>Npj*4VfE~pK$6gB5aSXSMs==-EyNy07aFj5#xtT@u`^B8AG3yqH%`6J z+BPaCxYe>!JV&5ir}Rn^F}9h3YCL=XBNYJH#5~He(A2q*N9dU0IASr0&GIALeBs$Y zMhyUO@T0O%Qe`~Oo$hl*t=<cH?que%k5C+g8!`D)rGbT_SioWs;4rZO$?Mx<`lA@n zC^bLAtwfN-!$z1`2P?j%M$5d(9qwSoG5>Pmja#m;om=TghpFL<f}|QVx|D`2!Z926 zkkz+ReM~Ay;S3X>iA(%&$2cyL3Ndw-vf8eZJ=OtqZMY-ckTgxmp@H;gl$^UTn#?=) z;frIq!q)s4I7sgi4s1L_9clSpdC7y0e*{Ao*x-g@qn#OZ^dl6ZK*iF_`rIB-8yV-E zhutI37gYfLzQ7urJqEuHTl51S#7cH!PeYV>v||wZm^yz(FY}bNzRsqAEI4dqEKd^> zNto+1skJeVq4P;^u;9J#&7>8rotGSwP)DteNpFVjI=j|jM>fhK>~V`FX40?(Zt)?v zevjuk=9q_;`-I+LxV<3_xWk87aQ}u$=!O`3H5loUc<3{0&;)IGsmK|ea)XDFE4)|Y z6O-r$UjT=AGbRjt8PE9#%3}wvqraQcyn7H8Ucd%yFrR%Zz`^-H*h+;};06}a8P;Qu zc+iGR;Ha>=Da+`IgdzrOFokirB|cG=c{n$AFb3ZPzLQh7;p4u=(+5tVy6$5>>zInX z!3RhHhe=q5l&KOq8#IMzilT#uVkpC0um>TtwARo)0AL4Vz#Pk<38LVKefR`$aJ)gm zutkH4ttcF9(1-fzF^=IAdH9EGU>URd3I1@fHcW{A`ag6ygkx9*W+(|g6AP4Z2!@yk zZGeRHlLicdvy6(cVqk}$6aTU*+Xxyv4rs^)b|{8(Su*|j!=LDePH+cKNFgfIM6H;M zSz<(A7!#%X2TXJdO1s4{6BSZGhHwbIG1QNSxT8q`hgM()A7nJAV8fM=6jOi(bjrDc zAjQ7e3!~FRNYDm8N<>1#kbi&%PH2Z>s1cJGv8XV|{&EwU@r7cvH9HJL2xO0U7zZ<S zg;205q2Vj06Ta2)hkmRFdOQa(jGc132WW5wa<Bz<NQluZNUk9VFGL4i<Ex$H2qUov zY=Efx=?QV`H-tE?RsaV56B(U5yDQ1TNjL`oS)TDLD}-o0f6#_Uu!lo%2HCs8tuTpx zkV8mFn45G#=UR?()Bndxh{JJsovG}I{Fsb?XvBXoMk{$FER0G1F(z!l2X$aU{E-L# zt3P&n4^g3oV892n5shPMAfc?oc{l`n_=Ir;0Ixd;UAq$J!-q#O%&4q~lERFPw1s*o zHFNMt>lhnyfQCvS2Ufrbs(LE7v>-0g8V|{aU~mV=yS3g~$fRNqhq?rFs0FZcsl}?k z#$1lo`G<B;1<j<x&b*Cs>xa;^2V%H}%OH?~tcL2TgcQOx$E+vN!iIQYg;Sf1t!ySy z`Gj!zOMLJUj|x7$Buu(E1aO#{{t(R7%aR`9hkj_vdYFV{kfY^Wh}HR?QGka_Xa;id zxFVq|u1pnl5dRKXfCX{zPp3j3=X8z9u!m}ptm*7X*|f+;u@rmA#&+nM`<W|Fu|7@G zrA-h|z>E{JM7i|5hdTfOR7i&RLCS`^pohzjrW}V(h#<GwB)*tLVi<=<aE8P&!LNI` zlGw+7PzCWiO%_T`d1yUJ=_OyNhLyB6msHW&q#}K3N_&V%Z>fj7e90_yD_?2{Vz7r; zxP*Uzp^u|YW7$V?AciOElc~&)g3N|a;0I&mAe_9qx74UvT9t!@QUc8-@MMO1Fq=9Y zQ&fU3`M4@(ScT=$Pp)je!hr-Y)y?Z_Cf5K7S1N{wbOn3(yZYl2nTQBjz=U!jhH`Mw zO2wt<*#90XRZD2NP;n!f{n=1!APHX(2Y%?zAA-;KV3AFzhi)*N24l>68X0q#1OP~e zRRDm6%Tj+Ek0{lKRTzg!sD*&x(Pc7{!r;Y+tjBPJ)$2$Va!^n?Z3jm&yA@@piz!H7 zNJC@vrDfI9w`@Ih=!Hj+nM0UJ_Q<?Q;u1sRy?@AsONfr1F;oaGkAF~Ab1(*O5RL~e zOAdift}{jtdC39Fo#V2GaPY8jGKdMv%SeI?6RihiV3M4BR~qFKv;crYA%|<&1V-)A zAH0%O`G;PBgm;hzfE@=;HB#4_hdm^ROQ1t6b<)RdNr=USe_#c6AfBa2MwDI6d+>!; z<o^V7k&~QskV~rvY!F#i0Ea^LSe=Cnb8rOEFq_1=IQ_7ZV<;7F_yhpZ97laF9O_x8 z)KRpUBNYWsZg>Xbv<DhG*Trnf{vZcTFc)J;GDG?yQ{5R!8Hac9g$A_OdTH2v<%^|k z21xh^Z<qveKqHe%+e~U2a(ISnNYgb9GPje5m|0hn>luu*+<*A6#x<AmdainUAY_<{ zS^%*&wHV+^Jw?R_oK0PrJ&og#h-<5dO%Mlagio!B2UCcJd!Sp*I5Q>#m*-F*HD%NO zBPNJ77hqV2cR`1%Eho!G2Vb~`cTmvcIM0tw5pD8?-8u*4=uP1x58(O)v<TVJiT_*c zn2=hKtZSfzK-1aG6ES31)AZ5|dw4*x5SYRvUz|Y`qd^D9MXSQa377<6f0~E>UA)4u z*B*f-&lQW-`v(aQvB)^xfz2uSFsOe}u%5lm*zKk$sb4A_-KTJ`)traSeFsj6T4nN` zKg|)eAX|IbT{p2Eu+>S%u>|$tRdH(K;47Kv`iEt>s(+vaai~@r{hUj<gnqb&LwF{k zvEs5YB$8_e*wreOB_j1BIh<%;7+FoI(+8+6iRQ)K6geAOEuH^`S<YjIR?v(BF0Pn5 zu6v+hZn#;>MbG9jjh~1GNFbEMJi?^(5My|vSeS`%xZjKQ2S>42V5mZz@c$FH^v&^D z&3z~Z0PNbXYhf3zBZJ`NUf_&F5C>#a<dZawU-}DwSO?ctMRD-q4Otb@a9nbzhGM{~ z0m;y}Gzd2_hf-(<b?se#bIenk6MV=<dm!F>a1)$KT#t~FEKWgeh%er>pwz*k<C=#~ zNQDWpgz9x)(*lp}L55s7v-J#RST&lg+B<}W1W6Io0-fbT<qvPThe~*rjWeW}!wd(K z6m;O4o`8jfiHXU@7yij#d&q`bu-w~8n+N8+U{Hof4hI8%MV);hN>=H5=x6^OQHM*F zd*}sIu!n9)k5Cqi^|FUza9vkeQ#FEB0=W}!zyxRjfQ5!-g}Pr_w*TD46SVrxqBG7{ znvf1i2nMnIM4LLqvbaY#46~VV6jtp9A$$a9o{D!=#^OL<w1S$k_-DfK5VMtsb(O@G zV8eg59fxu#cu322?(628L|X76npBTN3`io=F!e|ZZXJkCXhqYoYoWlfp8(M9ID~FU znJBT|jvxp}AqU8<hdK@z>R<{@go=XjhJTo9Z>R=ixMptjLyh=}wB(1-#A||BYxqi> zdf*1RtcPmw1%D_=WNd835S3Pl1rv*6g}lt_K#P7L%82-cYw(SXsK!j}uh~Y2c({ao zf-KDTZJS^TbRgw%=!K?kY>s${^_fm|*u!$b3gfQqO{@+%3;%9kfT4XH-S_6@i%sKR z5UWr~g_7u4%2gkbIMZ@)hh~PMU+L7QF-C9b$8TN=T&ts6_Jw`WM^31i38yEoXb0gP zllpO!RCa7y;04Z`L7QSf5^kZ&txS7>vVjN&U?7K#*=SA5j{c>`a(GJ9CR&F26K{xz zIsFG!3>e$-P6PE5gPP8A*uy7mNobA^kFFngh*NTCh%5&e4ja4Wtp;i!2WQ^#lhsR6 z0R~<uh#5SWc1|1<+YWT%3;+=C2J<U6`ptm;hf4q)$QoLToXTT1s1S#TToB!J;1U>l z7-K94Ru%E~wGF^K^cMNGcL3*%=JQI6((M7zh&VkKG5=3RW{nCb2jTRGxVr>tC@ENF zji#ASc!&p5&S*%|9bY&U;{NJ!9=CbG2g-Y<eP9L4y>$KfiNq|3aDXUBCuAYIXSBG7 z_2i6TP#z=i)W{LbN6>~hBT59lW6SuHzW@MLc!zROMboyOB3)5cGALt&2jS$n5l>vz zKucek2Q#k(Vo^SbzSwCCiIDBEZrDyY!Am-~)|lA@@lL^Ow?Rqfb_)rMP|TZQI~}&s z9?)rqXe3G<k7UGfly)$Nycxn?k|MCq7lYA;scwgVSkk}X4;sH#bWkU1$cEB8^OnTd z1rJ*W5eIr4l2ix<77^!c_f1(p({+o5SP+eyg#Tv7ozCi&#p%#!td*31pi6Wx2V;MF zT}ugNAG`a4x;nGWClM7?7{{z@sls%@roEU4a@KzMb_Ejm!5k*dQF?<5g~YiSgf<Ak zSkis)21pR^b-(w;C5LX%_kL{CF#kx1n+Kqe#xti58aES^!L8YNx)To=ywtoa*#!1@ zKa|%`*3kP&_`MmSg=q!(ahBJAfP|922cl$CELTw?;>CN&@J9d)uh7r@P$ff~x_0mf zV(4_NmSt-#RCW3_h1<toYROZVxg_s~M{tw7nuK_mCjW(cu0)c4*t;<~hhVq_QpNh% zK@xE=#_ENB>5%QZ>S(Tcx_tx)Z{*|=EdOZmpgaHy7c#tePa!^Q-Olj?;7i@Ta|9W3 z?C6nUynmax-Gdj-TD^Mn<{|vZ5aG&{;O>+&_wU-KfAL)M?C5Y_ymQwsjjLzx*d%l2 z;Mwcxlw&(v?c9yKbnTo!c@8(aB<RqeKXTA2K?4xA-8cZ~{5|b??wq@S7tz&&=E@nl zd;QR%Yx~ijy_NW|g{$W-Ua5WK#$|2U_Fzay_U_p`nR2DyuJYjhJ9em^IRMv40Vwwr zA;O>Y#)*TZE$*RX|5VP)43-=@cErfJ0|04UV3r9pbL49ep0~T+I1^j<Z(za92>J4x z=S!bEc+fb3BZsb^L*nAc^Hfbv8~-G6M$H}iHxDrC;XMoT1@Ld(I&|^S1&cK<-aPe@ zr`C7<c;gH#(7<yKG3>wtop|HSlMOYzZ3m4v_UwgDd<O9Z*h0tv02(^JWb+R{;SI=; zKjol;PHp%gW7IvuMduVu^T;#_Jmwg+NjbHxs1RTC@H0*@!4%cmB>$KL;*biF^N()- zxZ{mg?#;86d>(mqk3aX2(+w=k!PB6aQ7ZJ-J96n$4sy9T<4rspuK3eE5#fW6JN~eu z7*;mkh~q*3h_gvQ^YjzZWm`Tp;7^@}QWF5u<YXG59coqMYTW!*&OejLMw@i<gtU$^ zR%)Y3GiwPMrK#S)GUuu5kpBY@UtDE+P?7xjvd?kb38a^bY8u<qPw|Y?j49)k(~miK zJO>z;9%}X_Znzq=PLIo8A`Xmv6?+<e-^FuaF1+2B&aJt2`H@3>wMos1S1Q-fhMMa7 zApqfsQ`$fD>a>-bhC1RTJP{SPQnl|cq^U!kAvMpF|2PulfClwCjwz=6gDU_{J~`Q= z;>C*&KleRj<v6kU$FM^sdvr29apvL;sLwdJUtdGMl`<>(97#?tWj^aJd4MS@BR=(n zbe%gKZt56Mko_YKD(<1fG(4C=8nZd`q%uj1{cuCtPP@kU(~-=MV^b=j^f<0ld~vqU zGycTYAB>Lfo0)OiasQ$X&iAGIU|#oF`%!B5P&ZFv@o0BfUf{`mEat_*7*s6HkdqPs zhXfY0;;2=<X}0&RQw})*jH8J*@$e(=<@1#rEC9KfQ_el?9Ig=EGdqq>o4@vhoN`RL zt7%7nvxN*k0GNYLHYd(5b(Dr$;$A%UgcA-v<oG@4wVOg2_s8~Gg6WC`ZQM*Ov)RL5 zkkr=R*2(tVSB#VAI73u*kS09$q2oBo=|<tUr4zLT4{+$Pk}uq0Km^fgF97(PUzBDK zMuqPl)qBVF9D~7^7$hXg2nNDr)F=Uohk$Sk#Xri?qD_e7AGXt%JT?}LOU#2a;Na27 z9y6Q;DR6o&lmAeFut%Ky*&{i)@eY3Agqy{AsYBFx$FGWVpfc5og_--JLjGaHcT|NJ zpR30|4&e-b(C8mvdE*;D0!J~<Lnr7c20P->x^X;08(kBl7*}*Wbdh6vs5)NjGQ*~S z1g(2So0HN4DMmQ5C5~VTqYW4Go|801eCqJUKicHRD23!2t#}SO1_Qox003W<WD7@L z2^KN-V}AAsMJkRnrA=I8fdiT)0Q|uZZJ44NX+h&5y73PvktdJ<&>!BM)Q@I70s!&w zhclf*OTjq<U^?^Viok-7a~O&hw`!s@T%n*uxhIZ(0pvfvW0`s|h8onc5?>|>$6&g% zBa{RcF#obPy@<4<9#hKZc<5+D*}wx-n^0y?WGTx@wk;MTx`$^#!_2nasvpg95;`pU zA8fj@pHG1&zQ*DWZ`6?;{QILmFX<AAo`W&nh+t93K|y%*1EFBd+{R3ii*eM<9-T-< zN@x=w#vP<}wJb(EaI=_8#4d>qv>jh+=?yuxj!Msv9PsYvkwsqTW3nn!&1ly!Yhe&X znQWSU_Th^l<tj>`;sq^G={;;jZ+uiFp+Ou1n9$(T9%=apFL)8d_T{i|<4BJ;Qeuxo z)X;w9q1ivu;heAyMS4~hYghwk7lGvEkaqGJMfSl8s*Hmi$??WH>><F+s0c9Oz=nI$ zQvbbqM2#;}i_TvGYbwM7!%3;UZTQ~Pl<|-*Y=;2HKkk7kWy11w7mQC(m88EP_GqK! zkrHQ~!H$RAV~4bvtzUdwz<zAUwMJ?OF=`0_=mb}|23gEMvQZ1k*+Zvjm2J;{YAn(f zX*E`%OFi!K2^gkC9)2C6aB&k7RYa8>L}gWAXh+-9WtF|^^acQWSB!Y*@w#n!%Sy6{ zoY$rm9c#T226fdB0AQmY0H~ur=4uYo4GC1JKw(Ufdk*C`>~voOOzT7ifF2<>uk2&) z@c2Q-J_3g+lUT;b>;Yk?(2N|<Xa|hOp^ZMuPQxxaSwH+CEN}D_zQ^-o3v)=$YybG- z9rajoC149+E{P{5_OOOE0yB<(d~zP|pxr@CT)yFcLK=ESF3c_qwtL(G98WS$qf6De zB9YM)&X6oPKJy-xkZZor#G?(x47&ijIA-{Bbu0g2m-&jX9mRmtd=qWtgWxwCzNl$` z(}}YUT~)vXD)6eb0UVWdq877Js_Cj|kk<JFz7?)hEH3d631!T|iZT!<R*D&7v?G&S z=15KdaZ|-K5gM^r4uElZI=v9)nGeiyIS#GF0fCAZDD=*rtkKsOGqrImnFO5Xhgiiv zS<{W>M?8}KIi7~17CIu;vGwy0Rj?zs|F{G<?BNeM^JFcu&P8wV<<fJ&L;o!+T1l@h zuEpd)17FK?m{V556l~zub@p(_Tti5;8x9vpTG}f<hFomhIb=$c0Ec`55DZ$BMu^yj z(UgsO9D7Wn8$Gl~+H9wgY7=9*Vt&LpV8rJE=?@mLc+N^}{hcZ5y5I$Y`JnadkHxH% z6VNyg$&H;o_W)qb=qL&rk<z_-NR%h9?5gi*y`OBmE}SIwM?BUnBnsP*+HE=fO<3V` zZ;X~HF_ma_JpvXqTB9%ksHr=GW?}n~@*kh*WgYhfy?1>3m5!&R(&AC+%Utaf;3Uo^ zNm|EdXuHb)s6~@N7bT68yKCdP$0M3S_)KaO04W>GJiH+fDiPyj0smgnV#wi(YJ}z- zxbeGpCdtpF{ev)xTFgF5v62T`Ql`I$BdAb94Y35$J&;d{2O5Q%Js8DKU`^FM1?pX% zIgkVFECy2?f;4>H0s0dx{X;vb!a|(gf22%Fi3dEjj@#)3Zj?iVJW)xR6bHW2VwA`= zyn{jrgx}#y9leU+sY#Le!<bpvaqxpXd`6?J7180wKU4!SxQ=(+Lo6VJH>5?kJ<ez) z5&%F|Kj4NUVZ}|c)=Ig8o*`O7L>o`om^EO-nhe_dZ5t8|3Ff^Br!<Ygg$=<;TR{kx zLYTuOP(@SB5DyZ^mk>lqFpHC<#Pcy&Jvi8kWD7hPLpxaCJ^x&S_I=hz(2f;y0syd? z2bLY;yxeMBA2le$YKYH2q#$&xU1qEVV6>h})RbJg!=@COqTwMy%n+!s1RXYwqmV~T zsKhaBf;kjLXe5I|G~A+H7Xi%!5T*y>O_rlAU?BDcIrM|A(b`n`Q4*b-Pr%xgq#)w_ z12EVMZmb12DkHB+$ZGM!0`^_a?HOqGAaNAQKQP~Fq=Y}rL_ai`ppZ`$-A0By!!vAQ zA>BhSK*B$;($^G(thvGyk;6N*Al)g%xz&_E_?jEOA2g5y$#_VII0az@MorNmYsF(* z7>Xjq(=Q^!!rY;KB^qZ)1CKBTGor)6beqPU!zEn8Isf<w8imXPVjOvtqi#G%<xwJs zV8%2`iFdTx_}K*)-b#a@5-83fD|7>E%?>8K9adyTh?%5EtR!45M(lM1Kg5<9E?OyN zP2bc5(~J&Se#9?g)MpS?Xk3Frgq<x~5scKMe^i-K9mAc09l0oBH5fyGS(rSq${U^| zPfUs5sfBC(gDtF#K$s&p=E!2mLt;=xJ$S=E_}w|2mOQEnL6DQn9HL5uT2j>r>F}8F zI0Sf1<~jg_JP5=}phrT+1I|4K>3By9(%KT*M>)=z?ci4}oJebd3j7I&%)I8(aRe{U zpozGl*9=HPZV&LZ9M28RYnI1r{$e5qrTgT>`Txb4&iN%PEnq*C17$S|dEm=rvV$%3 z!@u0aKe$Xyt;BV5#QqfsaK7Dqfu=1uh-={sc@P9y{)s!hMM%twcYKL2j#}$AMXzOp zg<an)!rGY;*gr4>Fp$GJIK(b4*MNv;Ep)=O)kZm3f=zH4bUuoQ9^@f*4fL((QgVcR zLQyp&rcHDXQAy~4;07i@gE`2966(x=;>*&-Xz475In0$G+D8g<TWLm#Y7E*X#DbPB z;FAo(G3+DE3|;fc!))S)G4v>IFyoj3$DPE?H(~-?lp`>F)nytdPvD(gC=*|h6a4)a z4)rEOhzLB$1Aa*ZC@sbX4T-wtRV(#FNdLHEh^6IA#)Mj=0x4WvLWl%6aGzgr1wpLD zIiSNO1cOExg*@1Uw7}<h%%(T+!#eB+ZvF#}B2j-b#DDIn-$}@18Us79j(6bcc;Fu^ z@K$TJ9VTqym<p=!!~{18oQ1YlD`4nitVG?ZC1M$0kX&5rB}!QJ*~QI6CmaJjT!u|p z0_|xAMRv$m_(L-wWH}tiO+=qiR*`(Nlt7}AP3+{yI3`EHW?qm5Qz)VDOkl8{o2HPH zKCnV4)zpK&T_Q#2m6n`ieOxab#$fqFC>(=1#KVgPmqFl*K-gM4w8MM>g*I44S|pLl zJjw$FrxHffu=K;Z;T<}#LJf|?sQ;eg+d0a|UaLo(#FB;LJE)d*=4e~=n_|_81z`h9 zjA-f97dnRO#c|!JEF!41!qN(2xrpjNKteCrP$Y?pKeXI{oGF#q!gE;DJh(#h@n<hS zjJGMoZ2m(fyxmUVMuC=tKp?1JjLV?qm^(CRY{?oY*pN&1gwo8zVDQzAEe1bSgD<!a z5-nBvfXXMJkkm|x(~9YMaK)XW!ytfzo!Qt<+@7bFDGnKjUrq}eNy8!B1FJHXtM<b) zR0BN~WGwVTIq**Dh)0K=hu<L?Ig|r@iGyo_1%yG&J%q$3=>$WL#dCnk#7Y|JoP#*@ zQFTO&KOlua>{!e&4?4!o_x~D>jjd^Q^hay4>^yF6Xue%y0zfqkWN}KZLi8F|_US#i z9XVW&iij^mfJiE}-i?JA@mPdDsMm^w1Su#J=`0E|GzA$_k-=SDw1iEA*#}N6mep-a zfh~(Bj6*`CC;9}@S7ye&0)WnN;X6!I{2&o*h80(wX@Zc$PJre**n%FhnXtkrk?4m% z&`a@V6*|zIcZ^)m_-l~>z+e>AL$uc5{>cpL+Lj@NKYT(B#Y`P>Qd9VBT%NGYc}90l zMqebuDe;coHO|R|geh25Y;}z^gn~~-8b@%2<0NS~yaN|P;U(C^IfR|WhL*W(mF_%C z>qL#OF4K3e>)N~~sQ*9>5^dpjv=($$Z~Gbvk~9l|2-eRXLTLPK8tctJ=*$+n7|g9o z+OcoTzU)TQ8ax~?Zh*--66-#^LrvMob}Un%`XfX1g}^1)bxqF)wc3iP8zn&RPb7>h zs$JCfX5)keQt(5(YFQXr!oOr3CYypQEFyt0Md(~mAgf+j<b_m3)r}3)C6t4NOpU{Y zM?v65nH(vtb%Qa8NnWJhs{zLBh~7A@1f*`&f1wwQGUIJ!Fkjfjb<{-S;-LnUf^=<4 zj6hGlb}-zeLP^BTS{%xvrZKzTLuepn0d>s<&#t`^Bs{2sI~Y_~p~uMiYexi*H*kkH zd<Q|4)-wQrJO9*()LO1T<R9TCgjUH(1qGfZy97LWA9@%QFr~yfh)OviA|N#$KLJxb z)d^JXL`fNHKTzU`Zs1J8(rusvS$Idb%!99PA%1=YJc$uGsY8Y68#<5!EXZj{0Fr$~ zU`Hs_JaHe6)fuSRQ0lftNYKJ51rvg94WvEl>9GhU!Bc363RM7hLjHr+9^daV1VxRR zHfX~v&4!hA!^lYXNpc^Xaa`J9@+B|>IYspwArv4Ph_J~Jk+_s=B~&J*TQ{)6k*u~> zu~<)KlK&YsAmJy^*_b}H_2h<xeb^8s$q@hoKr1MNHIbBBG%h|Epj}54Sjz*b#D*f{ zXAJ!VDgX4+c`iiqH8&=K1*m{+)C^Xrq{7D>^;b_xmEcNkphGV_!nVnjSLgL>1Hf2J zW^_4@SrkJnnIdcZ9zO-r-s#rlDylzdm9Tura|Cu#!^`m05h|y0ZKOm$9K#@#uC)T~ z)FNr?(C7D(!z_7pe#XK$F_uOS#G3Sj?|_{^FT}|l+I0-${u!<T11bQ2rOy2sHjoUb zoI}1bgm;h!s8~WTeTiTU20ri}EvjxF;%Br#U4h^yesaU5I9#N>YrlHiWpqL)1m&$h zh2Ne@H<+!VElaaF7#XfB+y)CL%n3hKghG5^CVdCEZYI6d6byTG+ioN~Z<zk@l}Z@I zsQ&`peKs>M%k4p6abu{4?%_lIn5b`3hJAp;LYVCZnUIrlbR$1R_Sq23F$uJcs&(1$ zC_9IV{ll2)@<#Zpinw12rby|KgE*WCJ3P@KI`iFy;y<8*KGf8ZeOnmT9BE#7PtXoI z?T|fS$}h%)JKVvO(8kXOmR@WjXns?1ZUwFK(5Uu|#MTx%iD8|DhdJ1qhRAR`X9PL5 zgA`Mt0ex6J#GAf^m1-;?Upbg+EJXDr(yN5CeTakcUDJlHMC;km1b0b}gb`AdYdy4D z%vekfbua;e%9h4cSQ*7XfWsiL(L^K5qu7K?C1jSqPKbThzEG`(tXZDV7pVBEx&MEw z$=`3<u>v?yg+^=&XUugxJv?~E1lNp@qPC&ya7eW*+D%*vlrwHUG(3@kWwBgeD4aR) z0MGb|!!e81>N=L&Bm`d|B4sU;kw0g6tOOB4m1*?MFm{eO)Cf^`qeHv}WNze!h%9c@ zsex3^9mWSM$(1<R^3Q|C!%i=UI=fTw4kQ?ppg07mh|2C*u9f4)2et#SLOD8f17nN_ zOec?t4%)VGp;I7dqDJz$<bt~A%f93I93s~y|E~1t11Z>`jEje;$55gXw>3a7i8J!t zszq!h6@Y96sF1?eI@|-fM%s~=?9Purh{|lFIe6yfKYSF_)-<VZvwhG$uK)7q__^IY z5d3@C5dQ!xc_?fI89tQDS|ubTnKmmE^Bg{eO;af7_2rmCjyOQblLvrcL4yJXmivb) z*uQuP<=vZS?w>Vm{m|VrxRIm5dI0(j0`RZi$Aa<{ev;;}BSe=7?@2T_&XlWh_5h$m zSMpw{S|sbuo7d4Gxqs}4@gsOnBfoLYE{)?iPbX2LI{WqW28|OmkTC_4BUi4SDtKZc z5`8J~+&^{H0K@|;59>Wxu*6!`yO(d@jXH&%8}~??J*ql0-ZOgaP``3>(*jr<QSs4Y z|IU(&2{<0SSi#1fJ6v_|W_11jd2{8B+*geN$W?>w&1y`c<HpTnrT>o{?s@mJdQ%O} zA4YVOBgeF7cpg4%;qa0B9h15_-TMBK6X@4q%4-fG+Wv>n8cv;%2cC2(6o9>QgZ7at zDe(Ngf6_MnE5}`+?Rn#_F=ZTh=sHdwq2QS(lu-ULCnoLyh)Jw?+94)0;B<=TpJpKW z2OY^CjPNy~gfhw%XyoxnsH}`?r<iu^5z92cVloE+YO?XC9HHnttsK<=@Ft#qa@uaM z<%Dt$x&!A5&7FN%d50hs=hDk1e=HFvJnBXYXPSS`At*$@?D+?rL*Q}HKFI{qke62U zYYDj?h0+F+ddB%sr+VP&=S+J_Vy~mu#ImItBFSOuw!yUNr~kk)Yr97$d*JZ~mR!7n z$DaDcg2$g?*ojB8dtN$dErn3ghpM@B^5-9}WHb)KS!w+Xoq3!J#+0BAqb??Yz`28> z<<R4(KT=Wp$C!2CDaRjw===|=apF0QM(Q+#1rso#-3T64+TrWAbN2DY9Ct!9lA;sI zK`g?x*fi2Md7Klco`0s(>6~-;`3J{;2pVeEf5gd;pe?CV5+9+8-RPyZ82cyB#Ky!@ z9Dw<P2r#E&aRndibm~tsGtpENQlftKha7MIS?8H^SbMfAf3$gon{iY;m@<MwmWLd1 zD)EZVXIJjWm}+8dmq_k(>X(&$vO9LtN-y=solOno%l|fioP(zxCaFtNAz$=)C+x`N z6zHF8HqjAUm?W}?JaNjL&MySX2_+SCOnyx=f5f4LC1VFF)ie!V=@94imUD2DZsx(s z?t)S#$VGSxYAq*)E{SE+D*KvxI3bPm6`hvTf$g}S2~X>sclId-JL%@>QJ#2IbH<yj zNUPO%rf+>`oJ*R~h97?F6RMtt4>@L>fNMuctpcY4HEOsQy~G)N{F!mD{;~rY8glH} zj=J2Iy$5R}4XV-KY|N3%Zvf_bl@qkmn^R0=yF@0?p<WXc4e7%d?wA~RG!zU}#A!<e z!ACf-Q4i5HOlJ_OpF$>a40ot0GN?+%;Iu{^T>lNG8KFU5VuS)Hdo-^f^^jZ$yVn~4 z*n%DXz#nI55{o<?uplABT`pi@HJpe@EcRfBF~%X5)10g$w;=~V2q?VVL~l~|*a|1S zQ4V;pt~46?2R6#X6l5JsLvQ&ImBwflf#_%<4S7fd$$^h%K!<)zB;2z!)I5BFu1){2 z#7g4f4~G>lIWcLFJucA;ew>4S0MOKeHi(WPnhG7{1Axl_kel>8=pS|hm>})gkx9L( z5-VFy$k;TGejvqBDw1C74kWODWWyJ|nPQKYbHz-_>UX`o8_hI<8^icYdG+YWF$N(> z`bF=RgG5V(%7H(PjRgR)@LW7-)sGl?1OJQn=-wE81^}c0;4$;tpHAL^4%z)@A_j2` zG%6t+-hC)uF4-S~>|u@aj4DKna>vuq^*jhEWE0=1=gt7IJZvm%I%qqnJeK2+cN_v7 z%K;Jp;&Pw-?B{z3$<T%%fg9}*a~>tJM<+r7C|*HGEbJ(T7H@bfX@%4rC#0k#?E#Gw z32A*kBL_VGp$c|nhhlp14{rWZi)>^PX9Am&KWr2<^7+cB*!p5P>XDJPWCTk8IH5h$ zrnXIp<8257zylX59jXpWB9XfnI0jKtUKuGN{{Y4UISNau$#fjtAdFB*lR|$mrX1!V zmN`Xa4sw8sN^B|!HZQ>qZ%h(GmH)hpL+UdZB^HAlnRylyEhtM`WJ6+8e9#hwbE4v` z)t9Z^$Unfep-Z@DC@Ff@vjBCjI}n6>w|y2-V5`Ju03$m_@$GF-(+fxdz#IdCtzVYL zj9h@kRsRs=Z_fb_Vzfgs_3KD%yWxxfX!RfVu`cdlp}QfC<haM(h+L6@RoGfrna>g_ zHF)tK&G3g{miWgS-5Zw#Sp%!}qwjAw;@gt^1DWqANqYskolWd0J$reUHcxknOMuBB z3NBNy5^55^0L&=qSjT{1`&)qBV;uK@gf@<&7o5P#8_JxLhk&|{bi@img5k&0%yEu0 zcGw?n!Nj(JN?*Oqx1`R&$N#NTd|agZq8kA{u#FRpM*v*Izs`a%{YtV>#Xh$$53WTj zfP&zs%Htp1@b5!90^#ba2pz%D;W?^n5J1i25ZxdjWeE~oa`>YxX)+4NHWG`Gyu+z| zDX)p3VaWL+cxC8##xo=)9W@jAwsbkiKN)?x_6|iuoPY(s$n09zhDayoKnElgsi-YA z?jIQ(3Xj0rKE+tg7&TnkO91l@aS-NtJR}Nx`oR_9Sac&R`^PiZu`+UG#UP9NhcBvO zOF^|tG1^#-J&d!RT#G14<au&K^Cu6ab|Xr-2_;9|1gHI!DuwpI1~$qEI#UUxm;lJ2 zJ9xs(3TucKAH-(H5dSicf53VkLZ&CbBWDka+yNYhJ$PR_^$%i%LuHL52sW)Lm_`!? z7LFthtKfkY%;cpnF;TcaO5xRgH4=RAl+oL&nxt@8<J`-!AXCvnOLX`qdTLAv09wHd z@N5+w6uCEt`%+AQh{VAwRgXL<Qcw`?J1u~jN6ku@vw|p3Q?+1FN$5x9m0c1ftkHGa zwV?@ZRG2SV(F#|fF{GKhL@e`g5o|Q$s6ifUC~eUPHRQpM!*0nw+H#1X-mPljEov3o zz_qWAMUhlYLSndfXn!hs6k}w!UBE`i@y20I=0x5|sDTA1{$UUF{I*@~U`0K6Jof*L z<DdK3M-tmAu>Y`-qbrk@=D3m6oaf+UM|_mWzTDvs*$rJ#d?Dy}u;~(wh=)A?(|0}V z{hob<*z-oxkTgiK^+?h09O76-rjUgmfhc@I<|rp$h$fwJvc{Vn(MT^Yp?0{)AZ+9$ z)`~?~rq|Aa<#KKwi~>i<X)ajhG~z+0#^*Fb$N}qN`6dXQBtzt&1YH<u+^!Crvcw<W zXfn!V=k^G(I6`^sAy}ru=je`2_Tx?BgzHSNetO{%I<M%K$%V+_OiIG)rbIE4h=xR^ zHNFWV93+w4L4NA)G-AXVa)BK5PK*d|9^l~~tVav!?j_h`9(;kc%m$qN!&PW(o+NM8 zB!VBvq5m0zX(}oRZkA)BaIZZ|<?4Lq*-mVW3`ApY#VO>_v|O+wuqnM-V`-Z0r|bb# zB!wu9LLZ_;N|s4bO5`6LuU!HWIc(z`HV_}81Ko6HU)~g*Wn7cr8^)gnY=Z$0qkE*I z8v#*9H;fPw5h;~!5fE`BM~{#e=@OJu8b?Y?38;Xigy;_ou;9=C#d&vLo%{KmbA9gT zy1&=j{S)EOyk@*Bb&L}RLX*8q*}H!nq1CC*n3WP<sYLjxb6<nEtpAokFb$AZdUtU^ z1;Dz5xNWYR-n5J3EdBh^@qll*mo=Xhf`&@^8&s_eEzJnWb!qX>uN}I4<j_O$nFpL- zafb641<TOTbIDsp!UX<q3s3nx8`9@fPlMml*IA4sQFI;_!anDIr7<z)S7EB{k#&4m z$9A3BQDH>jjPD5VFYz4USEv@~8#v9A+Ni31CR`jPFbT%B^syC|{Md7)4?@o>C46+~ zGdfxGpqBrQOS1}$4^D1m@QBSVbP<xaIG)#ex+fT&2rjJOeBcDD#t*8h2hg*9Va_k1 z(Mk$G)>7>d;s;U!zpTjzOF`R3&P@gIS8EAWk#$QAa5ioXIk(J#4S|r!Pld8lQzXoX zUOw|LprSD;5Uit!u%o<LuhRcD-V^vCc0rEGhqZL|#pDJxFowJx)>Ffnv@3vP#9gw& zjFe3A`rA-4uz`bT!S8%o&=n~fYbCwg)nyqU1^M?N4p~Uq9MpNIZI6huqR=?#Gu(e& zjTE4NrLH&D9V2KuEil)6$|0iv#B<7qRcO~vn<h`kne!v~P-p!_D@}EJ1Jo9jBJqG` zjv}H%N-ma;$@kiZHGgli|0)5xt=CNJ8d61h{6zUZ^?B{R)wOFb8yZQK3yU%*VpGXh z_OA7g&>CENjm$Jo3(8*%VYk(>4zxNa7*p=4&y&9=n6#UFX-zYH^n!rf)F{;TQq0$P zd-6)?=AB)MY6@@NRC<$w_GCX<W<xGHM%QJAxM<9C8OHmqT!8VrD793m4k8R?3HOH? zAC|1C1j-`mC=ThlK&(dYC;nM8Y<8LQ8G^87R|{8`H|a-`@jaj`k6eE$z{-fca|R_V zWsz#e>c!~U)1J-}CFG|*YKr|(F%y<tMe)At*U*hoSC17ao{-x}$N9s6CP*aR8`F6G zo8u*tqfc&gvKakd+qIQFnXELt>dZf%&R0+)a4)@%KahT!?nrf3f-=BMyT)gpP=u{W ziz2cA=r4L9=d`}Ys~TfpcT-p;+HF*vs05`SA#uhTtN+jzzvRlxsC%1WW5X+}-D3pp zHp-jQvTNSp>_rLr!}#={w3L3gbAduSp*rTQ+P4R<;7Yknop*-o?B-taPp+Bz3gK`= zRswE!i+w(u>*)G@76=DT-JU6?z$NR*EL7*FP@}61P#YB%wRGd1rpvl;dDX%-i3N;M z*b@Qd{%HgEtrJ$p_aRKg1B^d>d%eXXW|L&GE{SW?)rG|NGL|4`eVOR{(hLtDrs`pT zi?YiIX09|Bxw!NK*u1I9#+Df+qOskd68mx`<sc}=cxUya(6tvdlPi-JX;GYVu8{i8 zU#zLDKb*x{qU9A0SS%R4xQ9Mv$8XQ=dHdQfXSkmq?LEIrBluVTAEU3r-~QOpFSc<u zy6pSxByFK7G3kyq7NC-(yCb#X%&Sxq<4a>Dt`p|#0xG$?GZXkvnz7^QhE+6f`56ke zhEnCV7SHb7w!6hg6f8{KE0Mb+z;2X0C9M3uLQ*xrVdUWj(`X@?UN({HRO9o(^4~cB z3Z821&strLIU_wbE9fXjWU1>0Ub;KXDSUX@K~T0QQy4z-wswt+RmU`2dyP=SQ$Aet zVl&j^yvM<ddfoJG-Do?q?QQL{3A<kLKpmr4W^>QOhu_!%Do)?MA?#QAyj87;?^X#~ zTgQ-OwCjn*Tv;nr!7v+x>E-H@=7)<m+LiU%8948f%bq8_Z2F~FNd1;d(_AMc1Cyg` zK08$}#`rU;71jC<=nRbw;lbdB(tbRu0QB{S@lDlkk0R6}qO<*BSGPAqPDt!aI2)}i z84^$)`>E4+qvZ;Q6?^gWyX?TF5}uPMZjk7uV`T}-9gnKT+|)Hj=+SwJ5uCT+DfdJD z#F`%h+#ENsM}_{Q5+%-;XYbw^?$dU(HqkLzOSCRM+!DM$h~s7Q@;$Hp^1I6Z+F(>v zLRF>^aMy+LJLMTWpNvTCOKXvMgc2a>1!t-L5_MZQMmV&^y4d4p$L*675@y-i8f6eW zxZbobC@RQaTExOLDG`g#H8W)fiuC226w7Q}{M|w<XqxzcspJT1$I?Q0fk|ZAx5hL4 ztJCv#vHnj(&Wn-Xw9>8CzX-Bf31-4$b<*V$9``0fUzbob46(hj+X?P%C=tdNMLWOV z+BIEwEc4lZO)%&q8g72323iLvo^~-?@e-WlP!xocsmrVEOADe69(5f-rwWVkYOJBe zO9kC*9bPNtbsSP?DTZB}P3Awr+vmL#_f(OeNPdjHj-fQsW2Jlw!ormXYsNN_J!wid ztn9^F)~T`z!KD`VxsMlZ!=I+K=v$xUhl+Un-Zieu<@i+;DU9C}q!ijOB_<%Rl|{fA zsmXme0h^!~Vc=tJ7JJvg0W)lrj&he)2DLq2iHkq{vs6=*^irRy0L*kZIwGS!{G7?5 zs+v)*7VBGK$?My!r+UTNQvP^cUb?O?1=3i-y8dO0ea%_qR|D-GH<rk<W?>G-XhDh8 z+fV=7<@XJ+&QLpDUDHDgd-KuBt<Q5;tjirk?uw~cvtDhv9M)NGd3rH)j34T8zS0Ho z859fB>JG`J6vy*-4?RrfeDu^zU`kZAIhO}+@T}psMySk_6lo-vH%5g_E86eOX~m1a zYo5BtTR8vZ2Ss44L_mFwbDt^mI-MecN9vCrkF8)P=dQP=u8l(p51KttSa_p2#gyc# z&^N$$Qo<Vf>{1@5ftkX=VQ1|HYinzZ_^Dn2Py<(U%vl#It-i%uXAl$&3Jzpy{}R+4 zkPhxFk>s5V$^2us+^<B5_vZEu-+_rpG+_RkW;pTQ`zy$+FQgq9HuyN6c+$&9mxp78 z7No1?`M~&xT}wKC+MJLIOZFPH-{f18j08qirYZs?SvhsQPh+Xh=cxJe*Ah8L-#r>h z0cpzZD`^1-L9*?gY_^T6tXMwwsUcU?`Jxz=q!igG7_WQ8dFI+k>Q1lBd(q%NnE(-v ze_TS@EVke8N@t{L6bq{hRs;a}w9OWOMzJ?OATX3DKoNFQNYH7~QqtjF`3SklAW7yE zAwVo;^DEC4IOpZ(D0!PJj@DZHS?k!O;>F(iYzuZl_X_i5Ji2@7VmGstd2c%EY&s<^ z)=BCv2>G!+Ww$3qm_p^v7cbhEb1p$jl6aj@HqL|%N0d+kf9dVozC@Y7D=a#RyX}>h zrM&PJfn*!s)(*VyE2|y`W%R(6!|@d%_ezty_^`B7HU}C}C<Bn?q3I+^%9(T-nTVfY zxS=FU!?HewOFX-Dd<}#+R|f=jbEN~zGO@h^Xv_CWHT)6U1w*~+iCx5hl!)VI3$^ty zM^jC)nDDC`O6586|CLzG_i~EJoGX5%!rp2c)yv_1^6`1#gPkyC{*>r+J!_{iAw!q3 zOf?H9-=4xPOT!A@#eIQGy~TgI??rG%btTY?k3ra?uwU?(M2g^P<_V{g{H7-=YD=sx zYXa{7=7h^~Hw7z4#PeDE^v?J<jn^0QZv|`}@E$}s#>-wamN`e@Ec@JUP1aibAuK$a z^x+ot^(f)J*s@YzRDs=4m5`q;{)EWUDlPKylp8BpwEd>$qPhnNVeW%C`M>5}bxvyP z=b10zoQE7_yRVDu5P@QZs}@hh1D7dhVK(im#9JQP35GHKeB?E*B~t59iGwF8^4I+D z&%QT1N(EM(qtBOF6w&ikLOuZNAG%3L0H=mKp{OhD`%p?j&P0y7&mk}#^y(RJ`-9WX zJ1~7uN3~cHlTk(0DQrjB$6+&_I41sA;XjA-bdH|!_qfK3y)6s#<JZpAwXiCElOhZR zeO*tv@XFFb(J<#EB`XJ0VjHb=O1hA>XW#wca6At-rR3Nic(}?2!>96gM8fGk`KtYS zi6)i)f%^-L>{7v-UrH{hWr;Y3ZFW6BmAv)r!@JOblO-ERjC-2Cdm*0{w+TD8F*{RS zEk{f&Vz+tz8@x&X?8D2jwT7$xSNw`D-b+dn3fXy`qwAyky4{*5ZR4fa<4gaNTHhSu zOTPX!E4VfJ!8^Z{;Y(o_9p6z{5{sBrURObd(|VS$=H1DX&aih%9`_7SiuzXUq9@Bd zEN}(;(FNy$mhWi!gU}5#%@em+tLwi<6wNQDxd)|LZwy4UIYa-!%w!%?wNo!ve7$02 zo6_6-|2X&NY0ZOy@8-9F;{H6@KLgG0BUvg9LFW-?s|3Xre^w6l5WU+o?nsZSLMwCr zxp7en;m(aL`xC{jl-2S;q)<t&&aCRGf^BB1{HF$M#+>WEHH9jd?YWX1?YZaDoUVUC zQ5BoYGZ~fVf-}ra5WQTYfNutj==9HfaQeccL%f-4oA|5SStsLVjLJQP*_4n<$P|NY zIi-)j)c4!f0_Axdb#~9OSj;VnFF?cltlCSj#>5^U2u)t}{cSCJxqGgEJL@BFCLK>E z0Hm7J1`If9ws5*yI3(OsH<xR2urd<OrMhg^`blu)TzswZohjPNx5YxYv%1VeZA2Z# zAXV!OP3a!ZbAA8hcvYCE^!o39i>fHceo>q9nQtRvU5jTBZ2xr@IhD3Gqf{lbY1FX% zH8GwF)fVq2N2`zAN)}Q%Kyl9CX{WLHHQWPi6tZ|o!}@jE5q~fvP&t74(PG(G_RJHY zss=V4)xq4=7rMS%B>#5X5bxGYQ~5q))DLyN>+nIXLbE(@*6iJK;eE6B3x@q@MGE!n zu;_&Qtogg8{fX9h9z1glAMV`^GE-fPP#fX%#x_mL^|!U9Do!~>tGtUmtyih>WRgi$ zUH+kP7aL+CoWgy%x<p@c@}U0L79!yL3njnK8PnUp{wgHNkW@D4cAKt6{`#;4teD9> zs{Z<FcU;xAKx)AZ23(?L;QzbT&+@WWWdTMo7T+Ui#|u@9%%*HpZ>JJ|l7eR2eP)LP z$D}ounLo<IV4(TOoy>O~KTo&rvLu@!`@nqU5JwN8^;UylxaMqP1vMbqh!+Z!80st7 z|450b)@I9ZUec;X5I=QKa5W4^u{QzneAr&@fXwChlSi#5pBaD!f}Z@h^fZ@pVUAG( z;;33nR!tccRP;um5@IymusZCM1+<sus?^qNWbZ9ZA(T6|FPg=qv5xFGtj@K*V6tcO zS@nPO$5$}P2KNOlX}EC`7vDaC@=d+hNegJSqHPF5%;n^3a;pb4N>mbtu8aR??a_-x znvJMIa8O29K2gU_m^10eBfi!uHXUd&S6c3S4j>)vvDwG=kPzJ_vT%Okr$uUHbe!U1 zI^$)u4jU<7Pq6wlo#DP}85hA}i?ef@@d`$qUN3Oy1id~unNX%~{>?xms+ZnaKPbPx zT1?uoF~N*b!97Y56Me~rj>fZ`CI7^#_8N`2&1ti=RntiK*(5uAuX9yS=}Pu+nfaSH z7a~#TfIc;ICz~>EnR^4m_M}89w>74RPD5IMM=XNO6$_DidXks4P{s{W+^+}-m15iE z<jB%e7HJR7vOM&ytfs8$9XMdS*5!)pFWlnYRy9$dd@vJS+Ole*YrICUgM$Jsc=t=< zzbwiRSswj{(@GS*OEh(J0lhV775pK|W&95d|NPz73451lcM!$SbsxU$Z)sz{$y%&B zSaXHJ#r(9+*p&;w4+sH-WS+_muKns7tHJg+PJl3b3sy=($(c^ssg!%BVMbWV8D+)# zoXuzJ9RA@bqkXxszyNahdQGn#FwpmSdT!Uu;==SZsOxhou0o2xcfhIbd%?OcS*<<s zUBL@z<69>h0z)IR&vv%JXKPO_GvC5N<7Z8t(}3V2lK5ng_34_F@69zjq8l!ntEB-B z5NHvqBBjhThWc01$83#f`bs$}Vnl;?ByN{OndALqgoN(Z%4oF|mb757{EZ2h=M)`a z6MH`C#tzhXtk0|E^hD>KlPy`xSUa)a7daAM7wZ4Ok{*f~KVg=!ZWH1hBNiy3*I%%H zKXtV*6Mn1t8?wR4lrGh&Wu=B@%SoZy8EZ=BmePJpv*h}GE}d)Ly}>HIZ8+H*dG)PF z<T|+GFD2umXb-#pk*OKA#V4iM^fVOBq5o*;wpqxx*W;C}cd0ObM}CI9_8&|SsKN^W z$m6Qjf5iazs&T_6WZ7>^rWL80R|r9bMoUFjnA9ltme+UN;kDFe0BNn^+cG`AB>GKP zU%XI^>oE%(NA15s0ml5VwQ}_j+vNsk%oR8a*ZL|#sW2tI$%kbSN_v1uo~7&xChxX) zW;WIo*Y(jV`N8s@&U3qwx}y1v-u?2H@-3`aO~~`t)2uCS*WM%3U$nmTdFEL#`0n)0 z$zkhrA)l74O7RN$;YUv{GU_N(mfkqhY0qna4lM69nYx;2Hh?AuQOkHM-`?$b-Tlye zp>t)&JiC3?irXtqXGutY_yrID=b+hp>+?Oz9#hWQ_pD9d|1)oEHSqnMUF<5&qKW8{ zPW3;N(U;7wDvq{){+jlzLUe2OSZlrUOVSwcM<xVya`*a|c>4Rso?Pu(`!^ZGb_#Zl zKOEUQGAedcVSHkkrjdfCgYai>r8X*$!0TT?uUU<cWtP7?M!Ij^Z7W+bu2P?FUe0n- zbmO1ZH=TUMUT&#{1Vo)NmM5vl1Cso!iGF8EUQEA+O(MT#J?q-yd-PC>>Ev7Ce^>t6 z(!M;BxObv&%-!P0n!!28vhrV<U-zdQOn(-~A`e@h{p)UmZq&^U9(ElC+G@Z2HEQB< zE!p=)QOb?KQb&=$#{GJ}KW6&3vmJ4qYv1&vg2^XISq=*Tg1_K2ZU6vCoh@Jzx` zrvL=WYuHfS8-*1Lh6)u&0ob2UufvY22DAVHxyZ#~dDkHlkGvzVQB(OyCeFInVWg>I zEJx0Dw9u%za-u*rXm4qxx$5;};LPx_?zRMlJoVPaeI-T5rgPKk(|~ts@eJ0D+2aJt zr^~fY4B<4_?uaZjIm|*i@3HUOMfue8&)FZkTy3ZQMCT^?aG%;5`St0;aE{s!-4Fik zP23Ch*XnTIR-s+ul<DmwlRQ_(+ncvv7wcrsO=<NN+cz3MXC}UyfuY!4t}Wv4!QvS# z)PRQKwL>4E4RSoR+^Oof%&Wxv0ef)#WxdryK-T;~JdVWK<n@|=S>@~Jw;mr(KS~qs z2BF8i5U*vxu8`W1OqQ-oAG-f+f4n#IK=$40{oMCI&#e;S?Cz^1xH0|>Eu9t%1nfdm zsqzhjAtZ<W>zi+^0f!ut6OD%fSCq(^Hch})R<9>Y6;(s7um_i9X<H*#$-K<L#bx$3 zcR)5juHc63D=Kb)c8DyU?tAAS&v!O63Hst&SvI!qZw0ZzNId*n2uNakNbH>uP?JCs z;dFgskQ|JYQze`OsaqMvH4ygE_m)bPX#ANKZ2K{hR$`|Z|Ib;k2x^3dg3l?6`rZO; zS<wstL1Gi%$PjE81`|wt^dKfqVz0V9+tV{KbCbF)0BfI#WxGCbip6Nn3`3}bZUFX4 zeKhChEBp&?);hi7BG3KCVX-IsO(G-AI;flw=vi8_KNOG3Jgd{WOym#zGx!+;2PYEn z?GyeLTDRuK_=`_pIuC~EMfv63YB5hbQ<U_tAeal@<6VQbhC05ndmr>7&v~=t=lF(E z(g4a6-*e0j#!_0>DQ+YNH(g3&*bn8pgJF>zZ-qXNnBtpS4%u!rJ@Bg~M(1kYnLK4+ z?~)>5pbX!#9&sp#eVfwd@KJgwZ2Q};ihY=lm?{xZ5e2XZyR7${;;1CJU|aFI%h+#W zKNj6`d_oemP2}!qg&AYZr_9B3#e){EQm)e;`leJ*@qIhJfB1ojkZCj9`z1YZLv*I} z-nlB;9vI^CCr4{0`ik$bt=!gN(i-mitFVv7@iM=6%5!{w?^ahm{k>P$`sMehhF3Cw z_FEQw|9o!Se){K2*U^_h|6LL<rb6ifg2vZj`rxjwL&E<>d>xlP?fN!-{#4`ZoWO(o zhtoIG?*Ci~dUpSK)sLy?=VVe^<hSii*?+%3nEZF~$A1eCsE}#;XD?4^Q8&5{sPs-d zJ=-t8UoVdo4*LLM2nA_W8p1^ainT=SK)8&57>Ao9t^6^b(br!Ti7ufvsMgp)9mEh} zPEY_3LAHTV#?TV<ZO(p<dH*<-0YOGTqz>OGCH~T;Ab9$~P*>n^iY&t_gh?aoiqbZc zEgW1hCAdKe6=r}IU&1ckN@P=Cg*Zjv;X>e$LR>)dZILprSv!4X9dn9P%m(*H^^n?3 zdP-1M8Se+XSBSRh<nVoAf%mG0>U7^y$>Xj9r@60`_^pyDB4r|<4M&vJiP#VCOT}K% zUZmS^%qT`z;0%mLt@6KRRhw2wm|cakp$8s53S1NZY^cwf;h)*2l#lvPb;MEsTTTyJ zOfFu0+y(PJcgR#sVNi9*Q6(sEG+9ikN_@g-=qtpf45B51HSttni9^Xb%e?YXvX~5f zxMNzSu7m1V6bpECki5+$n-Rl!Je|c1RH=@PoW4%~Y*hp>>_~j)B5?vGaB%oGiddW# zL-(Vkg7rPUBLMgquNGB|SHWyU$0EajI2FZI8yfu9m;YkI0sv6B@hZ~H&ISEgq{ej6 zkdk0-Lvt9sq4uHL0`UJ)hF7*Tylp&3%xHw?<4CX$3Ibu*OAESdodfOX^7QegEEQT8 z|7*9#?<pp=AZzV5*sPS!)W~f!N&AI-)7VHMsL5b7Y_3f<D*s`9=;bH&+iGCJ46!sa z;+B#!_vG1wUq|-2LepXYW+)@07&y@3_neMxw=!XrCYHMzgv$eqKWJ13cU)f@LyVDb zbWW6!bC@xEcIlAjhRYS&@26sIPd6dSu2f4?SIO7esDWp)tCcziot9EVx)7kbpHnKG zJg<JFtFu)fY_dz_Jl3i?8!pg(thT)3a;Nm#MN#KYRgf0Ia{h4{v4CL7QmF%|sL-bo z%CPQ*kfWX!hg~st$YsPZi6aXy?)vqQUH+l+lioXmm+pD87$65g01p8B{uDc<yFHvI z32LbEHHAy=oi1)Tkl65^apQYu@kGrnJ)^~fy4EtT)JBUF4;RKX%ia$I0V%V)*Io<R zwbA!%Ub-Fyz_I5=p_Il9pP3QJf5#&P{;kVip4M#0g^_@kEy@)a#~oA}<c}LQ9nl1Q zm-#g=SM%&@!N^CI&R?e!{;AD{+os#<?|)5(PBs@E6>d{U^YX6!{(e4|_bl|_*VMV) za)J8c9sLWxrzxo|<>$<Hjjx5r(Lk`J=gmsj#AOSMzm!(%_;eBC6~iT!epX+(?`dly z`{t?bohO%5JRc9en=eoOS!?on&wloIXhZh%r(x3jSO4Q)Y@2^x11ToLmHxc#K2d5g zTO9QF&6{1+2Xn{9eK>iT#+|<4T6;fhnfewi?eO2tYrRhmdU9cTmA&;_-)EowhwWW^ zsg7;&OIv<H_m=j`9AV20|J|MK?D`max92~zTL-ZP58kF8lZtbQiPx5<pzWc92BiVX ze_A#;cH3U*@dr`_bT{Kp^}|MFCj(NR6>gn7->zji`8Dmq(iZP>XiU=hccEv5Sqzi9 zy8>4LokIrJ;4X3Ip*dLAe2`(D_FMFo)Q{S0_Z9tFk#I_p4lsTh>rgu1(xn&TcjMpw zrCs@V2rH;&_WjTP|D`QHJGtW1bpMMuBz);;@@}DSs>rZt_y@!d_2*-fR${2X&rz>K zGi{vqb?JqHJ-HY10x!Pi8YG;n(i_VBrNV^h@9amq9FG_Dh}>ZPH+<lv^5*f$PmzG` zzLSPKfSfX|6NP=6^2u@WCI1eqs{JB_8vcRj)bEB{#J1(kpN$Krzoza+ejCYtKiTo* z2P(Pea82f3w9<n=xlCtFI_5LYrMLohQhNCt@!!zT&c|;0w~4S#iwAVWk7Ezx!%x0G zctE%R;q>3p11KjEUj2Y(_yKJ$5lJTA(#N1F515bulPc-tC^FaJj%W}-+d$$`1&?RF z?ScWUJ0R4iEutDF${B@gixSI?I=2`lRUIX#8m(X#-CYGBRs#T{rchfnl%xsMiW<5} zN<J5=8yZviLK9kY*Kje${5Xcd8Ed5)YhxE{8yahu8*ASd>#!K>cpU4*8Rw!J=Vljo zD>TkMH_o#y&U-P=_c+d<Gd@r?KG-fkBs4xWH$J>AK4LLG@;IKzNsdw_$JmkMLdoP@ za$*}fd6ArYdQ7HpCS<54WZ5NThbH9aCgisz6fPzd9VZlXCYGuumfIy(h9*|$Cf2qk z)-5JJJx*+JkNAdVYUE64HpDdNCUvwWeFK?}{F&eZj7LO9DvoKuE-7m`sWlXA=45Iy z1i$)&TL3VtngVl98Lmz^IY<V;6qq0*H8<s1C<C1N25ln>T7q0xWqD~AKbDJGaza&Z zVS1@(jy0y`wp1GVr0;S}(66Z?%&D(wD3LR%0FiNrz_{hl2qiHhn2}IHMo~+85$80p zCQbNj(#xF`L;~hy(Ow{o@$ew&pF71C!}OKF$f$-HA%M<r91d|{DwSSZoX(m6-aD0} z{SBhedWo<SG}IaOK0d{upK@#n>KcKEIEI`f%=#2v0iKSdH|6uX6E2YHP%ee{mx!1+ z1s>qcCJt6RfqOUx4HQs{rRyYs69D=?l^y`l;|*x{?PT%BhcIR)195P+Ek|dAvJ9gA zYf^31Fq?~6(t;0xDTZ<&y&Oc_{7NhP#sr_vz(KN#NqKNVrmf;6TNgT@0S4gVx&W<P zG4i$=*n&@WGXlTkz-9tC1Jbu>=LF<rNv!42l;qK|WWv`_+jp2-h%_%yEFRSSB|_eR zE~x{EaPiXAWqckDsesT2_awq$S_niywzKHND7kEy77~8inC&hO&Hy<rQ*<1+^7e9l zc2?6qHsr#lnP_|IlMeD7jldlw@W(@eQ6Hu40lp{F?4RK)@Tg5>mXjLGIJE#_9U<Ik zk7%<0dKENC$oPe0I%!BzE-B&ZD0xlJSiwC4D1~q>M8Rq?R0|GJ;i6wrEud{n7+4Ax zq~nX4v2;*N29gt<^UqAcDKE603yuQxI?~En=uZsOVa}+9RVOM)ubG%zK82uZwAZu; zBc>2pRdP-Q#1lD8Ej2s}$hi^5Laz=s7N?G482}Jz4#4jfOWFCKm8Z1G8E%XPwdKIG zx8_}5r9eB^To|)0S8*gZU#tXm^)#IM@e~~u3wq_1xpNi3m{ExohA1FE(IXF;k@4tP znz#`oeOP%ei!Epm7UdV(f#^CEkm!MVkY5X6ON52d(*)28<vg=mldxI|OchCza%p?f zt6cPzq6~?7*_BZ=yJx`>a^TlDbS;G3Vl5h&^BK3NO1l`5k3~W}s|p}l1qb;Oy>J<c zLiif8e2R`~2tCh@t{`CU`7^M_(Os=Yj}i(?1(Qo8z%yqI+5=q4eO&sTuC+L8oQkgD zDrc~N0$r=Q=uwdF3Er_+D8_@oit{<bz{YS;${zG7u7m|JfVN;1wfv(5n2x1O2MW~H z!GBz$5fppj(+e~ll3)w>jdJitN(YPPlX}_!_<heO09aYnC_5j{{QRKVkoX8LNJB8e zd<kd1Rf{2uH<oH8olwzK5Y46zRu-drotU7Ojg{Z&fZ`XP_n7TXKu!85A|x7LPgE+{ z`lX5COzyW!fX@lfp^d1^NiPt+a6$nMEd42T?WtmieTxyj2VK6kT$OTdne4S9F(`WC zPSd$`$LV~`4!KoLzD$%<kI<rTdE1x@A`8b@guTE?RMYM|81!pP+^3B31iJDkwKSGx zG|n`0Q$@rl&){06@FvtU1$nQwUi+XU3#9Ma%`C}mplw8tI8`8e=}qVx;a@wRnSd>) zo(k0s$QToF(FAnE!*`4^i}Vi%xa*Qk=*tN`fKyF_k<jJ$6_FVFHDioTL)ESwA|Ggj z2Rzr9MvQaWz7A)$G64-&OReO<RS!(D2k2o`L*x83PA*5nSjd@J?~DhZsjEN3qTtSb zu&=0WJoVy8A29WDlT717p`A=b_+a}Vdnx4~^a!uf!I*nRNLD~YCseSb+XQ@=B*dbD z`EUU=bHM6GFyEH|?T9T<`KA{V-I7U|a4$@jQ_G@Pi)13ag&x40cJ9(W*Y^gU?}Vj0 z)tpxcIsf)~d1L>o4@QK;iKF?wc<1wi=nn+BjHwq;tzoJ3A{tA?^eG)}WQ3d=J#gI{ ztR>K2@CHAIHnkKZZ~bl&*P<V&?F0_G%P9=7^Z~e5jXV#xm?=tAz4<a`kfWq3f)3EW z2Nn>XrZ|AqtC&74x^t;jEPV`D(sp5rrjhuJW|~e$BU@v?Q`YOH-`U4u3jTd35dX75 z1VSA@s1@c_$Dx5i4`%?M>M{BlHeK}lno4_kW}_T($Gu|rZ8H>-?&|T>`T~aU0>+7u zODrgxig*dlKn);(`lS4+-xzZz6!>BQzSdU=p~4{32<MikQeay?=Ds9aCE#^p0gMd| z)K6u7c}KV1*@pPqw0RX|c>faC*j>n6tZ7_e?9_ofbw<7MR*SAHoIwLQt%Ja-Q+2^` zm9jJK#+2|h9SK1DJ!z&%r!T8%qk#-ChlB7XXtUg_3h(LyK~%CoxYmi;U79H^=~M>* zC28=s8HVjTI9)u=eIM-90NWCuaE-C}0zgZ{K$8D>DbI~MIZTfvI0>Z7bfNi{1b&#z zDt#`d9x$y_XL5w;L6d?rkfgkL+jD9m?bkQsP;~t#RJu2q9&UG)+xBu2Vwvj=jMVm= z9=N!QXqQVvU&oY7y{ai36<(V?uQgnT9Y9#l;L`i$I%Z3!Y4xS1<t!IqkV2m`IHk|@ zB*VB|!0RKa-nV(^oOn9H&lxc1r?}IU_i)JD)nt|te3u+^Kh$#Uen(Xr1-;;edhE|Y zwO20y8DZ0O<;BRJw{%{fML8U{E*juWLI0(%@N){;=Z!GoPw3_8fS&r<fRS#5B~60l zn_GKjV(CR+_UNG{Wv3C$<{+YPl;y+URf%+3xH))-f}WAYI;pKAAk*4}`37~`nmfz^ z^_U`%;pIN+{O*i|<uX=!;))mIAzxj7G1L0}(Vqo{(!NC|-IyyBmJuw2KL8A0A1e-H z5HP{s;T4TTmqVTD{z-%7)OObqw1P4Hh&^aW>7V}HfqBcKNEMpKE>G4k$r#aRgT)4y z@(ro)>OW_Eq1#k2DquU^hgbYvE3vHFv6~bNXa)#X;;Aj8-aBHYaL|W7p8-HIE=#Y? z!%FDHBAIouo1eVEHo5m=&Q#(>(66&WrV%x<$_VeJy>kh}kc1g&kbOR0rFfr#(U^Y7 z1dP8AmULron2XL`1M5&5H0iHv>?a=kf}7-BgwPl(Zx2ZO8MlV`gF-+0Qh@kMJvUv3 zfS?7E5S7Zk=?w_Ge_YNoY2j15=a}m~!1?8rg$I*dUdvULPj-P~*diVEz7wjk13CYD z{&hWu`#xQ?9P*b2M*GqZK!H(;AL*firz=~~M*G9#vgFj>2{6<7PWr1z%;D4ofPLhz z_CX@OBIi^NGYotOu3?tJ(T1XLw9|AxtH_C)c?G~y4CW)?#IVWu399u&mthUrG_c+I zxX=vLC%&R3)!F-`UW#BYrtH%?Bfm+4e`?X9K8x^@9@a0^KN&xO;yev+6jd(!{gbj) z1|UbWh~I)m9Xs{)O{11H%XPZlQp@M{UO#CB;o47NVbt(MCuBYq5j=$uFTyZ9Zj8hu zI6fi|zffsOPYIIwd*WbAyS>VdRM=U11ohc#2Qb^7LB|_>weqrqEB!C1cuHUr>;6Ss zk~?$2v{mr^1|B2=XcJ#Bi`r*~uB!s*LK&ZY_bDwP{1#r@b7BN0e8Fsw3hx`B*Xc#j zuK2$<JzQUJKA}egPX6f+!kLE|Cg&bh(pc^ZThfOEInq}fKdSf55GQi-zEKa(GAofp zB_M<y0u-aD$}z~>XKPguz#`f72XZZ4`%M8AL00(J*&(ur(u=(H7%ro1>FYg8<(3E& z2jrPUi{_i?h!XU!kn>ES)ze%gO$a@0@#`VmdO(DRD!KlYTnb9)*s%g~fL)IB4-TeM zP2d}LNI0osx$VK}$A>z&r|&hBZ@qSjk$fS2J@oTZ`ac73tt;DvhfY5i$KFmZPSpBK z_P;sgl)&wIr~J<Lt;t6`D}h{B^P6stC_P2bO(_k?GhZ{fdH5zsH}1meC#-kbt8+u@ z9=B9j`(_BkDGRoHM%;!RL?4mMS`I04wl-&GJ3Dox)3?X6()E6WWQ4P4awA++I#vz? zJZZlDA+CB@Nx~qZ3FiNM#(bds!}95eVGK|@YlspB=@?7xTxw|W<lun*3|svuoMr~a zNt`#?tzf)@ktZK1d@G|AB--cxA_%vfeBI^`#_m-;4qY#ye{}CetBSYnfR4VTWk1oN zh-0Fo>MTT|)P!H;)jLZ)a=vagKd|bI7P@C6jFRu*E|ruHTnUgfl^3MD#Z`B!Q;ch- zLkO8fKICC3ajWgEtT<y_td2%1%{24HRFj99kFwvTl=}j9x~CLHL5zq(Ot}_K>4+1_ zFj2xW(9<$QXsecs{4N@YAt0hgd#w!HSpdz13+Qt>rV>cuf%S4_6%R%Q8X_E`>VGAf z&SzLbkG%v|VnEwFJZ<Z!V@OE;;)TS;gtxJl@dCpY`Ei$;p0ew?xBJc~Gu}*7)N8AK zD*9l?n7;JhmvjUEd%weuDnd3=76igp9#wq^Ti4rJ=Ghn-tB{sY3@8j*O{gxsx2L`1 zl>Dyrxl59Du=tFjvJWmzs=pjAcvq-)+ZbRJGm%Oe=SnW@#;(V51T#wnlqpJk<G6v~ zxZyl<9lfpwSyfD&K3VmP4mb2cBx_lP;5$)WK)WaPR59~<X~T=0)#zaq*3(K+!b!S_ zVK8og5#E`c3}Dgec7qD+7YGnqho^gC$Id(76wN-7L**HTgu;o#?lFPbCBKTuJG&PM zHHpKogPHB&4$lVaIPejl!_TjbL(X6+!MAjgKPHPsF8oYUa263Z4*YFFeRL`P-^+`T zsn+Gp%V~zZrRT%BSz|(rOw(e?VmDjJ?{cqR*uMIk@AuC2Z`-S0Hk0l_Df<`$iMkAD zRjZo(*M?N3wv+e&IjwFkH#0t46HS*djN%c(L)<@d`+Bb+?*SjDm*)UEl^BO;!Jg45 zR%{bY2#w=<Qo>!YJ;#3^FRC}|b%Rzpx0}J2a>~28h!~j4V%8(;_)*^%UstbY4ip?P z<0f6#`73;pOewh_vX<Md!lF|{-j87xHr4&x+MQfSe@9`{lt;;`maXHJDYr))Hf!}s z+~%l@;s9ARu>w!yvMDrnOi;)T5JUIC0~y}xsMtm|KFn%N@QZQf^<cxZg~SPdcHzp2 z5_zTiVhrOkYpa7KJ?0d0V@Y&15@gm+HOK2RFnE(~<W!22btUW=-lhxjSczVO;uV3# z8zwHZMw5jji6nPDxu^gXnNyal24l@9ubp6~>u(Tat;1G3m|=%|=FO0xJ13&eR&!mC zOW2dlW7KYXOC`v3(Hf)sZD;(vN`g%AsXRihs|00Y*CbfpaE4;~)-eK7M4msPFv|BC zdHTX-F1oQc7tWhcCc`YVnJKDP=f>jnV&ortKlbhrR00a+g)#-X*>~FsaVm2qlbhQb z1A>ila8Ovid?(W$`ZV%4ES;%a$ne@sT0o1d%y%KtbFvxC9)@LX17F2-fez+RtKPW` zSH(>pidz*O&Q)oqWa^DIF-PieIv;Yn=rgas6ox)jypXYc@{XqdCSyR&o$_2ozk#$z z#a?kXZ04HPYh3*fgEhDHyzJj_r%w!;NcmhA?6o4xl5>6Qr7TM->wfFsPf!YyS<}lr zi4{oUZK~jEOvPr9QbCt;o0;74(?3!hW1Y71O*w<!w~WMXCSC-kF|X~U=I^Pe(#i|7 zit3p{h>2e0C(X}deY|g8xJC(NZ$81r`!KvsO!kbs$#v&dlD5vZb@qj`o|^AoaMIgS zmzZEqW`uhFm;#UJLdU|OZ^-kpj4j{Rpk|LRA%hnjzhy6UZR`1kzv*;5e6i5|U#wrm z)`c6t=NEd82K^#`cHTHSTzGj(<4>f~aDs9yQW5(8QEXjKwC5Llnd1CoL^Yi0t}OO( z4Ee_?cR4fOUF;X24It}jxL|S?2hQmSBwp@vVQ*a=ls)Uz-_&sBURWGDKNOI9r^}W9 zXz`UMZ6GC9!%c|e?XZD<V8+?3k(=20w<8vDfmszAHzlsT9lbIXnEkx#rp(>9V>f7n zatAeTDdfBzzkTL6c++)DrS<KEUtCb(md0)Mg}0M;hk}ZJcHO>o^!D`w+TdcEi|*PS z@22AQgG<@E-SyAEn@)=hE*HJ%VSMG?OwLenrE<52`Q3N3E-$?9edhMe`TKLW%3Rjf z@cM%K<QV_qaAA$*{abBM-zk>AxD$4y?irC_&hI8)KjL=rlfrgKZ{@^_Bg8*7T0B`! zQzRt!IU+p>hYkw=RCqo4(Go9ToQ%Ia^1SN3R5J1iJ);}a(v4nVFwS{;6Xh2IAyLHY zw1iu|kZo6=#|2%nS^m8o66T{`c^X9FS=nUs)%o2`tN7!Zust5eo9*O>!<M7DMtHKd zw$(zrJ73Q7A9{}qGDSb$Xh+Jc2GYd&bg!96p*{@rIzTJ4Z3<N<npL{AS_5r!p4Ou$ zLa6Y=j3gKqiBya37Z!p=K3m&iPa|`3W6<|J^EP;8+jbnKJ0iP3Mc+6VKY!z5i1kaa z{o4lj>W_Z*Q)HFi_poPl1`Tk=%6q%b6szgFKec%3QohH~dt@bV<zJ!$-;dYq+SxJk zoWAdG?5}0;{CX3utda=bVd^kDaAs2=7KmCsh}K_8KL}bZ`=qH9LR~|uzbfl8Hcl~Q zwF`uCVJ`|RaQ0%l{Am?|)8cP!Fygwhj7Z?CvKs(V1Nbs6+gRAIFB5(;8s=-WYjNYJ z=GKD7P%mdDJ-gt))mZkv)fWNP?1KJy7`OS@Xk4<C&?@I&CAD8N)0ZEg$ld6AH8R1j z<DrYTGC<-0d@KwYPa?A&cSGPn#d~Cu3)l0`9&`1cn>z7@K`2?Adh#)e#~sN;g^)Rk zDXXne*1WFHCc-`Crkx91jkRK0kHX{-oV>}Lrsp61X^$K3Y5Com0<b7eb&*wJG=(tP z<8EPGw178xWfu9<H6e`pvc*^}d6mY4f(X?n3r}g#CX=~`kuY7PA}6&x^CIU#cbpR> zn^Sd5GJay3<J8ehER2wc<CP{KXk)w+PymtV7y?XnU7RCh|6T-k;yn@@?_A}`7%uGf zL~;(Oq%1N!PKm@6w|fD!9y^_Jxj2BiGrYZW`D%%dhIHbH1V;d8%#Mm_7O!L?Qn9T~ zI8^;YR~KXxFHg`ef1>w3iLCArExp>6Q>{r3)mFpEaCo5nMycdBNR2CAdH{J{7pcG- zbuGD_tg4@ptD^=T^jbp7wCIqhw7CpPOh5YL+90qx5;H-Y@yErAP8Oi!sYijzV_0oy zLi&|4_37T1k_p<Y8`!(OWXFT9xGCD0oxzk)xY&3mS+3W&P4`6<;vV>j>#Z&+f%<4w z_4J-o?gPP|Ai0b{A|jNa^0%=@4ri#YOQx-ED}PVs!S*R1XnW`msXO2SIoPBZbmB?d zQ-9Rwpm+*z=EG*mY4J8;ZF(|ZJ7?-*o}v+%U>w5<p&1xt#p)>Pk_9R1HFIQ7Z?f=C zY6uX|u8ri=Y7Zhahw!jG2r#%?${6f|!Vsb3(Ii%!4nQR-dXsB5bpX|VrU9}v#VA=$ zYd!Fir=qHh!;95UM4%+1kEbgL$i2UhUE?+m<l%eLm;PVDxi@q$X&g3XF{)e<9|yy~ z2pA#f!T|3mVRvNxIMUWrid?NVuG`aK!x>*wmZ*`$<y;#uB`r3CWWwQ3gEU43bH@ZZ zqqwn<yl5kUs&iI~JIQ2JwQ5Z?q%+tUsD`XN;BUd<sq1lnua*qPAbdm;q*c{>q@rrQ zk+SZ@WXf31VpL_YIXe;ZSr^%}gyf};F&kPWQy{A`WUt|B=|=p}K6<dFYA^z2=!E(d zp`RRTQ9Vu;tnOxA9U`x4oCFid0DRF^>|0$fXD}1^e29-#Eo17OX%w<mi(F_2ed~o} zzaH&6pn<c4yv&*+gZTV$WPQx^=cTT3FQl}4lpqqyK7kxjlMYmz3T#jrse2*@@2dQj z_OZ(%2B0!K8ON;Z|MDh_t<Lzu0gPQ#<-nL^ESZ~XahkJZksK}ja{6Kn(Oj*5O!*F> zD<&%P!faeMNsR`Oo*<99l8$1K?ouP4L=2eD{?%8EC0FO2k4iKE*tyyuoer}poDjNL zNKZ_ZATUK+VRA>Kzb0l>AQvWAu5$H>))2jZwrWZ5I5t9(ZPp5DQBs|T8HfvwiN#jj zD#kU~N2$=v=AE76qmiVsk>qN~JsvISI9VF7iIKC7$t5yHjJ?!7D^ygXq!}5h>oxai zar2d^5NbVi8gPIxQAmFG39_sBzr1*b2$Ps%3qbBNa6IR6Q~%ygo2r)coNWZfCF{Wb z!EhfWm*IlgyUQ6n-8@(ld9mLt7OBl(bDF}rn6tCMAllD;Kon>gON*UCydg(vAZdRl z+Z~*t>CXX#a~W6wAd*NI`@zCd#X1u0YG2LY={U|PcWJ0BFxefk$VRbCS;f=x#y2LB zBZ-EKn}}tt+H9oIe*1v!ATo|5l+j>OBn_Q((0&~q<@Q{|?+(iB;N2vQct#c1vs;vP z(xeb$WJ6<i?JOscyWc5BD^o09I!r2wPTEJ<0XUfKfNf0m#a5e+pct~Ubkxy+j_bpb zNSHbA)J&gf!am{sb>+7$G(gM%SrEMD=RiG)un3v3m41E|s8;=VcDV3mbq!dXE^>AP zi9_mYZgzE)FaGsL&c~8ZsXlXTp2nL0tjS0qW^sA&4OvBW4qI&JA3Vz2ZIWY15(u?Z zUbbd$n>$q<jkAMrRd*+c4k}1ReN7<?Qca+Mqi(l_v?%H4P4n;y2Y^DV@t$NpSbV#6 zW#7#xcftZg80k@FPm!CB#U{62N4j4_4*xJqawm&o&2e^iWX>p}2ntrGkyj8s#kS-S zgM53TRq=R^|MQSLU!ON$6pnI{COK+!%rdX#{I8{p0HvMnn5y$;?BLPL+hd5v(iLFQ zKH1J(ahYt-I~QFs%6Ca;eUJ>~T8F%`5~(9`=Nj+uz9KKKtW1y@bgkb!S}c1rmb|mz zv)`>ZXaexLo=y^PM5N54XB_k1AbA^RZjZa%-O}zH=n`JBJZgg|w5*5>Ey#%`C~B;b zu{sJ;ZW+`Y;rCa`h8s!OZL)F1&dt7@in9>dF~L=8jR@&OvpFZ5y-bQp%rWUrw|V?` zDBeA8BRV=xhg=J5#lzz=f@3Ey=%39mPZgL5vModE&T|*RI3u0jJ#SN9bt13M#~tWA zglpd%GM60~^N_aLM}Jh>nno-;@(!=d6|MbMvO}QWk&Erd1{brBA?-^#0H2-0z$TxJ z4gCc9V*OYy-)y#_>*=G9iOM?bb6tL71$%e46}xYHJ~uyJ{+Rf+U(J`iDGJn--zGPV zQAKr5|9ZRP#cZ1<kYXWeklf9<(6<7}-b166(;fGXe~_*pI=^EkP2O0wYZ&BtuYK@Y z_R>dMKmZzV_`faFLmvE3`ab(5DBxf&`*(bC%lewb88FvQoYtyRiFy<~!b7mm;G`<@ zLKtan@^9YgcAGQwC4);JbN}HjZo2KqxF;V|!yjH;=k;h=Az-Ml6?ax5PIO*l`*|9y z6bgwJ|L__E{qg)jBF*B5`#W(vJALzH?Mb_oL2_awp(~5v5~<(5-%6S<HZpfhUi<|0 zcNmLAVH(_8=8-Z3IyG~*q(g3P^34|VM%`11Mj_WH4P7yuyW=Yf%3`QCTHyWD+owml zKs$O@Rewe0=iV);5hk0C8YL=|6!c~?Il4w;Ql#}fPF;G3rh`ozaEN|%ovKXn#Kv{R zVIhibgGA|QHFJk@Yjq4xy>!`1A~L}{_4a8uNeGxr@*#iJ-9OxSNv4{7h$RJ#+eK7* zr68f0Hkag3lP@8gTgwST2YB+L*M~P`6yXN6VKU<jI@UKq@zG}V5V8|(_nFNnKg2?Z zeYxpm>3Rr(?#d&hA)hx|`-)P&*{egB3P-nCSIa}T=U-esN87vVXpLF*N$TxSoj*{U z_s_rqOjV;o|Gllq3e>9nq_TxxDD4M*6IQ-|VT~s{?yuY*oab2`tD3Vu&8B?(^W%1i zen3ZZ;M0>mDgH$ie!uC(jrZBxDQ(vKB9Mvqv-l;#hx)<XH~oxpR~51@{;~bqOzYRh z3!S;_<L&!B8M$P{XqP6lLbeMuy`Au4MLV4DO}#$yORBBJrT(z%!O93g@-7p2x^HIj z2uk%~ItuQIc&*5{W^!d&89TY>mLN^-*W1!|r(Iv{83SbfV~}5RkUkbUn-e(VhL2am zi68X*a^Ib=%}+^cc2LH6@&TXWgFd~Hka>sTWyV8dO=a+tzhfVG7QLA^SkAk#Pu-#C zgKE7AIt>A@JQ%vm;reNAhABpWeSF<Sd0FxCx{`p~BT@f*de^5f^`CyM3(#^rG!L9g z%$c=Wurjypn^!SD+YPjswEu{DWCpSIBlFgO2t7)kT0z;pCIeU?#{ik%x?uF|0619e zV{~ynKd+`5ZCar(cw+rWgw)3n++KJi#Xlrw$KCI7N+p7rBMtmTYbD-)JzI1)>_b<) zA5u~vN}!?DKMn~vK${HPgF0i**=S0KMq_o!Di77ic}SzeA<T8g?fVuuAgq@CE$u74 zYy;;ysaI|fhW6*oxebtyUTrH+tgH+kPwTHF)d!u{yC}4p2fmzpWTx+C>QBbOhCZM> zd3Abkht(I20=aJJ4?aKjkW*hiFU9?Ov~%Ug0&=6v@2}Y8slcUO>c#WNjz42RzMUi< zP2d8pe*gWH{PpEgU)cg#UH27KHp=Y8dbeVf`E{_#A#npie2V~c<A0W3^h_ok<t#1- z$;{^r&nknkmG|fgVUF?deW%viOj8;*q6szQ)Qha|HxWnxion1dKALJpDOgbrRsE4f zH5d=$4<d|KF9CWL`4{4(%fK#$Q-@DcM2ILUE0OYH=&J#eCaoz^eCi_-kYWjh<6RPT zWJM8&N<01&1QKonWNWKL6S-OaK&gDzn=^GV`r|qEEVzDw8NG|Qoz6HNr)nLvVK@W| z6u7|c2jrc{ma;S#hqnH>-nOchI}WG8<FN~;eTf_hth1H3_ONSfZZf@765$a%-JX{m zj5WdBR8lv+@FU)}8y$AY3*beF5C|{Su})Q4>s5w{3TvKXl@$s3T*0h8#GQd$j+j)7 zCM0tP?;t0YMW^0i%EK~+q>JXpwqp=9=DG9_v3&<u<6+10LZf-g?_-~h{FOI8PBMRU zPCAmg!am>)_?}5b&6eFZ?d`|RNI1j*W2G~vVj1;pdT7b6OnQ+S=ug4gvK9wyGG7J8 zZLezk`ylZyaA)Nb9nH`NW>dWwyO`J_HaN4E3PY6;@cp95kpBY+{^1qkh+KLy3-&63 zu5*xPDe*G9?xGnyHuUlp8PBUzw@(e{@i&d|TevB@UTMK0;QT5j>he8j(QGf<ce|W7 zyquNoZ2zk1LRsPeF7r6x>Y3f6boI|K<B`{e%r(yFQ8ZR*03lULl~I|4mqwmVw-~@T z>Q$rai5o$H)LYyg9kug>;{O3_K$O3)78D;sZ4P7xdjNRh9g1uCxfm2PR#=c^9t=p( z4Ig4OP!S{SMNk=?smLBnLr^Br4KU!Q>ucKzRa<yF<tkQwM<S&jkX;Jo-J1?o2pN_F z!6*;`!{(MHSu8<eU!xkq0OJG&UX~Y`xjMxZuR*dWlBRSW=TLG_ftJ;Yc3Pa3O;JF^ zr;bFCaBNbwB`n-VUY#*A0L1}zEyw?$J#1nFul;}n$QRo-l2tuPi7mHhrWj;FBjie= zKpHmOQc35WQ&17t2*i&-MHG>XK>rA2CP8lm0YD=FNJ>zr2?di-8B`Yp2moPt)kLdW zo%`9E9m_2cekF}O*R=rf=+$x#4e`SqY!V$&8R<GTE6*euoU%hiE^Y?OBgZ!o%{B1n z(OkY}1tUr``n)1w1n|{UL%3Z;n7!@If$L3f4zvYaWQIv!LPYMkZg@9%R9sE!4#g5j zdlyvmKqCxLr=6*nl=rX=mWrZL!O>nBs<{$h*stT2-1AL4jWEQj_zs1<orf)UL(PT{ z1l?kO3Kd>Y5(&w8kYe0(4*>u1XhTpu^9b~{J;vd`bHoDx;;@H3=7ElR%%dFuc*i`H zHl268V;lqo06DDI4+IVb9PZ#p0SO|GegMFKmk`K1<ROqPoCg5)5J(W%wuEFbiXgEN zh}s-ds<2(nAxnS)+X&JGGj%N?vDm^J27-)|lwk=$3<FStIFKJ|B?|m1Nr;{_GNc$R zVMExC#027n#WAip9vDItn35_L&1V3~nO~m>;<?2%p#d@ofNOX(fq4}K3fW4^1kOOD zH8g8|&LLwMNj8vUY0g1c>>)yAC6ML>jf;;AkMe+4kO_={R5m-xL;!=b4gnwtCjmed z#K0>OU}g=)fkAn6IL7~ipzl}fyW$yINRT;1Ax$RJ+r*9~MT@oQ28HTMa(J@7lJQZQ zHj0t2Ag7cGgy>he@{@dkCJ%X_;~w*X8UW0}zzEh*APQVs3H|Ypd6c6Z0&yog&S4LD z3<QDWXy-i3aSw8sLsIjE2R-qJzj1i29$%}cKko4lb>i<I?f}3({_zib5+t4mJtzQ_ z22lW@?Q8>C8b9383jmzZf)A|dIp$%tcocA*?|3K%$w7{SOy?gIe8)oF;f@f}@iJQq zig>)jFZON54B=s47fW(7WHD}jt8)ltgaj3=H6m{VQJ_5vXb-FT<DoiD%JUpT6@$$P zD3bgLOw>3KR<i#Jlrp%%u1L8^`U%91!h1;cyu$*#jIwWv!P+oCIg~(+?2A<qt9yjQ zp0TnHV{PS7VT@I?Eea%j7$V5^EG9hQd`x(NAyYv@v^Z4?QXtzZ$SfT~#!d2Qb<a7& zHl?#o08D2dGR2@h>fsN0Fz_7c*zG@NDxH7ygM<Z<X*U6YKLG639{rGxK%|4fg%X4u zwv{P4RCwEgY*VAO&7VK8JJS+IFuGR5;6TnR5Sgl1AOsyp010|2;`ZZy=pBc2@TWrb zUdp%b1OP$XS&#RY1Rd=q$bR9`4{=zmh5P{{L2xykCL93@jST8Qf?$N7E-qI|EJ9{h zi$VbOA{qa*{l`5*Xtj9)*uCQz$4to~9i`nb9`5MJf#X<^t#t??jg2r}Lp7I#r3Y5{ zk#Is@MVjs8YGg5!t3$jqN3EctY8nIpIICn6?Gc1WkVD96#b~Uysn0_O8RgufXIh}a zF(Hm=;p3qE*r7b~e;DQ38jgU*<z&WI=uyuQL<|63YNgF;J{+QFwH((9($LKHM@jsl z&htuI(h?<zqy>^`09=~W3x)JRHr?rjY<km+8MV#MVQNl48q@`;v^ulWX^Em*EAsUp zsRuG0;}#@@nks^IZZ(v^6$CE?X@*0_(Tl*I)FJ4AX|ByNUZtgwx<j$_r?Cy|^<ugp z-EjZN4WaN;fh6$_^Ks%(T&XaGST;yz5K<(MI=`g~k|_<yPW_6LCZU{lGXo*?K(hRf z<q8%6JS+^><T~2Y3S@r1%$1`RE9l|CRnUnR&L}U;QGsY7hXl#7K<<H#ew?EjL0G~N zGBd=2EN4rGRpduV(4Do8AgqC+ih6=&xeon!LmoL<#0xI;p%;9cMnC#~1%h;=D}BF5 zNAS{<u9fi;WE{)2ZPf(A)2tT+odq#RL7D&va^UZTS`dgf>OpXU+;AWC9O*y~NDx54 zVWj^}?|EaqUi%U~E1;I|Ks=t~Dubyo+sTYBiCVj&A-Xu7!VwrtWpR=MfT9T@C_4XP zy!8dGJ;O&!a+DKhRizH30R}^e2e$C;MzJSVi<!&h8=jQ6mNFLJxO2b>;#<Y^!qo&R zLKCzwOr*@Ah4cALTF)wmS@t`UbbBkm*xgC=96#uNzdrU0e!uN^UNL;<{BmcTQQs~w zf|x&t)sqYOf$+K@4BmMD;t^{A;3I=A#(Rt1p;C4(ZM@v{Z9MRUM)e<mg<SW++N#;i z_l?5~dCfh@!+DL9IY=ATah*U2&q1-z5hPJTL|g+V1hVZC+Pz;vXhAtRO~d7iIP^kC zjRQsXk9(1Wq}`AB5nUtnLNj<n4FQ7i5yagM#p-Fr5h&KbUEFX4fw`^6=@tJ(!ZAgi zp;AfoLhof+*A>Qi;g3Bi)I5M)NxVZhG|cEJlAk~aycrCC@Cs5b9?%4e7pPM9y&)VH zozo#*)5YOcjS~YQP<}n2Ja8Z1$&*0ro*rhDJ)na;oCB?e5IW4$0?}4HdEI)&Rzcto z1JRWDNe2T#mvSxF_c=r-TFf>v5DiLQAd+7~P$Hy-Af)6E-G~7cYz>2%m{R~;L6pPS z6hWvER0Y-(6$(TUffMjGj61xTBktjL9i1kAqRq?$jIp8sp#v9=R5uOdHC&4poRH-e zL@%73AmvICEe;$+A9`q#r>sb6y#X5F8bS1e)l3Ka$pb$S6pC#V_l5tWIs!lqZX)_s zopL!>M&VC9lmj~rgk|AFLXd{@1yv9ZL=tX?U#-Vy^qU<{Bt=%_#rWa&J)I-w<K^um zJ&N2UZXbXN)Y^5TGDeqlbQ2%)-5w?dMxJDq<ReTfBSG<9Ib7O5m_s>n)FmKLJnZDh zCB!^H+CPlc4fTWn!~;PA0wmOvJCNc7@q<71f;O<D0zIMy9i2&b-}TAXewhQLftpOc z0~Oi>DQb#1h{M_O$`P!eaGYJ#90WpShBh>1MA*h><i$ShqI&p40gb~yfKxmr1V`FN zVV>l80cLb%p|CNe!LbTbz@>NKl0i(K+5iQFDU$VBBxiP}XLA2$VSc7)+6Ib!mpl*@ z35k<GyaPcP7o>5abIk)z{X;-9AUg2FIFSQx&fj$5<9;EKKQLpnMbJOk<I;_0QdFV^ zp2L3K5CAkoJwV$WToDN+p(a_~q+|w<2?P%FC`YbHf_7DSfaW7BD*9ZCm3;HFBM zLoW^lw5`ix#2x_Ph+8UA5s@Qu?k9itr+@w@Mat9%q2E6&Vn0wJZekbMsgQEoQ%oUa zM(NXX4Wgt#;BLj%$eq}60%%Df&~|;C2HDh5cA?c!%3L(T4M7k9*k#zn!#yabKyX6| zVVTv8&2w&0QuqTuv{x_UkAYR1Z$=$d5}o*EVoKJKIH3Q-crIUI*eC!j!EkIr6YP(_ zkzNvc!<=!bmToDRcBz*dAm2&iKdzl7ekAu1rqqez_9=}_t|T9R>Cl<yBso+{o)@Fw z+B?+LI$6y<AP_ukRYByK|5yzd%ITNdR{;%W0FI*%0vUY53T3FxIIvVn45Ky-QzNLC zkHIOYcB-d-YW9hrkZQ$#C19vASE!k4w}C3><qxCy<Zhh<**Sv&L8Ahl7gx3yDMDga zaANrRo~C`NKQKyd@v3SK1UEF|bU*^zxWhTzWLJHcjMh+lX#+X91F*8Hwr(r8cB{8? zD@)Q;`R!tX9wt|QtId3*(#^v?aN#aa%0S#ha6<nYA`YdiEf+Y6Q+{cb)zBvHp)0@! ztiTQ|!Cs#P0p&J{7jgk*!Dip4CF(edQ03V}a7sr3QPBNhq6CT)yRIER^#gn<*Fbbs z!<MYco-E1|Y{sVK{U|3)rYzB&Y0@BLO6Frr7Q}`cV93EN&-Sd({w&Z2?S_PAOhP5m z3N6wmt<o+n(*o?#4#m?pt<+8})mE+5dS=vm-??5b*LJPfel6Jc9S4Oi*_N%@o-Nw) z-Pocn+qSLSzU|Md?Z3h;-PWz$-tDKpEZ*)d-}bHFQl#Ggt>6wW;TEn|bXsv4uHr5( z<0>xS1#aU;uH;TG*FJ8a&MoC;uI6s;)I$F*=YB5ehHk)G?%Im3>7Fj?eyhx;F6*|g z>mKUXzOL-fF6~aF=hiOn=C1Bm$?fj0@BS|E62$5TFYy*{@%FCqCa?0EF7hs~^FHt7 zHZSx}FZK4V<yJ5DX0PK;DCTOf_kM5PmM-{?FZqV8<qmK8rmy;Xt@N(1`@V0<o^R~J zFa6dp%!;r5=CA$=?5xq+{{Alj3oQBuFaZ~^0Us~|->v*6FatO6e-5w%N3aCj?)*-$ z1z+$dwJ!#5FbAI^_jWJ{hwx%tuLzg02`2^qp0EmU@K&y{3zskizpxBTum;bt4eM_W z->?q5Zw&9S5C1R_2l4MNun-q<{`UW{5hwBZBC!%TG5F@N6G!pxB5wOhu@z4*316`m zKd;<wu@_@;1%I&^&u$ivu^H=b8K1El*De#Uu^XFi3cs-&qb?NBu^ks~9pAAY`)wZY zu^%gN82_;#|1CxivLO>L5g)Q5BeEYZvLo}cuRgLQ<82pDvLyp@9R}$f{^y2@>X2Sc zCx7xKFLED`X3h?sCui*_8*&_LTDFqfD`Ou5g4!&*vdxqlkhWSbo35(<Y^{CjFKcTs zFK#WTYX3IfD0*_sUZrxXvSNte@TPLqjWG9S?Wn$Cn2NF-DkrFpEdx1oVaO~uYiW_< z+9(R$GJ~^ixNIPEC?1+q#A^R(I`?5a1L!;VY9nvR7M8;~l=3FlSUkv-Gb8T{0#rN6 zpH}#@ONwMnjc4|WTpM#JNTQQMZ{mAd(9+bi9j>e<7N8u)6H674Iv0k^z9GX3))o@P z1oD=a_EY@n6Sq>()2!!vX0mM<WI>P+)r~aH?$>?NmYe3IGk0`JfLuk^U@saqPZOqA z6$C{swO7QlmBca^`sRv!B03qh94?5u76gk8T}7ktsy6OFw9|QNvtU8>VuT<;WZ|3c zXF16zP0^S}pK4OXLM@n0Om3dd{Io!b1O7nTNh=0D9h6*)1Efg`Jk)iry`iCc%|LwT z#asg60e~`qvO|;uT08#))5YjDNCT}po5g(R4b=icJod$K0|{0hs(unLw8An#rBr)G zRVM^3tb#1!18SFqn%dzF`Hx>pHqoJzT7MS`CdDpLLvllu02=FJfP+9B0sy1}|IBtm z5H$dNTUPY8Vn|m>@b!ummnhF8Ju3zzqC!bzgFM!DVGuQRm&62e+A^=mW><-aLiS|~ zL?`e<LDT~Y)iG0^P#mIIJtuBL95*JsVJi$oHLzN17aTHR11lEjU`Mq;d;%p51Sx>B zKY-l_4#Ym#jBH7@fjQzr8@O%A-)<+3b7w_y7luyh)IRKk|6sR1`%frXNpg`UKPaQQ z4(1Kz!!tNIf<gaV_xAKq1Vb_?gGhIFQUE2k`VVTCQ`SnyyW)dCI)qy@_CWBrSJd}a z@pc3PK#l_dDrohBTogR0)H)GFJ*>EG2#}L!ML*CJC&VEwoML=V<OmVDZM1?V6b6{< ztV$JxJB(*NpgBI@k3R_aip;~-ansI<EC3h-|7>DXa3pvW1S|*yEQGeApLUHCggWd) zg*zKbGIj{ngDtifoG06g7KA7==1!_mnSSy%$yYHr(0O^opDqoh3WO>EKow`jJYi`` zFoV(+hDiwoOvQsaxRYO2O-*k|IIy1rK`cQ`!#tQ}m8j#OZ-`4rc63RbVEIEoNZoXN z)sYWHHh%xN6_UfBs<fmFGz{{WwL1Dxu%<6igE|!YI~h<xumVh3+qY9{q<A8x8)hx) z`!h>=dikI{1SCO(r`5c9RzQ~k5`-*%RJz-ENyvkvPrEp^-@8BgU~k<kpYww31NzMr zTIXXcSBaf&$PLxQddi<f4Hu($9SMPaR?yQ;7T4G&t~bcTke_@~tY=n0Lp&5anr75M z5L9x>L#9cTcUcKeKU#Vby>np{oBOYA>?DB`oLoOTcNwU4k%K$k8DmxnI>^+Sg4zj% zx~`qHaS=nE3;JnB{7|-eEe=GdF9<kUDhOp-H}yS#Rl99CS8+*HA<Ecaf7hg6OgZ^= zVG#eS|CD#t8P_?$!<$zy(+`Cv%&1lv_&=-zksDVxF%Um}sM0&zsb|I07X~DTrwmF| zSldSDy?t`x+SzCPin!Xl{_}E?5HZC4ig?4;;SV%mr(%S7ds~U5Sc3~OtTGn=P|SW; zGVE&86VThqKh&k&YvMex12KFJAbNvw5fuA#KLFf0WH0<AE{0crXdtQ(h6buYus1*e z5IB%v!GZVg2}Ed+VMB-45;|mvPU6IY_9_m%^DkpZfgD}cv$t>}x_<oz63gf>Avuo* zQ37z)F{VI%{5-k@K&=)>0P|ipw1+XMM|k*tGL$Ee;Uk|F<1r-J5#B+9OP3lP2O$4p z){3y4{fmbXVN`-si)M5u5NObP2hkP;`W66Dt`RFbN}IN=S#spiQ8WlIX1S|O_d1NH z&D1rT{k%=I7r7w0p$hR<rVOBJM^4ZHAT~(S>%e*E?9FRy@Em}(0Cet+ow%b}+8!s_ z&bZp1Xo=<|K0T+qAi{oli#@$<aH&6k00h_dIMZKEshM@Q&Ad16asV+g`gRCBmcVhV zC2E7jQ9N_R#L-2>I$s`e0K_={?I=#5NrKOVS_mk0&I{}%0AHf3o_V@6tuujU>*$kz z411{?+TbC|z=28=h&b;I;wQTPMm&rlcPfmoLfY&Ck+p%`8E31EYDvn)8_)kLN*n}V z3Z=!4CQ&XZ#Ns+<JNF*Mks%)U>a9J8d|A=E2E9w=M~9v}5-I>LVXLBhN`&VeBef)G zM$Q83uppvxdFMx*0LZ1kjsSEgLOKQV2R#!73TI9#89K+GCtYlXmZDaB3#bhdQZ26D zluRqD5%WWADRTDQv!DzCs6-%?HjH#m0M2pr$gSqlhZUa&4N5<ymWszLY_1eF8MmI> z2PjA@dg~Bz{;{s3)j~DRpJD~NbRNRYa|?iWG78K&g8E?+Pl+gctrncr<gQE?k==6G z*f0&3#MxexXxf3od8eq&3WCNNSVVQ`JWVlk@xyv6>eikG@eR#4`|AHS3ladt0u;83 z0z=0ud7e5?9x91j%G`#$snwxuI12cuU2XKTAp>W-)1h#zdFxw)C?Rypds-tX$%=@w zR-$IKfm5P+F5Z;3a!wi<9eZZh5#f%^5$v6qUsm!;g{gIjtRvkGtUJ{NQVFG?3!0B4 zpM;c%lgNbq4gkt*u88UD3_?dr(p=ulWAEaIi)(_gX1kyjp-$|dW&n7OK1&fRn;|K? zp7<WGW&&U=vZixf>WJXfXB;Ctau)!O&$)P^l^s$}V;B9Q<miUF^Jia&49|$a)v{u0 zoJ+WI39Y40BD<)&i;HM#f#6B<vb!3puIq|Qys>ZEVw(H-p1J=jvF^|WV#lSlX(I^} zSjZ7E(1BcnUZASu%d9)!Dx?xUe4H-`DF6tLw6#N%Uvu=1>d#0Ud&1sXAZ^USln$+{ zb;#?TLE<3~@qNcS@oUK1NL4qifz5#hX;@9F0y>NE3jm+!$W*%VkLg(uZ!gJPf6jra zfk1E|>l#RfSXdEw=*%H@;mGhZ;tg=@<tZcN;BwG{k^VKrK9~5%jFv(Y-XSb9R7#?j zD(Ds6ByT9>0Gq)0WRQOxt9(rZ0A1?hL+B7BDi0H*M@;9Ci#@R+-AWc**fI~>Jm-YV z=@2<oaXNoNXfq`F3l41py|}<)i*9`2>P!O^o$SLm9SZ+Ul6-PT0BFu5?IR-qZne9j zBrjZO8BUsr1ST?q5+N2F8bQiove6_2SOTeFz68Rw$7SRu1R2_2p!P~{EpJ$wy5B%9 z5es|d?=XRBi&F+tEUv94d|!ebc*bEDuK+S0{n${bK=P@W7!sDEss}RIGQ4h?QaS=5 zN-5jJjl>}GCBx$-UPxjfpqK)FS=<X72Z9pSm`WmDK}=wX7NCfrgB+c~#267}N$OQ& zi0;FXIeA7*04#$P8f=JOrf1QNfU0~{dIvwKWRFK&<4nZE;sH<U5P0RYLkM}5M~t~A zGMP&-`vAa<6beg(0Fqx7oZ2{g*wBn5<aY&O=XL*rHjbk8V?G1PWCGh39eUN}oEk04 zY`XP6ktM4=<jg0B6!$|oTIDb#>DzXmh(m3RBOw$CYfzGRDOB#WEpDt}V1%_rk6=YP zb##ckVwe$~_){XPOq?+jx7Rn~2p-nTDMF<K)q&KqSzvt;sp63~Va11=4S|zMTAC2h zNJo(OPz?=DTC5UfHZ5j_oLD>3rM39AA~VVvtVBbhAtB}|<nV@9(22Kw8ic1p6$s)y zLP>s{gHSH<Q)2Lv8U}4gbw9+KJ@}Iv4mq(s9C2Yv|L3lMSe1nMYEh|%o6J*6L`@0A zibsUSDTh!a8}BH`;xfWbmth0C1L>Iab|nAVy&RPwzsv|2NyHD$Ifk;kso_8((^&)# z1d);yE<fxO;px5OwYTA=NB;4Y1>FH*^`J|L8$w_i`d2x~?Ffp87-9l`H6yLz1i~~J z*otH-a7>!pck=|GU=8FgU<;cE6XP-zS7gaccFvMd=U;?52O<B6-=fgL5hxdB%MrN~ zkW1Q-mqujE;=0I3dRtEjp&7^s6Kb2i!=!Wc&ny$7+w{y~pC=pl!5NV;kMv|qEgGbm zaF)n3;!&aRR!b(aEFg>7qMHnbSU6kR2P;Sg)D~i|AWaU|qo>q~ilFv3y?93>|9PKo zSd*)?ahT$En%J*|?8CznNGbU25DEVeq#5`yhfa1K6hsCW0F#L9U0l0L_A2nzR{;@I zrs9pT6;RWpniF2FQ?$oi#acSK5MXKJ3xb)EDg1@3Guc8BbMuSSLnZHu%27evU<6+a zkuxl#^AC5VFxYp|NipU@IE=l7B()r^d>gfzYAkHdCiRGGYYkJuBxDkASr9`2m#4i* zseaxti;jb$l5)g{AhF?TLvl?UuefU;=_*bM9sUw)03emHmB<eH6Z3vjcdJEOpxVxY z7m>$uY8_q@7Xu0aXGF%p9f=uDtzDGP=|hba`G+;Iah!+?<b8$}NY44ikwbubs9wU$ z03o*HlzV3$wxHetP0knepa%bSt{l~JPJU;RtQRAu?R2tKoVd8*#q9#|#u9Tv;W5js z=`R8KOM0RZhtz{5i#uaH9xK*Q#ILCCQJ+yQC{ck**+aOL&wHVhKfFHW@c;O^Wiv+* z^nQ38<iPYnEWFC4oG=_hC52dpl==SvK%IWxvA7T%lx2RTiE`;(zp+-6<Xz70<@B)8 zIcSf2Va6Ol2?i+pZA=;xH8bu|MLQ^|^XqiTdR$HV*~(E>p=djqHqkha@`e=tMrA0w zo*KzriP#8Y?P%i=j-f)Jjl2fXVLs-B_Ggw}qN$=I@FapbqGIc?#g<G-HAckc_+rfh zM>GUu|BAvZ+9Di=shj@<f*F3ODh2@@C~3M_WHkORC~)Fym?JUv1OQzmiE6?uNTM~= z0b!D+*|NuX6!0Y~Odif5=a_2r7~&lwDweXwaq{M@?%}&^p);C8AY5S{$f2`>D}DlF zZDhyQ_~9Qg4JZ=gG7^Pp`t8iD0-em_LPRAi>cJ(zj+dmU<UYh1#^;_C$2ZVRAYOyi z+@qhY!|S#!^a!FxfPw<Of*i&HPV9ua+9Mq5LG=8`mhva}3PKq;q<Fx~-LR!Z*s34K z>q`oZK?GwSRDuE>agqSQ819Z=45KC{#TO6;5xqqPaRiLY!541|0MgJq#32g}#2?OM zvi^bqqvb=|je-9J0u~6#&6vg=JkW3K4?*@M38_(w%4|8FV_I5i$sR8P%|<#}1U>jc z`0$1pKLtcELL27sHdKc)$e|n%#Jd1M9iXuybOOp|?(IP29s)8gm}F-1?t=)bBQT;> zY>*_Nh5io2AKn2a*1^Rh#TiDcAl72v!VE;l(M6IkLkt8s=qVYeQ6feX1dCzS0Hccr z%sSS^Q(yyhk_a6-#~RB>9$4!q#^D0NQR7wxtnfl*iqd^xXK$8+I7lMQ`l0b8ZXh6m z8^+-|Ue6$a;w4uoEfDF(I5I#sqji9Sxqh)Exbm^4f)kGmM1Ic{i(+bkMr{PpBQTLG z*num6FbV%p0x^hz5pSa*YcNtUuqY}{1^ELV0uB@h5CVThuO3Pw?1AhGlOfn}DNVx{ z^Z^cejy9qKA7&07;1Mie&e~|}HvEbzJHi<*ZcQZRD=z~a8VB$6=_2C7E2VB5IRpQQ z43T6pBgXPOT5_*C#KL%l%<82bs^akOfi){a6(Niq`XMz##zhWuXXaubzo;%u%Qo2K zt(IdPO2h5q!MBQ&A^t*Gs;R)B(=62K9?B*T9l~TV0vYfj`96><f)0JsGdS)q#pGrl zM4})7MjoF{^5~HuazReytF<gI%6>>NRjxg>t04Z9hwf1`3BpQF$`sHcI4i>}p28mf zf<FIW<QWFbGK*qn)TC-06LmN=BieBufa4N^A%!9(I^dxg+Cev4wB$G=GF-tM;x8zY z&Kbx-BEd>L_d=Hj!XonvF$%OUEaOK6Okd=oMTo*N0m-eHf+Ms69-P!WFpocRu|icN zCK^XR2Qd9qGY~P;j^d#+tl<eKj9;PyNGGS&1R_XE#rcXtXD|f}FG>BD%_}HEB^rW7 zVFe*dO1k7C+2|2E+o?s~;xd?~G=oBfT;xHtkCI^FBWYtE;KUaI(otb$OiW{BaHJq( zG%cz$A)~M%kVr``K^tjERh5ueE8|X1Vr}>VMHzx0s4nURBIDeWCjNs*VzpNU0v!K* zRX{(YF5m$#C~zvugCVBUI)%-sbfZ0wa63+JD?bSPfG8q{ClqRdK-)qaRzVv+%HA@x zRcGQteL^|~QDz2W9PVpjlteIYuqeGk!7yz^)(!74B0AWI<^Z4-T1ZK{Pf($YECPlb z4(3LHA{SOcC#vEZJj6KFQ&uSSHfqTynsKZY(kD9SI&Y&ih~h0yB04xVDE<{u`=v~g zOGF9cE#v_(BE>FRqaVxy7AV79VF|;$;l^x^syIkB_-7uMVk;J5l5|EgZ(}G4;u#*~ zFwx>4hJq*n5k&BGvG7S`tJN3@!rYcMC>quv>Qx}?LO&tYoPMMd<3TWZWncddLL1uR zA3zouv4ls6MwIG>X&cNK-2rZ}FqYOvN(vH6tJ3)@q#SD2A;yweoz0xiVf>ckHD!-j zJ4D;OK~9bk^rCczC@l4|6D~ThUfyCO(hC4?i}YxtJhXO3p21RKWnqY+Dp>Vw)-f&Y zurhtZ9SHMWwIV6#7ViY&Eud0Dvu90e;&OEkZ~L`r(80E9Zy;7JKojpPtB-7TBO+Eq z2A9LH00dP^^L0a3AW%V6Ahsc-w3oEcb^+iTT*AU)Mn(hzTJn%9wC+YMBT0s{BmRQa z`p!JIVn&-5B)iitOko_%Vf-|TV)%g^S|c4|W9v!-UU-%v?2$7@qIdsGus!U95P!&Y z4meUY_bx~id`$Hpo=Q8&>ui(tA5=+U5W>*%gdAFzAiSY*?1C3h18%&-WH_}nO2m2@ zA}Z_<ZiCS&iEn>{PCHxU5k^=bRDm~dq?(|iaZsWp-=$ya4FGKFAdxVLgJKZ&!7>6k zB;vt>A1*VZ$xGNOaP3GQjsrFfqa9L-96)0$C}Jy70vyJMGn}}vo~La)LY<-m$s&bs z3JhnLZSp{(9=i61eS>>r!+H+SnG7k0Uf7(fVyfQa9c;=z@M|u&LogzQceAL8>jiPN z4QZ9aRt-{alqW)avs%R!I8Xv16QfviA%#nBT4mIIMI|bZfiC}IV~$<Ke@TTRl(~2k z!W$k$H@qQ3zw1nn^4a7eWzWG~2C9BtMbH316qTexGD#p(AxM;@CNwz_`Bp;V!%?3j zHj>1V%MK*dxIdnCH=MX+ZzLHJh>Z!t8E~Q>dO<oevnYtdMrFBATf-RoE;E`VZZD!U zl0ln=R8$mtFIpoQh7v(vg8GV4a$N2(Sz@soRW@Yr{y6$2hS`B*<86P4LasGOUN|o1 zp+(pV^&~}rqAWI|qw;nxaLxuLs-YhsXrzUggj@BC%>*``STOuVavvB+`ieH_$)M2| zm0+VSY$r@_gJ{8LMiwq&v9su4D-?o(K+U9(C(eQG4?_Pa!h?OIe|+njE2~}v!#--F zqPx28>J6{wnlol(sBt(gTBC6yB$TP7JM4iNtf!=6rj!XH=k9kW2CG5?n;}YAaMJ=C z0{E~)m_`etl{B>e*1@-i7Ye_^B>+2Wb_g2ISbEjiZpDg61!5KMSUJd89BZ&epoJWH zM3sOxYs-mN>+`s|0=fs#E>f0XXn`Yu;}EujE_`@!qvmLcf|~a%D89KLzzG0cyC0f~ z;F=l$q~WtWjk*~kD{G+|(4)9X+B%52$IQDrR8gz5asX@kCBWe=zB@5EB^Io1zSDvn z4rO8dxmo#hGsNUFy#tm7qOD!T(<qI;-NGG!0uKMyf+-l~g3Bb^U;|9qE_=;xFQiTK zBEmkF*f&<A+93Ky6vXDL!muUcK{k;~!t=3<qV{sZ6s#;ZbZ1JZNzB;zn+Jj#(oyQR z3IKW!eO&~c^1Es4f&8Y#oWN)+n6#G)B54**C;Veyk3=W9$82!fgbWi2>!mcrVIu}& zg2^E&PCQb=hpEnpn=0fp!pD){%Ni-sKDZj)NU=|v_pnP4KvW#|mLnBfVNr775<mqj z4l`DW!em5Gi5?Az?=mrFV?mOE!(G-pG>5+uJS{roOmMtjmf`Dq8y+GCB}}ap6<s03 z!5-XhMy4Er1*0GA;~KqcIdq~O<J`0(WrzR%g(KF(q<$JNAmOj4lS36I*tzu|prI0c zf)%ig?b-rBD3Qn(Sv~REBMO`$IOPyBHDnpkMfhQhiNeRt2>?bbdFL|5CyN#IL97SU zCmh(sx*DDFk;wkx5t^ZM-`uU$yZ)8~GKTjr8mBSi>^Yud7y$qr*4@!1q8?)Ah(e>` zn*!inMU~Fsn#qA)o+6^t7d^6JHVl3*H1Xjdm`@cFBTOu2Y$x5{p`=s-#PI{d%3+|z zY_{MO|LWm=&RsR?`GG6*4w)h*tcVJ4LmQleGT@;v$?+Z&$6LL_7Z{0yr1~Xd!H5J# zp?L%-xZ$?tVjiaQSp-5(%)y!_{Am9Y*_A-5OrUR1X5;QNV&>k08R8O0fRe^wE?skc z78CRlyulu|W;v33AfQ2-Z^Urku?LxO_z=I1e5j6yB7XU0@|z_~6XP=MqD9QrKrrGG z%E23;#U56BPKj(YO!cKi+tJH@H_+h{ngQqOgh@1Ety)-a#NvrJZ6y#yFgAl%T0L3@ zLhNaG=H}tk^jls0A;hA#T4TW<w4F{?M5raz!u~A80%lRJ-y@<z6Pm$eJA+n}2k{gV zK(wn8Hp7d#%qJoQj6}mZ0K%U?00avfJXla5LV~dX+>5s`qC|uKAR_!n@E^vB92FuQ zN6??VdmI;H><8cx0CEKFm3;r1aidEB;t0Be#*bgffiM?(Oh|B?yPiY=Xw+CV>A|4| z(UDXNK%P8=+MxC%#}dFZqX1l4Z3(YnRsj6ap(7~uYes_R44zX<@ZQsc)(8S?wGnQ? zxd3Liv?uo;U!rmm)<byCY+<YX-T{aeYpmXb-pbj-nilTagDAgB%?z@jPJ{pK&CE=A zZs*BRQ7e^e8UW9N+D1p6$}#gif~K7L)hksl)`IN_VuBX0pINhT`GyAIm~~va)TJ9- z3}E*`?P{^dbD3;&y|C7~I($8tU?qe0EG~BKx~D#alDpr-h_5bq0Gpfh#dT0&|A>^7 zREiD8O-lqN<`jSZy`=veeXZfP5G(}2^BY|Kq<0TfP%S3cI4;!`9eehC_8D3!ewChH z!7NnIZt?YW;8=56<WP$eaVO1N0qUq!JH!A0l7;Rlht7;dnbpr*oES8YZT3wUTX}mu zb<S)Cac32F1-)qHLF)iO9+??R<RwAgaMBGy+2r*eg|~$XRcvQUmu5lWJg8)D@-TPM zK$q0EpkfXZg<6UA_0%T-xe#QTbnt}5i8k|4W0Z&JQE87q`>>+vUnpjVB22g;6QFhF z5Y$RR88*sMjd=mE$~Z|*2URn2;yT%^u2j|;tT16HR!h5f`4nt-hIuEKAGUZ{v6Br~ z=0d_Yg^oSdQltM*Ic*ix=d}nGhftnMp@b?yHPLC%x+fybD?;YX^Upj7s#PLuI0E3z zqxP(3Rc6`(@FYR%+@qbi){Zn+s4>n7F+#9b$!=T~XO`6@vr1W%ZCN?XZakwYEHQ5X zBDC2&B%_%ukYOI;*SFGfm({+kkuwuK$`sVk%4p#z4lA<xsTV#VTSYN4_|)UbycLHz zkG-p11AsP;)eC5t=xAA#k1jbQ8`o+LycTp1mKV;2B^%`PJ@{<N?j}ziEnQp9TnW`V z+*~r6JB#Wy>q;1!s}$L7vNd#hgwuIQv;c@K-9P;trV>FM!-bSL1-askH~s|P(>$a7 z>I*vKkmLWdQYF4k4m|USt=6gqZ9*@*one$M=wCTbkkJIut9w#MdxKO_{y57COLTu_ z(KWm6^W4+U{!}Lb$ov+(S_5qcuymnm9+Eu8!$kcijuTHO_~(tURzGFt8z%ct&jdCA zp?db&IaSfOxbZ8A1^{pXpl48t+CgL%CQJc<Tu<Xq>h!XkW$g|jD8bs<lw!bxOywT1 z>j(hUr!MgIk0|}vS1F*EIK7<X9Ps;{29ISGsx|3psi+sTY;v~=g(!z&*_w4g*N+W7 z5GExw2sLEaLHmr5HBa$MJ!}RS1B&Ajyt|-M(!!Uqpk#^HxkpX_01bk$Vl>$k9+zrj zkLdqd#~R_l#)5|Ul~lMSYw(IlKX&tv<xFcK983!J2*Q$Eu|^=|02>HZgg=4|B^$1a zN_pO5jkoPZIx~V39AT2ZB^u~KvKWUknv%rHc%yr8krUXoqp~n@5ia$3N<-?gwN=7o zlqkcKHzcDupE>A@a5E2ZrqUm5RI6g;xQ}(pG>PmuNS8zzh+x9>jG>SN9i)Vc<}OJ@ zl2j#(s9auA(xRQT&9OYkl4VgoQIIlDrW4u_kzlY%nSzw#nhpG8`&M%dvV^aJ>>8#r zts{@q0RS7HBnK^7)0xpEgC!K}m~CnSfN!Z&E!YSpT)0t}VEBVrtT78bNOCwl&87by z@(4vi#(_sYN(VskxMnpa;+mmYXeCxm<RSUPuqbi~AJ~Y;IAEw2A2IMe6@y|O)dm1| zD$^{w9LHN$ksX5uk)M+>i$^R}i|9m+nH*^-o#4TfOK`(hc#EPpT!O0mJxeN6ji&@7 zvY57l%VO;EW>M0VHUKOG0B_+c+y1nfe8Lr;*kX@K4wWP61TtboA&2Z7a?mLm1bn_| zVIqlC5O&}LB69I-Vh`fRZcLM~J!zFW%4E)xJf#x#u+*k@<0FH-l&Xlrjcckg4}n@| zF<xcjNC_f`V^n2TbbQtTBT`efV5A{kEG{4KVby_*;~1TYXxXe}4R)l_qN)EuE^C5A z62A!WN5-AxB{V@Am8SM3BvBY!QKG(F?1r?1O$#|(@g(ge*D8xLjc2`Nk7#uxkMxa5 zTF_C8>S8utn=*(=V*!%>tWqv2^Tu=jA&zNsw?F{k1$iaAC~^R`j_ZX=Kb%1Zn&1P0 zGpnU_&_{`;2(h+ui7iD~6E!ua(Mon@)?s>_6!Q3i6KQlw9-X^K)FovxXR!p&X8TQf z7*KPA&<9flIWu3#LXsuE%HOP`F*3yu0DkC;Y=Hcu-FU-_P=?Az>eolTm`km@EpSH! z;*Z1RWt>)ekQ%?Dk>lBmILaexPdri&avY<|eR0W%p~4a^!-K_u-bnwwct;xRtfn5% zu_q>v;*oiLE5PTl^hA}i8Tq}0dV;uJ*t|!OI}EV5a0#R@o`H`qE5#$8rqf0uI2Tnz z1sydxMpg#2;jnqyCA!wjAQsfCjU4ZP0NBTZjdE&^uurZ$p2uO_F%V6VV;qky4?e(P z=BJ4x9-AQ$dt2tqZzbDL0;3>63qnP6(E5rD3vjv0x@3fDXDsXD3W)4%5No(YW}fW> zc@Q42+!jO}_S#IB5lN)80zekL`)`Y=m~J_z#}ztx*JLjKLIzXya`<DaJkU3ZalB(V zjAc=EDh8-`^drUIh!&C?3;;re1JkTo;Q}uLXmzoiHTD38FFXHw77AtJAH{^YL<-@m z{n98&j~3}c-dZ@V5Bos{FAqpCf(uEOC&%cJg)As-ovf4tBr5xPQrg-D`_Wc9M#WPq z3bC8h-J|P;1G~tjVveVr#cAbXi7MD(^@%KM-W+N6-Z7}1YoH>J8B`pdqQ-54*!}XD z6gvd@`sb6g!$dR7Ek=@Ic-EwzHSh>TF8;x8(?1s>G`G^>;z9V@$^#{DnM7E|jpn;X z-oSw6B>+tExCRYA_(kCc(N9hiayYpksJjos8%L+%v}wiQqCQM;)DM(8W%&eYrIk91 zn{u$k8M^O@m(>1O($gC^^Rc{MngJlIf^utv5y5~GohSc219%Wv;Rm^ZGZPYebfOSp zG(c^}Z>3fZsPGQvV052VUdr+`Su+l0#uC7%a{5;k5Wxq46emi-5`)kd=3stM(GLD+ ze=akFRsjz&vLXRTDineV|3Ds5qkt1pgjSLniAE6ppl`7U706%=v$s~qvKqYx7tFAG z$Wj<KRv^ccHu&H=>>>_%08qHGLhgVOp%515FntPma7S1Yxt3yj_b^sM2mk;}NH`V# zfCqpi6_j@n<WUIz0C(k)VGTrF<yRhq@DEb>6&Yj&D`5{&gMi0$f+)BUStDyt10e9A zTXZ4|C*f-iR3A2IM<}r@a7c<Qu@TX-bp8>7=)nIE+93yj(0+AT9+`kRlaU!&!wr}5 zhcyQiPFP+55DumAa1E3&VNwe=##JrISLBdld67Y?C>GZEOL9R+p&=4E*b_qYG^)@$ zG9o9cI7}$VBqMTJg)tN15Qdl-aDbE*3RZzf_=fC<5DMXKRC7{>hETj=T~^{3&wvp~ z;f<C<5S>7Q?BYg%^i^AuZB|i;U!f2jqbb6sIz9o2`Zp`_kbHx*krGi8*l-vKgOR6a zfnV_loe+^Q5ey^+k6(cfZ;>zj5Rxx(6fHSHoG=OCFb{oY9hx!@j3*r>6h>ph5-W6* zmsb~f*gztJj}gIzr9>gj)envlBg+wazv2Ip*!VOMF?ue@e4d36kI;~p*ejHT8=_MX zlQ4-k2M?<ubBI+QNNFX#rzR<BbL>J##~=qr;fSm;kzY|J)j$kmp_9^55XhmIMS&66 zz(@_$kO_m0pCDRcQX-6KCd*NO9KjUn@H-!=f8(ZivK5wAK@IFMm`D>A$#5OMg%GRo zmR1rSoNx%yGlQ8?4y)k}bY>mI2oqaK5QoqWV6#bzb8}B~7!(*RVX}J7keDwqDeOTm z|B#zgF&2?2GN-8&kVz)5*d?6_7s*5ldiXd5v5=ytQj_6yA5?BJDG?o53-i$um3T1+ z$q{NtmL(yYFrgFBrxsFy74Yy6#<2emm*5Sv=#`UH9?Vf3``{JH!7d9*J>yV0YIBlb zkyrl!o=G8!1QQhG;cg{iPo%I9Pcn;E(hp||9p#Znyf<bQ!yV(L9Xa`r@JXUP0bK=Q zZDi4(MZpTQf@eFybWs@+1c3^D@uMZd4{rkwx5*O&VTB376T2}Qd1V_Jsub(NSFBMy zK2i+^5tr<urFFy)?tp(4GbESb8`^<#!Z8+@a5j<yUPg!||MV>;_)F=;E@|<eI9e3< zQV^~vBAkhqJ>e3E!9#lC4nxv+Uomc@fl3{!hx-{3{)L|tu?c>dQvo9<RpBE#fs3l8 zc<6u;vH%b0wWKKM8iB)6Uf2I<s`L~ox(eXK6Pemo74sDEunDV|5#2}~IEWjAfm(JZ z6%Az@+zF@>u?nl&MJK3H5vG;NIYGJLIDUl*{^ULFCVKLKm*o*EqvDO0suZiRGhren z%P?-h=@x9bdMvR&hYA(0FqM*ZZQs(EsS&KQijchk3I705k=LqprIt-Wuo=-aoyvR* z;SOHmNTax{dI6x=M>x_dsKRGk_|^;V;G0Cj2_zAiwS^GU5FI1hK;(K52|^|~!>;60 z5D3&|_s2Jbs;v@1N94edYr`6tU>?8GWlF*wj|z0L`ZWL043NMtA?Jb0H&vcf4WDE& z8ML3PVG%Qd5uU}R07w5PB(b2^imSAR8k%q?fMQP3MI^3DsU;Cc@-QSUF-kKAI7f;W zuy|Nxad6V%7cCnru>}up!i2}k8b>RpbV)P`v3hgitP=4L1v4ac!W8eY9wB>!oWf81 zfDxClF70rA6C!$>qqG%6clfC#kCM0%+dxjnF33<HyP>QL8z$tyvy&x^o&f;W5S=o4 zZPKx+uJTTJ5(=#nCIZSAsIVLGfS<j036X(PrF#&05vDV7giaL{C-t=~^E7fHB`g6B zn`;&7vko8u2}@Zn9K;i`s~}v#Rr*jQV_~U$(LL2WSFUTi^6N`}(Yg~6Szd~efaEz= zvJcGLHRxcU^K1V{OZaL5N+HK~PalL4;gBx_9AyhJCZ;pHvC|)L3#(7_93J_a1Bepi z@DI<x4r5_sMF=|MfIeR#4(MRMo;4#)=|WURj^&ZBT>}8Yu(5yYa_hAr*Od~{i5-gz z3xQ*GnbD)S%NTQuvda)HOCxfbHogid6^Q`=mvA(zv>~imXFoVuVM-nzR}en(o>)d= z_pon$W<4yCOqi1w8$li%6Q$xS5dc%BP*M>3@D`ZBeUU>DA$1UEQOD<!PDuO`@gTkx zN)WJ@w}TPL{Dc)xk`;RlYXIO2k7bHVp&xV0y{y!fsdl@n<_!5_Ohv~K)ik9Mami3Y zJu|V%pH}}op+O3YGEIPEYK=S@);bs8(q(4*vTkuQciFttXTzn5zVO>F1VJvSw6svM zDzN|z&-A&hVNwMV3v!%tT<8pWLAKbm7`ODN|FmQTQ7{fEw~xpr+QFrSj1XLc4%y%f zjW{$5IytH2sqIG|`@j;Gzzywngg&ATj^h^!qYxxqKPdHGQ=vXkWU2M)4f}bIG3j!g zdk^aK5A9GD%`ltx!EH5I5X6&gc|w$msC*Lv4<0hh`zbrp@O2mm7cOy`2fY{_m|p5B zuU%9aD3KMKQm?^j5VE7r3lTlhvD1vAu-d^xzR;u6aTe(GTjHs+a{DcN<rMcj5kArj ziQE4@WMjZo%~;%Kykb$Oa4{P``@}i2peSRZ3vtF)fes$h9$M?775ozUg0c~z%+_(P z08kgvLasHz6Rw%cYLOK?%+2=@M7I<w^`jL007b+wPyX0o??54EQ^Vy4f`xcG#{8Ny zp|^wq0KiMFUr|iPI8D{H8_8D~d_guDHh7#1E)bCmiX9aBs}>%@57A?F_juNOu`aT6 z2tU0SXTcXwA-RDX8lw#Wt5Q2lrVjkk7L~vfhHWMFP$Iz15z`Qrzkw3yWF>b~6A2Z~ zyQU@X&<>iz4a(zQJ-C37trnX>ng-iZ2ech)mxX#^d{o7FG7`?|Bs+&_9qCCB>;V4{ zY#4dbp$=3RLZ^IGW!Mr^G!9@z4wE3XMS+0-U=DfF7TDMhvoat=VL-t%;gI?d)DWht z>6kSU7AVn_nmymGY!z=23qlAKPW=)eEYc)|5EijP5SKM?av1$`T;&lh++ol^#NH^Y zG2dJs+TbDjofMK07MH*bLmjBpv=sd)9gSf>WwI{ah@4c_bJnc55g{`0*FFT%Im3hz znuHq=5t(%cTB`yQzR=uhOBCG@WBgIHVisd(tsP=cC9YC#z@&Sy@ow!+5We6L@Q~2< z+8_9kFFsP&4HOFQ0Kx#k-Eh55qL~>u!fde+3_nGCda}~i!4qc!=r(Pn266w}qW4kq zxYkgiMwR^%u7DK)BbsN(9gYLwtZ^8nra<wqplMo+A5jqT0L{`73~v!F;$YoKMGSkK zAmm`;U2PH0@ZKr+;#mSIfE3%%@Twyn5%o}RA&xZ2Y;g3ouK+O3C}j?)8`@vd4B{5# zez8PpBH-phD3>L>UHS|~gk##lY+DO&{B$;!)f4PfCN*mnymsxHL+f^25cks$7=dRS z$!&*G4*xJ8??6V+o*mlZMu9!YL5_#-Y0DgO2?fFMzX<?Ho3_PMyn$#~*rpf7;TS%` z2{%O)>~qElFC8^O<ESk0@SgG|!4g?<VToA`<jlq{6dMJ@hV*f4>OB7+tJ2w@wuBL% z6ggB6T>q>r4-Z4ah3;VI6h62^AEg;`8tQGQGg1$4GY|A>?nP0}8I)Ia0uf-c%ut~d zn$S+a0l*3ZwZ{d0O8#N8D?p*~4B;L{L$MF00Y1=>^><4U;m|1uF)}RPr8tKUFw4~o zp&eck7Ws4;VG;TRR1TX_+=B(D;eHMvQ4B5-Tj&S?wD1r0;Np8pw7mEkh4G)%mQ+gX zSzZ+ylEcyvA}0-H4xKTbQ1K2z(+@5&UcXG17-0<quSmJa8l>Qwz0=DoVopjz?!V+3 zRZ$Z|jdJ!N6QwTKfoOO!dk?Wc@f^ho;12eA(mksl@^k_a{Q&<AJU4FOz<380E@U|H z-aUEp7GC0JP~bpv4K;352x(lxfe|?}j2ICex`r85!5i6<AxZ!l4IVsqP^3$Z4;AXf z*>j;k0FcBDglEsEPnI<Q0f=?(oW!FCACk+sP@Xve#sJ)ldJr4{ckt>BbOj)uzj^bz z9!zV`D7K|l2l89nGVNG|0NmDPSQJ1xz6~Fy4LWX|Tcbn+yL7hpB7k=>50V49cp%Vh z8Iy*Dx)?9bngGnHwY-pP>4v0HlaxnS;b+OEhl=KRlW*mWQ~?l!$M5870RQ0Cta|S; zYM#J1o>sWI?!Tn~R4cp`Yh38S==vodhz|SWfAwI;J0AZSuf2OSl`s4UbFM$=mbu%j zT-qPdgZS462h5&t`GMLg#w_J{S;{?!zzgr9=tBGFopaEMuddG60)QK9q*AV)3Q?Pf zpK(lSMz5^^VCEl#?(^xQb`;V?o5=bB5U2Z8v{0kz0_(<|abN?$AC&Y{aKDB;0-&CL z&=F^l>1+!uqj;9OWT_k-iw*#9{K4*@DqV_hpCbq21c1$)><Tu6?m;CR;QEWN9(=F? zK%l+0V$LPoGBO7+)vjDCqO`svk)bYe;;BB20MMo!{LHkeLI4FSMjq0Vt81QYG6P^7 z*Vro5C-DYK%pQ0C@(sboV4BVzKV|z%!_uI7#329moZ+V^L|fvnqu_+}siY2Lnz6*S z2vaDsUFYPiG)sv*XtU^|`!p~q;~8h#kpP_sRnZcvrd5~JTL_)9062-;Go?xs0BIsK z7r6F*s<T-N=gIZSdt!kET;QrC?VNZXa+EWZ(7_Lunfg<%RE46P?52U8<?A$j@Pfxz z%f!2vue6|=^2mDbnPeGkTY_h%e=g~c-nB4+<sSg$TCBcgldX%Vhgh~Ot*VeA#~_<a zc1fUTuB7V`bgm6dq&p8<2bf`x8mB^YbnYsgWUCdO_aoK+7subY({;J`k{#E+X4j~w z<X(G}E>Tv6%!;fs<6h$q^OC*yCbJMe*C>*56_TyYhG?SU>-z`1e?0HkIj`4wJ|5_< zy6{ivlOI@Xoh_SX0ln+_udyFqzP-<(ZPJi(RN8TiW>X(8Zu5MHn&0U!eQxa_z5Z&# zwN3N)amwa@9UI0eC#<p`&=W;>io-Iw!OFkSZN{0jOZ%D`x6C~Z{nDEfkTtmflH-c2 z=bct)g+Uj`8Ku7-`-wV1;Q<ppwV204l4B<W>NIXgHz10{II5|pp>t_(C9bRf4pj!7 zoa$-yI4cUPBmT5{5R{L)^DFK3o#g7bSw4l?x4QE6gYFzXa=k!?l0?h5r_1hFWl0)= zi`ARd2aOLU6?kC`BD~v2qVIarJCG4ir}HT3ikQ%CHS2Kg8$1?02UEU;C4{p!-} zvoGJvxHViDBub8Xpm191oR6F0D^kKwUJRdevt@L|-jMF448cAlcZqD7sRM@(RhcH@ zD~C#_;WN?#0~Q=u;TR2}Q{uKwln^c;n<;s!&<YvO@;m-T7^;)ZWwfvEdH1~d@Fw{i z)3WEL1o7PYWOE})X$($D`!TKWYG8BYhNt33da)uaK=t>YVZuC`elq`l@vH6_CAz*C z#H>RrR901%YY!TBA~fyWl{AHo4rp7KfzaPuFSNXGI+W<wv~Ez=u-SAWKo}?7xZ>}l z^K8-KtQ7BBHB~NRCA)fKI*o2WcI(kChM-yJbEQ*?=}-~D$bDiL%lV1W-&s?@-@B${ z$;9cF)7bS7B_sKXv4VN^364!MC*#gV`_(ri@zYjEXgOfo_&Hh2?gKPFaJ5x(XZOVq z(MnXCe}$gIsMH%f#gkK4IBzL*x*b(+P4BGva{22pOlYwZ{W%D17<ZbkcA&*<mR*rr zWj^;}zeV{bf+Ua0!5wQajZf~@SUSBgcl`(F_ZN1j{Cvzv8o^jUYWK=FQOq9rKK}ae zl8k{|yy?CAlY0Nz!sWhpd~nczjfj+uJ-xM*yyW{zI^;|mcIXqsJf}6eO;Ae-><-SJ zcy0T<sa;J;X4CZ6U@Cm?HdX~`8F5Q+I`tgx>}5_NOOsbal<x+lt6wkD{HltoKCu-( zM$G9C6E7w?gK^wHNH+g=F8^n~9b`-yJkItP<d}lB!+KyAHtJ&sg&jje1y^9VW))F4 zySJn+hkZCbH=N~$ce^Y?x#n8tek^YE`omD25uoh;VA8}uSF@3d@l>|t3yJc_h_^3e zr-|u&oK^abWMivAL2(IvsK>%wwebyW(vU{1yGtAYWu=S!*+%ZUCFohR6%E0}wMQhc zxnY(dPL`T+<Hp??KCe7?Ui5;j)Ekmz%aVVJgUVCM;2Tiq_^h$stLpdh<I-BAt^y`o z9yKwu9u|JjQv<II;yl7tvjNmld+bSZkzAERr65{`U$y?liLwhPaIMa|UR51`lJpY$ zcr!;c)Az1SJ@&<=paY+XJ=5UTJTA@e7-=fCtU7D(>vf9V=mA6gml0cPaJejV*j7qp zhf1h+)k60s_sJWKR+75vu)GyE7vNJLzUO<U%T`*PA5hjf9h2;%SYEW>b1^hxSmbGj zyz{--XO;J&k48Cz33I9PHbDa!=5+H8ADLnAj|zh)G|JCPKCP)>dX6f7d^Le2rdMo7 z^L?6obwd0DC}Q!>+4EnTy=OXNwM_%B*AZ4_f1-wU`EHnsof0^GVcE=f$|Yfh*HP*q z<c4RB>#OcUkC8f&A?q--NW8`nu7-8jz&Np@T-&6}3vN!@oW%%zo6<U+D3K@O&X>uG z#)&44Tu)qWG`f6BDFa@1^}Hs-!O&#h;(qcC)4=VdYy-W6+L<ZqX#awHC){%1o2L~n z_Y{5UaywOgh39hf`^;3$a$82(){S@dnZF=Ug#~EmPUrM8tyR;Gq0_`{V{P0713Hxp zYF_JXfBT+<HI2rEp7Y%B@_@>j`iX2(Z$@&Zsp~QVR(0UcH|p=?JV&OFg$a}&kxn-7 zGd*@zh4J*Bs|;!6y7;ZD$vC}x%m6H}5^Khp-|Rf<m$>Izcl~Kc;fBpTNh1&W;CG2N zU|HpvFH>sc_5lJC!mrD0q{1Ri18eAIY9>bS-YYo;Evb9eFwbXkzSmlaId+rrmuq3} zskpZ*<9?9on!I1)^{SV?X97To6GB1ofk>OOT-G~xA@zgSxHQU{zh_oHukeK3l5+Td zLNE4xs@{34-}C$dOEiVKy~LK7xUJ45sL0;Q=q9=IT!MK1v{-G%q=@X<kF@+8>`#<< z2)>(2%1)N*@_H}jc@w6iqp<Y8=a%E6dNI0PN9^44e`@~eZ|xqv*r5GvW$XjYs1WfA zMZLIbTH<tfjGy{{1m5@WVc64z5pPijTe*`-^Pt2FS&2Hv6Z5e8J1vCq;YWs)T70Wk z9E(~L2KVj!kBW_xe^1Y!g|!oOCa@g}={=OD3>kaue~<f<mT3RP7+<v!5GR<UHgZW( zPeFxn!5h|eU*E1-KzfA!lA@o?iuYskw`V_kdT^g^#x$7dfWxgye_a%ItC41!iv_T_ zXPvvXKA>h3;AJ?-a<!c5ihPaVam^b8F|aa?Ta1x`+T%_o?{A(7*ypuiU<_)BGo7%X z(tLSh^osC)lhd$B(??rNf~G65R6Fil+EuBzxXM|+AcBMkp5^HzXW1{_uG9dsGWhEN z3-{7nbd-xMM)<JQ?pwhEVVSYQ%<-`LKh1`*)_Lz`N}oR$toB28;8|3_ph)<5@`iEr zCi8tuBGo#*vxz4zwBT1lnLmNywnE>ZZgKBR3B^M0R;Q=odjI68bSpA=1o(GfA!(&~ z*omV_O|*b)WO(t@%<M+_cUfK>56TXP;~0S{-#PRD+=QL~P*b&g_E@00Kd9ywteN3b zb>}zj@&v+)r#uD)jkd{LYcf0Yx~MLK`gON%T8z;KtB;~X!%b<P*(3cLIsiZmM&<Et zsv$<vh2I$Gr)5*g@ec-Ixz<N4yUg>85m%W-sW6i`)5N=k!EJ6`(Y>=`&8e?RW^=jB zFIWQQ&k%(Ssk>+)!Z~{X6hYT<_*y5A)H3|XQfEMFs)v=?vu(2$E6607yFfcRa%r@8 zSnvcRIbn|OOo%J1el8}B`PAQbVTWd*4JjiH-enGRyPo3?%%c=nWH04a?m;=w(v!~M z_vTM$!pmUYMy%%2#*m)AgKgvd-Ja7Mgd~!oyEu(^|Gd~Y#{A%Y6B%UnMv6H`*YU%^ zTLWmPHkA0h=fp+c`*i(6SVib;uf+{0>;~gCoS4Lt`fUb-rJd3jhr#)WpA+D($W>h^ z<vbnuE&xa-#9v@Ske^Qn+F1Pw%*^RX*7;Bohl85^?#3kQ=bNT=oNiz`jlV@4bKc~; zVaH9k>faB1IhR|M{rX7v_;BhH@2xWZ<fie0zHw?O&%jDs7D1Q3Jf>?foSTc#9gud? zDE;D;;?@BQLA{WdMg|Ilf(cc_dD>Dd*yDK@qUPv<1S#nTCJlzX2HYQX)SOirTG{ER zOv|5m!oRE@Pdxapy!#!#MXHEowRY+wFO8R=oMcmCDiO%UZFAn6cv!l&{PR9;e8!15 zJos`owEj2SO-ryak)~3SI?1J}DFyX?Pfxfg{rdTU#9)z~%LQH6E~1Y{v2(F~TVh~G z+NZoT)zyg_X>_V9fhBu(JMBfMeY|xDstU#a1OT_Pjn{DhrKMVz%w?j^43$;W%3*~m zI&Ts-Z1T6yMuqicRzK2wadDMQGU1SZZ$NlI4!Js0J*0U2y%~4(=ftH=rs`vUyk_0` zkC1CkZ>SRqCU;sg4Q=Xh7k5g<ua;Hu_6cX&bAQA`r*0{K{dSQKh*e5i*>)RQF|^<I zF=}1;ybkXDR|I<=6Mr&mTV28lSq2nxwHJ|w?MyWi*2AsME+Uxh(#bxeIEQ5-!Qdt< z_m4P{id8QEQER@L*Gy(u>nO-%%$W3*y4yTWyFNh;Dc}5fyrrh-1uQLp64uZ(#JNKA zsg0*fzoyXJhn$sN!z_mxmv&lczwLU2^lQSjO@6mY7UOcuR}-Vds&0nLJFZ-oe1eH+ zPcNTMXZ75#_{>liInjs}Yi%&Q<TQ39@KDtTnvW$#!Pqf}15yry6wOdCd6}U4WM?jY zdazfa@4<dq`sQ@%c}#wGKf~v~j?W!IiqR}mcFxquK-C8}`@3MhqB3EF=IQs)tyPkG z5b89xM+*qGoeFI2_kkH|v~KU(Jj7B3cP319;FH+tr1r$0Qd6k}YOs|Pm6Sr7g)z6! zo3&HDKRx*41G8DePxaWjF24lx_Aa?-M9y4RtE0(k9j`a-ew0M8uGh(*Ztgw2#J9Vo z`J>(=b}<gH9Qio(Y_qOw$^MEa{nssgwJ`3hIlknNCP$YXTYp*W)!SF}<dy)H%n+x( zw=X7EMPUsI@2iUf>f-%6bSp*AU-?v{=4QpHF)|tl$=rlltiql?&w+$mKH8?{49{eC z%o-}rB!xivs8coBM~{Rjd5%v8wiV_2Wi@Q_<c&Tdwk0L_(dycq*KPH(tCMpNNQ0eH zW2ZS1wQm}~`>cvU^5R}4X=e8K`ITPx9#!d|77%o&YCWe2LqF=C%XLCdhIAisam>3T zc+>9che^8i4*1>@f7UJK5#pP|>?Fgm$Ai_hkZI8z;<dgF?i{nazRgmVh01`An(8I! zEedzAtz39Rqy7&`$SDx(6Sa(<yx7M$W8M>oh3qR`0IE*}T3t@shEiY<Pn2s(_@yMA z%q1T4*E1g9+IZ^mvK!@>t3b(D-kx84Q8^%+rc8mtBp6aoNM^Nb<Y0}w1Y?Rjr}#0< z%{YlhrT%<1_pBokB1*41HKCIz6CASfOgq^yh}}ifaX52jYLadi0c9Q(mzm3)4fk`t z!8;ncMGIoJ6p|83I;c<T+}+Q?)WY;nb-}K0K!fQex!X|a+4w;+xSK*WS$G5IE_}WE z;f3u53U5QqutbV2%!lky8~dnqu&)$nyS+IRNQUB<g?^snWfG`QC;6_GH~^+<B{6XS z@z`cS!mFOy7<VT1$Vi$4y<-4=KDj=?v`M@_UbT}wCufO}Lt1wY`w3rfP?i3|V`;@v zg8y7(G+8jz36I1b$>0#S<&+JX;|?K|<U96+h9nBqTmf(iX9F38MutyALQfz473kx~ zf=5SN1cn`yzA(q;h}PpCQZ{erQL$<GwFHGsd$p&A*&svoLEBs1<#_K7P2Ya*FbPJ| zX3CtppvmS+J1I_Z?{n;*{1ot)u^r85)4H}aqonM`t;m<j@Y4{)%tUrkWCx~w`~GR2 z*x5QSmUdQ3L59F*#)aMZxQ<z!*Eh6z2Xl6P<@&o?%F7INj^$5-)%q?v_lezqH%w_& z-xGaMy;KzYF!8PFmwaol+I-(toWLhM_Bpdw^fqkM7jKx{NFn8TVC^QVv#Gla6~O4A z1iZ!=b%VKF?bmFVfD~~^n7Epx^m6X;9BfnxX>SS**d8sM{+bsmn?bdoXfjW#$P$hK zX_G!tHXyoh0+Xf#&sMo-(G>|pa6bt;(UY!+m-Rc?q8f}H7IsV~YdaJ7z1{13;ReJ^ z5@yea`BvXB{{^?uqvMBaZ+Ov2w;4*pjM_ECjp<6!-;%_2h<(u=hpao<oa;{kvPyNV zSugm&r!PkPj>$FpIZyg&)3`XVAiZlpb)nxcZNtwF!4Y@2T>$cRVY<5={lfb9)ZLiT zAgaF5UEg51yb02D@oDYcU1yW6|B~a~O{sn2qm9C&GV8FgYjnktV8xkVVNk$*8rIAC z$z_qgS`(`>O?QAnu98CJukXf1g~Sa7he83eN8I10B~K_|%wjMWRRG{?9DYgWO>o*` zaKyo`>ZMrfMsOVcSEgOz)6VCKlJv9#&pm2!EM*vyeLGk_CZs4h#PDiJB|z@`!_|8z z{mI^?U!xb@4$HDrD0vVXd2%nN$yr^%APHYgt=g-}3PU9C`sDA$pg<FLH1Cd|Bod5k zZ9i>2td?)jgNytO4(ZAY&RahZutAo)R|Q;QSy`o((EZFebiKov5Fyy|L9We<);}G$ zaa#d5Ld_+r;<Y40Smr4`&MM<giPN7mBrW_r8PMRRYb<@ZNa(jldU9koZOl4hMCyJ; z(};VI`e545U_gX>ghjRWH_g*LJ=qEi!QWH97QxNjUnTi}GxbACB*k3161M@(p=<fx zWUcQOM{V%v5&y9WiMTh@PY$NNo*zr{#|4-igJw!gv#MEtu?H+1^ao4)TH*NiHM&C* zI~@<L6|4W@d60>ZA_G{GvrY)tc!^lGpVR=AS5iMV+i$reZdKa#R>+P^ce04i)4ZXb z>w^KSqet^i1LQ2|>o4t9XfMlHAw1p-kKbTQ&xD?i;zTM1c^MQLrbwT!4N`nvX<4NI z#8k7kzmT)R`bBMq+*F-z(y38Jl8SYU<5=nWy1R$W8{fr#_kG)i?$9gm-y!4gY|S^H z;#g_(Ja%lkpUNj=Ss$|F5cN;sl!r>F^GaOCk$=Ax@ZUUM+}DfYRSnbHd{uctQchX; z_{XWnYXixu;Xh4U+it%<c-ats^2-9j=Qpofg!az6r*JO4#t5BnYcGqG&+*<n_2a|T zgQ%-X_fG%XTKMnS3&nrOcE7HTl?_>**k1a+wK$M67XDZF^Vcu$#~xhM@C0&xe-SDs zb7878gTT_+#nFgU-xs6)e&@o*@LSuJM1DW&RYDaD*gYD4G+MZnKKu4$DMO*OTI`-; z%XDeN1NYt1M9o*(mlKb_%Pvc{n(rt}(c|pAA4|m8m#3nBgp{XQjA&m?JEt#F!MI>< zUy;Gz7*dhxc!@3*>J%+fNw$nvsLb(PSeMJa*|I4SZu3y2Du1L;r>Y>B`?5k|_}9(c z8=rrOR2R4XIJr_xlOD+}VW2f;s>@RJxvyoWT03|<>3~6i)E)@z1^~ce^#H(2&KwQ^ zb^vg|#7&!u50e|1NT9@}L_ZG7L1tESfD95uWif8m>ZL;|Sc7<RvzGE__i-0%ou0K+ zJkP>kAIUdst$dNE9r$5_)w)b8B!q_j!836{sWDhyAX|!SI1yALQIM;3!>ZPx*<+5I zp!BN78Xnnj!*5`^{@S?1k&PqDj<LRPIPqd{mfk)JX-+#LcCwz(<;}P7`9^SUUsKHA z4^E>U&F_bpG8XcTl9tuynR%`cM{T**8XeVduFV~ffgm!#0n<$`TM$Ik^~)YFa<LFV z5aPgY%KiEAg>cwyyPn@)7b(3IF1v>PADh!1_xMM33m$!W(;PT9Wp;FbCFZS5>%r*1 zp6<PG8?WoG=^X_;$5`rarn)3A!)l@A*S~NDJqHH>1h+&633?S%#OJ2?Z=Ol=AVS3F zPrT8uu<GEjQLBGSj3&K+k}q1K?=I10Grit1aFx}i*8>L0vk4fMU>QjLDpta`(;hG5 ztIl0sMu_=N&rJcQO_`vdtGn;w&z;y@xlb}yTs?n(g``guoMy%#1EvY@Ga%k@aso!& zzLF4ttC%H9ak7nsPFgCi=Lb!BuNQDS_{#&{+(Dz*03KHZ6RxB04}X!ID9+LdQLSM@ z$|-YMruIAU&5CS~+RaMr9es#z0_S1Y0u2BO1hWnpOA4^jAc5*J2NTb*WxTQ``K@;` z@r0`08Suq?i1MeVK|u>wp_u4rYlTei@_OPWp6@20qbnvPUakxl(O2DpXq<3gRC%jo zCG%#Zg`g92QPx6GwvYOWH}<nhk%RLSNfx&(k@wLWn*kmxRNiKRgwFUG994k=id?#Q zR4XJSj4c^vj^Y$45Rd)bvpgl**oUR5d>vM{G?cYbA4J_qC4D|g>Q`2-y`9sEoY^9X zlbb#hq^8fc#vZPKerFp#FgcoRfGPLQ6Z}+x2i$#UMJG6O5{20N`yoN&PQjmlywUKn z6S*}dA?xxwv<D{z5xljO4uR8-=SP4;A39!eUT^rd5b@|BmY9RO4+>d~74qF(rYkh= z9_|ru?Y?K4sO_z!U-sQw&Gu~ETgwmL+FLKCsqJr+XZh}LR$u635#i-q`yZQzKpX%s zOe@@wch2&+32MUk^j0(USi~}~*mo8eIz24Ha0HPau``MYI`jQumeS7lwC97rKj&mD z`@WS+ABzON&${q$Z>=ij-~NY3WB-0{4e=fPVHYjp|L#725cTg*-QwSaq`IR&fDK77 zYMY$1fAvkKi5B;0EC(zR8!nD#1tQrl>9AZ5Pzy1dOpM0zEE7E5Fkl;7wnWV(0*E95 zi{FmZl#=XoV5&!xzT7=>=JH2zj{9e)rR2qIsE1P`Fd!|63<ZV_a-G!m0r8PYVqm|p zoi**ep<x_uPYSqnGVP4;PJ&>N@KI1SbdjSN)c#mv80XBOoU@X<V+t2kJoMiHM6~m$ zjM;=29y_{4LW<=ejt(bivCCs1=va<RZ#XGh7$79k^yo)ZCbA2~5jHB@EDnh!lJsr4 z_F}&oPMu0|Lje`_a6Tl%%*ak31rP{I&{DebDM}2)JLU+I0|aumy3guPN0JGB{Aq~^ zVE<wQnca15#4w$UxJJl_lLgx>bHJ${D(WKVKB*UTMhHxE;e>~aU!-B-b_IZ4^^0K@ zOa_QZM(CyiH|~Bbyl5^_$$9sHDNdEm_?B2nn0b~qsZK7IX|5t%&a#Ys_pKzzp-}I# zmKELMd+EwMdE=A&*<1uaj!hm#)8)5afu;A$w-ZgxE{>c^&ke#V->V_GnqSD83aU_Q z_qOz(vCiE}uYi<nTEv~Yn0_iqmcCMLEmQ`8{rvBcjt>*dL?>e;wDKJ1-q}JmChI-! za9G}vvVG*m2HQ>6Bj_J4^XX5v6y7PmYO72vG`|FN9|4raZxXv|-*jHhsC7I7ySB`I zsTK3H&Uf|Ql`GLxZE8Q7lZa$D1+mm;)(=}UC%uRo%J!okQ>~fc&+f>6`)Be?ZPls` z9`E<;#~U--OLR@Wul%0LIT#6Q%{OZBb<CP7)BpKMwS@3F76H5y4el6L^$kd=n_JWP z)%iTBF|YzLzv=L(Yr3NG?t{nkp8|e8UTA0}&>cA_>2G9s{hY(Rs}_E8E&-fYIKOo< z{?)f9!%Pj|5x43V=^WVqmc`v8b^EVz9y|(F=GcysDRquIk=+O0@{CP-b7sZt6ZLW4 zm96+gkZ@{zFP7K;eBx$mdHn96?A}%K&K@VgcE+l%0cNO8JAql@9)!HT(eWo^xeL2P zlKxBas<0L5FE0{hl#fUZ%DqpW`>6*x{`DjEoZ5Mm+cPOmm+MV?7@t$NBhHt`lE1WF zS8A0_OI{AhepAoSNFpBa5}KmxsFQA~+XC|bPK+ZK`erG^Sue<E&1$-*8O{RFNAXCu zimFtS;BYI}(isB$RACZeTI_5O#^70;u1iv9b(FE$QBI{v(&bFrU0piIxq{70d4@@{ zQxjE`Q_QGp5R5bAtLcohY0P$MbtCW3^QCf)_9yw}SKWV@_~xxsP|Y!!mF-PcM^hIj zA2`u7?^=}p!MO9sPE7Cy>p-)8&L~1;dykm8RMcW1<h=Q4TY#%ub<25d#`-9o2n}=k z61nbwm-q3b|DbAew`w1C2spF+_<Q~0WagFyoOcJrEO!`=XWpT*w4W;X?j+od2<~?$ zYaGP}#EsowIZTOn4!~c2#T{K*{h~|ebU18uUeB!o)qA6X$$<rn5$k8yb=cvS-%G^) zuA2&ly;@Ena|vTPjxAy*0xg-9?~W7%`*uz}dikR<{O?C+zQ@x;mOoqa{(kaW7w>uf z^6qmE4&iTjliBqJ9p~Na5<z3XS8)x$dN015;!LG2LNDz0i~ZZCU+6wu8r^+*`ri&S zrF%u;!rqAEzpvS2-D@Yu_Fjhn`&P`?vte>!|5e_<@6{K2K3pE#pL+c7M^j4AC(jGN zXJ-HX>=^6W3Lg8t@cZ8{7GLi+?ZTgTVh6j!7ka;Djs00WeXz$qIjp;d4(a1s5(jX! z9~^!uA-DAQ`-aXQ>?RcvgAx~aS%;cqaKH!!|LM>4Z<-!{Xp?TJEb@%}-!@4V^{;La z1+b8YGRRkcsQ)0qV?3fn3zdLJrBy~58zKx}b8|@<a+bjQoV@@)3&=Q95Jsu^M$t-* z3~S})M8g3TytSCj*$nOVLpBqx?J!R@+F;6A!B@B}a`=5xWx1_S#F*Ri_PZJ(z3_{k z{5)kbw*}BIiYdmRSY;00pKMGu2}A0@tYL!zET74S@HcWWE|vK27aDBGzo&pYwJZB= z9bN4K{c+Mzh60t%#w-JXKsJoaDh?nRauN}hY>fV}L=oA;vjY>4rC|G_Ps$_Qg%PX+ zHut3yRIoo1EQL(h#&~aF4zRInWZtzQ;Z+i^LpA2^b|h4tC)AmHd=2C7bqFEF{P&Z5 zVuwL7MP2qn^|6hWcc^G0yt_C7=g&Ceg=%0&>N|t<31GQqD)0)D-sCym4}wrYaxU;Z z0)oDQ0G497`jT>2VnGy-QS#vfFBl*rxyF%PR#bNw&npt$4+Okn$AdVMCDdU^uar|# zyj;Y4UqkpWK`?1J4A(Qv;moO>&9hJE--cnlj4?iVFo=i{fB}1NxZ4QHvdugo7dTr0 zQH`ZU;7}vgT#`Gmcy=Tw(J%yuLhc<c!qWgU=o|}ViUorX`as&=7<CxW*=jm=oSTZh zKmVF6{wxxT<}uOnmTBgm+)h*5MBl?E$XLa4j>q3&8;>%1>NX_Jos(~a&a;>>2M~Wd z8!E8_2P>lNm(cVO)TJB@tC~NZ%+mpw<uyfu$C<YkQAg~PF`KubJMfU*EZhz*)h(M7 z9mBaplPUq7Q)K37i=@CXhS;Q69oYiHh@18)^V%rfA;!Fz_c};_l*#xWl3}6<JJOlX z<&Svahmhdl@iNPJ5aNLz&jOf{s+;Ju&Zsxe@hOzdWEg+q9_BP0Xe!TE_a_6zX{Y)S zqM;}mMbt~htYc`{y&PDWDJpprt&ass9H0>x?VPl6sFx0kLlHIMg*uUwldPD|)t3+9 zNas{Xl;RO;)n+fv7?a+pG!*(3iihGy<MPi_O(hDzfz2Asg(a@b0D$fiHYTCWi$V8{ zG40NnH+z_JR9fI$8lxE6ABw5mrrmy<gCFPgc8&&FWr8X0A4~GkJ1_~CG_(u!&2B!> z6mJ;He+tHvHVuFGwoohQ{zP`p-3>Ga#gkl|H9s8vm>j*Eqb*=sw&ntFV;2C$Mp8N` zd>HD%5}L;Vk*|~boq>sahC!d=0;`w!vkY}OawJkKIa4ExixB_{87_)0AeE~1rSe?o z#tb85ysKo;xd6FB^8j58@z27R6g!2XdZtpp?^UQtQ9MP_Z$t`5HqeKPG$^|C<g!sJ z97t~B(ggrREXsVOu<=8dqdBHpo_oQ|93mb4!9O3o!#vo@x>Q~P;A^CptD#n@qz}T~ zO46Vm5M;TM(}mK^&Ql{+$<|;fo9N=E>_Y`R*dB~-hUI>!O9;d4iJ;?|^=J;BY8LdV z5~jrrmAI6}$#EXpg{hn7ZeW)u6A^20K>HNRoSb;%&`!@v058KdxJCXCb!HbzQK0$G zh$yp0X*B%tHd=sQ{DERJvXm>EnycXg&uyysr<Ad}kBP=ZKAH2s@otvd;Z9aEY#>x~ z9!Qa?P4(a%_&YWvWhXDistMZ14O(s;;s%~HHDLX@pRyaOMKP~BYGu?Rct;H4cm7>A zBpREa$<9!cYULWwqcp+(n}U=E<yqh`&qFC%I}fl@ZFni3h!J5IZonF7MyuCcy-DtE zf);f~&)QW0OWX&c64D_B{~3d)lrVY4b!t{TSvU%2n!DNWfeZ#g7j5NAg-`pD1?ZH; zl05b)6u|;j;mB`}1=T2{I8I~a>S%$pRp62~&64sfosX3L>zIb9A~u;yj<LOo$yoyB z8^cR&I=G0nvK$4f%UoyKy!W3~S9&!RDK*Kw;>uFQ?3<&MM9Ed<bd>{K2T+V0cEl#s zb)ft3D<t00JWOaUGOV+((>|_9A9ML}IoB&=_kG$QZcLjq>_Zo(y{QFZUN1L(OHHZ} zOX0pletb{3`{*9eNBdrx7I@~Rg4bpk4aCF0(DTvT1`VVdkUE%v?N{T-km=+3YKE}` z9&wehRF>hXJGBshxjKAjSQ8UumAb#3!&O4wt9hIlFOe>fthE5+&!B9a)6$IL<=7Ur zW+Z1xvb2<WX5M{GGYsSpCg&!mh0W6~mIXnZ>Fr~xnGa?CyE5eY)y|>hO&bPHG2?7* zvG_{2U9=fDaE%OSEwMC8s!vM6#Z*v<&PE)!Q1Z7VDi4$}ulM^wJ2gkTI#kh*)hUlc z!Vf+0H3BNAgeLfBJm#?<vW^W^y_q_?)R9<H$_WEaDx>h?F|V4QXi7cBT0NDpiW9&+ z*C=UKwxZvA##6oYP@CAGb_!GV8-Dh&r${%3c>}Wu0R33hEa5S@gl81s(V6AW^D{R% zlhho~|ETscX9+yv6Gpt7lEXGmZ7cQ~ey%`7wB3?O<H<2QgGv8{9vA1gw!mDuh3a;w z5V?5>|IE0|7)dO7KFQ`;!=bL>QD9{x2+6a8LgVuL!KtlS3sk>2I=C}(o(IcVdfDLj z<U~oH!1UM&7tkqSfO|Bmq3Ib~>Io>7uke5X+eF2X_WuJdw>#fL`RJe;auJH-WA6|c zMg-=I11d5x^*|jqL|{XuYKvyN08&XU0x-d%LRs8je;?I~K%K_J!nO<MyWj~V@|}oA z8LLj<YnIy;R2G(;;BER(xIxou6mVvbZr}W@j0xFzslGEV=R$cQpU6Zb;)`jp2uuPn zE!+IcoZJg?d9I?Kl?LI7UYZ7)GW1n3p0FWhbp-hj+QF^unldVl1?A$f2%qAH@XRQ< zu+>WV-gi`QcfVF~X^34iO2EPniS`l2P%j?-d%7sCxmwieV_Z^{(lFGS^xRT%v*b?Z zsyH^_Jc>z1&<<7e#m}V<nz^6*F>L;%@G=+!4g5P1m|(?OU^{-arhC(c>&iz=gLuZm z6%>yFOyekec4UfczC`3`h8TPjGM*RGl=&_KHNpK_ri7JArZpukV*URsyTNaHk9xWm z^W)PPXX-=rRn+(=_?{Ccu-fQED9Ys2OLkK{G6cDId7j@s?pRGUrz#4YKpRCZZK%g_ zj`IN|J^<jmxbc2d0r_r-8p(rsuA(BTjKStn&o{OlbKz*#;6I`W^UIH<u$mq2aYKkN zILGJgy5OmU3y|@Z(uopuUus?T+VMzKx^ohk2o*QQ#1?ahOc*nY2cUnB)-UnI;R+7@ z$!VVpx|{094z&5TK5%C~yx;Jl5NP6xTH=B1kV&7=9+s%RNAPMv#4F}zF6Rno-}=Bs zq=h-+85>FV#Q3ouN)kUrH^Hc?C>e>zXF!uqXHk0!h9F-Q*^(W71$AQqV{sLg&Mx?a zL-|E4ei(<pai%11FH1^2gIIul=5kV;XSn(dY6*&*91t#VBXzoozZodGFrTZrHlM}Q z;sp=crabza-|CAweihozg!R3&%IcNac1HbJdJk&;a2UGTTH<}|opR-94y(8Ojw7aW z3vJrO)rj@Bsex9BWBR?kKItMv5I`AofpdrNE0iijVaiB-{<xD|EP>8s_tuEL1rfQ! z4{myOi6BPsywZFjvcf!e`!~gB<Ij<MI4N7Hy<C9vht%gwkQ%-{g@ky3r{|v|%85T6 zyR9%Dr?SHUTk&q=_#SQKV0nQ>?CU*~w=yL>+;884Dfe}pxxu@ecp|$@cbuyaSvHL^ zQH&MHj=a&x6!bE3W^Z#5KU~l+v$}?ozV^Jqj%wFbyQBoxQ$<bdlSAjDw9#<fH1Y`2 z^{E&-ugUXT3MTkKb|QElV0n)@p=@!9%6ce^PPlIqmk+#=iwKGL+byf5^_zZuY=-*R z#K+lp*fR2#UEpugO~DdhCH8><Cg}bAVaJW^+lIYUY!iz_-surWs-oHsuAy!t0jwVX zmk`u%HP^AR-!j*^FHzqpx=<)Az6K^&+coe645_641HeZ?_yERjUVxY^4n%{I5{B8N zW&Oh@7jH8~dN&w-`7kDJlzPaj>dwv4FkQFSw1z(y`Ceru2Lu;rp*cuKNdmDW(v9ia zJnNQ)y7&HpL~S-mrQEA~1`alx)<wTQ9TB(lJ3>xZh*FalZg++Of35$eSG}4$6a8yT zy+W9Wti#A8b968SOOk@m>4>)dy6tLL`LjcgbIEwixjzmmX`FAj^KRf^q(If{$Bjo( z>;EP-H$K$3B}IrtUCkdl3K+2(!IO2D#W!NtVUbF3tk9_`@WIK+rv;9`d>4B3KAy+% zb=-azUlePQ*A}b?+)2=*NnF_v`Y_pW%_Q41=W57wPZU)0>YtFWt3wao{ha(0_Ve@n ze>BO(?tr}?pBIOUt{p`F`}_9*iYIVDWt#|Ge1>=;Sjer32$hV*>%$ewoAeRK2Jr^S zlPgUIe0m^tL$rx(vmyTlLv^Dgm))9;gs#P^8;f|BHyexH9#l6u8obhMA{hnJFqNXo zwwTJK7;2cwWx2JODHO$Om@8J5x0owG7}T&(eYDbIaqK^k<~j8t+17KKV}_dNkH2wi zJ%4gBR?|{vy}Z@(^p`=+3%b8nS}*7wfV4<Ns9YP#fX_(lz{*I-z0Jx*GEU3dOrfI9 z+Tz#~t&8VRuC`sgpa(u~V`U=OZgcU1(Q#Yb%kJ&Am#@Vgzhv)O(SFJC_LJk6uLQ5Q zU%nOvK4IrVlY3})J;msRy?d7XLwnDnxT%vbL0ZZ)sMVcM12@F<hmN;Bg`*scr+{L( z>ImS>i-U2OVIu|Srm+4<&4EPo@e);o)=$lzg`sOc8&~3HILP(U)YBV^K&=^UG3480 z+QTj0uXjr{N4$XfnC@-Y3e7*?e&q-Lxo0;OuKoO>LF!)@<&vlgB~x)G52p|lKVxL7 z3zYlw0!pr%H0PL?9Km|S)k@kWs--wDWH>x+85$7fP<C+r-`Z+ce(7p%F}3pcb}lwR z?`+#_6VDn`2YA<K#uJl?J;|*Nz}_Jl!w|qT+LgH5<Bit;U94H@0lOWoRq2K3hX?#V z8$NO3+`M@VT6plT+W7Exn2^%If{w65cX8FPgoct71HOC7Y-9>4q0e}C4m%~}!^!JA z)1GUfG<6&oR5XP>6R+ud%`|cDx8tA9BYprmm_aXE+LZQlrNnXE&c33EDc+5M3ETY1 z(|aTGYnwJ^a(Os$?Dnn;XbJpZxYS1u?X&+$qFf8He3;roY0b*QMME}Ck}t6si`<_1 zWlBPQOe&64hGU75+q!?}$<gDACcSs{#ZsSa9C#aGula<a5z(?-nrCW+Z}QkNe~+j5 z@^2g^eyw6+>)F`RJV2n58Uy28iUx5k6Xo#(KUi2Wpe;>|oE|7(*2Q6@TqFDM5;09n z;rzk?u>Xiv;)gyZ>SnqtoR-$BUMbQ%42HkG{y+|f0*>SK1tK10s|tX4gUBEvzy)uo zmnFjCPOjNrJ*qrSSiFiv=Z$Rx0Msm%=;Q_}vonnOenBe95iW1b83!jb83KDNfp&*O zy?`@S+qs<N#v)|wS{zFOSU2dL;%z@Zd98Y1m-z+(OgCPf{=@|=q|uov_eQDIGcdR> zIh&J{MLl=ZR0W%AVizgTFgUQ|_`{<StE1J2r5l*yX!cB8KQ_AL(+gN89O&24kkX#M zrf;2tGNh*6()-ThSHPT*{R)C|2wy-b;4OhcP23+@`Zrultn`Y%qQm$wYN{PXGY94N z8JZq_Q`~h*LoNuCVfk-P5TvZM0^$4agc8sg>)S@rpBq*qIhLNp3=2qoRN;{shxb2S zO$h-_!g%}un=knBe5ks#m7QoDG`{4%X!C-G3EoWdEC#R_;6red$bC#!#f!(d!%)_7 zd!<$6RdzWs;8E<@3oEIR$9><Ywwse*rQESV8T|B<o~R6^RrKs!<+FkV;vqh@9ENVh zfBTl@mhAkEm7)X9BXwzeQUQgE*%Hd={wH1X-@TdcFmO%0SgqQLC@nct4pIWMDe0lq zo*NM}4{-p7$qx~5zzQA|)5b|C5(vdQuoO)ItZ%`v4NSY|1WluSvVkDduW;pefg~!3 zQxE2B2aleM=|EQT*jMlrcoT$4exOV_I){+9dGtAQo$Zr8S&KT%{LfgrY}3qTv_@== ztq@?;G~>#D<MlQO53Vr8!50t$kqc8;SK+?fV(*szkg}y=s;0<}w-2LlCE<Q4$1EHB zK`{3(-U6okZK}k&(1;dn&T;j-*+av9mjY5@ohm_f4k$jSN4;Q076H*R6T5M@Yx&j} zfcHSfIUcx=9T;>}Dw~-VdrFcr;pOASSfCIGgFXhk>IOGZPaaqT#h6%>?VB2F#>Nw* zBTS7%7t$9ybsO|&a0Ns(Imw+yejK29j9M2HgU0(j1#f!m>0OM)zI;Hl(1P6%O62Ek zBD217eI?aj);kuRQ_*Sj?w2^jT_oOtJ^1Xi;n!aaYB6h!=t*f_2tcxscYB4j#u=QM zV{UF9m+HM#MRXOqGFoXtEk8RPNc(z4Qe%uumgSpR_Kl0A=?3e~r0-!nUKFC7DTbF| z9lu1qOG8|86nC#C2w{ALl)@;kO9h+{=9x0d&M*nWU4LKIt8>nev7?#83N9V12b{LQ zp<B01&)ikL^x=rxOQ6FGfiAoqj~9_@x~?j)-C(G0V)7V9X(8SqaSguU<NkMb<j>1< z)6pmZ&@UYB<tUyhG7TN#_qeUURb{${<hZ|M<W`z8-2wCqONkbhM}6Tk_{!}leVov# z&uQ8LdnLM}SAPiB5%rxD&RF%b`uSo#45IX3`#k+np$*xH8&`jjboXQV6Yu!Z>Mu?V z6+#GcH=G&sEf4(1@NQjH+CbB<WN(wtW_3M+AYsn-UI80bUI$!YG&%1p#{YJN|J;2J zTo3j{{lgPtX~EI>q!&<~J6>_pzA+u$Js>-sEF{K5(a~wzfJq@QRvE=iA6P)%I~kxW zYttmZ{-}LOB~474A73z9UOsya_8w9Cr~l-!>?q3(OX+8J-p|*|Kc%~5hiZ&&y3b>U z29<n%z1U|=JE^%2Ys$baUpiDBlX}~|NA&PA+7YYlK5fa-Cj(m@=#4XdB=o*x&=JNQ zLE5zRRCFAk8fDrRu=h0$FCFNR4c(I6j$J9(11YtZXOe#V$x>LgB39m^H940PP_k%C zvxbpJn%|$M3v_fdOiQ``!0W7<85`X(IIf5??6K-z>Tav#D;5-#bjRhPXtw4oqWGZm zaVeHqh*A<>D&_Fgoht4q%@#$ZohtGw^S~jB>^h={<sK7ZkBM9d@%S!_+J+ON;!{#t zN&0jeLjKGd*-cV!%m!;!SwAUTs=JQ^L+<6{!SaB}Vyqs8>o8>gaWXf+Ij#SezZKD? z`RcxSJR$#QDn1U?Ht~(2>P#p&{oeq+7??PuxShItvE3NMrMY47SB#*qLRYHqD0Qs7 zAWF8bPdR4O&%laCYeNHeY5wGD#u6=bJ2Q#^ZNVdEu(Zq^S`<6y9y?*gjD8Y`4I^dC zlN429RDpiR2}43Y5F6_k7sJZ8faxw`^Xwy<TJm5yqWRI}XdKIEdlnvKh0}s@W^hLz zv7^|3YuJ?H$i+ON3Uh?T8r%vj*DGT&{PL1r6%VA-IJg{$Q%w^3AB1&ft6+0*j3(D3 z5e54;{g~nU4||1Tc3FF;6aUG?>yIAi$m2?%fCYS~xqfFH2A$m!q3WgdNYkW7fE?jZ zb5lW75$F_rwlM+jPadh)hE;!;iEX0Mbr4Y;K%@>lc$*fr3tiil*<i6kR4S8FO=9Q@ z103!1v%>iyv~mzRDw{UWMnp)#N^BTU_p&u$05Wix-x1E0CS!1D@=?YKh76dzDzTT% zdwPz(v&U$kgL4k#iDoMUI2Hq&H~ozvB3j2)GIY*Oq3T&(p9<{ux!f+BkqmZD3(kUp zgNFMd8|M&IKV&#Ax0?Ahid=mVjDwa0A@SC9M^5sVFs%yzvSeGXf^HHG<9ygM`r_P) zmbWG`+w#=mOqYCEvs-dVHgp9<mSNMShbxZ{D_7W2q_#Pq7}B3g<ulH}t_k$O*@VZZ zPR9|T;biDTcz#3k^FlK^cDSmT9=&Kl*T7?+IaT&;jw1h@Np2o}M}#fzkY8U+gk9vZ z5|38J=1nS^6{0Mf=aMi5=PT?w-pIlPY+?Mm*#b$tflfT3)6h6<!i_<=@Mm~APC2Q` zvI4Mb;}>sf7X48UL$;k$4Ke8~9xq^Cs2i6GuQ82Y%HFRZrNWLW8}v=ruuHs3U`M%; zbx)#B4?f{2Aw=*W6sf>`u<TOpfjDQYCrcL5A=aC2-10}CF|xTv^66)y#oGWGy2b@i zlF`$?yafl2{aYH+abr)d&NH^<$pgsa$oRg#a_4Y-d&0!2apQgh^eayag?_OZh?RVT zDDjGp@}h30(*sF)Jg!K$!#xA~sT2IK<8Tv}a^v%CcJ#FMORW<dgE&UD%<{7B&6?!Q zw`1e%(}lv4G4|2dbcL;Kd3p%O9zXPBS^0tj@hCB#G4>@kE_!{%+QJsT<#540iEo$# z)U0J3%e0Df&Wj9*_t*gYXw%aDQ^eSusyLdp4^@7iVO?-m**(Qy82Y$A>GQcFH}^N2 ze!LQ@u!9in$jJhF7=aeWgua124|f*(vkOi9+_d(c@#YWI)2P|ycuHvY#ew2WF&l9~ z0#kIKlu)mna@a)1_OsBXtTYCn@D<}Y;md_=YP%WC7s%qDsgNp;F5;2>gh$M|(Vd<! zR7v)+Ou6H2_CEoK5<G&ujB4Gri5@m@+o44QLK=oN=JC|(&ojsOX6zd#cbDFDJelpD zob6ei?fo(PA9#*+WUfzcuK)PlfYIEb?c5Xhxu<vLhT`UiGv=OE%#F0qJ%2JcIyv`Z zb?)VlxiRoO`^X`KasJiu`PWAC6Snh{?(<W3=HJB4PiM@(t(c!VthOifbCdJ)tMdy# z<_{LZ3rj~9mgN@S9bb5Fw6J2ku<E|Bc4uKdZeb&1VY6c4L;J$VCkvk@7e22pZ2egH z0$$ucvbZC+`1SbWH>1Vxwu?X97k}Pa{1vyjo3Xf8vAEy9`1{G?pUK6)tBe1BEFOTD z0Kp{=`6bR1&g%tlxGpV$J&=@+!)!k+uo_zFzGT@+3lpYI*E^qgd5!$J#0ObM2`;1M zmoX=n`HhzaE-fGNSQfmyEJR%v&RiC$To!$}d<exBpK@txzx1TxVm`aLU@}$mQd+0& zoc{)mpgI%BwusIaX|Zz^8()%BcYWF;=jZQOLY@`tJ8w7Qpio1TP@8j<riJ2W3kk*t z0i^6`)H`9cW121o*$-{o0}Wq!-_`9%-4^1LN#HF+dwk{%Fold#uFFtxZT_*tpOY=L zk)^_501LhCbzO)98ViTS*kZ;ykVEI;dTMsj!|%lQCZb3(O3$u8`3#BCaX9BoZ|{N9 zzd`~~*N<$1Vua})eis#MXgJ?Fe(8jZh4iZ-P!Cm_X=Q2|g~oph>AbL9K&Bnzjn9fh z$K*h{8!_Qbk3m)F8a@t`NjLomb=*LE_+l=}J0V4(!`qpvm*BSx(E-{tC1cDmV|^;l zF(`Y*qmuu^)cP5JTEyMd(_8DkO&*2Vu@GQGScEr_7qgFtIS;S(|Ft@}ZwuS^bG+J^ z8cY&iq6^2L#oXG6w<`vFoO23=0QWD!n|0?N5U3dad3gw?!FgS2$BVTp6yxU^OZJZL z0C_HXit11sLFAh3w5lfRFwT30CvKbQ9ph(zbpss^(7IMC!eFcN>K}?g<onq5-h!-R z`JsYKjMAJ<Q3gV>##=F!ntwJmY?o$+r^i;p?6L2J_BIv9xi#FbtYM*^Fie3k?eSGi z1ORcE{viK0GtZK)=z)F;0Wz-AeK>^9vuH6JHw5j6a2&$E+QN!fpQ6cY3L;Q@Q-~{S zL#W1e_%4Q7`2n{{Yb8@h)nK){X<mlVTRYS$7Pw4>eo(2F8iq~K!^hpMrgg=owO++! zBy-<@O)HFBv?m>YPh*J0+Ta~k;I>LTkZM0nwmjl}W9rrhBpSD|wSZ};zA0t(Il6jX zWbf_dnNPS*XoR+p;#*&U8FO#?87}pyxS~ksRZNTXN12-2^6KxtR;F@BrL|nTvO@nr z>E-RCq5;}A_oHpZ&^C|Bf=aS4ZqrM-kH;&~DUq6HBMdU_#Xy6Tp7YKTu_VZaw0X4w zr4rEA)V6jiwS?m21puHTSowzFqe)PChSR{qcaF86N)_FbcH_fX;+UvZ3onr+(~mMD zU(qM&bdsOK_{Tdo!orJK$R78Q#}yyDxC5ozF#or?)f;|CHo<lyJN8rb0thcRAM*j> z+o4-4X4|Lt-Zwpm+f*Q#<3j3#CT@S`b`e%ee~eFqFMdQGCiuk>Nu{Z-GYDC!?0<0j zjc>o1*Cm7J^;)227w9*ezO7`^Zs;WZJ`1BhP08H))bGrzb1<uC9wY~+R%wI!v3LHU zL|HE1sUh6Anu7X1|F{fJyXtosJ&Gg2?lRaxAd2%0D=6Ms%wZ`mNsfMTeYScd&hs+; zJ2lnyGULW3R8SRa@+PJ1;SOaZkfAN=_ed~f3POs)gcEElIx3W@0jP2KorBp>b!d+l zHL3&Jk@*X2Zzm=hPk0fCfxj(^9hxO7#GClt>F=qiD*n-*v3t}%$wHXs(}?jmbt}o7 z^E!ZErh}InQv+dCH(^+uNRAlPwX)|2gOu&x@j+O`B!o<hSf*`lgxrG!CgDW0OVI1& z(D14>%SFd>+UscHA7cKHxaGUKLO-vsPdPnItyuM`Uq|}0_t8?pO<AxtCM2LEwAC|w b!<~1<H{4){T9ER)t7?H#{2Ky?0jK{5b9y(5 literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_cov_interp02.gif b/images/demo_Riemannian_cov_interp02.gif new file mode 100644 index 0000000000000000000000000000000000000000..bfe4e64e944b9160010965f5afb1117792357d03 GIT binary patch literal 670017 zcmWh!c{mha7iLyt-?JOLvNXw-eczKUBs3&DzfqLEF)OmBWeAO35hK|mjTvQ0HI+RI ziLs=SB?<HO-RIorKKGxyoaesh-22{h>>ce4&jg_X8i3y%2o5#}5CG)j;(<YVxVgBw zVcdK?eA1HAs`fY3WZ{}8G!60Jjn5bxW4{>VzM5dB%{Vx$t~T4**qsf!>H1%(E8*R_ zz=U&`(e8oq?um~*f|5Kgr+S3k^z;t!3`zedK4CX6fFXW_o=X9N!6;$~GU!THTbQ|J z7z!O0hY8PajmUl)8yFZH9ub?65r-*>=iy7>;7EwOnvjCKaY7@>!Yb|hjkJ{X^qbg> zn;F;)EDn>6!{G@y0s;R|GKopaL<}|?0L)fY&NemACKB_qZWY`n-M(<~c38yS8;N(x z6w<%`JyLOIR&nciiG^jUxJ22b7v&`n9-=Xo4=XAwYioi-YOW{NkV@(>#Ja3ob+?Ne zNhMFp%9|cHHdj<N*Va>V@+g#NEk$>pT3Wa93$>#$?ZqYS6_xF^_3h8vI|^@il$Cch zHg+^oI)g(xpEPydNbD*r@2aiqdi=Pn;mPwykDfnidQN%T{pfM`lct{1@}8>do+r&c zt*tLwp1ye2_M)Tf<)em|Pnuq~KBIQOpix?A)ING!M}O9>{=%aE)@S`)U9U>YURPBQ zJZT;r7#XU6JVftjJZkt*boT?f@<Yqh(e}>K?w&Df-}s}(@qxjKme#3v@2AEmXS%v) zGqAHQt+Uj=F9U;L$(8e6-Sh7l^J5bWA)(()&A&Zr_|`{XynT0ZaCmY4+wwcc^7sUk zi+iQz=_;*%b?D7nSI_#|kDu=tKj#-%pGH~ZldS2_zlPuZ`uS^%{(5V3cYA}i^L1`# z@%zq?jop9c_wU~yKK&k>_&qiK`|JGgrKP=zslB=Ry>Cl<-<S5**7i1j?*01pXL{z( z;`cu*tABp{__M+Kv-^Ah>-_%Q!v43#eI|2%b!~s+=l|s=>+kN~!Rp$<#?OPTt%IH2 zgZ-n!Ut5P;+lRaRhrj<E?jIZ;9v%q@9sPIpC@1fzr}yanhogz9Bj(D{+WOH?*3rSy z(cvN6^E`X@EBo7b_OC7W?k@Y!KKqc(J~~oh^SIi2d0Jb#+3IK`fSep0914Fx;E;c< z=D*7Ef0%G^u{l)KB@ko_P5_t43I9P#1)V6U<W%a=Qu*qZ#OcTx5(5o@6&^j=vVU4V zRHW|t*njA0&71p(%fqFPt+j6-7+zbQ8ERE?PFXUurR|=~;N%4Hss}vYhFfD@&p4Gi zwLKnd@KxeR6j;zSt}mr#%R09=PPK-AdK}R3sr=%(LYl0p1i2}oo9~DC$TW)M>q|6{ zr(B)-O`<SXL?dvdv*p`Bfs%8%OV`uyZ%C)3zKnFWF25&RJMV^Rf7Aeg0m=n^&-K>C zp#XJF6uCWP%3Wm1PIe4Vo9Q*yACoOL+*rUCX<Q1N3&+T^N3zOYUp(Jgn{18x`c782 z`{qNlL$(}s@$bv6WoJ-lnJyaRfB{K5!pT(h^K>!Dr1RWS`rm{dwFj0*o8o98VNj-E zAlIMs$5KEuZ8JDgK&V@g633Q+@oWNfo(LzXFJvlDZ_R2I9*9#p%PFnzjOGuv@Em{I z2G9!Jjl0$yZ&eB`q8*Q48BGSs%vEu&NgiKx*VuQs9O=DC<^Xo^As0D!^?Z~I4g-=b z@JPZLu?$FJTToVb?W3iV==O**b82;_;BA%6XYb5=5!B1}oCua}fQn1YL(rw1IO}Lx zmk$^PLmAXpuFI(k)*L#iI(9sU5*`2_lboPeT=ih&D>Y0`Av)!3jyoRYc>aTx*d+({ z+<g#5Dj4Juy!3d@CZwb*?*SE}u}<kHaMhL8$6OgSw>j0K_RzqIO6AjEzfa}L`XWf> z>K#O(d1XgyINC2e!0AFzmmoT)Hv&l)6~2SaEa&WeTwQNMigJi9gzMA@Imv#&SX|nO zWcBeBPW5Rl9r&%&1?@FA`*UR*1aAwAetWORJ$OCtVKWzIP@qMUL6f@F^Yk*z8y;a1 z4V`gY)mn<Y_^P^Pfi)}<wRh1+Y+hWHDs@jvhfo!z>|4zVL<rh-%PDClH1)-NziZC# z*|;<Af8)ozDZ9TI#o>AIiI%K49Ud9;+Y$NdzQLZL1?;R~u^$hIG)Fv-Q32aDLV{N` z2+ILQ%+=S=4~tVJWJMioI4?7Y;&E%osWzDIvrm$)p1=Pm+gv7DYoA$tKV5P%_~v@p z5RbwTRmwqpT&;)KH^_#gd1K-W7uT1`3|`yJ$1z<hb5u0QC0@pYU&jH?dE4$8)dFgl z+C?a@uejdRWgfkeM)H1%A+0Rl|L=$yr1XH{y{&hr1Yk6C-Hj9AF!!jIleE^72E2o? zlfaO^aH)%FOCu~e3|OKK>(|gS^(XXU2%1DK{LJx9CL9t@JJySk_fPwY6~8*{EgqW3 zDEo<1cTu3Y)tSwjtQ{9}lK3vCjILK%)J}Zl94TIHc*u+;aPQCavDZB4BN?nrFIb*O zPq3nx(Poz0fgq1;aQ~D^wSmvG;N5oLS4Y(`w;Xttt|1cjMC>+m!d)(h`EuRWf4-TE z%BhlBb{H_4-porJsgnCWIAFHFnddC}P;$&+&`Rp|Db4;0#bZN*c1FJn3v#NJ)f|VM z{C?dgjZ~|e8uVHx|0;@fkq6p24ttdRx>N5`bHZn6*!%gfyOf+7%`nF|e$!9y3Nxu{ z7SQ3qeGj~*CPpY5?h?%3N}?Tb>g1mpk>}kaz0p-YRkbn_u6nI_IHXp$VQM7I=~Ic_ z;F3XimJ7<&^TCWvoniB%x52fi%a%fx4R3M0PxScoU~(kPc&Lkg?(zm1iaDsUfchDU z@6M6A&emHU8)nEIkSqA{^)_lwAF{o-EBId3+Zqgi$W!&I;sHOhw_jz*AHbn@ov(_y zhCkkO9U&{{K63g0wA0(QhGmZgQdvOR>O1$f`5wDrUs)AN?bJJ*ee7|6c(m4N=aF0P zW3M`=vB!Qpk9}iST~qcwS9o_CkXk}6*PO<mmh3c!pKY-1c#M^=*NqCwZSe0n?Tz0M zt-JA~&vmQBr)__y8GU{&FlqJEMPy7<=Go|k?CjA9qurK*+{O?!=c!@8-KV6tjiCn4 zQ;o^Htqxb#&dFZSPf_1}R{z#ze}5P&*}2<B$$b(X=KOh@J-yrB`SwZdjW?ga42wfe zxYjS&M)`Ku?sg91UH18(pO--)fl`@G@paC#tA4+qf0(60R1q0GiNCw&_?i<3oWJ}^ zzX6a&G~ejx{<4vG?8O&+bMmtE*X=-bw+IXE`1geWgQsIp%3PYz(Di%YSMO5fSR7#S zkvWL*UY}qd0(+7J1G>0JlXyoV7>vyGr|i+;{4GR14$R>``DLQYdiWG=LA-nK6(X-C zCv06ne5tMOO8`3W#>h9hzk34~<8fd`G$&so8hC68ef$2*yo&LkAtzVVo&1~-A%j0d z-d_-R>NKwiM00>lu4vm0M1Rb@{%l0V_O#=F{*!d!J@(tdw#~pemkg*0l{4{OYx(by zWwWgd1CnGaD98W1W{U67rCkgBqnz*`Mt<FdFRUsB*%h91e%&fZeSs@UZbiQ=pvvb@ z+t|u_E<BffSMR-kW1-)l7KjF>=e0Fn<_lN+Z*K7JJJy}Mshm8%=<b|Qox4Rj-~B~C z58btkul-qqm0^+V)XS`dOr}4zJ3X6LlwG;`wPZC`>0V38>rHUz*^R3cQos)FXDz2j z{;3@ac24Bv3Vaf)Z7(&v){f}iIh?ujm(1l|PkUC3!W~alEIn7FW|}gLQ<Z3|9!?EE z_ke*5b2eEB@$U5Qiu7$x{`>9H-7W7VREE+0zl-T?vm4L1(xL?&IE4_GXrT4Cze;ZT zPW>ITOp4vaN~bCaLw@%0HO{)p&df1mUi3*R#sS03N14_JD}0JAgj#3^^o-&2SLc$q zWk^#^CpHWR2eiEkyQRkYEV`z*8n60)HtAEo2jJ3VVH~*r{zx>Be|aq(=VP<LW3-nf z5}3hd%~4*#n?EX1g51`_@e1Yq>=S*BfT%8#my7mr3cPV3Sr(bQP>0r<gai*0E4bbV zGTVVJyW{MqO$&kD>#~gN2`>+OweMpf;pM--i2QwHH)bhfR``@^UkOvswoz^r1Qoc- z2o3+niAmkO<!DpMO+NagEZ7H<b2$_n|BuGzqaoAwB>MKgA4_XDo(=u>{OGV8cl_cD z<G*cdz93NwbvWfcr?7+N27M_7u$O`i^`QNRd7`=SS5u+)EeZ>Op9pTIdf*}?*Lgt$ z(+)_{Tr__T(3_If%mTmFhn*h)+M<EwESTvv9?t@xR42p^mBe=?aszr(zut~g2UPjZ z5#e)lshvXz85K*sAw74~0}Z$ongV2|7>1$gP}Dsd`jjC=Kq5n!1Uyep9q|D<9fKKJ zoHIgzhmXNJ1R;h6z#=%8;N-R1iquRbh+l>4uri(37Hg15#6OEHWJI<sW7T|8{`0w_ z-2swjMV)`0;v9bMtYI8<0)%11Md<@TeFUT&1)O>fJj2qqSWd$rU}x3h5n(`2HOv`{ z1bv40nK{^P3{Yk}!g}JgH`jHU8<B~=x7<Rmr!k3(*JH(MajyyC$`*;|C=h4VjjX|& zDRmLF-`uBs!E=2ebwHXTGnHll`+OtKNRV)NHO-&^|M>=wA~T~9nY&Pz_W1^gKO`4n zPkcHVDi?N(MY1|Wy8OKJ7Eb}Eja_)g<bTd^@L?xN9GyAfdu_Pg#{>y#rvqIm5N|h7 z6a_*+f_;9w8>w*#W~Hf$fjp617;56ffx;*h=<NhhUY)CK0LUSFdy30Kd?@b+7gA3m zU+02bgI<^s7l5Bl#qv?HMpGPSe~OGH@0h^u*sK(pIHc@l#`d*eahbZ~Iv&-#6m|MW zrt5{f-br_TFGQd1^eLb4^u7`QFf-9@BL4Ed1b1Qr5*7))axXFq=<wSuHYxtnL|&C% z(e(>vzm_9KEmADU@29U^7K4ZHlWz1Z1@sygBtcV4UVDawdPsGotF)oy#o`3jiti@H z-II(f)yD?eOWpWWTwQeEoC<Ux<kw1a)@7AgX68ShDrx*v(jfUj2p%p&3C~P=0H`Oa z-}7vMmh`UZRj&ApxP{p22lPMU97qZna4a3lD&5;DWk{BNJX1D$p=>;<Y_hm)I*C)7 z%BkA^;7IIxBm4J*#XpGTJ$KVN!0HO%G^Kp~Px;zZ`L93aKO`TnUU;}s{BXbP;lb3y zqdyNhq{sjxG8<Mr*A-eOS@gY&9P8l&1z&jEe?i!&Le#H9Jh>t-fqY#57WXh&u0)l8 z8d&u^+L#JdimX(RtgPy)R4b{}&aSNbQ>kNArR!IvpIl{FQf1^+b;_tv%E_}IEG}<U z&F5DnoLS*eQtkA-TEghQc{bS;Tx4TZ6RB8YQULHRsquSW<3C*!xL<>mstq=(RYuob z@vFUDQXBca);AlV%_=*`U9;g(6Yr$h$@KqRQ<nU^E_J%@GoBNjT{<XP|9h;C@VM?6 zB?To_C&#`*OxUmY2th_)dC-~lK+OB95F(`b`J+9D;JZ@6&xh)D5<CLHk7}o7D<1(L zo<R2y!{ywrTI_NNSp)&P9$!ofR=7gWtZSg(CD-jYOa;|6JkN)X-@<SKGGBA@)P|XL zaquHTHoO}iPUGySBLu!DNZ-w^dfjmPRRwkb$*uE6(dQe9XBy%9SKR(Y!MrnH-m8~F zaHdR!F|r$%9tU-th!0%8>w<uMdfi~UqpMTzHtFr1$K3?^EBVN;S#u)xh{)w(0g!UT zom9Ia)ZKU!@`SUV;&Cs>3{?=}3kuo;V>>F#?zx9&a^1^}<G%~^rluBk71xXx|4gLl zK9Gd58(N0O|6@<&Uxfnr-?V-JH>b68Sl_$!(eDvB0&P#_??B+oS-A4{23g<4d*ShC zI3h_zuKQ|n-p=t?Pt@p1x05n%JuYc6Olfj}0PGPrPO@O)7J!EqoU)8|mRNI&-Luxn zcJA)GM!&fUXf6|YVuzp{Mlcqzmho^7)&b`-oC5}tQ-fG|10+{R0jAI%|6uTmpsoK0 zh4%7`k|8PWudiQ{Dgd10C{PxJot(=rL<fpDgjtDm{?Wrpb>BV106pG=*}@Z>DUi!( zuBf>-jR*L`$|M7Ll0a6j0h+77?zX8LSUf3}_Qt*RbH&4y7rUs|XBy9au185(05aL| zYa#`JLJH{nUl5$tBs$kfxz+K(ujx}sPR=Aq&=F5x1{N{#ozoF#Sm3*zJp@$Gku<Cq z0l8q`<~jk4nuBFu1ap3_@6CQ8oa3;NjZA*?!q5A`G30X&SODrT;3NuENG)rAbA2PF zZ|Qj^lnd`{kZQ-kU)pm&l!loV0P$f!Z$a3rDC(PrHr4MI+=h_mIcmv8;zGm=5t;Ui zTQrHrpi6c+qWb?mdcY~+b|Z_sc|D3|`}s;(15I1gQhkADLWvhtrym)Yh^YgeC*r*( zqHnHw`a2{H{Ds+Q)+H48C+6HTVe}hJ{MQT@eaHgALVJgQ13J8EiQ?TG?DiKseg!za zRC^Tg$~TxjqSNXW_>o!$G=ghBjwcEYbfNY<MDY+l0$mD{xDvYy8AAz;G4?qFN&bDN zuLdrR--PqhKELAZFbS99XgFrv0B4j{rZm`6K~)i;vnY@m1LWxjRxFP3*8_i)afMz0 ze>#XZazlA?5V?=P{b&~{EmnP+=gq_JetYLPJ+A|Ly{||ynl6R5*cFFKycs+`(xO&- zkHi&e#E3Scyae3J@{#thnu?aG_xU@L!MNULBzE1(>78&XrNi!xg7_7GLiDP1g8-V- zKc{un@98*q-1BU&@e`2(1|MxpLt|dW@aMj8*8Gs|5F|=&)OmsY!CtzO+DJN3c^swE zs*(F*ISFZcp0uquY7;PO7ZB)V7r+o}v7a4veGyn(`{~rHxNlRR^fVsbzytkWjQP)w z1s;weWyga}$3p_f{mX!%W#f@A#{IO$1V>)ph#m`GBM;lSlq5|^-JeK&F_Anwk$O0h zE<2g3bpahPiAkFz98Mgqj~kob`ldMnx#)A|?c@umse3ONUb+1Re2?ZJe&vT#WZCIT z)9LEBUJZ3q4+82GlBXJHr*men*;|M{(rSk+O}D3g&Y8Y;iQ>_Ewsqj@$4=Q9TAHWF zG2!~z&t4^F_Y7x7W@oObB$&Ta(AA$E4VWEIo1HWjpL$?sx=gBJAI{FnepxX6;?ssQ zpa3sr%;>$bf-VCbmXoF=zWy@(x*hO!H|^_Q+1LFSUk_%#9vyz=kedS>eN}({-T)3X zry^Em+gG*((!;>^6rix#ylCLO*bz{?d|s+|-WWYEb2KltF%LIe5Y=8#c3n_SUyv_f zIPq>?vuVM;fZl=R&wnvjH*6JTDNJQ?n|%3ZcJ$3cZqdqY(I#-wE`8CVe9@_Q(dEmc z>(Qb~lY(;4x3w~}-|%W?;dj5@@BUxD2OfP#$}I((ErkRwg{CismoG)W`)&~=aAffv z`o`+krs6;Qc|CnOv3xnXcRBUTa{AFST8@b^W8wmtgurDKyQzPrh?x`nZQvub;LGQg zqS-rvEBDe@NaZX4Tx#i;;Hz>g<k+!fiPh>2#>2qXdb7S;<*SW>?;5_WQqsrbgx8+Q zO*IFub-tVGC|~O_tEu|3Ms=;$99`)TTz{RuK3Kj!+`EownQfI@XS^fR->r`Z{uodH zF<Jg&T27=+?#CDYl37=y>#+ifM?aRdPtEu0om>!K;#^vD-B_0Usqt)0cuVo9;JXZl zyUv2Up2GW4khcrPU4n+yQ+d7y$syxre)X~@3pZXZC@#ebd_-}#P%Im%&<Ym+Jp|87 zBu}dwH_MH?fdMNL<a$`Z)4>o}-c+o4#nNW$ZJTMnWMkx-sjyrGtcJl|LWXq}@C*tH zY`SrudCC2f49m3Orog$&C|qGE?qVd@!)tPURjiYjcJ!sU!mr9@Zz}pd<SA!xwNkj7 z3SdKIo<St{eJXbl6_kgD+$D3}WAU`Y1vZg9cabm_i>H(UE?_{5$uOzP9sa7FEXzIb zn|q{;ok)Pujb8#ES=>Y_tlfgAcn<c0#goeb=drk090EgRfwxpXhMT}36&j3&WFTPM z6h4w5&mo+z8o`|)0J|^;`+#PFcLg$E{`HYpyZ3H~UBHuo;OeIGw2*l^Ie6|<z@_hb zrwjP1$*>42R}%+MH5IJm22eo&KC|UPJr?|w0?1o5KShvdWln%%!Ba+s)eG`!+*JG8 z^5d5|d;1c5mo2<Y-cw#sTo&Tt===WRWMHnv7!5ac`*_R_^2+W0)%zwfTk*M8;OhQd zxJAgIL|=&XOTWg<ohr2~k?!O=<+0&})v=d1*EeQc?|Ux0mYb#>fuy{cZk4vVa<(O2 zD;~9H%gpdn=U2TRpMPR?2-W;JR<k}ib<zIx{bSCbn3AL4S3T+ickXq4)Lpx87E&%1 zS5XDYxi79os^2WKb%ZIAuK)OU@AyPl<ZX)`rLf!yN_w5{+wFmO@;>j%Om9MD{kFqD z)|`DPmwa-~d(?EI<!=WsueARbTlb6({+5_}z*c(~E#Bp8t7il=(Xn-ak8E?^>DeGB z&RIf93FEd<HS|mTTnQp(=&I9Kb(I%KvmayMt(i6(N3;{<FCC@s@BH}su-UKS;O)}U zjs}h|grV?C$SMBOtGi#8IKSVXMg}SKom@p>3$0cuRkyTjk(LDb9b^Vf+etmRJVfpT zv7ESDQCIG~G_*`g)Q17Z{1Fi$q~D{h%c=+IARPw<qViLR_uH5G^llz({(R{0PVoCf zf0-a`am4j+q2=x}qs05xPf3&l>kSqlSF_XNa-Qb?2^vH)2U!V%-}$giPFfnWITqLX z0V;xG^u3ll>pujQ^w_2-v5!q2ZHCFFd^xS-;iy*g%){CKBA?mLyK9R=LF<;-+(72k z?fc2`D^((Cr9-$ZeSXeGe!ebdC7&^C@^U^RB(Vu>a8W%2=CfT)5RUD%v=i=Fox<Nq z!@z3g98LZZA6{GhP{|V*x({u1ehD`4j~i$cb^H|jJWJKDAN5MkyM3}+E@&HtFHh30 zP=1)~z-i6rtFjK@JIU2Y&ox@@{KjuEE>nRMwv*_~@{}vCJ?Fbrp(f&U?=9|FeA6T1 z1Iz8cT8Z?%ikf@A+FQihi9!6C(BiP#sS}gC8b9QBkEV!%_S=t^^K5^)s}-fLWxXm) zzVU&6%XD=P!*h~3d6_L}wZTvdYWz8g%`zzFcmVU*K4n{;<S>MjOVh5bD+#~e1(J<w zwA3uR`mPXCmL6CU_R!a1Ub*z<DE(0=UBKRCv-q^$lkYzLi8jOb;VWSzv+xR{m&31? zw>*edhG4GQfrW2A_MClUfo8~@qJY(|VgIdTmVF`R(fgBj@@aM(1nGGACQd%M(Q^5Y zCtNA)VY<l_UiK>PL%+ym@3c$YTJwO}-~AC4t;Pg9OY8eL?Ic6wZfk$|?&TC&VPAZ* zk4d{_21)YEZ~STKyJmdAvVy2?Ec=NEhH!f_mE=j2uk}|sxqa5Fq_!D&Rfc6wI73T> z?grH#<m68;0I<bopF%Z}o7wjw>{8Thg1FBcifv@QHeVaGk@x7wyN_O$FR>6Z4OYl@ zUjd{`m0UVnMVgO(|4$&2k|8pK*24)^@{r~rTD}$e(Nsmr_avxxq<elOGFo(@69Vo# z#p_Xzm0=nVn2pb8`5shBuqhBVw;<jUGzx#C|FYc9o_c8pLG~yKETuD_@2Nb0>_CE` z9vN5XY@uj-W8O;qqeZ6WTytjqn`!tq5(w8U%u1NV9@DAF51g~Q(TD__)>jBPqAp9$ zgu_lYCh()`u_9eed+l=&x_~%c<_JzuHMA6&T>n5Cuu*;MHz`@xrz#nO2ALxIAVI9l zQfch^W91eV`AG;GEb)W#xXX>9PgC#tEh!mNg4drL8*bV@BjY#hPI0H~WXVY5>@?wp zw_?5rOSFW8Os~e>%J_wqDRm&4?icbWOe%@cW&CwijNG%GB8&Zpc%uX3U?Gh_;oD@W z`BhHt5X2jy_0M3*I~Gu<+grDHqw0h{Ua<L#e|jC%Q>5Ygf!EjNn{cgLwFbNoe0IG; zsMrB?+}9|}&Lvp*IoejuNFf)wN0VE9G;rl;^J(_=v4%@AZ*8C4mbBvoh%lH?dAT6E zA1PR3+v2s7T^o;@A*V3M=%v6{#cfSPNMxevB%EsTes(?hSXezsO?x8iQa?~~s(yg2 zUecGJJXs*$U5_{2EzC<3be8X=08hACa{JCzO1;^`=|Yz4chO^Q&G;u?1<#bH$H&_{ zUOkD4`1tV2bcMhlBxG^BPr!wh@!&bft5dt@HLT{&H}8M4RyjZL+$8#Jlyy8%LU@tO z*-cTT#uxwMnGJUb?`1hs{e;dvcfPosI;n9qL9bdN_gX1dXv@uh<LL)3FNT$HRDG4} zRbwRJ*d!Hdhr)>UARz{meF6j&PQ@gM+h>w?>@|v@HZq_*)kwOXXmh%xCG*lKR=#qM zUUs`ME88NNC%LmkB_P|eX(u0slc-#w*qQ4k2Jz$z;{7{^xcx}Xo+{Q^+eo%TPW$;P z>9KlyRh)Z%6q+vm1^z`_H!lAw(ppx12&&yqg#_AE<^4u^MUVA_>a%Sc&sk2q+q2BH zUsRGz8|*h(b)OMksk}Zo2@osM_$K*Tpf-iWT6mW1sJM~AZ{F{0_DcblguqHx4HETB z`p8~JSgEZ^+ZT`L7oi&qqJQD9^_qD3pU-;8&ULDtp$LgPkvWf@sr=^sX(lxAw^ZYQ z*SXKeF5LA*Vjkvk*nT}ot-I`B>6QWMHwyE2C5>}tSyC^>KfFiKLMiYSiGJ5Du!JQI zR{8!3Cm>!M=Lhj(v(x4jb<17yL&FzjCfwQ#SONJ#C>ohLIbg<U>0{qi#>w{>;?+_) zk6$vFnI8n{dmV^m*{xe2OD({aOIpHGwEhM}P_5es&cu-TX?zwOv}3{qs2)z65Agzc zELcInj|AxaQ-AF=vp+k4@_F`CW~kocY`1z!w2V*hFTK6KtjK?#0q64d&g@rY31pAz z%mfcK$@eBSg`He*IX-XxxR1-1MH7{5w%5w(Zl8-*<O}vy6sikwZ4|0JyE<x}Uu8!` zeY6xn7TD<g;^cmC4tVUdXq=hv{DUwPYx!ZSO;NXHyqn868HaqkrS}TF9`KW^L*Iz1 ziKh&2mVOhh>I9$a?oA$--&i~Qhj<d6krhG-7Pa^WR^9I7Yn5kz6AGWRqCM6BeGv1c zIndDNO&0@VYUsCjL&D~m&MCem6M*C=w*!iB^WPZVqs<7B{l$h;{Jvb+dyX&dbTc#f z?KJ7+mh|K^!|nnOymYzO2x6$CB{#COafjWJzsgCi_RTfYp#p8Fpl3=cXg*&m$Qy;9 zl^`UC6WrYl0^s<|6p#y7uZ)t}=)9D6IOoYsY`r7asS;>3s9_2R1~?Ed3*sXLP25O| zSHcOYOi(1#Y(NC!FsG>YjR0N1yUanOI-icb=}AN5eVNb*IB`Gud4?x3Xb+d}M&$J) z4rk#n`Wiw;U|<j(Axb}`OxMw+pSGdvdeQYl=xqIXx&e-^znwjiNjG{%H}1FA8OfSB z%^l>Kn=S$JVS@E3y~%?wIzECuEeOs?@JYn8g_Nc>nxNa$7X3-UNe2nBQ4LcEtg!<j z0&Wt6BskK0Lnk2tzCE(a_nak&?rUYSWMT*vrwAhYHNFb3helKquO`y=f7w2gwz|#* zO_(F%{D}U0xQl4MCMjwtZ*BsWU~wGs<l1X;XE8sP`{pFkQvw%KVEe0t$jTrO3E^*f zs#!fSwpPL+C>d~$O4Cl@*-<IdN1!$ee=ZewnFOJq#>WVrg2aKph8v_gK<vUFRA66) zaDe@uy^2E(USoigB|1~GX&FTj_Qid2P>)r#@9hwm7tQsr3;NYlSYV_&B!y(hDeCwT zSy~6Ly=jQIqk?_l_y7rF5)yA)0(JT~mLWuMu3JFU40lFRn!>5g1pckS8aedUy7al& z00Rr4{!CDk10fnsO>%==ArbFv@<saAL~xj^JupeWg-^D4u5oQJPF>EU6B;4dncbr% z?ugTP_C`ar)F%;qWdwHDf9Pd2_f3Zvis6{ai_n)K7c*V%$xgg00`H2%Pg|BmOMw-! zcx?ylN1@>)lQWVQSj%hLhx5iOpY1)#_y<6+rw1Y0%_NP(IT8iY`T!o%a4uIQhErY< zW}ty{IMv3%Y!f0o-J<g*7tw!MC4q}r$^u1BJst;)EPG{-c4u%%0O>f_GB=k>G~cc? zxLy(b`__oD5dQ4oeO)FXQFM4g8fR%yw^%UXFk*9Z5*#AYaar9UlnILOwse!>r{uhK zr#QxvdY;M<JTr4foZm!|rO!$b)5wEgd(;xb%~Lw9G)5f~_J~1-pg831;OFlI#IoOZ z;!~Iz99-y=2$z1*q4j5Wlj;O_E|WGY_^QP5RtDJK4HOdI-;mTVuqdU+%FNg_-W#z| zE9s4Z!;PhTq^d=He3j2(-{xfC<z*OOE<n6bTcui?S3e?T9lXu5QFiTgUOaf3P9@x& z!#n$SvJZeC^bcV|FQBrB4<fmy1*xv$;Oxe~&~tM@KMA}i>0{Cy(3ecSOa-~`;hmWP z8Ek*g^J-k2Vm=eospL^pjnyZ;k6_}~oFPdCAjeN#oArEQiGDh0|Gz1W0P3>rCy z9~^vpF$WTl!aIgr?eF)T1`yNXcz+fV)ycqn5R0DG6we76*p8P;xSuKW6y3qodp?a7 zAlQNgO9`-t1m1;7h?4-9t%IDX;7}yS>FTKBNBJmYiIXURw1khM*jwfUv(S3{SxRdJ z6MTLM62l-keu8?ASw^yscO=?+#}GVQ34Z=>x+<gtm~XFk!oH2x6s<t3gYK|nB|mAu zp;=qtQ``jjwkGqzQw3sEg(?@gTZvc7JVl<kUP4sdPMErnN0@-QZ%Tk2$oN1GeCiz0 zeXcWx0dn302atevDr&|Qpo}Nh*bQ5gYp;z2z)=`OmNDs;&EJ(%A(P;wNn9X_;NF9~ z%$SJY(^TH_@wA1wa221xznb|*40mJ1brRwXCF2Dj30T>kv%sG-1bYqQd(-g#nRpw) zC+8Bux;#YNsS~`14@w-oL-3xVXQxiEph!a(F<I(8FYac;{9zpU<6~%O0WJnjHlyHE z3&ggokK1$sl{f%Z@c~uqnQ*SNin2I;Qg6r}KJ|}H=-@GF(Ti+vL&#UwvrsY-Yr)(0 z1bRV}c5ROM=QiZr9L|RVc89n4vT%-bAm$F}#mqe)H2AFG%#XXo(SCf-AufUX^5z`Q zQ9{NzW=6pFf`}{!g#6V9NsKsfF8&TH;ULNkfqXf@aVQ~gLosJxTu3Jfk$LLCk%VoL zH&6!<3+G_k8Sy2v%fGtyk)SJ-bL|CvDrqK0#SqaX!o-2@7p`J=X}y2uGeQEKkO>K~ zA)HO5uD^vOlR+^BzUk`F;CM#hA~c}@ev{-Yy-N7L?%$pWMxj9-Xi<T*uXk~ugzs{I zxj0siLoTU9qPd`N4$Ti|VeCP?70J<oL`a*PVkeUc)?{2F1FseC#oX`i9n64pVH7(# zrJ0<8g&7FaG|%`$Q_4Wo6L3I5UkFD)%pgSQ6V!XK^*Zp)z*ZmJL|nY7(X$g9I0^Fo z_l*10dTp*U4vkBqdf?xBq;?ZxSr0rB>VK4oS1DQPT%BPScwY+GmIb=Z@P|YTEaxn+ zv7VA{=$i-(hdL(`fpc(pz3A_V2(@6tArPInxgUtmi4B(wf#-`y3sXid>oL6ufEp5` zi1y1*<VR%M+W|vdM?s+$kaM<>P*R`N=rgloi0t-65*qJ`;!$saMh)U``{L63Ny*`_ z#LUDa6u+l_@<@BrG4c)K;!9-fX1{s=jhK!yitPlsFung?>AckR`XVFyVj}(=0u5li z@nHmq2e?PXP|hrZLh47HeF<?Wye~%^-Vk1AX)maZ`!AML34sw0moVDkiT~2TGY&M$ z99|OvKj`j_`*hCJgkU?}7q<64pdRXr1)oE!`A$My7{}nsZ#b{aPjf;E-ckQKL`4}A zebJCW6D6+Pwp%Vlm&B7E9Qbp{3wA5cB=9;_e7#R~9okA%*~E|j1zGwM#kn|?5H9w| z*N4QT!^FQi4xZSyBL2Hv#7z?Z9kfJ4ur}Q9KBo6L$1<GB0b`<t!ZQ>NS1tFxO<g&z zO$7xNK>40I1#--@pF|Vv><G=NZ~HWek@a{NBzd;GX!x^;kJm-<-sWd!v~bdfQnhq3 zsmA|B-5*70goU!rKN=|$?85>DPTryTS`;ij@7Io?<>ELD(YHfZLSN5R`sUwc<q_*E zl9`K1NQm7CQQLx4zPqBgDJU(GA%d2e*tm6~ASQXVVY(I@&A_Kl;%@A|zC1V|?HhuL zSEjg-Ls6M7RD9GG!id88G=@%x#o%%+^sF!Q*_}9I6VV?D8r=J+p6Z6`glcs|`&yu% zK9TTIuFa@RJG*Vc@Q6z+{5cMScsM431<rFB*&lb!#kkmi0sFlwjS&PpBOxvvz{JHR z`&l5H-1Kcsj#C_&A;P?c=)_jzntCdMI%u#)1zuu(I`tnk7Ff}S&1z$Pm*?@e6p*ij zP%H|ft}>VzAKUgrHW?1~*oA<e#IKfb#tnjgKXCYwXB5GNy3T>G&n=|GgPHT@gsm&e z|DE1`1-XWRzKE|1ss4445CQ%)<6DrKR0++6#N+qyzHp#1$@qyRXf!=WEu0e^wx#!* zXG+y)`EiU(I3$GeBU-|?bPO6K*b?L0pTvMfBIkV(U^k9ONz^b(Dr9T_(h2<b7fGV? z9AxEsxL5mcFY$!{Ut-t0I9Z}|dN?kU?6w%P<j=r)HOmcq@8QGt2wy2>EIj+Rcj)k8 z6tN?b_tT|GRAz_-m_A87tbztgfRcXz5`MXxa;&040fJ{Z#S`;{D4dQ=AoFv{-z;r+ zCjxf|uJk*2^%^L^ErdTzuz^3xg#%o|<KUq;?;r=hLO$zYzLs<|T=`jiY81nF4t)CY z$#Wgyk%PDdH)1?eeQ|~tn-8807d;ueqsK$+@5NuhzFXJ5`ZRke5CKkp9Qr{FZ_mip zv<SGW^Q=(;gqZu5PstERZuKHL;RT>xo`V;WU4KTPo@7v3!E$tG%83P5TNiFN1>#M{ zp%=GiE+ot97P>gh-?%gu%K*huo{n_i@N#{AO@iR!M!c5DNN<i}rwj(BNWA9xv5<}? z99C6L`0lh_YE5uU*UwGSkk7tZK!C0%1{y*=9BQhCz=0N6!*uPwpBM+lRl+})%|we7 zWZXY3TjynI#02=y;S<|&frAhmSHgiyhuim*TZ1@1Mp+C8mw($*L{%tju05&EZmeO6 zrO+Qavl>tW-B5g;BUzP^a?f$r?5d*uZB576ue~nJQT$rnhRR67VQ^CN&QJO7()IPt z^_49(2HA=ztQEPf{;}HWzD~^Q_VLkrheP)rwVe~=jef;n{{G`lKPIpPb1{0{BBp8g z+gIrQtCM8y#8t+VsE#H%)A)9Vq!%8BRCOhZItClUc-YE%w*{r1g}sMc1xS7Wboaf7 zR@%_@mCtuHFSUjax9<qw{VAlC_W9WrPmTY+v}2(UKG1QEavibHZ*0}7@t!yRk46+x zOXu^~bN%}+%VzoDOgwXO6lT05pt_sBLOc9?WB9#U>C*LBt^bZp_P19j9@GsVnI3Gf z_h8PJY{}QTP~h`M_Ss&ho&JDZ8iDI^0|Bs)2~Y)pM#X?^o~^!uLXHfLOHz&E1{8KR z4C+Vv=jh~KsY2gAr!&M<8dlwM5t-KAil;fL4Kj;zb>1?S;L$BZcDZJs{H@+w_xxCL zGo=*J^7UjQstXN1*wFJ;d+I;=$6qkB=Qk(KEC^p`Pqr=Qn^pBJyf^>$szdcb%=160 zrE$Z5LVYeB*OR|Hga!<m>{~qLGa$Qpyiq}pRuD0;jd@$C8;p5oRpCdW6}W$?n>DQX z9>S_t%j@_#t?0p`V6$Itm=XO7nDu-0JVs@%*_lXSL(G=p)=2)lk;~&|{E|r_dX86V zA-b<5rN7@f--NBX_aUpA|70mi#FZ38xcuIHC?uHIb$904`_lPrW9_c*B`L9<+gdy4 zv~v+a?&A@;Rsz}&G6BxVurk@<m5B+PbF!Q~CX}iIlsm9i>lup9r~k|iBhoYI`AxT4 zo95hjW?0=$XDehYPXBH6)~(~)hS%2eM@O)Z+U#u$&$rF?AL&CnJBEL%?L0gpR9fH0 zCV80G@m_Xqo5EkyGRILrJ~_`cI@BF?cQ)1YTs?u8S8I#Eeb%%pp4Un3rOfTu6^G-m z;Kw3(tq`B{j8<)rad*J6Lbiwx0KslU51#Dq5MZ{tb{>IO_3D96KBDq%$yqZX-`0q} znOr~LY3po})0AxsMOV`a|7+246TY73H0i8Qt?wC|o@X_WL<4@b{SC(qpIthz*4yY> z>oxw#x)9^#dc<*UNV_!L>b-UWBV|avY4H|$Dq*I@{#YP$On*1Mz5*qvL*W34sBrXU zMpS=%nrTMks(P<|hkP&nw0u;Rk_H8C=Ca8CGhip6(XET?ibdM-xiYHc42|dX96EA7 z6)GiMNWQ0<*^)OAq$a!KHeim*fPH>abwlm|&SkAmD?eybUl)9%p);TDJXa}Kjj}cM z&w#m!a=TAnet@01Zp{VG;ZNYe(z3}wl~D_8y-AvhonG#Z?@H3Aj9#lasOChEM8-X- z=noI6dO3--lAj&qlX$8A`XnS%^pFB!=6vr;<^oFb#*<rX={#PO-@-*ji_SD{W+CSm zFDe}<!GXse4Big7+QYtRAUJQ?GqG|_g9G~7|Hxi)AODAof;-PGGVNyzkY+AeUcUmM zssjeBW<lfHBMXFT3h@n05)j^mUbelAtHk+Hf(}yw=FRwKzyE-!Aptneksc@0f&!bz zUZ>_Lqa;fbm1J&S=Z`np${VA-HrhRvd9FIk1bd)rNI(AWv7~U~I*X`)Db7k(z8pvq z#2?oQA{#H_wUfHkUIKPaQh$j&<b30N>8cyR{X_;>DZCFRZYdDJ1d7%=JT!CJ%uFQ# z#P`ErYXzO>F_Toj>gO`35<iw36dbEqHTc^0qr~&5Ql(?XT+me+L*ev(#bXK2YDxQj z`F8!47rz}Gcf)eOGa7>?vMq?R1)MOCb*yL|$zC-)h(~V^btzQZMrw4oz9-%TnXd>E z385T!Z9{{t(blR<oZQ}>?0Of0A9$5m(UOa+Sg}Ehm|lD5OZ+ys;>)X<|K&mR-am>r zjEY~nD<yGuxfFY*;SK1+1}QJWMPK$X+|fKSTjW3Pw$}1P%`qp3JAeAE@VD!2P2m-i zVi-lf11B%jH3Zj5-r$(+MTOnHV#rBUrBDtBPDElJ7IL5{`UGWTme|7Q*>hL8)dMn! z>VN4+%8}}{%Czi^%d*Sc^qEO4rrhotQG-Ecy5NN1V;Zto?*K(UGKtp%eWrM5Hpcax zcAqR7z8?O%;c8<$oVvsb3#tEjZij+bH&TEhWSDK-!_MAa)9=&2w4V$l(}lMR1?(q- z<%Y!UP3GKSNu4NBwp5@^D1uw(3e!63@leAe(k0&y1uz&B9QYm#@%0!TxrWzk)Z2A` zezpF0#+o5MLD~7jFkwi(D-rLyukro3r=)46tdnctJj~mFK?d{~sudoWWv|JVO!-F+ zMjHpEAGMy0u&~xFXyHks1c~fhybeQgW+#nU3FTQpzJ<r-Y`e!b8Ljqfvr3+ZS-7@s zp(XRO90ktCS6#y$wlEoeu=3pM!NmfI5qXn4onq4~UK&lJWM!9Mrwlix>opcxjXq#J zAMa?jcctiMdQvb7bq;THv|HMp?bP{Vs4+e%nPb{aMajWIdo`Q5<@bY^|5?S?CeaGS z8`amld(docu{NPM_MI3xy2F&Es1=X2$hB%tDX=-0MorSElrOXo7w!tL$rNQ)x8(ll zc)8Y+??}d~dk1C7js;ob|6)aE{GmzFTANv(JqzM54PT#b+RVMy^G%LzIB2c?tFWkN zQPun(H~6l|N?h!X+5uDw^?{g>Zzb^w0oI;IymtlM;n{X+_qjj29_EP=A3AIIYLexY z#<Z7vQeb_Ysj%}5=VCu7fj2Xfx@;E(5n1+yjL_6~PeORsmOHoeUlc}oph}e4a#=5n zftS*$9rA3JjW%X8+kXc0vy1gt1M@+o;n}p@<lKOnuu%CXN`E}>rpaA)6s_#QTDY?S z#LKo<;P=t&Z{zQEHvL^dSmvB{j|<X2&06RBgaEGm5u{s>S;3ORJH;x(fl|{J5TE`? z>0gO9Cxd!kh4EtLiZj854%uCi40_Eyxt~Qg%Vqu+*S;zi5_FlazoR!~rOLxWin?(` zmu;Fji-Ol$$T-^iydcp`!l@~4!h(A$f37pR%^l*3Xx6>#qluq)IbWqI3#%gmkpURP z9Do*@h8OxQSDhP(I`5-33}3fe{V=6U=K6RFC{40@C_`6tu{H~5l-Y9f_FHfn0v6n? z)ntGMdzpb}tW8HT%B4U9^@n+<9%}T{%xr)`N&JEk1wrnCI1~EmQ^epbkRgLDo2mso zxkyt6S)C*SwEC^JdFfx{=x`R@sFB{WP47V8GT)}_31TH9f!dR_lcV_u=YgWxugv#= z{d#ikGt=x@g@5r}?&rbs-ry&1?YY68X6u0C93t8j%(VYUc)ewBwAj<O+>j6&ToI^a zNYixrtUE|oT)&{t#3&Ea^IYyAMy)0LsW1<KC5vddcy~PMj-@(KB?M@?XxE+VWq_g? z`T`AefZN}B4WogoXq&nf(e9p0s-+mI$LA1CQ6pXP-5PPj0&Cr0pU<$cdOGu_XoXX7 zS1~Jq!VFD|I&Ur-D1Wc&Ou3R#ZIw}zl5u;Laj%le>nf9XN~YuND$_4YW=mCO8<$O; zzJzlw+=PGPS+Q1QV3b|nFVBLpUhm<k+f)a#9Iuu9jHNt^Q&kzO?Lt2lZ565fPjNsU z6WXZ}>j4LVI+K3NkVa166~$Tb_EQzNt<`*Kh9UF>*jIf)c~dmNS`(-nf4|VAzk3sS zO2&Sg4{Gm5KRpJ#U+Q``z{+dLT3b`WTvz<xZoT;jv|n2#+ln~)RvArVUCS`)gLGvS zO>58UiR}fs_L_^Ut{g}GX)`n{UYgmcRp<zpJc3lL;#6ZYsFZx$#xLZGZk`H<-<nq8 zaTFmt9s`x5OK#IlEbf~PT1wvGl#w`QP3E;)%s*|&zOAuN=bKhM6=xlTqMtF$GT2tM z1N}=(!no#IYnNiwNEk0yq61Pz>h66zU+beX+Edm8REdqQ_hlu9>?s+bHXQIZh!Ofi zCEiZ$`CiqVT)YMYBf+ApBWG18G$lq~1}QgCH(1Ry^H{&Xz6{XzP|_j&wYERTg!=J> z!o;aePAzzz4#iFh%wsZWsWFJvTf}G_Ih>|o^hbiV6k(dYJg4eIryXIsjlj=IST*&J zIw))N#iiIIl3q2|6CCCvE@^}sGWnMcvtVPo2+;1dQl6om-J`=C>vG<ym-W}2<ArN< zVkGX+ufL-|`WIXMYvuvC*2mJ}ST(0+IJ?>eoonL7Oa1^*sUOshw$_RENt1hbtN;B# zy@Qszl|I#4onsJDdhtjCWa<z2<%pBWm6dR`i5bng<8Sj~?7=cq_5Pxjd=5q%PQSyd z)bq#Q8I33!IsW1T(5T-^6Tv`fpK$CscKeC-nR=}6;Jj`DK#dHLd99usd!nuqn!x>v z;{;im0X&{VGjX7)Fsur8d3NggcDM0zs6GX>vc?6>v-3IG6q+hp@e1LB$@<yG{&QxO z*ZVR+X(r7CWv%apQOp7AhGWBSpU@no>x@>$y5KG#U_#sq9f7zCZb=O!O>qS4kYjDY zJKi3v(XmgORuMF)w{c0Dc4V=EN(`)N56Il@%~`{bkGtv<<4;f_(O#*MZZr1gNQ^Sc zw|NDq;s(%2%#c^Ucx*c(hHu2@{5dTbdaLD1>nWhd6*{@zZZMo~T<m04Ef8fhQFb_G zqDx0;V$B*civ8Fw+jk}uD|ua;$tTC(6FwCC;dHc$3?x=7LILV7bZr({`>E=-n41#f zN@g~*chfrSO9Kgq^{uzoE3nc;iG1SHoFv4!3pToCf>kZ7J{$*GI(ZzkiMIOqO7S`; zZl>sS|C5g{z%NE#CUcMV2eC?}i@GlEIgG*aey2{;`}&JO6(*+39Xl9pZHj)RPLdu8 z1jKmJ&$VCF)3o;7WFr|1BaC14ieHQB!>-!v!2fi9aE@U&6)HwU9nTb4GkR!O9syJP zYz&d~!wjH$^rxdI*6CSKScD&PP2Ua=tyM!X%1kR$W}gWI^HI_vdP?M_10?3KsLEn6 z={8OHtn~|$)gyR-wL6UrvleOb)gp7M@J21n2;bVI!I^ZOQt8ELx=v%h*)uDRcsjxh zRJaJ?KRR#9vQlMP8#rW1$r70^o|<TYdQPRDN!0xhz~_-FOgU$=s-P*t$^r2hdKu<~ z0+4!K4JY5}bmCubfXtf^JRKCCmk8bg3h#Ra-<s0Y@b}F;fRyh0VH91RVrhoXkix0` z^C{RwcKON_rv!>q32t4aiq(p?I=RjFMR8J>DiB3^CF!pih4d18C9K`)F+Lx%m~-5e zgi-Xuu+e30*R7u}&~!^@4OxosP$2U~8m}c{@{gVBI#9M@L#IVsIi9r^Ido>kMso(( z<|e3*<T>07_`%z(3|;5@%G|8|?_|7{DH-tZ+ejKQYjS+hD)MeG+EQEwpskMO`bbkk zH^0tCo;0DA>sc?T)At8~;$++OcVpLna7i;7Pp94)=L4QWKl<fQe-j={5j|%v2sBhi zG5vrVAvE<oY%_{(#*8=<&2(?Nb7v$@N${#dl%rG6g!4=+snbU3Hywcj9PbQgxv-y_ zya`u%^WEGHsM?9qW?G#_&Pw)pNY!&HfOwf7EK8oejUCI-$Rz*1PE+m2hALa@_q<U; zFNkL3m=$1D)G<W7U3jX?=@I%VG@u>4WuJ7XsnjZ`$6A9I`%c(XF9(Y-Dbh~oPr7pH zt`5#1q$zfU4!hVN3D5zwG^uuO7&hNGV)UD9>VUiY+xF->D6JBX|5)!@&$BO?{_Rg3 z$#KX780BQDkN{cejAMcT1(%;0s0=wO--&bd0j@#S1FHfAmM{jeA0BIDI_M*Ow0eX) zzw0%IV3y8kYg`XqObylQw9+L{oKy#x=x*ULviv2XcgY(s#NMDJ9vhajX)23!Gk<lh zJW<nrfaW^T;Knt;`_1DLJMPv4W^O}g8m*n@?ifh`jYn)07BRAcdjI{sv?=xTP!AwA z0_22c9-jngFs(JIxyR}=t{Hb6Lve~cvs4WUF>|q2ZKj>n71GI^)6T?b)eqV)hpB&A zR&l|KrSV>jw^G|4>Z);B6#UxM5BR4Pt#xZNO@I^w>#87Eokd^bo;nTw5jlP81QPQP zl@WP&tVycJdFk5RJBed-L)^8Vywm^IrddiewK);f4Ae(5Ou{k$0wNMe5!rQ}+0BNx zIy!H)CVKz2aoxrua%kE%Z_FqF`4PIp7qR2v|Dad;F3yS;$tJyiicxRGXodT(orm0t z|D})4LAY6)A!+;L*#7~9KzqL?BzJy(42vPd^5WHiY7sT?4-7%t4bDU4!odlwITffw zwYnQF3^D~{c6nLDIaq^WPs9y!LuiY3GI$+5T-v%0x)5%w)LD4cwl+HKg9wlChlc}I z48tU-Wf%6grNdf`uiShP10+boPU(X_h@@K4Qfq*^KAh|s_X0A|0+NeDJbVl*-5D*2 zLTczk%9c7TSi-tdIV3cZ74f)8(!=ATTe`slEF_<9;21IF0y!vx5C{PTlmR;oL*~|l zBrwC-rE8S%Lu~-af*Xlx!h$xCLp01WYJ<)ije{oaL+mR0dIkRtH!(GB!-PHfgC}sp zP0Yuo@B5V5C=O>MC5XW`?7|`3gVr3VJcvSq9XDRuf+;w{CU96UG-<_X7%s3k-*}9Q z!Akpx!k7;OH>~K5sP{I20xdj4j}ZIhT<19iFf=Ss8pJ>pga90@!!7Xnq*33}I*I7e zl;wVQyDdW|-1+B9ct*@|CUly+TOU6N!z9!$P9@yJNop=|0x@(Gzh^yYWqQ3^g+Ekc zCaeRz^ja^l6+Ps`FPL9E!~;D1LM8OV$6U8tBLh6qI;dYX70m-L&=4-n!!z8<i1Why zU|TPomaW`mXBx!g2$(B;-Oh4@IDFSIr~@CkWC)Z&XfFQ)IhaU4K*KX5aFmn-EL_4e z(1TA#L`1ky<8LUTwmzY5YeQ(lh<-5bmjq4K151$FyjPGvC<7#@Wv*$x@B<as^Tc?d zLm%`(3q1lGbh0QsLNBb!K0t%YP(wXnLMLkjGU&nr&cZAV8aG@tMx~D_T*5$9!>ypa zE^OD7t3@Z!Y%{35LFfuKI07r+MgSGbcR|BEAOk?mg7*$yB}M68WvT}*8aQy{#$7vS ztr4kx)i7q%SdAM-eV4@1b2yS@Ns}iXUfahj7e8|3(4l)dlV(kuHe;Uamn+skZ0gj7 z13HvwQKI4O**kUWA3J;Zl17y}m1<S1SFvW*x|RQHSFc~eh7~)OY+18s(Wbq6?;o&8 zUfHqx$EcGjYUmVMLO1W2Elj3B^-{)*m$pr&5MS!kE8ezw+Jt4x)=b|#UaU;v(#LJs zwr$Ub&2v?2o<3NXe$AUljhbiHuU`+Nr;8ObdexwH)4dy`?rQY*@na`V-z+(^)?M?q z+}ky4=f+`jwXfrD>(;B)W2Fn-IB?g%GZ#OeJbCBnJfZ6MGG=@C@8QR9|MJ|Pe*BE) z*B>-pKT@9LGRL2P)GE-x0})J6!37y?(800Tatp4wq!9y|Le!ZD4NQ<3ry6}~`Q;Z( zAc2IDMMQ*W8+}%6rkQE9*@l{IaKTI$eX9TI%(Ks)(Pxxtm;nr#d4_q0HP>E~k(y^j zgCw7QmZ|1C-=x%y8)~@W=9zkg3FRF~_8}*jdd49}8hSFxrJiMSoANq(gmFcrXp|EV zygTvCQ_tm`<7cUUq=8AkK?#lNC3Q5(#h!44+RxE+(h29EVKnjOpLP7X2P%91A@IRZ zK@C;ZQAsVeLAfOSYMp;HaYYzT&^e`(PEOf|8)(LX21|YD!Q>cv=E-In$+W3V7-mMH zgqCFH$q`A`iu|Y-OJJdgvu9yz&DL#PVTB%gqU?qnH+P$d8*{7iCL1#3nWvRjh)Ks9 zYwEEklWf)$S6??Vswd5fzPpo8JqiEbv$<>PA*CKe3vF0Fa{A!~6`$1U$I*+`DaM{$ zyqM=wPE8G2<dI1(*<=JGeCw;Y_F;q{SYjbXmvdOT#FcDh6Nj5^=;=hWe5ff+m}zkN z3lv<mX;w$rJX5U`Ni^$bm~5%0W*Bj@xx^ye$eq$$aYC9$l6<fUrXN$zhzA>K=E+2u zdaC3tZr<wIB@=W+%Co$^`38?3NceGBaQNsuXA=A>wix65`st^ff41p^n12M+^yJGi z&s_7(K}{Jfc2?Ddk$<Ma1eSW}p@x-AIst{1V|by4l3J$OrI*%guBDfJIMP;0)|}xc z^;$-;q{FF~G_q=Em~`b5ed_<IuIua2t;a`R__3zUb@WlBk9{=ZCHm=gg9aLI>Vbt9 zbQ<#JJNHqFA0>oOVQ=vJ+vA55e%5JpaYwQ74{{uW8<+A2=Mb1c1ul?*RcVXLCd3vr zz~UdU*upk)HI91ZqZjh%#UV05g+5&367h&fFZ7`^dOSl$D{2ijnz0OV%wrdz7=>m= zv6|OBLwQt#6DDZ!E$NZZI_PW0Bbt#tGBKnc_JBtjPH_)5Wob$pfkrjXaf(=|qaojs z-xp6}4L`+VJ@|8&{d9tgiTUq;`$0-Q4l%iPu;YLYwBsG|m`4Yp3W8hdR8q|Gk684f zfS^EwCg_nXXgp*b^icl?D3bB5WpraTJKE8asId%s=))DDFhwo&p+9dqqiRR8RX3cM z47kmWh~mN`G9HnOeGnrW?t_RlhyjmZysID42v?PQL$_q?LVMxi+cC{kr)a#)756xY z{me)x`t;)z6Z=UUABB{2Fv4SV+>{={8BTGIQ!5V~i$D002~X5R8@j-S&8Sh2bLdQy zuD}I1nz4--DakWQ<3>nwF%3|3f)&%Khcuv}9a7MPl%*6NE=J*sd00b}t-KEUV!;M^ z@PioRU=BFw)dx?kBOk4(L_W}QK5<l$BlIA}F0zMAneq)Hv7krbqKUtKc%mHGycndy zagTa1f*9;Dhg1K^nN+1N)sCJMOCWP`3Qq{55&WQsD@GB~Vbp`G^QczPu#_cp(L)@( zNQNsY!HQZOqZ##rMwHOBi+MCON!!rmG$4Tq=y8OVt%Sxoba9DooP(C)S>`TA5xr=r z10JE!gj@T{jVzvGAJ$+<G%%Z4&2E;noLvrPQKyM8-GsEIHSJ9H(TMx_lyQpd-#W&D z2Xr*0j!d=fZE-6yr+&^UtjdKhM!^em>|-DKsD;*OK?_~<K^eOs%yW5x48X8L60kVN zJfd+XjNA$u`hdhde%G32JcAy}AcfEN0j~4)b$U`lQzrJo5RZN~8aurkZr(}`Z78A? z%aF!1vLyc{j?~Q+5P6?BI-6hxV^%!-h{Y+&cv=acHYWVQ%{o~7sC4kdAGw&Ar*a!& z5sz3wd=yJu<f4v5_#+K>=w&p>A&qlnBOmer#TGJ=2u5&1bd6|)Jmg^;ayaCC^T19u z=J7lkvGA1BIBzewN=1wEW*Ot?MkYYf9m^UP9P?;{V}c0{Vw?kQ@!-cTsEFiw%pn>4 zP-ZP>8fS<ktR;fVso==54ypb_D2>aoez4KuNi+qiBsTP+5$%=ThUFe|$pt6=fr(2j zgCDsf1~|x34tkt|tNY;UryDtrC<XI6zd7q;WMnQ~WTH0clk$|ifstj@1FyW`V*3UL zw;cc82AJZy1v%moibpJj7#&HUF!pf`hs2rL%lQsHMqwyB-?>l_`wySp$f%1kirYg; zhd($$3V&cK(d9Pxxu0TA2;HL}tV%2?YDA21cmo>NfCf4^!3%43B*5Yt*Ywb*R%^{8 z7r0>EuWmERf5Tcz4$g!&vS&>2fP)z7$b`a3?eDj8Lm#UM#WB#ajD6UwAC?8jzzUXf zg3))GupmW0&LM4TS6dyq7{;Q8(hqyAV;%h%&>!vL4|5FN98n2mr~WZ+o@2NloVdlM z3e71Hqnqkg7w4i+?36~JA{JiFge!>Ql4#U}6Us0$NB-H7zV;^V&)5enbWv94v4a0s z(M$VEH<I^_#5#I5L`P*WyBvs!5f+??p58NZ3rfO65%AzgEFeJ-T0*4RaR!eyz$c6{ z%4FIzZ_hcNIoxWTf{s!T#w}1^4^)_f6{A1~bYU-yTBy|&3q}2}JEe(nOx^0e_q`sm z9+tQyofENm#XsH-icG|!8vR(tLboffX34ELNKPbha#0IVfWj5Y(8oUfeNlali~Qr) z*D~m(3ry^yvT!EPIP66YUL&58^PsdmD&YuP^rNHmt^7>=COT%q^9F?+&H)_oqutWv z7IFa;U?CG4VG<&N7nUI(EKoHtFauRXA1p8*njsbtVG=kY`$i$Ko(}0eh3Ef%Zv|OU zbJWc&hR+iifgZ|%9oUHzGGP>I;Sl)2A-;vHzGcod2qGpT7m%SA{(=mcK^xp^;b2W} z_F)@HffVMUvi1g~(n%A}flbIq*2bZGLctUILCj8W*-q~N%A-%DYCSqHnrK2MK#v^w z=O1oi7-~Tj(BKjpAs4biAJAbP*o_|$ryqo(91QUg4-qJYLJ%A09{3?2^nn-pzzcXG z7IwiGZb2?OMFm^16Fresf=?{!=pRVv9>C!z`e7fGAz3;>6lftAb|DrjF&B737Goh6 zdO;LM0TwWU7xJNPtZW%x?FnNoJLo|ZMj;uv$Q!oIBqV|wG65W%5a9pnK@#;z4&LD( zia|=ury0QrjFb&c>S45~4Vusa0oCCi%Hg*zffGEz0$m{;?xD|K0@Lh=xa0%$VuH9{ zB2ZugDEOg*-o_a?AreR-7H$C;kZ$Kbu^}CDL0<4Ih7W}P!6h&)fN0?u^g$jxK@%n+ z6DA=RPyr+-fe}1`0|!eTWDFWE!CYeP3Dc|^Gzb<h0Tag28r*L@FiV3*VH;ku3$sHQ z*nk<Nfo*0%5#pgKI>pUS&X}4_;?6-9*P#u~NFUFk9NO&_v>_8TL1qjpOv(Wj!X!S- z(Hv!NJ_ZmS;;<aVK@;rZ=&Df!PeB-bK@%VHF7eVVLUAnOf-V0bVH6Z4Q0jpnUZs}= z@i0N}FjKK8r6C%u!5iT366k>#t)wF~=rTZI8D6XmPXavl;S`{cy><g^5{envfc=Q! z()!^S-r)=s;SA285zt}czEOU}$PaP>P|9&8D#pPe0Tf7q7v@1Gq`^5LLM+Yl&fX9$ z`ym!Q!6(9D9XLfD#9=8sAr_=TE@~?;xwAX5A|la3F6My|MDjl5P#iMh8Y03uoP!zX z#on}MzIKu&Zv!T81$AP<b)G>cI_hBdM%lPQ4^)FA_Qg$vM;spE7_tW<f}x|%Ar(R( z1|T2_I4T$(qE67T9&$kw)M3I->m2x@AFzQNP5~2YK^gxBbIAHn@Wuf-1;s;gg7e(N ze(1wbpkYxg<|jC19rj^ECt(?kp;PWbI=!<<y>l<gV)$ec78qd|?m-&*0TpD4Hfu9i zBopy8BEa}9p~N8;SRpvi5huS<j4(kL;70BAPB&(a8CtR)B*Hr&A`@F71cV?4lz{(~ z?ICK@B&;DF5~V|_vf5sPAMW86cws5@Z6Bl|7~<1AM&dX}D>(_UJ*1%=yx|luj3^uj z8;Z^zsv#CQ;S^5rQW`DljPz7n5J^`Csp8^*Gyxry;o|7QAE3eTtU*23^O(RRGR1+t zUJc2_VI1~BA4p*oSfLvD0hi*eAs#bLev(|W<Q)HaArt1oqbLu-9CIB)0Rmzm29V$x z7WG20wb`rz9ae1}LJ!Ygv|@6B6kOpHxPc$eL0R1gGRFb4cC|$#HBcut#@0cNu+7gB zM<_5w9b$$QK0zHeG3ZdWVOtP9(?TxBp$??eZWhWDG>9JN#XEFWJz26>*-OC0f!L6N z5^gA7<;(w&3A4aq8BoDPMAJ9+p_9&GA?#H=tf3re0Sn{+4&)#d)Pt7JklA*%9vWd7 zT;hIaB1DHFtHh@Vaneo%hB<1A^CWdrInUE30Ug-LC>X^b{9znmK@&dVaiGp&(bnoz zRV*~csQw`rRO^5q>@Snm)5Jr5cs1_=Y#jfi$4gDY6?S1^C~i+lV(c10hNvV>(c}^i z%0lzBB)mZ<I3*n9Arw|2W4ggn_Z0J%!X5%eAIWmsK(rr%;Q@JJAHsA`A>tIQmS3@U zAE=2J*r99l!x#doA9g_#P(fioCT)GU+)S)M+IILh&0^S1L(~cthM^p!L0+{dnXFW2 zvP5{u1Ts;fMod)S0_QsnjBqLLWk!KIj%+u$Ay-%d7x-Zz;z!w{AvK}l7KmdOLID}r z;TF308^<mh$x%>Yg8y9Zbje}j9v6%t;#HRuYeN?uP@$*(2OA_MV#qciL5KH#w}Njg zWxzIrHF$$LxPv`-RdV4KGDaHy0Tusr!KF0ebx`3I(19@p5giUQeKTPqwk)b{hx;@^ zc)}zYoXvYlf~zj!8KBkJRt?!EPjkP>F~^}Cf{hYfA{e}5iQ>l^`oU&AS0<!MQ2OB- z{&yeF0ax#LPetp15%@h`qB&oI5dTL+R|R*;w%v{@={$Ij>9~&V_>S>7kM($u`M8h$ z_>TcOkOg^=30aTV_M9?BQ{HxB?n4?h0V_T2P)}hNMB!%Ci0dx-6w(0hSYZ`x0aQt0 zGho*tYRQL9qP}8gO>$%5I)Wbj1rz9j9J;8BzL7zRfvZZP6>hE@^fZ3zix)7V9A>n% zWTG7G!F20EmTd_lkT{9K0UH0t7)GVpv|_>&5NC}EF&z9MVlV+fP|Q><IGnEzVhzL} z<YE{ap&m5l6n3FQd#Z7MkQ+F`9X-Jv-LVlcAs05O3I&mrP0o~0qP{pGlDLL^xuHip z0U0WdmVH=*d_fxap%)av767Fi)c2I5;T-mm4XOE=)`1=vK~Bn{lpTVZn^}HPxz5sZ znpygcjZbkFryrQkf&W1orts)WPn>l+oDTUc#_b=Jp$(vc9me62V-EDL(hvz%Q|5>r z+Km?ZA-kjj{@~|}sB}+{(ORe^OL!6!hM}?s7@!@382SPK20<Uzq5t@lA2dPp((+*{ z=Del>Y8jfV!Z?XPQ$7F4xQxxX96s~UfWjE0^BhRw6as0d5gVKysF3SeDT#p-hJhWf zlMRV04(qWWhwL7@azW=y<vcs(mZMyE!4<~GH#7(tFkuv8x&J=<vz^Tv$iW_Lp%OSD z9VTw@7=j!;3@i!7({_RsU_l(vA!_||JX{-F-;Ru~maku;93UnZA{(&Pfm7Fk6cS+> zIz>Pjd%L;2yS@9n!8^Rgd%Wkkr_n;_oTB*lVQcqsv@E+O_<<W@L5js1e+hdRCX<Tx zK^Ssy9(pjW>${}Kp+VK5drBd25(y&AL?7mWANKcvuks%3<{8|Kq3in^>Pw3_x}~N0 zEcsy=GQk{Z7n}dq;oHCg6+U5AjxMoT9D&R`JdbW3SOFGb0Z;-5AIb9X9_yq7{3NUl zk@TAyNFfsx8l-ysi-JKK(!msvavgjjk+|v<C_Hrgu^&L1{c!2XN5XG3!NHfCuiL|m z_Xnm~s~`F!I{)DnobD|dw#D82a$Y=Q<>DT2!4ZhT9$o^+hdI+gdLMXP%TvO^FfIy7 zVRlgWssY_3ydfCuA=nrfm&!q%rgEiU6k?*`5_F-`{u$86juH6rt-<^(A!dc`0Vv2E zo6I~Y{^1<xKp4#VfQI+YW!+Tb{Jia9_?Dp!gew*I^?;$<O%uH&9Fy!$w;4zQ6L4W1 znGw;0UBLfw$(7%s6=WAwy?iDtTVAE%9*#>K0Pn5?+#C2o7hW#(IGn@try4lHAFfHd zfdU(P&N(rK+-7~=L6Mvj1n4&LAC_wrVgW15vLEdsREN9S{TUqUK@+H<TXX>d8RFzv zmf%eSB76ZD&>`4bK~cZ~b;%MdOOzfa!lV;jjNbJgKt0s=9AXls)Jr_W1lH93;S|!H z(BgvLY5qZKy+B%(6ZB!#U||uTX+EIT6+B@d9{$_wReSa!9ehC^uwWD90rc#xdjTBc zM}n)0DjwuO5%l37eBm54em-0x6JVjzrvAv)(_j4Cbxof0n)4H6Ivv>E+a8z^D5z6w z{_g)5<mT0)RsEr=VkHxl;TEtGhC|QOz~s_8R%)H{<l<8hgW(k%&~?)Hh_4k-1_liQ zP}!a%7SMnn7*7)_QW|Eo2a9jG;mj#9pFGO&5|VoDvzQ;cVa3uRQ{x^e(!m@O=ILf$ z>hQkz(?ahHWL2n&Q@~*uFas5ysc~R}AEru{hgLjHnq})`@ZxhY7c~|%ff9NF74AV6 zXVdaiKm6SX#*(Zh?m-_c!4jU%9_8>HAOWT<3q!@<urkZRIAO!fJ^x|iGygCg0HR+% zbp#6<Jcuyix_`M|{bP6Up1q0o{{5qfF{8$f96Nga2r{I|kt9o+Jc%-;%9Sir-uwRt zEK<vr?AS3x<!_z6e&=wpf)(qPv~&Mpo#F>Bnzg0YyeahtZXDC4*T8{0#}6s7T%1^$ zIu&alzkd8Y<vQmrZM3y))2fa3maW{mbnC)(8V#H^ez_p+>qkx+K~{@c{lg}$U%f-S z$XNsTHm=>ta^EK1M=BOzbmTgF{tP;_=+UG*`{R_$Uc%L^6NbZP50xj2_x#PgjXSsQ z-MoAI{%!JQOyC}CPF%><9yV;|a!PxJj1^d3oT5RKmQ@`;bmz`p6)P|+IA~ivaXQw? z)vjS<`yt*}FVnflR_oipk3YZu{r02r)5QljoRQO=H2>sN2_5_VBMl_G@B{x1RQydi z;W*=1MNcC8?9&-K9)1X7h$4<iVu>E|#fv$ut+*mK>G*R>BeY3GT#Yu~h+~dA;wYR< zJK9rIkmj(1nsTpU)6YNatn=JFn#^KLEShi<2`53tGR!cspfbrMoN$5*EuF;k3M$oT zM;3wSc(@@a^sMDpoN~@dXPtIlb4^-$p~K51`t&1>hn|7M&p)k%lFuc()RUK;jy{?e zo_LP44==FrLyn1>Zp!J0{8UqjKjE-QYC++Q`kFESa6-pR?EDC8tg_BZD{(#2YTQ4h zoZ=5QrV_NyOP=gvPc^6<i%Kra60=pAo*WBJR$28^jx?SP7+62Cz=Hn{F?UG{Zn)x( zOK!Mv;<?wBSp~Y`hMh@cpgeH2(vL6QFj{WD`sRt(UZn7{S*HRI3}QW~j8$sF2c`2* zER7^-T&)sMOmW2&+Z2;O8gI;T#~yzSa>yUE(;Op{+%xJy;q-G0C+d{5jzHn{gU+=5 z?35;GBX-sgDzTiC7llF(eP31kpmJ1)JCg&B8u82$$~4&cV$C>J5sh_K!(@VKIRt;r zX<+wQ`A^CUD~wIUoIJ#i$Zo$4cieK%O?TaP-;H<PdhgA5-*MkMYsCKi14$<SB*c$B znpA`7IXYweS=i+C1J*u4V~u%!P+5ZxIHQo#&pw=yXy7TD@T31uJfUpDBr%X>E_5{L z?79v)UW1K$iIby3Oh2cdeReqi2$P9T79Wp%^2+N5xU3OPWR69oc(P<c1BK&HES><S zbnYMW3>MH=!%n_a>IlOKFX^nQdq18W6%8@;>{Ci5!>j|%h2V@&{(aHZLyEniqa5Ay zUhX=>k72xGAiz7@I>KR(XR&P}7FnJJFNi@5Hm_E>%0(>f@jz3pBORQm2Zu6cKtUyj z6WoFmq+STAan$26=<oz6=21Hmy-OYW=tDi|VHIKogC4Xv13cJ4wR%X!DKM;4RrUf4 zQZR@g1Vmv9afiTeG(uDjRM-d$m8^f5Lnj$5qZ!XwE13WIsAAEp1|8_}4^xF>9UkP~ z6$jLhT<`)Nk>Xbqn}{c<NQEEc7{w@Z#-?_CZ#$@<$2sy;6>sz|AC};QKJ4MTq}=6? z=eh=^D1nU4RPl~jBnLmbF$v#w5qQGW1S%$o##qX7mcCIV@@ygv*{CRGS<ys2Mt4O7 zdSV&%xW*<q`A5BAWfzdh1+{Lc!*bN454_k1G5iP>XqXZnp-AO59)nCdt)(8q7zL(K zSU^$=EQ{1L+ltEZyMDwhW;=<QK<X*aexySkugMA{Ui2zj3Ur_ZEy)IP6;P7>;~tsd z#X9_vj&xw}Uja*Drs|=gaY(3tLNg{`GC>M@P;38Frql%~$kC0Y*vCTgLq|3$QHpYu zqiT90-~UL#57D91is~fThEOq%btFWl>R6IMEaH!T5aSlXxW!VP>I-T3f~mpq#ZvoG zn|};09jG`?Mj}?wu!?n-2W6v0mO+R6Jy0=;$Z0yk)|vRMg`+|n<UUSuiDU?sr#nl` zFgT%9{;hNzz5oV2N}-5&sKXdpu~6o`@t;%Jv8M(khvHJ>D|KLFWl2)fEp8!=U>IT& zpFjpEY+(y1tpZB6kVh|O@e5nTHcGGHgqJ}33QyR?A{VJhZ^sJU;9}60%ZnZWc~OpD z!3Y%<^`7nO(FjJ-RX^Ua5T*DLi%j4`9f1EC<%l*^vvYU?8g(59G5*0#I1m8|H8|bn zCM2P2kRucGz!YUIx(-eV!>AQuSuhY0iF|Zo7V+RkEOK!RYsl=LGMkpPu*$4gyrLPW zm<2o}afw$%q8Ps5t&)}`+z^YHV#F=(;GUt0PuznnnW%?-D=W=RRCl_XqtrQakqK6e zgL~T{QM)+Q4^rSXr9&eII{Z<F7=$1Mkl=^6hGtB3!~(Eyy)VJQu?|vj!ym-(#VZ<d z3RCo=Av-2ZI?NGKet2h4o$1awtmPT(I9Q(R;71=`L5yCo0u`U|MKL@K;t>ma&^Rh_ z@;25Sdqg7<x%dY!G@%amIoFiD$VLA#X$%>+IPMj-aD_0^u^njoSadZLh9v3{jG*an zKNccJIg%^{Az&h~PzJ|77-2#ym$GJw%S0n|aSB@G1JCIQ52oPE8JT*m$2~>|cn8!S z4|ONbglxo1{y~gk-~tz)@WdxnWsyJ=dfeo`%|nNSL4QP#L8Q<GF*pI)Kuua5%3{<p z|2QcN(QqHRAO$X}vDbkGMsdS<BsLv|CwlM$3J{1j7V@!<TSUcbfpm+cl!=-b>snJv z>kdEek!`Rzf)>OWi^(0g@y`6^eag{EPO{C4UwGmbf40bwCIZ%S>wM=QF|-A3v)f>} z0ux~n2s-2q*WHE1h2hk6KcN57Z&)zSyX&OfDdyvigWt)M<FLglz77vLXu=*U)jFQm zQYlEJ!**5PIEdEtadNz35~i?4E-)jEd#H)8DW4o8qG6BUr9&qV;l`s!@d{udmFJ9a z{6@-p!FB9b8jpAcDipjOzLQiM>v$hJ=rc4qac&<sW`rw_(K|Iidtjtz1Q6c~<!cPy z=<}#VC93gs*w+Ut^H9(}Wa@SkWojU|(1a#LA&-(1s-fJ|e9BMxFn98^s5!ZXPiDSu zaXWtd<@UK5*UgDqu)-|SAj>&B#WT-uls^_q%VS8-4_=(&6tLJuImqH{MXqyl@8bua z$oEawa1F#D4fRk&w&4E{R5Ni_;ePv&3A>;UY!`eZf)#-A3ar2ixo{?=CxHB*2>|0} z6Br`rpe?abHVlLi3t<oRAPk=135wTSw!wWfC}`eSMm2F5jj#^f01K|*3a<bT4Hh|& zBPisMU-0uS#*~EU;tiPsA!Xtfx*$@M^);RmV^y;+;IbBH#}*Y=a+HJy^Pp6X0u}zj z3y=_jR5yVL)DO$x39L{H)!;bNKn#x&KOQIy&DVBThCrH-7{8M;zf%zQkW^d|6oWGn zGDw4qC{`G=MzZu0yf7PwV|}&238#<?_tRjILv6VL3qW&k)nyIrgBA6V3#gz8q#$g) zLl%xx8m|~<>oEU+`_L3x*L2=s4bqSf@Sq5splIZ^Kj$C}Y2YrfXpG1B8K^T1Z&(X^ zAq{!KKMIBkyP${2XpOL_4%!oVEHWxPkqfSXc#Fq~<491DXGZKGd7SVG{{S;(QxCCV z3%$@K$^s4CMHUMtGo(-tPFOSCaSo!RC0o)6vCs>>a2@v`9@qGagmei~aTk;Uk<n0b za={P!U<r$m7|;M0{O}06uo(&olAm#Z!=MSHkPTw7L~h|i)}Rg_$P*z6lb|6Mj4%)8 z;3D>D5CTCESph)|0*($5gXAcbXk?Bz2oYm54)!2X#fFGY^$WkS3z>ijlW<@jWR<bd z1>E34vB3Y8Tf!xc5D&k=3iEIa*AO#Q6exR0FbL!`v}lXrv=-K7UIo|-VqgpZ;0yb} z3B%A_!N)W8a0;X#4BXL2Y0-XeVHKx956)H^eE2St^H=_WIx8ZG;gAmYKn|{O3b)`Y zL+P1iWP@lFJ^N4y+%<Uov{^BuG5rt>!5|IuPz&(@55E8pwJ8d{AP=-qo3vmH_d*`( zFcDe78Q`F6lM@Tq#DKRrC*Wcs!N3m)f(G=!LVbB(9Ws1+NeaWjffw>9_3#XUg>)h) zB7xD8w}67Aay<`q4yTX_;6_HD37^MPl;;>duaF5U@+$-pPch>vyJZovunX+a4+0ty zp?3dH&PQ1g@(IPHoRA_Z(V&a)00(054}k$9YMDEZLl&N(3Bqs{j`b+xgklFOp5tjs z%Ww+Y$Vy2<46>nkK@w2$DWkL!nrP$?FF_0obPzg;5H4~m;gDQFp%`sOimvFF1fmX^ za29XbpmJg%g*6YR&<dsSao~WUl@%DMg9@Yo3)Wyc(IA%<S10wb44hCcCAu{Gpbn={ z4Jyi`t-+(P(GR@93vK#aGm59MGM{IJgSkLGEHXlaw@-st7Ck0vMR=s2LJH_GSD2O` zQXv)m_6hwk537(^|4<CJMp-;V45NSvCZrdb^FLg9erP%({O}B?AXMkcA`GNYk|+O* zlhA0dqKJ8Ft2MHxW>i58kqd{@8WA-@z>*HPcA%kAgfR(=-O)3;U~g98SdMBR#6S+h za60=S4fpU1p+E`yU=MJHte}w<%(M&Xpi=86G<%^5xlpX%8j{l%gnr1X4TKH;un&+h z8)9^;`D!aQYNIw`6SpuM3KLPWp|0$Tto*Q-`;ckk6pF|+S9|eSV&OPJ$Pe$(3cOIE zJB6%@p$VT_4#e<BE~FGK$qNyfDF(Z-yzmM}vPuNej>OOix1c1op|3T|Jp39<HSrRs z$VH?wLiV66rE03CG!LAx4;LaS%bA7b5+{2B7FnS*z@RGe&<eA#5B^}K&UOEPuYd`> zfD~A`wB`a1^pFX*hM{X{O7A9AEh|TD7)B3Kt2QgQD&Y_4Mo<xhj_d%iIw5@uQEcV# zFlTFJBp3_2a1N^mt@ZIu?sEz26CxYp3+7O%tq>2GI&D{qsDeT>;Am@A@vP)C51=Es zM@oXEuna27wgjOXq<{+bpd@n(yDp(denY!{lPkiY2E-6TEHW0Ppbrr^wB#TbnlKFe z(@A35bXM^g{4ffQ+iWA~IPCBX?{EpOI~1g5BGJYf{oo9GkPDsDD9HOqP74cEXsY9B z54ykz|G*FXl)41*BFq#$%~8AcYrpr4zxk`b`wKF;Dog%AGVG8Gjd1^DnY9`NF|P); z4n``T2viM_P)rTmq>@Aq;=l=us&OF_i|SypCOEpCVGqN=2-(m%yQiGd;*uzLzG=z{ z2=l%M5iGX#5V1?cBjLZYR1-t;4`#s*K1&V{0}cdKq6p-P^YJ=~yBB@23l(Z2KPI*7 zpgLCD51RTtJEgg#ARqIAxEv)FE%v-CJf3s9j-&FXsS9e5ur@bW!)weDJ;J|lEHZ7g z5bMwgu%IM;yQ4~KvZHHJlY<(UhQ!yv59}!x;kh)4<O}RT53QgG`2Z8nmbpdP4;@<% z;E+kqy2V%%4f}vTfP%T_%NJdR#|^Zq5tSrlL#uGC%B#%Et?d8Ga&yB1wOhI12GCG8 z#pW9902XU^sBV`nm{`e7`a;MnJLtd(qaYTae4&}*IOrt@q@Z`iS;gF8N~GWl{7_8T zWFg}FLTE>SBnrkFEW93g4r}|u1|dATu#P#$#%vtR1GNzIfC-au#{#iWJSq^LAZZO; z4&9&$Q30(I8Gj9hnaZp~<+l&E2M&5C#G1<wg%At=2c~jqUHx+ndbtcj8_rdX6{iqX zqnx_f<EP=)&L#cMvMhQ1kPM>`48DpG!s9d4`Fzj72&d#iVQVf~w-=p?3Am@ixYHfL zPz?R>3un*^y)tcn)d=&zsBuZr+l<rTat^#O3X#Ug4XpnyyaLi8?GL$N2UnYDC0)ZO zJy19}49>6%*weS`Ko6pevd72|^l%C@#6-!9i?$P$DN;om3z8lJ3@hjek01_ALbP2_ zO~_eY6df7ed>1GTFr?>-Z_Td#APgUL&Z{9jyD$pEBi3t7)&w;qlw%eVfhwbtHk?qh zlKqM#XcmvubaQnLiJ=UPpbJ4b6zpTL-LW9Qpa`CTkkNn!$Y9fLffveYUER=PoT%F0 zx(}Lw4iR<PJ<1Sj0Kje2*|7WB0~Haw#R=o3B&L!_ZcVz1vkRYxZ+?`E<xr-e0CCoN zEeGTo#fZ(0U<v%t2;~j3;G&!r_f2IXS?|5kZ@2#@9UTn%<i42wqdAF>GQ(XBek#(? z)g~CD*KM=eEl?4053lkM-^mGWx{dq*Bg?SIeMh*$;24j!yeO&(x-b?1en;H_eCSXN z*uW3HfCRJP4@v>Z(CVcfYO(>o%-=&fYZFliekwdVI9jC|@PZi9(Bw}JFWBQ@46)Aa zOyPNI;j{#!Kw=T!iD!fu4)-7o;F+k<;M`5Iuuc>%(xBd_;0n$l5FPT<>eM}^<O%Um z31O%X$eEl?dJX5G42NXUE6g*opw(n7PZkjlz@Uq<V9f`H3Wk6Pl5Pl;Zt0U?2<fVs zKFFC<vRiF)5AUflR}P<99#%`DRR~)ogqZ)X8ojBe1PzVwrI3NV#B8O~Fbr<)4CSC^ z`#iY+xV^maApH<_YZI4xA;B>8MCza@G7aQzh80kU>UG;Kq@W9tpawH{4Dk>T@}Lc3 zC@tYG?&^RJ!@%v_K4qG~1?h7O_ONbR6~LqppEyfyAm$I1{j}$x2^`|frc@1>@OhDx zA9-R8(U2+7FlDZw4BU0qchnDc%nwbq5Bd-at)LyiI9;2Z3(VTkKyIR0@eh*#4)tIq zhY$#{(CrGh9qJ$vF|*gCF>PVKBnT-}{jdq~fC`atES^9Q@17I#E|jJ&TpFVesE`S@ zg|WO&AUrjM-s5COD}b6~4fTK>Q;q)$jo=FP<?3tL4`fRZN;D3)01VVH3ySaycv&@c z<)xg^4O<`JnNkib77W?|3to^3`mhTpc~9#wO3>bR=|mdpzzK@C57RIW*KQX4ux>w( za}y5qJLiZr2%`~U5$pgBr_cqi@C?zgVlS_~llCc^V8kF=HN!^?-#H3zet&zNe@99{ z>97oq@U{BmQQ2w<`w$MdphN&DjGFM0gC2a2^Kk{px|)y)(|`%*fDQMc4!3=|MB4O{ zqjD$258RMS;I<RhkX@5-3W+=;qyG4eC-fl}5ksQOkl+em5)1UOBvb?+eh-tMf(hi{ zE!{8<9w!aY5DS<<3ZnoJyr}>6QzwnwIdtgAEo9ix;X{ZKBd*i5t6ns48OM!_25n!x zS?^BSix$lqG;7v2Zp_%yWlL-PG&$o(E}=x6IdwivSgv2cVWeQWf|YC`zg)}89Xy9K z;mw^96Q1iAi<3We>ePj^XU`wKWRpC78u#y?zja;Ju4UWS?OV8U<<6yB*X~`sdG+q) z`}W>HV3GO`CS3R~J9g{-c|x~N8!SwuPUWf=%-%hInQNZo{M7Sjbeze7Ll-TULUsIz z4dX>hQ>IhQ>aAPHPg+yZxpnX64VqlJQ^NLnyLQdx#$eXO#cS1y_RoI&QiAjL@@2_= zu{8B#*xUQ}-UtcSLk0iI)vkFq$(=+O>(siYHo?!|jWE-&b>XyX4QK8wKVEq8Bo?#& zVaG586I5_P1{-wnufQCXaKg9DLTn#T)VXKFeDp!35m!hVMVr-v`DerEG*fX!b^6)x zA8AMtMwd}CaU~N@^3et}?jWM?N8ZSh#vW7%QHPjoyit<4YgD3#o?DE`XO>pr$>d5` zz=>u_F1z%`8Vqw$XCWZVe9Fgu%83OPqNX_~9BHDtW}}!~8HJsC$TagiJr&}o8$j#{ zN5B2}Q^y~F_Bn-@Q+%<I9e*g4bW%zywe&K;1iN%o!Zt+gA5=K`C!BO5_2(acve5?@ zL?*G*6{4uQWtjifZdqoTS#8aQ7hO!DB@<lssN<M?rlH54pVZ+DA)fYhmYja5Ic1-5 ztkbAkaK^C)9Dd?~1BMVFKw_WbtaS;Reimg%8mOEFk~40PwCa*((BY>vmSExs7E<8r z(_QeW640JP_e(Y$#m*6i6HW*;&>T)9mUv={F^#ZdjN|f@oqiVM#T;z-8`Pf{Q57bi zeCRo))k#`*Igpk;sb?OPr}6Ngby_S39HyjFC@P?VR)-W`(An19mXN!pA4-HUBZM;6 zA!eNF%=KoUT&9I8Xs&(ajGum>IYq{K#w;mcm#*2@m34UT`fbkk*+-#%ILRgFf(s7E zn1A}=2A2O!Ug;R(j0-pXaJ|^c6miDYLTsHzt`U^bLI>rF9dp(}baO-t+}s><KJ}#$ zen{&KVAOqs_LN4_+15+gtAmE0L1M7IjB>DnhUz7Y+o(x?NXezg)aP61r(8&pu^w=m zjJ@}LNx6r#;=PkQp?%JoWVWsH)+!zT%t`bVRBo}barDzaT=9$5FZ@$%Gyz|obmlLV zpzqVMeE<Cm?uVF6jHw*eBjC^akqLU#!*{%Uo;ON@j!Y1N2v8_PCF0SKTZ}`2Nn+AC z)NzSez~^)Y%+2wT0*X-x;~a7F1_PfL6MpqbJ|z5%+?G|9Q;f=c-b;t(qyY<9ILbio zBVzv%D+M7<88Ku3u*yHMQNJDLZyiwVhy7ZV4uVYae*yd#4WE@RWz+*(NVCqI#zBvH z%wr$$2n8kT5e{Nxt0ms32QM<QkA;lTiwTiNbY3xv6e=VbRofC7n-{%%#AlDXISM0) z(T_nzk$&|{2R7Exk6dWN6OQu7ft2`3P!<M>p`;k*{*eh!{G%9>G#LI^*&+arX_01X z2vRW7ye%=QIJ@NKE|pZAlK8?G=cva!LJ<pg$Y~?hIS1)(GRvFr;~%-WL<(y%NGAQV zm%RKXA{7ZuJspJ?oDkG2TZBJsL@F1YxJ5W{MoM_bvo4w9Ts`f1PkiQ6pZnxzKmGst z&&{#p9_nBOFZ_XxWSR4o{fLJAW(Z9nk%J$x$c53e*}&(~V;sH!Mz=yyihk&>h36QB zI1~cW;}K&Nnh-`!qOp;ZV6;mxlpby%>X|(DLlgAKk1H3d4s6)tAD=*lG|ti$fF@O` zOJ!<Po%&R$M)jYgl;@`Y;-7vnVj1@cnL>A%&=yhVUR}H?Z>RzbPN>5gN-`wUs&lq+ z+yWc=m_;a#VUJrtkP-bb$SgS%omeme7fm5X3(?kAeeug4-z;l1xsk)JdUZe8_y;%| zaSNepuBw}rCsjFXsZO5g6vv{RWW868f1F|%vTW>p_<;#}T&p<R+-7Y#Sd#x;T7w?y zV2&l!!HY($1CI|aVD`#!4`(of6!lPzHfd|yUjDK@vET<nT6-pmo?>aHEfhliaf(dv zZ5{VO%xBGO#KoPrQlZ@kCwx*`?(RpLMC0pqy#p;&kivC_MJ!^GLyUURqpqXyhcpaA zTmtry9-0_MHcIz8>h#xI(eNf&Q7X}4XacARi*GoBS`9ViVu<P`ar)9*Vo7}}UG)$Y zSmWEGdQf+6_T9}<G+_-fu4J|{<?%*tu?~4q=^g(t2G6WZz~fO97NN05E_wXC*`6a7 z!eFg^bIOTj*u#=9-b!swp^4D>2gPH?m}ki>A%FO%9*x*Xez?q^dsP3U5&g&$f@$m- zR9x$@5+<WHq`ZfI&;uTdhzDS<S3DDH0v6-ohx6E4H9o&YgPKqXyYB3#WsC&A+zm%R z{1FR>LF&w-wkkcPdTLasnx8^NN1hMrQ`3gy9`(osIfi>_>_UqZD&*jEq5JDy!jvD& zXaqHEvkvA^LMxU|9XZzFj7-2nfm3rKu%W9>4RWF$OR=yQ8v>PmWI`HvGgP6V=)Fiz z(jVvWgi#fD7FEYv-t(q+y#Z=wQai{${P2W`Dd%EICX2F@sma?6z7uKiV;Gq*nwFgW zWZ1>DI$+{OALg+RaukDI`>3lhVDuExa7{E>(GE@43h^f!haUguz{EHX{&I(e{I`PB z%1;Qz5B=0{(|S{fPv+5vSKv&bYB5W`jjkYkA6-G8y2l|PYemUY)@}vIHADKS30|DT zIFTk})nX!yOo+oa{E%BQu(1z$w4xMf0mnX;f>S%^njBi;7drNFG_JSx8uiHZjAuz! zo{Ym2kkpS?{Lv44Am-inpbc#xrFc<y<sbDpgfehO8>MF+K}pv<g8W0!SGc*u{a6Mn z3J!DB*OD8Q=1ATr+&tj9Co>O~8!(J9k3q`=Fz4|5&zypeKJtPQ!mwzBUElTWpn|Wd z*U8qpvo&;piXMu;#VcMh4pfN36t>ueD0;z*U4$POpfLYM`O7bgT;$>v=0k-q-W@5- zcV7N?;r#pu6WVF=0%tqVn~SBk*KR8-hNueavWBfYzLvlUCE<rtI0d`=jduANaOj74 z2!&4I2XpAC-U||Pn5InFhP$I01VkF+pfK%NzPQ^XrU0830S8p@gj4v1O&E$v_yk_a z1vHumeVB&?N}vEsBOpwpT<`=>cm-q_1x45dUwDO2`3J^Z3$xe|`<p_Gi3EGQLM%+G zPZ<VAs0Sx%5y?sid(ebss0mz)CQjf6>hLvdtF5<cJ4gtia$q*>;tXs^IDY6je>jK$ z^u2x%5#BQnHf%#+)24a|4l|6v0wNQeI0qKQq*wpwg-+lFP2hw^*g<;WhkN)5e!vC~ z^TcupMNu5Za_}&IxTHW6hjCzqNq7ZNAfHzV9kYlO!^=WjyhU8BxB8<(zEHe>up?CX zhwd>ao%=NEO2L~tie=ygav4FF_!4vgAW-Os-dKpT!-jguhftV>km9{=GYEo$gnb|e zjBv)bx*AU4nL|@Sn}8%tLWNo|1?3Tjd58&nm<)`Q25`WQuJOI4K&?~g2H|?aS^x$0 zTRczVMfuxBh1`qKDhHw}27drUR;nU(SciHTJjS{%A?XKHI0e-(N9u@%ewYSH5C$y^ z2k@vpa}YE_1B@B!lZ7Y;SdoruS&1<c$vOX0m{BN)jchjc_$$78g?s=ZmJ$c%(noNB zhI-hAQ%DCzER*i|8chf~v#73D@C4;?zoKi%&O0%$ER0T498X{bo{B7U^2nHAKGe&q zT-YE4oH*X&gi+WBWr+&USc(a(z)sK#V6evF`i;8b1=V<|oYcu@yc$MHB({t>M_e{x zXh2wa1~sY)X=svb;XC<Z7Wpu^XHtldAOw^w2h8&ae)uC$c!g*v5XVW#utYJie9ik~ zynjFkOu#IE&<|Mio=>}l(`!twNeFsauEWf`XdngvxrAMqJ-9iCIRqO$j2pSB2fi8w zWk82+K+LuphjY+`Vfan9<eBJ@hFAZ<1y_iLVHk&fFfiw_77dDpGW0!|+nRpR2TV98 z{Bfs#7zajan68vfGGj;p#fy7TjDMI1O%O5Biz3<}22H@Y=W8u!p~QYTIcwt*UeXqu z&<<gM&^}}&Tib_X;5~T=g;nSWcJM~&XoOuj2V!Wl-XTO8-Lc{T6HcIqw`(>>w1;xY z8duPTVW<ama5y$pl9K3#1KI`ds2;0RhiX8Dycrb#xQBW8GG1W1@*2?dicKxui^o$O zX$Tdgf~5W<h)xR!O<<NgqYA7;hXaf>ZAmy@xCH%L(hd9(zyyYtoCQMj2Vg*lYCr>K zu*p5s&a}ZAO`tl|am0QI23P;k1X7@eaR5GWAjd*|i59AdVK6-;o5^#qhh4~oQSqse zvZQ}F2P;(^r0P=65>QsH3&nZ2SI`7kpe*=GD0f<uC8aTF(S&)(7L?->3R?zG7zJlo zhm+DHGm)E|sz69UhkIxQ!i0uwaiL%h*5W{i1|*(65t4lXn_I97PB1oHaxNajh;7)b zTkBK?90qfUB7~{UFUy5kRlHY)CnU;6ecji4vIqZIj08oLGSv!xXaq+4P!c+dthtC@ z!>E+_l4wAOde8(+$cEbJD@5y=gj<JI2!&BtxoVh>hP_slYZ7wEvpc1a0py2U5QR># zh<*SEm8hCv#ST}<1x5d5Qd_GV7K6IV@icA4I<t^Pc;i>2J=!aD)q9-_&iNF6OHi}$ z9;s74gk8kB8$xt|G{kB$iH!wTfQ4_xSQ;w3Pql?qm<4bshHhXULnXm;pipGwKxpB& zQK*GwNQf`dTH}<7SdgJkbwp^(9E!XjEYgbFM1@aq6wIN;r8Od@ZCtpZMOyq<MPaFM zKnwpN2TsV@WRxgS)4Gw3(Iqj!(uoBd0S5?;%HoRFiYf&{TL)j5S&}W;CTXu`;D;Q= zQ?SV|)lvvKF{2&3*4jM<X!sec6_Rz}1XRe)oY~F&=(K-$1yo={oMBwZRiDSbUZzb9 zvrrWG0EWKVig5opMfBW^_yEqFDA;+Z2fVWmI`OmN-~?9Cg=Ik2=R@CblPE^egmI+6 zHp0<3N}A#vK?jNkG2&l?;}%TH1XlP?EvXJj(_20(2~FKx{QV74M2EUT$#bf?!mYWV zK&@~<h4%Xg&{>Nt)!xF%UKNhqt}rDh%p_OP)4nMOb?An)O4&u~$V^xUwsqf)U@nD| zUsynwL}W)k`Uh5!1b(20j$kxn>f1}zNoe#0Sirae;uCUUE=+=zGGyN=KE7+%hhe~k zaHv}2IS6}62-D<*N-74kgJWYD6l}l-W4L2u00zn;hJJgLb#ToVE;B9-<ivqIvv>tl zV1>k04152WI&Zw+3nml6gQ=1zr0JL&YcO3`n1;FSnMi&Jq?neJKn`EvhZ22<JAT-Q zn_Xco32T6$S5}XmaKwMO1yBHmyFG`sT0>TjI0Ifr`Gh&Qk)|{WhG0MkPVj_Dumw|C zg;}tLRagaEz=dNt23nYfXPyO7poLp_K|qKEqw*ZIAmoZ+VRBvzL}^W51dLq(BwoOV zVBmxvIkIn~Ax!dw<}$46$P8k51zKPQqREVt3XLP%;d0oAG+5u1Fphethg&FyaaaXH zvxnFn;1RqAh1rgR_KyD{g`3?6Ey2k!cD=o;hGUG|8j~mu{)dHl1w#O$QkVrG8W2+W z)*1gJJGuGRd$E^qB?c1Cg;h8Mtc!$KFosV-i?raJbDk7)UTV2$!ph18Kx%~H!Hmz` zBY{a&l-Ng{BL-N|1XiepT!0pCl~8gxg=Pprk#3Slsz67e2XpX+WxA-@tx<lsk6qP` zxM5Ub(1chJ(p~OlnJNx?fFNGTYw)lMP2?-`oCI1h1zaEnR2T-kV>Gad1yWeP1H%ch z8K`v_PW1EyP@sjxeK(xB2dADC_DQ1DE{s1mP=CmUV{inacm-lWEzKBG{N=r2psvh- zhFtgrR-lAYSk9mL<eU%<qZ)<#L=rE7DPqV(V;Tu<vDVqej!Z&9i6ACvxQ7LE1tI@^ zIEfQ%*s<$OP*R}bJ!z5#K1Ky*c1j<XD3Gq?l)$k}DBkYynPpj_a$vw<TnA}rhEWiT zPxzESmcrI%kkwA`1v!vICWUIC1yLCASGdd`s*N=s4Gp(2hu|4|(Tt9H(p*4<f2M?Z zcm)kk6GlX78gj&}A%|*FK<lWEVDJUr3WZjX26N~Ji;lFINKnoN4F&duOqd4gPzjOl z@r#yOei((r4nQHvi~@TFPQV3Ln2dUm8{5E$UUP|vHC+JDV(?fBvXcZ?$W5Uthw=o4 zb}PEHVDJSQWH`@@EPWh*@C42Ahkm97TEGQeAi`T924WbJOWMR0IrPlHJk|fW1!%}h zPPhb7I1j;r4q0aLS>gvi(1&x#h*j<q<NyYGa9wy%2Vm%iZa9h8K{+M|FX7_0+~ACR z$c0S!*t>JM1)6K}_7c0sy0XS8dx4QxU<FJV1zjKpgt)u<9%buRl9<Q@Dzo&@02^NT zgnNjjqvC~F7?1*a^EvMnIq&vf{D)y6C(?vJd+6s}_ys=y1%_dmBIE@|Cx$?0bnD|3 z-HSg{{~rf%j9ttw?sJ>XUAf=MZ5xvNJtWN~my|}xrL@icey!Znh9Xo*MO3!AC21}x zCCw!XmE2Na<+tCTaL)GmJkEKa&+GXTI24ZZB4>H?2qd*x+C@BAw2Lk|A(5Jr>3>v1 z;F403Te|IV*2@Q=)MBDuFeHMz=&pjTzGj`=ShG7k^vJM5{>o++sh>|K^O)Lm-{F2x z$YDrc<^}sqcb<(cx!<P`Ds%13v*JkzRlzI|AyB`GO^@zPNr@&H?i}fH-fhd|N7fsz z>he^KXFT#y4X&5eX1Vq<<3t6>r!C`DTSoXJ0e?tbOIGIdcQy~${Lwmd`uq8it2ft$ zrX6mLJyGC4l9;Alk$z$C2K(~&3KOn<oCVIvg(w-F<UB2V8Glv)?QEZUQdx9K_oSN% zuqZnbr94xp_U_srw=7OpT-SA1$6NQv51O3Oz7@96-yzmM$<Ox^-dG7y7C^>!sF86~ znn#vjy45SD*n^d<!6PMq6~*oir$@j0`fx}q4h3>jg9Q%y$ckrqfhj03Mbxdp#D7=$ zw;YL<<-hin;Hc+u@Gc`3e74_pUp{=_j=wrMG2>JsKleVx70+-UUb2#@PH8h(7}7%i zkip5vxpMf)oQ2PC4o7}v3OlX5fK~Vo=Kubq`jb1<Tw4zsZHiGGDnwgRh16q}UX-d3 zxIJiJm0n)cI>pR~l*#qPAH+ufIqo9o8vl3d=i+0nldkb!3l(6E2D9$9pA#g!CC379 zNAI(PUNy%betR$QIn@?4R@>;g(o1)4N%;0Y>MeWj4@f(`7-dh^ER!hs_C98@_1g#W zmQxmY|J$V>IsSdF$z^BEFXiP$z0V`pKKd^<<{Y<*-2X$#8yNArM_a73?E#M6|NOFL zEk=5%NcP+NCF<@$4@gV0-L=5&um79F=w@H$#8L+kez^1Ws|!y@t~yOt`n3^l|17<n zvq_Qk^WT0pCZBX=f%Veqe(L3+6!qgBMcP*^|CaoF_m{A<ddehzjrmvXDj6W+>t*uK zE8g1|s`rlL^LHtB#B{OKr}9+)_5(qF-F|C;!Rjni`t;jSi9D5Ed%~E{K6w&hQB~Z5 zFnOEpOD{04%cu<Not<<wtRZ(eh85q*tS_i6nHW8rL*MeW>YrsoRG*eJbItkRuwI*f zA&O6_zlnR~>52P2#dUN@rFq(qE2vINkHz#$tVF!GZ&)n1dU{$dzA_cIeb<@>GrBzC zcaxr#kbcu4`#|q~Q@zTuDX_ur_Ho*+>$`D8Dm?c6*WCYVCS6rVY7Fa3B7cj+tTr(2 zc2cCyScOo-M*?GdH39WBpC$V(gh451;`IqmjsN;-rA>VYeNN(npmrriRH}W@16cTQ zB?92+womKISFIi0bkyk0uOGAAAt%Gmtl0s^%qunYt8-V10fh!D4Xkfg5A!z#t@>s= z@>I$LHdTzC?NJMAQeDyuEbgO9KdP4Gw-2IDIf>+`-t5&w+e*;0+=q)w%_mZn>udDt z_b99!*9xXN(duu+nX8S)7aU})Scx47-Dy6#PBuaGq^p_!uLsWRS7#>>28&3!b5<2y zRE4KK2fKt^m5=N70aK^a<Q~0KDhxrWT<_C^ndv<`{OAL*$NRO~ipJK6($BLUj{0A? zS!<L2re(=-GK6Ix{%c_uVb<#$oUK}=7M!E`XnzxGerwd@nDV1-DpX-ceCya?c0M*+ z+)nmq#_IXjAh1GapVsg|R4e7@;epZ0Bf}ZZvpshIG*){ySkG-Ht=xg{Pmy(p%)O~w z3$lNYFO?HqRaV?8uAP_~i*PoWMk>Ct?5qiTY4+K->~i5W?Si28vUQR8{Z$ebV)4ZW z@X&B-^Z7NyL-0khqLqQO6OXMPpS^$OtoxYvARXdZ!6*5`?M=|LtZVVdR4ArTfNukE zxmU;snK4z?8R}<wp@H0!gNxSmq|K$GWNU!L<zgFEA7L#|6TFa}4qlwOkzu$r4=c7O zpqRuALw;s_TZ-Iz#4n)DEE5&=ZXVvak#i+KD^dMOr9{ulK=JmX{Jrb}t74}4a%3+0 zNhw<9F}|>Mpe{<<3)4I(oS(W>FA`y$**0+zM`EXmy_^{_9gZpTtf9&;Rw&99G)O<z z$O>;|52+>cR@$ksHNR~R{=*9tc#^2GaTU&{b+@iLIfSJ}wA)!kdm`|cS|o*Q1`pHR z3u&^zGk=K#%43W?d}6S8%exGnPTgFmVkXiDY=e<50hzJqp~up1VEKM#S|l={2gE(< z8b8iiWqJ&(jKV<%P5GpHsdCGE3-w*YV;7&5$^AoNuVlyCRmj<k&iaPP%-GAsO(}|A znQ>J7EutCu|A_lLehVgVSIiVawzBD{>AzzZuQynty_}<=f~)o~Yz`mq=I|dbbuUUT z#>*tTE6aV{yslxpC|(iaWZBFpa`Y9UG&<edonu<Yt*?vM>}4pkX^7y67w4yaS7Y~Z zLUb3ZNawJv7JI(vMv{V%9}zE!!e-xBsT01!CP+6Ev+k#gClvUmN%w9D*y#MMKCgy@ z77}d^uh0Oe`V`EiK94=)^GP&l2U)%E%ez8k)&A<8GV5}$+S}1j?)-X?rAnm0??2Ui zfOGUVfNvGLZQ$j`--8atxfiCK&X8Rt1Lfjk{9ZA4&&^?c!gk%QLZ?Dx7m#-OIx;8P zVoJ}mIX0RB?a=7;H1w?XSFK^XH0Pd(?0=l0!}ef7_hCiJzoY@RnrqTi`5{kUTH7k7 zwnKbF2{Kivqh_>mu>6yGL}o-krjL_l16Dv%?fWnN<pFB<GmsI^QJ5*B4X$5Y*e8M_ zl&T}}&N+zRn-fJ`+j=V)f;zptH)Q$8TF9Z2(4KeI&kzWh8J-)xT8WuHA9UD+#Ltra zn|)L*Y`h?TC0OTf&2@u-DbTsUtpj+p>?gOF9RH~_^qVH2#X<VGV<are&}~aSI8!&r zg%jMpxB@ipXTXxd`StE01+jY)(k|r-lHI;q7EjvqlZXnEJJ~{?g3si-6EC8K#X(ka zluV~ytWY%42K$c(Y^|gqOtdGUr5R3Pg3QXmVZ7|KCz<=no=BVRWf7JepOh>e?5txW zs^l~;^kB$>K`?BQyXA627B9QoH<%6CzFA$ofL<W9Z_f=w&ixjqFwsWsdFR%H{`)NP zuHvY=&JZ+(6nU=GJ<AY7FNjkck{Oyadi?k)qc6i)vYsbHXSIDvc~Vg_zv<|iXCJ=_ zO=MqP+>>$(VL*;6)l2ViHcNZP3(mxa$kY#ilBEC-P!gZ{M5~%?^@dAMq}HcM7FTGQ zD#V2bvP0w#zH?WXK&E==JR%3&FYge&X|BYC2b%ET-f1~Sn595ZMc5dE&Su-_Fkso% z8&uq7fYc={Q#3lhS=(v5{`D8jgC>w--Oro;qQmmN!!L4@K4RWGy%qmcF`iei@!|QU zM2XYL0n2|S3duW*KCHxVXP^E%akJJ(vh>|R4e$3K(d;zocH+ek{-eiyHWj7YQT=M0 zKP9z4S^S(ufmCW4(dzY|wI?rUs07Rlo?KCUJZp0Cc@M7Oaz9>@W?*Z+-MVy|233s) z1F+J(*%~_3C6xmLR**Lvuf&8#H-%ySwK(PnPV)$W-C9Zu&s%Nw4p5Ur5zf`2>NJUd z)pIwz)Nuat@3X$rRY-?hv_P>G1A^$^HrVf%=l^ZhTm9W$0BPILPX%@VJ=e@Dq;2C~ z^tx_Aey47CnvG-cJ$LS**>&0wtXB9G`<UkWgfG8k%1Wp;blbBK&aZrc+5WH^2X8bw zv#cBl(vwnnksZ2@@Y&!~<yu^%*=I8+7c^&%4N%qF7#d3~mN%e!fDc3FMeXw{qWrN< zypsHQdS$@3s{vSkyhJFa{_|UI-@1?T_^p{)88XHAE05{JKJf`}rJDCU?fg42^ODV3 zR%hRtkeC*3xxb`_tw?+xf6LySym645?x3>bcZP=;#wEPs0IK$cTDI?Dn|>V<_2Hh6 zT-dedsWg>*ra?r_#~8r%7(Z(|{w-JvV4J2z#PdZ<8J`V=jj_xP7F6r1mCdGpkpX%A zd@5wTUJc7KVnHP~P;ny7u%D^&e^`%N^H9NJ3ZSiomuTXxn?Ymtc}L=LB4cy9xw4W< z^p}^frhbz|b&hQ$iK5aON@BceC+R|+eW-l^>RI}DQi#bl8|Qt%-zBP5+|6GZEHfuQ z3m)%3j1cpY#ZYHCt~^(8cE*xtA?^kXy$jG(qiP!9^+#ts=z|vinWq{MR{eZRn99;5 zPH7CwyqKw11H?T99`tkxSXp!RNjzWG2f+l6{es-<Q9t!-6)JsHy}b;TQl-Agnus>0 z7MoB;;j^I4S=Qhc!2SySi*#P)x+ID;cpf<&NH=6Q7*d5Tt1#IC*iak_{BA>vDzn`O z+h?O9POrr+5_1;q6X%cT-a2*`WwDJLY6!W@3-*4IC$sEiRl~N_5OKvSoxphihXbhJ zaI{$hh}1AlOvLU^DWBRGI9H5UDVG5x6Z=l$xxbJJajBg)5Xs<Es-W`W3D--O!Ymb( zmk3ru0ChL#W%Ww?IXPo%f(41C9!FJIOH+lX8I2N-{RAA^Xpotj!^*yQMf<;y<C9#% zxlhy{kd|vDO{DeBLa<KrUhoRxPHR-3ctH1<<T~g`{w@3T&+%uz998?sy?F*3Loa71 zN9{8#^1Z^lKFhegwZVyCGo8a~__%&&^2E!~0;X0!ORAVJ0!jGL9X>@8u{z6g`aG>? zvhY!}(j-x;;s#YI%qOUnrKQ8CHp;RLT~>(=107n?Uni)nQx6mInkxX)&}H+AFj#EC z<IdYUqX0t#fT0^#D@?N_;<Xo4&I3;u>fz;-=sFT~l7heZ6z&za(KQT*)@j6u@%s4i zzKW^Bl1|s2Z9E$KrQH9Ho$nW`cLlZ$%F@oZT8Yd(?~}<-#$^WZY0(qJO#zQL%md|6 z$j)$4E|)6ZhCR^a<0`8&O|OY#_V@a!N*I>q6y}R?vkh=cD|@D-TmeJHTl%ip@CDEv zR=b@;hb*XSL|LKk1q!_ROes@&8?UeS)~I+@$1Tl->sOjkVu1DEy3Z5>Z`IwQc>Y__ z1@b9|GGq)E>kDcyQ#eVTFW#2!!UNvxsI;VjuXbLM9scUh>Emhve0FT<B&}()8hp^y z7xObMk9Gm7{o_3U!r7w|{$%ux&D?YLEQ<}QmeO$@dxAyrYYj5sk8j?U>3J2oL8k(M zO_d5XRzdyj$xpm1`Q^bD27GD}X@iEr&tp|?y%*GU!>f)Gx%{W10@r`_SF-5iQ?6hd zb*dQ_AIhI#=|}JxZmKEvof!e%iVkCZd((V(kfEnHUvEgI-1SB-S)*y*;%<{7ml@)I zst<zuI|RR#OBZR=_zd>|t{a5w!MPSBs&vU$D)Hl!)31AizCHRlZyGRU!A(DTP5p7E z{+CpAYLBYBL^xc7Gk=$+y=OZecK6||GPaL;MoWWbL^RAM=m#)Q3zxUwoj6D11AadY z3R`jX0kr!n93JK3!!`3Aoa^5J+FTPflrU!s$Y(~V#_|dOX3$Sl<Ty<uz|V!rIECJ` zcLk|3iMW^D_b}ip_>#5At*Z!SRQx{zTTpXc;#>K(&zL3V!DK<j#cT5wE_e600owUg zg^U(<Vp?-HK(PX4x(+C+%u!OB!A*cI_|pQ?xjb!}8Itg43Y(*(t)x~*`6n}H#JN6z z|7iL4Elt2`iHnp{P0~Z>(BB8}Vj4nBrE!)yhfk%gF4AaW$$?KLlx1$7cIS+iA)CeF zMPZhB(L7Yi2Ao21^oRr#tAv+q;$0QN>gCpGAHwQO;1zo*Fn-=|@CwQ8Rx%cEysPzN z_g+GR>LC)J1a3fT24GC0_MTlsvJ_=={I>iZd#1uvM$;-v<^M*@hel7E*aJMiv5s^y zi8cV;xR2bo$gohnvqR|h9F~0odSE*3f%)9Q+ct!W$#*S{y64}uueVQVZR6^5S^9~s zTKUwE(XvkPG$o#9RWriy6EzDHg5sV6W}O$kj*~U_l#JNmHiJe>@X6V4euFf=5D3E7 zXo)Ug*XO0cdU2)6o~VAtnBllIQMf~|1@>tpVF7fc_l1T1fRtRe>e6W$^ba4|OqJG{ ztv>>$NWhzo#ol*=<^%4<kXOeB-kJ3i4)>;+qF9qce$8&$D(_x*zxvsY0~D;vj3)x3 z+D<8Q_$>0%DE{lRkI!4A%d5z;hBGycod}w0Z<(<yQ!jwFGR9blWyBSx&C~QRNvRVz z=rauT5>D}i&aDD1WvFuW2pW=Cb3oG!N|j>D%vuXCF}^y4VAj!w5T;T^+F_`s$zaF$ z0_YH!X+f(;Z1Ej3(G{MIlc|MjPXR<6V@y$#L@zIy=HYWBrXB9pTcr;jce&m#%VLj- zIWzr>MldFGbyxi(4~Q0h)WaLB5D{ksw;v1_jsL<T4A<8*Ca7olwgInM%HXt8`m(97 zLdF=&s_~(|Ily8=0oBEe;ZPK<Vr6-Du@Ryp_|C#<9Ezr8TP+J0k=FOV1ry`F^7WxQ zl<#$_==b->Iy_D#krKjFcEi&WBJy@4$`T^0cO&Z)xLe1W$^M!RKBc9b8zSI`mN}|Z z;o3d!Ry3+#+?0ig<ADKBx#}n^mpyomZD;!%tg`X(!^CO-Q9pydG`u_0Je{D^fKYTF z%xF6$&%SX%ZTX+pbrmqcbgAgiwmJdNG~H_PEox9%Ra9X!ZEo)Xj<Eb6tmqZ9xEN{w z1mI-UccZ147nwM;7wOb5L*g$(E{LuonNWC072{-JyA_Husls034XyXa>QK~W@Tl?* zp&~}=#)~s$i8<AK;jCDPmwKu8Y1~t6nv(Wb4Fpr`yRSIA_okM$Y6$y-p9JpMb0zJ= ztt`t#ppUHGxs9~P!(i2R)Oehn#~aq6bgD`#>r=M<yHN=P4Y<-M&FsX^#~ouGZSg4f zv?-aT)rUXmjtrK1aB&GgrAGT<ZjuHlJ2O0O?4mrQE-PiRLeQV;UY-CPYT`xtZr~Rg zc*Q69Bb#gUVQHY#*cD#XUPCY<TtbYR@qsLC5Ymu@Q~yx2+NAe2J8}GWSMK>nQw~Vi z=_5s>h&*iac!Mt-b^k>0$+HnBF399znsd8u;El7@k53I+C9e1pANSbS%Du?6jDYK= zv;Iv*C8Qw!gLp-znsTd8G)4u(KhF1Tw;Ng$s-x75c`~&^so7&Y0ILmsH<tf-Zf9q? z<tRbF>4;(IJ$?SJKmb*KiC0l3@%eK`U6$4hQ!_U`KFMB&ioD`?3Pt)7MJOWqzMV9| zfO$Z6zGScHn|*%%>a{0#PJO8<@4Q%8Y!x_S*(HB{YWu~HG!@?mA0EC0Q_~Iy;I)=s z_O3Xb!-%P_QxE(c-Jie8$S%^XVQACrAKAY86$(^M|2cT~M}tJON}Y`QO7*F1@ZY({ zGkDoa(dOs$Iipa#N`Tgrw7=Lby!H}oSvq#vu1&ggUGX^SgZ!TlJ%7=%y97dKY^Khw zx3!p13QJzq6Nu;H0jV<qB7fF3r}*#G8w{O@JnrB4RG4742Y3axHxbHJ5h9#e*gdy| zS2Ei<e@nn;g&DSyW_I@2&LH9(#>>(gU+U)=J>U~9z%m;pC^s<7vwy@RV5&QS&O*Qe zDA;29N~O;B=wzG7;cozybX^;>1y!vpTWJfi1KbUtYX17-I|RVOS3#@qHnt}s?+jHN zh(D$JXYX*_@8=Y1I711s|BV-q!tAeO{ZShhw|CI`PbD!zrxeM!bqrq^Al-rjfJhi5 zB7^W5P${F{UkKlZOi^{8&P3r5y8;>Q4$<N7@;$CK*LeSX>~hk9I~>i}y6#wJ8oLrP z-I*jB?sCKM#ZI1W?#;(hZ+pcJlf~3MNON@*!ci?B6_1@iC5jin%bK;Cy#9E^Q0V03 ztz$1#1VGU>hNQoo8}t3zvbyINa|>mR%RkW_IZwRTrr-WJ#YlqymVLBE^<t+F*8LY% zTirF2+0EWsmy$?^$&17S54-zPhU4|eJTDA7e`-3~xeBR&1beh{ZaaAV#ipujjd^0? zuid{Ve#vQP@Q53y%KrXI$ao?qxD86)w(1w4lmzuV*Bes!;}QK9LMXz=7gu!S=Gavy z4on_hy!kVz|JT;nw~w#fR6J6&W?d_D`)fIA9e3>3we_F;Rk5x9#SEa_B_zHjVih70 zxJz$o6}s!5r`6bMsx0c$^|ev9RiRU`=8DVjQ2D5eToo3opyO}_ahKjGVjJu?Bptlc zejDAhS7K9|ybKX~pmew;A04P?dh~8Y-Taqw_su(?7fRYKXKT&^V=~Z_4l)O2RY{3o z`^Az-^UDv<HH{BdCiTxNK@A0S79X4M<SP~uy4v)+t;<6Ag$zYXw9Krf+qnhnJP?*C z?pd`L(z+K@bObjGUg|ZR21A~^eaUlGaCf#4f8(Y5C(9yGI_I-Q%6_D}Z2Y<uP&~fl zJvT;wzT?cz%Px10I!KjBuS!SNRYIhF?PoG-;~i$>nF8llBW3K3dcrh93Ld_cJhhs0 zwD97nuF9?0Y}^+S`(3}=($QUhrE|&O{^q@Kik(rNiC{DMOEKT%Dmc-rxX&VC%Q0n6 z6Sece>y9LP_;vr~$gPJe-!}M)KW@Gwye>{k0TdCQWT%<nynzkHW>bj=@Np~tpLOov z`-ba<zsE@|71>2crJEC&U_i-Fe$!)b8dRxGUbk+fO0Vv2i>}nBSg(f5x|(!n$X{7^ z2UW+L`2A9cT(*!=ZRr?MayXyikRVIiGgZCrgmS+vEAo0K>-dA$UqNC4BMkPrkgSfi zYjMkdwuRCzL`=?Qo$*llq=D`LM@_DoQ{fb?lv#7xK<XAcLhYsA*7Gj9jM&MM(5|5I z<#CXx&-RRp%t>GR(5rJb^dV90^?pETNx>Hw(vat*pW8w&+3$%>b1^-K0CiUs`l0mE zQdnnr%_X94NS}YI>6Pl6{p~lWKGE)gn*E<&p_yigd1dN?8jjn$A7sf2gyUt%Zx*Um zR(Rp4r{~mcOFa1QGBo1?>ZO~=87k!^a1rm9$9?99^h|#CwZFTiHY_p^K4#CXqYX$N zBp&5PLer%C6-9R{j<0%LtZ;HllVw{U)lzED8wo1RywW|pOpJl}jxI{EvTszZaEqEa z!RV2QOv^JA$edvadNv|ma)GT|T$1k^B*qQeXPX<6u)?FBe%RhN^{-$Bs9ptLktPbZ zYGNG8c!$0?y8(2{KnQ2=F;z!~o;A>47w32_{TXF6r@8?oYTIs_8Mwn8|7nwX_$91@ zg&zZQH#9t`gMMsXctrn#*ga&Xp|3(gYlX9Fm|~W}9{2i#G(MLpPkq+n*31NNhe%+N zRHO^CC|RRkW&s>r3THv=Hx{o?lKZs^yBkjL4iIgphRkc)``@1ZE^>W1)3UszAZDRX zv__QsWoA-W@0n<A$R#fc6x|M|%!CG+Ov&?<WUCLmBQvt$GFxp!-wg3EZyxC+?mXGr ze_s5T?~sD`fI)7cSpBgmrIx*)`JRajBK6>-rePU{mjjf`o=$M|65Wd)^v0>nG!M=F z!3jmvHpQ5<qjP%{kIqVG=|EEft0_LudbIeRW0xamQ@aJhLZU!=MV3L=ctNv>P|Nfb zw|4CR(^m!2?Y`1e&Hg?uwQpKaf1K3;y5}Vy5H%8B(Lh>!M_qy{^kujWH~O_Wga;Ub zR6J7qv%kVzXKJ$cg*rca8zN^iQc^hn5-%$>a>J$zXO6p&CL@F$&Q4aUr{hB-j-7b_ zJMk6z=h_grFb?e1q$iE@2AM4<z;D)q@o!c^f3qF(VMzd4zZs5RFa`1lQZKX5^TC^x z_o3TQShinnIzUHBc`Z<~XXaJ3dp2+3rT!3!2jn3Qv7b;ii}k9s`OLQ9aZexL614Y# z<Z8JW;xrK-)E4DyT-}uuV&k6so}H<;9g`C|nkF3B$CBR=a|N;V5z)SZ!DTFdyWv)d z-Y`D&mS?uk@L7+tGd8l%+T3tF69>psU^}eykwbZpP=mVnvaR-cON+@$DB=k4u=za1 zLupa^d25x~o_pwB;=rRvnkODg@WUfp1;hzg?M!_X3Qnj2BpTWLinr;|<hF)J{rRC% z{m84SiNQ^_ws|KPZhIN4UOmAf51K_&pw~AQ<*!;3ER9h2e}`QS+)e~4Ew>|FSMZs$ zU9z<6O4>=^(!@&Hg9E+Yu;@{MXazgVGJRZ#x4NwF#>&9pzl}_j3TfBGM3Q+Ds}bD7 z+b(A3a)F=0FBNboY%&LcihZR2-F!8r%B&rOWCTlH2<;s5+3kQXJd59FiFR**{_W}( zM3NLl9uf!CZVSUAkZJM<2VI~yJ|3YLuBXXs+^Mpmzk-YnFvaV$2b2sfU~x?;{!Y=~ zbGY5^PWkm{!c6phu))bI$^h7h8cBn93LpnDWaZ|o)k|M>1p_y@?G~uRMATg~+oCk_ z){2i6M9<B01_aqru)68X%HzFZ_2|nSs@y*v-)ev=JY|C*xr>SV%)=*?)AsNePsy4M zccL06^z-7S+eb4K5{d`I5{?F%$G5oNkPCF=H}T(GZ$02Tv%^_hCb|&UK82-7SD<z# zZ$Z#(u+;RhfOf2Vo;#Z={;-Q5Wx&Wu8dgMqbOSjwcRaq^5T|NkI-u^aBu2GLwc9D? zuWKo>eLNY0{sFc<NV)6BN)~&JPN(&rzGv!iSt$78>qI+N^5cT!J}TmA#n8#ELmb|y z#cdaiO?32JiuadZWIz)Eb1AyUCY=t}11I03mw}IL{5b-=;dlFqXNFCpMC9?;_HQ13 zx{P{IU(#(oV0GqdDG8iC$oJFVqF)QqzQ%pTsOVQhG9aYU5cF?wkNGwo8rY_&{D&gP z9DSq%`I#tinC7T4m(Tl2sEbVzOPrUzHXo<;O(Hue06#BxiPF3T)vrjGR11<}^Nbfm zbf`_z*XFm(u+M|joPyJ2tZ`z4cP2-V^;O}dh-t_!a)^ubn@c~I_i4xuYlO$`JrM@D z{Juwpwps51PyenO@>1p>ejI%Q@UZuXLKg!17+Jp!P%;madUo4daA}`OvFatgpT_?6 z9gv@9z;Ftwf%9Thyt4SL^U=Yh-#2)!*h(ivHDy!Oq}`AOf?fA;4kke|gF%7jI)Pn5 zs0N&T7!J<im2IU<m*>c+De4<2ibe#9Hs$b5zHDBli2or@RLx5Tkeplqlh*SIX0ImC z7WKJcVN)D<9}jW_3?^i{CIgU9`r!G+%o-NhpZvB0Y4%4Qx<TvU#|fs{(X$IIx{4J_ z3#9MIl>EcRg`F1a8JCH?CG@gL=o_!NeUMxOgC{5w5%S`yG_JKvpbO}Ze!XzL=Icq9 zgRJc*ywXb<C?*z-4?=DR$<ufb1Q&Hk6oeK|s?DbIp1Qy<>|94v^))q@V1_WQ>2q|O z)MySm01IW3g;$j%J<mykTE1i#?_Iiw%<lu%Af@URg**BXRWW&b1IRfJR0S(!$=lf$ zgKZsGO%pleYm4DZjOG-%(G8jFvFd&bvTgK_(>S@ex@ie7#j{6#V(ycsf+aIQ+XFLo zYO&JObWQ6Zd9DxHAB5icJdyr?wi6W^QK?ZcP2*K4vKK!#=G;Y*QkqAZ+}%C<dU88R zq)QE9Gzj0PNjjFckrB$LUzz6i0hv6>fqE+8vEjRF!u&xnA>I@u4w-upB%L9GC6^kw zdPZ7vy)cG+e~J1jeV)hx`MTCayRVF@qvZFnqD>5PX9o$MB|m|Y8pO&!<d^nxllRAp zWjeH6n?E%xP`%>l*vyc2ab3y`+Ud<PYE7>>>n2mh3wlVA22!9r48->)&@XF?w`CR| zCM`adSzKIH%0ucYm+Ae&K=}owt_tfDoRFJ+MSWkOn?&<>i-PW3mphR-Ndxccd9enH zHPI9Q>b#LF-RREdSpzjm6S{3SA0-iD;|%Vqqc5a3YNZYH(HYYJ#shMLq`HEn_ISm# za9ZsUf$J0#d7R#Mo<YEd)H1eadH%?`*T6=5DLAj>&wfPj0S0EL_r?e2Fa$>M%<FzT zMqA%<Ynn3E@Kib6B0NWaFkCOFf?ZX~#ff@Zj(Iu%WL@5$mlv6zn+U=y8_52n7~SF} z=y$3HV<p(UU6&?LEVatpGfpnsnpNh=MDvP-W5qahR5Y)gECum>{Pnd+sXm;H0Zww6 z_lWxD(W7+HZJZ3>1+Q0;Xcszkim3FBBe{cVGY>;p+WCZB^$CCD6D5B9A^<syfu*-6 z`2vyDK49Q&6F3%nsO)#J2(ot@nt1ofqhaK1pX6+~vv{2I{dmjTS5o%#^2_Dw|1s3V z^(FSc7`-%nEFFXnSS9lq5=uYIx-l*YT^(N^Xk{PJCGiy4GDV`)dcIDSy&NSU%PR`k zFzAKY`SIp%2%7&~?IU8Lt9^*n^N3Xp6g&@-+DhE(N38NF-8Dd@zkvx-kRB>lr#fzm zIeFk)g=aBBLKIJ<ymw9B&d#DIq7oF(jJl{&_5&tQJS~yWoNo})alJs5Mc0=G^b=+t zYBV&UC&-d3L4j+hpJ}-2@A9I>un_)OR6lNEc}K@9WTM<&+cqRBo`Q&@A2}Ky<a||Z zf@A)s%=mkg=?2GV&FJ`#>F7o;SO=yc_3G(O9&j`fk^LH6w4;1F^GmPTgMev$77+%1 z;q<mV?A*0jO}rIaLDYq^pFAxSrTo$4fQ}XmjSwcu=><uS1f9HUq~3L!>okh`kMP^Z z=xBwbva#~-tcAIcYI}6O4*S5{o&rfYkq(OUHMN{&oFsZ)`zm8M+d!s?S0r=-@qP=* z6Q!%Wn^>AvTa{%ZI1h{E0nd?dhQa&_;HU3s3o?kX+MTdDOvc%1|HH>qHJQ$a3{j)& z7oO`1yNq11`*l2wDPu<`FPD(lu#)z?XX<^<xFSz2Kw%`hyc1T;VP0e0QD<df9DPm< zg?;AlsvUnuQU@!~%|kulHD`$aN`ND$%Z#TkAYBHdLr~|#6OHGrQ$jS|zV`#E7{s8Y zsY8O*&pWhB=eUJRLbF7X<bzFr)r+asUD$uv3*EX`hS;jjL8G_zT$MvzrCig!jMdlc z&?deK(2(p^y3`+X6<2QUpo`(>QGc)~t%6ESu}IgQi2%emBiQ{aW6&Lnn@^&}H*z8m z1zswa0?KnO9fJNba?^^+q8OTP@^}PxAO(4awuj$7inx4SLiH3bEZivdhHtqrGpb`u zG&@L+8J6qKR2zE8^Xg5&Z;I%X5t)Ggydvs}Cv<r=#@#1A6hNBRS`ey@CNU>q*F%v_ zrHjjA<wxcvIwGEVeUbI0u(ui2O+l#DATb*g`G(;dw~D?F9HOc`F}40n7a7jCR(x*E zgW8@n%PIK*5z0LHp)AGwAi2QfUth|^+mwdyPL+w}fMm?=Wn~Yr%mmJ5>#>XEeR)Cl zmHW3Mq_FnMTi5QihyaXk<a&zzJTFy;l`roT`{NX-1~>@Aid(;xneYfa6e6`7BnEcg zxmStC;6!W;C4TRD9q=RhXN(OV!A&xw^TKcJq=%BD5tkmCh|ELJ(!jSDYb)X)mF(X} z8fAV7=F)U}EaRq>7){`P%OXg;(@bs}OHWB??V&$S5V&@}OumXDMoT9}SH2o#+>gaR z+h1^N6ur;t7f}n6uMN`K_#x5ED|?$R;t+K43k5Ba^3<1Jc-Qat5sHY-o9ZZSneres zkpgA%AXg9ijHmSBv$W)=9OS)=O<U=%yM54fw{|A^j)24ICqpi)Gq5KA@H%$$fv8Zf z=GxguEl=OK95CeTzR4r2lzoF;UObW4!^WYjR7W+qE%Ndb#pJ6aEwU_edwT4I;N2(H zJ+BUZ@1TeoV8@47TTPPvoN&Tn49UQGiNGLP6P$?JH}18F)~%#(rASQn!4#%z-b^Ca z$<R1fr)y8+mNo1Nxuif_=w65!oRL*hpE7}IuDp-j=lK);0co<_KSvWZp+CNSq@41h zWgeu&<;6$oKE)|6!d3D>hE2Lr-hHaPJq|U-AP~HU%BE$wT<RXrnV~&u3u8zdC!%w3 zK2vC-IoJ#BzzfeL10#4KVRYxjI0NFMCoTxRi)uW{&^b0y^Vvx9gr>vGOS<uC!7*Jo zrDq{E{-@y-;i*2vh@`t97A4Af%ZFWYX%%GlDINOt_}FZY->owqd0h2%w%h~HxZ3)n zL~{5|w<`bQN|0J}HSb+UJl(clKWkgiqdE#JihKot)axyE>3L;m;Auer5UEavbBCvq z9bmFht*_={O+@<}n@sN>GF;(NAFNkWQyJ!=cW34jtXSH#=BQPPuF4`&KR)cVKD1CF zsO2E3U*IJBU|tr5liBB$@u_PKnncG2U6ks-Vptx#FgkH{gv-<(I~1OO`QW&)DMefl zw`h0rLMBDtfBsH74}=*c6~G#C<T|jF>8D$hI@MxNFl~Lk8F@#e9ZzJc)@DW-Hfd%& zEPHQOfnipLo4}7}!&W<(G~wtDL3WVAISHi+u@5H#eI|a))Z#>=86Q}bfgn-3KK+XP z`%%l>ro@_)w%O=_Uy)m8@!0{1I~4H<gM>&mJ4akaI**_~R<eQdX2@nI?D9*2t#t8c z&{)NXd07@Es?Zf$r`%lMi{3AZTBn~hx*w97DZ6~^aXADK^p+eJe#tIOnhr6UmmkIc zwW;}h^4aIf^YtbS(f7sS&xHdf8E6ySr_-_oLwnID4j<qCZCVaa<>Ju^fAQ5g%DrPj znm;Wrc<G?g^O9$==(AWc|9QJh+lI@$Vj8zUKl`2j1uGi58N9_G{TBm!!a?rS=Ewha ziYA>GhTfcewit3mNa(XN0Qc}@LJHq%QuHP?+anclW8<iw)jmboWM0-^lpZvx+<%|` z>hj<?U06kWtE_n_1S^?+p^}_E+#M9Rij#$NS!9#!6<*A>NPoNgG6v@-{WGXX*L{r6 zeRwo}A;a-zN7nm}(^1n-A9{}j@XSkfhrb>!Q~kxWiU+Z4P1Hh0YL4lL)tF@Tl7slw z+{LAwM8x@QI-ADpbC^xXwj1wEHeL~-xGUPbVOk2-6LmwgA*u%n>+3mkj*nVr9z;ww zpM3e~+xwIQvTdy6<9i=_61P@AzI?3xDdkuHzYx%I`G(_b(;1#aUG0m5^X!v?kBe$f z$FAr_&5d^Jhris{!?j%eR`qzY$+IQ!m9(r$MB`w5wR6v-Z!-)1-fKSEJ~u=D_7zMR z7FKtC7!D^qFgg#vmo!y(r23*(pqkO<F6@I5VzNC+QuoZuigRc=l`Q*f2BwomRay!` z(>1PFRA?HBf&wE7iZ9vqJks7^MZYC?uoqaRQ~=|BQruoKuz%bh<7~fGWR-flDd-gG z#l!h5Os3jGw$g%tr0>7|v>cUZ`w!lQ6z;Hmt!gwpUBa#<-CjH>G`SYSorM=Kzc03t zh+Ha}BZt7O+Luaa%O1pdzSg@Px9Ma-52B9gxhbgLQoKF&K+aHDQ(wq%dsIYFWtI(q zs7ORA)f$bQtp`eGv>x?5rYOwJK&SV*f1>RSlw?W!@p}x5{Z*Id)Z54{*kZtVZ+kS+ zB;u-fnF})mb5N0n%~ZbjBq-}bW%Fut>!XoF#D9As@FNEsc(C?v#g;<;YP#r{#r+K? z!u0df@M3#)$)u}B<3@;d6x*)lz3Kg$Sm*1HzZn&3Rjhl!O}=0*yfE2XH+pUU&gX%X zMPr*nSlmW5;g#Ol)Pp>Hd7IvAgQcJbVT*jui*V;le5G~=GFqQ0N6{%d>m(M^N+YIU z%rSpRhV1kPT%Us%jKrQvcORx)HHue9Wtt?ukqI(T$QIQcTwNVapgU~6GWpV~?@y!{ zw&a$vw_NY{{%Llxs7zOcg$*0sm@$266!oga>$r1h=|_W7s6|iEVYqRxVHreYp*RF) z@Sn8^)Pfk|_(AVK4j<HFY#6F-_}ZKWGwg0XAt?J}gIZi8ZCL*rP3$sgb5j1@o+Y0U z7c(p)=z2D3pyI?coqlrSJZOlLC=}^&COt6LGpCDpFumGHBvU5aNqE?5t@z2-w_v*T z+V|dH-~ap32h!f(=$Aad|8rRN{{H5u@u^F`2VSff2dZmb!-qq5NqVDgE{ai7Q*Ff) zMTW=x&!v{Utto>Rzv)DrHk|eHd~MXQQU|jNCvZ;%H>`WY3{DaX|9e8emmCo+7S|)w zyD3o;#$M#I0YitxbfFPKiZZ|1!{$H+zx6wc<yw*~ipj|;0k5j4Inf1=597rP``wDS z_(Vh91nl;4aYYX4l1;H@Qxq&BC!!b=SD{Ckiq;r&tP{BoHm{!lp5vCUkTa@_@{QmV z_v#HKnU5D;(7Bsp&L^+U{;3gJDQx)G%_Ab6@o=~MXTi6;Qx+@2P^T3>xgFm^!_|^} zr#4t2IWDApkX~SEz={^^|DfNbo1YZG6y7=*&M;hXhnV))%XC)^nw#J<&1bObG_Ti- zKwf#mx$m(}qcw-Nh-$|C3}7H~<O)fRM%Zi2Qe2z8eNO>woX#s8lqhgy8awd8w7p{3 z>9*bs{%}Hrn%tAFV5@yy#o^gSF_znqB%@0)HG+!1r~c{p*u{d&OMId`DB`0&pQ7lR zV6lg&A<I^rWfZ#}eTfZ<E-cfE5egBTjkHscG)07)a3@G)Ps<vt&^c}_o8D$)xr)ox zLNa5pHARaZr0i<1=&Kmp&+0Q<AjM(KHRBp(%^YU7Svn)LQKoV=U>O4z2!=&%9QD1H z^dMw&yV2TP#Ww<!=iXZ<zw3MSz!W74PnpGwu5}4bHaNU#_VCu9<5x8q8}>dQ5OS;* zGf+-ze?8MzWIStPs~Rv4GxraXUEDilhN467bvv8Ze<f(r9@q=m_0!_wGAx&D8UvOH z@;`hhF=7%RW0M3#yl;RLxSe2y8c{OFiqU}yqE=$ehBE)J^|1@U(yOhi#6*@>CAEV{ zRc_MHb8IF$et16@-L!_vR1Fk{zt_x^|GQyhn0Z<wBt}&33kRg~M0aeNswmA_fg6vA zTl4vZ6tOrqsu5UtDp|3>hMQGDxfeb9cva?0U&i5OthSBTh7^mFsfGTDEX*I0nn40( z&cz6rT$)Fuo1~K=2XxSj+ct=e@m8vP>9{!$6QbF~=V>E@IZ^c}l<<@4eMUM{dx;^K z*8Z*e(xC;BYF}@HK&Fnte9no6raSG{85i?<oONpJWnap99Djv^#ckkQf9kiytm+nq z71xP&(XuYSINpFRV$$DSmY>y&fh5}~Ddgn4*t9)>1(Eut7GGprx(R1GXY<18O-!+l zJ^{lO2m+8+v!vHU6v$#TR9^A9s$D8K=f}f{U8Gxrx|7x$9Y{ZGeo;$YkLdO6{=&k} zhQA^$tKIgf29AwJ*c*h0{Z3acL-zt>Eui^wynH3cR;ER_D0w|ZYF1i6e{f!7gDHM5 z)`DnuF=XyQ)jKVq*e%oY{n}j5s}M2q_VX2nbwwuwwqX>t3|X2^x@Zj%dYwd&)yoB0 zt&?Ikg&udENGvs9qJxb%Ocx%yhvk<Bc<w6QYp(B!HA*2g3JlQsryD7Zd-90~k$5um zPtj=_b>Qu=z@g6WPU#C<gQoB=g?^sW-!46f+G)#FwZ`T7s)fk^w|AzrG;S@%`Z~IT z_~9hPz9=97FTeh#Bc**-?j$+fC9Y~n{R!r#g%F=83B?CH(<i`<Y+DvS1Ym|SZ6dcf zzhY1N%I@=ID-4t2er<%F-%jNxb~g~FQgyeP8(AtkRTX@1+0Q4(b{}2O;CxLK==fU< z<!l~=_;N^zlbEr99M?;R)9;4ViM+89OH9$HJhmFUF@+a=>+|QbfpJ-(u-H%qiO(=4 z*&YTgqVJpVpIBh!{uyIdzJiPFv8Qc8j11T46ht%+zle)Yx|$kYl$>}ue2oW)R~zk% zzxNtFNB*wEW<c{z_<OFu{$j&ZrEammwR+}H=AkYI@<{xVtk9Of-&3w=tkK?BMbi<Q zp?s2$!FE=Ees=br*!g=&JHAZW)s>XwIZtaEP^oBFii-o>TjuI+NN7IW?u)JaJ!^zt zg7GUi#O)36Rxu*z(b@NGAwMLLjPz4<2a(AF_8XKtJfIUgV)5Li$|Ik@lLC97bD-gC zs<}tiLZx|Rfjqx}?l*Ar<iHd+@JQpO01!BzBM@H<PC{OWb_5~#fQ9kUg5AqWxWnj$ zbdTYLeU;Q+By@@+$Q4JMkg(Oq@QcPFKQ2oBd>b%MlHM*?+9?kBj|9EXBUow;eNGmn z7`tv8z)xf-k(85miot*S40#%o&QGa)Bty0^Zob#-McSdHI-yr?CU>sG{?I_0KaZ`u zi^L;|iPn%p5-^u2K;eLrIs9p4chV!OUPZ1>SFTnzh|F;?+7QShsS?K1tiWIim56I1 zdOIrMBsT%SV(`9Eh6?j?e_}olNa76(@|A;F;|MkCK%a9UH5-Bl{nkQc;mnKIFBZI2 ztiZrUj!Q?bc;5<==9C8Pli(~8H0z>Z-3GLZBlxuq;h2#5>NCtSSg@iE@${N3wE=Ot z4fcn9{AcXxDILTUHYn|(aPb~;iVQ*R9ozZ|3~7Vp@qkFhpi^v6dLLR)UqoK&l0L)X zeg(h?nUY;5|G4W?1`<f@6H^S)Q!H~t;?GwrfCD)K{`&dD_L5O=%d8_$jI$uSWY{hl zyS5>CABm{r2;S3ybYoyJUihzK)L&%g*J8*bJ24;$9`!CU=$-A_o?xvG<f%3E1`^R- z3|-|QYWrZHY%RmRr0=)~s!N8tt61;o2-fQ$!tu!m$L$c;-JlY>ltpaL8IAy&|B@0e ztqlaO?gQGBfKfWYoBh5z3>^h2QEHtC_up;I0m7F{PaF**P$IHuYPygF{of$^q(F}n z_&g`97I|n!vOH=Y5zDaYovD8IySh)Rh6$;8vk2)XBA#`i4*JfI?Fq7w(B~V_M<k&d z9mpgA)=$2X#TM%BD_rj?>_$TGyWJ?$fjneGCs4Kh7)8f7h|eS#bLZrhFW!z!$OX|* z{-vnR2hbvGV}8G4VLGCUcwxjEon;E+@|8}+xJDCs<#FE%1yC#x=o$tb<pxsbFRfM= zjoHYxE(Y9=ldpYPYJ(NmRxi_&DmyT_15{@@M!SJ(`qIY?Y7G4ApI#_;&#pG}4_@no zyd@%vO5pQua55!fw;0|{D=**|oah#OpaXrxbIZdF%4Eat7dP~_39ZrKeeqY9*aagU zmV0Gcw<KT_Y`IhVh`(yq+d4uOZpK?3WLSh?IS+co2t7i(aLY^0;;re)K5z~Z5>Dff zM1tXVVyVbdnbq7=8+5s55hBu2$w4fm*hERc?Cy)Ipki=UDaelvu41Pjc_J}r(tKOm z>wpc*BErA25nqvt`)#NfGuL+e&Oh|Dc-aR%XiM#Vl6vtiD)2qYGhS-dTCm$%y7;ZP zqn=<}vC9`*#Jr~)6eV}C-3Pr*6qbvrm?>^-<Al}mJJe+0v)BRwByejv=sZ%8#GxEx z^Lh1w<5WtGdBJCh09-LOg)NXuBpjX*%ifB2pZ5?Aj>s$)AaWp|$ykdE)s2TxrtjO3 zC!EGs5KUyk;Uo*xhr^H*!G<<C2Lr>%bSz<72j581aDr<JSMCYJ&U&6+<yZFTfL3m3 z<#xeXZrq^<@J}&f1c{c#o^50&uQM9&tq6QxO@WDmt`~zzNC5*9-?2V$G)Ap@h8{$` zUrtB^mH~5g?xa2<lq;NvGVc(?KrS3eyY&$vnf73M^@D*&r2lNZ;sk3sh@R4RolV62 z1;hl;nS(02#+0?-z7Blrj$I8&utz2Pd;__vI2)=aeA~KWo__ZOTgZt9L~q~anCaYL z2|W7(Oy1<e9Y9s2fIAUTNxrw~9`17(U|Zaogb6=+qKXR(CLr_w#F&jeHp6XWoU8>G z^ifeV?N(Bc2Oag7*<dyizRGSMTWh|T+kRXMnp&;FwIUmJT+@%lL@wD6#2nw$7lf!K zLrvta^FTR46^l4nKKBbXZ+PJ%X!FSP%@)-gQ1Eh?TKh|f9GZZt^*J{Th=>9Iq~JAt z<;kRnzj7;aUD0LD1jnE8g0bM>w_u_Uq@4)ECiHeIo-q2uz{oNc%$dv_1&c$lgJm*o zE$eZiFq{z&|Bv(dT07z|4KhZ8zZl^zHo;d<ZqIbw)c+uK&~44KMs$%NTQp(uin~e4 z)E_Ci)>+dffAp5v6?qo#+z?Xanc+fcScW7Q$uag!nG|c&}d~?I7U2>J%Ni2-&Wu zvp<b^{XU)&l+o7Hx|o-NsbxAcQ%9=@UNWd>4|T@E3yQtwH<~p@z5eom@A-7Ngh=hQ zSuw5QrW%^JuqwsG<6kFWudrtcXU{fbAgoN`-8Vv8JkZ)ScXwHb!@?p$WldrsA|*_4 zszfD;2KIL2cX8v-jf~d11!T60wI9Eu$Kh|5d3oaj$T=p@{GBKsb^f670ysw>dxaJe zAp<uv>^&<poVNc;feH6gf<=?y3Dxl2QD&dVMLj3@e{QW)WY*YKCB9+k!@d_MsezY{ z85gD)kI@iqZo-B3CYcumBWWggW$`x+?w#a;oNuEV&I1!M<1sqieH7=W6Q@e!&qo4H zF#t^rKtXOokH{bBHnB2-Hi@B}>?u`bfm7Q=Z4=F|OpDeCVqM739zn*Up<|X7!N06+ zd)UCQ<eINF?N2iVYx*A3!lYJ<q4gWJCmx2pK5Z>ha(%|*?sW`&(g6ljd&Y66r9Xhp z^a&`1iWIR%l08HmveY8oz}E&G5Ei1wI8)<xPy*>P&Y1szz~L_-0+iW&RLytX?nli& ze!(rERFy7eFq-7#$X_boRSq&s5*Nh-uals-kNTeinyvoMC@G8`Afe~T@ZoM|;s?Zh z@l%t!i#HhtpWWcx$Er#iJT}tq7Vq(CGQ5Wd`F!;?j~Ak}EimZ;+3YRk59jpz5n+US z)wK$CrxWM|5-4}I(k4YDnhkcaP9a$HhqL*VF%#Bq{7dKf$(n#5(mezF_yC={GC{o- z0C@AZuJ<??>i>fIpFdS7<2>~Jzq{C%>Jkt1rkp=B^8#2q)*&Gg-uuPSMlyVwlzHUQ zhX&di-*Yk^bx@ic0`HW(VTdTAL1XIrrGn50wIMnA7jjap!6k>D17$DWQU)F)3mm6` zef#)KQu&Pf`0e`m&2-+;{=>(Rz)pP+%N*{=?!;5tKsO!QqKm-|ZZM_{>eJ|_gUg?> zO!%PA`^Yv#<K?N|1w=a%`j_X$oFdH7TxiESHqpezW)S>2_V`O3(2PzpRINfmOQ^8v z?iNST&l=1O2YDU6_oJmLeo&|IvbcBgqM;67A$raTIdO&)CnpHJvYMtOh&5AZ5Zyq& zyug5BNEJ+i%sV!h|G6npvSSl5Muxoa9sY+A>ZLgkdBY=WA>AZ+Bkp?F(+};O54cCS zqdT?gtp&OLFugp2X{RfgcJHOCL=MhBLSsUv^EZI^f6-cch|_SoAJ3ej8$gxKE2qO} zP2{J33sRiNxsbp`Pdzd=fRzf2XK|BPHh@KB=x0pt&2KYz=6)p8Jv+Aqn~0D7l@#C6 z;01jM-C2VHW!NftZFn_coM;UfJ6dz`CvnT}1G)db+p{gQ&;=w#4rhWa0fIh`$Q#6a z&VrVK<9X7hnR)_L&58NKMLRcs?2Wnew0BBV6F+VUIMVanN(8PD#iNP^qTR?c`;(2| zf4JP2=q$b3WPJp5%0O!!@?r7)5xtI88l)Q;J9gFXHRr?YVyzU@XGJZDax(OTPWRHd zP#U@WEbJRXI^`l2=oRj8kmn$JrC4D86~8T;S44+TnaIC9$A?yVes22v;m?->*kJq* zF)H#-tKyT(#n3<hW}FYUYfedwfhGEj!TlQukhWrxFudD#Ic!XkCJcRvx$^Qo>s=jL z`}k~*fn2Lw<A_{XRXK!@b?#Cy2tF+kYW;EACGCG~y@@+i@&EsQ%x-r3&RDW9W8WG3 z5*lqJWZzQRDimSH9)^@%V+lzbQlXN4FN2CovL#AoOOnhzpYP|s?%(&ie)m5x*EMtA z=bZOE-mmB5c|!C-mrdX`GW6O7h#CH$4uSnn-HP!#>@l|`W58?1^~X^X5yFJ<_#jSn za<&jS|Iz+9jQuS8bTF!=^ehayK-!!5#)-mN-)HSDxn}R*76!Of+>B$3mrs1VMV{}b z&V0>^uo@G3bnZi)^UTg@QODuEX6;G-qo+0F7|o*H4{Z*W=U;K{=crC$9WJm)Sa>$X zBlqfXnQ`0!L^$8STv^3UFg)osf=5W>dVKm_YdqaNxenA_%%+%)$<0i=<BymU&Hh8N zcN7O-$~aLEnluBC{BUo-_<gpo#O0@FN8G=IvcEW2nQO@y3F}hV4WIrjG1C;$Q=5Ln zH&xE`m!5j)b7k$|qwmt{r}nU~ukTotsm{D`ZF*ZKZG-(7`kwtnlXW?Nrt$n@=RcUZ z`);Ry^@?P}E%%sBD&mRyMBv84c4qgA|NA>CA9ey>KECknM*o<&q0;Gv4U0ikfyv2> z%~Xjq2UqttKP?U|TKA{bsFdzVNT!*0dL?l+Vl9dHOgFtOYb-&Wy$ugp{Yc9!Ei`8@ z#*8Wnx%p(;J5ZC$MrOSE3M3Ok<a6<BvJyB$Rks!jtPZ!vv;M&Ot<yGAwI<1^z_M83 zRk+T(5Q|NnsKHemLC4)DYdwX;r~Sh5PKkHKse(RfC6R<;8<DSdRjK*eByKwq|K*Av zRKBa*&>>SF^D2}nHeI^bXnisAi0NO*_7O91-=ZvuJ;g}nb|dFISDj}_XBsv%E1DgC zsMw296XrVH-Hh~>$+U)WRcE-jcKWyA&-y(&;j(HF&Tt95^XTO13w_#CSAHaZyX~%} ze@F0Ix5CR7!jZcvx2JFU@7NwH5>2@g*RZiHe4(*V=R<gZ+v9QvR<VBe;gl7jW$yEe zmDrEo+cA~`arqnP4gDYM_n`{D(#CM6-7DQFLm&qHLhra#s}}`lEjVw4*g1w#s!wRm zP$nEm!9~_=myTvVvhT@mGAd)>)j(Xmcw)5oQtm}k%fM~-GbyJUT{)GS0!l9Q>j#!y z?hqR29_`xTwa))DP#!knEH~(_b;`z0=C)_^?V$1W2>W}hiB$3Py<D|zDsA&MBB@&8 z{^jbmktyOXu0=LQ-)G-`;Z^N_2=3VQ38_M914DMTx}Zk2urBC;LXJ^uJts}|{9soO zN%5m#mv!efuiry%PVn`-+Fgi%Nf;zIaNOpagDS6`jq$}dESJEz?OTR_18=(uSJVzn z?5?I}$Cjq-y_3~cs13Q7xYcj(YJFEOG`!@SwS@KZ_?M!<SLJ~P4zu4?XK6kW3LO?} zwmq3z*zw4m<S|{-xa}#I7jZkET&~rce_EHu#XTjmV1&&Cqs{wBXNo|LkAAa^6t<Gv zQV_|7IyAVbqI&k!H<@V7D|Gn)fnG0|cB`4-pB_zCVZXcyNA`Grk3^H#d;PFU<$!r> zvF<^tK^<RK=o_ZUhvqz`=H9H&+YDi>kd?}^WLaiiru2`bDcj~ISw}w({O5OI!af<U z7FB`M&iypk(rTspRfeta1c}#k!$p?n@c*_XP9nRYEaT(J2`4u|1mUI>yE<Qd+j^@0 zbeEY)b4WlO#E$^gA9VS+A~D0H%2m(j#BW>h^pM{+m+v%0yk6w}(4O+B{-&MNrHIo- zbnB^G1^95I#n=x_xK-T^9k(bMk>FwLnF%kRZPBEN1!=0|4%yTkGhFZ-vaEJ3#xzH) z5r2VUhQ}6IJ0x@9(+P7DONGfq!3E5TT{z$F9PZ*;2JO@Sh(wpZQ^c*vQt^GdhV^{9 z*FHtCSl$LzVO<ir&4#Ob1KKG9rR?xM&%nEh%@wXpXIqH0?|W;TmZmJ1Y)eP=t_+FS z2{6^`ITsZ5CE{nEIPYG}uafW(j7Q``jr>^3N<#L_CngFJs?i+9<GrGS!dz(zh(+EY z*MV=NZO2?s(P~YhA>?z(PNMolJYV(tRNqQw%?zeUJoh~+8<9H}chE2Lmt>`!_r-!5 z1{Quphs$2#daiElE4amO&D!S3`=RVCQH>|?wJ~A3>ndJJpkPnqc9-nzfv{7Zt}ZiP z6e;(5e4vB7)N5vP0XGpJJqWrx6Nd7TpO;wSt=I1>I`!((+lNXT)f(>M=_YfH64PE^ zAC~gHaepm+Lud5l&0RC((I5pn`mVKc7+Y<M55KuJ*sCSH_xS6$WWvHE_|v6kIaQsh zw!}#uLGTqi>1rYaW{<y9XP&BxkTPdw|FaNvT$WS}T2#3$_9bBaspn1vzfI%@UEe6} zty!rQf9o+g%4HgN_pP+>iI?p1sxDN5>X>9hCsg;<rQC1%jzYt(bv98PFu9froNHH) zNc(Sh?B(4<SH32RJ7idEyG?OUILw^nzU->HHvjb24QYXHV!EPbrG$H0a{bQqEUCU= zz!bLWblD$k+zjR&On}N7siQA$FW&vDmx>&c#2hU9NE9_F>aDQZ>2(ds?LjLWeuu1> z6%fzaWKYeoE~I97B3H_XW8@{HK!d4wuQn+|KA*^GMz%M4PjXrchI&DQE?Ft3uP2Fc zj|YMjPhwKSC?W@4Fo*3yO*0s4X;rp0*y-~7$=fFAY$q!A$h5TBFnjFV$NO`{OqE1i zF3dEdD>E`0Ec!usR=YnuT|!k&|5pN3d09Po^*F@6C~QhA#5vPp+g!XUOkvK*==*Yq z+$-?=ZlODDJUo)X>1T#Nyh=z5I`EEg2<jEUZ{#>cN#;~!66!w36&1bwF#Egza)%07 z;2J%Nr>1H^i#(p@iry9dEa<4J*M$qRq_{Eeztw;2E&4fJL4S)$CDv4VrMfQ(gswnk zRTEK{56Q`XUOYSet9>(jnG^514yv1wM-ZbwRG;=%5TF;O4#d<eCJZK>5Z=gfrq4_K z^D64NIa`PvMou0{HPB~GjsJ9I8#lh`?HMoUUOyIO&cptfE>}OE6R~cg_m=cjo34J^ zMFtmo!NpU%zXEN$W+BSWm7<wF&Uut*&h=O?#bmZ4D+y92_uASh?#Gt5Y0LJVQ3uPH zMMOTRqyb7OQhE@yv1z@OD%M6eH=SL0S$BasaK|R@t6H?Q<(jXU?IPTi5nmZ2YSH2~ zNL31%M+TC5elz7$Z~SR0_S&ivU(p*d$$x=s!c>VgA}ST4ZX=BM7X<z=Q)Tl~bI*-R z^Sc9(tNgd4HwSEv#3aPHGC)7FPFb;kh)dGVJ~2*KTj8e&hk261u^Kds6ZqrLQ3lTe znNHAEK9?;>)Cvn;t)2yg2scomA!+cKLYNB)@^~<L(K{Iv1$CaLdJ001vFD%spq?bC zBN?ngN{QZ0_AP|R3c}A4Qe!(IuFO<_`NuKS0wt{v#kb82DLg6Z>8gX265pCX7QCv3 zNZ@Od^)6*}@>vEqL^drsibU}s^MQFuw<o$)x4Q+q3<BBSsE|(B8hp|f9;BCC#nUmp zn0i$&C7RX~y^`!%*kgD-)gMTWbA>tR!OzlC?z2l+=b#RF_@`nx`*NGo9!o^^+Kg7_ zGYb@@Al!!Cfx{r7!X!%uSUae}dZcvd59Eq1#Wnhg+SMWs%f1tSeNPc(A#;#>XEk72 zEdDEkDaTe)KL+!^JDuw34tFBMLkX!qUW!qKTW1L=aqAFQy=?!wR{wQ=4`PW_dzvAc zVoZCysr2ISV7juG@?j(Md$v@Cbsg>LXF;(w#5Az&mE>zoh^JuI$zHw_`2(?jR%5o> z$1E_DLDkhwaL2S1+q^7!L%7Frli6ned+inB2;va}Lwq46v7PFD1(r!La+*srO|v{_ zX{4rcyAV*8e%1>PrYZz+ICB(@o`tC4ZxYw>M}h{Vl!UJskyNXPO5FQA^^@&Z;1UWw zVe6^ZgUM0k3Ogyd{30Z_6((F?@o5hBUO(+T85<;%oa83|6#$#>iexLB7NoJH%!3rH zfq~p!q>Z#q{(im_7uArdPu!(mv#pQr9XeGp(AIMJ4W-jzuEr<0^CALvoD5g+t*DxT zTa$+s+EOB!(51V2$$;uZvpboEaHq7kb|KTo1|6eJ3Wqn2q(?m`eYi1*R>(t@r6np3 z7Sdv5i-I6Zc#PAax^er6OViN17RS0P4_>XKj}JmxJ5!(z#Zipf#S*zFaz`};?l{cP zCYX-Q<okQYu?Z&WH0;mF8@E~=MrSH%+=7MDkX*E*1D8;L28~2?<nYmIuA?c)Q;F-4 zOH7DuLgt6io9)$Of0vqWrbBIQ;Z>(nVcYPPt<=gEO!p`?9M4Ldo_G`<mV9o#m|6%w z-%1TFESIWGwU}nx3#`AdRhA287}-*kncyb$5y%FzznEt2m7y3!wTz}&hfzi%9e1n2 zW!+;!O=BW&#$PQwDQkdV>r9bF!6S)>E>6R%s2V*E<j|q&SmGg-MA!pok)wiA*XzXP zhOMz5rOu0*>ngNxe?&F|6vJK1W+FtEk*FM$R2`NiiU4azA8}lvjQA9ZW#ztanKb&R zOmC9L>04a0On$UjHcjquz^6|6Oq{Jt_1~>cu+L5^OgY|-2-kxIPE35+EHRx1Ul4`- z5;@$=%XSYa$nS&A<Uv+uZ>)sCm#e|ocH!?{9}^g2jl14C5e5=#ILqybfL-Z?-APa0 zH^}2lYBnR=e{SGcN_13lMzozxaS*J`STPAgncl2Ad23Ss$5n7cg1$DvnfN_JcMvoX z-XJB&!D1weOy|f7ChI>>mAdzaziaaHO_vB^jWM>`m?#-9lN|1v2QnT!Z~JPFrs6or zZSxWCA}<o;SaRdT;NcTS1tZ}2^fukCla00zgE^4ZU*01_U=ewaS|Ug~2vimH#-PlF zujtK<6YmO#9NVKitx3u8K|-E$)G2vpBstYR=)UlT9Q$}Aj#<3&3=%*lX4JugU-H~K z_C9}7!1NE;6rjY%)MRLD6&gY!9+uXxOmibxNg_ds3W8v^2e8fkU0B9cv(*QauesfX zWCs97e@AgAr^esG$i7Q<olbS^<`0`gtn6#Bjhl*h5V2m6!xyJJ)$@((Dy<+#>XWMq z{}x7UP2X8h)Fs-9v_fw<et2&C?&Yr;_cpHJIcoAln4>LxHaF#p9@K><sc7dAVrzfC zFf|4*0^`&1sY-FDQ}igk64!CJ2Tz*TRi1jUZ~y1@VP&fEpsSqnlcRiEjZm<~I!HE% zWAq<w><wxx%wX;FEE*&>RtL9cLXW$qbcWu#=;{&Al$&F4pEz8e%$E2vQ&z?iv4zxA z?};kEIQQ9s>@>FpZPA;R@0*W<<ziV)oMv+*TdHyzSWbSb@g|3eV4}3%gCBjFuO7{z zA9LZ`a^ut3MnlL9m#yr4^0D2Xxk1VM3+xer)KD*IY+-ib98}vYeNX-NSr0ebMBR%n z&W?FiH992_^pc}L-*P4Chk@5^CF=Eg(A~Nush~tIaz58!;-wjN%#XX@`xaCh`4H_| zN9QOWgp_7*YV`Zm!>!u9%c;)f`DJ>lhb`<!6}%4w*;?@+EPYB#Zp;3oFZFoZfR+yr zo_&d$vh+%F(Mz@2qT23Kn|`5j3qDsm=WJ`1_)o$A2q&{ejIPniSLRaf-@BY|;}7$C z<rshFZbRzf>Eys)9jeSbKe|}H28-#x(<)8FD8K@Us8^M<;d{Rhd8+~3U^QSF4Oa7_ znieLx%)zavp%zl7?aP<!Zv}KBxZ(>T@pUN<ub|xKP#02a3J*d_2<kpvf1VEa7EBKO zZsJ6yloD}Y6a{xzL~eCv?5DY@k-?_XG|!#S%~6ziJBYW_P!paCdR3@~fJMpoT_eKq zLwAF9#8gsN(o=Fh6H_ef=<c>D4t3CD>r^R8{}w~ICmt5=>TNy>5v+k_wf2|J5pOaD z;`DJwb0tOydi-jV0e-=M;Y$O4q%ID;oF&^tFMXv6xkgB7h@m5khl1bE@>Z<W#dD>m zjA(16UYt%nm%vK4p+k=kLjBEBzf`dwBo#CDUBSF?M}V@flz*EkRVbdLKa`;dP@b(O zH5gHgzOI7jd!GhSWgd%0j3jB1sCupxQ6b1U<xO3D$lXh!{O|ZY|G<w7Hu<!MTxq3V zoueM>gm|PS`v*~DSLAM}B0L3k!p14j)4x3ak>2s{%>H0TDS|>=p%krv40m4*7<vx) zLxv?Gf2uMfl!D~k?96sk?N-3!CG7**%LDOiV}ktC`|!}Y)Od=`a%QqyD^)Xr?P5>9 z3v!PrOnrLeBsCpZFt=L#ilRFxszv~7&`YoBQyGE_<pHMkb$FsJcu#y~gaf>;2~iR> zup_eCaSG^{$tw>p{(uf-8tuU^+JbRiDHmI<{QtakZ-BmBre^a)k0m4@BP4sYe*Ts6 zkULegVf_q|d4Wg*YcNZc$rKAcX{UE*53fFSXge#Z`lO!VSJYkVLWXO!QlHQsw2{Js z&!2}Cd==L>*!Tyh?^FHLWE3Y)$yLEuqmqx!K^*C$sssxEm!#kPTk3KY!`4F{DG*x# zVm<w3uQA*L?5x@;*m(=DD-|I4^O?dR)Q13e8I*piw`uPbaVRGQ*UdHD0lz}lyJ)Kt zKbP!H@b{U6ud$ubbMWH`A0bnSErDvWvVG)Bl=fxkBj0a-oc;C^Od-{5(JE*h;Vdc3 zP71M=y>ye@qu(g$M7ZBxHj|6$H_82JV(`5rE7o2yO1?af3H8LogQ(+!zw&=Q{i!=u z7?g@Hn*MpBfYuUC$q1oFp&*y^AR4x*r!QN1*hD~o{)#Hd6gidRJeuq(&mF;lA5DP9 z6S9xlmis?YI#zIr<^96E4zD&iTomF-LQ#+ZrkuYGlJW-YguS_GciGeBat2KJXead? zVqW1PTt{aoRxriE^>ug}6dJJ=k8{*Tf)fY8KSO4l@l?l~cb&tJxK4xI0j|rAm!od) zM!nz)>x7UKE{C<kU8j@XA}8`aVG%))$fe6SbQ?&~6s^{8_dY&zYI?D=#7eRtQmyIV z*!F!sY9{GSSo)_w9v5833gL={saI$zNeOwecvwI~ihodGt(tSf7<ky3a_Ib@kr;}q zEu|;~a`7tE#uXx}&}`}QyQnL-|MLDo>i%HC{!s1y@RR+Kf&I~`{g+?%U;W-6ga2a+ z{2QOT+7>1>HV9V<!w4Ito}YuCpqK@nb$|LIzd0K3$U!j(a}I?I{X~va<!&kxA+7|l zBdJ~La=?Vk!RNq(W!BZA@juNj5x3LTF3qva1CrfI$=-S<j?>9XHeDt)|8^+&O8hQy z_gjY=Do<gqQ|_krF6bz`Zg&NW>o!;|SXvplX8z#V5q40bbvkT;HFe~MYV2F?HihE| zd~X`J+|h=h4Jm6<I_RJC;%DDd%cKLEa`2{~o!O<%1pU|YG`i6lS>wv>pSSfR*VZ=H zR=4Dsbn{ehm5^=uiE8@-jpyumzf8^1+N1YFeks0faC;K*{p+LJN!Q{7%ngWQfvo4R zh`WCliPAHz;jE>^6(YG%$8%zib30GQCO?UV0Oj{(N?1sXeCCYe%#*7%cyY8b^pD1L zt+RUMkF`IVE6mEf&69r=`Ar?SgPMf2)m#cw6Z}T*pA+$+r=IVwUahQQ_IGu2d{z+c zN0nJ8fuI_^HK?k?e-3UwzWj4`W$nF^VRHLF!`=0Tfy|vJKhCfkyq}%_H{v&P^0v;X z*hI&<+fwUB7dq=U?pymxo#&96@e+yaf{LXJc8@2WqK@0i{v$u(iQ#jzJ$|{wqg66h zEOz(f#Wlv(m{Mu)<`K68zwTbq;8yk1QornE7A?2MG(Je;#%<3?sSm%l67gWpTc1x3 zvpgdSDVLcL2x{4$h)8SgvXm$&O}mjM5hCQ7ays_Up+av(J}E<PAB_RCI-yN#g80R* zqo-p4-ICnhmzU(SF6s07N?q*Z==b!f=7J@RD%cSsy`B}NMvQVw+4A_=R&wg<rpK%X zdib;})Rsl)Ntwp60jAnV{OZY^3rmk&guPY@Y<!LT)40NnVJwhR!$8b<DqZRG_@Zs9 zqR<@svnoWrlLVV#Lhjd-uB)>e7ISLfMBKUi=v~OubN*6$TRAd}QqW7@#E*y4EUsM* zhYJSLbFGCXV$6c9lIJR5^b^$;Fp<!(t^t82A<i3&RG4`KJziy?)aO`3*N{T*jHTog zKDFfgeL`oSg*z|rQ?ASSj2?rwZx^)$N?r$^oEG$Mm2?+ZeyV)W*0?hNJbMJJU?B2^ zcDuV&*3~Xc*;2X>&S^R9**3XY{h!urzRbdG*`ii%>+{!`Mb!y%V*A>a@T!un3OyDF z58-@tS0CY}%I}>BhXi#_#fg23bFX83OLafRT|4#O^octQl*w~>pNoFly~I&xG0Sid zCgvVxHdu9`N5)pli)c0=|Ll5ewsG{|=Pi>}CGmU7QjI;Y2yw(pYyK#iM!l)552|Zj z>QB0og|F|ImJrn1a-o8>QlFO}d8<0YS4Rw4S1(D+-slz160HnMT7DaE_}f5Ye_%Z* zs%xcc^c?S18|B3DK~0`O&ba=UJ*KAr^3#K`d=Ah25QGqiCb;+Gg4Q25zpDg(%Z)dg zfEu^Hyjo!4BKSH%&4R6|e0}$J|59ofCL&Dnw`-Xk7JP`^{!8}sI#z}#d`L;}#hh6O z32v`9TPxRHz2NIGvObrr%<E@9{LSmp4y;#_TV4LOB#Y}>^SY)5Z#Twcy<1=~P=>G4 z&m;@56!j9Q*4mYf{!B@)$_J+r8*pg0248RHcZXE0Jtg$&BK|@|PCQYP>mP@-1Al(% zNv@w5%lC-sK^=)G1-SsPLXg;dAjSAu7yiY=nW|3R2LPWpYH0VZLE~cnwa%tv=htN9 z)pv2BL`n1wIz<5Kjp&y7=B#dEA<;=rCbIRDF@#ZT;O^niko#P7f4k3j(vp>DDo~dg zJrbh97Q}8x{8=(s;MsbfLR2EJE{BKw{a-_&5tA`2`F_+^0>U6l5{>c+5Etnx)J1oD z#3htbL|<!M^{+tw+V19^>w}rpNd}xJpZv^Xp6W0^{sXli4wfnf!;ZM~lzd#u$4e-V zj~BtYQk(+`<*g~g=9>{(TD?iLfKu))OVbN_t9Cc+dTi2rok72Xq>fwl>k%rs9{S14 zX{MK@`zTf#{ac-U#gneRX04u;P$tZ~HIe+>QRe0q#pCK<CbHdrB*u^}M)vV+A!{Yl zNxnB`P5nMI9b4!1zUI_qNYmC;AM}kubB&T7grLt$d_pNMa<hKw`R1bsU`o2JXSXJ2 z^AJ7_Pjx|ciErhfxbL-j*H^kk<r;MnrTwTIT$J{DA$mN~;rl&LffO5?nB2MxVKiZE zlQXTu8|lvIQEF6pS6+GX@#DVNF>mu(Of@6&DKtmE$aJ-+yvn22oTE<bg67twUx_jV z51QC|QR=k)x5ov-xtAO6c{r7Q;k$JLEjV*hpSC=Y-35V(&t2PYVqKn>-Ty4oK{ATI zU!gyCF+i-9{^B$tOAPz5v4DV@<G37TdDiv5<m+{4pXJ3<iFB|;4{=0o+KfG7U?J8W zmTEA)i8{e1lzRy<ZJEjr!ij93?MP82!3F*UB98plb`HfE-LE5l<gyBid`f2`<p^{& z5f^G>(wd30)QJ$ra^29DM^&5hTV9n;JHa;cDjYoDC<wX!S>^12Z!V(88zX{HO{f@h zj?4F%2%Y{S`+5iv`<W!%1k+%-xng|NEN|Xj%#nyFvT*yMNjLQ^2S0ho7*DP&8oL@G z`+KMD>|VD(O+u<3WC3%wkgBGveZL=8-2dpiR-L-0O6YNpuCteVVqO5uzt((x=u4Xd zvtG%H=p<~$sU8Q<aPi=*o0Ao?W4EuVgf_C5Z(mqIg;_CEhjS9yi3a~sOua`0CfSex zEVf4vb*EJH6(9U$=u$l}$xmnU)yEuVo96tK3|~qvg9#?~7N$!a+`)xC1Wz$e%Tb}x z+f2L7(SH?QsAqGBy&Fv5*MIfXeaCS3*DaBV|EA{3!F79@t<LEUq~xT|iL&&LR^JKp z4}UZMTl-Isgf>hG(amZWc#$5{iHSh@uk`7>(0>)#xK+0GjIA!!XHrzRD|nu-SeqJ5 z+-TgsqxpQ*T;SW2>G8MPy}w_|n64cgAf2<gD#?9YzCZ29<7`L6=W79`hVLgEcdD;k zT|O@{+|u|b<H%fWSBhAV>FHNXN7n!K5o>Rae(I=rjOti7;rRIEN6jvK-SRy^3^+>R zBFhN}eJQ`mFQ*#+yo~JFDrXt3SX{W&lw`Q!FJ`D?^<eMK!;W88a{Hfs)$*H0I<nr~ zH~tZc)1Lm;@w)@JUVBY#fBr)H?_N`r%_@QYCCwLqs?<BSs?_4{``K>3ePOcm@WH?D zkuUzvvP^b+)DAXoyx3o6nVRlRJ~;UG@WsC$*G%^p)mVQful+SjJlNiPz{*s)#yVh` zvObCfSOSN=6^oAm;wKy&B7k*1wYG^vtmzOZ0`w#u>PdhF5TL4F;7f#!a5_B2>t`Yz zaf`l|OXsYi&t;V$AJez}%VGU=^eY19EgdsUz%CGw?F1ZhhF#B&M}EM;B)MSk@%)n9 zK0@rkIFIlwmyRTF$P|aQBp>KK&q+!C;x~K&k^=Ux`7cQd22Ap%NDA4%<-R2;{AyaD zMpDFwDg0Pc)EtLiCWyVQ5Sx`0U#<}Er(eA8EqWj+|3{L5mEw9XDJkyr8X+a6y09-O zC2iu<rza)Da;kh}D|N_op~h88_WXjcf|Oi*W&h~Bc(#<ntxAP*DaBirvPn`(*mAkY zQp&J#rG6<DpJAc5QmW@i6_=&d0)~}$q=@a608Col{Iwdtv_{f^x~#NjM!$-Vw3g4T zhPAY|TYuV2w@jz2_Ic?T2h=A?N5zyXy=-ayTUGky9!r0~<yJ}Rg%tH?i-!CZqgTG_ zomIyD(#FG!#_xSizAl<9_?jF@lP0Q2JHE#Jex}H3b-`+L4H<LTlBt28rR<Ugx1ZH3 zUyGwlCiY9#A$~UIOO{DXHf~F{K1)`6zP5ROc9l!^;(mt%s%>YbZHB9DCj1<_7acZz z9ltI)K3Z6E+VeZ2$}Z)twyW`T?pU&Gm(dZlkg)_2TS%yN0JjUAIC<y9(L2Wj?i}~L zb0Wn5WQ6~T*v}`E?zm<ja=G>Sc-|e?q(dhg51qdC`E>UkxAxDcCj32O51rmiaGyQo z`O5#y=AD!MpU;45PI(@3LoRz=`s^uO<Dn7Ylk(X|F~HY++3)dZ-=hIuQp+xT{sG(p z-u3~3u>qdevH>ZwLB#>V@yo&W0U<U19!Kw>TLA1ni39+We;`ml005LZ0Vu!^THpW> zEPw+6A$ifeC<q=!_d!NQPbyy8zSOp<vM*CmGh}A4scImHV38qe*IYexL;hI3`%v?p zkpiMGJ2m#O=4FXq<X59YAR)1gL_vz#x70ZoY5=@?!!7L87`e*6%>GgRn|rPgLp}~a zx;OQ}t0&`shsN%IcoMcaT=u_0V-G&PNC2b69a<UlJ!w2jo}=v0*Z@uXaJfTU^XHL5 z&HseP9)204TV#qmwzsVQH#FA%Ye~Y&eWY9^oZC{w0CFHW4W7qHv`|oig^S)7fHNI{ zp2@SAuePAbwUdZ4JFL>Hhm`oLr;?G01_?M8uOGhs#{xR??3o9JhJA`gX#O0JzQ-h` zuVVcHV-o5-7Q7#s5a7hp)JMyeU$t}Idgv&K<+5YaN77?Qj!x>1WRztR;1@KTM6kCO z2Ub?eeQB`!X61=z<$Ea+lKq2ImlYiYnK;gVxy9_rcZEl}Or#*EX-5AEjoHfHUCMLN zSzWq8wpRF@fBa<d=bNqpcR$~9zqI<fz$-;zxzO)c@N!Z5cv?-8@UDMyG|aJUzW9AO z&<O#FB?h`$hf){Je3|cV!+}sD6AFr}q=8YbP&soQEqVDXqS13nB*8E*`6wC05(gqp z$G{~MJipE^4G8y=1JVRr<N)CY7P$`23(R$TT2>0Xm%xJo^UC`n436^3#zTV`oRk*5 zF<&Z{34I0f>Vmbrujh*ch!xW2A2iO&R6KAZt(1Xd=w0`)Ml@BRFNqOyybbxf1e+Io zRtEk;@%T9lg5dDY;vEzHHS<MS=(^K^c*A-(T6b-|2XCXi(aY-+y3r>X*s#$rdU<VQ zfRL)ZIVe*Qx;Z3Y+psyT{A6u&ggBtQHL5ig`ahwutyf0B*S5w;aFuPQrNFuEaa+0j z+Y=7D-?t|{ntHIW`M12&Rgn7TFyI;if(1&+FBe}UC8hDwK6;ynjXt1X5131%x3z(u zwPTs29Z{Jq(sCM0#a9-z>Wf!F{|cjEg#K;id}{nC&7})JB+Yz_NcK*(WFqphi|@t2 ze@Io=lTgO+I90M>G?CYm6R_R1HTMDLIKO-w0_#|`1Nae1Ai>*46cCMQGj~S|LV!_% z4Et1Ovhkx-9++mg#mVtARRpKsMb>@OB8D*q8W#7%F6-u7O9E&gvM>PT(9mh9<0j^} zpB}}jFIMdwnT2O*Fo~Cg(j+>GG#xbP3dXz4oEVM-3SSX&3J1($b4}Sd1L55?Tnr#) z#kXLAZBn0fkaJG*iZ|{GKms(6=J;P<BnVjAsy0aCT`buLc+alOh^Ep6bf{SBdK!eq zLC*5mTM}K!>@!`yWid)KCx~kyWFS)4Z)j1(4<hGCJL7m4`4F*%5iwSAYoR>S4+YHm zSUl@Y#-#WOZ-OgG%N6O8QkGfHrNZw95kg1gyZHYF!Q_L?a1$6A9tVIV!a;}Ug-T20 z<I}jfk}QBZhG@W&ub%-&!itb3kBWD)c@&o=uw*XDj(p83-W?hZOGK`H=t0_mQ2tsB z9=cvyobWiprFx9eDu~copBnCEi*%|Z`{awAyY-P&B$fQh)?u7>Rn$-7B_v^Sm&*d! z?l$g|aX`vNq@8N)Er1nCm<QR~g-|1j!+6Aeih0)Ku7$F~E~=!MB#Y+Zo+P^gNl=o} zLw6Z--7cy~k-PvxMj;{D)%UEm@q2|+cf;l0;}N>08)(C$$2HuSzK~PAdqb~otDh3J zwdSCWltwKG0j~WrN9yy`V-N9E>D6($*th3b_GaM|6&zhE_4*R;B!b5KOd`V5A9KpY zsMv{X-`9U#G`(04bcVRdbfNTgmd;(S1KT@E;$mDuLgf334x5)wJPzSgg5OV8`(}na zM#f79Pg_XafsQ{~sJ@>N_w9t+-k9Ed%l!C9AzsjXH{+O<Jk^WUX7=gaS_Cz5fLP+f z^MU(`>aC_D?>=ZJ=cZqc-X>hcf3x5A)_K+5`|x((urV|#Wrp?nN2uRAg|uVO9r^x; zVBW~UH}?<k#y~nsX?%mS8Y55$_muKMT4PkLk_WI`rC_aXtHTUu1_)MTVzbghjE`ns zB}j|p2Yrup2Ay7f{7a#cyll2y;hCm44?AS{E%wyHY^Qi~Do|HRqIX#xrK#o#1asJY zefsHDz@rxf{>YyudidBd-wXjx^L+rX%U2vJbsP#Da(F*?qh;#36W1LTw1ZX73>}JW zOmk6@)W17no+P6hZbuNEuVP4LegrztNk}5UdRW4CA0agJ#*h9BkRC9=4qd!|_@knY zu3`v!lO$RXpKX>ApPWuMsw(9c|Inh4Y$OlJd`re1p|YT2w)WQMXrL>mVAOCq{1_u8 zU2DRJzUSH~rx}sN#UQ~Ty^+qNGx=^UQ8fvF5h(1!a*Bg5Gs7hP=KVEZzfv%8z@wR@ zdlZZ<@S6C#6;YGi>{_qqD^AA;+lB(^PwvN#|GaN+e12r=wC0@wa*Q_M(B*aJ0kp+h z5)Qb|_s~{ON*6HU`C0#NtzDWVfEtISU_OS44N=TJW`Eh;GX4z?fJE0pD9b#}!zfjM zfSr<WTdYj?%05k~3>(@&PoQqtJMq#PThCUd+)}Uqma(^e+xaIVAo1!R;n*_^0C&J8 zl;4Ty)9)hr6wpEiW9H8X>nT0<Ub4R?GfraR)qx-yB$3%RO{hKm5aaXi`K2})1%bip zcQo2$zq{&6n7sMXr`*t_B=J0L1^KIcTjTU21WakIncMrQR=oKO?Qyth+$&_<U=P>P z2L^8YxhN+Zh+80Q=<!x!aD$jkq0fcG{EJFFPO`Y+m#6y%7GLq73=4m+GM-w<$DKo_ zf&lJq{Z9i)^D)DQvg<HFRyolOkT-vu=`!N6YL>Co4>|jxv%zdra&NQ>%6mCd5eO)` z@pSgX_IYn;l7cE%I%)}f<@>i4!x)-kwlL5&s<Sqh=U#EGw{-DVulh9h1i9ty-76CD zZkDIA^XkS>z##lVjyK-3r|Hq1f)18jkfi;|=H44&p(#3Zb+H={piLtsLpn7ZvA>@l znghr5MmXl79l)JW_sAwJs_#xMe;zpypgFI-<s#p_AQN!(D#`IBG4X_@UI`uZ9*Bkp z@edHOUwe=rU_g&A*Eu@=?UG#~A6fP@(g+Tmt3v;JlIX?Z^@yOCaha>cAOD5V*i{an zLA#)_!q4JGfpal*Dg|s7^DGemy5%Um%T8U8>OHPI!bDu=LA~=rTD(SI&~)O;MTfmc z70@oc?L`6j7>+~9p}8Jw3_UvJGT0k+@EiY!hP!+-4hOvo=SmJ~<-Y;}++?}eWYOK7 zsd2Xa@9yBIZgJ&lo_ocjotq(Ij$ckY7mi{@VGEh@oD~>$h~!-h{`jF&AHo8=>FJuz zm_?drK7xlu$HMCjuQTwZLi`H=knKau=wt$Ta&R;ckCm>#66Rhjx9cN490!imERee? zK{FBCfDi83<z}siq1Casm(e&a{7mYF0O{kXE_PsrrwOnh2Y_zDECY4q!$P!^KdQ3R z?nM~dDTp_Nf&7ifED|GE^ms<exS~jWYJxZ13?rPzgX=}zWg<(+xHr1k+pRfD^B#W* zQE%{mR$90Z>*>P;FX&w!wb#&bc&-KqDi{tN(mHlCHF~_qu8@(Xv%xN&!{vJ!Lgn%- z=8xyGj+q>QFV8TIbtSPIa`-m7br;P}=MT5-30&eJ{xYAR87D7=hFc+L+t{&t=p5Pk zuV0;*Uee9Q1dBx?Ze~5&LXthFe)EJrPi+|XW!RCpfQ;Z6!H3c@^Z0_y@DtfQ!N+Z~ zF2xA0F>y_GuqeQ!mw;I!<F=*?5^{A9yi!2wA#2rzl!_BYcpa2;Ufx}S-+<S3JgSav z7#DyqEGoLH?hoSd%Cof0gJ3?=vZ`YQYJ{-alerH#1zC8^l}Ow#A|~WyNlFv0Z?1&8 zaioWVb&x4d3ojjfClCh)C{yu0Wb@&+(hD0W513(<c4d@#@}d{!BN01!x9lQo17~#H zbs?r4t%<Jl!cF5#+bQL->e^4dJQl#%8)4@nS0jLR&T`J%Ase{m6a=adwNJir5F;?+ zbv-j0pE-&9olpi><X@J>_X}3=$5sdyR|vOPh`z57e=pIy9Sqy6IOmN1!qAr~=3k<R zg2!!ZiYf!cu~+|KIhMoThGB@s{GIIS$@f)97m%e4x=9E>gNE(Zs<thzwr{U?cwg<b zS4|dXhsN$4ce`^k_Ks`u9k+U--#YCyl26Mo{)|CQ8Ao}LUCk-yiXdUW6?)Fuy_zuL z+6aT%D7V^6v9-~~wXyBBSKrsh@6{#<*CiR$QQhiNV(Ze1>oVHwuCw0PW$)F|gzx4V z+_mOL=euz?(NN#W1qDcMy%y{nn~JhxuB*X#yg|J{IP%ZClDc9pp^19Y4f7hIdUNDG zY**#(Vj<93`M92|h>26ms90GKD`ukqdSTAH@y~{3iz;HiuID^=<GPoC_oGq9kz9Yh zuCv=QcM{G62~|@_t}7Jmzjf?=K+k>Kd_=gB%NhNfi0Xy_L&J?oGweU6qVgUp#Qp(> z%W5gCW<P|>Q<%Zyoe#OfK$I|$PZ{VDefbc)T07%wm^~;FnE?Xoys({22FMKCOEql@ zL$wb#!Mkw(n7I9fVwn$CN>A}w%w{5rYb3z}=YktxL4dh+WRo8LxgfVU5ifSD_E#8o ziHJRZ3KtS(pT)SQ;EnLb`|{+~z9m^O0qpA_#FostgGt;7Q*rtRT((K#id%Mw7Lrc7 z*sxj(&J9XT;I8$l{Y$qlBk3)Wac`M75F7~96|}tFE#(TYjYx<Ilj96Pk8DS@3*OiY z!N)3bpImQ_l){%2w6E?(scbaErSK{=UL(cYjKDVVxVGH5;$QxUHCNi}O4{q6wl{oe zZ~WWN5P8~c_%st<4%-NBe8>1ah{z}3Lmmc$!_5wkVYV3ga6_zKM%f)j{&ZRuj{*L+ zELJy~uaeO!R^0G|c>7H!rvD1x9?kFvi&`y>1X_s2F5zyTg;k|UU;<z7&+*v8Eh#_} zHb-sGI{b9E<i#GUDr6~#_$>>p{v3H04W37QAv(|WG<_k&q7Gr-(DYvnGOY6*Us~X{ z2+kNo+$KNrCaGzL_LKva58}ENN=J=}U`7a?93{?ek@myW&HI2pji>$=0jGP|G}w~C zBy=<9p11`Vz^yRzXYZ-V-~~(ZZF3z*W$?ggBUdOsaPCsgcA?5yhVY?Y3-m+F_23?$ zK<TNz#|+x>YMqTc_s?}C&8;7<&R!jy-hp|GG-uy^-e{TuX#81+!Yy#F<KIq<VJ6qh zsA{m;iIhR!5CDh)+Vfa<2iAJw0n%=vYxuRTYf+1&+y>OdGH>{t$t3_0tz2sEZ|Mv% zInuyYf0=XBx<tQe2$73OqCp?DJqK?b*$=}kF;F!85YFt@4@l=vqWds?SU=ZbRjGW7 zjNOeiYp0J0j_dFR<8x2(D&!knLL){thdS)gy`4Clv^>#y^vSMaSQm7G6Uz)6u?gbN z!RI+kB7Q5CMrq@jZrs0bAzw`K{y+mijZB=W*cE((kMpo(uCtI;+8&|v5;4h8vR$A8 zHm$71S{YONI+j_1nUBW*emZuvE|lef<#iMq0Rj0Z68K`V+%NCZD#qgw*e3w$AF=V4 zcR9>^;0G(P@0K^5=Mw(ap?EG7vcX0u<5^-!TM>#2)s<kXcu(+dk71uX|2Yw@z<{C~ z8_?<`{vTj1wt?I3pWqcbGaxYz#_>W|(?2e<2Xzd-B#B65BF+#TwJh37q%q5Q>?(N* z@Oq1^n$SLmIaZC0$Ee?*XfoLPPoVPaIs@}?Qh)22{XX$qSUu6A4M;G3^Lq-Ti9J|< zX24T^KNlVkARNVb(Z+ZhM)T!6QN;Gc5IoE!j>ilGOw(#lc(pf7f{<GHcpALIu{nf3 zrM&SlJ_KUs6|RAY`8;nv1o#$zgAEw-bUv@;ten>1Lfkj572(%)z^lQp%*1KneOMz+ z3^edw6K^*zq5?=G|H2;{;~l&p-^EP({=G(C863g@5wiG0WYDil#=yA`z}zR5_s~># zL`NLs;W?<c7l9~($P$@Ncb_|Pxu-)!C_KR&pqY=o<&H+r7q_5_7;o~N2h=4$fhB8x z`kfzPPTO!#pE%@JlrUwrIRj3d=Jj8&HeUc34|e_TuN}rN-XmmrK`nzaL0nDquT$V% zD8&wG(J9?KWfm@n-jU_<^{5m7y2SjLoS9p=vcFC)viMT3=}92f$mjYIaVNf5k4svo zPd18e9(MO_xw}kzm)Wz(q4XIvj@WT~clcFPDfykcl6H3Fc)g)^ISu=dl~9@P)SPsF z>F?han)qs-$!fmm>aF<I77<ty0E^4>6a4@^&-@6`B8eri*<o*+qLIu*69p~8FT!H* z&^r~S!K4kQerN$b47rN8czagh8XoaD9*;*_e+zq`s)vp%7wCFri%Y~@6e`VDjUOAi z9ybp4It|sE#UIR}`WQ`2r*y)Mz^w3hJPLRchSOlcSaT?_*^kUXtaa4G;*SE;<G7`L zyvq)f#pK|?bACJT@dM6jp=!t^V~5HG=3l}dG4!H4@OvigT>^0M>W4^Bap!PHd@dZ) zdloeQ88MH;NdR1?8$ZM^*LkIsJj9*z6gb6%U27gA9BfFk)Hb<UI1wd^^jU$WE~v*A z`)*tZa()t6IK0{>muXuc@e9;;<yr-lL0`nHZ(Cj1=I}xs%#~k%k4Tz>O>Y!EC2yj* zJTxT$XeWRsaI77C&#V`%?Tz#r!ylCZ#KHhb7>Y$k&v>H0t?wkbp>FkYJ?X@9GdX^f zK^$br6E8&hI%fyLMEpWsX4SSp7xoDmeS@t(z;klYfsS?L6Y`(s^<Aog|1q8|d^r0A z0GFG9m?m&=5MgV~-MkldI##a*6ZdY@{&uWGIXVG=xob97cZ?Fs>x?eMp$l0^X}V}f z0_N(cdqrZ{S0+>CFMiw(LtQ!2yc~cn+xp3wyN>K6{uIr`+#dVB@QE=6wO%Hej7c!Q z=d7+vur^Iu+h<riXJmqD(2-dNMA;bNf_1XLEr$O(nEui%1tVqxp~Dv}Gx$_IdkdWx zt+U09;~_#vmu&M6IhI>0XgKgu+zCjK7s9_PU;Er_Z_%+YPUY;-SW9pn*~|j+6w+N} zOFNoGDl<tIKJoQ<{fYbaP5%=b^LQQ)9oabCW#s*`+^Xc{celsrCLze=$^VANzU$S{ zOSGf^9Y95087GS<|2s4m$|TPZ{x>wX74WL;OZT>@+x7}G4M>oU(;@sH4vYlE0Ra#O z^j{7vYRmY)I4~C}SAy^V=D>$%1*d%pxI~p>|Azz5a7JYH7aIMS1CLkPW~JEue;jy) z;=?71;Nk?)eCz+qf$#B1|5qONG;+8)+x6Z5aA1$r3mlg9=1oJxiD^HOYz|Cxz0LPT z_<uNXg@Fbr?teJ2&Nbey|341==-U*-cclD3@~{uBk>6%tK7I1@Qzr!_;q<I^V{!0? z(wSG!+P1zhs}A4Jjza(XHeJ$48aJDxCgtiSu-32kC?^neAKsHt_5=gmz%5t36|*19 zS!q+>UOeTX!USfY+mK~GakeCY3mqSSN{Y-XNFwovl9(tpfSAZ;s0oCix9TeuZYiSM z-B<ZT)<1$IYU-q{axFofFu{=McfxwariHAt;belD?83@o4mcc`ClLeW$zY68!dwav zO_rdM1AZ@M8mlh(<-0ZxbU`^ei#`|Z#c=+=95|@v?s9SH<JIMouzrOvrBQE#zm!EU z-~Cd4b!YX<?F5+O3Z2RyvQm*ITfb6yUFYjc70p_4wL1S~$m*TKfcn*%(o0`gYw0P9 zU+b!Gg?znRSMwiv7<XWf=?;R`l5O15uXy%eD`@?z!NbiEn&|<08)w)xYmaBNMeL24 z0;3^VU_|xXVdbV7b0^~0?Hh+x>z+;IFnVB5u}z))C2N%<$oxjqgT0<_2II?{NV!ua zjbY`?(uzKQT4-J`-%a*Vg~08gBzsj*)7B9NYbJ86{fo(7z43A(kBVY>9S5gSOJQ?{ zbO>E)Ol@$9=ZH~TZ#Spn-pa!aDVm?gkW$^+;#l+IEKhjF$V9uU;hG-0^Cb(f$tjT+ zx`|TCGXjw$3cQrn<ZhHk4D0QWRvnftUEj(f7LoGM%2m;Mht+j+PUG(z!rkumAX&a+ z3h6)?r%Fq-dfFkGZ!Bpi-Dl(;jB%aTW}0BoXyUNJ?@|q<+V5@YQTYe^53!G$Ttojf za6X*exji_`qpMTC#(`9+O4v-3*;qMtM7hz=JWZA{>gy;ATql~N4&?(7iK<ecOlgLe z<|wgfn{9<H^NPsOM}BM1?km667<hlD^Dj=P79eG^^To}B%3I8;W_dvL#+W8hhbG~r zm%J=c8ZDhkJU90z4jVm>syw2xr<ZbwO;KFeC3%Y2{d?uw4S}Z~IAN>!7;nQL`gC@C zPDTqK%I?aE?F3<JXmDNXxUni41b7xEk&>9nT2UMbX)kkQE$6JrHFoL2iVbns4CjdN z5f7RikYcIMBad8N;K$vY1%IJFZ^=!<)7cfIy9~2<G=;ad%0}173=Sl8Va@{<0+6>! zzlAu^F$^xA?ZoRQD^<ecQBZ>h=bRY#B=LP9bxN;`^CFpYUSE`-IsMpDyD#G;>GWF- z4M|S-^#$$%8r+nwjs&)o!~rh|FtMIOOzJ{~kb5K>m`VIZNrZ~+JmNY76U#{A`^7FB zwQfQKc#7zy7MSUvWLErj3J<U4fa;}iRHZXMC|QeVM>Ie^!m^TwE|@H<I-c3Z0q_8w zOA^ltQ;89hs8|3(SO*Y9v?UB2oQR21$Hlq(2yWBiYFgn~AN-;y!^_gN+L?uo@cYjD zyv4>KMe@OE0EitrUITd<{?Nq>R8l<++1u&LG%GaEyubmLe%%Qr?|GL-BNW6tNO%$Y z4d^j1D6l+_Jj(PHT1kK?vs)uP+RX*O>alBcE3*B=q{O~<rs(f>p^jdaI>-6)=zV}_ z8-1U`d!6mtk`GU}-(m0o)2VVgoN2_U3XJd-3sC@{YFzjRn?M*u*b|d>nxsU4=@c1H z1FT<yPxc%zV5HTRQ&zbs`Y+mA`nB2gsb3Znlkzp(H}<3-H%VVXDuu{ej~h9NR!KAg zB$XX@2lN7a!wA$$?0dn1!izY`j}$R%S8}4L8KJiDko?Jzcd;yGiulKSHd>WUxT64% z=)~Yz)2k!cU}}}1`TZ14FAin8{*%~2KV?ctANd;HhqtwpszmBS8ofU!@=FjQ-Vu{( zL4VsI#i!r~%}X`~lJLc$5O%UI^W10^KSOjz!KVp#<!vthFL|Ix`F9TG&RN%;&QN7x z`Hy^<3GuZA0UeF5wEA`s4`a?oCk>I{jgY~5t|SQ~a#Nct`Ee^41-F-+2^O!rFyXdm zrGW&rYbZtd=^T5uNmB3V8bxB-HRVW*B-$~do43j<SwXxj!;J>wuMV>!POy0->9F^2 zR~t(0*&P2<4#MSWALT=GIsNK<1?Zi9CO-4Y#3*$ZCRJWNW3t545br~XVNfK@kq9+E zAE7_3mYQ`<^RcgeCE93I9o32nYj%(CB&mOBfz9ft&3V&a+L$aQX4nNS;7^Ao>tE%1 z60jONGSwwcMWNFV+xqZUwOVTLB&Ht*=;G}89I<Am+eFPyOQ()fa3Y>M-r?OM0Zou? z&CPMrtGb#qn4)Abp00m=L2xrVr9x939nV`OIN#Z?znh!pJtHmpZv}2T@f;fy+Kn$K zLFE(+8pBoi-;8vX7qD_sj)j#xk2;|W=P|%BKTR$V04y*8Al^*;nGbjg1`_6AhSMCl z!5^Bk_4BXJt()`u5R;W+)pML%lO#T}68bg1=5l(Jf`!K!{d(<Y&W_t)(JzC4^astd zFCOo~?$G7soDz{?@}nNR=bd=Y{K|1zOX8)?B`Z0Zpidvu!h|5g#jxQU+n|zH!F*{F z9ogajQx@Xc08}>KJ3VI9H_W#Yu3Im8*t699$=o_jFQgskNb)UMnpPMa;&OFrxhL+@ zQmoEj^SN3Yo@>VAk?353vJ<7?9+3vL_U1CC+K8wyal?0#9iD2SZfuv+&LLtG=jo*? z|AOg$onkW_`L+3vk1H_a;&Ah`(Tl&IdPFL}R*#NYdM5gO$x3?9`+CK{s^wbOXP-sY zMEyRZ-LQXcOl7;+eZ=MhG$xc~btv(=cA!UZwb;|CBY(e51Xj#fpZFg1oe4d39VFDk z=rf|`;_PRpg%$vyHQ~xfBJM-j<+pgui_4fPGHx*p`8NTZ_{GJ@1@{kc^q~qn-%0*P zJTm?php>w4<cN9q8`t!fvw@DuW1zk;P}6=UpdRSY<XDBBu+<YzpstI7R!$*IDC!Gz zl8$QtkXv;0KO2l~owkAXWj3wQY(cH8Ux|TYflgdC4V9pqm}C=e(t=$Dj?d$<Y%aUC z#Mv_uEmbH||5lYWiAy7+-rvD3x!`Wxz-*J$*lsK;10G9s(+;BCd&CRS0;{bM)qFm| zBt*I%W|D|}&SGHRccL5UxYtbkYGT40+LaLou84v9OT?n0F|#D+A}`zoAu&D~3+lp+ zctx&yVb9bheqG0{g#ABUoq0GE-uK7H?3giR$-eLF*vDiU#!mK1wyZT2jis`sF)Ol6 zs1O>mCyi2}ZOjl#H6%@?vQ@VFNR&$X&G+Bm|M!pkJoh>G-1|P~yxwB90Vs8OheU$X zQ9;BGPOOzFdaFY89vk%(AU=u4`!OL&eB!_-q9h|MMg3&QEf|RfE9hkitI9P@<S%v6 zUwp*x0P$Nm)Y}=v&5WFC0rCk4b&(nK;Ac+I7NVPf!0t{kARzZI`%qkH=+X>L#ubHG zNEp}^c^9K3h%>(qaBRXMje1es=(stKXw(e2Ff;WGfues~$YBzyTTp$Quqd{dkj`}~ z0Cs{8xr;^)&se=dqrCT{-U9qn@09vs!~%8}k#}{<gyfa!7K!$@BJcpJgq^a23tg5x zJIj{%%Mq`VL|mAUfGH^Xw4$#IDJklr!nU)!0jPTbab5tbWCk2A=@;30ZskacySii+ z8^!>HWyh84+m$fY5$`R<ezOoRBYvN&O2LcNCMM!Dt3s^p)D%&oo}X;5mkDW*2wg(W z0zy20m0c&Go}fkNnP-CwnUYYmdh|hx`hiY1O2}J!jFyO7g5=@gsnM~D)v<?VPe!wA z-V$7>L}6+!Z}|ujDvtn;ST73&V4;|j2hJ~ggGP{j!^qG4LZMPK4*)diXRH7u761Te z1IhVE@XZ<8U-fG0X5H-04C*h(BdD*sL&_vA4mGx6O~r}kvc=g%vAqg88#AJQ=u0_U zM^}Cl3Dyt`CPaQXFcJsPCYARWUNW>puJc77Gm-BJM?K+%)i{)|067f+U<xI2U`5m{ ziSFq133UG1r2`~c@zyoeEG`r{(6}RCy~KwbWG6j$^IQ~FJnCuwR$83R6jdD-S695e zJ_w26U)c6K!Y&MJh5=|Z&`3Tco9F`Vh5>N!UrgjJ)|tnE3ZWc7d<FFeASyI?o#xag zJVIsL(q=f}p?&^C!|8&);B9q@8kWR1pdLV~q~2=WdxXya9$}lL_+<_yROCz8;-^XC z6B!a4J81Zwi{i4QHL0Wvo*iMJS#UlPrs4*t1i-R|P^6;rNPzeY{;{&Qi<oxQ^MFEa ztClBO5=tE{SuaU11Il!Y%49q<Ti3*XNYXv+B(uXLw&`NzjN|!l6dZz$9)yNmy@;UT zP^wMh8C6g}94x}4-NrNQzhF4f5>6qO*Nb&r?tq<|fp9s9F`Vcx7IIEs^u|xba~m<X zq|ZBH-&b@?07imuP=sjnVX~2Tn~K`2((Q+f>WP&`*^-`x$Q_PoxGZ^CQL!E$xicfm zR(IPV?Xev6yBBZ{aVqSHLJ7xaKXwh8%z*^fTxwA4$U&DsWuk7Lzxb9U-hxI=?yx() z<HYXHbUeutn`WQNYHjJKiV7Kh&Ib9EJE%VZQO{A-HmlVbTm6G2T1(0}_sUM{tU?(i zW|bvTh}$=|2Iq26ojB1AG)g!md${o0!;@hown7pIoXlxA3cr&CfQ~W|ztqKEu#nlJ zwclqD&({!xS+_G_NInkbX5-PQU-q!or<#Lwzf|{&kjt}1UcejiZ}y!Lvy%OeD#0Nx zSvmvMtq%T?-y33DqmH1UeZOPve&bM09B>pd`)}X5Lr3-l0C3-EQ0yc$B<zlnPjd|u zb%DB15{tZT)BBu*d_fYGt0~O5lQZ2HKE))Bb4Y?}(dXzsPo>PIo&6Fw<;5-2#e0bH zH>1T`_~Of#9xNM)_0J&aOz|f!R%2=XmE&ixN85Tmf^V}>6n1kJKQM=1bL?#%g9&Lk z56O_c#|?*_B9<pHq4zk5{3-D)yHX)ulKj@Yi&>k_=q<V``iDunp_uOIB|N}jQge!c zB=(djb^#~ei-W>~9XBQY`5ip0vQHa7c6CqTWdLHF{IF!e_(>yrn+Rv|VG7_VfsVhQ zIz_|iMh^PS-4)2<Bs4?4SyW^ok9F+5K>Q*L^;Es|B3s-hyzo0y^rUCYy8t8rCpILH zRH<p1iAL7K*^6r^|39L4nWCL*@h@ji_Cf%E10;%e?u``R8xaUWRBNbKA+?bt5jrYr za!Ne4!r^x8;K^Aut5X<AqLnOEE*kj(C^j!Cp2C4dqx}@T{8FP+<62=kXt)s5Wdi`u zEL;PuwWB&OWnR4lBs_XcLUcxxp5S`FTeYO@9=>6O*yNDrXBrT2WRI@Ij~VgZkHor& zVs~WoIk)h&Li!Vn=Iz6#v_A8GBKmo)?_`a5KS2DQMRe<@(KKfx;uZ7*zGyi+vT5dg z72lg737*0pL4Ah$0>H2sEgV0LquhnMcj+Al`S%LyHM<!|xVh$y>Ox<yCS2d_M_wUH zJkTqeAtJL*9rbS(e>;@Cu@;vloBn=>h}`2U*2YIIN=oc$?(tBnRH=M%qs``T0IGiN zbWLtFspxsU$YZf9`#RU)y#ciw9N0PzRYHPBa`OIG?*Rt_!Q((bPJ5q$<Uj;02LQbo z;PZEPEvg1t$wJ!R?)Xg-<+9x5YjTQK;@+wE%(F(KEyeoz2)U|>@qni<?P;&nb4jmW zNNv3!zw)VPM+-=mM&8as99Mk0_!5AOukif&Wb%;6<8lwNCQ@WM6FIw2{5wZH0zGv? zJ&3&oBWHqsN`al(3em_gfaCxo5C#B<Z?}pkbRyc8#iEuGlPqhI`-nb|QwqysWP|kg z>gn6+$Zlb(28dNhOB~&)xu4Z~3czZ4FX>ZF>R}>Z{~;Znd5wDAnEyN$H6z*RX(e>N zeiPmByiwX}hZEUyTI@3#$yBdRWD`%x-GC}T0yVh%viTq>=xoOgX$Q&ItUE$nSXMjo z1y1xlra{5zTKewcy%?XT(G!5RSAzlK`_3aJy|{z?-qJrg!0vGCm+&&=Yv8$}U+~aB zA5qK1%C9Q*OYF*j>d1Rc@jE2Tt-rD#U9A3+#JXqf-&vw6XHM2|j*<e(>H68N%`@Nu zATZD!C^E~+o;tyTCaWVxNzI*rLNf)o{5`$jnTS)ar}{4D%<&O5LWK|@v4}$`E{pwU zqvqH-Y&PoTPQ+70?;^xJy=v{iQnKWp<`KtV?}e|DztN}xl6Xyk-P0QjK@A_ov=9uy z-nzCT(-T7PGPk?{7=_KyyAVd@>;|T)0XRS{k{=)%a>q-On*&QcFZv9P9Allg{N+>$ z0F0e2HQDXMCw?YcU6ztZvT=Lv*qplI>hof{7g2S<!co%tJp9jE%W=b{MZSL(O>C9j zm|c@X{n+Cawa^6+^@A+?o$K#u6rJc1uVtfVj*x_kWE4PDUExXd&~B4x@NH8`W5B0q zz`)_ZD*!&^1PgVSg<8If;;JLKqi=ZZj_I}Y;H_!e*!^wv%Uk&CPY$B0nBsrbX}=ZU zf7mgVoF|3PchRt2k`+C<vkD7eC2k4OMtwv$n>qL?_CL3L2dSxyx*4&P6~$MW2!{n1 z9k2Er;t^oO8aNOXqY5oM>7w5bGu+d4iVx`y=oqsUK0*+a9Q#iN)Kd-_X?IHH!&+Qz z4*p`J(tp}+_P^RxPcOKC-QwSumt%+WJ-!laBuOXG_p_HSetjP+2&YMoN}k=ok1yP6 z6dIf$bca!1bT1)jVwrIv+kNGzDA<??1P*Kh2f$sqtW%QXlFF;UIf!+D*cb~*Oz;>% zqbNQ|`FF6BaO97q>*(gWnwi4X+|PZdj^>Y{2GO+NVu0eV`+EOK?{j*@oHP4&qUpj) zaT)4Ym~ay0u-#Ao=!NIfqQ9(*S>ktza9)<^`9(+u2l5G0LMqt27zXweo^xO$gd`2Q zqudb;<EQ|TqSlj-5FGvB@0AHJK6hMraAdMA`O;@YIfs;&gN5^tuBn>Y^en%epZXGS zTk|f2n@0Qk=2_~iN1Mf;o`&}j_S`>+zg4D;P1{>n4&wLBhI9b<17a7uE@MvsdTkaI z_eVawHv7*D@3wmRVMp@22Q;Mv{|_DpQSR+>;L^VQ+S6%J(dEqMcgGI-SL`;6hR+Vv z9!x*%l+yABpw6Qg({-5qHfJqy4J=|)J7kges^{47j?L3cEqmWud40c~)%3{Zb@S=( z9o3yv*HleB*gsVKqi*VwPG9W#qNLYz<awRzDI4V@CekmO7sqU^kN-;!&g+YME#8_E z+20j8P=r)Use2e&JNDO-p)vr~X5&C8SF|%^cRaI$EBFOd@{AVwxGVcppX=q&38L0n zhaUoCS9`~?D?M~~c@dIKU~~*sqcLD^*Pi9x`BJLlL_$q`xd=_+T}$=wuCT>aC?*>> z-mH45WA?CGl>E|=OiZzlsjg9C<L7FhPa=AX#AOjZU-P$O*QM4cwEPYGwiF&!oER*6 z?%1(5|JXQ4{o7}?li*`)f2SR=Re&?><BBufAs@V>;F<KAQE~1EK**)qW`kU%EdNNN za9n_T0bSVNEUG&J00OiDB(3vi)9gSEfW<ge;WSnxK{bXd!a46(Fnw4Fu<`n1d1@@S zt3FtNR7$$4>1w++U~!fvlULB^?n^u=R^fXT6WC#IH6Bq`dwQ$7ss03@%Kw?&H=hG4 zXINPu)f`@H_C)3UH)MP0^aqP$&(A0h(9V18C&$-^0@f(vPNv9jc&8r#aIuv{*5a(g zF5o;&N!bo0iV4M$Ato3pU4>-dhWPqpH^y}pd~23AZI65sV#%^ggG*%tLi*!t5~`a; zNeRmeIv2A$ZrLOfTh>PveJ3`4yd@4hB<v`pbC*8vJ#m$5R+qu;ZdDE$n@c}*^SS$; z<Xc}XiqY__1`xnonewsnG&~SLhhL4Bw*(m90x_-n1(XKGn7eqCZ7tIoDi^As-*K!w zhF%$86L?rLTQxONzO1I9Rc`+?gGA+QOm~)Qs71a3mZdb|A)UP}C8pevGJL-w>5Srk z?Z;o7JzIMsc68x#8n-b0XxFzF|J8T__|kyvS1k{+SFXb*lTUvA^|><iWENO^FXBfd z(^&G+Dt`0Tk)2r6MUu%sYSJ{1F5{DF?*^cDCo7)5@$G{?-3swM8L!5bhX9TRp<-AK zavOw4_UM7L*}W2km+~GxTQSHc1CyQb{=1JHW2MATxPCdc2;U9Z>Mjo5qWGmQy?OOd zqu6z1B|^Z9kvP%IyDy0I|EE8!laVUw+ZHF&)W%SoMEBm`G;w7ty6jffe7N;m18Jcz zA_R~~$^oKPFI7QOY8p^k_OYtUS&wXbG@L^x;}mA1A8DO5FN-O_@9x}FiXpjIBu#2b zkMc*YiME~%R#g3Mb%^2b*-GgSnCad?m=>qI^ct0B8lmw7%bi6<!5h_b=3?~S?7Wq4 zC#&p?K(sS?#aZ@7a#3*V?nO5H$F={CtK9%;Y;b4>LERGB0GtX3SECGIK|G>e#N%1C zFwwY#7c&(5-r3?02#V_coy<YUHfI$0aGa{!+#{WG=Q0QHBdSl?;jrY^o{mt8S}P9X z<hylu<{aqU!Xo3<y>;2XTpg!>#37wV4{x&EB<rWeq?3JqVOU1KT0h6l0WJl#@6<hg zVL5!JAKiW%-K0@?$y<sHprS(>Af8OT{^5qQh@Kn!Cl}$?Bx|v3<2dDBLAfJbzTB_( zobG`+s8xqXNTb~&pIcf@wjIFI7bS6OCEx>VTT*A!LU%b`+^E6Y{3`mXJbCpH#E1+B z0n~2rRHH{=+PM5uU*9<S$bzcf@IasN!(ynsHqdV9tdH=TK_wAJkaCT5gLw1Z-{5XK z3(jKNpW+mrXFl3Ne-aT39g~n#$aX(hZ+`W%7wm{LkAHJ=X`mzGit6EP!w{9F3#S1y z%6|)n3}({z-7TQ0t#}SPZU^3G|CqY-u<mTkKTCwm7#{H(=dQchAc~gZiYN7s6)bi* z+6zRA64j|CZ_=~?i_R!4UrmyvPLU$U$iHF1?1S<lfCbIn+yY|<w0Y5-wwCm7A%UZA zpd?Tmgw3%p^d`<0A$3nM_t|+^$`6#CuEgKc&-J+zy&{?u9cSEgU;Ds>@Py-IRqjDj z3fxx1zx?%3I9=tTrr0c=N{T@NMu5#NZylWgq>I;Qj~)`?Q{@m%R`#SJo0Rj&uzOmv zRyd1Y#yjO2&{AN@WR-$(<>u?OXL#jm620n1Ty(SFP+d1^2>Z$FdHd>>TfvEssejMe z`*4|l>!J+1C@FD3e&*n*M>q9v4Lf+wkY%`Bux+de9q;-$_Qm}+wXQ$05Bxq#nECMx z0Gt9>u=B2a0-@vX0KzkVUb#}}nyikd=B~x4ZVKFVdqtGXJOk209z;91FFH>ESx;VJ zhV|<;{9jJd_Fm_|xpe-NTHfJ(Dj&BPSN^4z+1tK-jh&2g`sYlKJ{PNcr3$7sF%w~} zT+>zf?C8mK`-cofY(muZ;LRHv#pYPD?Dr}U-B@+1d}V{&tu_x!_ZW_5;1z{U4mCYC z=-JNURI*xxu6AZ#n#A5((T)dE?xx$b)^Xpzo5YF$h6X0evI&jPPUf8)aVs_Z@>ff~ z+|ymjg)5dlEtI4eT~zLs5ccjneEnLI=e8Ws0I(XXI5q;)agDip*jE%_T&AucElH7g zZ9x9vdnm1m*H*s-O50uyvfDQ&1`G$y_JKJ5KhB8<;gAt}xlin#b*K97pST<{uD8yn zSMdaKDyJ^q&RNhg161*pPqm8adpKrtcN6~GQ8(K2k5c5=M3M6Fb~j$c!S}3{ANN}* z-rctNZtGpX<heI)HhDTl4cCtq_i|{*vzrn7H@Lgbk{Ft*1Bh(Il@F7wYBbxASW~bA zlAi083#2;b&V6{Ms98LudHF`Jb-O{tF$tgj^D=5@w&I+Qo_l0O|0eeHH(7oF4mD4c z5=zqC?Sku%>&L<}f85zIdlS6v6kyIs?sa*vK^Sb(l8w9@B^FD`>At<zMccBsnxW-- zLID7X@SmQ*Q9dnCn|wi!`UcPD)4#ojc{3?N0$R2@>%#~&nV_<$?z|XEKdnv+#=#o5 z`c3~7nl538OubLx4{j45wCSTxu*&4QH790NPh>&>aJnZB95Mn6Cc(n1AmKRZVH`bi z3zDf1aVvlcb@|9Ds#hi?Hj@^Oxkm@s{gmdJcNTRUB0|J4f9{&$h@c(!5prQ6Xest` zI9CTJ(BD&4wDrx@Aro!}cR0+4d827NqjYmc+NnRB{V!;Nl8n=B5U&x&K{#z63l<wt zcU8&o(#-uVbx1agG2Uq1Q2<ROKogfP2>%E40F%YHY~C6px)%~M1CHWIo$iGQX&X7c zj2!lZycyV`u^J)zE0(01*h`CM!os#7VFlojUPz)~Plg6BvB~{L(xv#bCZQbBYyb&U zAiv19ALAI^pR@lZ((;@_eZ8jUy$GJ>L-+1+P1z_It6@Zs!$NrA3q|xy0?oUC5z41t z&bMA7l;1W)9~Tr-Lq`7Fk{}WdLq=$MIJcQ@u{MjFJGm2vr|ixi*!tgWVptVD8~_t~ z50zKyC1PM{0e34y_9U|PVrHmfAp4w|yQ%W@oJ(MT;TG}sYVkIUg^!YC9`CvOU>W2M zUjjywXd+s)L^ue??q)10-Cd{rePU+_1ek4|kFSDe0Z0?U(7ow2a8Y%#JTzqlW<#Q} zePljJLX!lHgPAa6Cd_8`eiFv{Kr}dm4P_|9!k%1c9#_#Bpr)$B5;0}wd-k-=!3e#O z8)+ILp3dP+MmUa<v*wnurLG*}`#sZSZyR)PM+H%z@fNF-KBF5X52>R{I^+uxu}=@L zT-;eB$FZpKd`L4Ggp;S5GQE8R)pnd%GGlC0(*VkSGBVm*ne!N&Ab<eYy!FI=5_)gL zewUP?S%=ZIxHedJG|jG&lTe@@oXOZfLre1%qE|~Zl^9o~n&eh30BmRm2I9X68?5yV zv1k0i(a!WjTv?D{dHU%sSl(ih67{Tf*j=eGOHB0x<a~YX2sEOK8nFh+3cM$n43N6? z^i11cF9GD362xo^<PeH1PHS{1uoFsBhkmymcufbp(*1DIY`9M{iF4|%!x2HJqvx*h zKC`NIIFm#T#lgbiw4fOnafY7d`Fx25iy+aEzn?q=S3Hc@14#NF7r^$))6-Z3=!6Gt zgaWIIht2{>C;_^YxCYC^!7jR@itdTG5h@SmT3#23fxa;8Q+N4cXqnFT=>onp@~Xrp z@E8!_$$|yJDZ9FhX<mU&ERaD`pdb@2{Btf$z`|M7Ts|W)0IJ+fg>n7Pgj;(Rw8gZ+ zJgct6kc^M8grp{Fb}ucB$=HvfWQJ-G+6rT{%7K3hqu*J8KxOG85I679XRbq5^Na)0 z5MK^BHwc#JxxeShS*v+!M6Y7Z3+JLsQ-6E?L*;1)NRmU+_AYJ*9C9SztU^2hBp*pw z5P*bR1U|t9?tG_|#E#Rpbj%hhpMB}Mo~%qh<E;7>56<nkSG5RSTDp7y;Tq#cCoF(N z-8oGNN+Qwo3Sh6Vz=)yrvPgQ0By>uFG5g(zCGUtYqSFD4bQ~?d+4))1K)NR?x5jX< zJmd&w>Q9JQ)rq2qGmIld>8o>7+n$UaCNx#&z^mH&j1zByEM!h%LcE1^*YmGj+Fteb z>u>hy%z?r4#cJLnB=@S?(FW>~abyB#(hmbojkX@0gIF!nvNNG6kC`_@R02qa`788< zs=9*#R0Ex}dA-8D(vVy^#)c?0V&uOnvAENas0ziuO|MVj7@?TKhybw=<^Uty<UWp( zH$zS5*ZdLab<0Ow+o}onev@kQs+AVGx^&S&gc8RAA8v#AfkD}Il{vCfJ37n2kDU|% zm3HG+NeO)4@m*E$w0&i4-FOc8vX|&VpZhCK47X005nj|NA4*`s4!2P)GiwzA<ai9s zOk~VlYK$&fM8MICiaQD`>4#h)`}q(8Q!jQ+>y*pTgUoB8I9g6Y*~f3Kw(|_k9&sUI zM?ATprQ{vVQE8JR2{2WNgpV6~QcK7odWKfsr@M{yCvvOkT20_AHar2%3S6Y-F4BSI z&XuRsEO|zPkSk;d`9QD^T^vkdvo6ok!#iPa(O5W%oGr;1-1}iO;ZR&1*fw$u7G9Lo z3kd)~j$#;B;AQRuA27*H_X$O5i;SS!Yry)VMiuevugi8KFp$DO3?=f6?bJnk5x|)& znlB%`A2XOp=qdqHW!{0Nm`3)#ltbqjxqOI^d_Q?#cmfj~EMQdqDoD1V?OhuzpP`5D zrSAjPiBN1)s~E4$OA~Mm4?@2riIUd~$<{wOtEDX$Kb@4?>NP{#wJX^C3ye5I^&Nra z0RWfv52i^%_p+u2m4hD;oAUH8c8(Y2_4e9c={>=L%93d=B&b6-4D;wy_ELa<Ce?2S zbUMJ)nnQWa57YZ?kCj&jctXc7K>?ZIgX7SMYS?}O)u2$JZVq~yHJ8PPM(q;~3FwMy zfQbc`FII^j9`MPVp-4t!E!mgS)alw16+79{iWwsi%6zPT{RhTls*NTrc1sk1scF}Q z<ggA3lhp&ZUeE~5T=lj^X#?^}#~D7|w+ftP4ud`WR2Rj3{TFs3n&uM?%HUA5W~k`4 zVmuT7L+aUGEY)}h=+37d8)3W=fNvmtrU8(^5k^)OC%M2ZDw7(e&v@Pe{WVA1x2HUC zBr1ikbxqnZ8wbS@Xs1Yw{RCQsknhQ+v(V`J(2qiRUJ6qWUDsNy%gC95y0Z-O)QgUO zOIXIx4hu_RUt%A4T1E*WjvTse{?hF>)b>bgt{ChXQ3C>{+e{_aAN~R|K&<?MS;;>+ z%!ll6V>r){-&J-!@e$tt0IIE!o;U*xYFp05Kmn{V=^vW=S=6YJU8>f*A~;m-gU|*; zxd^7p=wqtEN(|Mn)Uk*b!Iw@4z%tvwnL_#}iO&40ZW38@nH?J=pgpD=ZZKQRU1@<M z^o+%i|LTi`QIkiY0xo-=zpdBQdrc*G$-?m+8-BZU3l<eX$p$cArhF0q?`-#tM-Fz) ztOwu=cd5xlsObn02LR8G2}@E`mntc=e0XRy<aB|oFMt%amUKi&GnEvw-gMu7hlf6; z`wGg%=B^}FF+yeOy3K;Q#jg%n=b!@GX~~Y1UfPM?eLhUanKfEc*7K;ZY3I72zUbBB ze=13lO*==dEeX9)Nnpd*5K~*7^!9J!xj`Y`nrCfR^p5y3V%LOZFtAxh9AftdN8kI* z7K+d)8x;z5bAad(zhQ|W&r=}u2w4b9^Yf%<k>1DkQuneT+x@cP4Uj-SM9<_&@&v@I z4U#bvqgpCK2)qzU0>6vf<*(~Z)|R`iNPXn`A(ceWUW8@BApxF@G&p^CQ&9s^FSC3a zRzc4ZKphGodA;=Ls-kRo;yWn~KS|4kzti^x&ohIFXP<nB9^Z3~4ZHLYhE&@)IV_I6 z{4OuFEiRzTV+<yYYrh#gG%<CrB$UZ93y!87+!F4}@AQ>avwlDQ?<HbVFwIx4JC4hk z=>^bXf(ki3=u#*&4*+poe0H>5g$Q@bsDj-q9ckPW9X>r0+{?gRKiIm+2<|m|&{TBH ztZDuQHS%PZ-GQYagha#>^yI$CV`xSOAM7u$f9k;RQ?@c^<e|@ALxA%T?`Y6z(jD=> zY`8a6OauZDP*<NO-E!#9Ro|7o1qbvlgfM97q+660=-x#dxDgihZZL}ky*dIegTan^ z{-Pdx9?qd>lVEmLw9_2=rd&}SI#%zJ^APyO+c~V|iqCLDI$*6lljqO4d+a>j#BU3> z_~Pts9xB9z_HOR3kRIGu6?ujOjXYTBD-SzO1RqR*1hXIjH0=rqvg5^qD5+_Fz^G>* zhGdPD-?+CBPXg=ZNW`{_R$`nZag@ho`f^JS%d4=W4Vs6BI0|6dYr8gX$sLk_8XbqY zVd#079}kP^c_eD^8th^&`ov<dKB_3y^GAogScU-Nx5!9>z%zibU9PYhbuJb5^Gk36 zQ@JnwZ|1=7-F_<W#S*qjV7^q`!wgMc%=h8K7f$J`HaCtft?P_cSsa<@O#H6<tQLD} z{a)hp`iCcWs8Wgx$7OU+vp?zV5v-`+i+a<RI&Xs_8J+IM<#(JfQ@xWMd&l8QYq5-e z{AT~Yl}|sC?<DY-mv&vb5Ps|SbbqS!ouA3?lK{&liu+Kt);q-aavn!ld%s}_6M~`O z4T73o?9|p!(GbegH4TjSnLm&$*_AQX^*^HmA%qOJ`^Be=UaybjH=JV7v%V_xJ{bS} zrX=^|kb8+ra*<4*={xL+9lzh<ufJn|tiHLE{@>TXdq|g^_5n#5qBti)=T>p!0SOg{ zJ5!vAD|hyWns~7YOTd8SYRk!hn<e`m7pIAuZj$zu96Gi+wBO;SdO}sizHcXH50OOJ zDC6E*ONpcJNtT+0I^~&2^UYOZe`NQ@&F2<W04JQ#e@?3eyP>S<Yd58w@zl9HIpZm2 zlMv)@w}5t?Pk}iPP8>(rY4e?-ulM^pjh>DVc7N)8vD9lvzdKGPGodC+w<fWpur718 zD(;!ny^Z{{dfS3eaMMoG4IfJ`{HC~ZOZ41hb%3A|1(-&7PFVu@mdLPMlNWbK98bmj zJFufIN{rb27Z)&dAz=o9`7w%@@uF2r)zO~5-^<Pel01LMW1T_I4W>x@`8eAjmc_ao ztMhR_T@JVXjq5kGkXXbwF`To#bCaL$1g^E&Z?v#d3Q){ke~$gvX=mE^u_nj#(vR)$ z&;3`}mJFlOjlh!RjX@B{s!BTzZuDaC`xE<3d+8_k&kEdL+CQHOlDDWzyE)dDyYHsI zO;xm}u`aJbu{*qSzt)=8t+tzCN4u(XEgtJ$#Kt-7w5XduapC}mucrJpzA_pCAb~j6 zWp;yt!!-+B)KfR59%<Lxbrq%9+0061Kl!ZcK+FnZ*O*gW<6Y}lkvWlFnLpUy%dphd zD`nc%5o65oO}Dtc4huxkUW=}=n<bbZ-z>a!Zz<2S_nm)s^MJ!|<_!a<&0}$)bg2WB zSC0L?a|owF{ZD%zS6^B+#PEqwe;vx&cYpL}7D&qZVZF<9I}Mv3T1+t$D97#|VdA-6 zo6_lxajZ_{ms^XeSN(1WIkoyZEm%$XPaWE`W4|#zFLV3S&H{G`yTM6gS-hPLevX;S zz?W^QiCaFl;LfCt>NAzEJTIWw!ViRRj@>+MvV(A@_!)cL9!ibq4@4b6$Exy*o?hM6 zhI^w<w>0e^Hg=g6J?p8Z*&pcPfDv|(YC{3+q|w8E--<I<<4%DFp7rPkmYHp8`3&ZS zP4*A=w1`B@OKVqbq_y!>utFEj-eIS$wSu&5Ewwtn>xWR0vxgCJ@_mwYo0Hw5Hk>)h zp2Z>i#c{jTvAB?Z`AW8a=3<e>6t$8D7}oP#F<gX*e!_A!sYxgi6!Tn9-ix#1NFigJ zq@-5>bh9aQq+8FN+)mrfl2EjDUo=+i9It+M@=>{9lBZa!UMeb@R`=oHN~U10@B%^p ztbaU`VQ;Tv7%W=P{u}T6m*i>^F^<~t)0P0N2S9bL%nO}yF1x?8hjeAEO4HYxQ;%g$ z+ZSmgLIJqlhAv|TGOl9D1r%qcy8+g$0gVIjIJK_Arz$)zO(K~h{}HET>s?Tas|TqT zkvyE(v&g)$ILXIrp9&;2M=yqgR9Z1Kth<)tm0zXGewwgb*lLO0X;<|c5DW(^f&IRq zo<_O4dIt%vH|ri*wnjkHi|sBGvpB19(hzBeb}mf_9je+l3!T2ueaCSUh{=iYwPK_e z!t=fHpM_+1Q*)H1DKuX^gazAN>I;pZQ{ILn@wtJ6`!SkoJL*uyjDfP35pgHYN8=pO z<Hqk2%Dp{}kZXsxyaJMTMiaMjqApV>#``92bxBA)@8`ZONYDrEq6j?fnxv}lJe5lM zO{5+A^v&sZ@p0upk}$J~nC@ffCUXP)h1T^T*{5P?xr@x^SX@uvl{`M>y#QgRK3>wQ z7_XlHk>M~SRTMS}lwBk}!pO}lR^?ijw6ceBPl{Zq!0U-e6OM*|5w>X-k5-;MZJH4{ z`q=y$MM@}`Xlpx*#Z*aa&fKKiC}|*eiv69{9=llxhKnK*=ar|bt`PEXmj$i?0UIli z9D4)hQ$tM4da@8C5CSkVIi7w`9_(;o^U}L*s61y8=HMb#l(a#SAB6kH624oGNsX3o zN{*1LC$+x_S}JxLa$~+p?DAezHaNOcel#P_IBt>lW#})ChCOD9+|T67-Xm&aYNk+o z5j?BD8HgD(P(COEsPI<4-Kul8L{N*UeT9SRos_y9TY5#Qv)9#jQ~na5;`NcTgNP)Z zK=<*n0{5pu46_-L{)6cMh5}6$;6EEg0c-QNHoLx6Ac|B@Sj8qHXm41S6Wor2^D@$P z=1p29T_yi`YRmmFy|mP#h^;u)-xxP7t69<DDza>y@PY3sa@KuSMB#-bwES^{hryl0 zuGbooM;Ao^Nx2=0^KEofw6oaMz{Q@Xy(5WsT7_UEuexV0!{lELCB6|_D(eI{BSQ^_ zCBa#>T54y)eO+HTN=Walc8!?>EOX^zkJ^ny!fZ5u7X^9uzyA>>ZA3{c%fZFU)T2Gc z!#z=1BY3rk0$0a+=i1g-Ez2Os>T7|I<kR33sUK%cOs!Ij8VsQ}ebzQXN9IciO`zSh z*yM4S@2JU2yu~)jLnc-d1Q%$k)SN59V{I2=+O$p$=;-%kGkWqC<}kbM%!^be_!l~@ z?f&+<YZ;#YuRZwm`OLkddsZ6|7P;ce4-Js_{_95gwZ%;Z)!!hLd>k1wC%zdH{qg8m zeigPWGQEaUSFm1?aG(kF(LfL8<d_{!1kcMYx8+MV0z@*W=jCRk?fk9`pn{k#D%OTZ z|LssqE7IF2yFZ9|cvjxbXsURyF_Ny~1du!%(KM*mbsf7JS2li``dRO#!X;AyQH<lU zVEehv!^y9^L~7{M{jUC7DR;5!1ge?hM;1&k$z1I27kt?`z;5J>Yw_t~{H`0Wbzixt zb9t+C*EbfIRez?EB?r~P|LN1siAP@x>dr||W-fnxuChV)Zd&|->0g4VFKyy8+IY9+ zSz%c&CsxB<2qmiy>fn??_je$nFPu|>h|U5T>pFaV5_AO4E0`S4sjCAzKgt;@!5ZUD z+0J_UAcv86N15;+=l8c4<E>acdji?C2@k2hggb|KiY8-fLEm4ioAW_RBl)}b?*Nqs zDOlHoZ!{h;1M%z8^}0gz%^>-T$jl2kYqzckhB^!Fe~(3%>9JfOK`f_xg8o${2oO;0 z#!?P?=YH#n6VAJJ5NNf5$E@*O<6X+OM&RYFtF`Lml69sLKqKurt0p{pFuHIodL2@T zi~>2;0=36@SoB%ZcLgsAWLqh(lw0(>fN`ggM>>287EEzmD$-kXxqNU|b{Xu9*{55~ z!vbb@cgTNZMqw(23x*W;hoKj^Mq6aFNxZ2q(5a2;&`B|y=9;+93)nFM)F<d?4K~k0 z-Csssf<yEM$qs`qTD}s1PKpD8+et-PWl*++7Id|x*lDt9?G9Im1T<L0JNSASH{n$Z zrEwPup5^+dIEU*pf!HPrY62noj3<1iTDeJQIa6#ld4|U1BM5nB2L6_0iE({^U)A}F zHj1t%b?L<H?hcB>22W9uXEaICD<GQ?X0^4sdiS`?IzTfv{-q~R&y}m4OV*p_a*15a zX|g$61C*i_?0!JywvW~t*J*=i$pRWEYinn^m@WYADk%qIL80Ch^G2X08wi+m(HbN> zuJIhGAjyf{SpCb|c>$_l5E$kMVE~u2C?5Y*4wVDVn7lV7o`Hq?kA+rY(G<;27j&_& z!^VJp=zEv168-_BOMoa-7I&vPK0I0dMdc3OX_~U)HE#~T^azP}T;v6qm({_i4Yqi0 z8<hTg@(w!1debdNGhCDCr~L)u0ON#UXscmh&Dm@Ckag|589aNOi(Dod%>=f)wdxnU z82gendVvlLJV(-#V3A?FCM`3`7+jIG_R~km35sqH<KwS`dcYWCw2Pf2KGJ<cWyl>} z$#Xo$)!g7ZWs;57@Th;a|GEb&?5V7MUe4M`GZxh}?eL3`r;6TJj3&9s%XmkC+T9q+ zM=ze8vJ5uf1uYXTU)qMfCmN9HD%U{PBLK~|T!Qx3q>Hu|FH1I;JjJqrm~FhBJjD($ zWFQcASfnt8<GCV%P5><%(hlf&Ezbd7KU(=ZuzJcllv2LtqC2vSfTRBRtG3`Z9W%*W zK?pVt0vsDg3@kLxKzS%&SpM%v7f!b2Pr#j6!h?#X)V#k<dawAKYZ^}$a#`)!m$2Xq zMESOoHr{eI-mI}{vUu@Qfw;p0H+iDndz*K>=u`3Gq>V{|6JWfm3Z%yZ?jbc}r}35? z?pczKO@ymjntskFwH|8&v%!y<pMo7V2CcW?P77Qe^#!bN%XqJz!5Yu$O#)7WZY4>< z!YRr<<SXwAum>CVu9jZ60%DbGb{7pQLU~3cu0D|)@KMu78BFY1a<2qkZlLIO;$3P( zFHrI6RNkfS9g1e1tEqhXWMapIJmi;s(NpbDyf;7qmdjM<vhm)r6#GkC)t6k^goufA z$8sZp1AgDK)Xin+(E4W{x)WUrMmG%jwj!ji5Rm#~o~Cf-y&dlC;Nx3${?Izll1OId zX;gJmTFwD`r$A{{M;mq#4$SE}Wda@ICp`+Hb{DyNhLi*l>AFO+8Q|RUuU9Ai!UWXe zFMoMxNua|v$fgQ!%;I9Jo?S*xroby*InBe)tH7m-5i<m#bgv;<OcckQVAR2y_YK zy*a%K)Ociv18MQ`<_iMD+5xj|ig{b7=(wwH!!y@o8ta}<5l=gr`Da@axS6jhSZxCW zbLZ;w0dPU{ylE)-#kH!75!4kE{N+5La+m9*pUG;?XfPdFyT(-rd&A6{c`kCb1fUin zR1VMUx!fxWMuNgtxwqC$ZvmsUz`m-<RLsY5M+AA=o3dHouDQr_+H&a=CG;GldP3jb zjQE5b3v!T|S<<MhkEIwz01Xkz*s+2h?Gnd$@+a<K;R%g<H9V|qsctS;u?D{?L98A# z{c=OxfFQi;K*qIP>_*Yg^`Z-JKpiZQil}y>Z=x0M$=k!+PF+;a<5<FU^7}`nF7j6k z3q~9xTuin>82I4Pzm#JM<Wg_m&F)U0TFFnz`|9L(FXgv5c~XqF1Y(;9eLQzY_pX9) zPpM`$3~%BioiU{;DYWbv#!95Q9Ec`<8E6>Ms8f`D)a1G=6Syv?VHdcHSrA|bUG$2% zHri(L$BmZ(INdRd>L~SEKHdQh?9dFlSsa31<=OYR=rbwJjg$jP<(~|wPj0u8EeOBs z1wZDJO;>s6R0+>Nxn7z`w7t#ufvejz@%Hrr4df@PdP8Mf*Zq!7RvnY6-R2n`LuvRX z*cr>?`wuz{0=LFm4}3dVUh7h}#6_>^EK}t#-Dt-mgb_q}KWBcd6KyQOlU!ap0`O}6 z()P0WzID2fyi7@t0;`?Z((oVt7sy7r^oVjh{#g6x<-wAd274=a>RF{L*y2dzh4alF zHyp38zx+G+;6#Ua04uN2#dcwC8p;q@h<4WlVb>nTE_PYrK!$v-PBhn4eNuY8c}dyQ zLrcbB!Ns8p?JG$^;<?AYgjD+WK3Sf_0{(U?Xb%7{I*{lC4)dr;o{M)WJ(uoYMd_v1 zsMSC7arMG4P!mTwUyM)}t5t1Q!%eNYi(*8Zua^5>46ferG0OMRHTKn;;Tn13?J!TL z|4qB|R@W!-r3e2rVYyfolXW@3&hs%uo%KiSVorRXj?AcU1gMxmM(fAFp74!spdc7P zgB~5dPsGS0vv<%>zumj)By{n}e7th|HBrXe4+s8fy#u`KIJ_4ejoIc|)^d%g;&=C3 zCp`ztUAK|rjhe)}?8v<{;B(DcT)hSExsHwwI%osQBR6sf23(GyT@`F1;MY54ff}qe zye-=`Zl+T8JZN;Cs~e_a1HjMS!y9=D)0LpI_&EDtgf5@~;T+;L4K%>;rfW)l)y@47 zgN_;9M?O=R_C3uYl3O3dB>i{Fr+{HgFIf>eR}@y`B=EAG{)Fa`O~$z7=VXI1vTqo9 zzaLpIw@l}d1;b@+?}r{&BG-mPWripPN8$yF-_0$-+voB2RG>YZVosu9RVL|X?XE2H zm1{|9TRao~t56hpPdejk@i&J<uHV#m-rfBN8a)ZR|IN1I!+DXjPX!2!O(zfA<~o(t zbko|$iNr;3^Uq~BLtdUp14Y>qT|8f@_Xf_*Z&Hjrxnc(Yef8vFkKv7s$v+<Z2A=K1 zRfQNwk4~>QWUO(uiJ%Mr9rCR*@>^JxA2>YmlDd08vT;`@$i}Yu=%o9vqeeTF6R#<B zNBygx=Ai3s=2og^ETe<N-StN638k0iQuZNtX+QfrV#fy=)B??)q!R93a2i{~0`z+d z`wpvFvyP|aGqh3>lc^U)3uIxYDWgYzHeOIx{7wXFa|qV^u@y%qgTKBNY*6$nd50gT zi%apoWPB7n!}OP-^$@&jyz$_VoiRroNE~$0o$=^WM@ICDgpCXcI|<VGyqMa0*J`ZX zg7B5~8*d!VwQm9uN$!jk1DA`Uz7~@ws=j(sPwJwB(qsPQ{ao=6H8i?OSrIJ}Ce`(= zh90vJD}+%&Lw3iJT}}ZY{W)cweE)AEIP8YOO*eE}#dT+v5kQ7F)3s&XD_%U0b;40} z*B0CcMQ?e1Lhhv2tm!yJ1NR{OuNa+}NPLn$CMh+*y)(@d5bc|l*xpTe&9S$2nk>&^ ziE{_vKRIqZCSlaw)`wiDVB*Q9FOsMKgJP&W`-ph^X}r1e->R!1tp#A~#aV48*>2i% zy!R(P+J<?tNSAu|uI!H8+pGJ6D?o;shOcdZRXki*7cL6lPT!(@nUkm;zF+noWX1yi zlnVW3cU~`oY@_W@y!GHvSHG=NS^|!H@`w5-k=eA@pkvo~EUF3HJFhxJ$3ZyOYF3Bu zGgAA_6CBK0JaYHU&0V!^AngV6rID43R>PmVc$meE3#vB@TmKv<@f@PR=F|OSR}J-h zxtN(!`Ufiv&k)DL!$`Hbw3*+V;j+swoYEGaIaFf4&Gr>+TbvL6TvpW@^Y>Z96@4k3 zSA||+OGsb24mP`ZDlx=1UDxN5apI?1g=ZhwUVwjp@7h%o0<U<S)7{r!nHb#aU-6~_ z`%;zEzDhP!(njt8ZWEU{EpH3ITyBZjc5k5(%p1e*$l|^C3?Y?;o#34%^QWG^Y%U}G z{F1Y0OT+mN@MlAXZnBD{+trbJAL9v=hrzAvbw#V=D&e=l4Vto{Ws}&v*q1c-_TVGE zXId?~zqi($On!SO_48CoNRn5_{`MQZ?6cDRyxGb8eHYR1?jNZC?I44x%iiR?>^@@a zS$fFSZ?Q8{srBOZgL!|O+$JBW?g9LG)BNtO-s8aQXNFvEe0W9p@G!LShx66ipU^kS z&DpU_dV15LR}xj~?fW346NpYeSKNGzZPS4Pf344H;)<!b+rJ)GWB;CIwB&V-g0GR` zon1}x1~~<n6a04Uh82mA3*C47dfMq>mk6$(`}5;7{&UcDEB~aHWoQSk%OO`6TMYgl zZ&E!I5TngmGM@0`l>=P^1|a*cwhz>9i2!5?{|<h>oI_Q5@odkxvEV!JF$;X<GZ>d4 zX~1@%UhRp)bHkT|GYd;O3g;`&;gmji=qbl0iImspsCSf(YPO!u@RBz%^r(?J(hinA z>AGHd`SZV72xqrb@_&BWR^1+Y@1|<oFZ)LQVyHM2noJ4e&H^g~aMcMHRP0Lf6Dkip z9=Gm1(Le55cY7*WbTZ)2ELADHsie6+=S|OgxcUA2X;{s|%9h#_<*D%%X*e-obl&2U z)|4y1;ntM4_0B?Rz3*5|$t&wW8i&jC1npw43k|wLdGARp!M!Nj9}kt#=q$IoGo`#o zszGU9CP9t3TLinjX;#yPh(VX(My*$}vZLqQUL4#Lz1@D~g5_Myu>AGM8Zc~({4C5Q z@%Bpfj5*3Lbar|w!$i(+4)J*I`hbLzVey~It%IHa#uLI~g#=jD%Te}8L5a0~=DS0% z<`CJ8iSDd-9^s8rrg_f{K971omM25yt;Rn~C+fDhKFxnCety|k(k*?qTJkhMAje8{ zsx~Hnm-p(6K>yP^jt9-&suGqIhAIv;9n4TYA*a>a#06e%^ZNSiXjN5ctVY767{65g zhYy>-_C*RW8|?Wyi`W7UusPuuqar41%nqOS*bdVYY1?YhnE`-*njIHWkKFt@>;G=^ z#`r%*{hWUyRXX=eYIYiNs&Nlb8BF4&*ElH3A^bAQay`8e4A}xD94yRUtv>g$a^a@e zfWBh_TsZN|f@Ju{DyxgUeEi@*X*NMKz2@!HqKWacjJ5cq|3W?L<}Tt@!j9!7STgL$ zb7kQK3aYAYNIOjg`So3#O3*<D`56yo=hYn3*E?h+=PABl*g5zQFpe!6FFWEZ=`PzN z`+STbr57mz6#DlVSbakgjm_M5D@!}EL`p3C__|gixa--Q9(5!9fPXWt?2}cVZl4N| zIn?f`NzM-zMi8~+Zf-#gFy@86X_|8Tiy?AK4TWBrnySr<u8t|GXES_tl&>L%vpR*1 zvX$e)!Pv*5uPY>C7Rch=B!;qK11e|6BQn;IX=0gCdV)#bt*Z4QDG215=od_nJ~(Wx zYp(Rdr2NvmL8g`+SYPh}R5rET8y$7-Y{q*{`H5b4G&yzX#O<eQf6>F(!va<wK;5~= zYJP80VbvgWUagG?F~g*yGO4jLVr0dcuM67#t7Mfn=NDGyMdROTLu&OSZh!761fBZ| zt<@+Befy@RF!(7^B_;js%GbowJpK!MtFwgq3+ILdEFG4-YoSSwVR;_$oLcT0ePL&D zyy(>QoSNLX*6(YBb-^J#Wx1z|`?_l?sH=Esg$jY^fZ|k3Wu;-t9}jfe`HB*Hg6`41 za6e&{KM!g}yj3h?=O-)fza1y}c5&E|6j+?L?IN)j4YR@0wA)JC(VLhdEW5k5)6eFr zy`3AI`dz6z<-$#yr2rJI;-Klb#>UF?hy6s@FIweB9RLo8aiim9p|xDqzBN~@9Ix#3 z)|}dJ!jR@hsv1^KzoY*uEaNa?-wV@ISN04fcTv9wJw17$|E12=knI5pbwBd%{c)j) zflK4HkI$3e#U2PG8*1PG2U00n^f=+0&`YzCIpu|Ksk{9G6>_hU_C(}*+J!wk2M^GB zhJW=5=zp_iEcnq&qW?4=d6Rj|ewcIn3=&ViPDLeJX|__fk0XBS@BP#XQtpWSlH)4P z-;ykg2P{JU2SPCYIw#sCM25{z@b(;^-HiWuFOjrYNuor6F8H_RW_Ucc#50;FKSaDy zk)I!LXM)j}X<R$smldP=lP5hYa>MVDk<XbVV$!0uR@AG8SJ@BdWVSO2CxK@rGWCI~ ze-{y{*3>4(Dn&YbJ1xO>BB<=X%jtruL8H7F@o)}Bp_%CBSZ<E=@&_rLRi!y<&WipI zXW`elj_oW?2;`w^-<;lSqxI+W!o3pd6-;+iZuXNfIoI2xE5r8aZi!PniNm{pj(8Xu zpF_=l)xy7Shv|A>U53`7l$HRM*eK^>&*C)M`!jB)bmwA&{NKrKY>l=r_c~pgg9^JA z-Lx^M&&GnKCa;|Qx#az~ll*8-&B;b4{X<J(-n9IX_tH}P);K(9EACyLa=9y8DBo_! zHFRP8BLf=aUTSY^{GEXq*iU&U+#EI9YrkUT7<krCXpGy}3k5cKVgTM+<{!Myk-gJu zKH7h)Pw}y^$Q~$sq8K;OkoWVs!Tu!mM)Lc13G;+6-NmBodrSf}#=?y!P?wL*t9~Rt z<EgL9Ei<*`SK5a6go(6@)0ZFkwZg->FULymxbq)my6IZXik+6!+VQi{Rt^WwhZKxl z==m7nWp%2t^wn!h{2-rZblCPI)=Pe|<e@ad647`DL3v2FN_LT;l^&S9;;tR|^u>$0 z$(%K^<jXY=yEWS2U1@h#ek9D^P^9c+cuKcVmQVDw(Lw9e3U<jx3_aa^MC3xO+CIG> z#n6n>^2JEaZQOgOwS<o~q4m}y=4|s%4dQ-OQ~l>@+dtKIUQ1Lf%2s67-G?9=ZVGHE z0qrw(wYPC6rnPQ#D`HOhh3<O)4=eaND+YM1p;@cB$Cb8+E+Q*4nEnr8x4a}5;Vc~+ zqZ;d}0*C1U<5un6PRWaC?2r9DDQ3L}DVWsQ?HMDJB4YFgxxEvzc1hW*HcCqxU3Oy^ z@WyJ4&?X_}*nD_tQ;gMs?6N^%9!+&C=GE`LnwivDmjT&b<P@kUX{_^>yW8!wf%Nxc zSK=4Nct*-^pl{|<<N++TZPTIk6`3DJoL!Be_UqQQPt{lrVE=&7$^^(qwC%{_NqZ69 z?SbF=XY~|kjkQzea0zNN*VU-`(ib#PLu5TkF$X%^GZ&`f+pM-IvN{9SgnA<4sC%sP z<x43)7Zy^g3>1UF0AnEF)UfDEkp+EOW}UAO@DjJ<A_IvMiQjC(m<Pi;)Z7jH0<MUO zEM4naOCh4I{y}qB^OdafZ;y#69bOC2jZsB#bABAVvs0X}5{*)w%pXJt61SY?3F3dj z#cKr(Qho-v%XQK2+_5&$KTN*Sg}BQ^mxP(eYMl*W4KJG{bG2c5=K@$+qDVos^G128 z^y=&m;N0pIUh|)!!e&E2=YN>(**Wa|OB;ADJa&h)S3uHO36LrY)AgY{AGoj*@J~ch zF-E3EBru6$AxKrzUqJk6)0T$@b}p$kIlovK{JfE>m&N0Ho9JT(?jO^)?liEg6d#+I zm01+oB!D(*v^8R5WRhmLL+1}{G=A6Tq6Lj6s;R3S=Ri3z=&J$s<G>AFvRc1}^kCz| zE<<Gm0$@KYl@w#g1wTLLe=3@)JT)uROXuuV0-0>*7Qb1^UgrTgO;75k{>bCze<B52 zG5IndjRHWN8=urn2NdXhn;t*)iCML@29$d~i({_wET6`KZB#w~Ua$akOI78h{2xVU z;?IQt$MLb*VPkX8ZElg=_c8aaAvr>uo20plT$^hn#|R<GRa7c;A=Q}sYJ@12J9K=P zkfi+f`x8Eo&*Ss{d_M2b=k<J|quQT%_o^vnjCPHx3J3pc2a`=K1mZ37_#61X#R9UA ziP+y$aa9dRTa=4wYu<=cegMA(2oZ^263XH4X5I0Mbwnpxgz&l>OUdTMVgzgn=%{A2 za-32}A5vv1No`1;%7f0gkX&z>uy2tYj>_D#%4vUe{LI$3i%W1NSx6IbcY-WX!IxSd zShZ>`qDB53zip`SxHv7-Dx<gYABVVok5G!mu{p<^sD9}xj9%$~#`ol8kN7jt_#U-J zSqmRI$uY8&n8mZL4f*ga=ZjyY)6Vl{@t9NL%`X+6s;eV^3{S8h%^k>sdl;jO3{M>l z;wC5S^r}JPGB%EbS3$?gt=^~OvC|C&<?k52#3kVc#hF?8rY($sqoDa!PLs}+7qJAC zPMsL^;e27N;!vOno<m+)Y1TQzG=A*A4KPgG!pnQY6x6`Zc#G?jrJyhsaclTDjPMvI zf~UkqDH_`$CtOdqWDTnX{E%W2P<wel9>-fYXj}j5k-Ezvq_ZSk1$B$wN|CZoo_nNX zc1!OMK{TLFIG!x<w{G55)hUaaF*0HMhX-(+Q@m?J_Y47Tuhe$5Am??H`(aL=z&3Hd zh5M$T+!-B$H1RVsZpA3@+zVbC3yUXS2TM|}<c~({r=I8-X^%=V*TqV9$Qkwb6}6j6 zzq92JDxlsw?jXs;B|$tv%+^+ZW@dt(Au;#U)T{oah$?>ds@ZG2aK*;iOhL)5B@}(v z##~3qh?~Ei?6EUpIpq0tgym6J@8vseZeroO013Dmr`Np`dY!8zgCMTMA%r8di_6Wq zJZbwnsS;a1k3j4bErb6oBx^Ck!Cb-_qm}R4Yu#-F{oz2>!NLg+IUx(Vm>g(>ZSzGA z(E~~q?^>`H!SLUVhK6->Vvhh-(Emt_=WUksKMvsodhb#A-l^d&%gtPtti6cN5^c+Z zxy_Wu*BQSFI__P6{NK!fvt<%{b>iD$f{AtF2R-MV&q<mrsot_Ww`SW0Wu3HHRxNHt zmba?U19$iP59yljN)J)7JyNu%mQNYKyM|6gSl#T)P}^?O410Rvrncv|C9B4ao^FDO zAAujY#1_+t->Sp#_x|?|r0}jWx)px>dy~H|S%gTIA~l<<z|R<17&v(;l<FyzBpA8g zl6J%h29Q0Jw=pG(-@f*!7OE@x4oe4c2y~DgM8Djb5J|;r={(Lej~gKd)>TvAUMLWG zemk&dnk=$fCya0rd5RY-!H7I<Cjr6>CkW_^J@_L6htT%oWc-pu+K_bjxpZyEbNs;_ zhw<^pspXBBr>hoxdSsnXYj<!DrF_3Ve%z`SDtJ6EI~F*hAi4^?R4>udSna$^=F`qF z%nE95kzVZ)4#lu*1W~+>4`q=rPT>D1gW4mBY%iggF;XZ?=3Pg%?>l!(<;I_qiS65h zF*C=#pGojrnf)RN^<kxQ&VSj~a$<7iq;kpjlLapJ7*npcExrzt({b@DciQ+S)oc)O zzaotZ7Ah23;12{pnw&6EKU-|2<;i2)Q_r`cAUPhbeO^(sI+%j7u=%Jare78scug@e z1HBIrom(1bio61I%9Z9`I?o6h4!pQ5|M*DHP}4XmZ8gjITivyU-rKViDW@IKe1-9H z^UAGqQC3{)jy7WDL706fBXE}1be&EkO#E<3l-D9I4sEXKssB_CyT4*_FjV9$ORFD_ z{{5@0x1X4!U$xt2sjF)A{6t_^K4G3e_*rFKVsF@|dwYP3Mh}3gcYt9F2=Q5hnAD1i zb+)vkg-yT@X)1e9rl^{{uDApNa9RtLZc2vm*Io))IgCb&5v~hXDT(?XN<;*>92W^B zM5`J#<OvE*^qQ8QsLp*8A0)2<ND`XEN^QKhrK)rM9kss{xa}?mA&8#jw07YOxmjLS zHSOTdZ`6EgDj}tz(J05sDCYisoaE6SF!#EkeFEEzWx=P;A<0rX{=zBTcntS_DVoZ2 z^QY(~m6et<WM64Pt-mlptjA=j>gtPQp5!6pW5-N?_!7$H1eEmyrIS@E22Zgr3JYRH zhB$=s`3<M8swHypF(>66+q}V+xs#U*69gVk*3FQD9vK>DjQ2>%4@<>zcl_{$->VyU zUcQ*yhBgk-{7MiP<bdOUs_x8Gt^O9a<p4bJO7$?-7d-cx<`dp2`tS{^{jz1A(p<dE zScfOE$_hjs>3LC={P@v;bpFpp;!4AAc9MMNv*jMXeZ1Jh!6Cn8&6!=!A_e1VV*$lg z$=#V(_fB@c=(&F_r0eT*VPjGH(F*kXTXi0xm>iGg(83D}-d=YT&S-&(Rd2ff*NC%| zT;gV9JzN)2S~}e)F`5g)3K!p7f-`T=U}9yQ7^#M3{+sas2%_z|BU!ytb76XxCejb@ z$zxYf%Bv8D^zW$|H*`hDvOIeA-<9X72w(ywy)lKZYtoCgmn}(%e?92+O4JS~;Fj3< zq_O#>CSw%S+3vbDE%Ut~0yn!fq`}ESwh)tgfo_#h7EB#!KYZyiGp#q~apR1m=W&eM zVfbtDCl@Zw3dV|>2&=KN<?ociQ!-ZUxMn*!qx^ykm;G7aY6HT!i)!?X{OIDc@q^oA zLn%G64g?WiCR4GF?>3(Qs5<o>O<CA7R3e}JSy=74+3FN|qS#3M`Dzxs9PY?F6+es| z)2vohOG#}?p7#Ip7bke<k)}Azk=OSxca}>Dk)l=D``Yt;cl_<QYkQaz533He5BSGK zcm)M768KSMw`~jQb+S}Vcw7)cG;d6rZXvzHK8Jl1z;j$~<2bJf0<`<TZ&Ne+T-9?~ z&&p+V;n8~8bWd5`j{L=B)yfP#m1Y0ndl3gc&VMjc!rw%e>-Z0_;)mq5*i_}Hf9s#> zVW~}iz<(b(5%jbT=@f!Qyt?RdZ|TMj#0<wSYC=pAy6d}{Q`4WTV-{_S5gv-~as0Sy zQ_%cyx$*9@)W4pFqpgDBGn+b7f4hI*2*IC|OyuAX)KF@*G#FbF608%%iVi@!GxjmU zr$_o8M#gETnK&#ZKO;DNQ<I3w5rhZI@Aur%^|>E1Rkm>Z)|Lg@Rz-x)q1qwQyj0Uw z|I?~sL;8TINB`pXLc7WI!{dWA<$nRQvs?k&cOwLGO3oo5A7yD_3&9=t-_6gv>IQ93 zjXYPrS6KIuEE*!Vg~2RD9ajvhovJt9;|6TZ%BvldDEYJTA0+p3^xle8wYs2cJ-Ot< zmi%FO6EJFrBk-(YEPz|g#GClZEDIrCpA6Nk@5|koxN&vwf{1*=-`+ca_BC$|#czGL zs0thNe&rIrIuAd(6ir}M>O{DMu*I^5vB2LqO3I@phw7}a?0JZ=^XzHQ{9;CQ9!kGT zTT}B@3wK+Z$S{8Xebp|~Z!puw>b6tYM1ZMxbKviTUq$}oo$+7Zy||+P@Z*b=KL>x$ zooHR`$@=#D=d<t9`mXLAJNIDx*!kg*Kf9TGmqI7TuU~p#+)w?~MJzY>4G<}9yzRGj zF|hR6hWm?zDZz=IyVo8?Q~m#}8Lbty6B~d1D^9i<nR%4@t1E!3b!L%~Vfbs;IAQB7 zqlk+lWqNMntSO<&Rp<>b{p|Yg*Z0rUk>+OOjGZ@cUY)#oqci=P!G|;YZ;70|A<l+t zLlgmP*!Mk}%^^$s$WiT9nS#5)5vzB|T)57oQ0MUQ(THr@Ap>dgO_M5Xw7SE96M@2I z-n!M{y-uc^IIhCni{}Sk8`PM9D}!ZrJ(i5VwlGHJ8FVh03|BK)NU8ffPwz7FZ-#5R z_rFI-rJnsv9@>XHLCh;<lKpPx&82f?$tsSkzUDjFj673&m+*IX4t#Nr=Bv$6lFbxe zXI%D?eNd52$G2U@uz)&7k<xB$grf1@P;;)9M?!~k0AGTFi+RmzpsPV)Zs!dnx#Fy8 z_hua}MBtK(!@2uUKW=#u0NyGUX@{Cx$coLzksFmZF8xl|b>_?8Ul)InII4WGFHmS7 z;vmdxUcKsm6ljRFQ5rW|i|QTJJUTVw)qwaO>@WA|1)4W-G?5doYsb@9)?U-=z-!(~ zbieCg_T-(jVh#O?^yLoqF(TvX_Q*Z+Ka+0;RQK>!Eo~t`8hDjBH-~DvK9vU{)vjgz z<PWj)*?(^;?h27Sx!U~{s<?Y7$8%Qp%ifGewS5lHJuB{lZS&P)t=E~+?vIfM`8Rac z{6Bs`3l4mVvKmo6s#qbu4M^v?`2h8vQK)%j9cQmQ9c?FHEQahqDJOm6esr^cZ~H`e zuVe`O;{Ux7A1}Ebcakc%EjMl`^Hygv!#Mr@e;1}p98SHL{;mC=%7OipeRA4bysP>9 zyOe7Y;a%sCFeeI9IzE}=U-2e?jW6&=8=qkaIm!L)widQyaR1dauk4dJo0q;P;H35* z^z4#(!`}u6HD;13pH-&VdF6V|$=&^~zcnRSaMt(l7T(K`vhtkRPIYwMIA0uafRpvf zDY)2{vW+Zn|L^tDzx{cN^x@oh=_YFb@mamw&m>i&|4>~+KRy;<6F<a;-RwqktQr$e ztq6WGfUL@D37l=olwQ^H@(f<aZpIgdt!}s*Dsz=^A6F2rM1cq0D^5tva%C0%5jMX& zNlmY~>m2Op$vNs?nCxdM@SNNEs0P}fGx^}+Q}}><Y>eicB?q!}@%!ZNDYO0ru2@Zr z*+`VfeeEN%wepvtKEwSwS&b1s;+r~A#eo>)uA5S!=Jf_?p*1`61Gqs;>_^-o-+hni zOzGr!<fD2kyP9dBkZK8{hEu-r_+7aR-Rvl8yI?<#{bkOh#l2UjCzo*wuIsnss&?0{ z9<sfD@=;@hjlp)lbDylF&neNFY4+!n#6a)I3*#0>(?z|8%S1!f(B0Dp#n1rAm6a=R zjl#nVc6?T`H7g@8bsDY`Lwc{?Z_LlGEtcFbh`sSO{-g@<szSREMXCYYPslhuar%d> z@RosH@;hrj$nJ{hTph)f+fd@%JUh*8KRC!~IGFV{2=~u^K=yQu6p=c4EHJCt&a|s2 zCb<4c!T}?2@6fHlfk-Rn*~af~^Gg=0Z@CqV=j?C$2zsn>rq@O_olNh#=H9DN6a2o& zD82`JpMx$Z(WwHS490xjccA<Uyy^8csVIcFEV#^~-1xX&bp95*>-e?K6)UXHU;afJ zeFh^bIm1r<$c8YssiuKF)bUL|%#8y-*X~~A*oMnht9AsUAVX2K#!}$S)loc&dwxhy zo>Y1(s{Eftz8h`%xTM3%d!3=z{kN{1JzM-Hzm#nIsq?<pDJvKA2gNY6yC@rI=a4x* zE;nx9N^Bx)-Dk8e7gx|{xkQUpThf+nzfF}M9kRYtVI;cE6YhC51d^2>;7xG6_`LWi z^>Z0WPBZ;5NVLkd*1XnsZn$+j><h;S!`aEAkm_EcUe;Z^)5fBVr^4cU23#lR`e^!+ z!J*I3*eKwBAmbB<o~0j$n3^mZ;{)skX0Sp4bdu~^{f25^^P5!UD4%D6{EM;%U!%je zs*dJCsfF_~mtLq=bjU}c8w~nY`Q=JuD+ca_{)R>_g8`NMW%>2RIqEVT@XN{y5==?l zd-sMy?|iEvy`_9^SgdKlDb9u?=0<~iBkk4qM(GEOHpEs;sWUM{O2Dtmr{JyGq-Vn^ zV?F<(PO6qGYDGFDqQsAzQ$z$VmZu?wC<iBA@ek(|`inY|rn#RNLN9IsCrupr^S^!A zu#h3tu$XPpFH(xS?jZlX9&+MfY3lvrKv77xYsbhW%xov)zGl+A-TV_I)|Pqe&mu)J z)Z^8co!sK-a|;2{E~uidr+nVseAMw}Uv!Pl$-ku0^jQLL9GW5BL$&r(Po^awQliqO z9(NK31ABFfFH%Jpb+s+H11cEqG7;N2wJdJi{}L#rPxC^0H4!J{>qR=l;{)9oBSu#$ zp160qnj(Tlf>&03(76=3;74cfW$3(>JilaiDy!S0b;V?~qEB0q$|LpkKz-QuqKtSj z(!K9k-5oyecx1!*<o#uVn`rPcYfZREMWFE0)-2g@3^y=sS?FO$)W3g6SN*Z7Ul&fD zt+=$rkM2OsT>J+$P{IGma{=ev*$c2!SNx%0)yVwxYZ0Pn<_7obTNd01k4M<?`*)uN ze`>72>wj+7=KRH=?^{6(j%|k|q$&tV9So|1`PddFL!}EJT~=Ed(_zS8a=%B#-$YEp zPD?NZY7)6jx5x+6Z-Ih(h=IRmF?nL*IQ7{FUEd^6hpQU?mCBs}sTmnoF(h_|H}Te{ ztIBUOO@^d^Dz<0h>tJ3)_~0Chc{Mlq_{jddo8#?T)q?qa$1l`Nyi2lgvw2$YO<$IN zyK4O*hF@#sVXIwJ`19tU&vk?HxdonJ`&C@eve}*T$UqrzZ}2AWh$jb+{Artf2;gm| z!yB=3bi6UR&i@&Oj4Mgb!lVQPMgHM<AJP!RZSb2!_#7T_D-d}^gFBVzCj}u{3el(B z5OXp-{VeWg6tW%wS3tA9H^^UDv6=cy9*=wlw9H>W<z>oX7VJDdPwW3`Mb^ulV_N~F zo74$8yf4aOt9WEVEo_r?qO|;kXFuMs2f09l$;YPi&4w@R!D<%;+i=J~L^+@)Y8Ak1 zKyZ>erBzK-zr7rkGJyO{gICqUp8){Qv1HK=D%8@4%gyI%2kF`qLA8DEHay(&65_WW zteORD{0wW7$*b1LYh%H!!r;aV!qVHwqfn!%kR!2EKf`}#E3Q5}J~)%gogw=)B!<?C ze7<{{C>;Bb1Z%=0dE|XV6LZ+Ptp&Qb1kkD=ly{B>Z^m*z(FkFcQR3u7dx5;zWxYd` zV8kS{uQvP{i8p1B`i&|hZg2cj3;Xqw!b29U4Fztd$Nd?KtD(oOwH{+51)ANCpM0wS zYDe!c4YmuAYzJA?O(7q(LZP#mJUiZ94fi&Bcz>gIsaMj6t2tGRNC~U+_-*b7xKJk6 z;DdJ#6cY-d!%5221&q9Nx$tMEgCmzr!A7C!9TByss$3jJ*_agD5(T?E2{o-@%eN9- zV9wA>q}h^GgAmt$q=Lt7`T2n+i<gctWg2PzinihdvaK}uhef3mWg_~M`TRY8Rdik% z0vbT#Zot7Ai)cV7D)ot-uf6S-1`MpLW*uvNI|jM7$SrGl%Ir?XH_g)j;^hk|`E&H( ztA>?=oF=CtT$A(=Hl?D+KUY33O+=BEJ-oB$7Tsgy?YjBApOD})wY*a}z9xs9gr(Rg zqW0pPfYHVB4Vpfa4r{DM%xa!a25IZIof~T6<x{q<?z|L1=54}qhh7!F;&3CCqqJzI z;?#7wRHk6X<_-HcUNd*<$syCy_0y{?<PSV7lP)od<0IbU%?H5tN}`TI63@Xb#-8MS zVIiuCus0e)2kmmhHr03U9KrfnQ6XgEHaZNuA7<)#gU?aH<8kyyh3KaO@J_nPrwB!` zgW!)6ljZ@br<=|nGn@})ilKVi)X#Q*X^8N}Dy=t)KEo*a$c7Vx$k|%h2UbE<D1q;q z)rm{I!!T-z;gz=#lQ|N)f)2AwLZP-aPRz;kzteS<FP-;M5E<cp7pMdqsk0^1h?#+m z+A9rQ7B525GGmd$c-SqC3z~d<;9m7ZEOaj;BEBzwUljKQoYhJKccFx+9zqL)2E#MT z!ga82Lmm4_QHHLVN~lVJXB{FFeWf`8pmFPzn6bAb`VX0#!SXzt7uJa3X~H(AFP)kG z8B^zutS5mVojyV&81U_3q1{Z2Gt}(<P1N-t#fWvGwN_rXdF}>)TfX;<@$|iJs8OV) z3xkih#3ycLmwS270l--bZ;&D`!QXGeg_`diGVZJnNZ$#*Q2&nIai#9HQo6)qZbmfB z5YBAlU^G$<MXBlt3ofGb4l3Ej#WWmo+vZIn|182P=!g-#Rny(bbU^_Lh?|$D{bwP9 zG(l$KO}IA%G1Yp16MOjxuSXWndK00V`-9tq2-Ly@_3@znt9L#fGv0hk_9;PE1MaTB zbKGNbccXN#zRf2*Ro$Z1!!Gi!p%9mDaUu2dxjC~hkC+K8VcuzR4{M0ui}6$0QB1j0 z&ewK?Yy{AREX5p`kn~0P77KQj1$#s1w$_JRdvTZ4!t0=bemugjNy-nXko1V!&jQNf zIFBzrlf(mk-?XcL(LLQo{t{~3P4_kmeIzDuqNcWF)vz|qAb$$0HM|JDMH8N+%f>O! z1;q<+3_Sk0BK}gJ_cN2HH!iaN7Ge9Bfe6^FIVO+*N7RPH9|7P)B<_cF9;<rZKg_ca zi13><H~<HK%z{m^+AfMq8xPALv0!pCz#t9qSr(U}24_aAZq^^`xlL=0QPpc}uxCuZ z0;jlJ<j5M9?Vf`Oz^NXI;c<s@hm+v{SllUCxM5^x*X@g`t1pLU-H{lfMvWux84~Zx zBG2sNxn4ZsDA`l8Nm=A#K~y%+zi{|tfZ3l~UJs1W7O6^m1w*UV)eJ}W$RJu#slIQ# z*UCi!z49i{z~?l$6l8!dEUpYZ)J}u*Z0n1KE75OZnpYjs*F1YH<@sS@FGDrUoD96U zmJCZ&yBbvaxZQaF$so%Yp-}+1b0=?1Ryo(PewX($C*%=b(>iQD+}qj`o!IjGs{MmM zk++-SPiS>@3`5pugF+8#Wo__lF)7Uo_)#o8h9GY-FXGsf_D};h^9P(kf_h>Zwk)8n z4Af|hk@<yz*Dm#Gmu@gHWN22LjYQtaBKTIy3_Et#we#L5a{17YxLoKU^Vli~hc=;G zRQj3hpITUj278C(`MAh4$rcgfkoIrH9Fl8@+cJ+e<)T<{2@}r?IZw>w-P?`*sKs#F zsIFbcv$v5V>WCLPL<Us@M#V#moEa`8;Bgk03zH+7$*AnUQ&8z&%zrzm7gcaQjN2rs zdBL<pPx}x6WrK`E02~+qM=(+Ew&C@h$Wac@OPz~Pv%`6yUwKxrV-y36rzs|bWcULt zcW*2F0TY?L@tVkgOl+7JQlUQ~7tlw8%f;S-EQP80q2>olYw%nyIIb8O=s7$Wp%qL; zfm5GP7_oqJ=b%5-UjLMMG+#Cj6_k;vN?mP&U3WNYSQ8xxs6#C^BYkP`uQYB9ic6CT z`GrC((H|gRh+cTi+dzWt5P8G>Q1t47KN^Ti;@EhHfZ}D7LlnGLhMR#RZMDKHX)#@O z*~!yF?__x>WbJ1t#4`=pRi<zN9&#HEySWH|#tPF!pPV1i^$kPZWI~+*U<wNygo2V6 z!52{A01dDqj`PU}P6Z84y~X*8h3P6aw2+aW)*oa6ou^xS=2Pb}fku0-M8c&>gN8Gt zkL|LZG|-D$-mgS16bh(G1AWC!IclGY`m0iBiJV*^y(L{n^NjU&BNyKs9}kxi(iG}l z<-Wg(Tft4vpx`EaiEAv(Gypc&dgR&K%KcOW(aX%}B*K5ofQzw+Ar0;pEZkj01k5M$ zk_Pvz1)b913X*{qMnR>emUCDTJdNu(sa;P7Xv^aMx%VDSxb>nSnH6sQQdrTdRCCCb ze{WIyaa~!|U*)cB@HK$U7aTW{#(f6|t0S40U!2<S6xgG|X*3=~$1w;8uTL5ezDKNm z^IkWIr<nxn0Py5^P3{7CxvOEp2d9U{nEuZ5gNy7`4f1$2lIJZ^LepUeAhJn>SJJrx zaL}7LL`^F=gT+<GhU8$`@l0@XD<pyjCZNC>OsMp~B>*01j)wwdpg}CyI!)L@ZN=Ss z<>wxEzUOgvOF>}$a^JH>*sbdFkpt$VNpRyLk|L7-X@GaQ7Fu=h!LG{3yYtBBCLy!< zDKN*_N7~vhk-Ig%YG^_En?Ow!4L01m#>VRUM8ADY<ZZ<BXa*%!4hVK(xmz@NIsv@7 zTS^JdDF44Q*Op+}bl7boqW=pbmkEhu(`V`2G(5~#gDVLI#e9V3prA<rurm#cQHQei zAo@5ih$gtf)%aHQmUsoa89)WJKKiY87b-#=?7k9Zih4<gZMNdMg%OJ=o|iJ&^)le~ z5(5dy>RGq3MjZ09#u)nB&(ZHZA6<E>G+L*4!(!xxnuxHD*6dx}q`CCY+g9YONwF@> z5$+iZevQper|En~kwVs$6sxok@yJOOyao$@!Gt!_5*{+)4MfBP4QL4q(TD=4w?YDF zTzJ$nSq7TRgpvT@vS_G>4DbR9LLfnrC!pymKhSKtv{E#=jkf^61N{BNTK;a8!}i3t z0i+A>FFKso%FC&V5_F3xV?qi!t_O6_)U_i@NQj4PKc8HfyvV~lisk+ryrbeS<go;6 z0KgaN$hR82uc`+k7QX$d?RY#Xs>*-1NroHrEc;#b-=B-zhpnjcbI4~jcm)mCQOh$& z;)&BjbTeT$SZ9xG!LKiJT{?oKorMx;T!~EReSZ|0#ud%t(gL775l3roK~Mlm_sijY z&>WM%$mCOSZS<a8w#gUOjb5FbT(P@?;4qQ*X|FR+zq)mw(LAx{RG}F%ktI5D^EP1% zTfZ_afIV4jk<F{{?y5v*THAEKmED6oZ)yRpzn2Feo@(|xDimIOSJwPEVZp%ADvXD2 z@HnF9e#n=CPj~zdYcH=k7M^|OSAykO3>$x^`;<H%U_5xm!#pA`xyI`4!<!l|4ck9f zl8%2fAWrTR@@D>1*ExAR9479iE~XQ^>uR`Fw(Ha2`_tskQpxSfo0gs8cQ&_`++-}s z0Qr%?23W7H=eCUR&*4u-SCJO3O#vSc623~_vO5v+{icTPmjnMspQDc^V+neOYg50A zzyJBQI`Tn|E4Q@kzLiqO-&@d{u7pPN1$ymJr;>>Kmf`2BOeVjY2A#PSjP69s5!>Pp zFrlSxiAxZPQH^9&@8z7$u{){C$s>=vZ80HYX%lS&;&jk+@C|R1-%28`*vU1C5qewb z%~aP-kchuuF|90x{dA02>cYtto8R5x0h|E9cssDMfL@dZZ>$x{`Xwt%GOi<2*;wy= z{7)A>2Qi279OfbAnk~}@ay|aQWWxme8a^mhJ+0DI-C)o~bZZz{YC@fkC+A38@BV>F z0)`9+uO)9s^cSc6Qvpl#qZPPST-5J0)rfL*tb2MBc5`fxh+E_wflkL;=Tx7MOmda@ z?_nqvqk#npvtGY^6wCdRj7BsW_LGnsW8vLkpV6%!167yxjDt&qs=E}cqDfJcLXjKu zpG)jA*7^%nI1C$6Cvq6~X~#I00t*%qnz9g$ZG+}weR@Tov(9E#93e;iqPMJ3L(rgW zfa?#X8+n{F28vP8aTQG)7k@$fG+Q^ta_?C~$G0`=Yh~5xi!cR&L6A<Fece#8t)z=q zk4_(-^kcB(DSS`S+Jn>IDK*Yo!=)AB^caoso|YvgfoQ}BC95=6pG`ITzQq?cz84%} zXJnEvw*;IIFkupH9)4f}=chgiqJDGgl&fk06%gu(&Oxvqu|9mD#i!eC4<acB@7L2b z5VCWNnr6QtM%mJ{DRC1Pd2@}QFHZB3hyz!`gQgjxr>=IG$SS=l3%Zti@!h#=FK$K~ zxP^&Y4kT}>%oEQ3ZX#TZUc2G-xa5P+{A)wXP($^lw2Sc@LFGMT&Ad_XQ+1X`FTSgM zcIBqGjDxLYZNsctYk13m?}ONXOSk!O>vel49yLvT6+5RRuE=+K!%Dhp&Q3qHzbLXJ zP_V7pPJf^d?z~Yi)c_z##|jwGg?f4YhQ?n2ilG``F$gV`y-ck<b=XA~G2m_AXY|Vw zJ)j{Qdmv#oi!n;affB?$J{Y-b-g&FAC2PhfdgOnb!kgZg!MEIMC#Nj<oP!UB?)M%% zVfjP4{P2OYf$GQvv&Tr(CO9>t5~3JiBK@%Mfix3sqeu-d&~zV9o$hebH|gOH$#O~l z$V8aBa&Y_U(4;DcxI&p6aA$gk)GW!?REM0KGMy<BK;*>yTh~Wqu-Wvj?q%F=5{l?R zo&qRC97LdIV0uw|;h0Oo`;Oj`4{{VW?f6Y6k;z#rGKKR?0|!0uz^^NEi*liwMeVvH z>`voh$Do-}9B+^wvT9YP<iuQY!D(;VQ@JWQ9k0DQ=e}i$zKY3~u_V{{iDP2fgjt;{ z!zMDDoJt$$xAV-{iP1)n8{e$#6xWX?k*DmJ(bOup7S0usbJYz})pU^hh8r?ktwE}B zV@$(-DKBZ-s=jl>I%=Z_c0!^T?t=$`UAV!FzZ@vfb_<jkhXi1i1CbM+CEnYbWAFD} zDzeH$E%o4y!Fao?z@G^j>SWOrN9{E+Re!aN&0^Up8!;#GewD~|7y)x0`{s&|vR{nI z^|~Nw;N{bbIJd%oH(YKWq?FCL)*+tt+l5`)oS&t(l|PYkx;Yts)=;PIic?3u)SrDg zH6Z(B2brxW0@(cBa4U!$%M{<ya8}bO&W|HDi0#n16fbHbZ|jm#Bqq?oGja-f7lR<T zy36F@fhW+G2B6Ul4DNUKk%>2NTqQ8_Lh2X3I=xk?U#%YM&<&)&`ix2UDM$dRqquo? zP5ICpazaKE>Gqo;Fji88<Fz~;i<d(?CEKaiE+Ic3zbjomXJhn_6Y!`%<~U{qWP0kc zDzLwvFJ4D2;GAdCX!w6Mvodx%%9`8+ra*Xx!zhj3gLxj4Db7Z7>H~0Sy&c(x(TxFX z<2vMJ17KG65Zi<W02`O?T(}0JcenTXT4?luqnkOUz<XdabQunSS{eM)TzLKW^pMp6 z)pT9Z@4rKaK!eBK*l~fv<izD%W`X)o(soO@@}tfrZ#z>hx588j?t+T0>029?je$5m zsrw{|-k8O)O|7E~FUDlSZ7ok`<F{W|HsL7Q-C8aI9hT_NRB#J(`)*3r&(=#dLK2g0 zSDZ}(ef#LAjVwUC+ns?TfQ<nyc{Seg?+l^ZL~FBww*0u&{<@zP^5}mgis_s;4_<kJ ziz9}Hyi9m9Tx=2b0#C68U{UG&8RvUgT-N)UlDhJ-k8Y%*3?(aFKW^G7stxcfF&a-6 zI=nXZZj$}%(3fP*{fyP^;~czaC6d3GojBD~l#ZJ|-!@umJ;75N+0O8IcL>qHQi*Zh zsFzqBt4V=)AT8CbY@V#-{%myXlDc6frpsORZ<WexUYHRv0wAW$mk0w81yaS66kCOb z0@t@e;zv~)T&A{Ugh6kh;LZEs6ZF~~%RUaI(I5lUL8DkMie-w8S;{Wpfr{PJJU-#p zOmRZCIhqr38r#1X`a7xxY1o0V$Tgh%QREdID6wa6XE5?c30vncdG{y!R)80uY)spT z$-J1+SB}aMS$)azvVm)Z2tn=ZccskAMcKYG|1_ek@E_$J-~F!eAkoq4&p2DfY0cSs zXQbLuvhCTx-Tfho)S2P-D48!Yu=9X@=G*N71MfBAQAgDD!bVQ0!U)`9Iz#Fw$wq6B z40B{F>6WoJVut{L$tnl(g0f~g9p^sHsgBpvu#DzhV$0u5QNzE1fCT_Rm|OSD%F)rc zS)Wc?IxC3(A^n!qL2+RMJ^jB({nt<bv|Y69x1kE=8n1u;-p$5Jxm7^YH7I5d$Ztl) zWgOjfb}opXbElrN(wUuRRV7H~LXzcXe;WL57jq%qGrwNsFOwaXXqqWrOat-*SV{$V zA<jcN?89zH1UEEOd1woa`;x;(q1uJ#B+Y@N?Q@*)T&HU(=kZl4t(p9znWp&Ob&pIP z(#yK**NmW?GOX(h${^hhGuPNma&v}5t5K+&xz?e|&y_Cm14tk?i_l8h|03}F%By|2 zV8F80NnA&4Gjy|9D$e*BSA6+^x0(wxJ7lH(+J@F>TvHy4v9_7p#tDu(>VT+bP!jMk z^E1UBwc11gNkA~4jT;Sl$6zPG8k8XkLm+1Wg{!SYz#2Y2mt!4S8@ZVC<{UV-)?iRv zEMWiMWx$h2Y-ed^zZ(-0IR_@xQUY+Ceie|AT8ixkr(!-(F{*c!0W_xr)#);TA$cVl zhdwl`Y~+dNrll1XsK~s(c+4sx|CYA=-Si=lD*&91J$8-6c(GEqehl(A**KqwZ6L9+ zeUSJ>t~__hYUG3D$GP9yA^rOgIvLMWTNR@?%ecpc8aqJt_K?dPeUM3nyFqsRzHzMq zWj&VbG?Wsvh%G#&D#4K*K~j#P4i~?H+%eR_^yma^fRc`yDdJxp95O(Z%Q@!_ED3X2 z<xZw9tPB%YredS5QkJf{%pLl?E!`pOSU88AcXcMKK!uoT9S*9r1Zki^ryU0qOq@iG ztdg+;7pYt>RIaEBy95L5!JCR?8Stq^NC8z*6<9Op14&Eda#5vx)_A_&^{Uek;*O;_ zVjfw;WNm{xJ{1=|5aW7zF7E?5D>bpKEDLq}4g|3zOF1LfQQI_O(i~05K4`ZXs&Da_ zbFLK?BeoV@PHZ{b@&Xr>?ZmPOOU#L{6Hg^_g;YTLEMA&YbxrIiR`W9r=78q7OyiD5 zt05U(Y?ls-*Ut%bf;Cc=cVER`FI&UuvBc}~BMTUSZSQeDx$Ac_XCIQl26kb&TD>XP zXs?n%rNBy1-=f_WK(|Nbm24}@^Jd6N=Hqx4WC#0v|0g8l6eMDZLHWx4StTcY<Ns*C zWGFb<8|;S>H(_WGtw6k6@5T)YcKv*HXC&K<#21dchfJMpsDjv&vQs;HqQhP6S16W1 z#5CH%ztu(jLrbx^Z8Q-aS(}qIl;t`ENu`6l?18tko~-z})&#k(1A)Gb-i0BcxN?Rq zAk&CGk=dN_pHr3rlsz9A=k_5Ny-(`<pWM!WGp_k+Dez7DJ|#6V$B)ha-KYG5Lky-X z5<0-&>lF!Gui<U**Cg;MbhhsimNKex<JY6Xcnz%dUGRR)5L7ZR=pDrV6yyvIm<V`o zQ32Txv?(-!I4c*JgYxc(fo;*?Hz35RnVLrxWwN5#Q6%NkFAgKV&Us(N?1v~~{TBGu z95yJ|49`^-m-De2;zccpsDL=)IgR##5m6&eDUR#+GBrBn=^P|k0H?>4?tO_ujiF3y z6e!URsEV@sQR<NtQlTx8`|!C(>JEtKMfH>S73qsvA@riOl%m)Q#X%A{pd!nS2~HrM ze3bm^8eSdHnRDjYWG?H0ODea@0VFk?%W)1AKr2QixtXk}rm;Zo8;}8#>;MS9@=mPH z!J%YE$!itjRSUX&l&FT!caTuvie<qc<3S3dl=mRp+$oCl{^ZB_oTLh{1Cc8g2TnzS z)d887%>y@94A)Lgm?Q#k3ZUt^nuF{kwB;MBMwdCZ?rTtn_K&Xn*S$LY(NBVJ8SnC@ zV`(1P>~pP<Uthg`E<(~5LD9_77~@lU&5{FiVs?DUuw{_@V)kXcLSMdjUy3>PFU7g~ z*^(i3=<wO+9uqj9a0KbuX<Ft4HRrjJOD~h+#CkPXhltqc{qGLM&(FcY(ZqYhCYtJi zw>FFh0IHiIfyxw^ySzBpK;%Zvm*pHe8+SHp@@xf!z=Q;_40QpZ8^#kWr_9#ge`FUX z%f*bZM=covK)d7lnOJDo5-w9eJj<4qabk$GwE1nv{j>U-TE%l+T`xS+P&sZDS>DPw z(y_Q#1-bEaxbI?f(VPI;nEW_Wj<*b#H=Uk_y?WW?`FS9zv7<D0bS~PclwE-m7D0YY zincPB47tJAU;3UXmp5+yrL|!4BFM!6V&;2A=yuhtxR_9Xc3g+W$Nuqmah-(L6Q?@V z1HOHTt`PhnSSu$9j;_dYVrJjI1->qqrQR$Pu>&+;{CIok;{%>gR2)z=JfoMR+N9$N zHSz32K{kSuQ__bLl6>aR{gtm8S`qLE+0D0%xd2|&*WN>1`&PNvaFUOHQV2{?a)si= z(c0^#R#7`q^_s<O@5L-z8YIcUoDt7fQNq@@1d_vXO|{UYoyE>pc+6r});owB8{WG? z!K1F*$jt|9J^*Yg#<o)2=%9Es<mK|cN}Hyt58&F>;TuAb(iMMS`Np#&SwSWrUBw}h zBv5|j$M|`!;o6UP?gMr4AoY%qtJPEYB|qyY0yWjM^lM+92YKz9O03FNXzXXq-8yUh zAneP~r;?$d6usPJ8_0PQ*GVd<gNTdjc*F6Oav5J<Q;R?;YQOkONyb7VnkjxHE-z}f zg8?|yo|1-zab?2>Tm1^9A^>y7k5;mx?I8mo6LUeE3-7E@A1PL~5K+TpNk_OWyJiac zc~j+h{`dJoHxuq;Jjemd9?WJO=Q@%NjG%Jmw_9LrKh6r~fJC`m@j~JIHURAUxG&g@ zX>fiH97zOU25>o|M>Y$%PT)tZX#7~z=a|BC=RiPqA4}DFrS4qVr@0ARric~(jbWiz zveeh)fwR;(UZWq7OfyI*oy!^vI*H}-B4zt&(5%tmSZ{d5TvP-!pU@ocj^%P%=Sred z5Cny5&3RE@ASYXCCizgLFt_?KNR)DkUo*w>XO8VM#S;fY4oj7cBjQou(a~c+Iw?-H ztTfd1*{eQLZd=w)TP2<9HwqkTvRl~pn&2T24$am4z_jK_5^^3Oe>ps7T~gk0h!Tnd ze;nmBWdV)D&*^s9b{3vnUjQl>w+)IK=~FXn@A2zJXB}J3%7sP!kc$ExL5rDTegCRC z^*4<DAq4trWCh5D2-IMLs`9>iRj`*5%XTq4iAD)xE{0qoK2n7wpHja*l$|$@bSd~& zt4x_w;Bwi3>{?vGQ^D~=5SzKI2G$iej`{h>qjURxCc{OWZC7rS$9*g!&E8Fp68q1t ztIpu$&nf#VeE$$KNAa!A^4ADexNQ?Xlof%Zgep(Te$R5MphTf3Y!^AzKW6Ti^P4AT z9!Q0)KW<Y~K6`hpR%72b#Z5(b?xi|0BN?X$JbKjyy0BB=O$<LbXmf#@?(GD9^(LGN zx+hSShALWmr}A>w1AF{=l-1DsWmx)<pPhOLYXn)WhDt-{c+`H_zq}nI1CGFlXi_QS zRiE(o!#0m%y;vypwT*NVdu&&Ja~Hq98e8eFGbrFDHq&z4YuTrTU5zq=aOEG%T2^PW zol#%vQgXs7AnqDmso^<G-5@0ZX#e)lr@X+gA+DDn{<?hDQiDcTfp#H$HFdF{j&;7A z;|D3>v!t)1f5ydUHx+j3<|d#Y<aXA1bmX|sKK-LJX3%}I!0lLZj`uG)uDLXBfwCXz z@!V<lnSOH+sHV=j)(D&0EIT5|4$ZFrxX1*t@6H+&r|HTx`>c>DRXMxIVaVcU75<^@ z^^g7EBWcY+cpz^7dys##yTC}8hWj-}v;IkUC1sF$+NIy%tou(cUG{SQufc3rSLJvL zaP}Y*YmoJh8>rL_(eoV5ewh3^V!s5tpAHSaNZ;>LOQ=FcT*KpB=@qf8T(JD_oa8GO znGKhrRp(@K;#ibRP%@ewmz|^FX<&%qHbEvUbQ2cQ0r6vw6_~hSR9XXXo8HL@g*k;g zQX#GY_jgy6Pf$RYWo%=WzPOQm3HS@{`-YYqmra`Eh!gKxAG$|?NHVP)uKZnea<vA} zzA+&4LpUhABHs2{^7r%|`y+kxERhE{w)9T|oPSw4&kR3RgbOBPMavCR2EY25_lZ8Y z5AGGqkBPYX3R;YZLP%5***u!SP6n5_zPeajY9;;$(2iHKD|YI@bEWUUce=!n2DWgO zsq4>Z@+WKZb6lmxy#L(o`KlPFI3B$)(IaMqoNm56Q#-zTx=8R&5?dAZe$QD#)%&15 z<jr6%oMd|X{xX|Ho`2IcW_hvaXTsOH*7S-wd@mGm<|zrV1_Rl;)S3f8Asl@}xlQTo zbMt?~E@&+E=I}goX-U*v87P#tDpX6-S{o@p5mcU%sQr0jj~yT$oVck({5xHD`kA`_ z*6bFbqwufq)2_75s9#5;sn0J)qya`0ZY!r4{8%0+5>T=$JbNQ#x0`%LJ+&)7aBbOw z$_E_KjC;9J@aQ(LaAW%CQjgN7(dfIWv-NI84>exKpWDbWwY*q(=1HZ-(XY2W&VQ<x z^UQYqWD%x+#~Ei$AJDZ<y4$&FpHzG>cC|q3XMRbxc-kD_Y47CyI$IGENg>et?EMOg zI3O64DdGblQvIV}cn<ji1Ua#C0e~s6$X?4zQJCGktCb~ATJw!pPg?rS<D)Q}qGfy3 zJ>;?GeSwK{O}BF1pKqB2i=QVH=AJQMYGELceTKd*kByu1X}WP~IpVY79-gyUSGg{D z{HBtBT%n1B9~mT3ceK${q|-O8J*Kcx>osZ9S?!Lr<5mfta^U9hb=P4E86oAKPd`HF z@Ng;%=r2$iF8aInCAnFEMXlE+54deg-R#d>@np0FcPyQX`C2^ZnZ}H%_XM<5$X<y7 zpmGq-61_H3fH^KG-~xv`RV)GIZjVVKO+tm%?rYDPXL#m%m;RhO^YFzlJ;RXh8zJ*W zis2bP?<*ekgsxXU$gMmRxwpEVcj0rjK3}YWM}Bqe)@m#a&_`GDZ<arARH(BK3Vm&O zpI+=_{#m2<iqVKgO0jmPcf+P`Z5m=*w=N@S-0WjMC*5Fl`qX363{!4cVF$r*Ic_@4 z{l>7d)$(Mk;L(;`F1Z)Vz=&Lke}c}vl(=N)6>zJ$UK-Fr$mH{!tUz~MAQwZ=WCJ*D zB~B>=|9g3TNxWk*Q$R|g1R(FAuuRDno>S>=l_OSyrTsdi{;^_5j8;KjZJ%#mjpIAU zs16!8*s0^4FgW_ak1+i)#Bow>l=Y~HILd*|(cAF8+O<{fsxNKuw)T;W;?9^r?WD!H zBTRLd9XK_uknljJ?=a(*OeS#3YRY|)%_r4#9^9XMl&k}%N*`;#DFm<p@YzXa;S??v zrUkp%%b0Xc_G79KgCt46&k(r7=s;Nwa-QMXGSmQl@i0@Orj@c9Xk|D`Xx06~%rZz} zl)ok)G2^CKgDNIH$aB#9axbs&Hf`}qmh4-K{ibC~>?|SA(t@Pd=wNfLwkxrypfD+) zrFhFJ?KCwx^BvmE_Td|z%h>wJUIRz1cz2#?wI6(*&)>PJ1<Qm$t)!o`EG5S-mT7<I zK&AnJl4E;9EzMM4*VZ19Z5G%xvB&RI)%!EsL*>?q7#_+{zq#0Fx{8WMah{(%Tl9@i z$D)LuwYnI+E9r5X%8~v{?=vugl294j2BX9MGFyBF*KZV3n}32ehl&x-bUDGwjS`)q zr4s?A4VSDCQmhT2WElX99QH=x3T>}e>@-PDG}vjEYvw1>dxh@!3W>%~A@Jvel#bBu zwx=#yP_*)n`v6)Qn66qdmI^IYJ=P}}TuL!uyNnVTd>!0w5RILUGd@FEij8hV98x94 zoRZ2Ga+&sa!ir9FtiH%&m5N$~sn{-pi@AYY(YsWQQn42|jI{W!q!L%N4aHT4Qugv4 zni*0%;Wo<kKagn}mI9kH1OFLh@E6YQ1TD?m@n0pFuJ!ksYmx(Ja(?8i2U=PzH$%jn z-HJlxL&V=zK$Ksi2mDEO`4^#|+q-HhCXLz!fyFnUR1u-SZq-Gnq`>9cyUH!+$gm~@ z8^DLPXRm~G9$x;SYRMzu5ID!Edz!nUptM!wU0W|b#dc+Eug(ol!2%g=N4GToW%tIc zmNrU%nK#^-q@=Qd=z$H0i6BQ&Dlt$(k5L)wHub2imMk)RHP@iZn<s`DRQVo2ck9sP zamJrG=bkc<)tpxsp=>4Hjn0yseQRbSKY$E226?w|&gzUjJb&TLX|XNRvnN_?EmZ4u znQjzZU8jMTYO@gV{>w+3y<PH&vIz6J5?(65aOM(}VjkNAOSWIRDn1i#I1<B~z7{B5 z@potfo&N^1aw^Q!qgDQ5-CS%f5Pih7Q*NadBrjMdV#pe~7zq`<>173%cp)8{u+3$I z%qu%YF4aAYqT91pXo1)P6CHx*TAm0BbNRdItuL>(>hIgIu6`0f`n8yC)v|jgYX}bD z{E=hYw~R{TXqNl*W$gsyd+m>q!Luema+9+%kN+O8?d_c`n*7n=9wVmFFLS!kEs|4G za&x*_=lXm}b*2=hRbvcLD^W2aD|iDyv=p8SD>=3*Hn}(`<5#yV1aB5U?8tKM=->&H z2^ZTXWx3{Xw1hE%A|1>@ovJ#&xb>d=m6T|2UQH3pigDxyNLA{e#^4D6KrKmz&vQMe z!89I&B86KEfjM$d9%{eD*XTVFPa3*pN|XG%ZztEm=RK$VHRBxbn}~%4>gBI;nl%4Q zHOjI+dDXHayNlBXzT(FUs~O_7x$NO%Ax<Y(0~P9^{Tc@rM;=9wPh<8l*-o6G+S-3j z;=*_PP4eHpNczetuz|KY`8ei>+lHm|IB8400|3U#!>v6nf&xd9CbS<w0UqHT=-OS^ z$bJq4PEW6B3VZE>W}QGvxEG<-g&rwqy6Ken&@^ALA_Tx3|AP9}5wf!GoF60|dt1AI zBdaj2+fr^ey!Ax_Sc^CY<ZtWHu(5oLwC&)Od<GaWbL4xTzF!}j4ldnF5rzk-HH$B! z?C#~O{J3nA!9UiwuHASE7DBI&TrlQtb|BP7=~#*PF7{rXL6_epnfcTsM`gO0ekKUx z*<sF1L<f#)x{BFL8aneK^yvOmfEEuKYArTJ$_YB!&)#&DHv6F~a5fzc%eYCZuDTb{ z`FC$+!S@>a?Q_?^sqz_8i;3~`Cwnc^Xc<gKagLFJ&VNgME7Cu3S#s-jynz+!?58zb zq)*$;9%Ne5jQ4<<eVfjAn=*GIL%oCZ1fA0~oZ-fkxr66qgW|Mwtn|hh7!#kkve&1x zJv=waUlc^W+X~(va%}y!Xc-ScH_rqLS_-d{Wl}iIEjZ25{FXwW5L5Ud8NqF#0r_x# zfO7uNC$`b-e<RFH609O7%3paBW?s!O8k;eT&p-B~M7P??w3buHZ_aFP!jQ$#VD{M3 zA$C}9^HNLYaM#yg`4dn;^KedSP>l=X;}OGu^4`}>^>9v3S7<iEN|#xue(30quriIx zkZ<+Xj<Q#5=D^I6y(g>kQsC(LfUmdQzODgKwKdRzDzOmq15L0@Fj+>>65YWm8qO&n zQwf||RH<JsL(wKJXa+jH&wejfwt&t1dJP-JZ{eh&l9+x$G$7b=oR-xzBt4(RaODBY zvn<U?j2jk+%i$SOum*h)P;&>Ut!$~%h|$@pbU80=xB(=7%RAqbg|mKR!kU#d1ICO4 zrSmhg7MD!?IHgyC7)QL~<6;As0V#l`2$RF;4)x(Y{YvwsI7>{*x$>Es?U_3kawH42 z_zZNl)#LkK$J`sI6oxA*8As-cy~^#dNSvgi!dNPyP^o21sqK0V*150cy^*ztk%sp# zp%u&8Og))~z+%Sp-yUk=mgZQ-UR$~T0;k?rhN7~iNwZbM`A=DEoGR=IL43S7XMO4& zNS|$op>YB>fO>9J?P-Rx+PH>wS*rv?ZX;7K>$O7g@*~`UR5OPN?%HF3rNEFql(#XC zBSVbT<Exw#K=qPgTBt{nwMaQE&tQV=jh73HriYA`!_4dbf#(*yj3k6r7Jvp!QQ^R) z&k}PhwVAiOSMAqIEm>CTJ6VA)v$1__$XuO$5)eSmvqJ%mTW-oT8GpVx{}%<62VfVM z&Yl+<cd5=8Xk0nU8bT|FlV>D6MSgH9mWF`#Dg<O2gPRpFi)#l93(~Dp1@szdfT+}} zi`eSb1qn-Gc}{dK8`F?sbjUD8-6nK>er(9E8oDaqXL+q<Ac#9Z*mupeI<xLZ@Qubs zN3+@R$X?r>{Dv}ru~<LDubI}5B@Ml;%~6~usu?P4V=357;ddX@n}JsG3^TtB^?mCL zdiLxqw9d5Eagz+a4J)IINL^*BDxQ2?gGU#2%|M2s5S;0AjG>ob+~N?{-p9dp*Wx#= zjK{zNT39RXH!uE84%6CSu)rhP*dtQ?Uc$Tdvcvo2Se1%hp~@d&a$gxn`PVD3x9xpH zN=}^(^*wup9KOzK#T~2TO<@6*@c*Oe-lLiR|2TkuX3XxJ`<=PulG_L&m(AQll2q<( zQXz>@NZQQ(I+9z|Tq+8UE{JOGl9)?Usqb8JOC?l7_S^6OowIXx-g|%E@6YS?dOSPJ zq*E;eJB?PsQFRQ?rhoyH-*`^cas-=<cWHHZCJI7<cK9`0`B5lXwx86a+;gP*)L1`B z13Dw1(qpkIpk{RT;?G1`qattnlw)(HOVL8hUpmxwiSosV>Wpjaz7r+o1y0ooDJON{ zSpstHHbLEFLUeHBQ>igjiuF#H6|<9X`4(Bs^CyJo8HuIGZ!hQw?`PO7?F3d6rE51` zjL8Bo5B)cBURf(BBdWlYo;;{q0Jii<ln<n<^MipuXr6y7DfYagJG;}!Lp~z;&c1N4 zF-KqzxnCfx%K{HpT1m9h1lN{^$kvXj<fPp%?dK`;fevXRL4XbYkeAjDiZZM8-wVl$ zv$5nu%b_311I)%}q5cwBo4ohdd`E8u_Bc^3fjIB@o22Lepl5@m1MT|z*VTdGaF9XY z#}Lr3qtn$>jaIu_?`VtPcjZg_<~uff-DsxNUj9p!7cZRLEJyaNcK&V;av$uvu!p3s z*>fcDx*FE`!QUD)<!S{o_Y_k^c~EHJCseE-kVf8opA>pI!A?1fcKK&oK$?zuV4`$C z$?yEqYo`YPU&rioz#6MkLzVWOf=I~H*(aT^hSeSPCeZ3pbO*LpG{?t?0k#ZJ)RvdN zC7NoTmuNCh*E^zXIw*H2xJ$F0wAUBJ6UWiy)mDxgj_iKxQk5UZyZHZclu+UdsN?8I zEWo*Wo%bV-dYA?%_lGoGy`^GR^qxyo2n;v@Bue!I+5H$;4sIn6`fo8WAnBbrlOIqA zQrqZaiGH11(~noa3#RdJ_+92ko%@XDG0Q2%3@ymdP?3;vJ;~II<2roBR%^tk##Z(p zimoP4vJO%(Z<n*1^5O*8Bv*>M<ae8LNK)N4=5>i!C`b?q+7AE^Sx%OV0-89o`LmjA zD>2#0L<`@}muJM(eHA@6CSM83`PA%@^%D|1nOy%RPho0L{$8!?AM#XQfPm^7pYV{_ zH8B5grGZ=xdVH2wX&~_L0<XQ@`Q27elVPWJ)WMLcqT)rJ^GL}j-d{^U<cR2{sw2VA z?|lD}lxoZ8W~1D7-&eLJhta-)m7!f`;kK47jJ<Chj5huQUD|`}BglAyjl#Puq<>g- z+cd1=F(*-$oJ7~8MGGTE3;)D^W0JJ7jT|M#`<eW}HxO2k*dU^IJ@Lnfm>Y`8_ge5E z^HqU8ripos0Il!NvZQ^gJqy<Vz~)E+eI(1=!oyl89P;x-$nTF&nwIEK{j4>0%{N5# zB@C@i>FVsnJDVR5rRbSWlIGj(zxQhWi<mOoQPxbNUV_rJR=`Hs>_gRys-A~Dze`)P zJ3*46mdtv+jgF&1X}n}SNV#m}le>NTT=Gt6om{)vWR%8slu(0YWUgAG*toX3BVUuH z8$eTbts;%aqNdYIRJGIv|Ix2ikcu3?me!Lj=MqIT8k9bY>ckiPuGPEeOE+(6K>yMC zb-w%~ioZV5o!`pO{7tH73tB?ydn|0U>TI+h+sNvXj28z~R}zm1GC#TwW53$y902G3 z6wqb`31%F5U-m|Z7!l|eAyrNE-PGkC4<IJ$L?zRtCJ*J#?adwUkXi+6y9vlZ-DaiB zwI-s@eB5}^|9I?gmo~FgTYj~)y!WQpd@TQ<a6ChDqGGkbw)1^uxeDF9yJRIl(yoA1 zZoh_m=vGYw^TgkPt1gi=g59mh>AGbgiwzQfuxqsR{2vefn%~4b{)y^4=W?2YHdhjB z3v=@~LCR4bxE;{e8DgER$#%RD5Ji*QaJ<6Hlb!3-6%SS2q?<9a&K^+k-;;A@z4^K4 z!5i&}19e@Nj$OD=5)gaP+(_Kf#75(YZ3u6r;+U~xh3NBx(?N-eT9f%kWY3-ru+B>L z5?Rt9CF7pvRPS`Bsr-*!T~g+ltA$6WYIV8xq_Wfz`o1)h6**CGG;xo`vCg#)gHW(w z7+62%?N&9aM^7bs*;l&dkaCia=bg`&yrtCVkDdY(V&jO`ghV~EKoC+Jt>|~{`rqgA zwLyWec-GxExqN7O976evFkN&@mHI`0QKIK~F>27~Iqi5atJCyx`mlQv_@0Bccn@Ma za<~Sp;U-{K<AfTsH869q988pFbV!!UDx&HALakP~F4Z~uz9YwUO+)A3kfavNBDMZT z9<%cdpE3JHz^;HM36%vG&T<8)7P=<QI~_{xL@9Qs-b$yI8+gt>tVDJDIqtuveODgo zZ?`>;2-*Sb2PML?pW5E=vDV?1e=1>~_^%>Zz^H#|l?k?PPt>9&zV;Nn<1$#r_)jZM z)4;K-<<D;$1|6?+XwBC55Yj*GRhPPljW!Z&<U4j;1**A7=RalVM!GcJri_B<CZ;5w zdQyk7(K|+coM$@pQ4~>mP{grH#EX@-J?<M&>>QKbX=b6Q!SEUr>a{k#GPwT$pmU|^ zV|&Q~H|p2Nc!JHzO{0<xoIqxvUQA+z!SV8<M|=w1JaWLQtgAKGX5VVpYou_6oUpYK zY3djH&l5?+`TVr+ZIhS401gEpZLAhaTH<?5=Q@*&EE*TPNZMfW=uWUzsHjhSU2@uD zvj2a%j*B1xsYRNv=%u>yHwE_;pA<W)Y{bo|C(2fXbS%(XQ;Dn($C~E<Oi%61``iSl zLyAdm28=}YegmP{^pgCKSKpI#7}d=VG1mNZ%ljEqhPs}(ug6D|i`CUHR|I%ww%`j7 z8BXNRS8EOzGM>AHJHDH<F=LbVPQv%kb^4r5(_`E*jOsFi23So!SKrKiA9}3!5$3<5 zG>cbkac0`e+h^PA3GffZnByf1)Q+#elhm=WLKn4#*=q}`y}KC5Yk{QJYrEC0qXn<a zUPdpE-*N8426RQuGke?}a^%gUq|GjE#C$Jv$dmu`GxABjQY)p=@vZE;TqTEWRfj^= zz6+jrFOD?CuKyJa;@qCtgdMQW_1S;Nxn%E`r@8sHac@$-l<xoGr%Cx$Y*|`(-e3Lr ziP+ZBdxuI4uQs+%{(N*61GGjiO*}!cb8nOU*puXZ;V^%Tn3--Fi%rz6{Qz$x=AcnC zmP#Po=j9jVqMuw_S&9C=BNG)geEDFJ$yM3tkhc%KnlJs6y%hTXk=;AV=imQ(NoHM& z%|A1I`&sxj?)Sd$9L1`*FQI3~H|67^mPQPmRGWtt@0~8S&mK5#IByn(J8ORXMPr=x zp>~d68w8yY|98FP?^KcVsA<I8(%%cmFBBb_uSh99|FkwlF~-KLr{GM}h_JZdVg*FT z=<bL{{rO8j6B+HmWEcAVj$0K%A#ruKtINZ~Ah!bmRI~f$oz$`jQM5T}-w&I8@<Y3g zsQ#fda{2u#*%qR&)Nc6dIs#UwQp=~zyUsJ4OkeFOqir2bHBBE~(kP7BB=UZ=8{SjR zRhk`|wiWTQkg+c>9^7|S6{v2jRdnSyuv%8^?7Vt@6>pY&D`fNQh1!ti2s_cZrxo)u z0w{TiY%JGJ?N*#&@OViaK}P%L<CJNe>}IaO&#t4#{GyMw{$8!h#8JalAMRh%4DIQH z)3q~6i(9H_{X$w&LBiAiWQR*TFi}U%qIk&<L3hdvy~m5|zumerxnwYKZTY8Qfww;h z(j5I%en`pR)vHg{yb26cOW5>ERSLdncIVC!qsE0>#Z%csu8a5&iv^VGpD8br7BV4a z6r=YVTDB!KDYu*%(<$t%+K4mKaUn}Ww><EzYK12*y$Y1NS{iI$5^JQzdy77P`qtm^ zjvbaNRE`a>S)K8_@6SqguvME{1%7s3_qDH>@4YtR_1pX7{qoY~`}HrppVS<<o`3SZ z(7?AFq4q!33Vkvf&oZwqnw_=)`WwTz3tSYeENkx2*zJVGR-u!}yWb=$xU*$03|$*m z6?Qq)N!c8>{`BCUq6^&8V<x2V{er0HqD*heS(W5*ehB%*S-Il_(g9HEpc-2x%G2Ny z5%kYh)psAxpBO<Cii0{beL!Gj!+(E*@-{73fvUy+pt5Qudva|bEUs+AJEX4urQ-HV zUiI!H8gper>13GMT}cm%pL2x?yT$u`W@l^{zPEkzI$M6FS~;cI$8DO|Epa3$c8}Db z#lEJA4p?P@Mp%m2WHb~+joYY=uz`td1keg>W#IHr+>}bPGSlJoAYq)FVx?w~9lxk5 zwkmCdOu{CfBs=Qf<0d``Fu6HJBSKsNTltjBZ5`}AXkb-9T3WftM!XZ{H7TrD!_09e zbShcSC<e{V=zQ}N$@Cfz@VmQNqImT@t~sU$?@GyZGMW)DOS2vIZ_FZdbER8jg!C;s zU<bZ;N<J{{F?5T_j0XCYx?!o7Nf8+dNlEJIE^5}y4%o#_TMB%=*O=3h>6~?nUT`j> zVo@1swRlRV3rgwrc7WYjIwjuD5Jq`QC&moYrM4!8q(2Mr0E<b{qUQ0_da<pqeLlND zh?8A%J3yKR7K7n;J{j^$ul@=nX(6k&mi<6xutlN*c*R>P`LW%F1hF!Y*)u^+r*p%; z^!i+9%xe2bWX3W&C7)uGb@^_qLDRa#`f`?af>GHtUd_3a+ii)hb);XMlmF_8F_)Hn zl@v>IiSO?-#d{vfJWf(7cI>q<-#?I@o+GhUEWBrnkbA0(0L4ou9&jV(`h`y)3;%gq zKiK?e3s4C)2?yiyYX<{&#bcVyyRn&?MfNeY*iwGv0Dto0-oK!->4IgC+Go`q)8LGG zhDw;lNbZ%nl!W!|tk%u9GE{rPdSs*U-iroz1$leJX{ICTSLFBJj>rPb+fr<Gmm85m z(ivLRZ@q?_5imE?fyg{Vw|y-?wZaCw#B+-KOdR_&PIaG>tSIg|0uobc=|6MNg#nTd zGcJ}~GCUEX=`RVmrCIMNV?#8P_ODeWU+WeC{!I>=ws{@<Z&$LVUIz8&MPEt%n-O_G zfg0<v558#tPUS1k&eBBSUDrX9<w^ubP~mcRTimRCCsojLUfI+3--38uxCfLpY2X<z zdLy6Hhwmk3I+)&%Tw`=e9M4NN=w5mB0EP!HE(poEfUpmp2IaEOwsp2oV@UCXB0_mW z9;+m=#$pHlBlFnj-zF`}l8tHq_+hVQ(!3rmlZXtjvVg~LPl^7!m=+mahhDUis{d-* zV_N5PH*%FOSHev-?w$Um@~8Xo)q$^8_6FH;wsjXj6$`5+RbUQUE+3hi6w*{oLO7?L zl3Rx|teWz&5zqIFpO~~!2|FXazweImLpU9o<p%W?>BTo|5BkLY5^hyfK@4X0;C6{{ z&6&GB>Bo&S9HxRCP8@UezL^=cBeLgkOqG&x4m8KOJZFV-%Ej`<QENjHL;|j^VJ+gY znXdsH@Bqt-9v!e)9uW>qJ0&fv%`jR13H2TX%RJ#gjQN(N5uQGX`Cz9oMSxlP645b^ zf~tIkenL<kO<)nf?~t{X8fviqytEPDGzcnAQ(5VKG0F1M_O!!GxzF6WyVqII>aY2N zB@n^ieU08=7aLR+c4LyY_1sOr1_UZCu)8hTBH2**9@!DBgKC4yxqIVual}H|Lc`9G z_u#B_F~{Mn?b$*@%uRi2c$ch6M2Z?&8ESC2OF8K7-V>-{s3BKCHQ^Qa!p#Zvu#t*% zAq{<SwL)?01M<Lt*^l9Fx#c4-Kcte@bB}JweH9Tg)!0%-9YG-5YSMbF>hhNVdR8g5 zg!fpX@4T{&CMm@i_r<49w>p@eQuG^fU>(#z#u01?1L2I<<J^4*+KJfu8W1WdT)=2E zgk9ab^u2|Awrg^2A?X#Erw}N2$YX^r<;ig{WY+l1t{q>lJ@MSMcIe@?)kHC#TiC=+ zMEI5VO3yjXzIU(3Fs`9rWYO15-G=zVW$jyuPPL2Iw%A#q(>m|QgA~+$>#dzP0#6p1 z#=geo3Efx^$3%p8sWY%bnq_Q}*zm5wFtiFmdJ=X8unlnC{?-lPkp4m4x4W3Ii-RP@ zC5n7MSt_A==^6CF@xve~&V6r;6JI3lomLJSZj}#ENTW%GCjPlaS1KinrK~i(_&S}4 zQ81j2y-$>PUv0;u#Z8^wS!IaF(IjniWJ`&KbIx+d?UiCG5UcDM**ZLgCggS&YC}PN zW}`m497|mE*x@nt%K+r1n&OmHcyb>+`yTcg8=X;u9p@riDDw8i?>J>K&iqDY258I; zl{(jbJapvqYWGUEv|EQ_Cq+ODU%v&C|FBo}H$~}1j{F2j^0BjE>aZ+-L}rMhDByhk zeuwN#*qoK{*53J}Iu)|GFEX8#l4M6xJFX*s)dNlvt>MC10GdmHsa0SBnuzGi<@|$s zVfG){O#Gb6aDrZ1I}@QeiwT<Rj3FZCX%hAnc@r=?H*aLZO{OT%_*Tx9mib_Kui|$s zMzvDO4J2=K9=zX1Y`y~Pz-jvplFa9S{^0eXHxn%#1S`i=E*;_oqEZV*+I(Kbo~G!^ z3sZ#B9#7ev5$#YC17XFd;rTdNAQe7NK0A&>@(=0DTvXs5#5nsz14E@2U-BD=_)Ulv z$X05a78OiFu2JH=b7h=I)tsw-{SH<#1#$0>^x^^-vK4ZVkBs95G)!qqpSxDLv)IEF z@gdNJj^1H!RuyY7az@Vvi}+Ch5?fQ&Rjd|SB&VK%V5U}9rwHPYfoNB%5I}%<Gxb8* zkQN}e*zK+%252Hr#psFbg2hYMM0S`;ii~B~QN16c4{B;M1ry7cu^6*MrYl6TG@AMq zr0O{TWJ+tZ$I36#ME1H)+^5KIbcm=l5<X-q+IEP9)4tpC2@Y+K&%AV4ypWxLkB8N3 zkIysMVgR1Pgyb^?od|k?ktUG<vJ)dYEUL#JhW(B-_)O-njuR_72&l7IyMW{t;I-JK z_jA;&<mdg~bP-ODY%t~-Bv_PLfge^Se@{|cq=_w4<W<5pKhrhI9TL=wip)AWLFXf( z-~JlT%cN8&l0k?WN~GEz9hdJ!HyYY$-Q&ZBV-T?DQ?6hLLC=#cXitD;0YE&U(;>P( zw3aFxijTi**Tli7fYaS76z@)pYJz0sr=<sBrtWKIM~zTz2lXEcm7B~e6)KB0z1owk zD)0CWYpgPj4pG|zNs{@#U&v;HjfK?Ew^D)U-fpMVd3O|>+^b8cWf~qT;y~ivM42X{ z+&m=>0I^+WbzsV<rv%tsB_xC@<Vk>(5%~GgLf&jt3}nY6$%Z%*<FAH{-y?FLEc&}5 zz@8}ONEDj@Iqgm>mL9dkMBDjzoSOvg_pcBM9Nv@KrHCdTAa-J|AmztN(!W6uFXd~l z-cigc&{`xa;gp>p>b!G%C6b_Qy<dHMAnSA)O=Q!6;H;|W@uem}jChzUXwDQ2<U$gD zA?7jS+D7_R=+31cg!cmkrb2d+DCSEOcYG-8B5o%l;UmRZ-kE;jNRbxMa{or*Jw0mv zY+u8DWw8%cRw)~nd+p^V8!dA;tj#+VQ+cSUMVeG)qQo*q5hhs3p+=1cC|XbuYq(?X zq`Ow<;G&PU50eF*n9xMFb{Bx%0b=%g9MgL&*~&(njw4b)3JjWPwS<`Ov;*|5+oNNr zkL5PI4k`+&1hb#~$9#Piq9q1h=gaZxkwpI2YYgUS`gTa%%91l&sx)5`mH%RRo2KXq z5=){4PvjBYg2i6D@bOU(*GKb#>X)0iCo;)`^8x|cOu?zgXBHpB4)xfz<B%2;B+3u* z5Q?~H$A<f*(?3jpJ$)kodtBc*dn~1j`dAEmhuHVnS>x+KzaGecn<RAm3C1XkV51>} zJg1lt)nt{X7+xVZKRvfdoZ{zS8c$u&D+8cv%>TFRg_89?d$<PMKiOa+ytPFb3-Saf zMROv5NskVNe_oxqd?%;5$<AwnBAQ4%6Z}w#UlxWB;a@8s?ygW&K?nT>ot)I8tKXIV zT_K77x>Z~#ZVr-KQI^D0_8Qs`8WK-)0_3EL7@)v7LG$urBER+eV;Ece%gmvZr%xRJ z;`y}zF~v<AXNvTKB0WKpMnoyY=~~CN%W~4o-p9S_h?s(DB^FI!8w4(C?&Akfm?}Fq zBa%py8Xs=VaNo8Yr3KW0MAvA9RSB`63OQ`vR^4FyLE1i2vZ61=C_3`oz6s&Br+NWH zunYhQ9OG-kmk7MZYv<<e%=L96D-@Z9;*TlfQ``qJQXmD-%vqGof2$AXK`2H~;`Vvd z-DwF|qAOC&<&v_a<qf5jyl(|R;&e4G3MR?j>X5+Gq;Ay(1QCO4X;xa(ES86oD-DgV zaP|S8`dWGDOJ$x94#A&`5vsD2&SJMyNpEqI%fwG>6!9&xREo0KGih}5WPwul&5W;~ zYgS^;={Wn-zP9U~y{8%`x-5Q?cJ$46*}7?YerNe_FiUnsmf#_BnJDT@Q`~}|+*hGk zMv==gq!|e6&V!I_CdumD-KN$eZYO$;Ov&`LS(t%b%z-t$k6FX%r)i*fxahb&7@%I{ z#dQe=Z(1}-S<IEF%<TQ-T5{ViG$Z5dgK)Z1LpAz>(OA&RQ=<;~!1v5*x)Pi6?0bfV zoW{&|usHtUgr>S!K1B*ooMVGzHP!p)EBKf700t<<Rs+7IvL4@GI7Nof|G9aO2?tCO zp*ZL=msA*2JVO;}Vk4wM>FUHIE}VQE#Sap_RMv3&rfkax4(gyx`LjDYTeYoI4hn|n zOF2aFbVz^P)0OY{8!9PEhBPVlvs%n7>*WeD^A7Fh4%to85vNN{;+cx}$}&%tg`1Tn zM*((-gh}@WTl3*z|F0M*2(wE-JwC4-`vJ9vL$GloXb`3a2)qZnIwB=rc+|&~M=$Uh ztR)?2anc#7l<m2w>NA6P8mPd=5PzQ;mi^nIBn=wh-4n)7sdJ?$$-*NZDqmE5V0~X% zi@#sAP(^cy7W-=~{gy>cmm@EQi?0#onkaHfloYq>J6ARJE^45jvCE7nKCW?57jvF; zKD3*nV#mpdlzn`yPrkQV22T`~rG2Wj^|HFzbKK?epY7&K$P>ideJ`XX{fW&w(tRxN zrw57B?gBK?+CLUV8AZoUS&fG^e_~bc2BA*N4^_wnOpDlpE+Y46A?=Rd&zilZti<6G zUD0B{e;Ny{Jeul6J>{ZBLtPE@OW+l-(I|tQP0R~2TwodlS4LP&o8x&j8P5u_oC>58 zr>m*>Wz|%3Z@Sa&hGg9qQ@N85`9A0-(eMEZ7Bs0LN+l_#O{GEJfYQCMU9S7Olp{?d zpE3=})PiP;lPeljPb;cTr*w3R?Zq5>?8S*qzX_tDcmL?Fbp~9iiOGRsw^W3uxEKfp z{g}%yXk(|?*zSseB>r{?l{A?JM%)IRuik&Qm{Bn&Yf2MuXupuHD*tpxe5K=cbfHqO zvc&<32;zljhBXgY_t=cm_S~xbcI$?etzP3QT5`@=n4*m0hapB-w9VS=07O0{fCi|= z;?GrbVHkmF#6<vFLy#CGNCtKwJwS*>nqokO*c#3D8t;dLuO#SO$M_G0(UzriOq#gq zwB)>l0-x2FKd9P&qwsad>5J|~!yR=CG-(b^u@EHLZKKp{8&wFZZ=HU)w^w4GqL@mN zarafKZaY27F0~f?a>4k^3I8uXR+ksqFtt&V(<2q|Da-^8GsJ{^AWDAdSQt@Ii~(UC zp`v(Y>B6w_d(i)iZr!g;(JQjU?NrFRPK&2esFDJ5`Bk!|rwV^`$NEjv^N^YaE3%zm z!5T^8hSQ=$<_i7O7G2jZwNj*vXo@ROWK`~jP&81Yp^jl0wj1nX!KyoNe_+IE&;bDL z0aEg)nEC_~jhR-6=0D@%nXRcy`qwh!zIvDPzCV6xFT2_!Hbh$*G%XyVJN%`|Ceh?S zgWt||$!%7LZShg>X>r2}u^{En%L0{kMEPc-yh^XzgqWzs{fl<4s~beA9rHDtcmJNX z1#C+_aYyW|1t2E?r9l8bKtMA9rB$M&hw_VXis)Wl<=-;v!zVwtIK)I&DJ6j<8`K;# zPpc9-xwop!1+QmQc)#jFZ#f{`c<iGI<Z&hM=W}^S9rXB3rQC+Ma*#~_Cz+q_>wa_? zcx!QXxW??}JFSwZXNHm@8fVWAD_X?(4wM}n+v8HK2fDLlqlr-j2(wTHCnNNr#TD-y zFZyuS-eWn2tw&GymcKB267*%OZ|K%L-a~R%h7jU$-TOyDWB2`DKdt}R96mcx?%dq) zsV!!G`BU4(?UUDlUASWC@P+AXyv1)b;tx<d!HX;PUr#g`nnx`R9sJnds#NQ@SV>gt zd#Gd<#JSXJ6WuSN=eE#!Q0^?MvN=suF5>39`pdl${c3MM+JEzU6vqr-I(j$smI9tS zGgxrI@2r${LXtqstLFz4S0?>l1dl#0-)r>mOl^Mh@R-)&rJcsM6EUoR+lk=yPs1-? z@^}D5lS|!xFD0FD?ds_qv$TJ+xw-`|hA=%AznWnrQnBy7rTphdIo9`9FS;7n{1iZ_ zHyDjNTJ@!M<yt;uHsu=6+6La-|9KUR;Aw4#(~s<*T8TWU+jZp88w(aEKX>1oR({*& zrS8Y&mp$V8M3ue5Bhr+tzcnhjlfQ%16&)!H*OgK|rc(}_c|0~GRmvXAklEz7=xXqE z`q7E;XnXE$DrD~>Gf6V;ooAZL0NMK11~|uJEs&I<oEDx4*I~6(*4|~g89M32iZ@kS zyzC!4Y`W|Qd9V3tJn{|cb9=_D=`V8AA^Yckwuf~}II~FOaU;^OW}8lPw$p{VJq1eC zs1XS6O3;3B7n_I^-!3O?Mx{wnplfLPrpKxd+Mw>Wp#z<anZuPUDj|z)tG(Jk+BZtS zNVt8Q_n9>3#jFiju0)+43jCb~4(3_>?5DFVp7!(8h5oII4W%MaUqW|x1tkudKC}@O zIloh8<78>Ib^MTJ>5BVYMAc&D;e8)MNolgW@4tvTheTD_N7+yR?3J^Py<G1cA)cQs zl~^~DuCiG(I<OZczX~^vX?Sqq#ji8<zb1Sy`@MUc23f(Fm6qKfdLQ&>_5>ZBvM=3o zt{`&gbdi?}+H7GX60WmjOP~F((JASb;YRqZ52K1~=(_JUl9a2RzsT<%{>aW3!d>d0 z`{Z)-b(Eum?~1&G;)QnG^TWhhqK9Gx!03_80vL|X(<>@SX^`!=bn6#W>zK*!ak@LJ z-BK4cSHJCwsT^2#oElyaDk^m4-JcB-MSq$cyL$O^aro@dKU~kM+5Yu3)gikXoyb=v z%Af<eY6GXMa`FB<g5sA=da7e@P-8}faNJn>vfGJ*aglngf4GebfK9^#WcjWPTj`7U z4qO7Nw8>zCXI5VaI&PI7`-)jPNkhBZ>L_Rm0w0b;sR_QPM3>S&_UM@GA1tf7aE~c$ z8n$kEf#W3BeBZvI<p{<#X6}STXOHH*0qT4ZT_l)X?iDgBNsv!OcpJW6x}WrNMI43n zhTGz1ID(XwQ&LrA2MJBj4um%<2A5SOzu@T57{u{AMG>a^=OH4iPbrM~D1Yc2!2p3O z3Zt5RpPEv0+J36~E%BHlIsOvaK`W|KrMQym@H@G`M1(y%xg@KCyzKLfDu~qnDe>SY z$pi8>C|^e~4p@C8a4~{9zE@Bhgl)4~p-C;K390!Sz>Haqi9Pr}xoO9~Gv@0hJ|urn zfioEUe-QzRz7+_KpLn~^-)<H~1nR^b$yJ!C$sd9CS{YH4m51nZwrWD!i^Q_oz)Hzp zQF~c9MfllD2bv1l$~_~bk{GZ9PpjQQAa1gbfDp1(y3Ya^fi#KfEbg-)sO^G~XKdE1 zaH!yl>ZKdht7%eg+QJ)xtvMbv`pt;#yDl$ZVO%Y$6f38dZ7XSpaf7oCw%r=6{Kbqf zri~&|tNA>ikfu}{P6fi>v|GpQ@@o(T1zaYaUJ=bpwi%}@viM{497ZNgmJ5J3J9RB0 zGOs16%D)aQa$InF_w4%@|I2E%mK&S72Uq!lR0H!q+tb<h#Sl5EQ)=Bw73o(w^A{e9 zD(UOYRb_h66|3FQq6<V=(T&lIsQ}get^4&sk;;mznzr(vaXsfgxvReq@sl29q}lWj zp{@r>s9tJBc&}1K{h<W4Vk{uTQWd?u*{$1Iq2Ffyr<GIw8bVt*ko`;bW^F0bEZ`^J zKIEZN*0)q+;LrVttXa_y%+y!C9Y{C6A2BQq(<!V$p4X%!4pQ#BP~F7_qo>V*K)>NI zo|(}b2^EwttA1silNL7)7ghhzgS#k_rq7xc6VzmD=WoMLl4mc+WHqEYxCF#6z18N` z2=8sk^owR2OK~*&tlB?1CaiSIaJiGlKy$8V;Klt?$^jZtL=5?es!S21%&>(h>@}3^ zwR;q-noy{_0%fqlid^Mq?BvO0cwtvfpPo@grYA#1vMcC;{scKoRFDhhwFn(x87S4= z*c^(v^}tuG=Y+?Kp1h_@pHtU}zJE<s%H;MLYrW~L$d$>|S!qXDEF~{2jqe|Dgw!+S z>*836lCMirwVMdgUBkEItmj~<n0#Tt<1b3L!|-x^zK(uO1vWY8mv-yx2RxS+6;yT0 zN8K<H*fl$qkY=bo+jP9a;=uO%=<ZW(HGeVwWu5i^uu(WzcDiS=edFb$!dmTTKRa%R zD}7vidpJ49%SHTwsiT0MRcQtCEV2?E%N13u99Phfg)uMn3&?B$P|$qao&c5W#gdBZ z`0N~)dI-JXb)~aEgCw0BBdAUoNe$hpl5UQ%OSPsTA$YFjq^5mpDe7BcTNz#B^SKj- z)3E0I;N-K;sg}LLvKKWAm0I~P147oHM=-&X&!kha``j^yGD&hj%WEzs5p!J#3%8+m zh)@s+QZuh?e!TqnvD%(zfd(F^^dMvXN8I$d!BgV71bY*`4j5I2S0()d-)nB`pB0`Y z-*EA2D_8iTar=jJ&;HuDs5fNa5B;xQX&bL>`ouxjKd4gv#*WYC5Xd$HsFho<F*j@x zIT<%DAihxyF(!i`V^=j^`(=Ou%KK!?RUMaxFw?Hfx#B0bJKp-%kXEPxMh|UBQjv~1 z>W@1lE*YIPe1UD%P~n$z1aGZQ4kt`($g-{l%?#7t#u}qX)>q67rEV3ERB6W^Jmm2q zem$nmD&rCAyrYWDuiFkvodjqlbL(~zS2%=xPDlt~rRtta6+1{1P6o^$+eIKRq3ybb znRqzgwEPF)cLXFS`IsJuGKoDQSAA8@GjY|%4<MW`V#0X&74C_Wu~x!i|Clfe#A<?t zVTHqgv7(A35PC=Bio;>+Oym|DcI1Xx!)39j8q}x9g{chTFs_&l@z}ki1Y3&OGmk4> z&E)G`ayeC~iVP2CBGzcqYe(Gu8qslQuU<Nn7`B-Lw((OKz1qr#Zjd9xzreay@dnba z*z2%X>e2rq=|+pOW!=y%7V0$%xrR#`V`4sVg&ao?pB51g!<!30kHulVN0r5nE~W>Z z*mF>s@KMzMbRM*Rfn3E9tYji`sqi#q6JJ`2qEPD7n9OaF$e}(=<ElwW%jJ6<OyncS zY&Fy}14dDoeHwv&!%es$ak!dr_#*+sq#ouun?Nbd3;2=4P0hlnw?eKh3I|0L+l#`V zy$cT%i123}PGyqs-w<kdL-!Me>fA6TSj3w@2UI*WTPAaNgQR|w17dGz?y@C#;g|+I zyqSaHVNqEe41<_8Es3zLK03=(Wf2UY=UE*z@p!|5Ra}De#1u=!+@e?^=ebE%^l+mH z-Qz*Yf%k-6R;gz}kVZH3E0$0T%k?2!qL+K%9Gw{VE7#VmU^LoTzDa|}Lbnm%(rNJ5 zY>d>tql;Adj2q?&O*JV-yEV~J(EvG&$2{X2{xXIhJSO~97#hQY_^@)4!l42a>BfzA zlp?n(Fc8fVien`MWS@{#IM1Y4=o!oPog_Zx;31n5qJ3*|){^9CH!h+OLEMkr<sOO} z!xVS(uP@r(uV7z~ql)d}AK6yJOiVQc^B#{WraHX}5Qa)RM`7LGN0@KjpzhDR5X%tW zrJsvk6(;-?rg4S%cd<@_&=?DoN`?PsOMDG4PLDOtmMI@imrN_tA4-*e1Hka}%I;pV zrOcA~Xw*z3yo^O>dSO~P+T9%}CI|7u7)j<3&U1zQ9E9nsNfY^}^=JxFS{Zl8%t1wv zu0O&rv<|qCJzwF4t)2)y!6}W~x(md{r0g#jkIOW;r*R7pSLs4DhnxK2BFk794))eN z&MC7wRa+xCuOBbJ&OqW?k*yragWo6PxWcWFbK7IL;nCE;kws(xl0^1tv5)Xt72aVZ ze3_UHmQWd&Y0xbBN0b5bs_<A&dA1ne9S;9ZKsEyKayO4^JoFD$d5O(86tgy181z$m z0|7IEN4{bUKgA=;IWSi&gdPsPhD%<mvDW{4FJK|Reiq^jK-#^S-3ySE9%KME&V#^T zWo0{>74G+m$Kq=D^k4P+i78_t(>gF}U5F}<@N<UzGb-O4Mx=(rA56pgaC|Nmag%^x zQXwr2%oqTR;Q#vj$PK4&9*7gi{}eU@LlA-hNJu=ELnvjU+c}V&`><Uynin7zDHc+D zDM`QhSv~!7z|ekV_9|wMiu%gdpCZ5)@t9v&L>U*BO@MyC54#TVr9;ebb4&>n^L!e{ z0Yxl$=I~@$f8UyamOd8j5Z?lUrnAZ006dU@*<kR8l^Ga#g~(pUDN60svqrspwSU;K zZf?vn8I$!3bK|E44~t-}V&0INN&z&7)lh=R42K`!%ZP{5#DTU)0&?nS7OaheB|*jq z(%G0QM)fa-U^c$~oms)@h<f$HdieuSh6@|V=Ho}$Flw|(XECCv!jUlzTPLFe+c3pU z1l}1_ghM*PeNR?~TgWvp#E1iUsy_kRXI>3(Z$6q8;<Zv?1x&Qa71%DPEdPG-;RAOH zN*g^sw#1}Zj7vuCQum6j!#Buxi$*Zcf@q6lC}%;`1fQ@Y9G+r8?u<RUh+ysSc!08l z^6Q(AJS0Iv&}1&ep8zi<KsT5e9S&?P1f4uBF__Yl?p*$Ep`~9t;H}J^vAOu`c;s(R zOig%ek@Af)0_H|{rYgzw39E9Q4Gm$NAA{D+Ip1^=vUfk@^D3k6kq^{;0xIDd=#6iD z<E13|wU|@VzP0U}Zpa8)l=5pqf8k<=Ut=;JqtDz$Pq2@c5u!PG<iQD44JWSEt7B<V zOgg?p)>r*~Q@BH(@MZG3Z<9sK2ihKegz_kC*HS!Yi!F4^seZfoW%!8iwog~|ui{-6 zGM$PZ7DI5TtxF8VJ!-6|0bH`tm4&@VC+s^hzc1SB#TH53W+Wtva69G!xxbY4Xj?d& zF9ULs)p$(%D$CjH?4JW&o=0m<+Iu-_hvJQqG%A`;XIGQ?lNTk`40JaYeW;cGo(kK- zV`{iUC-a|y9)w37pz_g!w2;n6A49SULQzbNQ4J~*i*gQrc{Z!paIp85jzj1=2EYzf z>_{YUW9}Rf$tGjc3(#d;WJ4nQ9wX`(RqG4g<ETL0XOVLi?#;)2eLzBOITmf{TnL#B zE4znbQ8i-Sm5!4JIPwF$XpuM776Z5A-{7JGkcP<fOw26+{e_BN;y{<Z<ru3+X8}Y( zFM>>_3fH`Td6xQgLg<?`lt66ToO<#2CRF1UVx9mWCcuLQ@di^VCrRy-WgLa16I+J$ zTD>q2JSMFGUE+qCWntQ}+2lK6C0s(?o;n%%QQ3GgfFVr5568LrtRUJt>xOA8T~`Le zAr76-fab*oDBE_ypN}aDTExvsF>#PZHs&i+ZUgIL<`F%H$24*Yl4UpL%5wCkul(GB zXk<g&3!&-Ue)k*09c9o<R6FV`L_0y~E*Aqls(tfI;&Q>*@dv#Y3h#R81%J3w_!Zc_ z6R7LhINt9?(>M4>8yx8L73#}4bCUt{U;y&9p9;&Y^ZWERr_MW=e6BSdy*CrWa;(3( zGI6PU;^M#e-Qd=tqWcqML;!=d$bfE9<$uM%jp(PXDm=o-ZBGj!(QeR(2L>Mnc4~in zQ2~ZLB%oV35byBRadUqD4=1K#iuq}3qw)mGEAkH;`h*N`2#0Z4$P(aih?{WhS#@sS zg?@PQ@oz#bBjJMLo@dWL?|9TeH{jc3;X)kb6GP**`k`HeI~}uAJAV2acP)GjVB35p z@;u@WN4SLpC6m*`I1iA!LWNL>7fZ~KnoV7Orfb=@^7?bjnR8dL&<hO2J1&%8VB|eY zv!JRx`S*Ng7iBVZ0%KAR<8Uyuf&9$|)=7l~5Fi$xA$(2rDghEeg*47V-g`p7^^bP6 zf9}$;e>5iaSZJmhk8xrOt*ypy9>Tc~Ok}*C@lQz9d*M(GAU?4%=>*IhD$L<NB#{jb z%Q<IL%HJt`l38!5tHLg~7NWnua67gTy?r;6EnH3h&+FFA$%MsZVGAC9zKew}#+|vx z;ztWZ<gD5P1feu?XL!S0Y{ODKx;mZDg{}&<vJoZRgc6-diI4ByG8Y?$Uh3^)cJNS( z#D;1dvXLwFJASx)XsP`3i~Fa~C2*hvTab1(G=~M7bL+jnwLJ9QmuGdTzLg4j!iMdH zLpShCGP_@08hSdAZ4{1B5JR{^&z?pWz84NT%RQf@XEVI}opmebO&_kDDdg;N%jnU! zsiDs&QP7MP$QQi>d<Xe43zif91@eAn^~I{nmoXlIs3Sni8G01v+}4X9|GjuSTu}tq zhMrc2QV2qHF0=?hdp4{hZ?6p}S@2lMGA1UT3l9okDsgR-y0ET;S~yvLE{=Vgj)f+Y zhXn_E$ZSC-Te!##6BpI8UBBk~-zs|+v%`SZuu=E8f@H36MZ!88y#o6Rak!oje@!4^ z%F@|_sSHFY03Q-=*W_)4>pNIket3}rz2H_C!iDgzyjU`Qxs=Z4ZX9&G;`W{91})hY zPUOCDVZs^+Li+6*nu>q&f4D^QFr6%+XIRK@U#LqO#ES_*x~f0=2D!w9XrR6Xa)j%I z#A!fTfGsl-_&+r26%H?D3-93TUn%^({@-?__}4C`;LTM?a_%{Alu-x=a-Isg$`L-# zo{c9!C}iO<EHv8<ntt-PARHhneGlg7ma!yi!#FQa?v9)(M<&93sSrE*IYFnk^oMVs z?BRLqLesGu^*rI5RvS(0Lcqu#6tLgl2(^7Sr`$3HrC=_IJu+jPA))KvU3_HLK1aba zK~Tnh&M|+_p<A{k?q8e=Rh3?Z_7Cx<UV4TsQePciJgiK(7QZVfn6@x{8%TiIWO#6H z<Nexqh;u!#>T9s~|LE_r)QLjB=Lte`$5%X?PQSV3SMux5;I-FO{6(?5Zk4xe5ubDm zjNCrA(Nw;d%RzIc^n=%=1p>j&`gQX=wNILj4M~r0=$`B?^IAVMbXNJlwm!x;ZJDgX z#P`?x7hT(J{iGxU$5GPw=v`^UjTGm?XxO)7$?~o1;WItiN)ESns=Yb8JB?o?l8$uS zke_WHQCKwQl;0QY5xQ=VVy0#9MlH=OwYG9QZ@f%ZI=LIa75wqz*Kg@haW500X4zfY zHk-2;;H9WYHFp1$n`)-sR=+Bi#1ka4&~h!seM<k~9y}yrtOX5hXTNv-P|{w5&Y}c` zf^8YZQOB-K9X7Npn;`fKoF%hO=)%}|i>vippNXu@zIf}D@Z(gq$iuc8x04K=v`F6C zuQ)5M8D(1E1yuX1WkLILEpnV}+sfF;izxjrs47a&v^K-?O4%uBi@IuMsFUTNxktmB zAKI30Xsrb$9RgplEnwTyH`eR{*;x7;i>b{S$!imT59wO(|MK|gVPkrFc`|E9SVFrq zs2jU~CP+{Vj5+3U<mKSaH<{29f-T9#?#=Silh=eyJPZ7r*7uTvLInZRIH1Z1JQ@A= z;ckBR>r6cml%9TA@o11oJ+DR7#5bZ(L8|Gq;9mjiq-Q8rBOQ6L(2fX{=pykOc)>i2 zvf>%pYjZ2VTrUc%w~#I0Zrv+3#@5a}#i0(`qV(Ep5)T=lc@O|MUrfU`TeJrSi24-` zj*+h)wl}j)y6~5e4s@oajli_xtFp})-d&W_v#dYaKC3<p25Ii<&w{G{i|ik|7AB)w zDgO4fQHU)w!IR<mej};e`HJPUa}Qrajy=9}(?kt>S>{eDVTx66&~w6G!kf%mxZC!< zp$yDc0tyqrB1H8Kf%%saKHJAWbjz#e2LPVX3vEiN7Hb8vhG(;03LmE1n{>IUX6fGt zNT{g^&)LHJk^?>$Uhz(xeIA{&8&R?vj~b!pSZz&iUa-Z=%w`_G@10s+@2l}5X7<XJ zJMfnp-RJ)tlzp!tLW;{3l&e$UXLaS97w>GALAYFe_>$1lC$Uph-q|a^-aTyFPwr${ zY<+sg3&=iP_p;#Xzdt{=Mz66Vyrk<^g#;2h#F|?MUT!uMAb0Eb^T>VLRzKlzn^mPh zo_*%BEkv}a3;h_V0%AN#6fMMi#=R!P54G4xKIJ6qCn-DG?zt~L!AaTQO+iPukQ9G& zQmq98u*s&jDv~2<4z>ZJH(G4fO-9lW^TXornA+_<K9X^wJ3#VDi=E!3k<62Vr=)vK z?F|b@vd-F`l6~7^f5+tMNcM%KQ}SO-9n2?2axQnDQvB88VD)<>_nKfJPRPuWKgrBU zwGC8}XmzwV8O_U03RK%;cF^hgXns+5pt^DELDx&8*KZ4+*0eKoaxWY$xMzEM@3B^= z<4>CkRHIJooPKYAYJ5~0(CnSr8}Qo4Rjufyue|;_84>cXdvVvs7yYv^d&O0Piq$H} zuJpZ224Sp}lhto@FZRtj0m99(_`Al>MX`YLUqPWjfIkh525<me03iTCc>oA1@5o|y z(4k^`efwDzU8z`AClAvzl|7l#`$DGr8>{+qaik3SgH6@1u4^8>@B6Ch&g&xlsR5Vw zr|!PFX&Sja_3F{R;oAf{T*2va%@O(`mGr@g$F*bk+^S5D!O8g&jO*1Qp9Y>hIFX-d zv%Kl_^#4U7A;Vvj;68R~@c)ZM??UsG?3R~5y>5Q^-%BbOq3F`Wn(j&y)Ak>1X`Jn2 zs5;+rX>I!Qx_IBY&x5Ux7KWLmOvOXb9xsj69DU&b=Gl|4?^vf^-#WCtmiwWFm(Rkj z3Ir%2Zf3nX6#oMbIEb%%_6q{J4|=NZ-6{S1`<`P*^*M*HSK9vk(6m0n<Al$_pui_s zs$Gl4kLq9C*#p1au!3nYKoTk$rP{i~I}?FtKxC<ej?>4CDBTwU6HRep#USc!0@}ij zk^rXR$N^^fMQ$n~Hk@mN3k7D<(P8*$;zq^dOse_|&DkuYiJ;kR)A^d&9E;zJv$+I_ z)*QoDGI%b}QN4C9-^FBU?z)@3)|Ud0<H28Uc%G^KQs{eW=}QqgMQgq|urPSOB<ODK zd}-*@rTLrTy;=)pQ4_%n<uUWM3%BCUTZYVm$y2!mD%@O?c~#w<!vz0R#UA)N$^V|; zb^DgAa}2i@Dzo-}xLdIz=!7+@Y41F&b{!YcFPj&ihyvO-c{bR)Jo%8ts*1R0cbEl+ z1Ly-OAFgWyHQfSGT;*VApCmcPpjVCD4uYvMqedO2k0yyY>(wy8z}=Vd?XRq7iCT4* zIRdO9?aSda&^<prNBj2lIl2$%%wkEyCeL?Nu=>k`M_;SwjL&3f+<|Wlo6i+G?|BGL z*4C`fk-d%pN`exzv>U=H8LGi$m9O>Iy6JF@Vn%+Z`S!|8hT21bor^DvvB@>5hOWc$ zz-HI#!^d|sYrBrxAPEL#F~nB}Eo6aLsyXa^DBzP07@^g`Rl%wS1$CrqSZUK?+RXq9 zqm_zW$C$JQt-WHdY|iGI(K4K)3i4g|a&)WJc%!e3o&^d}Rr`yx;aXMlHUs)uJ^}<- zZZkkd1u!}@)&1N+>B?!om3Gp%a5FI79O+REutHwOOqG8wub#SyiON(@pmrj)k}Lw? zmfHXUuKj$Yav1-1b>>yibq#%vWX^iSA@#S6M;Pli_UN$b*4!9OF1Dc5c{xXAIWC_* zilQ0-YWc<h9l&CM36_3_)hFET9t8noWjB$)jcL2xjs7G&-xBsm+9-|UAm)x8ump0K z{H`Yi@XSN`g$qbDGmmxk?pKQ}z(|s%?WWZtU^EM`crn(|*wg@P%n$hScO*$dXOj0D zQ3Qd>UK7o{?68$8$)ZVNBVJtxrtaUYJQvqzX*ivFZM90~9zW-bMXQb8nLQydIBNM_ z85<-hAl|@9R@=leBA|29x`JTb4A+Lnp<&6`G?6TTss~kr0^DAMAQ1I*nXcpx^`wZU z0V8q}oHkE(u-=SlJzOxG@!vo|?#l5SjU6+=FPVLUASPm;qz�o37A-huUBRFbOrC zgist-okhm2ODE$2JSHr#Q;wSk`2kf%M#nhI{>I+|XaCGiFj`aOIaaGh8`VVl35a?} zcJIA(Bqz`}QF2`~O|G4jY{UTpS0?F-zX@q3lGTD<julohwDeeyS@{NOA)rA76}37e z`i}uI>sRKXu33=6m)#spcPh~5)n+AUz0YI|M(4U!U;wXEJ%T+)a_vKH<X*_7$+a+& zjj#e(?i3hU4j-_<B}v^SLx7DDSAalLDv@?D0ti`=H7ij7LD+P#gMBTD#9VH1Fb?1g z)+L84^b@NIhJ4qWl_*-y@FKdvp%&DNn@PYu!YVa2(a0f3kdka$3qtq>H7Qo7+5G_A za>Ifu6+fE`TW?ZwkFMI}{abV}Ez`^@+am`2p%#xY_TC=9sv_0^0GcKg#6AJ0*n5r| z&<UjJg?CgXut+3$1e9Q;k^>$Q1_nO##rifV0%^Ubn-LiyzyqZbYOn5MMXE1PjUnBl z3pvmo0X?~M${nd18jtJksiMqaOVfnZ6-5viUFvbv7Jh!0F!W7I!Gme>+Jiy@?gxS< za!LypO&%M-VM8P(27mjzV32j*F+jX-Qb-FqlI9|AgDNH1-j}6i9NkEi44zCeVDGO* z!JADJ1;nk@4Kj}S3WzZsA=UvD1}Tt+P<pGQ*re^w4~azzF5z`Rgmn33x+sUKY2?_L z={lY$cHJ~ZH9<M|3_m?_(bU1(qA@FgAK$uBoMN$&hdkKbAy&rhr5Z$Iekv53t}uP{ z3_<BfyDO8{38{n{5Y;{kgbA5UMC?1~m&_6c<c7Yd>F1%YF3$2qU$<yz_pd?&yTMO( z9K)=tD5wh?UUExzl|};<dZBa2q+W6Q^ekwst2GVohZ|7c{M^BNIRcUmg!+I51B^=` zvB0;VbllE@5iY8R2LGg&{s~Xh3k*>FOSUt~YfN+D`vre-^~TSRpyHraBHL*Y)08)7 zb=MP>wrw49hATo7n4MBbAj0~t9qC80V@Du4k3-aMJlO0Mc##Yyz(F{qe$q7Br5J4b zjl7)1*g{=e+zWVIO{2}xv+|kAYImO^gV+I5Gm9#~-4Uqn$y4Π<S49qD7iX7?7^ zjZHHA$}NGTv>qg<?+?;D|47}_Z&2vSllhFRYGB|Ak9tFj9sU*>DWN<aAA7&mDKdPE zh^lhbk>fbdoCT<|Q|un#!I5l>39wijx6fEG(K%?9gn2HX)-)V}zPNEpuE?#LpnE!3 zD{@A%A9>@mg;nXK8N8&qKUu>!0v?xFB~!%t5NH?DH+Z)MH@W8*VT~&se#!Xr6-Jnb zCk1{@Bv5YL)82%fcc?OQR-VZbvTl#aK1c21j}HjzgdFj$t)k!V4NW@yPK5J(w@bE~ zBZy~}n>S@b0xA;i^^79Yy$LpFUiI6W2ns-C?oMM>^d1p^<92Mi`At_2rxl)&y>6Hv zQ)(NYE?keeaz7dj%yN=V`j5ok1q1RMTw9*y?}||Rc$HEqHs$cPh+8z7uJEVELC2Mn zqkZP%uM)~)b65w$)i+Umj~bT6zzB>8g|LO9+>XU9U?algeTAS2>_fo-kjg-5+%tZ| zz!Wh_<EzNORM`J`I`=@P{{N33yU%Rqe#!k#E_1)P+1#&lNs{CqCApSMm~A$9b4f@w zcS<#-QmKz?DAg2FsoY5_3Q5Xu-+zAppa0JLocH_ve7>H~M=2B-$6?wP1b9iVPiIr! z5NwrlqM^0XLWcya38_2~9DOlk3m2S=MbFSOukh(}yHPyR`v$-tt%`ll5v=01VRE4v z)9|Bq2?l4eRZ!=vjED^GfumfwiYoT^T7Wqn)rk`v0}>x}3(T?HeCAGGU}M01n4gL0 zB>-sW3jXQvfZAYIx^;3&4}Fy&|D#}xLw#rqv<q2wSGrN{)BJbUgNOFOKs6hd#IqOZ z5kFuFvWqZ6EclBre10DK+899#at9OyRht9=;8>|D=1U*CW&-`VB5?g@daD@vPptXB zSmwtc)D)9^P%WnUbw))mDt-EhLwHVkmgWK&Xl5Y?sHiX_>~q!u*KRjq#d848olfS} z@If0PK&hnfR~3P`{SNqMzX&ietAOEDqAR-v*A1iZO!}Ts#U}e<m)Mx}J0^cA8kx%( zLi5P}pv<92sV#zO4;Nk)bO@`8t;Ze)x}ie%d0rZfUqAZ{`SjF5cry9$1v^A)Ec`4P z4lY6e4&sFafVXV4>XUFxReVQ((Z+PqGWYn892eWYa^y>_BaDys^a*mFK!XU8KeI5C z3YrDo#HT*2LPd>fs@(#GznTlLJMZUBLT`2>132f^vI~!>o|aL=8bSaH8BQU<KP1Cx z3Z>i16*EnxolR)Xc>z$Z;4RVEDFy26bkUl3N~~YX1Uq~O>-ekF!{?sIZnsVm)jOjF zV<$!aOFkqTA$UYZg9Em7JuG>|NVlgOc^^PsAOu5g%@RA~1K1@9#e~U$G;m1?yAnoY z!{P1lhrduwxY!*s3YSYSU=zo?Pp0J}jSpj|gLv;Bwb5OclFSq`MQ(C1GZbu!80Pbu zU^`%v$Rl4JmK6D^Q^JM!0;tM89Dnte-U$}Wy_3@Vo09g6esmg|N<eJa!*3y-M=Aw* zas{Y|M=2ES!wJN|kcEd5zg8mG9BX)5?4h|ZcoybwQ26I~Y)=a&u@Tuo-XD7JQkK5o z5f$tJh(DczDp$b#p`bWiOBxFn80);+bQxN5RQxc6XKtn9j*cJ4Cb40s$ay~~bWj%Z z)I?T|Eq}Fb;v1$f&*-XTrT~<bISS?h1qoX$8;L+CEi(XeIaml2u%k5-q*=`_zi*)X ztGPCgFRfMy9n~FjgM<3XJMh&<9cm0#ymR?Tqc~w2mJ)kVZoC3M3aw_NU*q`g%?ckV zU~}NW1}`+SNAb72;IPC(Ix(rSX4sFh`RIH3keRZaVdQ53FxJ5C25J6VI}$H~+3m)p zlYKIO7`}^YO0WqSNaWA)HtXUD-spy(ScbZ@;pu}|ugQan5Fi`Kd#qK8uz?5S&|N$& zj)LN<V;^z!baRp5u=EezXr8m<w3Hv0+}efX-%>zZ|BmHhDZfltp%Q!+r%{bR_#3JG z*HZ<rN*Kw7VFdWECB|v&;ldwcZ#=AWtC=SL2L}SB+B_Yx1^`g7c3Ghcn{gEl(co9r z^aw`)FF9#*-RL)O&>zSyJPSd~FU93e!<h1oc`fV$v+@^L(1*^S2>?88`Ys3Aw%0At zLctk(8@}pBbq1j-xX{ft{wsjM^iRP6pQasWaZhordIEnZ7kOc=HBtea8+$MkK=i-C z>cPEqrlFbL@$~8QAWwLbLaC(%dWVbjH#EMX;E7)<#eHtK{Z+q=^X|{3KE&~_5^lsb zhVF6&d6+1>yU6u!NHa%ZvpZ@tHdN<5d2LYe52y1F8&$A|95m$r%p|vh16)pub3&^& z367m)RDCzP+6UD#0F9ZZpIN&G>51{!rh`1QL*Aa)Z{Zd35c?cp^x|Af)cx@eg7s|U zDMF&1sbKG#Z>w?i`D*`V&b?JaQdS-2)f$raE~uS=uCWi!>TlHAbHN;RNE(TtO_Bw^ zu#htM9N(~V>bsG>K^+H;G_L==?-{I-@Kdmvi%|9^?kbp7&*vVFMFbws{jqrTqiTrz z8vF>SPT8pxp?LAxQxp)3)YQa2VEIYz$A%bU6J4+glMNbX*v&DM{IExdz{k3R(3>pG zf&%(YxBtT+CUdxE@j?FZMELGnqi;Fw4;F>q;(v3dU@PrECJ4BR<G%x-N?E1q&4Qa8 zIIh87vGMR*yVB$KSOU)6hJg5>apgfi7ApYoPPG?VZm$vc<{MXB#x1#odygs%H_5j& z96bh7FkNJyn`~5DH}W|_@F@)Qh9EFEecTR$`o+m#*lWgKxrgb+qEc@s{Uy7qNTOPB z0wEHbQvUtCiRip?WF-aF5sQ2~j{x-`lm?&$K?6#Q@Y8E%2z`*r8tm9=v%pM(*c9q% zzUKu6|6B{f3xo@xxOAV;3ox7LQCy@<-`z2ee?P<J^mapHjyDinjHr!XAYf1`=yb`> zl{NJ(uHYN)v98!t1;R!(GNN-o4)w+&h5-I^1j?gUr(b2ztK#nK3~aIywp-u)FsCjN z_vD)z)?4Hbh_CC&lkh1VS|PdXzv1=`1-f%yx|uoV&)A_5E^6*<%I%>BNN~zsAI!-G zY)%!bjD6?}3llS$5pY6tGuEjy_LT2f%ICdZk)By^^Jn~Ah|7BbR@VR{=bYUKLxi?s z!K*}2VZH2DKq(pfNE@4yTckAEe(<&+j~2U3NtsX>dgp4`*6p=Jz$E8mE7hYnC`hHR z*r#_rOe>Im(}H8aTiH9sB_XcWvHU(A7^9=F@iT(0bI1#96b<NRu?4FeU?;fH@$uk} zXGdX*=AaqHTZgZpJnxJUC^vxg(dL!_SYk?a`s3lKN(Ia)+kb-NaladRgOj!i@b3Va zY^z@RbaXfxbE#rN&@*GD8(kQy5q}g5vb)6kapPeB8<TVv5R0KuqDtAuEOyUPG9oC} z`RhcCs2SEB*9PD~H;u5gz1X{g(b#e{@Vr}Kh=Baf6?n=<KO_?+TwI!2rGxM7xCFsd z3HOEzF|Ci@oq_@nyODo_(C5^8<(?;gREYk`<C#4i;*VpFYoq_-5cgyI6aMD!KU(es z!4#MbyF^V{v{&tsQ9LZ!rPz}XaoAB15X3&=-H8?Eet_whrg9Gmt!BGJfffW%$L^7J zM4vVhP;@k&qWGT>L+`G6Q~?7UghZj|#8JX~mpp6)I{Hu0b5#4pJgc%LNN^G;SY<Yn z4yRVUdeK5)wbXaW-4Kqlm<76Fbx{7-I7}7cZ~*yeQYw$R<P5~}cC?;{`8~rd^rIm9 z{Bu3wMzqXcPJA1-mrtEKjuWgVqs#IQhRK2(v0YP?2WOHn=kGN@|BX&JBTM&V$KGQZ zRmYcsOZ@Gx8h;7Cnntz<+5N6w)Kk>lTteQ7J*~;35bz-afiYCcL4gvmGaC{>X;aR{ zzQ!3xjtM-JICx+%{5>%8qWh%Wm-Z<fCM`|SNq~QjGoSR{;ZH2GkK(Ul=>f}1sZhr> z2NhR4zp_|Fb^&j$J${vvjjkwtS0<p{aX^Fzd8@{u+qehblPBxK;qXd$Owb2`9*8Sv z0A>R=Q9uq^V9&D8vI)!cImCbF0!!Pc{t(!24$N1v(c{$fwuf9&#!jXm6r77qX*@b{ zXD@O(;yI%J@|5B(c9$SX_rctjTl~v@1=<w+10chT?EbzG_EXW`BcPip{^;@qDgwyr zhTi;A$F@ZrBV$cC9H>5oM1WFoSs=wyr3!&wtYE%E`_pLwt@8purv*kY3-W+>d}qHZ zEuSn0_zV4wAv4KtnBvUbZ=lh1rRa&ez=gcs*n-`Z!!M8);#UQFUd`q4_i%8a(ORdQ z!sWjOqq0$v?5MX5_Bw+x60HXzo*-8Jj*bFYmJB12!ROa_CqH;oN8vvmtd=o)r7-Uz zCp^bOFzU{{56Re8omR>cd_?OSIfhm#7I>)f9;qL_!A35#w;SDG9gZ1}-TUh;C`8`A z@n1E|HS+Oq`5uj%-SCYyMAey-o7k*ZN8#zmAL>avA6<aQjX`XtA)uZ;pjItk0C0LS zR9mX{jEFl70F#^CF;X}Xn*~x>l`=j7l=8J4y6$gUI@LD*r9VR6I%Zt%v5M0Vsiu@^ zxxk+l-b>FejCPNn>^LoN9&c4B2c=+SM>D#}?R`xcO|K*`KA(e2FU3^O>^*S*f0M}W zqVHG#yQe-p&fa(SRFnJ8UGA5rT>pMT(yi6EbA!dQoMeGH#r{aF1Rel{lp2_1S$We} zl>5{M7)8X%C<@FfY`zuo!(#o_y|z#XFW^ZWSiybjR%+KC&T|DCR2AJYzP$dl|E0eX z@Ufrz(@9U{L3-4AVLNz{$b%%`XCVhAFz@khXS#0v{N?d2`NzWZD-Krz|EAts3{bBg zbQb>4uYE<9|7WvH^&kZ)Z!Cb@!>rd8?tSZ=tF;I`QELN8Yx7Z}ZaF;>1MUtZ0O#oY z*uIZfYuzNBi}-@%+B;jB<pDq^Ouao3bi6WP+mm1R&d^(?y!+N+b=f-{{v~-Yqjlyb z=A?e9wd#eiTTVQaNLV|K7xAw!;l3rxr|YI5v8E3cAh_FGW-4f$$h>Bc#aglxL&zQg z+%Etvj*`KPJq=~dniNf*)0fp$ow7I+apkCEZS!8m1W@@?qjasU>GG{^zCq~>_qXA) zbzCp4)`XqhaEY{DC)C4LU`?gsI}g9(eCSxVvG3vIUzg;G?!!x^@s7a*`Z!^}J``~m z%Tq1>azpbiHVB5=Qht;z8+U+XcO|-f)c(rr#W;rYiO$h^#h8$*>SZpAGj<{sj@5Y= zKRF7$=xq1zFcJ@(aB{xBL|B-Y_Zl_0qm@Z+Z5sDIZf6#pEfLYFod&QLU+!#ZdP)rL z4$WeS$p+C^`5poZEXxf?5x{b6IyYOVTEhloHqT;S4)`$)r&Qnj9C<Ot_1f`(l9l1I ziz#L^;WBZ(ME$a`7c;|69F5J0($uG#&U?oaU(7hzr;RxcI&?gM2?OqdzXxkn_SsvW zy7MOD$9adH;4nEqZL9uv%Pz@PMg1O70n4&eQl)JVz|AV+<eck@4^PdI<Wv1$555Sl zUT+a3-tVco?1`%#taFt+A*wbBupKHrU$ie)Gv}e#22!6WF09-=A+uDTF?n_6YHY7( z^JS;5_~KJDOrA+}`(KrcNV);vjxw+YKmeSHoD0Dc^O-maxwsHz12`i<K)L)aMe&m^ z$Z+gY-#YkBrek}oR3upjDxTU>bzC%jxfLdTc`{t|ls%u`Y<aj0yyJ;xg_p6rYPQBo zB*ZLcsp2ZVPwtgX>ADfmB)W>;bNV+;G;!4DcY35E7&lFo&QX;N<%1nQ%mokgc8u=> zTn(Y8S)Mf|`Ie(~0*yIPb^9Kq*I4}_AkyhokbZFlmnPP^ELATfCSsLKlN-`>$=~w4 zk`evX{G}osuV7P@k&Heo*1=RCx?6NRiOVyIl+&8RR00K*WRDENbt@!cmI4eEC5I&A zH%Y`N_n>$PpkIM?OcKrpCY0)gb+<uBt1659uC&vlV`<nif?QP#Y>_;MtPVm*(QqYu z-Cl+1ouI%8Nv5fWvG{4fQ2FL$o`zyp;r^(>exBf<-S%4CyEZTSR6(f0`THYxM)Z|w zT(}gk<ssNsMUc4%kfc{4L@hbP8X%CZ#BvY`U?r671NU_ZuVZx|g-I8)1`W3L^ChE8 z5$7q{F%@w|o>o-3K1tX>@;WPq(zuV_+dmp$STyc75Ty<Bw`TMbuAL`IFR<AMwI++Z zlC!Jip;3;_v#xIJS;=C6qA4lOIQeY}OS63Xai<BUC(v7yKL(ZsxC~3~s%jHX=#rcP zKQK>~yG@~B=>%F}Tc}h=6>JG-R2)jFqX*}f@3#_?9j~%W>J5V6)hsLxp3I8w<v6!; zew6a>%!%FXgg>^mIP^d_L3YoPW+=CA>t7IxjT`Ed>r$v{p9~gEo&+m;Y4lkn7psq@ zA@&Rah1?4o%KLV3P#u6>7(4=&Gm@lY*;szzm=e*QWEdl8l&Jw?v+a8VOd;91F=Jqv zqmAJ@zj;!v!0QvPx!LNwjYS!*YZ~{#!ryt>h)h=`@Wsy|?vFk)1DKY7^OuKlLwrcG zYP<0Xdb)2it~is$%gwb6*gpNuFk8+-F(+xk&<<uR;EOJ>@eVB%?qnipQdYxEoYrif z|E{<3`_3}m7h=Waju450Nqf4!5r4i8>2A>BCkLjRF(;SlNshVpM*c=c>5(D(j85cB z*d$GSu!h{%osj)ry-zM}n<Nc%4&?E4`XH=wWsTn;Z%Do1NEhVcD&<B(-`>M8HB+Zy zvkY5vInQz31w}uKLV;<sumXXth~983Q%ce=ybx(ZQoDtH!Qi7rj3`SzdbfUHnvZ#Q zqh7j~4OctSW7J*{Ce_d~Ogc7SDE_%g$b^cDeVJF78QgqwCg)qy_&R@xEfITSHCuDK zM==H0_j-f{*O(v85A3Ijb`fk<#**_NhP;u9c<9h}(dwjs8B_L~O}4UoH6GYjWX;Tb zoV!y{-nW{C0wT4|_vJU~I%-H6iws!NZJOC2_7T~`2|k|{i(+DxrOPOTmi=q_D<S=N zmcF?$3>6DfvC7isRX#>riUNUt*%}XRQL))BTC3U;4~dKYDk1Cnd&ky7r1}-?%_oD4 z)7D6`nD0!B3D3few{!9)TiJSTeEI4bO2YTn21*S5PL^H>(2=r*s>aSB!nB0|bqGXq znOoToDa8hvd7De2033c^xfBb%RIOOe91E2^2WsIN4?LSDRAqAruEFN@r)Y!-l@kUH zh{*2x&anLeg~5gw)(8udF8p$j^Q128Eu8r!-;+F`4r@WBPf;a*<(T0kJIb%=;51!6 z!!`Sb))NyY9=y?cV#ct^4@{mF>0i!EE{%?Vdg!CZKaJ9~12*|lj&<S=BQ*Ib7Ifun zVQ7x^>gHCT_9eV6Lr~GM>KO6<ZaY=(&9@<g#q}J2g}qVJUV<v&eKW$mGemwO(rG!+ zp!7rlb>H0b+Nt6A?vrfgqkkp$18YYs(wO?<eSXY>zkI)3!>HmvI_>Zqfgkq$q{}R@ zt0gY{&<w8WmG64y{_mM*K>qE%<z@vQS~5G0b0hnw?lTghEVSOflOA=I2RX{dE#I*S z5~xhg{hiADmC$u@>XuxvC7~>u0IR!*czVC>qhZN$04S<to}xemkg7yQ=+R1MeLc*c z3r}Iud@D=BB`;l&lsKD}?KjE9l29M2ZQQc*rALLLTh7N4pdMW4(V^`0HTdTH#~e!0 z(lp$I#hC5IOZ4T%Q#u~@GNQYogQ)wNto?f`aU@gMZnIt8GnEiBH`{Yt256xYC&Bzi zD62KF1t9X|Ds3q8Zgfu01=ii@A;z{}IdhFQeCtXHK`2ZzJ8rry6`SqW0zX;FJdA)Q z1MnzvPrVRQbeQ3~%;bQ9i?MdM5V^8^KtU?1js?r$(&H6i9%j%(TzH1YjRXMR@lfc_ zGpMq@u4Ea%LU4U1ff>MscxW)zl6B2Ho~#+b07qVNLbgA<jR`=y%~W;_9#w++jUvG% zGr4_l+j4@SF4)4T`pOHPcf|^D<rd5ntio5rbm>)XKLxE3r~i^8v+Z)=8I|&O(F|8f zxX@2rvL)v9B%F5JG|wP^Px>%Bg8(O1?#n;Sj5mWf&D_2N)Ta}e#A*0Brzh9^u4O#S zOB%}d#KMl@;5S*<PWC&M@YB(sAH6_=36TQj?F66)Y>8-&Q>wC*boRzVQ(|Gk3b)TK zgWvbD5G18^LTf75B2J^+H5RH?$Fy9ni7UB&Vj7-|$mSuFSR5F@#T_Da)F9gLLs0j3 zk;(eQ=N{f;b(wCGpx)EqU=3aWb2+RwyZG($q<!blH}C_F%vA(D(~lY4QhcQIMv_@& z&De-pe6bUc0WJx3_G`5Q=-QQ+#SIFc05wv=WwtF<QLINPL(J$(274ttg)J%YIVZ=A zkr0V|TgTjs=3t-l0k(Xy7Zi{u*v!;QsGS)!QHrs1Uv_>7Ij-69K&2z08+r(PO<N$} zy<Mnjni;SR@s5P~aT^mjL!F(~O@195L}kY78yTGtcMZnDw<Ei&>}uQW1W)tXU0N)N zc478nAF;q_8Z>k(Ct@-?A_s0=ViI0y0#F=Gz98a;neH4(d#UmiHr%-qcIkdjlBN*R zrY?p8i^MWR5l|I2pEQEcd79I~7CrLA?&@!)#_nn!2#_q99Sn%^m~0pQUfxT_EJi|l zjZoe_umlb>V2Ga4<MFrQ)t!`E0VEz`O4)0TO2BfLg;0H+=6V$Rg-Pfr;*Q%ia*qpS zvrpQ5;8EHpvpxM@lxVo50z>Q-a9mZLjg&zu0n|vPIFsRf!5X(aujkIwb+x=W93k8T zX29BL@FbHp27T}8@uS=E>iu%P-3zMWUYP_q584#K8P>8p*wNE<K?Cj>1l3=L`f=1& zrO1yyo7ZE#F;lImDlD20$ZIb<Q6^fHV@vL)3+EPA=7@S#a$P1(O0dX!@&ph5s6xJq zO@=3QLRb2(U!XYN7ihmif!ub@{|2^q8={A6FyH&TyD8{<ND1nN@CR<wXDsq5n)TIf zOc#ZH#m?iIM<vg+h#fG4>1(`5LC`FM=zq!N%au2~gCOc=ccT<u>@hi#PotDBFIS*? z<N<bmiYW3ep~O!^sTlfja{BI@S!8V%Bb>lg0RTxX$PAZVi(t$p=Q_{84*}U}Lyy0= zl{mXO1)D+qa8BdDk%^J?6oURwjXbzC!|w0c7Y(&pe)umx7zuH|1Uz{o{k-P=Yj)k) zE<;RZ5G{MWspz+w{yGf@RE1W$0n6DA|D!kYJ|B0-ZP&QzGEA#UBA}pE2Y2Mc1IQ9_ zITNip$QU!YH;|od#yF-hL?&b>abPF0565{D84o)bNoN9TwsX0Gskz_2@Q9U=Ly@qg z9L89jY`7WpYoEsG_}ErIq)Act3H>Ey^iqZ-Y|jS^D}L&FQ#DXM4dKUy0Aq}g^)%~c zD&N<p_=cNitjo4I-}FitZ_Rt=FblAZQ|wB&ZK#UB&B-)a97{Vc7a4vX?#G4(3_()K zsx+;ZQBRl6{fv-lco>;}aH!}mgejPo15CUnab&;mK0Jp!8U#A;Itk4n$PyniY>lt! z5(ROo{~c;!T+|l3do?cu2TNOKk_g#fK*h6m!K!g;ZIJBW01zk%vk0OZ1wk&?n*%NT zcrDJ%NocAW;{nce@|x6=;-v_3kC-T&J1z6UY&3>d81u}KO{ybE<vT_(l-|KZIs;O9 zh^<MuCzh7H4UeKQ;yB2hbBH~c`;UbUTpN-xaFD&10#vv!z!@2&L(KMT(S4^QD2w*W zOhK(`D7Owl-Epv+k{?BV!+6)l%pqDJhpzenl0F2*1%WP;!QXA9+_128Nm2h;x_dV? zud^)=fCjLc$Nda{icQFei8`072L#bJ(B<5$i6dvw!OMfrQbAWF;UUY+WHQ8Ih?%Cq z06%^E{wgzO+2QDHBXp-XI0zEx$c#<bm{(w=N<vSYJ=~a-XpTIe$o-HO{wi%cn>Y!- z*?Ge*;<$Yg)JpsHscy(AHq%HU`^k`6eG5D)6zV%kXM=sy$uM7T8B-E=O*`bkfJ`L$ za49bt5(G}+7Vf=JJQk(XLX~Dlu&<|fUl(tE5!u4LEdV8R8-oaozHJx0%?PGXhL$+Y zU<xE~8Xlt1aj`phRTS1`8?@!apV7kbBRd)H2zhJjMic5tlbGA)GiM@J?j=8TS%!qM z=$Q{7o|P-i<(h>yczDi(^1AF~mbXByq;I6U;}qlg@_SE)i)TF2(k+xx2e~HA@b{f6 zZGmfCf;S0S7Q>iwv<JS)@LO@Fhp$Q~Si)Z!=T-RTWtc(T%%Vre1D>BB^3KW5FpEBL z<7j;60DD<F0egb7u9K@Q775UKAh2rD;wIm(cNFvjD#2mPPy;M89atFYMLZXVdU?G* zwpqC6+VY%#ru3X7Gdvm5;oD;yZO6M_Q{O$X+6N8Dfp)cg(p1XD<{m4Gv77B=fGyZS z6EkitJER5PQInma0UJ5G$V2)jk-aKjI4Xuz$G9zCF@w9anOka3BN>Q-vFHp$-g_kT zrSE<lcR1=Q+=s<bvS}KRh;3&J1ClT=1#kvS&{~bNE_)29%s$3t2217!6H3s06c^qi z@<g8?d?`{ebmr}rv$@`h$lz{B)dc-#;l!=}g@pHY8Rw9{P59r`GLPWkDUnd^9A?rQ zGy^xC#)8>?dHgE7C}9%s&Yhb{Hcindir;6XQ=Y^`<bNYg>vS9dB#*~0e%Rx`S|qDk z3Ok-~3n!eJ19iap#l%8Wr>!6DgGX{tT)@I#1!epDL5?`~(~59KLkKT~1uGdL67|JC zF6JcX@%yg`ng13d3q^nXxdUn_O9n&6=9$ejJdiuL=os|%&qJMZc4}orA}~F2YQWis z>CL&M=CFD@Ilg|f5lUnR1B>Fc{Ou7;+9cdwgQ<DyXJ}@wW{PAe2kPPoPL=fXC4jwg z+3L=`F>ffUJ=?XL9?JS30y)MnoOITZXMBYDxy<?=xXh6Zh;+<oxiaD3m`;Jd;Da+B zeEw3CS7XMGRDiYnL(PXE>nuis!sh7T#v=g?o8+L8uM<oaqrKQlrfX!8zo{S&BsOEP zvOXj$fx>4FW!sZu!_-p%@~s<@Fh>HzpK~cCvN@T>G<n7xDukbHFLxm@rj%ua$sE^h zz0|dy-`4y`C+I0bNq)VM6Oqp}dr!o^&CZDYuxcN=D${;!D}=oKNg*z&V7E6#fd=1_ z7qrY<={VrG%uJn(y5GI+y)0p$k6I17cBA#iA+i`oH>LFEur~q|ppbpaEW7pDPqNmW zZ<y$b$v07xCc!yS-%6TiOV#;>+<MKq6DJ31Du>>WKhUHy5{4KqlxH($p?ooyZh(H+ zvzbYg5IbJ#2Dkk!tw@i~uo;5U&$XN$h`%%r36FfYw+SdGQJ{s)4g>j>@HYN}cq@~D zwTGu;vv?F$E}gd`07?495H7x@oVpWpuZ{WD=&YmJuP!<Gy&I9AcsotbcWFDg$MQ^4 zW;l=oC0G7Ebau1dOyQY4eG+Z1bQZ!pgdYQP(*FSL{f<SSth}Cbg}`UgK!1+V&7=9^ zr{wkAzBH7SEw3vNu@upzUnHKr#z!yO-imH@m+imsccS(7VAK@;jLz8~tDk?WbJ;|u zu+E7MjaQepR@+1Gd5ow7e>+dbWk-o>_}>Q*`AH*UE&kOzGWmzTw>iX&ck(U60BKu4 zAT|X|h?_Et?ca)eYWF?V7}!|3|5ODNVzkHnxUvI*12SeOch6i}IdrqeD1!$xl3uuZ z#VB!!zi#dguT`W|N0G<xj*=WHa!M&xZvGbbG|B6D=DAkgDT@s0gq8VIyJkP;pI$J$ zlKx$;KXcBW&u^>P=T1uaoaf1MCqI*v!HtDiJZ<&P1~5hnOPhRW;wAiLHv8Py07KV} zMQDT|JJ6)ErdQA`*BmAqhPAuvp?iPB`yydr`_)UU?;WMjEGlcgg|*t*Ke2(=j)IE} zs|9?H*bFyHdY;-{qdvuV8!sJkyU8B&NibjOR4%sO(eU!#+MVOqt>?8@=*`rKV9cir z&R~F7<swD8Rb#hZO`}`I{Elp_iAZYhwJnFBL$Ep#g~p>SWdXIN7S&O+O;%~H$sZQ7 zJH$q3v5>T6gy@dkSE`J~Jt+qlD_vXr$+l<~2vxVU)G>K+pq>5drTLxDj;~JPLdxn- z|81EoR=>Y}`vo3<^?}y4>kp(~d9Ci&7pd<oi=dR>ta-mQJL{jIW-(MSt7bc{4Hl{z z11QM-)zRMMu(WScC1KT_ULM9D61~w?_k+Bi9oV!DMVqBz#`jxff)w`IYJ39=ST09X z8CL(22gydI--g-hTbzfjY~5Z-cQf{5`g4mVHUucTX|apz7y2n)ul{$pZ&>+`z-u>) zg&MGX=kZbHL)O%BF+Y>BV34QT9?uZ2vJ>aSqU|==hIs~G+7G_OJv&f+(=_tq?=rjN zKN9i+$f-X2@|GOuimmd=pgfBY-B7fVL7Gp8>F>I-Vcc%yyU<hjYBySo^s;G%);D88 z6mztTmFb71H>Zm6w|4rF`d<o4i`6Dx8Mx~95e!FkHgUZuy(62{-2K(v256&|a*=|n zf&rQ5A!je$e)eQM=%SG3XWlF!bs<%x)x*x^jC1%G24v=d+ZL%<sW!RSed<?>@>hps z)e2Aimw(rk^V(%PiVB{MZVTgABE395o;i|fy>(64A#Pn`w9Ml`nb9m#>q>uokz6&7 z=%~Ci)Q7f^;R|xhIdin^xb5Dn3Gcw+IRN)mbE`)%WNlbUH28zZQz#~bH7g2C4(2I2 zN;j2+$_8^8R>azz{Q-)|JTt80S_t~HHA&WaPRMCnC_g^OS@y4nTtcKMCM}UBve(I+ zy4Bn#`va@#qCbfLH;V8I>Xn|?s5D<)?^VUjiE>k1%f2zyqpD8kRXy|8ZKLO(ADxql zycOc91jeKisG^m^PI*JY*fa`JLfFD#KV1QW5D1pvAh4^H5;|Tv&1He#dh)A#3TA8% zna*rGwC23-vop9=;vCEm?A8`}280N+OP-h;RB1+SC@U{f7^Z7Pq1~CAgaDK$_eE_{ zfE87Ym;SZbHO22e5eP4zm}KrHwin@x=tld9aHA#(bjTV_B)-5#YQ&}>reKcp>xit` zA|LYN`MG3sC8Px|j@8iv0T=;r{b<R1mms4hi&je?R(m*^^GfI&ehzrV;fwL*VA;)S zh;`t^opV_wN>FLlQ1Qv)fN7%e7@z3h)W$otl7$jgo%ZWbdjt~+w$#UMZg}aeXD6{> zSvEir2nk}iHYm&Vw8&p!j|$p%_sT<RH54?fHQ&32$ba^8um~Kwc%i@HqMRojznYbo z+Q6^mQZkgFFe`YW?slvDsc|nV!ZwXiC-@%m#2QgPT*@L!E=f9w+4WXtt@TN@vmpDM zX7YkrdwtR``|B@L#S8172g~iUV34#FPnZ_%ka*9Kl6Y;7SBH{l7ug|;ZhFWoz&Qi2 zHDtasDwZ~7)cjDt2=%9==y?;3^@THNv1?Q82Z?KSMTeL_Zx?P_Tx-3N{x!Z@*fhhj z4%e(;Z~C%FFqlUri%E}I0|=U_XMSom48c6jdw3J3{Cc-mk($2~T~6|5cnJ$blLz8G zF+x=N-@+fwE2_&<c9lF|A>e=c%URHfdk)aI4tPcnDw7_1`+*a`$GCV=wQW-CV_r5R zrd_~&s!nDAu-8|J&xd|evS|4`Xz>m89_d|a>LMhp=eUn2B7%VXh$r|ho4f=9xood` z<eJf#V&NefUL$G?uPG-B<Jo8?(nWx$*X$FWU_G;wyBlC!)pW>aTv_DbGl`QoYIRQi zCdzJdAp2&8FvlG2L|$Sq8i!te?>A4qb<vvt`0LucFL%JbH#@Tr7?k+>xYj+dnT9AZ z*7MB4LBb_D{VKp3zdwg6@}V<ZFYMq8evt=Un<)P8lS26(yY=#O93hQ&mAQUhb#Zj% z09`FKB`}97${Ff6DZh#t4e}9rX3RE}e^vU>?CgyVE<}BWPnsG%UahJ0+<Zb&z-xO# zv8`;vxJ^hPt)C>c(~i``(cTR5JKw9)aHz}#mF+U#W;^c=>eSfexwwLbN-Fml*H@*3 zxe*;Q|A6bXz2M^1$*cQXa_H)gwfWHcEgx57qsKo_`6S(%liTBn(sk|@r;N-A2PGS7 z1=@T*#5pX|!e$;=U3q@^Ww}g^k+HeY(PwglM8aRnXZO3$io^X{l@x;uNfz&lz5GH% zS<?<|l~*6Hw6)YJz;pFRJuz;!CQ7_UX^+c?UUC0{C4Vf?)!Y>Y(z$(dkHIIb<-t`M zHPnueVQ*i)5i&J+Pn*8HM&BP0mrwfFC%=Ex^c_lezk=>NxpCXc<K{iZ)BT32E8Efd zt^6ui=Y9o=W4eT_HzLE@^*C<lz4eI49q$5U#Ls|g9WWYGsSujvR`-C|o^NeYCWTbk zV9pN}+ba=Y0EulWOkUsv5?S-VQvTwY_?&fq-%hGXA1f|a`_15)VVGUG>cHoNdL>KO zzkX}kfm<)f@q0`jh%t9M@vi>U80wk`ko?R}dm^rwM(>kvr$C!d=<G{GsFZE2{$c#P zye_+xD|3eeF`j+v(C8UE1g~YJEUO1psJ!*aVGn9)fUMd``eR_d0iU=1y_#GJph3>X z>g8#6p1uHBtLv>5m*guX{3*${iQ~9j3)X~y1)kg5y6!8Co^UbB#`8dRuDzOTMA`xb z5Iw&!KCL7x23Wzr@AmD-fjkupEE;H2NLFOGPu?o{lg{OV%{`i0KL`(qx{ymuqY>JX zy}CovYR`Q<w!Olt-Z2x4o-Djvv4T{ufmJ%GtT3(;Po@RHxqJdPk<MzdrJvVqQGf06 z+Y&+pR5Qpy^K<;Jnjg;u`}9ITfgc2ZOrO9vkc>s2>}T`VH(SNTYqQqbx~6yk6qxVZ z^F{(<L`u+Ze9EOZ=M;;myGonBLpSvcI3GzpKyavdEC0G6Ky6zbZx^ib!ApCiz$okq zJ{G3A4USm*7(eyShCmuf6!AzY^U$wH9d?h*Cg~RRY9PSY5aw#~^dusrTbrid27cGs z{}VTtkv?JGPgS#p##xQ3+^xraowgqH)h9^mNAA(pOX+|AelVv8JB|$;Xd&UkYzz1( zzN$0g?qnw;#iDgO$q}X*CT|{AYUGNr_CuI&gAuuxJ;$aP0%P6Up{Iwqi|b%5l}kr? z0}P`9FU08TL)AXrED!84;YN~JucLd-CCkNz4_1Tg=La=M>Olt_a|i04|CSX21v*-l znXZw{=X*7+!iKSqwkH%l+U9MvX(?6`d(Q<Cb=1$v0=bX!Yx_wW-C#>e8lSLoyd-2i zsmc-isf88xYWN+_o~|JmX5$FHrFgl+CMf-SkQ;2&V&kH_ctrmc7tJ?{uj!q21gld7 zJnKF|Hc4t-y$4jDoWsHFj)JwiL25&LZ~!9pJ*weMwo+IXM0>l!mr4&U0OLDB+A6M| zD>VbxNhTe=N|AkdQE=|Kyq6<(q_B4?iyo7c*CHbfl&ffSRpHKb8{hC3=OGtH`#pzj z@h$!Qbs()N;@g8)f-{zir`fg&@9^c|$s~}nk-s^@b~#+?bqk5{6^ysHHA2w9njaR= zlV)o_d5k^rO@D4R3DrrrJ-RHUUPGn7RgLly!S9A>8BsU0?VW$vtF?0X7ficY)JNRs z;@Q2b-5|3KT87t{iT$EGuFyIh^pik$=NmB4_59dlYaKxiqBa-qIQrE3`doiauqLYa z6LIrngRPCiUOqqx^6;fS@Cv6_tsA6gJ3&j9^CFY+Y>;O18y#x@<*o>|?i!7vLP8J& zd7h}ssu=j7>bbq->Zzvw6(%su8khoUboQF%XxJ7osHJMB*h6M)kmc;5i1U5NYeCAD z&Qog(g=!}f)-JjWEaKNl%JfT`V<0V2+Jd$a-qu5?!d}jwrq%#n?CRBACaM<@b*3a0 z?Q)-g)=cEjvxucGj}$m^82kf7tAQGauu=kntS?H!%aH1Vz)PO0%fVx~NTRP;0a98R z5be_}Aezo!S|>p8yF%4h!}u@t>NtLJ{|z(QrX7f+s*eQ4X<WVk!|@|f;=Kd5=qGB& zf^;T{%#l5*nVL89PY*-4Yz}a!8uL{38shNK)N{A}p0SGf=}+cs$k2v&IevZSwzPO_ zM-R5+?$rONmdY}HF-@vHS5=^P74<c85Vcu+(1K=SK~wD9Y5y8)BSmnC`0X1s?;Q~R z(zWNhTHZBJ@nL@MZEUym9=#uW_m6@1Cld9rybniRS%a4Vf>`dTWj1NPwyk*hZrDL3 zCy>==Wkn1hdf7cILoDsX_tTVdAd4xIxHuFlMxUDT@sJ(Cv-`3pG&M3#d3C7cjdEhf z-ng63y#u;&4Oxb}eP$opW|SP-hWLL^^)<ItL}gW217bFHdH-$Nl}FUaw}s_|fQ(i4 z9BtVFTn<|;3>+!L_7H_cbdiBxL~gZ)G}8HeU4Mr8-08&Svm2zZK~gRO`^iDC&HTK2 zR2(vb`>a>N>RnVN*&9FPpqqz39bbm0-zOt`ZNq2E7p6$#!TbYP9Vg{%jr*(dHkWxY zo95u!FV1R2XYjfbDcGscdaQad^>U7oO2EH;%43>g|Aekd54_8xsa2BJdc%@1pL+ZR zgg)DP6F&XW#gQSNZ3Icp<;DWU8fut}9|7|ovtIiaM`rQY_Rcxk-nRu?kip6j*0-W2 zR+epABLWYQdMAm8FE7yJIaIH&n*BM@pCqOJro1~#|E_-3K0{LG9-@Nwt|nc5{vi%j zuOkM=$GPMjw^fNLVE5wsa}0$!?<Q$x0>Q35H@?mw5t~oV8uCk~`WOhPgLvaWd!JDU zRdobxx!ucN{ce};b|c&Q*CVPLqL0S)#{Oimr(ZP!gt#B}(EW2CzP`Z=(9jER_lfN) zcwy{1SXsbz?eTTR^lM)mSB%>mO#-N~g^na?Pa_uf+=#!IBWs|fFM>|pKSesq2-rE; zD)RNhyKPcRi>UeXl8fE-JV`;}nC!KkCmV7F_$iRH&r2241kvwo>rQXy0P(^utosMr zL+3VvXg#~!*1m!9MVo6BKwMo7^z;+GVUBhfqh(|Jwytv=NA|p}jfhP<_K~%{rg_gV z34c+)SrV_P6`vE<Q$tnbfK@CFiL`#f=lm-3AWKT9ut$w6L0d6vVYTM8mB)g~#s1&( z!=UFRwIJf9Z<o<mBA3_Y!Y+|+mV&K@_^i6*8p{{$Ho+y!Ylf*ZW(6%m@4m*9$<KaJ z&q}-MruC|DgNX8*qSvPJu6+stDkhSKUn}~oBZ<a1RTqK|xkYns6RajclW=-smP}Mr zA;m`P#RKgFA7}^Yy-NM0(Gp1u!xl5vgg2OX3Fy)2o~M_hUsL+5cN1jeU%M<f?-yMU zvN!OuG!*;P+i=PG%V>^nLa)>vTc`iNExm=QM}p0w_lEW-f^;}s8_16jTetMY-#`06 zt4@rLyeg#JBHFV-vks!_?t<;Xu1*@V;p>R?-=t$>(ILtm$tDABlS4WbU$s9liIdc= ziLKA}OEyNH7L>l#o?bHo)10(qj^e)_?ws?ZPm2z!Px@$k{RG}e(XxE(L0qpvkW|9) zZ(*}%g1!&^<j~Y()%$i$yz~avjr&N{zP7GYzYc%<_9HQK!anB!Exr(>?MKV`cKL9^ z&uHf`s47i4nuwpGg(lkOkCEha_)T)8G-LY~hy^xn;Gk<y#SitV07e<6KfSViu{<7Y zK#R)P3oVtj7U$^2m5PWd5!Eqb$I4H2hp&0$y*8s=l64M9UWSGbqVe4wQq=BCswUx+ zsTa&D`bLb@5hU`j9L2X_{naA(#FTtP+~#M~tL699x~P+KOCM6GCod=2>gE~E_o|Fh zl}AXl=D2=ITlYVtb|(<5_ch+97H99LoID(O{5PWwtT}Q>E$#m4a+=#bXr{uPi28;8 z0A6i`=yp=oA*9HKVBK@X@~z8X`0JXq`Ax83T{5*S(Dh*c8T`$#<n=!729PM0@8(ZF zyd+J(4J^x|T5v7+54LHRrU>ZI^~*L}kKKE4@Dn>Y)zA=nVgaP*b4jnEFN8Xhfa!d3 zu-rzx_&;H%$j93%0afh}C8Fq0@L_v2nQQ_A0sgt&=l!m)?mvE~=~DHzzLn1=kOx?O z73yj4w2b$(6Hw1fw?R7RKq8?hn)1+Ub`8|npsV7=1Ld?;yX^hXNwnWDxC7L%HcOeu zqG97C(SC}IHQGd3V>mNDAG`j{*#cq`**nbk+}9OyO!9;n$+*8)m13bj57M8aI!7s4 zrB^6^!kR<+bOcD1D3HN!@c~g&TU@cVL*IVH{SVt-#$QRs-2_BSm#UStRtxR3a{-$T z<{@UC5xDNxy5uNG$d_|O{I~VreFmb$(O*=}5uz1GO5L^h%|g|7EKz%?Pdl1u1$3)h z6)Ju@g!TU}Pyx3LxVJgICvE8nQssd5$3BtDky`wfVjAe&@Y<@d9ITW=eLMc>gNFg; zAJ;h<^uyn^3VEuDZ*o7@5Wt@HoN-&PdHiXIhI8CnzLu^LGNw6y82go^)757QdH2k8 zFzxjIJh)ZQ$kG3vO@C2OTs<QH5g;hDNfzglWiOk1+kHE|N*8!b!zr9hyP0R>vwt$W zA0Gx%=k)2(d-W=136%G6N{|f=E~Mtu8LMcKI6w5^b$|X*3*hgo;IPh;Ir}7eJjn0K z=VK0K>YhzL_e;ZFF6ae6p+^Z)tkYKip)V%BoVB1S@=-*u7R`_|dyPJnsg*?$nV8=t z`QtAG?`O0pU;jDazISZD!_Gf3%QqX1BtWq7!_V?(O9KVs!<T*D-2C()cFW+y&S25e zfd4Z2;Nn((9Jh<czyHl`JPmx1^jV=VT+?XE)BSIS@R`pnng0@Qu59)_!5pni|MS#o z|1ZJ77SAuZlZ%mCnr1$Kr=IGXl`A+7ePPt@@XA&0Ck-a4A9`GqlE7g6-tivHxpI_F z$~|MGwQ6Ad{e{?N`?E#z7J>8BcbANGwRn-so#!Vv-Sx~i0C$qlzm2Fz_FKI@?xsUI z{OUEIcGo|f0M1%NS27g});iM=v#2hV{s@^w7r2dVPB*H(X1aQ7E~mfVsD04#FR#`9 zO2Uqfy7)DL)#Fk=@AeXwje-h1;c|A)?Z;)a5FzcFx203_YBG||8}+HSGTIHr0u8xZ znY+lv^G9yX*ovH?=BkuB9q?RwbR-7ZBw3?0m9K|7QsDi<e0YUpc82_0kODp?d{r&n z?C_F|vhleUnQ8Ld<}1Y$Giqf?FfGTy^t*M<<%aXW;gx?X=89#~%w`6z3_+Cn8?@f^ z{169j*bJ~dGO7l|lOx(~B~!Uw*_Eg0zX!yRWaMU-dGJVf&k-Wg`7gq&PTf@&{Cj`t zir<-Fb(u=Wt>cxV|Gi%8xP727o0Tee`<c8u-IM7J_{tR5WX^g*geMI`i|}sCDcZWi zsDMGagQu(d%lzW@hL2Z<_x^6a5p{aKxoK`U9ow4`Q?gi*932cT_c&K#PYl0=J{)H8 z)o4&YFfh)nr9$JU`h|vW&E_MEej_ih`Wd~26Ox4O?L=6Lvjs<U8hTEhCm;CDtZ6S- zZmx;nl4=&pyrKHcbZ8s7^z=ylI;7-S#^DI5G*Q^+TAN?%5yBbv0#6Cx@vQ4t5b2{# zaXs@Q&drkF-z-UjZ#{7pnO7sE8ZuV08f%F1{?%3)IK_o4gEG%rN@6AtMB1HsY2I8J zKNcKO;-&_NQ`!-Q*FL-miMthBMR!)ON%}W@>q}^K`=Zo??e%DKV%|oKe3HSi#J=GS z{=6mWsKLdGu%Nvvh*-2j*YNi*?dol${v6W6`Aklajw-Lc;kUd8dw7?~w9tDX=N52i zu>GlH+>Z_VJK66tQ4_6$qWT7RM5oa@xJzk{c(W1|aMbpkwzu5Nv30%Zb5zmgYWTra z=H+I^R)zf`!rK38AJ=JkoHPxFThp`ij&P7+Zxd!v;ja|mJqn4vNkWEydxePUSR&3R zBP=FL^1ZpV6Y{^^j9^*SjcqQ9*mVJmZ;HisGF07HL3PKZnV1ajoM(RD1bC^Ab0oG- zylMK0okBcj3w<KuxTi3_Vg^~5tYVpwcLY((8&^H26kJA|k>|T#+E*Ft&)<=6SLajS zr^CPR7h%uN_+6Prufk`$FVk>MN6$;ZdA;BoNqc<FnE~1w)6mX)P+PPl|Iyb_O5D0A zK0Yf?J&I{7n0V3RpC`sAY*ut<P4c~ME7l{4A;dm{3|CqfjG7J+z2Y}`aZB7W%H2?r zqWoUdpri;|RD5nU$4-SNC8=shm#7-bj?<0TO0!b7ohcvlM)Y23ZVi>L_ntfq{3QK2 zN0ro>Uu=z(zyz{D;&YBn3yWr9FWq4grvzm9PL`_c4v09`(PC!_>5QtS?ps8V&j_cm zG|vm}+e)tTLbP0bB6dnXu$q~O3lR;pQr6O#DG<B@D){$TkD^_w;u7<q_}AAc1MFX> z(VmqJe;^QNCF2u07bJzMUcT1i<Hf{tZSp*gqT{t5E+68HlAL9SV$tut9VJSy2PZZc z&O$DWyb(f?r<H8}Q^X$q){9Eze2G$<DdyWJA(S$dFJBof?d|-w*c-R#A9--THTHA9 zcVvh}<gTytDGT=>$w~=D#wD$EDmr18CRxo3G;h69;M|zVX4Zbd$0+6`Zi5rq2UP;U zX7Q(%54L972p;E06}kq^O8d}Wfzd|Sz1v8}?jLFvC&Y|8eBkG4C$+4O-BQYkt=spP zqbR!|Q8oOPDAGR3^sqR4xMJBM*+5wFE<wp3=m&{Cn?#*l|6*EQK7Z_7?ibBu&%K8y z`Ro*Rp7rCB-#h=;<|ys2Z2y-LT((visqwcGVhyV#FB^m<xX?}<pwL}nTReNdB!$Q& zq>!HO?ibIUhDuvD+i%{WKZ;s~YgyTJHjx+Q|8)2NLd=fuV%{D$TIb?dJbMCm!Bo`; z7{?Q(DEAgeoU_-U^$=ga3-6jU_-B~>FD`FE?yh#s)TqUiV3ghNtlSFcWkh)grqQG& zD@yihv;#2@^-;ZWsZyVOKCIZAHUDt!{3VY-edIf#s?iY(SGVXN?^1Y}wRx6%ZF6F0 z%(>T>!q0@@<N5M;o{R63&>ULDXq9Jbhu$kG9d@%kRFFB;x1U!uTr;eQ&e%(wJ3h&k z)@hwD&PWas-C2g4A?s!;*Wg9>vGJ}P5q4s~knBGN_xkon+S;m%^7D3fccMyJwTZ&g zmEn13m*Y`K!$1<ZHzO};p6fg^1+&ImBjH)iDzR&Ga@VEo#7@6Ef_WwYAUB+jAa)nL zRaeE1_`>lk*><L&3nGDA`JPW^a=-UzzLz~c`X4~BOj{$0+-!jj^_YE2s!@`#a?SO2 z%Edh3k>v`x{l>2LT5<OT#Jb2#G0VU4|7z@|N2eVQE&mjJJ>cB~Qdh+<t~b6>t+74d z&fMRLddlugnYDRMFK;Q=lD;}I7Y=_}|L4!mZGjyzU~LeDPraJfMcotm<+tO6I2ih% zoRrfLJ763g&rYla8$6tO6JVx~NiejX-WN3$buL&SzPny{t<%A5^=Clv10j3l#?>pf z782k8)l1jpWLtO{O1{HcimxFBFbVr>Osg(!9nZA9_|K-8|H-VlPw<Z)vrR>*v9pTg zge3U)xq$CxVT;6hi0&=@_u?z4k7qg@WNe%k{}Z@W*Krr(cdjRqsQ9^Qx8=#ph(ptH zgF51sLvT0py`;*5pHG_C;3h4p>m0Cx#Q1dbS3a^K_XVAuEnhw(YQ-l;u9bOJo2va; zens8H<Yi$6OzCNs{8f-_o1%C~7P~xnZIbWf0hEC-L$rxn2qHb$GYkFXr!49>BZr%N z`BAf7;9KWq*Gm&N#YH-^YPtW&Gop#BdIp8gt21KszAz9DSr!VsrOPhzNvLIkJr$+x zi!YTo-Bbym?P!q?T2tIoGy~W|?!nR>J!+TTbeBN}IHHK?P37&-x9^yl8#A*0S&~I7 zc_BQ=U9beEr}NA=WgIm%eg=DB_+vn8Kcng2H@&@}r8RN57)-soJXZM5;MWtgat*5f zJBo7iJtAhoeu=@@pjx^3uiqvI4y@Kox%Y?#&4@vQvB`W=i@as?ELJjnZNmAe!1{PK zM)pj<BtZEwZDZ8UC-kgX-jxLLE<#)g7S(n96Bb%2>iKwY<FqZV_u+0&+KCe3`<|va zAs0yq@oBKce6To=Y$w16U~7dYgoGyIgeT&pE3-sw24#kx==S#H^Y`99qpPtTBFpKK zw+hxW3bp$I$3M6!CeF9(zSP8MGE5GZ0^)mT(O5nL)?88c$MyfC=)V7w`rihQACxIF z+_=HLQXJ(@+#|OQH7#&uW`(12q=6vdMzb7Qfm&%<V$;m};K(#BcbQpVG%YhLDl;?7 zoBI!d2mHW!aISN`pRaF{*?=842`5Kn)(g;lt(KDI4oiJlPoNH137u!&YpA>4rGaa- z2!u@6f9^Xw`_N$wuUW4VF4#)qKWpq7&izCvHCNamt`x_}OR84qd+?62IK{=6@K~c4 zAWb{U?VUGG<K0>R=qgvop075JtTR1s-@L5cYK9Hjpcc9`x~ffpKCZYyMnM|?K+25Z zS!TEPrWIZB_7Rn9%V$z4W?Q9KSp>P6K>3F^Eo)-3hp?KDo=;2!!Jh=|o%SW}$=k+k zKBIM1I|HmKaz%^y0<g~3bytPd<p(b?^vm6aFAmi8HJqr7)%y!ljv=^e^;%~B(61H; z{3EDjwYF7;=&2Y}!UMNtFFHOa5FX>TzhHqykb;BsQ<GHl)L@(*ahvpW^|LqZ_FGIj z5pXk&w$H|G`HTQNSMAf%xAV3rN21lbbc=)p%G`qd9192K3%X%OFM>4Xjkei^Ug|@f zoyxNhT$p<Ce)IV)*D#%iR2|!A^2>mwh7Da*ZSFqr`*Mw<q)1omO%C~f^zR0J;jV)F zCd>HhKRUQdcPfxzt2*u)zY>9!HZ+)3>%8V{TCAZ)sK6c2EeL!$KP%%wu?YTpFbT;! zQj8m;dqQp0az+$Lsqt~{Mnm}ud0pC5gc)poeRqnN=IuD29e#!rR^AobF(61A{K18! zlBcuE$rR-gvbrAB4Xt<NHk3Z*>5_5NzVREZ>xp5V8S$z9<op%w7K(heY|IqhO}G+r z&3H_)ft4ORbMxCu-T{?M6}sD$zE)r~3ook&(zX8)w5NCq8Wg!HKprh~<O?Wztt(w4 z)ZGdG<V)8}VPK~6hsb%>;hjzRX+1XpIFG;M3Tt+MeksxD2eEnn<mGPP*A-hfUsvX= z6V!0@sO}HiZwcTSJUEetEAGOrZBe+X^FwydcdNUaJ=Nk`n^%IBTO$FNM=&p<E055W zBn3L3S*3Llj>gB`t#|e7mOQ`?&m0e=x~VBQ`gsnYgv!5~;RX!MwXR;#SmGm7!*Yx1 znsWqjJsuiJ!o-&-$b+n>7g3J!{Il~)G=YDZn}`2nQfb5SlU*v36kj+<RR<&okU%a3 zZT~Li@07$$g7Wd>@&;Wi!Ch%y*N$Hp2tn=EFF$jfssC6gQ9kod|Koq)jg`clj^<Wq zuLCM@_JM8NwD9=<H&;vP7WMR7tFA8dKhCc<knAaDoUq40+m=l&cTI8G@eP7nBSrD} ztOAyzR^h7k9b^lP+Bj3ff6wg~^lHC%Rj=z(P?L!+c6F;is}93b_Z`En&n3+cI>*Kx zuI{@sebw;OmY4l}EprN0KzOuF(5?iKH$<|EbcIT~L$&$CQj4&KR^v$9L^}|`_1538 z?({Onap+17RJHGPe2be6AWZLMI0d_=A2^XI+Z%VJTVvH#-N2N-&LKP6BD72JfT58U zU!$eRt}Rykt!>7~ZSfc9w4a(ju7v3>yGH87Dc=w(d~r=U%fiPIx1CRP_WgD1d&&_3 zUzJEua3ZL#@J}q)4+Eb*dezfV81{u`ojTX>7xj9Z^1brI#GG4O8jj3q_suFMH}5pN z=^YIwj3~81`@_~L+DnJdO~3yz!q=d6X;DGS%3X?Mb6@1Ag3f>^8ked`hmPatl><Ra zWQq!o8uA4e6?4S>4?$r~$<M0ZL-|OoWs25ug33O6*4>c&XJ5h*2a5slX19Xg;ysP` ztE@5)HlKn$?s{jr$-JAMg>w!0MNwFzsS2MA=dm5n;ew;LWfpg9NBUhmyJYvA)!W}% zbV^=l&-ioluy!B+m=h)K??8!TX}&j7qfRgLI?ML$i6ft05DHmZY7`YxD9KHy)e4m2 zlpwI;Yb_J3dArIC&sG**J{BzBxm`-((vZ?-3`NUI$|&V(x#n<i=q+{Ndu4X4YM7^{ zPoUif{LI0lsXf26_qhh)d^SmQ8dkHBHsjZ2A;5RI=G2+}YuC|NDT%9}wRTH>g!Mt^ z-(7ZKC@6ZGlce0{j1=nlg3yMvIn|EzxCPlCZD>Ocf0p)L`U4hY$3V?!_!RLyRKcfv zjyk5M0^!GG@>G_z42n`$E|s=aa${YCPo`)We$lF+$R+R_@mU#VHQVqp+G~6{oqX+g zpS8bGc!7NNWsvQ%Zl8{Wd&*U7zhSm(#N}Uld5f+psmXRRD-8uL?xChZiFrZClZ|Fn z%br+7{=!A2UO(YPcUYd2>|@Myf6v+cM97#nG_?hx6jjyZ?4yzCdf;iXa{TcZ^!b%! z*c0C$Uk=x;5|sN1n&ROz<1)o&zS=%~%DP+gW3|^-Cc9GUI?Fn_{1PVfYtEi~u+e&L z9!NfY_JT)}YHJea_=m7Fy|Hr?IpVAaE8<m!d$e&q6)x-e8<e|ADD!dED7}6R6?64` zp7q46BFnm>HO*Yys@(}Xon(01`9{cBf@L9H;VeDr%d`W(I%H`U>(sN4R^(e7Y2$bO zE~w2sZj0Q$TebFIH9~cd?B>hkbbpFft~!A<mWCWY=#c*L)qAO0X1=r+69pZt=#Pu+ zW-!#=b+ui-^T{+(5O@1FAG4`bY;icn{Nxag?qEQ@dUltBbcE!{1Y6CDuD#m9`k%4S zgOV%Kq3wus);yMC%UEe%iS~AaLdER;Jx(_z_o#ss!Io)`Rd@V8*T~SvJ?e*3i`*%} z^ew@E_!;j$@if?{LK9l%l)Wg_`VH#cdxx$(NITh8fwdQ$itGRdBr+F&^p(tJ6qtX1 zQf+NoA_>o)l{JJ#?3L%MP2&b#>H@aY6&m@R)i%0P{mHom9E%cs%d}(rB!fdxAk%k_ z2c0Z^J@)K_f&s|3{-<M}!AsHOdmxfAPf35-Df>4i`z5F`)ZxCMODV8R{bU|&Z};1z zW!mVK8^&+MH;=#kOHkchCtLQ^j&{jVISe%@|Fa<LVP>E9_SuNNjxoc#x*FvxeM<44 zUiX&$m|c3=x?=cpQAe2n?%~VSGIrJjsL}L4R}~^(&CE@$_Q=2bGd#)hRX1wH;cw=w zGERN;bn}2a4h(#m*EVR!X+R%r3P_5v_v7lrE?rA|pQnPOtLR+yXJa$Ve{AbJ=^3c& z^NOyLF{33oF>p}xO)4en>ieA<US*2};;CtUygDILCH?lS{67kfJFQ2m*9i1dP(DAa z{+2j(FTX(7j*@cw$hTW2Rurgw<=K)-nQq#LnCm`tj(KW|!wyw;-eD`skhS9P#NS%z z8Vr|G{wlX}CJVaR{6|q|D1B5_cyey|tCk4Sq2cv=_N?<;MdMG=?-lAHN$0ix6I$MR z(RJW>m)1*1=d1MbxZDm3%4?l2nZ&9Z7?OB;U6|pMir6_?q>EGjy_`Q9UkJFnWv|}P zhR9Bm1eB5Ivmf3oY<WQ+3Bwh0w|@qad8^$G+S&~=bNknkJJu*SnO$)i32Oo8wQaf< zz^Ar-te1|Zw8Ed51-Z0+rf3mCNy{2vLvCsB?vjHVZbkoju08i(qwbVhv7%1hr5(PS zm#Je9B1nJ~O-KiWnjCTF6uabAtDNr#o@+QB|0EOH$+2wcE75Sw+JIX%_LuAJh`G&{ z*MD$oa}4!kvvRQRzrv;U2qz;k?>XZS?z66UsqP5h9a8TOQ~YS3`?vAqSYz|_5L4sC zT+1uWIhTEH>yy%c@|v^;?@PXa?j0I6i`^8Smwx@t$m^!h0RP<;MD%}*sek;Z9<AE< zQw@;n`pC-tH^NrCn+JbSk>lupO(JD&1s7e;Zf@|wLSK^uXMcSOuqk%9vozVV_rcw2 z`Gt-%qx%ld9s6|A`CRpu|IOUrs`6i2s`Z!GC%(*ln|Gxfd^ivkZN9HDaPo)$)?3et z_ncToJ~{Y5N;$R6z|-*A{`-L^OaJzqozV@+^LTdpQx&q@^~q-CLA57kHqz&R)dstN zvo1DRCa<0goNYP185p=A?!oM^_FR!Mxp?yX(=8L!Zlu9I>e^GoM;o`~4=S{Uk&Db9 z!DEZn9z#imV<}RDTOxm-4s?)}Z&WzCStpS?KTs9_NAmGK9qzI%MM_4}_Z1DFuybX_ zGhp`3fp-6RseWPk&-T2m_}3d&5cJO{t&vVe>{JX{;#w6uPqmDf8B)&b2BaK)3O5Xy z$J-6KV59_^l8NKX2ItL*wL-)0;=BRN3mM(MdQF`bMRpt9F}TTvlai&zJA#Tq(?^X) zT<3p)%%PT>&t=XzU++s8_Bi*~UDl$uSAK`b@-l>UeE0RRVdD+>`Ugt9`LQyGshKgP z{uOTCqJOx)!{$ifOvK}0$%S*gHfP?a0qt^ar(~se5o`FuCmpgNYrKhl5v0@D@<aK0 z+GIX2&qeBflj~L~D$?Y<DDSCWTX9&B^O-X*FfL0|5WwWt^@-tV{qE2r!vk&eM+Xcp z%EtQ1MPw8i-VlBFBff7Lf3+|BOjv2`PmQtRy(w0M!_j|d!k*t2h{h0GnrQB+Z5-ve zU0t}(ilxrO)cVqlmVz@g(PNc8rRHZip@Dl1P{#sY>fm9j`|h{&=sksi>WYLj2k(|z zwoc?BEb0J3kjv%@Bh7vYJvmIQseV`O@M&mUm_t#Cjx4cb*UHtI+M~~ZdtC&Phx_Wz z=*m`(Cx>qq+xI1}UUk`Tu8_X$_R_{KYYNMdG3yA9F}7TQKMJf;`K<Kn%v(v`C%;zK z{mY@~)A}gKKgnZnvk&(vSwsN%>d#xMhopaH)SiBfu~Ab{oOLJ#iOVdz$*D3x=gct- zut43iC*`;LjZ%YF8-p4K@wxS#l*dL>zc4j%H_~L2$seL@Prq_{YP}%}-r~_E6P*kP zTHC$)CPHM%WOudkr=I4)T?OHbF-q4+p5`82e6ZiAjKYfPdr5HqF%m-|@8F9U6;{=! zc)kJ29dEr#D>Sw@Z&6A7=x!@D;q-hoU%NNMv(4<5{wcvbrM4!tbAP-7X!LQEr|OQH zzFCCnCPd)v@SE*$6@=Uqjs}z{<<eg{PflNI^im+yH2B@-@8#$!6w%m536!D;PQA*# zcF)G((T4Puo?Tr%ed~{oUE(f+-ImwD7H5?dRS4g<jD@p1rhb;CWirh<sjR$UIxCYi zK##MRH|&t>G=K9>yQ>;(OfD}HZnZFaJlo&7KHCjBK4|iw`JAa<-hC&(v|6jk(L$dD z^vEk2`tlENgB8kCpTLUJ8%10abT=>7(nCSC=4-T9Pr2hHYD;Ojr`>c+?<q}v>S-L? z>OHYEoz_r%{@M=b7j2!U>#^)cJjAjNOj}QE#Sf(_hmM3`g61pszF7*H{O2lz)*sm{ zoiJ<m1)aI}#Isjp6WIM;Fxrsz-rvgdreE8}Y%y^`Ve6^dGF7?`Dtm(A{N-a<C;G>& zURj1>x7e4~8|HssvsB|g{)yjlyTUlh$P2VorHYCx=T}xJZn_(Gbxc&{B+e<A*_XVZ z$r@{aDzoRtci6t0s^b-&0h+n?`A5lHTUTVuwLjsET%Y+=CC)!L{DU*n`W*IX&ql0j z9WN>X!1E@}3bZFjJYt8kp7$LqXnlb5*bfA|+z*J;{8e2Nwf~$|N5@lz-r$SHiS7O{ zSMMlh!RXE!X>`|6j9lBA_si}`MG99(;iqVvDz;OkniVNF^qY8qxQ!Fo1&yUmQ7>_* zy!2t<<#5Eu9cFf}){eQ)_czQIAM}xVy>^*(BYlIdyCv<7^6Xt!_9*}6$?zKu@?gzD zdv?T^wj#gen8YKh4Vg{t1%Vn*u7oxY+CNRfNH&-;D?TqJuTac|zf*LQZw(aCOMs4Y z1to`P?-DL~{?VC}KTl>F7I&dv4xD&$&3C{fc&;FAeMe{R?BmB-$nXZdvh#8i+h`<s z=K_A0+8=SRemliZX7E|pFMIF!L;QlRh^4Ko%`ii7=fkwrgVr}f*%l{5&@n5w9-fQv z-nM^YcR_}m(#^%Ri?dwJaUZ=qPUb5<+Z)bB{q13%xI7tq*Q4_oRZ1g~HM+SI0x5kY zd)N3wxtB}&C_5!y`GMnB)$rOC8GnHkFg((m(QviAFkyb8z~1w)>dJ#-$x!u2J}?uV zuI4DCRHcHbUZT!I!5-0++o@xyL%a5rTJ_g!eo18Cc_u=;-eQcfzTEX*bW{kMKh}@F z`GhFAy!G_Lu+ydaC)A=HrO4CoN_Jw8d4xbeU99NQ>J@^GT3pHd^kU9_znb3iRiVi3 z&46TUvDYw{AQMiE4eP<FxRky-<I(u^bb}B7rla(p$(>C7K4PEA5FUAA=AFtHA=_-{ zYz;R%`~8I<-~2+4VMg9=^H~ymo7)j~_WU-z`e)|J%jI%WKxG1N!^hpAcGE3BmGi+a z)c<vzmF0hF*aofpLh#I6L=bP8p>?{6W3f-J!1KM1a+aK0{tTj0^gT~5dDWYkN=F7~ z<h5>Q)LHpjefLi3RtUvOL<=(Xq@BE0bH;By!%(%_9ou!==o`*XU6}J%(n3ORd7Cj~ z#TDnTnEj$!sc~n^vUi@)e8&muylHBBajsb77uL(bE(DVv75nRtDF0^Uc-Vu^BDc47 zU{jJLZMe)ZcAl_$@KUmDIwSqq=9BCmje&|ns=8iTY=Omg0>`3-f-28|J^l6#0cjce zc0cdy{Qq3A9dGMYzPxOms9(hdhU+HE)~VRroHvMamD@EJxO9ByG0RQd22Ca>R^bH^ zJ&Hvw3Y>WJI^Vp)$FRsNq}U#s!qJMOes1KySfypMY}aY*Di_^N-PcOR$h&$!yDK+o zh?1N?pJT&q*T7$~kb)CP5EpnQLSGf>S;0<y_1@njA2)wjVU;9vA=TScCFXCijE^K9 zL_~0CGUpV6juCJYTM(RplCng<1gLd*4PZA_xqRCiA6X?ptczsZ1O{s5M-_IX-|!Hx z$JMuus{SKlbSiX|zZ((lu<{ezS!6Ip3`r!y(s|Gw0_ZiKOaf2lJ{j1~k^K*E=@HKK zS~N0BO=|*3ZDX1D1r~{R>9H$LzhY(jxe`rWnn2qGCzQt+Dg;4aV8-!?PA>Wdfc^;p z?}+HP5~@##oFvg(<P>*M6#f&#?}$A=D=PJXj{AI99)lo1f7iN)N44VN9I=e16e5SH zgNDfp1@bq>RdcQ!s+&b#0H6^7oGxjSjKEoVc&r$59e`D?$w*;=?bYf+!M^k1%ro9{ zzh9zWgLV6QGFQcEpJ;_Q=g3#5FgZN@HLR2yR@y8WqZ3zzd4Xx;Ay#PUUH}jQ=(oa( zmjHSKYaryPP5&^j{3dgmWUuJP0;&)rfZ?XRk@UB%oH0xZ5pe~JtQRArzRC1Zk%Iub z4U1?_MgBK}yf2XLBcmS+H_s?b$+AWuenRjr5tJf^X41;?$Z*yOyov<%<$+tN1)v(B zRfrY}a-jB^qRYFD!ov&_Fy^<-e3UCb9amWt+Ef4t#w{7FuzV}vAmwHr0yavQi*l?) zaz3I&c&yn##V85gJp$iHw`P^QxQ=3MeeJzdP*^znB{$@NPc@EWmk>e_5oNs(B8q}h zU3a!9%Hw|#F%?|&dpzm_8J<r<@W_b&07MN@#!nK_5rPj%4wYeHDI?HmE+n4}2k>wy z3fM{vO;zQlXCi+E%VsrK!C!?oi7>VI)C_iSEy1#s5~@GUWyVm^QzIC0uyi~YLdD8_ zp4$vpEWrH|qN=$_0H8zo6|I@**8*gOb-A`&ek&l;Fv9zQMLnph5Mk*8A$${St4=@- z!B8c5ncL#bPb5Q-j*)Sa--rlNDnTl#vaNX3J1p`H4=yoFEAa>krkccq{;ZaScghZq zKq%t#EFpMXuq14Q1XC}74g%%83(Kzx;2(|nuAEl6tw;){7C;U3+ka>~D&Rst(lq`{ ztXL3W`tdNa04***Vkt2}=n}sW{mU1-#g`@F=GO&g+HiT5W0>CH=&p41TRaO8R+!w! zJP=qI*2-nMO87^3i-aI0k$(y>A0{!CtLBU`#ab@nJRZ|2*mOR=6;Tz8d@YiRBqN)| z5E>Uw<3S@xaDY^nqzb2Cp#T|TMTV3RA@5bW@>uZGb*<Q?OK(}GU!>B%+h2SuMfiwC zj!mBW(T(X8!u}&;#8!T1Ph<FG#49o8F_kBtxbhzZQB6hvB%|H}^?)Fosm78-`10hG zeL#kv@bm_v?AH4=%=Ma4BKnO8A;kGTaXlvYSg}_SCE&^Sg3!O0P*``F6{<Ny2jy}F zp>_=|;-Pmykc~9tD1fTrAv=ZV3&b!$QvMObqePGrd<$LJC`FMD7=fR{LR+zb3>gf< zgFe6Wc@&&C*-`bnQQqtfk@dZ5&#Yws<EPSOc(o57ZNF8fuOQCd^5iCf;S*)HS|&lP zESB)}Mttz7sHVaJ%k01)D$xFOcdjuN?b7yLp=tEun~%M&S@&aY&=A7{GbN<*yqoOH zZsdLsG;0UzQlU(s6#8-~@_sPpBNZ)yY-g~@N)kfSw!FbZbn}oDE{r?^p#$(!qz7~W zO2%XJuy84Yv?r}BGx&lGxe9>=PKyy7Az^XtM5tq$$*8yC?asIkqmP0+{i%G~F@Fil z+ax-zObF@~Vt$Osd=(*oi8L;4JN=%n%^;%wii*w+)L^exycA%HQY>@SRTypP6)u8D zG=GUNRt2HE`!`Sjz^Bu0VNQU6@*Ogr)DkmetlX`d>-RBrq>e@&a!g<A&pp`-yoME$ z%pE*JAjF);m*orLLDSc4_rgoCQ0Hq8@`#uAkHGUJ5+4=$hz!3dxV=S;X$52-lMf6b zPkng>ZzC3-yJxgdzTE15ys~mNqQ^b^s>|0@^rK+e%?N~;l-IbV#u>#-1Cm%6`jL^4 zpoRiOE=h%apAgF$9%2IM$TJa|AgI+sR8N}*_w~)L#_VpK5KKWy@|IjGVu*C`1xfaW zKv8BKIRaQ#;h{f?vf05fJ0v_m7`{&gEuh`1T^`s607E9y`?1hdBk)6F$S*9yR=f#m z4F;e*lRLPF9?6Mko`kNBz*o4vV?_%7PLE#>Ug7Xnnt*EzvC<to+w>HT#cIrTGGd)v zzqVJN!^i1I^qC%%`&-yv^`N8jpua@nxBzqMpRK@T$^GfbF4nj?tdH#-c_Q?=2ce)= zc+WP7=qo~*ljB7%L`56iq!uA+CHN|rhwLE9Bw?Y&+yS;2Mias#u&@V6xKuejLehxE zONWiXj|4+X#Lz<`Xhbk%zZj#71p>sFN8~}6s=DRnZI|YC-hRiwAjf4#TFqsli^&#^ z;%$a9*}r4kr1S6cMKak0{35b)FiQC^2~{h=tUZ;Jb}IfLlC8mRq63Sad!AqfL^`^o zMvGtZmWswOv^aB<-K4AEkpF!%Egs=%T%aL3Bq>U&Ot7!)Jb-#)DEkgTjSyudmZ{@) z@F^i22p*LVfgi&^y={uk7mbq0U=|jB3V^c2utP#{wit4OiYzBX2)9k{%#7VjPTQoS zXk7H&1<A!3EilX?J;wYLo4ORss2rd;9!nYsk?j&<R)~-8TPkm#4~tYblK9BK#BSf6 zCSxDgC>Fl93kc!&YWy8R`TSOpnsbf$Tyf4=HfRFV$wj;%X#FIjrT7)-+P>dcan&N3 znPAM1V9X63ibRm*0>DoI^@50LkQl0x46SGra&HixNxdZv8YPRM4|Y7r2LK1I^eM7r ziUBz)Y>dF>mNH|S!cJWZNNei~T_MA)-b`nE;=Y|N+`HKKVK;^$jXUXv6`=Ay$n`Fe zk$mCf$M|>^ev=PG@t4T7ySgvNS(sGZ#AmYRuF|SSvKwTSR@^;p%NJE9?R7N7dN3M| z>{li<@ANQEibhcaF%QU^bwZgRMD!rJSmLIx2vGR|l=}u!OnOl8cPc{!S>a6OaUoXX z(UmFqE&*&dv*k1yt!riSNEE4+%e^$}J;Fo$BpX(CsfD-`rY7Ghaki;Ifi?iq^%IkI zQ`0I?+vm~8#cC8^1Xtl~zUH&#JVGj~C4V#2{!<?nR2C!N{aot)WgY;M;Za+^sxMS7 z)!@1+-jPuU9Z-oh#1KAM3Pi_--}~^a=7td70TfRHz?)#y3K4TX68Q)F{*T1I7ob+S z$OsW6UjU;4&~)mQayi_);{l!9vJVSYaDIAZr2CW@dQ^m14wgN-J5TfZ;)`1OOI@KK zg@`V($@@mNkhH7agg0j*cF-CSxyKBDa-j-d&(4`Br|coz;=#q2hxUH%YsVx0`&^+B za<A$f-PwZ;U&C}#5j7uqAEU9XY&mS_sU9)Bl&sJztTDA;HmiC01M33pL%k8Lyxxbp zErbqG(SyO8FKfv%>m*Dk?Q1?3mLa+p%^Ohef@gCfk~ZK`va~-LUS|f+<HA$0P&^76 z%T>4Vx(@r_;dF=`Lt60ln@#>K*HsD?&7U};{@nvqF5!}Uy0<rqWLASe5xR!F*yg`^ z@Jk~n?&R{LaL5{xdCwy`xx!^7Sx1H6<PGfqKO|cu4lio*9m?e7{E|{UkavQ&Pn-Ss zXbN+MhXCH90POpBH&8Vr$p5&=A0ycnG~`<?qzoFq{~|1f3g0Jy<p+-zpx_0cMfO<m zA(1FaG>|8NIsbtMcgVw=e?bwh*f!@Hd_+r$nmh(|pLC@=>X}r6HsSJmBY^GN*rfEl zD677FZ0sqBJT)@w&H?%Z^w{Y0Hpdn{3d(;4som!&Yes^NzbFD(k{z?S%xCBB9TMFw z3B7kzX9utd_<VZOs$g{NXZ==<d*5fbR=w59D(Wk%H3<E4JU;XQN@M5{x;5h6i4r;E ztRL+u(j$jeZ|5|41vK14?sAT9IR5Nhl`&F_lrgthA`J(sJ!l(J*qPt}1@$9Re>0_d zA$Zr6P8+G6kH`Nz25kK9dG+eYff2rEnL+gQ%E$55ov-))`nvx{`236f!Q{v{hiC5n z`5E>S6WNmc(<ijEpyNkx+J}*V<tLvN%})J&+Kl{F7Iq`QsQ}}BB5>Lzvk3RIGGWs) zGnL)@XUmV<n5Y+{q8pLYq^G+i_ko7!s=LqaThi-QO>}-cgqf&OR|`Dlqa|DJ)p7mw zG6EH7m#NDo(>+wOc+Hn<kMz|as0ktQ6SR_IK>13(z4hLw&Atm`y#O&8j@>$8#}u%E zS3L;T7N7YtHvrLqb=CRN%_X+9L#!u@PpA5sT)X|<Z+!RO63w(J*Ld%20e$iAa6cG- z?{(rW=z}y;OutUKKoJp`n&Gamko6B?_$+&$>=Ogq=BU!T)c#ra#R$cL1#N2os{<Fy zMf1ig0jsLskE*y!{$bTSZyG50NFVO+OcRv%UEHHLz|xK>%(Acv0CD<iH`9cwmlU#q z@PxXsP(K;tqb4379*5ip@zhc}jFGgQmGWMttfrKN3&|Q?@fQxa&*~L-z7;bFst<oM zin_E+dP|h66X(lZ0N-AuZAE2rg;}@w!$qUEi4*&C|NOMonVgcV9z3-%JAeAr`m59a z){cXp{og3wJ)kODDzFJOoz*M2m>V;orwl0em1uv;_~<<`PJG_%__gq(;W<w~ilLp4 zw|?`*DE#RAI?x%JfJeVp`8&_gX{p`T$UUACUz4+Fx^!u+lW<v^vd!s3PtqbGzXbv6 zPr694>bi8{$W;pbQ&!;pM%Apk(F8333i8yZ>;p@4omTs^k2-x{l`h^qnmwcoQ(rP- zMxVIV)F21UR2LWc{G%BD@097ijnpBR@iFb}so(4>|Hd}9gN<vf-975YK)%98s?LqX z&quP(zhn4Bu&igEFB_@_tPM0jeQ6pKQJcOLk*`~(;a940?5=BUbq>c8m3U}mR8Qr9 zdvZBCxmKWEwYy6STf4y_eEpiVc2N1bEaI#8b%=+vzEyWXqRZ;>*JhzxcAL|)&mA=G zk$;GVSS^imY=9UGs|q>yRWXS~0}(L@rW`Fe-%;_Sq~pt+1Bd7eiL<_&0L|Izgqz}J z@%~8psY5n$MaR|{=}R~iYP8Ye#T{QilcMoDlNfAhos`<YaM<Ryk)4`Bytz1|TVuIq zH!<W5U9Cb|?_wjN-1~fkcGU>PWid=`>AX9xb`i!ahF;0#<|%%}v4{N>6b|_?v>V#N z&Wqm&8*RfmAH-fE5^y}Lu71y4Y`>MzwZxTFq&7hs*ja5^7AT6r><cDq;bIz`C;BnD z!X0W8T#h=3hYjP>)#i9mcBkpSJh;2=O%ZfRw1aHY7{BFkP3>fL&(_vN5Azq69jttV zn5A%U+n6rQ!Xne=G5yUsXna#HO<K81yg<UG_U2}|Y5eI&pRJbgX#;KA*P1-GI)#>} zNlx;2Ha$Jq^zvbXn4vM49i2H*@bCyW)y9)wMnrFdigK#2n`I{d@A-|kinMTsQVT!} zSBp^=Q1aYg12pS>=>;ckVzsKLq;UVRY_(U51Wa#_^erNeq$nk8)$gXWDue{f8(=9y zcf9Ouz6X)65Ii@tC1*X1=N4zZim(5$Ix7=|jkQKL@IPir(~dRvXf=uatX&zF@k`9W z5e+XhJjm+MzSFig{?TSWA$?B|4(U9mzOqyVmE~45aGT-_Q9lpjFUBvaxs5X&Zg3_S zmZ8escHSX<a@U4?pQ=ZxLXD_xW${Gtsmzmdw&=ai0MQMnd@k92iH`K2IE))66&M?p zV{(#pRVA$y?|6>}?!F2OCSIlNEm?Zg06vGMC4Pj0u<)%LvkWrTU1>dpSP$KGfAEq% z687Fc4c{$^7McTN<)v1$3ETeJ^;&TZjO_HUXgI6(8GF$mo~lC!Onmb;V0D$5{@Zb# z`W@mpKPuxr|4zGg#KXC8?9M1rU+qu(1*fi${;%M=a^1lOz()3-vjEC?1Mg|j5mFXU zYf6qEh%~e7!X(<v%fH5X$DKK5cDW=EvreA3Zu(XqFyyYfF7i~rNrH2|^iHFP+%@1S zp)5TeI4N-t;oosP7O<!NR4_y3g}BT-g>^sd@^^%zt$iAHt9pkRY~hF7b){lbtEN5Q zsU~CBo#&@x<L4o|QLe?uW;WgZA00C3rN&|dPyR}sc~$Kqk}KR%?WWnAQAPtRsy)nd zFOC~3d&X@pjq-_6i_XN@)zia=dp&mlAs)R6E_4}4IBYV{VcDQv3*!+h;fX2vn{l1R zqc5bC*ZcdnWsK%)H1p|gIX<xo9&n<f6ks3VkKc&V)5E+*9!+Gb>#Y^$r95Zux_tc3 zuS=IElMN1+*g=TfPS;Qcan-k7A*)^rorTK>Y$Yvuv*U887iP<~_ubDszwqsWW-Gk8 z85U@Ha<nY7QAcsI9cH;`&AT{YsCIvhX|*o5e;#~Xt5^heX!#}r_Abt)F(LLV>^m6L zZMApRGVXzg+xja!b2i`fE151@%2s3C58dFM+m<n#55DYr)bZ`s_GFs||Em<t*9yAI z^s!}KLLgRLU)(|L!M+UNyA;+cfA{6AeRlAYVyhi2<PV5OWj-K$dgyKL)aG$*+U!~P z>j3A}6q!Jgj{0QHv+Bk3>bbO*gnwf=_apLew|VMli<`hsPeH|uBCqW}uV5Da8ILz; zOpVhHkVfdr?TZjowZ$o@9ytVali8nZ_+IdW6;kHEI2UemZ~u$4-{4j1ht!98Frx(L zcjpu?qfhYM%e3J%O~xQ0r(C2JCj`f;xJ?0YcYk}hg=;$>c||xB+?<=UT=ib-7m@PI z@mE>4S&ve+XtUR}ezbP6c=CB?SB>G#UjbB^qrvtO*7icm@lfI1!w$VL7lGr~%%bXv z+5B6t9R~+&3)f0RB=0X_+Y%u=7CC#33U~Bes{&v*@cB`AwciYjs|4`seHj;dRHKl@ z&t%2|4`V@h=<@bi{me)j80Ls%19CY45S4MizZRB514oX)W`5)mrx+DdfcaXJUBBg7 zpKf<94-e1NLFfa5Miy1yHjzoBN~H>`4i0X&*l-(z<6f@8vV5RH)!<MOglq&$BXf>T zmAp1$XOA$k=dMJy{pTg8oLgO*+s@{#q0A34PxeCr(WAD#tz&Kc+;CWKI6EwZb$Zhn zHD_mAh$}4+vA<tsUmvM=k<LGj&_?!>06U1t=kh$fB?>1&4cSumHj*4zr<6p1gC&u{ zEA~j`bk0B|G<T7)(V;e=Q&c&~JP6Pd!dVC9pxc`AGpnHo+V4MTW9T&M0Y2TsLODE; zXO~!|<*Q$t1UB%I9;m6y2Hew}o(xyleT`L&>u38`gLjhh_e{Ygie>#eY$pz;s$()a z^(cFdy}&KI;n(9;%{)nFz2Oi93XY@wC9Q|R)~|21OkX`lZS7WLlM~OJOw8YnW#tNF z>M{`Jl^B0wp?5j_0v5U}S?vr_rhLe>ycm9?9}-&4mLF`u4*1^OG(zrcf%pk@0eD;V zZCvOS^dJbJVA%&Vn2|j7y+86EWb*!ZOL|9A@$j0o0T(1RDrWf@>zOj0)}-9+z<3VC z=$%`-|BgH9@KbgAtf}IJbZ7vH>6-!BX$RQ{<a>)C6dL3Y6(UT}FLQ;s1I&XX?AQ@D zQx3NT0J&rzire{@cKP}aggevhEo1qq0%#+Soz)IG$b)6rNlU20{WRA9Q=kGFvg*J? z2gq^_$NN6K?qGS&n$lW^@0*zbDvf1-wZSp;4rh&fn-AV=#O_bxB#~>wh2TG`tiw~R zOc6v8Op_$|4s!4$ZeN8I*rG|=q_;rtB*SSF&QKOfxr(0N7-IAg<X!snyhh4DE8w0+ z?D*6BXk8I^YU7D{96Y;S!pg#O)*vAxupBNs!)GLeG?Kw%=Zc<WA9NS!qFDC5HW9EO z&NFL;l1Jkgo==(h4}tlD+ld(k_3aQ?CBtFe`=tm5&h#wrWTgR`*@-qqTvm29Yx|VJ zHJT@jqtpnDHFD2<nU&6(BGwt5L#BcKoATpuF#4S23wVZ!7%VB;0URq~Svrd3r^fID z1kyUa(vEgavtULiZ3`z6Z`<ETBr~1F*Sk5q$Jk51>cHlS%*Q*Q{8=9V)4R>GvhI`^ z94m$m%S|Xhm7QoS8I!x#wmApm*a&aeo?Z~KbL^PiSGgWY<;aih&|qc&6&&K6pGB?h znJ)bD&1b+=(MOkYQmnJXx+QF~5FZbJI49$v#?Hh(XFt`QY-GE(Gjo9a<bI`Fv(U>R zz;^_8gcev*|2$S4y3cO>vtDzBRao>bzq3=)E^7?JHHl@(<YWvJRPPefrPZrp?$?7{ z4)3{BTrnBW#%1Lv0k(h<tp9ceyUlvF5b`wnG-{!0b_yo3597sZ9Bx@XoFyr>=NK_? zl1B_YsofM#mcS-AgMW-#{}%_Q_()*MTDg_tUwBsWV=z@%`zIpekLtslIG8UvUxMlR z6JPwHz?C;s;CE}F+k+qW%tOpMUd=7#&H&TAo#B+hP;Kku-t;2%`#E#*!I9fp#G7wJ zw~>4pW>nO1Bf^Ql(-tj38M{g>S0Foqd+ANLPPuAIxH!>TL)>?jLXL~ODhqRqC9gzu zAAGHF2WHO!5jY?#aS20>{cI2_mtW~dK}*C;i|)N_aY)3g*E@E|+yEf{!LIvq;Mf|N z57l1sDMN(<to6CDYV{*jmS=6CVx=W81tp5}(rV<?2;=U;tvh0-Sv<L~am^<{(kWZ3 ze#J3SwZ?8#si1cDwR0M+ki8#%x{)S>K5;B^Ts?k{mH0Nn7S?nN^bqM&Z2zgD=bM09 z#0t!gM#FJHX5v!ux1nuQtkb{uy$`>VgDaHN=#rwtFX2Z|M<f2K24anoDNXs2O-&sV zdX(%8Q15$YMIRXni2~f*m|(vOFPK``k<U_BcXqQl(yAb)g#cto+(rzR_A;uvdZ)Yx z!E~Ypd5PHB)WHwuX9aKMkFPz6;@zOqdc2%bpEM0-L}1@Lb+7383HZ?qDZ02E#OXU= z3A|#;mG+E~Tz6SnB4&n8rE3Ix2M$s+_`m*LF?%1&<f^?Gdb4ZHQJLG*P%@War49x9 znTPw&Nc7zB#ZWWPr<sXRZ_e&`yoVPz+VYL%^kZq4V1~I}l}1<?Y*WpuuUe1dK0Bmy zgMeVVi=+bZV56FC$1hQWZdh%3^~ijd?U7-Ud%oi5&5_TAPo6rF9A*(Cv#QK&&YP%~ zcNKe%Ro6!>!j4lRK6w6u5iGoqx!6oP%Z=K5$L0npf5`dl^I+u^9?ZYGC?SId)5;fw zL)$r!_RKd4SXctr2nc2+06+l8t2~vX`c2wVoade)eJS8W(u|j(k8B3Ij+0TfJ5`0q zkq%9S-rk6#L$Ce=<Gxz+&A&0@iEP2Gx)~w#RQurW3lp=!hKnEp{F=?75kW*}s~-mz zWTa@<g{9c#-w@i!fYjLi`+o~q5`x=Lwdh$+)AML#@}}j}Oltn{c*33$h;sIu!z1j2 zSm{XIhvcTB2Px8=rZ?_TX*YZjXAv3tJ#Xgm0gexo*u?PYXLyOE`~k4hyK%bKrzGUU zDVx37{V#I|P+k*Eu<wJM(Q1cTraxdAmka-1qO`->HJ8S=YG<A@VwDjqw>@~)!tt#* z>?^yI?bX!4-4S~0l~EFODHE5UEYkL=hP~<u%^^werm4r1mOeMW;RvJ~Ji}PzX+5*y zcc#qAFMeqtzyc0tWiV{|nZEE(fd+@(8YEt`u1;$zxwDJ?sqkuUBGa3G$i9t}iv8&C zV^jq+kRzsIxG+f+aCZ|l+X$2HBi$|Y>dfZugHoBE5%aJ;RA$!HF4XvA)HP@#4;C)U z&kTMud0r-KO2U~ke;;p~gwUi6dNUK5=3?n)Gcoe+8#5oC9&-!k$heLj^C4cA$bm0d zN4jEfnAqjJa9AlbpWpryN2Z!*XP|<(eDc)__CQI&Z=!YmVnHyw?EW(uLP?b(w>SrK zoCM1VW@d;g!pOvH)eBWl2_S{q+K0LWe(wgP%1QF9Oj<0!J^S>1ehxW*=)yy@OU^rE zIU{{w0|4v>-!4)g-!U!iwif6j-ug(0)b%NbW-(mEc|%rJZUV;t<jv1JFdv&ekvB=i zZl)>45TfV6c7I&VQhYWa+&Hy~)!Y8RDp5H{eHSbq7hPnGded08gWHw0hRzHIJ6v^2 z6bdb*N|3h;<L&Y@+Z$|h;rf?gJ~ZV6WR7P&^l&>fO9a_0KkJ#wIzWa@>Uu~JOmi`V zsFL=oL(hfBFvorF9B6#h|MbB?+oQE2QGh<NNxI*MVY4W`XDW`gdHiDPjZ^KAKrx&3 zw(6%J?34&1f=?B{GTCy|$Fi^BMRI_w2P_K1?t;Q94(6MZ1&M$sPCr$q4Vp@W23EsT zsz2(%Xo;7>RfF%0ssf|PkWel-3%;a&(sGZHDCI3H8XhKfpulZgoX0A1vJ`)Ioss@U z{mSKOmJd_D^wIWB8rVS;-v&K#K8WyP-Fqhuif~R>kF*FFAw1gam`ioqU6ayTzbkM7 z7SHp?=0HOF+1BBZuIGl8M>sD|7CgJA<`}aUe5+yj&C$Zh#^h$mZV}@o586<vd;|xH zo`S~Pg#$j)wo?p<g>kI*kNTfd4*f`I5>=fj_42)XH+johZuD*`h#v{^X7$JUiyMdD z#U=moPF(}1wZ7$_==Y}y45n@0k21$!XCWu-(s{n=+$#&Sh|nh74m-w4G8<7hd1<j> zup4Z<FXFt$!!sob-o*SYqYo?|>i~QyaFLnJHv+i#zqvnUJlyIaYMhFh|DW_DYwu~j znSV~Wn_8Qn&T0H$IAAZO9B#I#2JfAcIs`vt{3-3}sm<KBlaq-hd&HOS9QVO#!xr8W z>{2voc<&n$vvlJI$ft=q>vr_5yu%9gxtar|77$D0gGC+wof8qdedv8n{(tl2)NM-% z9tESEZ;pzG_TNc*(~;7Hz#G~ElV?8<rWahed0>JSvcn<yt&!jQ1$$}1byZ3A`8}xm zE_OuA3Gpoh0<0bicRALHecFJ<;0>&1<_DzvO)uEyD@w&w`;^pr9gGS2`1rY&<8d>L zZeUA><-5L8ZTC{MOsj>bXEk5ng5j+xz$TEf^zy4!%(2Ts*FIG>Um%TfM)_f!K#~1q z&k|kYKa9TKdgzagRInlS?(N+BHlH87e^%9+vi|l?-d%L$ZKjFJz6Z)B|1+nov`=~z z-<ocZZd^PpP5S)m*5TK6DT6N!Uw0<FZbF>1{T%uz8K?wN_YhLje@;?jXJ^@J`!woz zYo!1c`LYqR)!uuK&8EO{$7UX5b;<4DAiAAA%QBbu$?t0mO>a)s7g==sL?$3pRx$Rc zr%sm^HZ?2E9Q?~v*x{_!20j-rAQUu`mNZUa0gNTIv@$fyz1;c=*=8pBuTcZS;hl#< ziQgk2Y}kT76cdzYx<&8O(Gsp(nC-0P&hfgRy>2qQW%aj~ZBHI?3)%_T^gOfSB{!h> zh)w#ew?@ho<%w3d5sR(Kj^p=59Th0CQ2rZoFd%w?{)B-z)?cBL$#f0Uty%toar`&+ zWB7pOT<x_R558ahRD3Sw{jkF(RkAZW+tQ<xG|PO4F}bobUh6eaOqh@LHE;GcA0U89 z$5F15_5X*T)1q7!xUqW48+AHE+h2q?RCIPV=?0nZxuj5R`z~D9;J+D^+wcXmH|YvC zBB2#$`$yx-iLBq^HqQ3vPSP|YAeQpmRw%^_(%A>hu{62U{Hew=ucnX9nKRg4t)oux zvwKqJXW1%jrS3hr3mWd8=9|^l)d>&fqi>IT>pqh|uw%0UVYAANRV{N_Z3wj6+~m#q z-Yh@taXmKrSFD`N-`)47j-Wjm&xzsnX=va>-S}PS;nL5oo$qK00nUH9inVU?5j{cX zH6uUX1Z*W78J}I5&-2>8q`z=s{)gF3gweWen5FHIfM2xz>AY>BLS~7-Rcyv`h_^}< z2>V1ka7x6|&UP|M`vlNtJ$1~K<XLJIF@v>bdB!???1}Eh&hJ*{(bsJHygpA)48`O; zbr|zF+ZZbtO*r?u(7rPGxOqea+OQ7p{e1hM<lZvkmAcrH%6IHmdB6F^oBbwZD~l-0 zd3Y@L2ag>9jG%fam|E4<eNJ_*sGml?s{Z_Z<Kz4?W-vpmjGUkApp3Lw-t5AZf(9Gi znxMow8EgO-BonaUR#UK)VE4lf7c(lmWy5WE-(D?D_M-d3-=u^2U229yat{anpC$d{ z<o~bzZh7mSR=ny!Ky3HUOP|Se@*7j$ZXI6e+(Zetxv1Q(Q7<1;8LNFx<nHuBu2|?= zuly4juDe>!6&JJBS8$%&+P{(V+YK4*BabZ|TrpRZW3?J-kDY+VvbZKb8Zdg*WOS!m zUcMfg)Xz`{Ku}eG`Y|hY{bvA`!<^SAu!TDbYbl8Bi|@2t)u%Cs4i4^JznXc+;j!t4 zTxo7&tWB}&Gq;K<GXt-|L)^BrF@jwhfkTZBp`rdq^xR~DaEa9_7#UTNK#T|17;-m6 z-mlQs`o<6EwY~*|b=SHufs6H8gH2w6vi%BmBBuHWA=6xNQ&!gNh?ZOP6a7;98QBgg z<%@?{+hX_w_j%7N&J-FERz~vO)5lQTh*BQj2+7GPH&pagG)=J^zBP`Z@*`2Qb7f!? zIcIg*>b!A0)9zYOZ@2aWDW)u#QKBCi6lvbQ+kUYeK`qvG{9jD}y~>_*!UZ?^0WsTV zH3hu|rKenD=WW~6KXD}9TVI6ta$b`w+#MyQxQN3$zmF3#6_X8rE`qnbPr3MWr<w5# z32K&-Qji%OtG?p%$%#2C8^5S~0+&A&zDk8#&}OkVrkhgO#MP$3nB6<u9sPBxg#}r% zZn7hG<s*qn)8qBZmK|W)ts|hVPpU85G&e`yx^V0vj`B%MfQR@DA!sum?tUh(N=<D- zb}x4wj-0oHxj^}-)XLMf|2fAJpM%P*gzuDFGd#`Df=bSrH5&ZvmjI((TFs<Vwe^uF zMwj`R?f7?jKZFpoTa^8Duic@s5kp4a`Nn7NFCf#JHKV&@`~X15qFEM8XeXhA#C(OD z>${RnlPTlVE7})m7s@!laT6^KcU^bAkFQ41^d|chdhB55rqiDntOco&d%+Ifbmv#t zCt4TmJSAhmYGV+-{fFe<Zg&WaFd~^LOtDXFo{&O)>xeNr<?n+><rgFj^(fQ*f~<%j z;4sxpA*uRJ)9Qo$y_F*vWk@gKDv?0y?J~_4V9)P|!kzI3auL<NTBF=zM9)fhp4Q6u zbYIg*S2x@v|CnU;TV@AJGHTi){3{X~(EF%)b#WW7Uv=xX?-18(FaJ=xyFM#x@!QVo zog2(7#<DECQ3q-Xr{k(+OD?Q6Ue6&xZO48*p*iG9#;7nogKd~-F+p8r!q1?Z%8}of z7@ByuaR?}f5}6awK)4d%H@RP$z>>>`cW+Ok7uaymS~K_AJ}9|7c<D{g?kj5%c9-8T zUMTb`81^%W_wVHTop#sMa(#076mm1JF;X|WQRrd5=DOw3!Dfwxk>0|F5NfagcmP== ze|iGM#=;4b@yiq9^5W?uMno5MI_}IzSDD={zvMMESawE)WzPj2)N!%&@TE7^e_324 zqhDIG$8$ioJoFagegs}|=ChX_NMU-BX_UJgM}~B~iTvMsQL;nBsrfm@e@$w{?3LMZ zB695B=U<HqF<U-=V`yDG+}34{Mt>GJsMd1ATpIZg&1D+3uOxyU>L1`{^9nSc;Wcc} zj+T`nUEzB;F#98xm=r2QJx2&})_F-ZyH&6JLvlvjTrNDTPD&;JFl+m95R|IEW{Ge! z)-A?5+GVE`%A{!89YPLd^TUGKD{{WI*SE6lrgPm<`?vqtb=ziG(4*1o045&Os~K<6 z)qF04T4hGY=yjE7bm%{x%1GN*u=AtFAAG)KIbBy0O_@0S;A(M6(YgMa9G!|0_SR%8 zbi#z2#fFrVk(9v%W2;$@eY=!F`UUO3qgJwvLHlkeu@n#`Weo_)DO{^WcWXO$6<V>k z=R}P@G+ZOkAd@b;vx~sNMhkksWV)&myR~_tgk=zp+HKz6-3h8qFxvkEM8TT$VJ`P4 zD6$fIrA(?B7M@-~5dn5n?(*Ny9qN3O+=OxA<`GGI+=3D717)H(Df32Y7oQ%lowHso z(gq?a7v|tBogtb3_ij&gGsBM5QG4tr7&boc&J*sYOetHzpfT@>n~~?qsBWA29w(ZV z{t!dQzWY?7bWWnw-TU--+GBiNmtjhmHt+e6QS>Jb&C48Y9$`wm9b{14eI}(F`>cNi z%g1)dm|69Xtub6YE_(I%y3|4AcwV=~ZX0dzyG=p1C(kOKFWKNpTMDF%cDmo5nWBUf zTx5H8Q=UA|A3iPa+e&hGG1GOK_vo7Nc>ku`YDn65$jxBh&3YrON0zZ2F0JR!$kyo5 z4Sr>`$f!5!aXJad2am;7V(}St6~I-F3K=db3^(en0}0icJ5|6^CJ>IMO`iD>0i#9m ze^|e1meh!S^twQTpw$IAFmV8UoJg-uL7l0Hn>6Mzwnp{XN4Q70GEC$6j+r6ldIfj& zBw-hX9k<GErhGt?3)&@ZV<x!^mDVup1`s_~Gn3Y45N%;pZhw^XqLiK<)5_?zF}3SU z02C2Ws2K-Z77o?<DqiZZ2@kK(oblW@?~0doGYif$O?KDa=t+!w<F&Nl^&)1=wBHu5 zi`Q|JTTAqOj|5oSQ!Em??J~3v!rwWfdi>J)wqj{ZGm-bo`Pb<sulYUe)G|@Ln_XjM zWu1aQX`DMzFgF9XU6$6L=r&_Y87?!jeLTT8rC^p=BY_*#O=`&4efyU@6|u%9;$M_U z0faC@m+L2~QFXM)$~!tiL%pub8r|9(UD1oGhIQQri;RiC?g?wshbHItReadDB=0C& z<gzGbuE-EfoO?xhKf&?REsi8!)pOvwb<UjMn8KO*<Z<he1)6>9Ef|-&o}@%}Z1JE+ z6T=kVqcQ6He`KBcKUDu4_s`5Q`)1!6J6Re+$TEwaG@(*SGpNuughb0M_N^ghO=Ag_ zgjACH%ov1Jqa>mlOC_nMk|gDx@8kaIe%yb;Ip=-e=Y3u0dOe@hV+yWQ2=lqE>&?0? z#oS;MMH3Q*5yQ34qnu`OEb_t~4soe3*m}T4595rdg}wSrVZ~#O$7WFxEa4~PP)Y|| zlPS_Rg4hzlVsVazX3PnL7<{+Z_i?JYg)0z(i6{F~`#y{`LDr+WqVW$0zH==2)Qx$N zKX`~0jYEj_(r_>-II;h5C3wx>dRruIAo-)OuxH!F5y%Fq&}CLc45PZGQH=W`Hj@-L zpKiM-Q7;Q@y#O%@OD9gg)McUBCoc~zfCy=1lp|R`&2yKv$HK*DIz)=^$DP(<u$Gjn zmJAjz(~H{Xy`TyQlr!ABI3@y0>h{f)Jg;$ubIxN_>z?lDWi4u*d4%Bc3h|}6w420( ztefLlNW0&t&(+BvRJ%BKh)<Q#8K=6gj3-m=<gg+IUIgo*Ee{Mi3<)_zbrn$83Bp=E z4T49&uCov`K+rd9Xp#o<*l94o48jBKJ3{erV(h0`wkAMoH1RNy@SX7-A{?SImcwYD z@43)`KXqV@TnQ#Nab1Dz0wV?YRjxJZk<zvd;<LU@-yn8`?!(s9SaDzbbg7pB>Nq#* zXslBCWQ!!M+q^$GVhBO=={6IKh>qM;G}rGP)j|NW$b+n>iLA$FtbHgHJFbx}NZ%)R z!Lv_y3`7tVuzJTMii>vPyQ$DDEds@r$5CH}s0q5=4=r2`T9^b+{b1~23=LYaWGGn5 z%_h;^1oc-xxu&5n3VWbMmFn(UP#Zc&wz-&va9yL)Sldyz@qwj|vWb+3PF-N*lbKJG zM7DVl%VM>Mv~h=7ik*OJYzcO;vog+uIQLJ=w}#8dUk_FP5S4IPwVk9Q&=AC4U!!<5 z=#8<zz5`)Sqt_LSv==D0Eb_OmkbO}`uY+#j?oaf+@^cc%)(^!x8TxS7=GaoGyHrEX z9=iQ9>K99-_D$p*^4=7$Wf(<uTILoMQ@z3-O+mveOlqf$`=}mNqFAI2S540HwwFPz zeY#!HBBC7{@F18=L9TedStVHw5D>C-S#@S=KFFQK?V*#+n*A&VA~>#1E;RYFCgG4l z8pvQ#wDcXK<HN<i+xK&tdGG$ZrZ(>NCXp>4y!ipg#^}+WC5S^4)v}A?)xPJJ$-qkT zaC|j)`XALvj=O#iY#PRKkrSCp!P{PswKxR79O0UXsjhVEJK(@IXCvjb@=1zzpgj#@ zYQ~+F3kq@(osNP;Jf=21eue1g644OIM^OJ_<i0V`C|LM;r%!03Je4;1$jC=E&j3hJ zOqm0@M|Ja>MK9h-O^-$WP_~(TKv`c3Hcjrf@S&!1bS4rMCez-o^yP2LXAtvs{7!OA z<~U|!-4-m!^+l0qPrgddw}UJ_cSn(R%UB}w)BE?F>}S5oo6QJ89C48RY@>IlGiAN< zs6#Ymoq#m^g5>77;6kFDj=LH)X${DT3hI_$zVEnVCg*#1!@5O?PO`Pikmz{e*T}^U zW{`yHeO^tk2Hm4yb`@|ek~uOaVyJ@1eo^G=vFPD%w<d!wswh#dlR5gO6f0V{4IfNo zE{vsrHK!H6-I}3MB|6dAV{hX1M((A(<@`;rn-q04_+Tr)J#$v>g25DJ`<%#5(7i5= zgocAKQB;TstQMdc!#pfY?E+y|R|5R5gx*43@igBV#4)!t<x?Go*cLGy20^byZgJ<v zx2{BUpozNMqG!(oFfhq6lYY0fvoQ7O{yk@JN~EqI;#ie(+`76=XS<t5B7R<`IyZ{k zrQr6HTjHID{}o+2`+L2AfUl&b+qhD+(ST-ehF`B8B65VdE_NGss@X2GJD-s>T9!5? z9MwdFb17Q;7PQr)CqC&%U9J;TlsQ_;;5EW`vXv24&4Y`n{TcT#Vt>0m`3!Wu6g;^! zpX7Td;Rm+`?eD&7d{cWkh7O55*X<sr@@~8JuSVRZVNtJ5+UxtXPUzm<<BPQBdW*O! zi2YECa+-s>YEK8nmBz7(rn*JTP_SgPlR_=aw04D~k(Fq6qtGjnyerF3nsgNf+WUl0 zah1{S%!<D0n8c?#{usAvN%-zA<&G{CyDG>009Z-hPZfF_d>(-9BwwTGkDNO=z8yv> zku!H(RNU=2Jc*`oa=@Gz6k?Q~LVD*YcgHPCWamOzKf)b(Pu*ZgJw4Q|Vg@n>IP8t~ zUv<8JoF(JsKx)bCdYO&$oc!8u%QRH#fXgD;s)OP$|2XrxljYK7E5El!v&BiKayOeC z*OzDb=)TDFhu$tuww}D`Z`k+1NOwJvVmN9ScCm7+%3z^8K0KfELF`R=4r#+oFdlPF zm>|PSp-LkgW3ar?v>~!R9g{#-UC?IRKuz<V35!d5XuL@R#my1CuK$^P+JTFxKi~I_ z5l>PwgEL~H^meZ|DHM08P>5HrduZ)Sx|3qz?l|YzWavNA1N;O*wxOY9V^=}99Jt@i zh^w1Ov6B1QC+#M9d{}4Mt&-NQnMX#Dy<XPSRg*zFlJH1=-d7?evj?o&Mse!^n-xRc zajBxC7dQ86wP)3>{j{HIUJ@PXy_9U)7g;moR%f#u`p2n<VojQ3XcxSSpg{h<N?}q< z4nt0*Rk?{pgyND~PMKQX_#-)rc|S;*074N!iLXHATw?%FQSS$o%q}#U_U+rpR8#KO z?~ocvMRv4q<0z4SCD{F1g(&rJXIx*)EX7(bbszs?6D4<tuVzutYx4ze7q7lpOf_Ia zXysj7mP<eG5f^G%ZR`NUVyLP12DUVc(dZ|KC@}Jy_EQYSfCK_Y01Q*8kG?-3t<sw% z;VV72otZ{Cy8=-leK{X>JIcldsws`K{~*P*Wc1~|2Ylhgf$044^^Yd=n))^>EnlZz zyJfVt!NMzvmS)ibKBq(5e8a?bQE0s|F!-F>{Tu>BQLF&Lh90oy9OV24o(V0>cr$V+ z41__06ar4`@PAWg*`M!%)S~^yZ2P_phwGXxn6e5FMu5$fH|DJV`1I*Nt6S4}kVo_G zzksq`GG3pOh*Hb=kvaIh^BBTB$m6(zj?-q@0@wN#7v_1?@czz;l9=#2vC8)nXSSbJ zGD{IvY1Db;Yqj~019{KvZ)n`#dTSAJ@WNp=b=T9t^0%9?r@AEHK$1pLRB+YCG`P;> z%?AEOYH(B?NFe{L!bJtQ0#Y``8Ul2sePwCZ<HkFhtiP?id|Ksxn~P9$IH?{N(VM%b zu`y{?Jw9sSoWjb@LuIf3ORapCZs9|-p=REV_-5#R<Xi9a)%dvS1D|(I6%Gf)=WIK= z?-AE(&y!=fHt&7R*;w%+b;MuKEc8dl@VTDYH|>XBr6tCRl!2<o)ahkkDiovV#O&_a zT3c^UpalLJ1Ic+o)iwnp8SZ&7QmJct+lF0zUloJHhU*nh|E~!-s2s)<LUm5!yWz$z z{Z(?H#ukbU&a=6tPdzA8FJ^h_VQXI9#}CTkOLt8iZhL_xwWpHH(sY5VSG+cIcTMlV zw6$m|y5cZ0rLXLS?G@uoGjrxaCH~*H)@$s0A0wC7VD@T;M}3nVsp^?UsL9YQCalTj z5x+x3n2m>s9K7{hvIWlN`&i@?=Z{^-t}g&)a<cR6@>zxLVFMmYhyKYf#Y1I}OlYrj zYOxzVe)mApF%oKX`)NB+rbjPvuu(h3uDYQr8VP}IJGeX`qnB=v$gVi%BaG5L&<J9c zA3ic|a%pQpoSfSG%IXh=F^e%?r6&j=uEM6~S!?X31!k>+BhsKo9*6??>4#C^Y2HmN z8`a!B_!FGR=_2)3?Dv`aq_7Kn9sexl^L@3qC)IkTf-@Q9UcINp!;O~$JOVI=@yiNc zN~b$PnJtB(#Wv^SIvBo}j{xek-rR)CUV4YM3l9{Z?1|a09&1bX>fe8RYONP_plszT zq2c{H__~dXcc<kJqt@x~K7v|D!K??qQ3GAx0RH#tzd;BEE;Vi_yw@}B11}ESX+)Kr zcz=ubwxw6MVxdg|xp3)BMD+n3pj%;#INbg5KvCQhIn+MYZfmP&p%2(pGr@MM_r;E5 zldV;Oq16W}4pbqE${Bg>J;jGRvb*}c7q@y<d=!MPzxP@3Su^3{d9y5eAn2$NVR*!> zA8HC6w|&C(+0wX)R7o&W*a*LJKs&IbtWIf1#P5fd9Dzf{@AntaxY?pFZ@~*a#8a?} zM2YT#=ne{7X%lZfZ>E$&xbV0_aAKfNcM2bSMKk4sFv{fY9SyI_<QC$Z@uk>97Z0cv zNqijI$QZAXk4Y+bU+?%%Ojj-D6YR}=@Bp35Nt?nSVeQgB^sAj?m(LBCf(`#kGA5!7 zmA*66&MFo=0IQG`o8l>SOey~3PYboGWtap0`Te__Yjo#GV=*ga<jc^RkSor<wte5O z{`%~r)ZKz;ZnVKMTB_CjSJYiY*{D-dRKH3IMZerZy#XX}-AVMBrybxLv=ep*<%%x2 z&Dm{w)=J3lr?5MOnWxY)g-?I_en3#5sjFC+Z8Whs`VF_GG9uG;NZIsBrl#m*j`p(_ zZ<F|~I8}^S#7q8|n{`qxcd}9QkNSv9!cUt6(i}|gK`2mVvzC`aiclWj+UG#8hSqDm zPkOQru5B2KH&h03fKsK9s{P(L%{o*nJWcZ-fJuomP^}}RThP9pO<aa-%~Af~IN+q8 z^39)GN$7LE?Om7-kaYgeJ)|JL@;ISw#M0S^j&{SCElc?Zdgj>@_yPQpjwtVM6%UQu zzvYF=XKU4T{;yeS0oZZ1I_PEq+!2=ms<Al%W+{crUJRlT`Wi{CEdMxUt7^0-QyOf& zT$txw%vDLf2jg7W5qRmJa^vt#@BdncvyP3`Ui?zL+g)?(*;L*4!7q<_iFl6cA#9P> zhtR#Q9m4z_WkJRY>Amqsimt^;BTQv&@m}U-%!f5Xt=XX1+whH%RbN&+L1#`w&fG_# z#2JG>E}@Xym=!<&LP|Iz==+>kp%2|ISZ!Q*NmP%k5k;+26%jFRh+0j9K91T4c=op7 zUR(ga`I>gCLP1DGe%A<9>)y11anV%HCDM`5QdY0p&DQ)qJ%{$^R-Ys1N#u0q2yk0? zIeIAJ-hV~c@OuEN;X(`SpqQ&Xz)Fwryj#GesCG>yHbsG?H>%pw^?^{BU9v*KbApNC zwW%KBld1f(Mroc#-}>AlY_2wgS=YPb27D8Q`G1BDHA;bAmyYUeeWzlrPQY_R{V@7e zkIYHm`fP(zFz2uaqYePTS*Y*wr0C4GF!Sv;Ko>s4gQbuANjz*K9?rb4)6cu0@U`GX z*po-gwTD-;(w*8r+^$=Z>Q~NX+DWwbp0+eplFfWx8H;}r-88QpC=aYM6U6%#xXMNR zOyX4=Tu_36#-B!*Ns(}rA@@%4-dNw(_vO$l!wWWs#H>4A@_>mP7^jWa`6#7!l9?d< zdM{7cG<J6UqCQXLSX_`A7UTbvnL@SC{Lh7fO_JiZKKl6l(zVS=^qH}%bnRaTc(Lj4 zC`xn7QJ&2y7-k4pY1%BSFJS}|O^VdbEA>)24nl4RSh|an-uOzg=T_sHnn8Sy8j=AU zwt?aZIws<xo%mu^eXQvkHX&(RxnUzet|gJ&>(nuveyoy%=_mENcBQ`Yf2;NO_h5US zZE(KVWVfzMQ&#k<0%}WGjzRNwN2e8G_B0E^hYjDj8b;1J<=Fc2N<y#M(lDAv0|Onc z8E%AX+%8Io>9c_hx4<d+j%e7^d{C}hIgqway$7`yo~Gh48Rn!DWt9m~H5)5n2lF7R zU8R}ofgs;1zx8jomaN=AomV#dE&~5Tnkhhi4@~afpuN=JYwm!0v0US$9(dW-vpKfN zzj2hm`%V0+?NqbBphkCEy3X~`Bfp1-Bdec_p%;Y!l;oHz%FU*RV29J4W%ekRIA?oN zMLI=hvtmiXYigQtu#J^eW+^>WJ)kf<MtffOA3Pwl{!PkD|G9_qtwXLn7&TCRS`W0t zhpO6!-QsvlTZNGr@_Q?03qMkOeZ;1#9(NyTUQ`sUo4O%`8RwiBfyA|%UD}}Smw#|j zBX7{Qi>Ncx?kdZ)$MR;TeIJrZMB&pT<hYSZi9BFL!L&LaG<i~(<u935!M@Wo`}`9r z1~la6(Uc%dh^h};oer-Wss7{^r9-IJ<!s4XH+_HCVf#kma1&$DZ2D-;ly=}XCUV*< zEJC|UUw4eI^qsBEXKTHm@>-NFosW?nQ|h7B8Z~Jp&jj3v0-|EHbq53o*Z&Kj!YJab z_pd#HvPj&Py4VgnZZUfJ2twFF(q#(ug4UB4J_8~e+L*i7!AcFzP#dl8M^ki0^>s#s zy2<)#E94iJ28<Q52A$l#&fvc;;piM&X-?nxz4hsNp=L5j(Xv`?rCM`8(|ehr9LCmd z2kii!`Z_mgya%D@1b%}zVxFwW%#mVaVeW#Of;arMcmeb(2~*04b4Z9h7D7>9bB?W0 zMAqx4Yc2tH>Iczh6x8*oDNy2uQHIwA@=rI9suA*GN1?7s4R!~{ux?7XCK?xWy*-d| zc)$2sU$yQ9wz4`%t)3ygz}D&^Yagl8O#&&#zB9Q!Ri3~&RwS>~&9|Ve9k8K4f!`Nl zBx%IS_1H?1tUW7-Y?Jfi%XLe%d2E$uQ;N<EO<fxGq>Z}8GXo`R5I9mhkgartjCoET zQSH_(W-BjG9jO^6xTR~_Gt_uD1_@Ygeznd$q~;UyI1!|nMAoxQSLr}{Z_m{wRI5%Z znDW@F1(fDp*qDV{n|6^^6ZN|^EpS$DOR;av8v;HLh(1Js#Y><r0ZNWjdbS`;+dxIg zS%dXKRxg82Sk9s>>I(lcbiF_-HTu6sKw2aE+F#fTj>eaW)7r~y<wg+G=!q7<G76Q` ziC`!{0VOw1Da#pu?yuHP(;qzYjvo@SHeaprCQjD~)SR|fZ8ke&5uh*uzP{<%Q(XOf zw`o3}cV%~u0NzA^g|ZOy40Y`(brVJ-8i5{HbYvH{+A3P%E>F2IG|--@%WNe+ThEqB z49eH*U@I+wvWvf7b*?d5%2l?FQ{LaJ(#X)OW2*-kC?%0khfRAeHsjLBK17&ew7lPK zHukCq{Kv5Qa~yt>&JK7^s5GC<q01eSSma7D58@TylM&G%W#|<idLW$>OyLHnjEMFA zRePD}t7XaXpHr%S5bb`3!Iyy|qA%lpgLZx1Z@OGI?Olq1p$law6ROp|lQlW(HQm5W zFMT6Th4b_JicSXc@7WsGQ@KTo!<`~`)EeX|Z2^9dfPTaIJD&v)M)!svlZ$5|68OkB z1eljV$*fu_nW4SPCZJ;|&qF9eUy#;--ZTAVJAKtYtj?DyCtss;G^+<Lp9buvwE6np zpM;)&^i6u%YL0B>0ETd0U%O7ISz!IUZBQwG>UT%p?0d4Ff$0t}P;;1<dft0N{|%y| z*~AD7H3HPt)e{DLZ?sbjutF4zFL#Il@0MViNOvm<N=$|#Yk?BFWivO?>e?4dcy#7> zeZ6NSrJyK-Ksn;*l#`Md;|T++Hm$9zqM5)@4rC~j$QlVCz;Vi5H&Ht_-_v8CZZz-K zKSM=R8=pnSy{70As8HIyHf{IX5L3y=1~yIBJq!GIKCq@9(?LM#`alm!pt@#=Qb40f zs5eCZ$=Vib>fm^M-3HrQtw6GF0b2<<t(+iKX*)Dn17bQBE7652OWjJeY6U4@jR#46 z#?WbID;0e`iH^{2p3*J{xo!wHE<UWhI2GB*&?GRlk|}yVpy36i`^6wkCkx;6IVSu| z*^!2@?#Gx;2_8I^FM&rNAt92;N?4;4W}}Bpl^-$}^zc(Oe4SoA2$*KGWOXQ>p*Xi) zsg18T%|3dE;W0a)=iu*=EK~{?5on&?!l};*9y;r%Oy3l070l!|auGnaT}c8QghJ=- zFMHCs&3!G}YDozIgVszy2IYJOJ2omv^@!`|LwnU6jX&wp^kv(gb~i{XDHeFa)L9{8 z{xFh^H)A#%8a@FnJ}FR2W9Zd4;ck$(xv-T_D#j&LpVah@k7X-5csI|TH{X;6|1`&4 z;%{z~;Af3`*KxL?I0ciEV_<!Bmq4=}sq|$^k*J?DR$cf7l=Q2_D)on69eLo57Z^2- zF>cY9ft5|p>j|c`Lp~b}l68PMdE8AxQ=TqyN(1`M%V1uyzS<;%p}q)GN~=CrbOH5U zfU$mgH$2B+fq?tYN8t~1-ybCg1z1fIP%E=I0YO#FP^$@0dQVc*oT3?|pE=uMV7zv@ z@O?<cIL+=KTPdEb6BxNXoja9GRvH00tW&?%1kx!lxOQmvzzO{l=bPJzAY*uz8Wa`V zSe&k6HaW*ab@TDh)Jji(iH>T(BlXeF0~%twbuUXTi2-cDWaFIB&%J_HrX<VNhm&sT z^GoX;S_p2vL4hDuF?;YkO1mqWd1P}W(?btV)?3uy*GN{+3(+Wg$Flt8{@F}F8j5Rr zjO*f~pyXJWmw7IYn*f0&QuuvjLAgy|qlK^Lb`;pQrSQ38VTIG%Cs+2;sw;}tfqw=S zZR)-0vnWeqX#w8<)i>$x5=C?_7{A)KgR-oUMez%)#!UmqEI9igbYm;mYEW$gtL5iq z%KZgl8&J>aXRoA(5XfrcDMgY{B}=F~%6MB@R(&}z>2o!y-Mgx@xm+|=9{ioKovUs~ z)+Q8iwi;`uL>&%l(VAmxzA5-4ZBWfq&bv*<(Qb9VIU(i{CsybMpOO(uM-vvJ%ewg3 zrP)(kMJjp43JF3b0jN?OU#(SsW&P%q=o|lm-xE&Gl?PiH&-m-Kgz9AJYd+A32qfdT zN{#J=E74%t&t^T@sZPXCRp>4g)O4-_=*d|;4|*f1OdMW{DwVmqg{Tzu+z)J|5lFe< z;q#^ZvWi`;!cQclcY2!oYPX+cUvkXZh`Qu*O}qTaiF>bb7uQPk9IW$#nObj-X#In! zaz;a4s!@HPcM9&nLDkq!L3GdO_@5`XsU5ZYF2I!%Fp7*V|5Egls&PwGiqq*TtRY_2 z6P{Yd-Q#Ggbx2rY>{Y|NZRQ$)i@%Qg)CvV}vq?k8D^xqAMu8oosFkTzPgcBL-F;gh zQxhUCO{lsrLXEH#f)*^sAiJFBZlk7qPC6+lT9twbN(oc#=RlG%;d4vX)`|+De(u|U zAk7|I?XDvlIuVL#)eFtLF9lX>`t^o5r|Qu$8)?4U7lc09TwM~|EaR~X`fKXzPUV}M zaZwfc_K1J6T79^hu=hQPu!Vo!{41U0<k%?%JCN#wwfa_tKO40w2b4Zm&S8Kf<ZgK{ zyHQ5qhA`tlZ06otTtfiS>WJ}Gh6bxxdELCuW=4EE2=fJf>@jZLh#~5T2L1x^&buC~ zRh2D`&nCtFh?GAMe*xN~c?xv4iU%88dA0T2Nnu6h@TsemFH^d3*_P=eahvT#l@xuY zsr$8EC24xy-TBhvk0J@0_LHGp$~d-2#ykUJ(xeuRs<_IC=AEx`@hg`X94~y`6uT%1 zc~?^a`KTRHZ3;D2<%2Sq0Rtsn!zHIOE@%kH^%b&0Sz6s*wo@Z-Q0LlLmA^o38isNs zg(@fGyB_b<dS9*T%+PIPYx(G-MyGpWkIk#rM!&t8o-FpQx2Os9JAd-`4A+mV22IE1 zy$Tru&8uD<$Awqge%B+im3ix`-XK_79UfnaN}WzY_p8qd^O%~$*RIOGb51+JH;$D* zF4-Qc_dx?cyT`Jf@*igA9pCFmeCgXC-1-EvqK8mHm#s25#TYK4T+o{0R%NK8p2hVm zu?}^=sFo2!ZwAyBfo|#%tH&c|uJ(a6;}PDPg}N&TeXsVb$a<Z1JvVUV(g^Ij$!=^! zDYo0VVOw69v{T$I|8IX4;_5MVOE%7ftx90)+EK4e*aj)?o`d~&qDu4G$Ip7UqiU-R zeRR4)@>HRHnEfC*d47s`-mIcMz<7R5|H-5RFxGUZScr1ANthkC8ljJZrmX(?m6(IA zy=-t@1k9|#*{~t4mR!Y9h9)3U9(g2-PK_h>E?2{-n&z4DY>C3MG7YrFzA_7|qC*l7 zE-{XV?fVf|eKI0fD@otwrceVaESYqi0QAujr7teGKLKt3+wgs_Q$KcT<v$d7EpJeh z$x!xUs3B8=boZRe)FS|JZJ!ptkPBB@7uMfWEy~0j`c?Y0Mvzm1f8#$Me$m^s<wn-; z-QMe;J2Sz<)rQ`II_o#Ts{sM9FPb($X~*Mh+w-;VZyo3WN&5VY+!#N65<y1zr&SHC z1=h!D&&Sm+M}g%5u4$n58arI4Zz`ujtZN-3hq0{NpK~jvWNa3aK5&kdwDdh<^+4;5 zxBsyqDBXaLmMKw|!lxGp3)cIjt_5OdVEjtI3)T#;+MPcti9w4UiJwf4lv$h-Wekf# z{4cfbPn=tBg(RNUB}R45-9-v4bb;i~l)tYkI)oC&j07~>>t9U){=qHfOjLmrejYET zH*DtLPt66<0|Fj&{r)lc{Mz29ZwNDI3Qgl?igPd7#eWc=Klt0WKH%u6bSB5*CqR2_ z`zMbw=pwQd4H>TlY`_`r)NX?jPB(%`YI~xSUuX%Z3Sod@2D~sUjt<XIOOpe`6Vib; z?^9ilMd+}GNm0RCa&G?1H)lyu^I4vUDq`4cA;D;~WvgA#S?9mfW7z#&%%B4Mmr)-d zJK?|gVC=?arxS+>F~slS_yV|3@92olHZ}U(6pV1x%(U{T3HaA;iqQU6rCzkgcNign z{6T)*>Vkpq1|UlDk^8^NV`mGCx5s|GT)IDYYtj3J#iwSa9o>(tmKtlZ&Z3^Sv-YFO zGZ@Fw=r*N|k47M<=qGccN5((wg14B2HNhKn(`E}Z<LTp0m2r@tPWY<R?}e3WnMBGQ zDcf!s4&0*^V%$rkq6+F~FC6@Gcdo5uM}ufKzQDApL($**FJ9@9^9Lz6@Ih-OSP;Fq zT8^{3wcpln&8pq9yIL)E=)?lkFmU!oFu2e-QayZ`VMWen6~f(r0|I~7a>4Y)vmfi5 zz7Ja7IoX!%`)bD5@t^eO7VCym13%M;p}+jBAMwHdu9G2Dj5${jkG8mM7UXZzxmfL$ zm-q@X7W`kne3oYP6;C`NyU_;W{&cY#2V_=GD**ra3*RT053TNWE*T*N7B?1^3Y<=; z_~3vl*+i|3Bum7(j*<+~h9%K8{;oBvwoly}lfPxgpI9jT{l5J8liwezG9TR4D?i(x z-e;&ds0=Uw0nRph2ts-`T{d&p{n&@*KVQ23oZm5I+W=uXPtlKUA>Nq0S>XQHqs({X zPY<QXYi^~in_FD(O8ra-iD<c%Up1L)P9KlWvsDe*tKY)Nn@2?cTA9H@#NO$+_Q<cx zA8xq+%S|kPWU&PIb{}aii0!G-n=Q?Dj$r3(%Z}7*70UrgXs#%x8^w-BE<2dHJ<g8C zB_~5N96Yi-e6G>VhQL6me#XF7p|WP{>(5KxBF$I4eJ7^2hC3=??hogwott}j>d7!J zoX61{RfjqI6y_fxMQV0E^R~8B%XEc%9TVsmYj*K6JV-F$(~md07vhi(gj&5lV!6E$ zOKn=6-}0Gu&%SCN%MSnu+EXnLE$s9?R;66!3E<(i3*?;Y5s`{Yows2(0Kc})$g+1$ zL4hzSNY67i&}YFR>q1-Mdm5>Ti-4dbY4)~b`S;>R%coy^ew+<Up4RJaf#LsTVVT(w z?O_sZ9lSj+4oKJP2Do}F?M@0B=PdeN-rKl(*Sr<SP-9yzBs}opkys4n5}uq@dtq9D z1PdhjUv_-x`$RbOO|Md>BaIg#PPe3Gm6pP+e+dx`5>B;EG1EjqsC6X;Sw31p?rdq( zcP363f$xrzwm(eYB{QL~@WHmwpuzZEi#6)o`oB6)<3h6JfJXj9x6lYoP#)K0LLleb zV}tX7Q}rJ4xknv+f)##G)$bnQs&NwGv6{2HHuL|tujgdF2LpWq|25AIgCq3?N^a8M z7rmgra9%Xg#lKmen;>$z0V7oH0cNku`>im0^+!312yB)nG|Q!qO*Ph5HqjcEC(J?A z%Ed4Z*}si<Wa!mEOcQ<JirSe~L#2k$4AT`5_O!HH$;aiPc@i0y(!ptK=<n7ua45w4 zT40avQ=pW!b*6z?v<XcQ*D7J|A-=xmn$NmT51htcy>ci>@qOm5Xan1^YN%fDv*)S+ zlr8!kt2^1j)zbW}(rzu6OK?7{JITwqT8wwT{P$H1N+HW~wptI9(`&T!4L8C5ar(~Y z8!5j^MER>!wTS*+XTc*>d<V{MktJ^}<KC{fQ*=aXDA>MT1I|-=$e2BnZk;Mao#$0c z2hYIMbSr7FGYeqVi^(2dV<uHUQ<g=YkNiVEjb8Ce;HdNv`Yh(Ro(&Zk*mZ?McYdN< zavUG^b%PWt@I&cNV{C=JVSAF)cF6>^EJWViLyK7bY%=Sn&76E|al`8E{C`~Sdt)!m zTnY<LMb&8h?)7jDoZ8Edl7ILgBJe%@JPZ?Oh5_In`i{8+YUylhiX_vK1_HK9=aSkl zxA9>Yn<ow%W&L&RHTF@+r4Gpm6zb)A0$L^Ow6s1go~kY2rK`La;<8E6>NXl#E(!XW zSh&cE#>h3Ifv<pD^{NkSJ{U0mSohH%y-is*=(U3YNwKNFhp-rzL+tTMyjpQgds33I zJ{hzziUzst{TNS?H^3i#P1PwS<nQ7O724;Rbw>7Ac2)eDq^@fk8e!x!R=H}eOfSO# zMy_3mEh=1aT=gpN==w!AI*LS9ACdIZ9wq9ZQ6I^bwO_9ir%?gwKQy#K`QM*7i07Vk z^u4GpNnD*#X=v%I4U7{6MAzz;p}B+Gs$$Q-WGevD>08F}*9~q&<8z}p>jT(n{&k{h z-<<D#nSlx4M?T;GyDQVAUq8>E7kNp3eX_pwM^B<=E-l^BgL_Tqn0qpLWA@mn^1mdg z|8h;&OvFS`?vth4yQ6BC_z*{p*0aHaHL#|7-V=(?BVJSF@hQgKE`oaD{EkB$%zS&t zgxb?&!EB37*Vw4}ybUrXAR^Z7@`<Dg=bzV4unXnSa0v;+P=`g1Vg8o;^Ty8%!+yL| zY?btx^$o+_qfQ%8!k6oAl3*=`KKP?j&K?iO#UBwTfA(*Aka{{3b+UVts%|RNv&i+Q z@9{ZY$>bqJ!fAvZiKBZ^x%2x&_kaAgTCH-ryk4LXzR@nU+Wo$2n^MkCQjb3RViL6x z_C3>c9b2J*j(ACrd+2={nsstXY(6h>EafYYWZ<Qlhh&VpJRa<55i|*Z;Ax>7TMQ4z zLx%)V;zM&-C}(D)_W}{oM8vFB5>@DU*zN}BhV(<BzqGTNPR}x+hiR~omvjYHc$!3x zi$|r>Fl&6n=>r_Uj^q!ENFIPXLQDn^LuJG;8`H$#jfvsyhv-E47oM;*W;((YkN98^ zE|5D%LmiSFxu_WEznqb`W224`<;O(t<&gotYAOJY;XyBs#;Bi@=fI&S@rU;t!za@- z<4km9*eUg3opRvVJNeAwvE=O+P$2^72|OcR%GGE;gclupd;uooiM~wY?lU{U60`FK zF|jgG0BwtOD&u@;uE+7f1`_m`1j-R8=PVn9hB9+}G7vlR;`VP|-VZ-2hRWty)>^Q> zK}T*o=4)nh*2+Bf87vyzV>9ZG8;h1V|2(@_9ezLg09^{rl2OK32;G<Fzi6xx^|Qej zs4m^u{6bWq7|s>QuYABWdgyF%R&tBM)-iaNjG`A6+HQ6hZ61BSVfP)0T(v4(#=e~D z$iX`3DEbs+GtbcRrn6)4Gc47+(mdZWp4mrU^F~CVlzTn-lnu;FVzwhZ1U><So-c-G z(%~n};IfIElQf(m=&bq9VuDHL8WH+?e-1|sABl?{N;)ha&Po@X93f;y@t`bP&Snkx zjsfsRKu_1(-D~HCk1DzV!F)jy7fgefCvshP!be`few$?NB+Boh!4At3jtuz3vvX^) zJox~LoN>%q?=i3aWu<qFx5+5P`FL13!7RB^^>W9~ifBv22zdCh!!5~YPB%g&cd$85 z<@26rPfW#C3FKOqPn4VEXU%lN&t<lqI9&M~w&U)hZBj&pZ*kpth1$My0~0ty3fsI> zUQ_Wvh&g=LF;SzZj6*PE&?_?trN(!$H6JU+Vs-}^S2Flz830r?a4yaSeh_~kZWLZV zpt}4Xn!&T$$;24O6^%Px`VXNYBP=oisLOcq4h`rLF?<k_+tRQ4`wA>Z3O%g>^<=_t z`dq?lhBhBZ?WM!FNlU;A4#76^GPvt@esv=hnkTKykU#?@@}1cV8y5L%>zo7YKgQjV z%9oVDrp@sgGTzyVyqE7U%5Z~WO7LEZg4&%LieG5+FXT2NLY7Xni^a!+askQ3y?kgQ zUA~ZTftqr8Her)>tb7(7zE@gTuE7t7<l3*R443|oCwqgha4_@ok$JD(IdFgl*HDDp zr!?$Cp4=<&;Q+N`(!9ef^_;=*IA{DhXqA;3G__oQ<p4aA06+L@2iN&Z+=xR<NYxhS zhVpS3R}4D~WZ38Y58jwXxWM+i()enVuIbgX@+<K<@D}8?+I8?d%<wBI*ES|3+`vQk z<TTLNT~q3;H!;7|v8(A=a3~<Sd|&fgt>4vdWd0p$Q=jwoHReqPfQZ;jmp|A7jg-L^ ziO@?-RK$skBfFaa{J=esA~<-&9endIV)J{=8^51BL?X7$_%(kozi~D8;%d%~m6aRI zkvD)%EpoeCps6kJiWcO(7W705_D>65t5tDRtMcwv)znt?idM~gt=bc<x_?>;T5SfK z+KhI$nWVOvRkW?U*Je4<X8os)sCCnJ(@neGHyu)MI#%3tzIW4Q;-=f5n<TAv%BFUY z-R)kf?LHOle)rk~CfWo4w9~Y11#P+&visKd)LWqyw|3pT6*h4z{Ld}A)@{$!s}Z|z z@4sf=%e&pn3h86wWAELTlR5l0-2tSxV=VB;D()nu-ih<SV|HL7*-Zk02q7*sJX@<n zp4^e+-vN&6$h_B)ivkK#JGj?6PAT94K>xR#d=vlxmIy!|z=6Mk0QedJg3A%<|9_!c z)0?ZlA$GFAwf5mz0yRh5x2<mAoLTVIuz|MAk4lJ<gO$EF>mOG*9=jR>uvkwnk+?`5 zzxL=MRRFENXR!Us^9EY2-$lP$S6^HUy&3y@@Yc1LH|U}q9sk=+<2R$9U)}TQ_VtN7 z%$dQ9{&$*R-%I{6|N7CL|EEq>vIrmQXq|b;GxV<txZC#bQR#+*Z-(yP{P2`d&DGu9 z+5Yi)WAL@`$DOx6y^J#yR&Bm_`}2gADPm+8a_8&wNIBJ*xf#OQHxSI<@Mb4RPYW`7 zUKa2aD360h68aO@cqOv(;efT)Co_cjyyy3>y{(8OC}nkmJg!FI6@ZmR(AcG{Q}@?; z4=$L{@WE!sc?6Kx2il1>`{*5sc7MfHB(!t%)UFRN7O4vO@VTi>LWbFNmeGai>1?z5 z#_1f(+jG;o#6Gi`JiF28nS96hjWY!<OLH@_IyKu+UI&m4$Z7T5y2vwn00<Pp#u_^^ z0>Vo<<Si`Py9<Gv>2)M;kAZiko_h#;q3T`u?6UA~6+Y!-;m3*#(8CgtJm4rE)pYDK z{cy%Ng~%(>EWHctiu;GCfr9t6fZ)l<5fTJ9ccp=(3m@Ee!pZ1r^l@!50)RnI@W~bE zeXq7<Udribmmv$+Ud=bz4ETMz-tqqGr{=Du`A;_lP>Y3@9@T>jt^Fp~7TSg!J}ul7 zds%#LAK8BJ^R2P{*FN8#O#1Zsjzq=}?)bljYW=k@oeQ@=eYq#?v-rAmY2+Z!_1E;K z8~ID4pVmM42bSJ=0G_z_HD?98@YVH~*#c7l#VLOi&Tn3jI)5sy{pP&T@<aL%4-05L z1FYq?y8dhV@pRB~?Rnfo^&5~jk>T3X4U)y$BkV)Vn~_i41wGvZX5~Fa{*PQAH8G!T z&~k};e0}`h&B3*?;34zYu5an;Q6WJ{mz!xi8A{G4H~QLG9G^@O8mOTY5B`J8KzB>h z)u+yP`On~{=bP4wvQ7UJ2jy5@3yE+<S<1LuFvCf~fR$y%OzVHgb{skJ4ha3{5Q~g# zYIAQ4h#y>kp{HiRrk~F7Ro&y*=4VkITI7KMCV?IdSVMNdvUy5(pKbni?{~DqpL;(B zKLm8cESkjeNbBN5wpkXp1tMP)`fO{TR%AZ_D8(?R<dlqwpr`B39_k*j_*b|2xO5|K zOPAnNQ>DL7fw%~5d5c9s=$&VIJA{49+?b}12AEVGWTBp}Y+^W^NkJsgaN%f<Zl?rd z>Y|W$W|<m;4%S+QoBTJFu%PRrm7z8!M#%z1O0{%P(?f+gz>Y#V!h{f(STJ3%fja~w zN?j{uW*-n6Dm`0<nGwl3p|sEYVk0Mp{Gus9npAI<Dbm=Lg>YkWREyPnUDAYb_%sNg z+z-)};xp}K*l~mgSt-dTGY)QuDZAEZJO3>wY`L2YIcLz{m|WI*B~LG30<jX4kq)I4 z-S%X;4Rh59HV~2NA`3}cYrr<16cVgRgK!ox$2x(m6wQ(|(%+hUdN$&e#kIHa39tVC zNp9>VW}5Mn>OAkT2;EMBob@~?mncxcpB@wGt^xpQwgna54^|V1)7aubLfM$StD_Jj z1Kg>8=Vh7;q=>MvZu}TiW7C)62MVKYHfs@M?nmOX?V`E5B^@62??G!wnwYAd>O<F^ z#%H>QDRTDE_h_vEfIGlJeNphS3>?l*;Y}+q@}pb_htI0dQ`LBL+#{j4u^BINW4I?9 zA}IaX@I{d7YQLN&U4|WsqNx3mc&JHy#4fW8Tr9v<6Z13nfx$pB{XGecBnM>8DE@9S zcb(sg3Rr+>7Kc1^UfGJXb1^s?0(tYQs{Yx3#JnS!?GU}it+;h94DCPBJ;w7kc%43d z+!-cUEy)i?SsuY08kr(ts{>pC0xIychueFboG@{uZW$|M<9wV)ybnZYDSF!4ZYtZo z^Uwvr!h-(34-3c&loG(xfh5e>JH}NjX_N<&Kmc(~xtq_TLF``eVeZTNSeSmAmR!+L z8jqrvXYA=ZU!5H+t=0Mv9pPTrdiG2uSmmQ6-Nc81?kp3v^Np*czfm><X(AOaA)QDP zW=2U3O9vaT={X>vvge6OBlKu$t;5Uac+Pc9K*+F47+cI$>0s(xnpxy+UEr!eYlIo` zTXFF$t{#un>%J0~6CkDRGr`;t^yQW$0xZ33DRX@z2?6x{R9xYE8+J-)q&h}J3aQ@q z{9P~I83rL%mJ9uh%CZFL+D(9`YXW=gks+?aPg%+W;3EPTx!SW5Z&zCzY~m_Jr$OrB z1Zad$6^>b1oGU$HV*`7Y)V-$sho5OtY>6kzf$>R1V;yYa&_0tMY-Te342UGQ*Hr-) z1@hMK3o$-JT&>rR>HiyB%8Re*4jqj*8L8fOh94?2x7c9ywCh3vLQXZaBh4a|oxO(_ zsTm{gb%M5KxRwTC9(c|dly!P>R3iw<4q4SgQqJKHik=KjSX<JHqqP|5%*X<|CxkeF zC(`;$k~jUw&W~sm>D943EQ1~HlAi^1)#;*k`RC?%w{VopSUuKD!d&nEBsF>?)u3CP zZnwb3Lv)#E&gAhXzT<(x5qou6E;V2_Qfq?sP4{>;<}{02`-s#F(-=K_CLluNcreUi zMK=3VDcWbTcCT`9hufW@TQ0Ao$YmbuWey!$w*qQ3qw5zNxn5F@ua^V#=joYxurLC` z9d5WF5ZOE5&!o#pWW>V!6GJnKGX!tzfQ@<kS}4jj%rx`9z@!}s)2gReA3j|Y!ZH3& zbhjzlcQU@5e}<G(YJk@p#R_rZQ4}rk0GKdG-0agK#Adxse5Mo#XZ)gliv#4;foj|- z?c=g~{IyvC2(gY2RvqGbyB+$Ldnn7Ta(s@e?ihy*l{v+GS~7H#73Oy$i<%NX3?455 zv4Sfj)M~Rl-HX`SQK(sbxCE>t?#OgD`uh}U6p<>MmtDuI@!?Vrkq#sGq?@9K%@dC` z*FFX&x|pie7@BD}x*l^{EK>T{2#Zg&L2Oy%U~bTNZc-a19)JJ9;+;Hj6^iN<(B=fF zQo(ir55@J$_ea6tcOv1fUU+pF8IXg3*nv9|e!PS3CLwMKpfv#SL*TyHf_}uqtn^@B z$ZF6!#0NTNSb}*Y#{7{W?h0^If~`w3x-|)RMHwZMZiqEKe(cv7+BZ9{0A=?M-ps-V zdt?4EPvSj7{kNS`%))Qpk&sMF$h>g!Bnu7Dk)5;?btH~Rihd;t`2k@5jG*&caJD|& zbGOh{0^A2)=I4#^yS*@!NX!EPR<F+1VD^kpmdXPHs|)~Y1;=IZB;XYdmo1P>7Ra4q zdHqpghpN+{`|z64r?82zXCu%ALDpjcC>En1(@!)LaZjb_70H$#G>jMk9`g_~v4Vue zmC!MBe8eLjHZ%j<lZBn9W6sfW^CWbo0P#uerl)*d?^tT4y2{UPStN*C3jntWyJh6G zB4*CpT37%Po+b!EeM<nCaM-ux2cED!0{K&X*atY!$-{I2NEQs>192ljZV?G5Lxhbm zk$><Qco}c;0_q(xuNMydZ9(NpaDVAIks$37-hYi_r~MmO|Dw<`INyU!StDU(I);+} z(a(1ekf0BV_~QVu2xsHSOzt*Xz}g2`+C%vm5<J8BR2mQWT<iiFM!aglJQZN>0jOyj z=Cv3zNy5#0Vr6=j82}ij;Y7^L(9!c?easSb&p#HXYCEn~4CmDbzEgEE_^oUv2b`ma zb`TRs3HWwE#_R@;^NyYtB&aCBvp&!O{Ml12FfPBu#tCn4gnPxu-De?wv|vUE2Sh!X zX#(~U3tP)V%}FpaMF=3ljN*6v5a4D>d9(Dxvn{w)K0?xh{m8>U4aLZS^Jiu^a2)gT z&o2Z_6#~4CMFhkklMDc;RvI~#1oM2iduY4_@$DpDUGB6vokfGy7en8dmO_Q7-@LQ3 zZ`_L5WpRy<@v=iU({McK`JY5&Ckwm%ch#@}S1Ca4$S8-9vCSUHe|T(bHfHyERF%N( zIAj-C!M*E>Qqd3OF+Qq^UKM;fb`g)Fv%H^Y%jWYUhveiw3oC!VlLuE{Oc_rGc$nW} zS(gU)TyS<pdUk?{gJ)C$!1)h?sy`B$7yx+5#CG!$pP1NQc>1Ub<}V&~gN~bO!B(nb ze{zs{0+e+mc3%?TSs283LSjwvt9V~nVd*^+g(t`1#|83Xw2<TUP)Ic_<2-bLfc{QG z3=k4~8gOPEm{$ZZtK_mtVr>TvJIchImQ7i{pf54YaWVLx%*>C1m>f+kuqMEiOOa(a zFGyz`f>M+&ze7~vQ3o7L0A^Uoh0;y41%BxXIhlC(^U!eCMZI!-I1jPH!$fYxT?<9k z5pjEdU9BbIETa=&v{e1@;#Pme%&@9jCA^-j%QB8Gbsc)LzR~wpoa{nl4D;nu($04( z{^TNWwV;ZLoEHu-b7y>vpul~!5==gau#vYVB<DYrxB1<SsD|4Ate5q+#tDffEvO$P zjL{qtHOiR;fKp#%JRJMg3Hwr#TgKyJVw&b?*j--8U;J&^^G#7sviUc(XLOoj(sfIP zjiwh+R~<4^?eO<_^3Qq-c6KDsWhHzO!WplisZ5w%F5YI%yv8U8RZ6T`VWBRPaD5wP zlzkL<Ck8r-&S&y2ov01Uz?Kow_2cIoeX*EvTpgb=C27hj_s-*;(GkVdQMb!xT1`N0 zU?HM@1F~HnIh~0F=&*2Fn8U|5<hO%hefZS#bA%lHv*Y+<=I9@EWScxNBDhg14F$v; z>kgT<C3nLd20YxJPr_{dQycsUC+5Nb@@_pr7S8kQRwW3{gV?X43+A4;jlb<_1(5ah zDh~_%z-V$H2|hHNP}PX<FvREa<O7ND4Uh1tpKbzt^eY~^mXCWv>zE{BGPPRTv$kzY z;hjB*|HDMSpxwQIN*^3Vh*@>J?lnGLOGfe_m%SQ^I=P+tLPRqORSTf{Oj}aQ<Y#i2 za8Q_`Se9XzPolwACuGkGz9K-sMF0c!xaN(x0e?<w3yQc7f8P(;#mn93jF(9|S|z!2 zq(=9geLuxG`(L=qPfdTtxJwmS{xQ2*iwGPwf6iZ_IP&<CBQo|8&QJ^Ww@+Rk%6|F~ zk2JvJx518!@1Pj<U<R^+7JU2;D&9}PJCBi}`FZ=>hg49q#zCkC#^ohu?4D2~Or~Sm zw<>9B+u54)3J1EH^qG47-KJQpL$Uya-8}-L-E(((E;Ec4h6H(VGVlQ;c&2X;0#x&y zh$&;q?h(c{wWDFp2eU%z2bXp5CYjqlHVEf2r(-XSw)ARP-kKv^@)pG~T)O`Xa7LE# zt1Z}k3Hl$eyCx~M<7J=HH^ey}s)30x>WBTNl`v!kQ&Mx~SetGv-jbyZ;7z&s9)&`5 zWO5C_!>z~!A1uL$1pR}L=pbS()mygw9+GJk?B*KYx|EOJ8<=HcSH%NMOx#}@`T-NC z)pK}?g&Cv&PjJ-7tXuKM@uY`2>bL)C-)?bHh^e(bhrfP`hn}bT0xaZCCfv^9qFhP# zV>`STQ5(vDB<_ciEqh@4rxtt!fB+2;aJQocJSTL~&W<|%HQIuprw;Y<eFNN=3t!9j z5s~r?hj5>~(WNP<Iwgk)JkDYqRYONHHpt!!%q7+p&lH(SD=0$6HeOAPFWe81(6J=n z5+=5bgq)P3hf9tg%f)A!;Bg7yU#VbY(hvdJAMN+war(&;Vo8G|?xFw%NVBrGqiSim z91DD^-K9Au=Iug*gs{)%g>X!YtP-H;Fx1QQC{g*=VjAubOV)Y9xuuK)GBb=6(a1!$ zlTc+caS<JDdCY(P58Tx~S#o|?LayVP$KmBXbTp7$!b2C=L1XDrkeB#WOMG_lfi%+1 zRf|*mbLvl_Q07Q4!<>HmhZytwn5SKsEvv;~Mq)V;Cy_R6U)y<pj){%4M|QO!?z6a$ zw&5<G#M)x8l|(G&)A>=aLBl3&^4#$fF{+Y<>?7G{$axmUrnX+k#|7`YA%Ojm!uc$0 zJ#hzkt4!N-(&`gl{kkJSoZQBP#)$t*5e!pI@sD}vAu%EXp1o-udIaCz{Nd%1(hlpf z7h7+)SH+YAv8ZAJ;s<X$Ie9Ge^J8$~z(gXhM859ftMj4TvD%lhWvsi6k{g$JXILXo z*G@WFH#kA6@SJ3L9ev`-s{aH}K8_igY%+|Sl5^lW8uA=1X%HWty!(~OMABJ;bw)EC z>C=QOlOPu*Xga2<R#Ggc<yt>RpeJ85dvSNxh{!tr?QtUVuiy<L72{vgGJ8B~j*n_# z;@(weRzAS5O8qQ0>?wcc(YVLH*)n2>o6QFRx@?4a>(hd(l1~tLp$kJq_IL*ZMCHLK zI1X$tkbl@z^49{thk$=Qj>y}eYrN}3q9yj00Qm=qfevFRD9rgl?6qrig+51XSy*vP zZUzRpglMWhfxQdd(hO@vurJj~k)QC`zr>C6EaaYx7p|cr&T0Cz=u9MSgwM6e+Z#3i zJMWq-g>E{8ABBZMZNR@Q@U|>RDnL#r!4gO}?ItE}_oE~F(X5gh?8^_3IK(&s`&uFZ zZ^d;Gk-IXmHw4IL{*6Bb+4ql*xyM4iTq>Jx#*3WM#C@|@u9PE%IH&ViBW>)?YfoN? zAKYQR>Qj=OOL^xsgDa(Bngp;V3BR*Ke*Ad}><s?6G5&PXrtXW5_B^><N${E%9BYM- z@R7Nx@GKNEyy}pMh-+xcH(B4}<)64J{(g&yessBGvSr^m4R=Ai2`S5b<i@xU;{Ojt zXCBD(|Htv!>AsISH}}n)&2rB%XRcV1+*gsSLe3pF_mPAoL`H~`RO-v-jv67A${aaT zNs>zKx8L9UZ`<ef-d^wL^YNI#cp@jGZ>Bf>6XrMl!Sk6h(P6%%w$Gc<CG<M^{P&%u zv>hgKM0jGzH9GsWlOuO@Hq-_Qij0T&SVL?)!0x4xn@D~jYxhH|K(;zhzfgkWe*$~L zH;=t0>@nvAKJrdkpD5K4CjNKNB>%fux-fUDT~$#yfL;IP)6<$7WRr^dzfHi`gJs^* zr4#P#H(iScY?Sd24~NNnLXO9|&wKc6(S)D)dc-Vs0uo>Y)_{xq!fBv^+(HpmK!wIM zFxxP7Qe*Aeyv|#5mmYwzEKUH>dTQ?xm+-3&*&}i5=AJ;4c7-P~Cb0RYQEhLFGt=!S zl;IUi_s{Ife17X#EQe`u<0<#1@LqWmzttXiTuQIjD!$3#-S3|--sA6vPu0nz=QsU( zW8Xa`%ldr@cy#{r`{8STUjv_Jyt^Cv^N!$seA7oRCaj(hU==WXP$sJ`2tdU`=MrMn zqj)5RU|I#7s$y@>Z-?%hbyt=9sgL!FZufeHo1FQ<E-uS4ahJ2X28jPML3%EOj*s6A z$6QU;#N3L#qBIA#mN#w3cXvF76}{9;`bYnLR92zG;=i@28;&;u|EBGK{#pD4w&Y)z z8nydS#soE~cq9PudQf?w7dQkeHSI$->7ux08gj+l0RU=%jzPFWIO(;6f-`M8vO2O( zIzquCIj2J=VTg50A=tRPNiwr?Q<oM~*-8-yJkL|Bc|et+h&5G&=yfLj&Qq0aYkS;= z0CaVa-Ux7Ksdt?px>;_%yT~wf(S5Lb*F}Gmw@?bR7feI|ZUsZL%>i7YHe6f_p(VZh zQH6pQ;^O%biyUTCWqL)m!?kG4bfheRACk>hz&k{{b1paXn#KH(4Lmhs>nw+nn2+Oj zwP~GY&uECN1um^J&pcahoSzxw1ss3r1iSVHT|I%g(AK`|a_ZvReZSLLs$+<g>}eIr z0KIB8F~Y8fO2O#+0B!g2g>9w5UV2mmSqbXQ-~*K68YTJ2PLo$sbER`-$}SAr-H3tu zL$lKW^-XmyyO$ocz8h+AlyW`bEC|nC(BTzJ+z)Ou>l-V(h43P5!ko_6I*%#@>wR0h zp_w2cgfFpznuV3EJX%K>1A;(T{gY3O6qxUHDf3zFlzu|$@oRD4dyovZ=JC~v4zEhE zP9Q6sZ+#sho8}-#X|`McmS0ET%KOY#Y4IAeuTC3b)dT_fef7q?{*2pS&gyE7S-wr$ zQkMtJb7hx#8bkU0024B1=brrhc**6`jACe=V{!CFq%~mrW&wMd#8+wz=#m6jd^ziU zFNeUL&y%)$!d~R0#xzAH&erdDx$F%yen23!B~pRIxtNS;X&Wagoas|o*IgbNUkyS^ z6!X<O?VoU5&bvmxbtBW<X87oZfoF5=Pg`1^rhQ@=u5*+p3A&Pg91LX%8t_d?z<Rmj zvM%5=8k~MqWBs8n#evCH8B5}VDVQltt6vQu@k|@*u{zULS425&B+Cnf`3XY>x^py& zHm<vb#qSz)W>6lJKU9*0a%7)Pcnz~kG~mDF)1uquOtGpr$P0=p44ru#$RCbo^oI+H z)YHf+crLy`z*0JS0|*Cj0RRG|gm~xE*@yK|@Vf@V%eRTo8}X$Uv_U>oEj#6GKwge9 zR(8A;Y_ya>R^-ot`qeuk3?TyCyN#y=`@wTzQWdFkP(sz%u%)#`#j-Kv;-Bncz2Dun zLVE3pekS<nOmFXf4I#iu4%BA<TgjJx4_)J-Fg26c&D*I2iJm^NhT!+A>eNBO%_Ns> zK~GCtbhoDGkhDCsTp%NvfSdw2MQ?Re;X?pmIMQBsYq01dmm}gg^Ns4$^~xBgvh?7? zQ(qS8CTTk$$u2e?rkDeh%5G3PE}G<m`DY+_tS3ISaxn}u_wf18LRHjdYpAYuP61;n zScv+JuDEP%)H{~verd;6Ugsh#hg&tH8!({9T@Eju#EOGNpcV(rXK>*h>BOc{ltVBr znBPv!xH{Csr@YZs1tbrYT`+#wE97U4mH&fwggw|4Z{{Zj|7F@S+Lznzf383lr=LXo z4(CbMtoU9{XT94Qald7H{Ccpai<O}bZ&-Gt)I$%3!j3f+gQQx6{rMD-FUb}|FX|tt zaB~o$0<on~NdS5hwegJ#A3#E}9I?rOfnfN6Qs)Z*K;;%!cHB^e?o_%Org3_-FJ2ct znYYOfFy{tj)+<SEqZIaM26;mJrxb#@Vx#Q&-rS<jx3<`K{8-F;%^?MgUN0S0dE~*} zJ<r9@V|&`WSYv*8G8)Nk4}F5~o<GYJm3)Nco*{Yic~g}X?s<T9_7d`9<vvSauNvtO zV-$V1WyJg#1MBbgjdpgcI(B{Ybo-`c>wW-|)i`^_qpR`Cd6jdiAHzm1bRM3*+cf_l z8!{jB#~_bGt`hl9CCWxX?ND;`x^vw`#H0G$qizNoG#vq(1!tE4<PnYM3yT_C24WFD zK*2-_=$YiQ8#%R6y6@nlLF5&IWmK>35MWhvR?%BXa>i_RX%v-cbLDvVL<`uU?l_$t zER==<!u5Q#t~5@b2Kc?6IF%oxoMOXk%me}AQa}oVB6hZN2JIpDm%{-;tooj>uD{}k ztbrz+9mLH?fRtP#!I!WP@uAX(2lkrc-wHB(uu|#pv9r5#6|Q6{M@hR)f4!)pjCv(W z4$C5-E=kbcI=sxn?e2LWZffR&)_)s|cf5{gg!?{tqfZAG`q&KSJC1?eQ>l!qmrFrP z7**?pMqfg$hW(hFmNe)Dsg}!reO6>u`qvUjZ-Yx9WT;4djY?5kPUk(vBtBM@a0W|r z1SCv2z%+sn-RUXhT8K3RZ6>sid6s0NLKHrxoV#sX#6fo|OLYqubUjtpVH5cH01(F% zx`cbY-;qVu1y8=CTT{G#{C;jPC+M9prRw@aOa^I(pu^KhIl8FHR~0p)XC0F7FD#|f z-i0=)D>KgEW{3|$0LIS~_?;$0mA_Y!<pQRK;BzVtdA&|*Bi~vrM%HAOmMXsP?ACG> zteoq5bCLG!TZwl(p*&|=KWn(Ive;sAJE8<_^#=9Hvs8&MYoKrB(v+kD$XY=82+k(y z1fQ#Ln9N%yMI~P?3E**4x;l-dx7E!b#SE1$tRKC;*`0U7r%`+rFlyNM=kv`Hx&+{M z!Q+bw(TRZiy%e4Xb*f)~JLM7LaKlk~qrqUu`uKM1)0x-j?_9cA!@h~gD7Di?=J25g zGSa0lq9)V-2H7SztlE5=cZ7QJIm(?h2H>DFQNfXf4YR8S`e!ZR)4MrLhQw9$sJUxG zZeZ!P$H$eaR}l?<kA#P14w)p=gR<yH8f$WgOJw{GW&X^Q^8>Ag51)Vo+TMj)`<?8_ zS^|5cAO=XwfTNZVWreLaDlIf<M;kyS%w?A#NXCF_a1|_d1Dr6f3Sb&V1Q8#|aJQF% z)0nxjRj>%WT1Y80l}55$s0r85vA<0*j>=7fQ|0ms<X*$<ykPMj`j2U?*xg6Rl&#yd zB|5q&0URW7j>5MpLx^1gRGgvZ&9Ny_oEAta+)p9Zm2BjUdY7R_$IL)XPHj#Q>4YKD z8?PPi0nG@4;KnG0kBrP#h=B`~l-6AFL2&F66zc>f-Q|g^rzB+S;Wc_1L3BZ7SYs6C zfpC?a4b00L;`-fST!uTaiaw8($QyjrzC-c0Cf@;JAAh48^w`hFh+Y`0^9}-~a-17o z*4ATvZ2Z%lr4HkPuCut@*aHqmxsz|anKDBumZ3)0Q`#oP?V3c~7RVd|yuBhhwUwum zLw%%CqCH4n02s*z29P_V(q0fngSoi!J_!;`ETv~@z&iSPGkpxd9#HgpVDl#_=aGF` zrCK+E{7F^z{``!SB;0vIN%=3BDHX=nO(CJUM|L%P`B#AxW+eO=B|Ql0<e_a>O^F@= z`_f?8)Z95hw(G{@EAcW>W4SI%&@#>jcUPcc$LLHw<;NegCll<EP3lN}lyt4&j5S5~ zQma>Cfda$P=MdI`lO^uKK(lwU3dnx6+~7WPFcNxu2^MnjAfT)L<PLbcrkrpVmz+P= zH>pC9Eyzj%J6nUCX+(=seyez*ag}tYKi^RRSZ_l&V+<A>M0V>Ury>PP;bb@K+*zE= zc@{LG3u2+7Q@L|50|5CCm@Pq+ckHf-=@O4aLK912W*e&9*}ytvKF4tXJs&Fb_&?XE z+`q&LvL|oz*k~dO%ih6J@CQe*Rp3B0`Sbxf5IG)=gJyWZK8}%74j@}$?)uqapA<5_ zG?yt;pt(sWi@o?3hJI-L0$ww=Z2&PofSBS+k5Gvg@u1;uIYNq9%{a(}8;HX}XM&)f zct}JQEI9ji#0J<K-X08SFR6!d5y(k2o|z^}K{YH54UtWiy27lu28U)2fE78^$!s96 z3`ORQj<fbPn;M;m8{L<}-~e+7sU7OGLps8QoD!De1kd6(V3+z}Yb;o%2j#Cf@4}yH z#2O`yNlG0c2M&;NL3IJ#x=DZ+b7{{Y<}Y+UU*p(62C87r^$-_0cffaICk712kpv7J zV*_>wt||XFnna@@&Kr<Xb8$cr*`;1x*i#D94D;$ErPs^c@bU7a!8|-FQ<+Sde{RMA zNq9q5qn?tKotuEn$6Yp-Dag$jBZbGyz9be%#(I9(g9UR;Iy<D$dPsOZEE+YCh=#u` zXnmhf&!M)Sh^_Jlpq*_gX;EJ89LdT6G+Pdr)9<A{Jrg!3t0yn%o<iz9N<wLX|63&t z>=8LB%qbKCFHCVqa{^E#PmPL_J{wmQBvqIqZd4H=ObJFoJT{;;c;gRn*bz~fQ<YQ2 zf<SL}Zn!l^vH(<q6AY2W&<$7!yjVtCFj+P~2`_SKfkHc5O!`*OZa(l_T?P3rkTc-( zuU3%C{RK+*p~rBXl>U`WZocz)Xh0Cz$(kGzU)K!~3LSnz@tMCS(A7OwcT$-ABP>^+ zM!;%-Q69wa4b_S=R6QIRJVQCV0Cwquq|(g%CvrXG9d5P`9xxz-Z(%Kp)GOIYuQ9Oq z2Kic4`&m?#o(U}3+&K{m?R+@<S}xym0vySlk~md>{8o?1c@l+$xYv_Ixg9TQaQ@cA zm33gkw)w*Xyy=DH-~&o#Pky-pER6<nxddUhT?_rJU;88Av?AJQh~(1ea*RpT0%Yp| zKu2kyBTOOvC2-#(OOGy63eKr59OBKnW7!!AN6WAi#-Mf<{K&&MSK!pNQm`d1clhn( z=fuFc>|DEXat@r5NXiu^bmEs_jUM=AVcs)niU8(`N5_IvMj0M0kYNqGG(d_$dU>%5 zW^TgVxo4L1;O!_zCY*w=zj9KeIz;saz`gH<YLLEW!FDy&7*9IRg!t}|ya6QS(!HD| zQb5%B9~9Yh0}|6m3U?hJZi2j5W#+(hr==kaZ4_k1bum_F2I_k1nEY+72lsdG4lmaP zaYHkilw_U7w|OTUk=*gZ6poRDD*xdD4R3TJ*A+)PMT4C$g{FDT#4P{!q)*drjGQT~ zmB*qaqZsGMp!k91E&zW`>=@7?l&z!5cj}O06GXHRBA@FZ``43uXP`q(5La}tKNFIX z-HoC{l0K7*;CA!%Q2Yi-MBGt8*NuAu;_ppMIpMQ{q*naS3o6acs2WH?FYwy7-cp9( z`(V*%it+`%WPE<+&Plf@pW*!6GYb^_4p`#dR4L?ccopf=LdYwz$}}|DsdOf5VKLNg zB_vSj-VO!PL9*wz<Zxh9mq1P%ARG?lO{LIILF>13BbYGbsLs<g4~CI>Uk$~+l^ly> zajSBClrk(As23dix;pqhnj%plBqIjrWLiU(DCr)gUe(+$Ppo`;D9yCFe*5rb_!^!` z3bv*sQE%leP}u4$SakM>r#n`eOC&`n!!^yj$s2;Fp&z?~#=wX4MWc@urX_oalvpIu zrk)ZxMv7j5I7oM=S?6=K;v6lK-$t|}6?V==2FuE2P{|iFplynQH~Qb7t!m2<&I`um z-MlQ~BuDPAxq8c5^KH|E?T(FMAf*mn9Ah2stwtTT|HS@8@rFax1<#y=Q_^$Syf-}9 zpw~~V^G~XZW`kN*qOaAXaAlP<CwU&9@Y!VOmE_5dWo75y{xT8<hv<%x7Oz;#&5(|w zb3?0OJI>IA2!S}^+}oXyNE#*6ZRj#8aD@2CvuYC=d!{CeuW}<dgL^e2gYO(SGz1OH zdJkqd_sO3rZG)?>-P)Ks`Q&(FA1r2!<XI1U0Lkz0wRK&J^fHU;r|M)bL5~GJQAx^= z-w<@Sfn*9t<jO@9n?(;fe0{RyrDxKXjwCK!B4<)z>jc=EIWz;{+*xLKsveTIBvqHG z8-Xi}3o@tY+dQw8>it4qr9saRfCICOdhxjl2QOU;a${UtZvjF8OEt50Fi&A(iU&*% zOKw={?j8GtEF#0c!p=X=y}_M7ER*Yv3P{8S>}kxnKmPEi=+1ro-7F6%ZY&_!G*rvw ztMY?_EC2_}3o|l@IH938EXlQA3V-iIU0GK-G5k=TK#Tp$B1Vts6H=AgNIrq5>;%9Q zaW!&mSL`ilb_N{k#Drw$ymjBZ*|!g^L*{1gtlw;h+G;G5EW?r7FdiT*u>jinEtgk@ zdM19sdxPSow^)5Q1Sy;Aho`hzD=Hr~Z0MtBD#LunNRt*?D7#(n8wDnneOd7k2Rwyy zhMV@0{0ACR>vKgVp#gA+KbmY>PfpqBtt*Xn%#r%iMoAn2dn`dR`{I$$$><63jA#~X zLa#YF;bAzRn`&;SFUfU*5?>1SEaJG8D2efNkxWn^jv^O~|JBEl5ySk1p_#NbXCcF5 z2iJ~AU-J!98Mtso)c_Y2M2ZpqsK)Yw*!>`#<Etjusj(^eDiHhB0W72ooJysn)L*xv zk}C=+p*wdSPW8WZ@3FjmHDM{*cK{N%@ZW>`vk!YkdTFqXcu10`&e=PBr?aaZONl2m zp#G9`BU83X)5>3eyuXEGUC*9N`%s{0Mv7aAQ%U7hExVF+0Jh!{%oXSJ`4m82|9vYc zWdOzKkS9xs<Z`Ce&O1ul2J$Q*H)DfX6r|iTE`9}%F_-7Kc*-(7j@au9*7sSqnL6SJ zNMTE`c+?R9zWourYH<+kg@So*3||_^J@MHM5G9x{2XO_!s89gzWjsD2>Yl!ZbIIus zdu5+11v3ix7G6T}DP*N1yPfN4$0HMOra}DT1snk%*q?{5Cu~5I3L*G-bEl`*GqQ6d z@ZB#<VS+$d*Zb?D&Bk6-jS$1P*vXf#dxICp`7)WuGsoar5hUvUjWt?2fC+Y@Q9e=% z{;ZH5nVu=Mv~ZEK*4n<<>v5(2fO3Wj4(zh%fN@^}atZ51?I7tSUMa(~8#{_aR8e)W z_NZ@4BZUGm-kytJ-#^N#3w$kW(lXx~$r$*d-O?%dUjXgkiZTp&6@_ni2v@pN^xh?E zr9V{}9Y=d`=GFeNmqUrHPu$8z(W6=Z>&79D1`78_zRtF00>+$Hex9pT3f!hUVJUGR zEGwIgzhSpfGU&A0t#8Va-ZvSUboak}E$;H!Yz9R;#OP;<Sbf&^!mmHCz8QX;+y^9m z+5Tm;!EAKAIDhu}X+8HpC<AZPd@*(JCk}IOnxB<vdfxgdI-_z7VU@hzc;e>8jwqXE zyF1s#Zbb*ortKvc$=C~BH#xUb5p$TvYcQBG)AZwI3r_rD<~r%dr_sDuW>ND47CpIo zmAB8YkCdC@&)o{)()0Di{2M6Gv-;P5Q<^Bxh4RP}aYieWCH$kNtt-#ZzOZU41q!H> ze;AdR|Ei$9Fuyh+cFcTn8!LucN;VM$*uAED7*CmamH03>2s}F9E0m|wO&r9E>`av$ z3-K+0u9DO1xYT0fg*|0n+1*8AQNW{}&>|DI$@?m1*?zDRzttZ%jUr4D^W}@+zXN7V zc7K~d*64lf@6Naila$xQs#9o<2C__=MsD>xMse6x9D(=fOvSxoOocn9Q2n1cNYEfi zD|Ob>P7xeoyy|+>$?BcQkqOg;aM<&*ZUvsQ@>kjSgw&xA*CcJcoWCEl%nwj{ZdDXy z>u&stv{lrOcHndoY0lqYkq)Co-K=tXaO!rODc9W5|FRi*2Ibw~)rr)$$9j)HJ9Dy^ z#T}eRUsJ`)7bgL=*!h^b!Xy>6Gf%o(A{b#TXdE63%G0bLusv3Dr&u$_ZsJ7J^O&ZE zd;0f7f7w4Tjp*=l(!Dtgia1hNTwUtNuHn8ch>^eiQOc?ttg)WG=q~;o^QvF5$m(Nl zL0o<Iqf5p!PTGG<t$8r9LN~XX8hG>vh3y2<t2Bm_-j5~w8@A%I_G_5A9YUTm0N^M` z%Qkp+%p$`a-BAI}a1{&~KG+p9Ol-I1w@Tb+2n9MT4b`G<wtK(m+_1wL>8H0{F20UA zJ@nm@xTsWZwGq>6ywOnbT#vX-nr+ao9xCU<{3N{;q81Y~R4#@PQnk$tJ`g5VIpBav zP93y**5n>As2?jXMh=^*-ngldCHM_gtp103cTB%D0LY`gice}<7$v^EYZU!v_0`Je zuwkA>?r}kdAoCJN9`o|?h|YDkpbZ+s{`)7(bMs#U$4?NdP{SP3xSLRrnX)VyS3P5i z+HcH|jyU!bEvy;SP?WR~DqW3)S@6TMb8MO}01gxYK{-580RkC(Hm9djY!p%h6v2ww z0PzJbf%t4J=~dUUtr^8uo_B8Y{YxaP#Um}8T72XWG?{7sKpLhAw*B)5A$gBxPXx3n zU;ahGn0q46ZG=j-><p>t4Dto8E=$A~2Iz$h7T~++;xwk6S{;|1%N5QBL<43~e*a3L z9Y}sJh@?GfAUSGA(qU5}fZsNSCl{5)Y=v#PCk6yVG*pk~J}Xe$;8NxL)r{!hu?wCr zD~?sYmA6lGP|*?-Wly?B<a_n35xEnGb$9PxbtYa7-EYYAI}DYtkfvDL4f46UhKNok ze^lXR@usaRBi8Yw82-ygHGU9fvbG%t3h&AjZB{j!fz~<>WkNq{mC=P~aju*-^Ji4F zup-rlyS}R=F+S1Ed6Q)pB2vIf;`xaa0;oO1&d*7oq^pBQE%q-y%lmz|QPNE&;!xzi z<p!|O*VgTpWSHQkAS0E7nOnwpdleoujb2+|DGI@)MV7yTWUj_TFu#F-%xy-!tTb4k zX`?()MBw(w2Fl4z^RbF<Dxgj|>nVUutAC8@JGgH2E?pE+3t=GYxIM+ywdPL+_OwT2 z_z~f2CHQ_eL5@A(V78r*AHEanKZAChAL~}od?x^S?EJ#iaInNWfBXjjiRTB6o|i!; zE2^eE?#Di)3Tq0CD_F2#2K3iHeb%lD1=&O9D$zv=18oY#1&7m?4nrl<(_&{lX(1^3 z5a1U`;+pK6b?}wy#&^5zPyc?7oQWxM%v_e-r}<c@ab2x3?tJ)oYwqcR$U+kHro(bN z_3ns4(<x5E?-0%x;J;Ct*u;@HS2?5eE;a=T-?UKXdv>r5DmX=bfV7k^I$nZ@lO;)c zV&iR?#aG;C4~Y*#=Q?t%V2co=KBY$zW6@o#JZ}I);U5#MHP4c&eBTi&TU;Hu?k_|f zOIBn%I*DBj<!lERNESbjbKm)Gz#F*3@EsFb_gpwB7@@O#Zf$|W`^rE!=3%KZH1_k! z;A=)5mf(T>%~2D}X){f=g8|++ROP*N;o^V@L)+UOY87RIm!g*COn$|$2-CfGJz~*4 zj}|T%CFD!ot}N5{#T~W47yn{XELV-W4Hjp3Ooxbams3P*RIgc{9|GR)zF&*2)v1p+ zH<TPc#OZdJ&s(o~J*$h0-^{&GlWd-FzSiT#Y3uY4urCGXoC^fAvyiqd`_NKH%_!Fx zR{q1~PYm%^Co5X6;A)Xa5SRy^K}{%0(E;-99yp@jmv8J%^UFL$cV;QSJM9!{a!kOO zEoCR`6Q2KX^X13Dc;X=!pyBV$-p&-T7BR`PWK%0bVP#b2g~6wjk*{Qa?C^P8v+_^1 z<6EXLbKf}_EV4?QK?Y&Dg}5FRIQsx4w&p)M3#3IpUo1k@dW_a8NsA1{%MP%(9We*2 zyv#8Fmm%^$BcAJiznfNUcx#n$`-GBu@p<$`WM`||KFdiqwi2<0bTAA`;0fSYj$bSF zs!<nh4uVPOi!_L+u*-_<sX#e4%`xmm%xU|Jw<?P2MY0ra6MZWWRew?;TKT_(1RmBd z`qi1ee=t^Gl0Kxc{aj85$Knm{kyuTXc~*gzyj+iE$fp0&GmYymz;jx#U9^#FY`Ul5 zdYqin#uC^fO1v!cAwlZX4!IW7FiYQ=TbEIP><~4=^SicoobSY?w?f}L&dEo}*KNcQ z5>H;#UVn1HPLkREN=bkDmk6&yjT)MB6>M>W0C#qHUjXHTk^|6EhupcYL0koHRG>s% zmE$0#;#->cP#X<7d^KgEv?JS59`WZ&q`pCMR*(H$E!)*<6&Sq8*Sw%Ge&6d$Y{B*Z z60O&uTV2FZJbu>=3GuCms38DB^^c?xu-`9kxH{lUf%22@tOg)j@pSbiI)_NEQw7vj zA;zMxsue&rIjo)?!F-x=Z4ql$d!kH!NXQmERZsXYeae<&RKj6J_t^}KN!#If*vXxM z(>b|8r3C7pUr5wkh{{rMZLO^|$NIzl>JaoS_~p*^;K}p#GD=0$>ByV$bmRgy6#jDY z+pOg*XyMnD=}nL}U?4xkPDrqNA(j953A>{fL^Wi=p}ZoX3#``%RJ{8prHf&_w{S;X zoFcLuxpY!TWm>X##wNZYq_&t~4F}uSn{iJ8-o03KtCnsI{<ru}=6T5DK1E6&L2VHm zvKM4V!fO2s!L(yTD?nN}=gHNI(|b#8gMs!vFr8ZZRbwS=#e`)kP``>HE@^jaFmLMz z{iMx1HkZSt?cqNQ3O4cAY=@uW-T}4nA9VMC8a+XLHMV^DY=W+bt<EA{y`Qcv&XAhA zZr!h>Qz?65y3wYy02)&fT1#&Ycd1?AS+ff>9hWffyPVW2ZR7=Z2_hKnFpEUM2gp%N zACSrbA=8+oJWf=$wzb$npd%Vjhp+Pe3UEucmGm!eN_APnJ7|4bDcJ_<q!2uw5-f2P zK?PL{9K{l4tCK=kcdgQ_BFMg@Tg8l7^t^>cH2Y$vY%Zv7MnSp%F<u8<E>C?n#f^L- z5n=;o+3zq6x5*tkcAh&#>@Xqse4r~3klIcZ6CE)i;7tSV0GJxC3$ic30;nCJRx;2q z1*kR2kl$s5@e8``DCviQOzlL~3mH<cS=#Ary50^+uiy3|U==42_As?MM#g!QL^9qc zTZP>UsajiY_d?Sg+}bNK+#q$~=e7&^m|9zo5XLII(0~3_$|1uTO;_ui>j+y;I&P;K zO}{_vs}c9?(;>rRm9EZFL6j1VY8m<AE<zyz%h%OMdoBYc9Z=AfcuzGgotK)cz~j%a zTQ}aSZ@-l(=p51WHf)=yFeDFXpOKu8=&J>4(TFu3+;eiWwkgC6ABJiz5Yxm++i-c; zzINI!ucj1cMWt^^fK~>ET_#j)`$|WfVHzO~w$cvai?&M%K%H$6pdI9P01>t13D^sG z(JI&5UVa@e{{o$Bg_}_?wN*=J0}W^rajf;Y&*~Mqxe}?<%ydsPS9~9dkuABTae>j= z$`hCfO*N()rMM{*rqGj)Q$d7N4%gS$#C;Em&UaPVgPK8U@Z(PcL--wn`Ntm6yiA`I z6Z+{I*^r@jtdJ;aC0^kY?wG7ZJ?Ev`sOaWWMNB<iom;#NT6EdVvm&!CDgbJ2I)(8W z(JpMLq~|TUuBK;7Jt=cAn<c7KiQd<vg>o1{W%SyIs|l9i`LR5)k+;sO{#BB%G58e; zQM;ypn^ph@hyJazYKvLK#&kFH4ce!u4!s*7!#5Rj-WTGdqM>gX85|OLx`@;H7#o7t z;|OqnsSgitc+LR3^1%Uv^C^{j;y40<ZSmoN8KQb2-IzukJO!qxttZ9-Ib>ipQz<)s zCyWn6<!oNC_|TVT5F?GCvP3s&_O%PUjqUN)u?Ah`#o5*dSS=7$rWq(Q$-&Lxa$WG_ z=Q@#S+*R@##~$+I{@b%@E>^3agSojj0wB#=VbaI3tYn}r{8Y*>IS0GE6e?L$hj2s^ zG_qK9?R_BUsrJuaG|McoqA}Dx+?J}2MeSVCJW<=EX@@p;a2X(|rPCMP9PC)?Q}1;h z(t~i~AibxygmjlWoy&Nt!)cbRKDT^lIpf|Vf=N4eGW)E<L51kVrgLwT=)Ws5T&&!3 z;{8&#W3z^KUpok}sI5b-6&(qy3It<jLFzQo*cu&d)TY%ef9}+&zhQ4^3h?(|;u;Uf zH*rMmLc)h!-H7rNdQ@_r^ZIFIaC!<*dkJXVGjvLq7FFtK1^#5kpJ({Km9s#$swJp} zeSPCuY$XherPh*nK$@$zqMFs`we0#NxiNEk|LWDgzSp-S$xJ?%-x2ioYt^}xqQm+E z)1+ceYJssnVKrbF$WOv-0c(gSr~(EojN2KBRWYe_6P@Yc1uUi(sM(H>o1u|PhcVe? z^=1BTj9r8zbn%_<<h=a9=R2GejQ0H9@!cDo?}&QokiQwDG#&c8r#R5rR-MN7e!VPE z5vCV~bLs^$EM^(AY09W=M|2wh%?44^?8V>%V&IT1X7yHa=e)cc&?=iR+l=%;82sXp zp&Ld(p`7`jp#)wf*wz<>mnz+gr)zR!l~Q73!fCeFU;cg`bytvA@3Ph9_?P(IDQnFj zv7zemR#kJL*#VZ_Agux#KzzfR=G6K{12J6-dHY(UEP+oEF5?j=u{y{)@t1~Cgyz2t z-2H%ascrJ>cWr!vpq5iozp$u&x`78!#YbRCPQhwXV_qj|KATvfVq|<K(s+@s9YxSi zw$)vwTO}9W5y<De0&<~&_C-G>W#|WUYc>bi>e4{e*8*ZIQtx-zAT2wFy1vhKVUk%r zL;ACuZtNN)qFxVXJULw+8WgS;Z>zrm)EYSDD@+V|M_kGVn;HaT#TeSI1SM}<^K^nf z9_}<uN3Xi<b~@F$62afGkjUD$IfmjkHk<5{7)!*{R8NX_TI_VIM;v!J1T9W@?Znnh zbMNuLx_<Tg8;eD{t}E934c!<G;z%>32cc)}fa-D}i#K#szpYL>DI)~bw*bPqT+_UY z8gXJ^wuzcuHglHh)DEl~9%~hZH8^Bw^3$(PhPm-2Xm$wR-!gWnU5pRs{1#B3HIDwm zds-&3#^cpDI|Jt!jj;+ylQE~z<!KuJ9lLWy3!chmP0`@T?(_Z5=2sP>TLvXg6z%eO z@#YNERhQZx4{5cbPl$b<eH!Qfw{I~-|H9Pu0>5aZiG&MQhkIaX+n;3x{C5ZsV(QK= zQP;;7U+8$soZgf?_oVl7e3y&RJV*uCW&wg8J7bH3zm)rs829PIqvKGmg9|U7erX!t zH}iGY6Sq%Pp6Y35821201_p$g)~a0$mjjT#UAZViz&n2D=6Q#{#U9g=i|4L9uzssU ztR2A|<e<4%mbL?d?^n&zPTDKEEpu6$ahi6otoerk;C8yz<bB_J3wSYJ@4kzXLBt|a zy2|XGTV^S#j%WZCt32j(BJ<3}(~*7I^ViMUd5PKvrZ|QrCpI7CWv=7weHTC9=8~3T zt3Ln!kJ7=X1(1p`^xOw@@j6<U3^p)cP5Z#ZnLtv3coXqo>4>TEX;2;mz~2P4D&Ift z{;<I(Ri{VjZTLg`g9FSSHf_E8o$7@uJ`*Cz&V+>PJ-aD`7`oBh@+s~u27m1@**!cJ zC>4eEy$Y0MGOPlKpEk`Jc2eC>s%wXm@KyGDs|4NA5D)c7dVJ0w$abiD;2M8anfH)} z9<lSkm>Hj_BPe>6rkD8waL)9$v*UVQ%c$m_S>>JUk#-mk^xY!9g@8iaPh&zsFRg;| z$MWLtxY$WKx-=E;k^4$9cAQDiuDUWii1J88>~MTUiLKgg_ryd%Cu+*=sZT<;o+TdD zNjv(O&KHhjs3c?0#vN}qXILvvy~8msWHRr+Jb#V=8l)4IhTip{+MZta`tNZuOIKQA z9}9}HRT1}omQeFZ<}lL|Z~c#9ZcV?Rcl!>k%F5N&q_1u0El5ikXo1vvTDqTB;bnv- zsE#?!2Xv2}Ox5CgXhz7j0vu=Z_gtnQ#^lyGlqqWIFrXj%D-(+V%Fd^MV55rfUfE-) z6k-R<9W9sy_z?Cw=5I{K*DH5+qQ-dE`W#XCk-u`7`GRZn7n@}*p?}629{!iic?&ia z@@>L5E;f{-ymo@>-;AQ!f@X_YOCLHCTs#`Es`iue_1C30WN5Yp=BI#PPOCOc>Yq-o zza#07%2~lW{<tQ{0;Yd$){n|JT&Q9~!vsZGEdo>41#K&^DnCG@m&{9^CS@&UwEcYQ zpb^x2Kr{*iJ`+29ri|H^{V>%VfYZSussjHkW!j2INfGN_SUo=ZnXc#qYF2@oE`naa zxMp*ZPxm3HW`nJ>m5-Dn%>ZC76`#J+U@S%GXTw%Yafm%Y91$^_@-4)^WQ+cK<;N!C z=mqw_*WM4y!(FcGp9E$<Obm6qb|m5B?8D2E$8K2VK+kiFt&L~4pr`*xb$)crY9f6T z`z<C9i2l2uu**qQ*V&%^*%!U#D0phFjTfd?(c7t@Yw+Zslk&+*y?3oLpThlre)~c% z$(sA7eX&HWr(DhLxlezU!PL_dMaN3>>bt8|x^Dlj9f>J_a$edX?eNI<?2{yjw)Wx! zeMPg@ZezE5uk=ri#<Ov2%YH|c2QTev{b0SiANOq>^wXsAbN8J`#o1Q5C$IJgOpLse zeO6mtbLryO4}<GItr_Mn7e0B^%_Kkj?oe{LRruCVQ1R#7`ay@XDQ|^wmZaEL%Z(0x zdY;_*-_@$(<zs_)+8;j8pS&LtazgNCYkiU)7JSua4Yh5}-+g-rr!zeyhVbU^K7VMi zF6SOsme;`4;DyO%nX_5;*L(Vp!mekwE3Q?9`&V=-+O@sbrN8Gc|Jax=scCN=&y=S1 z-J7V%m%HT73fB}MzY)f8X|@SUFc!w$hfGGX(^E%Sg+_{3MNf{)RZtUDk4Vez(h%`z zR*U5X|ML1VJe;+raH)$cyEjkou4Aq11@M5Ln%_x*Du+n3m8w4G>-7m$vQo<peB!Sc zjeHkpJX{T|Tvio6EwrCEFiV&^{%X7v`}M}jT9&Fq)^8ql`Ss$CsO#RHWxR&(1^rtP zQMd$EPTg|wmT9r%uH)r^-)6BMl=_bR+N@R2RS_^3zN7vk-(mE9rvs-*{kZdK$3NuH z@QmKToBxWGKgq++jebQGafi3;2JMa_zI({HUG}T*9z_5O-F)S<62FCAPty2)72)Ha zV?U~Y;`oM9rg7`&gx1RaaXl^x70m`1tLR}%#+Hb-93b`0&$)Q&^Aa(D^P|XVLUo-t ztEHhh&3#1pPfKldK(&hGm4626*E3(wG`)MuZJ6wTEQ%{!x?oN-vN2YgcT)lno;%Sp z*QDuq{j7Mmoqu#trkTqP=oah>{vQ|fVLBPQx&9wBX@M1h7FnqKK0ltm)L9kiz4gN8 z)sJS(aj&%ba%Rr(Wp59~h@h;)@F!ntQ_RPZufA+jZiFXRldc42|5AT@M_)-{BmT>` zu&UQN{!>>=j<So?JCp28isQYL!YFrY_cLmhvb-i1jXLYi%q#r>eUVS7uk|-~r#^c= zO4_!)^WmSU>I-(rU-^%i=HPgn0;hh0lphPG{@dn85A~DW@`SX_Vnj*e4nqd_%}$4u zP@H^t^ECHw|5ydc12YSd*il2i)?~VJ^r12$U)bFWKoR_1!ACZ6dXBNA>R&rtGec~S zT74-q%NznqFsNXqe;(ZK{XnVv2gCaDHYI*3N+K=RV5LfGn_q=Wh;!(u#etNAL9u5R zVClnOX4S|<d~p$f(m2N5t2~oGROUWvNL?=>Z=k0D@zA>_`*5LTakEp7rvWzLQO2pa zDk*FQu|<N6mFnMemTic~;vO}#qcwlA@l5AntCR%ZORJ@qq|+7|^NIpKr@AHYZ;;K~ zxdh{>XHfLZK^DKib(|N!sn8!3rc=6`hxbtr`Tn?ArmT8W{QfsXU4v1~0KVc9O<Caz z+(B8*)6QoADA}?AK|PdqpHEm8$Q>Y?2iORO9`I7Q31JSubBt+);qf*$&n;_v1fO29 z^%pQ7qv>r5e~2eY{X<K-BR56%wjswaGr@+dEP-^)S^2}#347KWEua>7K_?$?a4^Uh zutXOtqe3uBrYL{u%hj=7A6<geF8?hv$lAVCW#JqmcxjO?R_H%!9wSnca%f8{RB7{I zXH6G@F`}xM5(2nas!N%6yK*(Oig&2jNB{to7Fp^TfLwKQnPXl!q>X6)&cQB!?xL8y zsj_Hi<vFA@O8!EZ_J}VaOHcKf7@R>`nRi!ay6r?hHFPu^nYKIDA5x&<$>XM|?O^1r zck9aiZHG5Q@Lk%FN`ToLi>Aw>``4c*1HUWaQu;3U@Tz&}UoNzoZtk=k5w4fflxv&+ zX4GoBra$&<UOQxv*Pj`Rn31`P^;P!B<gCSG$XYSgF~tcRwqi{OV0Z73;(t@;?kPXo zzBu?;SmZhhUKa#2we~7b6fS!5+2Zp)!S`ks;A$%A(S(KgYJ+?JeZ@V`QI#Q2cKdL& z3N}b(L~|Cvmqug6qzOz|9!yg+Qev^>^Kh$N#X_gW5Z`~<r`Jto14Xhf+98)4)f0nD zetvPGSZK~$afr>=5*+m|d4sLk;`7<2O^C-x`(^01LJ4U|;URNKlf;#s|NFA~c=(v* zZ=3v%XdUdkyQAg-ES_V?DTYq?ICb#s2@#QkK&D$%j70g}Ybjv)+WNqltwznW^*6o8 z0JlqkKRe0wE7^Tvg639@<tO_>aJl8s%VLC$B4dx~f7_HYcG(R-1F*&a*#sd8>OWIo zHwW+Ug$E~=7ayOUv_A9gR9AUkd^W%N@e{#(h+tX>bt@<1R41j0QBlKA?||Rig6ljA z_EhioH`D=**bS`;%S!jibfdt|=KZIHvufU`+!|kVZ!~uZc5REPbhX;zpgOxA)m?18 z{#jf}02{k|0aIMss+J=-`vrw!*9Yiqlvzh_6X&FLCCp}QcztLo!?)tNryb1r-D{Uk ze+G@ZooSZO^Sic;8lIG5vv@*iXmfF%XtObAjVB+IZg__XOvXDDpD!hdck$iD8n5b~ z9Z(XZGp`f1jY`)N2}{gYC-YaV`z|*cTRENf>8~wSC+3L4K+)ifhdKFvb`s|1GqaeD z?YS)R6=w`$RD)Uewnwx|X@6v|WHm8hf_776UHItT>hFmZyB}=xTIw*$G}g80>yu2K zoL;NvMjsGIc+J^pd-C#Lj6Du0zYlOYG1MIA-gJ;q??kl{#N{UxLQEEIiZLi!$c+_} z=>l_7&(c6!GWc;&`o)Y5)Cwyrnft<ryi+=}ih4)Nu<v-h>~y{)ltSCm;e}oPjta|t zoQ#6#OPYr7<4`T!cjedU!Q7s^Wre!s#X)y|TF!2Sl^-<$COrCB{9lt?C$V;;Zl=$f z&t*`Lh`+hH#hkzKl3z4yhamQ2VH$jbaWrMsI+07_(B_=!kQ!K}gBoG%47E_`j8;&( z*Z=8{4)dra1L4jk6Z7?u|Bh|4kUg|9CwowCtigMgrNGW_;OH4Tn4czX3&h&<5&Lc) z3nd75mR8$2Wy=+#WlfcS^7?M^W4$i!4=S_&8W89l_~hWB8c4;`<8N{}dB$FJe^AVP z6_Sd3N?@H_=J}0Nkv9z1UF4lgq3><v2=<Q2^_4uvOmVYHk8Z5Gb2DUo3QeDW9u_>t zyB3C=X!yCrCD@NlKsh{dFEBj}hwlLbc0VpU+pW6?!)v#$X98un8zL)NSoG&-?@@vl zo*F(XJg2$j(uEB*Y|9&kUnCBXb5Jr`4dTlhA&cY0d6ta3;)f7!cV3u;8VkYX`!WXp zg)7+tEd914h`B2Pk4y(yc1vf4s6A>Q8{o*3T}5p6guzLWUF!(B#Q~WG8_qaWFt!o% zkJlIeX2f*VnzWT_zLVJbLWboIKRIlcIl}Qmijqc?D@T%Shot|OsT-oU;&m0P=sY<< z-k%;4ADZe8auk@^Qj>%5e>R9NBsc^BEFF-tX+#imq$-=fFM{QB6{QjjM9Ga@o;hLz z>jnGW(RWu6!J_vf=qeQ-h5g+Xskijic);?W;5*B5Olv8<2>EQ50@8+?gamiiBf4@l zJ6RIQNhGvo(H+dV)wx6;Qg*$A&8K7D#7jRT9t%m-X@T-M62<lhr4S%qsW_cP`*(7N zl7|iOnwh<g0VQlbzcV4!Ls6a$c2uO5+m#Z-M+W7-y-=@b?1eN)<!~<#luM5r8eZG% zUfMuh$PuI}9w>k)`z(K|fS+Cta`gFWR1SANfOjcd;8ugeY_>w!*t<BjRr3<LeH(eh z29#T(g3-{9p`tY6Wl@NdA^Eb{)QZaU2C89;KH7WE^1IuY23a*OnT0_(04Yz4BOC-H z4!N9ro=YtXxP%#*Sn7-6zC966iZbpJNz`)7Ogc(3Qj4Alai=RNu_QW!f1yaaGC2s_ z9lMQC`LOuy5xuziL3p7J$fZG)`bEfb&28kKIqP=Celx~!@E}?1F3R|>+U>&kMryK* z_vS1~u$|(LaDybph;1<lwHKDt;gt*+^aw0fq{R_OrWJ0nM&j&{`)5WYlFXm5KI;v= zEx(f>H-1`8UscZgp8r=>%pOAhd!olCOOG2Kqfff9eCFes)U>-tWyWGRat<pA6KW_a zTn-|A5PlFWF=U<AHR!nSg5qg3m2FUPo>?lt(?K<sJ76JXa%2UG7H?k$VY;1)P_qk{ z<$KQL$K}}bCr;@tbDZmvXd!-0Mm9%+LTi94=OJGOi!Q1vhPa4su@KpVZajqlBE%+) z8&Fe8xV+hl?FJdn1_@x|QC;D&B5dahwAdaLd%6}(&w+31;>Wopm>pZ0O)?xe0Q6%d zX-@wsMV#Gd<MGJn-Oi_<Uu?7%Roi>_&{5v<z7k(Z#_XL697N^8Axo0;IK&<|h@TUy z?m<7EL~L;d#j!$Uu51$|0HO^~wN`B8$cO+gvH0&sDNM}K+|&vB-`@>n-(WILeJ#oe zaI?hpPlL!tgZt?Hw}I!eyDQ?<VEwm0eBYZ08W<Z*J{R+dv765y*ea6>D>SSs)LGV) zG;FZ#ol<KGmH(KG_-LyrGbXjb1@Kjr3vN+pYtivtaqe4LndCRd^eSaWJbC|YPlhEa zcvHhL`OJgfFuwakGRiyuY~aRR5^aMamQ?t7SOR<pv0W^L07a&&)X_ePJKW!0jf)j) z#IR9ZlG_b71E^l4jV3_dJ6AvAk%`7c$iv>T6N=4m(epBYNv4)Ge(grYfMbfrgptli z#DHRuu!N`C#jtl{XILH{jB|;zq3|9)iZ#)7fgrx*o6rpo13SrVnd)*`pR1q1+~`!k zpe1&AUoqe2-M?VTt}BQwMW6TxEryte^|<`o@#99T#NUu4vj-~KIo*9fC8#XPr&4`! ziXxM@Gr$f>Z|*&I{Rtf9-|4!oV9vTmtH4iwJ!8vFQPOeBBuv9&!R$6fpyEaSk5V^G ze#K$Ma)TW;?&mCiRgjYm*`$BaSeah@hI)48bh&B|9t^i+N!|(;H)Tl$=7`~{NNlMB zsq6wVr5w@|fOG(tcsxrokn4<he)6lI$&6lK&3q}1O$h=8zZ7AXsJ)`1lyIc+`-E-j zgkrV<m&AUue2u7=WMqKjtU|7hm?cOhmf|R*0l&}`wZhdyi*zgr4a4m!If(nuvCfz` z5;^GnOvrIej-)V`#9ofV$6$qgm!u|D6iuimQ$s4SLSdt!NzX*|oMN#;uIkA|v2zRD zMir_)6Nmw>s>C6wNv=ZSY5YDA_N>87fFu{eW0l_wFIN=PQ<U!HYN;;>h+QrcLH`7P zSA-IHC2~YZ1`*EpZB&O$-na*R7b0pBinw0Lal|SCif1Zq<hBNlpr3@;_GUHbdz|b} z@OTgVbv5<}G(a9I7Nf78F-XSBe=K|b;Bmz6ElFwBFAe2JITBT$0tZLe+=pdGI@EXx z)4!>j1;IBtmIQZ2srTpy{p#vtDk`%kSFFFJO4vRjG?e(-h?v{Sf16C3oHD^F!qt`o zm452WL1is-Bv3i^I}8Om$J@noY6mQ7|Kb=1tGYZMk*g@#rdlTdYy)|@_Q^SezH?<O zw8lV|STdJ5j*DExatEmK2n?Tq6Mlm=FV-aH`Ki-9743gkG~M}%=kGmk3(Wbu8<|9a z{#|iE%qL~+AC-8c7NC5q!y!TMV$~6<{DmAby<qVauB)QlHP@R<*%xeOwg<obW3>KO zmDe*?3~D&*r;$$GQBA1%+Pkvs+i2L(foKeVh8`3@%YqLfB`rBe7fW(r(4mX#$ym<4 zmf!KkHsaPcQc8nj)`IDYQxyISp;vT$MYt;vjf-1^+xrbstVTCay%!!Gp&q%)sD;48 zK{&=ij5OFe>ZT~W;VkZ^T<IbPhY<Pv<>TArymloLgDs!j^?iA<Tl)*<si=WFFgh7_ z(r{3?>5D`z7r=G!ZdQX>sZFkxjkaa5$u3CM!{xy?C)TSinY?P8PS>M(2x{19rUyrV zFZ4=SmMac{<9_R_0l715q>x;a4kmSi0`lSl4_;uV6P@JPY9bh0ZC{HVv04_kTpWGE zSy9WQ-=ZUE@^OrCq-qzCF4|b)?wFFl7fCRw^R@5Ia=&<}C|1uEnMTj*wvp+&Bw?!< zWZsXwt1<+M2`L#Vi|BSh{giC8hu62q$)#suw?;J%#idY+9G4Z26_x+x*}&Vf@WTz; zq5cQjZtlS2+lp4(5ZU?7-+Rz8zPS8jZt62BEygyJqlb#Z0_}4w2NzbrKto#HrOJn} zndCD{;6k5ZWhvnyp)3A|$?jsPnu+wz(~}$09t%>7u$^T&op6<rb-Br^2;W(*jwU=d zIr7zQ*DqALy3)@GOB=8IDOoRaZf^xkJVzE54cf4)D%As4zD%<8!MWmwic;<OF4&&3 zo$UY|Z*Ls>@q+h_(O4zp-=6lL?(TO<^Hv>&eUdGEwM9RgndHWLE~HqyBA~-uS-9xu zKShOEa=dI)uWdC#G>2c?_HjxBL_XZ*%;ygW!E!PUk3Njd>K|!4YZq<G*jt6wTKp^A zr@YgAt~!yJT-eysp2R#wKHBw18fdSmcynB!S-kNO!OU?^`K9JcmN5*b|IpVCX+XUy zsr=F2*ubw9G@AB76Vo-=hzpjgX&a8MSq(q6YBP0eO4{h3&A{uyW!*l*F4^M;-m~ha zH{yCET+hw$yzkYK%yGitgSSOLD&}z1FOgz&cFv|%MWE}2C#P>^zzw;Y4Ih@t|MKm~ z{Ms2R>bmyde~hTgi_@tDJ<;C_<$w8?8sTbxS$|?)*ftaLhfmYF#Bf|zwPEoGQsxs4 z3aCN3t?;5J?<;E0BXBGUyI1|crhVhXJ%rdt9o7-`4I&s}`z9sL4J^QqdkK-F@Wn<? z4YNMItcB`8s3fumn-An?$JM`n)_%1vnxq8fk_3EZ*r|N_W8jX<{OLrxw~*w^oxkF4 zC;x>rbfP}+^=rvILPTX2jC8!qS9l0ey4;g_C|vgDRf!xR86bm6=Qd~@$`e=JFZi(; zh(5nL-|P)DY#J+5{__j_WAlU61+C8y)7d;mw<fENqka4Hj3S3>_LF}f@)*;Y4R!^R zMXzT*U>pFy$)Hlb>z?(0f472`zDl%Y&M?co(LX*uOcMC-{Wag{x&O{D?KfQF`}vvC zz52TW^W)elHNQ`A;DL<k_N$B)!*0gM>6?$*kX#%G8d~MQtZ`_E_f|>E$EjMb|50?G zVM)Gk1IKSR2ncR+;+`pPT#4Y$3}==jT;<Aem0B4Bid$S|W`${v(!!>d6{4n<6{eQW zKc<zH_0v+b>BIAe*B;<Kj_bP4&$kbwdD(V;ylwOGP1te6n^WD}*7b|$bsQ$igGG@e z$%H$1E`O-aG1;PZYkOJy-#YKFn%Dc7I$vKt8~xN3`&aYVmoHf)U@I_I^m~nbaE-a1 znP;>5I4bqgLTrBe|CC(*Jf8mi@{W7c?Ua3_XMgpFAGmLw`9UX7frKv)Wo}1Q*{zF| z*5wSsyf{^vJEJ4Qqx%>2F#0P7YtM3^;n`L0z(vR#8T#xK95(&O7NbAcW4p7`VKscV z#QE!JyqE3ua9>OCr_QRvrl>(2!}W;LSo(k5TG_Z(^Ppzb+@fuT@pFovy!(?su<&Yy zLpg!&7c3wmZ;SIz!Pe`G;Jcg5pRYYRkew2~W9ye&#=A}xyt$?maNf@r<^CCyyR!x^ zU-ydb<`2QR+~Hol@0NBw(a>pS*;dZDV_^_SmJc$GJGD3Zd8N^N;k~oIR-c}Xxc_+N zmwMv(mNOp??z{VA_l4W=yAy8flY^x``o*)d&c!k<yvuo$+DF$O6TQdo!xi>VH+`tj zS}*VTy8t0X_^;-*Q2$6KwA@Y0E<cJ3FPwbrbF~Y#J#>0asoePE^GiE={(ZAk?m76+ zpE=-jYf|yfzn0UbZY6QsR4!gmON_0at(_%u6*E`Do#vM(;1;NwPe~WXHuB`Gzg*q? zWdHwqE(N-;uC+dKbNF9;SeWg(dbHVk!s>-PH*ffy3iQyZ$bRCje?`&d-wDMB{2y-i zV;Aq#9ME-;9k6{|ci~Sf-ELi&aaTxiNxj(cWV#Mz_HWv#b`NRd)mGAN-@45P&7R-< z|94^TTeMT>{1-pV()n|>{{FCsxdA7GCdn84w+8+U0G2=3I<4o5(Jr_j#THh|yq~+B z-T@)&6>arz;se};i$PU(qZ^+!UkH2Zb>Dn1Cp6Ig=uf2zy9)&Nn8~F-Zv!k3|IcP@ z<25`j&}j}cvETBZ^zEqCDbKf?t^aj-#?QU2-f8#l{kE^U0b3C!VS9tl#Ba6lUFPh& zQ1i)lkAt{#Y2&f`Q~x?%Vh#4ox7N6qjrVMwWUF464sSdw#ubDX5fv&JwEG~d972jV zpBZD7G=K_x#Wr-;KZVlRe_Q#q)i$e)O5>PV+)$f-Oncrbr|uebj$kkw`f|&{=#qdg z^w61Ue7)`MMZUpmi4(d;+da+$b6At4RtLZ!Spx(%!^Gu@bR_zzO?Q-#ty0rhbl67e zw$l1pYag?;_yO{4bx8L4Lmhdi+=~n4b{X!mc(PdJZm?7pDq$h*_>jmdBt<*yW9UE^ z!a5yP9yAoEChe4WkLze|Ie13<p9pI8r?4_x(yjTNQDo$NRA_%Tb8C9qyHlH#>Q<&_ zbxxJM_~5OiQW{jjyW`wI{Wp%>B8*p{;=$1K5*(ALSn9l^ZQG`&)rq-p6($&y7;98} z2KJ2Rie%{KWFa;OnW}R-tH?^^cq#1cC8P6c9jDUl>kbR_QtT|SzEnr&CqMmlR~Nws z3mMgRLlmSn3o_EY{mukA%L#Sws7XOhX^uhiG1No9DALuc5awH*Tag%F&(f+yCVO4^ znn{cDv(n%neOYJpUtnD9_Lorwv-Eb;T6fR=)nzK(n(HK(>e|4)O+x_O+5}=^Fs*Vy zaz0_YraXAVS^4qaIQ2h5ZzD;~q?w9gh#(H?Ccm<U&$Uu(qZhv)16{6fuRoJ^1$W>i z9BumMiOG*;9?7>?{=`=$k7G$3=Qy6>w#m0@OSwMgT<++Hqy~q1dRo!_wyKB(u<G*k z7PlicrA&H#m;3gFWAzPcOTHOul_gD1PdcB5UCp_&;<q!P{@W$LwY2k|UFLzGTei4I zcgfgHsMRV+zSx((>;3#l+pbt#R`aY=V_Z8`<MWX$*-K|{64dm4P*qZdzWU1g|F2Hp zm=+N0H9tu_E&sI04_72;SvC0>IW(QT+<xRBwnj7czs>5oaq>n@t-QQ19wS|^CbS=y zz}!V=wp!;XIEzO;+4mcovw&HhwR7Bz^JhYhnv4cxK8}#=T1pQZOsKypfs<tjL$vSS zE|nf6wc$Q4)-G<pQgch?K;DM$Z3$ZEj!hjL=KYV@3a?5UK58U=rVRSucfHx^kyDm- z{HTODP2T9RXV0wK4XA>WZ%(@+WcI<0=0T;lQMmh~@yZOcf%@+fn4Rdj@2UQXuEe*V z_7QjW62e;V|C3f9JX}H5MXTE_Y_D`@)u0IMyAFRPL&p!VR7d0EbY#o3>z=xpBfS7o z{ck5PR-rt($e_{W-HreYyOxUHv}YP`m?id~2GAD8`ICyMZPzbe56HpjtKN)Pa2L<i zhUBsh|A4aR;FW3ARPQp2UW6Gr<Aspqtn`5NT6O=VR{>M3^l1@cd^aP}!ezHkXNXqj zbC7&(a;}M558B$<tNM_qzIsn_iT$GtIrF2b9?g}b&9?76w?GF?nRTZJa3_x)PI{|o ze*IW)^^t`V#8~D=i&ghsAFB)c7i}(2l}2RMlowql*f%*S+u3E5jm^as1j0kS1jAKw zJ0o6iz2!iE6!0dR5~udfp|_KmiA`OkDSf}06S&Lmb6R04vAN{M7<0Y7KjP1pJmS$C zoclGk4UIIn?%wBvIfhF@bdj6!mfbm=minq~b0^nxi;TYAZ@plUpxnXozIz5#mOpg< ze^<iaA34X?Y^pw}w|4^)u&Y7cLd4$$fRV>qipz)i)c;xBy{G3@aPz`Yx7jPkkgHKF za_bOV^-d$qRT_)V{R7s%B=B<8Qz#8+^VnY+|M1z2{_3l(%|>OArqu3%(x6vjo#YgM zw{z5*17OCxnY&dE2c9wdha}qlB%wl%&5<}ve=6_qNW|K}%;&{J0dsvmma^_>PVS(3 z%5872zSv~6(^0)0ZqF5r3FQ&}Af;X*)U^$S9hkt0#qy4}EVYq!Ty-d}T>!fyMV$g@ zW<hD!b}Pw9ksG{1C69f`5&2*!_M{$mL&rY6?uH*C)H2cSa!n-i32utA>o?#Z)GL2o zf<5Y;y5Sps=eXNvX4DZd5U3i%{h;PQg}Wg@iHUok$=pmP_N%dikpr%c$xwb5HydUd zmLac{g_22^KS`MR#aK-hkLgVL`)vVD`wacQ8F88Nt&VaR=oq^??=H_mwZ_8zxk`%z z@xf4_f+_cmWGk;=wK9pX)Ky&N@0Iej;%8J8L$L#nIR9~%k|12KKz?I~5}IoEff=}V z3Hg(;adT02>(i3Id{iS{cSy)}wwCW?WjP$>yalhvRv_cYYS9HH=m`L;t&d%y<9@MF z5A4gHd#Vjs%W(yY!vc&@gc=|g4qx4g<MAfelx(c+J`E~rw+CHkg@2|WR8(-hCq}Ib zwzV&*ROQMENm$EXg`(-CmBj$gwp6*^jfbzvZ_mk79FKj&LJ9fuv!uP`ffQtI$-^M` zb)#s7%a~3&x{r@GnJ#}yi35n)$A}o_>fVG*TpJ!OU$<eBB3DQ`(7BQ`nN*vXYizJw zcw-S|<Z;jdxgoGu{;df0xR=fDjr<E>JD75>h+coBmdR|ZlYD&Pj3HzunP+Hd;c)n= zHU2pX(a&dn_uflZ$o?ahk%jmYgLUpBgXl3a`Xmc|lSNE9vg;fY=zbavzq-9V)Uy2& zj>EuyrpsTO!M%`}4$-N9Yzp1?)gC^^qh(e0wmJF7ayu90;Ly6bB8z4Q_S>40yAM7W z8uy)O{wb3vpMk3*VG;+@%b}RNB2EhleWW)1QZc8Y9z9vlN?BFfOqSC*9ZDuwXLuM+ zfzTZ+^e?`jLHORyePuF9@sV^(Yf19(DDE|0%TC|RY#hUp+Wuq6D<d1Hx(dJ7Y%oyH zx=BJcFUrjmE#44RK3-9<HA!_ZDWzuU7GKo3AV44J#ZCBG!7_2LL?|iZm{M%Egc{pJ zM@{Lul($91fPq*1b<|@KPC`^Z`VQrHF&*E#_wih1uLyN>QTGXnucT`xl_WF^F{q`u z=_ktMS?hJYpIhDGUcQe}nVO+;Wr{uNscGv<VkL7@@d1E7wn+VYH1OLK+z<=ZnrXj$ zH1STxacD1JrX=<<uwts!HU))sBE~6uS9`{;I*@Lo)TI%j_IOF7AsqLCfu&|(=lOee z^-@sp-4o(W06e;l(K089cAUwr`mw7?ig6&MEIh~c^Y=Crktc~54hg-qi01u5|2&P7 z?XI-ZF=9P)rM2BnAlnB2+7q!mZFig);xP}FsGLY)+Fr_e;e?xD$<+~a1{v~JZxv7e zV6^O7*G;|==@26SM~eMPmAlb}`xlGbkWf-JgD-DEH8h-ZwkG^$VFzTn8B>E%Pyr`n z*I%N1hqU~Ss3l;Y8*bWsJ!99wqoy$}wDUm6q6v1vQDH;Vku7T}y^O@wZSp^W`bm0p zvjlxdfc{0=J4=*5DaFP3RAI%qC83<pJjyU9<KN6~K^fDshFm(UD2F~9(bA>l(zw{R zp{MugFB10UDymbcyMMsqzfTu#Ln7CO4Y8Nd9RRUZg!;z9@GhzbS$m8+mN<lKxt~RS z5^A0avJ6yh`oWC4cP3!3LXQ$hUdqJIpH+Ip#7arHQc{siq)n`<<|Hq3ahmHKwBAwm z0sBFUQSdUXv|%;m${k>0u28ThogP(cdGxGZ_dVsApLLk|^5^N^ihVgp&6I+d<%Ea> zJ8ipisl7_*&Ceow3*RcvaIVSFz;Afma{;tibnGJ%eZ31Uq{s=0=ZQa1brRXng}XyX zuduLI?3ln_OLIL1-do&BzE6Ll`q&lRi3qtepiD%p(B8*hkrs5fU(Pnm{<*(2sx<L- zsQjv+S*A5^i^cjL?@^q&IiA|{L4s)`*(eU-lm_Mc_?Yi_O<x!J1w^xKhv+*C^&~`o zT7omuFq4XK#~3kJD0?ml<mJ(}9q;UV1{8}WU_%mEpAOzgL^2%L`(OdB3mLYKN@r!s zlaimfWfppgIB<(Nz|HA=Nwl)2*`_KeI-s@53Mw*;)gF2C@f4m?bf$%cB2C~2iKt)1 z4$#kBr-78GLR_;D>vuX?J~ov=!=D7?T#egT!WG=FUCBv_o0T?(2Vpz;s4FbYSB-0* zclY=#<c>4t+oZOBVwsGY94o!iNtY{9#|b5f(nWYD-VpoXuGx~@MhTcKg>2$OK>hK3 zyG5|HUZH^!%0fwPx9QL|l~1wEJ%4Pa3RZ_#+RVNw6=mv-oVEW;!JS&geV4#q2ysKq z9*tj0&*->@_W~7a&^sHBKqU8Iit8CQRJnWjY5sbLSb{yqM~+f(<N7sWX~R-s!8p@! zijVT1MlLbXqa@sC1okOYaobV!Eh(~rA?rq={_6@lg@=d83Qa6z7zymS2rCxC*^3Y@ zyheViQ(kwMmy*u$nGyT(LUAzpjkQ&IlzdQ7$y<ePdecG88T`$Ry0#XBO{thwlIf!G z;Jl>&S=0U7<x1bfaY7-+dCuB?x8bc;G@pq1B#0K3_IxnAh3a|G-z{GW$O$Rf-~4Fx z*Id&Rm!+bDfvM<{{ivfd(V9ibG|T>r$3B$GWlLZ}Jo*+9*DZjxi{P06B7zAI6v1LB z$Z$N|n+~>Fg!l;I#SEwxV;z~Q+xLEKN_EZ3VtmWGz|t(Pq`Kt>%|lz}NXv>@CCa8h z@p75Ms@ni|+U(X@SA}uX#8Em9>0Q2@EAM-+uFnfY$#^!War*-u*GZDA7Q{Ufl&SA| zR-$!#XOMk|sOY;C^CKDinmJYpLznoVui$a*LR{D&a*2YD5+V1J;Ib6bVF1a%zYLEC zJ4&EVOh|a;)Q(EyV=tyS#~&?ZRGx2fHGg837#;a847b)|@D41yt;E%3qM-L%P=9Yy z_BXiRv)J=fWikh;W?EDH<>tA@>E{Pf-2$8};{)XNbnkop>;^Yo*ZB|~Eu*}TPD#Y9 zNGX7=aFe@3TE`6$HIrEIQ9kAu36()dFaV&Ej!Y3jOC?C`ZA1uO<V}P)NTA*%@b)c_ z%v4@Qf3f;|TE0W1@L5q?^n&nUPnn}EncHb`s0X(-Gv?(LE^p&4?D*wb$(BW5m)}=4 z|4`&wCD?DO%I~nv50BqEFpjyMEB8Qj^BMm_-IloBchSd4a<*G=Z$<y_!^<S?4*soX zK(23buH_r1jUjiHAveN8#^B+3vKpEQmV-yKnMnC6Bu^H-0!Ek>vcK)lDXHBxo45Lb z8J^$u|LAV*zdEWLRMOf@xW<&5-KHb;L4F5-YXIimBD#l!{zJ!1k>nqpd(!o2*5Tl~ zTwdFjd8r|^1$C2N>_6Z1;(iM1VL^+H9G{O_VPGW`S-l(ON8Y>m@X0fJv5<v2Pr|NH zWKY!p*UA|&xYvuw^HRCzLhi!{Xs;^tcVb>B9$v&p76Hg23Nnf>6GD-P`LF}Bc&h;J zAiZPA{4X5;wyJLaZ&j_GuHjz^^45fcAH2K%yos^3d$hG)0vMR^sF{&1s1b2z7Ei59 z(F;dEbv;VKxFt%(XZDWct}|ppJ9nh&*^Afs?jy55yyxx&;AUkaJ^p<^3pGc<EZ@EC zhsN&ANRc7X=g40sA7NLB@_j5+wFLc}^8Gh(_=E)gosMhc!?EYr;S~V#qdc;Lj)>tS zziJ~He1t4dCX+=27*J;>G@O3txBRPr@;|!9=id#W_J-&<6v<sE-}C1EmZC2OGv)Y2 ziQEYhZkmFbl0HZ58Gb5|zkWl$@d<th98kT5dn)BtbzI5Wft#gZ{z@3<1-KPDR;GAM zhzr{-J96%GKk()InaFP9%2VQ(?;`Bw|7L|EWIG>sPk@ri^KS*H-7!ykg@_myqJSm) zT-jdzwL(_yA|k(@L~NG@@kBFh%6}zN_|DnYy*fWKaEn#{cEZ_Oa~W!%8QH7jUXK?| zmxWh06EH(edHaG0jeb>^Q<n|z?i!RJ`e69E(e)D$I=}fwNb9E)H{tS814#<4Ds8?& zadvy(Xe#Pos}AXi|8Ta_0*O_3i#ayBz1$)Fm3@JjTp73TyvDT@;6~W&)1DZc073hB zq{GIEP0_Uxd-U($LlY>uivYN_9WS7<fS<8*hJh`V!dIl4AXv4UXUezGyy5f{ZhaZ= z#61zuzDD=wt$cm=^4WhoMTIb&QPec^_4Tahy_XzIciv(0eiwh<pR&QduokrYE6<N` z<EG^y721z;VduP(rqf<H%17BT)qB1?P)27t0rQl)&lRZG<WwAp{L1`Q%V5&buXo~v zvY1<mZ}V5jN`uc_NqxFDHS75?!YzODT+Yqy>w7iYH;;%NHNyX^HQ4cR{^83o<d_EK zz#r*7+USF@p37#QSS!VQG`wR1<8%$>BGSCVD&{Be#9_tbn{6?+lT4bt%QF4q5KvOC zmGy7K-MSpTS-Muvua6zX0<s5B_IvN()p@V!8aeDWD;qr%DO=#KC&aN>CHXNoy!9*l zbcau7-Pc8)$Q+&NPzcT*>KwUklR4j1%%+VrY|eh(LHw4kSFMpgKW=z5f8PS4AuuH` z{n%3ei{$2f-!3H}qe-FIb%$nb(aDte<85Y?ZzZ$iWPsde<_%Vspk1IKQL)~nuP2`* z_MIztP2XN&jZO{C2@8+R$q7S$Fk7lykNp#r;iWn?<D&$u-dmW;TpgIx%s+1$=(L4P z(&yR$EcjUQr;o)71rl9j$Je<KRzrbcMv+vhsm^QNV*`5Ubh582wIgx9@Jw`p00gVs z^~pNf^_%w#-qE0l@!i_Hn_Jqoqb;r9H3rO=7V$}|0F>p{R%?c%OwOMU-i%%vET?25 z#kU=yKlRbHSDkN<pn`5Kh8>CA_cO5(U8Z8Gxb6XM%Gs2VaUxUw`N*@>?JDz{1%Vsj z&4%AIQ9#_<bpx(mYecaYz_?lLlDN;dQ!|Hjul9^=)Z|&yJMDp@Q#C`TB?c#e&Rxgy zZSI}Xi6DVQF}o-F?=|J8Y)DjF&j)K4Yj~LsB%VyB#J)GByvnV=Q@R4-qTK-~#oYUb ziMSZDM5pmR#St{DQTp}Wy%F)@hjN}q;ufgaQyv-0Qel1_v>fsH6@_fpzA670J5$6} z;g=mvdn3;Gfvf0d$IhIJI~#;JLi_5()0AX>HdflU_R+hKefwc~pVhz&uOXnX(9-yd zxqn?phK<Lr`hd&NdB(D;x=(Y;s-Jh=j(M8q;B>JAfG-bhq{<l2yAJabSdT1{e4vD& zt!=DAafQY2xJT0)RfN}o0L)<$l<-OlxAaBkbY(`Pqu0b!!)03kgd^^m9&(3YS<<e* z*zSDry-WD^)WGZ0KI`6PYU<Kv{lp*q5i>L0>cjn~4}k9-v0GCpXA{uChL7c&wb{+7 z8DQn_OpW8-Hj202rEZuPaSif&arR&K9-fjanOa&`=Fw@@kEL)MQU*CTO<(nplu9@q zjF<Bdh}$~~DLkLq;A-dV!7dS~zmgzbrw0;DB4bM!Yku_NT3Yt8=k8BqX<LP}`>qc1 z%OjvHO;E4*u^FB{eY{Ek)3Bj_p||~~Lit>-Sh;%?mcA=nJ~^#g?T^W5#xl6QEXlxS zestK7QRvY8>Wqf-b(GyB547F%1$Bw!c=jh*R&_E?8)&^Nod>Zt&&O*_NWCrk=?JT~ zfgnD+eh64!?4%{c;s7~MLIS_YuC1`Pw39|qA3&10W}2p(Pnc}X52^s~+GW2yVroAl zt0%rExyp7dZN|@qqqvT}vI*>=j-%zQdxir@xbyq*GCFfs2O#=5)!r)!B5l#jE%o(? z%2YVY^dxYk!@m|UZuw>ruk%afX-w(GxqjT^>fUSQa&4f#O*3BOIsL9Hp$10P6r)oB z&o-jBM_;fci08{uCwN#pPK%J0z8p36B_0)Ep-N3W)%q9VA^U7BHzcOTYi+Knd^4ME zJI4Je%s5x`K2Xc;^VEfuHjQjghze#r&bzNsEeR~pwH)v^m{X{xiy$`Ad0x=k(xdfa zyz!Os<-0-pV0r0cJfTf8LY{83yg9$+P;Vd9@>@n}zI5);r42BHfA1<T1jlQ4C!OC^ z-;3RyJ&Y?La@FVgyu;r2*?)&<9)LozrNLWV9zewdOFY)U86053RfCTI&rDe_(JXQy z9(z!_HNAe9?H?bDxFy_}`rQVL;8KfiD&?{KK|{;ud(=iiKu#1`S?Ni!()Zqw2$BI| zb`jnfSgw||@t(%GNt4n1z@6r#OBzqQ;La)Iyo5=J>iJHD<4w@Dl(Qikk8<ylIz6f# z?uQVT{gN0fG=$}xG49WEn)Z!;M9KASSO&wB=x~&Gj>JY6O7?oZrkA*q)(4c@yG__% z4t^lqeW#;R8&+hqghKk{lB{<4I8P4Tw7pWM^MT@38%HC=fALrR!!K6(4XO^0cv~sU z57h>w?zo-6b>I_QUp~rB3Ej`pJ|@egA$g?<g#8A=4~q?=tgH9XXU~04f*VcxJ<S_B zjZSHlYQJS6+!CB_m4zmFtj@x``R~v`99La0he%?zC>T8$=I$!q&Ey?VlnZ?BZqrhF zm@&Ao+aSPQ?$DW2d8;(&_>j#g=oJpV>+YXvn9<XWG5;SlZKf>29&@>MD@Wbxi6+81 z!di~}9y+x<G-T^1T~vT%_S`Z6vq|{!AZVyg`^KB%gZu$R#2AgReqS<TLVCwzPlMv} zDd%(~pA)TUm=C$k2-QBKY^HlYHr8ZRhjOM^v7qpDrb3O|(BJIN1HJ>ReIqQ~cnPK2 zPP5*_EAZ@Pvz$4$((lI6;_rWtrgn0a+Ds7XkCs-mItP_5<h=PZKa*T^C%4?K4DL(@ zp}RjN9@jVhX2R5!FZ@U&v{IA<xtd$^K8<fkzX7%Bj|{gTX<*wvzNll_>ARAC9iMOy zYzPTOIx0t7WF$eAE((_$yrNexJsXQt$vW${o2}g59Uc4XMAZSztV$zlN9EHDxtIjp zLDtX3eo{Pt<`qP-kB)F^TJy|WV{a8YJ^E&vS$Vq}y!fDT-REC>NCv=!s53b*lZykD zvC5u0H|e7`f&uK7KDPE_;?Fu4k5ZUoahd=gAQR*GMAFNCH^KF#7dFkmZL9`~_I!{r z>DI(0$T_Li$UUg>H0Ll0F|23U(dwpXF>t%_2JAN?k_|tAHx)@+dVV89DMe~CU2k9F zUkiBNojko(<Slb~fKp^y3val1I#CME_pRC~*B&sBNG8IMu3g@k*{gaJUJdl8-7mLy zLPP;JEYp&E8nBo?>-1c1<ZrV>(mQ#bW&j-?8$m3|Z!8lCWV4(-Cdgf>Rwuth9Q!~- z6Z~cczJ>IHC$rgGz)pvFY_;+5PV>AaycMx-su1hT%@V4343=-Z-=Mt23n3RZ$2LTZ zPTzuHn8M;L0I>xRH~HC+HIGP~=j>=QWlZz(a(Ur|;sORryGE?zff)SkaiX#6iZ05b zix;w}7BlPa_M|v~S)4x#-$H@goGu=1<pl{~z-V!D;~h(14o!OfW`xMX_G<ih<I;>q zO@K`TJiBunX(n8YT%TSM#M=a%!E(F7^gQ&+XY@tq@FGuf2@yenb=>p}7;ET><V6ax zc@y~8)4XWZDfvs~lQybfkXEuHqDEWEeQA+xto1ml_z<gSdjx`!TU9P~iJL|&eID3z zvHb6LCEe637r?9wFN*UdFyHlgM68IL)`$Rut<ojD08x>{!NKTxFp11{p6<WVIcQ0^ zfDX1Q1woC4g;u!&PhtH7Q>Z1<ViL`Dpo90#^YC*%m(zy2A}icl@xUT9)C7V2jjr|Q z6%cNQJx7>ib-i(RIpe37O@wV}<P|h3zFIUr%;1K|JW3&Q8eol&@`5|L2T8oh>EV`4 zSP=K@Q3G6AqkMeYm0h{TWz%qgP_#o-v^l9bxedO%5fLNh>=^YvqU3NjQ_~ZC=~{lh zN6G!=(}S7Kau*lb?(^q*FrF8nEO#Wg@H9KHlYc2-^G7=m<+fvoiSVttMFq0@R5!Xd zMIo?}_u)5xcHIRw_36QFSqfnk8cspvkP(vLE?F(Am05X%d{RcnF~rcET&h(QHei&? zn?F-ZvrnH!M99WDyOD0Ei_=D-n?@09zt8T%BX;FNqv@`R0(cA^a`htQ*n@|!`fWPN zKAA&AD{`lMXXBb2|2%hu7V(Jg0f}M-f{zDkp1Jj@qFk}7B4V-V`m6H)mJx{0JdNzp zH#5*!GUC$28EFYBa1?exaC%J>nN5Vo5_ubEdIHh#odT~&&Eg!9y!y)`50i^ADH?lH z>Ou&uY>9rE#4?5f0VWZEM8A0s7S4blN-BO40C8bC0m$(i0-_7u{HocA=dX?*!F*Xf z9XgvG<WUji0dOqHFsAg<^n;+lB4^)b^kHP!Va9{VQD`8^aM#8100Yy*qeT_2!Pt+; zK;PP<FZ3=!<i7_gi?XN^V51p`l|v~C@kK0jhLzzfWw>B%6wgZQ{7<6hL65pe{iRvV zq6%ALiV5;bnoT~7>m%UBmfVR_;zjpyFJ#gV&C}iRleeZhH2VFk_XoY7ocmJ(@l70= z;P|{#<~sOtoEt6LKZh0`x}o)M{P4WY8K$cHBec$z{FhK;KEv~z<)<nXhfolVZnSpW z)Jr{BFdn`u#rMkw%WS0loke(@3H(sw*g<5m-<q0RoYF1pi{E^af{KZ>^{Li8a<Pxd z-snK_vxRF1r{ReVrwCsN>YMB!2RA*t9x+!<?zCFD_{`en(SuTfhb!KW2=x_>6#m`8 z%yRC1ZK8gW7qr6Te1Qjc!m}26Y=$F#wq^gU3VH&g>s%C(R9OlIj*^BCG0yME#pq39 zZ+5B%vy_tZj5gk{`hzjDknjp54KMxm?OveT2xB*;cYc0`?jT&>on(_PDGD?p?lCcs zm<PLN``_f3H6E|GE7?}s`|P3LEw*6CzWx`YU$|Z(*Mm}o>kkrQV_eLqVYHVii`;5^ z!~tK#>%2(qxENXTI+VC6Vq-<>b3`@^x-#?f2C3%|nJ4oHx2+Qp`nQf~jHzalHwAVY z7JXK<g0TXH!(L>FHJKBEthV!akI#nnCmCmS!lDU92kG9srNzS!5PKFw4w0kXh|n(j zYo=YO6`6}ZO{A<5DU3Fs>)Xy@`Io>f>JZmw{%S~9i=0A?a(eecgO~%12ZtkyBc(;L zNiV4(2u5Yp7L4q&+^VjN$x}j>jB)c#TvR`AOdZ7n$erOb!m?9Q+=CWx<mFEf#3>vP zZo`HW5V<960uq#amRG~Hcc?jAICLe76LLJEEC3J7V-zJ1`RyXW;P-hTZqZS61?v7q zaxMp9$u;GJtVSW&H;i(pM-wk0q})&+CU<C^+MryJFcLS@M+lSa;xkH$LV(}{5eV%} z#~fMne6+}`4%1+>vp`xDLWq-IEDoe03L1GKYx?=~2>;(PJ9|o6J|bfJ+VxK&MU9ma z3@+J}XM+dFKZVZI&mSVg{29jZGw@g`*-z*lB|${D;<k;-uFT>z-)$6?NzarE$bDDs zSY?j69G{;M62H*M1bVFuvdj*3=_@-2<9ZS<dG|rQDUcAs9GH{9x@)3f5HtA`Q9yw$ z-Gq51D7^kT7Z}CUmaho5EHT@Gn0t)~yaYGX<wX!-+W<}3*SByz(Zm~J{sNX^Vs?jg z<QcFN=<C(e0Cy^YH%;?m*7Y>I&KCJZ2p%U&Vg-mTN$+F$cXtVjC1;MZ=if&s-G@#- zyiK0Gl5#HV5rmV;c4zJG%2nnS5?dz9JOR!+ksFW%$!FbSZAvY#oqI`(JdA|Lh@e{= zWABctRP!VH@y~C_ntVw&&4LiID=G!}jXU~egk{mlV%Mp>xSNaJK@wP)!x5b^wDufi z7e)DY5BFUSXFswib{f&luk!JQN1ZF*SG(&_uBA)j!{G<T(68?!2vBJDr+rgfsGV|D zX}nKwA#oIfSg^5#a6JxABH1R6bjTbGatRu9IVPPR{CT=7;qbg)0J(S@P<(9-(Hhis z&9>xIPkFF*)93XWY#<SyEG?>Lz=E>HHDALdJJJfJ_kxIs{KebLbMhnJtuZq^uj7d6 z9Yu$b#bKL^MadG!2HZ9V=U^i*h~fIvgm8#>&at`Jxf9aJk=~A=AYX8@{&DmGwj;^m zrUZBX{BFOQMv??!O%C%K^Ld}1@eDP^#)oY<m7%T{c4=dz+Ev-5Xc;ak+SUi#D%rcE zYW_d@|4P3iOBQ$sm{f+e$ZlQ+7AKVSBa-{HQ(N@Xg3{79H04ORbKl?X{E7&lhi2!( zA46G*zFCA~cwQ3Bi;wVS!75WF%^Rf$=eg;RWbie7PvadQy!pi^ya<8pSztcEFY{Pr z=db^T=nFwt03c)6>j%1c+Nw0|J2zUuPF#x)%E{Qu)BSL={95PSfkoanrf>@h7Q^Ub zc3!@krLg}JVt*uJ$Nv&ef#J!0u+YVbAYsvNA~b&*krTm7U7A{bijFsihfeGLD(*^} zmNE42@8{^G(~rv@pSdiKEvrh<mL-db9==zcCMt@S7VnWDFjqp3%obS?uMRMxeG|=H z*EmMN9B;-ZW7j0rC<B#WmdS)}n!d#Po6UY~dkmFxJp%FSrEPqFQIrTqZ!Fp_fF-at zhb}@Z9_LoL!x98VF>0H(juxqcSldX+8c}=WeOAp8K(Ofa$e(wIlAsa5?D6%h=xrQ$ z+$eA7^g{dTtk#q8$0o$7N%9^hG*4!NC&4{lu&wws5z}8`8-(XKZc$Qp=q%Fv8;9h} z@wX~*X0Su>a2o+^Z~PM5{r6Lkwf1s!(J7VWMZ}I>3Ol@uw&fOWUE^*TIuN?Xohgqh z=u1B!f-l4b=&z?QzbjwREvi^SGg)x!JJ14(<<$%w=NB*#49Jzisscn(QZf8A&j%^k zCCRe)-16W3yLn6lr~$@Z$g!Na;lzQRqC(4n&SwbxUvRAOyzJuT>@hiT$>+dK^|3<B zf3m~3J1MaDdy-x&thpU1nE&66o(Ed5kC_Bm2Gl>+9(t_3M;8XHli%K9ygO9LT^zOE z2>lc-49PD+I94N=qp(ycFbvrroof?LZcd{dDlvmnRWPg)r4Mv<tD@V}Cbhe9tYUes z+uIw5aRMp}0GSMxpf4mheqFO2sXB3sXSDTnKv$;WgCmwZ#TBMmMh}}D_P!m<d!qgL z<fg-5Y|7pf?x90Zi$Xd=qx;$ePdP-JHGI4i(edkqzK{HgfSw&cPTVw*e|6>Pn@2k! z5@fg=Fcn@lyU&jRq&#j8I)|{DGR!|8^--yP>$5X?%YX<>x%Rw2Amv+MS1DpEjT$`( z$bsi7X@$nKb3wC)<HJuX7S?7Q{e#;N>w)SgO%FJHd2w~`?E0gg1IB4Bw~GEH{P^!x zTfxV6y{%QQQB&t)cBkwawNmRi^z?4S9@L}b_66ORUn1Wx_S{Q(u$lqRS$pnqXpoyR z@xxN3CBMIECV#m?`;5=8c8~z$Sdj}V(E<cdB?%k9^o}H;_XQyVhl7RV{s(|sZ}qll zC`G%H+)`@O#t0sBGg!KOyv+RK^yzY|i^%2*N@b{u**}9b%~c`RyTjZgGYplSqx>dt zz;%F$C6n@O<?R}Wykh)6T(7;CKgqcM(BV2BLNRRV*MI1AMRTIsvUa|;q6tV4duan} z<3ySbii;pdw+(PHvYj1uZ8YcxLXZK}!gN(t^mJu6aPk1g{0imUW9J{s(AG0Y<C?nK zEgwyHxvl?cMcJ*+^|fXK%M-I<9{{{T_FrTjN*3!}3AU4T&XyUkFfS=OE|)<39JZ&= z@=4zpGyNRCT~;j93vBa%oBT?stF-yG@YajNyz4iSfMt&tVPfW%igheN!3aX>4yZ^c zuWg{zQrIjmPu1Vkbm8{zZ!h=yp9CAf+Eh2)`pEgya{Sp)S-4nu)?40bf<L#Yk1@T( zR;t|hCMv6n)FiRp>i@PRWQ*f>iui%+WBLUC2w+i%Qy-nv$2k2rgogn5F={pG`MlC* zbzm%SB7xgEz{LhAzb)qE{n@ZW#VDv-^04bLMYw^m!Uk)s|FiD&o%p)wtIsc&{?!n< zq10qYRO`<QgE2qqQnK8i+8L0&9YP+H4_|A`pfxVoR7D1ZC0NHY2pwnHG<Ipr18lM^ z^3*M)esK_rXk7d*F0hsHV*bgnmfR+j4ca`WE=TDQnB~KvPgvd*KnjC+UIgpYs?Tmz zi0|D>J{8@+G@^eYxZ_UcvZ=mU+BfSLY`tI3bTuJyqPq<c8U#FDP}*#?VgY#=IYs;$ z?k1*Cx7to79ZR%bjykOk{31c_yV}iZid|+gtsA0{9FFEi0qjbGO~E2WTh?jX0G+}2 zey{L<<B7D=q*7HsQ7yc!ktvdO53PSmF=@5C#Y(3oX}3*Vm}@PlWX-g6OeAXMU+k>| z!m~!ovqeVYSnNR0++OvUBPO{XxTHoa!{zC_CM*XhKsi-o>AI&4YahmUK3?0`gtj4g zM&4^kUy(tELY5c^s2<%A86`Nu0=V$IRkris!6dV|8nPW*{ZQkGq23kweQhK@TXU}c zPpmHuEajI)Azs-9$+z_<n5`1-o*fOU(@WM<Tj}%O7Z`l*YhkNPE5R$5&@q(U7gvfK zf8xL$K%{(xs8tCb*iDAu@+A=M#A&hNA3VZtlSz){0RN;IC_w}*+GdFGYJVi>D_9_{ zrg@rkpP>4%5K^<weP!f$Gg*UmY*wc~iR&I!+ss_nSIwg#obCtVwq(ze-h`mYS8c1( zS$aBUv{RAVibq!}FKnP&gh%gqUluga$*vc{+!!^bBIN9*Q3}mWDk!E-$Kv))C(+98 z*4~?Lp>G_e>aI#3kS`lV=kz1>#Von}5)Yl$K2GYU72Mvpb{)<|ejVOo`I^3mI@2X> zp=;JCV1X7#dpkn%ZK=B4*JiOY4Kx3BtTsi$sr@hB(EN9}d%hH>{IYSxRTgu!GmY1{ z*(oN3_m-G*-(pi4(CBxQ0=uRJkIp6b=c>|Y^#O1^0~nmbLxF9i(@j%I6mkEj=@IHx zUEuTjh<ovpoMtcA$N&1^rd5R#jlxSh9ps`MhGJ#bB9*}N`ycIY4JO#4=3Iooi4otL z07xKKCqzY~Pt?(tld(9J6qx3D0aBkZfJ!M*N(}$D5#SEMkAIxl8FrCpk&VO`j<TI` z9-e+{tva7gViO*uzVQGrbgbtNSK2(#AAe8P>i)E_xj4J3pdwEDd%(T_aed`uDo$&E z&)w{JW1J7(HoNU!6VDd@;$-m{P4Q>rh_y4w{f=v#wwUhi08ogK6Xx=4<S;&o!c`Is z;5OvYvs^v}sXzwc(PU^+47-KY7rVa_pk$Ce$_lb)nhvKe<dvr-%&jPUtu7+0)-z+} z)xXW_boQ0m@n1Y|y9(9%Amy1~&8WJRJ81Yv<Y|N1Kb0uZSGvJioVz?kptmV1HA)cn z?_0`$hoO@iMHrgNceqP87)2vcv1<(CO@}!O&N^A!F5X%Fw<*0=b@CLzFLD(s+rE(? z)FtD{nZF7SKHBzO586jVT7Pvclz3%)wVwRA)M?V|JF?sTc&+S^bnOSBxA7K5?7&o+ z+OZ^LYUwT6`zE#FF>{pkz7P$}L6n4&5sub4I>l557Bj@U5eK)qV%RVm5saOal(_!} zr38M*5LJCm^hXJ{ce=Cv2l+5>MjJkb;^l5JP<$v!SJi!^{Q&yW`i13-oQuLFs5=pr z+GVhy40K*G3}dIZr|4<*2j07I_(X4367`C?Dail`r61j>uW^V1H%#%U-i_g?HwpK! zmO<rqz7m5w^<2gCOc+_Di>hCv66PtqO_vAIem~f1^K_(J9>_zWpgd))WddmGq07=e zRjcl!E#_MldXc4_*!0y)carw3(yxTAdYIK&jF2lA)11`fQtP8MReF6t8Hb%V$ViIQ zgm|NVy%3jWFjdMP!iV)Ky4Bsm9PKO9L$2S(DlNG)QF&(q;Ghg7g$tIm?*u6ei0H7< zx62nv95X(jYY`Be)cmu~C+HiT(%FJ;8^5Me5>)N6o)D)kd-DWNR;<qI?{q}&%q0KT z-RIY0tA&ZI!u~wb@FAl4#2oXstwWbV1M8Sh8*_M5pU1^ILZ5aU{;rb76UPWftm;p} zciZ>9Xl_dDj@S+ek#PDa?3YgBbfHEc$S7?<(5t<vEyiV(>Ov+eM1i!J9@kpxd3Hm` zo1v2oU$yB%F9WKYK)i`BCXxpAlc?VfcFLWVrseuiFG3v({Vj=9(i+X#_f+uE7BcCW zF~jRnuaZ%+qH#u)UE46ZdGNBzbQnlvYQP!o$H-Q49VKklW$}ZJ8o(ID$TiY7;kXgw zSz+3P_c@`y)*xk!$EV&wvqsP+DaWi6ysqX|NJwL|$58O}7>@Mh*D$Wy5PKwoy-`Hf zp+Ja#X-+*-UA@x*ZKD+|xveE!><O?V#_RP7C3mLSX-?vwTNDn=7=daoBxBZwz-cPS zX%>w~$k2;?w!Vbw*4A)jl4DT8rX_JC2RDCFsPst=)n$5ow3lv_id`s$W^G~>qQ@sU zu~9#0xAg690MI2BY9~OoV`mH{)J-h0$sd}##df{?S;zC-7fVBK&7<xDh{Yn9{Hi{) zdr$^wx`#%s&Zs-jf$bPR7fyJZv<#XKf!!8E@+@d>3~`eajZ+wAl*V@DgHHqvk}!~~ zb9D~BZJTmEm;;`iih*^tZnkElhfBX0w9GaXQ8xUEf~<lJD+V-112>0a0j94i)WEcJ z!$uN&w0khOFh1~88?9vaMPeN}QEa|QTP6mGxg57Su$4r8v-HL4p|Oy^>W3?7cC0~H z5_ME?s_?q15qU_lMr=3<c4Dv@BAh*`*ua2B%^?`D23o9rIe4)~-+&nx{P_zNAOL1j zVpJP-16k^48BaLRg=BzEvp{CkJX4|A!wFipFc)7CzjYO=9|qIMbKLsWGjrLyhvWUz z;)X}%dRWhClN0;0eKxYFKevZPjSaeE6O_S#sSKH<L);UnJCh*q#vms1)TUQBW4pT3 zhV=EU#5pq)D&#g8Bt2uvU~4oP7+UC$cXKIGeDzKkVS(^>0c?~2Hdr2XqwLD{e!sQz zVMXI$M>E8fFB4<+g6TzXW*+(rXigI2?oqi-O`dLEoV8xB3kHFX`~b&(m=%NSX2(f; z0(N{AY|99uIY6&gP&XyfY&)kskrSjZ0~$$fdO~emsEDU7G9F{^yb95xP_rFc{Ujc0 zk}v`u43t2C1-3ypSarkc+_&>`{_nRoaq=H15RHI8#V&Ao!7pLp62;}^m<az7Zi zX%~hJ-T8K{qj1IFz7KCM5~scQa)cVh0hBQiivsiQMIv=sAl<0>$f|+$sQUv}1tukT zIUC#F__en!7=*-t0H&e8ssQY6fVLccI}K9IdpF;5T1!SSc5>_7qaY@eV6!%k?q7&8 zGO^Zqs5a$P$o>0uMt=L4Pc|)rO)-RD1_Vb&m|G~sq@>U^G}f&i6K+T|8p7F=A#O=* z%QTv8!l0`rmD}Bx9oJc`{^8^6#Adh%BoMnaf(%V&3CMQPl?c^NkiIf_KZxZ#HE0NQ zIll_sOHAq0);U{~di}`6i^BWv3v8nZGa#2^v<xAq#kE^@83qN|GQrLi75~XPdjZ5u zBzE$QRsITbn?_hxi1kDecNXWTpn5cleed}vR}t87PG?>D1XYdvu*n7q^m}MVu=U$w zEKQ6r!dXU_Q3iOa-)M~=o~rL!OkNmF9|xP*Q6uY5^nL1n{w0adl5=5lXxGKWB$=Cu zT}?LIHm7bp=I?KD&pra;#-v`_U?GcwnKpwBv$5wNaagL2tfw>!7MtAv*mm-N`ci5W za?rM|(Ccnsd8|nyhN{~~+b~MI2Nxl`JyeKd8I-3&Cr&01o9(znZlOAh=9U0<90G4x z5I@5|f8=jD0Q1Vr_t$?h>E=0TMFtz&JwGyqb!WoP@7dnH2(fD`vhTDEt>oCVAntv5 z%O$aC1>0zv?TV+>$gtARl)?;%UGvzw;Ud`4w~90gF$_q)Y6#Zq{8$+JOy<aGEPLoI zQh{ui3X}z1>(M1piLWTCP;jEfkROSw&M!Xob<i#wYe0mU%z+)ezRunMucl>(-ZAs* z>@wZgki=hu#uBj20^2+QY-YE?S!C%xiA{8)r4oc79nv|Ad!&-bh5=L~%|WZsLGm)k z&dx$%MSoG9094Q%rg2Az5B{bRKF-ByiM|9hk83a9GtQ<sDRaP3K(F5e&-73w6k<qQ zKvx#D=Oa}UJg<TQD-zW`jZMfE#~M6Qdc0Rz?fKu}jO&)$#eX@v%N%#Y;HG)8_1vI= zow#F|Y9XRp2*vsf;&oHOY|;SOLI5@+QVESz*AlT6e{kahWUx5+^J!J%MLBoSJc%M! z+Qiw!r|vZyd~tP8bKl0mPBdmqp|Pe1aG63%D4a+*fgyleLU%B_Knjsfx{DAu;-tyi zNSHxwi+_f>Pxxc_u$zeJ)+~0b=Un?W=**yzCA+Pb#a2UuGG5db$Rf!g;%Du4GKjK7 z$!Y;YzHGT8m*%+Gan?v)`F2Rbm4Hht;CDHVvNwdX`_RN`Kh*?~JJ$mrI$%zq00*i1 z1SRc1AcF5vjk!X~pJ3XepOziitr?;}FLqiUFv<PkUJt$9mq|T(l)U5o)(VMxF4b~A zGt>gMo>;5zS;rYKFz$Q>aXmTMP+48u3^SgZaPtUM{AYaMj&qo*U|`3!8J*XfFC;%6 zx{z6@C7UGSf|TZ{D5!`q2R^j`YU%T+C@S;{C{}9&jj=u40#pp^2UYo0%MwJc*>afG zvK+{V_F=E=U)oJG0Bk%K%!N2i4;qjmyW>u88{6$f#~4d!$@g>i=YowEIQO9Q4^FU0 z0hTR&!NPfnI9d4K>vKRFLye3lbb81H1NDBkF=5bv3j#Nw`?nM-O|!70EG*PRY2k#h z3!-0AXqgKJNQ&XDtL8_CzKxb_&9O6{tQ;`$O4A5%{zKF6k9S!b)NY0BJ<3_HgSSL| z?s%(Sa}U#Pin~AyfHcj$cNL}i%s^8X3e`FXbOO9JWjJpD$jlS0lmJ4H1p0v3N|ynk zo`SkeK~=D@{HNL<IRuf|5}^EP-*@Q0`f&YM?s%HMasVa>=Nwe)d=R#GzpBfXR^$24 z_N-%$^fOnTmVR>gT(l>oC&#jg-fF@K^a$5`=8ft+h&VI=mMI6eg=$=o|C|S*{u*Wt z0A8^$6)bfoRjCYQn)~e9i~UuzlY0K)kL3{hUB<7PC!8@5T)J0b*6=1_otr>B+?Sr5 ziEtlcn_q^pV^xegD{M70FXDI7E`wwPyM9*&64$0^0mT}fpmk8Vzz<-nT^1dG$x^Tb zDb)jbqLCU4Y?F-w2$wxBU95uKAP(4UokW_=fnA80Od`pYo;8H=+kO3tTQit#?&p^C zn2fI(t*KytVmG7>%0jG`%e!byFg&q-Gjw9(X}E3zNKN|E2D{R<wG!4e<hJgiQV$qk zV__>mN);?6pw@uTzD2)(3h}GAmF{Hfq8Da;y_Q>lYcIK*gKZxim?zFHav~x3j8+F1 zjQXOULF_I+j^vNIRzM6$5J%yNE0Gp9U}t5gq~7aEDA4$t0n&nsZ5o13*gZQw*TtSI z)FFGE*C@mVcxbQPP_v_I;a=8_J6@#yA==+uzy5S|qX68+g`Bk*HVE2&E3g7ILdD-O zABo}|VqpsZ`r9(V$1B5(HEEpfiRzux-)sLXe~m(DgKs$<1r675m>{5jzkEQU7OM~g zh*Xyc`t9CUdLNwFJ5l9O?ar)rYoooI9<&vi^OHVpTfX$8GJ8K09NAd$wqMC&Y|zH; zxQr@pB6CO>wuYqNf2dFcUj}VAE%8as38HgC8DEvf*a{Y{Z9ke>=+HSp-_$>0zDe$( zFYVG6at2t}VtY_9%$UM?lKz*UKy^&3{lOo0*%0)0Z16(&PLGcqp&i$jOy7{4>z}r{ zIlE8|115IPy$t5R*~Vz@_xt+CV_i4ELm_GP{LPyD9rDDQ*|+-cx+`<Oqu<^SiQT0{ z=OwBI;oi`m-{IMZWcLMYPly`{d|@rUlT%@v#@X2@b`9Xz^1*%{7ifZFMuvxalxJnn z$2*(Pomd;#|07v9cTl#o-xAR&YXjtb(E$#u0(RMJ_&Co}CDZWBxeD>#l^Ra_me&*# zd~5Xmj@Y3xV*MM;w_lVkphoD$%slPd+)<^|nh%V&d@rqvx_)TtQzZnDPqs@I+l(LI z)}wwczmfUyz|}pG9my~1omyM(;<S5nEpLDTU+hu40${k*R<$~^S7qenl~xD(X;SIk zB@Varq-t=-K~Thp{}SSc%hxwJ?)yW?Ot`1JJ^X4~_3Jx_Pr5dIzjpqWdw_Ut<&R&L zru*IpeD+QFBX##+;l4+o9jad#9(sK8;jF#?DPbP(25|8b@2&Q`(dTEEo_IZMam`zm z2Av$=2z+8Kll%rv_)UH*^Ofw-t>tF|j$tmvJ8mdA`1AY6XV=^h#|}O?`Z_-5NA)RR z<geXYspOBlH75a+jaQ;_JrJx^g9@x_)ZN0f>iLX}L~Wq?7(zAr@_4bD6|xt?`m7n; z+d`J5$T3#^bO_(|tsvc!m)Sj!Rr@l}=2OL~T<z?*dvltyp<Rm7kFT*NcYe1u*WNel z>3`Du_j1%c>2Q_j@TtS(nRPF%$yJXJ&G0;3<EEsFvWF@!Zp;*S2JJhxTO+-3e2;nt z0mR`KM+9UzePPUjZ_x6&<=s_L(AIJ)5ZhKo5<KUrg|4;~RrmbMz&)UQX*Em+p9}D7 z*=U|ss+AKsZlETEP!XDw2lYC1LS1J@nx5V*Y&T6G>S{l}$Fc=so=+L@(ox)^nJSqD zmRjXWeT!oGk8jFSUzT6YGO2QuTlznW?meEV|BnOsvHN{<pZnY?F+vE<om`rzB>K)Z zr8JicMPswMo1!FXE(xioQcJ2axus05m1-`r?kbg{{Pz2EkL{oHIOlx!Iq&m+KVR7e zZh+}rf!Uc-wra@yySkDS3GWu1*nam_-<<gI>X`nH-%&qw_6H<hDhmCFg!_;FvCmOF z(vsJsarkKaoN43xVW?8{f)86EqwJh<X&bP7v}E?@qNv#Rn!o-_$0^!cSxdWlt$A_j zJ%Cy2it5)#2M^?VoK7>pYta4g<6G5t_2qm2JTUqD>Pz+Uy<1H#dVLIrQ&N_9&zGgQ z{C=T+n1^gvj{_Px%F)egvDM)R<S6H5jDkp4>ABUlV)J(Ix{`O_grXARm3XCV1>Nbh z_{|+r5CUatQSVIVsVswY_94T)ipQOc{=_vnt!XZaeYcyAUEWdYpz2fH&nk=Pu`eu3 zr=eFq1WDgDXaLpy?iVB2!waVl-Z-}~Bm^%66xlApm^jyO%d=PCo?)uR=6?gaU$}wn z?-0n;>3ym`DR&`C;bFgfb<Vi|ck%DfR~E09%B_=!?yos!HB=vroL+;Jg~IwT6W^O~ ztbbbK_D&URFA-oy^Ol7PWM<YMlR(`W9?YiRWy5a9uGw#kuy#4dp2)<4Fk+0n>fIXj zZo7%^s2X+{1Fs;Uc~k|+t?PDwmtj9Tjr*?ra7SyD?&seeqlB;c<4gKFJ5IZAAa~}6 ze=Js<>hmy{?PNkmnW|3(tP4lw@-{R+LI=gUeaC&}INCu7V>M6Je+fM|-EJ*P4Vf*P z%e{Zzu+}rjj`d6Cd|LA(-Rc<7KhzvIZEc0pyjvys4T^2Y`68XkxNd)bsagatQu~|O z%gVZxZQVVi*vReGHybXHB?@8B#<}a<=5ees+02s#%>37kwK@gQXfHzGQ;ovYIp&(6 zlBwA!t3C>n`Y~I+YO&YX`?B{wXT{3GM0NcQQMi+%Q9J)q;Q`jeC7Cp^#v0jsOT8{O zBSla9_hc{oy{ur$>MT4=32>Wty<j&WUwn9Up9UD-<&dq5PC?8UpyXk}JU3#Tw7c3o z(K*;du~xoZ>isRq`v9tx*vRj7;I|h0*fDjU0lf~^azF}2r2d!&*^--`7qavex2enU z2Z|$qCycYfWU1>e@D<Ks>8h+&z;wtpc)z$>jf<ej1)~?imz~FSM_DhN{)tM$e~7dj zB`hcE&ElY{Y@I{0M_~m4)>Bret_IxpcuwxTv-aSKzVUhp>K?$z+KK`WFISVb<?^Gw zU5(dhMnN^9AtKM9=JGss&%o&?NpX=nZwXtSB3tp1L?7Z(qt}KI%aXJZG5&k~e*cXM zFE&*f;)zSHdIn>HWH}zeq6(&-5{UP91ZigH%(>xT?s?-Jl+m!U(*ECYiRavmPKN|4 zn_v%n(e0_oC-yowZpUv=tsxkrr{4U0{^~@}u&2!jntBK0rhC<+w#{IQ`KUa4omAFi zDa-0{E_eP*_<85|*kS3q%E=t}Cpz4)-os&SB^ly;`4t9iOYNSLnCM9LACvl|`5T-& zT{ikd$!>)}dF~ea^~BAOLC1Gz<sGT*TvM(*UXoFl|K{%lV$aq+$ko*&_*egCJ9(7P z_AQCI86jY;%aa~X?9$dShOT*EVDX;L9UHaeaRaH1^5OUCxvnRO_pv@Kbx%i}mG_L! zIdQgUQ3IEFQSAxuyT!ssm#MTkSM+m}1hd;&N^kb}DKAm46vh3S)5`eJaOj{fF}fb+ ziKtDK`X46BrvHNYoeFDl5Dn?QV7CUfk#nDGPHww=E;=`><+6;mZFeb&@q?-?HPTYO zD)gT@clU34PtqcdK{qoNL>5Vha$kvaV+ujo@6z5=T`r`fj_;mT?)-V9wcb$uKhKTx z<eu2rROC)~rsk}~Gc8pYLuMU|j$YH%b?Q}+I?)Lm4oGFiN&qqbIds@!D@y~ERp>id zQ?g&|eyild!PqqoNx`jMkvdK1)~su_hj`!(Ve;rWqOVpZAnL1j3~CL#?#V!a)9%Wu zyvo^$?+#s!mlNlbm!=ikq!1@k4J*xT#K#=BJh)%`;=i748*Pouop2Eb`wlXd>c~0z zk(P)}e)}eTO5Uc}e$*r@%n<B@99+^+j1Idjbi2?)Mv3NmvECV;Ig|FJfA7&pA@dLZ zp%%B~cIJk6&*%(LJvW9dK&)@cVbb8>x*yfQ)Y`Hz(R3Vfm4fh0O?{ttnAL9Vg5MtP zs&;6RwSA+A@TBn7$8!^_YhDfKCfCGnimXYF5vvm!(G9|IxW$F5pL5nl>v{(9O5dYP z5%?ABuk8UA0IU;g9K2KU9^J#}XRBZGq)6vqZs<GPHzyW?dTPHGsApN%LD_3YYNr7v z>E9yUWzyLq&4;yoM>Y3TjN`9-m1jDiX;;n44k=YKSXJeJ-gue+`2Bn0q*wiWgG>MF z@FW)vmKkA&HkWjGVh}2)q1S!X2+MQBs@Lc+JTdMr>Sg&)QsdWbxnO<JC!$Yoc7%$G zoZ<nw>aZ(?1S(Xq==eV&wn`-KqAC2zQdDul{Ji==Y@AWq1U}9OAI2g4_kE(vDY|DV z2qgH|hoC$7KMmF{;YP8T^iNnJEng)IYZakw+nc*i1i#0J+xr`a&FGM7@RW#G9XwnL ztOQ4ep60Ju<AB(1GgOWI1KB8VmI_~@@U2tQ9RR*hApF2%f@-%c>mrvWSWs3+9}nFH z0PWkb=fyvJz6`VvVVimQpGKG|iuZw`IYO4QSf~)E>-STiuq|=TT3<I<9ta**{!d;d z$o2QXX@zbQ22vw`8;;TDV#KsB%TK>F(^N-zsyYkf2P_Exct2m$P$U<HmM<W%U#>|> zX7lhHs=UVj1cD7mw#cKo{FQ^-u$wT%m4L92^#n}kYP$si(up6X;pQb6CAqsP@$jo_ zU-35sb)F<>WW^nZ>GB4*ZJ+$QVq_@~nO+%hT`5akeJ!+a;1O&i<Re`k6|&LS6LmH! zNO-J~+ycc4fS@k7eLNorcG(U~(mm2ZX!%UKXYu733DY1^Fo?K9Ui>DY>L;K2=ulE> z#}VksIdlQ?sDaZzagQfk<*yxd2;-y5jIoO}Ofv&zkoCbC`un!K@y#0_g<OGS77{gp zhIA4j)7UQBY`bLrPf23HH8inwct%L@Ge<rpB{{!cHrM}jYrDlhb3_g`IUzzsaPgEr zA<S42)Ti--Ls;9dD>DkZuV|<;5;ip=6Sn?0KgnWa&`9dD{}Q$<PfXvsu?EQh<8=rn zXu%h<hOYV8aNz?X_B{iA0;xQ|Pm6mPo|x2Q9ki*uNZ(~q$0!0T@H2yUVx_<rgf3>U z1?DFM*T=(Gw4&^Ei3wJjM@Jma7LEMtBt8J-U-LS8c;sE*(XS=wfYWyONoW~TX%*F! zF!J9uMdythTAgQgoI6n%Ir(oS&%qmx6Ew^ekaL@dngWP_xRo=CF2gMr7w5O^jlhfx z2}Ul2aljR-i+{jFHB$(Cr?<Sn?x3jTK7_%n)e#+C2rWXC45@0N5R9gk^AQ>2ot4hk z?(x<=cAv<IIhCWMsz<G>tfI8qyPYof$Yxg`d6qfZ=>I;mw7-r$no_8=H6vc*x|O$T zm*(eZws`BUcb51KqrP{Q{IHLG?^yahUTW$|Av_88H$?egI^h4N%>QLssiZ8R#wTFm zR={_q($8g{KSsAD=Wg5ab{qT%2Q;RHR1TCIqmCH|YLsWFC>v|-*nSSSUH`~-iyb{A z<)BSt$?M94w%7#yRtoki{|{3hyzR)yoYIb6W5K~TJ3^Fqx*1ZV%6DF^_m5ZJbv4@O zSoyBwW4n&q>|!3-`atPBYb@j@%dcd|?uFT1=f`%RRStd29H}i2osJ5<qP$06zx77> zp3-vfd&*%tvreM&uuJcrC*2Gi*-=USp#%m2y1yaNXaE4r5C9DLDK{(!Al3l6WiW-$ z>trGn*M;@*YeXD^{?;n**4jq}#El20`daIHOGs|&7`QOE@3cu!b6Ee4OOMZzqXw#c zZZ<qQZ<qXjs{iKYp^FqIN^9$_#^E~e)9b<qZZ(Zurq*q}u(hpu>`KVZ1Fr_!u1s8~ ziSo64Z?`<Z88^}#{`mIQmv`v10~dVnTzhpd_51r*kMCT6^N;~XYx@cK)1q9(^?L^e zt+Tycecx)oyEooGuGkp=dhqVeg(03>f#-5vpLC=VACMhaC&6dihp7$@>$iRCx`WZp z78vQ{Sr6q3kzmsDr`dA-&dg6@)VBrpL!bgAv<3p~D!fLgMLbf@mPq5Zs!@&hG@*m~ zPD>o=_PcdgkfA<n;y=GvIER6X;G72sv#lrw+L;jN+v-Q2e!47{2d@i}Fxh#R-IU*G z-Re2^PmZe1((KuB-a~DBeK^OU;nIcum&%WBm)F<puFWv)F_|s29*>(XvYT(5Eq44V zoh_ljOy{`nD*NY3y^WgYPWjosn>$VQG&Ky^?zi7C*o#4vb5Wlv=eY)1r@oEVrjz9W zbF=6y_|9{zQv42b3Ixz8_Gy4?aDh@Vx^e7+TU**p|AwQHJ#uhp1f5$A(1o!z+-Gy0 zb@!B0j9gS&03q!7eU*N8Y4%T_ONWq2BH3sjyU`_lFO6{d?5VX!dp&~uIwPA;rAgK` zoVmT@JkE|0VtkG3kLq$MNvIs>ciVpWcvI}T{?o0|o$;UACS$LBx;=ID!>2nE_WI9) zxij&f?@Al4d~W}E`@`pZi#_YVbS#a>f4RRrf91=A)t?`}JOtooi$aL%!NpF5aSM6h z2eXg$TRybR4s{dIbNo{uR=;oSmS5W_ri{Lb!n=OtGr2v6Z<0$~*4>%1axrwP{JP;k z%?Osf*NN%JJ>vY2H-|vj=z#wDiknZxzc9f`-2m}#$z%05imm;C`^OujkaIT;M%I9! zZiHc(*cGWomZh`R<YR<G&R$_D!yn_!?o0(8b3C?XdvDmSsl=hRPn!l5E&K_+EY+vC z3guU3ziwd{l0@>h8oF-C>Tb<TFQ9p=LoW^{A1vvCJy%4pYmGbAZ&JT%>0^-FvKOx3 zA(Z83#JkTR^-3rIq1H9FC<d5aFT_2Twk|5H_DnDS{q>FEHbn+_s`ahYoQoa5U6K`* z?z_BnJ9&T4tN4fZn-${22G>Wmbao>)kvkzzZ3`KQp`aU1H-^@&eZSi?FLcc}{!h?} zE#t8^2J0zZVZa?567$Re5T=R?-!LPO52=b&Xf*NM^6x7$jFF8!C~?;}vn<%#=ccVx z*o#b)FYrDAN^M;9viJ5vJ=+mQ6!$$c^*)OZUSw*`iz~jbse86&k+0_(Zd7|gu(G@y z@-)dd@%c+@cF{Ig7LtZ=Q_iM>G$e&c|J?r+6I>n|D}OEgCxE}6Qz>w^t3l^`XS)b{ zazYNeDbX64(Am<Ga6z`>-P}s+C6_#N*{-9X;^{n|h)<Fw3=0TKYG1}nf~sbSr+8p} z6S;h)0XH4qAPoAp6u(zcd!#kjgYY&MQ!Gc}bZqu83(zfU_P=_VyirY@*;8Dq1v&X^ zF=pGT3iry!q7yq$Ypm0=gc_&1U|As|g9>W4hWF=0Ta!+uE{f;ihW^Y8r(bR$$wBPH zrcq}?+~QF)V6{RaEUqyJ<ui<kEEARf5kE5YlwT|G8I`?-)_i1=kci*!J*z1(;W+$k z#cnUuQ+;d)wfHB@+uJQt{~(2L`6l1Lt;#<x|9c4G{#kr@YAt%@1XM4SlfO$kOI#OR zV}9x@YFsy4@p|7Qn?Igyc^ig~$#3jg_t%!YU^927I}E-#%+sn_%^+r1kXk^Pn&9p^ z(W%`)w&D#MbbW9Q>VP0pHCYVOk<yZsLPZLvmo}E`T1Krk!bp=0s9A6}nzaa06^KEA zbruc)K!gwpB-Bw)b%p0;Wz~tzoCB#;RXkE7cjEW6^wm2h9J00xIx|=nt_m<*E>ELu z8IkJWDR2kG_T6-DoenzO%rsYyk+f!#!d#OT0nC>3eFR;~ixp6Vlt5fjlYWB7D#w0w z7~k>9jVQ8%8asYP39gBVbCevjv!&?&{30){ztFv*G7*JVsMG1;z9f{RoboLXr}=Nt z15P!L7LK1Sh3@{~dM4z?;`3+aEX7>HeU4Sp{VwHmldcM<7*KO^7a=>&T^}`!a24yK zqcqNAtQ}$Qg;~4+Cxw?rKQ|T~sgqBlfK<%B<`~g+u?aLtB0vLQZOB6F)3WUjxa6G> z?9?fthz{Q@4e=Yz*69W~n{surnPIMYsldygm6-3z1*!d!^lto2D$Ha=>8y}A75$0D z$=*>~D-}Juku{btd%D(?t8;0N^Q|RGk~2CY@Z6Rz`Qns%H!T#FBbx)<C%6ID`a#Yi zTGg-}QzNxIC~Vnpv2^P@cYjH|Y?eAP%C$51UR?D|Uzo>7vA`PtNHEiZ_|BcjBZ;zg z*H-cee>!ncvp?f{Z^tg1Y;XUjUyBtdavB8<YFF=PjI>$i%NGl<OvNf9Y+WG<X;oIM zP)=p3!)o9T!Ll4|S!x+bKG&0&UAZBylYL0YvLNZ<OHJyyLS#VEr&_c(1*B$RdBJ*F zj<8mZb2&kUsHN5*4NY7(N^7t_CQPLkVUGT{R(u?tsqsSqG3|>eiVFd&k1um5J`vGj zgLT@lHUA`MN+~*%3)WhtZgA-N7+O?ai*04tnio$$XWtELTcM<Rrj;VYS+<&LS}Asw z_v}+JBE@?GQ**u<-v8r_vfhTuFOaJ#m!A1+ec*A(tm!=OIaf{x<&iqU<yA-(xxu6i ze#R>Y5#0S*Wp(kTL;mo<9zoZslXvD!kGee0?5j-sNM^S%+mFRYMU5t{_p}_BFMKEh zsnpLxERH7TZ5u87RK)Ez%uHl^Ey|(KGrCFRvSo?8nNSF@)SvO#6n8tur`PkU<KkR1 zL>D36`wLgP!79H~CQ6b(3b!e_GLR3;T4d_r<Z`W}vyhO|Fj<;1hy;|W6mwZ?j*Tw( z4DU#dC5flayk&_mRirU)l57(&o$q27srk%=bL#$dQ5->ET1m!yTufTwg<ACD|MKyV zdEw`2$T46~kvooN6ib7p#GYZa^I#$gewwyV%?;NnLAKI^26_1R48{lAz7-y}kc(_w z#AnX$W7;yAv3ueTu#dRtDgt^xfU2M&zf!~GNAQrIppg;s2L|pp58o(3Rtk~z6qJO% z`N&zcaZ1jv3j8+$I))R}qmTW|P5w?fc6t#NyNo=|cW9ZFxoXJlT8$0m_)sGLHW_`8 zfozZ<&PtdpA$p0Asb`=CWE78wKOu%Db74clh&=M<lWSZ=9v^-HfF*LlE(8RdiZ}v9 z6v<!-GIA%ybE|Tslj{kB;-*zGB7_bF0AvCeN+Tl}TsVUuGgA_ni!hij_-ZF;w-A0| z5j`SA4GOU$GX5GFg+gG*Wcn2uwF=-mB-H;K7!*`11E;+SH%!1v0Ngl$`>{y1+>|Wk zW}~GjzJwzad@5<!@*NDAckBWXtDK5ku*2KbTMEheN(mc?!MRu9=BT&@O3C#x{1kw^ z#>Hta@7pLyQ3C@H2;o&+#C-;OjO+P}kF8Ke%gcBx;gR<wCSyKpU<~gd*j>U$ogt%^ zsPWjKc<X-LKSq4gTF~wW8am>UPa8Mpub51OJALHh9`n+Uk<kxHNFJ~Fkud8zIedVG z$rs@pg(#jF-OGR-VjzDL&~*U14S*$(5ZOY+Q3*6$0xOc{77}4Lv1d+-5s4CLtQx|f zfv7P#?C5&pC(p_y8lS_@-z`KWa-lMmCv6dy#)Z=u6--h_8W#$+1VQ8=OcLrL1^-=$ zx<J9dWMpy~n0Ln#SLvvFF7g}$BU9?c09Ix_iK+P2iK16_xLFGRvoy)~&Yp7sx{Hd3 zrpm}2+#fFT%+I7qqvXN<ss#!6tPp;A@q8bU3~+H$Mv0WZZKH8)j1l%70JN@AP{F2g zCsYphQ1O>}$RaMbpO0T9S-vA-=SbMWOLzeVK10W6kB1q)+b1}JyGzPG$4B?_Wc3OB zJudP(KlDLeik{lRX9R2&fIdw?Cry%nET%9OEZ<A;lQJ8K<l4@VU4AZ|Kk+6kSR5%3 zdM?nRzF17h-xVWn6Yv#0XbBmA{}()mfVjDwo5_WSkt1^G^?5>wEfsoFl79QFN30qw zix1oEmcO~n*Qef!{sUP|hlT=3VDZomA{<zxgb@lD5?Cq&&Y=)!(GV9Z<O1X3Egt?k z7k`#eDI(!o0Q9>%HEjU$EEoTSjGH3k$Anl^I%;8!hMi!Xe<j6kJ&L=>L$2}M>H(^h zkDpj<l<|e*RQ#wAu|(hY`0j<<InDny1ft_mCrC&sq3p@?swmso<|DHIVxQ|&n}57h zo24?83(FhB{|b&BG>t_x;wu;^+9u{-vgI>UcohTHlD7XngX(`9_k%3st`KP)>^rXI zBp*G}j0}M#^9^J5`tehIbWafOx&$eFj$w}DrPSmZZt|6L_$n^)G6mNqL<&fl1u?!$ zjK~qlZWdH89T`o4Wy{nZ0HL(GHAje`0WgJ?+}$MbPAXzI?YJHq7JCk!O@?j$uKzR0 zO3%%CjgCIUfI9qv1qq=yWP`A&q~l>?XgYv6N`NQQ;0!8(A%=#N5s+5wHwyAO5Br;n z?&9G`DcI)})DI!{8vXysQl*45M#9aAv9HMZDF$+Ov1rw}X_kiVUQFWB9a<^)X_D+K z-0DQrD@2J*;rXzbG`N4yuhFn)<RU&7Gqs3E9KEV+cg5=RwYR*`KMT8iHsTs3vg;f( zOW*&Dd*QM}N!vh}y%)}3BohiyXX&VRGFIKA<@NImF-I9IJoGt<>}=ugaFb;+5qV+r z)ejdIX!|BiV8vWy_1oPG;!1=au2qQmznn#*zNO;r9Z)j>dq_eZAyt=A&`Vt8?vw__ zHQ!c+J*`C)co-#uMgj+s5P1?<%>Luqi%|bR@Cg1{&m;QxAOVCrOCAMwa1n8O5_*7K zkSMu%zz5FY!=v-zM`?sj^UzWxP{_l7qag>l*zW*}Y>#=$C~V`k{Q+*b(P~w9b&XN+ zXF0fH6fRx^yGpsM-h%wDhS~SB=}oFgX4G{H@s;AF67*e*v$*26YCazuGk@|24>=}D z%G`5>VqEg_?u7*g;~52;!H0H;v0rz$RL5U=wfjon0KOW)K9e9T2<QRA#lMsi_`5qX zu`N={#eYKlDF$-06th6Ey!!Hyx^nnA0{V}ngv;&tA=xeBA;b4DBx{Q&SGdWYD5TgM zCCb4q0jRT*>i>AHSrRy?3Nf?(!DufclOS8<z<wlz%<IbLLKDP@<ae+Ln(QOY;k%RF z%-PlN_!XLLuo;ygf#xCsR24iEfQ9j304d`*l~AV{5+;GBQxM0<h;RmS>*HI*md<yZ zFt>!TvxF`YU$&lMPSM*U*WaEY9Tmr6<I%WP3ciYrY7t{rD5wrPZep?MLi^AJ_x5Wl zeu#%$<u=3b;#SF+dNI76+Wd@vTk!5_1sN0Xc;$k|qvBD#m|WXV#w+~5pZC3z={r22 zcI7Vx!=pgCWW2EeH%V*R;&?@o81t6LJi8`A#qsd}7Kgv5UI{kCR8mj_K<qOD<_8~L z!AH0G9)*UM3<KC70$x22KTgB0(2*Ik;xGYyPKa6(G9$Rc<CFp#4_3X}?}b9-$%djN zkVePNSu$6OoRCM5-GPYW-w|yM`oE&K{1g9okpbPuMeY|vcT?aT;Fj~fo5v;aE<eI? z8a$H*r_jLR6!>u}{1_GfxC;3~M!9jZ&t*FZZ#<uZd`LoNI$(l)vGqsV#^_I9QL(Q! zV}3}w77s>`Qt_`S_;v~Et)ys^=2R!PBybWBZwhqxLW#)Yt+u$UdAB7z%r)Be%b~;E zm%Sg}aemyzKW^_?TAO^-`zNV40|!4E^M{ToGQ<|_8GfwR9q)+x=YU`3;szFr-%9TW z527n&!rW1uAn*JkbabFMYDkjAJFtILjJQB)H15Un80Z!%dWnHN$HTAiWC!2c-O+IH zJ(NZrS6<(mLx9-Q;PM}G_y2`wE!KVc06k5z+|~T>FJaRK2BesV%6$hN-6doIgKR92 zDsvY34FyGTYZ#2fcz%QjKSn{AcwoPYk-V$;4l25WfgBOvU;Tu+auq-4gTKDv_895q zTnN63I+CLDvegOSXF8RjJ@rzEe6+`*ZV@x&ixGaB5B5jh<>3b2J(`c3y30k*sl`gf zML*W4SPr$1HYj+te_wIA>@KPz^@$X;o=yL4e^QQq*fyN_G4V$#YE*pZdn#T+zK}V9 zFM2VwRi${2R}#61{y>*%dG%K@kb_jbOhpp_NTW@~#f#`!KKh6_E|m*UU4*3qx7K<f zOadZ})*AN-VoQMOe9kQ)!Xn5C_f_F}Wa!tU4=uCpk6*QP9+_zKh1yV2$9ZRtaD|Cn z_)$g$i&_9{os>QP%FV#jdGI5PUn;Rc)dqYC5A&UtSxnwHz{C67<HG{5Ps!8haIBdA z^u`nPFdJFNeR=(NTdO~QApGUwe_{#H{DXkDcbAG5JA(ecF*qrj0L16kXwABR+vC`% zdYRh0*fA{mHqO8ekWoE{URmvmU6)(g6o4BRH!X>=TL&)`p64>FksVb0I{>r99pd0* z>jm;L4|m?TMJB{G?ftgzao1GewL90)vqCtZfeY||eO`iE;@8Xy=XqT06bW~YglrI_ zTe;APMR@Pi>Bq$%8FY9!wN>#v!k+}z!NF4bGdDN3`bh@Zi+=ZekrdWL{qc!J#ZA}g zuw7zg8GpxO_01kfA@&3z6PR!TfW5*m=`{FSCj1zGuuhEm#zz8FbS({ei;Ryt+qvq5 z86vkG)V>pCK0n6C^GUGpVfb;vJWb=}gg0tcocM2TstNz<<n>3$XAd#Mli!bizzW_C z9b0K!r41?GZ;Cy$zZK}uF~fFq|LsQ?OT{9;uwfuk7RZqKBOoSw?2wKiZsM9pL2S_* zbH5M5n#~;Cto{Dg<@*EH2Z#;_JA1-47W^-5ieHH|d_RGIX}+B=Ek8YeNYn1H<JAi{ zj~-AmPxr`isqMw9uiyUt{e~+$@#BVJW6kgGLAL5RS?wmu<ui@(+BafmyY1(oezmR) zg|yN@LwVAc-6-Wh-!ET1>zRegN*u}UUw`x?py^o^@-?!jNNWpQbN9FCf$|Oio%y)! zd+d{+jv6aoAG+1jQYxlQS;jb?<L-{-uTk)!YA4Rxt}FdB5XxD{^rg|JWG?~T;@+vZ zb+_`iJMXDmLMk@k%dVu2wrr~7`0R2@7!xF3fnOc3^Od$7RXppQap%Ait)_Y3Awzf0 zY|n0RuZ5}!_1vFu{T}C);G{T1@clek)gkZceHSxep`43BWL*!<Op*fmQn_Zcv8w;5 z?q$s^>vVoq=1==Rqs(ii+uX{9Sq+-oBj0f}Q#1#^RPUjwc@Q)Ekm5(>5O*))_S7a* z(`sQWUT<}Y*<D`S{rg&V^evHlMSA=0hUyF}xfqQM!Sq{&o%6#SuDPI5zr-%?aa4)j zLbnL-*g-QWaeu(A$-4{q_+Ib$hv+VHgzSf`VYa+p1XY|I?=;))V|?k>c3%ts!Hxbl zKYF#3|NWjr*@vBrDsTV-v0Q5bz$Dy=t9v5LwwS3!YXBq&;|*iB4d>KR5vvi@y=<uS zE@b$!TEzUhgz7`LTg~r<_t<Y+=U42)R!V>Rp<&PAVMX}q1flNPFwWDry_JCmE)Ck- z8mCP~Neh=$tKy~8?sdg~`rj&eSMRp$OMe_ws^g#96j%pCy2|UK<v#AG(cd>2olX+# z_V#49bV5#tEteXpuNXYoR++T)d`2N%EC+v>{(iredM3M*rM%cudHG)QlDylg<>uY7 zI$@;YnCgA+J7WmZ(&ub>GV1G0o84>br!})HLtS73S?WE9)hI;F;VD33XpuYYP<=jG z{WqGsZgjbq?6=TxFX7&oy$6Ga9B#@GJZ&G4QfO6Q_BFe2fC0vQ6zDD%?R_;%*evh{ zw{AM|a%`8==Sfk4Tf^OG`8`W6p49>0`aO4Ncs5;X-*=}!;A~>{UV7OHX{VuLe$DTn zdlH)?SlVpdEw&~-^;TYWI{7(Ns|?~uPCu-fl&5;+k8Z4zf7Ls<W~64e_n&vyzsBn9 zwQd@ANm_nqtio!azWg?=?wGgU_M`6}=<KI8?bk_ie~sK`yVQ}$V`^0KpyuCViWZvY zoNd)TjOdoQpDA^l2lPFRi?j05LUPu$FLNOqyQd4&7^XVk?V!X_!g;q8mz^<L5xaY8 z8yo>$M5M;~JzX?g7n?40eEfM;%rxG6`bn;rd!&NK&8Du@`JlhvAnd_J6e(qz5b~I* z+72)#M`4x;ROKr&o^|t-Zu0$Rtbv&eI&f7_qhHpPLY=@I>eKi8!!JHEZ<+sz$XW-` zVL;L^rPo=HvtP~hI0naBz-KONzMyrR%v<8(7#yW8k{9^VF;Z@Yh3a2A)F4&v1}V!z zeFpuXFH!DcI{&cRSz?Y&$j+_bv>GWE+vk4BT5Ezv>okq>DonAXr_#GYioP#<4FgKA zm4~>+4#Yu@RJ&fPa*9!Uy4KWd5|UN?w&~;M8G*a;QcXz^T^GaRi?k6nu%RchX8dep z?Pm%sjX7O{{a}r1*BMopM(!cTIgsV5?j}Q(Q6Bt4nG?V_ed4$-A%p^2pWey3{At>s z)0eHR1>g2U6NCv9Gj$jM!vdpccTB2${TZ?3grlo=e+A6kucqW6K+*UuglK<XF5F)j zsnaE3nclW6iQtlt0U@5c$2rvrjTpCIF1>b+x_Kw)z3axLp5}tiKDp`-VX(;IKg(id zh-0G%PKmqgezQWZtg+}W1rFp+=j&gpi@6*f@AklfLTr+;RCdrKJL|{qzu;v3>16qv z#A2f<+2_pUde@vCv+|lVd)G~c^w^)W%ncnCsfj`eRt7cbbWD_XJ1^gPUJgy3bV<6E zhgF458{G)|WOmDxr5H_M-<Bv+kGh;kLFExPqcx~ReG}L6dtvkIJP%iX+q0#Nk&|i- zLL9K`*4R1AHm|QqED?dPMUI5K&b?0*ss*HPf-{`w+_Z1eJe*IJVnYSl4Fi)fbCYSa z50nD6ia55BY}{<fc~<Q^(IEKDi>qma`l*<^o|#Emd4Z!$?Z=BMo7&q>hbAO>8&CJz zTG!;9Xq+wcQ}<e)XHH1l%2gYe;btWHf()KM<@O20UftT6I382Gk{}wG+jk9zZ%Umb zc^H+gwHmf~8Y;HZs|R^mNYi1_4N5`J*(8UOSWFagMaa?*Fu|ltv+=#eb*7_)E6+c6 z;#iaF&5;N<ieC+M@AB!xa)EXot1g7SR5$%^ye=Ekox2>*TP_#lOOCgQ4xh0Do0|`V zY#=k(<0kIvRdjg&xnJZP>h4!z@~=h9a+i#uPv^(`q2>%%wQppP6A|f1>rHNI-+7N1 z7b3Lw(e-r>3Rt#VSIofrA&N?~JHH5Yi~SJS4POh4Y+Bm2e}?3Uw66{M2=Y)zOKY`} z-{^v?y7J@;dZyz<_#n%D%k}Cgox429`hz#3Iuw37TPecIBiLgJ9yv<&5`@Wd*2gvX z8@(sK&L7^`Xo(LBaor;lYMI=yG;)oe&as?w(`pBDod%!dkBciYR_{5l=NAdo_3osu z@gWL69d(hMQXAu(y!EeWe$yHppeK}M{S#@Y&{>WE0GT+TN;p6VY3)U?2Re4orjWX| z8|W3ADq43vXmVSKzW3<a5s=yluwwLWxG*+aU!%?&X2Y`?J(Sz2<o8(LrrM<|kY@aR z?6Zm!%d#+?Q0I+6;;oneZop3HPkGMwT9Jo8;`-q(o1Htdc+;PQ;^fp+yM`Fr77sve z5cN7nx9zeV(htO?w7DPq`o0tC7agUuQ@;0(xI6cVRR7c;%F)wT5^?#mAiPggeF4Vv zmWYUZdYA7TK~&Xyhl{^V<MwiscgLM>BliiBSrSlx#-3a^)--{c?#p{ch05M%1)(mb z{Tci3oJaEeppQJ3VMuEM2{VJ|fFW7}f_<-+(N4x<_68m^@H?p6yD4~tNj<#*AhM#p z*`ZR_ej57(4H{jefAewEgzPPJJtR%S7M$KZG61pqaOX<<x<v+b+ae-Ckv*|;=6lHP zH_!8OODmT95aC3~-qiaCyf@{2?M#Y5{^hYk`&enqo$2yiV|f^B@=T%_y3_mY*(TL; zO3Tw1Du?^k+-o@~P1KcdDlN@2((JN)`k9eati6=ekam`@7`}Fh4zuwovOWLc1_?sh zqjaN>S#ncR0|D9+hyC=@`J;lyeLC228NI%O<+b~vM|5}Jq|*73!fmqfcRD1H0bNI{ zx@p&LPGU_iK72vnU;&uEp%lKh)0Y5@&C+WS128~i?<eH!O|3g2g@lXYF>$aAiTs6T z`1VOi8qKY3Bj0g`UA;~Kjlwf?b5h8s69ujZ^gHnC?BrasPT8dcVpbrv`m>ZBVdokj zb}^8qtz_w{?&vC-;V2wHU8#ldrJJQ(QH8y@=obfzUf;RYrxqvRc+tRbo7k?k3h_Kn zyzA+GJa&Wx7R$>|%Pszo0FLgw?it7IId}60{py-I0?bDgI4*%HCLmHOcyduwv&*<7 z5^{gCVEPZps4u4~zWXezKj*-fWRjjO9TLQaQ@{nA#Ol(UjhnKRHzVp?7O@VC53Sn4 zfK+*t6l@#^b|nvpOte~kVG+6T!~xi$J`XDY(LN$<V`rN$sX2m=10RRUPL$sy9OKsW z(+*+8a{3XnZm|!tmjYK2S!R+O!Y4Tg9;+qKt~+?e@L@9BFD`$D0S%$RVe4*4eO&*N zPd|`xTHb6wT7#ZGENS_aAHApZ`<bO&R7(ghKdm!e%yB02Bgo$S=p|LpU^maheN#6_ z(AjP@&F78Y4u0TGi(s>FObQ*erhx!&3RHGAu|EMazaLlhpfTG*3ZL70t)lFyd;FH8 z%Sz^U8@I<X3rD-HCGIc03yVQabJBndomsQKDag&^sY|;(5dwoS{3>7o01fJcNB40; z>P!!bWvBgeS|7(*oIhq-8Lr{k_R=*>QhYlMmLdT+hdxfo>N#+)Wv|)&tUTg&A~bPQ zCG)XbFroUeK}Ea-e$0=Z?Cn|UefDr6o-T901d#o{&2G;&!#eS#CHBuONUR;_o|^%B zoso>LJ0bS`nS1{LJufgs{SbBYq#SfYiG5yS`_2lPfd+AqKCvHsa-^C0x~kF+!7}2? zkpXlo)xk;QyxFqz+I_LQ3ji^uKs>6R+FyG5^TYX*G^iyF7A^q+KtXHTgMcth&8VKM z80@g9XXEX0X-*lKWbRO-Oap)g4HgXmzBE``g-n)&q>=8$3T<{RH~C7T=~VU!0fc%4 z#vH8MH=I8?LPq-I6Bw{~Da3Y?gAQtbZRygI4~;_%=H{_~Ad&P&(nGTvr7N4-9PY2! z!7~ZHwZi5!0w<hMeIV@0*LO1dRQJ#=*pNH^fCO5hdv=ASx{KF~JLH=}#K-X9Vl_^P z$95{0RTH|ysU5O4&Mig^7dPdcphFHZST--2B_HexH;1@R`fpY%aBT#sNwX>3@@#+R z+N`y`jq-V!>C~3UBoWzynh~zkt@o>(T_KP_A=F9=@}x6gdV{xp?-nhZtbd`oMO;Lt zKiKQ@$V<zkZj`wJbWbGaAR$0v*P|8|B!iaY)%Z+GhwkLT31+v$1(4&beu*Klc&dSy zGza0~+3^8(e}t9tj(ofob|g2)x3M|uhi~l4?HI$B>Qp09Jtyh{2XECCs@H-*yZ+j* zdfTvLACY?|ag)CglD-J*yuwC4YR(`*qnlvW?X1)sSlqJZ^elUa4LN}ZrSdojLsY`( zEM2IlpEuKy4t6EBF>`9{mzWNARmCgJ_fgrdiz2({H@}Q*v>QZUMq<{C7PDor+)2Xo z8IMMf5B58y%&5j3>&a|alWs?`;05Bk9Z7%3e&shLmJz?`%1g~^f67J>P&b#e)dmVw zuxELYJ;AWdoSe|c9NxW0d0=R41t%QbnMThE5x92UI~U)S^C@@ic86JdF4TXL18K!4 zZGeY}A;;dTBv`8Z^Ed~VTsUIi-(ghrA6$AI%IK@hx)i7@_qN>lef}YKNL*lEUyhay zUhx*s^#DGBV)wzMr}-`W3>|9voV`y18=KM(tANLZoCzf`_x5p+N?@B@hmig!<2l9@ zI`euBdh@v=r;Pz`wnA*E%+nA^qYuOrksSo=zL4xQ>k+lqp}Y4fsaD2!ZJ_0Z3LwUU z+Lk7;v6$&7(c2=?1GvV4*1={T7&j-=?n!2e-q!BaA^B)F<ka;Ojk4qCjP8epD&_dc ziAIOvKKK6HS+v<B`@&-fg9Jh)p^{Uj{x*1=|Cyi9Q_Bf!<RCPr(nH)<7K?FP-=@={ zAt9w%!;a_Vpj%DyKQ9+YHpFDu!R6#!lYF=t63C(YGdlueS`^qplkj*3Tj3Kkdh&vT znSTa@HU8WtPEISnk#mq#`JUW&$lE|yYbNF$)S0-QAH~|REHJ+2y-Be^)Su-%D01Yf zPfiL>-79c4xpvbOVi(Vn%{zO!Z1GK#`uRky&1PIXNi_KYVfs%({CL@0s6{RBKt{z_ z8EwC15wyWu=wb%}xN<-rcsefl>F#n!Jrgp@9PnX>(_mXuANgN`M5h*ymclJVa92<G zXV7z`c4Eg$PADx$R*!1ptxKPbX#Dr$fQI*j4~}#@_^w8BLUh>4D8g>%JXmCIu^2+7 zS?%_yCtJHphsQ56U_P`Qt<_NNxg5U`zf21BD#_pN+nGb}2)7DCBOw>k2{31#Y;mz` z15<s3IeX?NtU8CHsce@J<s)5BjH^W|kyValkOob&wU7A>cGs+Lrqwi#oXWgA8R^gm zA;q!0@}BzWzRv6UBnr9JwG3agO_gm1V6Om3b3gOZu-mDCLKRA3>9>bvFLv8-uRbXq z^{Cz!#2-SIMJ+v%Ii?(cI;2u>v&>Ei=hkcgoQoTVC>V64^K$oyP<yEpS7J+!cC#Au z`4O++{?uu;aPpN9ZS@uHl|I{Q5+|aM^{E0be6m^JCl+f;U`se}vvMv2yY^~v1`cv< zZt*+oZZE}&LnX|Ejm7`;7OEnvyBc60CD3ab3k{j9fv0SlT{foyS>Lmd*ky7vBHI#L zz`Rsh2WDRHt9jj4FxCThrGrug(teY|siR4KlV!&R@DHmTAHoGMJMe1<w5J4Qb41fQ z6AYMSJ)(YA;AX8YwJ?MIwpMFV9EiogAdG_)SU4ZzzvI6>RqQZLs4p?n!QsGmS-QdI zFPZmQZ>H~j=H|!V#06jC;JyuC%14FsER!OpwKDQ`9yLc6kEPk&1}e`Q>2jve)1e=< zI@cTdd&6&NtL0S?E{E9e{1<wE7LtiTT71;{!8h;`)=i|Tw2g4Q0O%pfb!HVOiU1Cw z^~GdCy(%cNz=GP^a~FEKM(<Z{=H$A@DEsFN-Mi5z1_~TjXYPkcpFiLX#C<dNI<}Di z?c}mjv^Qv{Fvp9U?aFU-TnuQB!)O2??LN6~qHKf7oDK<o!^^fNvKlq(MD!d#E$9l% zROY9xT~$ilLuEw{ZoRQl<>fT{djm`X<QVAbGL&&9iv<O^6MJ)}69jv<i{Y`JobXi0 zGTQ}R+fen6^z$fm!P4t)xbMN49-Z=CzwDq3E;2P6sW1lhNo5~usy8c}fBdZ&ufPtZ zMnsx-e(5{sJ!F~@0%ICHX4Z3-wSFD~#=_~W+N|P+dFHOF>uyr;i#Vp*zVN5clPUwU zYdD+2C~D=Y`^#PmPej@vnC@al^URTjj!!AOP7LNIJw(E7X*p3`)`mFNYY0nbvIQ*Z zJwjxY#8^O#RU;;o?V6?=MYcrNW_t3NPMx1!;a<V#{S<apcJWv#cn{4xMm(@46|ib| zAJC|V`Q=VzemE5l<j7x!#fW>1?j69!<A2?qKNG_C6W&Md!Y9U&eIsEh#ES<{=N_0B z@7I!8Kpq6<<{ylbSNdvu;Ojher8q{y@s%(W|EB%=;&CW!UtH;Cg#&DT7$RNNcu3JG zA=D`RPnrMuUA}(TPxRlyzPIwm>srKplf09Dt?PBt`?WkBDe~6ca(HzvP;KFf24(k8 zU>!sn`@}30^w($fQmLZN+ITCNwq)|Ge(PDQL+_VNM;o_a-hTDKj;4n#yPuznn#lFH z*cJDTkk0JgrfLJM@_$6#${!|q`j!DySN5<4>*pU`>pov~rxe(S;bb^PV{LEWoc(*7 zA~k^8vgH5L=*zHv+RI9tk?}#b8(vQv1CM*YxV15zM<2T~epTa620vu@rDx^KrjVuP zubH1#?tD4$!~1RXz9JoqkRQ?wOxV;NyTt1YPnhl&p|U8AYvJHyjyoIDUNw81)V^@u zE~8R9CUQ;)v(9Yy9y{OrDUCkCzdQEw(%TTHU(>%T>3qTVJ^P0$JpB*!F(S8G%-G#j zb86@5;$yn(40<dTVot+US)++wp5dC=9PdL-f?6%sWP}@m!S7bkPMd4x6ve%Y9`P>( zW;}G$ATw|x=a%p>_2X)?@@apE-v(uYdt>nBJGMXHVd10cR-h8Cl<lRtmO~$g>L2AR za{^i9M_mYgzAOMJnAho{xR){fXfI21J5ehkLJtGfrJNcvf4(%6>-<}(8)b5fI$mg1 z^<)HT_1&(Hw7>pc-4nxEgvpe7z4Y|{jY~3{EaCn+<5%(TB0vF~`mlP{ncy?KuudIS zH%g9w>6|E8KmN&<l>Th2&e!N~h)C<`YHDp&Gq|}OW7o&iMQ(Y#v~zvdE8gjTlkeQy zMThFK8}Vk$;#2+&-$`Kkn1Q&PkM#tEX1tLfA<0WCJvgOTTerwyyO(|q!kb_#5o|Bs z1jFR2(+o~|`8%<76ScEht-UIHR!6o4djGv?0DNSb84j3U>9}!vZD-}j5+}DB7oQC$ z4h9-&6OJe5p3~F1G#}_e{1J;yxIuSC+f-4(=o8Z69L2!nF1;k6ei#FM3pq6u^_!Yh z==|JZ<5r6@))TdT3K3RAWb~=f3+A(e+k?(+-d5Z0z7%gnnXDk<)?ZmI1)=TVe*BjE zdKl+TbK)X`@OH05Zkk!H()9Z6W)ll^PM-5~!&yq)GjT>srM>TGu7ADr*zgwD6~Ae0 z60VuHWaoO`Hlbv`(5}z>)HY{s$ooR)E{4sJb?JL>-u*$T{<yZj%FiVdm}#)6eH55+ zN7DcW__9t89zom>xiRaXmn!e6dvZ1FvZD93y3sz*7-)I_n%RekTh{!xBPoObI?GR< zcuTA!fdQbj){NV?&#P6W+puV)Z}1kP1po?c9%|z#17<Ak(uk&K%SUF(r%=G=r{vW` zrID(?iI1YK=W_qEUblB-vC!GvviVtbzV&yZhY_e-BOPF1e@kF42S+dg2csODR*LM- zWFhswMG}5<_guC8r7;l)R{TNa9CcSM$}F5wn5p2*z^qI5`N?Ze$YNBNb@KwN^pC#X zU6nyOl9$eiRIP3wdSkt>*|eA)cDV+&DK#<ggyVIUGwEz+?W_WRjGN9MqR01JfoPkl zn$t%bMWoLuh|<aFbW#>gF<QuS6J!~JMS)(K?ufN2&03@5QdbfxFxRd=3zuM`w)yi! z{i;?@#ox_FRx6jwOJzh_pV-wR-I8OwI*pBZ?^^nkr{vn0l`R7SFrl)B%tC-^EC9&| zP{4ZiAf4viE<yl<wGN^y-`d9^Mv_^CJ{O%cyg^&<VRR59+hNHr&UQW#xih4hbNe~l z^+)Nt=i%9^2ZO}qpGWi4t@jm#Y7Wr@hD*YibQ5)+;Ip1u=7%hbc1=Bp8;^s}pPS)q z>S*#Zvo6KOGiIGicsXwbfi1@0_7SfkUYdwEj!=4Figmo+xbzV9#5ktXNL-I$Vrx&D ztO=oSq{nutwekeX?R1=ULTia!>r%fKvG0;~jQ2+_oZNT=`=-FnOL%$0PCDo%^<}Ad zadWpQ>0wg5-OM3<xZ?&lTZ=Oe?g;BC&RlgvpW=BKS5XjTEm?(kQ6wyMRdA};MSCZL zRI7w6(k&ijLq#@`oXaxsj#S(gVhrXI@`D8;tuI7ZOe6thw-llJ$fbv8Ygu%HmQCQ& ztIV}6o3kiM8bf_?M!X{<K_O)vSN|SEX_n{TDf#>v2FyAM!PrM^wb=$KrbzYMe-W64 zCmM%*GW16eh&L#f9G`V2)gX(1dO9}Moi`u1#fS6tD6W^@rOGBwF9+m?vFm#rUE7*s z=js#{pLrP_2y{$);-;|HAck9glS7*~c9L^`&yfTa&XZabT0^}LF<QbZkOTRpJz8He zBYtjekbTDfdB0BdGiU(jkq#i}b=n?l73F$+VCT{N$CY^~vp%qD92w<@=*%G#y0U7Y z<f@+118Wc;!LA<4(m*5{14^-k01BvjNXXeQYtOzUa79FtARCu#mA=rk4fwSDFkUuH zH+9LvHqg`{p+QX)$G+Dh!loD2X`iy=lFztQ#*Wr0-ltn^wTB0VEb1%XBg`CUx|IZ( z%@)iG*fu{)3l>B5AKv<~&1gBIXqlU>lv&XB{(WbGmw}s3m_K{!v*1m-V5VvO$a(y^ z<8Cc8*)`v3YdQM*mvo&guxcX&n7WV;&&*J`s?uuN>30skX_ANFNL{tk2TL<%5w{pp z(4)BBh|R1l`I7{e>U(Z(!m9qju1r~h`@@ZsRr=UkKGdL(3tue7d;99TtKTN+HIyj= zRsuOK0h!Y*N9*A*x^+7Mv}$CRN`9^!hP?+5%rUV%n%lb9!+SO&<QDev+|BlW%`XJ; zw13=<wyjVs2#bp(Oqom^SqS`;oT9|FzCTMiVmQ64H{qeJ)8@kfEvPwiM)Ls(ZeN|4 zpXR6Z>F6C(nMzoc>@FMNBx@axJa+8X1XHbq(9>8ZZ(h<BYq#wXJ2;~;;!rerq>lR3 zaLq{O;|z+F$|NtWZ*=B5x7<73VC=5pw=`bTq2T2LbZLwVq0rAZCt8EuR8m=ro{UZ$ zGlQwx!9_mu>{#yE^?a>yt|ayVNCA8aM4W%3V%`D;ViV*GutA(Uau(8SKZy81)?BMo zn@&`7*XqVF_WOxcjGcQdGN*G>=OT%9^c-7<>4TC_8^!q*9*2>y3>{rdKZ5iz*>=`i z@<ITE>C7s8vC+WI$eL+aFP}meSw)ksg>~7|ve(nglEqJbHh>)pv&|7NkJCqkI$=jT zCI~j7YXp(~Vs^svi|dcF_5GN3(Mszz`{ozDk|h3frrvp`?zYk32}FrO*c#}Y3Db)A zn8*Lm);n9h<)ugCj)zmHw3l6qTB|#OZ23tFv16OMiMXgrx42u*KQ&8h(p`6SyDkA_ zE(hxR(W#j#`gURP>nB|u&z<EJgIktCIz+L4w46R&lPDPT*38lAd;NgOKF5awjd|Xq zSsJon^GS+os>`U73*n#~5C^)b%hc}!%Sa3ZvW$nSG3gfNI5Nq0x|)<u0>;HL_pG6= z$TT|Jl;(Q)$4<k+E@$M~lN+?07DXnSA_q++r(7`1-0dR);jjp{`OJ(S1sMuoB!|!@ z(*ln%+^oe+Bk?OH^wcd0%Jd^@OE<{uqnizdiB<4UugNm!uRS44(C%{ZO+2t^G)P8v zHTsl0A7tt?iaO$$&Z8hJY4&rO9%kSD#en%;>XKWptdgnFmxEaD-qXot=>Q<bKFZQv zIaSRrjf0xpzr=3uL4VC`|Hcw^16R_VoMKp)$+Bow8lm&qV4JzenZHb<FjtG{E|vPZ z5*j4Vp8Attp*5PNWgTN|3LT@ns8@u=xAh06KDErvzH8}bTaj&|RN~qXHe__U+SS|6 zxh<rXlQAN)ov6Vkyy+d-K`gQs{*R)2acA=X{{X&&!_J%YdFFi9oDVr{=6pVuB%e)` zkVX<Z?cf+PQX$GIgoGqYHKRlhBZ*RNP9gP0lBE3h`v-Pi+jZ~0-}meAcrvP?bPSJq z>M2Ppt4BJDquveD?FKyzoU>D$u*5UuJLyVmAWcuE-mafn(UB(pp!O=q4nr~x23xuA zfs9Sn+QhQV=9%hTX4(nH=f0zlCct`2AloQ#M$lneteAC+gK}`;iBQ=StHXXuDyWju zL%O|UD@?;IqKzl%!CMDu3@7K|VXXm*{Mt}n<fux7U<Vh7qlJE-{`8ZD_5gttcZkvm zY0h1`W_|B#R&JnYiT9TJdF<6|rUAA!#79Js3?5WG|NoYX@)S^zhNeQx%4)w!R~2S& z_DFB%909PA5vpMT0I?Z#Ia^AD%QTJ!ceXn0^UWYxGmZ7p1`x;eNZ2|V)G))rPY6&I zBG{Q|zy)8<PS=~@?1z-^Z|CT?OW~*-z4H!sWrPYML1&eu9MPL#xi@D*m|HA5Xu(Aq zc7m*jm}j?@3=ui-mHygDj`<oBKh$HxR%`oM)CjFS845Bhl4+)b)jfOPT1j@*i|G4` zACK*YEr1uKjvq{c=&;h4<(9NQ_8gC=<UK9i;=a`-`btmG-HZJdXI!N_BVGVNo|+uP z0;n$L^Sa-m^GUjZzkK@$kjezeFqtl|t`RatH!qnEp%JCLN1ZN?`>`N0o50uEZ;+Bi zlp^s+ghO!Y2ctxgcr+6q%h16M1}X6+COO)O`Oe_ryZAx7v=b-(T`^qZOmsz>AsBXR zB-_>AN8d^2OCT*O$fk(FeF`31P*m)sYvD^N-@)N+d;JOQD-6gjO9<HGBgvk?T!`Sb zT8%}%Jf>L$wuk_kk(VP=<+UfA%WiSB+nph^u!ARDRgQcxsS(j!V&N<9;JHkVGGa(l zh6WvEVv~_zOeFWM1g!L6Yp{pe*GlT?NXs4tuA_V+F+ZiwW$jwIq?~t+qm1MsH9S$7 zz_GTRu6<Tl_p<I<?vP?0M;qVs%Xg@JQx>b9u8gUt1glrXeO79bl0k5k0vG(+X%e19 z_$z?seD8oUSTD-iJPK^cWoV~`nLtQ(f#UlVrS2RGez|z0?*Q}t+g`OLhRKNF=2t#( zh1n5NQ9RjeMQeOxRbFjds@e$#Y-y;s?**xuI{ZHaCXf^>z<@QdwYsJ~n{mwPv(@VR zWWUS{Ln9I;gZM143agZ6dDqTv*)Er(W+UFE@533Cx5#A}Q%Qm4FVBoIcZW%Kis}cJ zLCVQN=GwiTbcSPSka7(WYx70xVN-FCPbF&T@B#rN<e8I5$CB@{Cm>Nyy518)o-hZ2 zbtPfSFxH3Gncv&9D~tHstK|yHj3$EUqfhSw^Q>4UucoAuP6lGru>eBu9pLnM5Hwjr z))NR&C+fE-8~buhCG#U?^=^qDH^*TO6B!uyYo8_r&>8c6rJ81F`5jx*-CRa16#E_; zG%ZFlq=Kc3h;o=7{mnh_IrZ9Sg$%7ePM!#F{|r!$1{C}vhKejIk&W48dIuTW+US@% z%w5#J!i!*7BRD(<QsR&y`a@vbH-`O6FCz=ASIoe4i8QwZ^-U#z99y+91#4T*&-jOt z)_?{>VAv>WdI@Zz-fP+-H7&Aoo8dpQk(-x7!KU$*cI%V{#2wY~%s<!UDxZ`^q8b$_ zujqjNw@**zKR^uUZ#+j@h@s#+^rlmI8|S2!@#-D6-j6jo1tLs?2yg*}Q|}}J0AOYU z?DQE1P2r?8eKn;@{EV-OGBeGtv37~1+abbV0V@ZOpD256SXNtHi#kOBTa+=gT0thk zq}8as9J90-+cjqQ7Rgo}tV`t(pi2L(M1tdh3Q-PA-bc)QkFNNCPsr_`O8_5i1)G`n z+S~N|o;=zN8Qri0N2EST<RW!UW4m0XEVi%U&c)s}U>uoc=`Gz(Smf&73EIaLmmxd4 zy!?PwbZ~7r?1F(_2~BXZTfs(s*<Ez>G<T48<=_y#_K8k<7C*0P+#Z<dRVfA;wgY7( zIlYNQc`C(F`9*&4npV$>kb+ai0qX0qLnv9N5H%-506-%O`-sxBPjXZ&LF8G~+XrD& zHn>wU075Ly!S;Q|2`b6lw2@QwfTs@D=Zc!P!QR_8cVzXBSbel#^0l#fUp>q)u-R)p z_0U1NMOG~ev@aQ?yT-wnfgRrUHc^RXeLlSDa>yiDv(JHK)!ToC<9uS7it(=vE&gQ5 zs7ADz+f*7x5pDDxO#;Og6qz>aBy%?7Ic<DXR-0XO3-mB->s1<}Q!30US8i)Fuf@r8 zcXe0V!6`Tzn?{tM;Pgv6?OB_h|KDg|k3-NTM}4tpcoz8QU$Nh2Iu;My2I=}kUV458 zDzRMsa|uu(x}Gn|pqQhJrP#TSS0{@cxaSQ2`qL%?RG7egKgPu4`45^^HJ3<>I0ej0 z&^|oKmMoiEtmgDw<YVZkmFqyoDa!@yQTtUUzKo%z$kd~5?N4K<v-Wy?6u(8<%M11O z+SfF{@iUB#;9We^8|wj4ZS6N?YoZU6Q0es_(ypP?ryLM%#+D?TGGZ`{lyDq;urSEH z6C{%?-jrc>n@TUSSt#GD+e)S*sK84v{iVxvL(9{Zid_qr{k;*_RTAl%RN$+$p>qe* z@h>dy{Hd`m9<mMWh+r|YZ5os(=p)Czxu|34Z3^2UK>34f0<ueqdno7%M?LI}W(7wh zySOb03s<gew(ut%krhLMV$Cy6CP_)za5Ds0&~=qxb!h0sU80HFhce<kS0fEcjlv2> zu3-Bn=Aqil9et>$7aOhDNcOmRlRk#l638&h(5@IbHnvAoOr$H|K{^%t^^48T-aqIr z<Y0APnXiKMN9lT-@~8B_Yeay>7k--0H0!xCGGWHG*$lO&@K1~f+Oelh+OH|I6QB1* zJJaZfzoitPQDi4pFJ11-XF<a%`FX`oYCFKHx_tR$qACO=YnmGFlscF@RCCZ;F93>j zXQ}}R`T*K5nvY6EPhxYJOB7m$MpVCKQ10cEJFV-SOjPzHO(ue-0t<DDL4ZK)fo~34 zQ#;K^IoF(ToylgZWidX>rdx7J=6F77T111(u?i-8UDK3bBAEcN)~Df@BEXu#VA<gZ zS_mdPwaCkM&NvZV=hdj$bkxQ&1VLcyr|lWq*sSLr;Aln=v+y8oSCIaMgFb|0o#;SK z2T1ZvK7Z?V817vpeyUG@`@`~sIpiz_e0C}=$^hYRtWL6P52Ax~-%4o9km(!y?4^B) z(f}fcb{$L0FMgPHC=~tQ@cDvuS9jld6(Np{tKbkedGu%Z=%4@H(Sz!?01eh06ec!$ ziyIDyqC?p2T4!tyowZS70UIAE64-@jbN%n1f3iUjzvEM4d~%1n%qhBm=t1oCCZ)mb z)D%8?qT}QrOY}s2>RaCfb4hWMhVjaG$Br&UD-XuaJYJa4@h%&Qo?Y^4>aWLIl)X*V z96k{^<Cn@Ye0x=TSl;qNHBI&5UDLfUlX1FV-Kv~Up-i0a`j;2<kILI${4+DD(DC(+ zPD;nj)6-w#g6h58$ZQC3LH2Gyw{wrf!F;Uk%e<7uHw@^6M(Bqk=*?eW5!#mrH{Yh# z?3-?nefW6k?t{l8O7HIfM9db7+%8Fa6#rQhbbP3ocy3d1rAmZ*(<YgvmM@`&#%ZO& zfQ2aSu{A<QCv~>%iqd|-=blU%`&;LKuYDY@JNW$8g>%3D$L|;2``_nZ-}g*gftVb4 zg>C#=ryAV;m71d<q`0dZWgB?dH-GIrPAJb1BB!2bNOg0*<wYIPk~<kq5e7t-PHW!u zD;$fIyr9d06oo9ESd=R!gV<tzJ9~#jXhq>e5!izI6UQVYN7gUv-Fm!|amzEIHB<87 z<yrT^o1J$>N>diO!sX=Vc!WgUQi;E3(MopujfAb>TI`v}hcmI&xgp0&bf3u8-Adh( zOTUrIojxu=0iY@(Dns0_<!76t?!Yy7Xc3s;(30#M$t_tbA`srx@tY~(zthDdHpMb- z<fdAQ$V9mE8LY`La9qA^=!a^!sp1Kj>oe2<VVJu5Zv&M5gzuRy3b0QNWr11;A)IT$ zHJC$kVnVqd9j}A|n}C*n?C+sBTl-J-ypax#8!&h`b9(e=zw)`E^}2koS(P-XGk`t! z_TS2jxhDsqT~y3F+4D#n5xKopRipy|N0I?tSr#gZEgWzu%&RSNR=$9(yo2>j9Mig) zX*~T(PSB2}m0np)QE!O!cQ{eT`ciqUBt={0&aKFbF1O=l$&-f$G*bAYr5=lS+ZL(| z##8j%sABSEQQO%sYHFT4>_q8)l}j%=XDPQZ97#5Qyii{7UPB^3eR)YPbz2s6S%tUs z<(?;su~3v8WtF(^sbrU`h#)Rm)qiAa`$hPLt(19LO9xqoh%VOZ`j!1lzF@?@ao0JN zEvGpAnn|3K$7Udp;2<5eU7;>0{4Q6ajsk~{qV2;Xz0vznRyBv5J6~0^>^T)_*Uo(> zzT2KF@Ci%#-FNbapp3iMs>n*M6J=uTS$|OI{g46GJR&5n1qI+d2LpnhAKotZx-w7~ z?%@f<DR67~y;7;kD#9ii+C2;X@<dMF$?kgW4}x3rBL6Zg)?M7R$L(#OV_gdVgz^$k zs3^Cn2%)<y*-CwH#$HD_Y)0syCEpyJXouUSWlQ|PSGX4^a8f4b#08~MSB7K0AFT@e zf#z&>-3S%h$w~iFktsGHXqV3~VRpET3J1a44*%$>oE9PZdRn>*g6M1H%Tauc&$Pub z!~`K9axv6QQW_9(kmj%y=$B!69f&$r^g<fP&#<ZKfz#GV*voem2_O)W&hk!_<qKOh z5iwD$y)^M%`n?6O!oq9qHRp%c^N+;RrQYyBvb8dz1cd0hIXMj_k=D|+bQkp57GIfe zJS45fL3{(BXQK$boDxwjw^N*<p1NKek{B*Hn!Z#spB0lwG8N>e-y}Eqp@Xxcjv;N_ zM!Y+VUPh?OEo8m4F^unv-4W9GgG)C|6LE-IQ#10Duk&WN=LIB!0i{!Kz$pxMoys(9 z8OF`k&LKabI8C4l3ahUWtA!7wVdbhbHD=6(tTvCzT*o;1752abVpXuueVq_PIQV%U zGcnMYfrub5CAbwLH)|NO8Td4=QxD=84kY<W6Mm?LAf5~X%b;3C2>@fOWZ9awy<#&Z zXI>9H9q%aho}C`L+pGAgYd)y8G|0UnM`>?OU85G5vHmxcbpnv46ee}cmPSOk_+w%Y zfNw!kC~!crvt2AdYb%l@bHh@ER74r_);@|I=2jXm7Ua5Yf&jx6euR|x>=TlaHsqa& z07bu?3t0vl0U;S?G)>csvWx1@zuga7Hx{LKGGqkl2d2&O$S!iYqINuge<LxUvYn+| z$LkwzxjU*;86l$w8pkj3FS|%`wIdt~>~0yU726z@<uwVDY_8{>B+QFfEjgKcR-=7o zYvg=sK#xXpmPI{1Ul3@4jN+N6vX9oZwG1x@QZlr0bjZ$I9k@1sPsFgEc$S8nY)o6p zw6ku+AQwL>i^t>ava<FAD)J8)l~It-T@IHxipU5g60Kd8|7ZZgsyOZGyda8N#+}8G zm3;R<ga9R21gW>FpnbDAr0I%uwOSy6B9tU~gDYy0(W<k=2TAU1e>PtBgWGwkd0In9 z1B{KX2<Ck$uamzVTv0)IL72*8mQeM@_>h?^Ov&!4eoNl@ypAYU>CKAwmZux@J*Z5h zT)|XzU0>b>^6aaLtnV+h3()(2q>VObISom75{?fEvQUcqP21xO&a<+lV}rBs3B*Eg z)-m~qOU$+<*2;dsaSW3Hf=AQR4tjEAf@mPIIH~^9Jyjsg?CmntxFB7>Xe|G=PW0t+ zUgnZ#9p;b#7DNz*brm_vK@S^J)w?KLnEN&}lUtAa-|#Ofg5gcFPGYir5dcIA5M5FJ zj6El6UB7bA2&<eN<td27X39yQxt%Pdf{uoe6n<2sYvaX_c+)|Wh1~uDKy+Jiy|%K& zYbf9`T^%qnSN1q6!4L2;uWG$U{tsJNISmL17nCslAN(jcD{j~Q#*}CwdziA<O%r0l z5`HVw#SB-pDUYGJD;R^>;z!OH9_7|$$(fa{BTjaLJdM9}sxOKCblu0ovWhdZ4Xcox zS&sOFwPNEkdXAronw;D+2*+y>>GU?-LmWzW0t&5P_GJUFB&dVL2gxoPYjkL43-fYb zxuQg)%H45FpAzjoMAOm%@wy_qV}O}LJ^lK_&CfO$j7!i)xmD8M#kZbH@5QYRT|ph$ zKDZsRTk$`9mrN}_{SQmU=Jz3eIf?52TnA$`#d1~#@b{Jd(G2L-DJvZS4+>zL!rXlw zlmTnTLsuC!Q82K?8?s02iDty&>B!iwBO*FQt>_rG)t8fUPWm(1$76=T$Z9g&G&DX! z;@AWE$t-=d%}O;wRmRLf2M%ajlM_)N;}%6%(P!M~sFYEpOq3GkLg!^`>2e+Va9#uW zP%m1rjT~1A00G1*h$x5SiF-UAteJN}gpQmbByCmH7lAS3|4&x2%A5!wB4&s1p2b(5 zto&hfzc8ysVAaheR-#=`^|c>Qoxt5Y;PXja$UJ0u|MzeE@wMW!M1@+)1v@X<O`?o7 zUnYEBt&EPXCBlP=hBhGAGNNJ|P$IZzq`T>OCvc|$2-pN7gDKcjPIO?E&bYqT7SR6_ z=nJ7<!IY>N=8AbzMN=mlHGoE{dWI6{9sVHnS?3e-YDaf~@?4-qtjKYp_}JWVZj#Ee z48GiAB|5sN91D>q^94^ZLB$X8;H#=(I99q+{CflF3s4;408Xb^hA@e27qg;x!B#Ul ziwFb}0DGR5GKua|Eq+%5d-4V=5KU3YPq-IF)xkW}+0t}t5l_qv0WLz3{8zbumu_o{ zhJKubEQ|FL{-?|WB13`F#pKk<VUcQIo3)A;ooqDc3+xvg1;B~f9Fv&hHE;At=@YSw zJt~Xz>+N*xGm^SymXtYN=3oEz5>OgTmowMXx%^T~c1{dWS9b8$Nr-VXuEd7FR_N~e z%Q8HXTjPGQ9-B~!F0Iw2jw`VF^4uPYB+BmA-N+@P@(x*MkS_a*A}>NL!$o-}<j6F` zSIpDVjzFbcO|6S)i8hp`>Pa;dU|@2qTpArK!bfcMI2KV9qWN2<cx4efDrDJgZ`Yr= zg+q1_kP|#<aU1}1TKp6L8TF3RzY*xI$fRSKq$_inPBv1Ua<+}Ou8xK)@|AZe*#C*8 ztj3$(AH;5~%NEj3w6T!@pcMpKByDUH%lfqIkH&}qqFZGMK!CoAGOJQhwNmb;Vv8&3 zR}jB5dbZ4u$+&86FVc<W!CIHIby7h(0GgyF(Q!3b;#`JS4nv9xRC);nB%l-rf5f`h zM~BpQZ2{%*MA<FimysXZ_bJLYbcNC?39EHIj*w(+&%^g1NopnSI>Uayn0&LNcpoNm z8z51Lx)}#DJSgVsnjvrQFVWm6XMFM^;tFzuu4?S19IXTPFhK5w+!cfYon9fs1=b%M zCySCW0t2u-m4gWyQVv9sTmYt7>%}e@{fXVTinFd#LxYIu&I*h?1-?i?Y|<NM$4qtZ zn%<o#Y`?RAQ3aYd4&|`z9S6>B&{R&CAW?;8sx?0$beZ;^t$E_;MT$hThioYYOQuLL zPS7VsWDHfLx9D@uk#hAOinS_z00QyX+HYfT#RiJv>V&=zP`V<2uK}oZowa-bHNsmx zc3yqH3@*MzS6q5vS70pd%Fk-?(b;a2Go@oE_Q`M2WujhN_q%ziMk*@iV6}mgTYNdw zdTcaB@|I`iB2h+NWwo8Cpzojz`=V+qDQ?{-yZ3>OTBVWAUF42b|2NLVK(5LjD{@w& zC^Ei?;rJNYN^~&})4&#Cu+79)EoD{Uoj4P8w%7`J3IRm)0pPU_4f^_a6B;(4E%)AD zcW6@MRFC2$5so9uwBZmCAv6GZdY9?BjzpOEUt3|ryLplTfQ&W}VD5ySqV;zW5jl-A z<6JpF#p8AriPY1I*DKZ2`D(X-fKXyvw5m;-hav|d9$l&2M3lg42R-2!nN|+Gq6;>t z6%5zK4}X`O9o6gX5qxtgYrc0@oA$mj1ujLhv{FIclpAs->Sd*Fleu&v-|J$y?HwWS zPQJLHwDdzo0+y)P?x1L>qOez`2h8_5c>n9sqK7xI#Nc$ksza}&u4Xu@65Vjd4Dd4K za3%^uLF@J(K2hX6hm$cqo-4w4`T<Ce<%z7Y*#`u#aQ87NKKdWQT0a0OPtVh*ixYl? zppsGySCf3+V8yR1jT4~rl_;3cf3&%8+-Nkr7ll%RYac`p6^XS2<s6BUlUt7FJ>oXU z6iVq*c#6~wifkFslgt-Sti;NiJ@QtO3wMyUu0(wnvblwx+s?(JqUEHk<wLGn|H{|M zB&v+`XbwNHqg-qEKl8_!@5$~_cnMToq0mo{3|+4b@^k16{~q&)9Yoar!r-L8bk?)F zBDqL$wk94eZH(SK5MHrJiHMq)(?m++`Knic9*ue_c0QYA#1NnDA=UOsg+m3Rf|r3r z{d;#L2XNZ01&ratHR(!WbhEIDe06CwgDuj{Ll^fVAM-HRzp<v=F(4wekB2e5PtLB( zJ!6qF*qJ;cdn8!~(6Ay|D9F55nf|AShE&35$mY+FS{0_F;#gvK^Zm_wbi+!ZM&*s% zpXh?zNFYr{pjjP@LRb1!th7rTQhc7N+Mw#)S5)M1z~w5stT#ifIG=HfBfkQa!P8|X z_~Os!G@q(;tPmyQJT#wFVlm)y$z(+W<odlH!6QSeW-{Pfn&bf?K$dtkPUGLpYz6jR z@4X*%sWkpE>ln;KV5~vnV@;&Ql>Z^+S@F#V67;KBFflV7h^)e^yvW3K6M`=G%Dv@D zfyhFWIDjlo2?JDAP(caU$Q2p}wqY634~@XVH`r)Yo0zzY7)S*pu7i@chK~T?07Bk? zW!}5(WW2RtP{`x{0#^H!3`$+>dNrmf9kUAfG)vBX%!V%AkwY~DzfEiv0s-#+lAe`i zM{A^xrb%m4WLD_6%FtOg*;0f`>Bs}OIn2>TzN8^terooHkE+C{wB0HlHTg<L6;KOo z`6c{Nhh<MmkXgM8P-2AmH^GqU_BOhIbzy7yn01fTHqbWTnEt!xR>MyDp8T+2n~p&A z)}+6^)Im(As3JXP$3@O6#NG$$ReAq5Ri5%z*6%~F60SjxnSGb74}C#c0Z2KsWhUuB z5YM`Z2CuC^l>v~u+AkvdE&o+OBY0QY6|l6EFb)BeW+2uAMlO=EyA-9`&5*}TCG*ni z;X9pqH$$`P_OI~ogsLDKf~^5KIAUM;Tf!j#U%aqK(y<b_Oq59|mCKEibM!F~dMJmF zlS`16mJfDWy1NI1By3i;<Gt&jt3BFMk=CY5?*J7q9%^{Pmn`<b>FzJisvN3Pv1zW< zK5hKmhw?zOU2lY_fFt^kn$zXVdg4)+HcglfLI=Ms2Yvftx0gb12%3GpM3>JJ5!@a% zbE~2{K$nI#TBC$?9g9dmD3Y_460En5QI!{pRTPptiJ{eClbaY_nI5vK;tmC-*#iSr zfNLtvpmccKR9N3wJ)o~95&(&)5DEbd9j<_sHi&HoLG?%f8}21vePYXcGTfy>*{c+j zqzDqQpfeS)6#|<L0CZP;e3>be%uhYZ4>#?Rj3TP1gv;Q2Bw?iO*iwarBo&ky`X&QA zLYK$WrS&PL@yF&%!(HO6Bu-FdxqR`jCiN8lf@`zF7DW~hba;EpX64QE-#}?+zT)Op zzkAmua&rx)?oSGDD<%^q%;BeeX39h=v5pTX_wK3ePoXF#J8N9z&~j_Lw)Le$RpbuT z=y*0pRl7-GJSsa4B{uG>Zc-GiE5i?@-7p19LcG8!!1AC?vk<UQP<m3>i!ebAzlINI zu;F2R00<|pse&-htcQuOA9&x_h8yyO-3cKJjl&;5WJ`W0Dy^v5CdiB|Fzu{A&GDIb z?F-m{J!0GnnLe7BD?gachQ7=kaZo=>C6+3br=CoeQwK>F^SyBtwY!vYF|FIEDCOXv zPR=zW?GA;%*3^UP=f~)Z48Hb0zw3?khLjA25pxMcqO7;l7XU!(Xv}K=GXrwZvD{<I z34HMt-@npjF_f6q7oYs^Y-#hBkL^wU^SLQ~J>FZ<lr9e&(@Z*Y+uy;<6c{xMlz;Z| zxcpn)%%2W-RaA@xXbVxiSVeh<rc!imToKq^OjI`Rfn$uxhUd^#umOqDuo(hUAi<2& zpkX~CARau64rTK&pKyvlFDTxyK(Ya|muS#j-s=(pYjIq1sz<i@<gh`={O7sh^3S$y zlBSP%i1Y6ScSo6xL1RO{_^b-HUhq68BJ}w(^%Uh>4qc&ixsmG%TowP&O0;zN<XNF- zU35tTUv`9Vkf0&~01+NW1B5{J{lh_;VL!LU8V~-jv@d(E!KliD8fqI_96F{Z$_wc! zP<dLisW~QZ9o)QP0N%40k*YniTO+1m@x5l`>KK5lch;@=Vccxrna0VJx0^klj2y|y z2&fu};XRJ$Oc^vzHaT?(@^}qDOCOMJjGyZ;(|eTKA3glR*`PTz`bQ#v{DzmZzDxfW zrQwdxA(O}*bN*nzzJmTf=H^n@>AEZP)@hFu>GL9j-TP$gxz=it+*0eXXEQr#_r@d% z@f*B>2mSfV@8SU|{Bdm$sGLQ}W+#Q|RNxqa`)l$gzb2vZ*LQ<UDBH)I%M*=<_f73S z-ugE4#QxOx{Brwq?TYkSQjU}Ws@qtWcY;Z)A6TD_e}Cg-pr-5D<-F>Hqc%@y4%vn~ z6{nFQuLA={?Kn}Ydv5!F;-ZGFx(WV1W?W2BrDyXH)7z9slgP_byOPXu+6)fxF)txk zq3y?foz&d4ZUxU;4X=TChNTnZ7^6?D<f8>zVb$U~oZPE#3BbY)iq#}SXDn}W?ew4y z<j#u)zqhO49NG5G2SYYLieG402x41@O->Iy%(H8re=}tBG|@QE@=2(1J~_?cnvd}t zh>45*IZN|HN~x<o!ZJ7G7fX&O#U9I4j`rjas5@C!I>+4V5z)a#N5s40f>x9Ikj9pk zBxs<ist91QrPuq+bV_DS^W*P>G54Rm2RGTa|C`HJ4SuCEs+U1#WZ0~4R-ui!T!|dn z^39DL!_8dFJ(OuT%Xm=xji6g<F;U-@Z`qtX3o}Nh97S4w;xfH82LbpIyVuE<K3*T^ z+poH5sMcgN%UTM(yaHCzuClj5p$le*mQ7&lM$Si(-hdmgjQRn|0kd{pEC$Qc^{vF~ z|8{8-{|oeq52a{6iOoJR{Bfe2a-fNpkZpIY+{~8?zISF&`-kP6rr8Jmr%2n9&Z>O7 z;ud4H#T+@|p!xgQt7y&sS66e*OQ=LwrL#)~+A3k~L|4W5Sm_hT%WR`XWe*AQ9Tl(H ztt7?7O<i|VO_7{^5$Cx{c9gK_eEh=l-_T0Te4&qb%0f2?PP6@IGvaN_iWL-ByVaQk zYELJO_bzKChH^ajHO_O;_S~hpIqfDqc-U@tjRCcN%`!pnD_I>v*e}@JDR9%@NPyY* z(*9KDjv-E{X9LIxf<1OIV8lu;KcMC%fC~SYh5PjYu0FeAa>eW&&F8{TUaoz(>7SZa zapuRCLa4=V@KM#@Z%K-!6`~fb@CRVk1?^2i7Orz8(i;~+cZd<UP^?Ep+o+xJ*niMY zTg)uL_oTv)dg0u*f;{W#Dv7KTXY+BIxs#VO`kEUUhn0GynDi2LZJD8*&?)x_C>TSu z>{Awz$&hZRSy=hLg_O}ymzsJL0-LI&?rU3-|IR7*g!D`QA;NS8fjt{E7oAif;NspU zQ*oRps%sdJ*bW6r_isb3i|SC<1r72W0Aa($N>oBblRJI@YQ5Bx#s4;|CCmJeT_ls2 zP;^wbj@(-uw`o)q+N&<FkQtaE)W)n}h}TZJ*aEcgi`yn>Np!umOMCb1bSFssv8Cwi z`JV&c?v4>PZ1)>i#`99wyk&oJh4M`UiT9dbNZqIq4YlkvO{IaPH#!}SmyB{LLrkf& zei`PzuGxfiq(rXO&4}+jQERFIJT0E676=Djz$!R-jTDO$wy^1|#5hKzi2;FG_Og{i z8nQs53yyhs_o&iCP8CTRHkNfoT`)OPW?$NS<x<5_`4c>jx^F?YM<-)Xsx|9{x;W+5 z(It}n$s!TUL{U^6gej$?^wMfj3<1z@a{m&1$ill-IkbYQ*jFrW`RSe8wqLsPmn>l| zKs6$xFXy5kF<Q&3&^>V`U$S#bc%R~|@{Nc7O{zu%uKIn@i>u+ue|NAdS62q~P6)CL zLn;pBwq1{=RcRmx`|#(d?>x)}$t*J9q4TP_-n?0{$H^X{8$dH_F%iioNT7M>Sh{W5 zu+dpun)L@NY1(n6JmIE-N*Pz!xsQ)zZRCEC9TQNZRTzM9lxjC#SWU4<gh=M-UAbCj z;GWpoXAn0}duT=eSgkDg*Tv8#{_=l;;Zke3etYv@=!^3X@_+YOFA4Qx@a-su<Znw6 zwdirzn0gt-lS2LY@Oaok{Jdf*xx_-g<7!!Gb=|w*uVs_1f+aPO(xf&dv~kew=Pgok z$<l&7xnS~tUAaxil(JL#PFJE@gv8$jAA0TWui?Ykb}y^=O6b^-idhBA6k?ohtB9yi z!b^Qe#QRMMmHD0clM180&bH2c$l<J`*xqDklO=j~m@hbedP&}-wg7Pf!STI(c?cUv zBAuP}HMzHt5c`;y?$CV<-5j51yY8E17+Z<i6Vm2Supo|8-!NQDZ<3pXUWnY;(evL; z-0(N7E{ntj^Kfk{&j{I9CKyr=D}<y8e(*r`aLEt8clWFfFQ9|Tf@ZU<nCl>rcIpK~ z?EOl={2!q5na)#JONWY0$BnKO6okwC5D>Vph$#JqDy)ciG|_$HS=1V-czyjps~s_T z@T*tn8@unnROc976qGV<u!RGji?%f05_<j<mu|dNAYHS1RH64xruWm<{3EPbx#u>p zLFanYT3e<;;L?k+3?lO6cQ<8DREBxY0eIiM)`O_io{_H>MGek&nZ#8~syIK)Bz1lp zY92eTh!XqYpxD}R%G(j=V3KuQf5PhZz>o63xf?~KK<?I5xJ>5TndGc0$&Pv-yLJlH zqkc}gqr=61gnlJK;NEt<O1Ez=$T`V!kSN96F!S6q*sLrhDV34AZnFZ*uc%k91}Cg3 zs5+iWL@x!5z7UZ3ym($?-khb=dHIBx#I>W!x3vE&ShBF|mJy1WuXi~=pm7IqtNyA5 z0}>?Y0>w`>X}^{2w_&Fv(7h4LfT#?=RrxsJn~?qwvLY7q5m3L0YPq<<MVl6BS<dPS z`KB*U3gZOGtK{qOiicVsx44g<xvgNLrx@5^Qphl`2Tc+Jt3`i3wr@g3EZdi)AkqVW z1wFVhasMCn(Dx0pSw9vK7bnQFhWaF{N-xWvd3!MFY0L~qzDw3wOS&i9u~R^f5JYL! z7g3>e?^8;XjVu$CVp=fprV9A9#Mve49*U5O5`3i9n1q^<7~w4HH5H~rME}JH5-h~i zFrLm1_CHAC-<h;F5nQV;di}Ionng12G^*}6!Asn;+XMz^K|7nNF5zLX0ddbwF+Tv% z9~Edf5^|FbFK;n<%tnr2WNu|5Y_B>DSD+u`wFDq)30F9hB$vn&GB5I}ei$jR&yw+u zhsmPiGNN~+6dv+L!vMztXB^X6qSbzo^a_zsf@ldKbbxZ<+^bAItti3y|K<bK&_kzH z7Wy{^QNV@@MAAGS^gauI8w1IrO6}m`S6k4lWYnYU0`rvihwRb0MZQsS<Z~6Y7!&EM zh5W<5{6_#*C8PeX?HLHwCdq<P31196Es%e>=w)6uJS%2}0DCg&E<WZavS_zVMcrq^ z1e{gvb$AIiZg|U;$7RUGOV83U=n3TboU!VgOHn<{pDl(Xj>r+JbQ2fK;SqLPj(Rau zJ)MnwL?Xj5BvA`UCeJ&nlbS$+2sFG*mguPmk>x<h8J<ug3-a)qD4iu5$`cVFm~j=y zO3BCnt)VZ}7bu)?(*IHr8i6u+<fOKY?qWj)jO0(A(>o399u@Ly{q$pr{mU#=bbDwY z75<woavlKt<cwz4qxOE~kf6EC0@JGn&1GGxxDGc4!XI`xFA$0V1k^I#c&Xx~o7BEt z-#w&MFno?|b5atXhugp5kT+s3m7W0=ppJ%g>&L!m^Gb;)lJJrijpyy24{2T`SL=vY z^!mDVrj*vTJIK%NUhOp5@T-SzIf)2FQ)nG2tW%E069u@Hq~H}IYD?}>L_^8vfsuzH zheYW(NE}-zkPVZwa#9>9z4u#hYwb8z=O*(d3USTP@l|3y9>xJ69<}@@fJj@(F|q;3 z*963{uW2(CmQF(e@USNpsIR`LaX{`)W{jg%;BrEk!1epgF|?~aBfOq7nH|%Vr6Ol? z!__SD$Uu;cENVh7r;7$%ARyj=jg^kxE)z0JPlD~V8Jb9_T2{LM`t7dH+)Fva(d^|S zcepM)0$df3h8G--=OZ>-4C(w+gE;609=X9wJwuKBT9Y6DCjAyshsO0w0zgi!iQHK* z-%-~M13=(VU*xi=fPc-#K_2miO4(LVj4w3n)F@irbZWTptEJH9xaJ@pdKCk`PjI_J zhH|B{uW}&*B2!@eE>r!&)GtOmq6*W>*^tB)E}E?>QHr;j_C^22C4C{J1VY6VqRU$$ z@F#>EKy~<|4!DvEVi#Bb?sxVVD(nX}5X8I<e($#4hF(vHhH%iXjO)L$)&Ee7_D`ux z1|t8XLkY>SA})NBw|`QglM>J;3r%-$(C!xGdjTLv*gKR}fG%MR)+!)0p7*{6QoaKu z4Im=mKf!k!iHR9$y}~rYVc<2<;V;59I*=riu$^_y8~1ykC^guUP)0`0uvwvD|MefN z*g70SwaaQ1gIb^=`81>;BIID{k$GNrrR@INE%b^nvWsol!WF5&lz)NMHD{sJiA6j8 z*YaA>(V1tKSnxWwc){72d2Y7<yV}w<gg5=a#x#k;P-HVf<f-J{|EcYh$r0DBg`O!i zIWc>-nH5}Hf!wbhtUONq!a!JNIDEh(i`c2YA|j8*MAFIUx@1bou8?yCpUgGVeWUXo zS{Xk!OK4O`#~B5NFC?2KoL2=ctv~*@VejGLCyJMn@BR1s!dLbMcA;PI26_}9Hh2j6 zsO9utMfN{x?Izo>uLafm05!ah9;3o915ec9p*w;rB^}Cv-Y4m_0O5eQ1O9(m&{hCo z9E1904dcG6{fet+>|EZ(A?hju9`{Ax4pcz_;l3c)UyM;;d|;Eglx_yprcKJ!9J7mu zU3WzOq)N`LNqw9QrmA|;3LJK5a9bv#E;Hl|01`)F5hfzf(W+Ee%-h$^FRqC^6cY_) ziDa*dz7jnw@Pz4WqGYZ}AfEXbQxh8V?8{*cx$zm}C2BYxeYg*OJfZLw0NzA}jZ)#3 zDe#Lopmi*G9~DtShE=TX!35Ce1fVlL3iYA|wP}X9uF#To7}M!2KIv92==yaFSW!8+ zuN(@R)kU&OL~qz1Drx26&u+WJ{(FdK`Z9OS#IoKS{ZvKJq)dAPk?lB<&KA|z_=rP9 z^e9`)=<AgV>gmrl=!-?@X*Mj7C6enKQc%@+CrBsybUKYI*W!1K<qtW*6Fx^h|L`G8 zz+W<WPlKo-r2v5IisC}fvs0n>zCL-@-e&dT{k<i!=KcAaG7PkU2Q9-x!>NLN1G7JC z&%$F+d<@F;E{e|%P2<7#@JaJlbpRGEy8ZMsUt}u*8cxO)>my<Hm)@3ic4{W>5@4@= z(I9Iz*Nr_fkXYE0ft(Bd&=`8_s5J7MHPY~$iCZh81rK{nhMif^029&d^QP+}&9-W? zJHGJp3iMMP^a4#J9pFQ;Y})SYrf`L$sU+m1Nc~jEqj*UBwWe%5<m-IAz{*aq5Guww z{bC)bdX65}>;E;BP&#$*&&<8Ac*N`tc%)v(<?dH2Y=M=Vv;qJKbl=$)V=62MK(4Kw zL_fkIx^e#XYX_S#@I4$7(@1;!J4Xy2{r>H3_=B**&9K~->$J<rLs~h4rb5G$lbx$F zt5KRV^Vh4{m~XI7DIw|8W@rURq>FiQGEuf!P^fHy_E(5fmLk_9s)jt;kNE2BLiQ|D z*z&jJAOr4)vs)gdVIV`71uOUk55}JzIy@R<TeH17`6|+HuE%$gi~>wvI4p#Mzcze? zM+|Fp%n|+eF!0hA#40(a{}_54kLY5<A6Gz|xsWdI^?Z}8IxaHCwDu@0`Y{QX5iP)u zo%`6ZLMm+77rnK1OIRiGFAdh``bHu{e2j|9!y|*35?w7(Pw*&94e~LEqZU7o`us+? zZ6o~W99Aun=LM)E0sRCc;-b+0Kf%s2R~VF%5xP}%PYiN`{FbtMESoGRJ`JH@<h1~! z9RrigO8w-UR<!NOY1q4vKBq0b-X0YVP`&uo7&c9X->1U6);>R??!kB0U@QRi-i1TK zbI=SN@nMo;z1P*tvFLjr(T|F!9j9$e&%t8)-~yYt1t8n8)fo?qHjP3?ui9-eCDhx{ zx$N3aZjs3tW&?!!NrTC#Ut#xE{Gc^_se)Hvv_9})H*v6#9mKQCjRnh*v<lIn{er)1 zH{$HaKM|sbc)}0Tn_h)LlDNYk6(F~)AO-+<KLxdNa`Ef8g71GPo#o$2ru#)car%jC z*j<BOUh2QF3%!rKcoi=iA(+l)qt&`l*}2FY(&fw46VZLpULIQ6b`ZSZ?(rM+FScM} z$0Xkx{e_CAJ2K<l#i3J>4^-4IIlRlAu;4<(N(bjBYmdTAL|#0u`4r*#evSEoX8M7R z9PRSDL4X$%(%)m?M`(>}HN!!>jfnu?$L}qg=}nF`ECK&My}!EJ|7H7&j3k=Ka*OXn z|9<tei=Uqrw7B_2KU>`P)Y}-o5c&FE+>_C%^uf9{SmNQEi-fCLaZ5KQ(R_SX3k$m7 zD{)5t^0Y+x_!?}823;dUf8evqiq8xZd-DIF*L%>ViE5x9mo8s`{aDwycS}NTW2Fus z;nb7-7LRtWMvw3iAAHdj?2Tmq^xta@Xwi>-cIS`G2%p4=j_*I#<`*C3TyVv$da>+S zDE?tKw}e+N@?x!;H?rw4m@psq{Z#n{cKExX|MqS^v|5sj9M4nuU%Y|SGL4%tg63G} zcGNo89;=<gBkt1><rw8U0B+<Cl=wU6bt`Q)8)e@y_!BG@>~j0l0L)God2`;ibpEVk zfmBd0?lB>z!w|K@hUMU3Ii_fK6PgJWNhP0q;eGxL=5VwxWLp3Hy|Hcz8=@dny0R-e zx+0v%7IJ5!{cAG4eE#qaZ~7|#JasbR``2e*nyofJhE~3W-X`y7$^LIv>|JjH{MOp@ zK9&GbMKlu*)zcvF0@3fB-c7Zj>S(aP_?~OKim~k|?Jl$lN0pL#U-`-%&lgZBal3`N zvm_DIWAP}~u_qJ0rnNZePFsu#5VO;<*Ruh7HG)lpps@{eFLFvrDYM(tOi?t)MjH5b zd3M3K(w+ue_<a@PDZQTo(irr=BZkpf{&(-kum33n%B;?OpPzp7#ixRpj?xI3Sn{iJ zyJlz*J&N_N^Sk4HC*<u)P*dRF->>DbDLuJF-uou;WgwvDa3`UpE%Nfc!v{JPj|`d) zNZddDW94o8@wg+FXXxNRIWIhvo}d1bsQJ=u#K;P;X$<6vR?HZLHG99PdUXFkE9zf) zzx@^?A5NSa3v_Ah&;HOI*V-8W!2)*RnO_lgjOi5psU`9a;l%4-t1NkYX{jBfsq`Fq z0&Q0NepbIv0wJxNDi^4|^UE>GT3T0q@0AzP)8G|g?a_$l$S==@(YpVhKePYy`=`aX z_n-GJ0Zz6>E1jFt;nucp-ThLQDxcVby(mCBi$ddC`)d;ip;~2$<6`<P)PGhQ1*tpq zSgn45Wo8)!`X=H=h%rU@TAYoC-;0Y$a>9U^=JmzWm;*T(Slh*t%$v~-a>vV3)hqj? zjx1Kz-SSK->6eSU(iL$lHrb6?mA3V&H_yED6$6uvY16)9DSp{7*MLn{FR%eXv%5_n z`&Jj&!~6sjuvcHr-#$0gb;90JBB<!uJ?S$OegL&=n+@l_PY>z<@4sJZJo9X0Gr$)* zeCJVcg3%YwrPbfQ_}K4)u-ni{qQ23d^q=J~cxXztlcbBtSSA**!|!jsutmvLj<>vf zT#;IOM!HPJB;}rh=4oKMv|BX44jXg*?r}-INBj(_gPUWSSNDC4&4TZP=*+9yZ(trg zwyX;1RoO58dt}6M?Ulm_0kr-m$GKY&bCWdWCi~n)A!(bErFP6+7ohoYd)9SdIV=!d z{rF4cuY~nJgCnQ>rpf{yy<btjh@)#1U;MYCB^&5V6p{2#<_k%U+K4S;Ph4JrmXm>5 zk;*abL*iu<S<_nAgSYwVk{+?s>52!*({-hB4VA|3CzpVcH%@M<IOf?Ft3AjuMHQe_ z@V%S8qlS;y)WrVxOkxWDMEJKFYtP<3fsy@G@|b9yv&Mn*>%X6c@2;1NyM#s#>OCq; z*fM-~{`AQHU*{u*EcRja2PaZqTs`=K5m|aLjJO~X7&frr<nLIbarLy;-MZkCU1<O9 z<Fa>;O_eEnAe810H;R_UT#qPJPTW4>C>db9eo|5TWMk&n=%sik*$bUwi-qSqriBp> zTM%Zh;ZjzX*Y<RvNxo5e0JEUG`mh_)aEHC0WxsY$j7Db2v;b+|L~lAgf(*XOFoHO@ z=$0g0eyN=-RYZ5v-=&4wbNSgm=flNs<6rAdQIG+<9QpbXm&|csF?;i<a$0eJzzC(O zuMC_rz9g#e-I^c2238#JblN)=?3ZIebTymgW$GohKK-7Tj~yv?(eE%t2S*T*XJT$9 z^0W#pRx7=dtbJV84r;A+Rtj7JN7aA0to_s;WS%cr!jdA9ZsnVQZoV2@=WhfR8Ml|& zh1FsrTuB$x^@<+2)Nw$@KDPc$bE1=e;`-&oGfd5Y!EY(vJy4X$z2M8l3frAZXgFd{ zvZcatpUryj#Whu#nKqFJ%|!G_Uj}xtQ^>Z%2u&e}V>@wRnWYxdM_yWL$;rJ6&mdU_ zsVc~H?hV(?8<~&!J$VdEN9neT`}&qW690VFXOqNl+tmh?e{IUgeN1Wfaf2m-LtJcq zwsdY{z|qxQC&RG4R#Z_5Ny+TDsJ62T@_GSSfxjeb6rGXlX9<$IRlH#LouYaXLXr@~ zEIklZ?xOKk*dKybVZ-<<$GJ?2Yr*MyJG_hnPxY|PtFDUN<bAeAs)E%%R5^Q%<tU^t zh8iHLaoEC|$((@Ii0FXw)Z3#@K@9<SqJ!>5cco4DDgTvqS&j08`zkV(oB#CTZHO5j z6RL6#f}ONjL{4N4(|u_v)3k-C_bNgV^<<eBy;TVf<1*c5xsC?Zo<_eRH5sz31a>~M zAScVsnzDTtn<!tnB&mu?0gz-kgyCy_l)OA%tYAPg7i7C|w=wc$41L3U>ZNo?Xm*WP z_!N5YTpB*DjwIZb=9iy1(MMS5bTO0%hR#>^8tv9QYp#ePqv*ZLWtPHLVP_B?xel^` z3Ma!pu^jzw1FPhgyH79fXzWfyAE*sTD6B6kWdcA{G8rV>GKPJ(c<}kowUd|rJ~2uP zZ16u&a$Ifyf(}C!LVT1ZtP_3~esohUv5c0kbEvQ95*s9q%yTvjFMxV*1vysiDtv8P zc5u6hb-}$i#cZ}Peg=JN<*&jy<*I;TkSdZa2u50ArJGt(#LX$9y<6uZ)bIaz?(y%` z9qk)BTBl#=DV>J(ujoi$nwgb)%oScqf+K_Rvr@ZDYs=v(kbssdiHBJN9;`Bl@@-E| zqK+(n`72+GfbU0Nn!PFCUSeO+Ifgv3#!(`C4cOP&gP~`w`<z}!_i7v(zZzE&P{E1t zd=gNgdv%cJQWtdX#cADde#Kt8!nAi6W~KVr=^CNmvMJj?44Vng_A5ZzC4`#TAD*-A zEg~$H3ziV*z-}9ujBm+6#A%7CXRp9nw;2>P5jmy2EtBDFS_Px{_IBiqVRZvSX6CLG z-`V$9nQ%=0jm)NL(0e7R!Ia0W02O0~RGIG03b1r@mN0;D>;M2TjIATQu-&F0Jw4qd zZZ3oWY_eZk0Yk`>|4t}uR7?{fj0fYMj%v>;R`I4i5&{SNPJmNfQQfZJo{!(z*CxZS z#?GV%0L((~?u}U=7+R7jS>mW)H$sHtRVD7%IKuRR(3GhjRBo|^JouZE*^CGB_MIf$ zC&D2Mbq?k~08?Ruou)q%uBktId2smRR(4nDH;>8UKtpY*D}K}8(jNcTN?3>bhN_Bp zQAN}&jVk?C!E&sYe)Wm9PmbIZo`V-%pB*S%x9?PeA4w*ub$n093#lR;UYgN&nMvHt zf7*ZDe!cfP)!G5x4!B!4__WnXC6ot3*0s2304t!WIKj&&b=_xxo7o&-vM&Gp9chD> z<=6>C<OcOha@Jrslf(RPNMHDQ@6z|iqJNto&UV%9GI0N$cTg_$-RskJCc-y=QQ#3c zrh>L!;f5*aRR7}PT!a50`yzUfbk=!kO?qDIgW|6WY(eM#`+nPR@EV~q<GQu>)PR;$ zT6!2&$e)|;ywvKv)aj%K-TA7&e@cRcPdk_0YQJr{FBrT8XBX#4f?|6fm{>Fgv%zIV zV(BB@uf^_G>P1Em57I={gN00k?eO)Cg&5|RTpFHh{repAsxQ+rt6P7Ku`es_QLn5_ zw?n(ye)$;(!@fF7r;tVqNKXJ)ZZqr&Y0k+unh3D%061^X8XpYy0c4c0?1W7%^oL0C zy=9FnB>P<w0pZxNVb=;tGgt%dUjq-SI#|0h|EWNUd%<9{;Ai-4hTEEO3l8Hf?l>?; z@+mVt(<m!f)8p6Io&uI~Nd@m~vDS;KwZRLbb+Q`+!27ou7Qx{5EIZ9Vj$x9IJoTIm zBiim`@Zr0~K4UeP02%wX8R!}2z826%uo@BHYe7i!+3qM|?I*eu2;)$jRVQj<L&Mt3 zQMmKzGD(JR#yxo2zWTnyxqW!NkfUplb>I_fcmHIY={WeMtc}a1GT7<*?85{hVpf_@ zR+{Us&{aNsf4j^1^RDr`F4;rv|9fH~{6n;;)#WnX^-4s8#$1244I!ysYjnTV=~dSv z&pKA<z*P8Cvc9dKr&~z`?s}6O@x7!E@zKM*oPm;6w^ywLdmy(8gwt((_w2F$%FTV1 zHf}fG*j1l*&vJ9mD{{Y61FP?Lcdc~4H{)J2<Jz=4_;*{a*_7Qn<IrN`@rQNqj=o1n zT16tsqq8XAKIC;r)9dSBUv>_8RI^D>R$pgNc(4($`|a+}^@r}3y=Hq3-Np~qS9rYK zb$yXLbPMO%oaoth-V;#ZIUMRa*ylNl7#v1;t$rOEjd0JF93I|vZfqGU4;>y)be+ic znmq6Ieib(D>Gf8A_+^vVCrS1P$>G(TUT4MK`K!Zj{Fk4HJl?i@%|#5wt-6;F4WIJ# zZl8Dj+U>nM<o#{Nd$e+d9qau@Z=_9vowK(-(kJAz*-iRk<6$@N{p-BXc6Y;2wogNd z&(j&NR!^V5HO0;CKAkf@fJow=&Ffu+Z&ml}<-@~3VGr<`SA(J4##mpdlLh4G0H~bX zp+Dl+#J#2Ng;4TXM|h*k2hav%@rr&|O#OBfz3w8$)`z?#kuFl@eto%P=W6^EPkJhN zjVU6zkIF`rg!{2~#&Flh;7a~;jw7m4{_1AF8b|zn(t0%C`pBjEhn0<sKOEP7F^;}t zXYka)@CA3@+g^M**XZN8@tJXxrw+RnJ{H3xzt0C)y&W<8+h_Q~?^aU)C~f3#qTkxY z8{43Jre6MyLV+^#qf)|S#E&i{WT4&Nk-+z{f%;|t$JV{aGyVU61Ap83yg46onDZet zr&2l0oaT_GkaKfL2u-ICI?Xn7W*rEr=8#mX=}4(&j**&BNE)Ff)sp(ClxyGb?RUGb z>vp@YfBiQ*++OeJ>+yWtxBEVP=6Eg0|JqicgTsag1Dr-EqKRR(rY){_`~r`d2C6>v z$Qd@;GGfUY?6C~Kc6wyraNrJ|d;P6JWrHLB*DRtxb?p2U{0#Y$Z1ghnVeme-Tll&5 zU2pmlb_K;>v>!S0@~L(J721u>8B8n-`OxGa5*3Vpvt`|zmxkaMdv~=TTj@_94%z3~ zsxdqus((o}?m4vOCIuRtY5aWuoe<)+SLv@`RUPn8`Tpv(atQm}_BiKIx^d_~o<ZB< z`;R#La8pBvf`Yc43oU?#KIixp-Putbykm4ew6yC{-k;E0Dr0}Lf=+e$pC0Hb`!rNu zOx<^6?0M1HzKdbjtEYFIJ$hxfbFBDH*x$vl@=rVXvxer-9W~cN)vgWJey1i}96RYe z*zn2lk^gw+x$uLitu;pjMmxuy=Yy^m?>O{*9Ey5fX#D!ZaNw=k0VmJbJxR3d4?}7X zM&yRQzEBo^KT7+-r-8Oz+NuYAZygaoic;BsF!b1)*ZZ|68ZkRM9Y&giBSp~H-RFWY zaVBzYB9)8B?>BAh4_4V#JnUIE@(k<eHZt+VxNC5rv{*ZQ2rAxoq<=X0&5-Bw>WbH+ zNBIZ0h{v#@ZEaD%$Ro0pH~Pg9H<qIQjJ|oLz2n`v(gU88n5gIx)##%KCl_x=NxPzG zsypVPfsLbn4aINP2Zw%L)!DgNe1-F-x<=#W$A>#m*Ty>EM7FC8&d&N}I7fZ>Lwy^$ z6Z-J&r|&%<XG8bSy!|^c_VdojlZEXwe|FaLXbK_Qp(StYQ|aYL=ry!4g@iEFv1<zt zC7}b78j0lUcltBPRF!HB_HUrl4?pGW5^O-sa#YL(>UQL@7>$w`_4QA+UP{)4OljYp z()rx4dv{9n@6;3~R?lSmrv0>`S8RLmbmgvTlS9*{-07Or)8o5#pc`UW?@TMcjGdgF z2LG5|2YYvp5XU!))A0(o^CH`GC9V!*>p#anjd~|3jyunf8@l}tUmof7`NrhPJA2*n zGHATo=eW;?@n2@++(XD7t7=bwMa5rCiT~RhMV;H>Gx^T9WXA7&yo*lk{G0fT0{YhT zQM72(+|&3(t6AEyz@W*U!Cok?`OdKOvm1`i-c|_^?uw1@IvsL%AnHe?L}ym>&up*r zu1zL$v7dK+^qjlBJs}}rF67u;)6-bH@&tNAg4Nx*r0emiu!O-sGii?!sJQo@HM{n^ zypJ>9op^n2SIF)KhxmV@TjNUJr(RFUnww1<m^*w-#nox&fxo+dPP{+p6`OrM!V~tM zRT3GK_JR}Ly4FO>4M|LEqmLF#vrJ+Nt?x;1zb<<DntgY?<k;&R?rYw$2#$49*I4xF z5F#@zDIhWlPKm6zZtv#sx^gvv-<h=a%w$r3>jxLq+o;*3^9lG1>%*&qCu<u%xCJDa zdF<dOBwvY2ZcIyd=zeiI#8z_fMbE?JstGT>+2jV>oiz=^KOr9lx*x;Ve{7iF+U>CY zPD$?--MM=Smq_RKyu6wG;L#qVfj#F_rz~ebt{7|+;>I8AE(kww>+rH|v6}1*2&+h4 zIBT5L`zY*<c9OU{h33EY>9f%n6DeiC6Z5_=#1BOEmk<Z%7L;64cQ$>%g`^HoMs^?i zbR0T;s64eR;giwb)Q@#BZ;rLU|CB2JohmstVy2rGoI2>b{<HX&4-oQsHsSN!p|t7q z^bg&lvZl{Y6R`_k+lSwzZT|joXY$hL=(Y`!x2WG-_AUi{`IkmortSTzEBs_Q_HW6H zlf|EZe)jY~{NnfIi^kN~f7Wm7UD=xl`I73Nrtmy%qQna9DqCX}3%f`2nw*F4Wgx3$ zmk#)$bNd#b$`I#VaI1X><X5bn{Z|G$n85$x$CUtG;I6^|@Lzr$p-ugN`0-IeFTUXa z;>QcLeQp}{tN|ZJwAI{{VD(J?H$U$4h!UTe(9hoa2w1MX^*{W0vK{7s_;J-K4PXnP zp&&EahCAuWAbJ=zUimLSesp<Gvg54!tN-xh*4s>+KmC^<-`NZ*6{oQF5e**yhaZo; zZTap${P<t$f&cL1h0(VYPt24Wpj>+f{O{lXFx0sHYV^SUJ0D*O;`+~Td2sjB>z4f= zCkGzf`|?)EM(YK%wS0Zodur{@XKk(D-izz}E(AQh|Gi|#jXiI#GoS@Hkg0U_^HdN~ zE;w#ri2<gE2)Ras{j4{xfWPqJ+tvxeWKIVZ*Ah}G=f@!|I5-R-9|1iiilG=av#Gt> z3?eNW79){Bl@GN<8l8B07l!lCNQ|XuE8T8~so^@K3rxF1*TAQ9a*4pglg79-)w_<o z(hZ-@{(t=V?CGG8q}j62gv+z#k%vCao}qKi=PKgMljbTD8!pdPrQH26cb3s@{=WLa z%cS?`GUhJ7KY!%MhxhWvUJEIoQ``EiCg*O_^G(3YJ2T+p=&8i2zbo4@B;hh^!1XWb z*NOU5^HO|$-t~8QQp^OAeZ`q*d&TQV=c>h?CV;7Rg;S?HFTGw8ZbLyE-xiAy#vY5M zmsAF>q+Hw9-G|!@G2gT2+KcgbrLN7Bb)TI5tKyzre{|&LkQVERoax?P^tDUFyGY#W zsu}zs<<xE6`(||?8EY@!1zqdF-5uT3UviH(IrLmEhl}wyhpME~ngz%C{<YjAF<t62 zA(jjHADYuw6>oTXTy48$Vg8{ex9SvO^Iy?sTGR6NTOY~RdJwx>h0<gzA>Vh6PXEHh zt*fSPHa4EB>N^5Gb$22TL-1aR#q<H(3ICh9CEdTI{h;&+vFi(j3fiKcu7t7Rdc4Tf zYF?;CYUKGV#pa!#p%j?ZSMMuy=p?M#J+*2Rf`D~)dTUBHiVd2U$<Kf7Nqy=3#mPcU zS>1kf0K5I_o!QEvU;F0Pq*{q@MHHUreSp{a|Eg>Bw}lcSmSXaVtf$rp!$ba4xA9i? zU%L>*<7wjFkcfwMO@B)Qa2D0}`#4y#N=@&Q46)Q}m`RH9b(;A1<a47_GTXkj&Dx+R zma?GOCnjGR`=71<HUkE%7qvw>T9-Og5e6&Xi$1HTWSyg8MH}y*;5Fv%L62!a8jru} zj|R8Cyn_k7eAo<kP;sNmV}M{^G~<_8PpN#&AGwk3F&|Hft3+r93!}!070GnU8kn2= zCQb}0tdT-Y*qvvC_z1HSx`nPzc;0!g`X%p-o#Ip23w*!<H)JFrL;&J!B}Bc)L%>sC z%MG0=25Vj?c-j1I#|H@wu(ujHMsr_FRmSV|o{GCnonr8@{8)`s%Mja=_J{rqkg8a6 zdK0WwaC|9F>pn9_XPA$SJ|c&K^E%f?>szOPeXe|>*V8ikM9JQ-sOWB4xtVuT(bm82 zIi^N=5MwjKvt51>CFA7}spXD|gY&2VkVZwPFJ8;8?9g3kIYVwMTeto5ysEsl&6G*Z zHA<B4-67m{lXvHlCqCn%5FI#Z3`Z$LIrOn@`K9YnW^mQFYN@~JMpMW-B`vmkfFpPf zz(@2<5aIu-PznC}tEHLR?#gv7U9Lac(f*MXrH526=i&C!-H9ya@1s2~%Y&uI$ZXYf z61LGyP4WI}!!z*h-p)Lm0w0KN>_@UZ($-u=)u8A;T+T7JKY>m<;Hz^YJa?1Y#gbz) zhI;*uITLiZf=~<?h*yNHmXEu7@bGF=5;!sfdBg2WK+YT@_bDdB^5DXiobH*^5Pg%E zzLhttd(l_TuVxp7CQhqVi6QD9=`hdJvC8Kd9eR)xxh_s3G;^S1p=k`UnW>NAX0S2w zVvzbM8P<KWY>r0_d(!ZJ-$_=8YjjPHGSLkel+lTWi#YZN^brsnDA3!E-{!<pV>;$I zEoSGZ$m5q9?=-xfyR*@uOLf|9638UOt@J3JrMx1^wKtj%OyXSA8^}ns4j6O_?R3|b zO5nEu5<V(kr2InAL+p2>`du?rZ|wCn!Pyjsg&OF-a@=(-pkg~9tJ7NK^_YS(ytfJs z)NcT9wXA)78Vn2`-r!pR1%X9}32c??%r0}fTMY7jtWNmFN}Hk+>yij%Dgs%jBmX<T z^N)O*DF@)w6p9mP4AiSNphgXR@9j;sN{^X679lZ(VKfjnQby6x`kG4){f5sGyUR-f zbG<ae2tR&P6!!_Zq)-LLJsDl*?65KG=X*AfYpuP#+>W#|n?e;J*lTX`pw1fgt7x{F zA|T)C4g}~bmHZszxj_7$A~4W5(c{?UR<cjVR*!asSTmYSvt;kI+CzKnVREcnP_Etd z3GOQV8tZLIQU4~%-SoK~f1sM(`kpM=cwn$scBnvGnhG&Ll#V%ix=ybo_NoajaM117 zua|#hJ;G6&DZkt8DktfBj{6Qa7Hm2^3_j;=ZIYhnCP~G>k3s*PX-@sTB~I%?9>i41 z4Y{MORxyvDZqafyD#qSWEtw(GzX>2BiSBEb#NJk9n}RJ%tiw$i9_qG%=%fDAs-iqk zlZ-)x>qHDbTFP33`I=jxzESZXen<3$lsw`n9eeAl$Y@f0N;&K241cxm*<%$Go=L0% zI?1t9t4RXgM3^Szj<TzZ1!b00Mc`KjY>irAVVpQ_4ZGKC!xbBR7CB?6&C%0@o?YZe z=%^i(**P|4m!!tmt|@OYbE~{pm^3Qye$4Z9b;`mW;Dd+KOmp{-OyRf2v$W4ULW%pb zF<FwJA>A@F&yO}J*P;&H4`h1hup%~~GghfFug69h(|b%VoS*9Tbo{JeJah7%Ua<w& z{)LNtSvg3hfk3>z)qLUjxqUh>7)MNO6-vXHAa%=oYVf1kD7PY(`d6{H%kB0;9});S z?hkX7lof6j)@rVZyG*pdBDNP%)Gs-5?2D@r&cI7tzQA$yB=|&*BO*4}pXa9hY;T^$ zio#3}Wn<qx_f3Zzi}X%8vXv?Xxf_CN&`AISB!wxSQ3XhPfDmFy1fQm(9?Q`6Wc&aL zf18B*F2KAIVpo`Q6&qQ>M878EzY`+A1GrZb>?8n0z;SZ@@g6;saS$aEgwINLe`iGg z0RBl+|K~k9aF&?r+Ku|g!+j9Q<2y;I_t*_D5B(uyt7NDjbn_vHwEKMglQO><09WA^ z_>F|J{Ei=GVqu2Z?NVe553j6>D-q%4Ot2i7on_#s_@quD@)8r-#zg<31@6&syd*)s zC!pVzqsIia{(ta480ZHiL^%mvyt;&MCmyUL;s5ZX<wE3={L&Oa^7#q*a?qHD;8!4y z3ZYB_Vp<)+q#Y}!Lv0DL+z|v<0^2M9qtWq}M4jeZ+f^abmkEuOv*d*IBqkg*1&ab; zHn{{tA@n2<|Ba712L#zUqF(bOI%w!KWaLjl#555nPk_j8q37w?K|X7ej-3?ZJ7kDD zGU^El_Zz?s3L;E20xQU<KLBns6*o45A0(hJNl<P7!MPDbbX*J@2ME}@vxjuca$2~U zcp;M5K>NVJkBTE-5dZN`Oirg_1v2E1JKO$aYKz%><CA}j59!^JlbPsh8EQp>R6{0z zTovMrD7g28z%B`X1wfw_!uHJIxeYmT3B8SvJSsqcrv+}vgH;hRGmHqi@BW0m`;G%P zQ2>o06o53!GYN<y2{esgp!RQmnB1NvK?7j0JGWqA@*rAXVRS=b;Wl%j5JnY4&(P#c zSwJQL$XRlL2jj@KXCmRPk*Bc)(hQ((^Rd4G;EsHbEYD~HsBdHxn~wSg#J&??CWP2; zGRzVQ)ylxNdM5tnq0@Jv&WiEI8Q9ictU+>VClklxp?^zD|H!H?0kPiz;5`E?A>(;M z^t|{4_A)0u7suZa)dHZ-3cWDKgg<#n6F(2VVB-GraiyyO(&7hZMUXj5!zmeOq`f-n zVumUgKp&FvD|Gyn<Rs%Cvk@V(l9uzGk8dHL3Laze<WW<8)C)$o?PYYG5c!<B`w3GH zV<RZN$S`>XPY8{a<;Nfq$9eEvn%o<PvzYO<qloDL0>*p9h+tBBCIHK1BEIfE69v<` zWgDV>0O=$7kIxz-geFPghXEi%0+mNIIOK{$bokXou$xTPUkIruXEy=BxI8z-#}AY6 zV-iFi6a9@Sx5TlPH2jDd>$d~D1jPNOW3fpauG4aU3m5<a+nRrAkQWiQ1HU9hd=qa6 zc=B8YLPW#Q60yh1OMb5ku~CBD3C+vDiG)`KbUlES$6wknBjLZ!f%F4G3jb7u1d2(A z#~2t614r*TceU%BRT!?QHo8uXo|d3`J<nRT;_G~Is119%RIv|Q(e?c7^809KGi*B} z;^1BMH#&AjfD8pt&QFj-z1Um{^cWAGPD3P%p+(}Fm@q^Uqb5fN*R6tY0w8;2@r54g zJBgtV$#ql}o%3uf#UV@(6B5pYr^%&Nfm|#Gj`LuD@7Jd@;oW8gD+$EmpZ$|p@I7KA zz{3J`<U4tRfDm<>aq*b|E4#&5qG16VRxYi7CkR&Pmm#eYV#a|g8oo6XYkQdWp|??K z^{$++j-`9!+9kVNN2;WJ`TsK6H?-`J1e*p$A4UKlLgnIpV0p;xzf@efCoR*k;ROx% zi-82qmtvBt-!t}@aghQN_8kG&F2FB|FMQ<ZyvWD-eLy8HH@qa{-!Tq;6T{<4*g+=l zB{@+-LRA5Bv=sYVh>$z9*Lj!<#>F-sRG!O7m%#T*;7mR&3@DeNfP*~f)Q)&h01`ur z_b!KyoQ7wTkY6osctdo?Zx#X!xn%_Lk(DI@tsCLMKO{mfx!%*4;7NARqQODw$mal1 zO2U%gqs|GC*8%=hA@(&HE3-p26K*D>fPMkKg@LRCP+_Y{SmU$V--*Z}GOibin?GD~ z{6Y8<170V@EFy3%4mh)xN3BRKz(4_f+<QSz8G;s&k1LqR&ZBYfWtdz!u+BS=%}+{C z#13CX_R;X81k6zjOd=r}JQe8dfNLaOdQQ3=wgD%WT{tO2IYT3>0rZj&?zkU*i6Fmn zyY^Iw;xln#eh#!up1;9O6Hf6Nm<cle4iP3#{}xMNX#fIIct3*x|27BJMqSUBK$GcP zK3v)n<iEKi5n*#5c0q8z>9B(%%5D|F6fz;}8OS|q`^U39j}i&pE$~D1RynI4Ac6hE z_>W%fSA~>6_LuM~dnAaneEhFf0rozT^PG&0>O=Dw*~V*e5Km+ZAD`n_^^Moy*@hM{ za4$*nBVVFKi0=nt?l4fLbGPOTS%MVdlcdORG>mf@`Z^yuM8ivIA_>qRaSv}hhOhW> z<@N{Uy&j=c;iYRxU`T@Ezi<CT2)cC_FC{-d@~iJV091*w<tX%bGA``jdq>=HOL9V; zk2av<`8=dNop)<@b<%xIr39t#h_9lfdKk!eTJUi#c)ARRD1?{4h8`pqNWu|^#n56B z)E0ncGi%*LYV*qA>*mqdgSxxEX}^47dtVIm5kSpQyV*}#K{2gcHi_lhaTpOyruQ84 zZ#zaL*sYEtTV#m4%&c#cv_%Qxn*jS<hH=Y9E(tKE{*8P_hel&V@~>h)Z+r!SeaC;q zK7?&tKsNEp_WbT}J^UEHGV+d)*DS*y+K+n1#LW`0lcbTIpRlbTnzlc|J3HPyl#9k# z-rDnNB;udMO5XW@1(=n5jAGYQ*TTp9iqWxz?6VCe$NexX8t9V}l*yi9_$JgzdCppZ z9}#rC>qT#Yqfaw1Z#-d9G(@HVp2>t?Djo;U!LtN45({P#0JBQfI}C-TF^&}jusfm9 zVgRFgZE$f>yM*QVhmWK(V99FnfcUsgmaA8CeTD?a{s8p{AY?wQFbv+Ymf*75g9U`J zTABQZ3e_MO8X)4&$cBc210q6p02*~ta-m=IW>Vj9vM;`h$TG>mN@@5i9x^-%Yo><& zEx~>lM5O!~`RIq6=OOACs1CC5`{A>gM~@_Ye1*{Lx6j=+Oq2TGk!b)|B|cCMpn4g} zwtge`gIO=dnF2DRhlwuc<E&m*eXKxhe#9h(-!$n*S5dL*q4)_QqJo6K)VkMa0r@Xm zp5Bu0af^W{d3GOGM8B?6g`kT;{<7ASYhd@IpnJuLF#i2WlZk{Q+UE@kh1+6}FrhU$ z@Rrv%?A|~@%@rJ^IGGS1KnKSN;GGXDjyn-rB!~hYc4(D{UunRL1lUC~a>0r)z(c>| z7e7Y>B5{t0{&x9X_7agN6`cJ|K<k;Yj9z1v5J;))mfGLGwY~UO66y%QRNj%@ls1KY zCJ_@~ZaXvfs)+^g9$}tc`oqT`6{5@^;WM(Peq<z8F_Ghhz={F<u>|bic~k|X(eK}3 z=AryWNk`pZgnZ?oQZV^V-r7iq=Q1AT0%Gu=&l!x?$%0vaC}J-iyn$Jus*cDcLG$VH z>9Txzb&v6(xx~+Qy*6tnlx%+Tp*})bHVqmnM2v^apWdPC-^0@ga8NV6qXn8q@C+8z z|3hvABnccIERl%(N<{VYq<8qaee&=BPcrhw$L5KP=n4|*r~KH^hWRBw2nF1{^b9*f zD5)oxyl0{+XlN6^o8Rb5Vga^}fm<Tq5>%fx>&1(iyPuNrACF?+_ue*7eB7KOOxuF{ zPDUm2(W&<q;MEb$EB)_7@x#8zW+DFQ&|ACyOIS}-lc4{N0P~WM=Mg(P$v6>!RCL7o z_h8}o(U5<KqI&s!a^;0b$l7aoju4tDfwReoFaq;GEIsfA;#_o$DF%fi+~h^R4PREC zK>}d)d5ln@&IJ5|M~}W6LKzv#M;vqdg-ZSP<_cV4GeMr<W)tf<{LNuZ_|b_TP$2xU z80IVd_E3y|yIPKEB4fwIm;ruU=>(=>BPvDW*-v`Nn~2(dA9Ef9OaSsF2>b&c`V9$n zMl4s?vw^|lv*g4PY0~t;&*Khzu@A#;9r~<&+3&tID&8I+X%FZqI393Ji|pLrY};&b z@q~tBuC8mAvSzy8I{&)4!9788n&!l2buYsmUsM{RzDv`uhNOl$@3{0Uedx4LgmW78 zOxV>+mz8a^hB<@oKk~{R#Y|*v6nT~_R=6Mfv7m6e+fUyq^T%jc#0KjM59SKYHr5cQ z@#y$p2x!=o#&?a;%K6C}xZr$T&X0FjhkZ-vw{|`b(+OWnd~tEh1+SyylaCKC{2dgD za!+cR99_k=W`fQ9&QOm1khFt^&-6)=;+d}ob#XdC)~3lpJ2SL8@U)@X_F}Q7o$uI9 zh0*obl<%Z|%Ltt3>^U!pd3`sqZarSTVShjW;K!GNNzO5KgqI%^G}AlV@sC;an$WVN z*A?U;EH4mKFUD5E^TK}q6!&~otlMtw=UNbNqZ48U;wgX52h&r5%U=_2=Pqk{DTkcD z+(Qhl+SsGDHx$%UmHtd~PKh>uxmgSJ4NXwnVLi4>FZ;@ehN`TL)=rh9bLm{IEP8Xj za`aq{NqIm;<!&v?3!oF{`f`HJv!0i|!#Yj#?QoJGW)RG}Um&9sCh<U>q6lJxX|`0- zA6`Yf3&}HjhZeH!|A!wp++wwT%ZAz8+lPq<^DmIKn>nO)uqPeGPQ$&d5{k>Wjza5U zBBZF~hpe}CGomK0(0*LQs4~gl=He#6W3ZtvGxRdlf7>sz$pwF*(U*tI8TmQq>t#bX z&ZpW=x$7}d7J><uG~f6PR8QMf>)4!}FFOiww)KURK3qDRvkCM;KdC++svJGv4AV*_ zx%FrPj*E!u(kA^}z0kbc<VsBD6i1KS)(Qg-JR39~HGpf=h*|S7?@pXLp_IEOv275l z94XaIs93hHi9dh%y?pMQxwP>jngo2sIy!OBsuDJ3M`+>S;=YPXDM~)ptA$>uKzD36 zZU{T*dXvP--=Y2RcFL`F-|bWHyh?a&OdZQSaPD}4+dC!d{R$j!<GWZ2o+2-@v~qw? z)uJgAw0EtWs)ssSoy8IsZi8JV_d#646RukLk^;FhlN^Xw@?RR<txlc0Jm$RIn4NPr zlVAP*dm&YGR~4$i%h{Lx;*Gbr&QCX}a#T@xL)9p@3U+3H_t?J|xf7`-r?$^)nwqCC zWqa1=cxd;uBg$eps#)D(CcgF3Y={<q!*uQ$e|k-imf3^+qq_CoJ}@O;#^u23I_a2q z+mhR@oAR{JIdQJ-(x7}oy=%<_YPjTBoIPc@9nHz;h_GKidrzCSicY6{Xvj$#FQAri zkl{{5ea)pv8x&c2Y^_OJ4#ROiaCgVl*!W#{-5(75leRss%k5B?yjXm+3`7KETna}& z`4}T#2MB~)*T)e4VYqvX0G+uB1t4u&r21W$6WaSu<8))dT<D<Uu9P~pb9|1|(qK^v z5v<&JOY=yzO=+Nv5<#2pcG;JW40&p}=9q`?XW6OKS+X?K-$0L<ms?$Z(7qF}NG|(& zv+@b@JMHfh&f3L5d|~Cfwav^KzgQ)etpbWVK<*=>ZX2f!vo&6f_L$diGcp|98u4Zn zZf<m<G__^g%<8O?ah6-@zYFQ=d`GServ@M8SgY>3x*4jmGN)D-C}w5d8mbmm!Y^gl z5Yh$NiW+eurwRe#3xuN%(l;YB+X<_oxqJ4tY`y(cd|`E_#(72!XH(tIj;3|!O%UK@ zhCVtMQR2;g2Q`(-Cr<}JzzfEp+i(qz%?GQ`0o&xzfYOuRTyu}Wb4SSg*Q7p$t?_8b zBn9kOna}LDoA`zS#P5`j4ZkVRQ`#IAzbB%g6ThKTUx^`eSFbYjJ*|?&^NZhSx_KPw z3JWVNe7erpFMEDt<W1#+Gt)`}VzdLy*44a~rTm)*v*8>l**R^^>yQ&T06{N%FivxZ z>g72%ShPDaN$U)?kaVD%yG2ZKr!xvyVGlA*H@s1(K4=@RyTZFegiPU&*~Dls3Md&C zUbM6dkj38^+@T5fg&XHo$h$Vb-s0A$tvD~zTyK+ODel8&Bqpk-jVNx$z%fx89Nl?A zZc#J=c=E?U=RVzYlQ@PD&DRDt1)}AAqb5S7+ji+I!du$0c7SGSQdKr|4i~3uy0|vP zOw@X#B~~T&d-7+DNcUh-hjNwJ`#Vp|_=5FCedkSZN3sHH7a%-YIB||N-@I-QwN9^T z`Gd=qKwhTg`nB_NXxvDDs?Pf4n*LF^rS)J_48mQzf{_l)b`>Y^cI(yyo-Rt%Exw&# z^&Ur0EoMi9^Jse_YY3~exJr1I_NeAuvOs|_Aq#s<x61kA57C$x=eaUt@WBH8l&&K4 z@$#{!x|wSx!q?u5t!`JW8wDv#foB^K#e^0m956vRgC1|+8<yy%&M1p~oUUJ#)dJRO zqv|ARcPI^!&DUDg<3mzvoA(cUHGE4)LPb4>6Xb3)>JvR5%-)0F1nbPvCwC$Y&D1-X zoJC&H^uEA@=70v=rgsptMdMbM_nViW_thx>NN4l>E;@Xc>K8@P5_Lx+9FBFKI8Apk z&|6}3+fLUNZkMrDuanj}q^!qRe=yWLe>l#ip$2b%pdG7ydf`N2wT5x-t)%@H|8?Wl zSnK<96o8RodfsYKrW;}XinmDh5rey7VhRsuik>^A+g;U6Q``qq%Q^uwt)C+7&0y<g zq4S(OYZ8G`_bKZuFsI{RanWrZy1jy&_ZGiqb;e5O76(rhi0jnSZ+BU5x>TIt7^hW1 zZ#cYZn{HI3$VZ^jWi6=hS#zq^>*{r*h%?hDpU7Ixp!CYmH?0Y$c2RscfAF>pxR1x| zdUJBy^c#mJ8)a$>rGuJ&_~jWTwEb|c?oh}_^69FYWG3avmnoRT`DRSCW3BS_irmAK z^1{)g*ph*kX0yc;MJX5->QH8XylLU>tU}!u=3TACKPPuN@IoY|>0sp}Zg*`u%BSz0 zxmLfT=#f&rs*fC!t2%Qlud}#Qd-vQwrB^M?ai7SZy-WEy@OTtDV;g`km}9M-X)oFm zx?5|J&vCJCFE~;?$gAvjT8r{I|8QH~r8;Jpi>>~;bm{HN>C&w?AK37(K4oKg#EN8q ziQBB?dBu23C^vn%qN)V}A97vc=SE6lb06S49Cd=%2+YRdQBtsv<l+ho#t`S;@2LBs zgtFx2wvWS7^K?RJrAdk0ueF>bL}e=Jw%G1r+Bn#i3U(%5N(;Z~1h5ZGqeniTY6{d> z_BC+(%5oB38o%W{af-sc34b}CYei<s$M>f6!W<>a1f#G7z~L$Exo@?dnbzx)OExze ztWpkd^sEEhORq;uA(;U4BLnI?$~i*4+$@Ie5_3~3aswP;>7hDL4DZD=pv#%1qT2g@ zy{;jCSB`3M0~nke5^f3aqC%Zqf`#r$)bl5q7(Ef1Y3A=I-dkpK7c~X-eE9AMkfUaK z9ybf<RqfY9b+*RkcuOImee2?RoX)BSZvkgOnR|z*ZP?%bWD#uj+buoTOmQEJ)W|;e zZG(skQ7gEl1Ol7%LdV%6vuaU#<k`b5xx|xTE%^Y14ssy2-tPrD=3Aa=H1J^KN@@1* z8SKpr*8Hs=kNwC@KJ+6U24p~*<$UJo?YL04FLD>VLT$Ie^~rXacLroNlzh(pNNHxC zW|mk7an%zO$EA#WWSc$NciFh{H~iK(RA~?ocfazcnJXW-Jic0RrSZ&)S!MW@+yI$o zatr5GrQYwbf{K`SOL@;K0|ws5iEF8g$$*u3pp*JwNBNLIYHup9#F?nA9qA>ZV)|pd zoqMy1ji!c>YnF7*$o^U{23Q_eeA!aNc&fkew%;8a@8i5R0c6%TI>fXQd@<b?K!D|o zlN2*;N=9pxISAl`OT(=l_#k^p+3}@3Yce-JFLw(S7BA*T(>NJoZWO6bww;?m+$6Vf zPgBpO0?Zp%p*B=EQJ?3U{m=(-o~I*G+j=2Kdtvowb5~1<p7p*y%R>-@=F)J(XH9f| zxW)PQQx@AiY=)W<yCvLEOZDG~hCq#6(LRs#tMKgz-^douF6CU|IP{A4x+Z_vQ7PEE zqLx=hM2351p+)y(U@`(k%md?3Y8hH`a%1(q<VjM(X-kc>2L<q!8b9s({qWh-heNFn zjpkUjT()F@-zHu<aSJRAJLNFOLNA(~k+Dh`U^$3n(Ly{M;s4}oQJ9!}L<%i_?R0wl z`m-c%0*y!`!;Xe>e~fZt__<L_+T%?FiyG%9vM-*e<e$~ZnR?;@m~{coumn2$9f!-} zy^vO0Bua8!B<xH9?6;YZx$3iBV&1ko_^N1}8%praCSLGnSk@Pn#*Eel5{!>ll#VJY z9~Hx5#5RFK--J=F3mw$uVQ(#TyP^G1fT3(w;0O_5Niqe1GDUR#M`jQ<xCeHShJXf- z06^R_Jb<s@DdrfAnr-?DHj%RK^0xvsm$`3^o_2$0UW1=FseZg~Q1MNEe1`e(%|m$X zU@<(Vk~?6(;YTkw)sf4;U0x!)>`BPkome`~Da{;(Zdo=&T!rmnJP!<ApT)?T%D%WQ z=<2B{aO7yN*=)Jh$htHcH)hl`Ra|~W7V?K6JWAyzRc;D8tLrzddA8TE>sG+NoVF`Q z&$IF>Q+nYs1XwB~CvLQDHAPxx9$tN2#nkJQiFrY_@$0jeylkU!_PyKPBOToxd1YQ1 zU=uOqNGxru!`Tv`jCN=2Io0u%2Hc3o$^ZcC46yTWuseH1f+%qx1<idMv6SVVdGKg` zll9>RxrmjQB+#K%z{5i!+ee+Q4&<I4=ce=yDl9;vD&VP&YFSc_A0HYC;8Su+U)WgO zQ9?vUz;?wpY`lq_vgEZH=IwWc`5+!!c0Fn9e~=~4-3XkklfL%dM_y^nJyikswk!>b z;6j?Xfs%sp6j)jX%$MnuH<BAZ3ayfD$vtrK2pN{lgqQ%F&5i6XBew8o-{vteNyavg zYqa2HTP}lFoqCnmnduus*p8w4FZV#ki7@Y}qPc^UbE#{N1K1A_$L?gGeo}GPN(c&N zLP*PRHaJ2YGJ*{|>^8Jqw`R&s@7s?*Ajle=ISmd$wXW+xI6&2omtGH`o)1{giRQuM zJz-Qyj{i3tFbXXS+VlwJ>)#7sTz(cgoEw<ukrrd(FRQj3)TByZVwx_7@;N&N_v;z? z74~@vJV^Yqw!&J1IrMH8AL2`Ih#anbrw#kt3wc_%{a*<znz#LE1=qFSDU=EQA}jf7 z;9Awkv6g{dw_kUrg6+Q+|FnNN&<DDxXr;I>YSS3nCD1uDyoOv+=s{u~?lbM<jaBYi zvwFC3^0=)xK)+^91Z6P5L@MNMUZFMhl);{ja&?=?KpM*8Jl>S8cT|<~#-ES2hDmdF z64)6Pmy=pLjx665K$-D_@NG=JWuX%d(RZ$9XdH6Kf0Ul4ksBlA#1nF3mIGbJbFe1Q z()q|#=6wUrsmqke<xSAr7DFox!N1BEs#*Ad`S#I>`t2E<q>B5IOB3ESd`xd(m(t0N z+h95me2>cfLwZ?mX4bt2l-D^z%%8bggj5AJXB!C6PQ6%#;D^c}aJQrBR4~}I;$emJ zyPJVnhv;|t526o~V29{AMm$J(qW8l}15*u1WP6z-0(2%(;kiJ;fv!!Fu~v19aQ#aN z5)<;N5gGvi>+^DVj=Coh%HxFN&7Tlo3*G*$fa{x_^Gn>?a>oYfh5uB{yEw|-UeZR4 z;vOMyIyy@F1FH90+(Au*Wig+qa$ors<e(G@+sq1VkNRW*&_cmb<OJ+!FNYipwI%9w zZ9lh6;5PX4cQ<h3=<KA7(WH|cw*lCWMD`{#Ym>W;9}FO_jZsdHocgbYf8?hKQQ?k@ zH!X&2DK%B{Xu7c@=eRUC;M)7qUn)nQy|+6>dj;fbH9|u9pnoE3-4n~)0qh!S)6L=R z5;KKaX`T(m`d8T_kHc?EdULmA)a?}XMbkD^ja$Ec8u<JJr(;NI^}E5ja3Dv+W!n?9 z?{69k$b(V|9(&C3#tIMit2$*1E@X{Dx3!#1B0}rDPD<xK%Yo%veAv-ZZUVwL?8Oen zW1dme*{uz*G%<9WBsWl!{PlV{F)ATS<D)?U%#V;`oA2h+NJ!{~h00j7tf<~1T*nxH zSGAc#Z<NnNOEQh^?AC9wzR0x#1hQfsljV~3EcoUxINZH<Tmm!bgO4*C2d6=Id+nZ+ zSVbVfl+IcMFu8YGZbXPZNgDldqr-vxcq;6(ZBBS7e+!9z`UP~zV<2G^7OeqI&EQ__ z<b<klQ(GVjRHu|XAz4J|4nFD*sM5QI-Zf<IQpH`J_nF_Pz@%sSrZqy%jAJfJa{bBt zWDVF`l~+H<w!zt4rNA#YTsq6R(8vtV^}F-m3408FXh#xrq6H_foW|}cAGH^Ndyi}^ zEx=h5A+P`VZkB<ZVnF1d>`gIdqEJ6^?E4gd4hdlU03ZkE82-y8!o4w$VQ@ra_ThAv z2LN!D-Z~vZJ7l{UCi;ubo^A%pqpw|m&vV%bVG4B?lN=2Tpo=$*_r)~EKUX}Tsj)sV z1LCd~<qwp?qtERoJRU_7YBC^dE6)~3q4kGJ59Xh2zEU3AwCm9|qhlnfJ!#$UQNv3w z%YRFDv8i7ijQ<_cT-3a3(^bb!Amk=V!K*7U4<Z)|nTN<K;DJ2Io@emTylQZ+f9Xl- z*YCw<e`)K}tK>!RUW73VN66q6G`Ekn+UDiZ>qSa{Py`Bl1U2u!|GaPm6Mir35HUE2 z%<>(DT96*;7(q;l9QGW4DiNec`lKk$Q>15?@PAp2vMgmFQcF*XbYvZf=_kFu(~%w4 z3ri3{!)f>8#jtQvPA1U#Y67-cp9}L_glr?8!EH!+!_~j@KzR-Ps0JjS+jq5OF;lu$ zF=YQmYV+pBf6Jb6*11|_<gECIa-KwSE!*dR%*~#$-*x$xT8h=Yry%D-%;JscQhzFX zmkbxf=O$@DGkf8_j@+_mHme^;q4qM{(Nt}}FLQe*`5AR@I;CJs80VijWip@L8oC>h zvOF>_Im%c*43-NmC9C|P&)1@=Yhg7T?5I!1j#t2~$!_j`kW+ga?Pb{MeTD8MRtYox zj1(yC{iP*0vY4EIAqeZp`{Gu21XC;Z$uR|i@z!Xoz+V-{r_Ov)v`g&+5|!6KFT0*O z(U9Gjux+Om4Y=D}KeuS?ka}h=_^Q`l&4!eTyR9itu$m27696DhSd!j6df#?n=-;Pf zPPAsJ;x*r;#5?;M#L}VnPiLK?nmC89Chwo*^LEDEKeE0^x54{Y*3F3@MG-FR@62u4 zbLi&Fi${KD`GELn`T9Y@*st4T`@KugZ#rrGR<m>VnXXgShW(SLGE3DR))xT<9UE~( zQj(HFGPaRcLCXJYw76||sdCop!q?BAes7RTM8_kH`(C#^obFT5-uZcD<C65nrS0pU z{eJ7Zf7QeIa#x>^z7v4B`~)P#={`U7LoPA!p@YOOZ@|pG(_aNJjVJHhR|^At$ostY zqFPvfRwaTHc-yaztbY3^M(#>$e=c7fbgCEH;vF9FPHwRqklJDOe$u}A`;punQ0Ct) z-x-(=J?(g5w{Djm-lVt4E-27DzhjGYYm4ofsEGw7mC}&1kpWw2{LNmcwALBSh6<89 zeuIO8(9rC@I8Hrc)%u|)TJ5J}@H@ZP;%|tx-^}7pk_I9<g`N%47k;MsTk5bz2QZ+q z_=CWGZ>?y;NzL8)S#v!)VGu<R?F*kyc-N=Lr|0dtrg{>pn~k{XtyZaW0=aokV5fcM zGOQ<Z?}*ha?S0q#Hm$uj{B!@>&8z&AotF0*Q{B3IX9D5sr^7Gy=tmuhIUj5#kWC)8 z9431NUjg_9nhs(iXwA-LVSyS6qsY=Wth(tF`y~EUso8HpT(o{5h5gj5FQpEz)grAc z^5zeNgyAvWGqbb_YHdgrUB{=i+*=b`Z(U^{{BFJDXL+&abY9$WaM<}<!P^x+8e)vB zDRFAfmlkZd3Rg+a4tUGmqc4IA=*80oXID^lc-xXr<r*ix_$I<uF~N=+SL&&js8ez9 z1XoXLT-B(P%T(ZC(`W_W+6_|*RE=oT$s~j144VjIjQw<uQrE(vwG-+6&Kuqw9Ew^y znfdYIy@Njlw{V+d%}$i6pZT1v1<)l^+yoEBlig~(pcqwU|CB&&Wgj3Etaht9umfpN z)`z<+w{7=A*pO+~rsu>%WiBm7*-+J#14ft)=j7o#=i5uQTh~7UBz=ZJ?wC^Kuh4JP z+D(AJjsGvY2;DKFvFqrDiE3r^_S8VT=O;9F*gbdh9Um?-3TSq~uf3kPHOS$63+ri- z!()3)^y-<47yV8Hw2o7LE%FE;ux`y)B}L=J6Qxn{@?mAD$2yIAJeARI!wL`Q%df?) zF|o<pzhQ_1821I^+MX%}54Cw(p1+NO{jE%Q4T2lgOI~^SZ_AW(&_(y)=7PP!UyJc< zGmp9D4vke|j+(Us+5`aMGpWUy6NJkhty6?Z*>;W7hVoD*8Rl`BZS;$j>q7U!JO?qA z%-Ug@fCP0}nPoANUFv%pgq1(f8Bz!!1SUpjf)8J7>E=Sc?W6IG@9mtZkH;Y~7T1Yg zTg37x-w|Zix=Q$Y&Nk)T;5hC368G)gK*Pp(mK^E|*f4!hUK7f*`qjcI2N->;>4_}$ zKkmx@p(1Qdq(S2TpL$y-rwbk;+%?DZUO6RZ7p4GA&0mBZ;{)ydBRtW1R_u7Z1(<8C zEn)|4_D~L&<hXX~;{&RP>*oQk>fJf~ahbbXs3C&1qJTNvSmS!A@p%xo`NCh7SeMlp zj8%%hW~5A{4-nw4D+Poo!#>>=07k;pvimjNkXJwuz;O--neQ;{rRG`#M73X33Z|C8 zq6y>F9+J9@$x|gk73~;`21O5-jik02sQ1cuv#UgfF0>f*QAwBW%B#NJPVSmKM6xqA zus8At#M^%3Maw;+VpocR(X|;bTi$JLA{MMXK(~kh#4a^?s}SI2-iM+R^;4O0W$veZ zQ(CH^oGO2-(rkU&qJ0YU{o}NrGB{2R&FIte`Sw8p+uLx>Si^^@BqqIj!@qPmIl~PW zN!<O4^7_uOIQ!hS%f(tC#k>tc`pW*~uC#^hb4Op4JFd1_rR|!%cW|Xnk-F@uUrorP zD%8^8Zur0zfVnoA5E@OxDX-UpHD$W7wV_Pd+Cn69fP!n{L#;frE1Zja)vo4c&vWUh z%KLQ>caM6g|B&c7Qvle2BfPvyR9rIbu5!Dv$FU+CmPH7?0cdweSP#}V#Tp;09ECcA zLYmzwwrv~{aMv$7;33{yO(IV2+D3BA&tg<qtsWeMX)XVgA1?=kJMsz)?*{ri4s<A$ z5L0XyPnyE+v(UUu%zE=W_@*F2;Q7k&gbpIuuwwtV_fNrq*}=>Hs-U1-iXKjv$x!)> zSm)9etBRPi*EXkG_cmO~Rq7<-O~eX)xq=Qg+(ofi*8r<hR;2UNJ<nPB;<IQCPTb6? zmMf0!NTAolmZ!k9drBdF4fSxDIZ@QLX<EI932ty7EDcy<2^;7+R$4X%|FqRLQ1U?P z#KF8!e(j|ZNsrO*6Tbd4Y~{*cjtM8*;JgM>sjXjW!?wzYS=3mS@3d~)2K&<Of>`b5 zwm!j_M`?m(oW{R(aPx_Oe2H7)RHo%K{fOulgnW(Nc&C!`hMVd62X*Y$^oik?a^0t6 zF?P*eUWdKWHS8vh<eUD#zv`Z!t28`JN)Em1uB_~NnIhkzZc4`{?^e#WHUc5qmf@Qh zHRr}{FFn;=&A5D*4GllQLLR3{^>6ZFfISX4mZzm*u^kRjyDbg?WG%!#xGPp<p?R&q zccvZYH}g*8zQ7|EdlpX<#CpiX*F&Xl`H@9z)yxsNb6;$}hSUafjt;&2`gK7Fm4Zy` zh1d%LRDzIP>W;{#E*FGa?()$#nCf<+x#gb->^Q#K-(&nYZ=@;hpq`)+>fCg#_JR{j zcbd1$Id%$_MN&OOO7b#TeZABd&j43^lXwnoi532%moPab@pMTJ%-=a<sM!|8hO&>e zyAgiUCjCqGCJ7K?{M78Zjgh*NeDhZ-pz~`}Jk&H4AX=cbcWeGpCAeB2{gAP7=20le z@MLoiiL8nL)QSzXXKPvCjv@FCxu;|H(Z;`MKLGe!gTr}&(M_?6Ep)DvT1>&qx=ED{ z)(xaav^5p<MUG_Oe*J8PWh`{l6uMcYbPPd9oMzb8jtb_&j?KM+Fq}eGJJWQ5a&^$% zL`rcTc6TP8eCNz|6jBPE-ncLjb4PW;PJ5=)DJH}0^)pI0qCnQeY|F3?d!E~RseArl zjvxKC*#W3^{3>PIc#XphSWDa8rPGH#CDKw2u}$n)XUQ__1lvl%hCyPT-t+N^1brv0 zeqy)qnm$4^8_Q@%WGe68IH8<Wpe}YZkkg9Hb~ORnd5L{FzWUpzp(VH63f0=QSzklC zf|ETcqXI^hDhw}V_bWn)jc(P>-Rc98!5E4bgLddcwvI}!Vo;9KQoF$@#RXuRFX(w{ zsIB#9=McK=rEJ56XX}etkL)`hw6c8V5BL0zjVpN8tf;V6WL`mZtPnXBfvs*wArNkd zTRS$Jfz%l7`b}C_19eF2b&ZYWTMT(FPvzz}2(V;#FfiqGk^M?(Td!ZS6fCX801K-f zW=%y=LAnv*4l`M{OQO4rto=caYNUNsp7x9rjkUI7(moz+EVrI}-PgBJjwonqqEL^= zCKCwN2?`*&JwCOpP<xv8iaI8{12ZI`_o#s2BY@Sg*mXus{7f*|)T95h{%S_$MzeO! zUbb>$_Qs8h0KNO^PX*ne0Wtyf>qB;2`ZP@mq+Xv5%T$SPR5&6b2m1#o*;CZ5-~8PY zKKLY}EiZaOjCURunTgBf{;7*4s1WIHZN`3^|HMfGva0T&)hn!X0x$oUYuBu%J4@M5 z86s1Tj>BD%p`(HpL!?S(>Lw|;%IaJez^K274VLZ>{vAZ#^YtsMiUtZyKk9Sz%TA}$ z+l*_1t7MQ8$D#Ff%2`M7_JIyFspyf=uPxEtL`eDQljlUEtQ)03PEgcWkbGW^n^SS% zP5s)G5H+Te_WBdA@_G^-CPoFyh6mh;Dii}wJJHciV_1A<pk5w+4miJiQpUYJ3{o2< zs!za-(}vDAYkPlE&|e9Q_b3mh!cGiEyU{N0Kh0E<;vYCtVrdY-k}?!H^_dJZ4g{|w zvmRvUEs61WK85>{b4Uj$5jx|yox$WR6Ne0lDWXIE+BV8M@&ioP$@_s<M3xfwEtT!6 zPgzPBkr4xQ^{a@)XBYf%2R)?sX@d;4LFOwbj0CHoa!atQ0A$=*Rsb0yNjtO!p>{@W z^ObFOV)k06q@7Hvtw)#P(wur4%WPD%&deid8}|jZ+}nq1y05*aC_XEmt3y4FA!TpM zpLv;5uQy>z)CO%X8yMqlSHrNB$ZXe)O6NrF%thraujFg8Zs(N_W1fP1#;AU}dky)b zmd3>l5A5!#OWx-21m0U-ps|j$y-z{T83_k$+|Z-s7;SK@C$;3KdX&y7TR~}L;}c{1 zbCL6GBZ<iBV&2xqH9H5{Bu5c9|77wH9cM?Wi=}&c5IX_qJ`*Eyk%C=?3J`{lS_Q>W z27=vHzkD$=Tjpk)Au>;4tJOc7m#u;UIaVCn5m5~?A1+l?)8Gj}W<^CV2PivQG&W$| zg%)g^)-?_ipL%1koxf3rW+F#4sX>8t$BN@26Gq7)=dR@HwX`P!tWpJvuGst)Kv5@9 z^aVpGn|A$`Y+{C+mRY-5ytm7nzPd$T{g0-mM7RyH-JnynRf#1S&d$U{29IW!dUmI$ z8BiGF<C6-90<Z1s-KiuL+2n!jmJ(b96sw5@y9Iw+$O4Vj;op|;k|Ht@v)5OL-hRP0 zo|yey?`DPaw|mMa#j{*ewy_5jsFG(Ey>4b4mepyIBT;EnwV7O&zFNuBAkKa01TdXK zRc){ypJF)!a+IyQ|EeZ_VdNE^0GTF&EE7RyPu*?B?xqJ=j`nP`EgjlGJ!$y!Su^)_ zs^xZnL|Un=N1Q3$NJ6*P`}A0^HH=ewfan4Uq<@>Mr_It^I6rbg!O(H=)UIx06TLBJ zw$@YbKR;p)6}^A9IJD(g(@%@sLx4zC2-an|X}2f<47G(VmojFw>l}>_)m(7Pa67o= z6HTq>`N2Rvr&B7n?ypeAXNCO_6uQpPo*0kLJ-7$~h!uZm;2<fb&=R~6NLeL*T(5o7 z8Uoz{c^xRx8QnIyUZ%Q<*Wp+M+K}h&kTPPMXo7MPISqGU;i_u&0f^IX@=t+IV77A5 zaN2#4rEFE?*y)Z4vc?9nTqgRhi!QG&CI6;JWn-tzJb0YmTB9Y9StQFv%yK}ki?^Rm zpH~RNfp%|HAUG8$Ir$P8ZiG>$*2HcdjoCH4nT^GSGH5jsprDf!&`-hL`Cpb%-c8ai zKhN(aeC3|`-l4|Nc8YIDKnpKQv#Hj7y7k(J%BEfrJT-R)j>I-y0LW`b!=EdN%;H6r z0f^3d@KCXT-a?VJQB8!nA#&lVjabyGFqD58Nv(G8wq)PXdH&Fz{oL_v2d@-APKv^~ zTT9*bin`2`{DW6c1hpbr4=W7GZkl8T?FtYnAi?yhg7u2XVnw!@Ls@GkQtAP)!d0*- zgXQD|vL?TATmYN3h+Je8bp(fC!lR^oH8dj(eg$bF`r@b|ZlqnFNj%l`?P|R{k@O&B z<dWw-K*I>FV}D}fxu(TmZu(9G9p}_GC;*Gi1BT1)uB3VWy1oieJ;Qg!hO1!b6u0I- z1siwm4aQXO3*NE4YF=0S#!rXaFnz3!KLW^;yE&64Dl+v$l=(+K@`QlR0ZJFK!lj7v zs@7xvSk9joC^4P#UCg$YU_xJYDOv>Hp}21vhZtt4Zgt8Dd&Qz97CH29vr{NrPb#xJ z0+pqJtrK6{7Ij!BijYd9`O~CzGLdC{0H&hdzJX#vW;NhgMl!eG!d13zx{j0m8=K;H zHpFgCl{KqMtaz+QziGXG#!X!UN_}PwdzvW^B;$bW)b~uxX{OiJY-N&2Yaf?tFpSdK zsb0N>*rK38Q&7*lRQJf9L49lReCdD;wzrt2^uO4;_jo4%_~GN%9CqHWF~<>`bA{%Z zgf?fPCLJXCZb(QqIfSUq`D_k3CCwpJs*y@k%^`<UjZ~6qB1!7&T%_FB_xHFT_x;Cx z|LZT~ac$S$pZE28PIYLP^w?c-+?~jHzBJnZO7)r9Gc_LF-@tTrOckIZfnO*7NweJ@ zYoM2wkgO-Lv7gg8_-?mUgH5!N6GuhLawGn<tcj`bKNq}G+!A#zYnpo58P8nv_LRKS zp71NEe+m28q(Lfsif=y4wVF6^Ufi*3E!QNe*IZu`ShK|mX>#Ot)A~+x26SfFu@M`! zss5IGJAm`yY6(#FhZB@ckvL#oNGJzXcrPogcM<fsvKCzU0GA}!rO;15|NV~4-kc&8 zF1A-)F#xtfwL>LI;V3UuO-`bAjZPV+E0n*M<HJZ<b`-mx?6}bg&#jSruWFRT0IcnW zOaxgxN?&Y#vhzql;npF;H+y1-o^fG-(AI>IY)Ejhv9Oi;p3s^Gy_3neAtlXx%=SVH zeasHuAqgGY*Q9q?m43TTk8{t@bfv$=%KGnfXYT&=%-;Kvw4uc}D=Uk&@_hFI70ufY zpTq2Kuw2Z_B{$M!6CA#|Mo8(+*p??zR|-MvUl{JiMA-u;ko~q+HR15GU7LDgGD*Tb zU9RGqi88-kf%6<iUT-H8I-vWcW&xnydv&dkR(zL+iMWTGxkC({9!paQi=it8pvhVt z@+e!406NKnyP4@jV<8?NXnXvRRrk@g9RLtTaOgn{^qgz!@wBS&Ox3*f#FEL?WJ^Sy zcT^jt$E7>Px2n=rR~g>d$CG|OyR8mH(Df%I4eFC-hrZ=}_R?3^GVo8ZVRs(<o)cAk zVQ0hSmX~(W{(dJ-(pokBgP~;8pd`4;yq+4r)*|tIbhlUUV+(?V-~knzD`^Pq+YBTA zV<TYD+`M(%o|$%9FcXf)+Ux$>msYL~tEiy%CaMbC2|h5pP&?>GP;02e)Y;aG0E5aS zs=Xdxd)H-fsw*gfTd<ybhe4MW(NF>*O2CmS=SXD<^I0*JlJ2Usi8n*Atw(lhs-D(d z<Ek`sWjXX;ljw_1r~AMi9?@@iNF^$yb&P~YY~$|K(L~4ee!Z~Eao^tVmx7PaWTXv4 zJGYEh*?&qfNGq-wl2}jky*VwB`dk`l!|JGZ8flFgdwp<K-J?V8uxVb+WOh7hQED7V z(tNHSxbD3bcu&x1aQs)!EcHc7*vqXul^!Gl)WC^5pl8!j{FUSH;CUakxv%(P*HSXy zwjC$4_8c<@_Zl33IoX(DcCzGFOsnDNm*#s*O=9Q0z7`Z`m9}|bm_I&J1G?a}^i@&b z;mCDJ%GC`jujlHx*Bb}+_jc4h!D1BbL$ao*e)a@i<DI53ImB+&hw<aUsZY8x<j&-o zfH7~qr>dLA*BWnaEj@MQX|d7KJLP%dM_*i`rz%*NMFhXB+kWfN&s<{BKPQ^RbBPF` z#FS%6+|!vXx@f8NO==y-Bq)A5{R8_68{%P=)vVWdD{1pTHVl{ZW}dZJz|d{A<-ur* z(V<#j{-np5WtoYmfr~*dPn>Qt%>de0T&4?1tdC#7@6@B5m>!TizgVyAcq#OuO3%YA zxIUE_TOOQCs?IUGtabwM3RK_2?AxMKvgp#C7gtzXSKvOa9H_+Vim6eEPYUkt4qaT2 z(W(fD4xP65_Nvs)+qg`-0b1tNjOUmOS~Sv4riaI6l^ZN8ahrDORVK^q;?X2pLzxm= z4F8Is-n3d4O7aYadR^2`*|7vXeIAg+YUix<sP>tDd-=i!5*|c!ltH1X|KHLs8E@p6 z#MTkx4!b?T4A7Nn3YR%y@q7_F=%@c6*I?!WJ?&~Y)jZuxPK(<n^L+0F!-4PhM#=dx zi(!+>c>o`wXq1n3c~Fv-kbFM2l~S)FajZRAw*=ZAEsEbOORWr<PS+-e*;hGgxD{5W zsw6_OC^hHi7*s85lIu_qKhtSm<QTo@?t@~vP=Cev#ka}%aV;zLY7EEqQr-JANdt%i z|9O`{QsDeODP>R9fmHb|8TR<S6NPQ#gd4Lh{-ALeLo?fSm1dWz;N>iVR0-wLQxyE3 zAKPN}fhPxcwJ;~#Y3R9*Y<qNAVx|FU<)~TI+R7L8bNn3d=_^-ml!XBN?h$pndp}0L z-F$2GMSb@#=H(oHU``VcG_@Shy}Qx6%fdQIl5CM>yCjiqy~vm3xF*5)M4+h;&iTg; z#;ouN$@?PX4b+EiFEi}hw<E8+x<|%!N;$X-^A#rZA&lrfxt(QK<)RoZ+5GxpepFbW zE(=Px(qG73MHF~jrUqY#VZ$7Jej~f=6{Y-TgOy^vVA8<xsP!;y>!ZWj$@$WlEpaM` zX?-cmY74B(#2E8*Cndw7ddN8E5%Kqan$>n<Z0Bbsc{{=Or)fGRQ<u^;yhRDJ0TgiC znNF2YywvRh6q(ds$?`>Evb|OZZa*|9`a1wd&3@gzVUZcEvtTB3RwqfTxd&-I-i%vK zB;>P`6-BQVfoPZ}uLDUL*<Uj@iUTS`>=f~p2*6ZBy_aq8$QwX;_uDBg5Fou6TChQC zs=OqiHb>AYhqrYpe>^3XycoXa@H0tb%`k)B3d=rHo+wvC6DeIbBba(`J~%FVeCLi4 z7MPGEzT<-=BMoxwY!z{pvHNaZLM94E_Dw8Y|3Doczki%<r*yH`DV>@J7V9S-&Mz5= zLf7HqdsCG^K6NrsFv@n<vQrN(xpdN0-ql)gk`Te}csIjA_>7Ffp)WH84qKA>K?wK0 zYD<o&b)~T@aVISM-=^uL8Ah-$ytjNr<J<OuLPGNU(Mi;U^t?Ww1ww#GTB(Ei==PN{ zlO#YAm{M@f>TkltI(ODD%H+C3$%j@!lEEbFag6>a`_&Rh^RnnH8`Yb(fYOUIe$YCv zz)!6;qsFeq2<sw9@Rn%GwSiN1rYX(HUK=NDxVbOaRa~VaKai}`+(?1lHaxh*PQDeZ zAzLkVQgx9PU^Y32JTm2PogdL_wQk6*2;fm1<VQBf*4JkTrVSQ=7rHxD!?GOG{4@@y zeLj$A@{|!dW`1v|bi*1$8a8-YDgqkS#>FI3XC80i0Er~DWZI62N}0pLV;XH#q-mS& zZq@!t))wNf#|jx2G9KsvWNs#vGj{yg@2m|GFFV~SM~h}BY!#u0EPxU}V$#zT12rxd zz((#1q7FC6cB9kx?bTWpI$N_@F5VW$yeKj07D;(1R%npVxMiA!l0C$CNGivP9IT6A zdr!C(lV4p=v8b54`1$K6nIVEAkb(JdB>V2+chs7*anPVZ8>2aDf!NF(%YVV`y0gfD ztDL2LbU{nXy|V}!D`TxUo-@!^9-%(o6w2xgXs*OZ@m1EyYY!b`+=~0+4ym;<rPP1% zkz0`xsdcl`n!Q2{H_c9@g*3JB2uX;Vl~AVU(Yu~oG}Z*q_$i+8m&@@qj%OPxiHcGq zC4}HfS0XUPF<NTh<C#R3l1IWg0TCSvN-VgZ{hXEWl$~Os;IZB!Y-fC0g6v3%lgW@I z$1vZBxK!_?+5bClsX;e_SAwuEVj0Yim_9r^D!q9g_I|Faki4Xnyf|fqwwdx*eTvko z{FawBe&wlNtCF;JS002G*PT*)@FoE$u6AlVs$o*L$z!ipZt$$LN;9Ks<5jyf)8VoB ze=c5DqrK8ITvyd_Z=JcF_lJ$NrFNXRF~R=n8cM2)<Pvtc+LK}xkXt!iw9l^|ba44` z)sx#9mTHvT^|7s994;ovyN<L*Rmu9r+WO$0-O(9dp3Ov}LJ=qOv>Qwm*L(HJDo0ws zB2VMTs}Aj;{cp$)bWE)H>Z57dK9d%Y%pZRmTPCK@&rQ;aZX!FMjmjq<_w2)+5OvC* zZIISpQ*s_ZTTXsrebH_WiP<CSBrh;f+>tb^61!t^KyO~hg~rVx{o@mG%#jQ#H}jgY zKWU!o@NmH>Td~8qqg?)4eRP42=E?WHQNxJ_Mi)#TNd=;f*%HK*KRR6inUKuvI(iq# z=~&fVe`hke{N8>1`-Yp{#8RQuy#?UP{o3uCXZd!DL4PhR%cFoZgl--E#*ApGA-N)v zG{8>4?riC}Q^HeoH|JuDnY;FX5<b>shvgg*?~g64MI_c9$=>FBjMBlew{C)=J*Vul zv+RR+{@Z)WW5!NZ^%KEeKEc4f#r7VarM9`~akg7#_2=@b?{P~qg}eHFlxBjvg}lb> zP=bT{oJXWFFAvOkt1;a%m2h$d@%oy2#kZx8cC9ZD@1|h3apPC)l+L<5=G5XL5&18f z(EAKENiqIArZ$a-B#3fGb>kxb-(A%b54wX314Dl?<skoeng%Tdy5nI0`SPA0S8uJ8 z{(WzLU15Ur$NRA?jjkRl1vt0MeB!EokR(P?l+D}ax+TMXHO8r|aX#jdzWc*AjDlf1 zI}oH8OB`~BDduy*9Im>3PQ=+Q6xrh>L)I_*924Yqm8RVqJ^_VN33;Z+U+kjT)2ixe z9lAj<q8?XSuf}?cLKNyl%e-v%EQ>s;BmiD7A0e#rodZz~MWF<rbVA#Y<M}Ro?%ePg z5)($5Giw^|XgW?vMsUO!G=;Fb6C_p27&@S=D51mc!40+Yhv(!QyCseonKlK!+n=W@ z;3(kRF+vVOVtfy2_nx&Xf(Wq}&Khx+*4z|GqE!-gwg@A}zJ`8tSjRq-wTCHA!8BTv zRVG=Aa8_h~GP#>2mrt<@y+PD_@{^H~XQf57q|5n*DDznu>44T=x-4}}Ic_HwbzI$X zY_OR%;Z{lfJ3e6Uu1<zo<s-t2oaFRbj^tpKTQFI}joWK>s{63ud9Xi=EE%~mRuW`J zQvZf#$1g(<2_82ey#7Y3@r`URic`NXk|KQ22@>*U=J|*KG8V!tpXZ?Na8UJRA_TbJ z_zJs~ZW0ozP-?8Xsq@$_XEVs{e9j@Zkg@uCd)kDcn@H-FR6G*mBA9!lC{U$AHYZtD zFr$b(N)OdmwscZTsZ^QZ;^J<obo5d*Qsv#+mDeYx$c{N0m)dK0PUlt-D8@Ka8%u3c zEHhO(Fx9AbZOm?%ran7EH}u0krVwjc$}KFCF-1`<%^MyNm7KI!%Q@`D+SCQ1r@C5G zl{$htc1spWN^x4G5EUrX`CLU2IbPPIs4GL}B9jp4|INFp=@aclD@SG)aF@8rDY}Iz z5gxS->zeJj-duyx@K01FZ2Y4oVeP;1LjJ}}vYWosLz^k6*+xt4#<{G1DG-JoAw!ZU zA)=j4<(fc-E4z#0SV?5J^OD-{H*@8juN|04R$<X)BgRzowO1T(oN5B)=2;OP9yH@; zHcgLZ)GF0g4U9Ddls`!-{v9N*pUYKC8k057QPhGd!~JTN`o0*#A{_%_Vk`X?SxQA* z`?AVYg_JYw8e#}VC7<<=8y&k>TG<=r|5~@g)S&^Q+v~|Ve0zh&K*yT+mJ)YMRXDhO za_i`Gssu&m1XIeJQxXs;Rl-ah9#eZrv|8`lXjE<WbiwMrPSUbHRzOy3B4en2HUq~& zc4vEi0pc{B?L!Zvb|?fvZap2M;$>y)%+4KE@!^6Y^bL+<a)cxm`YmR_O_eULPp#|e zfNPLUY%>+~S#U(zacnz{UTeJg6X~bU@gwOynFOR(e2y*^-Bep-@3S+cQ2mV8Jy7YF z4-3Rfg@Qx%?SAWUQ|I89|D0GTR2@^Cuhc(A!3@{o6HFRDxx9u<dY}^DWGeezOvulY znc<%mE^d?T#I*@a#S^$$4fjN#WN=a8#&`G65xeXpCBK{Y=yhITz))u?3gu)h3B*zZ zn~XonNtw1&B|JA)5~En^qshu%V;+^?PLDXqy0InzGI2FjEuSUl#Ud?Ns?0Zhy4p^f zrYm(Z6&}7Y`IfkxFHM?3$}-#4c0m-Y;Yx$+!M#;#5WEa8RI{Lr@BLJlvm8`OS25-4 zple%=3sv~^39&!P=BQSQ)6e-zTR%UwoUzy@%Jxt#r;tikQzg;(PFie%%o+c_t0%xo zCT4w_Lm**gH3xcUHsR1?+i-WAp37tL?ZcxJ(CdVI1Bk#tPJj@;7Ab#eQXZ-eI8`fP z_A6YTJQm%r+A8U#S}7HYik}e@0gj><43MMCd4I|Qm<mzt(DYwHfh#{j_xVtLSm~(J zG(CG7W<SkRaisgD-L|Q9RjbUD*JF)0R31AXX}m-y8nRS-D^*R$qBL)bqQ@`;FhC(v zUG4js`(r*du5!J@MBt|Exc!Hs{SN3E@Kxm$N0C6jZhglK4bLP6zJ{`D59Bs0s_Cd3 zb1}w_7O$LMx4i-driVWUDn1Z$|Joj%yp6&8Z#hK)o5WzoMr0OWx{Zlj51KqRX38|{ z?ADqMpTqBV3fk=q1H^RMP^yAzlR^lL=vb*(6MC8kYoDYC6Xl7q?Q)Z2nh`uXrK2i5 z?LhT{FpbP{q%CG!06Bz0WOFsk=oBB_;IDLID`G<%SLqj5E~-+k{@<T1EY;R_c`cUG zFBs{^xR*o3K|V`;B8v3a`GuSW(Crc1ub{QJP}WUOmaUcly3-)pPj8i>qBW+3JW34Z zDnH3`%4cbf{d>(GK9YfDzuZ@hZa*Jn%oWPHNsfmqC<e`wu>v~juMii?H{>wUq%q7+ zGQ#jc@_~}%!^2jGEOu}7Hv`02y)l`ymCc(fo2ycf&|%Q)AG5t)sqDj*Gp65$H0vl0 z6^TNHwLQx-iGg?N#4hrqG}nU~a+zD`#3`1#u<}&>o9YpZLtgFjUF~rYYyLc1adg-_ z<0)yGqHH`Sw@fFcu~d`JlXjXJ7ZhFCKvCIyQf+BQqlf}tX!jk`9Plbs_Zl0t`JxLS z%1gZ(GfA;&s3+#IUg;R)LU0WM2HNokuCQW4o6ra5KeMU<j?xm}*VMI(<!b>Ismfw+ z8a#`S4CPCfiPdgo7hjrZ#;+7#9y#_J2KZH$+$5{(RLZQ139)pwvvjp?iXsiB99<&M zrqlu)2&7khk|G;5rtDip=2xmU(3LDIiR&d?xn`Iu?+&TFSjA^dcIM!Q8oKH<S0;3` zD#}l}o24F2AsTYke!)~5SgPIhOD1$hRjJ^*Oxh$@#v)fet(_!<Relc*sk>A46{c_^ zr0MhAc)<4He|DmdR#{oH)C7;^b&lIN*r_Z(b1b8%PbA7Kj4Aou;_)adOzztX(~i~U zTR(IQ4MIy>`RqToN0-T5fP<Og$fyMYT#gc+Fa3i8?d9B<sFI4{2+A!@YAqk$!|gKi zQ=eza2xvsVc6sxg3L|N97F?YDn9?Fw72tR`(=!jUESKBqlY`HS=!!^~TrEp=l}_A6 z&)Hjbv6!{za;kb2h1A9kT;JG1lJipzDrzv{Dxz2UJup@MGnay){f84vwntf`{iG@w zu<MMfar@-ncdZcaeM7PdS`goRDCBzOne&3fdX);|BfL>$^~K%hzo{w`SzC^`+v2AG zd8n&A#lfpJOv71aWD4=%p8I!Iz>)$Pf?nzLPF#}^j3p72SYSCBQ$>MEkP*UmBovb; zz+^NkmHv)B=<|FiAKxSFQ}1UTo1_qjh5u>PJ1J@t6ty83U|6omrz`r<iKblV0@#Lf z7;%lH+RIY%<I4He3;VcALavIAy*9xT`c<Q!P)H5!Dsk4NUv$O(pw0n`V%ZUY9O+j4 z`!`E5a_fU$s+_hujf~SGdXG`U+gqh1jiJb^?b(N6M6YsnV~WBA^5P-0tlJc=mOSX{ zO)F5a-?T|5Xd<?-J+F?guFoO{GL-JHsxtK2?~(B({qa>v4Ylvy@I3d3o`846twwWh zvb~Sz`Oh)!U^xxfL00-@1%xsaO+~@4VFO$J2VBlJPW?~^Xd9fls2^fE_V^1+?%gXw zjN6z}x%Ow6kTk?41{x|*VY1FJ!xcJdeuY#;_X_8#x3)(rr>b?dE5^Qma}%ao#Z`?S z>pgH@k;;|#YE#9RsoBQ8b@Ca#rFU?uQq8AWz6jP8sj7No?EB41wNsS`@C7PCQHtwP zscL>3HY{G)cWvvTvvDzPZ109lHKnl~tPWkT_Mv9hcE1JeMEfIIIFUDYHM$ZvN|X6R z#@!)f<2;^ydjWkwdbA0jg*zSv=<d_v)~zi;<us5WQZ%;#0>tVZn97fKJsf60lUm~X z_b2MJo=MeJ7)O2ASeksLTt}<&Fjv)?qDW$F=w&HexF~wD@P>4?9N32E+^Gd+%^I%i zYi`53jDl6t_kTuJgxnsxa;0Ui%$@cx!DIJ&DN2R!RX+I6nEk%@+@=ZE@yaA(A}wYi z>ibB0(17S3De{DJ^NIH@Vc+iDRKDV|`s?5=IOjt>YvJm?Z&CSGI}4VW*;m)M?tWPt zx72cR!Vy%~iG5zbvUUZ8zQaB%JN_~-17{N7k@QvNa|r2HTxsjfe}1@{b>t6%M5i{6 zvh~c9AMJ_e25Q?mLjeN|U)<I1of;PhV<rijG|s$~M4^Lw)sBO4+DMKCC;Qys>-YDM zZfTn6E8KkOA(nh=vaf9WnZH=e=Ba@i*9$h;mS$5urR&#!e`!_QVwR-SX!+{fpt5JJ zSD59ipglG*tF-Hz5xBD3VPfHxg8c@?wH}#g2i~O`j?5>HJ~$}pbff&CYjv#Iy8}7H z7L(%E(|4nu%ioM|GoQbzixWoueADoKyTeX*-F=eo)<Zmr48ygoTcc)Eq1Ef@oQ+qS z2aOj4nsE9TMaH1DtVfr-^^GCh7v?)wOm`dbrwZK7SKY$XHShFmx|xqmXrhegwM?=} z5ks(={XXC6aK+Olm-puf!3I-^iK=@JsGc0!hxAI7>rf;ox3qUr5|CAn#6i`f62Emh zB0iw_dSC4kepsz{`KjkFM=wT65Z?MX{ONqY0|+vHy6I7`Nv^@=u4>To&*H6J)l08B z!5sj>q@P;ek`Jv(4VmC|r)al)!x09EoGMY5MCRri-r#QPboR@`XP#Z}AzQ48!qYe3 z&`-=U?cxmi2s#`)!HuOe{+?z_Y2j#{+e5c<%?1LZZ~$V^Q#N^I|E+a5>tfEJi}6y4 z{g~APv+7y8%{IH-jlDqy&#Z1R@<GE^fgXgUe_r^Z>FaY|o_D6cJz0@AL*IXJXVvW< z3NwQ4tQO{$^;(4}IVi1|teWriPqH{q8c3F!ci3=nw2D@m_Exyd=vy<&<U;gF_|a$P zAG5+Q=Cya@x0k+`<ZLU=UdYg`s~>UFAEer2jqdUipORm;RH5{<x@>)Rtc@n(EZe%8 za!=i^@WgLh=sJbc74&!J?kK=&hK@d4LgbjPMG&9rgtBkt-mH9L09^`QwrJ~DS#~cr zHcT1gcVJ-*17Ltxjny;@cBO3n+o+LZxa4)q%|Wiz9^6vWU%mdrWK}QR#b!0=W%|Yi zYB<W{*+c<Od)_T_ry@P-^FGp{ny|DDXMa^v)dJ5SX;VKOG4Q5~`0rS%4<~v+TGMO( zaheK~D(kH28x7+SQ>57?Qa9t~`z$AwI(PNYA1Dg{v-~mlQP6S=_|E#qi*VEqQ6;84 zT6&WX7wKNll1aPTV>vXC%P#j%_)_n*gDQi`ElgB@r38n%kQtujan)%gV%x8F%&t)b zO8cH(CxC$uMvm{f&qwH|gyB=P0#eaoFX%VIay&(yDJ4t?Yf(GDUscPbAW`(WSsQ;M zt6HtErAymuAXjt*PkLhMV8HlUaJ2q}VqXcufYz9aUl0D|`;7hMVeP3@bHD{WEt1S@ znbq1}u5IwtUyTfH95^!E48j0=)sFl${a_cI?=L%wtcUa#C?r|;D-~ur3r*6*@(#bd zHgg(temy%`xU%{3#@#V>J;>~%rDHwj&Uu-KX2;Fe^)_r$*oTj>-?;(s8nRx77Wim( ziq&F!&5}yo_4jt92@Axw8F>1U8A;UvrSoPrmH4w08VYqB2lM9xxo7wip_b6I$!B_P zd9&lPhV9ZHtLWH}rP)-m7_L7RmS^zVpHwQeH#gOwoT{uLEsCTJg};bL`xE6FsM1a? zMp<*iy^izzE>lDAOhZxQ=A@}kg*F;;LOXYzb;jQHd<#D{_b~-L!@Sb<w^y2~b?Qv| ztgV8q43aK~CD3{us3$5D53Sk3VIr=P1_THJc7@f2%Fh_6SM@t@oBo}3ss`Av&Mj7} zRfxNE`5j=8Kmyl>gj<ChWgVH&P;RJ~HY^9yW869u{xA^Rdbv4mvJ**9X1i>fJ=>K| zjLZF*khX4Kc8kzYlvyLg?bM#~e$YCho#0gJuJ#mP)kgA1)+hh3!Mg#U8q$KOoU8N% zd$^)QK=eih@2<-}%J5f#aA)gzddjY@YPHVcl(vAntmx7Ng%zfw$to}9+7y=n_2)Jq zxmq?wdt;)bE7Slk;y$6tfUy2f?VpgVjWjI{YHUzDb!`sqzosc$F)Ov25r!#FZn{Ff z?-@{=@p0{H?N#fSSv!Wqa&3am)E8PFYgx&pnfAA1O4E`kq_Ona34hXWG4xd6T<$6R z>V(s;j`_lXoHIgO;$LzP^-i$9S18m}5q2Mb>Ve0E*eZSD$lLa><b^kADm}4yte4-O z8N>14Hm;`|K*wZ;6&9(8EPBixVHu$lw^crjq>MEmAp$d>BAVZ)n6wyyUS57g>euv> z^gQfwp{x2uUXKF{*7&6shC9wqRG;CuP3df5`AkXleB!h<3z`YaPdk_A#m>|gicGGQ z9c4(E;3JS!xy$Qb*R_&C`8$&VcV_<%iT=H-9WIY*3~%rK_gZO1d-v|Luc=g9J$&d| zr@G)^>T5O^b!>5*G>9xRJROr8S$<5ep~PNiu@Wq^KALd)xcQE<JXCH&YHHNG9_qtn zbja+udL3izblg-$5NBMuT=>P}d8Le-*iZFbHr)DoSo-la$?*3)oxM8)G*l979p>5H z<^k70-=P~0t3rowC3)HOv?GM$Vu|AlI`5k-u(|Q9;kh+NuXO}v%eg5pH6@s{nW+XL zsn?d=0fpjP0yjJqPZ;=mWNndRqSt2~Uf3I$cz%of;u+~CTI~W|!zAR7-Iq4Xq95BE zq@e)tmn=!^nCt_gnhMqY$CtMcV9wN3tIArXrdqG{@0hdQ@sysMe*bGm;%j+T$~~z% zq0w&k?#(L2dWfxetTOKXJ+Fkihu4{KKY0S+$XD|bW<e3@yCz(ThtI-Y%>A~<Gb9vO z#2%z+veg!>U(C)uN{8@olXVZeiCj<Fxe-gX^<(JNbg`^vn=s+Xnx<+qK6Q)uOXhCp z&dHmz$^Pu;%6+qOzq*``To1NB#vU4%D@aRnb@ad-D(A{pk)!mZ=hBVJZ95hOJv(OR z(nA)<OOJe;eY3qk+fAIRE~dRoa~ZHW<4o9ay}ye(E%R1Iw`TjxX}E60Db$6*6W<3; z&%TDLlIt?>G&BSZutSV~z6V@nA72m={Y*g~2Yam=H%<ZPdAL%lO#u5as@jQg7s27d z@js6a6(FKT2`Q6M=`k#$5XlrvTWCXsru6tLiML|X+)I-mo%n8{%S|fk!Rc_JlSxNv z$m1_byGu+a$;r_YfS?gv;Dkc4yLk}?Dv#ac#6cxWNDGIGrqfKYk$@o#g+?dif79q| ze6w{9I-M;0r*KPV2RI=BhX+ETA#Obsr6Zh1w3ELG!6_>CwivlNAOBmt;ak|QMH;?D zgq1uZyOm4)YaiVTRalvn)>#K@I_?D(x7n7>7ot~q;4>&wNkyEcts|pfJDsVa_9R+U zmf&Ya3DF#@%|{Ri0qYOi#ztPqWHRy}v2=k@+JFK6W#X%bOlD}u3~t%Xy#ih8ld9p# z@29f2zSN8VWb$%2qJCDTk&5jWMJzM+<qd##Td_X{^fiEfDjNJlh@2Pe^JbCbLL4~Z zcOvNQhA4bC4SYku{r<86AgFZ;-Rp#bono2MIhg|F$q@h``pI0<!^R0LE_vY;JV1D| z<qPp4sP1T*k9)`8zGMsc=4i(jTJ_l(>DI#`w-;i+4Ttx<^e;F__B_XnJu7BI95xq# zAEcrVilqi-6W1T_WvtlDzSMm;rSmcE{J~(8y!Lf`rRlNXY+8~N`WYM3D2HvI1=}IY z9l%4%B?P*60GQtjm;^$=A`f4|!(@fwhvy>IYW=TN;iqBhYYhB7KIVoHd4mR?D#6qU z!G9?Rs2JQh2OlrMy$5g}NivsB&=;ZbITbJB?S5j6Ze`>@qv9{Jw{-Avts+z}6Mct@ zyik0UaM~zRbo4CKnRBP$VXxwuSt^GU`%xZ#n2B&Yi1a1E)5TIgeBXik>_SS;eivo$ z^ows}bpJS{T#HIhB%)@di|=vrO8`_hz)BNB5jSuFP}!%Qyi7xsQ_oJ`J;3ZqEoI;y z?7`!=p<lM+*2w3gB=Itz)}d1B<{6{S>lCbqsY9pOzl4Kbgfg!h45(VZz|<I`$;G^J zRBS@l3bFUa(kF#6E_)PYO>9DhnF=qB&d8Pf^57%Y&JeC}kZR0j#-0(Ey9vM@7THB( z;Om%+Bf&LJB;7yBx|KB{*Y+P9mH<W~;s^L4GYs?lHTbU_d?|oYPC0Pej2@qsmUjxg z3!sK(3D6440tfFmto&O9)<ET10xmzAKUA|pEX3SkZ*BviQX?us(L9SGOSA<?*eKF8 zaaC}n{ubr}8F8BrF7lB2u?i-^3LC-;&YCOg4)4)OKFkE*-k%PqixISKN?fr5mw`OU zLqIk}@JFYbc@q=&w3@pa*D5M&1Tf(6TfNE&@Bu0NY(AzO;)G|>B67o|Fy}A|Xyl*$ zOMp&F@pmSR?r|^;RAc}r^wkq^kV;qY=IPa-R>SzGEjPUp;P3NL{Q$ZI3h46i4~^}M zsVC)Z!HBI;EBVln5VHf0u3}=UsNfSJCYWgzWaJzOL&l1Z%4jMc%|o=^+jBfmI+%d8 z?NjXeMNMKCW{ac`il9EMR0ZSMCG%@W1=lt|ZHh9^UKfBqOXy7rIfg$y*BIdA2)~;I z%y0<0l!N^q2_+@Lnpt$#KxoXXl+)+&<xm-yM^HC%P>I-dQ3!|D93sNkaZhdQB^+c% z_$Yfi&H{!~`IHV-W_u@5BFzG9;!&s<Is6jA5g;~SrbZreJ|PG@BTzh;j|>xp^$f>8 zG-=u;MBS*=Z7ORzHrSN?t>r2ud6zdRlEsuPqqgYo?E=t;2yh6@P8g=F(XxLO;DePg zzN^J&9)nMLs3{uuj;z`};f+!%dZR?@YccK|ky~d%-dG6=I7EaWx`@rV;{ch_xCJ)! zFST->cN#A!cy>r35vrliQbPb6(z_sty?5G()PeSR$E5ORgJb8FGT-UsUVHfMnsVF7 zH9#TsQ?JRcC%W;Uz~=<pC2GS@g4#46KTN<weaNiG>t~-y)&5)os{zb6&UFDB)yhY` zZ_>+EHh2}`Kcj%TFV5AG(fGC30}||^ROyChT!+X~y8({6MvdVk#$O^{T|4|%9&v=C zC}mRp;j;D_pm1AjxvvQM##5?{(-NET@C{1$&Xb1+SN6K->pq$`(N}1A*@Aysx2aJs zX(lbMj)1Y%-uR%#Ec+DZ5(k^hMz!!!Oh-J8Xy-i9ymFWDSeE=^HXTZ5-)2O%@WC(4 zj&VMtl~+H)M*DIOZ$6L6nvj0+>cRuPAlxxetE<jl^VA43@*Ka~(YVP+EOkk!%NxjX zh&%5VTH}m;QWMtYI(qG2jLPXmbOm3dO|Xu2D8YRDAA$PbY*D=cbDxQ+okgdx(QCZ? zzs#-A_Ohe~K;V;1dlT;lfHB*z-oQrHh|w}7s?<GTe80>WS$JDIB6!v+LU^HVc#mP4 z!mDG(@8yxNGK10qXXw<K%PHKNj9~GkeZ_^9H98ep%GLcZ{<M)|6ZW~IQ@?T0Gq;Ld zZez>D((xSRB_8H8)&48>*d)|`oyCryz9a=3D4E@i@Yr<50-r_O4h6AC9Kj-@<szUd zi=_SRz(fe3#%p4#YWW%a2OI{%+yT*(7WDBme95hR+h=(Hwk9S+Y8L^2gQEQM%8T9F zPyViD@5a5lJofOyT+_b8>&d$;Z#h17Egb-<-Qap2W?1Mp$UpELR=G@o-gvO~U(gU% zoTYqukc@jLj(Q=&ZHh-N^0x5U*hK=yjhB!wXKiA2crwd6Rv47KhWIdAUg+bgu^IVc zTq>On-k7UkdF{LK?Cr(xZ!f)n>#o?~={~~GdUcU??RRI*%i;49%Oy6onBsTWW?zB_ z!a+ZzKj4NJ(csr5(RHHZ1>3<2u>~B4mv+FVRKFSC1J<yycWCecVU^`JBgF#>ZC<^@ ziH$uav3g1^v--%MZAhq?%YvRP<Dp(Ucey{yzWn_|_P2+No3FVSD_=B-Gg<iOT8&w~ z==dEb2I}mFM6RRD1QC5a>?20}GXiEW5A{cc6IkYk?E^mmyQhSxifa9FBYXuDolC>C zu#u;k&KK*n!)OR;6XfiuqRMZ?)>1{~-*?Bu3(cLW71V6ICm$R_o|r6ruzvpVJB}1L zPm)*$AJv-8ETFQe=qI9*uOdA=OGJ&pO*~NijE$P$5MFce^?Se*C?Hp)!WX<*1duFI zf~Q7foD6)#9hoddzIys;>&D)K^5-G^potAiK1}JZ*~D$WH8%Ju?hoZT_ml?riEG`U z@B!xLtj#1JUoXUb=I;x4MmGxZU1VJUJhDYVxky93VLfXkz=v;Zh0Vzy=D>Z0S3gLv z+r&_Z)wUZmWtGwx+AKcYlZos>jNE_z?ZLyh3HX_IU(zE|_Ju!aCx7&u&?TFVC?H^@ zuRqS`pdJa(Ar{CA6Y!_Ndr90AQ7#?t@!*4r4Kg$9oM?~tpyCHNt8}Rsks@ggU7G~A zrb~eG(A1Zo1~V%+{=FC$&bSxyhld9krVfdyfLTO^&_<$;EWcm>;VC>+v0oA#(KEfu z<U?5>X{2l4hP#axm+u~DBC@DT1)*Ocy*q_E6!=4G9|ylP{$JX|e~r|qto)}YsmDHi zsre(o-QZ!`*chmi3LQ><tV>yD<2%I%+SthVucZT+b0;1S*JOBZGpIf>yYAdOHSIfV zox($?9GLW>q8^J$7SD%P^%st+&+IHyb{UTN^9t-l1NVM%9x>26|Dx)t$WlJ0jsexw zRZ3~-2)^})$fZO12}~Y5r|at1nP<N2`Evv~lhM16hbZgUwew!C$XdPtPHpcDsXP8^ z+<78X;?`*Zp3Om@WVk#7Fl&6&A|GUtTQa}HgZb}6XyuN5S8MOaW^<6df2ufuLIPpu zmRmcv>`u0NzVh_N%G%3|>x76FJ~4}j$tGhTmtk15aPzcZK2WX)isO>!omLQ^|NMZO zxISC1o)dkFeU7s3Z1__#-oJZ&=>_Ru*OcbKefPwucz}?ruzq~c-X|{VW=tV<)82Xy zP5QalNiLnz{bV}W88IiJ$5Wy1Bgp(dee(T|Gs|l$u5SlFyOtOo8IfeXoOJ*H^W#U# z3OC#@`}W%U4}$qoaPYigUX!Pu=*^Cp4@q-X0?b8=Y^?Gs5uR0MmeA23zcBsrQ6v!f z<MY$IU;hzur9mB^;aOIf?d88`cJ}AX>c@$ArEW1Z#aV=poH<#YTt1C86ulgfHP`y^ z%Dy_c(UGNN!;ME?IL76^A3E1qANuyC=%>2KUoO^TL7T^a7WptPU25jij-hLp|GnK; zwj4S0_V&pyCkl<WhwEN8>Z@9EG%nj7-W$DbQHNJ)7Gv>Ec|m&M`h5eK)x{5&0#5^y za%`Fe3j=K|CIFgQwlv~IyIFU=Mz;CGwDHWX8grj-wC$g-vs|y)%(j<xHJ!7+SeucQ zzGZaEKgWEeWF~j(=<g2RZu5XFo#N2>StoL$+^OF4Csqj#S_OMg^>zNZ_vO+d?22FZ zO*OfIZFWDl6SiDzz%*{r>68n1GtNFGd-sqPJs|tG)xF0z?hBu~-rVwM^TIBx1*k21 ze>EW0?h5bf!VYVU*&>5@c~8VZt-Y3<hqLB+)4^9dw-@)g{X64v({20Gq9^gXWaQpG zuHW%Go}QmKlK-y+h6Lb%1#A}h9|>$tlJ@^dV9t$Ik24_&EFcXB6l9a_{*%CJ`U><s zuln>gU4B|j{XY^|`1EMst-2SNXo=_zJDdNv1oou)%Kw(YZeM+M&Ffak`zN=ry}8Nk z%-G<1r{RAju)|O9Tz_|$J^r5rcH{m1=!O50z&<|WNMh9b&G&SvB4fz?1Bn9vEPt&J z&TVWrB_KonShqzwKc^eLeQRmkz2?qdAcNWkYbEEth630#Gweaq%OsDZLy%n0*_eV# zY3JUz=+Kdk-x_*cQX_0UNrq^@>%N8tuunj2vuU)95IRDyKfhOn#@pBgqFXmiROUSW zIIdEt*3=UY2tI%N=rxf#{Re>Si8)dVL1Hdar(T?ZHJ=hE5*+o$lH~RWjU_7uDiz9+ z;L%b@1%g}^J&z4^_<U9#vd`F{6VWb3s^JxbKtq^{?beVt8n$WxErG5Tw}+ucoQRZ+ z-`*O{g9B1OB>>`L^a1=6?O+~a&m>YPE%kt^@z46fU=bX7arljs-=+x|0_iTie86-U zOephRyUVXkzHvndP!Qas=lKoP^Zd4rrhkDJuUvSA055(2`BcYEUuz2YhkU(U5(q_e z%cG{h*6~xG>;r4e9YgFdPwH;+uozll;J3}LixWYs*;%`*e=nl}Kf!X;=0F=Mqs@VL zmPN<TM0Sj91}sf4yuE6mEc2mR>JRmJ^uvSOzu<v>wj_RQFZ9>=l>hBJ&O|A!3v^04 zZ3v7PxsKvKUR6;8hVGn6x;gmiw={6`SHYmARCp`~xU03+*MU**67Yn8U{<MsY1^mM z9G!sfR5^DFt-~)dc9Fm2MM3IbfF2;;d?}($uvsBdqgUyxk<Yl2KQj2%wi&@f?zTyS z{jBI)kiB5X`kE$tpm-Gm&mP)$Jl%L}ZQj-9^RMb9t9M-s7=uEpZLfCkFTb4EL3J0+ zfw8zjl=huM+1|~6_{VccB#!;rX_(JnZ%o&&?Yh-(d{@e3m*L9Vr=8}PM*Z9dcV3WO znE>RTnZ5+CCoaAe$`wSUIBQ-s-Hs~uwJ?9kTyW8v7a8|c?`p;8?)X!mm~9y;S%BG8 zyC|D!_F%Z9ZzB|h<9z>`M9i^VuMc<CFBdgojD9XIyfAqYWc<Y7&tl>(%dd<6U`Jzg z#}lK@i9NZ-Em`wVzKj9P-Gg2Hd{<I@(pdVJn{CE@>o;c~Pw4dE`N7wZTATD*{te6A zI3;%8%Iwe`=59mCgq~`5_R`WBc=XS3Rfw8TvZg&N-BwFN{vkEx^^gbtbFy9dbo66A zN29C|@eTF0sUFM8#!T;)T=jKi>g)AEF4}!4LFK)WvZFT)e`;1U^&UrB%g>3&jO&oE zsb~E>RgaIXsU}tT+6(_S;{7IUiIW$)jZ<J4uPzDs>0YtHvJB<`$4?ez_ufFN#PnQ= z{{}06C%WkYtY#LJV%4Lg9Lb3X<V3V0l`@(RBI}SnG~uQuTcw3zf}E>!h0rtX5k|SE zoFz#@;)jjCT-?Z#BrsUgr5(|jrE8d{Iz>ZlD<6IkG9*DP{{_igVHt<L?9#u`oQwxN z@PQSH>QkJHx+#6=Kw4+f{r=B}F@4$IJ_*E290%hfR`!|MYSrnM9_tit#u1(!sf#A1 zI}gh^*l#OSR8N9b*>#H-?$6cje)s6^Buj3N8{=C{2}y9-OLK2KD?x)1prEMzfW04~ z1}X}yt$-0a?xYGODg9_l_Sr(o;@!<3wiON7>?UZE%9WC-IWbR<e=;r>jrQ2AHiB-> z31BbnsQc-doFi3<>c1@zKk^6Qn}$17E&6NCkC$~G>K&KK<n<^N>){R;C941AI2sHK z(tK-jRhPY(I|_|5j<;zLN?Yu8WapBdrPy4aiXQ$o8EHqZLTL&llzV<|h}?hT)L3+~ z>3&`0UVew{c`t{}_7rfpTL<yaed)ml8BgyUnj2b&KD%e4-HkO8adGw1-$TouUb&-C z{D+gW!sDX6)~!rR_ZT>B%gA_nmX<5GT94RhT>0*Xd7f(PXKkaDr<k)f{&E87kfz3C z=;*v=#_fwe#unU+Go11IdlrwiCI(P0WX)7hO-V%>7v)&fjxNyamQy;Iq^a7Dc0=kb zkB8GUK75it_A6P>G&XZL&rj|?4KX34x5OY56&?ZhO4Q2S9~bvty*G5_z#A5BZ%dW( zD$_xudm#7tWK-$&S4Va{Z$~l2pX!&=98@;xXCIz6FRppeV`ZF|9y2ScDi-%pEgEyR zAKp>@Lr&RjT$$<Pn5gteBu(NEfb57Z84YZ>r9dVt9w|wD%Oo3yT*wYu)a=f(NHz$i z=LS+G)@7@_q*VC=X>D>7f))e=+5C@ao0OpFKTbyaeHp&M!BfZW1ZJmxJtv*pvVkUr z(6yvv_LNKHeAwP&v!{VoQIR0mrZ;WzYtGfTq_c2iw~?1W9ep@XQT2^iggLb_OSY~| zb@QaXPVL-y*soR65+t#o3IoT>_A0umA&MW2W$P|TD#VtgQo-`fi1KmLa0-0ekIM9I zEzn^>R`<5HMvSAEtsEU&ZDr4ucAbC`n7y_bZ=R$|FWE=atNxNSQPd}|DO=JawYhc- z^Ij%Vset;}XmAWXOj_#rHteKHYtJ%#?XMJNFTG=^lC|%rreY~4dDrzY+)4dd)spqN zPwp!NU6HgzIYAoS@&+C2<<v>~t(2;B%ILkj`fc@_Q}zb=A-I!kq<3p2OPhaDvLgdE z6qd+Nrg6AqCpmVnc^1?y5eLJ){;5{&VoK}l%^}ZvX_D4T$_&c}a#@S8_Ge57gJogT zcDX77lgHJNxzek!=E_V&l}-H}%al0B!rt+6cr~8~22OM;tTZR<wp_?m%_vH@u$S(S zj9oY;rA*?}y4y{&z6A;HlBSeWw@#0J3oE~<UhUjz<JNb|r$>T#Zx~@!`u*6oLz1eC zEmALz#qHYf<2N+?<H0L#Ryd35w_y#+XHRl-F5LaQIzV<ZC(j|{ITxp2M^COBLZ^?h zvzo-?!#z<4^FT6YT()W|X)cD2v;;aZzEqYHhnyJml#KA4mBu_i$xFoDoJExpFu7!_ zP66nhXa~^n1q{q8d+#eMwx5a)PQiZ@xc&zY{bz%L4v2tZN9-UE|3nz@^1NA{2-zV3 z#ni~_h=2iV<R2QkL~N~n8!V%tJ)9D0j*;eG;1VBoI|^EXI=f>shPIq!Hx(<~8rI6j zFEJwQgA&WSQIL?)$3{)lK*!YZx7DasXvjK?{Vha?QlU93_+9|ku~GL$U@;lK!a#&T z@DLm61HjW6$ZVmMIRN)$BSXZ}o@~rd9_`F}n7K<L?yeA3&cQ4)>_-^*b>^-e@ZfqH z>VeQ6np2BK_G^$%CBzgnOsi^+RM*G#ZN+zSTzPEdUn;%=z)U(}uf93s+Y|bM?S4;$ z#HXQ)`PelAt^$#%eK+pWRxnkBYt_LA9>rZxJub9J8Q|krIB*^>%QP+f1L2r09M!@A zUok*v0yII*c%zMK5rB}W2FXtEh3FhM`nM4BoluZfwn{@a3$cC#IG2EkhHmkA(veJC zPqHL5rt{&Y`3e|0(TeA^EIk&sKINbx7$t&-Dqupd8FN#J`NqRQbDU2cycQyPD+2!; z!jORf7!Q+m=M08YvcMcaMMd)or`FiXVs<>kIcbrNhvq$PoTT6Ug6;PTAkeK#2;QGX zwovh30Gz`%yvNsLuf4!505c^h3`7JxJss&%>@nqq8)bkJTMyqCqfffzzGC8_sq#e{ zm_@}cQ6c3FT;-r@`5^S=_#hhz$rjN(L=pgx;vpRgQa(H+G_6hINxSnf>tyFhIu&Z; z)v=M#bYkwmp(&=d*X5}Yx5~lPxxhmS82i(OzA=$sfd9r6wLFw3>bysA!XPaqpO0Fj zVIL`$-%-X63cvs|>MOAOVSV{SN9<<-E}o2f#K*T;oIe~>n7JP`Tz3RN5#qWSAj2i6 zhKyQZfTLvm0y8(}N_a61e9ypr66P)n0~Tkow;WN>ynl&mdrldi1<kbpB%~8TeA5|T z35_ZpC6>-6z#{>;n+W-PNg?Srexbm0T8v5+qVDiPms{BCz2IkR<fCon|2lE2#pq7< z-r?noZ#Z~}Q?a`X4gnYuEg^X2qDdP5l?d4&0E;05j#vH!h4=3TZwgR7RP-t}(Y_>k zw{uP>fa(Q`JE`aIreA)|#|x;)4p9*_m&)R0J!=WNLEtYka+jkojSDb-qRR`zIEb7Z z;-G34EmwtzTnLh*q4^9jm?xdgL?o>Xr6Fo5jE9H@kRd{8bLhl@Cw+oh8Y`4O2w>M~ zUZIs{0HN%s7;}k<%HU%b1>5&%p_<9KK|;W9=BYI*bm^j21?S^3LhGT+p(i%zE`}$- z{AT>;hd|ub6B^!a^`gaHY(6zYL<7r&ke`#(9-Ne^bENGKrc?;wS?A4uC0)M@LMq;B zALilL8b{Qz%v#QhsA$0ptQJIWQ;xsE07c}wWiQ+-8uSz73KIwXF6x*?_KE^WXR!@r zutbP$6`~huXkRfRnuAE<rKJk_%7>5;ee*9I=|ez<K=ztgDv#z^;UWWSU-cMcM1RKI zzlA!!-iv}pJF|S`c`9ah7SnkdRW8H~E~Qrn6~CfklVVXfL`lYPkq@`wpNejNt;dxL z&%f?H(-eKJlym(lAkgy$KSd{cUn^=9R)}XW7jw{B(YRr!#I4Rwg;X%i8~2;+xeZa| zc=vXTuws#VJA5bDNkbc=@Dq$fKTv{j@7z!6(0gb7qE}r!54%9czJUB38h2iZ;M2f5 zku<uMe};|p1>oo>CFht@GzJ6`B3S@jy|nZs;VShvp(eu|pk3WPU=l5jZDphKXOY)t zF&zY-M!_+M{d+|M>;esQgNn`vP|#TvaOlA($NsmdFf$6jSu%C;*UdBQJI{@ia8Gr^ z>!8`;eeCjZ#SJz(5RoNNcr>>Y9dRgkk&G>yE!?%5)Nh{XZwZk&;L65JzqW^ae~X<G zVj7@x7mmGiK<>#>6v+up65RB>*78$XK-mgHUSk~tjMxkf@*6s7V6FhQz{9PO;c`=m zGZ4@Pu{L5vlu-I4`AQs8%8?Im$UM!NEeV;G;pob2In=e~ot&$kM;R4)av|j#AHT-N zRSVJY$ox0ID?S0ZX+D@pIM<wR4~dH5v6q&_cJETJD_M1qvhmPa;WQ)R4K0L6!!2;y zf$boVffKeq+MO2OM&R$=o@+Dp@I^>sP#p?3a}!uUcKz#A%)=fKIssT>Uh*$*H`3_~ zWnk>fx_<`aEUz}KQgPOIF5Rbs&uGy5FlN03_k@gY5u&RZ(wSwA&2Fv1Y~)EYE4f6P zBWevHz_WSM5kjedUp66O9=)MmPNQ<sk(d&(bgcmO(lRTHk17)(cp~3yfrVyJuF-2$ z4+9(#`mS*<`L(q?<=}6y;q&Z<_w47(O5MP*n_rzX-X1y&Ka{&#p7YfkpR9T_AN%4% z8z$*c?}0ZUfbCdP>JI1+@tBFp?1oIvK7aie5g~C-tHSebU^xS`NW%>=9-}jvKAw-G zCYTFCM3vyuVd~S&jh!Z;h{K}BWa!}&a{;2b6!`!PKgWkhiKWs6mGHd&Cq6?@_2p8` zoNdPcqXV0T=pYVie<Bt;>bD|<PD7%bnV8#V_}^ma(++puwTD{J9<wudiH~tD8t{)3 zM7e<OG5A}(m^Lc@&7lX;?}a=nI7oY#+mF$(sQWkF9_EUU)z8s+1E!4@9SAK}Z9pvm zH>dd+p15L8AAfpHcsl}B$iu&2^etteV3yc-z~BoSPwuznf)EqR1D}Ynw}of>Xb7KK z1af7N>W)0jgFo<*au78h6e6!<piDA!nY5mrFp*{r^&jtY7)!H$Sz6A6H*iqiBIuR@ z+<zBr??I2Q)9ykH+)*#wJQF=4iCGomE^io=xQ|NzR&-Js1DT77>6gC!e*Y`}@sj9v z@PRiUzZXUSxw#}PG(i-t2}6GOiV_dsJYgC>=?y~1Na({4j{Yes<Kqt81?z?Ixs~S< z4_Z!nVJ>d3oA+@o6;?b428S3O4+PRalJ%uR>?#lU7J@;Uw|zy@5n_IGd80`jg0F%w z7fGe^5YTM(^cTd+0mMO}l;prD<3_*B|Dx#LADQg`KY(95*<@o38^$)Lmg5`}Lff3? z*px~_8!8D=Ds;GaWX{KGgf=9V3aO;SZO$Z(RFVowlFF%W9X|Q)`w#4gUAx}buGjnd zem)BA%M`k3gJLMJT#N2gw2>c9Q&wz?3W#IKdE}rRImJ{<^77qqW2!Ev<$DYAHzy8o zQv7*QM$J!3{&%jWVe12V8{zGX?^O8#otxFHmosblZsZ#jp+dQBE_J9u?P;R&vH6>4 z2cAyqqP_zP-|p^zuH8pe*PVTHJE>n5Q-KU`c{?)k|5VnVfPZbs%Hd+<FRH`O#C0)k zh%m}C1-?ajB2JmeNI)wI#qh(-E6z_4u?_H&epqm)YLLN~Ei|XI{9Wx-SR6~`SsVOs z%*MJfwLXc@_XgB2xyq2s>2nuQN2w}57ZAJj-<myA>;NjimR#0-D?HSU@~czJRvr8A zRen4A^4~MBUizuorm4OOeRXVpGQ09sX~8ABX`jlwZ`qqwpHbJ@l`6kty@C)L+KI}q z8ZQ2xd-2nU{d5BPx&bw6_iccKoV})YxuNaZngn%&lK3kT&Y~cwd5tZoXBl#sf~j;^ zQ1bW(p`f!)9DuWkh%_{`n5E{5`4SYU`FX<baU1LaOOX;#&Rb}>9=NWas&c*oCZH<z za&Iq`qN=EkBb4jQ64W!f@|Z-8RIyZtwA;n_n5;GoNK_8Te3G2Gdy0ru*|NYxoxevc ze#}uq#(l~<GkC&B!JWoqH^Ik<3+Y>)78IxzP@8oX1A#hJ^#U@?2s!)v&D#OxOXD-7 z08}#LU9|+c{77Z2K=IuvD<Ug50HtFT1b+hdARg{&)ge%ze-lto*8J&F7>hWr5CqdE zpy~3`X7ld@C{2Nh(;8YidyS=hyG`X5OSu`XR+@-d1k@IYaF`7kpnwB8>-vc=jt2+) zk|6sfYX91+C8!SnqO1dGxi875m+$D;bjRzOCM>sR@<XnN-i=)m#8<(tRdy!myPhdw zSnsSq{o7u-dedT*w@Clm7rm}5f=zO1*w7xOCm(#zKb|`{w=ed+ZvyeZMXu*z@uU6X zZ9Ct4sbQ@6h$}<Sgg)<@Q_rukeecANy*&6V<yg@6kE&9u2-Pn#%&r?1?z^KCfASCH z6E;Vz14Tm9nfj)jzm3c1Llz^ubM+t`{O+ab{{NT2@H&hC?#gcNod19bxV-ma)2D3D zs|84HfCn7{=?u8Af3B^t%g@)py7TP3_{mAHfEK&ct&zi<#eZHkr1G1F-tWF%>A>rw z<X#vpTHlrRfO3}Kc`ah-3!(b!)a{!F_2KUy^H)lhG0vIGy*KMqvgR5Nz{3yT>R!)w z9?B@2z9a3?V$25ZzZ+#B^(3%oK7A-sq(p0SUB6B+)vSMvcBtN)YJwD4!~qJg>+M2^ z$L7CRAvs<xiH7)pMjO|A>z|lz^wzh7*fL0#zu}w?f1k+0y|LVV7{9#2jAEY_2|v%W zNmP$=9!abc5Rdl-6rFNT^1K+=^a_RDIisG?0v(cE)|tF>u(&KWaT4ZSFjZoFA+>BW z${;2=E#E{TxlFH>?+cznY{{$Z^QhRa^y)xR-MZ`Dx~H29qK)X`k(&Bpzo>zZ@w1>y z=hC`|_Q|Hlrqhd}n)|$TPEV=7r^gFGu+pZh_3qc5S0;Gq7O&3gPSZHi=MZY!C<IOY z0r1s<a&m?~{@Y^Xp2Hc?O=10C?`2f{BLTh7@?{LcG;LyKo~Vs&2>wkArA2TPvAnlR z6$ohom7Ky$O)iEa;%ZCnmUrL!H$Gkcqb#ssGJVkDV(NZ_5X!3zy*ig0Gv#iK(jJ`y zULeVk7j0i=Sx~Z~2cmTM+Z&Jk(n&&t-^P)_CY4mFXK~t*&{rneAsZS3pnDB28*Gm) z_14R|qLaQ>=~rInrL%>QYJ4}9s$+8TAOjSIW`D*Rqc;AbYUeuw8^DMyqi>D!6%v|Z zp{oX)hj!seW+;c@--5zAx;FlI(Pyx2swg4^<f-C2x6q#JIP<nT+a7Vn&~|+&04P$* zPLT7b#HC6lQFn$ybpWe-SDvJj3*nkq=Ssq{+q(Pu+!E@qcw+g2Y?Dj$d+veA(~`;F zk4whG>x<ozb;@SGv|Q=Y+POs9XY_H;)c%WZvC_+d&L@U0;kN~rCg>fg>r2tSDR16^ z4RRRrB<wfd;CJ4E_ndFQ>(Z9t{j7V|fzcyWkz*&#`b10z0SH1Uid2<uul6|qT~up7 zwy>5+fNE^EpUt)u$<*(#JlDs_;8q+NDvi`RF1JN&PEN25KLXY>vr*emF(N1egD$!w z$kQ$Kl*d2U?FcE%$(kGtd>}`7H^5bV$Xz<G#qbSPqARhQiyBJ}-5y_WRh$csPJ6&l zKc1pdn1<l1uQ1ZRs59y!ftseIE~ATOf@DN@m}}qaCl}DJDeZ%3E=iyR2I_a>(2;1c z;zs@OVbeXq>~1OxtWUmTh}Eh>+e8X97>jC0ljS8uk4yUo7S$3`WEyvfu=`$<P|5?C z$4MRNSws@tRUlI;IY>jtu~ouK_UZOW1f?3asQodXxbJOH^52rPOHPHl?Q6ZozOy#D zL2>ScK4}j*Z1UlM7Ey%O#IDYUqb~WuQTTyT-k|X|&5w%$J@G`Bi)2+ZO*cR%a@}D0 zY-es9s|v%sU&U<@sT?$O*Lx!NUiY1AAChcH=;wH1p(z=Rs~=Rmz(KcsOJGC+S0x#u zPLjYx?jtl*F2FNqd{W!4VRd$sFz3!+nX<h_yL!FE)AE6Q6Log-ToM3awQ*EeMPZsH zj;8Dj=;%d98dNkeZHq{1esW*EF|?jBK-6H0eF!}*P++C5Idzt&J2k7cNxmo=<sQ}C zQ(u}K2+BOoiqsvw@^N`i@gbc#70*MIoGD2a@zf;pst<E*+uQZb$=N8C3Z`#GOCgdW z{&a0joNhc_s1{n&Ab!Gloi5g`r=2Q68@BFi&S66P^`}s(oe<*4gwSJJiVk;#VpR*p zWn-F`i7P$M0~@pKgWEM8O1g4d08#W85O8vlkDXO8&U2HhXIMO>n5A$z0L1AcI1pQ? zcHMBB9>5U))wVaYtC+!6Ft1@6N7u)!PHVPT7l(%zHhrW;85B6C2NyLCzW1py09vd! zZ;l)crAFe%<m)3|rv?UeW;QLHOm`cl<e##DbRKW_uq^TM2#I^jI!6(X1`Y|sZMBN> zS9tHH(61d?P3VX^cY`TO6}?WXk_mVi{#t`6do5IlIhx(b&r_kJiujlc7T+X9ru^U- zN$u>o3aLd7-$FfN3A8*W{74kh$RtcZRmnC+mJ{voZcsb%#J$TjGnG|^{qAbM|AS!j z;UYTW1t;CsD(Ea^U!!Z(JOY?XQ}vIoGGLZ_4^<fzCK02C&d(l@Hh3#%sb^rjE-;o$ zz$)>G5wqjAu!{r-<fT;4L#k8mZUyWHyWWnBWCkCA^h#ORJ&(p24c%e}i!9{aR^o6x z4rfEN1|reH#Gc}6iw_&J&F`%hq~ok6YwDvxNT<BV$J~<<>m`%7kEhfSi0`3P`K0Q> zUaWC5=#qDD_23dqxa;6q<l4@LNKN{mx!u-50pp+Ek9<$*b{p=`?F;>2dSzyJ_t~a} z0}F-++#aV4wSYKo%zd<R<<yOah800MJcDn~ylqFlpQgU(Fty%Q)-~pv8Gy`>^^<kp zxFALCaZ1n~ki*G%>A&I0+)=#YozT&3@#-dzJsik|Gj*Rc9?nb0Dudneqiwu1F(+TU z%sI65-u6ukJFZ?Lf<IImf^A`Hc$oOQH#$07&{s8p!vLVKDuY_5kghYU!cPX!t_eOE z>E$_ko&L8KwehT(q<u(is+bN6A|j;c(HXV5=Q5);qp@P*$CK#$`P*B<2$BqY{mHT1 zct>x7>7!!#k)^`;oV9l9!nJ1<@zKoVI?=IHb<ES5qU?Z%O*%hQ?!UJKDMhHN6m<=T z={-8-N5zp40>A@X?phV7t%E$pq~|ps`=NiyRWRSu!!CKOZ1$)9a``Mz<j`}zV2X=g zPOEu-6{3d#Z|3C8Zx&d!K^=?XL$TJr6S>`w;Wmy+Kw_QUP(~0-0T~+}kc<7P3Yx)U zReHOe56wVW%*$YxId$BWb^eV?Y@#T&4z?rnVP1g_kV2uPigRQzziUeLLRBxhFjj1F ziA#v?6`TsOr<PU35uHO*A4afl9z>vmdf^dNe)DWy<a_j;82-UbOMfs_0f}wy<!@@Z zakme=Mh7-q&q7QTbF7dpKOU?9r>7Awg_%%<K}_ie5oF^8xVNsgWdUMEf-=?-{{e9* z2#KqNZ=<LzX`lietB;4;><%ii0l+_`S*5ehPm*=J-6dQOJ(dCuVVWOUcn~j7_ryHR zYZJt^;c}CNNiDSH(F}i1S)%UcwyfqlT)JsVg_aB4Yq#3@L+PeqH%KXb*QoH6L{KMH zQcD&#wNg*F!Bjp;PmMyiqhY6G1o+qYtx8(05FJ+`(7j;(Jt^NxaziPL?}A2d%~EGb zz*~tX<Xi48&?3E`@L(2yF93wLDX=ZRV<Om@y5TEki)#Zv(g<n<02?W7Yivc{Cy2@h zT5yMM227y#jVeV?K*Hp3rhxpMjTtAY29Wbq{qp)k^DJ7G0gjT-=gjZ{X!++`Ve;aS zR}k!wmi-d=&IX#KCgam?pMehH_SL?u7HEVV{uGmURR<O@LAoi2|4n%~?1y8E+YhF= z?LrIpHjo{|JdOruyAt`72lubt!ZQYVDIQl3u&>ZXd`cVCY(j9lxr4CS^H@$~69o~D z5dRb?C4}!Tzk!=-jbh(@@(EpSc2jM#&UFH8je|Nb6a<Z$^<HU@m=(q|ai?dY+bMl^ zvbOMoTBG`6x8GUAn7k{6`a5SUQ>#SdE7jX*jdApQCE59FLF4KE@{AU+*4Zl=p>5EM z9WDWFlo^>p_^1zcTiyXy`?EF};9hX39R6#lyFTrapQGY<JZ$GI55;X=5wyBe`Sxh{ zSL=8O7a`7VMNuHmfgt|DlMo63)9!`-LxIOnYX4C2?;j<e3^55tv<9>Y+?jm)Waj~= zt1b+_6@nVEuHt?o<R2fs^`ri-Dc<4K^v!#$0fzH-wBhMG;nD!%xeF?~4VuKsdH4I_ zexi_2ld;ptQ}VdhPrX_p?S$Ye#}l10Rs%L1S^v`p5x=^Q=HpbEndK)|Qmx0N^$J{c zG_}gN37reB#W<Z7lf&w8hnG;#Eu76PvI*dpwXP$iZ%gFw5BT#C=w_hMz#O@mC^!KX z^!8dBxi@VQ^8y*XM@Tv9NRImsB(RVH&dovba&{QPtP0@XvwZJW@H;TSxa!${5U{0= zUksKwp1#_Pli0lWSG29Dd)71ooKqAb;^1?q7V8&I#Tmo!kVIkXME<U4V!eGzR+j>D zey&TM)5#98cj^-#*U1m5LBzDfl0wMmF%JtUdEk2w4#cDfp)>qH=Y<`+z3ZToujK4a zsn9XiE6$_%n~Q!8L~nQs;x@{>JzqDFl-<H~P?Z0<_CEVv;tjN1FoFoEVzAG|<I^5U z@V?;QQQ~n599V!_a;)5Xc`+d9+NqOI??V8a?GQUX0fm#}h(0&JY~|dB1;k1UVJ?tb z(WDRpCp;uhO4}vrPYqjBQ%Z}HaId5=U#1Nt$b76B^PZvH+uP^gqJO|xc#vY@)8Ugp zp_C+nZ%Zr=A_{%`uDQ9V*A!NS&l(gomYw>wa}sfRBbQE_O25=1_~?h*Cx&mA&_~!x zej>YQ2H$NIovQC}N6fcvzJZZGdpK%EZM*(^<(YCn&y73^xQ^a3XL|1l2L1=%HVU4d z16!e+T*(4UCZt7lJ+SMphvuCxU{38iZD4ie#hBISEMzDJ_P<g^S-&U_aUB_K^Zd`% zQ*F?|`E8SEcn}l1wr6q}A~W16sf;CtX5rwTn2akm={%h9-}aJ=0Osn?ECb8@%%yu1 zq8GUn=}8>nrw2Geic-A%u3gZ!nHDcV-f4Fax;NF$Uu2Wo0<~uNrMmVwOtg-dS<+i> zxCp%;a&od@A^T4XI<@3y{6`Nj3w}kxOjh6Nf5zU=MtYlRZw|5SWvKL0^(ZlrTa$F# zQK9<A){hX5t&ek!vU6zA-uTgUu~r6qG+db^-tu#&Kn$NMLE`@?lPUtnMtyt^WtPbL zvI+<>T5iwm>+^9_3cAUlCJ4G{J}=sKBSlN-i`d11JvFPVSwszwcOo@$jd+au6S$kC z(K(U7cEnzRqk2;l`48J_+$GO`3VM{loV!<;#zriAoXJsy{9peNAjBk$$%_zW&;YR4 zD8!}m#=oxA)5n}|u|2YCATH!^p!fcZsRA0nU%&<VE!_PGfrX=07`+)$XqZZ{I1~iD z9@@bTRhnVJKBQiJGx}z{I^zPAQ>bU25YqggObq?$S%;pg?W(+RTD(~%OzLfBY>vn# zV-8IzF?*G=BpKhr`^%T9{-dy4wt1;?@u+9<{$99G$Zo!ku=ow^Qq#LU+dKGMkS&Vf zTBfC%dYB8q8SjtkI1P1^dw1zGyT5xM**((P#tRS`m?EHeL4wV_V5f805PSEv*87mJ zV9pW`$!N8*LO9f2==5E22kLG`0ezUtI@=(n15`{;^~~eVqL50s+blHv817n#YB2j^ zf!*cpZT+tX#D3Jw{sly$X<!Zw4YUat+xq$%?p1$3czUj(L<i0!KjbXAoTiuUXYFCO zWM<CoC%d4QlHKA*1rf8PzW4(t_GdroyN*eM-1r>qsvq_S9O5+r_K$(k{};s#ypLM? z+(9mKPK2h41%{4LmtKC(4l`dK(!CjC)xrc~c=uEI-ezy?Imn2svp$_LpswP3WO^J0 zwnv<CP$D=*tqEuDB^w*Q8QO6G0G^b!HOlASBv$djA9MIQH^fS7_A;ChcR5vpd>_Aa zn_~;Gz1e?HtdHKk1bGI=*mLucVHyY7AJq&g^_hAGuX;?S_@w)>9t_(HqtK75?O>^L z;i*}^Wz3adJN#4|nE+Y+8^#?{@;Mp9avkLP_4b?`{rs=e0<fvbaM9Z!2yW2^4jWZ6 zL+}r#UhuEje(b(gtGpa2$#F0ECaQ<nbj&|75cE=&g41)F(8aTgbN?1!UNoM)g8n+1 zfT@BCz3Vd4$eBxv51?$}+$W`~+v)oO;22X4r+V4DIH%;+@WB*Ct1j$EU*_an#X@^; z_R(bZ-^>ejk%9@O{lq|fsg~RCvalTi@h<V#`{7K+$2G@m<Ket#D=T!}YujyWo&~}n zu7JSWZ$9h8b<RHUE;*R)IRV}Wj{<-Ig>p3^9MBx!1PGiH!Cqt!bYBdxni#PTqB9%p zx|;ZPjPKCEJoy=I>j)bGd7mEL_`x1S(=Fa|0iMP>cG~e_-K%t+(}cs3{6$T^CmI4S zb=eTSyA*UFu{Qm51Jt;HZ%*Z(O7y&5phLc`S$VIvh^cnr3Fg4LoE`rP;v|malj+Z1 zi<TPAcK+F^CcwURMD22Pyx^&{%LQ{G{N_I=1yKuU{UzX-ps3Ujm)1pir#-TA`j>BC zf8nl7&-nd?2sHoEw4$rWz2|=!p8tch6@TsSL)J`FvRg;W?-qQ6WSzS+v6mr0K5BqK zR;*Mra=r}n^Ob<;1}MNv5BD?HdcH22e!R0r;7wK9PJyM75j!tuq>cWJ9_61bfFKYc z1i(AfBHXhe+ykWV5($nh!1e-4bz9SpGoey7E~XC7S{3Y~q(_pKbiLtcCg3rb;o>@& zHyYv@0*wZQ;paq#-|~cd>E=fWvBdtMko})H!g8nfT`Dh6F>qTZ=irCPR-3*!`=!UN z!Yo{r2De@PeCT5{_kiLFSFfV(H(YM-G5<UH3cZ)_mB{m(g+w~$@NaJL+Bf=-qrwB^ zhr~eEH>A|G>t%m@2FW`7OqfF%MXx;zw_L17GSP~kM@0EWcyQja3oqe8#EWSRurvek z6bY*T5pJJ=2FL{-6P}g~;Wj3WM1j~bVJFaQizhNpP}Y{c*S>Coe8a8<Q`UCIz;+Q~ z0WktaDOaE)EO-?fNEJ%q2!uWLQ|PXn26t0`wIp4;lM`VYwp<tV+F^0ZB>sKtP)DcV zJG(5cyM^WO$7dhKnSEzRI;gev#62nd6t&NnV7LDl`G3CM{@7BBv^lh8Y)M_^W<e{5 z1O*BTiJTv!pawYeynX7_{HtY6q@*EJOdW3eO4xk-$BU-;&*v;TEk`~MUq5vBYv|GW zU*BaK*6P5<z(t@9;+0ESyD40xC_zo1NSu#6@3l;WQ?b_kS@}@)<^1y(f69BEj(Qc6 zQ@=N<S9KpMy5@hY0HGe~rS<5<w{gqRu9$)uZ=aogep=NI<thJ8$)X;aRX&)Nf1qW2 z{F;(uJMivPG5qPy+II)bB4S6(N;aR^|KfrSd{h0hqKflPyH^5XOWOIBgGQz1FU%Wf zA&<%5Eg*T6YWaJl=j$AgA(!*BMcW*H85j4tV7Ju;2qkzsl&FWPp=SFmx?PABj3<o* z0miT}Jx(VVj`qh#dha@kAMR2d+h=PTaH84XBq8p&kKW(W;um`Y?!ekYPxv^Qga`dK zO2^fXfR%8E|KPkyYZ1|t?<2z}8#4^TMuU0`{5vmYWV>sfH6>-BtEvoQScY5O79GJ5 zD5<T%bG^i+C~NcT!kvDj^_>fKX6>Drt!}>tj>_F;M~C}t|Ag?Mcm{LZQ_D*lQT;Y6 zFn5B@vgI>|b#O1K2mhT|q;h(?phNA<pVii_uD?dXYA$paGl5CPc#<gL>w{<OT#94B z%BF24W+)AcoXX$OvS9nv_IC{Uu?NbTfdZb+zVCN<732Pld}H3OpS<i}o$K&x!O+L8 z&$w8PTs6%funJEEl^&>U6qOk87Z?l!)+pc=ne;OVj>~ue5)o3NPWwrjb(38td;Z)S zEDCh?F?qaZ31O)M#ps~S^%2SH(F&lf5sp0*d~APS0t?nn1X}uFY+yVIu5bQzNJ%Hy zxKN;R5D)g^lv^~3bZ(a}icE?`LwJ{^=%b$unI$y$4KHSnsBG*&80GksaBQExdM|fZ z1AZ0MsM)qIJjrz&r$SJhK8{qeTz@;>@H0hd4HmdRwt#Rxj8ldKEOw=w5x)PEQyp+| zNgkO!C=D*EOmG*V-4WuPZK_+o`x|AtC2eMC_&gctSZB3iW3e^x3`kVATisus<5n#$ zQWO15=4HD)Yluudpn|!yqHleiCeo*mO?Y(yXu7wy?qRL-1t&GHc<D-v7q@OXxZ%o? z;x((!*5|kU?L3>Wy(-T(YmupBh=cIJB+MEB2fC$62qSGU$5fJ41j#p~-Bv^^V51q1 zAjDZJ%tL6XnU^SN%zK7R8+e}}c7$!3aX_68@nr$j^Y0V|v}MtB&7KLburku!0%nH} z1Pr*g4xti~t974GcqyPNm9%Mkg2g1vm4m~YfT@|ND;ZW4n%Zf36v0{QJ(EDoVU5#w z{UK&puGnmtX}RHWHL=Hpx|q2uhKFaA_c;8zMehL-2_4taRv|(8T~FL`9Y*>~RVQ)+ zr`@qXTRgC>1tph~ii&-Uvkhk3gjcAZW?42D$tvm@n>wWw@gjtXlcuj(iNPw0`NfuB zmmh~OZ9D(_w+ZkyDWBB@(gYkkNi7Yx96M#+uGeq|<1F~*37Hy;BIyJc;8hkT$_y$` zqkBPU=qN=7iQ3Uc6M`8^hE6XBf|n38bY6fp7Zq;$*Y8&B+4majbd~sCQ^+(iPpg`$ zMEpoEIv{t)-mdfBSVA635V_+^d&3zsTor#}r<H~<QV||UDShB+zK~Zr&VV}4f&uLs zvG<j8NvdSLH{z@aZi-mU3l>Cb7l=E}6WFMpa4;%PLbqIz=G@|fvESt$3nezi@py>l zPk?H>5+px}u2+j;6t*|Rfht9_#=+Ggz1U#U)y_2``XGY;YiU7qqkyXppm%E{zvrJ^ zb+=qSs#3z~v%S;so={AMSZX9au?Hf}uRoX}{h3g@H`=C@RLDh%S-UqTDkBT15X4p{ zKe%pc-2oyUC87!}3+T8$K&Utmt-sxV8$luwZita8_UmuzydLc`0UB}-pcfCn!g;#Q z-Ojxy>NG46r*AYg3tB(S$BM-nwv{vu8|OwV%tKAnru*$F&)+9Luk+hDD^-3~B+wnJ z^R%2|XKsH`Nca_#XGxwEt%Ou*-gcx(h|H|HxhQOZJXCmYlbR*%u<k3dfn6;v%OQoU z%4guR%{pow>ey;$5FMShRpRKYw9{(<gN1ugAaeObL&YlAoWLJ1|0w^kT3huFO9&fH zP5G{&JOCyo&lvTzDFdEjKjo>SX?0eu5}^d7Q-X%sm2(j1>N<^_WiWNKN%d!r=`LjM z^Mi_HZ>!kH!C^7md)6IyMA~P9o<mOEd8xC^5t!J~)ZSL8&>J~0kISDsV?7GP265dk zwv+21w2sWM@|d(#SypD^`=aHP%o7{>QOMipb)QlVH`>~$CRjw_AM^_BC7}ARIXv_& zPJ0@iseE{xXK*7?c->p7fWEexRMfq-U*f9xBI9%!!_n>2_B*RAP#ca-fLA*YWOS01 z%ws1)2AShR51<OYyLSz$V?U|(Z~)h^@!W8615MeU6RG<4(T|-A4R#dy2c;xsx;l@= z*Jzf&Z0lsoRZJzPHrnm=R64E}EvDhY8bBS)w*8MwL^R~lmwqo>4^kHE{WYC_T*&$v zMGc7kdEI3Z%sad>`^}Ht#!p&09cL!H(jC>a8h|#BhO*2o)z*)0HxnL~1?302j8yMU z?(*}b7w#89G;fc>(VuPBg%7yvwTtxZtCG-$53H1~BDyvkDr#s}Iy4{lt`C@zW`F#t z!g~5Sc7O0l-=(CR#eA^|Nke>?KHb}K%c9d@a3!6{m8uE>52Nylbta==%QKcIN(SSj zn#)bJvl0b)Ykvx0c{a;YIj)^y;x_2|Q3=dvma1I9gd`6G$`?3LOiP2%YDKDYAt+Q2 zXhWv1@QT#E(v5)zjS$Bv)AmH{BcK*NwN21+e6ZKewsC3e-T!o+IKF*$ElIJXeL_>K z31M0U3TpKa&ir)t@1<i>hUM|bKa*K6D@(VcE=BMRhCg(ZOB%x_yZ7Pli8F9@D2+A< zkkcM0q?^~vEQ#vY1z-yX_=u;P$pqNWm~TGn{{tsX@9G*x^LGEF;iqZ2<BYsju0b-0 zi1x~BemZHw!^E@`%iFgU=uP{)Em=|9oIFGdYd3m8BPP>u0B{@BeoGx}v4b0iqlG1} zDSp;%hz3Aq1kj|?P{#l7SX7K;?tTv1C+CI<c3YD>`ays>Su3D{r;RHLKFGI?fh>?K z7)Xc*FlNu<C0g$Ksu={*MqrZm{?y<4e5hkX7}%rYd|1g|jC!c)0-a9fQKE-P>&krD zbcf!(>QC6N$?E<&JV&vL4`P>tyu%{I!@<$rbpTwto1SI?cIl-d<WwY!#@z?8Viqm1 zHL%F`tQb}}x{K(K20R8jlZCL|n8=in9&~pBg&vZ^HD%Il2Uykt)z+^j!s|WRx$Q>H zG~Id}1QbvpKD&LDrnRCM-k|6Prm6r`6@@^yBExGw84d~Asks&qHcA3G;KnaJ2RV=Y zKrlW4(K9}4s~P=>*l|oo@=WAgweTF}5c)9xu;t5pF??f}s^qhTO>(~NNcNZySmoHR z-=xTmIec#T*!5TM!l<EXK@j7Cj`BC?jfovr1z=YZ1fZ%1n`mBif(+gRo5nz_7ciEr zUYCOQjL~+pI$ooIgBM4;O>6Hmffy&!2=g*4?XIRBUjNBy*gv9G|8uZcGE#8Jy8b=8 zMz~mf1gTDjZv$%$5Q|478+T^9t~}qu;2VV~A`5h43$2^T1Rvx690iexBml?7bi#@& zfPZyRq*<8(9`@!tt)tUZ5t(zbXy1`^)|j}~;XsDG5w+_~<T@<uv<oYGC-&oeFx=(? zY)9VxeIs`m;T!(}Z;7t)dcimEY<H3KpV9PziD||;g7g!ZWC$UQ671`ZYdqD>0V*|B zcT-rqJ<$X6rNg9t+&1QA+}Nurply8KLl^@wMRZVRAx<@5=twuvu8@krfJc~R9CyFq z`Hz*VZHY$j&T0@R5H`OQC4YPJ1QQlXdq@H<&Z08xSI3q=JHjL07l}Kz#Bog;WLPL& zJi-;}%!)(0*xf=5UMK1ffL_^yo1Mx^=^j?RH&geJL2Vm6;J^yqp}yQ?#E%v^ZW_X) zBqH<@APb2Qyc^#(xzlQNZSSUNi1|XUe_6SC8}ENM>V{TB4+`4dSYQhY<oAwG$+-}V zg2zVkTvCF1&BKf4qOft|7?}gEzVtFl>KE<;sbaTVS>(HoV0^!NJ0RRQ3BX7X5VEG- zj7YrD=e}G(+ulOcPgd&?JP&yTN-TeF(8&$;*}q5nlvJLX4^=*36SZe96XRIP9}E$U zb+!DDzad6u!lW7XA|Ou?Y)2(Xz;;o$P@^AE3|P?(MmW~KorYZ&Y!X&*-bLJQy5hHg zs@zu&HJJySH)lV8;%>>ArjVoEbK5o4$41y=s2yeEC;V!YDG!>u)hv$^L#I1lK2Hzw zYM@Wc!;;ReU34tx{k@HSo2dEZ(o3P^l`#8vcDM_^G48f5?FWY;md4Nh5q$S}y2~Fw z7c$-K0mO8LTigg}qbK)Kkm1QDSUfL-E5@$oMB=Im6s0H^Pi%`C(U^|m@Qm%jq0A`j zin%ZZ259Km4RFXcTwN&LFa@MgyarjY3lm)Si!RZi5Xs@{*}tx?rRk;+O*sh5iS2?9 z9il{rumNn_(*DNcslzPq23K&|>7oykPNJ)mjUk0+u2EP#H_g2BW<$nbJN=A1{YI{1 zKSWtN(o;9;qIX=ueByU}&)~a2%vpuWJ38DP!|DI~Z1Q6JqWx39jU9F&&zsCTz9}R) z*^Tm7L+zXEQEeu&pA4_;h>*hYbog<Z;)Wqbb5SFpUCFTBX<U|A*}xc$ZHSwC&cnsf z`ED`yURjis=djr_Ykv?g4HO!=2aoWaP{?+oePN><<Ukjqmzvci+J?{B^_AWkM7Lha zc5!S+YDHH%w>#oAkM9r};rYpK9gIxD8RLT<+z~7PP71Ni$YRWv3VD~+VH-xbWU0H0 zubg)tvlW9ck6t8MC2nkhZbH7KF7ix?9`9eczXor+e7n|sgif?^|KGt5mwDc}@7aa# z+bvffpAVu34s;kIX`1pjEqk6`a<_h+Y~O=EQ&2{9`c`#K+S{{|4&$}%!8jOkK*KH_ zhH2qx$IwGvD*JIa!$#c)zY4WkV7*apdR~s`SeM3S(bs;haEn*p$M!@gvfxKR!pU~4 zlHJ?-&Oxf*IQVyvV<4_A*2@j;f3pN`jvWrj65|Q5lN_(f20wQ~xC#yi+6H<29GAo! zYXcPbWOuAhp{cdHsdb@8mdqM)+4RVg>82sWOP`2`N{p#*OuR!Mu4E)`sIZ%;;ooLj z4s@h^iV2Hx*Pn5R?T1)0hizv0I5`!C1Zg_T6!usJaeMR#C_8=lzmzV69El#Z4x11= z?9!!Q7jpL%4a;fQo(6B8^}I41GW}{kw7kn?folqINYiUHLnQf5sxXQfn->hj*~=bI zUcJ!Ub#qQuA%2<{M>B=$B_!=oEC(j?j`3-C2N#}8oU!HXm`gHm!-%_GL#<~H*qCw| zTfsNX9(T!UH<7pl%h%mUI;@&yel9^CPs|OEbhx#&o0NChdL+J~2bG*tan0dv-@zw1 zHy^oO&RA$C`**l-t~&z3Dzf&3>l7>E`L7^<%S0{PIGJ_<NT-2DZUbq>an%d9>!x(s zH~Q?vO=i3TAm8;#9FTsEq^Gm%c^%F04~>|pZP~f+f6T@HkfcFy+h86TTPK@j3-wa` zH--zD%sua98n)^)6`Tk>!|TV?oal%wQhQB}90Hy&=DUQn_Xl)*zt>*VC;k0`P29B0 zhr&0^bie1TZ%gs;wt~bhf6;i(r_`0V<k==HuNaNir1q^GO>gj+^R}4hC)Dl|r%~`@ zI!yYsNgRYxr}8!0R4>Bba-r#878o|eH;q;Zd0j*Xm{8M>9syA0fKJ$eeQNiA%<Trf zU!y<tRxk(hlVNr??Y2|Lup=OIku2iLKCL}A4%^7<S7c-ayRhVJPJyz)gA4g9`a6<g zio)JEN%?wzj)q6m!$QDToZdr2%!^-NXcl%F+@ibrhc54c3eXG^T~~Z2+x9_8(bZ(v z1v<fgDfj(xj8n5Q1tL-3<o9SzFkXf?IP~twOMXS#0{p@_*<W`--l0&hd?&Kq82K(a zuWZ72E_etam6eg7U?0fLh%`;AOj$y!iI6_w#I1V3ZrfmpHQdjSXq2X>`pGi(dN9@> zY+S&5|MT{}D|YN4GATGtn@Gm(D&Dc0gJq_?d-Jt_|E1vupYUFw_)GguHXe}B76zVt zn;0)g1yi=r-7Gq8cat{ZA$sD4mNJ4^^(ncRboP$9eF)!8!nNw1jsKmJW>Pltfmi%% z)i0XY=Q`nJFCbW{JLcG5%oJ2i4o=BCZYS`sOFP>_driWg|C`MFmJ8N$0ap)K=&gWM zkg_`h9<ld1>Cal^aAipDpO29UW&OCTI(xfP6t&cv?Rt(NGm(s(qbGePUL1o6mvE+< z4tvsQ`s5#_BTnnUbzhHr?mm-W9%Hhvr0s^1Y|CA4Tki`~5pO|(*i8f)^s}wYK~{_d zd?s|zhZj5kE7`N~Sh&^`jFqcP$AKRZ`*L0j_@s6cc+-Nr5zDyn!o?qNO6d%`1vT+! z()6*#Jo=ow!pR~tA9~uK)mg%r*QLA;2U`xTH*cm5QIGBzl^Kz_AKNg`0j@?IEho7v z^rczUJhua_WM}hidyE$`dCy8L4>!_|EHh*6$sBb|4}W}=RsNxVm<tMW5$=7E74t!V zRDqnW9afdY&`=XQfOF7XYfAuxEMB<1-QCp@Y$D-1ghayf+t+<E^~`kNxZu8C1hS-- z057j&a@`Lv@i%(7*Dt%N(Ap^g^_<52`IDbKTEIXw-FDtxetxfO=YG@Uy6Qvjme6HQ zW!rDP@wb+q#otR*EF6C#n>%jyhEecF6tIa4SRE--mQ&G8o*prNKJV#Z3XVv1qXJ71 zq8ew@nW<zaD8MwdPPRYxsb?_4GaLH_ByTB<^3EqXy}jR~+V=1t-%<2Z5rXMQIlk2S zs#?9E%pzl9{uO`y<w4hs2Przq8M9uS3AX@1<4~E~&ia)P+iUZ6YU6=A*J`hTHNpnp z=Gl#}TjTX^rvk^H?|G4{x99Hj&ga!j+2c*I@r$ipd#+d3M*pdY4R&1*Wp`wJ8^rWv z?AQ`BOIf^n{`}IOM>UB-M=oiXMckcg$}L-e{LrTZ&+{5(8=scmY8<0{c=p2o!ktqU zwE=z(U&M8%YW<Hb(HZ%bRluD5%69ME3+DFe=)NLR0YQ-xfjVifzf7Qpjl@j*ED!dd z6F!)oeEwmtXCclK+>0nWb2@K+;D4JhO&1a<LSRF*nl+HgzrQ##3r25FS?as&-a5-G z*nI99zs|W$ju4rCmDdR_t$gy(I9*a2TjsYk*{yT^#u3l+r$S0E*ALJ18DEcWUF!?# zNjTTIztX$2w?{Vy@mZ-yKUYwDGvr5O_l2ZZCt;;g;efh#npe_3LZrwEUK}=i<w#F^ zPW^gqZ-*-f49reU*BXTEypVM5K&4KtK@eVgK+pM8`Nu1%C8gJO_A{f?OW(z2_7p`E zeWFaK&0JJDn+rGz2&>_Rc9asAHHB7MB-W^=cP}fWtw(?c^yXIiG}?cDv8VFCiQ>a< zzZ1XI8U7hvG|cp4qKv7VTgVL(mxVeX+Gc!m0U9u_X>iO-UWkF3*8SX9co2|#T|9_? zwNKH$Q*U!Ul{i#upHK-hxqj#Bbb94JW2gP+PxRF{>87P8dE$;dxHnUlBv~7Z_O<y~ zdig?{)s;&Z6RJLGVA$=NM+f$;-kVlGGv6e>aGFB%>K=Zfm5w^yJ+`c4;kn)PLfj0< z>SDC&ml|x4N2yY-&&JTfYT7S3Z=I7w!WCh9V~mk{e<7UpXGcO1z!o%^Y67Tks6lTM zCkoZK{@tCSfBfr}jW2Jx#vYzOT9U|9w{Bw?tAUj5nJ&~7Mo0dB{S|%z@_SvPlWWb3 z7-()>Tg|z^l_783X&?~_q=mhXHQ1F{8dn+AZ>9q1Ir)X)lj`x_1pnhc-nhUyo1!Pf z-*uv~$yJ%%7uH|rPEY7#-kzv*@_Gd?8>?R2h660#CY7d%C*9BY6|J2(s+n}aID7Dv zL1w&XQ`7LrqS~e*rTxs1($c#DXHugL{L??9hbz6GGxA*#NyeGF1&$yQkrP8R+Ef6u zq`F)qrVvHC0}vpCL&B7{bTLL3^MA0Q@mk}IlS|vP6%#r2SjO2Gf1>JLJB`&4VNCuh z9^DE_Pb^N`nQmX0Zb_kIE{Aw*I8HNsy}-tnR2Q07_T;9D`?Qqb!;G73N{7BM@TXF} zOjjD!ju=BQa`)lzSrXER=&t_)*W=i>Sd$PIdEyPO!g1O})jNkrU_pB}W?@USQU?MW zS)R6OtE~>tqtcd%IvekBO?DR03DFx=Dpo+5r>6Oeu97t+lj+6_2PfJ!F0=_9bU{k4 zfW*;FrCgZfo<XaTB5YYSl|PpYgSBO<XL>b({Y~(zU!>^Ws}qE!387049l18!1D!l- zu2LDlYYpd#{nI9*X!1zH1%;d5hN&bUqMbTaK-lSMnHy%Q_e%sfY1yb27DF;vMyDGQ zhE#yyK?@0|EBfm;wOu(=_=X90+quG<HeaH!;*johiW2&5_SHE%4dFkI%hV#n-XGs9 z&@g>bQ!Pk>0GG32TVhXacC0eOXg;gXTdh(FSm0wHkYmoK+pH_;%hU~NtuZJ6hjbrw z$C{mf6<}#|E4nR4y-MzFt0Ya|x)X8c1Z9x8HroJG%Vj|=a5R<ZM80+jhZ-h_G%-Wa z!aq_Hq8UOq9?EZmZ5MY8JRd#vN@NApspQ0%0&PIRK~r;7SLBPpwDw}hX%Z@VVtTJ# ziF>Gofg4|inUIH64);MY&m`lNbXt&4TO{G}tpBDNS#Ibo7~>;Q`SgR4MVoz(zr$DB zLM-$)OL~v50jREJE8VZ3{J`I*Y}j;e)-;wHBz-TA|MCN*TpVgq*(mRH8&p>*Hc*b( zIfk|F?G20_foR^C=&`b$>}U+L^0N9|YaYq>J}vol`F<~0WrJ}GgLDiX!GHjv5~%iw zL}{xf4-*Y=ECf=O?aTa#_sq3odkXKGN*q+jYf|lK!SniiMH4rAf2c7EXlTeUce{%} zl>l7KO;dqM#K$y!YevikV1Z{fLsRi4R$r*Do3)|R)S_GHit^@ehcX+r2p2H+cP}=9 z|2XTk|EFV)V;NQj*gX^7^xIycI8&>j{In1Vey?$aeZ4f#qJmF3;pA;;Ws|odV@R*_ zR=1OFW0>)=p8+*>J&r$uwgI!4nx|a?$FS||)55CMR_fsEnGdQO<<;8EJ}*0gjoQ)^ z3%$iQp3C$Qa$AjzKBpg+v_kQ<nkW4mC_a38HyUahW4z&b$_p=KiXt^CyAB|rxLK;m za==~IR73=fSM!zDFwYEDf5L5sCj?%rB*mpwHWKZS@aJXJcR>)+jP4iLap}Kb-Lu{N zr6R`VmOaa2r5T_gs@^~EmZhgbL?=znpE{L#NQ&I#pOLwpWv_c!JH$0zs+@8M=9i$9 z@uhP5wQZD+e(R|J`Tvr#0)Yv9gl3D^&7l0S&M8*L<R&8uNStPV!uRYaTi2AN11}NP z2DK?r*BP5UKbO4d*Gzlc&P{r!EykGVLWB+>1CNw<i^#4$$+h>1zB(lmgry@0@REaw zc$$$v5lye@D{!vYLIb0r+C*7~aZc{%rq<pYM{i#{_9seX59^pg-Cub0Ni)@<PWM~) z<-VFrxohZ&p>LVrX)20$GQu(u=AS`Z@?M}39=9|;_6B8^ycZ=e%%pFQ@{ZP*s=uqK zgRyRaR8M;2{SIC2b}J_-hp%)<*?$Zj+eN=(<cfGZ=RaEt`^~1`+TU;g^WN=<P1dQr zD|+t%PfPja>qGPW_XJC1uQf@vcMzg&Q?|<$XM=hX11lIQ5X5z!&ppLiW)>xSSRb*= zbz`;`YyJAE|3j{1KjNWei9V)c+@>((IiD01nb*{W{rw6v6aeN7k56bs2gD6<4W}UU zDX8m?GUb>JY6(+nBUZ0|tZM_f|7v@fZex`Ffgp!D=oHWqe`!+Dq(-E%-T+TaJI`RP zj?@%ci<y;X4u~jng@nb$4oeLf+{i4bw_K`CoYb)&)O#zEK9K3Ig0K$N?^fHhiGeKW zOtt_G6x}pvB4L^ZIABmYlgScUW6VA`U1j5A1=!gy$EV`%t<0_pWL@c8gAlI9NR7WC zf1_{52j+Bb69_P7>n=&Lu`=x#5}}rjt-AEb>WS(c@o*C`Hb?x|<4dBm1S0AGC#!8U zP%{@DNmM0KgL&&(IH)2H=C2e$H5j57;*1g34WrR5X0a{4TqX>?aP`#)N9C^y<QQ1^ z;Qil6LXA^qX2vqjflR$6ng)YQuxDd;?$<TFW*}i(=5*@L(lBdYT!R`C&Nxp~wL9QN z&pZ6rT;@~hAUEq5-F}d?oY3<l?x|i47dPOc$D(P>NbkmM)z2tct*Y0RkSbHyYCqX5 z<~QA<L-)#5d{#QOLgzGAscbhDAWWunwdX@5?NW(Ur;J9>_BP5wXeN?2MS@W1#XmW| zYV&QXD~j{8`_*(C73QvT0`Xsfh~TyTqfm!D0=6$nOwe^`90(aKLyk%HqiG7OO*aJw z{2^^993})dx)J9IEfXf14Agwv8lH{<NMj2UbX(M6ykPwe{@5=-dxfT9=1X8rYKTeM z3gOH{sy)XwNSxFdWNYd^&eHIja;Ejpk(SpKz72z|TR*w1`E{wA#@cT_A)qY(lB$zI zI={GzxrmMax}16`fyGv3(FV$+ZPza=U#HoR^YU#cqbe6Dxdj*p{@`(eL8Yw5pR3W? zKpFSIHf2Yb%eIEj?3<x!o{?$d*#-q5&jK1jSBg@Kbn@NyFsx5SyWQDg>aPP&c|id} zO4j8N;c;!Ir9}5}Dtf;Z$vfimT813w?lP_0@C9OINLFbhx@*YJStaezgm$(<xPP<1 z&J$H6v+B+?1KVtE1L+3vCsamn(+{L3l`YDuv7D1$OrhyRXL1!nNYf<lJV=wm)uqI; z#_Mbwkrah_<H#jQWCm-`lkflwUzbC0^wSuee8(Iyc*r%d^}@9;9OZfIR!wHt__O4+ zjVG-40+Pph)_$kvDRVN19S!zJj#dJfbXqgDo!RQsvO;GPLDkd5)WhhUoqE0@N|SC> zX9{<iQsPjJ21fp|^*Gc{RB3vq6b-<|6Z%zD?J<&8Fo+=7ruCO?Jnin<VP!NwNnpi0 zgF)_A>S#_R_|lbEMN|LQd|J<=+oo|*krq0(T<vxF22E0Sd$i>oNym6{ItQ9tUYE|w z?vMSZo0F)iIie+>#ET|Zz^dz><|wYKW{S+fo{bwEvfEJX`ID`{v$~mFtelGw9<%+# ztxg8%ujPrd+Zt`TC7KS;R?o@4TY<2HAl>WHK8K5=#apoq58v;T4Q1^c`VZ(9kWlp~ z!1qYR7eIsZ0iDbv)pCqfdlCT&VhJd-P^T(Pv%CqV8-Q{!O=}u3_z|of%qEzEHyjIK zRy4g_GBW!_R1=t}SlOs)OuB+(sJDtH0}xVsh??B4_FzIa@1uqX1jB5=MnmD&QtZS* zd~IRQahflJZ!kNlNg?UTL3psya*l(-v?17YQ8Q9PgWT>~y=MgtGhR>l#l?C_@y^Tr zvFmdN2mI~1*oJf1K&j6Ihj@_c;Lgk1)XAtD7DSk-?l4z(S=pw2<8kUFer-iPHRhH< zA_x=A4AeNN+xgM3l#7~X>!q*_er!X(ggCv0Z#&0VnN^$xqepCRhdb_qCjbC2i&`R< zMMrK?wm^q+l>!0f&<O*)cI1B`UT=4#wf1#Ii@=Ww6(~vlDpd_fTCYNTj+mm>TtT-I zQQ98F7K!?-LNH<<Y2j)$w>8d^u+D7SXZF51DS-{Dmd|U}<Y0T@cbW@4t3mo#L0TT~ z*Y-b^?$7S;m+Co^Fy)hk-pMmRxtMe7mz(82M~>mFWUZ?--Cj1qaWcD^!mTKv{{~@u ziI!tQwpxz&#*yAFAVo}#;<R4dFxKCoS@f4&7~zGxF@;+D4jOXk(SjCgwzA06mmSfC z=vI!3o5@Y2h=fzTowX~DM3>I=Q#p}s-7M5w88R9~DB)n^Ksu~laoy?14{hQxcb0-l z>hr{eP;j)Tw%QU)urPso%TjA$nNOxq0aQ)VamAIvo}p=!-DM9-{nJ4h>SS|0`}>{q zSQZJB&L#ZKm4-dn8;dbak`h*FkC`O>I^-^y%wwxetB9mOJc*Y}@x5F^y3_-E^+(o% zuAKCrJzKFn;SsAvL0q4L<6ad4!ki3~4AKZp_KN@Z#FoY$s9XGNy9lrhYNoARjIvoE zAmpmWUM0)jY+dT4K>wg-Emx-*6tdRZ?0(8>d($?TW(|w2+DL8i?pE=I@1N1CY|%R@ za=~7CN(w+H^%uDM<)Z{M?W`?ThTVA>9<dncB*k1Y0e7mj6U`gVOjT*9^1<ur#aasM zjX@z8ztHHEoKkR3he(*J=P`RqaA6=6i>?3n$!XVAJQIXzJyFs(iGM-TW`ZbL4Tbk* z7$*GC5J>;)f0z0|cHYwLw{@N}uBP)k{ng1L5U1pS;$z!(>p#vR{Ftmh`CKcKy?dX| z_fYQ>xSNzgk{$)5^@C=aRvPeQpI#*U(hq_8BkytpZupZcItBMiZ-X=v&mVz*R4r$r zjlY+zKZb6RsQxw2A!wo3S^?yEEb0YIdxA)=CK`Z=fG%6VM*5Ngu5>lrpnr0n$5ojk zA|FuE>$s|8z87_9ImKP5AEvuaFQ|-B6%yu_Ph3rlt^MU(Obku4$vkhbjy73G7dq@= z2f`#vZ?mNRfrkrjP1}C^4==cI*++KuDVK0nhOq@<_owa5_<f1pieHV<iTPe6<!aiK zu&eA6;hq-$eM019)dX4Bw0Xea=|?Y3f0cxFWD{nN$HQ(Me_Jo|@{T|{I>dNelJk6# z{Ct7*S1(VmmRk@qsXonZmC$hmWg5^V>~Ndox%c!r&W+8?eT02ClBb*vqe;oU4)6df zp~__BtNPkln|`nqIYk53ZAJqCuDiA#x5vmTa-RA?y@?a0M<Rz*nP_Mw-`Yle+pIn_ zsR#mKS4rB=GVQCN;;mex&x%JQU(1$uNzP7L<r4538pu%n2C0Fu)T4u@+e*@AkU~+V zc*&kx6K(C|B<x?SyT4^c-!|1sf1fGLR-a=(^d@1*Dv!OLpZrJ5s@a37G}dK)^H~~C zv*zl0jMX`D4dQOvZvFOdUEY+NDVD*+ml;n9Xz#Le*kZ2U)yt{jQmlpaf;ive?BtQ) z6kWrYbzV!V2rhD1l34$$>{yj)iv&HE7u$-<A$g#3zPLP)s49@W7Zcj+?l-)gAgrC@ zevS;=WnsvR<SHLI;@qr+oTG+-1?nRcfB$lt*0YN!T%FiX^$@n+>ZDE}JFS~Ec$j3@ zIf1QF4Bxo~IY=vPQd2=Z&P(wReiIbrNZ_RA=pVdC+295p{RVA(B1l6UWcwcf<nyV) zj}MC0XjnO*oGQgn{kiuntoD+W;6lUvn#_C1y_^Bk_F}K3>FVQd5CUnqLH3=%qr=wQ z_wO#%Vy@Spn9cq{!%^6Hw}*|u6^kRwI62X)g^dgB*|$?)6P%>WlA`EK#d9}a^gy1c zwXgp_&dxj<$~XS|w=v5-`)$ioF?O;vp+aPAS<}#BNj0RhRYMX&V`eb+u_UC7k|olR zgy=h#GD3}|qEut4kcv{#=9%Af&U2pg{QLYff6bXW=Q{UXb6ua$=ly!sX=44--2d`2 zT2}~7t<YD>r$40qN&&ZH%Yi~`pyajUDWjJ+UaPHX=;4^OP^)b+7^!2}q*v=F2`vn? zY-jk<+sZMM`t(U9+N8XXy3sH7Colhoe^FNq4^yHhDNs6*sFe*r0`9-qK|i0a6t7=7 zH=#DVL(wBi^5%`^wsI=PPmcIKK^IBZMJ+}0wA;(BOsaxKRrZN1GKb{~e{C2Dl6SUM zZa%1DXCqQRtYlK2rO~ncW_CkCr$VLVOzm0jl{2y>slT2RP-#0FVR%O(gL`7T9tv@2 z40yJ?Jibw~Y7}}<0ycO|*W}X2GcwkI#-N&2Ecm(a&WSzch8U^8efgk!kwZj#RGK4+ zu`7%DPvPK)r)rE`Ew>V@G?RDE=YIhFZ)>TyGV<+!wiX$Ay(~qWG$0vmik8=L>4;fU z*?LpC!!K{0g-Y}7H~JOrPi}qmKJ9O~t8g10n|7<rCUIC2YAQgl6Z)3~8tr|tdBQUB zgCN)PZ0MysQU5YmH7_~){FgX`$+u6fFSAZ;_1JnXIiu{qLz(lrj^0WQ#|KiLE?vG9 za>VdJUBQjLx}Qqt2WN+4RStZ4x%G5YN7j0jaY+;XS98$gUSjFph^AvN)>oz-zI$q* z_)P7&5S8trPiNJo5$Wr!Lnpom3}4#)s>x%dXfBL>e9x8d>^6E*0lD18YI$kQV)P+a z(<*WP1&X&z(OSxmMDqPJ1S-LH-tlA|_#?fB12k$J0+RKT<z;uQRo_9%9c;;URJ!1P z4XNlJ)QR4dzigMGUFgijZf`f=m9g{hVkBCvl5h8vHUrA_>sKr`KC$VE83y%VFLt5x zx(3cXwON~B1=y6(8~aVF7l*-39W(ja)*mbO5^Tn*r-_@2XH1H$|5mSaGc4l5u$C$* zdo!({aldBT3~zX(a$;t2B*$zSXNNF(QO9~2P#khV$)-D|agUkUKYebin74OOzn+nY zwGsKBSzp<erh~H<ne`5y8M6MCxw9@lwO?;JeB`yZI3zz)Yn7aj*9;jg@7)OShEmiL zOJ|PQ#VkaCigD1CT0(4(6d)HZ@3lsA2oX0Slu7|!u9Q?Jlt#+^bH~Hn&=<U&Y}hcf zCwFZoFImo2tKqat0!<@DGh=KDq5I!}$zxLZ?3kP8RdN^BctmW6R?MUfKQz1}fMGZD zd9wY+^-U2jy5TKMx6<1)dHrP5YfQ|+_{_#Mz4q$vdK<5K!(&gs@nM3@F85*3w3jRQ z&i`HY_3Zn<xl=ASLCVoeHXp|%(y}T#EMsT<oBR@9ih5!3#qQGStnfEJromMu3xPRR zvydGA<h|F&@s|9Gm!)T>w5|_Y4N^>8t-lNG9$U3|<!2haWLIV0?$f%Ss=5%-`A|I? zAgQ?w>I6wfTmcxxcG&{E1}KGUeMKcr9Pe~ikBEv88q5^ZoB<sF+hc>W3D|(;65+^X zyW#l39OJLTy=fX!rjbtCCz^7RTCAXJX*yXwaydq;q_1d;i2+uo@t=h|{a?S*)t>(9 zUN+RWzE3Y3wEFRZm1))Muc^J`2Plo*tu!TPJFj$@nsmvhT|<^jNzvZ0RCr~}O|{+F zRK(LJqQ3y9@=<T3;7LH1&xH26t})b(Kj+eYR`jWL>P|M%o#@1<Zk5Y+sbpu{^pM5r z_-V1jjrrr3@B7+s<cb`vdxq{EFw$Jt(!w@*(twMLagTV#>(%qwLJW|2=Xt{3nRYrV zFt;50c;4T|<6f%yT8os;A)3R6DF)YEw!(oSUPmHbYje<IVh;-)%&0@K|HvfZs1NN6 zKY%c$@1_0dXs@N&GSPY0SGIM&mbO7`pX(1pt;PI2i~8uC#P*8(H39d@thS5(<Q~=9 z@V8r*hg?ESyX0bG5rK~bh+eKCO7)T=UP_X^*5qmOKU#^UmT9`rn7vAn^yqb=r_OG6 zy4rIw!mp^oK9c-xLnet}e(I=s`%<?8pGr6*5mbf-Ey`Aidd*vg@NuA~+i0~$NMm)5 zr$|E$SneYI5FyALx`<24=meaf+71AQ3(<pLn3^`U+R%j!<y^7<Cr&knGY{gd9~xzL zW;?fctzo2QDK@7(GwJ-JxrWwhOFmuo)3>@e{Afwly#1ayJ-*M~JAcmY{4cL9h-a$0 z8*WlRy!$Wq;;>}$LEmj)^3G9EVknAnlnRKz)OB^qJ!d2<_K?#L3%k|QS5Y?EE}fOP zrZ=RDADYxWFFqq*sn*ltU}Bz|<~hb8&y4l%^jFHTbeukQ?%N{^?%tfJ=9{YD=n}2G zZFZ>hbBlhTQUzbBtMQ*r*I(y#Z)}q!(ZdPa%dyv0mhzMBNy}MJU$WGe#mQ1KdNT3~ z4(bzPgk9$J^)gP+7Xrj^QIcM-9#RwG9XJ}BJfr%P=k1Y?eLd@Xu5DC%llzVu;_>P| z3BomiQSeJ9L#M;e@P{)BVHE7nUC>y^_QYFQu?S~dTvW2g*_wHtIcI6p9ZzRccm84! z!eXW`pS%CaA}=ZJjMa6OX$dlwyd~>8_o%Xq|Awt~=IMq{uFKU4Q@4?mTFo|GBYd;a zb6B-cCCV^)m08jWfM@C`YznG3g*5+>IK~x8GCy0Azr-)4ofVRRBP*$!vonHbkl)#k z+MBd$vG4TU#;e^Q^ja=F+;=5pHh1r}U57ol;KH3*C%or+i~e+??er?u$}@MFwQO<Q zJ;PVM&OsiUd0Y~SOPA++9)vbK=IoUK9i}*ry1P8H5@$8c<PUpnf8T)nY|c`xqf1Nx z5lI>Gv(mEuN^o_n7cV(>`+N_LNt68j%eEg5yB0-rNCISX)8HDo5IStrXQ|Ab`tIJH zj~*GtOXX?ZS-t@jH8$iJy)#T@Ywu1mJ~MZWSp83P;}bDLLu0A&RDr$9#G5Rk`Fo5P z@0v`#FvV1L&L#v01LBbK6~gjte=Vk358!li_&7e1-gUI7`XPBm1|K=wb!l#4*VYOp z>_g9^s%?UY+ZwlIxy@**T@l%-|Df-(%GA2{UFM|9S8?igy7A5%MsTGT5y$(86*gH9 zesV;FYykut42&Kb#2XIhfak}I)X|L>2+K3`U)6*<mV=YqbK--Js^u23M|9U3ke_^E zCg02tdvtf2or_4jeRMkW$mT6X`oQs%(_=rZ%sNvK?~^v|Aur(Pw&c8{+b3>$`N*`T z6LUP=e*IUTgO#}zYI~2m`eWGL3k#%|hM7-DkMlH1qXM}1i?JDuK3fGd3AY|~)6!V_ zuA7KjxT3jw=pmtPZck2JMPv5{vv=bn&Ejh`hQmg;qki}Q<YGPOuU{8=rka?^(CE(g z8%3OC9piGWSDmIxPs`xex(4FDeV&bH$~4YZOQ93Mqw7~`_PTMM_>|1{MTuNd4VjBb zKG5%XT2QDsEXsf0>4$H4cwIG5fWJVwsO7zFmus?a+>T3e(#{O8=ixSI*N&m}bj(f= zvpUhORKkrYg*l4OKLNIaNBDA<P!d5H2+|fY2>pU}*BO$VF!6^N{ZvB6WUhZsB^Hr! z@6FEL2e9Ah2?bo@HwatE2Y>O14FFQfDW<<Mk#hp&O9o>B;8?+~o9j>v0ire^^%Vt5 z=#jBh@B)Mi5g<IoMBOM^K#6h9n{iAM^o_O~_#VFXnZJX!wwUZz0bwT|nZ6ej`xh~6 z6Fv4d)08f39u-?GMhiunK@EgHHlZa#e~3=Vg3L#C9ouLu3E--27=49Ayeq*%Nu)9q zOD!3-Xp!HpF$CsapnI@U1TE4Z00=`yhq;I>U`^&%IXr8TXk2cpy+!?~FheII<v%d9 z?|ZoWHtk<rVm^fK`+(_&aB~7|6jh<0jFW&Ci^=qA8n%~q;4hU>+ev)FKu^-}jR70l zA?z~Gr|)RU{w91jcjGrcwoQclCIS!BL6z;1y3uO7m)HPf*E2gyUoLpdhje>HE_o3N z>w_;Z`oDOVK}?hV<`viJoco_JsGvgqACH)HotP^@v-1Ck&Xv!=#P{Mp@JxSIdOVF% zssQkBXYi*U5vv5?Z$3`6xS@iK`9Q(nrK7WX#3>3<Vm!lMLQ626&|TEE>Ilp`ga-v= zFi^$^p#81?gS$)=!#}=Xv%Dn)X$+K+H`wqHL0crI+r~jPg~r;s3Uh^sqLh=)d)*ve zuL{tw`KBkBZdnZk!#-jI1M^#a;#z}*+~x6`OyAA+Z5zf#y~pgVMu$+SrPFGqrk<_O z)X+nL|7<~d?O22_>afJlLq8ZQk|4z}xij3bz7p5xXXI838<eBMg#Hd6_Im#ywgW&l zBX5Cwb`8RM-qDwob*u{%0)NI6p5yS%8$G13FX;{vjNVHMv66!QM#e{z!RqIJKcv8O z0z@z`x%`pe_goa#5!JZ=Xu}GsLK%skLgWWo-Et{=sCn5aqD;CaPDR76ii`D%JT|+? zm<I^^M%IY-Ou`TiKP@B{a~-Py%w4{O?z!pKHG|RB>=7y|ntm~OG(7||zKL+EVnJD{ z7v*nUMNFmnDuJOqWIhB><y|oNUh+NU`j6NYesLK*Ch8{ubjV{nA)MDR*uF?S)<vA< z6P}PU?*W3lCiBW782b#Dn2Z@E@0{Qn>~|>m#>L^1c5yCwUbDBnu{CBXz>*<CT&jvZ z>u{lNB+?fGQ^oLmypoXE>#?rt(mvsqp>c_>xn5KLdk`+)1=#3VO#9-Is}cw>1t;QS zzX`y*e5}KqQU?k1mropqaLZgY_C)zFs$)GB`?4zL`=p<?21(lw`q#n+m)4M{`4H@D z=-GXslhE=4BtsK{{vyQQ#+0~Cb&Dot6jb#NOGc=YHsDJ9E=K3`5tq2w16w7yVAW-^ zEIUvebz%dHW+MUij&H|JFtGRe_%0sO9SxL^BhCpxfD!txIQ>JP)4Kh&M|@G+pIhd> z08Ip#U)#&NH}RKDj@|fBBK(!%fReppcI$_Rc0^>w%N}A0RpFG5Le21|w_ECqwh^z3 z(-Qf~VR7J#z{)ias=?9|cFgH^vs2~x)$hTm6fwddIvH-x-yY@<*50wJ;yX5CS#*3L z6aSkFN)XKN82C&X`%^k9@667139wicwuMZr;2~qVNMG7o&SGfg>8L=s6!_1KWPk-F z6kFKv)ilZLIB2_wG)=z~(SN2_B`WHCc=Qg&Vz-3)nw>aFY~X^)vV=%S%rYr@mY4r~ zal^+O#8EPSghDJ5!!6fcgln@;%hv|OouV1n?#^3E0IX@;<hByTX=;uKguAbIuhz{f zr1g&F{geS6?GsX10Z{rFPPl4ohxQ|8m2c>~gPkUsw^6a#q@$WLk+-yOgEEEMjh0sr zI-TdmBvDEV6_FBq4ULSpxZYOxvExUYe~iJQso!m$$o&`kwSJMocJbvO;yTX=!aNx> zEy7P1pnFB=O918<7foA4{nK-b?6H8KUAroQt0pcM*Pj8C7ccS)n}=V4p_fs^^o+M* zokx8hG^{2orxBiOAv?&op7M3Nx!48(&8Oq)#PXlm*a1HAyWYi*FRna=fh?Mg5vs%J z1LC4?;b8`8`5tnotL(tpPDjJ=W6lqLy11NDvZ>>t?*!dyWnfC_Ad5@1AIHu^b`n|R z6}=tR+t>&xr<_ZOC~joM-r8h3h%ziRMj_i>4+bov*SOBR!h0=Vol!QtoE=q>CBk`i zp}&cUYa$$<!b>$}eGsAppl;}xpHB_am$D<ziCf<dW{MFKwsI_`BaNz&#U;@o)ZWP6 z8-KXA&#Fc)_PndTaNKbXRpW~<5fL+m;NZ)L-?&yEg6~#Jdp4AyPIHlAaYwKA8{tY3 zwIf%X=Mk}_jQ#&312nEQ9K4lQ7Uv(88<g5wjQ$Imdf8)I`NX`Jbsrsx4PxZq+?+&S zvOjo1-;cZDuF<FBX3t=d$tZBA;Bw6df8%l=h7Jk~Q~r=K)V+j%0Co#p#lqJ^J_)Ma zX1V+`(aMwi#otNpM&GACqbwd$P90oEA(J2%g@LD<MsW{sWIRq8*1t7uFgR><()F*s zi-c~?6`;bLFlhnVe;DZI$h)_SP{ub&G@7Tmd-ELyO9rLGe1ptk8kk1SkqkSW!KG;J zerA+hW&UgJslCFbo}yenz$pT-;Srd>5^OC%SdT{n0;f=hK-%u8*{%WYDdc6trxUWV zaTS)KR78H0*Zxm0;Fo)Qnq^VzbK?xF!-f9Jb2e)<gH{Tvje@>N!(ODKuLw{9R73~> z;7SMXVqVmn7Q*sI4gEm8LT8d7(w$qPIn;6C)5|*Fd!0pN61{AM9r1$*y-dM&kcljD zWD<EO)IGV&`ogi&+GqVnhp8Zw1U4OOcGO9^ZS?w9$guIr*Dp@K-upHA=n_~&eqOS; zyGo2d3v^WM9X$&N{mox|ow&OGY_hpJcuI^+A|qDgpN(X_jZ5c0R*|LdCzOy;-=Q_F z-(2)G9oz$UlzkF()}b;f9bf&Ok_7M&5eUkne0k`-TyUuL?M7q%m%x3s@!^j#C%sHC z33QD3HR=xq6TtUGe->YWND6m7l?Ja-SFR>8<Y)}J-L$IC_mj4X*M}sFhdrj1y>Dz$ zf`0~!pu?uh$Uqm;<y%f(eaR9yXd2)1dcV==`GFJ&Orn7SiwF)Eag^e3SO0#SYn+t9 zl+C@A{)hf!0(1inQ@}$5;;DtdsMA2(ArbOY)w_T<kJ?n4L8jc%&qxl`S4Q0&MwsJo z9LwA{*!MCevR-{z1n$3#j^HB>2~cM!$Ux}oDd=6l(bE9c_nY0;F7)4;RvAR>{wtR# zGk5oMhrrpTbrHPJJ>MSJXLJtC<T)*L%wM2%tVbYs4op~{iVXZG_bTI5v+*bCSMT95 zxt?~IVKa1j*uugmsQ1CU>zBb8E}|XtHVXpxlfV?9Ek!UnLin=%;HS!a&$34m;S9;B zLCIO`wwfnKj~=9_0`JX-Kx_l55kwv#_bxqIe47zh`;%D3LtN&fexI6FdTp7^o5tR) z%%UB%GzK#T@JfsKr$sXOoUiv(qud`6a~?YR2rX|)zIskB%nzK+mLq+EhtfdwSL6Zy zqW<P(bGI+?16VGE<b?@h`N&wZ1V4j3U5fOHeQBw>1~&S%ss4xD4}c#{mXG|`MnUaQ zBO|_-qRvVzWDI051=;!?VR;o?Jo#PWGa>?bk5!krVX<EbKN4)}#s>G9qDm#*uYpfX z9-l^4zbqa2GXK%z!pF}GG1T`_R%3~$SM5)Q8#j2Zi4X^A-xu+}=x-+i2=DuzfCEOL zhD3Zv8ou=9SNLK6pPxj(nhEK()qAH`S|lDn!}r=I=vaEt*+0L!kCcsGlwDiIH0a5s zZvJ_u>?hI?RQ>Ps5kUSl1B~DEXMFRV{W0}_0=T7W$&p1=3iauX8W_8X;DxnSKb`eu zfGJc&bM4=6r#s`rL3c8mNk&=*2#WBKuV5`^PEN=rv6;ApzF}}k@yOb9DW1>Jlw+py z)>AWML(@)Nb;oQi-{BdT0)3<U-#^p)F0)c_9kHhG2Njc1a+~($KNMAL=KL%ERy929 zS>bZg_}I&+xwh>z*j78ek@+X=lrA%erd`z*RRIsPwGTcIAGweVOY&tsyVYgo`-Ws^ zrZe#0wG-bzzkBuKv{$rIuNfxaN%uf8bCmC>^=<Ihg$vqyD*abC_cwD|_#JWNJw?W6 zZe^p_S=>H0TC@MQPT$wPqFtxD7*gNfWnDB2=~4<cG{w!Ft@0)69`?U$b7sH%@S%|d zRFZAfEfv3Sq1E(hi3x0T|JP?FbCb8WB^n;j{T;hJcM<s`=vdy$()NVa%hhlGCHx@` z{xvmA{<-`JK5n$(+gH;?3jD8&8+S{jNl@nIo81{3;Ra2j2N(XeKFmjHX7*Tq<KLH< zz<iI+sYQ2nzVA6ZZ?NR3v_EV}O=a$k%zq5v|EjkD00C_JKk6-TgEO6!#02Fw`3w2w z-KmhKYw7<{Z%qgruJ`8rKkBVw6DdI2@PDhfjyov>n6dwV_12)Ob>bhY-lc%oN%Vvj z#^rOTi5=U%3}3-g=w0_yWONR<j2XFf>;&Ms?y-&UBsbb4Z!(MTe0ajMIYZd}^3MC= zYR9U>CtEp3xe2i=V@p#`pI$YenSQYQRrHtFZ7k{D-LITKz3s|cTRGXjLZ1|sx#f5y zw0##hWjG|hmLUVGJN9wb)b>1RU;XyMyL$6!yZG}zb*5@LYi}f)ov(A#FWx>_`?L0U zNSBrfeBMq<l2R3_F)+q@WtfSCnL`1a>PTG@^;Y#{%7*Bea<oRBw|bmbVenL%US;)E z`gF~`L+tero9*NE_w(Lh4D0o-#q4-LJDsE5T=m9ZuB&B;xMU$_xM+-xX>vDBf$s|5 zy$;rnv%dMEBv(bE#6|1vho-Xj<y9Xk4)&UxqHK=z9g043b%s$CRO$OpZjZBP*_HTR ztzCuq?_wQ?BgVd7(hBDK$I3QYExBlwSvBZhFR1+a!8zZdLfVcA6X^rno5uH*rex1h z^3Psv(MzAVZeXI_;@33nZZ!FAy6I{`ZxbmViFqkcizsZ;y16HCwZ}-gBKRF9X5B%9 z8)4b<X%q{nP}Jl;V|lW2U#!ctOO$2*8|)q>&5t*I-YE6Sxmm4*-}19tPN6*4iITRn zY|;m9M?!ze^IZxz4VR{0E9#VE`Xm{)71n3Gz5nIWWl_7zyLmr_2^j5RB~fa=;2sTg zKD5*JCgroD6zS{ZBHTCOf*jHQ&qB#b6ZN60-OC5Lcg@Qc4D+=vJAYP@g7cA$+BZ)a z1G$f_zG3c7kwr4VY&-S8d>>nC<=$XJ>LdKI@bA633Y!dp$!7P%@hG`N%PI!>WAkl; zmb+`?l8t6wst`Y|VJY>%EH(Kp{8q!}Ui^|MY=6Wyevl+BSr5$=IKAP{;Gx<dF`w{< zqK265d3CYoetKQS(e~Kyx2*pHE9d@uu<{NTP#LPzdNls<a>M7mbI0b-*`FLGI*!&B zT$)O&iO(O{{3ZUI$fiv1n~q^v!WGn7`R`ZPE+zi`DNfz|Z)GO`NO^{&O7K3z^y=+4 z4u0G0>Iak(ouU=ddwcEQpPygW)`(teyV{qTFqK6HC_&38#t1a!MM;|(Jh+;VK-t+A zk}_w&V2g<8_9=x&9JZ9Mk}alik*(!kj^5AdQfT8RleH$%N2pd($F;V26uHYp>Orb7 zK`NzmfVh?n_6z_5l$Cj45WsTK#yB9uDB}io5Q8vrO@ddGBIbcRbc~lWJeC8MI`tlz z<Sk_$b-%8R>T=Y4N!NH&lM&8j^enH^+|J1hH|DqWYECWX#IYrlL}=yK6*0<W#ZC)a zO53x61e68aVUN?Lvt_>K6%ADAZ13yy2>qJ1T`OJY6crIox+Z;9XbVIwqSyanob^xA z)>HJVNag{+y#a0Gb2a^kzsg>^*90O9`6+}bF`^6vq;@VbX$Q0ru%!2fo!3}ccQK4I z&OkJUNMWPIa@w=NjtWsyCQV{qhBJ@=KPjZmR8x+li!$U(M^AKNw2A~2b6^cdfY@dK z<T)q`j|=W2!Q{mfbw#7-oFq%W0j%D$P2>^n2S{(8Wx%I=hmxrB>S~BixCxJou>z#m z2UpwIbV+es&GckGRU)QZJ)+}i(r^R=wa=1zHV(MlB*)1Epnd5#qi*a?n)TcUJw-R2 zse;V~+vxx>B9%h2eK@}p@ztxs?%@rWxlr%T{3lzW9_e2L^AvdWzS}!*+>kk&ZZqf# z$y$|@NG+juxU)&658m$$O#66HiVr*C0hEyVz({lPbEYA0Um`xk5Mh%1A{SA&TS^Kv zBTLE32O%<~Dc*9!FNR>p_Le~$850dXThU$8?X4O6F2SCSudSOw=bjzNIMtA{9(aQE zvd=hqQPxutgiAj+6zYb~>pZ~2QTb=XoZ%UgbKzc6S<9wp%NDz*a~=7H8-<5#$^PYb zH!wf>9MUPuR<>EEQKdBoReyiauf}{5Of%GWDy$$wih(|9=*+m$PX*{N1d2spD9E@` z)XWRP%$4+WOR_EE$dK~uS=A|9>vHj@i!`O4@sC@-<bq@83>atk#wyqit-I%=X&l|) zu+tq<CbD_U9fJJ|uHuR}_pTVc-|T!L{z&GEoY0|Axcf_OQqB+a=y>JDd~2_M-H(pj z2<lf0ty6N1<o0MDesAI^-q&t&XKo-_|J$YS)k<44iq}X19!mvi4QEb_mqyvXz>CU} zCv=~z>O0ORMH`Q6+a1w*dO;`Su!^ZntNF{J^V!1dUu5Tu_q;T|v~!?Bxg%tk?ynL5 zn_n#{yXWns1;`s7Tf@*_iTlrJi&S#I+3QTq8p%A`Q2)dgiX!!-IO8L({>oTL6gaUd zDX7>b`NrD=4ZBaKqbxZ;?y$(p8-098El;){$mC0(x*d(eZ()ue2N+?BaMX6-oSkSl z6gkb90GFC&vKLRD3fp0KgaX$CDCh-()?K)=<5@&wO5&lew=i1-U=o3LSJHTUk0jK^ z<#G=yNdx~{&Uu>rgTevQ6hJk%3Y7w)#=2E8Ye^2a5(srPzw{kq(%cp<gDtq%M$)^q zYNXnUWYVXV0n#pOxE&VIlLl^+QN5o!vr~Eg(;EX)M=xi8td#3feL&)DrX0orF)(HC zpH7cH<r08JX<&_uw2iTa_5h>}$B9nnk3F-atPYXt0fEWCEup9OY03eM4=qPMac#BJ zYJW+OC{wnX2SxUzx)#La-%`NY3PqrE#aylZIIh-vH%UMhT30^F&M#|MxA6HiSiW<f z86=q<*bG|5l|wW(>)jlwm+~uV#Xp!S55zngcOx(oIV{rTVruVNd3JL5HI?Uj4=e>z zj5G2!8@rU8A30^E?*#<P->9i;mZDB#V#Rf}r?iI;4(^Tx=u`4dT&MR(BQX2gH8%Px z3XL(>vIp+Ojeg`4&Q(E1RFB{naa3=pUVu?kjGARcz>?4a9rsWd8iI(G5->j(`%rKW z1kpk=ZjMKIM<<8{#NT9SUKDplj6U!I(=NhG+Y-#G&l5R>84+=wjunxi3O@E3l>mz% zeBhmT(8IqI5TB8tTn45=5ZyzLq3bf9Kv->W!oTf!bOffA1Su-Y91u%uk|2<??;n{V z6M-t_;s9|3tdsbcM*PP+A1B7NlA}&koret(rvZR3FuO-4oZ60m!3cZq9ZB?I{iYL! zxg6M95^{+aJqr-*I0T|IR9M8y;UMaGtT<<aLvWfs2co@*mlUea#yC1oxTft;w>ToQ zg)m-41o)e?B-cQScc(Z7Y(Pq*fB<S7Tqhdfo(wXF@+lEO6?AAUv<E`-_!s_)Bn2=w z%$7wgVt*7R28*zIKN-KdOiTnpzlB{X$(T7M#DRdBGuzB33)YDhe8BzYC7l#zmpK#k z%|q(}OzR?}4#G|gh%=;gY1_z?KZ%_ZA}b2W1=06uxJn=BBrV*1@$i@LLGNjq>AjK> zzwCb!^D-CvT$C&!<wyuc-xgCoFbKHVtQi6KlM`l~OO!AtU~B65Nj>P2ITZSW+e;<P z@`-H>q_k}!GL1D$KT|{@&M)S_Xn`si=msirhK{$6!G%K!$916=3Z_e<42vPO@=yPx z;J_OE3o?|(qXYarfDYavK@JqC<Nbj>Co%yjZbCLe(VI}s$e5<YY703tJi<pk=s$_z zDwu1v%9x|4_3?@JC?Hl5d#0$!(>LW01vdoY0a`w2%R=Phi7|MI1g(dbkV=8llqLEn zVh@=xO~Xr?A`K!GTq*{j62&xpf-}VDVkeyw!~$%V==33d=n4s9i%O)W;D89m+lJ|) zW2qL<A3AY{7o9qGh3-R??0-prsnJg)xx5zQUs0Z^9&{T3B%ZeiXy7Iqc*CR1rEwls z#Z>VN#oUr1+T{*3&_&_KtuR{Y^a^GC+G_Do6^?O_nAS@43C91kAT0A@Ueb!CBM3v3 z%XeFe{Q%IyM+4Mo|2g!1F8&V}%K`u)B?F*<9t>0(aOEfmGS;PB_fCPyoCm0wW`GEg z@qX3NAS&lHCvBZMWC8*rzT{zK{uJd-(9>T4gg2s!DPgvDRSql{-9=9GpTi$)y8)I* zUlLxd;#3~T059lie-{~VdWm6k`0BJ0xNSx@nfOO=u`><gi4pKzyrgk7E&(xGU}V?y z(4kZi5#U=9WWQGzqJOwpC}6Y;h=%tF?-q$41n5{@$Xb|^1pvb$qC`Z0E1G_&wGg0O zravZ*qoNmLVzsvuL}I*HR13?!@mxT}fq=ewJZ7@?zjTPM4~6?d5B!MV1)!`?LQ`7Z zKne5?D7CVH3|euTmQb@_aq}kV6oAxofl>vavV?6ck@0d7fPer~QvXOhdqfYi??oR< zi#Z*Wc9+I{PAeb%nI{_)+f7gJSuBGuRobA@(t7NJH>-}f-RO9kn+5=L2=sc(hSQ;C zr(DYb3Xv;fy?WfRaR)Rlz92m$LF+=no1nXrT<~IQ!>>l^HBY?6ujXbB^^58X(b1uc zs8|RE8$uv*QPNVkrIS)ZC$Fbt0F(jL=6k4^mVB`{`YxFpreE9Ommr;sJ|nt#N4Z)$ zsZJNfw2$Ad3TBRaH=lfk{|;h*d*d&G*Mbf<!#tynvB1!!8(7<fG%@B6`DRQl)K6(F z>?4YKSYWXNrp~I5LyzmCPy0f?A_SY<1ZzMYhEQBfD1h1&-WmCm+6H!l9u(*rE!oEc zCzHwzry%(hZjWRbmU`LvBVMZ?-3$OF6yo!9_Yj@61wX+G%r#;zJ8%(<#?+qN0rBI~ zzeD(0()C-x%}>v#!-krlFIEVYJ5H|E-fn2az2@F|MkZdO76W|tj#v1RHk^}RRL+ai zH~>hdHDyAmSOzMB(!^M-KSgT_6-&yJ2<ge#z@^AaHz*N^hfNZna?!uH$B({9{mUqA z>cwbzb4fRE+$?7PK0usZ#J#CHKVEyIsU~KE3pPobmb9FvkUQ}58!#E{AiBe}v_o2| z1lE~iKYOprIpMS`?vpo^d7tR}`0mbgcP1#rcF~!S_t_I<f{82dZ3%P;0MC=4XaI-- z+T2N3szUz*L=Tg6A@`38dN1ORaj*zmbRAXV-i(rtpo@7izxWrbXw3F`{LqK)?*N|j z3Kz8ixm72n#?+mYj9&fj#p+k1fAem2gx>Or!~db(MJyHPPc)AkNOnm4YkK^H%Q)|v zD&i#gRfHFbTVM@&PX+i&QVBrI0r;py{zK^{q_bNSycgv9foB0g{>-`qig9Hm41BT> zKACXrd>=r?x(e|V^cH|e+`iB&y#<rwjh`YDcgNpaUM+?%#Yne3-Z9X<F|6`?A9k}V z(L4UhTxQkK`dUd#=Q|_g1G%BBuU2~Ln&-r0fR8UF_YMp^{%8Q1xk0oOwVqfkJp_{& zEI3c=cf5=&>96--gl<OzpZ)q#nF2r0wi95|L)zT}EHFqW&N476)u|VKA4+=`zq|h+ zd#xW$zs$VOCwjX=J3c-o_1^=;g74yUWtr#Z>G<fddsc=IP}b1U&-Rn|Z*>1;AUF24 zVoUVF_~(2!vg7n>-?JTAx6v}s^<Lw?)6jo+2~TiEiQ<Pbi_h5rAi-;%W}r^frE7LT zhZj-jMaZ^sVnwe4c0-JN$AwFeD<6!rZnx+C;pYwZVV~;~Os%0Hqvx2UkrPgr{q@oP zH}90W6E|CyHKA|)aH)!a#c~TyAS^)HzbhEq2~)U6^sPHrjY@kkKogxXK^jNc5_yZM z?9zmWmteR#uA5A3k#t%pLU_XqcmwKq_<s&qBz&oL^fe+x3~v=hEih`m*VNBoWk7BT zI*I``Sqvh|aZOg^@PIn|)I0FbH*t!!2}RgbR-+~>72b6O9{QHZwWFZp&c|1&vAW%E zk4N4ah?DOp#iq987`!dup2Mh)Xl){VD6Ven!(`Ut^*iVQ7dL~uv=)XszxZ6b9OVmu zM+~909Z<3u!SzG!B0qYar9gfGWx7EIHN>4(j{pH9&GM~B+lXa9{)70DtdHa%G-!G7 zX<hpT3;pMkj`F)5BNJreC>=e;C~;l5zbroI?fUBU9HyW5fONUc)Bn{ISKO07g-soI zPOCouLzxLQh6GN+SBr(sZFSTq6OP;Q=V<?F9iB4qfId8~hp+wlFO7@bC2^HeK%;ZS zkO}!J?@VwA9mp71mLMkep-~a;?S@LYEuNwaRf=!A*F*1rzlW8-_X|#bH8JXD#kO*X zzI>YD)xAG3SofR34d|GE#>Y*~mUla4xE+4#xbgiDLrBG(xcdp7^BY{IO}yfMfJGpu zc*Id|0uP8D;o&clh!S_&A2;ZT{~J3j++E@qq*NO|fVMx8Um^ff=FmZ2<SpkUSOf+q zISPK7d&w_frg!Tdnt%HOdR~uqeba)x0@=S<EZF@d>v!XS{m=IA9GS?x%~R&ZRYjUq z-|6*!74SNKnS>5N-ynWI^MQOzz5Uf5SK{wp{OB4P8s*m^k_N`BA`9mbmPDX^;kgJ8 z9O5CRrNB>^+s>DfF%&RB0Phh+?b-fiS3ukkLFCn5Y%Cr~So|X08LfU<@(H+AeysEo zuABM^w0%;96PXg19zTZm@0>jQyYL(L?ViVPM%>D*TL*=NPk|o9@v4?xx*svN!fk2j zH|JU`3}yiGH|eDqArJd|7c}mKZ4!6qd@da_f^<G3LU>I&JE2r)AWMXDWkl>(R9K^a zM{L2H`$oY#8G!)6B7?Fmc_TDThXJlYl&-HVdL>?Y#ji^W{e)8|T$^}x>cX9_`p7ex zkm6?OZD~TdYeqoAjUXeI?Av+Fn(cFXY}9ZLl)V{x1)#%=ss||<hyTN0<0V%}%x`qb zk9NrR>1y&$$c6|gVr$~9A)w)jD!@eGRUL|`lXfY1B0)=-Myd<C2LA9e?;;rjgUdr2 zEn$ak{gL-hN{j1wWa_tOPgX3||8D5(Hti+_iG%(!_M}SPr5f5+_O^#<)6w-LGoT0< z)pX_Sc7-nEBG>!!b$6daUMY76-8S4k5ww3E&T~J~dFU5AX)C9fL`qJ?yie17K~o2! zrDoKHPbO(y$@t51IL4qdP>&15p-H)TmMzZX;6bWyb2w_!OH+suIEzr)`qGqqUMQgF zbi5HGKG9VJtO*ajbZqgnJ_Hn8h4Cd-<pjWZNgDX1_lz~TF0kZ9U3kbe{LY-g+$J?( z0kJh!9nSN(vIAHEM70q4sx|yOpci$O2F;{=di&pnJ$wsRw!U?GD$l*qSr5N;p2j2{ z2Pi4`-5kOym5))R(RC+qB~IEcm?^!xlNe^uj*|z%ICoibC4;2PmGh~js8H9F<@Mk- zSYAS*#ZqN`L5Ze%FPIl3Nrzd6T+WU2?Y9tuC6&BSpY?8MGk-Xrb_KvFR=xF0gKCJ< zCC<Q{{ihCU{CU#!Ma=};cw!^l-}X@rb9fP!X*B^b+?biOc6equH=pEhEJY~_FHw$I zb1tG>mI02xFRyeiNYS4yJ;rODtDM@fqmMsEml@V6@!BwNAJ8<9to01L9@5H;DLJvL zUS+qlS(xN#z`La3h?Zq;v&RE&KyV{3+(Fa%u|?I4*Pgbo+>CnTe=r92hp1=W;Q8gF zy=oU$G@Y@4rMj?ywaDuy!sO-y(?flSU@k!OG{KWu`gqX<h)Xk4_u$>Exg5$i-1Mk( zOys()JF+%q{ngMNv)y}V1Jdt~i=-Hu7Y`#y>k`c;gNM}DUrD*c)<cJ6|KwTCLaU<u zFd}JS#|*ypYqd1)0eB6|$b;@U4Th(l3O>kAL7)M%ypvA}KU#!)iDY>byEPd%lM%(c zexS<n={KB>Cgl?qo4{Lq?55A%$$G^p;uHsj>n4sTVvEzhOPw(ViFmuLH_Sj-?VXUO z@^kq^0NJrDo>XpMZuUn5Bw7KQ&RHcx8LZ8%N}Z+}z;l<(;GvCeT%IQgOGa;QXU7tE zG*Y{BEEiVnQkdcVE6L2bz7w|0UG8SZ-FVlgt?cKIkKHAnGYSs-!|~do9yVj)Ihjna z7>r|<O4F1V0@}ETGX?22-616*!|RyALzP+yl{Lo>9eZuy9BJ_SoifAx>(A@ZuERQx zv|ZaN%<8m_zturC%v4c`OixG*-S7M?KXv?dz=fyd?46I^bC~p;HPVzw((|;-s-L~C z`%s-@8feG$<B4c~#WLDYa%&F`;?=D>iIFt>D{N7y(hcb&b0C5-j1N)CBXP(j0gXE9 zSm3L3!TM#g>ah;pNU|vrNEgGmN0mcAc7TW4sZhBLJ^0wfb1AGzsv~IzI%t_Q18%ux z3-GLvTkM#imlGhGQbhPtPk?zjffg>xdg}5-VqVVWo?U92d?#t4rVd?(EY<pzk^n7F zqKqng{dYa#Hd2l7Z4y#P^YODU1TVvkmEBhRw1gW~&N&)LF^t(jkLnbZYVV&WgNPk3 z889Dkk=F{5B<9sxv|6oKjuFod<lA<AQ?*zn0PSl4U;vNh?yE%PK3ZRXv~9Se-teZG zFg-mDoa*WtI35mA((zk@xWk>Wg2p7JRfk>BscItdQm@~I|GfBP{9s8>$u6}X(}z1U zs|w$bdmX_IC!0Y*moB>X*cJ$g0R*{&#|$}>ph*vMUC<@=SXa}sKxCbni+)<*rC6yg z43HuzW4lV;((YLETY}hd<=&KK-vR}Tx^2dNyRBPftlt$oEB<P6*xr-7>E_p&00f!@ zB*qL95DUqE&-QD*UEMxEE4}qqlYYn7q}|oyLnOnnJ?jfvwOd=<d=sdZ4&R4OSrn}( z)vW_kp8|9MpCGwWX_mrw2S~US5uLcnc`de?X2`VaB6(PGNEZ2e&Q}IW#nmWlSapuG zGCTFIh3oQzX#H;9#ci-!WU%a6^+O<H7pf1Vk2vP%Dg_)1QRf)zmD_&ib<zh#Z~&>U zox0A!H)neIUpf`ejOpByfncb@awR;9o?u4DQ(6ZCIKy?px@aO4-v9u4Kp_%dqo;7f zoBMOX>qytvL!=9ihTD2rDpkX~)MdVAYJ9ejStS|iqtCud<^_fKx9pdQTk;57v^Mqa zAAOV(2)XwJsyb?cTT45$Ch8Dj9*rLS($o^iqJEOWR_8OhE@0o}Bom049$iKmwMKOs zD<c5Z?+D^zU~Rk51fk=zmYaO_T_-{2P@&pq@P;|O6M3q7x_?F3#iWfiqCKx|+f|_O zRCdWud(ug*`FZBC@Y(;+2G2a$jdor@ojR`vaVyxdjm0k{Rf*tw{jyWg7hkpR*;~}a zyIDu&E4VXWD$&F)ZQ-hI@5S1(nUy$bA0WQ%811aG`YrAK+4@NKBJ0q?2}K+ITEdsR z-La))&d%^+(tLMiMDzG8A$xY8$M`qy`|{v&v!i9?a+Cp#qpzU-&|tZxr>3Zc8(TVG z#P&pUJ{dk`2DgxW=RVmytebkH?LfpI6E;<|p^obHnTS>G>N^k10ssxwK$5q@KcML2 zu2XJ$9cBe2CveRG#>0Q9Il4XTUAz58hXI*D=$!N1Cu(6~*!kam`<M^!9`}AWy}|3o zKEp@&3VDagN9!F;XQix}!OVg8nKQQgrmTSQZ}$*r$hHwuO_>eIoJ``a%MhFa+&?}# zzva+g_8c*GbI-wlN?=Xa9dsMOjAU^4Wc{_f`jsMQP0kLFZ5Q!gZxd=HN3Q%R@H|y^ z6>nDcc!qauru_DUn=ZV4A8a+;i6>}TH5H*dY<Fp7#?B;ozlURwr<q%wbeP>Ip)8o> z<>HgQn?7Rn&FxkKFEwj8Kmh14f;IJFw$zX^c-^Ew@?Y#{v?E`nH`sj^*ZQnuFCdEB z#XGuD{+u;CwfeJfCb5AELAyVURXKX@DTTS5>IqQ``m7GHO>*eOU1powCztGS-}3#t zF47d*Wr-HX@@fvQv?I>zBgfqhR+A%VWsa)<<3nBPsz3!wU}J8Z94-rghKwckwd%3; z%&l@|Z6t;wCH7Cg#-zR>lP>tOKKYTUa&vH2g36XSrp2Mwbhe0%!Qx+NY=Zo-^MH0` zFo^%C#S*1rw^S7{9xw%}&Pt^$jukQ%J}<>ktzivhG^~cO3^#$>t7VtXIa{ukZvJTS zTY~7^u@P9*ZKEhYVk-X*DNJdzx@TweYrGLGMcy4o2JqnjEs>6f*y5Tn+jxpa85V2z zhA<x%Yfg-DLtdqcHO&4{D<XVup0@;Z%aI8b<t+!%alF<G8lWo|g<_j^Q`arFtea2Y z@FZhHu*5Yqt_;jdM>PB=k+{?K6`8X)mW8z{-O@JPoFzuylT}zs8|$aDw4O5DvW3+g zn&&4>ePs&9`P#;rw+|PgM)`<1XZdaZoyjZqfPj3vtBT3t=aTsGJgq&U@<Bzp!{Vz! z{Pfr2s_FGt<zK0uqV$xEAde}b&qPqDdTICawy=xT+NSdCs##%^%+>oELKtIpuU^`i z1Dj?!LS;I{+<u|y$mFpu#u1G@Stl&FA3T$j9(N5ncLmYFxl7UbYTC0_A|WJAa8E35 z6H(F>OF30VxmTgo;W?F}B9s@9eT-dHEl6${Q##*O&JIqg`<i)DDLKAHfjPcDpZnlK zB;ltmcuYyAIk!D<$QIx_-t*(Eq94w~;C;C!`E4Y(38!D{>%L;HP&%8~T<pf90u6tP zHOZ10)f7)}NRF}N^$0IaAro%ybljrt7}r(oj;C5~bpG1he*J!jr`Gz$^jqldMLroL zNyrVJO<!y|z<lO_QkvT8Hp&!1n2*}XmMsk6So^5d9o@bVXR{gXVEUBQZm2scb?MR; z*xy)|d2r6>xMHJno@;!uVQ`WmouxmmY3K8JVG4Fg;5aFRSUVs>P3EG!L#;+B$X+@U z`l$L5Fi@D6H?1YaM;6Tlrw5It^qxnCUrQ}sfm+I|POL~yo0t+MnE-f$i6q!GzO(4t zwqwD_{{oQCJ{jS9s%%;ca#GXMr<cuRU6IRSid#3;$O_|Z05N;(+`8X8c;_Xvw6a=< zG^k#q8D|5EkvBD?_SQ3tw2_AE_UaXW>DS4iriADX^_~IaXjLAon5ObH#bjjgSjygD z8I}ls*vF#wSIeHpnuWTZ&qPDY<0VQH$Q-D>-h5*OLrc<F8VQjNC_?`7FH4T8`ZR_x z(aU6>zsGWBS^8}6;6Ki6YxZb&Ws;b7Lz>%ziEB0%?B(i)6DFXwe*c22bam_XM{_V? zsiNZocsa0ha#h816DNSW2cW{)H5LgXq@%WEm|i_G)Pv>24i}=lG27T;dn$LE<v#fq zvTP8kpgtH`<)hwX044;d+^a^MQLb(hp{NYpWQ{(P&NN%J9WcmgAKvoBiqj5U4=J|M zC4)Ua)L2uMXdz-V015N3R(;GL>7-3VSYxVSVH2mJ^xCSYF{@pAtI}>J1sN1m6}yrf zH9>IUvUe_SoSn7@NNkm3a!eqFDTapw0BsQg2w$*CsR>4@X9K}rpUg?QR>j@m^lx30 zI~9*+>pqR(0+nT?&Lq39bgX4W6;v#ke2C;6umTNR*O9YaHQ_k@@uq`%d-s@f%y=-H z>Ma!EGZfQ=$tYQxEmgI;=RIs^9lRlXkR8Ii8a1J~SCkSvTX~q%$s|dfRR~9E!+51k zj~$@9dCI!9thyo@oF?aPQR-dj*?i`<r+x)l>d8m;-3ao@m@rl53Q?#9O{w+luVmrD z4oz5uGE)y$coDnGV^wdUuqnmrJA7kInZA#ukEvWYe<y3V$Yh#<WC82IgdL0f@R9oc zBuCJOC+`5*vgjxv2Ia_8OXei)^O0r7pb|iC3{UmhA&xKas!e20O|BV>EB$>59*bZE za*;DiX|a&!TBtd~@lJ~WD<o{X{6W6l%4o_V;l)>BR(ZmdAd&6H9=PGH>n#^w1;bd2 zEhPQSbvJr4T<%m?QdnPPtuL(9R;>CIzuRv(>|+BR&}1JpXw$s59&R!_uG`3lBr+Nj zXE!-H9arOvV3_a}=jSdZIJ>d<xy+ViPcb5d;+L@1mnncfB5`&BKnN)%QZF@ulARbV zlUbbVD{N)*>vl5OPtI!IwL%8WrpJk#Q%`1HA{U;7X-|fmpQIhsNig`8cQ89)D@%}3 zqz$?TIk7}JwQN}5#Zs#=*3|}V$i>o2<06B(($SBW))Ld500vN*TEQC(0LCGKpDAT> zjm1GFh)~g?h_gT~7JW}$B{vSx4lv~0F2+9#esQKnx2ifVH@GMzO-8;)#+(G2lTb6H z)OwNaUUO=)7=DAE*O{3{n*>KWdu(pNC)1$MeF}ZuK7hdMr{FNV#cJVNUeUXQ?6Ia) z?)H((bp|zM-lvFTK{`z8UMc+R#aZdABO9L>fjg-rCL<{xyyZ!E|M16wUeaI5*sq;{ zbX7*$e!3N_*Iv?cGl7O^m>sEOV8&-LzBR}VE=~o&jgx*U6&=YmFk4?6SNV>@<RASA zX?>XFyxmbis~HHQxCZHIr9^@M71b{Wm((;>>l$-xK<mx)Yl(&?OO2^(r;Wh&8xD3f zn{Ra1l6j6>cY`$y&;l4*&ah+vrmY7a<fcxvz&--ljRUD*>r*y>r;-r|oRO_zPYHEb z<!`>PH@8R;B+n`#54XJbp2I*>$OYwOrvwZOM8tAWFgb7@Oxv9@`l;Cc5HHnJlzfuE z=eK(=!a~ftX`Rx-vYv%~zuxdCq{JRznE~v-eYMFCdQ4W$ay0fntWFk{s<az%{2K#V z08Ce6;jONgsE0{#K*a})=u6(~QreB)6&ckc(@G#1?hjpYq>554Y6FsmkC=L`{v`PY zIjc`;N_INyG7jRsEI3X>7oPy=0^b=HRCBHx{sWh^HsFffO*`tYcXc3z5;)F2N<qFY zF8Mk8lqF)>E;7yZ+*JEDU?K0A{LglDp}%crK&ah$F)^-1nr%Tep1ol;l%d<tB1r;L zK8j38nyDwPQZ1DWWB5Mmk!iJVRxmw5DfT^^Eh(wQjR}6kT$~;0@vaIZH|KyUH`y)V zw%?>GW6bPt=Z|SwV;p1{cq^WR@=}7wD8ZNv#sT^XVSinTsi%|7Rh?XTrZ%)1=v03{ z&|2M&W>;y@#oBHTm&U`5o$K96`AI-cWv$#_3((&V+{nj~f|F#G=H$qn!su|q*%yn# zksx8}?!}Hn!Lq%<DJKOw&aX1--rZd*(3736xwX@Q6GCH$#}6TNIcl9Uhn?$5-_8AG z@Bxfwuh=2QD>4TlluSClny2uAcO2j&<z<;<6=b4NLF@^7Dk0{F5SB{U->KlPY(2d< z%=&^s&eev7^%>g%bA+J}El0(WBf%zBv#rDi9Ted{Q_jj(&br_Qbq-Sn09=&VPYgIa z89En?>*Pk}siAq8(eR|k0D9m-4gD++9^wY3=xVhGJy14vg*%{xm=y18yq5h0C{Jlk z3yJ9rba2zSIuMpjX+8-Z0HmvBX0?nt_H-6@xKw3F;LRwW*S!OKYHf0+QY@~N^tDR< zcP3VzU6Bbs&4fbMMx@s$v&xp6h&JPh<35mokz^yhx>q^bbQWh{Bk<#0oI06uK2UdW zoBccWi#II6Y+BXFkn|xRY<L{~fp2+;F{rLgh@%tO3CNSxsJGWs<H37!I^ZLQl#)-{ zE+fvCwr7$jd~w!zGk7H0v}X5tn>(tN7gp8*q~x8mGEygr?Tj!o|EKe32D3Uz20Y&H z$}$Tk?$hG1Ou_ItyTifA3+Z#T^5jstSex&wEmoX!c0LOhrEZS*<v#YMjB)EZs+Tzz z|8qH$a^rrcx>2jYx=#yx!3>P!W1dNhD~u#10W*$*v~^9{Wv`JM#aS)hOWyR*Rf}U( z?m%9-kr}wK#!%DwUu2zoJkx(1@4vH+%{H64-#5(tGPgo#o4H>il55Q+x2TZ{m4>-S z=6*?<OF|M#A=QlBLL(JYAr(?Tq*5to=bXpmJkEKX|GwXUzI#0O{p0)oyx;HF^I88b zEzkk;h;{t$Ou@H%h)1yk_RLKY8c34!-P*0>SDJwj5^e65-WEiLljYU2Fn^q*3#T!A zm++tBnMbCDo(Oei!NN{>WG0e&yX8c#Ocm!3rAJYBkUm9)8rK$*2RuNq3#I9xvKt}* zg?Z-;A!Gmvl<EPiQxm6z@K2bsKjT64Ay=+-JTNbl#S(GI1=?}QIxPOdIsLH7=EjMm zl)V>$(=mmyX!bsTU;$Ll%e0l$!HfX4`8A4`aG?MQ;1q1d%!>kH1WB)rnPZqxx#JR? zJ<QjWB3Ck66@laM=K}E`*K`=iczifn=WW?{kBnA8u$^|f`@4yCSgUjCEQ$K^%O)*^ zOjh}$h!gzh@K!!x@Ud_4Q+>KO)$}4n8bLHsl_%K;)xYL9U|H@=ip-PYJ9fwL%s}j{ zb@=Vh`6XjJ{8Z2~nri{Sc(!guwHhh27yGijjHm^e`x}QoO@ss1?$^GVJWa>Q0LOsQ zZpU~j-6Z~M`u8*@OAY|OW?*RNd)pEEwK`(#z`rYCKqCc|&LU2EZ;wX6qSG<@(1>qX z6Rl%nUS4uqD)00j;)?RDHgQwg8gM-M$#K3P%FcG~g}Vg)3?_x;p#}nAKm@QU2qdlH zL!5L#Ecm{Ut>5xu4=HA_oVh3&d5X&4`YWv67a$JPmIUx9h(PL#tG21(MOlvP5AWyt z0LukD<I^<~HEEKO{YPmJqNI<K-+1<+7y?*t)J51Y_3@-!FCTBlp3{Yrd&k|ZF(!4Y zDiJ|p?srOT@h@K$+s;}nA2Aw>e=?T}gj~m>WCO(IuDClKk^?NUGsheVzmhTTd=x^n zZ32u^?`YuC<X;3B3y}2vjSGbG&uuUGDLOhDM-?2Usi)fN7V!jtbDqZvtzl_4lE6%7 z#-&W?Mlz3hL2c>fRfqsFTMsyR>Xl0Knl-yd-}0MGa>2_fms+;JVR>K1MyW$4;AV8d z5JKt8H3dR9zdDTrnU|Vk_keL4yR$=|-!?z*dEj8EpaOwXvKnGk6fEDhg+|Fq1W_@{ z&<8^HF)+;#dYb)Vgaoh?e7WeEm*xja*e@oF8l#ab)XA6%Y*v^TaO1+9u8xUQRwJny zS0biM@(As-&R%<z)TjvHcjw;H;0vM1r@eE?CP|<p9OnJRXd;%_4|P03qr8ZMN%jA6 zc}rW2)a=eNP1oCAs!CG38`JaL!v6Mo_}{;i&3fa^0$a&9ohK+=pyN7iC;Ia-_$ala zG|ixO3IX_t3o~&sl>q~4;W*<jj<CNib+%{9m_qrZYW>Zfa++Nk7vF={zc#})zXf^? z>pVwk*Kg%IFkeFyYmV)H(lyQV`(8QdVg&2UeC!z^0w4B&e<b#@2T36ISq(xXj*LDL z;;K`@^B(YAEPf@bMy3DGehaYS<=<Vzwb~0Mfz~u#7G46b$vy3#s<P0b>tnm1=mJ}S z?js5S{y{dv<$D_!%g}%x{IV>tU}CY;f_S6pKuOAADGK~2a$>qds)xgrR)&Zj0dZ7# z-)ur!Z{V7FFkKQkFJtN$e}5Eq3evxS{8*~E_>#Yi>x90=WQdHA97KDyjSXp9qKQ*7 z^~QTq7F7a3MMc&kcC*@rpsJ*ls8B_UL52*aiU$Bpx%G8H+bs~@xPgp11!0hJxlTv7 zCnhG-basIy5ITeIf(Lr9yR$&Rk50Q1ruX%uFX}Pp8VF)1yB^R$xV?9NjVpGV3RK8j zpMg!hX6u}?8pkmYgjWmc=`G*h#ncA}uQ(rtFbh27Th#DZ&;Uym!6o$_e8Uj0Oz$=9 zw{McIeNZ^R7F_tCBa&(`8~S)@Ng+3iqH?|y`~|zIJr6?QT~mTw3^!_*{st#-E8+Wg z7OokO_V2AJa-|Sw3As^s)%HxgQp~9uz?`<#W}xfd*ObDJxldR07X$<UohgNnK}hkH zG;@$@=@7uSre24?|Ch=lPt{gQY^nRN7vDyPI?Ji6zIfEXsOV^q1!`Cs7E9`IIl?X# z6$s&AjANhXiad>4p=2tYn327G%Q!57)^G1h7W8l%u2qWmqR5id7l0KJ25H6K_l`4v znx1Yv-0O5Ed8~z**?fFv;6gvUGte|uZyUt1-p*tN_zM*7NfxJU$8farxdx>}Hg#)_ z1$Ju!_w?b2y<2ILf4Vl}WUYq|4NRIpB7}(L>lB>u56-v+!olGn3YMSJ*1v0v?^x5u zJz_dDxACSK4XM!pL+p%viP{?BKM@(Ss)3I_`qoCOlBeTDg}oPn;4Ml~o@sJ4H`IL+ zoxW1Jkt5_&PsYf-krCh9{fHNAu!0*%!g>|P$ZyK$ve5X8j>3tIAgSGyD0xeBDtaL_ zO7Wp-u>Qwh&EoU+R?aq=7JI7QUQI9Cx;KvKI%ToMG(gxh#1V0|f}?>BXH=bc6cjrV zS1BRY=-MH!dBM-OKYqt1^lk-Gdf2xJjpBRtHQ{&;FYW7Wo$&H3RPN1-oamuiu{oMk z05*2O;wC|Noh-f|CB?RV5v0VZ$JP8QU$}TWQ+hsgAP{@OE^f0=R!EG`LGCac(Tuz$ z6kJ)iGJ!NL|8Zw(T^HEwC~?m^W)(`-2FwSDUQq(bRqh)bRlYTjl#IxczGm2mXt8c( zYD|#rFN(#A>QARC;BAhaONKLaRG8@db&EgB?iTosw>#Nt?kY#E@hWx=le=FzXA*mY z?j$VV>NJ`d%zc7CStDpW^wvA>{c2<WaYpb_c+pvkq{{2#(gg=oRz|f1Eyeo6rw?q= z%J%FS=LkRes=bN3>A19z*~-K3v3d!%NxGLYGbIc}w^mV)m#V5Rkj>*^m)GN|mS_C4 zo|?d|(dUK=e1C_=k9fkx9h$HW0B}cthP&*qiZp*cc;!q5B0#5qDh!xY!!o@EpsMua zjQ4L}a#oy?Hq!Py1TfzzNTJ`HWiIbCTmm>pw&O3~u)d)CWva|b<du2r=h|xcr|~cJ zzeYtgG9iiwJJIbjdID6_Vm+C8vEbFQEBd$J0jB8jU3Eunk#N20RCTuFS5l@LJ0cqB z>`iDXzaJ{ESXF<$&1$Q$;9Po(yI4|ipq8naL)?(;tL?u@ddZPY981x}24<>r`^S>A z_0S96Pp9qh>OdV8xeMDlE0+;jn@l&t*@O93h7*GOrd<y|YZk^8IY5+KIf6EBSp|X< z`R}3*eDn9P4k=0Qsj$29aE)Vwxt@FgNcme{^ml?85KX<9ocvRR;t^q;*7MY&NAVQj z-{IM3%HbZ0v-LI3?7`a}p$hIF4frs6<R*c+cS~+|#c$5Q5i0XeW;kue2W$>-HYb>M zIb5mlPv-Ec=@L|CCwI^GFecRPZ4cFO)KPP5H+T4p@6q^Vv9e1Shb1WT+=35e#eUEM z3<8t_!mrJk8($eCP>bdvGMM@I9}3PMg14WCw`llz52X@9Y{G{6QkSg_n~NK&q3JmS zdUWr=HLzwlw-+|UXy`YbnkT4^YTUJXLI=YINGLTWAinP*`6zAZwINWW#|Ebpm?qT4 z$7IJ|19an-=bl!NAB|L_WfZ}?kisretV@1PEp=q~+e~xHd5~`B7t{nryY1d!_k6ke zqWz|?rJJZBJHC>T*Rr$yItrKWX<W%Y@1SFvZKaXwXFR3Pa#Rn0A2!z4GnM*bxx|Hj z)ugEJnZqHIB4r>4jQgjE`^q)--o0GsoNhj3V=+0O#|l=GIp|f6bIG(8j0RiMD7r<~ zIz%CFD9iS4&>}IXk|qz>L%#O(E5K&xMI=lEQw#^C+P{?BlK<35R;J-42*F1?9dPz` z&*u&uT|Ru&U4_!0Vzt9HiO$r^;aar1)7xYz@~O&Wer88fw5R$^-FQw@V&{?94h?yJ z=u`oy;JQPL4>wXxAEGZ#^=Z;luAlBR-Kiqfys?@qbCh?aOlA1{t8C2l^F1&`i#|@s z%L7f210!~y>6wns))yFa&dj;)GC4{^uC3{lQk~)d)|s+&cs{F0+8za%IvKXV(#>(O z$3aTPDNp|j7HEidQg`2%+CRZ{!h!f+6I+<ka;`?5jUkJoKlJP{LqY=y_O}<gXe>Zj z<3hTiH0eWRRqEr@R|#MHm|1V$_$X6wpR9`BRI84@wn_b<Imq;<sIkCxUs9d_&O2k6 z*1iH66Ma7xj!=mGjEMeGi=jRK0@BD7MOOW-x$(Hse&d7#60H6<4S3RrbYh7b04q16 zWd$m{{Dz|{K?HEyvW_o$-EhOsrq#Cny)SvLQfrif=}`>}DZoBOWwbwG=!v|pwbueS zbi3YmNkD@~L2=*D;2{|iDOScK#Pye+FTwt**FK!SIupS}3Xt|YAKQHM+Bv7pmQA2E z5G-ti0-JXgDB;3^#Ej{H6ymaV%tTrbNtF`k{ANDH5SDr+Q!U<^%A=zsiaCG&zH)C~ zu<!3JSgUYaA}gC_JHBM9H&4DFF4emQ!4owcrVC_^-&Yxm0r9ya@T<i0_J3i0Vat6P zbnvOJC*FX)b*|W6@ye)NE^0th2bp3e&ouE)B_x6msr4TUIkZ<kCs$3Kb>`{^1MY%9 zxWN`2JI++wR-rH&YS`~Dm#|%otw~%3V~lN4D9@=VjPX}McZafPI_F$c<6xJAlsqM` z(xrT|pIR>NU^>iVg2duMN*c+gfez>X_U+#WyHY>KFM~=g6wC4t+bpbH69{&&cc*yo zrtHKik$YU_dm{>(Bn@)<yhDnW#+WyL$i*ptG7b^oYl39+!Rdb+9N7VzHhsNiPwEr3 zSdXZ2dw9$A%T{MrBXvi7d@t|eP@3tsmfzJh8%F-J?D#sjfGAkhtb<f1yk#j<i;&f| z5=2=BIs{0L|B~hA7+uIO;>^?{l3(TGL40TOu`#A(y4?dsCxtb#f~TF88-?HFA&d$K z#&O|L|J49mK_tZAlaR)AMIA(#&%K`6kOOuU>qJv$)F87H{WlW9vkDMOW#8Ob^wFqP zQ^<gfWvaUGhq}>JMu@ICh&1zET>c?dUBlJof^B3FH?e(qEc=K}=+l?tyP$H0U)e*d z-85MRM#1C&6+=Kp4o7+iJO*91i<Sx9{N%LLE4Su*vU0}0XzXR(6M_ZPYHh~C&6@w$ zsD^v1mkGFSK<nZL64t?o>S=F;bq)z!%e7SpDkp+4)-6HJeXdWewxeCBpNvULz*L{v z5WC4XHR_NnG*IE9KXSulWVoT<D7?@rK5dUOQ>DLe&v|#l9+8hC>rru1&V1e4@*=7X zPVw$#IZvTjP8fQx_z(#`4~U7AG1DYC&c?2{g@~_}YK6xk?YeFA#fR&3V)8te2mOeB z8pspp>q4CK)r_5|t$0w&Q3VTuh}SC`^eTnRkq~v~RP*z@yeH$-SJhWf2D~@R0sk0> ztP`kz#v!r3sZm!20_XFqas6Q|l|F;753*u<rn1I#28uV!F2~Q=ic$gy?D7)MMVVeX zd(nG!NA0A^A`K_t(+pAZWGr<7-JH5VQ+v1L)wx`{d}V8QVn5bkSp7qKYSTp45z5R& zs<!deQN}WxCE(A@b|i(N!3<-K82`AY{|*IFF#T24LcoyMmYRWu0O$2zgmp96y3$%$ z&A`RqS~ZB9vaM)w@K{4oj2fMCWLYk#$Ab);f&TC~x@7IsAlD72zEcGohV&kv%RI3y z4cr}=ihSB?nr7RhMCkz~<@bMI>y1}U!FiKc1$G&z@WVpd&-i7b^gwdRF_8T-7Ppi6 zgORHgk8-1CboD|B>thzis}}KTnsrYMNxnKP1xj5s1*e)}Hmj#XHKT)d*am7Co#uL4 zT)jS}U-(@O_>@J32}g_4868(ZG56f^Qytt=J{T5n-QpW$ytXW9<akmm+ltMVJPvW2 zarVW$$}ZCBHo(8TI}V(azxZ3ITsPk(KDS2%E^TU~D9)8)XNgKDqab8y{zgSv>i)Sq zj*nhl5zIK?HgP+?7a#5ve+=(fo{LbiR{cSd-azTG-ZK-9#n$-ghI~<9Ty}YEXhu7x zvko>mzq;ipynhR9x@JAA2Q!b;!U^mGKb0YxAru<R8ug>k#4E;SEqvw$SpRXqDO;@O zm&ebl|CCWM*ofzVu^>QIl%H`v5(*7q^xJgbh-DRh#5)989Z}pNE7I2mz+~^U9C7C{ z%hc8voq7P3TR5d&I{gA4N4~gmNagjs0l?TP(!o`c-(k{m0Z?EqRnM;P^@~Cf9%AgK zEPj(}7S6O}3+QY$*mArKhhEMVTbr@0lROMA*@j(M=Y}}dgulWSG(lJ+G#%p<;#OZ! zQR=qsyNg6eZe>bTgqRBiDY)T7i3)GB$U3S0`d7Xhp6Kpe@9!8tCPxwidNe_5DPluy z@_8KC5J$aJ&q}G}bnx!9+*YY<JQ-hh7{3EcRSs3`O!k1iQ5(&M$CMHMF&b1sv&pBL zY-=-%Gmmv)m5@5ucYdMI`d{Z;Yd$xgBio--ftaoJS+V*m<tBT1p*Bz1duF<>)~4F1 zKwdpu_0(cTJdJK1XtFiN*2*huC?B@eaD?K&#RS-Yp0cxI7oH!oUR@ag)R|OiRQz#f zQiPhVf>T~ysU9IgBB~YXOqPb2;g#&V)S_)3K_u1APC~RKl_AQwewiJv^YNh={85UA z4yCToBu?M8*pL8|Hywg%uW`-fnZ}i=*9yU=Q=2B^D|+%dHqX0kfyByMF^^wo*<f?F z5;9|K(*(1dYRu}>&g7~sUon<PY9dFz9}MyzD$yHyGIv3c!HgUlryfQ*9?^0wdMR+~ zi-1fg`S_@<!gli6PlxZj3@XOw8Y*z@6`vcFGo`4W^pM`xezFoNrL+5l@6#5?NBn8a zD<w#ZRDbUkk>M+`pzgQ7ed3TBQ8t-6sp_rV$4)iB1W0CESMXf|`ctX<@0w9EQx!)e zC=GqEf_=Kr4fm5yQgZIAs`X#HxzBuEw}6|nIAvW@cF&R3XKswW6cjU?BH%Y^c<<c9 z|GKn7URwgow``ZWR&lG@Kc4JvI{@FE0_L6!MTr5Gju9`D<@~9+YsD1>KB<mRj4qUF z=uY9+cB%Ave>{UMw?--IIdR8K?x|9VrJJ9G8g<Nw(p^Ipz1k2wm67eQqPZ+!%Kis^ z0WKaYQs<@Yu&qlT2JC154QuX$RatAkO})7LR6F%*<tsz>jkqYXB1Igm8}{eh@&4Br z+)$fbXh1w=3TIvvo58ehIdU>K#o9X#IgPs0zvyKtd7*LiLpn~{B;0z*Msqqhh1Uon zu|Oe0=qk%|fT|~qlXumc28jD++Tq!H5+H(SA<_9t!tPoca`>|90~W%)-m{Civ>))n zN~X+c1eThLf})I}^AiTZ15(?pAmGKdc>(13bv{!9=<{cEcYfZMetZsC1<hY)?Y?^) zSWXjtFGRZfFbQr6!aX@Y-F@-nTEKB*oe$o?XMhLgWUoEG^$Dm1BN_5t%#;a&ZJ24G z*Fk^@YQ1#g8kf5YEX{rzd(AyQU*iML5MfBVA+A{+D$~SI76T0+(>;!!+(2tks~`*Y zfuPU)y4+Q}&QjQ~jjplSQhUZV-FsB82!><ffoS7j+M4aE`+y%uGNf*^;M~ki@z{iB z_%Z#Vt^iPHDdM1#`@Pjbk-bO>!1ck}hI*L?Hd_~OUEigRFR1U%5Cei@T<{lKH$<)k zaWw_6+*HeQCJzJ4XuyBmKph`dCycy);RpGX{3OgHT<Z95vrA9<vAaR;)&8!0={Ub7 zm@XYL0?#k`S#U7=`iV{uyW#{k1;RL1Ay25T0m20t)#eK*1_VT^FSiDGwa$Q^01f?~ zeMjZG<qoS|1b7>-QvGSo8CJc5t+7^CUnYG}D%jDS;#psjJuvZKk5g85k-WP`)ggcd z0qk7A<*5aPIAzu|BU3TO9<&)@6hQT1io3ecL{@tQfoRxbXXhb8(N>!w{)i$~t@_T8 zusZ%Uwipe_i)n54F(W|?4io9&+?FQjSFd=TBNHYcfnC)vskd(&lua`Qw;R4y_0%9I zR#sE1Lsz<T<wDQgEX5{p<V6@{@mLj+{jvuear-~+#_3g?zu#7=&%tiKS5A9KtE(it zES}i6E;%Mm@E30iK>)Hd!J@#&veZ!@^*{*WK&y`+kZ>?th)~+`?S$erfF}rCIAWz% z70&^29wc$7Xf87-8Cv2k(H%k<b>lWG4FDQ@s*k%Z3RztIedm+>17W}6LqO}jvBGU} ztkBIEF|GSXK&2oslGc=<rZu!0<05sUlI&0}D(1Lev+wJ2N{+=3jm+vjhf=aeEkJCT zIWXj`p`vdwCXnm?&u6eI+fG0sI9EzRf#D~%DfIotEw2W5Ke?+~gmYiJR^z55Dja{z zM%%%|$^%{hR=s-gomomRx`1*jUhg)MAD!O){Hc=5a&abd3)Ih5%Zj~L*G_C+&@my% z9Y1&?jh4(TPFMz!zA(4F;6<S~7UGZUPx3=CK$V>S?*1w<PD&5RJPrVG!XOwlG|*f@ zRQw1POU`FqPO0}`S+2)Q<&fzLRl!-7^f2;9<&vI^bLNUpy!Ko*Gk$0Y>R4q{#LP*J zIPa6Wf2;O#TnJGcXpji<H!cef%#m7iaG1tYaEa9SvL`OtQsRvE0%f-)|1fL|o7{5~ zIH6AGKpYE;eyOXC)gnG@Yuizk)|5`T3%uHXNh2l0biSG<nm-gLAew3RrCKqyU|va6 zdI(*>Vx|}`;rl!^szp!YN7=h}9+Pdg_ARwas~AZ@84l2TgA{fEA+sY)ktFY9I*R7b zguY;@8+9ME@*C|66B}6c-jmt>Yc*2Ey+#3=Au4}8g2{`mLPlK<m$Tn1#dWd`A)A`` zWIhdN+Wo=)Y)t<9ta-S)w@b8Qf!qAb_?Nh|+UKT56ce+aAP&`BZkOKB*>$tyO<}D$ zkXohZDUw(t{``%adhI}zGldwKeWIb=;ne#9BVh<|cq%1q)pv-L6ERw3FOD9Ic`s+u zj<r>#Xz?mPn%tK;n15OP3L`FHtt`U;sYO-jOkh#m`VV%nb@3^!W2R|m>enlwV#9KS z9@8aMH%`q-V7`R1Ti1XAgBTvZvodqyL8D8Yn5HNujPllPG`pt1UiQ$Cc}q~if6j$< z$4qYG_b1vTyN}^5PH8!sie}oiaxGm9MEB+7vswT~?PQ9(SvFIoI6=@C9s?Qt5hHRO z^1@+}9z`+zkQ3c6C^I``n?fJRFb~*rfh7b>{a^_#<6L73&n@FU_rTKLBs<5^;SL<@ zmv_cX?scFJ*juRYD<&SquXL&c%wyybO^Ej&2KEJjBe-s*N?)42LeV+q1oQ{X1aQD) zWPxoF%@du3!!6d#R`wbyCu>w^xn#W08P6TByLbA(b7Q{tzmO;MKQ_ELyS|7%QU|40 zKu(wr#q8d^qgrpz5Jm1cbw?drQN#blrF9I5qUb%jy)6qiA!677os~85U#Yd!7exbR z<(fBRD}%{MZoaJsk}wGGm;1<@FLo1qWO6UY{`h^|qQvCB)L(hGmP-($>(*B_WgvR8 zqSmKbwMrG!X+iHoQE{q4a$l?+c7h6XXL-jhVsv1*EmqpzDsOxOdkDWL$gC)ij1j&` znTyT9%DyWbKP{pe6?|NzlzqYrzT#(E7Fy;veNyT|NnUHv>O1N>SeE=g$Li`73Z4}# z{mr|{svsFLXB<@{eG3-<{jShawUAb=U)DGcE=)b-iF|Is?W=(b#|s?S<2uIete<ZR z>hB^4#Vp=Gv9kJ98{FF}`+Yg*-ueDqov$iZe@Gg@HlHYZ!2plJt7X6Fw_O|+jRC-A z;dzCa%Zfy`T&E#(an0kWZ=b8H-nTcksl=nW6C!8u9n#7@Gv!V4@q<tFTU9Kzd#@Sd z&F{3wwaG;mk!sAK{GA1xXy3|)x+&o<{RakBF(>w9tM+{saqyz<186D=Pbw6Hw<mHh zK6CRco{({@fUaMSfQz^AG7Pua8J|z=B|I|-1yW_IC~<*v+Muq1{Hm>XNl}UXh-}L> zWy^DvaHW@>wlkhV2wL<;$@vYI{2^{y=7i>AXv?zVnrBy$eSe?iA(*PU)XD45uI_$K zj}kwkSc^EiEs#yQbLr6CYB=pXShHGy^UnTxUBu%<+GWr0IYPqEU@o0ol+iT*aO1gu zcvH*Qt3P+vJhix~>f+k{4BJy;l;?Am`|$k@LTdi?tn+Tcis#GiQef3L=z|dSU{-2* zveN9Q94U1yi2B4sps+&W@3*nD|CAp@Y^2daz-?H*BQKDP`*jNcb#_3~?7I5i4~l?4 z-G1qWVM1%IrfB40nB5mQSk~Gj=#8hiZ`ZC}{B-VH#~~;2_}HB5BY4@VKrh@EgUUMD zN?W;35yFo!eA)X2Q*Hd_e5`bGU>z9X&NHMxidaEa2ORk&A4H0Z55oWa3X0s74wT;x zOq}es&a94dtyc68l`RO=So=h4%EfHr4!Ere5!C0V8+w3w^d_U0mJ-N!TUk9pEnbFH zum7S@^0#!1VAT6B0~5WM$Sq_Y_A!|OvQ!+Xx&SY;S}kfNh&=!769cn6q-%i<1V>Q* zd4|SjCI{6J(UvEL|KbN_31UGD4e_AJBxNZkENQt~W3^hYhl&S=K3R?S&r|Ob*G(!^ zM1*_Gw}e8xGw*M$i+vv7ml$^G2w&2IPxXh$4+xyEgnEjnSQ0VYTB~dJH)o0J1aTNf zeBjG6(`z~~jbtEQ{M9RIf+(#c6`O3ybHJYoB9uiaPpQV%7$A08x0SJ66m|ja>M~Z- zM=)G|!8DMc(Y?~6;;vS`KS#qcbVxj@T8TrJ3aZWk0&iZ1zZO?U>IKbJi6-~V!#Xz5 z-NJxCtWSR%Zr?NNBwnmURJMg8?V7CA`9Yj>QmTEiX;t*K+8{z}qq^Q24XMU>M}ehk z%q%8wE(cdes?kxYI-F|0AZC6UFBwNx)E9oDwXQ}BA{Z*GbmNd#AEu;1Y6H56_zl(E zgYR7zrF^m@a4zy9$rqB8@gM6J9_gsyC@5*NSd6H;B1_=<L5wVjf7Twq+^+LQ2e>6D z_isUbQj{RwYbvg;(v3}So`{vU)q~<y?z)S~EqLrg4yKM85?_tE^}sDO7DNHkwe92x z^J-<0Y7G@-If-S|QLt)<0j}fVIOLSkicU)1Fw>MEWR@)6!j)iY<A2l2r=nD@3^Udk zqTV`|03Oplf;y3J6mw_1o=6J1>0Uuav3esy$#`Wb;Cb*^=6dyr4!#{Yg|(NvgaJ6D zK*MihUn%!vjrJYS`Q`gX{Wn<Q%%W6M^@V?=f7`0bYR~m#Y*oR5=0DoaDjmdbSr6X5 zV|B9G?Z^!@saI@3S=$ZYxHhDBD9C({`p>gQRA91xTV!|b4*A(g-9QbhrB2bf`oeOo zwgk6)Qb)POLAi1mKE=U=-!bDSSCHg=yYj|15s13jk;v6R49-P;??L@W70if-a{D}@ zxlObpRoczdCOPh<m3l?uAXRMvD;*d$xkfQk7JE;k$kdG8b^ljyta5%+AH)$sf=*@Q z?H}H4rcf%{v&3n==?7D!8gE}_-+?t2IvXk*se_PB!0$(QT|2T^oZz(WMN{6qr(}?d zr&=C%Q7QNoel`j(uz+~Pc9NNLRrt<|4?8Rfl3C`O5mI_ur$l|4-7M4gG^!x~arE0( z+#MwH1u*)H?<J;dEfK{}qKx+#Q80IN_ki(oCr{z0t4}+gK5X>y#SjBo;b8I7Sd_?8 zyIX*G%Q2@G;1W7~pev{2CP=$RM#}#-HXBsDK^%D8luuVjh3p4K#s?bZkaj?Ed6UW> zo6}aeZ>v7&2sk7lf3n!M;yuD*RHUh|96}cJ8O6klBXxxLy)mKnftNy3)ZTJXTTozn zUU`o5#q^NSx6{H?#R1TJK~e$|_t;ZdGR8DAxUI-bqDHjjMg0`#OaDla`x(Mc^6yOv z_ix2s(IXxYv=9Sh<^sL?r%jGQ_W<8jLp*AZ9jc)TU`1czq^sP*^6$OBJYXItPQKA` zbAW`OI;47EBI1_h;bV4kr;U*(UV4ZxqByvVQ!g-cAy&U!|Fn38`MF>!=6zpl@R>+D zFHF<{K=k9D=-ZM@R)NAjb8LNbsNaKF+);4!hF4es7uAGAe>{UTDpc#?m=DmfJIQp! zt4N8D=&ySSvVo}fB7vLtVxLP!OQ@X+_KFk>LK^FbkzWOU(!sp~ki<bu&PVikiO%7@ z$56>f`q;vAG(SAW^Va;C!&0YnLVYFpJ=S_i+Wpv*_{gKRHzB<VrT1giOM}qNQwM}B zc+rW7(){ib^Oqc9Otn+j&ojvrZqaG6Pk%-ls9_&@C0K@EC_Sstx^TbV?WKUg{|&SQ z07C%`f9Yix(03-0TG_p+|3A=9Se>!me_4U?{{roX+pj+@CH`-qol}nKsn!1tv_m+| z84iBEHdbq2s1-1BxAFN6VzT2^$Bw2KH-*%3hC=giEgNWk*$Phgntk%2>J9Nhl(eFI zQAR;mo$j{;<T$;&^(XP(?RSqE;6f9Pw3}vqAH8sO>zb1{)WNr`5@PPRe|QQB189SX zTR%NxTVE24;BmEEfR~`mA{Iqe7*=B8AUA`Hdff?s`|`s2Fjn}1C`8@+N+*4EsL+~f z5cl8mCtj`7fke8^;BAim-Ktz1`0T3#IF()E!oJCZ6m4ajgQDlY3v1>(<I2_{?y90t z(T9oHh<WJ0%n%am<PLmV;bK1h##{;#%jAYCxTr5M#l7rj$@u_VWS_8Nzcf_JzIyt+ z8lT`RpbVU<65od3=OXe$S_MKL;nypo43lF0a`P?uTt@K2&Do1!y?k;EN-eA0O(`K{ zq0r6tmlQ=$x^G<DUXt3YyXuf!m3V*jqXK39*f#eZY-$?<b)q-Eg@O-yxv5gr!pRkz zGE9MseVQvb0w^&O)kRFn$cBS(%a~`P2={d+30fZiN!W?K&4dV!NvmInWo81(;`T8| z&O%*6S&d@S+rE_D@4r6X^vd6D<;S*OMt;7fO@MI4&T1{qk{=u-QQ~3Ykvzmf*dGT$ zr}#!S_<!#63PKRwwv@ZzBgd7=H)l&g@b+FUJuiyS3c6*v{z?mlu18%W>rYD!3kwr3 zxg{Pr&n0KIx#N0k+iZd|lVRS#HF2;^<$N?u>8@=GDo=aE6E`=hdTTYbd81J5?3zL9 zhw<)>A=LvvH-<IdNwg0U?yt4eGzWEz4&mj#Z;qK>G5I!b@!8YB-Swl+7S9C~wl!g| zers#edGD94=Wceo-={neM}L3eZI{c9&=LFc{gshSOuvXN(Aqa`y91DBkKY{o@mlG+ z<&U|rUAG@I`|dtGGk503ZZz{9<EQTSyZt#2f6OR#-RgXMQeWikYo<|4{LC4!Ti5$C zr*YGFOpmW!AFlm(;n%0a)DyqwlM9dBTfTWSsrzHlr@vfX#TdaKUpnv9fzcLgt>FLm zL*D&C_enhlZw&q%|FhZidH&CT7CY;IwuTO$?D;+%hCaVJZg=tT&zWF-t8IX>KWY2p zjl6%qKLsDP`m=gp>EiF6(u*-)w?7>{xc<L@b^wwM2-$P~572IiBWO-%^n3$}e7*5l zc=ef(^e9eHcZgiJ!-iSSlSP5`Jof2zriOF1FnKZcAu5s&wDUzLx)q=*`qPzq=aJU! z*7ehv3;<9@??!|dDE??wwN+Kd7H1Zy%toeL4Ur4iMEkVv>BOsyDg$?ip6H%vyF}vy z?FRoR(9Zo*sPlW7XAJ{;+Bb3|J>{y24fiBn+f;tAYb1VVwqVBR^BBlFoREV(d2v2( zFDV2sH9TZ%zM0R;sZ*890xJ?H+#<CX5Wj{TDBstGOy@aJTZfT@6`Ms3Iv*gWI7gAF zc>y^dLnqAPsqgG&N#_(t@Q5bM^Y>;c2U$-{?Q)DO9#c{<2vjePs8(6!fO$Ff#y1?s zB7Kc2ZjZ{oAkoK8B!0UxkGx^B7Z5O;)hZkbsW-p2l^S+}Q_-9gX3?nmEHM_SXjTn_ z0Ij=>q~G7J0jLI&(Co8>>~CzCi-u(YJSER`!mYyjlexONg8clqD&fB$ErVr}kz02_ zI8>v(o#SLd`V>gx0tZZDxQ9RbcC~r5!8vR-`FzQ9FBOP`q2`Fkvgx-P<A)z@O)$yA z#xxL$)OfITWUAi0qfx7a15sNaXZxP6-(&KLP<yxg>W{6Pytd^-X{(^iiQ<h1TyFZ7 zW={!w(%|~E2<Jh^SM<<BgpbIlLdR0ZT~fZ^u1W|ESn=_y$)2x0?$YcFV(C+L0*k*x zR%z<z4s)gf)dU3xk$bWQl?A+;3{*5NZhoXoM6#BeOWH5-)VJP>1_I~|C@l{3eAo5I zy~*b0uy`6j9@U$qmERDa;U{@^_Drk1rH-%P(>bUqTi_tT!5X`H%=zxE=$6QlP-~N| zC}MTaD_k;idOg`KVj|FVTJMzK=Q$x$Ks3`E1S7e<_`LYC{tR*yU1yJ_!UTXF8@PF& z6Rn+f20W<n*^*52?r$mWK+yk-+Mk>Zd0pBv)A8agVsznpj#Tf5C+n6T4`zk5Uq0Na zj8=`5T|`_etBicwT)i{9Agl6$^D;Lgwe)yU$D=(K09_|D;QVXkpARrl)i5J^bV;u8 z{!oi*TjIH%mr&1nIABVNzUj2|+|W2P*#~^Edv?k26}9zL$Bl|tqoH1grn>^lutrC@ zb-?^}*LeJ+J5}E*Kh-IpZt^@9b4AEynIh-QN9MNW{Aph<)tMP(c?}=9edU0r*w$p3 z$TH+!)PkO$#6YqprFOq^<g*sY-F(;Y_DLfye@+0V%VQ+FFx}6-&t!qS;~lroS{^S+ z{N0_M)KLAE9DL~JY<Vl>ZhPt2TIjxWGm@Fd^lrFBqiD1eNgn6U{jo16&i#2ko=y-l zOpgqf`;%!&=WiU1eLeHw&ztqj_j^9M{FnIp&)e<spARl_d^F0t=RS&TTVG;%q!f0~ z!}fP_AKOQ!%k3=q<ZSoCT{p5ldKNHeJNu2sH*(MUzsLO-KeYcXJ>$m%H((cST2~m} z^`ZE7()V+}?1EfRy&c*4IQq0}{OtItk7M%jZ$EeOGF-Q6<Su;bzw_(XZ!P~~yWdMG zZJks4Ukw|qSIRWcCKjf-6o><y&$Qj{=|0yVZ5Q8sHgHIueKmfj<0;h(V4TZPX*zu) zBNi-%$-N)JH^gr#0MY;ln)zqBTQ14?EyTgtx_vv3en(ZJtV2-NyaL5`5>lF3UpVwO zo=5to@=6@8ZD*K>_GbtX5=am|&cQ{=bKh7cp>fT>^1EIp&0SX7o8tZ-z+xERQ|cnQ z1iXuzE}a1vm5v*Oh>5+|mIT^I_pOsB|IDXa-A&t@)U<EE0y;Bf9X~<X1!@olhY##m zZH2<W+T2X|V(0tAt=-}mSwMiANqtRl*oE|<-!49Q+;>f#@b)ZZ_y(w*0#aBPP1qa% z!tTO~5U^8f<i$D~l7D(vhymJGH7PzDE`%LAn55ZuQ52?da0%{+54{kWEagp83CDj{ z$7-_hN)t-zONd|=c(0qJR%gn>ixjuX<OdMo8h|wpCm$sWCbgwnbTSX*CttQ>%3$IT zu+IN33<-3Hh)t>99%NcBr;2T!T_`<o7>`B62p%*eiOrLKLuvCL(!@4X0LIycu!Ko< zENWY{B;&%hj`XPM45z@voSzAZ>6FJmFSx?Ihx#*;U|uDkQt$5CiRGD!z1@4XJ>#4r zklrX2zwqJWrR~Efys`NjV%25X^&9bXdry3}1HJe1ntzdWRr*M()TQym*!dgSc8yC$ zG5qUG+IXiVsf<U`M`HW4Zg)Dn)mfh&Jnf#6aP2!f+&kx}iM1s$66YSNM9tL=%&qYf zo6XGC#M`~e^jYk*dDWSlWrSS_$G)*ozE_jUGj*Q~KaCU3+p^Eob<f)fj~(fxZin;9 zNqN;aIsXkgLp;Smbs+*vNdji9%A!2ui9Dbj`#n5X@nhZ&-v+qCx|yDboXJ=Gm5-At zP&O-2^(jzGD9|V`(CRACnJLiwRX~&}G&B=?W?Hz%$7You=>IT}-3JF2ScQ6gxE&9B zH5vPah5aOeO(?S4J5v;lN11mOI{Xslwj#9y(f=5z+YGo<FM5YotU*Qs075BQxB&!w zXJb89ilWRUOW6p+HUy6${)sQ#C5gzUVE^(8ch`}C8!8@-{YAot{1Tn!VUKchqPxln zAQ9yl6iyV`1QOffp#hReayd4d|Lb&-Wd?R>z6@|HJ&zYu0+rwb%K<hYamTlFz~`XY zM>K58e1%dVbeCA3lTgsLF5K@{q*HCD<c@IgDb-7ccd*K}df}SMBG>o?x?iHC@{-9` zbn*=PHiq951#U2~)|yDw4Zq1<Hz<K-=E8wI7%u1|mYOUG&$7|R`6b$9v=Uy#av0m~ zRysk%{()ng0pQQNC@35LYdvSi4f_VD!h@im0H6W@Bmf}L!DeMu>RG6tjpDc271|)w zD_jWx2=}qDBgBfA0Pu=;O$Ahh+o;rv5qS$>KhcajNZ9gq(SO9E3IMpmsg2-3e0gjD z2R0<u>ADH*N{AefsQzjvJPZJKUD&c;qPYN{7AaEr>l!d$tP_J$7e=+s!*}Mf?|E3a zgc^epY=k4$H?bUNjxD0Wbz~858j*jAH9#w3c3v1D!pI~(v`EmOUWc0y!1_XGx<tZ; z>l$}I9=6_wDj6V@49b+;;rDph&UMk3^qPun>{U0^AD~=4=GrxQsa;#W-3DyE99zy4 z99R)fji~hhB|6L#awQ4+wL)nus0*eV7YKH4h3c^3<MGmKt#vsgAsKL>mW{}xH+Esz zLy6^oTaot}NC)>q?TvDI^NJc_*$05wF<CaiK{iyQ!%0wol3)P4C7K`g10aSRh$~%) z#(_GrAq8~A?mW7?yqRTtjSuwF69%+?i<ZMhj%ABij$lh>V7M4Kp+c{eUJC&54i3_j z#P<e316YC)tefHMuw^r$FWEQ!TVaP;kcTwnc!LyhJT#Cbgafs8?P9R4Jk)`}>o|PV z<*rthn3_5a_7ks_*DL%c5?jVWENQhWEkGPd&~UzC<~8&JL+}WXf6#__as)$2g3%<X zZ!4Vdjqqd%>iua~UdS<UqD|mRg322KhF}!HR!VMiYAduohYfOQQ4&QyCtn*#z)q2{ zH5_yh8xqh8b;a=?A{5Sn`mrIWfadcg{>cs+LV`NBLW4;6!&;%I=HVaQnyJYK(Q?-R zh_}>45g_66O^4#Fb<tWtq8Y<(W{dCuk(!8lA#J?*YwRBmbPrC@A1CO^6O5+!1gyjG z$HBQyP(Oy?^UqzifN%{RS?nh4-71{E4j<p$MpMb+yO^tu``quYi$-LLXlh}XI8}jd zwMnnB<;41)efXEHS5@6RRoc*bEXWk%UI-gnwhtD^g9c!#!&!nC__1`Jpu$ZEiv;JZ z8cy*9Gv=Y$biq6p{5IxMS69QQEBin0!)9~f6~uHM(H@}nzB3t}<WR4YeE)!1r>24M z7W=V^0UB_tRl*DZ;SV+VavX->QzyY|R|E&2@_|ke5)pO*)9%XY3}QgTIl>(bcqik@ z5ChJyR&QYt(Ky(B407Q(I?<i0vSxB55PO%-9+APuYl-o(cIHUwcfyi$0Je&C*RHq1 z7l*#f5%A?eC3Lz|i9(LM>m8?fLXiN(v9-k?*TqjPhp<|n1HyxJ_!0@;NrDFv(Ut3b z3LiWS2WQR0ZA2d_Y}`Jcv%h|%y5kbIhS91yfjnxBrk9u8|BT%lMtC})L(I^#JS1P| zRl<N2$#II$_XN>8B8Wo%IIth9haVrU*a!3D@ZS&oN-NwC2j6IgJ#G~)VWV%dVe7>4 zI{>_NUa)dqnAbY82Hd%wW2CHuO=H34UI>XjK>=f2pmoq7`9_B}(jrRuw;R}=K7<^F zLM(*N(}q%3A%^R)qjFE;-1=WsLM{;z_vpwH656*?qz*v*<RA+9{+V^*3J&@g4StD) zsN&z;rlX@ii~czO%(M@t6oa&|xchku)qAM|Afb5lL7n8MxN6jE0BB~TqgaqI;_!ue zXb^A@DSuB?0Yc&looa<%z%|GnANJ!2jnd)IiNc#iR5=m-iw+-h<LlMn{I)EMU+c`n zb2!i_HsUG{o`yk;FQdofo7EOBTe#qT*F`Pl2Ny9|)Pq{w#?*NT58$C3bFt&3Mu3I> zMS_20Kuy;9v~9sWU?Q3&c%CKLsl|7KjPcHORB8)G;l`%@$2RBrOT>H!96ApWuH^}p ztRvRlgiH7X85W8KAa+RTPSVJ)b;O-{DBnNSMP#PyJ{nk6joN)MeUJ++;A2O5e46Gh zK8sZ)uuW+K>HMa4LDu>^t!=O4wK<%Kz#FXV74#K1us7qTAAi_oAr$U5bZQ;uOYAVD z_f*}4x}WcgcI)+IAnvZi>T!a1iHPfL<ZlLIgvkGrJ=r3me{lpG7$Q3y6kmBZZja^@ zVryFwH;C}t0CM4+-oMq6`2c)2fMvPOsI)c3?ueekh&{vfby^F9y01bm^jRRWBW|4? zM1(yXD&i{W$PtRBcXY`vgmZ+R^*|jskfY;5&tDJm)gQrEAwe{F@j9Yr9r29^?`ETi z8Sp6_@;3?2C(!;~N0t-$k}1T!R(SFwWZy0hUCV><SZFp5p2vbQbssGtfUM5<;#>r4 z9fs?@p;9fhW+|q(W75odd>JJsEZfo?A^ea84x{yg&ktV!CL}F{?(t2*NXWf^AN<%K zPhr|Sn;@6zNcU)AHVgfb2mj4RsRy99aL6hP;Z{1_kpXX|AvV?#moP6z*>iRDwGGyn zJL^I|m}d?2n$G}NabloMQK8%srdiF#ZPdx1;eR0dhFejDMEEQNdYCTgs3S-_(c_0% zfQ$=GX$!i2hD0y~A(sV%=tJ<TmZ;X(8+7EL4myuL*8>Q*5QWQIVKIv6-$Ya{iC?y$ z{@{?OIEcR()caO+-!2jUctzqnfZ(g=?h;Yy7&w=OSoxaslZXD<D&om}{v}EB5^s9t zk7y~e5$6uWx9wA|p2Ok)o4?K;1c1A2G@)WGmJapi2tL%C@OBl1{kMJ!CkU~a&;{;= zvwt|!XJc-E^khIcaKb~3(NQ+Kz7?K#0$#t)5ACCCIjC<$<Q5N6Kt#{ABEJ*SEgXam zLWB=MuA&S7#i4o`D84Q&W*+{N!+(v4N)G%QXA;-b-PqRseD!zpwJm%1T1#{6KY8rq z>w>uCTcfQNS8-D=_fS0~#1#hQ7Dvb%_cHJy)R#0bYQ+irvhGT}e?(8P>gErOQo946 zK)uW6nI9d=rXe;N$XX)0i-q>7+|EV|*RlF|e3~%_Ui28r9TV>4K+h848T0UK7z6;) zbSkmWH$*LRpLnPpX^3qz`f;FU|HZXw5U0%jz3pWM%Or@*!6o|wf=d;({NM-25?%5! z{!k6cFqIaH&{=%qGEfR69edi)?Bi5pldGr;7Y7IzNOogQ$sr|@#;3MfGlm&R8LLzG z+#0j%o3OyCo)h@z={Y6FhZ;x8g>|p=ogPl>tV*0Ld=&A^d|^`E`I@T#w{(-*8xe|~ z{!_LuVyQwe^+z@@^TX~UbEfp2t%dCCx86NG_jf64Hsq;?j%$_07o*S<%8b*%u8uFY z!tdvaw+}Du+9vSVnktyEm=z-prvYU^P#`=A5p0!H4@7wg`~Ue-GrQ;OtRQJp%dB{u z9^sUh<8AP{F*8|PGFK`m=x%1C@L}gGO`qTU&W4Ek%?A>c62fB$*Um@AT-Ur1R~=H7 zuw4C7dXH%!v&45X-wvDjqcKDN`07HsSm1B`$BN_4_zWp$H}Z|j@JOeyQd`$Xb)q-M zCtBu=>hD3N*_XdWRkAv*4IK!jA?<bhV7*|5C2`dn4J<z&%Dh|vVn_fLk%rC&M(ujF zE_dDP#0{qB!MQ(|toy85<~_CHxQ0j%9V^~yHqv05B!KXXDi@S-G_6b9EjeG{AXpg1 zY!WK;jT{aU_ti1DUKQ5wlYS+_JGox&1oexWf$KJ2P4;*XIpdoD58S7!L^fWqGBK!Y zqV(eLu25NTwT-3X*d$2%(CNzxMn1<%k4dT$MS8;>0ZdIWYu_r&T1Cc`OQ=1v2Y#|4 zbnvh4m4I<vO#w+M=9H`PHjk3kGGAGXB1FwoE?GRO06(_sz^P=pn6G^(vs(=OC~dbH zXnV~yvN}x4SHmo|_{io=dX-bXL5^(X$KEv2#HN+{iesufH!EX@eAJ}EH)EFagH0pq zMEA-XFvVS9EAI>at;kd{dkz53bq>n<AbFaB|6w0u!p-$>yiqT^TQ^IY>_bPGboV&| zoy+!O7n;-_G=!#ay4Gf8F|0+*W|vc*wSIlBY-QOdK!F?Io4&t)=N@ogL}xm4Fh6(^ z1eJLr<f?Y%h<RWd+I`W0a4n%?_~RYd<(SYb(U?9+X`;D=x@_!fa!9GKeJ>T`nmGIv z>jHQuT)R-WkfC(YcIMdCq~E`UfYVC`$0Xb>79jZtXvqYr;LPtC_Bk5eUuxQK4<6Zf zZVl9k1tLK>u^ia2#z^ieNr_=$I#SIC0}osMD=1oM5Lcx{q@nlxNctJDr(s&@d_Py| z4<lFj2nYRehy-OMKv9>yApwbG3lHa1nXAh-d;Iajx;x6dN;ABHx{89_&}FdrFmKSv za~pZVB1q=XyscgwNZ8w-f_*&iZMkZ2`P4F9iY=X<>3Iwlv>vQjOY1k~#fZ=uDhhzT zot|+%;xyY@>GyiSs((zjAE0j!EDJ?{6*c))JdtCAcab*Pgsp^VBN(t@1?C;m{muv# zQvRUKGkX-vIas!{lPjTx7qZ*V+W*%Bt+dUn>iV07FvM8P-s7Zi-z6iFm9HdcTQgPr zYxQo3rlo`~WV&Q7k~+LStBDgucPwFI;+xWYm#Y!nkVTO}Q$a)3IQWsA9Jz1vwkA#P zXs@_H#pTQaQ`6wwm^Eu@56=v9?sQ)9q4(kyyW#!XFOzeFmV!g`O`-au6L)bAOA(3G zFmp3X#TO_Vm;gxX#7W&8nkIp}At0qk-haC3l;T-xx|KIb$i^R}c+}w1yCI;|@^3_P zQDv$aKyqM=MI&Mgo+a`m@_gnCBp;ImHFVmtgNOR`p+TNjw$+FW#@2G>4<Lr!6S>jr zDH1KMOx<>aJXc+7;xNBM(@btJfEOxt(7=}Cpxn@x)(Q(6LI%cdLW!M=23%7cl@!4& zD>@lf3CQwD?w6csi`Zsfy+Itb4(D+D+Q~F+U@>3!t-Z1$H}m)oJtph?x&Sas;{MfY zgA-bl_tU!?&i}ak*x_Cl+7U?E^--JAXLK|s`_6D>%x5OR(G+ZbrVyd5+B77NqNsVx zM%{N7**g^^K1+jY+x}1Q@_Xz!-PXv$HaD8FR?MwjaV~Yw^JNDr{$<(fl^6)S^(%|z z@|YT-2B-wLTE*pQJF}$wxxO4_+1;Tx`#A=A=cj`t%4k$_99h_t(I+Jenl%5KENb}i z#iK)?Q{*Dsuh=c+OC|LD*U2s1le=6i9;N+6r<En~xOXKW$eaEy3Xn8j%M(UQA`bn& zla}&>D>+C^BZwy>pSn>LH%Wp_*Uy8&_R2~lJi(I@y@Foy;IygmXf=&3WS(WP^cDxA zN%L-ZU!lv_(^9X??k;4<_p8WlH4Iv9;<FB~gXJd}=_VX9)vs4stYS#P^ha`T(sr%V zEU(<S;$WUXE(p7D{y%D_@jKvEx&OJ$ETz%2MMvmN&Y2UFPE35u^<}WkFAh|c#m@X6 z44sQV)B7LCx7iKD+~+o%`~5mX(l*yz=Mp0{m*gH&A!+x`{hH)b=2DajsZ{E>xz4R5 zl}a_2%B4CK9d#-{|H1e3eSdC`*XR9uz7E<g_^F*-e^AwEZkJDhhG%uY`&Es{ZRc0s zLJn!U5R}8wyUe>uj$wRxaV)M#uD20puBRt)XeJunk7Sc54pOO(F=`LKnCe{im&u_n zs>eeihGbg4>oNmPdY56-+f{V*L6g$bZ1<j8xb(43F1mSY(CjNuI&bcA;U5%RpOh|{ zk1AKL#6ygjmcDoLWT*a3ovw<eE11n6I&e!~oCl<i>{y3m6+ZCR)o07duwy{UzvWMq zV)<xqhni=Hy1+`0krMK!<<5Vb1sn9OD2K&2KYtg?GBh9*W-V*0G;C9BV=vwdqtcH* zXl18<7f9GX_#xM9$9B?FkR(%MRNf*-ycwfXq5UAap*zDi_b0ve-iZnG+D1%M2{Hkh z{Ys6yys7vNu2)*W%7BpNl-O0^(<zW`<FYNO^ODIkbsDK#r`{D$?{c}zr8%?5J^Luv zi@X`y58GHy+biWgliH3s%A;17D`ivH)3uq8z<`sy(ohUgx;0JhvgMn*i2qie{t2YZ z_3`<xGm{H{S3t@}{)}KgLr%D^W9IpKH)3;#q4KbC2uEs@^opk`eG{@F-^+V%*&J56 z;{)w%_wUZ7L?drBvdr9Vi|U^-6l+l$)0L4k^Dl^Ui*Q-{pz6YqWQM}!ta_yxDlRfj z*z&LeX6=G4h?t2%zao|G(pkv8V)~6@&fDN9E{oF3x?N!YQ%lN$(I<|`C(hnIH*0=# zx1Wi?h!Am8mh*=mXamv=Y0dbmHg*&$KcNk*WxyiwL0%q(5W3yId!_7dH5`B{86$5y zWicej=%7mK+KK5HK;AgBBbVDMtRTVouGmiGnW_Em7Oc=ImTOd10-#HFnjM@0A@$a; zs6oG5U-v5Gq?6fmudhcfU*GY?v)3ifDlAp<*1OY1EHaW6$w!9FvgF@zBBq$h{9O%& z9gTq{#5Yk4pm`{^KOY?3*pR_zPcL&q!)(K9V2xN-Ab^$J3)%j~IbC-1%lt)o+)z^) zP`{?aehhwdg<iI8T{OieJGz!OvU_9+haA}xUhJR;AXh5P-j3nA48j?7cs!8lnx#Km z!>N$yTNE+P&vkk8b&vqMXD?mbu__A*3731Y7+61U!Sb<yWT&BCdqU@vYytti(0W$@ z6MS?W(%r;rtR!0ewy7`FO_>5GqApy}Qpv#&Mu=FxvtVy3Oa8yI^kw$JcDAfw7h%B( zU9mk@bAKmn9v0FIj%X~-^xy=m=mUBc{S2UI0XK6z?)uq5j%J}Tyy7tCXw_`BRNt=c z(Y2_TQM&{mSc3=7vcro;%WBvo<6N)hJ;lqcN82o&GDc_{*p&?SBo=za=-7r1JI;$4 z#nb-CN+x7lbZi$q^k?c!4QDO0QcZ6EO}u@WBDPzNUBxG^jWrepbz5-_1jwAPus^cy z<W1SF7;!{i;*3b+4B!3<4|=qQ6S2%FZ-;IssRS-F&8?9kq^rCzXw<LPrq?j%c}ONj zPch%&O*uPH#5ww!6_N#s=R(8z;6T!C|8B7RGWgmr2<aBniO=*#u@7PNuh?JNY3#YV z6_xKG<l0Z;%Q2qw>iI`!x%9aMpf}*6DVP_A9tvj}$3x6!D^-Ksb~?x059z2)sjau* zev<5TJupTFZ3jE|W!Drc47C1TEeq`gyFP`yAAorA`>XmP!6e6&ET=>a<dB_Mn1%Pm z1$$>TR(2Yc^1VJ~7lVdJ1|4AgV;})|%N$XAYP_Ym_>CqxSUQy*wTp%IfMyspp$s`> zJnN_(#H$7pjAWSL!OCA;#Vp%j7jObBTE$P?$xdUr#51{b;4msAVjc26_S(;1oL|w8 z<>$nL2jTlfdn+v<Zwdk`NfJlX9w(scK4;~Ba0c1OL+lM$o;5l<Mwo|Jt7J@PFS)+n zwV!}kYh&N5WK1Z5U4TYw1IVFSW|kfF5Csxz2MzZq{%->2-=;o24bkrz&&1u%MY6?D zKs=YhV+Ww0Ywn%Wndlc?hi}y%Eo&tpA)XXSxUeQ+O<l7N7A#~QC$mZ7{{HjryLyuc zm910^A@NzYSe8=}CwqIqkZ4A%ViT&^6cHzn#18ZTCvC%$F|fQcxG^Xwkk9hl28ZCU z9qEO<vbYj+uhz6db<G~S*Q#J?5biJ~cG4!K8Q@t~1~ZxRHE9C}+Le9}2mj!g{+S=U zh9Fv%(FzwlZACbHMKRwPzx}r#4#+~DSp~VyGIzrG`%+95hDKqY+xeM6P6zDR+!f}3 zGo0MctFjgMKE7d3XE+YdK|>RvWDAx%870nx+D^Eaj-rC8tTT2F)GFI(ZBF<sB%;yM zM+CMgwu%;mWi)c;YdKC7)(Meq%D8RPZVW<zp>GZ6ESYnqn;S6-@r7SGB7!BP75l9- z(<yghxuaP}lunItU1o32O&utMo0eJ-dWYagknFP(;@Q)jgKa=pOk2P#*oY*9TYd=> zD`aeibi|99mI34Y0!OAnot-j&62y$s!1iQT=qz}ya5lHM%DM~|!Ds2<T05QD2^Opv z(n#=s%{#d@x$(QuI?i-X`}xF?o!}-c><=o(gY6AqwfwdX5kcQhyEjbMc%?x?rCu92 z*ZyyiNiKs0Tf8wj#GcSGqMDow<Bl9BpUW}WlThZ8EM$?>AWi@z=?ycq4HALpMFLpe zIn1!$$%AC@0V>#62+=!oZCORm;KQL4wfRP-;upcx3GIRpgWO%kKNT*1gsW?|@xShs z{&ET{3qZ}~({TqX{XIdaRy-fk<|OJ`20b4}JCZ#m`(b<ij6^#BB7#y|Zu@MrMxR0= z?AVcMUemuGN?i4d0|a^@85PmDGyA*(YhbA3Bf&(d_cG~aA9FCtFiObrnu4AoL(eE2 z9I6DL0hFh6Az{nl9q%*<K%H~A7Un(0$|)PLhlZtM^hlW9Nys^5#|n>E@Y;qXYe6Cb zGm!?N<4-w<D|B=CkneQV&feXh!aOhw_9BA=vsj6}tms*8UMD9#n)Ah8^o|cL-o-b< z9pf&rvwg%r4RZYf;(2&jC>TJ7QvC%-0(hcCl=7+&ZZ3e+lCTD-mV+LhSu1L`cEb{D zo?U#<Rf?E-jYXXFZVH(CpL}`fTKLp|fwSeDP&=_HP*>Layt7pF(9eCI6qJGk6wn2! z94F3?L&E?hxd4)%>5N-B7<|wXWsD6MGP6m%fr*iK(`@fqNPvNHNDWjvf<3T)I|Vbb z6TUqnioUO<21^og$Z24&WpE%I?AJ?#guagZb;qB~iRMCGirCeUpqU=9Bvn?3!IhKE zFp(O|8?NM}0|n*<9B(Vm&^YogjSdc0@`<l00?bt}NB^^}AJ+&AkrwBS!XiI@uzKBB z%x66!(MeP>le94(JP3BkBrY!Q29lv8lsEIBo34YXLv2TJN&j(Wbjc7qVSAVz`!ET7 zm#Hyj^y!a_<<JH8VKT}><JIAKY*0ba{?)RCH1`Ygq(`5@?wzy7a?sI>t`_IO5jC8T z#k%Q8XgKA3m<W|FV#8A2y_*I{Vq__*ipUK%d7Jk?$Af`nk0i=vp2X#yiY|6`4Z9`` z7B|*#Ty#1110<k~=?<X8XF=Rd-6Pk*Hf}63o@vty4#<LBPN+TaqO{wq++^V!2h;?3 zyreA_r`hG-ijYgfNCW_!i-pb9CP?l>`av?}5K`=+zlo`+E)MFaYeB}9wQY6InR*N} z-b(Dd=jPhUx^Dq-t5XkOhVX}V1xgFIz$)Gw`^ug{_J1Sqf4$)I=WQGy^#EohH1>K` z@#iN1NUAWj^a3(!n@FNS0X~8_gJsme^|`xHv06?J02WWVSQiaB(ste8I3%PjCj28? zR<}E0TsAD8c?JVLG0yVAxM$Ze-KH+MV;E#1D|?D#mdDx&-<1^Yzz%6*ei%p;9O+&I zNj<~TOi(?E(k^I(m)KRTL&fzmm#R?z04iA}RERG=KZlf`fP|e}|BzjF<$td!MYGTd z16?~f<WL*fKP%2IR5B5I!qg+p2>`-aB-viTC4U@a9(iKCu5;x#BurRH?^<^@b)SCC zifM%Sw-vs9&JrWEzxv{OObYS8lmdSw1pK`0xr5qdD*MwKSTK8?*UU1$Q}216na#CK z6j{=%NoD!ZQ|(yXA!bC)RGaUYI21dZx?8rGiYSK!Mt8LH@o@aJ1KZt!q%z~zocuXh zUL!0=kDaj&-Mkj;**8Uw52n841hz4pdYL<3jgTK=?Al1!arlAh_3!0rARD`UT+MWm z2jl*}0`im=pseIw8BFE}++dsg;DZzy&|AsBwvN;+!%VmWJ_UGmT4(h-{?zPsN^;8T zWet5yV9RslfBm5acCA+u3Sj$f#z!w~h3#ic>s^oK!Yom!UiIq@r@`k7XCgaT2UT%r zs1Pr>u9yI_JLdNd_m1u$0(x&J)^O5azAzqR--1Cx;LcMYudnRwcHdqOn_}DML7%^H zzY)VaW1*5hi%r{oHryr#Q<&r$PGm1Qb(w?Zu%G<%ZleBqr~@m4zxxOWi?)LVtuq6W z-~C05?JeeGP4j@ZC37Ux+m5wE`H*^CRca3KPw`9c;Wm(Ad-J(j@vI~Hr<SEWHu)3) zl|ubnwtkI*f$0b!k@1_Ac5200`De$Zi^^b@WQePsSQeS(DI!dKzzJ{5;Hc03U}u5u z<a@qRb}5ytLtqn3sV0;gc`HX_?fH0+W5kG(Rwd{2EH3<<(tI@gvsQP)ZI_jp>d%Yr zaX-;Mb$6304azk?d}wAS*IA`l9UYsvEEV)9rw@OEc)7IJ;>aXBZv3R7=Is{G%GA0& z$57XNFT0$0eK+})ZR?vmac_SVsqPDCUZss6T$3{nZf1UX=Kjyh?d(R(Q^uVlwaA?R zhC>UhB^AvM6qr1%y`29nYR9)N%W!S0aN~MNTgHb4+||<N!%Zfk8H0u|jE{f*TmIwj zR~&WbYRIkBFTZR)&vqYucEhwz9tAiR@K0C6eQ|(UdcYbG55uRwzcFtZQX&c1vun0= zJsRP6LJ#m3z^!}v`@!m&tC}nFP-^X(|7`#+=}dlTV#>8o`C&b)o~@w;OUY0Bp;D^R z$+Y3K03`#cV!TNcgcfgC?xGxDCKyp7cM2#Bsb3>7T67O_z^HX<+RL#{UA~k6H_Sv> zU!JO%!1Z{@JuzWLF%i}yo&6KIeZIHktUKbhW6Xd4hF3T>Oj-H)`%JeKIo)5MsdRb+ zw^s0fg=>~EYnZBh9<bxPQBiF?G0`le*Xwv&Atb_PVA63bHbdOBfokPr`@QJag!SQl zfvry8Yo_z<wq~45_w<#4#*OY2feQ5cgx2E*IbULyc?(kmGWKIdRt34M>&N}}|DJG` zIQL&r+^AL!U+#i^%b!Zs#J|*2#y9S*O7PSA9?l<9zWO}fT?2pwc^n)35LRpj@UB$d z_kgH;J*j1eSZeXH-R;TAu~Gf&$qQW|s(1Ho7}bLu)Ff27Ri(wz0)d1arC8jy=A$q! z0mDen;(?J;73Ct<zlm_n|1x&FM|5@mPFoOQx;<r%bu~>-^hyS`OAUMNG8b_b3Kxpp z_gOW|m>#XsdQ!ggY#rWQ;(FwQ?w-lt6@x<-qjLzK*U9<$W`0uE-g{;SiKBY=m&7Y= ze^RVuYz}qZd+zvlJwQ_TRx(Ip-)5R~vGt^hqD_cHwp^iEOEOVXuWRX9@XM@8ZEf?d zBIhT(t+d6_qg}~B7bQyWJR3v9RSaXpV>gCW>G)}mQqU}5R}QQXDDJp*BSz*EU{=g* znfGbcJ@HuC4P!aaTuU{_Q9v3*y}jX0?USYf=va1pcF4Ju=dUhaa{|PQ;nxS>&|Qo} z3_wp*3WK^?sNAWfV>D<JVdzmjUWTIVNs`5?1<e|}{eXL+9@5Bs9@q3%<E)pi&Skp| z%Ws+A3Qcz!gvSw9cY-owoV_=-<1C!fS_0OYJN{OhKjA8MBDO`(pmmBtjM^{MkZ#^n z%aqv`gMF2w)oC>GGl+qtD;5yr%l^8TXe7-};b3h|g<_k4u73mX=G4C+k?N6>NW01o z_3jdPwP;HCHTCA;McF&N^k(#^5Ntw9FL2AkBB(<8LO+S?oW(0h;tr_&AaNZPw2+B> ztwp3Pd|w+u+?PU^<s-QveIT_9hd7DJTMzbq+pyt~q&51=>YmqAZAe*CUjrD3z|JeB zj|flh#5-SibEvRw2JmgU=VhJ?hZMitF|<7W^AGaHq#H1YmA5hGYZ~$R9jqp`7sJ^3 zY=}Mm%Zg0x;qz>{1j&qemZ_&dl0E7dEwM3cq)w2`HUO*iOhEwYg9TX#((bo&4ABJ1 zKq}bH@mHLagMZ;ST(iMg4a~}nAfCP4tXx$ya?Wv^AicUM_pA+Oh~LmUW9O{$ts_4? zQBWL3x{mH|!y4oUv?i}C%Jw$8TR$S&UV$$%4Q5zQCG*^vsTkBG;92lHVrfKKlk6c9 zNSWWrw(G^p<j1>c$?f)5;y^Ny%S4RCza0GUc^S*w&dTp8TsIU*HXF`R<s;cfWUN#; zYQQ+P+#b+)xgz*&v*rQ`{3=ag6K4mM_3VNJ!kcU#Q2g|O>)aW{&OcYLz4AQnK_JfG zJ81u^hQ04Bjfos3>_68zXw*(MXMQNe?`+6W?_d}qU&kZ4rpQNk_*g57K=yw<Lwcmm z!tIBpa+~8LDz;t!i~B)T&>Zlvx^qFMRL2=zg1qjCrZt!LcHGg5Vi|7|6ePQeb-ys7 zUbzc?;&~Q+D=kceEZ!lWH|e7D1*o2husBt;AlJCevfZ|y<1J~cH4Ehl*W#2&RJx*F zJq-5rRsL}ahU#2ap@p3QZoY|4J7M6W*}Ka@dffBBKc+5Pt5Yo8Zvv8KmxeuA3*VC| zkUWOmwF6_}doeaL^ekuPHVc*!YC-W)nd08rF6pyOyTP3k`?@lGVQ8&3J;`ea)J-1W zuZ`=CwmGT@DG0Sjd<Z{kQ{~}fbJ;j{HPblLlH!A9K9vdVxMK62a^BP=ogMI)F0~Zc zY8;vm-654C!pLAMz>Sx;F`gqOH^2llAztCYnhUy5^$HU5naf1<)=!9)0%$UftfhIs zQ|KDqBYq}UM{_ql>yq)0?o@iL>Imiusbfamvu{#cKd{27=D{tKNoVCIJ2B&rQLW;? zI_iBAp;cw`5;@BY{=~4a-nBu31QHSTT?92E`@f6nY1Io0a64p>UX+vRtX$*4KzAeA z4k8|sDs)zt=CRG@u(H|f=656oT(h8E3go_>G(Vuah%ak%Mef~z$|4osoP(A0-tJd+ z!XBKij~ldqv?m3?Q#Zg7<p62Kkc1d~1OTIXYvAr@EBnz`+o?8NWGHSfhc#2=Wpg%O zN+*E9LN;Lcw~`_BSw4(D-+dmui;w*qBewAqb~sj;v4y+_b}|si@_L4hB)%0MZiKsD z`14&a87mQJ;rv9n%+gf{Ef-Bi%fAxB%$SoCYzuqMqSQ=>TiBu$QMCMG%k|QdsDcz+ z!ZXDgwxI#7Fh*!Y$EkQei6+W;X7=~}qMk_i-zO77qQB^W^k2s0jpFPjF{v7q%Y(O6 z4t@#vI-M_uZj^!(lLeB$hfbc|IpYb}pT)|;-7GMGWDZcRDUFt8h~ankHbMKP64v__ zP@nR%cLoOG|9hDDo67kI&_rf>6f1uO)I|dD!|e%505Xr|v!M3#J#8ufD8UgBFKLV8 z3RJ$v<a-K%=nOKe>b3<8xWUVT62DVq)i5e)QKysf_kKzQnQvYa$cEGm8L2xr*Sk;1 zZLKjAG+sMfxR`R40OGG5JNvaZ`*9Q(r*-CYo7d$Q4BJe4Ero8FscglEr$hwmw;`W+ zPmv~^XS({|crzdsZ};yT70vf+ll%1=&y%QSwsvBYs{^=R`kC1C64eov;DV-bqOzR; z(<jixU0lJvLoe+Rmc9UY^Vu|m-hGIAC#wh2rUI40MEW0K?^czP#IzcYh*_$_;E32Z z^gQCZW*beJ|3<lp*7x+yM-jSTmZ-j5cWjD=o}r;<ff~OfRhQio!|4{@&RXS?fN<|5 z1;2=V#@FQmGX(KCUQ^?d8-j@+IY`udB<W~E-zLFhRp1Z#>T10KYP$g;n;b#1fI<j1 zPZ4Z45Ddc!j<L{uZoiSxdC(CwQWI=GMRYU)Cv3fP1%wrG`_1i$&T~SslSD8*qEv_B zgwW8%s1~Uo*z>_TEVkBKVd%vNXT2Kk^9F>(<iN?OeEUf;>sY#Oco8J-^~tU>So@+u z$4>E|&mh>jh*KX%kNJD3Qh^u@TK*AX@dJ?XRUo$jB)UZ|kkKE1hM?1Um@nsVor$F1 zj#SE`F+T+Pst{L0FJj<yESQL*(me763K)=O5%l1}g&UbADKmub-eEWZ?{gK3{Y>aW zcqPX&)>@#s0BYxT_NKVsp|^E81~5IBibRDAhxQdF*1-06KozP4+Cg-KgGA%p+Sq%V zX5}g|id?y()~EwQR*%-!^7z>_ntErbV^F{OT(sGbOQusqg2x0ADRP*HAGUHfcchz& z;J7H4BC@tEeQ<P&uGQObjsEDq<ZMa>IsSYm5)h}}Dkj-rbe9=|56$*(cN+9Me4KDT zrXIx0L$#F?&Q=t<fraRe%jMJywfo;j=pp;pz5o^O3$T6fZtX*(2WiKM=q2D4&25^e z{Tt^W=e=Y>%1naxrh@XxD6QW>ja^Tw2ic?cjbaV~Q*{yB0c711oXP`g<?fmQ80dSk zy6<!VJ$Tfz=TQ5V#70K$Ff{1Cdy<O)Sw%2fKN`RFT(75|GCy5?Z|*GqiB>0}QwOMA z)A}&$f}m5N9#5EjHLgUJGYun#e|`USXu#ZrIPF?w0B(Nzv_CSMX|}}3|LBZ6;$k|} zpJ@MaR7A9ref|7ICGf5IoJv#vwodbHuvvXvdqbt!l!h0R>14M<Y?C_wq(0E8h;B76 zUXdD8*?8W#j3z%t(*%H)uq_&&^_204&?eZlVIa{8OMC=Gd(^37j%GYo&<4;k;>1j% ze&%q3a;(6u_MO+cCFQIuSX`u1A5aV4uU4y{v*3Sbp-!p?FWolm{g}PGq)RvYn<7_l z^l+@y#V!HyhuC!W^-p=7C;$bh!dx)k_hNKQQnQR8SvJ=W^%%PlD%VM%kp%aHK#oOi zgo%E0g~1jBP=N?kVAmh7A%?s6Y=q3TP3<?wQ3}xm4sYXaGl_9qDoJk*(nhOo$z?ie zgQd*1a=f1LvJ%W^z&e>>=&?(}s|I@-!$z4FK|A@z9z!_XM^6&bD%SZN6{MO)LtB8b z3ZIC?iyBCxNS%1W%w(Y25YtAed$i)c6{MB9%gRG%qEUWdW>n|`M*0$}fVW!C^QbLX zE)wXV`g!jdA9JNI|MgYuaYKT`#f1RWXF=+=8?fE&^23fN_uY!GyWPWFGF~Qr?;#p8 zcc-XxVkb&YG);T-{y+N{Dpi+$SQu>eUHZ|ZMUAJikV16>!Gq=1dKH&fa>hy%bThfN zfhiT|n&pw@e%vfw`}aZuuq?@69_FNHu-;^Sgn5VUQq(4Ho(Z~nWX)z;$tsh0SqgG3 zqF=9X5^5Dzu~bd^tf7l+C=YM&nAst=7SU0$gb&*SGy+8YO4Fz}BmM#^&(Rite(aa{ zbj<CLvJHLkN61hGO(`rkbGj<<4-Hit>0wJ$&jQXfV^uy9?urw6XrqMR9m`0%8lR1r zX;J-*&ce5TC;Zc@#QKVeOawm>oa1US0}NRGCQPD&3lP8;sAme!IvOw+#*K%}RRJ`q z8r?rvHDmpO7o;Xks_8HKO4;9@7@5#b`}_zx8fGYsOFu)MH|d=}K*k0dB_<kHIvTd` zk|Mg>9D^3Et-^4L&31;`k4{#OJ5tP-tDRy&y1)C6nTFx+1e-2-TeoQ3JV9w@4LaI^ z)WE*jwj0Q6X6S8!M&^zn&59@Ij+U2Ms?H!Nliz%qu3A08Yam|nrqK>4`OfRm?>!d` zRY!WL($!)Kn2tIgo2Fkh?9l0)IE(%_5B8&k53j<Dw?I#Sq^izBO*)_@Ks@A6tor|w zCwqoJ3kS4J=q6)?>DT=#yGB~107(I=dX(x`3OX(yVGF5p9v-1#p=|Z)zCrUF{Q{Hi zs|1Y36UbW=ZvWG_AL_4rME>=2&fEoTI-AaddLk{{29?G!E4r~5+-;^Qa~)APfy+%J zUVmZ3HpYE)HlOLY#W4(AZalY~iYj1strGPxuc3D*N=1!2%U;-R!s?ir!}!<pcht0T z9ec&}(H1*LZ~1KGwbK;8d{sQWqzNurp(Xp?BcPbTZv`!wUV<WAQL96sfa>Sm+rXHw z>U9jSgFiSw&>4$`0Y0MuxX?p_euK?^E#|aQJ#hLpNGZ!yi3<c&5!y>y|E;gTp8BdI zks#Ul{vj9m@(0Z1;k43(*1&qW<1F12oaESZnNaWXW~|$K<B4leTnVYubvJ?U=Qlu9 z5%6QE7kRPx#S0vlj_P!Y%L`07@oeG6!b^x5Y}MJexUKZ-^@VrFdUG>a1WKVP)#3ft z`8a|qfT&*7e%KsK`R~NxMS?ODy-y#6rV276H+-|B2z#%rXS95YBWQ3fzoCgr9Rz>u zPQP-WK!32HDR}eLk|0UP{YLW5_y;Xrw-t3O-eP|A>v0JWI>tv*`c*asO0!-++o6RG zw9r~z231AX0LXaf^`}<FI8_+c1^oBn2lfqm!gJGsMxn($kH}SGLq5?|q0DqY*lGr3 z>SAMlm}!2N>Er>j{9$EWR0PfmENx^N;K3<f2-{PE`)<d@(7#(AUDrzfD*d0(Mt5Lq zj)q3`|0mZUq2EjVMMJ02h*muMxLJ4XE-WD-Be*3!mDiAJGQ<X+%CJ<aeWQ^^(8AB6 z)aa|%5BX>B-eSb^^W75Pdp-u?yJn$g$#Pb0ZcfSn2!^uGSRGEx1Ob*-O@uqN;KxMI zBpF&JK{<$+SVfS+1$*C|eh&5SC@EFiw&-uuy|6(zVo22eo#{BmHJqRu+OaKMz5Q<% zS-kMGaZn{%fFWw6!s>r*ll!&iQk<vyi<8!H@dH|j+U!3WqQ6`VyKh6@UxQD(*y_ZP z7Ku2A%M!&zWsUyMAZg|Jc6qnnwC<qQ69nww4Z1ZJ!z3tq^9Gebq%SuV-?U@ec26P& z_na<F)wUXw7AMn#S)wVH>91WE=x;lJvF|C}TT$NWRx0Du^^9jtYD(-mXUe!|V3}cX zP|3tbs5QgK0`W#!S-Q#-*Kf=n+pF|T<VEMpZBc-_;V+E(WFDW}NihxBQ{QFZecztY z5g3V%$hsTvyxvsc04iKadC5v^{vf92Vm6`<kr3OqaiUBm*vz{2N!;rni(iaO#fasD ztsRL<Q^3bBfSRiW)l7n~bl2#$8=9H4uPoUsGDoqQ<qCf3T0M2%x9>OD(p4=4*!2W% zU6hD?$KxX*PMeNZ*oW#6aPr;qO&|0u@5Xy*VPK`Zy__}(hPKs1FSIT|ovFp)8kPoZ zwq2zI0CL{yUiv_Qj==QcG$R@KJIAUwN%*L3m1PG~@1VaxRO*_P5`Kerw&)||iN7<a zho<N!WiUIq2q%jZmKA%<-832&zgT*J1ZQ1r`+}W5@6a7P48q>8@l5~rDCJl=(hb1B zEy*B}R-ElJQ8^8WMR*ArzcFbvRZP~n<R|nt;Y7wt8uU|y{86P@T9n^L?mfb!wXKr1 z{(6QER}!S142+e*Y0cj9Q0>>rr6~diI%D=N_fVyfekBh;rkzmjg98>ikbe&weXZ$t z=^*~Rf7Y<^f*GqxrjVv>(vN)(kOJ_vT6FPtKs+0vY6}@ko@cPJYDUnzot9iTNj3M3 zyz8|mK8HBERxfNh+!+fJMm}74)x`QdYZ)=Jlz+9y@bGx`MEq07VMM53oa2Yku}^I; zdoBvIepJ2m3V0MddfDf6?M?Z~h|#5|t4o_Z2`{hsf2UnNvRN~ABjBO$xO>9d)7-j+ z1I1(Bmkccv;cwe-g_K@=$e7NwkJW#S9^lBT{aA#RYT!d>00r_eza!)4js2i4Y%eYR zB?9MfI2WgFkt6rV|6%RcC1UA!xP(sKNsKf7KJ%U__im$GV&;1{rchGr?AnW;Vx9Hb z$3H#cxu17x$T_k0EEFIbnwxQ49>2j+-hVMS`}^}-txuqUKu7liqe=QLqo8)r*xvXH z23;a0OYk@*+J0A_VaQnakU((8cC&|8zJZ)rlk3!SX|c}|7p7C5XWy({9xSVi4ll7k zppYFl?dtlkZ8>L9p?uWvQgi(0d^vye&V??w)|_<awJSBFBMPKUm$-KIhrc8`e97fk zuH=$`>ek(Aq8F%;3YyYu!??c_RL@w=N1H!f?H!n~p8VWYvd_dCam)7AAOrbW`oibQ zy&JR5Nb^1q9hs*9NU^M0zsL34FF>ytg|ARjO#k<N+fC)~vaEH=L<mc8xe@Z`r%OwZ zB@fQ{Umrhe|4;qtIMlAI>iP4Ks1v)nA2ln3)viW{N6s0?l@C;V-si?QMcu|YH+^6O z@P*9Tbr~v0I&qoDR(Elph273NR-R@1vsF1;R5|h{#-*!uQ0}ygtXnCmd$bj0XxKfR z>ok3Iq`Agk@7>LcQI41X?Utn)Bi;_N@T&UT)j@?bHThS^lE?a8FGlpVxK`!T>!EVy zzrQ8jEZzSoM#g+v$mn*Icm8a(S9%467+ue`mT~+oBtF559T_Y&L)mXmxlrpipSr94 z>@R+slca;Rz$v;svq5Zp2>cLz{dM9>P5jpC^?P4c9fCK3jTg4?ybmw8iT9e$k;t+P zsXypgxD;4r5JU~)qCf?zk7wx!l{>SgQkH|eel3Ph?%q_ZHUro401@rldFc?#_VZFt zzPKu!IuYeo<vw#}CE`%+T>AOe&a{e!(-Cw38m4$}q>m&R<V%`z22`(ozj)by#l8La zTU(VEd!OoFidfffG2bT)f0zC7;SON1cr4(?UyFVBYwSz+-TCL@fB!rf5kv0nqkzj^ zrb+u8wLolL=-Ch6<*2kKUAtax@$pL4U1Cj|nC$!`3X9@BnFQ$wv%TC^{1LvWGLr?} zgFq3)Bi(7^mP1BHQQ}!b8e=^RJTK>NnxrdDEQt4&+jWru06Z=Ec8|G&A@<!3AaVTa zpq9u|vTTr{bgq+iV4>@JWn)XY5UF96R!%r^Pg3Qw-SESrCAj;bn94v*gn9UtYM<D4 zw{J+4pruL1a|&#@y$UhCoT+4<mvkaRf$TKJXF1o1$DUX!6vBs4RiS=IGC<C;(I>C$ z11yw&^tu#}nuplHn~-0%ccd_K^DHBSlz5tl3q}<PeY<>9wsaS}UvHbgCkTiF*NZaw zB+k{XBldX!ysAf+x;`#i;Yl{TeUNcAw4vhsA`f<av#U6T#87?wO80n~fBwiMNFu|4 zWvXu3OUJ_xNvWzM0lRrLReXC>^3)vBZqJ{fYeYtjv#ym(MH#6{Zeu;z(?zG^SW3Ur zL{`4pQkQtn>!phpJQwqd421}9XNCU(#I0U?G(U^l$m$cq)Z)u!A|@WoiLFUQ=xlIR zAUy@YYN6JTv`W3wHX<kZ5S?&0_@k_ek~4<SFdlC3Jzp#>X9}Oy_ocxdvr4as7T@{8 z%303pR-{nOr2o#DA25$NfmEN0YKojCt9j)~LTJ{&&cz?BLp9&3egOFUcafg^XaXB5 zRnhq0DfUMa$YHGUxptbR%+a7uhum3T^9@gpgZoBQp8F5$#q+q<9np%Uc*v5Gf?Z<Q zJU-3%%G>Th`ezGw=o>`1Bv!}7s%HuhcetV@ipnopCiUpgzsS#_6=v5G(dL9<bK9<h z!zfEv)6q}9iGxMs*_P;Qi){g88ICEPP4aH{UWP49pHn#jqS$y2TjC@Fnkmr~($WE^ z93I%cPau_(-mbA`2X_!YmBxLDssAj3nIod(Xnhm0(m<#Ms-msA-T4xrJm>{LD$lQ> z_~=#2j+!r2OY*{)f)>aU(te$xkre?u{sSop8@#46xdH+Fstu7kETsSt!2me_28jp# z3jYfmG*SS<vP7NapvL(;zRDiUG#<p1)Sm(F>DP)sF8Py3avna=`)B);*7e;^T8HTT z&_Q|KTk-yh`F3y4TQDwu7z;^>iWaAy?2_++j~+`>kU2A|t=YWpPZW!L8jCNI8h)sJ z&q-A=uuP%g0e2D2ulrQCLX*s-Ol1Fu;y5zrk9-~SM*r@F@m_?SsZG9=Cn?KudVb8d z=T#-u@CbLm#U#J6hiK{4I&X&iWOJjS6Wus~05GK--qeg-wN+0F`6CDTj*QFf@s9%R z)I`g#(_nH61hPNEENv#%!?j4)7Z?A1c(R;ut3hPTD4WL*MZRzmB4sVxYF=(2hm4Z_ z?VpA9kAIspHFJT<9onSdG3(0b-pHtW_fx2Fxy(SJyq~n3m(<kp-xYzk|NYbZ&MQjA zu#HPL!gE8)B_o!ty|%(f_9E$$38+gv>%f|Qlqa#38`~p<)GNeHtmMV0&G_Clr$0B` zkhLv`vFeIkqD8lCmVy02Da-f{r|S}r0C>icGq?T!$+4IC?W%t=KMl}(&c03J*R$&} zh3->f$@4V5T%&Z>!JdAl>e*z%<&}O|IYDSM{4q8(4Wv}XANHjPiQDV_ahCBrsfWme zDrHC+{Uig<n(dc6Q;KqB+!DFl%aG%5zkEeKjXmWFJm7t2dRv3XmHW<3@mb$jT)-}u z`w^MtO(w{kiAEQU2uF19<GH4rJn#67KWmdMFb68u7xljhY#)H_aN&GudY0JG;(G1= z=Xa4ODDTHY2H@Am^gfnE=V{OJarJL_{D!~%%KR}(<E3t7HZtewrA3L4MFaMO$-a9U zFXpXMM;va|4(sM^^jf#1to4vx?kqyF_Yde`b1{rp?G$j0_LtckP%=QglPb~4-#^8d z{dE(w%|E7u9ik*DndzfF1&4M?Xf8nA0AsW_!9}mYFiR*GR(MHoEPAI_Ql*i355MlB zB(0Jt2(MkpUpLh>N}TMBhm>9$=dQg=Mati&AUFAv%lvFD>DcH}gjvbI9apTR2~yxi zDc|9#cOofU#+h&Uc2tVrx5n}^bJ@1iiu$VvOGCuvf=XP%Cu9`D!F2${OJXkBe~j8! zuRSnhE;Fzw_gV&EAW%{ON*YClh<FO#^9Y0JE)+d&`&hk@Vo$}u9Vqs0RES9zBvAxT zq(T!Lp`Cbfyrp>C0Yn=`a$Q>Ij;n%8iyWy*+a*e=jBs(cy;kS4yswUaIP+52LQ$>P zU3I}7?<nKsvJ-8EnWWhHcztx^f^1d#e9;y8ym{r)r}uZvXp&HZ)M}$tz(3NDjKv9h zlB@XA<R@0YsgkJXhs3XoR*z+bFoa);Y|%~G;IC)ofQUXS!uYzs1WzJP`V(JtwSE|> zM++>8`EQdHM4nUv;8AVON&tYWw3Sxfz)C^B10MSqU&x3PAa}&VjAFIgL<Ce95kQ4d z0q|HV#H~?mCKVh85a$9U8u9Ywjq=v%vaj)oWK5lB1*C_n<VkQ&CUB_nO7$K}l4E*3 z6K@h}1ui4E9SG4&#V>D6D8$oX58w)^v8o$BXdRyNChb5F?EOW5L{-=OuSZnV2$H|> zKf3)(mW65r_Cn?{tGKbLANYqe{MhwD-<@^9k_1+A8jti%#qmXw8Y^eQ2PC5z({YP3 zjeft{jAZpj`M6ezNbHPl2l9TLYR%$}`rSTghT2tvmQSE#yg;sk&soAKRDG7M)lKEP z5`UHMpOA*PQ6=!Q@QOx=Njbz}7a;DhI7WrWi@-}1$%;mBO<<i)p@e5Y_-K^k)CZ6s zD8fY0QbSX8(YZvX>3&_&r8g-BckYVy&e2Gf%K`-@;N55o1ConeXNG$wLDM8kwgmRx zyFi+2@nf3uuvd1WVqKbIBn6+h0$l$AnBN~2r#|E^wZ3LE^{GrkAU!R5x@nAD03cAK z6%!;|Re|I;PUSlQ;-p#NPCw-u`g7G^eo`+@iFn-p$2=}!#<7a0LiUjs4Ja*96g{Jq zn(~31A<QNtm3>4X*w|e?04>`L9TZ8FVZ<x&P@{D47+$dqARRmn$i6k4*bS|~%d+9R z<aDlQtUUi#vZu>9nW%gZqFg~llX<SegK|^fB8xuB;#Pe(a4J6Y%5#YK74yo2BBPBj zsBWH2FUI`0wbTy`{=>JJ*kk@0GnY332%|0YMZQdAT${vkzd3+&r6;l*BW;lIvGz#? z9Fh0?=~;&_QXL{qL^pK~09aT*mwG!9Pxx&lCwEa>rENfQmFJd}x$nhdh6zuh3LzfH zlM@lJsCB}Qs^!;yaj6=LeQ!ctw;~`DpQ_}KsK9t00>JK!%JCWz(q)h^05lo{j>b!$ zl)Wf4(fo!*;{{4Z252--(FZvmfK;emGbLlunNiAi$cc<KS&G)a@&!dpLgeOgc~6=m z=tQJdl%zCGdSVIw3?o%$5wM2uGf+ITUg7f@u>G5FE+zFyqTS-j$hOP#qhP``sy#1p z0EtmZFwm9l#$Z_52t9(ezCp;%kNrj!_82&zO&Z`El`vFl-$5h$$e-^4swnZ+9#b4{ zKMvI-lG&Rn7Lvoe&!Wj9=)@0b&5Zbc%I6N(-E}ttj;`xA6t8N8RPYfKcsPX`vUBkO zx=2nku~BbrQXxkRd??!B?T}t{OK;YvjBl;ST?Fsuj=Oh9&0>B;`nun?jnYTH&?l!U z#0d<{U+QP_Bwtr#lkUn)Q;=aYKPaW<!-dGPHM6&cJ~L}aep_igdn#kckY)d~1hW2L znV*eTdpo7%XMl~%4nJUX1nDMTWfFL;*E7*w9`KloZHRGeeqsMuU_TZ|J};);_7c~Q zRdd5;q<;vhPEh<i(8V6Y+9i?OCX-ag_eUm^dnUVjDfSG!ILQM+#=zJB(A;y4ck>!^ z1mGdsZo#0KM#Xxr{@4dpZ>usgUUjZDI9bqpnGi*4Ii5Tpt#{t7=&1aT5ziwJR8UPs z*w#dq0?k0FPUToND0Zu)EIaxi_5**jNiafsM*L@+6?{}u0{hg;_tbM)WG`P@uj=V) zdO7=F8IVBg>(igVy^w$L0c~Rm{TLa9H}Z9-#BZ8L-19`fQSczv0V-H&iqUMss@7}o zI;1p2<lKQ%xzC>j)jy6_0QUUab~l~xes><*Mybbuhlv3@L~gCZCl*3W(#V*Vj3<yA z;Y6&W*(=2*tV$*jZ8WbjfsvTNfQi`I7n9(lWCas~;$GU@WUukL4*6|y6^G8_rvxpw z1cjmn{eYSi@Pq76LrUKX3WyW#->}{&MW5~O^UJ~$5vOE!?&GE8icd-vYn;il>>0U| zbM>K{uaxTOkzM5jge{QdWf@+#mB3a4q6&`;NSMeM2}JUj_XJZ*<ge;&);6P^OdRl0 z%2Pn~VS(EH^C%CROg-cG`YcW}%6>OdR}`ZpT6EVSlwo6Qt1vr{?vPPBI{%zfxcP<9 z*Z3-{TSrZxl*bFUMS{(v(DD2TXN)4!PGLzTG25u%8AVgG1Mi*{6rPI<n771J3Ii)g zf_0KZ(GK&n07b(rmE$a?9QCI`H7GNUrqr<<`5GT{_}GQ#RB!y9U9P<3G*!de#$5TF zWf^M8B*ywae@Vi+d=7vpH%ES^CZLZTwM>}WskxgyAd+l+$sfk3KkiLRr6sWyUtDyS zs}|D$0Mz;a+Ork4fFgCI1Mm40*=lY1=%W`pMV+6Uh)OD2o%~q}Vn<>Dp*}tf)lXh4 z5l_WK!}#zTJfb8@HZSTQZ!ZN=zZ`L1W7S#yKFugYs4<6CU}K=0cN8yrm?{r*m#S`0 zYio**&kI|_ZLhZbxTDE-S1+}^tES5#Ppaavl2G7}-q$fF?G{|zI*PN@zu+wmZcDr! zU;HKtSXo<=!%CGru~~Y3RBJ_wc{$H)bkF^o1~H!1-pK}5aN@lvxAV=)LV`wp3>sBu zKYPqRIH>EqvufU`Vi{2V7f=17v+9n?-WPdMveO~bMzq~6M4H*dmL}fjxCLl(6= zZfe6u(b7T@LII1`a(B+dGHGo+OHq~Yo0JS{E-po(?0{$@0LsL}=deh9lB`MDgh7<o zEM8WLfba#Ip3Y{c5TX`%#}k+;bfHJI#bF299rY-uO6)cN^J-6+*B+|IzT7J%J#V3o zGe7P*)ssE-fFq&VERAT-&%e49<ZM}a6)m9V-I(>$sl54T<ftrxs^q9;DUjvsX<*u_ zs~PGwiwH9ljr;%F^9$7Zy8~7NtYS6#wb8*ngAdrM%$2C2#!^e+ts%_U*yS(PN16t{ zo>43GV4Nv4)VeKuRCecd)gf<H9nUp~HwoVMY06jNy0-H#*%Wx9NI46uB%<}cpGQob z=_F#WaPZ3AKwgnhKTAtRVhsEfXL|6bFs7415M0EyM2A|)Pw}ODer-W%lD!+(_Q%Og z<7*dn2q}qW+d9*CE==9i-|ps1%l*-~g_jx5t`9Loexsgwe9!+Y=b-*G$=u+;-#Hhb zJyAJHQ@mL1@Pn3k607VB1UMi7zkm+va<_Q%=$ht!-oQm5b=mYk)xNm%-n!_={L7m9 zPPV+fMW|#C1*_x2jB`BHbTG9oKkT1V%=mc8C5jTRMVZ^}?cel<4R05}t805I!vtuE zY|{(Sk<W-i?VO}3#|fw#K<MlVcrXy1MOW^LQe*OpBFTrhqEwL{`_l=dv$^wa2uI#E z<!ri2(bR>l#+W_Q^W)&!k=IW~(#v`_WWXs`NQX}coV{X{XT83bOAV3Iipcs@Ynf6V zV6h@)EB>kIql+v-U>or#u^p{02T%t(MmE?##wz97IDGE4|BY3yjnVj_;&AeBN$dL; z=NTn+Vk@q#Drp*?!BMiAM`UYHD1z)kx`VPkjjP6kXDn;esv*tqL&RI8gi{o0WJ^Ob z&<xQ3!syVhCc5j3e`dlMK^AnkN?tGs-Y9wXTIc3V%kYtsmFOSi6@4+nr4t#hH~qLM z;zZx+otG@H_Jh|%Upz0DDqM?f^3Gq)H!-k|6LPCtS}op;G<w(h#;|0St-|gUSv5ef zj-wq;-OqXG?Cz&}{nX}iJHz(+>)R*3B3GxOyQbZf>$49F_xyv#C-f;4h}qo~J)i>H z=PTeOEWSu>Z(g{tq?X9~OMX=JGXvw8h=9m#+T)h-m#*Y0F&%7HE!bgq-C{pX{_g}J z@y(;+y?4L9?K}PN*Q0L~06F|qho8OWDg#bGs#6mq_1)WCnYs4qj_u?7U$gIC@*f|$ zI<4YWt-!h(J1(o@bZD?snW5*TVj4d?cvJKJBa~&>?CePCr88lh98JwI?o&54a(&kU z$EFUs9U0SG6VZhPxIMkh4R%6K#%y9!p_I{sY4&p0t%w~nce^lC=vY_f50%YmtSmGe z<$s^v8<hOCK<oO1oG09ZNpg0QwNb2cteTA;$30N6QK)zzj5%PcVOiN!>GNe87Lt>@ zbq<}9N$?0sq2=q<oGvSeVopdwuSA^Q=CM_&gZWo9Q`-dan8JO~_?V)!4fi7#G!j)X zk-y7p<C|<2hLnrjs%x>qy)<qT8~zQF@;M%6bRuGDn3D#`s^F$PT)(V-thZ545->2M zl+<?TT|v@~=K>JlanezYZ+4%1*Te8=l@`qL-xR?xwPbFOCiUm@kx03c?Njg1Ca-tx zyg$2TQ}<paIfy)JzA^jFOIPIwvCsg4-SlF}(q_FFI<>Rqg&Rm+KU0)zmDirmUM-ox zJ`-ziGvVg9lD+@5WVphKa3I97@3R)d=9NxhfO*5jw{e^+c2vQ7#L;TnQnOntWAt|8 z#*x|xDXX{($#45!Xq@Js_!OQcVSBV8doW6w;-*=Qqnti5KXQrYbcU;(4W=736~{)6 zv^1ue)?%`lgoM^(x#jIi+@cMMy*(>qwtxhDbe&%NyB`Pa2e$P593QL%9J0Ol?e$3! zos(FcGDF&p!|qL{v$R^bv!ITL8lx~u>u))3JwH;+E@=nFcX@n#9rs4_OmfGm9gJo! zDcwzXgBg26`&Ly3k|=LBCut^Kt5wR`XA|q`sGl=aKC+>6KvMVN+O(uq)#trc{yJD| zAF~UC6$gy5HBrOJuXchMW1BBl#bzxv#51I4%gx2Mrh)Gd9MnH)_2=O3{?Hm4KTWV! zwp~Qv?{<#L>@SpWn6c<_{7j%B!W+fZYG4l(v?O!VUOxkzgPT(c$b)->wC0d(H@kwQ zLvJXv0b;g3D$!C0QS~>RSaqkjKWg@FaQ26{sl|%YIF5ZjdoryH!X`kHty$rQQ(~G< z22qkv?#pO4*_Z-0U{3Yp)ikgI=GWj+NrXcPV<9R(z+?$S`R(egT7fLy$#hZpUm3?R zoK{pK8ZYj1zW9xORJ?+apCbcwH4i2*un4U9YoSL8kq5D2E;!o08gkra4(ZHLWZjI$ z^gJ@OimE1J!$k!X_q8tLX6H=+v4ww6R`14)9+80zdQBl~ddPYy<_bL`h(;ycq75sn zVN%7Di{hAY%b41k3^iLtTW4mJ)REK0im8MFbmCEsq{_G(sqvG^--guyjch$YCnA0G zvf3O*KXupb?#kuK)y1=PgS*84OQzv#oEfM#KF26E37^~;O$GI^a%&%7jIMD$)6>Y6 z2-V7>go7PbrwhwaU}ZSLQ(bL=i%f}j8PrCfOZ4w-nrhmSA9sctd;1^Y;dC_{)(@za z-o4ofk3kKh*cMA0lAKm8g}piMDijPDE~KFcrr2f|uSk|`F6`bsJe@3_LOQcD&N7yl zLY?vt2HhV$dcEoya08F)9Gi~60d`TIql_PNi1U9qI1$}n2A>w5xX~i(qF$0soFemN zjlvoFvq0w*iIbg7jnBB$N{v;Fw89NLhIa6LuO~TL{!)zdX~e3_<OdF7O8~li2kG!Q z{Z44E@X5y>A;&tIAba!ppgB^`O|oG;;`VXULA#9Zmr>xu=%=p4G}(ac@CD^`@K?RC z7WXa71C^r<?{JCf;y(5LDk>LPMtV?&RnLO^wVh?KRTj1=mr7Uqx$L2S3!9Hq2VMKU zNYs4HJb2-u?zxEP;~@iKhaar7kO>FZuz+$1zGusdDr{79bAEYGqF*vecnuTKX6U;$ zph+|BV3`+1k+K<ecVCUj$d5F9v=amDRq@juG=Pl;0HsQ1K}XjT{2u?|gdU&mUvj&m z`ERn4)R*iRc~zu>tO=q{4|gOhHYs20lQeeZVZ6CIVWjZlvNm`W7U&(_Dz~9?&xbeY zA^Ahc?B6wg)0}C?DkKBN1V~@Yf|WTwcpKUQQW!-JTXkDXh3L=_W?vb9AIVjBAwZ^a zhOJ=}nXt>(Gh|ML_B4mA9OTXK`5*g$^Um4l4gw-6g?|?Af&vgGNOgKQ*;7YefurCq zSu~Ww<IZb`rIJ?oAo<>!bD4Ld>Jq|%p#@Y<))FZUz1Dj%n!oX(w-vHQPM6$n3GNcy z9<r_%go|MpdrWowrCj6hW|#=|xO@9@P1}#$-;P%=kCLo<Q5rikJE&JX_@QxGOY?lM z(4)dX6_cWjo)o$|p=Fywd+im0Z&S-O)9Flo8Zrl^tI^*C`%9yFpQ0WclJZ#|K=w<Q z4G%PHY9x?LY^q(y8LIcoP`5!>k;xx2uY95O%d+*5#c;96%69f1+%21!?ZM<|sm;cb zoP*0GlZ9QVmPwVnw9v>;`Th?7qVh}Y@@<;dhrzVPiJ|{fbT0l(|9=#p-I>eW=f1h$ z&Hc_U?vcqQNt$bjLaw3M=6;(?jHJ1hkS1MJD%%J}O{plAYe}kwN|$eb`~3-@$K!qb zoYy(e^Pz?P_IC8m=qI*@Yiae^m!_xkAtxI52>uMFwOvf5j1IPiacUz=<YI&k4tIJb zM?tktu}zKDBCn3c#;1JnDLIg!t``2*)oOdXyrP<>Ggb^U$ut%7Tp^BsjUBbG8P3xc z6%xRyD2fkQg$_e(!;^f9JSq(KqE>2|%B1dY9t^@};*F6bMDXdae-;e*Vuc?$ohCa$ z#AG{U+5+WB)V=F&UHO(-VlJ|w)OeSna4~23+duC+2cMcR<W8|I0g4xkWr_$g5t*h6 z#@1<xagreiE(Wa+jh@eIYkiP_;}DEF$N_9()OO;L6=eL(uH+zDcmR;W^;bUz&M^26 zzm9bO9+BzOuYO!U^IM^)fIfC2BVW_h@fTTuh!WM}h<*&h-Xe){v7#x0*&i87qKlZ( z!6^XP<@P;>GO*)Vc+4U!9Zf^YXQ$${2Q%ceTeDO0Y4>#G#)@)oYr=t6<a|1e49aa2 zf@A9TmoT9he<=DVA^wqk7LF7inYFTrI(j`>`7T>bKstPl6VS8ZA2T5LNg`DXMnAxj zCva)JLfiR$u9u{X1&L>#Iy9J`F6@W7BJ1WQXCk*ROC!xhI9B)!E?=b+aW5L7dUan; zhUhgMLcUn@7g?l?=cbI35f+M8wh_~cHPdA8x_$MR@yY`m=7DVi@ESh+%Yt|-0Om;s zCDEy80MKwc%xoBFm;_A3!6h=16HMU(tfJC~<lcb8>4F3=0Gfxxeebj=WFIEMb^Sq5 zG9CW#<({A}XjgRsa~keVhj++9?TX^B_(6EI!aw6xgVo|6$tt(=#NU!^o(dTbUJwhW zN2DMnI`be2Jm{vWE%t?4y{j$Os`^v1ug{8$7car#2HcYckNO$%jVyxK7CCcM<O{)1 z@!PR8DEBg!i1u<`=9s8Y;ISH}B$*Z(`e5G?Kul1p`vg*=Y}h`$K6C;nJf-12sU>qA z0HvbOT)zlChK268h1T)PzL0i>QvhHbQiO!|&_P4HZbFZ<U?)l0;eN@1ongoM6>2|| z!_q4AuyGKXN;1zv|7OaES-9~}n8G$R)cl0`O>zN!zvWG+{xw3EU?Baxs(P-9v7od< zQmOy|MsTO5@DkVABKvWw!qEr`1+^1cwL?X=e`!rW`y(zwBER8%b8f)BNSM+i$Zvep z`@@*Kq;%O<jKZp<e41z}E;L2cUF~Y7kKeJt8p#W|GEMX2&ei+AJrKQ{2Pr5L_3$*C zBn#h#<m;u0z9I!afmfJ6gHZ)ELl*2X338ebrD5StvJesuWCVbvpkb{GkZ?Za=t9d0 z(~5Ye&M~x3%E#T<urrW%C>_Z<`9%ga8&{cMvu6#?D4|1+W4*twLANpqE#IK}9l7ba zLRsxbt@YeH0Dxw<!HxIuZ8WSb?|jM&HOX79*ckMSt4%-s627&9v%A`P4_tb;>_9?( zVrB?Z%-L7(rIU5sUmVErcasuRuUq{APn;3H#?&fmkVxPOpZrjIe;B$tnm-9hlF$_q zbf?g9+N+*{QAsT)Njfwh(2@kwVZp^f<v48lj)F)y>%7k}P=f?AWY(t*CsQ#rLT1IO zVaTZk81fqK-k4Xng-+#q*B*bEWGVi`_#Wd7%PefwfgOeQ5^tS4NMlNs0S&GZ-*$OD z*IH&*+`&S^Bt*EBB{GmC43Vuq!D`=Y;d(_u?R=W+mALAi8Q+{dh#1gbR!fSgEzyH? zcoico6CO64R_a^o`Hdyr;h|-$AThy05K1%!3_{(`(wRs^8!2q5RPz}RoiY;OQ6t&_ zfSUTt#cpba@~Ls(;5jUK<uI%&>C90Uv<59K_DrOe4B}=&+T1Vx=gE5O0gt-`JAqfI zTQn~<>lafDI?jg$3t#Q}3A;YhP-WVB?qS^iWvF@``NVVh?fu<#QgBWOfszN0UhB3! z8-7vHY#}4={7I>qB=Ou&;tfuCIq%es+aiDP?XkGDIxaL|L3I+?d;Yqb?fSJ&$gUb> z)b+hOQnWwsjE=}%tlJS8DZOWYb!ZXgH1*-t=qCrHP@9PMu5+4OrIlm^`F&~4YUf1Y zIVLaT22S|NB}5cJjvRg^+)R!RIGmOTJ4S-hU(2-wz=D54iiY83npEM8^GQgN4=89% zTtO%kVs)W~#)PhG=|s3%9OpynXlN1%dUekoTMyv_d`NEFr3ybdnGW?|OHq)4DR}K~ z$K;Zc1Kp+r_6_k*W^(NicPXRd(@{Qk*d9GA>4BsJopY!DSi5%DdIayW4Q8oc$w~;; z5x_^m3Cx4CQhs7>l3&61WwfF;Bh@E)#?Gc<={K<t+ub)=@Vl(K4v$^4vt*I9k$i=3 z!FxG<`(s2jS26G0%5>JiRA_}n5nIB#A`TmSq-L-qN?UGBHjECP3<kOIvc4ik@BnZy z0CoutLr#<ne}I$^!z1zVj8;^g5d8HAaX+3o-f#q;0No)$k{2wRycE)zDA^_mQ!(CL zCwHb{|JVq_hcEnqFEOKZ_s|gWV1m;0wDNx}v38#FAF|Tcu*z$CL>gRT00-H3GtI$G zjs4>8a8vQHof<S6?L{Vev5@zX!*I4HxySgcnV_#C41!0jQB5XUe&9(_Ci<K*L*nQ` z3fQ6V+kkMAeV>Gbln1`F0CD*A3)%2+8q%E>E94auzMEaM0I%Z1sd;CP;uJd<vc3pV zs5meY35jMxP5_|(SSSU@DhEIXY~E0T&_#lMMk78mMV>lLJu^gHMMKXm^q=B16ePjV zLmBzP&@6hZU(V1(k0LS#ewYa|;{mPnK;8={Y(9;C?=|?D_v9zDjk$@q%@*56i!WJ7 z)T3dgNe~$`Uxp>j@8Io2N1A@`_l2gQQ<~M(CR76!Y=iTV7Wr=V3-_LM!+((uwgK2G zop~C`!YMK`gJ_YKP?@nL=(~scV|l{AaEM;!#QtxH2BgHlN71X$hsQ=la+PH6;Gl9v z+SEMm^x(r@Z+IM^>BxYc!ov9n`mg=n72E^`(F>2FnP6NJ#FH)pwieuKU|}7hfIQ(` zz|^HYiAb@RmjF{KXc5Ufcis+VFE+yi7htOngwsinJD||00fH44C;&Da@qj91&`qY* z579Z}5#^g#t-h1!H~qxuIEfxQ_%a$6J(l+8=cxcd`p@vDts}2G|G@v`A7H;ab?Bx> zP99jHpy-Nh>DO24*PA4jtC8s+BsY1|8bZ<95mJ`tLK}wQUXsV3kwxn0656Ix`q$63 z^N^1(n?*n$Qgz-C`Vn!%Vblf4SJ}hC-{n$S$%OIP*<fZiGCLaw!O;aAilM4@P6!<w zkO%f7LoJj3&oNFsCxQj;YD9`n9bt*2i^22h3y4$r1I#$1*H`m@jkJ0(_9;UHn!T-F z4wWQ=oym~HNg$0p_!Ff$t$S6=ERp>rVS{_ZQ46PPmm_jfV~2El8$qY*G_H$G8AjnC zif<5r@u&;ryxPvhUO>h@$4u)I(b7nDGVR=Mwy-4Xxbag&(2LU02cm;mk>BWH<0+X7 zvz<(U2zXK}o<0~RDVIA8Sw5$IH3Rm~y#M1=;HN3CWI<m~8a!PvxFJEnugOd%IEDnZ z$O8w{!Mt9PZX~2k71E7<d6fwt;475V;b)G0JhS)XnK1ar;E!S0s`KLO6w=2wr>X*g zULFr#+qO<&?XKrUdzZ&qeJ_R=3sB%mAfF^~SsYjc3$2P<x-Wj}c(HUF3%(@z(IF-h z^4$dz=sTo8HYt^08T0CIE6<_D*Aopr^I=+!U>{2}_DpwE(u&r9CcUZ^Hnb(_grC{( zhZw{mUS4+hUo!bMY`VYCed~oVlPPhXo>BjIShcwGTT9E4Q&*m?L8!wsE?v&YCFQe` zsLOR-sz-tnm-xq$;Cu7R3|Wu?k}$q`EgE}1Itj8LO%(vHT}fa!=BB}wO}*n_V~H*7 zlTCBqEj$Ul7q?}p2DZJwiDzxOCxJ?G1$z)&$oe#Y^T}}Ewu05QXSfZ6d+>UehEQM# z^!hI3^3+}FiO4A4tD%P*y`NnS(%Uca5PbB_Z>$=XHv1E>yr`QF?5wAn>R}CJvw6K| z8xKV-|AXJ<4RdNF&gLPuTg0xB5Ms^e#?Zo>=%-bzFP&@B&Tn_-=3rsf&Up_Y1utge zTkDVB>-Vvd|7UKIOo!2u;B<g+22ePM_hJVNCJ1o8d0-C`lmr0VeBE?7zvar>8ho<l zIt<p|{o{uG%e}IRPXg<o{_95nJGT1=cNl1f-44uyyAOZ5cW?XUed26@Pd{3;{*uxh zAMw-*VRG{O?;|A32j8dOHg&wY)}}JK<#(^`a^xR8BFY}IU3OD6T%_zL!cG|ZO?P*? zCd0b{pVj8Q`nq7URU=B+b@kaQuZ<gb-EQ@hi^1Gz*+gu~!+OI;r-EO&kjW$Qn1P($ zB-4Xgel3rDz(>_zKQF3mvBwuYRhSt?wA!cD8Ardmc1hKe4FB93@_hYyPbMF^Z+Vq> z)+XfVLW%T;DJ8F*R}=frbbBjk?=G+p^mqiI@%f4nkvfm#hlfu=WaGhZQ(^d1(yNE& z8~T}UMZ*?m0dt$H4~sXt@U&l>XFUtGbM-LG?ve(FkCo%Lt5g89{n1Y@9D4mDasF1? z*Y|H;|2)3HPJ0bPmZdw-{)r)$sYoDdyi%-^KWadynm?Twq2r&uu|IDV(!2HT-)=6V zX>0aM?KB}wRLyE&spR)_gO<xa-%hI7$HY0CyPy0uT0_~f?{aR6B@`<7#oHE29g+#v zYxKJ?aiL*PKzB*wo}`H}&AQ;~Bg9a6Gqf=WeJOh6oN~<(X}`VmN%9u7tKY;O*VZDC zo!dOF9=h>1m2UVH?P8!=8<668S^OhG%=s-(U!wnqO_`MY3onS;%@=TLMb3IibcLn3 zPzTZiAr$3f_1ZxbVX;d;vDfaC=tz~tCg<prq3soeDgszCl|;DDN)S_W(`_w~@>*Lc zJoxW`yN#E@_3eG$=FhL)Jbmm@hgHxlV4=aB$#AW99cM<`Z@gkq%Z+9}9TVSmx<;Z5 zZQhfnidaQmmKAd%r_t(t68be;4*#ZpK>hKab7^TzIN&OCkYT%qhRWZLRrEh86fGmR zzp1c(?{@2iOpIofuuPDXMO;&4u-{9}q0MS=T~6klmYUbe#+%xv!Sf_}<D8*y7cFk% z^gRk2pH}N@YlNjp*bM@}5e^SH)Q1CTg(#yyLM5fz7>JCLHTP0DQDOc%buQZN>W&88 z?r4iN9oL~)Zqkzd_8EdeecU7RQ2);oOethIzewAuI@Q0cz5Zl;x6$Xib0=fWX;vq3 zmsXoK7Z|JMuD92yqNc2~pgX}wasv@oj~_k1W7{<g+)o}I%&s&V8SHT0-E(TXO4e_Q zJ?gZ(WV_bjx_PJm{y*@IHHN#K-GvJ$t!)LC57oxFPMC(7USr%!^2*_ulXD~U8QGUQ zUFGrN#FkR%1x}^XS9B?&EhoWd9CH`F98psC1ck&7>AFPdzX|559EduwM~)1FlV!8s z=dDyV+&MBpw;SR=ia9If>2k#B*-L+<318|Y$;9qa?^O+_10U2p|GRYZ^uIqpPd`gr zlK^lt#Q@zxXTyhqfQ4c)ITlG|Po0ri&QWe!U;EALt$0NL5~wHT`i-p)Sa1{*s5U%s z?!R7w<alY3hRB#&2uocRI$hu(piaM<CaIod%~NDFC5+ahv@F4pU8DIk5+Njty8J{D zVbW4eS6f4Eqei*Z>RVY2-B@jKcHHafsC52cik#WzlCg-KjM{3KZYbJC@$?57Wq~O# zgU9%$9VBbDg!c-^Ak_Y2j#+mh)iD09YD46^fL;vhaBSnxupl@WPRX(Imqr0QoxZPP zM87Hppo<F?T!Pv1zJCtu`DA$o{BTobU2=E4T`hdHcu54AI+FH#7-Gh6rCiZ(eVZ~@ zC~{-UzV9i)IJ{HU2!L=*I=g5n*Lq&)<CxQFbEMf)E1ZOTgdX21(CD5;W;Nqol%(M1 zZH%fAhoc9tW7}-qbzFl`)9T;X>+f8^xP~$)<x6G|Be&g}s>r_xg^59$A}^LzDyClH zd~$hTsyo~`brE@Np<ShCMiZNwFBz@3XQV5ob8jj^w6F`PF0D|G{fqahOz_8CO)B<$ zWhj}<=Y(PBbnenHqJ;|`7!Dow>wp`wm=CiTVR&_D2VM#!iYM?Sm5w1J)anK~+J+br z)9w7k-0{6i*Kh@)eTj(+80ty=;yoMue39WLS@<*#q97hC`y^!4urj|alM#^)V~>`d z!jvd%!W0U6Je~BvA^Za*HR@Q9Pc=fddqW?qZ)Uof%zxke*pHC1$)eeQwYAGlSUO=) z?QS9`S&MppOlxj<q>^F=w?noeVq-N(DH#WMmGoA{4|Q<^EDB|N1N6j?CGAr*t}k*V z3Ez6;^X0*VO{n!szA#1ilIKgDxLaRcXZe~JCL&~jFc@xT{iZf-o~*mqN?r6Yyc>fw zh2lK~|DB!3b3Yq23kZqQEVhdyHo3q&m?L?R!AuV=Q2lWYCUz(E$(x~pf~yzKh)NqD zg^i-2R?3l1J+a|M+2Q9a(ICv}Rru}SUWOCX9VKl%cgde6<;k{7#PbE7lI||PT4u}V zI?RvUj~Ws6w@4q`2QF|rsxIOA7s#y3J7lF<4e8)5inBg*2)QpwZ@#o5;`me*Y|OOg z=S6Y3EpCIBoR;&B5c1jOKF|9}W!RD3{A@$V!-`Vh-q=}k5XW$$I$LcYEO+KE9*;Fq ze~X3wdb@wREGG5X<5qEiH&xbyPE}W41YiEqdR$(cs5ZQO19Di$al<bL`dqQcDsN2E zi#MP5!yK_^{G$AL(hE7vhwE|I=+4cb3sw|UL`mpnf>$}xmn1kbKW3)ttb=`+X(5wu zw_1L$=?u}kMly0=5XRO<%EA*2b2lDI)?D^93$2E}`FIRDbBU;YrF>O+RdUk%6$sq| zF3!r3kvMvx&r{&Mg5)g8O-JjYBhs}Uo(Urlc!=&*d2H_Z$JW&T`y?uCvB~X7=<?58 zfuGV(LU)`kS;<n$<_z5M{%J(rz5MjC+$_M_sUxt_i%ji7PpZaDar%IEpwmB=)y9Rg z)W0i^o5o|VoLO0xx;y^h-ft~z7718JtdG!n_56HDsNBGN2k7m64a-ly>}U&J7dDow zcFh{`?-y^KkbC7*XOSc%l{#!jFRdvghR(F1h!6L039_rlyalG)9Ay#qdjJ+EBosSk z6y_)Di+WpKuqHAkWqc7wdvd{P`O)u90JP-1ggJ%bBCBqBsp4YT_rHI}97C#pXAKuB zu=+=l5AzDVl7xCs@V3)l(V?3pd}3>*t?Vme%c4@SsI1IADdT*@gKIjfk2?wq&vi~c zQrUwa8w5x91e+Wj&y?TSyX$II?MDn5XRPnc!wqy>tMb1vPH0cSv`@BH?JXuKeQIda z42s$)?lR2c_2=wBg7{W9?4d@Pv~(q~5ecMv$^N3QNH>d`_3RFD0cZ&T=Yj^V+Bgu& z6i{%H9z0KS9HK_1XcrIIerj>y11$#!9+|6|%u<W8ZH7o7>xD}{O=%`@>JKxT+ZymN zlKI@8pxM#1w_3~(4YS2jT!U#AWQt(nU2bBoqp2d@O!AyX|3mR@2GxSW>g8w+T`l1J zx|IpIJu+QzPZ6FUUdS(ljoLwv*Azu_X^mv)!wHx}haCf1P|bt=v)2hqDoIyYnQXhS z838{UC+xY)Fm-5#PQ_QtV5nAJ)OHUM;e?wuud3~C<1~e6gMX+tq`vne4uQ%;xseph z1)6X1C<vbC3#S>vLDrd6$|IoLpo1-58jBR&T(AAHh;P*sW!@Hb2?i0df&i3TY_H5| zwD><e2w<F+rdyy$0voMSjn}SO@GMNhPB;9{S|O=X>(q!+Tk@jPyFH*Le}f=al~?gS zOK-ylM!~+khSD8~mrb>aV#9!aVHLULuf|9=ML1}!?O5aeXsUYLCrB~;j;p3h9O4or zOTIhON>0xxcEE!%F8ugXNgS%cDyhcEhSrgJvrweekvF0tWZXDZYPLl+?4mjV5Q0lz zw`F7EDzlWZ05l-O@T~m(^n8FW<zN@3V!E%v_B@u(ezXT{X;U6PQfB{Jv*eHF<POjm ztG~p8#h1HXHGK4z0Rq@S!UXKoV4ArHRgg$_g1cKVE3YS?5#9s3D<tP+b5<(l%<YNp zci9HPc+h_=2-_B#V(a{jts0uwYyk9V;uS=&8?u_z{c+<NR~s_XaytVa#WaBh2fD|G zn!~f2nY4=G!E6}?S()QJ!LPJ^wfsj*UZ_vdEG_9k$sshzCsm_9N5k%Rr?IrFmMz$) zS-0}3$oYiFtYWGQnPP|oYcq^};Q&x3#6L>UGGF>|opg5&)r~Lxcz3zXWrt#oeZc&N zM}xJV-6{HIw&z##lX(XC6prG~q8Sc?KIQEZ(PugF^&8Av?@V&8&pDdTi2L|c1|L?P zKYLv<g6hgVch9WAI0Sj|lcg8hKIs+DdB!6(gmz#Y7F}kg+h*mz10n59e!p`u2L%!I zCH><X9?R|pVEhuzb)sT#$az9Nk|=l-I3u#l8Ysf#4Lf#q-R;qEM$wG;AOdMLAZj$Q z*V=I$s6?h<NmRYT0;$3L>|(HGEc>E`=%r@%Hz}E)l8Sc$RNN;$EDGd;q&-4Q?~_6w z>F{-QCH!Tp#m|7<0DvsAkZmvood^ORr4ID(vA~TP?b09F0wzU8T6+n$rr5Jr)C+!% zSM_Dr$KL9W#}|f?Xp(;PI2I(Q5&B$MeyYj2v<{}!1j$_}kb2Xfz=U}7in7+g5(;LI z8?C&V1t-b!mk&B8X3~DKz}X^q6nh}~1W6|ngSjTD{+|kyez{@uYU6xRg%HRN0CvW? zzE^y?qQ77N(oI7ENU4iLn57!V(oPRT@Wlg^Pr$Fg_u>ImEb57+nBvc5kO|4RwQ(;= zk?Mi&oE?AWcxd*BVbOn-B7<RyYZB0|_|7{J)rtwcdn@3ry~J=c+Eo^$wctp;t!0)8 zHd_Fi>Nb1rurgy0jN+kQ#YLIHU?&;K>D@*{`@h7>VX(92i|@~1K|2LL#p>OUV9y@H zqJstB|3d1&z~3N<!ZT>tuvJCxxa34h^c&OEr#?K-bMB1xj^WGm2f8|n9})Owel(Q5 z4Xw`xocjq^wp407OHK0u;{dZ*fjrb{Zc_a4>&D&@lp6;Q!XanzreJI4;3I}$eL;50 zeGAXcKi~3?-+<0yA(}h-gOVUa0N@+C)rqm^c1PtqY3=~V(lE!?E*50GK#82Cd9ivT z8ITZUKW)u23sn*}NGbyqMABh#k<ckKh+I#gE=Aa@3vv<#$(gtjT_!9O2aV<xk&S|C z$D#S-u*7j#{Lu!5Gi_nJYqp7HR;wx+baG+N(<0-pgRSt#7i@IZK2q#;&3jlHO*4|> ze?2Rb_qIemcF3%C=>jPUmKlKNK%(jok2;X`&X!9bHWcj{!aI3_S*Ry1o0O;_QGC8w zds`@SFQLD@B9sme#Q_aH=G>E>-rJz2nJW#7jtL`p!W3CoqaKT-LvOPW*{yjSvZ}Vt zm7`b%?nwd)RFPK~Eem}!r`VFVqTC@{u(!BqR{0zw37p#%<~3Yk_}egRK|YFC6f<6! zFkY0S8&Nu<6T~Y@950NCg`N_c($_xMbwZ9Xd4m@)Uc%4`{7f?`EU-cj6vU(6+3s_+ zsVNtB{o5(xyqj6$U^D9IVV-hs<$Wo&0O4lM5;7pupr<+-Ca9BT56y4A{3=4T1~feY zlq+?3l}OVpi`7WKDP_dF$iC?3(vPyoqXFmwKM#sI4rDef>2i7Y)(mj)uj8PDMBlp7 zQ&)+XfiuPnK&RP)KE!>M+i#{OgqwEY{w(nJA!Jaj{F9m+ISW)-m9EVxXjJgB;aljJ zvZ=Unm=)PH9JQQ4D$K$b$bRpgb}8J$5U>xI1qb1NUHOa<tFn1g?vBz%Mc6`G@u9qW zb7n+LY@ri?YPTb~BP*qh0qfwXj!7WbmYX*c-&LGku^C3)I#hEN0JdD9giS_)j0XvM zdRx1fsAMqsjQT3Wi>AL|Zu!0J?8Ad2KA{HaYo+GUg6q*2!mdeFils3?>Vp)EF2=Oj z`{_<<oz|fmh=CD<S~|5ja7(t2qvdQRSIGj8mD_1Ng(RC7WG+x88=((ur&L};j^FmP zJJp-eRS+t>wjN#Jj-F1PD0<Kcvwi_JyYRN)OQ0SBYFb=m_!yelwXqHn^tRpTIaj!c z2gyZGi#AR(JPeakz<kG&J%T;lV?Rfr5=pPGt00`2AQQn%-b%G)d(E-<<DJ#VL~O0s zD^SaW0URK>S>M;G1dsm%!lE1n2R!x6{Dqb;<z)p1IN-n~v>opns;|-rF-F@pb$WUZ zy)dBkc3IqHwu;-vHSdxem4Vc+6_nuAqain@TE}yez$6ANi@Y{{i!R!@Vci0)BireP zfV~(+C$*O!#w0{7P&1Lx%w*bO9yGcuLG(B@1A1rkzq5udg;}$-$$%R?+PI2XR~&Lg z$Ew75r{rB@kb@AFI154y;cmF9mekZ}{(9$BdazRJ7%HHaufG5?wlQDqbC~`}^RIOo z2llueD=wqHm$Sfn_&(VIMg|ks-)_1p?MY+N6b0y5);iu}4i9%vRwlv`2k(@Jvu<|^ zc(V6Bi$~V&N;(RTmKIgzjU0F*@5z5Zc_Yxj3j%owJH*$1JOK^e9j7OfHblpccnLJ& zSml$9LhHT+GwtPdE&1Hx0v|Fo9tjmy`~D~lu4<qnapi+`-+f)L<*}!*gR{kZ$8Tp) zguNGlXXazyq)6TBNnUnPwMzmz@~Qr*#$I8@AD*_`WY$gu*E)}{=nuc9m=E^Z_&YqJ za@K$@3<Z%FwH&0c^CPN0Tr8S)jJBGRdf%k|VUhGKx)w23>_uI{V7@Rwj*LCVD0i3d zl<CV#7Ig5jtF*k3z+YeF<obyr7o81*RZ=To`H_;M0m;jO38KF?L{Bd#pp$&7(sF~7 ztZxW>--THyNW5fWB8v{a`Qf2e<nTjiMyX*g13DU$@N@S>FXnZ_-ods<zXNsEL6!od zV7xVfPf_VV+{3~hyDV~ffr1~l*1t9Ee{H1{Uu&tb*?1u?8zckQR)g;aTW7v>Ui;x_ zN?Xy3$78ZPzIb)+&A4&p%3f1gBp}a-obS$jw>5}0w4q*0K6K&yqv^Yy@0NiU==Z_l zq{r&T+wJh&-~xMP=P8We?-SsIi~>tlT}E-M;jyG@SOM9;Eityx?+HJF0dw!7ouFrp zUf3wR$!DBDS9yfbJI+re-HzfF!oDR`J=spA)26ELXFr5K>!;ZlzI{Ff*0BM{`~1Uv z1fu`bFuyb0di=FD?nhwnzm)4M@yBbAeEm$>Lo?ou{qe|O`e5@y&ox&ZeGo?ueU$ly z+PQk;^lm_#TROTxaRH=r_@+}P?cnchTQjA+wP!jNIIW1MJWuoDa(Ro0ps5s1-!L8j z&6?+JY2{D*bE;0R?$O?NUe|AHyRq%e@sN8VgWHzRv<Dim#%=4CG&Y#T3@~0@6?)zv zHe*3*crOIe_tz#xZ^h<6{pm6Lq+?G{y#ED>nG0c+l^^|IY{i@Bju{ttTluWKN*GlB z-WKhpW?r4{`rg0Yt*XT?V}0kpJFtpc{3$+qZ*Qh)q(e48bs7ZsZMLZ}v46YuUJRp? zj#~W%g7eg@t%kvhmrs6Qa|s{D{@&7|Z@jvZ2-=MYYnQj;C^?{AqrbiyCh>~GUVS-P zXWR-~i1HQ}W}UMEeUVT4a_xV9d3&EKVRFjh*XH{t?Y>v;-EmI$s@YytFA<e@q~4}0 zXeJ@$Erg|0S_|ajkTb4IsdUo{-Li4>3Jv`UVwvu*m1kvoXA%f6Ee!LQN}V|HS_$p3 zaqhIQV|2TZ@9!wHJz9)n4R2qk=?)3w8npQnhjXdwb^8K42cK*F;t@r(!!5To{PnaC zRB2R3f&6Rqf}WRSe-A$O3{f|&^>L^lZj;s;@9lh1_zYVsVHmX_i6WnV^Ae)Tm~L#0 zJQal>!xXRj=|rCSJ^@iFVFfjb1tK55iZ9vCtajBXn3wyQSTeils{ZiTjnI@5@KX;| z*!G1>DTTCe&{Q5~bJXZ(@5}C<D;&k1-hrp3Z=83@AAA+fit`JbL$9&r6%GlQ>?;4g z(Si1#NScNzgor+MGn$;dTB>y;X~f$kVWf7_c%NR|RES|>L=86LP+XZ-Z;o#HKF2AI zQZ2iy7!k(+)71cz`VF%xtJgegiNTgGF*-;<Y85fk5hF?%UnkYpjrb(CS81-_b9o-D z|JY{A;Vi30&iwa`nU|AV&HVDAbkhMJwL{3I{bX9l;wa|i?4nLgHejisrC6xOJ(?(e z=vs7Uf*V{uUh{TSYnNVk2qrtJ-yMBz*Rv^2J#;1c<MU<_`T6GuRxr(7g)55?^^1y> zan$j@1A8x@cy{RKn~dd(bMx(*(-8T9*@l9Cgyc~}m4gZRLIQZIm6mgeS1qB7I8FhZ zO^$;en*8EF^}h8R-dp8RmTD$ZJQv$pu2r8|tiCQ=CG{RVKS}h|-tw;XIq)hfLd0?2 zfhcAP;4Zb^!A~rE7;TGcI9P5COPw)$7~0w9^eVvRi3NRyn)LnorxTt=1|OdZYw4Un zJ5}k28Q3fw-^nTZn=#)2#n^soo>l$h{2tbFQn}6S*HKaQFum}C?UY4vsUliLK#N=v z+IOHf03+2}=wLxe2uFY~+MR*CE#8d}2*t|27H#bwTs11t55*u3jEiT_k`bYNiu5Z% z?n{h<JhVno8^S?<Gx5%FJV^Eiw#cY?N&YN-?4AHy7{wsS8%)3q-q%P(vDh+gWC%M? zy*z7hNy@5qM1yR0H*0N4V>=0I*(`+h%8O8)z%6Tgn^q+*OlLhNR~Oaz)f=vIQ@K41 z^R>lN8#zP0y|&QGwN}yO@ntEgJ0hg`R8jX?xb%fJ)%Dmm(W<<t=n2#T?Hhs!IdVz- zVBTEhMu+*oZ{A{|ED*Y~-dSj$ws;<is)8JBA~2xwrTQ)y1`dw*CLIkc2BlcQmBrK7 z#SUX#;I-{%t<ePJ?!_h-S?zp|9L2nON%>;d$_t2s4Nx?U2~-$a0N+mzM}#a;2?98I zK>}VXEeUAw!?N0kM^O7krq*XxmmgjHQnooB;fMoY@v~7^dyabGU_9NPNaD&e7|Ylu z_ln9F#?sqs5UtdHH!C~e%-@W$m3214KY@^|H@a-qgs<`=Q^=5Kg-&kaSC5HCDm`Yn z8>zOcccT*Yo?#JMF5!rinfnZ#C3W2&Mm5BtiE6P6K+LP*0xU8@A}vqrz$339d*!9z z_^wr@5L=v+Y?4I5PBc*BO!2LMn@Dc~S*%7u51-2Rn@E0t+-B{P9%-N{79{(6pDZ+; zL2a%%w`&+Zs&F7+`!XVqq@yy#f|y)e6o)E;Rn}NYV|q9ucj1XjOg@BO?h$&9?^T5h z7fBqCRc)t(WmP1lb7cz3Uhgzmt>+_x(Cu;?O=J9RNr%O`I=R?Euw%>ObR8i>>Gm0# zF8P~%T|`Evbt_F{y11kv3DhpwjE>%HXzom^o7B+<Rtd?_?1`?L&F3(q$49hp^hV3a z@eitr_rshSmTZ>GBxaa|!p(-C9-L|9ZRTCHLk{F;{uhn)C%#m$;#|3kxsV`LZM8x( z8fELb$k}zyUOU4|qzsN)8ysC$T4n@oBmrfI00T`z>S9r>CuoN~uwP;kh=2tUW_Ji( zl4x^AN_hfiZuhOGB_5-?%#Sorc;qIqU8)Tt-#Ijyj#pA_h413rNkt9&Ua>hc7mylT z9D||o;z)UBFiq=$spt_0jjG3wmdy?2WJ!5TWqQ%eW{NLLe%?0L`|SZW7#u9=(v7~i zKLYaS;YhiKPo#JN<5m8<QijbS`?URvg6i+6b?ddO;-NNZQ0E04_^~BotWm5)&%@h8 zxJ^8KoLL&!jK82|MXMkaR9`%}p*N&{?BBTQ^`6AUO%@1HzVPkQUly0x#m40<Qkdc| z3-P2@M3^9yu6q+sTH{FFwej@JW|#WSP}S3O3e5}i#j~0*ZQo;0n5T~HB1o)9vg)#$ zs<-e}!R0{tnOXN83)8AkH<D3r*7P(P`IW)SaTV$R*38%XCH4%vs?867F>iTYo;!}v zt9eoAw#61J<@mj?n=BkNHf``Nb5Xj_1RDmk!8qk$_TNWy|B%a2+*&^3kc~^hPdcn8 z^1t<vC%2y)4Lma5$(Ou-<9nRLJPsEngrtmv5>KAHeoH$-q6^atMJz((4PJ;PCt0Ox zOF~`#YP^1_>ad77|2cH%#EZQ)H2H2hH4`LIDvn8!^Uj7H5N|X1MISL;_Y-!dN2vW` zg0+iBD#G~T1hL%0N(;R3zo!)WN5dM9nfbybR)+HP*-<UBpG5R7Ky;-Y5NuhGuSz6Q z<i4X;wgx5dhD=gb9|6WJRPm){)R$RWV-U>?oh2p_0e_x!7Gl@KWi+Qi@_@S<KBLtq z6e>Dv=J+1t>G;*X3F@lz3vSv&B)GG(*uPM>XQMSt?+P9x#8`zO7bT>TFgvU85NJtP z%fo|9W)s0mC{1@vs84@%DH`S8rK^PM6?*6B-t7YHlX)w0m0a0Rows2q>gJ0I5tI_x zsyHBuesG}UMRg~;qK@FA%ysY}7?HqQIj-BuT)kpo0E>eC`&f@bFbW`A&rq$($IX(c zb)SKbsUT|{(Gu05na6PwC2HpZO?V*3Nvcf}ao3vBY-~ZW`djJLOwgI3IL&bXC3DSY zKwl+2e>hTYyt!I7l={y^6DHfD7?gQ^zRh-0W0Je4kuoOAHH$s`xtvqv?d`ilv~qyg z_r9}Q5qI3iznaTegD(JH;Z*?~aUmce?A)dA6VJ2qcc%i4uRZ`d`NRh!=XlT;q0FOs z`7bk>a~71o)?l~-L8WWz5}fiHMOY9HLxe0_mewxV;!(3?`Ej~DmaU(hkK(gcc%lM? zt1gRU>J3tI02&3)-DUV1p^3&L1RWL!y8%K?Ky()<YPT`gGazR&MJs{wb(&~dOtlFh zerx4AIZ)(MfhIHDuc=(ubnY&}m}qSQ(xG#Viz#|_hphuJZl&Rl!vyV(cUHVgGr9n8 z8RjVS?rS(f{^^Xju&gDIYP@jxzPF6h<xoDa(qI9&Z^tDN@Xo=8qwtq=rg$_MPQ9%l zz}pqlgn%khcqP&srE9N@MujLJ_staKn^dU8F$!g|1ob@pD=iM>AHGo5U49$-rm+Hz z#VcyQp38Zt8T;&n%QDKFZ3ljPEj%(@F-GJU)e$Qsy@p?&kXqRZR>V^Fx8^G<Q*>kV zwP-8;!IYi(x5gbHOFBhMmt)N5It3Gr`IOKo;BYxrHXWo>Tvbp`_*KC*3jjIJaLt-2 z&VqK`6@nuze3uvmvJT+dV5@Y3fl6xxTaWXVb()@E-kEI>G}Z`?Ye2nnj_KNarBaaR zRgC6}jCIuc#%YkH?#p|0&Rr7M9Nfvj);wA_jqP}%phu-K*(Qv=TK|pQPmp{1nXMmF zX#5#3=kg#bH5&LEFXReMtcz}CxS^PbOhqEi{tJPaqWg0fQo!!&Q9>xg<vEKMj7`zu zm|9s9%pUnZ{Az63`fOUB5ULBW7$uay_9`wPf23MS#bQz4hN8tF7$$(cG0OUx6y3iR z?v9Kea@BMm=)4xR!KY|@?@e;jG$V6#bwSQaAd_aG!2-c@gB!O*F`#p7He!x_A%6D6 z>>4$H(8vR(7;_!Snr=()of1I0{CwBp*5t4i!YPbW1kj+Xl~0}-PF6Hr<2u1XS~CPk z{@Lu9^XX?sRQx2^Ea3RsxW;64urB0#6j45pjd5WdoWtw?#xHl`Rae+CXyzp$iqd>U zq2mG-_^fr7bntd(Lg<uuG!hmg@+OO|w$gb4MUl5)Ygz=U2IO0e_*mYKz2?<(G8oo} z73}#Ip|pB=6ul}rU!yo*T~|<tM$u)lwVUzUdGlJ61id7J@es#gmeSlvFs6eV-UIbX z6fHxJ_6pFMPIPQ0I&Kr42Z5R!aqcd};YzM$FxP2=dv}!MG($8F1@3ANjWAAvY&N*M z+iZ&&uBy}#YXN%15Tw@(bc_d@Y;ecJG?SOK?G}K#GlU7BC9UErRRY(noa=-t`EBv! zM7T^-vYMHVltCzAym#6wny~kCT_BtrQ{DZK?~M{gsG@ay)GO2y4!uk{)U(PK6Qayk z7sfht#e+FYvjFJ;-oa8-i6yW_**!eJ!d!vy1Wf2RF2Za;U%RxUgW27^+|s>A7Zv+5 zS;QqEKz+W`E?-D-Uj5eGa5kDP8+=S}oGm*E)Me%?kF(`M3FzMZGDDymnu8tT=s6Gs z8h$;Uds&odlt(b;9lNIrbW{iFdJ_x{4Q+y{7EI!<V|kpR2T(D`g;7Vf2<C2vP)%sm zm6@m~g}shpoQEkOTRPD)lcLT1_%C-+UhaeUdcA?}ejQqg_tVPM7a)UKpb7RRdeM)M z!^jDqk*ic2Ly&JA=1!veu_^d>3u={+wCYZk($3Tow2!gE6i|9fX+uhWxNxrJvvJ!w z(b$E)`q_~8Zm`m+m#IvpD7IRFe+s=+N%v^#V1=yBrv=qxh&$L!@3T59`T4)SXKeE| zbM~47h&Cfr&huPnGSPINxb&N2fCAYpa7<=_4!s1uzXVM*MH9!-a^PrYax^U{I!KC9 zFHq?(2Rqc~JYUL)qiExZb`C^CCU94WOfcH!1eFtvaUfgf1<O#br3=Wy=BRHp#bAV> z%>x>(aBTS0uOURoaw;~8qO%sWW7WaE9B!P%(GLI`Fq-8~nWUC}v`Q5?Aor>!f<8SD zGa`L6F+7hQHc@>}L}_uYWJF6Bf)p*-n2mi(nRrEIj?y3=$T_1DCA2?!7QDL;(<OAX z1!{H(joyxzw;;TcQ<{ZS6q#<tUyR@p{*k$O*&RZ~-6ZS#{L7(53t1F&ju4=iowo4s za@T;w0CC|>sq^rF{mlW1cOVB4&J;y8)%;?_<n9@zV!R2OIUG|KL0god!365_z6gXd z4HjFgm!l63z{(`-+HMm!nkd>kN&-F6xfx{VFmJ%57&%Osc5&@yxSJHNO*zrRh3fqj zsNGCB7ScMg%F&}!_LS?TeAFPieQ-7Aaw9kzndN-V6_xIG)wgFKc5a&E76pfh1FgV2 zZ~S{G#V##B`o+FWrr7Br{pi1V<$014m~dI-1ZIRS3Lz-Z=E<&gA5Qa9!R9MP@t)6q zKlJ*0dnTJzk#szYEzcmo23Sd)1zkJ26|Q!}mO(Xjkpr+mR+`6_I47b8xQ^SP=yzP? z{RKoHci|ruW>tlx(xZu^R`OZBvY93D=wR)h7vte2zgV@eq?^kdVsWq)HqS*J%ct zpf2rVbWQJgfb7?TwD|=0i`N7*O>PLthDo&<@7oxq=!6nRra(XJ44qSn+OgYCLyHbW zi%O3>9QZ=pmPBovZp9nD3~d3R4&hU9n9DkA>`{^)N8H8%rA0X*WBENkvk?pX3LsNr z(?YO{!UGMfp>IgaNe|_fPt5Hl9q4%mB|bB?B3MZuJzONzhFg9Wj2DqIjwstHu7dT1 zy2qT|$xOXLF6~E^-LU^jbofg!ZwAU(12ObSjo@#xzJ#hVZb1Nr@RKUB2V@&eb^XBA z#RByvO>F^R;|K|sUEgYpDGo>w|977?EA>QshXIQ)PO(-K>6q}NYD7(&?kw&eEzLMq z3eqhnq_H!U&e1eytDX21gV<`%WT3o*N`!?<44iaYB2#`+2u)uF?<Wni-LL}pGTO`R zSD}(&1v+-kbl+`@50@i^IY)OszY56LL0OfQ{qA}<ReILW;m(dTifSSQvZ8_P0Yt|U zig7GQ(FLeK!ZGRs^(_F6ya~pkROhH0&N2zk4$2QVIoKU5eQ%D|8qi=I<h(*LSOe<k zac%RsDpaml71fdtVuVwSnU^ew7tKZ}+Mz(>ZHj|#gIZ10xu@F-4>%dNPp~W6hWva3 z+=%>}c?UxxDhZDcRoM-NGQA7ME7x1k8^OBqa<kqVb&2R^t=)?*ULawLkgxfn7%vSA zhr<Rh)Ua&J^CIdAHWmHYOYJ!iKU6qA^69?#`*JVQlty$Iq2AUY;M^%3JVldlrDGA2 zm<`nEV&4kl=sR$oJcu>`oZ#Yd=2I<afZCZHvm}cx{hwc@e(FYX1Wz>MSc3Lng2Oy; z>}fLU7KQOeEm`VfYz$Dw4)l4FXsB#xlt9s*AvR9S>|4n=zk4eJZik*1x^+4JpvV^1 z+F|9t2gS(?@__t<`*p9#(dBuTW-5`a?q`@aBjMVuH<tC7U^a$Fb!H_M_vCy$d#{I? zSqj3%=opvwY&i@NO~>z<Mx~ql1v(59^#VAWLxkOz2UDHri9y@x#&sZP)UK^emU95n zY>;!OjrxoVvTY_B4-*VWfSPo+dNIMc8RYCi^m@j%L2_?$Ia+jrb!LX=4~%0lF}q0E zB#ELoeAWs5p(1D6VX!)VnyRytPXoHN*kr<&N@`(rCCdX(yM*fCq!B`%w%fJLZxO9H z#9d_(nJ!YR^J#5pN+j2-t=a$r>E>#Ax4Eeud?7lsFS6Y&d}z>A6CTTB7QT)0i-cEW zIt#TcgsJQA?x$`16=I!~JsNcR;H~uUzhx7G`y(gnEwkkkL#`j4yWx80@!^@S!1lKX zGoCcth2O38A&h(sB!~8;_Ak{Tnr@x?x%>P3LHCUYEvI&yZ>85hyfoRr)e+u)#Ov9m z@YTmzN*S+SS*C4~`y-+iLoAPezg@8m*&}+^=l=WWN-r;mSe~3Wj+SyeesD8pyDMvP zNqdp)m^YL6t)>v^QU3atzhP>z2Ifp&P`z~=s2p8VVx<^uvDNO@WNisdTXwA={YN=P z@jSn+(;<3k330e11;GZ(hSJ$kl^i4oKF}?a*ZubvivXAnKXOjoWQea8S^g2$e0b@j ztJ+~?en$my5bIUpX*QvymbK70DtS=5WVNNs0|YyJiZ=(5_DQ*PL@lYe<bBi8wvX;= zByw`J^2u~efs9-1uYy}4xW$5&lY<|3p*Ba?;>7BrM_RRSC3f46R_H4V(Jp>^%3rJc zvc27hbhwHwMdDrbt9V=8@D+*TVe%T?Eu>VUqe|1qh3?S%XZhlPd1jiT*tde_UYC12 z9O?894w5Jwc<9XYphLN`L2!GEz&?pivj@uQlcsKG!y=|fkiIDskh5Lmi)GT`FE90+ zPZFq=@}X{7kmgf6wjY{KGAFd;LNyncY9{NZi<D12z)PL;HkQ25a<Y5zf@19WG)&qn zX)#9C@`J*~Myos~r4qlXt0_s-e`Vh8GS9z)!G);HEI9*zEfr!F`>!D^MSgv}P>GPd zrj1w3YJcWX_cTDSCK4#ChwskZ)i`&0@_^2Zro?*+ADYu*lDI8%ag)kD|2`h*L(bhA z9r0KE_DTA1y27ZG`_MSJ{!rlosA9zX<jz`m@oAd0i$$ZR>cP~-i)Ta07_EjAKQLp8 zN15MZ&L1*USgpgpE67mG4Za0#NC?Ha)=uJ*HOsA~!d=v9FA<(%CVd*7bO)G<UdN`c zh-Rfy6W_PO#il-BUxkz0FEK1<oa^WFOT#wR1-U43$+8={a;7WgP2<nExw|Tv3!fXk zj9Xte-cn1eEcxJ)8B}sa)(Lk>fPXz1?xdRKFhQ#g|6StMl=5>iS|(V$2X^knirbO% z@xek`a>sT|YZVV=_PdsQd41e1P>m2YfGT$l5`CqTS>-O8ewY#v%7y@Ax|C~Do5nq6 z{fi9&`G|O4iI29HUUlOLf*ee|K)P_%1yJlf@P{DlAbBQjRwL82Zc#KYm<aYOj!`S! zGrba_A3F|GXyK0-P$U^yymmQ8?1&zzU*f^`n%aLhP$TW+(&&xlkQYe@4PE--9_4M~ zO~o*yu4(K2u|PR)(o3^-yhOmPkZ8It(^Z>*t=Z8Lpc9G8dtvO&sJ%$YK&1fR0CD%z z*X_9DDc}f7`&N^johOK>pc^t5;1K~W#g77Yqlmtzr0QB_Rs-!)<pJZPs0|X#gdtz% znFEyUAE)UVw(dfG=p0#=%_ysK`ubiOf^>20h;EH!)!}W5ESXw(eHdSv6bq7PphmI1 zrj^mnP}xjAWi+5hXE(1Eu@mkx_SZ%V>?MLEcTrbR_&TLLHqu(S!$*<b;ucoqtouh; zD^gzH1>7d=lUEwB@N~jYRi;%qaIM=)^V-rJS9O<FdZ}J(;1aL&%!B3vb;JJBeUs{{ zce-Ha<kphlkv3D~W_Jryd}(;|vhs?qyW@qG(qR5_;%7To#X%%TuLC2NNOn=p+pInl zB_5&DzV~7ucg#EOaYX4~va(!Tf9+@Ynga}qnqqaGOhk%kE#GC*2JF`}oYX4FvWLtm z))(%c>TFd80;USnC5Cw2vA^j>PP9c~mmzhzu~`=#W43U>h=j^6f6OT<ywq((UH%On z3Rr7JxEm6r3gbq!LM5m4G8e`EPKyH(*F9WhDcxatlAUfDwY9WXZT_XlRzlNosq~E~ z{Q;sXPV0{45L@Ipf3zs}MbNUU{H=*VgnjS6dCG4paaYhrxq^{6HlrbTYK^Fdk}Pad zkC18*D3s#U1%^=(N|Sf|G#n%mNBPTY+#Q#dZe)@3aFKS&+IzM2VchfXeDNZH$SJMw zFg)%#^7Jeh{fSwWBbVln`$btFV!=8!UDGLWqOA6}(g+vVTNt@-#hx2ye4ZBU7L~ry zw7i;u2uNCzzB5~3w8SoPQ?6J3)HUXi$sP&rqN@FuSEwTw1hEHjBoIG*QC9&_!Zt>t zPU;*pR$Yc@vyQN0aFn`vFuQqh%{7pS7O@L2G$mde1Rp_W6w6ZUQIC`B2Xxbd&xjd8 z4bl&Zh6RR-XN@dd6!S;4R2ON2N0CeolV;>KU5IZcNOz5oYIXyl+NnaKC)TJcA@X%q z6aIRYHM43nB#6c=4r&yeFFB74-;Y>w@(u!FqF`?```98!gQ+^l@Uo{T4P#Hp{a}^k z^4fgr^heL>78hQa?P8Rw4i5V1DdS57kO7$*23I#-vMhf1smSSFI9GlXHzQUEmZ%0D zLY?x0DY3|4tysLU7n&*w)k;h525Lg51MkBl#3H*msC%r!{ix!$F@ql*g||u9^_2`Z z$llYXtyMW#s_L}`s_O6II&U6c7&p$5Z>EDZEb@f|ZCuo$7~#H%9mMAQeDSCxkV4(C z@G<mU>tA}Yr}vW1{r`Xom-#Ob%3Q7!-~an*qm$R2$Ce+HTD?l!+o}>KiE7P^5k(Fe zY+$&K@JHT>A3)n`%-n(7#O8}16FAqqFxPH}apjv5if<|Xm3>b#P5lt^!P;7dpD#Z& zWxV}DtTR4nRO=OQN7?nria-Zn7(u^B23RJwzSTXP)+g>o7Nq@hM32M04Z~W+Re!hF z9as6ge&F42-(y{MBkd;x)cq)Ge^(HcSPuLFHe3F|+wW}ofBfv5tw+qQ4f?IeHoyNX zk&;Ofo&L#&zd*~1kE$+>y!`j$*4OTUl2x^PgLqhoAhA@%gj}H?{W<sU)K6>Oz)PER z`~Q6t*64Wk*QS`}^6uT~-Q9PA9ZPb+W!ZB4C;%xWO%i$&5ftCaltT)#zCbo`$Hfp0 z0APNBAyEJTKwys&1YLm!KtUu7prwn#GI2scxU_!gIIERggw*hA_ULaLEkl{d&og*= zK;i0tmqECz9TT;>|6}Of<C*&ZIDU4YTbTQO?sw)Ia+$eb8!19H_e=Dhs1P;Vn7g@; zs3CXNT#_zo?sILVqI_#gg;bLIm2c&@|Mz(8vBx?4ocDRX-mmBDNJr>oPxEv&CSt12 zqqk-DidFJvMGcz-fZ=38k#u^)P@`hG-ifKc_9w042w8XZs??$6zvtusox0um{1#y( z|Hj5Q0;xB4-qJZlEPe!Z=IvCy*M&x)B;qfK74uKm>qjJrkh1qrjVv$-#R-~8O)7wZ zB&Dse%cRKb0wyZ1@nWj)=allI;dXnb8~56dbQ<x@hKeu0-;=)TbHD%7OR}9PVfX;s zVepX`lqGCVBD<5Javo?Vo778`g2#ICex-bf>2$M<%}fT=Q9bJW0R>{8kH3K~bew#A z^5)Qe^^E_G`#gI1=f9sm=?94HC%=h6#@8cmAPgZFoc~7*I4z(7$l)Eon=674=CN#| zl<T_0Wf4I<9yqqf1Rzx+_*Kwcx9ck9X?-g8B4)fz@&Y{IyXc{wcdc)WZGW^$WohP` zml+EixT7Jb>W&UeKJnNdlRb!iHY8~%OCA9|F2an<m_pGIAfk^%QPuPw8<9O$NR-XJ zhBS2rk6W0yN}+(GE<#5$R6(JrwYXey$dt}H6E&}s_0Pw(^|y_MmYcEB{&HZzavu}6 zR+{6^W{X&QSF@2vUhxyJ4>?4Vuu@$!&=%p29uY@)?}v?mj$sHRlBf!Tdnst8Mm5)V zARZZ6iZ*Q&cT}1uV~tUpTfIW_OGEk^x|{2_m!eN!!STx>3mvYp^G+rSKTt!eIbfr) zLZ>sn=9Br{&IS-&iAcEu4Cuv6o!HD9(U0f~+d6*q`rfMiwZbrtY|u?{<!rbx8!LO; z75-_ALe@HZ^!V52PZMaG!LdG&_t(SKb4ek*D;0LySyINYcus((xru7HA^J3S$Z#Eh zwmJ-hr;30T*+3P#MgBMtk%CptgBSWmj&6vw0urlnIbWZ(#f7Q^N+J3?OOe%o7H~3Z z?M5$PH<MORz}`%eq+Fq-4=H0sz||}z&ORQR+t?orJ|OJQrh;SMp(#*QXsol4a0+3x z;Iw4gQdsu=J;?LAiGi>BYI%u2)~{cgr3cJdP#IvGp!0YT*qx+R0~(0$PKH!qTxH45 z_T=jJ7yLiOLFVz+WW*XqJ5oT_WL)w{!2r(@ZvJ&lW*YY5*N>z$yTscU^G@#lTszpY z*X-IXllb(50HHf2F6x4G_*+Af%PC(=WKQ5>@7}Wb9}p@SOZKmPn0qS&>CG%w+;Nz+ zrJ9MR@ZM=Hu{XCKn}KG~7j2F-1x7|03ko+Nzb03pYPYF6-VK6*oMGvE+u4}H2H_a@ z5&0L}*-)qw(v35syr6XnE8HlyPjeqtlmD9Q?%jy0=8S6De9gme5!N%@$MpVYgMwxn zrSEXYjMBdr5QLj#C)~$PYrhu8dN;{G*Krj{;Yld<HY$GLRI14~AYA}J`3u9%7R*Cr z3SU?D2zRrU-l3=OHmM0rPPl>>N@)p^;+L2chft=ajDSdGP|c*h=>omp`#M_N+TG`` zAHB{zN?G69!>hxe-mIvp39<GJ_S`|-q&6Elc}xXsEg*sQtOItg6XEj7T6XR&rqz=( z(KfvZhg2=|W{=tU;BU3h3*Vbj@@CJZf4efX)?#*BVD7BmH$=q@$Yb~H%=vr0n(qr+ zZ9jNCPJi+3>d)(~q8Z!!5GDSCz!%{*?0)VXxiOiEyfJD2pMdvehI)foQJb@NKFZVI zUqf=X&Gn$oME0IUg8FKkyPN02e8UsOWrI8iR8+~um8R>M*=P2Za!-mZE1E54bvath zC%GpjTkS+T@H89771Z~(@5`+oR;0zOn-vV7qK-r>c0l_=X_+Rd<LDh5*^aZ{J2d7u z11D^%I?5{ZMT%xYkEf2+F>c?8Dwp$O30mGB{(dv{Q<&(nvx9_Tjq7P5U4&_wJdgFr zW{OW&`0c2m3S^^(6~NYb29QenN81W!yQ0%11*Q(1)zAI6E7mPUR-r5MmZqP!FV5@5 zvwPB!ahW#~V)U!l_7h;8q~;rEE`+Ge?EJXHekzFG5R|wN|K9-TyU?j;wJYy!s<py1 zZ>F>!3M_Z7zPB{{+2dyCzn|@87=c+G7bZTgT+6S1u<mlx>G73UKQ^D;`CMe2c=RLw z*NY2xx(07u3c2$7&)$XZ?LW6j5+Sca3Rc~B?O5cOa`0)v@d2S9pT$#a=S{dd_r<S% zhPm(LmDz%znn`RhIK9AP1$#Sdh?rCQkz5vFfdbG&;s6gMmXJF7d1WDc`F=PrT}o3D zPJ$m3%M(c@fdL}>&_5W)rRd5DyYbK3VycnAw&X;N=FR-3nU^BhMyEBpfuhpFz-=63 zn)41zKdcsA7K`5J97x61fk;te52V^xql{|frWft+FKM`)7eHFFo<hGY-&Y9w=3$F@ z23D~dq(0QgfC%euA?Z!K|L!y&6!CLQ-g_c{!@SL{2=7<Ex7g-;yCZOR^Vt2pr>x@J zT`@i%gJ14F8<@L&^CFac;=go10F1R>`1Y)WMxkI*v>+lu~QuFSv0{=WOe0{$8h z?RPu`!1g;(3X6C#o9SY7W@xUaa835mB-DWI_%Pf%OT(5hT<C#<D`tiC-eryZx_6gn zF410p=Ll$c_rQP(0B{7bLaC%T7h{eotuaMS8pTD*2;p)A?TGt<<OAgdHO+betIH>( z8Ck9Ju=|)#B9R#Il-ATLr81`<M9(YvA7zPO8|?98zJ$Gg#a`j{q%z4P$GR`;ou+lF z&_k|*&WPeo7FuA;3zb+!AS<jRZKRHu7M+3qeyed8>d{Yv8(jy9Wg|yCf-%{~U7)7v zr{A8a%O?%M6#)*$Lk8f%v5Lb20MkkSzz|d+Kvn1@ku1|f6gtle_?%q5ZgD+WB(}|2 zg8w<q?E`?3*sxG2zfGqP4WE~3fKdh@GB413cRDRTmp+eG7oIK%O?lZtctpi)nrx>r zG(<v)U^#$4Pp^lGWn3816DWma_y)QUXRL@QdEvCR-H+r4*&ZBBM)gX4TML7>FEPM| z0n9A1lmVx`4K~aUU<$<H$uf&rgfXT;{9wn!zazBF3&kTE54gxnej?%)f&f<3lMX$} zMNn9<3-t5}HzdG=VtFt+{!$_jM!{TqxGkEoDvFjRt67o%Xyb!F$kebdj*SZL0Kg7O zs0(u-mI=)yA|?<Su>f$A1V70{kUqfEw=+(#U<53}R}59sdf79G{AE<+^6EbkkOSxL zNMwkedmkgX%SHqcGcNF8046=0jflm<V_6q0dGL$dX>nZG)d@a#CR1IOb{0wYwsKp+ zpVJ!>RXQm6ACGDR$_6k8pzb71ljJ3GhK-|W8A|}5i|p<5H|0q%fF%%*zjT6&U~u?9 z0O^PXTAEYapTnqP>B$5raXrhEk^eN1rrLA>;PESl1To@5q#)V(V@U$Lm!BU)4Pa5r z0MG~k`PdA8-XW3>r_kZ?T*L`x*2V{zB|B$46&Xi|r!b)z0Q4?4vty~~zlr=}6f&EX zmLeuG3&`%`MJ}a!&$I{w7(_o-D1eQKWWhM@8Duv^rdaBDU@C<ROXjAXN<{*6IF@wz zJ-g`DdJ#G$ljp7wjsWg4MfVR%e6*5&iawxkBC2hL;|H<60zfen8jCMx1Z9l1rpJm= zeZ`<<_+knd?u$-OXTiKN$S3=)bfLTDz8~nK8&bOfumAuK7f4#-6&gbcnvNo*hT?yT zrOUWn01(tvtu*;6Ji-(uREsPV1%5GM1z6a`65^Q^Qo9D8i9tl-5f=c!n?N~1g42NX zv&(5A>;tLo<+jU3tKW+3f0c)tAPecq`VAs4uqf45q3_~}53negcJ&W<R6vbH1y|tV zK~X+_ql$$L=OW%s<jn--@bfNjTcK}bAjh#t3I-9ve>Y>nQnpKcvBF#13K?NnF4kOu z?^crpq+iFNyaj*^g2XgNIKokI8ZSCvg?q^pyvIZavS7*R)JQHOk`0Sof@d<}v6C=9 zPTrJMFTAe<k0T<Q_?NvMnhPkTwqN;t_ww}9E0?-q5CovoTB_S1`jYJjZ<C_43iiYb z19`|ukE#$}J)^B8vb`i(ECawJBC%H^xiE^@6<;PIkw{l-sQ%J^B~$L&1Kn%7^FjcY zt~mq-xF9WYp`!50cTK_%|Cg(b0Ah&n0sx3-XGUtL!t$$PCoh?@VCTfjLs>A%_^T_= z5gyy;w=gu{z3X`S<|L%$pjIQmhR0wT+FuJaN|A6klp`rvvq9AKo_gxf##z=i>uOPe zcd?p<%qI!N;tQV&WZ2zfItT)$_%iKfSOA`KVY`+S1NlwAtd!n%@mGUxcfRI+Tk;he z>Rr$!jZ%09A{Af@*R_gPqYG@yggve8r?4V}NMMi100@F-`S5)_F&SIcHQ8i0RsWb) z;?RM3zERuQO8i5r=5HxItZh>hJa5%O0q6*gZUljdI!{9Nv0Dlng*Mh3qrT;q0l*V1 z>Iw;3u`LupD2dFgO3G_}7F3i%Cu$$hND-sgE|DVXMK1|$kK}LJF4MmX6rW>XNCf~s zoas0nj><)S8Hd&72j0h`B=Uso@dCiMP%yUeX>Qd>V8&Ez5!tQ%i%xe67LkZ)tsNjG zu)$sItBQKJ?*3{x)ZX@+mU)haxCj8h@|z4pU`-Y^FfW0EeS$zgwj}O&QQR^jkqeia z?tQuh!}6dvJiFtzGa}>8TXVoIgtku}J^okPz6&Ow#3MDn_ME5lTO|<Z2#9zt>NY(v z;e{}ZC2)lxREdQ-9zw(}Bdl}b*F7>$5bGW3P+uOjgoyaZ3vq%}D3M=?R<Jn|GN4r3 zqbc6VibkYv_h@~+&5z#dmI^$aI5y19)tDy(7(pfr*~}7%;lZA+_eWY&`OuD7Ql9<2 zdVvqE61ClXob(Bqj80G3CMGlI<5jKB{QDPs?teUOcoB7hK-r5&nVpA}(1VtFf}KQo zGZR_NWBq#<7LGw=5c8U@z>|6X60x0$_>$`V_1;>Y)BrppoS(;(y?yuo!@=q5`|Sg< z(eW5R#Q)M!`<^J3n!xABge*LpCZ~H(Vh3ZFJH-EE-Kd3GV&U%w$`aYIaCE9Xqc4;P zD`taP?5iKAANv27@;|+FI=eY-O!ya1&>b(3&lOq|=!Sjhb+})0F1ToP0tx_qhk`Q_ zx3iOLFKOLDn)3u?>xQtQ1HAW8Y5gER6zdlo9*9Qt5(J;-!GrOwiOj(pdT`@9_=~uk zSC>14Y!JabsIE1_mx;7sBliiy>I$RrTb)nAX*b@(q!~dExWbRnh_hTlox-v4_1>3P z;2GQwfH?LvsE>i9U$8-j-_48KPlbDM5x?oxrxho0D-nHIR6ib7JT3JhHSiZ(c#<hP zf<$Zs0+C#J2(#Yd{$R&e4S5CD;!+iL;bv?eJe&uk(z6n<8P+x9Wh>J({nP0z#054# z@)(p*D>?`u%mqakg6OWTgWS-u1BVb{ry&G<(b-N!=X7BS{!%;-c7+ZNW{L(5O+U<- zd(?62E)ltYUSKk$E4aHXra4(JOL&qlT1<rX@{ldu8^as@nO##iHtXlR-~ux68}idH zLvwP4CzkVJ{lxLM+&M|5(NDJps)@+3>5#{4l!hnjD;?U;<P%#20=A0*pRxIb`bc_V z$Dyoqm}%DCdnx<)^OIK8)eQa=Tpgs^Z2#v8R*Ao)((Lr-`ubDE8KQ(C8~VS~sKmU$ z0kN|HUHBUj9tZ%H?3y$GO<by52+bG)(C{W*ILQrm@lLm>_Y+H>Du5smM1sa(2c+zt zdj&mL-W>m5R4~BK`+OnrdmgI3PILeZsbmRsGGWD-dzoy+2|M=p0hlKd<;x@iL}myU z=5UW`SybptpUx);t+_sLRGQ4RKJky(gNd<9&F-`(B;md7XJ7FGfm~LQ0T&XwJTA+5 z>T!?H)RGdq6F{n$49@88DuGo)!)^$u9eOb{INq!jI-W0)j(?<S@*ts7lor>a(IEPO zDg1RG4{62-RT1H#^s0`ni406_BtPMXK^*%%aU=mk2z`0>biK<9I0b+H#mpsu1XVAh zZ@ydse_pvh=Bp8WBlzp0=IW(qh7u|#j$H9ZJ+%?Jj}bjff_}v?6ELlrUG+@|Gq#H0 zpOiR<K2E*+(;LU+K1*YY)E2s~BZEl&p``o&!|*IWucZ1M`{swrqECj*KTrLh8=yPf zhlg}xgz_;$!K5+n@7hT1oG-cXmtJoQ2Vs^xSmCGs??q!9!IvVLvmyfm{ECA<K;RGY zZEW$J&V51!s~}rd__5fBA`j7@);8CK-)`dt9sxiwuQzt`Lzopp?QgNppT{dg(AfRS zSGre+y?qhY^~?}<u6LcleL%rztn*RnM(x9mx>p-l|86jqHyiCYub<p(@!iy(-vA$* z?41|I4_sp)0N*rPpK>BTPvLnjDs(D$k}b4DXsYBPHG&68h4)@w93hB23n9EB;QNZ| z;VyT2ZLd&5F$nuuA$KP75g<q>4S}w{=NU~NicI)L64>KW@673NSRyaPR{5OKNxDcc z3D(OVtruG+8PsnLc5{^9b=@7D(Sc0F4vOgyiiOmN5~%$|Sb>;m{WdaiRdm(<tEA7Z zx5WVp_4s#q;TLZNYnY-_+|O5LgrCrbpGQyJzzP+!hQ&LktOvTu%JlgCv^Te`M>@Ld z-+%aUq;O2L27XfKeKk?I0x$Ft{nhZC=%D9U&r|a{phqCsGt1J&cM)*iRl(nu67IUP zEgh9wpy56Aa2FGqj~DF33WfiR2><t$+TR_sl^+>|G5e5W^QDgKUgt%pdnbN2dEy1# z+2jfmyls2L%i(8A(ZB^5-2S9x6bpqdR{5ODC~rqi;CFVg0%w`XI4^+^Hav2>Rqbyt z<>3#^<4l-GJ3)~f`{-MK=G5LmP5}{ilPKKBhA&jp)8gi+*Zz~Pe~YWUC3w>2E*~FB zylB_>!nj+gBo(%MM&J<|p5?todG#gn@t1JY8?7_1&ips{`rh8!e(?E95_EthbQ^;x zB#7E3?%uohH~G&|(>j>{Evb@xh0?gBo>wg!Hx0M#MPe{Nwh01&Nr8}*UdDT79E4De z%R$J@Etf_6${Sg7Wh<5tKBMMJhkh(C<Qz~k4?PANpw2wiwD_^q-79nCy?3oe;;Ye` zBOiRP+GYNQc1U3HwLs1bh4_FC{}!Km`)v86n*kk1Ti<jGvI`at0sMi~nNzahc)Tgv z>`GPqV0`?)4=wWh<9jj~0O!~3+$v4L6WDg7ybp5%5`|S(7HB2%O{fpvi=5^X=aS3; ztgHI_>zYTd@0MnLf4t&wx!LEMYklzd_-8jxJjziD`H}GA_I~1j5Teb&&{u<*M`j}= z4{yIdz8ac$Kjlc$``P-y#Qxb>`^aC4x@8bH%Fr#KU&q;fKxCMm{4-az{FMg^U1N4S zYu|2mtvK<XcZ*ZBSG(Ca#k*5(s8DD14lG2}8RH0(5%$!*ewBj3wF5O%aD@s_Na2k} zHF9ptmZ_&o8nes`CvlkCSrtwF^-dV@tcj97(gt8LL&%HnEXpVoC$tL;U_{tIe+rQd zci)1Get8a;2%Ae<Q&jNi8rSlmzexgG@H=ZgUdE5iw{;{ZDu^Yv<kXJrE*p>2)(?T$ z9B=Cn)cl&rzILi{s=+T9V3?nx^I$?UI95nyKR#mrfR+LH3-cQ{^}2`=H`%|(e0>R5 zX2xP7WGu1snnh86(>%N|hg~d=9({DZ_h=_FZz>11=-nw4SOy}Y+EPIzpTNu6L`Dj8 zDn>p~(ove^bBRCfTE=G>yr7-8-9hIptWUEF61)xO?cc{zgf;J_YKYiX05HI1y*<0q zt$1TiVxDj>=IF&QV+T)NA-$97=x)>lk>nd?$#4xL-Dyq-0|eAuQn4%@Xg&Z!D`XnA zLyM0e6L%5U8`TkY%jN*2!mrY5%NTSWa@W`#SXcL(QeF-hGI_xKS>`gwoTxl+92Z@7 z(fjG0*rt-ts5dlF_eeV*!my-^yVpqH*9!wUt?hnuI(~7tE|1_;B9$F2ulhS%Q`TH1 z(hE5bh{3k;;YH=ehB8f4gCa{TSeRtQVM2vm-X~>OCTfJigu(wrJV=^Qq1m3DRNcS# z)M<r2peyZ*FNZbnExj$a*<9arI=Lp7t&4vjm;Zh0)Z;1XmNno5<GyEBE6Ppp*Jl%I zqupU4Q|WYTOjE`0n*~ECAOA0T%3iS#?b9m;tJ8>CQ3|2hFlu#LDcm9BYnG?r`P-h; zQ^l9-&j^ayu~2q;QRn?UuSPOTHI(D~Or|88TJp+&L6K6K7?{8|aa3-NC77y%3k;Pl zDSpwCZMb_QRYx7wPePaOAfxw%$VoGbdsw&;{{|p?fr0lRq4e!Wx$DdkU3Uw6`Dff5 z6Y(d&>`n=CV^#l5TKR$O*eX?|<AE>OV(B-2dH$hq+({mbE<d?V6v<n*>()qFz8avq z+=iD;yXwl}iJR(#i(3SZ*}D%F#f;))bH7c9yt8t<uJq2)X)(;+J4pc8B4190Y6Mh- zRh-xjxBj*6qF+dMmeFmteg7*+svxkbh;u{8RE*-xbk{K59!ir~9g)^r$T7DXLJ4$@ zn!9(4q+=VEtGQ!_Z(>U(pDtA08I3YZu2EQl`s@CQJs?rIK$fNs(V`v4%`19}0KP>Q z2m$n+o%8%3wAFg<H#njcO%bb_8kpA)+-KvRH40dtE}$WSNXJHvWa}{Lm>{ZQ{1762 z<}K<iVNCO+$;idUg5rJXdPki#o(%3G-Dc$2viR>J><DoYC|j%$SLW$|wk%84ALlLy zMQ^Y2({#;!RTZ)itiz<pS90t}Sp}IGvhw5rR6AE1U;At~z;!6hvA_w@xrl3Zn9T`o zDHRO{2vYe2UdDy~6jki1apM-BmZN@WJ9ibW7qN`<b?sryYWtB&3z7F(D%LDjl|A~X z`li2VXsDXV>ya{_cQ((Ve<Z{2^_)h(r3wMUw^8{lXHDo!Z3n)N=)n{R+6bmZTx2Tp zuExF$kbLxwb&hG3qtlG5dro=2nzD>jj`|*3G;m!_;w?k<#L@e~jcd0L1|=mXG%pAo z!%wui-=G@W%pbCkbr$w&=5JHRKVSzCRpXY(F7Vq=C-Co0K5lK6{(QpsOPx@AZ7?aW zV}4K_F6SeG=5YMb$({Gk{U2QZ`Dd+h!i;lMav-_NX_QB$VqD6cdpd9nOsFO)tVd@4 zaG+zmc-b6Hkj{_E#5a`0k#GvTKT9w<s)a^`xT<$!#GI(IlLsy==~ZxO=Ol-&9q)Ui zQT}PVC<yHbP#e{q)ld!W+oltea5dvYGs#b!RE+T;iTpOG{!LmzS^`9}#mdEiyWb59 zUm8&~drGXB{J7e+Mw-eB$gu?L%%%ba=}OLl!oss+h7V?Rg0Q|v>bPyzDMRpZ*%G&X zwVX+3iw-qvvKzZn*E#?!O*Mnr^(P5jv~N_rzSL@c{lU8KsbvFA0Q^k${SiQTVcv5( z$CRn-6H*6K7W!ifpx2Rts4vF(0*&l4UheDc9#=(Yh#b<i-H_N2?A`J0g1J-)KS?6Z z6f@UYZz!<*4UwiXsvX`;#YRtmUpVR~@u!0C?_wo@MaBf?>YvW&(RPWa%W}4BT&&l2 z6g3!gTk1ZY&fD`adFxzWI?7W&enijCccJ8hQG}d511H??9(Vt}qsYGZdXqB6YTWz< zOK9HU{<3K6M*plowuSii1?r!pbuCGG85oFACyUw&+7>z%xG<wF>WzzMN?MW<Y%PJ| zlAi#B?m2DifO48`!wR@n45McFAvD+d;S*fQjV3P4*fy)V8oROq8nX)MXBD>T&z_qy z&(_@q3A+3a&!YShk{iWpm>pTz0!R=^@<p=gzDJMppr5uyx_WLd(KOSKDjgkGz~5bw z8D`Lo!u=k5B|s$VtYDT#zf;B^cW;)c@KoXsmH6lkO9wKt{WON)=FI=rCe$Ch?6Ht* zR#F1k@GMjvL46e-e<i$R`PBe6=c7Tm#2y2oRogv$WO2V-{67v<B|b|KZ1L*n!QEi_ z6|A<;&m3jf(gSO0654$nC*=*bOnpg^s0TfvEI{*2X@#kNb6Yz!ww7{<8N_(4v=PGV z@Y6LoCEz&#miWa)=(;8y$Se$3yxU4^)-QUij+H+vb$&_26rgsjR(B3n_N`M86%X(H zY)Zg)M$oCp@l;dbZfiJl+f4bNP1|PKEb*XxAwP+PW$7EZTuWs8;CzXZPPQi#7Q)8b zvmN}=+37sEv_Ha|1ATKP4`jerGpIcUY7wYoGjRpM>(ERwn3qnrz78xzC;L=e%|DHL z1!U=N2;dF@)Y?FgO$6mIg5ByUX{e}a?%=+?7{n+Q8fB7wQcT>91>2H`DcfeB;UR*t z5MSAx9J66ZTO7epK{Mllx0zrZil6G&Nwrc4X_Grru26syPWn|Woon8NaYXBYo0w#c zU$?%xOa2d1ZOtRg50OtTQ6o5rV@w#IWZ;X=&J2Q|ltrXq;U{FFCkI#yu{IZf(!w;x z!_CJd_%V-w@u<l0=#=po>UeC$c--~zc&aPFQ+0;&bK~O@jzV4$urwC+D3)xNi+HG$ zO(qN$=v~F{9gyQs=RwwhEJ%R~4!$cK>tTI5Pww?9*zKob8XbBf)y12E$YerIm-vD) zEZquma(&2=XjNk+g6nhNH||ys6oA6F#uHz{(|~S2px1u7K7s)8yVv$sRrw5A&YU!X zCX(AgfSe9E^*Y!XXf1b?`yi+KDTtbMADXGdNn;+cT!N-s!H57YEf#t)y{EQ~Q&8av zU#-TiyBGe~<i@4>u%MB5aq^?!)7{b)ry=%SGP!Nk(A2R_wMCj_&TDV{+IDw08Ek~7 zY6NAU8h|Ep)kC?6sN8Hmejw;xPAmg~+eWyfANto!jX%)U>xCX0n7R~~1Ky;j{WKhU z!8pEN-03;FgQ*zU05>7Y=ygSDfUHRLlB0vrNEZQ5(bp#VD71qK0HaRPykzw<+0YmU z;v}8ApVWp(LQ^ksvps$ywu6hp7MtIv%zdEFtp^k}*UWfzW*?8OdPGL}v9j;{dRTsi zQum+X&d*^q9;{)NC65I&sBYQ>GMWW?7BE;h-DRF@9&S2foI)<1M&RAs`Do(ACHRnY zb~+Q`gQX>}lhehDp2)gRP`R);sZK=+0q^?F1gX1XFrbZke4Sx`9QMUl+3k&%iplN0 z9x-V`mPuhBsZ^LEtN$}{wlWNy`T(SzYpy^5DY&;pU|@+Xh8I4E{}n;04ScLn@;c2M zSv3EXb}65$b3@;{oqy9qn~)H}B6<v)dup<0{ig*$q?QL!?c1rV;S;3|=>2NB-eyLn zG{#Xv7(61|`~D4BTZb$JB1zLh{KI=R9;CDcYc$PH6NC3Hz%!R}lnP;5n)d$dkYGVq z-R4D1gM{Iyh24AdneK2G2HcHFW%p21@zkR~54>$3-JQ0!%#`~nL{^|zqBw`Ow#kYc zI72Z*`&hEExszGpr1DaB!a6LFi%2BERn`3ic{%A!m`QH-MRvB|K(;~qV*Kqz@3CW@ zsV<&;`Firf(V%S4pyID>qucA^U-bjm+xguKl=vO{xV+vnP_;b=9KH$CUO!@F^=OkZ zlE_7bvSCR?cqR#!6!grCu6l+;Jt8Zw)BB7jB`D#@PWXh`?_*j;%EC$$ZqYV9SJeWy z`)Ypc-S;Sy)Mx{#k;teXadC4|KU5i?4I{L1<Oh>1P9VoI;9}D`X@u+s1$ZVJM!A6q zT!(}$(KI@97RgJ^|K=el$KBUuP5`9jZFqjRm>U2bSyKK)ua`E-pC;I4V<h!{dZYdY zt1&_HByi$<6^(d%l8r=}4;`Rqd2kSmrHDk{GWNgY?hIO#5-f;BJ;Q?q&~?WnUyR-m zkW_^W$RRq=2p~1I^IWkTot7?Z-RDP5P1TWy4nFjF<gjsF{9l~trr2#Ch(I{9_S^M5 zcYf@Stghn}My4jvX`d!(Qz@`OPJe+oZ9k2P2(k+B;TZ)5(HctU){ee<7xijVwJnWD z`#S_95(Fm|rJK2yO-l#>fHyClY(~RQSRu~ko}7Y_VtD>-ximAKJI7g25d%GA^z$UO z+;+Vam22cDgW&P_8a&EwjCaM+o#MiF3?XGVY%V`q$$1f+b8V0s&&!d1lYNev?Zrc! zTxvasUlBREq6*IDpTT@-xubk$!UfSRMzPmLY-Z*sx6vfd=U>9oI2Nax+)p(#`N|xe z4~0u5Qj=anL$G==pw?jmM3Vqv|McYwmAGKRR&CHk6Xcy{Gqsw*B6m?eHrR{Jj^HA; zz_9oy2zL$*{*V#R_y3Y|vqP<DXE{{YCB)%vgvfiI&7AJHG`<W{cbnsSGB01lJfFYX z5FUj1a;~o<syK%8DoQ>lij(6d7Vbu(`J`%p{)mqCP+jnuF8@Xbjg!sVw2T?y-*hT! z#qY=H%9+Gg9ZhX@!@&4YCbeD$Ss^D(*8B_uktCa=af24agIr`#L)_=;bX*S=`zw{r z@I==78KEs!2;vefKQBLU0G|*b7>lP}!qeK`BBU(^|G6ZT_!gch%ReT;Uaah-0P1l% z)cjAuUVX>o`#OB5${<LmTs7*C)pUh=Gk%leD0avTt;hEy{9>72>}=;jhh3$&X`HAt z1Zp}fXFr_{Jt3PDxRmFg6co|V!QMkOFLBeCqI=m=*w5ohK+GK-=KCgiJU}Wq4s%1k zky*BH-_ttN!8G~r;n~~WhFGxtI(-yVR#JMqV5vpLgHj?6OT)nY*voZ)VE;B!z1wJ2 zpC7-LqQwkA^IjqNhzVDIv#IQOHDT_(#m8RPj~`ZwRNqit@q#bY@`KvKK5Xlz$HoEf zIl;tIAM{ZzJ-H_LiiZSBHs*d0#8GdZa_uv{#Ja3nwdS3v^5LmMmo^yPHYal7Mw)w0 z>JrtBnH|(dJHdnXb2cw-=3HV!kD*~c1KAgu5m&ge#l>9g4m1I;da3lI(VyN#^Zfl_ zpeM?jLew;%@=ELAga0YD)}~Rf!8bKzuTIc!PxeR~Y(jprplR#bz5`ovOxO_)&G8&e z;X3pP_Fj4rJSiyWA~~n&&l~Stxc_qOvVHXZ+9m4^(}Z(zr#?b|)JHbumIj!YRVgTI zoxd*bBKK{8EDyw&9%bymaU*)T_@VX04&_8HK_lJa_kc=D7tC{=n#qEnasQG&04KKP z99gHia-pM@|KwVnT0y%CpNnf^Aj&@WHtIbUv9tbzPS85}rWRCaZbdP}f?Z-APpe8Q z=+{h&-8ZeI`O=AG#iw!Z@GM2WFeW0H3H1g(?JCn^={fPS)N@>z5%bx;^r;tj=N8vr zhJ9v}2PF)Ozm}JMecjB(RdkB?z=ZV(5Vrxcj&xLZSZ~pG+om+c@zM?-l@`s0ed#aH zU{Wjm;h6+j5SM08gypv&Fpme%uG5^E@Mf29w4=%S?~3*MvQ19FmVXJ^;~%vkAC*Q~ zte%BB1VZa<M-=kRc60S^Z$P)CVbNH4+Rxh=%z|L9jaCYbDRj?^s2L8>Vz|(q6L1I8 zmu=K7zv>15FaGhV@H199mwREyo)<^^Ay+q&+{!*2i=mhv%C#3$bVDAlKO;B6kOc54 z!AsN(ZuZBIu)n`=r{Qy$f>Xiok6SYM_BcE#7sfwLG8vS8{hENp)_^nDywxD2Fka3{ zHd!PaaajN84P>=wWPZ?oF@EQP{5)BI0Bn#dJ$zM~o>en{l$wCe@mYsOquoFCUrS(S z!%pY$`*(^@Z-72QJ$cl#_@+P};vxYW*`%3&>sUc+k5?|tpCcH$4hM+vGeJ<dZSHaA zFrP7Jh$(#SdEwlh*WZ}pZ<C-c@??2pTCAMe%@+zLva_e~DQ=v!NGrG}0j~FWdF4}o zH1cg#3p^}!*pCRiD4QJ=gt)Yn?J8UOylOA8HT{4-4L6tmY^c9}vfw@mAs2?!!=63# zg;`#0QEhTnO2UbK2H9ItQ~j$v6$^JNqeU)U*!T6xiK9c)mf(qEf0+h*(F0JLGc1v3 zl+2^W4?z8MoAMt09-qlL<xeZM6grJvYj@8`$3qQLZ^6jo?y_>MbAmeo`Q;8*Ev?k$ zb1%BErEM(AM#WT3q@JuizL()X@O$ETG=Rka>Wh2Q+FA85X0hLbVtz}0Ac2w7uI^SS zV-UW-m9(|~Rh>gub1O55+tHY+&<pHI*w}gJ4w%L)bj5wsnya(9u(P%CO`FTa(V};1 zkbpVS?gL2dj<<N3f3M_?7v^4N4C@ds(Iq1JfE-_%1<(-YtoN<ticr<E$WrgV<h~zq zW)q$227Leq!u3+_iK{5~@v173YTHj6uGolhiC4az{nCBD^Vkh#UEd$<@9I)QPaTq# z_7kabd*+*q9f7^kcDoi^OFc19Zr&*8H);0A*e5^T@N7O+1yuCpOBG4?oIE`z?gSHA zHUu~=E)juqm2PJ5&N`My8<FgRe$Jt11t>!Fgyp1uhHS;du_Cuwg&zr5Z-!RhpTGDF zUTyPd04J(9RPjunETA`lrihUH6sY2!R;t+t|3CmsR59+cT)~XL;L%<N7*GgjJeBf^ z%o{=g8M#BSf~Ssmvek(6p~leI+)`JCOuFN^dT<JuVc6nLDYWfMXgqA1<2PJrza065 zVf0;OB*0)d<w=p%Fo|5Cz5g+Ql5bJ>ySJDU*Kt?tO2V<9T6IZN?Gk!-LHxOXW9#~) zy~Bo+s9jK3c!6d?muZ1vXrj1!py|KwbW*}2k4gk46CHCjgX&D`WFiv3{(B*kI|KuE zc*EY>gBXgp{guM9!=^K9PLt+-mgRiRkKJ2gyQVt-!xq2&lJjg@NBv7`YJd8_u=`)% zFN3~$&w_=zr@<F*B)n%GQ8oO{aegfIXxD#IuCroCNIud)5XettXqKM~uK!+{k{Frq zqIr^e?ro5L**p!^tlZ?KJ%OfZXu4~a`xv%3*Ua81liZ!DY#Q)?T(yg&Oj@nifeZBC z8oU)a^uqU|>6ETRf#LMN;r&nvH?texp4h#J1y_uFup^{^_kVlFq$BYMPvk#oaD>fU zd=)nju9@=lP>4<Rdmb9nH}vKt=XbauVRE;}!+yrV+bev^z2>nd%<t`t?L)9o(Kw^- z$*dK_y{FLn>h3quLwf)HImo*?Xlu1fOpiQ}IJnX$eDM1K&e=9*2Fy07`faKlyme0q zdn|HxDEwG#l>L*&#FSNzT2Rn1;w-Set}c@q+c0J_!FeKJNb-r8D)aGu>uI<cYo=*5 zFw^T3nRqJU_{w)N$N@Ww@HbKIyLEC_KbB7)PF(%>qC<m2&-ZVM=H^LGhYc*)>Tuiq zCI89P@W{`V($hYOXN&vR-O9JsJg`Zyg$HJ|FWzppRg7^HVz+=s_Y`W7RM{2#v@qH` zPpXTFusHv;|I|^4{I}R~%{lR+*e!}oDAo;Q+bw>6H}RrTM%a&s+9Prc7?~9wLX%Dq za#0+~><t=Ac73jPo0A<^q*gB*oKkIGmjySM1q(?JH7Vyc2xTsTrRZU-Q@Ls?_Xs)Q zck>$2NLOWvfN|TPFhODex1L=*^h#SpUb^#J`R_cqitDPVb1c;y^IIM5=Q`quT8MhE z4Yk`e$#+3&D_4olYhC?zvpWc3bFEzR{?>EFUV8R9Z(ERf4jpRG&$}4Z%Cq^#S}2Et z>LcVBtvMF#dyTru@-;dw$)>{KqTy6d2*+qZwb<}ngzO_Q!fLZy_~h1b&MjUDx=GjP zpj1!ovkVCvzL%R$Xpv|kq8k!GBn@{#+s0lEppWixtFTzqdS_0~7X#G^ZWMW4>Z?-c zRPf^au=ox-!d|&s02mmS8W4lssPYqu@AFZa!y_$vN(ItqD2(Z!N6pz`B9~&x@^!MV zj9QD?(lSZM=eD|@S!Wv#&0eqhK+nSf+@iEyNAYInsDU0rt(&B6n8=vFuJ_&OvD~ap zxcjgalL_;00f}@wd8w?4d-co@OIHAFIgM@scl;Yv_&QX_xm&<*35@zB>vnLUyC?&@ zPi_o3E9h!5<(J5HlIRYCn|pOUAAG3MeCdzA&u0*@vKSc+aNc|U<67cnfD^B5qpC@o zRI2{%>q*WlK3vXFd+a!oa)XaZc+W+cdy5#vvd7HhO)7n@$kKyL!S*{QMJ#Irm9GOU z28v-q_yMvEmph^P-p|kIM4$3=V8ZH$ctO~%x^yAeIX0N{e8ZnlSsA=}>P~j~mDx2h zAQvG`7ZddR&5~?k52suT_PC$nD}<ZY;I^sXOUpbXbmFH0px97pp4)opmtnS!o@z;k z*tn$Y0?d@*SfIIqlYO$31N)vOj3<Ok-lLD&|9}L(CBK#bAeN)GI3(*^i@%ga^i z?0mBserHVg-ztZ7zjD`<I{^iBiefq_-=DANRiZ}@=h-OPw-uZ-yIcCf=;EX1WwRq! z-r%-Iof>_At0}vHBR*Ls2}gIuU+6=Il<$P`pYst4-?#{~x$?Y(x)J&BdHPm!^TIy6 zP0H)cVYBA@Z|uH39lK=TZhg#CB6bmq>ZLoCdX}E@0@4P}Rv}U|J4Q_~Ia{aX6AH== zx&y*E+W>BYaj}V_p<0u)lT8r8Mw~IM;iO!~akZ~)5FY1(WjF&=t=h1n_}^3VO7ID@ z@Oja>I<oluJF_0Qy$@0MWflLk8Vx^~1P@tioXB5tmYEBmysM*k!rXB`=CDafwWSqV zBoGgkb?=02aGGR}^*g79>k1wNqGdikbiP;{DeEzFp1jOJ=md3(o>7EI(%r|q`H8l- z;c)riZ4-8%w+kO=-G6gA(sKOPw5V@vgiJoN+VEIdp4sol`O3;ksV6nksr9zW;bH_` zrPbU!ZJjQFY<Ak4u>4@OlgtD_ssd3odWQ67T8dGQdO<=-p#rl^*-`tsB$0m-%q8yf zCam{N^1WHxqtg3(KTM5&RP3osR}fq@SwKm=ez<s5&_9Rkznx9B)8oYZ%?(5p=jd}9 z4lOu3)t0E%Wy#Gf;*2YG8KwUmSB+MVE-$l884}9uDry+UZ0qiG!%CBb>Qxr-G}9MA z(fX#`R?Fe#r6ZSplC8oe&}yA(05;Esr0Vu1-+ca(XZz#HNCSv%K?%VAUuXUY6o+^x z>+P)Yk)?3?PTT@`j8Pc3RXj6`&b6$_5}>(ina*OaYG~mO%ovP(+hn?Gt<T^j%Ewhc zUv~KY)_DKdlShAlJaYK^?biOEZ;$r>?mGaVuWgF(&|^52b@I$nvL=_TYg?tu0?83U z3dG{$20qQHW9ef;=U7iJEM=$CLB(-ZDFEAKbOakG4xmT0Mn}H+P>QpTGtLcT3D+vv zZvRVDG0^ZgAmR+@5aWtd*6vOYv1IMFVY{x8z51&t-+dvFW!V2@rGZ6=K7L3}hpgBK zR%AOyfPnUGkjm~*Y*cpeQc07659;`f3%f(DAV6HqQA7i@@H4xz0bw*+W?1)P$a_R< z5!@*UH!8$g#*Ta!DRHhi{=Xy&#(UA!>LofBY)9ndR3O&dPDaQPT>|B~VT0DqLW%R? zt3M&Sv7m?EFk8ZE?m%(VVl@{#(SMxgJy2cI@FoR6B#i}234=ry0Te)bd{?2;LrULc z*myC7+)aBZm!r=j+iNI&<xW`s_Rk2#MG;4SX^dzR>&?BxjRM|iZ2N2^s#)pfY8R_d z)5rIIQCilYspXcdv5qYU$)8;rJF)(%xp}`)w-TkoZrl>fl2FZZynBT>s$k0C4Rz() zGJ@x`YjnA^<wzB_2y(|Z!u(iHl);Go09a~$#4hsfcw*?mZ66@#x_hyPN7Z$Ys~Vp7 zRDd=O>;A~PpH5cz;+C0Vt)StU8nSxo5K!cDd<DsGH$VJmT5)OYf-t>e9wfh;CDErU z!f^y=%cp5l9-E99q=<J+Qgo4{CUb&aKJ>2JBKo-$Gxu@l;PEOfTz`?Q%^a~84znYT zX#b}4Qq@lw<$Aq(SJyS-fCXz^KcQ=Y(+wR`Dg(8pt{$_U`r{s)>MYW>wU)Z;D9@Uf zHUKN2hYU3Ew!6bbF=bOLZmHtFFd$jD>!V_tLbe}$fsP;1*&ennjEby?Vr|nfTVNXu zpMC++d^l`J95zgiIPv#=JcoK_N#LZkb|O8;duB#Qc-WYa6XG~V%E^X(zJBbdvJa=E ziQ^pEqH1^*R`8pno;xJPhD1x}VSkW?8*9@^<SzpV$Q)$N2XCLCvV)aO2!>mXlSkrk z2S0;TMEGr$Vu#ENtS_k(mD@bng-J%S3FbmV8&QUI$J58j>Y<K024r=jW8@EHMcNgc z22k<t;-P$L!+4tagXw0@kRE4M>vy)%=z<negpXk&aEGfmUM6&d4c8$sSfk}kt3C1c zX~B`4AXk^qPFmahU@KyUR>F$?&k>D9N@$sDzG_=#3zQPwo`BZov)%QHW46D^5jVh_ zL|;@rD81fM201I!Q(e}aEsY12aGX&VQb44mZXeEe6k^DJ$<B~DB^gN;aaEb})CNds zt$KTYHvo2A<jn+z3ptnqxm4^_Rz|U?plGqk`tB5mwPD=^=gO11?fF#Vf!3-Py#&^X z17<{h8)VmqQq0W_<Oc>fb7ja4S6*xar7i}S@^4wvyxkGWQ$tsSeIF;*=+5BmucOO$ z$r_SM-)}7FtW%bCC}zJE{+S=a*uFKJgYfAkmjWW~G}@8pAPy{?$_mcmIz&4)zJ2_( zN87&MARJa*C47humdk}0vdD@R!<z26t?lQ{-s1E01(`XQ$QB8?>s~5WTE`z07>!cY z*brOp>f>|oPhIC3tvT_rX9<3<6Yk<}Tdr-JyBepA1ld#I$Cu2{Oqy2c8|QM7%@mE) zA=d}sSZ3aXA6;&X`rJKerK^mM`BPi`uv+Gdfv|xLc|A&Z3*XYv+~=+^I`?5FOS<rY z44=<2>ZJLbYd@$1ERl7PN<|$^TmEU6(_)0Kf8+x(?A|hSh1-$91}mkdmIt)FA=Znf zN}rrm3dwfYM|9ix=4--Z_>DJv&dm9d!%Bua8HSPpINhh&DPl)&p+x?AGn)tY-{j%6 z+Ut%ze?iW#6<iGi8*!YK|B|t2NU<peE9_hXZ`9DB;#dZ^NMM9``76N@Yum@xT!>8} zSc3#N4iZJl>%0Mfcw_m+*W5^hHEf;&)@0EXXUNjISr6In5iMbh9H>IZTpLoe{@&cQ z2f{QZ(UuKL+gtg19CwO%oREt%#=qW`b2VHdzfIGO;DL3QKEGfk$mg9-n5$6Jb$YFK z<ZKbRM;LM_V|Zt;>znVkx3FR797K!yQ7eIEYb7m{k`?VzguLk3A9pNuyIQuQ$~#h_ zBuK>g2N>J)kF5sx(-O||I<F%)_@U3WE(X{T?^I%=p_72z8F+7o+=uA$5)&+a4H77e zMG#5-=X?g7Mxm3zZp)4<=7c{+W}0gKcf@ukD|?l!&KSOGMCQY3&{(-+VU@CrCFizf zj`tD$rwUS8?(&RmBR0`C7pLDxZjWryu+oo>j>3(5+Pjl&k&PAR5WpO6fPaP4fF5Lj zva*FXn?BaHb)q?bwb*ttzy=xxbk;BmrPX6)E_B<4V&pRf%-nIti{xnkEcNS-6?s)M z@!D+$Tg}3_**sdR)lvDr5M%U+=$Mm^VxDaR?sJ!5wUU$el5yudO7ZcJZw=uuob$}g zM{sy2%~Qjgfg_k^sXZ%*l`};0qLV;9&S7`NoDM#8VgH0DzwG9Duifi!`^{%%dN<AK zj$aptbr@io<zZ>&^I~DVu4W3(Vav|Xt#Hjm*7?2i6<YMvNP`H%&^FHuF>Y)y*<rz7 z;!rH9tsy2-?70XgFlCEZUwK9$el@aV534CxA5^TiBI4?nM|Ar@20tN>ubw@z`3-tV zN9Yg4D8bQi9mh7gcDey1jTTYb&gC=nZtdl!{1%FwgZe*{S1BM14?FVXlETz!^E$)M zzP3O4vk5ggQ}jr}PL$Rb`QJLQRwP&}maHETZj=BS&mFnma@3BqdrMV9AZ*ysIou%> ztbt$Ai!s4#U%_AKKDmigsIbtD#Mu{ukJavz^Oj^}eQ(<x{XEYr{|Hr4qSDe9i;2u* za#WHS5+v<jd0a-ZYil?m&dHPoR^UA|E*#cjfw#!RMs%FxD%e1HN<9>;Cp;2W=wv~J z08Fwqg>o>}i3a<jQRZY_N0Bush;aDv+~o&UXx(9JSbE0E(GL8=%HJO9EuWH=`5hT~ zsec1tx7y*}1)r1WW=Yd=(f1VoY~n2Y`o%^`vZ;O{)%mbV>2d;Dr;8k^+L16O-Q|a~ zhsM$Ed+Y%=|5fu?4<7{NYL~EMeR0R4g8nM9$z~L%PKBpZno^UyPkts#M~-N+$kJ;R z^);vE9gvtiS)QJof|cXC?+YsI4zUk3S9~98qoa)mt{nAvYR(xFb9R*cS$-S>{5I;) z2p}6iK<T%A`cqs=V764aPnyq+FeZb{*ks+@VO^q=!OV!2&WaW1X!kP3ykf+@%SlCt z;*dLDpdVJ4Y~rAw#pm`o%sLrzC^`dVT^&aSE=X1_N+uNq1c@vC?0H&MHWe3h|DB?G zB`s~uNuQHtFYB!=FKZfb%aA2#aSGfene*+Pjt)S=%ox?ifZthDYT|@tM22;@AP!4u zXTS1M4wUmTN(LBmo`_9@%wFm~#8{Du;ej)FzQ$afcC2HCi<T1Jru<uABu?vc`?UH> zmei-D=qZZ&%s%dcoUmaZPKOQdfaPfBlHYkd32uT*Ubk_4KjMP*RXqjD@wiOe5#yv0 zTP`I0I>>;fDS2%K6I!oPMzIT0*E6^5qty2uG){Z&q(aA;l7xjJca8>$%Xp{jx}2N- zpJTscOCZBVB^4yIEm0AIv;7(RiLcV68b0^}HeM;#6dRAxS~6j}J%s)4+EoyNtF81$ zA9Ty983G^dTL5`d%u`0JF~hbMkfq*cEk1Q?Aa%m&#{|VzC{9S*Tv%Zjcl$t|PA*Q1 z2~q;&nzd8nZe<+L1<9`2$@3His+jLauNZ9=cYUGTV#<@>Q_^pG+S3io`?S9+ji}oS z{}9+$(>Sy#at2~Yz?s&K*y~tCZ965-Icdb7bVvmo^I;;_{#<PyY&h+u&cGQn9U~$s zI_o2PEJyoP#AS)-fg?6beU9AJ^UW7P`ij@mVt-){6h5AObqb$g%OY#gpOz-15QHoK z_+I<=Zsek#)BEXK`z1rbImfK4>jUMX#b|<^H$*>j*q%$Xsi0_B1{$O|>0Um#byxxm zh*{AIjueErR=@x~%!wwd>RMq{8a_teTKe^ECstV@v+R9$hg6A=y?5y5uA@^9e=pCt zJ$7}W^{~86+yH=mRuE$gG_S4VT0Syt{rc867M^>~-HND)_i-98)H6-Ht@F;Szj9x{ zH-lN6c%;QAq(33*`(3idmu0i~f7%n9Xu37G&phpzZ=!h}X}Y+^snmBXzSesA+L=GS zcNj?#6D6u{Rkk%}qo%7(VxB#y>5VG5=17yat4)b}0yg>k<ZbRrmCTl%?&0rV^W71? z2?shhG<|9<L-x3L(<Elw>iH#^y_$O05*ueO9j`raAZOb0i}l{gvU2%+Q&->Fe{G7E zn=@i&%Vzr%<y#V8zIu4MGx77y^p*EXo$$oaelPmo22C;LhpupKy7{jUSLb9CxI+ll zLOkxVZzp$H$Ye&$sSwx(%OrB$rz>wI=r&8InL9canFC@*R_6Bx@?4~gyl!fH)$QBl z=)Ba~fYoehWVwl_8aT$^?_gL*OQfxd|I@jInUCq(<%Eltr}f8uywShbc)BkB-iE8< z|0y~bZ>Il0jt?_-VZ$)D&D`(i8baoNH{_Bia|@xlh9YBgzl;b)ZOFYMmn7BPFG+Jr z=;l_T%NJ47#c#iVVCQ_!KIe7bpV#~Od_1DB;Xk2l4A_JQ<~-TT=_KJ7Pc3+}b$06b z&XD7v$*(W7FHUgyk5*mLekdoQPZLnS<*KhWTpCzUrsN&ppo7!!LjZb_2zO0zLtvuY z{c?KToILupQSql1E9*OTf{BSMx0}D#GlokeN{A!lmjO(xTOnhR1d|Y>enE|%jYmVK zeFN*Dv}Av5FxpF8xveV7V8uqt<*-uc#f5%8uQ!tb^;d6Vr{ir23C>sxw0`*Xr;;Sc z=sHn%?`bVQMU^|9d>SglO?+NvN9qP>`v|+4?!bhSC~@~rCbcp#wOID1U&3b8Bg`>! z-1VXp@9fcbyW=({9rr6k(1cKi;*-Gr#Sml)oufnI?={9bQLi71JV?g@R~~%)pK<xA z_&;J^o3|@Rblx^F3J+cIM~2*2!{m12kx8^@%bRD=#Wps!%;iXgZjYHnf#a%jkErkJ zsi1Lc<lt?aFCsZSV!rE@R{V*S#o)k}P^}AnVI_Fu8)x;W6>o)HXSfBs14zFX9_$H# zuKkYS@3;}2xJZ=@og23jiu#u$?|g}1mtS2^Eb>b*xqbKTkJmP*UkQ2pE>Z-Oef#Ax z`m5s&S5L-|XCZAb*QV#;aYyZ6zor+Rx-HmVE%ff^0y;WM(beaa)uX1qXAj1QD)Dbr zi?!kU3zwH>KgINXT(J^LHi8RHMkY3~QB5pHk^ayY@}Ku8yK-0fO6wygxAH9)wnz7k z6D?gh$TmE^9cnIVg*h&9Q@w7Wnc>YX*41XIxfD`M7#<X;v7IO^>}Puj3&m;<xV0k& z^PToM(PcDykNO>`4}~WP^Bp3;&fxPe`=I8SKlA6Ec9EZN4f<JH=BIB1e91upV*A-3 ztsm0`j*e?WWa6k|_6j`qKsHPuZcU;(1aCN1T=?aHN7;WG>|^^`aJS8Jbe9NqP@2^5 zLRcA-$mTZ}LWRJwM}>uEx3jw!^TaF{!Gddy?6aiE<G<P{>dVJ&?#Xi<FQ>V!U$+%W zSsoBRBt83Ml%1n;W;!;JG0F}y^N|o1;=iS>ME;Ta5)f-b{FF7V;$PB68dobH3}$m+ z@K969K;$0EN;6^@;xWyM^j$lx7_p*{RQW^+cwH=id>WdP9YDM7HbXEr%)30KVrOe9 z>GiD=?tTD?`Q|RKI=?&dES{F@IaH$_eX8iZ+Mf8H?Wp|Bb`hzSOZW+Gmh)<*Yk^y1 zrPRI>{pQ0$o4s_t{WPEnQ(tAByZHYbUSr9X()9%eqiZY)n7Y_3`-w}&+NkO!?a-u! zRoITd)$WlI$IT&XzUtW6#F})Lea8kD@;q5aZ;t`>UDmw9`}~7m-%3F!O%_uK7&18& z$PZ9K)JnvEKK+#=ttYkgZv10}^|u{3jlzrkRgonUiudqzluhdN=2pKp+ugl5fV|zt z{bQ;r@8T(QOsD^#?9Xe$e%mr=%WOQ-eA`=YqBc9n!B^%17WUIs8B;$u;_-<AKC=wZ zyEyJ(9uMXxZIp;tjtxm8Gjc=6z;}n^Tl|V|_|A|vFhT5C>5g}i!=4AaRB0l_B^YdF zyegnxHLTfae(V!2P~bLev@)tuR?;otI4X~aFF=}tU|JxTl~+yd7Qv|{+%ZbCJlbZ& zqt;)BwWbGaBlxbw9AcvDgJoV-69ass(Lx65syFS#Qn)YQGv|j=Keo@|?(;t`Tos&H z7*_g$1*;p}6=@2{T;7{@^PTh#FhJgmT#xR%JT`doW6*-j?eu)VzGF|Yp;j2Dyt8hm zKT8$eUrczr!p})Mm;y(JG(s=2`e-%cXY#GRA9I+wRizV{FDak3XGZw$Jq(Mf{+zWU zd5*f^Dq11UrQv7~cUP;iTQabxC4HIsim(#J8Cw_BHdSva<S1FBSenLR*Mr7tL9W@H zeCE^8JM3s?9dLM((r&2|W`Q}qHd3nj6LxM=R%l>s7r)7o7d6K<N$j#F68hnnj)KgE z_LqUy+LIx~D-Kh``U&P=7BoED0x&cK>lOd+GtP4|m`SFU;wpJoLZ?>LMDVq)5;^ZC z+5%~{Xcgb6ed8391HH7&y;@;}_N=&l%hB?bsgf4_9Pgg@n~F@;ZyCc{Z>i{pims?p zEq<O?vZ6Pac?{V7Mz2H}akBW2;hdC+f(vg7`$C6|(XNGlbLqm5$6k%z@6Tmk$0<?j zZw#%w-gA{2OpJXkAdxB%RIr(AN6H>G`R`GX=cKGe;LbUn8SUI8SfJRSROqn;?6Y%k z)Ev29K-CU}3N-Wd#Mf|}hJe{3_e66ifWNE+cT7Upz3Q)#7k|HAL0^3MqWb7t{Da?b zcb-H)#z+iiTnDOJ_p{fp=1M(jPOAaVd50mV-^3pmRM*$a3nOVqjrw0Uwd}9z=hIM% zL7cstez!<!OSWvlZDhh1UqpljzAs<1PTIorg}l_(Y-r5XOOWuq^NMTWH)7K8uo!Gh z_q)rPqdHRjw36JH^xyOUNL=phe=UMj<U^yC0&VAdqEg_@E<#YLq^@Oeg(h6%J)F~R z5leEmNnD-;UDQ8v(`U*e9Y4e=yV%Jms}9Nyux#{3$P(KY^tx=}0|t6)#UaZ2L^vEE z(b_*k!~_sgha6IzwdlsQ$%SUD_~7%B|G26(fh%f5IO0+O8GRosbX2m^cR$_OHcUvr zUr?zZX-O2Re<2V;JlQKd)B3y~qK?rg3h0J>H)^u&=@(qzBq2VjmU4O@s!B+I+PhCg z_N<7-5s@UkXu=8-#33k67N}|w@m)bC5G6zIptl3i&K%<Cw*FSU)JPlVa*^aA9woj~ zgG@h|oBFbc`0vj)oI?x2y#t?h2J&e=G*=Vtq>E}3(R&<xedd@wTh;pv(aAMbYQM-b zQ6z)|Z5BeJO(4@bd4-9d*#vax%5<i^z`$VVE{ABQv)I%s_`Qt8%@!ekvVgXLq3(0F zlc1_p4m8D9NOuM4&!H(t<GaH#iGoN4;86!0Qgs57NB@ZYtYyqR*#Z)vg-VxrJk8b5 zEqQ{Lz~3%emKWZNhZQnVpYbs76|axjdbf`#BgXNV+d-Y_ybUsFwH20a@p+&P=KTko ziaNp6sHPIU#I>(p8<7$p@e<y4NZ_WZtqVpnT4Il!(}~6SY+mUliUrh*rjk+7975Mt zB+*miF%A!U@j^AO;+qIDmb9qG1V$z3E-6N`azrx8?IHaFA%G0$R1;d4_n>`K?n@W( z#)`?P&+J79#!Mm`&5;z^)xGJfnW3tCL}4GY_zX|b{Ti`SycjM<)SE-lxpB!1Z-2S? z-JEO-Xa4?m4vi5x*)^gNFBus?lsq6y9-S1FtXa7>LB!NW<9=|6I1^F-`X&FYODI}M z#=Gh8rvFO5uU)>0{zeXuAtS>XXzhME?|$S*yx1OxYA1(ECQka+E^5Hq&fj8euf0u; zIBT1uU$JiI$T5f07Bk{NqFcl$MArb<W<vd~dc2PhT;uwR$vUUV9$8GALrCx{W`yJC z1{ulZkYW}}*5SYSb0Bf<5}H9;X?N}@=xAeyv|kE6+=Yl7`b$}pk#~VeRv;Sbf=njz zj-Na6`k4}8Ou%fzc2CO=5j>knE~SxfDijD#)}(r4tEXgdnQ@4fj){3fA$IQidtb%Y z1L^*Zye%Rsjst1HKub=R9|hpeI5Tj~E65n4;5yLH2qF1G$OIE>61`WO7Ab|pT6PkV zokX8iE7Tu&eatuIV+u1kO;FydGM6Cl6|BUQT{AB&Oaenpl8SDdJ0r8F+Q1<y-mrH7 zjiC_HMp%*cPt9%N$eTp;wSMs}hC~2Ww3!27Kt>+o#X&=yzp)}y9KwlM>&<NK0yr>s zkFYsW*hz$bS(`}2pQ&d&&Ce3d=ZY?g3#{l@vs{5iV9|S5d8u0hrI2@))@YR#(biH~ z(u$y^fR}lu@m|=*b=#w<)jb@C=tsO$HFhME+!E0wPQjYu$)XE*7Y;6|L$atdS;_!E z^rOz$ZcyS#j7wWD*GFLAXS0zE;ubwjLmqI5;22lXr5m1MLLc$SnjE7^8O+EoOI-fK zSjLGQ94+K(XBvNW_kH0Z4xtKi@G2e?Gu&AM%PHLmB7h)WMDck+)4SnbIz)*f^42#_ z@x630IkLb89_L?z*}&rKu+AId)>a8VP4NkB`#~q{hkEcrhiRB~s_6QvppTtI+)C5N zPLUB&SX=YExH5Wc$JR7HaF;A%ge|o{Z>+uPFUg&{8rk$@uC$bxqY-CVydt<kCK91S znRrP$BP0SO-m8Sx!iuukBTqwQW&@cm48YC)N)QZQ(RckC%8w?B&tQc}9+<>_<D>hz zhPLBD&fI9ADB4z8-Ev2{B_Q+|V`*DC#oDgX6VLBM6a{#WSE%T(%7-`T$EY}n0wYpy z5>X%V{TqyK<52-Do>LDiuCFf|LzJ4t3e<57{=-^`EBT=Zr4{6&l0+YxxAO7c!|1Nm zm6FjzBn@3BFEf`MLX*)hUeKD#+f;KLS)OfBU|f&&++zsdHA7QY-db;xEHee`v6$}u zTN?$jHh9ryf|tz$FQ=axABkvGzvVrmAO(;6L6kHmO3g6_b|DKYK%Lh=!g_YF2F(|R z7w!VB$Y=1T(_~ROvRDs3?%p`E(aE^}VzLmAaxqfuJ~^~<{fXK|@uLvDfI0S4Rb6zT zh3+|FNbMF_6D#KI<kW<fNWe?-M`T@4;A^mA)Q~X&41p~M=722J%D{Zfo}6DX=RH7A zeMq}q5hS!~Eqai<sbb7CEQDr==<*1KlhHmGgnCY1t{zeiC0)jO1RBIduY64|D=(GA zUI^*$L)=&WR_y=vPR`a>!z&G9Rd?Sf;6*tLf9&z#6IUc_`i*$70|8jkL#)&sS!nWZ zTI^hIyTR2P%6c(mcm>v{CfKl?D7MSd<`Yf*ZgApN&+)k6%mhbp*`%rngSv-BPXR=~ zDHq~LqEfBqhLD@S#1PJ3-XA$c316724;;1oPmdDWb4U0{4v*6A$Fy+(60zh34p*&H zS06r1r)$ar=zQMKg&|Hp*BD-!j7z@prDx)e+=5BEA-hIc)zyXkTNFNVu$M3v7zzM2 znn`raTz)EZCM|fbLe#)(BsQ`_e25`pwjxOr%iGP6*y1QU=oc4s{yaq%O*fRBVMqe# z0<DaM_IT?@zv@0`OD*Y0knn<WWOPlXxTUC2a=*Z#{Wxc`Yp(vkO#OP5^4Tg8Pbo&A z<I0{J7D$l>mC!R-=fqWt@1I$?^^QmA&x=g2J0jK$TDvWvrN5k=S|`CJ1q;g$$WU#v zRDQo?Gl%duMvm*@os~mh^Dmg0Avu2{#<xHG=myb;wSX)kn-~?84m?+xwGpj%nI#yG zd$L^Jv|5Jn{4^s_8`J*yS3OJe2Ft>6I$i88@I28$w8H5`xax`C2+>616$wYia;bQ? zzr??ORP#p>ZJiryz1@+gExv?``DzOV5YgSC+@Cl^5;$aSh@e*<_KJ5d(TGj3N48TI zNjs|V0$vtPMxxC*nyCKwU);$aC^5KgBw-)BVJwkb&;4Te6Mc&)O2LbxR8|I5EM4#t zrbMZE4oQXnFDJ!wFI;;1>$EN|9n-gr_9h|{T~Mw1V!jNuKQ6a|V4}2dOCPaf--3k- zS04_;8>VfJXOH&kM+N|oA<>`T-lPa0&1=uWlDirqVm(-m5eW^+T|pV6R1Ta-B8OBs z-()WtqfHhMV8B`Z7y{lY^wHCtzA^dL%3l9_SVry^ap|ULM|muIZ&OeSFQbYV@az`} z!J*eVytc${rHP9TWC|K__zM(?W@2e7csv!~)<E9V6-;>{<F-dci5S^pu@bEu;y?mm zpT}_skHInchI@^E;e{yu*A*G)KSaS&Z{q^v8Tq%;jhXB-4ErP}_QVnsR6Cic6W-J> zutvtLa8PYEFEK7r$;s%kH=d|hb|<;d#D37Tj1~WZ$_(teUmAtV6g%~iL#VS~eCl=V zp2eBC^NfLs$JnLQzloAZx(vz872$2tOjGre>SOpJ2j8~Zx$FG`6UN~wr$jPJFL&Tk z^#gV|Uw^0cb~O$!&Ks(ojKZ$f+caCXsxKRV;6g|r`hkgt_Gs**1V>Qek9DeKADO{a zX`Nz-=`t`(yj1H75@PYR<?(7>U)o=+I0)OL*Z)Admpz&G0t~#<9)?OBdppeaj?^#U zi5F<CnN4#J3b*i(G&-s=nra}1_<}V$DdNedJ$Mejb43d+_!HKzG+(pk3k^gM@ZtwV zOd^r<<=AS|ld-=mm;>ox92wa>Cca06&W#Tdy>sk4Cd(x*J(YahK#mFP7d)7J>tG<3 zh{c5T3rw{{A34?=1bR1jb1>1n&B><o+Qe&}Uta8!nQ(L~;QO;EC!vZbl68zYRKIYz z=uFGM-S<lh0<p-O4kt$NXdH3TdRC1owQ0st?rPdD)F6Vy3!Jp_7dq{c3(2ti&;J%K zQzuT{$Jn%+IFWt{$=UXTdKPegWZ^NRzwl_GC0mG1Bka||u*{s0yx*IS>a+p~%rc=; ztk3Ek6MwgCWB~lvMKINJ-{UN1VL91Wuf4z)V~<7FSbn)JKCFesR83(&dF7eTT&MJ3 z0R%|)kY~0EYQ2gij-`~3B|QS|Tz`=DYU{&9XQ8A~%*^4=F6T1l_!WTtb>kfE+Y@DK zr+Y6SfpzL9D|OE=_2uX^OjR3SI{YK{{Z^Y}U%<44UOxJs!`_}rjh@S?j*z9&O|}C8 z(-GwRD0zP(VoBGg^rQT1qsY&%?#-_HZQgdNXp30vTzq`#L8Ym0#Ye-}phWcJq&DaN zlAobh@0=+NU1|1!imJP|=zdj!6i7aH{6x0`9&=vSJHMg*VXHwvs^?1A*dMOtB01J# z=lR!93XVVc_O>tS=n@|jot9c<O>`6eeDZNnMNj0c;&_>9<iMAYgGl|#g|7jx6kaE^ zUPUEEbj5yBxmMntcrIc%()w8HpT0w*{+VM%ryux^nZ<Ly<W+bq8JlnXD{jEi^jA<V z-FQ9N{0O309~Uqo`_R7weqzmA$2FAI7z@_?Ta__oz5c}_Q&FaU_H>@c6W+jl?J3(p z=PzxuMT)h)18|e;ELoWQk}(fdqi=F{QopCI<c02r;pSUiSU><+y>ord<Dy^KxQA)a zWJ!_CFM>SAFL6<iPj!z}o2Pn%r47-TT|NfadrkPBuhGd`gB_bPuyE3QNzy@?{2H6h zLzTD1*sINycD%?GVhH8w{3#8UIU%|;P-uAXuV-LmO`&~wQ+@81vdZ1i0KOBwqydD< zMK=o<_1d}n&y9P6YF=J-(H6Rv-Wm~*Yg|(GK>i{jCOATUzf{}dWbjnObKUPf=Jr?U zJ?Te|rr#sn%d}&IYehBaW8sQ=TX!#g!oA$c$YE3kY3Hgwv>be4I6o(wuOL=t%WwDx zCgh-SFK(hHqCsPlG{}Dfrgi+NPY^2CzU>ZIeuUFIuk$^~0;1Z()Xp_!hCD1Y4R{!k zqcqEk9WQ&9%yZ4O({?x7IB!Eo;c~D_ZGq{c+I@)f<YaA;&T}P;JAR8Bvb)AFTAzJu zP5c-O)_ptIQDpjPn>vB}vt2u>bQGXMQhQ5EFFc`U4!ig!=7rNSLR4S|RQV>o;{~o_ zgL9!bZHE0r=PEe!aL*^pig2rtK!|#E_WeB5*Fjtm?WO5HPt(r5G6#)A@70^WOQnWK zMYv9b`?mVa_Q4-F<KOP@$^SaZrS#IHC9liit<v1{Cv$T#ISPYwu@D2f8WWP*W@13$ z>kF@(QugQ1Vjc|j(bB<2^Rz*z!eHZZ$I;hw7GU-62)A7I*8JT(^|I2Kajjn)76okA zDktPx)x8g;K0{VwzgVZ%>NzpNfK1`)4XSb+171Hqs^OmVcGg;p@5H9_#TSX7`Ciw8 zs6T}gFVn0|*!5q>xpeqLfEg1ve9UDp5S0S}<WVvnOKy>}jMtwV{bTp5=~&E+G|1?1 z8Ir7Paq(gAP!$Xbcg(NB?;eP7b``_zr2|8bW~bO|hIYtQt>AVx)UQ+v9&}_jfP`#O zSPF>>hsy!T)Wv1cEe4!$pux^LGU(15NLy((#2YYbI)QET>cojWMC1%4^N!ov$CPLm zFPIwlX9dzTP=9)W;vcp0ciJ7i#_1EcJ_-m&8U&&Q>+(!#c<@ntyF>lL(4{JUc%o7O zdUo5})T|x+`$L8>Juy&ntx?o_=sfCS$6Bvx<1JH2_;pG+NEJuU4Sth>;aD5hHr^Su z>sv*CMuAC6Ia6`X-;)I`vVw6Oe6ocB$ja=AxjDTeZ+5JMckfhX(5H6iIdjzsH&3to z(@-DO_xu`n%B99=h<$dA50ODJ?#A{9u3BlfvZ!ajZ92vWuN?`lX4hkQtOmlBZVLdG ztrT?o`R0Ong{L=oj1=18#jUXo#$THTqlOC83uHt%pAG5aT%pqHT({abD4lAycbeGE z<o3xD{IT*PALE*H&d)M^_lS8`tPJ6zwzJxaT9W|-Q3>LA?9ux?Zs*>C&!6A*!#u(k zns9C+e@hE!<M6o-VJad&w{6r6c8cPSXBzS&TLY6~Yp=WsK)zlcGCt@B`+W&SqWwgP zhn$_=;elbl2d(rc-C4n#8Cv7n^e;*aunQgmB96Pc#!6a>P1*XU?q8qj8zqkRXb;`J zsD9VrW;7((G6VH{Axi@{-JG0gF12;Qqe3WN7!AMp=*`hSm~gZLaf~R!ytMshtlge> z;e&l;lcj=(_4zV~FX;~F?eg>m<6Xf&VpZ_xt(5v0@RTa~JAJ@cmG7XZAJ560c@EpG zE^W^<y?&B1-8y2LeZMHwS5|z#k>}h|ah_MJh1A~zpi$h?TVzY(u;#BU?N`O%^J;^A z-xG(PW$rBU8d=oF*|{YKjT@%?F^7#Ve>xxLCG6O`3OUE_!gj{I=Efd4nxy_Wi&pBQ zErm%;Nl$7B#<=0_76!0OS;x$4SL(Axh1py@0KGq_q^Dpw?rv-@b+E{q6)4)U0Fv8k z&yVu|inLuDHoeil)?HI9+;#iEs}Tx0iFFzYNlo)d^6LV*h#_g9t+ce(?f7Mb-R_FS znftv}(MYefhdqjZ)+R#|O=L$o@#!&H(J$?V0qoVg%JrMoSNI}sCTwAn4fvE3cRmI8 z7+oH3v{6gIZ%(h?9(~Q;`8($=sRa)rYZ84zi>m5AFQ=pL@RAV$X+UnNXI(WP?wyIl z+XSo0lCVzpk3FA<;{{Yiz5||{{d-Q_%fX9(RvI-zv=<rjTv~zMT8F#z=UmdY5Te`i zf`3{;yeJ#Y-|<Vj-4hSP)@!es&)$3Ctk~%s;fi6TF&`GU@!6-Pm*>>`r{6o!^)?$8 zdqKZw>;AYX^y8<C^6JXEBkg&P+Zh%@NxTL=N7Q@=QjPf0#^{o5Ol{`*l+Sa|l5L~3 zvQqs;L|!k{rf#(7=xp4Z`1_^ZBfNj4ixRAP&0u7-S?yNS`kL~ug<*Y9GSH(G&%e7d zm>x3v<L?jeEA+I_*SaDucr@sqfC%WEDI2JbO0<|?re_zOG0AyFUuD1UMz36o4ts)Y z#NWL!H*F=)2+nZv-Pqv1S>tp(ai7yc=SH&<nl0?BZXc<^ozj-1*!xX!YM2fF)!Hx2 zX{Z!;d4b9_ATglHds_FBgs~qs`>SqeeSFW=K4O|bTI5(I(_Tf$8gPdn9b9e394!OY z4x{06^BF}iy+I~8EWCzr0#eL($5Nv`{z&cguI{)$#3R5^O#XPtZbEbxx~~mtbq&H` zYI<~^UcY}rQYU4L6NMfQZ?#q$06>2;<D5S6J&WgWV}k#(;O#i@1`Yc8r@q;T^Sh($ zM1TZ6z~V@nKUq3qjLDOs<)k7kvxkW1q*|MEo$h6w2*CRH;0%8cxk&OxeP=@IrTw1_ z2)|xF`&~NtcW|cX2%=|OJweyBrcUG9Ao5}v1yYQ`#;MQa_;1*xa%u7JlfY{vegFWP zLgTMmhW^`@Fxtq-8_VvDmi=P}dYGnFfzW(L*RvmkzBW^eybr#CfDSOBY!u#ae+Zq% z*Sqc8LeQO$Nt^ZzzBdHwYdDfxWJs~0o3{y<b7PJE#5>+Ch3)I6?1dQ8aBz9Ktjlu5 zd)J^UC_W($0U^A26$1K~B{0tf_p#0!^<)%`6}+_-8nosOV)FOV!FQRkHbo^|?TNXx z!0&XvE*!K4pdLGy)4_sNZ$rn^bW!p?wZqbta(T|Ha*HI`H9CBk&b!;D`_~pvu&{Z) z9xG8N`qTg}jWmb!^F6~UVfSn*rD6Nb^iJ#Z@0jrRWyrrYeyL)ud=~7;pI<OA`JK{L zokhXH1ZV*bQAvPT(o_C^%Ic%TrGTgxI8<Y)QQdYBhlsz!+GU9@gQTG2`+9sm%e*QU z@Y^iNC!EID`lA!O9*RHrBonmtjJ*`!;NTl<WGIRM^eoZ01Ae&!zGnv4uFu~m@m=EO zf5pmr!vudali`fzuLM9mvI2C&DzYjCj{q{1GT$};__u!!j;k~}Uhz4?{y@NCLR#2! z#8dK^PaAL0#<Wj;n@bE9PAP|<mk(dR&*%Ce(?bZAz60x{L7y|hbT%}$4ceXtX-7co z=-_^_D#lgl9xb(xMtnY&j%>er*<EIa3I8n(Uf3`BLV{=KRO=?m{@jMQ)4_k};65h2 z7648AarJ-;wP|QyN6>CI^l_i}Xuk>vC|_JM1J~0nC!~#TFY`9dUT*oN+r@<36EpZu zID!u{p$z~?EkNC~21-MuFi=pd6-Wbt(a>gEV+Orz2KwX4kCIisVRQZyOQ}%+$Jqgo zGlQ#^RI6_loKi&An(?*Kpv!6ewP_GVq|8>?O-~Ee?@0W=xU_Q{I-$DQJ|21J7^P}D zjkiuZ7Xklga6IypeO;U7X1e_#6RZ`;MifOD*Oto5>V<?|i#eqfCkXAu@p`U;8%Ubv zoZ{1F;*BK8Pnx&{2LPVSr;+5WvDLu7VOmau)H3-RNc<pT;3q>p6Z;F_)4)B5I#Qjh z+ihqbOEpxBwnEnJjW>FD5=_bP@7u8NC4ucMlm^?NwbGEsW)PQ+!m8^>@DiG?k7p%C z8-fWVSDQhvra>yn{IAU5FPY$d1TIw!_ZxxTUoOepZ+M=Ye5{5)<2v}Q1#F!K+Zlki z5fri9QiQ}HV^2|ZEVzd*9L}g4V}f?lT$7H8=59kD%vIjX0k<Jq4=Lb!63it-&T+7* zma1pc9DJ<_o?`)LMAOHZkhNUM49nLj$F?Gd{|_R!4gf1$Zx#LBDwqKoCm4SxSbm~G z>2%oAR&8%BoW?4R+}G{#KThnInn1t<=!C!5`3C7Hx=En_w1U^QVWUjQejBu#g?hIN z<5|dC@+S*~*}P~w`AP=1^z(QGSgw`{A-dn#lID{jA1RM<-HhxgKta3vf54y6p^I!+ zJBi=rm0ppVO;it_u$Jo-s}LFoeoPZ_kr64}hF(>8@J<jieZQ<z2mYE9Qkh|Y9ZZg< zSf9+(s0aBzGAkWxys!!g9c9z~Xkd?@<?AGVokZg-0zXl;mv6K>p8yX^gFS`t53%44 z+q|hO-3|JlT;lgSXLUcgd2m+3U~ckFT(^?&eA@`fn>Oh(kVf7zFTzr)>yl$$i-P>4 zP7@ox#<={HlWmS0yq5TY)KfD1Oz=M@lp%Vx*5S$9uIjgju);<7JV4+#0$M?Wp=bT) z(!&3Xy*MXxIo|d7qbw0{I<$xhGdkW>6L<vf*hX{nYIH60-cB}Dmau`wfGq^m8AE(+ zW~yV}zO$WI7nzWyJn@+{$u(Wrg2xm2zJND|{MXa?L(>q;2)<G`?Ft%fl^Oe!5`I@& zstanvTPLUfT55^S5Ck+mAMN|ENjRXU5*?`4(FT4$LG$x)jJ_T02Z9=eBwc)&k{Azp zMdN>Ijr>g0oEe56ErW}fOU$|iwG5vqOpYwbY8AJ^E9i0a2)=JE;NNT%DE-b0X6)W+ zRl-hWq@M5q4$fD~7rNunUTOq06xP%^VKzW5NrQFzLoWUt+9MCXHcD}~K-syb$9ThW z6(uWlcrA_hIY8n%0-Bx3`<iq#qQ)3G`+B6q@tEKmc!~~AX@jmK_)-?mov(?GsXYD$ z2bm-p&i-)u@05BqO(eDi_Vkz(f5fAKWmrR)G@TUIejQ%^#-lb~{Vu@<Yw*|u*3~+n z@{#}-_Tfjk!aoBpM0|&33-b>VVQS5SKS|XJ<QJWjFXpd$Kgb;fY4QK|@5ch=(mdc> z@+}eE9__Loem&B&%*Za%Q>*;R!zOqO?)2ZQHeZus{)Q^Jd_RVfpQ4b%QGF?I8<02s zL+BiQ8zlZ7CeO<R=q3yPVHqsTA@Q^7g?#&qzp%OJ?-D11uH2=;F3s|70Kfw*K2{s- z6BAaQ27ZJ?RnV^Yg&sYcErHjzJ$k&&8!;3$)8~5V4z&fqZI6$;4Lt9@VFiRd?wt*; zB~*F&rmvd8X=d;waKWoKIIGR*eG5N;CMhB@M}2GYPrC6YlkfUA%s1oy9w~<_1y(}? zPcq<d+A2@_1bg<wN?1_3Kcu9aR<cw?afEWefj~GRqGgj(jj*Y-w)Zl_*q6Z$iEg*5 zFtxN-)jux`A^0|FunZdfvp+w;Uz`%TFrH#^f&!@{z^6#OzX|YOCUjrg=?#mxBMk{6 zK!dV$e~0=%WOr<_kUTSJ$vpGa-=Vx8yr3H1$I@_}b7>+@!QTO5mpPTT>|Pg6K>H8J zXDs14u}AzD4H47ZaYFz={W9+$g70VA?6-5yiaWEWZ)YbWS84@M-6Qcf000eX5W(Y+ zPie)-5k4M<X}v$R5&)&OLs|7OSuSYhGB01^iOp(J%Vewj8P+Ybu+c1_C4gJc3|djJ zCiU~COJL8O*UajN_jag|3^(|HwfysG<-belpW>lMZLn+)=O_9rqWm9gcW33aT%HH_ zPFV8KZ66;Cy+*Ny4<g_l(x09p;O<~}2aX_OKrif=k39~rWxb;-!F8p9<^YZs=7X;y z%`e%-TI1IeNc%sJ6=o<i(z<US^`$$Nm;Yvh-?HHSb|Z#=*~$rup7Jwd;a0bR1Xk+^ zPV?v6!ol-t&ER&M%cYpRw3`%}@?Q*%gcM)2{t)IlZFi@$llAVOEL@MUfd%xGM<}2J zpI#XVo)xt}di6f8V3^>*SIbIz_6rdYi~iYms)5O0g@DO$P|n`m`utDE>>xX<E&tAO zNR0t}m5|>(#aD+@eNB_w`~08pyy9XS*lp(C-|UyF=UoZuo{9)Aa|CDh8L4BYO(z+m z!;+;}q7^$*6ffSl$635&0r=+XF31HH<2p1iD<QaC1=g5e>wtiK`t4lmi<YTxdM>hG zwk=WtU;u#sZyNMg(6v=umf7xnQG>=CCTwU-*D5vh+&b)VnfL90FjyN}wtd9k0^m6( zwX@T|_b(TGO*Y-s{z6D@@hi5`WI8J)8<Da=#GZhs5ZVv|;sP83e@Ku3uIfQr^jhbL z{(nE!1y4O;@$5_U!CJVV*JDC*?5C{novgj->Hd^UeC&KR-z-V(;tkj@63k<fxGl|t z>F}(3>tX7t9dJQ0ooxRmO+9R!mzD+!W$|V)c{^NwSJJ>wz)<UGbFv4#Gc)TF?|o5O zzI7ISY=Zkcq2kKDKaZnjPt<{D)4J~N@*Xa~m+pj(HNXC@TAa$;v}e*p$p_z9W*@QP z5db{B0^afAQ9waV^zQXp)jf*98VvxAiGn_rmVasnK4d~;I1mHCqup?Y)^hdJPyGcZ z>Ne+$W7ZGI9U)(rx<Z$SqE{cltA|qQN`Fs}7D@q1l|AkTEzW#!sL%?Ysyj9N(W%NX z{@eQE>?apG{?fnGBaLTGQU^66#a|ViW+z9tiUahDmUO~Tb%ng`cDmK(@T*jB)^q;L zsm_oan>sJ;&fX7;UR;_fe;)PZ^0{?oiI4{oI`_l6f@iao&(5Fw{&CZ&tjS&R^iB!b z-MHw6e)t$}`qIc99lfYGjmq_2$rWvvuc<9wr$9XQa+YgOy|D>Lorrt*;_q7N#w|le zKNYTc=FLI$`gob@xpUtz4DUaO!_Dz9!N-j+>)dWX==wb0`aKbUUGYe*&3`YW>y(i` zU)24}t-dMyH(cH~d#+IyyPyYZ{*U(hxvwVC!$Beh{hWN!sE>=8Pb2EV+ZE0miy-4W zz2PA@f-@PTW$se~G?Dp$CXiHW&7z{n$pb^hV{tSYu4`AEch4D0#?D3CpfBz1j8<G< z<12`#$#7S@ON;Sb52rU}33+ZrgH&N1F(K$*dt$049nwI@TMqAHT`&a4%7zn<C~QTi z)y9&x#1Y%7(B^ob!6VWfO0>pIgWNNpYLqQnixTQu1^dnkN>EFao7+P$p}UOWQb%WU z=B;Sk6~&qq-!C>Or!x;n>n?rc*gbjD-6P(^vs`B!6ZWyfy7$Ps%5GG6mrl+^6F(k5 zsS4L@vU>Kt=cEJ1$8kKXQtNoMr3B!Ys?x2qQ)4z2PuQQ5xJRYa^=*#0cDA$VBRRp@ ztSC5Gd^+{*mc4HP!{$-=5cZ?wj`ybARbO0EJtpkO4zHD)E&jtT@uRSKVx~mG0ny{@ zsZX~YQ7c)PGl_VJh&S7prFHggiuEm@`le?KPrF}+h&!z3sES1vCQ;hdUxq7Sl2w$c zUQbyQ)~qBo0a@*anKB`E6Yb$Ts^!hw@SA@Am7>j2HCrK7DXsW=QEjv0so|o7@nB>M ztXP4VJ?nWXvio)YxE$bL<;N1Q`9*o5c#Q&TapX`^rtne9-NUjQVP@0X5~VNQKn|X} zb_!xC-desA7gGKup^}h>)@tVv$DpA;8Uhw*W%)0LA3A%h8?FW}#V5Cz?h#AQG(Qwj z6pz^@T8Qd#*nW~E&Eu))Gupq-&0T%tnVR(RhD}-ZmAM?NSziM~#p_WAL~38M^mIeZ ze>k}}zfTBh=Ha{#y+uOYCC9B>L!8UqD}DFct%{Rk#^>)Pg+HW-_@M5_+|)Ts8T*+3 z%9ZQ#p>$C~^A9GEXQ0?V%Tlcq4@uqU^54gyHDz{gtQ)#eWaWt9lz@^e^Z}s;?<~ce zu0^?DYSDKW&MYGnv6ku}($bPAJf%lHg}^BqsN#NP+Km?p8-5Y{oRFEK!cnx_sDUZj zu+&UXgazz>$}-)1=0l1GC&OgP%dbb|A(r==r=8Q0lU9a5u=$SpGNM~OS&IDEpe}Q~ z^1K!m;J*hpX4eqZhs)f`-CDWf`Gex`q(KIISg`(f7;5E`s0ogo#}ny#^?Z|+;_eFC zo>ij}G`;>SwYwm3j6?GygGX6%2b!|Zmi(oOC?9LGOOYPT4>(DGG^PYjsS_v=Xa(KV zjph%aaY>Qph9Zp_g;$0KgziCt^zI}*?|R%US;yuYR*@k^>N67iY#^6+KeWY{H|tbb zrhJx%p~k+ASkMgBG<k=Y`50{CQ+LbM{%9pT31%TygBaEgs^lYlVO<VA1yv;xh0h%B znir`dfa*Safi;5?@7hKT4+NlgUt~lEy|Yf};vpsh?zdHgH;a~k6uGajidC|ZT6eVy zqgfV`B`lCacyS(X*Ue%N#jVj<+AGJ|E<zu(QIx~N4-tsqsfrO}Bu7z%tvT}6I@LI& zvdCaq`6fvaR1r6=+hA2H9zx0G%Bi%5Kr$qcb%AsPfO$4_Bw&jL)DjdKxCZiU%Mga_ zMQP>42gwNS(MGK9;){~~)5U)qQ00=b{5-^u<^xP%dnzy1-7S+|ohIKIp7g9^o2M+7 zL=nb}=3kbJLw`8_RsBUr&yhn-eEwXh^vgF8eAHYZa-hQ2gk)40x?OuCi*B=Lz)@H# z=-E4a``c^!&zxkI1@w?+ZOzo;kNXlJ>J^wLN78~tXIo?X=$0po6Ljxw1R~G1ai1KO zIZ?W3Rlk##Ay5C&6E=BY<G@cz2likJMt*U8xn;si)5npJ^rdI4%i5$Dn;Up}74vTy zh_ls3Qa!weWEECUMD^!f@n1zMvl$F``{CYIHRv}R)+XzCsBKj&x^MTL?!Td1m;b<` z{gR$3SrWmnleN-5Ul`>*jq2K!=I9t2O!G%6A;od9`@x&cklsOI$r9K8pg3x9r_l8V zZ{6bYo*|===z{+Wk7|dD(uc{mt_A1W(&#k#=v#mDovu2zB7UQ6#OpZEo!<*Y)-H^? zH?QysNO1{O_;c%6Gx(z8WL>|rM$0~~<d1TYkdJ9Lic`QP>P^+`8*Ol7mEvb%lC_WD zZHbYmJ4C$l2k`#?_>c7t@QvwDXn&`PJC7$7#?EnxSJv}fKT(>O;u|#3Qwy>WjOL9y z`QIQQ?X{!h%-0iHr{C~B8a)w%ZPu4e$B<IBG*BM*8YgRu_X!~CAqnhWQNu<oT+~c1 zCOE1Ugbh@~AC&Z3xkKzRm)nMtFJg=A7gn#9nQl#2<Zr)t&V?M^$ka)7;)`b0iit^B zuUK+Ge3v;zj(RqL8gYy~pZozNJ<aN0rdED3lZ2^Q<~EGTofUD&Ky~4VO%Aod-aV@# zwY_#tOp~Za8!20b%`8P+cW7Lvf%tx+Q~e_>|D@>$w<;EQ*J^Y^(va-er!<@7u31<V zVIZ#YV+s6~EF=XdE9U2P+c+Fg5349)=T4yt3*29Jc`ZyU(=5fc+4mL9HPKP}AFU7p zc#yO#`tiZAX0leUIdWC74n@`IX@@$$$&h^Cl{sHaF7!4Fkogm8jp6Mt5--bDaQ@UW zmvZ!bop)U5;TTmzd%9-+^zLVPomRo^5^&SBhVC=^j`ovSdG9z8KPS_JPmsW#pK@Hy zcN&j?>Z|zI>OZ$NovKCxlJJc_W}L`>na!r1?R?J;de!FAsHV*V*QEwq&#?-V3_w?A zfwqW@vj)_t?9AHj%=|>8Gd+t$1APdfvN3<_ize<Irtm*zYi11pP)ghwFs=tkG|L+8 z<rjZe$YK>XH7aVa>alTANhs<sdYAl?h~jZ*Fg<HD5ekTfpBdvZL~y5umYx8&sBhti zQB*e0%(UWZB8x}06&gHdUN@fki=fE;h(T;D566{{p}3t`6jv081VFVG*QXlrgb{dB z6M+`e;Mk4F<r}hyHx{OUa&pL2UluTV47B)6*$q(eJ~uabA<HpQ2{%aFJ|aqIm`erj z<PDRlBh!yY$<Q-|%)}l}C0d5u0%dVR^JPtD1kF$jK|OS*V;suW`+yS3)iEnT;sOt8 zEb9!5Vh{rg*vLx4;Zb;=+#GI`FBU<LBdgmySC)BB=W|~HlogT+tjGC@x&8G!xfW#6 zuNIQ0h4Pb{x%Cg~oG5war>Lq3PHY;$AW`;0Y4h9!$T{y}<!|aK1n4Bis<vIy$6h*| zm6@Cf^bJLZ0<x0FGBsBz7C_7RM1dH#PZ&k9Sm3!r;t%e#&Hs{<yT=w}@oloW9qA~i zg{<H-5N`>+y5*sbaj8Td)veW%QzkD7K|SMr%PB%6(I5kLgh)rwGInwDb-P_`K-!G9 znBVm*W`_YC340W(c|}dsYmDbSz|3ackYgNZ=TC{-$coA4O(kX8^Z?<fv+~s(Iy!SC z$lT6j+!2H<(qg82MY)J$Em+0mtr7AM7qw2;O8xqc=gOn6N|3q>JZjlw6fgN?W7gj^ z8$(w*;|nlIdNiz&df8sjJ;wfu@nct1mWZ)Vl#*>SD>J3ijL*lydx7dp%gh}b?1*@N z|4Z$aWstQ2^_Xv#gFn^LK=xxsCU^#D6L+1BzjFn&Xb>Iye~U?%0&l2|0&0Q3nLtBc zZUbKKWR|x4Vb$G4N44vq5Z0pu8qYrMD(3{~(@~vZ!zQc}&-1Ca`b%S0n89<$Z0<9( zLPZXMb0XCw*6FXY1BKD+j-tjgK@rPYj>{RzN_G#-?KU1cSc+vPk*II#?zE?iq>#96 z5a!H$y@#`cDKu<~H&9g&Bn3nGZBbO>;IV8!(7{N1iPaTg!OtqK21Gq?`0du$AlNE* z0`Jh3Pzn*i_zRoKN0tz6Gm;vaZ@rNvz~j9^mSw;x$Fw^;YI(}d<2T+|rjUT{be;>Y zAo5sNV%xRQO2uDGKvg$TNRrq=1u`WY^Q`phRPyxn81M{}pC>Q(I9Z=W&~V&FJ1>LY z^>9;nvI3EA7H<b*j#Iohva)~xuOk#CvT;Nq(y|5TV)?KHXDIe$4&*mBRF0os;FSEH zMhm0!>{{3}dxRVaBBMD_uaqh__0D7yU(uP@W?Op4wlvr~({j^;=P|{bc5*o;H#wW? zzK|8VV8lksT73qVEVF3|-4@lJ2(<?h%NeO-1#yT>KLFLCqJ3$F{{BzdIb2)qDf|7a zS9x5WV;$Wyw7Ffyq3B7F-gK6J*lgqm#fiy1`q0j+ATMx%;w|1+YUc%sr)r<i1VS;u zSc2mMHKev&v`)NbjFOxU8nrhMNu*fQZJl{RVYfYt%Z#vC;7R|v7&9Ix6ptf{YE8~v z_8}|}ao_*du0b^acT}Nh(@0H~GPi4TR4-|`JSLgM<hJu~j$jR8FN<}z)uhx}epBWB zHKP|!=NSfc&$MMm(Ro5iy8f5=#FomwTyGZz>boI8%l%FH8>ObS+Em-;c&SqlrH%<W zW;iKlDT-yeV5#DlAko2uZEu(x3isld^}q(Vr_Sh4e`vYyWG4WTlE!1W0Q8<<dBuC2 zdYd_fFK=fGx+T`SXH&f^Za8^!yLwZdaMZJOYDx$9%QmVb3v>qIcLu;CHqn&gPjw~m z<N<gt(6eI+Ag?xA(l#(4wD7{E-iLl?1|XeRP(WYrEIs7g*abHDIK$5@3+zJxrVrgE zTn{p+IeoMRhuj7Rje$O@N!I!}qOZU5_0Bw-mf^wrKSWaRuh&nO)v39G9|hM!v9R#% zr+#K20s-jbPsR7J(U#o42FH0kk0<$GlV|}ZEmQqi6l*5Mv5o2s;10^B21{_q8D!-h zXyp12v3Z|e>y+~g9qY;`KNhT%r8}i;aFI8&+`YBVFK0c<ao|jG`)~N^B-Ji7iQuwi zxnK@*K)g&jtn5moc#LJX%w*pFFy$55OjH(m)}9AV0(na>JJG4mJ(P~CHqM^|&e^Uh zM}s2S7rg-4E!Bb<8c!0=RHy3yFkStLf@6;|lb5-j*tkG%hA9AW#otNHIjAgMV)!Vg zHkPK9&t@TdcZNuF*ZO3tfH9Bf-kgTQ6mmWMvY{d4pdsPgu5a;2W|AozK=*8Uuh>fD zU#}kjc~`d@A1I=Af!mW!+5AQgOlx*HxRy=;eZD*zy8>rJckOr^CCur;D2tYtnU~wB z_%S`dMC$p2YBqz~xeXN4lNFgpu{NtXKF8!g85Gy8fX$)erSGnmb%;F5+(dDEHa-k# zn`<Cb-xz<$b5Ji?Q~~6{J#VO^58={Vl*Y-5%Szl1V?1ZFgIz&F?#HFncXK1tsDLe? z&q9@p`Fl5=#@|LgNAmf8bf3HQe&R+x5vO;KDMT>fKGQ=bC9+a&?_N40s0H#a#=Q$O zOBRl&>xOM)&06wA%Ygb`QcV3blPddLn5LXs@Huf<3U0P%jK`PmtJW&t4}cX2$vaV0 z4AZhwtz2EN@qC)A`7Q=c@t>z`QOD#)x1VL%@M@Rlh^X+3*>l2GC!bq2XFZUnIsmBQ z%fQE9?_Sy9l2^)lX?*Tx)E9x6ckCf=S5b%vYZsBtthxkrMNz|e2m2Jd8|DKtW%7a+ znj;pt-4`e(EAKHXdF|PEuFoAOl=+rN!}SW_9BwiSoP0qjDk0ZVkMG362G#T1dxbfX z0rsoWi~UcE&y7SCQ?(nb$?`J*+2Lwa2|SM@PvL{DNB>0$9K{%2=>Y|Ppr*1Yt+6J< zLzEP0q^B9k-<^K0NAS$p>YeV}NfSUH7Pl*on`tP+`Mu~MN7Bday{h`aDQ{p__gSRg z=eqTx78K&;Fcc|#^=F#8Cu#h%W0At?>JL-raj}_jBGvl*6NPc*<TRlFbMCV}JaJ5l zE{ggGctQLu8hM{RoT(ML-JuIgRYsQ38(ErLRA1W;i6Lq~$^F|i&>z_<n>MNk>Y9GA zYv?IS`_Nz}u+3z;vhNbyPD@CBEBB0d?ipMo);LzKu&7!3Y`tU6uxr$-UuD5&N|Q!* zU+Gyv2_RUwKmdT-uR_5D(k_mP%NCP!Y0Pp*y$e119=M*~Zj=Hkj-_6X<!&NVnrC=; zu-d~1Xttbe-UH~caCK0?<ymxON+KmQ@S58DM?to?&!WyJ@j?{_PWUFq6gt26IA&A# zQY6Fr6^GZia8#zQNQWj+NVj9;p3dphm06O{*<*~yJPm~C6)?Y-keO6=g$0bK^H}?r z<}Wl#O#!nbO%+#k*E+auXhrD)ntr5X&Hje&N+zClnSXJ&hNGzu=Z7HgEvcD2R*n8= z%tQtm`C&|;&hz^TAEtaoKV0U8o^=s3ThUEvtMlv0Tr7TaE~+G${tem66O9_o`A`=4 zII~jWv1vBMMJek&J>mR?Bv0~9F9YfoX)69`A<KH8iS&w_^!I5)V_UL!wbglEzie@D zgF#0Y_W;3>V`((*E4;+j`L*YMN)ePTWcpRmWuv5;B285+5BYd<--GAni<X`>IT+7Q zPb3}doJMtGL+TTMKhWgv(d1TYpqyQ%;uC>$r$LKjhQu2@_|gKC;2*k(%u7Ag0BNwf za9sI?%NSx-d{34&Ey0$BypVP-E{$q*`+9RyKX{cANn4v(XrI}J@yK)ku8(<jGmBuq zv^*8_bAel*eA`K>)X&>vp?AjjY`oqrb%jGAM;?svFRBxQ`!s-R7s&0<XlE3a`U$gi zInB_qBEw38n;ZPrn;`eOfZMz!Tkog}WQyVz*-=f9J~?{g2yM82g+P3W&4}*t7P^_$ zQ^muhTJMfPhHt#%b||%JR!k$zJKpFH;R4IZZ8$FWIk)a<Ip{~Ob_R*ad$wjfzSFeY z(cag2+2r{oY|^o&uW>hEIPaHZ@r<I{YvYtD|CcqvVIr!IkJmY#H)y`^a~N#|zn-5w z)e$+>sr9x#;>MGtijUJ0Dn+wRXR7rp1E`?4hN<tE_~SO=;*E}#ZGQtl6-gZjB>cDf zyyc?i`zNVKocwBuxRrrSxU6$)qSo3-q1f+7KZ}HP<14LSa*6W2c@o05sjn&Al?a=8 zxltWn|DRab{9Qk|ME!p=gbeTn#iO|fC{ia$^~ycVdd-&zCBjtDGXpJ|?J{-siA!>& zda7PEmgE89lkY9d#&-R-*h$##h@NK>Ro4nm-k*PVZMvn>>Ai+$#QjS$)=}?GqblaX zu@mS&lkqQ1{uy7Rr$e<D=oxTx6oZoY_q&Vk%|Aj=wH{xt!mPEbU6{$6IEw(iw<lwL z!do8CvrD&gyM&~VE19o#BgVe_#;RCRCiO`}2n*hGEX8TN$*<Wnb|Ox*Ik>LufN|U1 zb$7RmOf4?7#vJWfZ8?Z+2v@CTbvT_5;r~8~dp4)zq%fABKCaZdZeED1d}G0{7W8Jf z$dK0=)kx0}^l4;diHA>}xOHSH<fQgS?mpaLXnQtWW52GVCQPMy<a*w@+?+g9-T8{= zW>7s#2UAD4x$qVdEg@G^5`|r*^+D#8w6vZHo3Z;)830!8oYQ_z5d8ZiT>F$;%*paI zsZD$qoh<Vr{hQqjFuhtr#|z^(H1k~5Hva(!zlZ*u4!+s<U*CQ7-+;uujOf2Yu*?G1 z8bsj(B7<M~5i2$z=SGb_rduPbgHNG0d`%wzLB390qk28o&Ef7=qnl|SOd#Wq<+pSJ zYt-q8Ak)`h0_;nlPKK_R^|=Ahn^sH8dJOR}&aw2zddv$dO)q?hb+0nn^mEpn`wQ*I zX(gH3DL=R%QhTi5MSWiXqv>AUng0L(f$v}k#x~|KryZPfia8&0*yemH5=m%7a!O8> zblT>e)0|30<`k8LR7kyN&XVSkRH~6AsVGWP`|fjHzu)!x51!ZSdcCgK{q=a<?!vIj zd(#JD%Z2uzJtOing?aPh_U?to$Q*D|Nodd3ndLy9ti4Ux8@QFpp}QkrmV)d8Mkk)A z-)c{Ew(IVg4RSsZ0hZ95Ax^p#s2}N@D7KCecYi8%q&Dy4eWumqnM<^dD<*c}%BR{- z%2PsZ|Kug+=+!QK--B=JR#O1TCBAw1?LRQyCPX+@;$~H`I$4<ccflBb9dzmX{Jtrb zS*4gC9pCw6WD>H~c&lSV+)+`_z{k#wR#Zs(vEZ;r^Y&=kO27W$eVTe#lS41Gwg-jQ z-*Pb)XDHAwHpZG1f|tXT;o~sMeIm+81aE$R4+V8nq$IAXV;(lTyw)D-Iz<+S;&_05 z?c^eH&%PS!XF%y{;1W-Pho-K0m+nXu;gqymeBDs`wM=Hs1jjYi{!gjNlF<d9yumm# z-E2ETLf*)R*SSf{UNv`_TkK&6<b6w(wxu1nV#&j@gWAK+yf)n@Iy(8mLH>3mV&SRC zFy-#-5-nFCl$6Xw(Bd6bSNJg9cqZcbjDreSkf9&ngUFAE>{#T&Qv<+Jf4H)?CzulF zIAH~~+5I-S->9&FotZT%nmQgg6y5?E1`mIT8HV(r;vK)p)CwTBQ1e1U&Eo0jN%<!0 zJrco7VW;b;@YF>LVvTs?nBpmp+Ejx~2*3%s${#Rry@)z0GOdNLE<=rzTZ?wD4_LYE zRWIrAl|EpshByF7vwjH3wC?CZeot>uh66KAHF(IlnFi%~!5*`g62$JtUR4Z5Vh=kT zUl$3rtgANlbY)>0;jl-ZQRBIx?HMbZSthQ)+*DTwrENwAcD~v)A#cF+*z5Y3b)#&b z%dk*08BrJ1W}CK_i}Vrf`(x$RQYl>e88wegyLhI3F+u%?+u;Et?q&7wQt@gIm!Ssa z1aX6faRjX;%^v6jCj(gM)7V@1fvzlvlpaJ@HW)YBm1QF!qG(=X*mb}(3EPGU<~nK- z#tTz9V3ki?N2UAYkiFYss>g@5!<0V<IF29A%pDOr8gEjN$(!o<vyCp?nv+Vq`K9&G z1W=R65)^&@y5i^0V%lTn#gB>aWsYoSGzXMPhAf21J$0;ba}T}X#aDBA=pDVcp+~}Z zN&SHSWt4>pQQV-e8WGaykgUke`aDmsIuZF9*Yetb7XZXLmkqZ6@afr)#kqn*I~~<P z3H!}RJ%~(lhS^wafe*Y_HkRxd^skRM2(sjYBG?sMlmhSzQQeOKa@`f2A3YU@9x5OF zWOvxnf3#L{Hh1Qic6F{_aO{5F@vNO=9Nn#_g^E8So%Gh3k~I@7nVa)k31!w&S0nV* zUJk*qhT|Da)Ax{}&(oAT;^DhWpQGMBYCb5u9Gj(|_p5v6O|P=xN|tpvQ92Q#7x40P zmVP5q(yv@h&twgix=z99ZhvFEURksNN7TL&@Qi;-?*)W|6q+ra&R=BKBuKIv_1_HG zM9)c-Uy<;<;P16F5aIVxLmkhd^&0A4w_FS#mmlsI)6{)5rKFywC?asP{X(102tYDP zBBW(K9@hGnIDL}upp-Yd@HO$*bljUXd<Q4|{-X6v)(}+{3!HY4ok!CSrz@@Sv+X;o zC89Xs$J?#B)YTg5d6vn8hfj~DMo}@J;X3xAt%&30^U~|sL1ThvcKE1z+-s7W%;7-w z=Pfl?Ec}|y&oR??YB^ws#de#{QG_{O3l2DrR&(6};Cz6WI{u+zAMsNQj5<X@9iOor zg!zP1V^0qInt#51R`o^jf5)3r0FFvit9}Mao#^9BEW$tUZ09r2#e>TG^iqI1dp6Zt zZ?2n<=N9;MVY5{~b9#+8i4%0w`PhdHG5t-TRO%{7e(m3sc?S~_kmo*br3W|Dq1Q9- zXn0Hpq+cJu)^uU1R(5~mdb~pORG4?Do1>E%zEO~23jd8f&NiD1v&}Y5VWQOzZ4Y(w z-`H@@G@VLG!$-u$mM2}74vBXl{uBHrYp5aUn^Zi%1+t$5Dg%(%;|ITOVOd{fYiTgc zp&pc%Bv@s8W<cARSa4Rj%91_kGGlIFl>haEq^%^-DW**P*8z<=tW(?0i)#O}4=nlP zx*GrR@^e>RKZePkB`pwWsxh`4`@bsZk1I@h`xnFhOnd$_CJIJ2E&A@U)3y7a(67N6 zS|H)65H-iwch6D?l{_7QL+GOrur+O!-)}GI(aAe#U%?`|rkO3_v|~YrD^xA-fLZUf zm(nGkA3T+hitQc-Yg_X4HTKIAJra|t@t+*@(s?#B!Fz|nn(LsGc_76lX(F1s6{RvL zJ+~zdQfOq(8@(NRql8sqjhN9@WLYvNaEm*yDgda2l(%>QPsn5v;UW`^B3ebqucTE; zz5%z<l^^E{!$sEWii1@t*rEbto!4s?0Jhh6*xAyf$w@QWHxr|g_fp6E*OZreEcos3 z!Zue&pQAio8?g_x(L`>!`gWhe63a%Lryu!_H{5IV6sj05+Q_1Oc&a2VPaIUN#-VwI zK;8+r>LEAcol`xk04gSAze?SuCmU5l>3vU+&*3##3VoE*W;_K3Q=^4(<#*i?@Y zmg9JFqR2~Y6>L8WMxE-l%mW)$h|ED2mJc#)d`bXGiL0d_C5SoDSiOFS%$Hc&u{<Li zo{<>8c4w~n6i7>V)?h^>Ql^=Dfq&`v*=6%ITbLL=Q1|}4bX%z21Vy2=%pmne0CT@E zP>$s^@O(5%QT~LY!U9m?m5LBZl{cjl#8|{Lz>iiyHP>GIGfzz?!oBQ<oIg2e^-;~I zy={XWvQpIT1=O7jg`_^1nWUPY#;eSz0CWCmQgT-767N_i&xQfg+L!0HE@iR=-Wf|h zmL3?e2(}qw@=jrlReDcOvE-9`R8*(~a>T8pDvmW(Hr4N%p1&&k6u8h?rm8|!CKFv2 zf&IrX?>{9cY`r8}fK*Gl=B7o()-ef<;p(&F8VshiCrJBtwO3-q5#3DW&KY|SPkYtD zG#PFg0JbKx?54n-Ej&npYYdxe2X`F9iuJ96`U!4*a%GwUAh%J6xIl5?=#2lx7S;l( zx4{TZ9_iH`0v3KL@1uj{l6#1fyr7$h9HSe8UomkjKvnF^KO2WJUx9?k1?4HVkvX8c z_S^^h+b2w*x@pA6mlX<)3*pTeHB%6VK{1FeJpzhkNMxEl{vVV#5f2iXt!60>7Ca<3 z-rqpPSw>P%b6r7a$7aqJ>X{zui%K(K^K=71H;5T_HoP3$D|Z$ge8*>a`9)Glp1L<k zTOh4~2F<-WJoiak@6`vr>p((znf`ap=HMXZ6bjKB*PIiyzn-Z&w8Qlr5!=WlogiYb z*M)0Q<p3-qmQ{Wm7zE&2!<Wj7bwXS-^-RI)>mvRXB*d97Spx7n>o5y`uU(#lA)i%2 zrW!ASs-HW8e4PARcqaus?-M-zQ4r~=!^fqx{dt82+k5P$SUL+1NVQ&r@Lqi`nO(t9 z1ME|pZ9H*dxp4&ZrxTB>2)%i8`R29IQ>heXF&2J-g4+ZVrlLnEZ%61aKm48FZ}d9! zqDH8EEx!E{0Zv`I%_OFW$T50$#Fmy{jA~E4ZW~)F^#!E00MaR4yjqiHkOzva$o@R# zV6ec`pJD0DP}ReEIw?~IvR*scJ?adQO_PX=%(KgLzqAC_vXQoecpHa<4J2>Y8+<e! zWeqw45w29Fx*i<-ZR3ULrq<9cDXN0$g7D85%|j7&f%HrEJEKG(glY;!jj@m_2g0go zo&854WUrJphXXHEFP-hda{H~xwe9ozUe1CY90&alo<V>EE+oxDM6A~BTj%T8W=q(@ z!Q}6txXV1<QkHGpAwP}0kL6hu2C9ESz0O%l&xXZ25N+|HS3jMLmINXKKni@IBXwoV zR{zArl_Jr^TST}rKxg5AV)OM`9TpS6tu`tLy4y)15VX$jjlgy^5do#x;yGnFPxcHo zNZ)@f&_H=2!+z$8y+)eGD$fc~Z?Tf5<(+03>As!}z7m4AXvu{1584UDRCLlva7<rg zX4bt6{oSLcLus0kS(Fo1LYq|}f=f{(P&C7t%A>Dd8yg1ULKGN5Z=BzbL}@gi(tj@p zDu)=18nILv6k>ceKqd?qemUGdLOq4j)?8PrMwO!td4|Mo+X-r>kh&u2kerqk&}$dY z@+pS9S5E;udCxQ?4b8x|d15u1YDbsBJ{QGCJ1+SCq~;m~CAtSHH}()DdBk*(j1BL2 zbLfu?H*fupEWW3EC+A~x<@|_Z6j56dw>hal@cg(RT{VbUdVP{O+VJr#9XrKrg|dD} z^td-u)SG-YvK5^ux3-NF#(($P=cQ?_AQfisKvR3IR(U$6Sai`qwRnE63Q2p4DkC-7 zy9EA99Y3}J7UI2^_iFBFR83osr6_e=QR?VX8v@FE^9FX_f#0p^lQ{6lXf9+zZTNCS z;G@-zuWBvNqf6rM2;WGTNze!arb780cL|pA(2G{31e_;Np_^&CnP#;w4s*5bs*^x( z0R)&C{3zpK$^q+(n7_@JpH3Lfs(A7=B(?jd9+{C|EQgt|v$VTg>&KiGR+u<GP*vrv zJej2y)I$Wc;d_tbH<<Zf1BVj!mwdQ_@784-w5jb;B#h3gA9<@9km!aCGwNc7zuj@T zi=vLbMM!57JXr+Oo(0`$ogY6K;~C|NJgYhft(Gin$6m|iUY%JPg?EXwLt>gsX=ME? z6#kS@y8>I%n6Q&WsXrG8v8O6X@{9*xnY~~tHSrWRdUVh92>NfsG4y0+MM{W<#FN!G zEECB=resx6N&;}08YN#)w|VZZGJ|RJ?g;wecN+u<3kRt=8f5Ax*n8XyQyn73v+T8# z9p?<K!&&BH((CaKctKmPO)^QY&+!=8B$=ftbEIy#d?vGgujY|s3(`bBv&k=3SrVs8 zVyO%PH5!>g7gm24k&=Nob{{j@zM=Bu>@hX)>v<r^`p^2Fs@OS+4L}?Yef5rVIuko~ zS5uk#XZP2L-N&P@PDr-)YAo<9*(_@gFsdMpbY|b{mZvs0yyz5npl_PpDkxD0Ec{;W zvj4)fTzZb3B~|$&%@I)DJD{XWrV`#Psdg~k4l(6pS*n=og89hc=y;`BX0hA1br4S# z_(@_Af1;<%;yu&qq$1gjic2Pjw&}ay3|EUc#&$E0DD#v9dTiBs3VA2YuKZ-=7VB>G zYOM6?FdWt@K=xQ|7;xMsJ56H&9J6#HhVO9ADOu4X&n|rMai`->Z&1+wRnw{Cue$<W zPxh!vQk%RU<b^QRRH(FDH76$OmG(8Tjd7uca#-|@VuNe;hwtFpFP$#a$Mt<AH7Ch0 zFweetKv<y24c%>30%6mczUnLmPXnD2bLQ#a-yEmyS6Hkh7BdoVPXY<6fzp-VSq7uM z=zEza>F$nq!hETHnwtX!6>EC}qKyI7_}LBB_MIt6)~(8Szso@K**%(#lmWR^c-RiY zf1&fkRZazE_LVhv)@n`$f7^Hrl)K-caItCsaps7w6*lDi@2^FB?XMH!Kb=3%dy)M6 z(q!s4#?u|6BIbM8mczPs8-=D|^*cbe`vQOp(jrFQ^Uc7Sbd;l|i&JFU&hp^Ek>mN5 zDM_CxcuOX<A$03giKY!TFYD54yKreF>&~MV^Jk_b{qc8x_cSDJojSFp9Db+dg0=kC z@-D@%B(+6+UMw2c+A2@o>)S~P2VOGYkfp(OUZnO43v9R3Oyj9S{YcO*5sI(TD^GZ4 zY!hG>?_kRY>7jR3puo0-(<HO{FJEK+8<6x^H#quyCg>Z>+~z^B^4s8JKqbdt1z$^M ztC<?B()cHV1&Omb#}~v>zoCS?2H%ysuFCy03fcen_G#*;Fk>@<_HRI(-%S`u5w~q~ zw@!(`yS1lBZzk=j^_f>k@?XU6V?<JIX=$#{LHKo0ARBJ60@lm!&XtwcX1t*^y&uEA z^Ny0#W-BH1yEhSfP4ie|uq|U0Po6<(jBd!y>d~?U$plbOY^<F)v4fb>qo{jXwXvc8 zJ+QR0qU>qQ^2g;Aa5J46MO^9m6>-*Wkzxz({vC1WY?`f5yYLZ~#jJ6>_X>0VA$BNe z6RewjkD1?Vzx2Z8xWmKe4m;Vrp$FM^To9?O)!5s?keqD%p;<#V>7L<Zz1W9M_jdN1 z#d^5tAIjp%%^n{ZwhxlHkK4CG$lE`_!@rlNDghkJ9a6SsXOqx$o=pmXd7~H3Cz3Hb zdq;b<J*ufp(BHMqH8i$B1p<+o()PqUumakeCWgE{DTk(igX1wrc318?^>h6<Cepjw zAxGXURW@pGy~kzq<6EX5ADyo--6*+#tjd7iwWxpVLDMUny|34OOkz&Fwh8E3KRh|z zbou^+*9Ff<24i2fhYx?(nmjVH&n`UevRp)F-b(}HDB=2Sr$fVTyg>;3&5c@@J*rQy znuVRfL_EK&<QkyillHP8VzBagGB6p9x|ZG&_M$-Q^)sSjh{W%gm|eS7Uf)jxM_0nV zt1n>8v<zh<_EZ;63N`k=zb@@o!jfS|4Nvf|lCne9w%Qh}Y#Tqnd~i~TJ9p;yk5Ay1 z!LL<a=8a9?Ya4Fhf}9f$<73vDj#Wn+Pc7<4Plb9IbP7hC@$LnmJnlT&q-M&TN>-HY z<FSVuq((@!VQB07k+sHSL9?;<tl@5H*~G|3I?8tM=_0hj)N1ejm*<oXss+jKr3!6+ zdKV9CRt7EQJ4_9MYCdT1MY6xPMW%NZO1unvQY@w;Os{vIN(rmKC^;OOUoL6%t>pa7 zjlwbOFWs1DHXHjcRN5tds=+1J%^hJ!OpRxi`CNJVu{3;<;z5B0(-F<?SA8O`?M@xe zRD5jesf7=UEP^@qc~(L(2JomnB(+Nr%BHAXEt?LE+NecnM{<DTL#B7b2A?ds_C6r| zB1O8sip=%0AVHOofr5EL_=xW9rpAW`9d*0a^Sc3#o+ThR4Ysb#?=iN`O~RdSt&rbG zDs4YhUV5AQ<<X0V(_ck%q#g!zSjD+S%7==`&7OKpfGhJb?ub&IGoF4u!Q*P|tY|_v zm^{4W&SRUWS;c{_Qfn<|f?o2FqwCnd+?}Csgpzj^4mXFf&7&KcaP2MZg7Mf_+5r@y z%y#+#G5^s~)c%s##OmuMo{4UmOPpdW{oCPnNHdvFZJo|s?_PAmfvs9;!`aQ<Xa`<O zTCihZ*dYGuYUS0hU0)u*);@dey9*|A<YmJ(-+|7|^0WL;8Tp>erxq2no=!Aej#A5O zQ9PU6seylNJsoo;#9BI!B#rt}Q}_hxmX>RpnD@JFG~&dXk?D}PqqM$$LT^46=Hu}E zU8b}ACqYb7*%B)xY|G82rs@82OzT2^%qP%r@2*z25%pZtgYFu+?N9#jO3sh=T;2Zu z)V?ZYJ1z=b$#BVmR3<b5kKp5QryR>q^_>z%lpn#RcPq-D&b5m+x-fcHS8;Sm)bo;1 zzE?^MUl<S4Xmf^&U<7}~DNfjWd=rJNCcD3*7nl41OWi~gTPYXWGE}tLnOwp-n#>gY zQdZP+ru(VQ-g~;NB8TKU4;--XV!QhFuT8+CnVT$S^qj53zBzdz`JL>I04F_Nr(*!p zpgm#D@Z9RW>{7>o8J8j%lU<|G1%UK+wMw4#bjOdBR~U=<IK*LBhe>j#M!^~x{iOzB z-9}S_QmAE}UymEtmMK3*U(qO4L(;jUg!?T`k->@PQf|F5`lp5k-nr2>O|C>PH=A&- z&-xfGXG3WXY7vRDF-*XyO_PLBt6=F%om2G&f7c3ANg%mxfs1;dPhq5E8g7FDF<Ty& z^ri9Sx@TZo(b9uf)6xo;KhK1G_d)pP<&n~cq3W)K5M$Zz$R>{k>(kd2%}8ppu1jE| zcl*^N!N!3*OQi_iEyFd(6D_O4uW9Q{sFGs8l;#hyl-f*Wie-6-NRO)uGmExA9F0OA zPAxfGSzDZlm6od$IN3X<B8>yn@XZV-TaFLvFd<LAG9F?p6K-@EUQ0dkGIx-yWgLD6 zZgh$ck*i>2`akb6UfHKR3SGPGr>`bnwwb0(^V5IXg1!amlp=O}>%S6%HPIn@+P9tf zu}Af?nE*%ZnC5*Wp;?UtgQ0nH;JqWIiKvqJc`4-gtNmN+;(!T)lfJ7@q1#kgUifUL z-hfYjH2=NII(txyPe$zbRNwiUtD~1(q|lu#v9Hk5nchY$4{HI*x-*{R*w(}KkMAFk zCOGP`2~bn-0i<(pLu=`WEPXW3BCy{f-bNAjKE0T80F<VHR_dcJ^dMe}D_j<v%RF8! zr5SmpUT)sBVXJZQ&Yavaxi4#|kUlj`2ch3!L|Q7|u@+as8MNslA_uRxD-5C`n$|rp zV?DvLll(06bsw69Dp+>Za=-`>CgH(n$sGkaezs0?ooSvl>ZncEY$m|S9l(IjH(%oZ za-bx@10lgUFHq`|EX;nY2kEaKN%YjuwvSAYVJ<~?^!2G0X{<^4m8WB*S~F8lowO6E zek;Cw=E2THs>&5hh|W(VWPDH<z9rkq_U5?MU}BoG$p>e%h4EY;#=P{wmJIEPo(P|8 zp8UlY$DKHO?x7hf4z#;BO8X4mKFnDv!LnDbFJ4^raYWy^@m_^)E_}}QR!6^^1FrOL zuj2c-7|TWflk+Vj@sOI>Q{}gaj`P<o&Q?Ekjr)G{z?+5hu3<95_<qeLN?{DARJKBp zXpyqBfX)UbP6?p4q6)KM8Wne+G1zuF_`-pBeMO+yb8nrQBlf-bjcgOeG@Iiy_aCli z=Lnmn64uDs`cssS-m|9dLvPqit~)w2xNn?Iy(-Ba6sfQ+)5ibUk2KEBA-s}(-L`=< z|K03*F23LL?4}%Ik4W*V6Tpmy;7Hd|uo7QjW}BXn;A$3zyL2_nF6GPN1WRzzE-!+~ zdV;tinJV=n^JpGvGRt5Fh_3JOk=jiVuls}vY#H`ZkZ40k742%8&~=nw_nuZfNkmUr zeONE&d*cu_#C&$+E6=~zNqsuC2!%g0w>JyV_elZH{(z|mjiVy-!tiQGR|cw#F1R{f zP#)|^x4RA$x!>b*r5(A8-+8&_@qC`~p=H&e=UEorJu+rkkhEx)iQI?g*bAkEgbBg3 zTKlbAh2|5TUYBQcXc|@x+i8J!$p*M2$LgAaI4o%VxCZZuApFJOufv0ep{6|iBpSS9 zleu^2i`s?RnL+J%qr#&$?<i`QDuUXKQ2WosHKba3E9lnl?$;|@3yzl`!zZwmDmk*v zo@=-jQfNg|4^k)@Q#5`1t3&b}(O6z{x&GSpJ#&_4-{Bzg(WA~^OvIXPcmnwu;!4Uh zAbvGOsQ~kjf>8mAXhM}my6gZ&CB^Hvb+!BwFibWa$EJVVYTgUiCbbnBS{J52KDMUf z;Qxw?g!drlY3O2rI2$0bKtN8@GG+{`ilJFZ=4>5gX<#R6nPGtxR$CS43isWy<`Gb@ zZf1)Sk=?ZBukM=uH8xFLjGe?Bfi3x@#cm$@#T2NLNLL7=yjWsNuQMNaH{nh&WpVxb z*O<zVW1$AuKO_^MZL$>GdgMB|Y*JX7jE{5_<i>6nKb8hc%|})iD6UIHKNh4Lf4fQL zA@WE_YT>`k_Z{rs_1%Vuiua{$eFz@8s~tQwOGZ2xlaQ(YEY@=|@tI_jkHY(~T-F>~ zB=1ep6=-ufcrLE1NqLE)Y|!(2G!)wfRM4Q~w)mleU#WIZc#Ud=|KK0m>TxJjBK+3h zIQ72xX1NhA!k|a$EiE#$7P|HfRnTHi^?5T-Kz$W*Hr&_NQ)-1>j&h$l)y}*PnQDpe zw9oSdLH4LbO{C<>aUy=N&V1&fbf#?Poa{fkqA4Y;K(zlw#9SHI|H)STv-<5H+JWpO z8H$uvDAJTmK*@vA^R54oYRFlE46?dc2G~c{uYwX0;jXws=Qq*4mRy0jm!U-EEi{%Q zb#rwR)FRyl$kEV64fIZ-iK5N95JIuu!|&SbA8N19%kCyB%mC$0nR3O|tt+{>&>ll< zI0ewOQ!G-MP2{dplS1cKJsXtit8A?t#6Y2IM6c9$(Y*#hXwRXh$!h6Z#BDBO2{7Kb z({*zgCD9}9;bXC!f6x?kI&f`yUMN6mENgT%$iE|>>E3I$AEUihrv=q3-x5XB6q!x> zXg3IhUDU6j>@2PhH8_k5b;q;mhO*hR_s3s#OGgB`pn@{~{BwiX*8f!^$_faG4#2MG zWY=v5LXu@n@67~MBigmB+*{FIoP(v`I|HAk_SKbzgnsU>mCyIQ6EJD_1*5M>!q`x- zBTSVMAjX)Y%mpef(G|+a6Erjx+lY{uxg>H7#i$1nkZZCf^SXTUcxpNVOZ?a3egHZr z^_YX1VL-D5V$mE7hV|p|2Md-=)pvmF*j?m$AqUGu#O0YZgxTKvy0M!lwf$w+G)H>6 zD0rk+g4;~|=Ie$Rw(a>h_kza6k5OpaKuiiyWr>dc8AoYkS{PCk?lUQ$hA10A>b+{j z62T;3hjVwU(Zr1^0Hsf6CvpCcWTqe@Ta%co@sG3Uw$<(yD&u`#R;@J6`A)y~<YcFv zFTexz^DRJfLM(^vn!}|H&4$bH1ak2SZWd*FPnoKvbYvzI|Fc@znR3~csk}*-O$MS) zVKDJPPmc)-tk5ud&J#6GJ(PPK8HMg5NFj;;1`_(<KO$o55G{)q?kfkwwcXy*I%J-r z-f}Gq?%8<lc{@v3u8VhhowVy8x$OSewF~>S#E52A&x3Yt;Ek&he2V)XrUF19yGc`` z&B>C5dqoPU+^bN=fNc9ZP<CIxF_dz6df$FOsPj(-@{E|Pwr`4rns|Uff<q9Or=Z`G zQCB{g?e*-x0wqRkBgcMJt{YkHRbNh=^04!*8LLNA^GzYu2rn;mli=c5S;X;ivp<Jr z0UVV~3TBLszt5C4pd+v3BrFo;t?9VZYNaD`hWCK7<pQ*R@1MY8f28=0Wg2RNh7j|` z80ADpnpnF7ku5ZgK@q}6wCQ^zBRSV{UVttykS<6Zm?Fo-ua}-keuphP{9r7o%fP0Y zav@qYenzqvR!egzs+$x{N;OX8brw)0otd~UI+hyutrTbgZ^UH!8n!XzMupDNulFq? zqtc<kT`)TRW6{yI;o@i+8F;nzI7f;{lVbG}UI0#hllXkWxhWltUMJu`T+EWF-c^%3 zvE}0;ch6<Nd2?W>?&Kn3TVC%_4_+xg{?5r2Zes2~Ci4CqK9Pv|Nqj#wCu;+fU(8hk zt?VSnc@|YC!GMzgzW+hDrnOI3ZIc5O<x8M+$+t9&E)dCKm<DpB_+&}hIZ5;;;}JJ= z#pew=H1N5un*P&MrM=eO4id*C4|kRUdNNF(K_jG@4+V$Mw7f`H7+Z-0*?(tBWX|DC zDcCU)xJ$<d^+Xv~UooEZC<FSI-%t7|Fm3wDiyTAg)*?Wk(5Awlgzx*$-&r=_JSjzG z!Xs(l*<|@<Z0?;D_+BFFEx=iUN9g;3WILo}J-{$sH}2na@d6!mn?xhyFB)tFkB+78 znJL(R+f645pGm}w&{dYJajs0<Po_fj9F{M@E-{tT>B=@)p1-KdTLdZgh;gHNnsp<R zPdLtqF~5SXVx|4v%#mU<E*$QWd_|Fe1uXMBRo2gt!R;}>7Lomx<Lx9~0|4fKJCSyJ zA9{+m>)%t|Fg3{n4*Vt|)o8h(M6vKC#r(HGCZt@HrPqftTf2blqfDvDIc!Id;yP1) zwOH|rs6mj6#7dti9yxOJVtO}Y917fB!Y?`S3)v+k%LFjKdmoS!wH@xIS8XVk&C%o^ z(<CD&Itm=ZHRo-7_Z(bfWZQWi`%iFbTvL+E$wAX40%>CIG%;rmI8hM19B|p;%AM6P zoXA})reJ>dJnEpZJL!rXpieYV)|x3_48*W0$`THW16BbBu_$N{GB8at9D$xEJXjxg zDCsJ>GlKm3t*?tAH3KL+OcA}SZr-+*+eeWHypkFqT(mz?U19Kcm8+ex6le!JJ>&#{ z@M9!pj=pk~YD$y}=ZM7$pot9eIGWgFLcG(fJAZDvS<$DlbmclC7Mr1<bxC=dLjJ@= z9|a;DfeLLz#g1wzR)?2aq~@+6sZ}9Csv98HS6Gta_@gxN#`ywqaiWYOQMx^_>M2*U zh9DtAT>hPsU!_T^vD8x3rBh!&IDIuGZI^Vm!qgH&?pghVPH^Y5j9sgMT}nW$n%8KK zvUIlqwf)m;^{5P*E*Z#yTw#b`0Z8AZiIsCzmVextJbh`aPm4rU4C=&ZSK|^XY}FW* zX_j(kHCd-e^iYtG?U5Ve5(~BnSAGz7N1B{_pHYxv0cD~Ab5asDe+5?8(#AxGC@#XJ zaD`|M%B>%rk~IKi#I9Qpy5z2NB-*%$HjYFWL!8Tz=q3ytt{8|qGZ3aC*(T_}1sFJ8 zF?fC!!3Fg9a3#)E4D|>ZLzlUTCeF~+ilGLM_+x^kK^G*I1Ir_$Z*s&67>A}_Ke3Ro z&lLSVWuj7uDqVDyAf{4x9xjEFSV_mO&((dT;0lPC`y2%Ip%mL@=+7C8R~$w^;rLiG z8rg$MW9R6plmLKI=232MIlcBO_z?i~97Q&oAU?u?7X#ocTTq)|=!z0Njxpu&chc?6 zr0<(%-#1eS-#|kur;<3&J%XWMQ>X3UK*Rq+-8qnO&h*`Gu{=QB<BFN28=`z#_Md2S zhKU~{%KJypT%(XXPvKV3jOA*Se*`-2mgp>AKdeL)lq1i*>Os+S3Iny}&OTV-I^S3b zuyd1H6)NHd97)$6y#JiUz8=YDnjGLOVoLDtGPg5$xGa89fchtR#}J=RP!<2ThP_tQ zk|lvJoY(t@YU4`9|B^Dr<?y%?UzZWxui?&bYg{;@&HG2W!5^LtYH5??+v&*AYWz(g znH!5I&=qzU;F=Ai%IKoz^NybkH4W+mWfR_|nc^=0H*dyKOEhH^HItx<*07ZuA!7ps zW3dNO1LR&spyULtBcc7^z_pc}lc<^)b@z)aF1(n><j-&aX#}WAcRM#v41Ap&K=NoZ zp**NN_r+lVjHF~69r^+B?u=xd?$VsB1`xAFA9-AZOQv71AnpvHB(^b?)&(x1!djJG z|2ed}r(8S-534oST3WlX+YL*Z_!NxQAOJ#oR7VMNgq+Vw;5es?Ruck_@r=4_)JBTp z6qkEjn4c3mk67x0xHDc{<zV?^t5sEJW**|_<7Ef-VvXseJSql0N-+Q`-tYOC^(v>< zDd&Lp_@!&@$KD@3zp<XPC?!Gs>HD(ud^Hp#0L)j*jnU-Z(l~_(0v4#`+QOl*GP-30 zHyf&Zv(AHnAa!l;{#>T9#1_VxJy?j7>Wm6+)Tl8#l$ZB=J?G7T$Ny~u%iZo?e|pt2 zX?b?|Zo{)Ga+-vydwb(}t!s&H@K(~B|Blq{{<7CRyR13k$x_k0*|FE%!ocQrok^Iu zB*7+f@}|?nBdCK9V&0Ebdh9>?+V)&m9Z+`1vtawv17}X{XsDb!@o2XgJYFDohjfZB zKT^}c?|B02QDF^r(m6IEx`8TZTZ^vh=9ABvrgznSb~_Z(x&ENw#+TO}NuS?7efZ$p zJIdeAZnNd7$LE@6rZ6shusUaZyXHV<hF9$ZLcaIq_`Wch{VMqM_EGK;RJ8$3V#DcS z<(DdlJa@ln&A}__{dx9}K<{DfEBZNrP{oK#nl(^tPV&HILiEg>bd=(OQdb-eTNCJd zpkq-<t@V-EY!)F?dp=v^B3xxx`(G1xd}HHXlm>fL)Mj5B?(o!Pi&5h#H2)FK6H|}t zSPM>Zl>hW5B?VCP0{{89+~tzf-D?Bbm?onP!(VeR0`%#g{)1Gp(2H;^&9sK#7&blU zqjuBHwK_vVsW^k66u9YRX?(fy<FzwCKYgrv(3+;E6S+Ep0$g?FdDwPMsTG*~aBa&y z-kdz=!ak~aBdX}6^xn6`)Ek4UxYuQY(bvy<Nqb)0loJf^2o5)*m0vQN&tPO!yksAy zZ5O#ZXVCT)5$WB)j~O9TQPpz77Vy$tzO&w!cD1b^D7|pT<TKNbyuAps3ez8>HZ4;% zg{0ZdYH0D*`^pLrBY*q2G{${cTfliQ<{p!O&=SoMlg#5HcYKmF)e|xiZ|0l`NTVsm zJNc2OfrMCz2{<+;$n~QFov`<#Qnsnbmm!TyvEPTy#Xst69jr@2?%0S`m(b+#Cp}Fr zi6mxoS|hL=&&c1g&UgGqcRA&R`8$nE16*7n1Vv`Lgx3`)?LVE;-Sh3NIy@e*Yq9(L z$j)p*0*MDd)e7rHSdCszjoa4MkIG=seJT!h%&lem4{0^p{^aOy3epw+UF86_)5O(9 zLviBvKiCs66BE0dT=O5~2?!zO_uSVa2bs$^@SGC~LkFtU8qAC&hgP4R^>+*fqYtDT z@n6E^60OT6K5g;K)hXJpM5Vc+rh)wS>vI~uDWX~6F(re)!u6^Bs8WtlGI7NI$|`lt zw$zf9V>a4SQ)t(ak^sk%A3)astPZ07`*RLWb^TNMq|pBF(GPQ(3fpTAhgLK0+)!L~ zgH;5ow5?un?dD-(-~jN2o^%7T9Dk_tP&rzI@a`{>D1GH%|12jnj9DjL?K7=F3w<Qt zwVLt#vncs&%}plHt89p>p`*ve{qv~!more+Wv<<`mqgzyp$f%f*%xbX_ebu@RZ^ds zhwV^pVZif7mA8vCg4WZ-ojNi=AX1Lo3^ENeLWS94MPq$B0XONBc!P_ue8qVw)!LGn zX>?A+2k}gXWF4XUgG_22QK554%zBI|9?Y**I3i@E+bxYltG;|QaM`DJik;b4FaBlc z%1b0+nGG>SgN|R-kfF^3ppK$XDbGzu42TbmtdP!!-bz!DS?I}T5aXmJw477#U3uOi zDqsJTJ|y$2kYfGgGGA=WHV9O(lflA_S-O}h85N#gsgbFP@7M0)!gsA0mQ*ch1ZDob z=z-jcWLTmUCIp?kqel!A;?tz!T409hKsj}?nEhM8Gkd}J6H%6qgv93_2lBN7Fn3*5 zy4hDOPtBo@QysB!(oYLg*K0cxB#hg+68?-Zd>sQ~J1{2^&JV@x=J)=w{^;1reRBQ0 z_^Xty_b^g?wbU^{dg&C)O#LVf?u`8)l=V(P?MVk3cOZO;D;#J@Y71JJJ2Pug443g= zr`{f~%^2X1+OyW1BE4?y=Ke(O$(xtCw&Y@BJT8^G5-Ph<J}BQIn$PQ~ws$dY__)g0 zy<J^W=^FM<nFY;u=xDvOIy<(@%jxCFUU@WyL?x0-GW4<45^<K=lvp`f=HuH(r4)U! z?Yi9$GkVmtW&;LI`>O4xp$XAXZ^w<N7M||_$tSrESnp1_kjjtrsSvPKyZI1fMh_C) zQ}xgp)_!+WRw~L>hClLNf%EC}L$OhX8>A=c)JCRw6yWF~zU3|IQZZd3TG?U8k6Y6r z3#jVWT7_v2kwOTS5Rpf5CxspY&@Nv~;pU)TvQOi28dY&a(67Bzl&il&C(t9oiu|xF zK1eOn<*tL*7q@`!_7A<P5pjoL#aaE=>l>@mj-W?!-#%TWw8KAvaPmrrrl2)Q&C>Fg zMJ&{!@2C3kRyi>|)E~U-_wY1k-!Wfnc)+TNENF!3mHVJrYZ-*(RgfZ|8)P;G?8?vo z>Uqn9Z4FRlgg1tt-;~Mfch@;?q;>2NIQ>1)>-Z)7RN0x~;pgT)v2^_JW!3*$EK1JI z$>UgUbvtZrFReE!930Bh%S+lX@dJkbm)lE3j^oW5=}7wxmV)(Xh*?L^Q!><{sf)kg zU|qD!M_aqGx@{%A7i$Ek5JYc)yfBt%aI*f(TC;qyAJL&vde7fw@m_Xzq1T+I*Y)=M z4{VJaXlb%_<%8;5oWj&ds^WTi`hodX6Z>v@bf5nVX6p4UgKVZ$6i2stQgD~LuPFMF zR&h82D5kY)mDXW;N6B0*lBCH)B+TeWc@MoqnAP;>8w@KYN=L<=-hR*jo@MpVsL(@_ zg)3ijuy3|Og)n+{uAhD|`Z*ST?Ogdx)LU>KI7EY-(gTGW-md}{L7ch2JiiCW^{vDd z<wWM~rVm99v`Brwd9ZSin$X3x9Uy)_oHg4V-=7<PSodDX!CXTFziu(hn_nc$KE8Q5 zmj5t5OHEAp=-GoX5V2{i<vwtJE`{9@$q9C02MnQYZ%=BJ)3OT={as_jc6)O6qm0S( z_*jmZ9*H7FPnla;Ke%hwMd%0w@sL4{%XuiAA1Gg(|NX4%ih2!n%JN_Ur|4(&X6-_R z^S@u*Z&D?~@hq3A_cBc_eT1JqIR|gUa$ajbT6a1C(^@A=X9U<%kt1;Xc;=<J7;LnV zn|*2jN*wCuP=B7vj;bRS4s7J(?T>ivOLag@p!5Unn{yD0&BG-cT4#YL!=h={nBuc1 zcLZK+CH*)YIR7!eBLaS&kirrqxj>IQ4_F){E3dy`;zYapM(}2`L<JvJ7%yHK?_=c` zES!7J5^S&xuxX@7r}y<9%j(jgnzJjKg!2swa+asp<Y4w{DT;LXf5}X0nU6mpYWxRt z_h!1yoc_NS%ZF?Pk1hT~AQnth-0kZK)Mhxfh1iurXHM>dr^L4#6QFzj9xb4AXcUhf z3D=7tT_;mcI2=4AKs=pD_nyf*XNmbNkiD9f(aaVXb&%cocpm>VgO=?Z35;h5pusIx zm{5{+wntboG(zq4dzdtn0Xt@DgC&YG=7gIR{bT${B`5!TYgx^kS+Vuv0W|R?F8m=u zGKdU|TJ^yDo8`lCKflLqmO@i|QsD_X?ZvRL2}pj6^Aq`V4-;b(?|L89gbVi^hRf9| z`Mfyf)gt-$*9E~+x)BiY=pKSihW%xW$hb54-i#1N#I+<t6YaG1&ENyzXum#%C^jUD z3wJn@Bkrn~!-noA+jP#8zGtuzMXHl<AFQ;IY+3#-A4m>6p)m94OZfsN#WOQW5^iMi zbv|sGW|Pl__hsX7&bp1E2lQVSmzBxCN(gJ3f_yI4gQw*+H$Z~`aF>&TC?H(hF$=2b zDT9H_(p_lYkZg{N@VShBdy%)>`N^q+dLRk)MyVjcp04-MNVFae4Lc8rzgBAM2DU#Y zy{Bjia^ocYNRqWp$}Y<TgsxH;a;ZdW?c`JEQmV7QoXid;J6xz~B%X>XOMl5^fz1D* zB}FOMC9;IveQ8iJA&n0mm4mwRLeuJX4#W10*F)*t{o&=(HZvj6giPphMTC)75I{@n zBbv#9Ne?G80Y??TCqo}tWRo@D1(bK|oM*M6uFxb30OGIF$zWq<!3W4uZ};m1p<T`j z{z;en?!#y;(V_+O1b*_d16N+3%7ovgAU@=|zA!&PhSv~NlGANMRv{%Eml!sLPoh1t zs={X-{6+FoZ$Ms#Nn9nvg5neEt%&E?&?GMG78FVs?1$0~EnU#3;|cc$A;ApjN*Egk z(Yl^<C5sI?HkBy_PH4L4*H`Q8;;f(gUWrA62z%no*I(AKFCEwZg}Bav<nqNLBS~l{ z_=*3iWY9k|2Syd4;qwq*{sAvWa5x`E-8e~`IC62W5>^C1Rh`3#_q#3!my)TGu0N-8 z^K^1?X$g(!(dqMKp(Y~w_%DI1kSrd^M_l4V_VMAjv(PzQtqg{v1r%E}PLDg%aBhEW zeP?RJsa;TNPRHI$=s8jz2YQNAp9DU7JDDoF{+dBlV75oD-0*Wz-d%(^BhqOZ;uLRK zL~;DN7a`)}jZxZ-@NwS|TC(5rF7eA~=E>8TFr}3SC23#cX?3{os)Ue_QoM1aPdDmU zCvt_Yeu;x%1H__zGwXiW%~~}GZ|eFrb)oG(z-AtJ+rB(`W5Z*z!!HMLG>+zS${V6A z1NSFOK1);U-)eqk?gijn=kQ^+QxKmpn9Vfj`Kvpf>W#q}xW1&u{TnCGvtvG58KHFQ zCL)N^cLPJMp<aNf+weQ`dQsWxD(V)JN8+Im2=JRfPj#pfVsCiA?o9ian&(MV8tt#c zPvvwK!x2-Bo(<>X$kOq}ckgAvHJI>Y1o$|=Sz%Xu@kJVdLHj{~7OcYk(9rZ%e6j%M zWqsxKj@#wcyYA{9>M(V&rHOR~_+6Z<zLsEg&^2A2N%c8N%wEN7_{jM4Qwm(#6aR$k zd`I1lhg7h|4|y{segp|^a?<{Gp&OE{)2th66rrxi;r~sTb3u38ex2kn2}ur0tW`ag z)D$9R$E`)9Y>rPh0VB8TLCv4=pQOYUhIleptk2XhiXVO77k;>W*N&K*jX7s6Zbg$x z5OK9bisK&n4A=pZOvZp#ol*0>+Q=AQOD6kjco&js(#1y{UIf@)iH98Fob>nwOC?_p zZ-ccUIwH#3j=pz3z=xbg!!!9{=#Kl>iqH}X(lN#76vyGm7<U`6@B`kk${4sm1NMNd z{9W-8$dkr5K^<X00@#qpR2x=HV-)w%l{Lz&L?goI=079Dvxk$FrQs(2Ow{<poGW_r zM#nxW{1>ZcA(U(*S$&pPl2fY8l^NORpEaBX4(g5U_y0>nT;PMk(a;#~kv<Q26d!gQ zL8h&0LVOxzeLIgUJw((S+@3y=N`gBbs8<;k!;LxzL&$fnIww;Sf}^SOGDmTf?Xoc_ zU~F&n8Gj)mQCkh!&Vl^!Z)gyIs62NpiQGrt^7sLT-hP;SPQR|wtS<y0F8PBX!wh8c zds>%EWJ_STKf`Vq8ErV_mnlQr)CNwLLZV6HDl*WWYceL?19eUQzr<~I=iz6(A0G~t zHrL_BB-WoLJvqyTL0-X*lHlFDuDZOqeM7VH2u~}arI4q0RsIJ|rK>daNWPr0xHb{~ zSRf-bGa9K6ddg3(VyR&a5>PEImf6{ycQM{yHqZ^5(uAOnk&AGX`#BY@-qD=sXm1}6 zed6k$mII8(4Opn(DvTZtVF994U7k+c@W(ZbhhBMJCc}aSVyi1q^asj=q+KUI4RK@p zADt$Ic*8#Km+k@i9LcSxtwN7)LIJYZ_iTtyvzo*nO+37ZRDXc%=EEOmk4IyqX9gdm zvKu86`Xw!FP6?cY_?ji2`8|DH=^tZiXZ1Ciqagw#|5fNU!qY_(=Kauwf2F@cYhoH( zjKYT<gOabVc@O4HB8||Gjl*QhVb`Z2M^0EMwvN}+;Q_CrpP!J{T!VV)4g2zKga$=V zdsCk?RJ|rOv_A_($*#DkHzbb@PxG#%rn)m|Mm5r&4KK$KPBy`#q{|y)2hjI!5MO9Y z5;M7N@W2<B5B^8z!ox_=l6Z+_zCIsg`%7`AUDYeQ7s*JoTv&y>@j-zkXeLSgG~jCe zzDh%dixwAQOP3-APZSFNCV6_pvH&tX$Ij%v767qUB9WOg6?$wH5<`|8zl;2Js*2(J zdg+VL-V><CZPXe8s?QelY!Ti0MyY%lN&;Hx7yjJs@;@o^waXAcHsmA;?*0mH$4#mJ z!tU8C!{oXb1<4TBpu#kc;&+LDHZAJr+%NL;^ObK2A+{ZIn5U+Xgu-~#7EMAFBU8AL z81@C5&n>ud_&Gi-jTBc*f+v&S6bJh>ON)8Yh!PK#5Qk^c4KA)B|M>~_WD3MPxt@~; zF)FzEeQ~ef=hFb*C=NjUU`zCYRmjqlyZxq%(nS3RBZxT%O!H2W86$C|p|>Mo#~*de zuR(l890g6kDjs3bnq}&Vxf}d}W#H;(i;22m`;Ua$BJ`14AiFtT(cC9XdPiScHq!}U zP4*{EKFDGf0{gsY>kZ-gbZ0i>aY%?*)eboJ8qKhJBJJPuLpfXDeA^8)J&g|$rKP(C zU}sWYH22t%o)W3*J?earF&{K!2eM+n+UL29OLGxc_KP{k!=oAS2WZKrx69Rt&$EvY zMvnTwv_oyg%QOhYL<#mj&gcF|FMPcrLvdm*1h6F+tSPE4HHKPTg?P4n^K1z?5s&C2 zB{u#0^6d2&=(q6m=_6<Vq2AMiItg&O7h)pup`c)eEVATiU@Pt?G-~k>8qv!}^l+{> zjoo0TtZEmo8nu3BSl%&sl=X6K`GC2UF##M+hI<Jhe%>Hw^pBSYi94#kQx6@_p1iPv z&UVGWeh|MB#_jay{-C9;4=H7@c)xWxzoBAv2SAgwA%QGuVzgsm)m6x|FwE!t4H0Cd z{!!eR4^&_Msm=jEU|+YCUWz*Zi@ig;?oPanpN#mCykCrOOuIeGc-&?tDv_hN@%r3m z-n-2L;U*jZyV(AB>7m~j&;Ks3`hDfU-xcqEUlac3;J0e*x9SdUT|d9oShaQYzpbWs zTg}3)7W|(!`#<f6{@g$Rr=#jm*MEPy-~D+k{KLg>^X#|#4s8#d-yW*k9{F#3^xgKD zaGQ_+J7NEK>d@cm^M7Zm{=WL}uju!Nm5=1C{U4inj2%H12m}y+i$THx0D!(Y00K}1 zX@LN6Api&$BhffLX>g2g&`^sgBt@&cSGcy;^ygwtqGyL%YX=Jn4i{A1+UkZ&w0&;| z4Y$=lxkL&ZsrdgPX?i07AR^EIUr2g+Cje_X(tcyI!MoPI(*54e=eGjxM!y-kck9I+ zTJHr_kNZt8?}{?g;3xNQi;n+)8R>)OHxE;OEWdg3;Lf}M7+?g>v!i9MHyfiDGTPDl zevqy1am}-{?ZcCDlbE-oop(Pz<2dBvyt>*yO*Z=83VGUfFQ&xlT=zAvgP|JP7SNyA zq1yZ3-l?4g<9DAfCadz4GcPA!?MQkSCMF-X^qx?-0FYFSMRMRsW(;&u2w=FP8Eelb z4GVUUyQ9;r0Yle#wxhq?7C-2f-hO<3UhB78c&{wLbNni0W@ld&`Q7i2w9q9WSIlt$ zh<1~M5<!4WY;l7(rc<hJE={zFg9EGq(S5S7R5e^vzKKtT=9uE{3*5!08`Te4U0Lr< z-UZcJU^~i3Efl$G-B>90H2<_v;_a;Sp>&^r)Q7Twh#Ma+2A%ly;Sw!VXR%zi)n)NA z{WgON19>qPuLdLlSWo~Pz?G5DhJ-uERKR!SE02DnUIitb<b#kMWfg{D3+VZ(e@p>I z0(78-d9@0#$|5Vol7WDnvBO$*s4+Mf0;acof+%%#0&cWe3+0B7DyOVQHOAa#_NKSW zSTSK>FAfvh_&C-7!Xvd|COKI`cBuhm#^-`_=9hsjK^qsrZNp!+8>qLflaKDVIPp*e z)~MUw)VcDuJ?`P^fZn(6_34;zk2V)?eS5t9^Ygd=05JVku9!mXY7cxz)9NA7i9h9W zjKbLV{!fWMy@1WIXJlEEeNO4<lUh%E0gb+6<WICSr8}hajYF*;r?0%$ui$<k8UE{8 zkF=Nas%4Wv_3A&OmuJBM(|hptJi}{wYLZ4Sm1oARz-zT_)X(s`XH+B9Q6+0YY+fE^ zc?EOPM*G+MAC#y7BR+gfF}&aYfXH03PI(_};U~Zf`y>GSOzNZnRJ`dPlM@Y#Bjk;s zd(SN25X5rH5j*<slCJ_<+*G4Uvb6aKD=CI4t{-%tatX{vd;sK`6j=DVVWce2;@gMS zGr(NL6BzOCJ@W4OIVYtM$tkM%POj9}f&1`wbHK&XVzl)=4^zoq3+%gl-h=(_J~IO` z4dtz8;iY>_KSm~r13rhTc`5;tDbC6O5{oSfNGGCqZ5w{`TZU6$_8g<U@RYvD$Qw{I zF&5Mpz`?C!;f4~I3iU1NsMCaW@)iSa>Rl~yV5Umg#o{iDYs3ROoZszzkzHYxegbMG z2I%U^X?H{_wUdS{2}JfOGE08c8>A?l-@zuf0Rih6xGK8sfpkbe`Z9V*&tQLUf_6Gi zV5uqt<TzzJCj1{o=i<oJ|Nrr0_qmSbmdo7de!u22+pr;#doCflh2~ZgHM_gdB~4Uw zSE)uSy3R%}sYWVYzBMILDoUk3m7m{VaL#$Z&-?a#J>SpACWG|eZ-}sb!kdite@XTF zfx5GOrbOCNjjamPZ7Io^ERAf`1ga2}dr^2@311I53BSwa$OE-wbl2y7vb0GNIyC4l zc1_Iko1T)#BIdBJqYMHNuZ0+H3;i&3i}q*pXJ~$o4eCbaY`WnTl!*^wPBbI{0!6Sc z!%KihS&B<gg*<)WHy^q!Y3L}hg4^b5JaGy8NmmJs)wi&fj^j_8KXhhWYC97E@tk~g z`<`v{5v-Dz38kP_ke&Bz!1>U<XfcK8blpb5ED=POn~QVmT-s1hi}|Madl5eku`Mf% ztf(qZrER%x!qLx>LI7g0HGCSHaMjM}?|`p}(!#OyXxI1>Gv;Ax%t<GF*4^FX`zz3t z<E;&)sGnsSVtTI>0TNXJOEq}2X=fGeL?05<w3a0>G`3&v5FfKLtBX4Fa<$cbs>6%; zV>H;gearR#jB$N7wTGD5#=U$5X4tDbU|EkU;<B`*IC4GVddM^h&uIzEvX`Z{EE4cm zQUKFnxB1?Mc+=3G(*%Z^??r`Rm|y6`bXRlmxp(`YVNr14yb(>iXyB~Ilz`#EyIfmL zd5u2$-2ZpJ6mZgQECeo7dxZW~1wQy5`v3uCZ(!+X40S)^hIKvK$ZZ-gx$g-X<1!`a zDwQkiBkJo|hNEoj#r*HdhBc87^n&K(izOg{xE*1+-gou~*<!!1UKqfZI$y1fa4K-F zK0MoCbO(Ai1g8-NaP@9&IXv%(+3x`a3DJpaL=C|p;ktAZs!(k#cBc$rt87INNaco% z?yrqQ%&P%tx-9hT9$+jS^X>%$tI<?fIQFAl^(@PPkgz>QgHB6Yq#mRhlV}t>Q6Z1E z1(y9b`j1HGANdpA<fS6q1EfbcC^KVbS9yMhq^ge-Ah8Ky39?z}81Z@Rf&l7paLXxt zkB!!qZ2=|9db%wJUw!D=rIWv9H&nv6vegh$NY|p(L(CgFc*rl6@C>}pZ%U4L{icqn zd`+G9A5_KE3;s|(i46_J=e-b^xsO$|MWL-&pZ4Txi4Z*?pu=9nfOm2Pb$T)b?A^RY zDHr+>h(!OlRst=dB$Pfk1Z%xDO^ef40ji1k$|Y-rO=`rZ)gYzIF2|3y_-oQUlD%Vl zPh>NF#_XARv@5OT{SHhbx|l3%Q13~TzZ-^*9iX*K@!rueQmyx15vOfg33&&uVd1^t zOLtZ7x2(JoZD#X&n9EX%GQg=<2S9x2G;DoeIQpZd(-sQgncKGds&M2CJ!0E|Qpy|j z%?cV85$q<}*U}8yka7+t+f+%C_h~GRTr%WK1RBOuL$BO^;>4w&_uPG$*!Q`>Cu<po zQ@bVeK#M&9t$l7+v>UDSaMDo@L_Px&Bp!3ONM)HU89tZHP5m{)5vOdbWZd-*t$+dR zfg#9=m+<VDk1V7(6-U9m=O>oP3o15~Kv#l%%Pl7>Ioxg_qvWXnJkNS5#pZXE13$s; zzh|mKgy(um<xw=<>TnPIuMJ%SIKvEKT`3cbw5`$6-fQM9^zHGnf_a}-)d4Zo2r~qW z<_U9K%4bh&4{O$4Vn0_@nz<$44uK7Q@EUlo?jMO${M7Ikt9|>Ou;~!@gU@?3dyoNv zZ|D_Zi5psX6)0|M^az+bCV5?kk~X84dmJ^UceE^$nH7wl`ML1;O7u;y#V`fQJfsZ< zAPge4-s4oW;Z6rp6b>pi7qx7xJ{i9`AtQ=Lv%phXMSy3bAifxV5a7kaVV+x$6Nc|b zxO|sRJ9x1DGSb{f$=4CpA5>U1wC4&(0cMX%K`BH71y8!tWJgioPrzcuaHp%#3^Hif z)<`pA0^@Olz7(UWM)o(k<f^sINdgqS8nLENRoPMi@E}via~FJ|p?m_3LjcIh3&7#k zyP=^gGDV?E4HESj1_VG!-w;4^vAc^0_QAa1>6-(-pRlP%K~;iR9>ILLD8a^0X4kOv z#5MTju#c9FW4)sH1eOL?lqR52CwTi*z@BLw0&M`r_AOg<B*=_q9nn9$YLt_1UG%|5 zZh#EUS;>^U3oWuPE1rc3x|wdHxs5Pj62cswfwmjM6q6|Fj<RwHVB#7~Zq}t?R`H=e z>WWzAzY)}(HU%%1>W9%Ha1G6706{W3c&w|;TY0zKPg=Af*OLJg-t|8Z0J{MoU_@RE zpQQ5?*+fn*K^?_7DbB$Gzju{Zm{gFB^E0t*0bH#a0R&x@Uj4a;@xDC5H+WGwdv;&o z&%0y?BNUMX=~z)%AUmi&u3mo%R|(5e3Fd6sOa!Tsvo}!_Zt&%n^-)}BR23Pv@`!az zjlQkETEDa!H3~l!77_0pK<#D#E2aN9wGW)*T<Dwymg3upz)wE#S1gnZ8`Z{>Q;by8 zIaK%48MSt~WHVr;(GZ4jhkk<jriyp`B1R~}vn0cZic(~?BHRvh;P5oXaU&GwX_=f& zO<9dg9t#z^QgSD<j5b@c&=GM9gYqNiYYzLya86{thxqm*Qv|kQE|EPPNE{Z?V7#S= zqhQKX>x>V%PYL-MiOjJk$Qj4SsKg_Nyf&rF6-PMbP%+cV?Uhq3K!%-Ks6Z|$x`iu# zPgb)hAtzTTU@3U|VN@y~nka?|OG|E!JK{DP36t}XTpp9g^N~Ig@V2A&S8sw@wrs^O zwdxt<okubRYnhcGWNXlV`g;bt0Cm`~*%h9>sg3OBLu0VMt_{t*<7G6~6gpgR<}N6` zr;6<iu51F<F(28}ptgxBdPb4`#cKx0CFyIYlCYbn4=PEy7^Yhf>V;|=MC5q;rVAkX zY-k4$`B<W`ED7D<)dng<ipiBOHgZB#&5`Wmh#?t|I>_qip=fN|njPVPd2ALUUg~;H zIv3{on4HV027)*fjYz(7d(G28Uz06u9N98;HAfc|#K}1a0LbyuY3jA9*6`v&)Y_Kf zsCckmWSLi5aVi>?Cx#+7U<z)f$W*M;Z?>;&lxLPT*SgmkEVZASQ1_gdqA-A%h(bDF zsp;BUL7eH@U6}jYBx`LT7QIgUaW~;B8OcS*)i@;`q)7u5=#7;S;yLZybkyFrSfg{O zOnwKfB_a`C@C9~W)@yeq>;S-1;7JgTIl(C~<t_l2zN|L#E-?*x;zeox(UUzDPn%w= z)7e{#<I8+91<*rfG6NFnB#ueIyU^<&944Y<Mz+AY8p`MRuB;L$8B2VbmZ8vfZc(GH z`El2sg$R^yfvPd;HM6u9@K?5Lzei(@=j9wlRoeE3$OR)27_}`J_ymbKH{P>+@Z$M% z9V6X7BbTdYHck+b&};)DY?>B!g`5=Pg4<0lQIQ4?P*8J+I7fp552BCi!x3~cRemlJ zE+xJ6J+9EJYUi~gr(fAA{4=nUChH@|B7SyRAU%DgJCAnw47&8PQwqQ(A>(2=TU7mT zi_E4)S@q<BEO9?NLFQ{v3{p`cD6-*D$sSNkUB<{+n{}BEv5e|0y!d&+&-YzY=OSX_ z!JCr9ZZzx{29{3mt|K)6UO`;pDP+Wl{jqC_1A8_g&gcY#5sLZ13X$Z9`tVfMzFW?I z3HvBMM3vhRiG>!$UwuQk3UH#5u$`b1&+(HbySw+jS2-f*<Fd)@c}7OI3q1czcj6yG z9o;~|b5s?B(KkT4$R;!u?$!7Hyv*`X#4ka6aj+k3DtvctD{K`JDqvZcUz{*aA<OjE z&fhs2c9S_;j$F<B79<0L%4ACXc08u*6UxCYU@vQ}nKINr5*S#4-eqqd)$m}OGeX|c z=jg;Hj)Lfes$93cPM5+sxelaw>`F57)~54N(A1TRiWU#9U4}M3hWQu{e!R|DKhbUO z=ZjpD?i9eTuOKc7Z1{_wdeOc<VpJ_TDcV|hn2Y*lEvLXv+1aJQe4#2gAop^MOkTZ$ zW0-UVnQ@uiGvY7U_^(glL=<|U<5+&<oz2+fvb_7xWOx$kTVe!e+*9eM+tCfmSs%ba zNdW4E-QKf=8nBkT$#)1eMeRo2*=MeXM}btC{yBicRLFjC&%W_=n`kU-;&;Tct-jBq zZr%A2kv|AcrNC;*UBHUdqZPz00Yq6OPjJQ2QSh*s^syq4J}ML00!Kb+K7p2fB*6lF znHN}@PQJr)bZWD!+G|sk4F&ogr2z9kR~Ce9K%Xe$^NIHG|0R_@I&@k_F&^@p6`L+i zT9H`;WCnN&o#b0O&ja&OJut;_P&R^gw&nY_hDmF=F)VTvdzU$N|0)E?0VZtF$0EtF z*BNm$hwkP0K$HJVMXq*@ZVxyH^?cD7RNI8QE(mMH@_TM%Jlr@dmRF?J)Wih?U|8_} z@_6LLwSAMW@UX(h?Xo1R^ZPy-)gL>A>dGfv4pL~wD%=#v-NeFf@NNEnD^}E1*gVhP zM2k2rn+P`+fKpg>LS2_-QxL<1!J3Hot!H0$;p>CiN4(;VQ4O5(T|0u_N)X5NTeh0| zS^rXeJb3o&N40W0IfEC{07n{}4I)w^LwV3x>8IJZP_?0D@YRT;lZmTOk;T>uiV%4& z7I_Ud`M>Q$+C?aSz&0;Apo0v%vy$0j4G9K9$Niy+<Y%y&iG%_6=fVSm^%uneEXV}* ziz0i)h<F{1JdJKSe<WDMDuUf2DfWgpl%)POM0IRfqgJg^K`7?JV`#MiZgJrhHp8Yc z3{vni%VKx&fnroSkXyt@NCb$@u*MJD90`uM)ojkxde!~Ut?gD}54Z(_b}v5CUz3FL zeQ$C(2@A_HY{Nr3S026A4wvbnAQyvV_yWXIyh62e<oRE>js$TXvA19er<!{`p7CV< zsUN$HmX>0^LjEd6Sf<=L+(?*@@V`~nxqeZt+a*<mzr~Ba$d~CBoHub9`9y%fOL`=o zE$dMy+sIM)y~5$Fo_zoY_C7-XdnTP+Ng%aD+P6Z@fnvl|`EH+V;n|+GjE8;F!0NT| zUqK3qEB`MR-sB<A^goU%248YVSz4kdHiFJN5MP5@$jP4&A}|nS@(PcJk6u90MzKfF z-Bf{}pYru=<iCCV9NCYOIWL0VL$}1-NA;e%udJqiAE*J>D2(!;X^jm%6@-laDD5VR zc{(bJ;%Tb&etneeIXk@(CVd5~(2q)i8Y6iEg<8S+y6Ye0R-Nwi7Aw6P6qm4f_@~SH z(rW=QJ?=%&9O4WDu;(=HlL7pn!fuUCBn5TEF)!{%W<USFr{j6X$6VQrc!e7r<loEB zhg37EH|{}4!w)`H>#af^=OM0ABt?sxDRmKNh|ublQ^h>U7n?8clQ+S0gQxCgWtPKq zoMfmz3img)3w@Z)MVMP#=lPAez#aUv%~P_I0OR$A@^s`^>7gO-`qpC(U%W3uKi+&W zUjFJ<|3s1m(!_~sl58*Rmq~C?s1PHs2+sdRwFhN=0^8(QDyBR`)np%py_N$4pLfFN zzKxq?M5o#`<`Wvy1XC<n*E>W;yiBXL<4)tm?>q&LK$eG+X<kwIfnJRBMBR)oyibX) zmXek?V8Fd@N|#LBj02O<C<_3xTe7*8YJ+7AryHEhKueoiAuqjhK0%Sch(*i*(Xp@7 zq9vq@<dSH-+#?ABzM&Q~a--st-6>w-q3a0ej)+yc?t6trr0gP)6l6^w_CL~B+j5k} zb!p8D2rl2j+8AZJ@fh(PEt|?yXvD2(U328ew?6jiyN{}p^+YYda3cmucc5Mkm;Uj# zTv7<0v-!}4`WXS}GG!^=cLJt9*t1@_MF5(oLE<k;XGy^9uiVs!r}0%<?nfc&yXJ|t zhC5CZ8h5?(Yp{sDO<&rz&DT%<N@jUu$os(42FD$mma?}tgv-xmH-GD`^evG;4s?4Z zLCVpAyZgyXeR3yDbR$ZHP>M>^j&Jc^dBmNkOngu0L?w-0d>?Z?|I@3HrU)yb*f9Gu zRFm6rH5stZ&+wjCr9^cCY{fxkK*K(?yC`X@hEaF1?poG&XWu?iL4)(ZKJR<VU4=7& zQ*T)u@y%n|8&ZEnr=nM~Ufn9*_-yh}*8(^uwFU}u#<)xFgH=Cs6$G7TWkCJOe|fg! z_w+Akz3R)8*8tvbH-bt=^gH$fnosMD7glW9{~eSXs~>O4tkQ6Bg<E5#;63H)tjKJ( z2EhH8y6r8%XJV0i(mQdPUu)?4=FWZXC+q-;zQI@LR=wf#ly!_5P!F`Z0atCm*r;lK z5Gqz#*HkqGuT6ESkZRRah6?LTp{gFsHmo}pf13Ct<1_TyOFT^tLqD_VbDTDRzq1gE zrPR82xuWkHqSB+A*s4%nF(yk<bWKzwRAF;dO&mO*6LgZ&8#{3kSI;t3fe-3krwPkm z`Wq_1q!iF*ro*tGZeCF%DMbfRp_FukcghBjoNc{jzmEMOmUq=^bVJc)D~m8^_cvfU z%k|VY8P@Z>)GZP7HC;wPpUHz;UbKv1?MS!Mdpa*YzK%`>o?#rkgxf6yD{K$cV7Bpr zv3~7cuID<NQjL>VBB}^dlIcg`QWWVi!kfJ^pRR(jkI}n#iCUDBQiocOb}44nCsF=} z=@e>CCF%TuRbnhRxSCFhrTM@2?yAbjU$h34A@LejsHB27fh}N3g|~BAO5MRd%B2<e zaCxZ&b&oesTkNsRJ#n8d_DNBWxIb5+6rtx7fml~X?^7W&&$<-ipG~Dk)pT|K-Y{?i z5W@>S?{Ue>9Ifla#|wwOmad#T()3=x_^6jE<*HU+k_^`i_cnGd@?SSy(NDs@IW_Z= z+NQEDkGrAt`7v{Aeut=Z?~Z~}L)F}vA^NFf5AM2stGU`)emqcUD}SQU*)Q6lU$e~T z+iM6TdY`q~P@sW*J?dLlq10GHGArhOnZh>%{Vxy9anhj1xvM1?Q-Otqi=D>`rVLKp z3+uZ5dvNAE@ywJ~qPsyrI&xa~K+kJ`S5p_)MtyJdIqD4eeLStb!+em6Vf|+3Z~t0* zax2CDIyVY+T~reb$f(-2KrPfl%hTC3?L;x%vtg)o=O0?IpWYsru7i7>@|%s_hNKrp zwJjEaTWbtjeGjpDNFfoBXlNd8fxWNQ{nkrW@4<5PT<6$(^2YPgQ&bhdua*E>mu&7Y zU0Bamwwj!TVWdH26+n+aqRXl(o0)LEx1zX$D)VR2N8fo>MZICwFGmV6E}Sm)+L5OD z7lE`~11m+$$^#PXy>XiiC4k?m+G(xs^+vbnP)(U!=xmVRO>0(r#f0vm{UXhE9`kcO z<$!)_iBYGG+^Bt<l~xUX0Kk?7H&b=GBy=-#1f_C*>iCxH4AKvP;yho{kPQH6;@9%R zWxSfs9BlJll`35z)tX+u^ofD9rwV$iaeL)+5Fp@V^N>o$1`zl9B|}L=Sy8UC=TSwR z^0<d=J5n=PG4T1`i;%Ln>P#uX>E>3K*!r(0HpoxRzNZ;t7i;wo@b_7|>kU^Y$ta`G zD!Eb>Mb(e-TGIe_$NC&9+hJJu-TIi#!@J(xAlhE^SqA=gd*9msF1q=KA~l6BjqS5+ zx#Cp3!9GZcqd6$@7E0djvdxxaH@p`Q<@;ROA(#}ZuiBgO&f~a-4cKMaW>XbBUOy;X zO&96Ec4c{%1y|>C-fAb^)7PwQtgFr;c>NX-0#zR=j#V&iBhj?~0$R1jMY*=C-}Y#H z2tVz?o|A1|l(G9-qd=d;t3T%vc5a1~_S>*j-*HDbG!tzUykg`l{YRGTlxi+jC)I3K zap&NNHEJ_l<~=m$MhWg;uh!fYwl0#{wuTP3Rh4@5#l#lB?wXORR8iYP^srt=Z&?^7 zQKcS@-!>ysG?cZrJ)O<goZfQT_Z$hGM8-+F(bp_8q-4r@kZl1|GD~Q@&ZAiv=Id%j z${NFEO)_G=nI;*@nbWBVn%(F1l|T98kki(;V_w-cvQL8Bv~{5r{q90s-mJcsd~iK} zY_?{~>ymzlAv1kDPI@Pneh#o^dd5ZWPSvt$)Jo{~m&R9SB!RRe)l2}%(C8F^WjofM z-{qEg-exdBCIj`j{DULwb}dZ1Y<<Msbwd{xK9ARN{x$DA<19~JYq6Ss^u>4m;~q;V zmTI?z=o$H5tx%x2O~_vH{Wq+L55Q}Z+)Kl>sB(bv-o#eUrHtHN9m!<<a+XP2s<R$b zYGEKi{;X8URk4<>K}|r~B3|#*x$2~PpM6(=k!yZ8$`5lYH7W-5oyjH0M9MF1-L&v? z-=6IYf4y%|D|^_>Q*Q^L2?EY@p#%uDJhJ(!{&lvs`i&GH@sFfOe2(P}(<$jk6($65 z&nhVuZEBjDfKKEdFQ`>=<{nJiax0$cmRe$&^haoag*)n&Cq-Ea-iun}!#q8XNQXk+ z>X3hoHALU~a>|XWcyMu-fkF#>gB1Xp(fUPjIp<ZKpS9CK6C!Z!qASJyck<rk6yuD0 zAA2_TJx22xRgFDRtK097&NWleNG~!T8{T_LODepYuqs1Zd~1I4d1S^fFX;pX4b?k; zNc@wkc*MS3KkDD;S$C?>y_%$ct~)$d@PU)*Ow;ZepzAr>#8{n5v8@U~7P8~tZa<u4 zAI-&UELfu)a|o*1(Oqr<Hn<orRiQ@$w|kaZnLAHa{jN4_(0O8Ci|TF59|F1CKV>NS zTnNoFD*yW~C)vMbe7){jpN03U3F+3U`0`)7e8&VV^oikvnUVB%6TFd_SgT(wF!Oz` zJ#}KkblVFq3!{=<mJQjkyDHg)y-f~D<JM`xOy8qlTfX~OITsmdnw`f_JIMf=*`F%I zN!zZX#@2e`*l$ax^dFH4hx>g`>K-3Oxagfa+znIVAQlX%kgAl$6s_>^qyN4ubfmUd z3F93Y_qHSbdAG$!+Q(6KwH(>k$QnTu-Jly{zX;-%9)Ab`mg|VTUyQ)9vsGN!Zm@JX zpprm_ZgMaRiCS5ykfTAY*!2ch@Xfz<L+XDjLjY)`#NrN***|o?`lB<->ufFi{5TI} ziM{1J00J;KTzk*|7mNegXX4ZhSk~Iyy^Jnf9hQW-iJI}+<SYRmk&E!0Znz}{qd^ea zL#p^e+>P2X=VqR%1@HEi-yE(N*kW_AV7IQ3Em5R0sIuqHMDVv?(3CQHPB3%NIA_y& zwux==D1fA*MIoC4(jq*tn{5y*+A&Yq45p2h(7XJ5tHq4|!(CN^)0vGlv~tY{|G}?_ z8b|i6QMJMFKL~L4sm?d-j4@VX4kDNX-=)UP7t`4Q;EhxgejMJH<iis4YbC6Z|EyQl zOY_a-3xnu#HdsInH>i%>rCa@gGt#XFQgNnv1Pvbe-D!c)uI|2N4gr$TT<JOQmd3kY z&zJ#-Ge@zkY%ydfpS_WKx5R*0Kg;MgD^+~H84W`X<3o<;ApB5ZftQQdcELvG2X@pv z4JGACypH8?Sf+Vw#dE@BBH?na5=#x95)Tb3faYQ0zh|L)DCN}t@qHDH#5@EW49q4X zQx^MO%^RcQRgH&lANbRme)-guTm*(ITP0iBRI`P(D9Ha$xoWmX^acTIgvWK)?&C8L zOTeM)@J)_RB!#iFn-pF))RgBh@`vT6UT<F405}fvQPAM-(y$`SDukj<_gI&?o~o4G z^bvPK9^%_vTR{Z|2=Xl01zWgB-|~Aq5Xme=!8Rp?qmisloJ}AXv#;phl&oti`(`uW zhlSBv&Tjg&c!q<}Ttk7k|7L53)I}~)`=Yy&h&!rK@^6Eg8-#X7KsF58i@AS<8CU@E zQe>`AK#yVDjs&?*w+C7taRmn82NA4K6{Y*ww+hv?mdTJ=lL;48o!c_IL+pXiWzY83 zaC2}jQ#&{X=RS|aGZE6->M)vXAb?^9bhB`autI0ZF=s}5F86BB188x_;5<EKOyzVD zG8%Qh7z@g;p+yb&WnU+@cgw1J4G#7yy71|ik(NH`;IlCStVrWnH)fFpiic2mJcx4) z3ZSslDKNe(e4&6D5()P@D+e>2o~+e4$bAqX#cXh{NbZIo4XU3W1V!^amUcDnwl{hG z%g8o<1pEi#j|QJDa?i#w3%a4vT;{d^7#sfa0bPDo(o5yHXLkZ*M&u@y2mrFj8sa7z z0tTRDOwg41wAW+wQhnecH}FbDY4I53wOMN$pHcTq$zovJbA#&7(>m9K6>cU@Wcinx zCqZLonWqX-DPvwNK?txS%#y%ku(Tc=l&uts>v)X2B6loET&o6WN*f)}r4|IyiBQ0w z0=L9&=TIJgC1Rgz4$go9b1_IZK(CqunM<wSEB4OKW~cuxpC+M{%Dbetb`}pX3-BGs zFjsbmMMRu@aC*ghc2|Wr7gy!%mt|hv!8gm;`@~m6(ZyK`KvOk16`A@9vh#>HTv!r{ z#Ihc49D^03s|sgfWVxpsZ^Yc0C8mX#kuQPdQyxUcKIOb~+N00#<8)d!LW9wmr2kDH zmn&W6RA{JCvkD<rsbGgCJdk>Bw4Gi=ge9SS0>!K|XzpGKEWM!XHqmKQ4=dy`1D5XO zs=+3n!FK?cuP8t3akv@07<{c4>dSq)RZ*|rf7FqEqR?=Q56IInCdxpfZ;c)7LX8)! zM_o%`9HxXss4)(cImV9^lw``{(|IXl^@vg!nZn2vLvp&&J7%7bhMD@NxgoZ|ayWc9 z3*DfSZ7hM!iYTHeKdMkJV2uJYnB{b!!L~ebR1H0CRwY~vk3};I3h28c8M|ibVd$y2 zSw;v2x(Tj>7IWd%iM{^lZLhbFR0$yIY{q3V2FZB2*m1g&c-cA^!5GqaILY#w4H_U> zHkd{a+A7et_ND66{3zf*ijV9iRF_o5(|5F}Zh9aO5<E*USZ5SaSbHKF1#DITg&r8+ z7RP2Jpy1hKFk*bwj_l{cSX3UGv16RR$pq=Hc_s4zy_nB-$wA;GY%}83=o|G>t4%A# zvIpGURU5-qy=Z<!(Cc3akN=1FwAcyueDym~6b~EfyH_>1vv`vd<qQiF(1V@PJ0jWf z>G6m`=1K`dunh`foQxTfm^P^0%eh^~i%j<uc2RNi--F!#+^x(rutmmNN<bUidg=ay z^*<2hUbd&3Ct%;3n8A_Pz6lwDvyk91MlqkcFEUYN2;a9^rjWo7$J6W}QD({W>?n9e zDm{~XI(?R%%!baI`YHAbh|+`Az@1=ZP31hoicjxatnF)~?pS9ue_-UdI#d&xiq8#N zR(I|^2M<9(g8)X1T2sQ9GO%(dfr3a|XZZ)U`S>J%IDB{EEh1l$@nXbAyk22cU$fS} zg`~8vDNXSsQQ_7ukU17y00ClB6{3y=RB?h?&ZJ_*<3bA5v6b}`w6J;>7D^c}?q=Z^ zS>AyQM^ze&SLn%`b8W(f+cgWL1G0LpTaGdk40~)gm*F2_o8K?hxObr5M46O4P#xFp z|Fqb&_E$qX!YG!<&|84-cYb-={O-|i))4_Da=^*-$NR>rhLC$G?*XboE+VVbk~O9- zAFEft*8oVZsSBomrph|T?^DsLs+xKR_F|?vr;Ntmu97fIJK&pWJ0A%&&3UQ7%qO2u zh%MOEy~9e{m-=6!<>Fw@W>{xF#8<8IfnetAj?tZtCQT$-rvS8B)zJMna@7U)wgoz8 zje0wmFbbgrJHwg*l^3|@Zwi?4ISj8^#?kKKfP(U0(=30qKTCjU3;8%zrBs<3(YKkM zp&cHKuKPR?b(Hb!#=$cl1Ka*Qvov?6{h3lp;?p<6JXEWB47WK%Y!63hJ#LzY(tO9- zyGbR(uug4J%|WwrDbO8@Ox@#Y(@(O1p)kV)PUdp0Isf+8MUZm1%gxnY8@=jWn<txB z^rjzI<x77q;QNHnLb5xd*(w^fOYG|3?T5SJsVg;+6qvUcs~gXN=uE#5OFkVW1HF|4 z61rWt$dAj|H5SC;fg1*+G9K;Pe!Zz_P~Cw9_CU0H%u=&lH^alhF$kG&cxL_wlxf9S zl?`EweUCar9<tg^rNR!~hD18cUZ%Ij-C!&qT`~AsnLOBhgfbw;pNQ~poo&BZ0!2;* z;qGy1BbrnKp8q2f^45j9m*<c)o4R4uFm-$EVeo{@o3QbHlw8~(#Fh_dyDmirv6w@< z4d3Siy{!Cr7WHWO2mh&-+l|lGnzCz0tbUwQQhj8=13k|=kp-d{EF(e|vC%7U{tJ@J zg8_5aXG*t0VXNKo8b+P>-8Na1>vQlNL7NYj6<Gkid*r6awft9X8J|H&R7j&AmMTW~ zbqcnPvvsa)3E?!Q{vnmw38)&8(Ad;>S3V&8B4uOSTdFzoDTuNn=kC+C=aaEn%`|2V zagzYJ1DJ(}Qka#f^N((RKQvlCAW_&A4|zl0Y*xq;2&kwzyQUo5q*(nm=!SR5m+F3q zBaylXp}{J6oA8|-hk|ZUO80SQ&o&Owr%OGm7MWQnc!G6Dk{W%_8%7!LT3D@2G3{sl z7i9gO0DlhnbaLZHHX`F&T9Zk^l@MWAMP9WUWQ=1E#JBOGji&uj$g?QUSZ%yIGo*PF zd?%?qMA(rE!x+*Ir?wm$%XRj<zC53D{Ab~DP9Q73o|6bJUWD54t3Kx=%uxr|)GF<X z;kJ|t>m5^g4SM?`HGEO2{OE`MpAc^wnODE5rMzj&u>O;g%FM(v{R?cXDbU(ESQbDY zg}{$;ndja^QrF?v_-y{h?}uMXlN0LWDC!G=syxruN?D<&{lRurh^+*~rT+KNX14kx zJ3qam+0|lW4=II(`CRu$qk2M5EPW!&`g<&f70p+$=Rq?fS?HPvQ25`aW61twmVXkh zUl&@`ML$XT&z@3zW$T^(wjC^l<|=orYL?Nq4$aMF=iduYw$^^CuKQi)>|qqM9ZuOT zU>pY6DL{8H7;Ckqrx3U<1qkGT&b0X+#ka-^<wn3?w_6}VRjlaPhDNP<+E;^#deex$ zjHR!JlU&=B>7KN2Mh}`@4}D!eysO>)$iF|mc0aAQY{FBqCVC{J9ovBD)3q6UuiS5T zNt><@c(hL*-~(c3D9>M;5(XUA-F{FOxDaSi<IqkxVPFT;Yna+0(<K7xgN2%&C!efI z8wo(qVcK1*Cn|+M*@rcjzS%BJo^;Cny!^{<QEbejx}7juGK}faXwbV6CackH*p`zi z@($R{<sMs0b1|Fwz#Qd_-+v)?rX<OANpXx-v5uMdPqr8!;<e94%Aaox2>*Q2i7ft2 zDopzFsw-NXR+jbUpZlNnukRlnLn;An!GL2a2xXOt4`vvK`y~NlU!7QT$ut#p>-)W! z0bu1x%%Mh50)E^Ye!@e%@0%`(?m!6g0+ww9onE>?utqoQ2@hRP8hjg1y7V$cr^@BS zfPS_6gsSopfc*$zc_VMSRR34=91$Or;RW>vC67QgintJ!r~`jhTPzLUJwnB9jAiVq z&5?WDy3^5csZ9qExrOLCO-|W8OnAfI%P|8e;6VE+`+212=~UqZlUe)W2kuV42QY1w zuD`phy&CJbVFqS$O3AzaH?=Lx;8ZUZh}A>@5%Ah638|RuB}2Lepvrb%51JKQ%8iTs zjsXFe&GL>&@pj;+8H)k&h8n|ic)9G5o#rp>=PR9nWiVg@*bDtFyRp|TuKlm@zs#Ng zI5RAhi?-vYq&)g@ADtp}r0H2H<~i>Jrc;c2HdiM>)p}ovk<*rAX#MKg>*-@L77sg+ z6x$hx_Uin*wRw>arouj1;OX+=`+J*bY4XN5Lmf>944aB<C;s<<=3}uTS4pZ>3!Qaj zQ81YfrW&vx;dZ0}$=BE1Rm}7~`_)L>9bCEZi6qCntJ2bD0HSTu{`n%<-0(N{kF3-4 zfoEdpF;I{VAblJn54?BImG=B2rXlr2{JlFT@?R7?y=s<9d)O|_8%jTRxxSr{l_@Z5 zm|Ja?G6ZO-S&nM*4q~m_K7lnsIRy|*#$I<^>v%sorax}~d(!Tqqi|WT!i48Wv#=71 z?Yb;)utk*#NnLq6NFQWH2=jj&S>^v7-geCG>-c%POr+Ak{Ms!^<I&$Viv{JobdoZk zm7hQ0H5DWaP_oPbuF<Hh-J^M01?B}O2cf^3F+E{^Jks`_>Bf4K&`<AvJhj~QhfNo& zUQR_}YSy7ZRi8m@)A@xK1-Z4}MDF5KG2q&${&<z}Alx>qCfL>i)K*J1qG2@f`1<s5 znDIbjxT>_8vJeiCC}+a~Ylewq*X^R^R+aK@y2Vi&>2L|i;y;@=C$37B$BA)@9TGx0 zPZygdew(QNHkOn%q>w|T=~Rp{d_V6UvZ?K@s1QQ8cD9`HPJOHRAdRhr2)44}p~B=8 zX{tRbwS`iGFsBTnV#_A)7%`;uOU%gTCa4}x(pTpJBjy=%h~#<wZNJ7wFV-d))TZKH zcelaK(iO`?W`)YS=STayrQ|D1^wp-Ya6*<r<wnkozTA&>wtDW_d$HG3w8qmA2IL`l z@jS^gSYJkK#_&?!6{*nRrTZ!upN>Y2wE6e1dt-h-b{P=kbjI1`m_O?$VhzB>k1!$l zlTzmO&4HRiXBfs_N@fR{rt?J2*Zuc!bx2a8*0jLKeR+x%jAERCxnpqowU|9`^pKO? z44rKt-Q5{pvK_nd_*xfBV1CL#t$3K8{LUr%Z@K!YwY+Vrja+yhRb@5xq+1TR<$eu) z>tWOJynY+GfV4KkH<Yj6h`2O{yI1GQ;v<ioA({MUaKm3LOozIvkjpk}3BP3;zO%Nw zR)AB#I0lJ12?m1et=rmmMQAK?n0<~L1cixZec+$Npk<@CWjRX6Hm^n@+zq6BmBVuT zs%L$&wXSG<jA^UksI>^hEB`LI+tmC{ws;1t+z*Uka%!py3)-|FuMB&Ldlho(Y1<kl z^ntPyk019noQTe3yT#5Sb`vh>Ugkpe&y6xZOtr*)*rlpbs4pxyZmm7Q?w$|4u2bC8 zs+6qg<MsesDgedvAMr+v?)rvI1q*9uq=NSVWa-)rQPiE2qlSIG)scS;Rp0SOJ#2$3 za{!7aAb}g7_9{C@Ayi!WYehN!b2p#{Qoa}uPCz(5xzR9O^+D-#B#}DR)G(|fJS-Di zwR*;G3}0C_mX+_4Qd^{awR7Wls?SLe1M_h4R^Xi$+i~;WY<7i+z@<Q)mu=Xr*`K!u z)nHc*)FirF)DJHY;A_Pk1*6_2+25RdTDw4|wr*6jw2}MKm?Rm$&^p{0qNDU{u=JmV zpQ;mzYO&m2`?@40;FQ3dH9bQDoCCH)4%?6{hsv|bU6(Hs@0%=2`RDOyI$}1%-Ds-1 zI`qm|)zQ51WiJG22Hbw-0>f?A+7fchAuclre3Q`8e=JkTj?X#n_Vu~$##-x4{D<a% zovkgm?AsDPhNd{C@2^d9Hrq1JXC|oiDZFnl(f$X(UB|Mkm}}tZT#;dWo5d#|^>^|Y z#iRO*Hp9K2;kfqH4VsU_O!UQ>^6JiumUXrPwSi*qOP#6So1Vdz4|+6apc%<xHc2V} z`e6bzJKSrbr8F&4Kk9!Hrt`WN(sB5W&X523dY&7R4^%THKDzCEH+LAZ#a&OQZ7k%N zc}%Sr$FDI771mX~YLz~n@7%wrVEZ*edQS&~1;RhbX>8GqbC_4+p=HZdpNyxaf)d}2 z<X)=ts%G>cG~NcyW2_bB@`)nt8whQi)cVy6xv?I-@uKKR?;OC|dFO#=Lan?1W2Ktr z%3ILPNU6O$Hn6^zcmt5#5GU1>wez0i>;Jv>d|E13ljM3|3|G{7WA5gOSL@}$`w-mL z!WoeAh8omlV{xk5(uk__Q3Cn0@Z|ec-9KABU8Hf}4@5+4qQ)c&Z&lS>dTo|3gD5NO zHg?)EKM@wb1$Q?;cQ)~G|A0a7zZ)M9F=T>5a~|aR*u2^HrlPIs8ez?PvP>JNFhXh5 z`7HsPf)JGGmtf7~EltP#Fa7&II)7zD0x=0(ZGLV^wQOSVR@`O_4}P>_IlA(8Q0|OL z#rTCh>K%K!K`6*gE%^N`$bwSEY~T6vzR2ELmQ*xmXia;grA1m6VrICcAVsTXp$8W4 zK1tjA7i^je2ZpJI?Po@M&&WPN`^^i_#8P9-&v-~+yPZLF2`)~P=9U4nPzzpmAh>DL z4Ba*!+9;pF#4A~hg`Vi4GOpk}WPMMLpN@pa#Vwb`MDo5Z)f-IW?N&744a0qn!wEcz zyN%DNEPnm0$Q7euc~(X4m9F+d-t>Iw&1cdU-QFaLkUQXK_2*tg=n3+ew5>!K`#<Sz z2D&6lq|RJ3hF_KqoW8h74Y*K8TBKe)MQ8Jdha85j&0jcd!cOu)hGeQMo#u(z3iOD4 zF@D-lT7UQYI>&%acqMKE5P+(|%u<h9kKW502ecDOli?1Tb<1+HLwv>szLy1}C0B8e zfI~=V3Ath|Ydqa(JxME(0(vQl{_#R<3clZd*keVgD@z+_7n!WlEFS3p*So>8;Xu{J z;BmtMi}f@2*jp7%cjSB56CLL4`6Y}cs{R@-nus_?33Lk;x^1SaB<z(0S6xiSmstc{ zXrUi=AbeP)vO_CA+tVMF+;>LN+$)6oe7wu-W>?4%XLa457~DmUp!3Gu;;GilXr}$B zpyIJr{0ZhQhDn~#bRe{I@s(cvZjTJAp=P|>8dZOoW+WxpIs+*20W-9|#0GBID|`rz z<rCrgK|(jTCnVH83<f6E0<q`G0piI1ft}_nc+YxTs}x}IynRpNOU*@)T!J<Mpm@-c zcFUkSDZ#hd2E}~Ry>Xgh56;6{bT5;r*z0B0ybTxzAcT$Dql+&iu50i8t;kkB?Pv`) z>VXvAHyk0u`?|+SwFG<KeZv{BaXn3XLFl<A@)XbSfu-y}r45L8=!iiEi!|dWV8cAk znB|f9cVG+`WDB5k#aol6A9KwU!vfiKHr2#h5{=m0^9#%?#$Em@kvPd7sqJO?ZDtax zGcka~LtA0!WuXCmF`&B!L1)&GmuJ9EsW?~3Q_q+9AXFFGa`D&&+CZqk#WG%>qEEEJ zJ7x&2D1jc4IM09DTw)c=6*seZ9K)yH8S}FWcpAG2?Ai={9L6HrsaEGwn*J)DI!rX) zF)EY@-NY&J_D_l(A*2uTCS+fb1Hm4(fyWOBJ<Y+!Jz(ER7%k9be=*%^38%`&S<Hwq z%a6JC({W1^Bu2=VTEgm*FqU8DP%4!AQ6r^CV_#ty-lT1>m)Zx@cD3>KAV5w^FviJX zx&J-$?Smv*L(GTw;g^vBK~y-%{z3+2P3RpD{E+@j$s|w86D#x(;N)+;EcEcbv*SSz zM$e8f)EfrBCqKYVh@w%a<70V&u|p?Ts2`<HGXX(`sVJ>;3p%#RE|S$#B6N{dm7#s` z%{Zrw&4OH-16k-{FSc9PI|LYagr8Tx|Hg9@k+KFd!q7b8sV18Ecl(GQdAPxPjoSuK zqsQ=NWw;xsyp4Guqh4;HQfh}cqyV=h_JxKJkM%NWPHn<MP<1Vllp%66!23X=Ne1^4 zXTU14itaODeS>K52-RqXx)^o-?n13Q2vF55_2F+m369YO=MJ2<hy(?Fke+)CIyO)i zFE?q_{Q{q;`(O%ch<K1tOEUV$aAoKk%fG^AfJ@cx;VXp54-XQo&09|r+{Iv%8L;Xp zu;&WZsGH^)FTR_VseZr2@Q=`BMr0F&yCA{IFKOCN(hQ5Zn0e`Ac~tOct>z~n%YNu? zjPPY6#PAQ*EfhycX!Rh181GWWNW7i3NbLcQk^`Pnf?U#~TT32!xMhB}Cu}t_@ms<B z%&4k9+Yo7zK>$bgY1Kt&3uv1}h?yjP>>%wmqPf+Z+X-l|&O)0{4!`uEdR?Td0S$g@ zRH+4#sWa7MV2oM6Woe#Pl}wvUqb-MOyU*Z^7KMhILS3v-7X>ni0c~}|9jw4vtO&pF z$lAn$nW&klc$GV>;Qw3@rPhe%JH6ad-m<lpe_zQFDPWa;v{g^QJ<3?@8r7g^{32K5 zLCLsZuTa1h#@gUlj}J3H96z?^Z;QFRut+nR1vz1!u!`6oWSX0pYQQPMtUtCQ_$E3K z92dcupj{S_8q0W`Q4-5Tj5il^9TrPt;zTaaaimQO9S3K$5`hoe|5qjZ8h-;$oX6?# zskW(b11`=3BXS(Z8*4Uv={)JrRW`ioJ+W}%)(7b1^a!^`O*LnlMO<~Xr<q}?7VQ}x z^B{*w8n$3eh=sVDi<VzLu$>nL#Zh(M<J?!k&epJgO%r{3IG&^8ZU8b~iTJH<V~{Iz zWPRFLcBa3bWYt`nSRpi=$LpRvsd{AGi2nX)(IRP?>NW#v>NLJRQR1Pz^6h(jPNEP! zOFiFT;eh}{&(L$GciUxv`57X+3YxPU-h&M?iWizhf?YT?r%3P_fMS#pTs>&@XSLJn z`@7`j9R`PT0}UoTyG17ULXY9Dgnxc^0bqBwkkuGPdO6~V+^9fn;|(W4iv_C!XWR+) zf?)kZ;dGD(LbTbCCjB$Xj<m!)s^uchHt%h7F#JOmf@m3spTwKD8=Axj4G?(MQ+k&} z!JY;=;8mP?63Axlss546e&5Ezd-2A6FZX4tnF07s*uA`YnnkLY)r#0}KI~TyZr4eK z-%CdBdQFZ2*b1<!TM@dx>+_J{jM+k)&|NO2RWayGa~9#Q7m!vc)b~b+nJj+zuDy{x zsA}uUf(x`_2Rqk15n3#&`|;H8;gxCw>EHmG+OW{0f@+lvHsT?_Jppe&udH{Fbi-ma z|H6B}0Ehd>x#BTV&pVOZjGysxf1%^>z6;MU<!!vpL&se(7g-176~}?{$s*eVku&;q z)R!%$WBMfXCSwZTvRUZaL#xla{ABt{)+ItKW!N%f$dZS*Ajr87;AZUmE%|9CO`F3Z zFiujYKP!B|?6V9ISyhnY>c<;1MO=4vGm5_949;*#oHI`|SQGjltSz+ra;FcHw&(Rw zHceSK&WNk;;A98z!1k#!rZ>^8so%2T14mx6t;x7;?X);bFsmME+mjq~#iC$AY#NEn zy*hFJI6Zr&?A~sJuQtAp0z3vS(qE+M=Yhh$W#qd!`#GOU?;B2vr7oLi7Ijs6h=sZ{ zcuzXMdP>Rcw8(&`qbM`LIl|o6zaeEHP&E)gwj>H4FM8)6Uf<0bHva=x$d2+u1YGz- zRT~zq&!#g2@P_p`lR4oD?jsU*2PUVs&_DaOluv$uN<4X#<2t+?bkBguv?tdTNC`aI zvd8virc8d}C>-|W42|?5I)hjyVxik2HOAU`?_X*B(}`g1+E3B}CuW4|0(^R*%V{H; z<0MF>2h_N63KI9jz9J*9fav;nIscD$_0?g^y2>I?*>M}1+2%#kJVmwdqWAg30Wg<9 z@;9EsFAH61V}a15Cn9I}sQyi@xIeobkB%pI5*p471@29hWU|ZW@rLnI`p1XIjeHZ9 z(zVXe9XZr;KHZT563T6)k#NJ#%bVS<XOpzw$zDio#v5_L{rh0Osz)gLHo#4g&LS>b zpYCiAb_k$h=uUp9(@ag8__kf}Q>xw{q1m3KoE6PWv%>VAovJEduD4uEl*$bJ1nLCN z`^}2+WLED#Wz!k34H4`r0GSAIo-e`1SX$<Ls&Uc<o{Zbne+2W%A$#S51SN>mB3Oes zb}N50vRAmyi{g3_ClmC~?I(Khy#5LCCX?gTXoK^KetT{j`w<c953>Chsb-QcQs`t~ z(r9An@W~`x<);XjHM~BA#@XsF`AFaxNJlLSF=%k|l*k%$H(f)~$nVBF`pv7Fy2EYn z3r~k6eA*~89Fwx67pjkyXj0V7oLDAA_63(b<HH{@%b>UC=yv9@c>dpE>tUCoX1CLc zKTCV;I8=AK$Q3Ix4hZvud#pa94{S16+Y9kYIF`L=dSqmWgVVk62n*f^65`Dk+z;=> ze-R5J{g*ra|NQU7GAMle>)TQ$z}Rh)EX{ec8>6l1I&AG3KV|Z~&R|8#X1>F-0CeCe z1j`3obK<>da7Clg0Zsy*rJ(Cm?_87UU9M`AJTp-9);sit{V5QzUl~XMEOncbOCR^A zfx8UBD>?PuMc{n7mzy49i{i;-r6Q9MBfI4C<i?3>GFS}lCT!wnnl#of6X=h1n9bPO z*5@CoD&Gc|nHem3EPe3f)eIez$Um*IbqjKuHe|ry@Nd@rmjgckTwyA1TylblrDz;} zvq0@!aaX()*SORKhycG&0EuOyZgT<dyN@&XFqDk3fKm;v)iZk@R?47GJxs^Y|7zZ? zc^Di-Q6sH+AD4@t=|3NJS$n=rCUHLdrC3iBPEmEGKD}6SBU(YpDtBSIrR;n4Dfe&X zQ(X~vP8T2f`9<{ycyIMg$I^A{`;Xw|5oF+NRf6HUO#0OO+N3@gW<yCpjj>~EvK^)~ zEmeI)DVXZ-b0+K}1uX3!Sx#2o1q2y2^_)zDwM^zU!h!VeD9n~(-r2i8K<kEn_vz+I z4aAL-4~IJ&cF$nD&Kxy53kQx!_D_!+w^Z!%`~G{Cs-3Vt`(FLc!Ku-$#aR=b>gj9h zBg*Fh%syUNWXrrNGNrJTH-{6wtBI@EV>c#zIO|&<1;qOq!4v$0n=<;;5mP;Z!$}%h z%~7e_0Nbg~ru6Gl*bCdT`;AW2-83O?r!FY^)aCpsWz-#e5|uL%kx&`-B<hSkjDmMw z>Z(56`e^z5xszU@>cG+82O7fOl%$+2>QlG8N=s_8XxvLs+_$Az4+5yizA5!pJk0Ym z(h0{-`A#ZNh1oYHTpLFMDT#!|#uTGl?TuMH67j+$?Cag8)Hm0Yn~M`SN=Hr?x-Bi} z1ZK57o@41&MZPK1@Dgd;q)RC^Tw17kgwFhMf4qY?KY1|lIbl#d)GhnG^LW(S+`gn_ zntSkhYX2s=Dp-$pf>*GoD7z`suP@l*%JhUXCHHRWUEY!s6woRRypSB03ppA2@xtKe z-|pXL6W;5jBBZb<f`?18bat<kR|oKI4>}!>$Lzhkm%-Lh1^laAqB@b6OS)>0-`8AB z?vdXkw<RI|kISpO$m<o`cF5smEQ+nAQkwT8G*UFl4;oqZCBIgE>hd%iE%#rFI`F^m zPaUqq0n6H!uA11>AB}V@;&uhczP8#c*PZ&s5%WCh%@oL};e7zi6foUrWH^xK*W7i_ z1B>+2B*paRBUJIp=B6wot3{=po>f)g*sZxDUc$7luT~+^WcJKgE<JYR@2{tx8GvvK zxjSic>l#3D=+wm~7aa%&mv|eOg}E^T_Nso19MN+V$<|p^tNxOZ8nJV&OhToLbcv$a zHn@5pRzJjIW~Kw7SGgoRZwb+jG@p?Ia#q^3Z;lbpZw3(mldEBS=gqo*)<q>G;kFo$ zBi(CDki|1NwHMf#)=-G_0+FnXO&BrK)Y}GUB&t-6jowFHK?S*)?y90qiR0}RB8I8j zFZpk^GV6U)2Z*^~sYtIMQos&by5=-y)MZV8JjNA;`Q&ZP>+3$#HjqwIWjT*nU(H4u zj;C$AD1p8lCZLZ0xu9!1&a`+SR!7(nbXF)Lo3Ax``MUF_p9`mu*SzGi#Cx@0qF4@_ z-Z_7BQSK8pmP7yBL65M#>M)JRcKai%)16^ji)hxL#TIy;d0$P<+Je*2*&6gen%f3e z%_w!Kdb5&i_(qLw7MQ4K1MNBxlQ%vVFO+>T`^G5O^t3-44!8`zH8S?n%*k>zm%0y* z8*KJ<8s5}$hu^54;zM{qP<fo}S=9n1s7Y;!bf_#%b4@@Xwas0+K>=@nB4HWj3{~&1 zefxhDop)GL?f=IQ0t$kHIB+stSvhc9E^z0{otYN6GRs2KGDm@c;z~1fTcGABGqh#% z0k^i$tVherm1+5un)Wrb{PFw$T<1ERbDjI*yzkHZ_0rrLgKBLOAD&}hY_eZF;__Ei zw1?q@=^1%O-kMm@4irb?LPoRWsNLv?AOKrU<roBEln%q)4IX*)?SM3)Xa>%%Fe4B1 zQW{U{!U@esLZ|_mf^ehPVf(o<3_@pX#$qsTr6PN$`h{GRw^^9`Lh0R}<qm86>ou!7 zhrB_6d<uCQ-GR{fJMb&;`Ejcn+AViuoMiOZu21<b0}^_fUv$t;8~3e&qco$Wk<r&+ z8C&n^Kmv*Wd4H04r?S^hMWHBR78yG4R6Y?Z$|FqGsT7fVCBhuJ%=yD{U6XD`B!5)A zVU*fLs<ioiQ&gH*2M<hl8|?NcMY5ythL5wYpJ5PZRUul9b$z}sFFL;XR{oD`w2Y3w z=~kiF(jepQJO;>~L#Ay;D)I)TjY$_!(X)Xp-u@7C`f#qV=FGNIabJ*DlA`ClGyaxA z?<JL#&g<S$xG=i|;k5Cf1lUZT-di^l&#uR3o*yMRfBhCbe?cxZx=yi`%&~ZTwD2Sh zjPc$r<MWa!PhXN!zCsN?*IpCzm-8QfMAcP4Qehxmd?C>}UBM)M818;7Qln#+Ld9`2 zx#)@`ijSK;_4kXaa^mKFC(v#VD#O+tZiR#)ai3l4GR(jALeD$$(FvFw;0G`?$mXzF zX(_q5)jjwJ0}y?;FrNfr9e$SN;pj_2xglA0f5kV;Xj(^e$7k?;!rt<3qGiZdw3F(A zv>8%1@q>GEozit7r#2UycPN~zqWDJUfr0<K9B;7V&Zn-q?whvGm-1AO30$n^F5IFi zKwO_Z9Q0R{x_vvCr6K0I+ux<A_#6Y%o;Eki-yAIJgC%L%LK)~7EjqK`^VEY$sLnjU zHqG!juB>e+ewIkv7d?%s=ydrwdsi;Tpq|_SxH@Xp6~#lLK)SuNU9;(Nmj!2ygh+wa zDy@dyps>?yIHy~ot1u%YCIj5A1AL*NVg*j--Ag$Z1O7f=Te}rERo%7MK^6N@HD7{H z>>Z0PM}+dG%)}Ljy7N;7hrQ4DOA6y=cc%&x)(_*1libXaRocVzQd_gg%Dx*>`_XBo z(>)dr!*+Jh6$>%CBeEh_{STZUY>686$V{JX|8>+JvJ>`;fsD^nfB7$ux^UMbmH### zPZ=)4nQq!}b`si)GGe9`ZmZ_32|8{?YkE#BTeKNI9LYUwKTpu9cC#BRMrBrT3GcWv z(m!bLGZ@p0t%J9MOX|^+Mh0=nmWPyL>0}zUPKC|u-@OhxpBa8@VT;_m^RHLh+Rcxo ztxk92P+DF%1FXf;bj{CJFmeAXwJ~hHlftIqAO`rw?0jmZdIwX*reMxf7Yk4oNo;jr zCWbVt7f1OYPU;)Lv%U6`EkON#YqUd^ruElTv5b$Gcs8~+M2gu=t&ORmZ`)SKPDmeF zA{N5{Rk%8d)`c`sjBi36j8sL}En%Fn##0-*vzHtBy53!W0nw`295p4PMm!Tkh3_ac ziBhkdaGB9nLb;tf<|Xtc9%JLGh$>$w>J3b_ie~i<5Ku-``6j~gn2JL)=i*7IH8k;f zG2t6Xqj^TDA`2@<tKo?LB%fC5OZsgmji3e<I@5A-@Hjf!BAngYmNmy_;$r!jm1hRw z)2eMy33)FOrrnKhCC<gDlSQ?pPvGr^@pnO*tu*`y|Gpm+zb;Z7qG)Y`lvlH~fa9p# zcGdexz?Z2ox}cfObooM5F{a_z0>T!1s<X|b%v(o;zSA1Hq*wL{W7eqtv~VfA5i?76 zyv?^<rCB_SAq33k5pED54I?Vk?B;mZ3n`-k89-v6Xh2eb((t+<m2Xo@tJ?pn)9?fJ zsQh-~4>9i96kf9!PbFfL`12Bx36(!JH^ub48Y?g5-#M+Cyf+JwrIewuk;aKGW*UwB zW*$$14PF2C4YSDt`Iv5)(bVro6NY?u0SqOx>_EW@d=yyg!&gQd6JG*Sx-C*1p=e2L z@*y0e*2<1?6E53Su8NNfr)gMpyB#c2vQhv-r^e}X1SzzV_tds*?E@CkcPgA!C9JF< zU5(u!wHj?{d9>yhGlsZXw0)I!P$<~OG^<z9{%x$&Vb@gA$Hav)5gQ`Sf~i{vr|_!q zotA-rzU5p{2PrqRl+b$v%lNqSAUTPWB$>AUcZA@Qq!G%;F2RWdu6ldxVuuQMcF>fH znYb__1R%pE#VVRajl%1e_aX@-5pwVRHo3Y&i5O^QAZ{QB7fHhoP^jt`Rem?T%bLQE zi15BNwSgHss~>hy`D2i2W$7tgkdK)S2iNR_%|05cx@5wNQFr+YM08u;rm44bLXk$g z33Hfain9|)icN+U6Et)wxVC8<1*fvU1f3|ztFXRj=)l0VHcrpBz!K1MEB_EMS@eRI zv}FTQ{>#S;X_&tvT)3QljKySUtEO+f?gqmxG>*^+Rt#sV&Cw=GqeA0BK4CL@6(IjO zCg!$SjJ~FDMOJR*nZ;R}LKsM1TAO`MdqX91Mz;v-(u`}NY0T4<;we?q({ZJ9abIXy z!jzml6tI&4+Ca1~6pRf`YlG52I_dUD>CIB{?zyA#Np%?pH`GgeFm6-g<NEwnqGB3o zHoQ(Pjft_M;5KzM6lDFSNa-+v;~qo25>17W?B&y*o}@h?nejX|l|De%bV`0AJ6%-A zq$W+_BBw&W^A+yq5}tM2ZCQkh2JH?&Rn$Si21rqtkNaj2Sg}W<QBv8`q$!mU-7vi_ zees{eqx3^(RJ}n;=ZO=oPP%+l{_MOV#n8{jTRx12_w9;Rj|}~W0+6=|#<vOj9L3a6 z&izfFOFT8JDA)m_dVE}ndB?&A5xYUfCy5kQ249~Imgb~H>a^hB3JrtgPLq0*b`<`< zl`9S;wSP+Y?ePcM@&{5W*kiO78}Avkdj$HL#I+N?Y8Vz$uM$R)*ZyXFsI2UA{O1*# z+Ltwg?8S7Xf&0Pcq<NxZ_LOE#;~^)#4xz-AGo`sm!AjG#{6yG{wSC)v9{pzz;U`bw zFEcLI<<+8xW)H|Mo1Y;St$d7`YX(x$WTMK3ROt0rdf0PY-xOVM6ZJgZe7_yv=P6R~ z{1l-jrIOcHNLn31BNtbfIio>G#-tQAmx|uxWX31fh2F+rzJS%|<F!>nMR$|)n}hA9 zFmFUb9mI!=+>G6Cwy~bOO5}CEQ%b3PMd2_n^mtj`)6;$pfwToe1qJ^C;;lsKWZx!| zh-QmxPJC?I8d1e+#0^*Uek?(a1kE<+Eozt|gv(+*M7U8utuGWs-KiZy=SZJ>nTNI= zV-KjUPbp@tC^fWbq_rf@#{@J}7Jv2{HtjqPlhR0>vx$DA9LK!pVT?DRDP<)~a(R!0 zxgZ61i;;M>iFvkf^Hhy!=V{SGA0H=`gm<Z6Z}l>96@v{)ls%YfV>_B=YgCTkv_iNK z!Q<b|#Lkpw^>55*N*kbOZ$#uP-EQjcteLBPv+dtEO}1T_$-B*0lodyXIpYjy`+0sr z=|r2X-oxclO3&zoJe#dfruPC7n@YrHOUz(Y`EZc3FGW$GnQKE)JfEVP1oD5)&;2P< zucNu#iMq=8hIv7h&;p7_L2_-4)k&!r9{1V35#cqHap;?xD-=xM(Tu!M79tY2qrO!$ zQQ^p*!^Xxgp|R@8A_Y}f)iycY3vz4Y1x9)ZsDIt*9&NE=t-ze97{bRKo5IHP6~7gs zX;Y_YlsYP3C6=b*K~u8eBTi8?w?;r(FPK+_qC;odLvu$Pe=_kS3=Pt&kE*+B9%k?1 zi4-+=Vx?o%Jf`^9M7Tm5H>Cn46~#pAue3)EdLx$l$Ln<CzUeE0aGsnwRp`McCgxzY zDmk{inW#dbDNU-VP-zdc>b<`VobU5`)OG#8x4vq=6l~2`tU6I8drEzjR`shwRSc3` zkk*rXRSkSRohIMKe?7LZCLt^&Ye?}~qry5!ee}o?q$jb4lKiB{&!9q~UCQ4;bW_{q z3N#MKus%Eo!Z}T;t<cWEP5jI52bJ;vOJyo~i&Vn-t{#iyvv2@MxrnGM)c>T`gD^Y= z!n%l*&>-cE2RNJ}ZL6VgH!!&(X6An3?>)NF2-omj<Oe&5a%5ptF-<9wnXXhsAWs<| zEg*{H50`euMs=s|XP#2N3i_X$B|ufBckDRjd;AMU)#ak{c|Mt!G9y^t(dWA5-FyyF zxAzMXn=Dc$)0C1Z>My1;z7l`Dm>L}5<0C<8nIQ9=c0p~r=bJ#)a2h%dlYN?I!GA@# ztDAYtw6`;P=jAVyeQs8H<(S(|maa*m=P3$p>esJ3;n^KI1|ZGhHiutjOO4I0=x4#X zW$L>}cw=(&S@J3>a>{i~#|?`5oY%rnilTUGU|{CH-e&M7NW+7vUP8c2tJsQ(_at_{ z4vm6A-L5V2_L09PEuW|E!|1-qo`Q^jwW^uD>)$-(d+DAH-ls%Lx_lM(%e-%|ERE{d z*ME-?`fFcIpLa=B4N<{_itwI3)fY6BH~0z-{QKKBhu(qRKGJvXnNpfVXx8Xs%hGU{ zMN`Q~?(P2(b=hK<W}=2SA1DgKTT%W;-XB4>!_7{1m27mJ5h-|2c|Cjk_!8K#`!&&G zth`j(y%ifMQLiyf6i-q1A_l8|5*52>s(+=93Nl{3cP1QXDt=+guZtLMG`t^E<?Ixu z2Q>D9o9-rJW}eDDQFDLw*>M+Va?k9;|2E&s{!izo2mXOvR!<>JG4f_!yei2?d!9Ia z(Jg)JE6wdxA$E+oIqPosmpP=eJyJ0%`9#I5#}V2+vDjZzn3CV_Tpg_vgwe{&ktegw zgU=OST^rYQ(f9r3Gx7M!ovGOxkr(tC#!$qt^3{G3OR7Cd^reVVU5sp+mYK6$rwHH0 z$Gs3KDy=AIwc9CWy_5O<ZkGcwECw@_jK-Wl`E6S5Ctuwy8n5myisRq%nR&m3at+E? z@dbm@X^KHfV(y>!qUS1x{Gi<<KEl_-XD1HJ)Oo`q<J7d9QIUaT(@(W`YGqd{a{2gm zO2coOR;rx&!%Tw3lNr%L?c+485*8Stxm+-PH3Y%f{Zy-AYS1Zq&PQ_pm}tOe1GW^< zYN32ZHfjo?-OEPjpPo|ydU)HNT*If#N-q-|6^K?>)%*A=k7`u8qJ<@vqL7BI?9sHF zvgP<o|KqUedWb0SEl!#`b&^)}KagSv-|d6Z-*8&<JtpQ@<B2O4u0c=rFVd8(rm%DT z4tE0$DLhVzue5$v>m*KF;4!kYx93%YuCLQ8OqZKP&kBol8K&XsOqB0O?0Ghx_u{Mj zxlJSOV-k&KGDzi#u3}^MO&V82%*3V<zsWVY&`&;}$~OKyg`rcFKwTkLnLr1~CR9x5 z;vlNGzdGIeY)58S_`>dHqk5}sO;Gf)Mk9^p!=ue9c5q>^Is5&C+Sx5P)W{>whe!Wi zKb<>rJ^j<>^2(|tdQ3OSSGUizXc@WcUA;R~*7DkDOVIVO$3sgW>`yIj^r}NAm9{7U zHukv{;!|UD-1y<(*PiTg@65NQyN+f5`^^d%om-QlUQ;p2lt=AwsWPf2r8SC$h?u2- zCtWye?clPJ*N+nPy{dv_Z^S+IU#oMqwK*PcLEntb-ShK=*2BP?kzmyaXltkUq3OT> z%Gq@;P4(pOeVs>AX`<Pb*FNRs9lWzJ(dpCVo}j?+ZllUgH15T(pV>GiQiryT8Wwhi z==+8%eHX=c%@tx4O|EDkSRyGL%q`6T45IKmSLr|10?G+N&z)YGx@^7N{;>GuTc@TL z#Uh<5-mATim(gH`pUZz%b&2|yxsiE0+6J_PofFrJOo}^4UXpTF>+|*305LC2<~e(h z<%+;8->5uV3a&4R9_iQnM`?SJJ}U-H2+VzbIA8UdYH}~ySxkl7d&IDdt$xjd_c%OV zx<v3CwE+vW?5tp9FU`b@BL;thJT6+l=b8E7|J~H_)^BeI3mvzXvN82W4zfoYN_;)H z=l)OPzO?^Slayy%ya*<z7}*=h>u%Ud6jWWXZiLD8jvYwvYsN54WmJ4ndFFb16$)e8 z15kEmYh{<**a&YZI-GEMwJ~!o_l=zO+PoCP@eLjF!V;jHZOJ=cwpc0JcA1{?j(a{N z@A!i+ZBM@iZ!Ox$@7mN1Ko~y_+U8p;BN>RzdTBF*wAN2>le7NecgrWUVbrN2;I4Ym zA(Qn_-A^eV1f`+#xl=LM{aXv1ip(!B_xc~s*kz8=S9T0N>}C98Y{aTkZ2p2W$+#tU z=%RP|+E)O*@ZA)-l;aQG@P)}EU$w8f>HJwVm)}{tddcLn<BJ*3>UYNq2~L?HMu9_x zQLm}TxL=aD1E71cz|OLV-~zibdeJKqPrUk4kLK7t=cK1KJ5Cz4aDJ)x5D<7<zTWQp zep*iDtPwCdn(XJZCa#a#_0{mAhw;otee!%=k#Abw96;V0B5VSJ^A3CF&G#NKe#u%p zcyOzhDq3NT2rdOxZQt`&#<c#f!IBW%zXKS(q2N|##J+A<zWJYJ^?`B=Z_Cxz-a-e# zv%tOa<%f*_+N>EmpmbXfo-}^}G{nj|R_Wf72M*Hep6;A2IgqyXcMB!FXb?{<|I%&O zMf-;m9f?nlSNktqq*lKQ#a001OPXan-5J{WXQ2lijA?n##WSX(72YxD1FjV1!hMge z6okcDqe45olphjY@dIL*+dMs|V8F#NTmcc$;HkMr@BLIqE368iQEyS}cStgY1I06v z#(lnGPmla8gq|P17&*TQdLSsC#!0H`_L`!+v@OGK-}gMN?Y?(f-|dogb0y47Zi>=* zdx%PFvCO-Y3xx-5wDBvUukEZTxo2SA#=sX<=MXd5XgZjpH?=P%9)xgfV5;1%fZD|= zpu)qmv~Q*bJH&~u_zUV3YMNd3Q$?sVwKM9a;Qsj7uA<ChXZ7EcIeI;44WqQgiXKD# z2BE6<SuqXIlVTVdB<B5iovShJcj-R>+y8_*t@=(_?~ifjh4Cl}Fp3*=LFY<F4H1_< z4(q>MjxO|$D%Bg$7R^y)Bf_UKcLlu`CB%Y+;(qEw0D-u|6#G4A#r_cHlcxQ1Eu!lb z+9!K=4M-BWP;l<1B<mdoG4egTx9}B{J&wMgQRzrYRFu%-#c_uD2%_-a5*fQL6Jfbx z5d3^z-TAH?CevF-QFRKIF*Iry6CI__v+1({$d96uBQ-Sm0p=28cj^EQcM(1a-}&Rh zB|(?+MyT{Zr$l*P+-dCIs}XL(mLRU-e3j<7bWIthFs()gSmE`au~Ep6F9mB2^E7s# zo#c~N&E(o(d5(V*(Klc}u9n_tjVW3w3SXs^Z&pCObwT+*?BxN&)~^RQ>JTBJ=*u1o z*$!lpY^E;j<^a{%L}}p>4cUmPBY51Pf3o}K5h+m<y6Q`k+VI)#8)XV;r@KsqpC)X( zexk%VPb)mhbH&}+683D59QLAzW3^^$wH@bv<+>{T*RhyzGac1+{@i*!s<nAqPr^V* zoJ__)ZJygc|DgEB@>P1LVDg4=0XvvXQiGU6ohNmWK##LLr{{#bStK?(6rxzS)Z|cO zihOuvrdI2f%+AZQlXdf1SW7QWpcQof%zT$}g=#O!Z<x1T|87COO|N-Ymwfb-(*rL0 zbADew%K|lSs!cq!eMTqhE_M2L<DJQi|D{su*}A&t$$f!MrgDK3r_`n1hMIE^<ass^ z9T#gXTg{v1?GjI8r8SoQi{7FEqd4<D3J3Hf|7Qk}!J6@#P$PmVSDw$({6tMQwg3S< z^bHr+w%c1*x7<-~HPd*nX?IKG&#;luLiMbC9VfH)m>$0t2i};=nW{v|k2@8N*!6{^ z-O4@W$Bz2pFMYUp8D`ZJg?llO9q{-JMk-}mHKUBzg6-(s-q($(w1L`uYmeK}Ri}O# zkr%RldV!vQAYxKl=nyV~CoJlyL~3VS2paRxj-OAHxsS81xG>PJ1$B5!me#YWKt<bh zsr;yr?m%T7O4!uH|JM?4b(`-Yf3r>n2#pR{>cAv;M=AYEwQ`<+jxHmzHF#Ch(7nXM zvrEqEYZWezXECMdOV{IO+U`H!zbZ>3MQT-rN*n3@iwa+&V15{+SY0ud+nWDv_M;iP z6SH-)z{lJ9!gVvQ+lL<yGsN|ntD!#_4+d%3DNfkgWKZS-h*0#uLUlw|_H>={4Zp$1 z-1d1Hdk;{4#OyRq%eB{$da$h;adydQqu(g9JwI?MQuRNCH1`zq%5lS}4`;zbgOZFT ztMof6<zsFRp~T#bxO#ilmn(woDdd@fDb+|Y;A&->&lJ}wnh$2Q3-1yxXkEShPW9@$ z!pMn}XlJce!8hZ+#PfR=b;9kOw@+O`Wlo3ZDXbA(4ds)n^s1^c=LV%uk)L4wp7r0S z-a%GY@rx#j-I#6q-ob;1z6O7t!CvwhvkP5@*=jo{3@lv>7}7rqb&FV=Be)XfyXadH zZ!vP8c>4;;sAeHz`8Dhj$>N?uCYH<GcL8zV55*F~fAfs2&E-$KqxzQ+RV37Fzjzo0 z#iP0pO?q6thknwC;4LAlg(R?c<T5ky7Y~&Op#Esft}N{Z{1CNdG@N-j^&}kYudJPe zE|4hHmmD-MdDSrB#dMTb7rbW@^_6@?%^*7}RVnPY{ADq!Ml7=`aA~0(zb{103gqem zSpg3<%^<;~WCz8*og;Q-%XBF{*&;H+p)>h+Bl?LnkR*WLB?N8toQpge{5>(TjpMjy z-dg9REi_bVqz+ROxa$pFZk~rKnzZ=Cldln?lvR~2+_P`aAN-iTWpEkIbjdMaQdDX4 zGxyhr*OEit`^o(fAP`+1s)x~MXxO&`xgk2TLI8Uuw)HY#X(j5tB+>HyaK|pn{X<S) zVy1YBko5%I7~5xPM6Ie>C3S@$r?jKD7xtz^{R6|ihpt#elD#K9T?lBa!1Djh7s)8- zkU@xIp8We_38WeI=8n!&GIC8I*G5i!Kn`yEH}GtQ!aIWek78tw4*W3*aVie$YZ^J< zgt$&Xk;jmaijhBhd_q3k?V+Lj>F`w&vdPlyvdHo+K+@x@O%&Vwufs-Yv*W!0`<sj! zKP}ftLCvEPFNAP?sOvV40W(MG;?JUeM~++}WgGyu5S}4Kf%wuJrp+7ru72Rai&W%} z?Z{VxvZIyA2L#zhl57e2l&PuQFCMZtF6~S<_PZ(SHXs|jqWWBL?tO6Lz8H#XKP#J$ zx<i%ym}6V2OL|Q)ZwWw6rpSM$D}H_@_ZlMi+Fxsp2ft63zn*A5hK>693K>t5|Cbst zhj#O%T?*Y({cQ~;rUo?d;9VrI5@*!E*wQz{a@I50>LmmlfHzPhhW5yo6vLO75Vr&6 z-t!RC9<g_ll!Twc+QjhqTZmVF@M<9?!b<I**LLH32<3ESYUo~Qpw9%b^Jpc!k$j~Q zUB24l*#=yZ5a4{16<-Tb^-HpA0vAjFEyeK;RNi6K2Nt4%A@`TQyKMk{Yk#$}=YD6< z?oAT1jSk-=$$xW(nNR6Bjq6O%W%*rlFpghphe|xrOiJ>q0)$!X!q9uB{YjAsQ`!na z_R)-zcA07|0Sk3TO$ZS~<eWMenPMJ1`zK;)39(oGs#pzmha{WBbIyRsZrwrJzCu|? z$!XkCw_1*y7wo21!ZrbZeu)w$o`2%4>vkw`Q=++8a?>!Ae?vl*0KgBPO1)Wa?V$A) zihbwBQ-EL})bwlyoDjMXyD=%N0f{}<joct1@&F*UB?tyOR};2#iFtMafNu(RSjIWG ziV^>yQJF-XlqE_!Y76u3Ri!9(ulhJ*nH*JB49}n=yUED*2LF{*bPYkimm&94h&Tes z<|LtLp-RVPn}#<Wx2MQ{CBZj~;Sp-;l_d95U6>K6(CYQXD+<mHBvi$e$F}8=zBkFW z#d2DZ*rT@)zX&o*#Z6BI>@R64XSVw(9hR*E;E%-!8W=Y*iOe5u*%NZ&?k(*4Cz~G( zL@OD=5yDj{$XHo<vEX=<81;}Xw<Uy4YHM&i0!HFH7VpS!p%Kl+h^IXH`ZJ2kdit-} z=%)fyr5}|pm4rBe`O`%m90==OLAR28_ufJ8{DsIPL+HhjHfhYEONX<kj#i5hS<y8P zswD8rmT%^Q&!cW@&1IADTb6tEk-y1u&-@To)XY_J-06Pr+!Xo0OR$P1j&@SV>Gb_h z?M6dWs8y28cyTu0Rm;xIXN?>LkeU;9sT0M?<5Z_#c|qM$m>*&Z*VF2d)qz($#4Uo1 z3<yN$nfm1ioiaxakaH@;h=9{=IqSh6D-vb=!>GUSoUl4I<0scbK@CpI))(KHK_l*q zQ6mib5lMZE0Kdr#n44@(efsENg8|72DZ#>i7NQ21V4q3Owq55F4`(*4-FX(tZkGVy zm^(w8tffumv~F7s7NbfCsKWr@L`TQ;DCkPFu2#c~2(m|5$Xco@-1Ka%>|KxHt($HK zv{KCEuiDC16ic|MC{cCgrf}E)QVpKIdxS-j!xOis%E+OfAqxF6r-5dpC`(@h$}}L0 z`Gs3hzprvzwH%$MNwK@*hgju7{=rDK5ahawZxWa3KZHmLu#!`Ol6FV5msJ>Mqz|q< zJ}w13WWa5mx?a=dbea(*40!vJaFZ_2m6gpQ$#3f|QuXcw*cw}Ya)or+O|;w}pyf0{ z%jhI}xI;&3UVoH_dNhg0U8vPi!06A_BSq9&0pX^e3?Go;Q|0Uy`=h(sD39PSo9=u5 zJ(vEAYV}2-Sg6#Uibi#*7{uRtMRIOsME#E^|FRf9ISCi}iDDMFhSZ+P*DRfnak*yZ z-ypQ<mvk?EGB5%LJTH1MAy##eA-#;gxpSN{PDipzQQ&rz;XS+(6TJ_E+ePV-0mbU? zqY!`jlycFf0;PhlvaUnuH+-8^C)v*=R9`QAg4fX`l(z{Hi8qGU!nc#M<ZXf-Cnr&N z2=FzM;*kp`u;ELOHWSPCQBQ&HuRV?D3|Jin2TP#ICBr@`qMf#BM<+*-q0aC|0_xY2 z`>juDJaXbhYflk`P|A}d96mo}=6=&c-dIFPNzxLabDjmU@B{Go68)@DS>@PEiv9MT zy~=AB;RSTm=i(%Z@~wf4dLz(Jk^zddJ6-ucr{P<etM2u8Fs9r3kmqh&onC;oHX&c2 zLqaVPHwf~cYv?Yj>?JSXThKQvWVoYkNmxSKifKv7^5Y>X8-&8cj#uQo!0;vks%Po? zZ-VE2YCsE2?l142lhOEMmcgPBb%d-UlURA?A|f*DX$1120n_gc*n_4=XsUfp9KLYq z4dvO=-fA>Td(LBn3V(bF@luR%o_OZ|)Qb8BaXY6i^>OoshnP-k4maKY(YE@?hr{(k z2@1C0)u4@^2kHY=eVEMY<Uubkp>QP~%a;2u8ht29+TFyEU5h$?L>&=Fl3OFyPB7#P z$cgPw(R3$@xv0MmVZX2tf2j5eR6&9i-jdx?I0sJBPa+*F7sFS0=q<>bLBEz-GUBoG zlciboo-x1YV(jf7$Z4wF-UPY#=*IW-$}T_DwzIo<M_!OjWnYoyd2#B$NvI44{9rR& zOb@u|_HyR=Ojjc6s~GwN?FA2$+hkZi5|ZZ{;itmQ+TSAnsVO%Q-8p5tm(4~Ws6$kf zV!M-qQbC0h&UT|8*EJPQti8V?+?PJw(ro{!Eg0d(R_O*1&1l3kK=!&ow%Sj&uK4qH zf^3;kW&@32;Sj-^4pU&oPU;wG?h^JW`r)MPZ#t}pWbvSV#{T?5u>WY_4fy{U=E+Y` z!({n-01>I(8~lD&pE7bfXln{*dixIj8H0^X?>rj*moBjgJVm1<7R*mX<e|q;h?(f& zl#09|^x3#$^W}!`!9b$g;E~s`N<Wij@_(-n{`ZeiMnV&=5X0)JWlRyG9gv?TqbdOT z_h`8fe&!#ja=&@-DT?gdVtDE0j^axT|2wWZuxv~vAUDP8fDqM#mi+TUR0$A&c<_%= z@#oA@r9$LOoryh2%%HfISc`J6Ks~iN8@dh8RzwKo*d5T}uldgx)8R;#+JXGU6UzIf zE}p(ig-a;OcL=Cu;pA-{+y*1<kqqgbaI{5g6>z6iQW4dRbDw<<x+}^37D|?Ol)_;H zb#JBe^WTH<Tgr;P-qzP6XhSHUn`*#hpj5~S_Q@xE7IWm5(G@~j&D(l|q;zp}5Gtx3 zrBHrYO0uGkT-*?!Q}Sp#wb+>yJ1)k0--XxF;q~<Ez-0U>*I<Q4Rz+fve;eZOPUH*f zKF2c;e-Kc3Blvl$Y`Q9PO4$3JabrD3F4-QQf*1{Xx#7>$oLfS5OZMUc`6{7i<jA)% zglw_oK?F5V`uklJbsth@y_-Ct3GukEb)Zz?j)p(p$q;p;4t13WJM#>&rF8R9t=y%r zXJ4{XZdM`OJK>kA@u}O9BdpgKL#H+vNTr-k!adAW0n)r(_LrYCPYiFGM1JDQzXH%z z8(Vv3+);u0=N8A_-#UyEI&&5Dd>cZCr(FxwERWBQ4bQk26J5{i?jM;Q<jQG$QRjTY zw}#HogH*9bVUD54;+8wCPH0%hqwXbu{SXWXpsOP$eeBu7tDK?LlsYKkqlI7f>;h{? z;t_M;`D$)min8$b4gRE$SJ^RjbM9bh_UjPqV^%Tas|hFdh60)nuB>eLQn5bNbmSNA z?bZ39caeUBogiSh!n{>xWhe7plgXhQ{^fMaj77nf+sO-rM6>_hyyINj9`mv>;@!`L ziTf#ztDkSCv;|hZF>(%mS#>84eb3+X4IH>x>1^_~o3nkv0vN9`esedu<!*H8s%ccr z)?nGo9B-YsuitoI)7_Kz^0KnZ-V1hjIfw&LXx`EHO}8uE@%s$<4dtn;qVsB<vemKb z;hRyihWTUZ^A`^GoM|-6%hLYDKg?@y#HDpGuU_;qgEw7C9%z@jXx#Seuoggl_n({Q z$<ai2TspGlUe3=WE}FnkX0&En-F@krqX0viQJK8ZQyPA4n64p+7rEeR?7_CS@3;f; z>S<>Dt7SgNXm0qJs{KQCv21>0`TFdcc_W}?u)oZ8Wr~BfQ>>3xx2hg?t4x@yj8*D5 zKfJB_&(C~>wy|1uvvJ?5)TAnKSrms0rMI}(oat<lW+;4Cn8WOeY>BN+nOk68+&Uf} z)lbyO98KAGFnw+9-+bSeoQo0cTqtltNL%4Y@hJgV|J^OF6*0c=Im$rk;8)x4t0OYa zQR`z3<r%BHZf}>p@3nWwcI9q)Tkf0IhSFu6r@lsrxBs2Tv2*uNNq8Qnh_<|n!Oz}p zAJ|+|FMQSEz~fes_{colOGTFhA1+8U;(5Ea;X_UhyIiFGRqIm@(EsI5yu?WP6;lya zw!h(A!>&(wAK$@Gd_56S8t_SO$%(==wLnXK&oW&vMy#r3SA#xR_E#p<OzEox9IO0v z6Ljas{C4Z*5qHTqamnh7ThkY2$}`?#lB<5QE4Sgj4Yqr=-<_y4_<p1&uv~jfGMyKA z#q0c3tZJTOQ=eKq?6dSt;q~FvD8Mt_SkY&GoTC&J`RlOTxun`N$s=CYkKNV%iG2j0 zz9RwS)g<O8Vq&L4`(+S~=2{RO(#}x{@KEbj4m(?URmsnd;)V}9KQ8^PUkVvc2Y!9g z#mBzwu&#?vy&!Yhd~@~_$*;t7^pelFGA=cDBJHTU*UFLa&lf<*cMsFZv}|1SRpXS% z=3y3YjR7_MA}Tx{<jj<X0HAzbxnx}(#d@mC?rWyG^iDUuI@<^t`*jNXR1ePb2gEjs zBAv$2QJ(|=({(-^>=bPV%x80dCg!G=URSBG^?0>HEIK2OQtKA7w@xqK)8g8Evi(y6 zF@8J8%QL*GwCd?*r+J|;WBs~fEjsivLF#6n9SrDHg$6Vq{>REv$A5#KEeW^_q6@N6 zwUe%fr)d45uqcCflfBz*D6*leAjM5a-<K~GZHTAQ$zeKe*9s-qs8t6`CG-tp>d>dy zeiy4}XJu$V;E{qTB?&p*GAK?lO_iRl(9&lH2w?}GMXA2$_1nk~${m&rHIAzG*$sF| z1{NX5()et}Tjlrimg-1+G{+%tP%p3mabn>1z&OCTaZGIo`3EoC>N3$RqO}Wii6OI- zOqAXuoK}Jw5=`#$kqHvfd}Rey-++eb07ewMfgH>EEm2XZFbn^t)6L=qP5uBEq$coV z*@T4DXD0{LDPEnw>1I&4cPt8jn%nE(y-;{E8jShPBYx5?$^GN^Tx}t3V0z9}Hr#H= zR{6}upzvkbVhqH#i`r+R1S;|>p1E-PWVPE1X|rQ+9TV_~jEUKBzE3e!v5lK!*E&>i zCb`SEV%U9OOqJZTb(8Cthh+?Hrt<t(zbP?#AiLM6c1NPYS`x3TiH!($WHXAT*&27~ z&&I#w;sM3`OEUU*i&1CM-Ri)Y+Z@`%d7!Fv`{+`TtNK2dLPMzk3f;v)kkdr!fC5K7 zp-OE4)Js=?@Aoc`54ZdAzkWq))HibsLWkj7A*AkWvY7g~?TJeHldcESKv3gr!(M4f z4-+p%jt-!P%<_oBKdOK@CJ)Q(UW|%CL64n&{QG?obp<~ohS>Ts8^cGP+vjbd$)29O z1_K&9ltIrUMs*Y(W<U>hrizc6tPr9hdeWvak=nOXdy}&Y1&7a+AN`b=du%C7WxoQ) zA9hL3bmM=-jWHMR{SR<nv}w#5kZ+DN>mj@Vt3}TvcG`##^v!PN%JqITZ({bND)1xQ zxx^x!mHXaO<dpe!^fn$yK5mJHHqC%#;IjgbAB@J`Y3@CTyCv9p&Ry*XuSb8CKgH#m zYL8dDt2v<+$opUYv()8#pkkSjDcH(FT_1z&q_-=3v{$B=OiNH4eS&Y3F}PN0uXot) z_TFPN7}SjP5LuKLPS?i%nd~<n@k9N)+Gu^{M`Dw`y+3EuS*vRqVj)T4mA}m>wW)?( zB>qOb>CVtpMUYd-UK7D~f7^FdX}zTQ=kax}NM{%m9SMXVtZ_Y|I9ycS#H57_A{D}x z4I9c5O#a({u^Z=x<&1p7B@pUWCJ3@FSr{dN>s&j-kj}kKkqr}cAvO*A9Ow8@-_~cE zl)uUU{E>4yC-yk})W+4ZhYvq78l_eV2zTI<b^zg7*o}%4E?Fyz-Uf4T7_ob;=9rR+ zbyg;J9A!4w&NUZ0D{S#$9L>h5t0ww3dw-ufWOa&y@UN)DmI;3z{qgD~^-vx5$5=?j z?UdF3;&$Ro)^n$g|332Kc3*nBR54mNm|H>rg}E2H|LNa9DT1fZ@O9FFqYX&@ERv=0 zJFbsF`l-u3c1#n~)EU!q;aG$B3GEM*?3<P=Pwb9FDW0dkV$A#JhCI_ruhTkN{jo+a zVyp|pvvG4s^MCT|*~Fdd@?ZW|Q;!miTw5KEytKM)s(kIz7qy4TI^c6+cWiL}7kd$# zL}ljM#XAj5Kkm2h`kOxa!=MiRtAA%BKR0SwXXN*Kv88vfu<*6>^c8K+POk4`FMGG+ zMW^;1#dqi*u*srG_P?^tKm?fsvr*U@$GPhMSlN!r&&0-o)H%z4&g{8APOa{$^~PH6 zeIUiL7?Uyqz?M|0Z39^rFtG8wl>NGn&j7@i!SP3zC648!smcWMWdaOr<TW|32O#D1 zyPwE9DB6kMQgg&Dnlu~eSs>?ZMS(X%9+G6U0KUtmXP+UfS&1BO3iA`1IbH+X>pi72 z0jPWNKU~3%U5uQB0jqm9`k7?ue|S*6QRo?i#>(rBk9O%hEgMdBu^&!n8Tzpd0hZys z6nFw`D`4$jVp%`{YcAMM$g+WfE$q4t2ePyY5VuJ-_D56Zn2dLvG`$!eI>|aR0Cg(P zPVc;g*>a)msd2gBmwT=`M{-;yAxC>$#=%B9DOCD6I;Vi2yKt-Zuvo@>Am8eU>Njz| zdo$-qm&lfe$gGg8s^$NV;4&F9yW*;?PMUj|LOn@Py$o2i5PImA;<rJ&yP=QVE3>1T zHB2Y7EGDH){J=n*GZ|nz&-d9gxb`*>lcg-@RF++{bMj)J6To%^*v34trGe1Qo8@f- zji7VR5@c@c^mw5;7%8or^)6Y49z`(ApaBSNGDpJyI9r^f%Y}0CALevIbXsk=sXCe5 zqJFV0O$ykzgo@^t-cm3>0O9PUYD5>`KQhUQD9#D?gE%H$Ne3|o^K*V@!Fspi^#9k= zdy9&;|7F&(3nHmg@1B<eQr#VeEc-amrVQ@x449)I%L0G^&E56`ESt`u-4mW901SAr z$p(;Jt68LGu>Kf0h<yGmS!Q3HiS^{}&;@%|tJlLvFwT;Uq*dZSDU&?uQj)}u8q3+n z*IYQ-B0nX4kO8eD*Kt!7@9#qYBJ2XjIA<z2y4323vFff0nVvw?>%}q+Eq2jj&Ty9G zhMte2+8s+be;KCaL1rEGX5|pr&J36>kK4!|+TA08v9b&aY<ud^)T&S01en|`xzYVO z0?&3s_HL4tB}wQ;m!6!@2^43AiSLPXdme83dLENYAwUjpP3Gi;%J`^ic%yUDiZu=R zwgp0!n=LSxg@;D1jds6~x&n^L0RhSD?vH9t#(;DHnsX4iVX9#iF$UqCtiDc%dJISz zPiDQ<h1jRU>^)e<Hjs}KK8Z;8wo=%~0!f>jmCWYe$bgZ6;am@hi9k{qX6;y#a<hTB zt;?J(hM4%t98mLE+VtOZ40bA1riRF>N*o9s_<t#sw+$y#wRgzkc~Uhjjc{Awf%*@o zAsR*m7Q2!z!tM@8pYekP`u(%@<#L8!^&zf)wCerb0hw>N$`_ZBWd!iCAl7ahh;@)J z&<u7A1{;fCeT*Katod=5o+}s)Cx-{wErDmZEXW--u=zzP$~xE?#<oqC0=Uo=2HQOq zda6R<tcC-@D0mWK35Z!|CS{UR1Aw^TgK^qLW)=WlC$BjmWKuSHJlMK2@Ad6}?4Mq= zQDi~(4^}Fgf1^oX1Oqk(h-lKA+%b+-VZjw|q)jc$VJYjQF57k~@I)rp)+3l~53wfs zes}~kPG#A64CgNSI1c!@HFKSoq#Wb=9RY?L0O$i?lSxRB5aKb=o@pMOWlzz5&T(6k zNwSgo0RdvBa{N^x31d0qpbNPkO5xm=M@y84XlbeK)o;?Q4%mSGNr6Mh5KkC6A)Q4L zV^Hfq+F@gmC4y4NeK(V4mi<;IxHc1Z;?t`f$yuQ635(JEC2(5Azj>kmVxVBh&=*eJ z(Hw>^$%CDq$#s#G664q;7-Y99J8-Gyo9^o@t#>!0AOWE{R3ZG}m`s`=`y@dlf=5nM zmCo;EFNPL)UC5hG)4qam%e0Z+<8g7BZj={y>+mgzzXu|17#df|9i1pm8s<=_QYJj` z)Z&{Hmtgi{)^6B7V?VI_9d2WfCpsqVMh}cUkY(!uxn3G%yu>2Y-#U3fz%J~uwJgIp z$X<hN#w{5F@xbKT?Kh#)#ue~nv`j$UnD$i8Av(mv!#KARwnuo=@M-pgRDpHW-Miv^ z|J2((ukDPz3xr!SZfA;F`-^j)*TBv+L%j^HQ^;U5;W(lY=6Hkq0vaa%k2?Z|I2CeJ z-g{d5f#*s`7g|S~<k;!Yv#dQJ6cXFGSZoZ-zQpXAyfKOU5t03noF<0E_^Sj_a^fX> zLN*+iU+^Jn>nByeH9_f5Lh(2gyT?>DfdN(ciwsHCE;)&a_PCNk&MqsIxx<th(5bLe zu5f<`*)}g_2|#N9d-J@IyUq9YueDdUOHxy-FtS0vQ(Ra<Gt1b6-F#>0xYCTV>eC$Z zqzj!j5dqFHa<=x%3RHcV9x9V9pxXYu{sHznX(lJ7f>IJm1U%$JJ){HIIf1<FS#{aI zjT@*fXKYbDI}CmQvW8!{fE_I4Bnmmc%~;a&qQ67g2kDTcUD?`iI2lW>XZ+qAju_0a zk(LzW%>-bl`SF7J@!g$%4Tdj16b$8&URX_f+BS4Yv~}AFz$Wu<c>vqV4{XgHbzEnS zLs_JOf1TnWCNPL|@!a0^nv|s%wtr($U*ytBGUt{c0b;1)j)%PgWk)A-9LA*Y_HJvf z&kh)u4w+Y3<KYu3r2SQIL^JxL>Cgl7BPXUf?jAm2$wryY9N$nM-(Almgk1rhMTgV# zUrK1;#fQ$vMV|k_IyxFS@|ZjPeA)_NOJ1?MQMcwouG0Y6BsG=`W0L`haq*GsTWeXC zWVWq<sTEO~5=x=V$1}hs=K%Qta<n(K<npebQ2Nc2s@bV%ju!)Za58&`PG0@1vL;mx zll0>245-JvR>b^{qF#1KVzo7k_V0*v7?l-8?KAa~c87C9RH5Ef&Oud(8C}YwGX_~0 zS-2EZba(pd;-P$!@5vr8nKaybY|(DOQ~5p1BjNoV((83$1mtY&+uFG?D1+RbWfKRn z6_4(Py*~ak;;~ZvYlm7tC=d`Ty;qPE8YexYDiht}&81&OK-9u`9Cw?;Pc<L&c{2N& zIZ+H~+&DXU9eQ6BpMdt^y)(~m<Cxos4Ll{PIuL-CQnz6lFJ)P5sj}(sxf>kV4t<F1 z<DneF+X4f&(x*?k0K~kN`=++vEp_f%Cd|YDLP1M(l90(`5N9FSM37~<#5o76{TPuT zy{)#20!^VpCJ8w@Kcr6xjD5yrxYx7$)zoQ%Tfr3^uTF>?VL4rwb298(07E8R;N8H$ zMs5Um)t1Ukwff)XMo{xqB`h~prn?wyjQ;MRcjC%_uU_b}jXhX)V{RqX?_4@q{pun& zb#C<eu}x{V3yfvh8AO4x-RNM_(s#0ifgzCcle6I+r(4RXNT9>hIt0&7b~r%>A)&<) zIEN)nYlf|KUCxf{GV#KC+i8xmh~q#gZ86nx+)77AP@!ik60am{2t(1DFLU<8m<C)a zm0~vG^TaP`?#AoBj~4sRug9$Ux(AfQ$N+0^6YOmY*gX5lpR-^flx6%f)|v#N46InH zf_DnD)fC=Y;(tcKE$M!062|SpW(mOu4yZzkSki-)nu!FA@q%9av~<EDCD+QAu2@7w zv1@?`^3mOk<$8`Wma1M<rWr#@TfjD4^7%&|?x@91<b0<*hb7prMV#j<{9zgLSf5Jw zS;N4G+uoMFc>Ch+qIDeG_{yB+dRD?u|Hzx`no}0QK*Nh)Ie`pF3L%>ci*`yjad1>V z&VVNP%@$0c69wiw)4dzT(y@Yf(pxPsduH@vYDivc$m%C>gQTqD$KE*)UdDZ|{lwkS z`pzYUHDwIt8Z6j{?#uWb^RZ!H0l}-{Y}o$8Z@KF$M*sVM>`ltfu{pt=)LY*#V5f(@ zJPytRjFW=vU{7mp5YW<o-u`X<5Q)3v>G_(`)-#h&PTniephG<wUk!$2!U<rDF|a*# z&a;@M8_F@Ev$WmQK0N~K-t=7ikU@1=-~w!`u@f_kr*pY1JCg9a<I}NAYfbOLoE+GV zHK_<0z<KQL9vF+XzHsH|+^z4Kr4=*hxX``L?ap*j=kA<$wldeMVIIXr53#b-Z^lR> zCFjcQk5#2V2eS{QLQ;=}_isJV@t(|5zRGG#0B`Gr>|(H7{8*H@6zzS!Onl1A&pspN zu#>aX8;<*cfvoHOVGIMv{7XC_4boj%fszT7EOf|V)Bu5JcvOG?{#)NZ?mj2un1$S) zq&rxmzqii2B}wmTnem~ng6${ueJ=d(+c>zm1?L!4ZgE57u$<=h_~{2~ts#XP3@_lW z|2zGZYDzp1p76BHM`K??*d5F2oZOHn(b`S?=dsuRwO|c6JaNr7e5bb!kRArnn^0IF zUc$QS7%Z%|Jst37Pq+*Nw>w-OBxG%Cm>s%^dJCGoD#w!)Y>OtqJl}FBeYKcfLEOoH zm*X84W);nT^^W_I_FERK(pGik;N!mz95y-pe7dhlXK!1^t{-#eTbF+Hym)22r(uX< zE93dmztIy!e^`oQ1h4q>Wlz3El5hR|3SvBW--8XiFj%s1GCF?K<NhzR1XGWw(_+3m zHlY(l#utYtO6x$sNC1s`Y9Uj&h}lm8vDL0W`(k)ZwmUARndrBtfWdduhN|_15%&X9 zLgy^Vh=*$Yq%?yV&tSr|j|MHvy8lI5*PL|Mu52jrG8=E$vz1zc04}ee9NIp=2+r64 z%(g)3Z3G2hrfk5Rb1C1|8eXS$a{Ijx5buv84D<#s$>~ST^RYlOQc4&lbKieRIoi)@ zjFx94jj5B~dfzUCO<q?Rk16#@L*p2!Q_yH!nQkTi;3UznK-;t=8(TOF!Vox1HWw)J zj}0zR3Okpf+S#gIkR6)JdulHJBc;(Q=$1-<rTZtkB;US0bp&NnHQHSm@G*DB(`=Oc zYt$<Gi`nJ$@H<V<?0A9_l)26z>zR(e*2R~42hb&0CaXczOJM1`Rp^%J@?iwdLVI&v zo?1hWdQnVSNp$+6shU>uEYn@{GRGiMvqh@dRZBnb_7@xtpoV#H82&TYEw3qLU*DYt zf@w<!FT-!TVGi7SZaq_TYmbJ}%%DxvYWGXyrlpI6=BwThm4FA6W~kt~3)ZNe4**_) z6@KeZd7(q8=8rkb|3D19QR4s@>oFcZ;(8@*dA~_i$^_{2L>kOfS~s3hHSaF<9h8k_ zbNd97Sw)brkH9)n9Z)<eJJKV)@IG;%rTr9|lG~tJUBDcL^=aIAf67nsK62sui>CU^ z557FF1PgV$YNX_LeXSYE-Tsj9zVMrLyOU?|UXY-G!t0Dghkk$DgfNJCU+$fG<c&7` zoJ{Yhk9zTr85OupKalhj!otx#60Na+C<pJ;ypMC{%kWaprK_c`(F!bs5sfS9!;yO$ zrxalMcsLu8YXd8UDC8L0^bj5_Tp%9&Sv|Slt#iGa0NoiUDp5M3CE2Xn-LPDAP_V^R z{1fVC{Uoqx8YEQ1pUI|>{1F#YUGen<#F&FwVe~+bO3cap@M*I`ZyQ>Ia$UEISdi0g z5Wkn*48eTU6BHZ7rbh#eI76`GMP1`_XJFwy4-D!|=9rN(YL`4P7o>qWW8GYUrD3s; ztZ|<flMOhlqKRC5Ax)?2J^}xG-n~{XM{8@6vs0aTo-To|u8wsX{PgcSPLIM%GN|v! z735)YH)nCzz`l+PC~rddQQFai4)N`|3-^1CUWt2EMvJ#e4TCVz>+d{Pc{yP>oD^nG zI;-v|HDFrG0ucavx;3>|yhucx9n<b6>6i5UqR5>k$*H-&vEB+kuf28DPB~vnR7_?N znKEz|L4T#*8a<eNE_|EqyIkE<6*G7Tf4AKNVqtoylTw3NW~7r+bfhy&WBft1{vmGT zP2`EvSa>z1kyzxl8ku8XfG|&<;y6rlBwqk7*b#b9iLRSmjvqu50KuF9?c)W^nh)QE zP$!o;^AN*{=%vY=-3%t0aP1>SzfUmCU{(=L7w`d49k+s3v@XI$8yAT#?WM&aTe@yY zycZ^+OdY_l$@bxw*Eb)qwH5_AjssWEpR8e>YU1MTzqBi*MMoZ(ZJ#9pjNEB03ytSv zeWpD#cEytRWf@rynC&XKFHv<aSCvPNkhr$9gSyB4wz~Cu80?*608GON@9_nyw&TG| zv(m7NI3bYj+^{1+4<2Rd-m&BAwJAC6Kpl;}ZuNto;zDTi7bs{Nv=W|kovLM=n2%so z7q8*NCwuH0{N>Z=k@&UsJ-6qEWfJC{Q^!1sfZMXux~fSwui16KY8pCrHcIia&AuHo zEBM9d*AHee7Ce1ADk#rrFz0599HgiD$9w+X_|R}o)mZOJZPnY-gNHorM&Bxe03;YP z_-O+D!U@)8@!=R7JH4(zVSx5MmK!N9I6AG!QohWR&>$BFQ9g!XEwg7m|3}w(M<w~c zasLJZnF8*KIC5vWN1CAK*3h)9%-o~QT&0;6;NG}LRya~qGc+?REkJXW6{VG#m8&wf zzGPNr77xGkob&wm{0p3OpZnaL&*yVr*ZX?Cj5p%*+!TitzSA-d`@xsnqeB$~mv@`j zW>;p`N@^zP#+VEJK|8=uc}&1mOqlm`ogHL4%z+FB#&22louucTO1T`RuQlNiwv3Y# z)3|V}y3Ga`!U;`d$81$PJ;FB;<qe6S(D1CCE5mJ_l0))&bH!Z^me2COYLu9R^WE9$ z%AZFwwSS5#g1#D3q8haBl2O5z=C~2xN5jtj4V6^Go_fos42je7a=<DBEtX~AJa<Lz zP-hq}YWDg$EMATAIUE~E7Bd=&nXPeiYqmQa*D%vRZQ1j(NyXh!g-4nzW=9m3&E43` zWs0}xkx-{oYF0*nV-w-Y&z1u%o=kyg=c2%hTb9nYF5bmaXejUvm#MkLEsS)@RMazt z`*r>l;y=6|sV|?ZFa6Gi8{<M6e;geosApGO^YuyfA}X5!MSfTw7JJrp#u=7enu~8h z<vwy~(`vN*^E*>LNutKb=w@w6N?F|neWEDP{Jj`ZA1Wk$Iw72kJ*8p$c@Wt|yuuAh zSQoW9X0y%EJZwB0B+ahQw%m0slu@=x+&{5f`{5tFaxEi9?X#>tu}Dt0g^r7NA9vI0 zF}kQ_FA>)lJ%cVw@Z9FHZQo3~${n`2oghh5!YenL`u#u&q(NOQ2L3@+GRuqxDM~;) z*lm5oUP<4z?r|r3-;QtaGwTj=HKP8?u$pw7i@oYi&d|&Du7cA6;bmV$M>7*{rIPR^ zZXnZ43DC=fMQ>ik&?X2TTIDRiy84B9(tBdF4czEb)3`Y_onn9JD${_ljY&sq{IlpL z^>eSz#tzB(!b-^*!Al>v>@_Xb_dQ#%6OR2J`6TSZ+H)Az<zm_e4z>Wt3?Nr7fvw?U z`c$xifVV59YL|}KS`G@}*q@!m0h+G`GL=8#Ku1_~8qwP`W5#6+^v={xE(%HLujBOv z4MHx;35p+-J8l?VQf!60c9ba5-W<Q?l0&~xl)+WasivgScgSD-XA~^;98xkW1qc|n z0(*nibc(;2T>%)F6f>Q4FeeUf<1@A;DVmw4@7GB;Hia6NKfs*E2z6FRjFuSKYm!oN zAVoess?|4MemKl;-v~Zyz;wJj{Jl|h79pb~%)?_|#c`oyNa5`P7flzJnaW$3;HRHQ zojbVl@)sd0x!TsjI*bb2t#s3w>H$xCTmN*6ltC*GF)iANvA=_DQo4;lSgDVpPZ~70 zEF{HX3;|UWxJK%6o^sZ6y@B1@QS|8oSlF|-@dhvzWqX|fI-%+HJSoIYIk5WhIH9k` zg0Wx`f+n_7WQi|aJMfAivN=d4#+UHnS>B(sjv6$sqVk-kDSez@kVtFL*=*c-JcG0- zA`*gi1z_tG2UABeTQb;UHqZ>R$9B<vhqA+tYVhqzhETf@Y`Bze9wUm}RN095oyvno zIrh`Xc{?T<8fnU*zOUn_BzGKV82a&)`nbHljFw4?EJyl5SYuP1o0a;D@h^pn5Z=-1 z_Y`S+`KYM^(+ncyqNOfwN67_B2c0-RZg=#<zAT7#PP*0*Pj_|Dk~U}-=4!wnbWR#H z?ql4KPq*0uzn+uZp2OHa&eO`_xq@jLeDJnv-i|4TjYs;fxT(<Sr|#+_AvxvB<rIQ4 z!&8kQ!=0sUJPtkh@K>fIVMbb>WKY0-aGv6NcQ=}!=7z*wDCl^m8qh#wPT)6R>azz4 zDr376!jJnf{VV1*x6<`V_7*dTNUP~2j=j*1E`Em7;A@j^=__Wt3I>+MwsRbk+&<}z z+uNk%n_E6LoXy=ncQC=GF?f+8>kF1TU@t%85~kwcf@8=n<~|5|zp(DByunS&;<m9I z)s&0Q{+@lp4gHgup+@uYQ|Bp}(x0hZJg(mQPn4aBaWshI*@c0%Tg6Nr2hC^>TH|7l zgbb1k&!&H5g8JAdEXs^5X(rDK0@G|rgJ+|}L<1!F7nEdUXO&foY79kL(_SA3I^V@n z&Un`KOgd_o^5X&h0c~`MsQYt{s|0yVh%0a%mvxoSkPDb^-=b_C4&l4XsAq7ui^_Xi zQPp~HJvncTw;WV+MB;5R>pq^)ut3al-=GauO!U&%OPh9%+HH>3GN?QJ&C|hvMF|<l zglI)H#&MPVxpE!$7&M(CphPMwMP%iuHgQR6myFcjM5YyO*?j(&G448AY$3z6Jk7lo zP5|Hjs5p5!CNH{OOC?s)L1SysGzO&0CfIQp14a)hE*B?)9+|{B<RnO5y=|{egQP~= zA5lg$;K1@pAWcoUCL54Oa}hT7gg#1BL}++go+3_a&>*DQT)iiplIx;We#voB&GGWs z=w35M-``Jig35Mzp7ad(df(A|op0hym(q*Csx<J6$LU&4S9~0Ov_!O7K-rfD*&hZK zKLtKjB$@h_q6k3?Be!K|tWpN*d<p$@(N*y|F|PPas9H$$)tOJL(#?#F2!>mEYTLh@ zAyuY_vQ0*7YFR-Odhsl`GK;HCYPFrYd{6Rt!|OrYD6r)a!*B~?#ZT8_<AA6oQx31w zsnC$qK=FV4f(<_Xns3DZB(>d{V@a8zuMpQM)4dGk0In8<r!)mpD>%S7c_jKIcfqe9 zJY(gP<CN7qZ8^)mt~4~rD1)*{$;ov*);X^7?IB<G%Yvj_hdH>v#KE9|XE(&?)XOvr z6BDTmQFDP;kC$rpXHqo9OqRs7;<)$<V&V))Esmn7%$x0~aoq+sYv$gUuKrV9M;SUU zHyJ5x=`W@Tj#r=60%{<X{$pEy@1ATAuK+LEr)8-1(W{!37DN71-OZ01njqELAAX%q zqVWvFz@qUf3%-L%0K+l>gEE35KVRDAV*jezF!cvrar~{xOGtyi3;f(lxa9Q)J+Pz! zgV@JSn=VJe2oK}wo|(_w0>)M3|NEvml#knXtdBx4eX;ZT=-qpC-_JRjepmeHbZt`9 z&j$AX-PAa;s{spaF(qagr?_LW$nGM;kOW0ljF`4E19io!`Ob$t#7x4(R0X;JWJgT2 zV5_^F`p&5i_EU)E4CN^9wwb4C_hzbZbI}BbDyKy->`Q2(tH5R4IHT52R#j6bgqQsU zcL<I#bT-9<;u4Ut?}|tRUFKgRqdf!$1nJf@>6$j+=GX6%-um~tsJR?XR|IqF>h|wq zGD70D-5+E~3MC1?ZK_k0zAQ-J9WD_ER_1V(R_RL8Q_}_>O=$bsh79##c>UL>3dLHB zV@`AGj>>VWE|!itt`)>I(9R|)0xA)@n@O3009#_+Q4A6QSP8^53wS2}=>mc1B$jUC zpXt{p`uw$XPd&v_c?deb<AAaUsr`neeN);u7c@`4fNM}k!4N?r)p~gBWjPY~K~AXU znu*B+idqs^r5X;s?~<<>?y713WY>@!XSltmeU4D?cNP?fNfhor#P`gR**ODl`Ic_- z3A}Bco?AMyZStywYQ`?sShY=pYJcHWZ^pJkOkn~y6dm&RQil@6UI7ilOp?8Fvs9+I zqH9FI@b$cyk!>R|^(FxwNI7LwcTL{huo1AK4I21}IFz)nQ9_9MVm&ixNVYc<h*^`x zbX+j{<LR<Kg?>x&T2xQy!5f%NPxFAuki}g0#vv(Prym2pRd{t*W~HY+2+s%bQF#QQ zNOg%jn(JbBCiLl#@1<a#SKu4hYG3NLg}wLR?|uDJwddLS=|#90&GzWY=<84T(_-37 z6uSZkI}xC9GTqRIVZ#LLj;EUk<?q5ty6sqVO_UVscNmWP!H1iN;@n*t{TpAuq&MXa zbs3>0>wuejbdCON1Xj(huXL$FY~tRGXrmuK$p;wdjEM7&-x-cFoYnSG4N$lY>B7%5 zD+T_?A(~-4JEnsP6Krjhsnut%y6RvOv)@2oKaJE)>1a&^!-<Q~z$40UA7Ipc+f2i= zRQj;!N@GPfNYRp^9>5KqrK|LJs-(o1YUxJk&D;Ii{o7m6#)O-f+=_`)`fz&hRmrcS z|EZ>AEuHtP=nYyZldH98&)0Ofg^1Y^)8zvg_g~0N_{^%O=h9Uny8Y7W?GT~*DY-Z< z&2wDyj-%yAkOqz?Gs;zx4%Q%lXsh-W)?Rm;PjV{R=VYN?G+r`v`(w9TT%5xay#HV1 zR_>5~nr^Y!=Jky}{&1N!4s5obUM^yJ;?k`}nDc7hODl|yhnT-*i<{hKFB&%lc;l9) z9j10_fXO8QJS`=4cjimEMT+5Jkg_HSrvp;-07>yvubEI}W4a!Bm)v+u-%7J^)3ldQ zp@g>_D?l*{3o?jlf_ZiOagt6uEVajC%!!mPOTH)qPMhMyfJKI`h;Ez&HkeF5bi%=8 zOOULPV$uWp_dLVx3*BtEv-b9B&+3@p()K#0dO#fwT~0<6(C+{Fb6<}BPAfVi{(XKn zL>>~@QU|G8=^pX=Pjd(@6#f;fcKh={f5b>B!-_5D^FquljAu0-Vo`n~uKA(}|Gv2y zvOS5hi@o1`oEt^_Rz>lCrwkkPU50!0dg{x2;3R5xfB{F4^duS8L&FdUFr&cpTVzBS zSG6yw&t56C>DDm?N7<P=S9bUDv7Etd$mnby(UdMRO2*1_rGZyJLbj&m#AAPoX)<}% zK|8H*>4mo$7Af^4KKS<RNH3dlVbWQt2}B^jbRUWO(@K{cmsA-VongFu*a?X)kyQ%= zjea$?eb2$mQ?4m-@lzZ)i9(dtEmbd4A^Ar<?e^((JDRfh((PUO(!8)JuP4*ppov{` zZr6)QAYlEE5WaB_4Sca?{}ot_*wMs*As#2s#xiEmON0WZrIVuUcT7o~J`9#XG?G$4 zD$K-pDfd}=!*}1)%ROt3`XLveI`VZZrKohN9ss3Dk=!6ZUjd}jc1bOAt1pV!2aH-V z2$4=(lQy-)QRT>)ICJTZPo9;I^nZ}<6eA{U2LL%K9Ts0$PYT8<9MovcC?eS2+ghT2 zcyA4uM8E7gEfwi?ap&ou>%XO<sPzuHvSz8$(LPsfg=g(Q>g_d;e)h9ues|fsE79MR z3cF86NZ*K=Sbyx@`02?->tnCGujKxGa>+Jz2_R2Ac*L?#0aj~rv;TWuduD5C3=9;r z9CL*U1yn}n0|Y`c#<a_bk;}3#K%O)#hoc*va-DVr+9;YuKQCNujh-CkAA5b{h&b5f z^G&t4cQI<I6G|y#?@rwFsO^b}kou4lp&0yWPjk@ciL3i>ol`k;>WjncuDh@P^D#Fs ze~Eu1r@wdLC?6<bm=!DDI$i9ME4e#gTFxxt_xD$OTkhK~vl}Hye4<!^;UuwX2e2ww zu)aN?vw(wwat8}-SNrNSh}AhA>G*@Alq`Hg5O}v%9km33-J6CVmM_#{<jWsV>q2NH z%y>I%#Eh39G|EjHpg?S2eRhqLWr)g|-ZPR9b*|KvKGZwg{Yf<h;AiI@e)2h@&imtM zVY4ET!p$HAXNa@|VQVGX6&`&=hXTWCfRk_Y#wC3ZX>A>hG3q00T(^}N(~#J?@kj!@ zQ(~?me_#y&93=L{P#Ac}^7>547(OURnZ{SkCdSD7O)C2yu6VI8kv*5S&$Z&kq!NQq z5hujGHG}U><lKA}7(W2YQBNHO0eiyxxJ*4jlqS=^a<Ovy=(Pb^;MDlH5vlzf6o<=+ ze6`H-nmc${+40F2*;U@_(OHVAo2*cr*_~1K{4)bU`g?=^QT0N~x_kzXyy26C<@5}a zuxCINbeF|EyBy)Q^M?R74mquZrFU-_;2!|hQ4Mt>ra(Sf@mtP^%E(lq7=CJ>d06ul z?wdWc6kr{&aGallmzW)l;^t@+_%FbLT7W~)?mDZu+<N6wYRk!gH5p2QhPSU=j^1qj zR1^7ROjF@#Yt4vEa)mc+53n{hsFuAo`v|*pm25!DypgYgwXGxS6j^N1-e4sTcWex4 z7>0&mGQI&rfq;Z=*xEzXGXxVUx2%ib!Hd$w0ruFxYmWw6qmzo>P1R_qI6_#^a<^(t zt+wO$ResIfT9E+G|C<X__B5qHRXjuL#erj|xZ#%~CRM@}j{__%3_$Gp6MF%;p~1cn zOdMkWclXz>dQ-!?q~@Y@9SY1Romu}^+4}fA)(%im#_bUF2?KP@I4+A=o8JzfW`H}z z%1jNt8(?AV8nhH3Mp?^G^JCetQ>Krj?@Y|XtfnXzlUjBPiOyOHb4ZUk1|e!5X4@T) zI2z-iv=)+OUfYF+QgXCY#g1fb*_R<y)KN!CQ%&!(<jKDEPz@cfWQ{)qKSRcx<_tCg zb6Ey99y(Pw9F|hSIi{xSbn$T)Cq+;eFh7JDy*j4Yj6(!%%&Yzr%qoBOAHj4ls6Ha^ zHpno-ij08@Z~dKY$=v+YF`<N;v<K!>FU3i?kXXCdYA1&*r0x%aaLiKacN^w?Hoj`` zF7*<0f~d8WF?TM9rwQ<=IVS%!vGhK5v6GU*9EZA2T!^%z`~m=w-Z^Smc7gR$Bb`GD zQZ+B`jMxG}5~qe3(si@hBqz1pL<2Ek4B*&gQHl=+g%Egraf5yU{<ZL_Tg7U=iaZx; zsLYcX=+PW1@Ml_da2;^ELvOZ-5A+xm;(^s|+m9U(HyaPDGP4R&_8PIyw0@*DetP$p z(gWW4fzmslipb$ET)5|Yx+;@4v};MNNMM<+^g3?0d9PJo@kObNzCP7Q1T@!V0uS51 zw<TZ;P~!mVaIcMYB|t+?_anCe^21eq5(fj;Ah=wXuQSimiDJsb_-$PAL>oct;Of@$ zGAsULZsq5<G%{L)hHS{2IqpJ1gEBh~YFi5e+(Zz-@5J4*68P-@{9Mx#YQ{3AZ$q8> zL8KFVR|!QA{W(F#t><&n1HMMyZwAxo{xiAc9vwemYp%jPR}YwBQft#3lbZfwNKg>0 zR(Bn>I=b&b^r1s<o;O9my**+V1VV)TuO4Ly)%{pv=y<e2c2hoIahWF1RsV3?uH=!2 z>dGsRgt>ER?o*!oBFk(Rzn|FxLC9t(zgqYZ>LO@+l#zJWwReu;0CmB0hN?VK8-{si zeXJ+;%@JYV57la&3{e0wH<ihdEMHnM&k%6|;OUA%d@+$EY+y-p_eF}gJYj~JO$nR3 z*siZ`kRAkanoJVfSNo<bZtM@NgZL6zp!Dcu9<GI#T=h+5@Yt~s_&h0FD`$hJeW#2o zBq)p#AZj~BD94h2VlqvFY#YOG@U!EMeIcSo*K}Nc<9d=-P%l9u@%dh(U+XPLXYCb{ z+*`Wy^>?jZr<CqJ%24w%lE@U;tH^_-4Gfzqr041s-wEDLWEo;H1Gz3AAC<WJ&PfU5 zB1&}+M`JGC-1(31V7OX>2o|KPUSLCXpMYpy;|{8gDUmAXHm;XjZ<Jd1=kla0><od~ zv?AN(3&{iimSQi4_LjS=ahR~H-Eumat?7<w#$>nC`|2B{9F^NR3lo*zxa)7P5Qq8L z^YX8s&k1EMCi6O?gMC9qvD*<Fe^9>nY>4#q=&<1?K-~X}sU`RFS3}&|4B)*Fdw2<~ z*5rTKbq(6;HT5WiD4ylu;-y1dx}n4xD6?C9$~RFstkI7XKdw4`)5hHKNws-dbD`1) z-IhwLe@4aTB8Nx|+1b|82pd=(g3qrLSLBfnr!AZzk?*s&ov}>%GDnX?gnZA*1Xo)C zFP@x98JrkkWjWe-T)pu4$jf-1ubHNAm9kaMn}oH63n})89{B#AeofeR%D+(lEK3~m zt0doJb%9gFh8h@qdsY84(^eSH-GJ}dwfpxR?&w#>U#&&k22C4WqQ+05Y(fs-{^Xj> zbt9qtS`fVbTp%vD*WA+)Y*KQ5PF61F&+>si7jL{AI@;L>(KPKUJ{uMyH+nb2usI%K zi0kw=`H_4t-!L*w!!}r_x068Jo$bJXJ?r`3rHg*!ziCd&xC2WjUN6rK+iBJgTeuF% z^^+1Vgx#ICmCb-Y=9<RcBK-Td!wr7=8Nz6&L3K${+;-Hj_;^w<iW6k_wM7uJJS%|x zULC<s0@TS_99%uPx=4pV0>_EvbbQ?$Kc>}yM8_8Vd3j8$dO7hFxZqyU`txi}$-IaT zqGZVY-$l_>FI)TGW7kt$nO?H$rkYfd2>2Q-pO%Y&%^BVyqOG$?rWpc3mX_940Z!;d zTqUAM0ZfJtcF6+))nKjD@BypZ#-Boy8vg8RPZY(s$vZU6wNQbf&+>4i5nw!z_+yn) z6vmWTiPK(Wt143Dh#<vbH7TaHYykJ;R7b3226cud0cmL2;>G@ZyaU{XKjTK6A!639 zU{}e+wV*gOPPc%CXS6=;`})9~+BTDqIu<ej=1TO>R`E_$Db`=zB~gFy(X>a1WSIMx zRjORFQAR9C+FuQ^9;{$PCv=A>F4rgi17eX}%q9!P2QU)ptzTPkuxz_=w9=QB>-!8) z;44$`24o`gETl0MpdtEcC`s;G7DH|LSYj;r^-K4*cf>7eH(Z;Lh4YI0%Of`23u*`p zkx2F?uJBa_O9~=Do*_LTWlniR;$vrPl>qoQqlJDBphszF!3WYZ2P4|WY$P=!)zN$- z>QBcUtu@7K@w$>Lck@`N-v9cy3h<g}EjwHfcuw@og`}~zc_M~>b$vQ6@?MY%IDuGP zDp9|n+C-NtaFz<}6hBQT5S=T0ItJnM!5iDqlVs#;GI|OyxL=C76NKXdXvuG%`(t(z z-RH9ApCY*u9^X{vjAXbp!fBrZw%!wIJzP)TdWOMs9#U7_1a=^nV9Y(N43gedlXa>m zgn(EZ$9=RMwN1K0arRQGPQ=;aAe_6@9|W*ZsQtjlKzB$yA%>;p_)Y7dL0K>ShK-oa z-T&shi8w9r4lA(flVS}=9tKB&-hQlFP)f>{`p4IECxK*FL6{AeswqfTL}H_kooO09 zuJ|<DNowZ}DQ{6eOw;k{9h%k}%ft(>ZI~@K0MN)xEuP>8L=AH<RvW@Szixyl>WyX< z+|Su-w}36);37zLRRTx^9F-Xc$+Fuo7v$|g#wvGxfUAlR9Zj$~&rqvwLn*3ZncK}5 zyeoa&Ep}_;qoi~OITF)Ui{T)Zlt{b%Nk4i%s4mly)%64tT}IkO<tM<plW(nHdK4Hu z*H3$Fy2os<)Qzp6%3UjK%$`5Hgx?a!1sc8)n#P?PTaxu!YA7m~pjEj0mhXor505U> z(J5-O{%WdIEU6AP^rmi?y#8<5N1m_OJr|_CKKXjBNPC?>Ds%1YH<3zSG59gZ#Wt}) zy(3DSvS+oMMM%~{rzRHS=HB#4`@DLxyPkqxqf2E4iv|>Bi1h0l4(gv^g4PdbAnKGQ z&JEN5%yx!K$8X2KOANikoPyIM>ej=4KA7(Htn}zP5UXaV@nZkT<D*}>R<29Z)^l>B zM2rL|R-OOilH*H*&+#+lS<SCz`RZ+xv#3`lRPQc7)Tp`$dWft?QEzI@01-!>Msf6p za}|fTd*1p-K@9=YvDX!{gj_^_kRl>|N3Gw^e{R8-B+%;`czN)R7;v_4*^S|RL$f4X zv0!W;*`&>_z<1d2i2LHZS^CikOdHwq&5O{o4!be3BzcZtNRc<?BEGVw3?;lXu2Fi@ zJ(V=OkZQAmYs)$<LEa~|d{3Gw@aF8b3E_!a<YQ_ajs!X<pW1>~w^voFM?|6V%|Q)b zUqjn}jw07ObU=u&<iMqR+$0VE@57Cz(d$gF-)*6$x>u?o4HA7s)H)HbXd0RPQd>4; z1zu_BZPeB<>EIn1^$o8B#f_#mBKcm89kTJlM>{vvWTybBHHt?cZ5}pv<g3U%tlhsE zs=fGA>mLSmUbq|#=`=hTBc}G`MtL4<wG#C++s15NOMx2c>>M8RW2^F~c5;N|J&t$2 zar~KE_iI0PtkbcE^|GdF3e~d_AeMxHaT`6KXl0bW<(FpN94gPoEX|q_JCi=kPAis2 ziZc?bXU`jatsv`Tt7&+Fv4&*>eq0hyl`%DViCg0!=Uqr=<<5^R|LD+??VLpt>SaUd z2t`o7JXhj5utQcxAJr*H3Q0r$XZ$VbK_3SNpG(lnj{GgXg074`ras)g2dk*&DtC(3 z&*Gm_59?=X;q`QqCvY8PcL|I0ky8z|5j8Ozs^=&O>3T_Ou;lY^Si=@`5DkY*IkGE( z*d}B*=eaE>Ablq)yNvO;xJlF<B4(L`HI`3|Wh6c>yV|J}o8Exy=16!6dOGtE*4IyQ zY2L{&d>e2fkeT(VuYs&1r(D0QsQzlFA?~Mc&S72bW{||%m1Pd=a_cYS1(@=8010Jk zs?A|GQ(P>PBM%jb)y(4V$)F#}nLg)JAGl}+tZbpVqNf_seO$7d1>IX-bm(<MAQtfH zQLO`jRJt@wO#;k)VB^px03<)MFw<m>UztbpURVFgL`~DMqbw{uBxtb09??dzYR5e% z4lv8pviIR;SgtSjCr!V?q{O`WD2M*%qs|(vm{4f!$y8~e?@Fc1{LG}u3Bl(2x6Ps4 z+{>NV%CgIU6fp3J^RkVX;!l;<zfOPZe)4U*c32|K+IW{37snx@aB9)XCfH`$NW)89 zT)dXA??t=XqDx}M|LXAsHCZo8gIp+aqbI2=hfW?g4N47KvC{RCdnK!m=aDG^uKC}4 zZNE3+6UJN@P^VAa)aVcLagx9ruD`KSY`Q#M-Qkp?3X+9$5&o;oINrfjMdddgsE1az za<v22*)ms-pY?Xe(MGFqc^aL1sCPk<-57i=2ggTduoSO<9?hC7lAYp+Ru-g<cAIG# zdw;D>;yk;ourjuCs&5v<+teoO<G()me$+K1vfx^>39g!DaYOi6^lYW(N3VXb?J<k0 zsn*S~q@X<LQq=$*bX0xcohzX}CPvOB;dk?qTn9$2#JxLVB>S=x_5(*Jj+dCPI*#Dh zA~Emu-yrFzVPfam31nbB@p5CRyVBhg;@2V?bmr#J2Wc`1-55cG1jFA%wKM&#<gkD3 zz<#L}8^_1}94v%h?=0`CKbaRW*v6l(;?0scUN;7aNeL0?HroFGEbdBe75R4(I>~q! z3g#XeCmLw}8J=(nc?)aZh5sXsXW%dC!6$?6ojiTW;=ryk`6O7K#y%SjH0aO*Y85?) zeORNB5rdv}(OUH9CeNIz`>bjVGFbSDeXi)z{*{Li%AUYm>*5;B=OkU|L6LfQUhAnl z-b5CZ%C3&)oOscyfu2J>zivTNtUO&eZV^>emrLm3;D>^SjT!hQ76$$x$|}?bbD`3> zdZkD4m9++Ld3I01V{x8LzWk{uu_di8J=9Om_perA)0-EdYA8pARcoHXhg5Xux_7<9 z$fLT6t_Os#6s><;SvC<dHH$)W)tCO@KXUf)i1<dmUX!?|3iI<e>1Np%S{96tjJG_C zw9nXkvP>L)wLb_;{=`qxUGFBMhpZmHSHxc$K;qQok48@Hd^_C^t$bgkQoxmDk`X)_ zLBB!cXRgF1aKzwwTAX#5O{2<Zg%_^PD)GYdBX>lc5gL9thgkZv_`A8xee)bntHw*Y zn@`whue-dlZorT3h)fHu?k_)jU1k1i^Uk_ll~M|tP1alkl8k%I|D-(HWMK`SC*~C% zSpuYXIx$d?w-YR6HO+8Ur9SEOmD^EOsdxDL>Nt7+)$t8iKP`2~nrqHa_Rt2AX!`ye z9~dN^`6|Luudjr<=v|}F5u6QmhNZ?sCjKW8L%t+hO>kQrR5RzuY7lOdwIUV~^pqbP z&-mDW(!oys*{<O!v)BhpXT!G+6-GY86-;8ZxR0(8pSKQ7*IW`@`M~IC{*c;^8M44{ zXV_jT45z(myVJk?<w7vm#g7tKz!u7|4#wZ#yV3@bU*Bqb^c{GB4@Q$j8_4A!iJu6Q za~;hTbnk57@VQZw%Taiq$)<nRn~T3(1A5A5UUeDDNO3VmqU`dy2YdB35~8a%pbc-V z-+<>(93rkL^z~fMMe+MT?w)t^`a`f^Qmw9+9e-{B6(o#|@=FSzdJp{iy`}!~xt4E5 zKFO{M7{zQ2O@Yr9M1hH51eiEVC6WT?<<)gWV0?=M?>r8gz@A+@FMKJ2V|F!;6cZit zlwG@<#>#Z|wgrrJUwKqT3Vm4TdZXF1Ml{QRx5`9&IJM?Z+_#2d_e#>ywXJCXR$W>% z9oYIkA$@eRCDYRDt=ml;OW5H7F{?djijud<g~KFA_c1wHg%YW!#W;Mj!>JM4Sm;t= zh08rs=OJ;<rGX1MQu=}8eO(J9ObvIh=)UfOi@!Gi-fh9|E!}?PrRJTo2OYI`rxmr9 z^(ypVHFvgj%1r6xlsLi%CU1+$ar|!GduuMesD+j{JC&(~-n;EbE$K*3a9DOp=##Oj z8^_*18MyoFznrt13pw%cx+vsw8YK+wQ>z<@YqKhMj@Ibfkb>$->)->n0zvaI`JhFd zqe_dJPt`%*P3SAtqspH~7*K_EsLyF%e3tg`mKewS=SEps@N7lYe6CJ&>wMm};K~}O z)%Emz4L42i45ciOkQ|}rS+p@+K0<9WOD?d<+gUktqkdQ=5N*{If1q_v1LvWmGwP$f zdmA+_<ge((KQ?6yABe?Y8J0UiT+1_>ycSwy_s@5DzAouy^rwp{ZHo<7A2)o9w&#zs zGNev+&|NgLW|HA5#p_ezYS}<3oOqhdYi&HQ69re#5yU~%#kSv+b&&XA6eJtC7_aJ( zwFu%!A5K!EY62e4@<3dIW5}icpUW%PIU&jNz}bHbdu%(#yP#45{@<Ky!?Y~;ttxMK z^A)S(K;n`!A#*uu$7ZsZDpFGBVBTkP!sS}Abno4=r#rson*NjDDc`vPYya=w*3Xp_ zZiF@0i*{QAu!~UDH)YOI_Q)1Krw?W&Ulqq_3US)`Wz;9j;7bbEg>ZsDw_ASr83^7` zcc(&J>dJ1@F@28w%G`a^S25oo{~<&aTgm@**kju&lABBJw!}k94)n#puW<W|A5l6# zS&tlPEBAI94lg&(lqn#uiMQz92f-dWg?T%xb7vCvJSEMq{(KWRf(i7p!TiLY-1YrC zQoV*mhsp-TfgJIBeT{a{h4y<7?fhC^@=(U#<M6OS4t0GvGr)2#1MjhjAJ!j&yfoRV z81E=w*ZN8C*K)_LubXbKK<u*MQwx9h*sco}Ts6x2ONM0wfa@9ZuI#m^JHzAhf9&)u zz>g`#!b@F+hPVB1oO-H&Kee(lll<S`Uuu5)SH`U{5nk7Nh3QXh`c@J>c2!Q=@3v`Z zl0@!O97%M~Zd~~CG{{!%>9~#hE`fr82G2OO$9%2+T!(|o<m;S0HfjY@${cw?-(`bY z7B-X}P5PL=cU97bCs|94MKvi!fP0J1u<Vr$;56{McWyx@LzNIl1QHl`q&5ZF<e{1k zbYk)T83!;34u~z%v1ya({xOP|J5R|B=^gx*chCN<{=a8*O}#F~EsoQk;q(W_wciR- zrqv|}T7e_%M)@$uM&(Z~&R+!r+0~^6x$wT-F_YhlX=u&Rm-WN8gdjjtXV|)+WCz81 zt%NCb9Fx5}N&}Q<WvBX}B-z^oE~#r}CF>)y3LM&b;y2VSa)x$beEtM|t%AL!p><7= zcQQ>4kc5wD`y<eV;k7Ex(EN7r0>W{_9t6r6vQ7&wdJg?w!#AC?&ib9Z#}TaL1SgAs zog0oy{eA%!AWjPWhCDJeFLRj+NKMV<pB%#12?`=-UV5W<hb&0Z5#stgb)TNwyb&?I zv&GD=YwWz@I_vM|WuqsjQM=XG>v4ZySo7kq=Nw#bkbm6jWbyD>QR;dl5p&hW+3k60 z?Rt}r=T*1;51&`wS-(Omyy_9@Hc>mh-fa2!s#o&EiA$U7Eo4j^HQQ~nLGeeci)WjT zPu0W8X6qkUsfBI6Ep9K`4*qEKf84e&_aM52l+YgZp$bdpi2)D@p!ORA4FdqcfB>ih z??GrV02hi<t;#NJ7B?L(r57;Dt{=?CX*ktsb~QZ6mp3^&Gy4Bos3}g8)eFw!7c3K( zXU1-{?8&r6E(<7B{?kU6GQGnOlOkmZkVHTS%tG#_?@Ka$`|xJ_tLuR$Os}?8usqpO z6K#hd{ao|_$~tgOmQY$i-|_FuZyzOJ_Xd1GORZ~Fvx<%3fAs#}I(^CGcK3%z)h5T@ zjo-fU=_$)0pWu0?=krAC-uA%9cW$n{VuwDu<axLE%bUK$m3NQt-umx7Cmp5g)!+AR zVYE#D$dmrt-#_si-7k9$-1)Kcf7j_hi4=>X6rt)7Wxe0uN7LuYPXkl<KLrbqF7LU2 z@9&?D?<?=0-oGyt0x+Ff8bmf~mJZiyon@fSmuAy(PC9cL()*(3!qU)T;|{`g6Q-@4 zdMg5WR8aO@7Yr368-NE&pOF8+ArJl3?4usL&%wirO*9)OsD|L+y$kfM4qr{nMR<mU zH8G-To=LS1Q@3(g^v!p;10Tz$1mS!cWKR<QLp8hvOt!_DG1P&1cqmTBReGIJlZ5oe zT3VP-j%op0dy6Q6DO{-Bb|5Gno%IrNMIVAUDaw@y-`hmK8@4xJKTv1xfm#M`^9uPg za<RDKQiaCjsG{)+oKE2CjdAkJRpA60xR}Iq)4C(z?pE}&q&vw40Mw-_3;EzoV&n9L z=2dL$=TQ4c{YXHm5kBcz0IYUD>G_79-Yr)g^9<SoSbBHjvr~e<>I-8Yb%dWsX5`+z z<|jrr>#zZ@Y<scn;JUp>lbb1*v}6QVJIoKxRy~ObGX#9)!=K!(Jdh~S3ygy}O&!7N z|J9V@93Sm)i}~Lu!AyO&Tol?P2Ty_I!(;+I%nHb>)PUC)!8P`{rgm=!oNd(fb9c#w zQVNV6#Z-eS__Bh<q>d+X;qqF0z2U&e#SW8jR^4v{z_s`1(JXM`{6iyGCJ4^<?Rn<R z%|P??aURV248?4wu<OCAnlI`&(_3?3lFVU%164RX{!FAhZ>5N<oP&pDYercbxu~Y= zeN&q)&o#kXtOHC0FgxUgGV#xOHr#o3-3YD_wPa+aauNc90I<kTXGLmypn}EEeIMtX zzmMy|wwJG~#jYlzdY}(eSG~oD0%Htua!EbPL)MMR;>(6W&=yted%=W@aht4W0g1&= zfNk^TgU+g^uGd@2-3OyMx5{oDlH;)T6LnWqg}5VU@2KINKr}iw7)lue(b%4$1jR&% z>=P#JFNjPFz{$x>ak9q8I42I%ASz#(Bt7{&{6AI|__G6oZqumrVl;R+#2FW$qmJ;! z4XOx5G4i(UhL~uU*cY^HhA7f?qWF!&<LBhe?LhDWlQ66W#HSxw>7_2+G)!8<n*$<l zas%msg7h=f!V)^_IQxkBAAa|35G64c;3(zF8_+f9Wd8{c%Dzb~ngFp5%IA7(11$8} zpn19dRE9=`I1mq_NvMo#ero%9f9z%qE?~)CiNkV~ZB@%!#Vr!YOxg<y?EPApEaP4f zaIoASe|9$gdn?I8^QRgHSehmG1*Ma=B!Q3(qGB&w*PKZ4xP0h?=Q`!l%L0bt_o*yn zLv{4oFn84(VVN3F$ob~f_~@vOE7qV{N};zJyi`M70b&f_5ktqFbzz`ajf6(gcN|rF z;D?NvWrgWc8dAMvd+jMEEZ$Y!KPgC?l3|6j7{{l8uR6@@je$>V@-Oe0lLBUjluLaY zBxPnoRi{}a9w7;t_(C0^pOw8cpj6_#6rA*omZj*=Q27hdb*lyeVJ_K<{TmMym`rq~ zxffA!;<E1mF{|>p8r(QaL9rB0yY_BQ;;ewDR6>ISQyLZaf3dFHDNN70V5wdfWB56% zOL&uleKf;(&L=)AIB*gbo${8rOWs3IhmQQTA%1Y;j^t&T7S?NZxQR|Zd^g{|b5l%< z<gnpnOqI?B0I)lVmDPMaI2C_3K&g}o@!D!Uw%R8SR=7}lTIiu+wRmBl?yR@pMQ~YB z%VXw0Cw-jKhF-O6lbC92TsL=@A!5H^s8`ngPzitD>NgH<xDkfhjWe&_L<Orn&K>fw z2Eh;W?IY4(zc7yhp@TCWCCiDqsXFFqFZ^8fvlHJSYk7CUR~1s;uDrGaPD#|B)%)2e zaQA>!a}UQUs|<<25X6O>ZR7trcfP4xJ;>OT&j%~Pd9SR(Uf$q@UCou+_CoXD%d30B zK50qQA@2RMO~z<fE#gWYU7|^{lKkc;z*MVjrk}5ceiW|jFfF^w+7Ht%NsR{OYK~Iy zR^P?Xi7Q|Z<|b*F%S>+Ttx-O%oH3Z^4^<fdY_q+IF2uThbug|N4{S{(HGEKU5&xYE z13E(R*X8}PGUa^fX{R;D(<BUF>Xyy`OERCGNw)lDVY%W%91GiVk-PJ=J6NhEp)pi$ zQ@Pm0W1hf%90I;c&flHpSe`xGPAYm98ayP1%F}`BzciTedS&H5qCEPQp%8raoisb( z14H8|vDk|Yc3hn@Ui!xkK9qt6Qkc2~Yy0PO8J_Zgw&j=`&@=Qq?Bh2l?1xRWW}ii* z67dz3d7D<-zq<I`t1skKi=M$#bt=2g^l7T;g^2H5q9hWOb(2PuVU}ABoJ0I=cR$f) z@3@(E7*ufQ>zXsK6eeVTuT#?QipxAA0;*dG_XQbBs4?B)i`dhBn!P(p`?wOC3TwC` zF%YT!_)<gG?jKr`i)`D1h=NX7{Y8SqDCFr2G)5zKQ0c+W|Bl2;quMzT&9Cj`;^Xs@ z2I7w6$B`car5BcS_ipc+B8oShP#<VCi_9|Ji7U(H4n?!M+qN6NuyQ$!`f=gSp!BzV z=OlGG`Iic^AU6CDrpcX%7sQvVnbK$Wsix^Y(3_ggd0<x5dHJ&Cr24<#hEqZNwE~-) z#d$MUwCB$vbFwvtW)Z%5A`KhS@xxkr{;HP)A)$|_9>Epgo}+eyke0YC)Pk9BJs<jb z)IkZ?KOV{mEUsJOy*IBe4i$*TrdWo;SxNC63y89vnFq{djoacT!Y+kOf!!aw#y5$b zK&6FuTZwmz5`K1LdrbGFHbK&8(1T>prZ{n<Qn%+$dd)1zLaF$hVb!tO9WJwxMJ&if zc94slM_SxLg}t~5XWXA(7N?sXt^Hj6`PQN;;!PIhH#4DW%^Qq2{#SyYV4`^fk>v1n z4-I;l9GSGu0%pGFc~z2jQ)Cno_Q5aEJ!-G>PX~WCwu*zU62SjaqfV9v(}_45UsY5y z%!`BFpdyurz0x?bdmN!*OtnNBER9IhhXF(3IQk3m+=*kAEVvmCTT4Rs&|oX1!-`pi z->h?MZ1@!ts+Sy`Dm;}<9fYkq;S@~{QaG_+E5pFv&aORB#Uxk-AL{FmYGwJavJA%O zA<-oII{ge}E@6y`{vCvLp(5idAY-QSoC>4kG}u6^(IK`^;|F_nxZmsxXb8>Kd>b;n z0!yk!uxaqzs=Pn-nCKCdWi~Vcz{bij5?SuYs<VdsVj<6<t|>{IW#^$?PzQ+7jX0Pu z8Cyz1cCoS1vnSG>w6kgA@g&8mIK8NP^vmi~JELO%ONO~P#lIiTN)zPYYc10Eb4ApL zo&1o0l(W+}2$4Sv4>QGtv9RehRI`hoZyfyZ2JSQjcvYq{9TXuJpA#H~@CUFJtR2ab zAzDK7J+hJUlCIg&0K|>BSH&NfDDROp3#p(%_w$fH07NwzlgcE|%WZSwACvGV=_`0> zkEvKz9|izy9?g7y$tJF~2p;S;XkJw2lmWr-<Y<=NA!C_jY$pviN<(l-r6+lLvU9Nh z!HRA;(gncgvrnhKusq9x;$QilaA73QTCbk8uYFL7sEVuC!WrkHzLTmtIY<@>d5L3o zvfEq6NH&07@unVomxKCE$`a5{R%F1WwNKjrWDcZUSp7gb<QMPekPUA31D80b-9$Q4 zQ3+O9QIqs0NxTbpZk2TCh*aFCTjFw`tC|joCo?M)jgarkl^(N?SXpAe37L>j`w(fo z46SD9`=$MbV?GgMWj%=pzrFJN{mUtYy8CW}WprZQZ2+~zM0Alc#v5iSLE`6bORjOW zCuU1;dV2yKw2VK}<TkvSbmr3T$`jS~zdv14)DV?oAmdl|r!lkKCoCJU*nQW81+c2y ziQ?BGi0>q9frwwthx1tBJ<!v{_^dv>dA22Hf+$`=LdE<r{k&)~zjXe@M!sXSY1aZN zZi=apeqKh7ac<D-GfX^h7MXArn{YscpoLWlPGnBuD_PjL5lUe&pgYH<h=eNTz_@Uu z@G<diPT5%3c<z)bg&ZcG+;UjP<D;fUg`;?ewg3KE_+}j9jgW**XJb35sA2(ftGswz z5@OA7NzKOXC*rgLAef4O!`^n0g!#>GzFmU8D*~`{V7)}~`|OM`oZ<JTqLWvc-MP_+ zNaBWz$w#k7O3P*6Rq$>AfGa`BV!pVMbz>I^%d#pw5^9Jo!!ZHG^SzN+(1Cmy@P>cn zMm?4ZM!kI4Y?%z}m5=^rA@0&vUpTfGtBa#7CSO>-G?3$w7+$cJ9kjXEp|cWuFbL)A zf?X#ge=y-;ir1WoIF&eXy$?>zBJS?5Xo;>Pkxa~EX7f#um?(ffP1RkSXy|1l#>%VD zFEbUE3qx3t7-HCkoC`=b3zzlS2^O}2jH(h65r6)N$j25CSqEK=Q~-eT2&_%jQC35K zalpCeD=F#Y?y#_mR;UUAs)*h0GR^F+xv70Dh?0aWtidHUl_l|^F?@u-Hg=PU_|8H4 z5+(j{;D3poU)G4Nqj=0+oVhdZF~<QQVt4IRwkP7ci0J5jh>Ezw0i5>36>7a!IO$)e z_w!m5Qrq2zeZFh%4P!yugJNZJ5U)ioW)Uu#CUN033bBag-zH*Qh;$TC&qo66Y{6_o zw_6x}y3bJy_FrXIX)><HZ-2#a#}F1pgq6#$#ZIyi69B4?gIcD+E(s2{|1mTsid|5| z-{?cMMMq@+R2re8)P*-OR^q@_>H)D5h{n+i_jGRS=~eztPF)$^Z@=$+(#^6gSoAkG zCi(*Qf-XCRgZvwZY^6zvw-bNyrAGNj#zkMfQtBX5+7BEBSn#h@+$L{-?^UBa3CW{9 zxsEkARc0)IO^4~fIQGs=bSEfLnYn<4-6A4mX0a_C#BEXqPeUvy?wkxalsA{~n~i!C zB-##gq?DmzM*cQ0F0CdV{3qAC3WXS~^r=N<(|?fi1t<|=oK3>!Kg0yNA$TIHE(bBk zstR9Leht)bvf<%=h{7n`uQH=}mxAS#mXF={z(yhJt9{GWu;0nB_8`;`5ulrl-2@uf z0n`~`JK`x0)qHF)vOu|piJf4d+g}+00L5;65q4WV9D4nDb-u!P)2Ps*-Zz1oebLZo zQ1B>ngxy<9#!kl}zLT*$4r&WPG{_HBDvmvPhUj5oS1geGnGx+c^MTi}G*XC2-eDGZ z4T6t90r$A8QM66g;KFb+43yMC9X+hvSV$F_5nxL+<Og#4JrCtTQ6ppaR{KNogQ>BU z@;)0Gofs$(P8D+##L7li66)Hmpnh%29?QM(1~MWzMZX)3XfnZ8QLU@u5HDyc19eXZ z)zIw+_tox4dQJ~5TS80$@lw{q9|uhgeX|P=>}QDvb?Ar$Dzb*jKh%#Q2^AZ$1K2(q z>^2T1jN{09D!=r12Xj&LxsW^(3J5|bwB1ay#O<fT;^OG_;c0}JR8QH*G8P%9Mt#g( zkgu7T&RNfF8*D>5VxEfaC!z}h)U4Q;-9@E`>?74=lwAi_`D|?1Xh8Jn-aae%AvQc8 zfSOVZ5&_TEt41T*$v;pwJ{3h$Xn;_Lt>SxzZnv%?N&KK<T9}wp!KlpNmp8er%9h~- z{xHBscu(Z7DES>?L7yi>9Y~OSPGJ-lUE(+W?t%Ei!Tl}a#$IG-G3_Libfb!e**t@o z33~m5ihT<>R0WCWS`4r}l~B{A3oExK;-FzEeUj1f&xN17F2JEr4NCF{eUcZGQ~G1i z^m_c#g>|3}@Y=AfyE)|?*aR8-or!n^VDj(GeCHsxh!Ta&%x79}Cv24-a|TyFA@>7! zyRt>ckNWQ|<1zlZL;g6OQLoRBEjfMACUngiCujpH4cmqp5Wq#87p$#y6?^6f4)sES z1*};IOu<h?3*iUP9ww%}ZAX3FWb5CSTZ-9tmkT-4+Efm>-Ymu!DRRm`ly0%)TH}gm z;rH2y5hnH~9|iVKX`y1pc1o;suuVABDh_oh8GHHf%P$(!S4%LzN%|2^h;xr>BSrj4 zj3_D{_<JN)b@X|QfkCo9jv^x2C0;ooJd;sAYNz}b)y%~Ho~@b5Ll2OU<s8&qk=?-_ z*~-WM;KR%UW?S>02=Oo)06#P#lg8fGGk2>y2TJ9Ch~a0g{Cw+Tjccr^bc@At?V%cz z)khvd=Phw*nLfS1rw(ezG!@lH#rBbq#Q^4$VE#4-`v-?A1c2DHvt1>#%xy@!8MJ^Z zwjaRm^MVe3ZBHXV+`k={qmFYVz1yoMwv7$-WyQKboP<A19~CT>bn-R@9Dsw#*F%hQ zuw5kd2R^omhPaJ$K`@qqQcUZewsx{uC4g<`XvZ!UdVRmSoOgcxs}(fZa2rd6`ZK?E zVC3Ab^I%F+6%7RliLc}D^=8hX->@I7!vT@dcZ-SYXCan@_C4%Qnfa#(m5CiEVe*1v z!QMALJ+nD3<xF?nWow+TH#qg}q<--VVXO24lk=PW=`p*vgN%L5!gh+(&}0O@P~rm_ z-AO}T4jOh=RXTD!VuFmQ7(YklU%kR9xSg5-tL%f!S?pQ=n&r8~LGr}#2`wE(MNiNx zuMlh0pKm>|o9@U)2kadtY>Oqa$U(e}L)w0sNVZej9({U(kGjA=)yw|oPtEmtUq-#z z$@9^fxU<st?py0>%WYqr@_>s-Tu{8r{U!@FLqg{(HirF$v&fd!M06|p*)Q6rH=}k2 zFBlL8p&Y5m`+~^j11rnOnt}sA()_?@AA&XFz@iyWx)II`$FJ^v!?MS9@DZaD$nQiZ zKzDuL9l2>J5|tmHG7KwNt#5-pmZF^m3<8I$y%(H{RBX>d6nqw4O1F7la=ab?^pdsi z;d>bhdp~*{Y~J9%acnBTcHrO?5G9rLq;9+1vvIZ1crPWu*iF<d>B_<s1Q_^0sgTgx z!aX3O7za6F6Z~4|L!;AUmSy~lzKd-m`M$TD{&^|<`SkR?$Gx+E|3Q^47cS)=FeE@Y zo`R6!LgyzpmRtgNZQmbpZCdl=yw9$%UIB>KoahZCn)U)5uq&$L%Jx%prGpIx`Nl$j zfCSbI?M?&YK0j*y;&U$&y5sSMk!$aC{QqWMyfb9@s^vWJ(|Y*Q;XkLU$H}+B<ibBG zYq}N3SHg7<nV<D%axUC-8TVmbxyhVM7l9(Su4G3T%;{dY*Y`B#15=D#qJbXBET2Xd zk+hRsod|B-V=W5DHPyVXxi8_fFPwFH231Kqr8aaqNy{}`<<!G;BPRuD<A>5f-UTCP zmF;d>g(<bsT9@=?yTWg<rb&eb=Iaijs4Wkrho(SUU%f66!}8Sq`_a<P4p0WomS_P{ zpqnp6C_)QYCc;ob@Z31((qd(LrfSG0Jq&w3WGwSy-YJMFm15KoPIVXyeIQg1{MfZE z*KIa_sHBN8y$5Ynx#(bWg=Jb;{A95;7_NSFHhouq(ew$E397z*t_i66qdXM|dMdMj zNnzM>(NP&%m5_5)T+XGN;w)tcO8G_&ufljJi>7HFH7JSG3l1C;y1~lR%4;HJ3{D*k z!y7M|c;@q&(^$7x)eK~z34p7}bbj*1$1Raw`dob*Koc~?MBy_H&K?a8zZ9_G5$hPR z(e<$|nEI?q(JS`q*Ms>xoIVp%*KfBH&XHhNTKm?cBQ7NG*WHc(KNOvdKhy8~$9Hx< zpJtA8J`Qte<h0G1G>3{pn=>JV52BB4&S#Qy+MJ>!N|H{tIp<6z$(I~*s*i*u<+tBo zu=it+`+dLf`?_A&^9dMSyk~$mz=QcTw0yI@8_^B51^Ui#Urwc?ok!+z15o)q<BPIO zwfz3&kd&n04J+bB8=;^Rc+ei*YAir>O%;)$Bcv+g6a8zTuW;O^s!nQ4QYBpG`I2L~ z%e`B7Yuff)(rYw}GY5+Gr8huB#)py7P1-kVOFq$O)k5?23*{-9O47|A40E0QBmgR? zxp{@aMm=a*c*$f?iT9p5O3K@E<?V%s86gk=3Gux?46q$_`e&gSYq07Dv35Ygzvq|t z&!R44TV0RPNn1JZwnDHhKuZYB*SJQkOJv>=MO+5-5)}iL9u_VOO%T`tpQ$OeTLw9z zlZ_HCdn6kvhn1-G82ie*fwJ6NOR$GTdj6FZmQ)km*1~|E6<a<UFOVwlFvTcXv5r*S zT=yXMf;A6PKqp)cDFbYRDGY_Q=k=18mg0AR=KM0(k^X@xxl(wC=Hj4F*aW*C(aZsa zTEetle`E*U;(#65@0#etbm<ikxt68huiIGY3h~_7tK(rFW*8R-U{P^Jit9THfF2;5 zLGGZ~3m<SwZ_f?eE--7E$kHC0;Oa$g=wIx*P_oB~_=&XUBEa9iLOq2VtV{$a3*seG z`qT7}736NS{d9Yb>?W={$zMIaMtkk-n<!HZAZlwCr^grL#X=lUKy;260zQ!nIe%w; z;Q_{PbQf~u{Mal;??>2VqOaMn!d@{45|_1nx_Zr|Q?nPVd5S;|KBhATg9+3-ePL=f zCkc?^uBmi(C5&I9$X3S^DX_o}Psf8TwTXHHL6OB`cUo)=*V}n~Xo`q;vjZl-*pf2c z&td^N%G%KE_7r|m08J2PL1PP=dF#T<CScb~BB2}SaKif)V2PyK)^B{)ym!?3<eKDN z<KN12C0P~+<EAqd_ZbQ?cB~Pn?*@Qizmf`qjs7F70Hu9Ya*qgA-xNB_9^uM*54Sa| z!CHSV`Yh<F)r4&@d3&V@q&v!a7VUxMBXxW+19({TZ`DDxr8$$~&=hgBge!Imz#rl< zHS7`BVbt>^IAo$gQMzI*r0t7P*f0#Gw!|4usFSoz>odQnR}eMvxa2*C<HQh6&%d@) zhlp8(x;J-wjzyf80>G^qo!@ix)j+PD<ptKgx~?O?2A<eGE4k8};)-_v%<U1JCh?;1 zP5|?X!1;DNUiGNlq%fvJiy)K>$>4TNA!wzhKoCwvIT15pnf9hHhOOj$lG8iC-jqJI zY~aLL>H8O}z-8a+@1BHQUi5{wUM*?z#pz6jmn~@t{e{+?3+WT`?ZGLB*}?E**cKEN zAknL9;f7&~Rsm);dT;W!(5<B^=X-VRinv^N6vStU9<KlUe=}p9T>XUgSLt{k@u#!l z9|1kec9Sn`$P>b~v%JW+w=UOuq-8jUP!+|a(j4OHuZ$sRO5TZ0dVM)gv})GMw3uCQ zZ&Q#PB-}Jj>5#P>slyD=ppqycUo;!UK2Q5>J~mn4HbE7cY`dMaY8sToI28U;Z)3`? z)H}i(?0+?T-N<2P+^OEQD^fsHLIOLE+V-xy7qT=Wf!cxceu$E`4r|Upq1$Uz;iE{H z;k|YN)gYV*tFS*a8jHQLLJ?VsY{;o~2)g**#OCv_eDhQimt#q-a04yX`l!eM2x3z2 zJXO%x-BEv{u*4m2%6(TfTu4J{No%01S5G64*AAp7_k@<#8asz4Sg@x+22)XkY_nyL zuT1q~n#mxY|4KDePDJtHgZ-EPeGiM2cwI3tq(SFAF+LPm?2o_)brkAUMyUtp6Uhc= zQ=nyk2O6w@X^Uxz3FHt#fB{;xDxi>ep^cI-EPopn%5V;i6c&BbWNWt0;PKug!GD*) z0K$`b5rm+=V_4z@SR^!}4J0{FS<qS}W?75oshw;rjDDjEUAd@ZkZ%d%qY<e3@(Jo6 zw^`zLim(Jgk7(mye^ijkZitsJVs64lUnSu_;aarl6FVovO{}DAlcMw#!B#8%d%@X4 z#W9?1(q~d_dB^s{`wg>?rDNLD>gd2UgDo|RR&mLM*3ggItV2QPiP-RNcYAkB@J$_N zc)lWD_BMcLh^%g3vc)>D_4M?}Ga%o~|4t~ZB@bl-3{u8j+UNU#t-1XaC@X0KFLFUX zTABM6%qss)Abhl>v6QK-w)9@;-&Bw=y9x_d96W+!VcL{GViA{)t}SeA34UQ@KLZk_ zP#I9b{Yk#W>RQAy0qhP)A!R}V>l|l$(zonhK_T6HN1Q%(xumYwj)O2aBG}ljf{i(h z(#w17i!|sebImF~!bsE;AX<V*okeadSIV1fcM9HQ;=WfW5ut>X+(1Hl5&(K&#{<W= zM`hj(70mFOfW(w@xDG-A80eLqj7w^-JpFpq{M%>S)30!5-D|h71*G|~2P)W4a`Cka zw(WSh#ND$qAlqnsr|PN;<Kzzkq!(PF15CLL00gc>ybie^6f=r>o-R(noaX9fArFo} zTKrvx+F>$+32ZoWL+Cokzm}<qy5{QjR&;OyuqDlTk($)R;dV%K)rH#2>qek&ZL#6x zc9cIDmh%Tujdf5XRYz<atUXJ~W_RH=pZm>1{E4u;L!BYzu)v)T-pN9X)TZ!tMnX!O zw;gXy9S5l^^_o1)cb4OVJUIC<<6lhL2s$IXx%cYIQ;;c&I#F-i1+vC~FRepBmn27i z6)=$Ci&|pt9~5&I3k)nf9PFs&=(64A7bewsmqC~h<k_S9tRz8b!YqvM1MI)q`rjX6 z;hE6HS&OIfHYZMn{ns}+9CXVfEtRjOD93eWTn7vkS8F)8NfofWM)#YO*I{<SvU-JJ zYeK50WpkTi<*@zzZF}xSFO?77)=CMG^&$w0K(S5HoX*61mBTozV1Po7{b>#@$Gb%? zu!|M1FR}46VX!lHoHff9q#j6gX8M&(SV%dCxn)}HVTRSA>K5GoX33k2%dqm93~l)? zhjM5gvTw_e+WZmJ*jAHB!dN4+jo=XDLNI`aAvx;i(ID!6Hg0yJfs1?>;XEZ*(pyq_ zTT>y~xvE`4Z?3haM*%n@*V8@N{AD6XFpVFu)Bmhw6t$TV4u|FsLI8yHWJ?YpFD)Sj za-zrtS+i$`%b}<q&0&3O$P$(GJ6HH<D2b%r#hp#C1nF$+=oqIrndUr<H+wJj%+|N2 z(pSKHA}zqOzw}MI0M}?61TeJ+yNXeET7-GXSJ|&;Y!3E+SQ#I^$Km9Wo*>AP$T^l| zM>&t7o@;}yD0TA3I8{Ro-V@|<bBen^gVf-lQ1qk!7@YZA$lSv;>Y?;PS7DMzLFO<d z*)B)y9PB`=H%DpoO6GWCW?H}@$JxO&>AcauD=rrwrRP}k*HDL&EGg#*sl19{lgMH) zqstF3cjrZ>%v7EEI!K{hMWIRa4@S^2e)tu;SzZon+Q{?Iyd~rGd|x+{|GU%4M6PP$ zAT+my83oTsmS@J!a@Z`2K({B&8kAiHVTqhH$BB$2HEv^Flr`cxZce2>-ueEufq|Ir zDNA9EHrEF~C|9{#a{$lI4004+ueakqOR31X&&xh!wg-8*Brm32T1uBs>UV6r8@vOH zoaOMDfW$`HpTR&c5BAHfPG3%=d8F_}l;54ycwo0>nzsxpyQewL`5fdTF)d$jzL;J2 z%LGjTDb1QFEg}I#FjX||a+5(|Pv;{?7^ye)dv4Q|Bs5X5pcD*norTIn-UO|rCQq~; znsQw7=7?O(NL;7dr)a1_-cg_x1wcTwM|#u*l)WABmVl+}`YN!^CqgUSxM=q`LVTO1 z#m58?+5=+SMIjI|xf9mmel|^$uws#Z=lJJHh1;}yrN6=2u7nm`OQqXvMlj~gRiacQ zDC4?3)CTTBHN3bCbWco4(~V7a^?+Cx3aH%2)EO&{V+x%~!ln1_2ZmG4X`puq2jjwG zBSEU|x^@0m>cTAa>{eQm{IifAsFS>n^b9t9v3!S3)rUj7)Oy=SAkl3wFo+{@k;7&d zc0)enT33e6V2g$E+<;k?3p~RuI*knzv`&$A^nlL7t;0<a)nN~gTpj9u6=*e3TCIgY zx^kl}sTVC_-j*=8b!fujlwYK$eD_Fun^Fl_<*$9t38~xy$2*z>@v28~Fh}cesBuJl zaCih$|ApHZr_OIYf!iHo&J(F;;>%nCeYWyo6wx+EnQg<#Tx)rk?5+Zsm3U<Z{-{7r zKq`4-(tq`J=-f`fybej0H(sz)EpAr#3#-|yhlTe*qslqjc;B?=!aVoWqc9oII5VPq z(xaO)@H@tr8y0xSgwE)uDnS5S;j*(LQ0?+GUVRj*uoxrVDaDO4ifm4fG3lx`4=SGO zzL%<mp_+pMPVyHLFwfbo@Uu`Gbn?q2d7Fc#v|A#?YrmZ$*3*~7907|TrmLqtn$ly` zGGZ_sF@q54G-W>6vgA-IX;xuFh8CR3bMpFE+BupMMCiVdff?-sWmY3krgqMxU-6+M z7_FwQ<pDuif`6I8{B=?Ctp+&&8&V6@tvo{{K)|ahEdrk2VRu`=K2suj+RC4JwdtJm zI>&-(Moea!zdST-(1yad>@J=gJ(1}yl^W2Lkq`-Wv9ootL_v_=Q!lNb33t*9U0b{S z05l4>VWqaELH`CQp$F>U1YJII)wp@7vkoie4(p;m|EQJ!yDmLwB3&io?5RFTOs3nk zX%TfcWA$r>7X}&;*#L80{U={2#**pL54l8u*rsr}(V#o~-6uQ6_3K~oy9H(kytewf zh;LLSg5-txPw#)TKL=?~#Eeg#nq4@1lcVb+I(e}$%t-5`85)!MEHVCb&`7Ekgv0m~ z>RG#+i05M)j|_WxDfjd*75u#6E07zsbeFau>o%wx4WddiXtgslMPGL2+FYxz2;t+_ z`0BNO4H9Ts8y^|i2FMXocJmzK$bBd1U9P8?=({S<woSbA#-s(br6&%i4LwRf+=JC9 z_uQEEjq!NwHkg(?k&5|vw({K;+cKHol+MxG;zjJX(}zM_ln`^K?~+MZpn+sm;l=tA zNZt9eP^dy=TC)|*#9ih+xV)LS|L&wWUzR65k>}!U>bY{L6AkkJii^QirMO4f!E~Zp zy0GSGs3nx`I#@7hKk-<E0D30>?YaF@C87d8wA9II+MDLscJ}Nn#Ic8R4!|?jRaVP& z`q-Dd?R2FXECppLXaHEN)YC-~>k%nnjNK)`I#k{UhE#D|(1m*RR0Rsc!f6>3we<&; z=|cdh7ltDdu!H?NW19k9!9fKUGV~g?L`ZP=^$f5VhsWmD=f=nqBFB1~kGu@bWHybO zLM_^VrwwTB8*AFwD^UA@B;E9DpIh!mBUH=5YMelLCfT-2XzodeU)P<d4+^u!V2V>v zM<Vz_4>WLsBW_rZtX7eJF+E@r=F>BH=3d%MGiWTv@RN~H%wmR(WyZgjX>-6KZiycy znQtP(Qct|wJ{L4Yc(t|zUiPgS=<1b>b$55+x~*~d&Wq03TDgLC<tc)K6!<KJU3QlD zxpbZe&8|sL5>#C*=kVDHaq~!9V_<C;<T9Pc6K0_VT1G$$tm5$*LOjH`E2HaOv=3)` z>|%x!{Gr}Iu_Zek*AFwI;~`Evsd@DfAC}K*N5%g@SEpn?;ht+6%Uurr<hS*Kf&}cr zn;<Um6`d!AcA(nQuW1R1kBaC}sia}wk#v7S&YZ5-K>#0*!|90Nw}0+)uoFU#J<wI< zjD=R2>w{3;fA<r0vLdufjhZ-S94f4kd8K-7R-gmvP5bWdYdVqYc~o^cB6Zy3$B$0P z$)&*z??dTdbh-K4u%i1#R;OHsrQhz;{+seN4&p567`!x1w`*&Gd6=hVji)AfWJI%V z6B`+kfNwE9#Ov=9a@#nr?{IV;|G&b(&5q()NDW+|Tn!C-qbas|U#B)ivb5V&n^2z| zMhyrDYsjZ1O>o2qLoa1=_{^k*2&P%7PFqW;y4ih<kg&1uTHhZ`FXVu_5><0%*GRMs zb%%sDrSl&0uo!^Gnao=4|7BzsW^PVQ-~QjPnxLfX#Egg;h~w;IYe3qazm4Oo#TO04 z-eWHFoNHFnu5{yij!J?4fB^g(RHMH_65yZx%Q+kfsquEFI~7-2@|(KKPM`NsJ&CmK zzf-9INc=1zQ#HMkaj_7hflEtn`V|`tc@bIE<(|}M5pg}!CoH&aT7uf>cJzD`q^i#C z&Xo**<&hJ-4Ve}g?}Ajapb3OjSGDIQZ%dyhiyO(e<}C727*!uLp4(PtjDt7<GceaG z4vq6>fVbUxEj9%g8l!t_=~C}A-|M;`Fn_(--;g^U_wyT2Eo4_|xJ2W^qp*!#<&ko9 z&{Rvv50$ZMlYe&SL&klE?i?IH_+56EC&eL1y24-4CP!S$3$V8YmghU)a$y<}tp9}X zy+QI|@UxpLJQ7~rF<&Vcnu}j}53aau-qP`WlvJiQ*?pQ1u#i+0w{hj2)+M8p@VQ5% zsizN=u%Uap$d&V7qo0N@`v!at8m)Q~bzB|Zyed#-a-(`U&Hu|o)$Q3wLDQ|_zm2}l zYp4C?4T%vdKIe4zU<1EDS!#5N<@0Gyl}}9jT8;jfQ1pkn*WWc5RYrNGYRU0;!$HLR z?>qdJr@!1Z(7tTnH@e60Rpv)ygMQd3*F7yH1@86M4w+A;fO{|#J5(OTdO3B>qG<(J z5+Qam9+@r~+Jy{%Ar_l^uGC{UQ-msd!At5=J@9<&y9Pbmn1bK{S43hA(nfApMo~b! zWW~)v{nsFv8}MP}T$yS9AQ(>kZ^<{?JPSxHM<3<7@|YdE{20+^7P=M$oB({z3uu+? z;ByV>p5Q!_<oM`Ov)P?%!&ju|5>#svHlL|FSwQ=$%&ea&*qC}$lk6qNCyQV*K4GN! z9AD3%De<rvMuta!>=SiBxze?fd^U4Kz%+Vg+A$$Me5y>nvFCy-dSu1VK|2k3-roq& zR{O^EqATkRx-2Ej6TcsMo@lTTFLK6UuR5AvvFR8L(0G{A>ui7G^hWjRr^MgdT}D7e zlSLh^XhkeK@|<*?k9D>y!aoe#FF*7$*i`~BQS?w^U_F`_-4Rwi?iJMI=XiOVh|4kE z^?0;=d2>}c%XAJvEAPuBvx}jxKsj9H03)k$R0U0B)Nq)xJZgT@)LYE2T7QhsRXr)E zhIbinz0e;|N<0)$@!gB&0(fLbor_A0B==vN4l#UtE|JEtmb>O*n=V`F+&A)iBy5T& zZntHM+mxxq;!Yft_TvVO#Fyp%(;Wl4)7PaCmu0Rh1ZipeA$YxlT@m8sUwS_>#05C^ zXAW7^5Fcv;<_=7aS8rYVc9US8R}0Z@Y>7^b_RnNH_b$cgZP<tK*6K*Qf67UJ72*UP zdfh$98tw_}6A_T!0m$2H@2>B9U)}=l$ZEHYD2|Y_Mla-OzD#TpH>(KfEW}p>QyvXZ zZnJnaHmd!`<=Ju}?Xj}^ug!md1@Gvi>?(YDg#Ar%wo)hFBjhx3TQE^<bFVMWI5JzK z5@e}e_+7_eo=bA1JV*M*cOHjhsN`T<Z*jS3x%0Zh)tsmrb1xvz2A9A5N1ClloJ&DK zrk17hY0u#o!2IA`mcqUo2fw~vt{Z^n{OvbVkUFUS@1dXC_8|wlH<HV%cbV7Dg^F<U ze_cF5);O2yet~B5q<EgLlvN2s<uiBzEfnJ5EEJF^lzl!^feHYm-Cs<X=#r@uIU2Op zH_t2&>%zek^_To(iUfV3cGszj(wP2s0h{?Y>CdP8)FYw__PE-MOJ68OES5nW_bB4U zmJV|3G}wo8lS&t6$^e(1Lf>QWWxoKxn*f$=CmdsG!aH3!79b_}KzbRq3FJ+(5o$0~ zv61>3<>U{j;PTGJBj3HrZ8xDlx+T<_-agA={K%94MldDn6iW%iQg^O)x}vmp$bl-} z;RIwdg`ALJnZ3evTgeGbf3t$j`MXeq2?mCpjunTI(;>2c?pGlxUU4DWjy--tuh|6I z8!k0^4q7@iOutcP7Cd>qR_~+Tnq`O3%i`lvq>e%1a1RM%cc54`HEV0u(<V@8<s7~I zLf!e=oK#%3o16y?s?9D(0cJ=VF|@hv)<<eCCfVG|lkO51->01(tfLKP+J4ju#s<dV zMCmD5(bU4!BpRRjwNxqeTBB{B|B0VP2Q5Rt^ScXW#1B!?H1MxgsTrfMF!Eiwi28O^ zepoRW&^p*_@vdmP4;@!+u?6l6{+@X;7|9oE$rA7CQ8S6`%(<`(GJUptR-@D^8~}!* z`hyurV_Y6m5XW0s_)eLTCrPIFsjbm-%@8(zbF_Z1o9eu0Ccub^K}`c=mcX~>?T76X zeI{e%{EcF&T&gAXton!9uhAEhEhbCN#<F1O8K&@kg-Q9%Sc9fp{u;pq?`ZKSCho-y zF)uLu-bgSbK8)h~AO#Rs1Q2kVhw5G%;ZQbd$`$Z+lB$^CD6{M~C7lB!v|~7R?Ai;i z?44^^AGAizkn^K+ySh*60bq8R{FB(@uAtMS-^9lR3&!$50Ow#Za*!siLu2p&7VnxB zn8>)5TJcTql%W8YTnWLk@ttbcs%w+k@41nf!T68TcPDdf=ZhX>RtRX>=?Ofe%(S)d z2%PFJ3Iyn`ASstBc+VyBB?g0}zw{uD>n8==*&4?_8X*U)y>6EGM*7q;Q@PQF#~}tM z>qEOJ@gmX^Fi&#%O1W!)MB~um1?3I)^j&sh`17z`s0x+os7OZk<w5dkn_@p=a6>^K zu|@J+beiTm&~<T)CH7+HERS~+7u@w)`n7%t=0NXL0K1b@&6y>@q5U=FQqzQKI91&P z=ze|%Btn!w!PnxNb)w3wXqT*5n<aIY|H|Nrb?1rZbH<@Q#{ptNg&aElKRT0geGz@f zv<HuivH~FzT^|>V&Fzr9iJ5gvpMx_4ORncdiB@^uOxSodO%HS4eipa|=X!!i?eYVM zPq9+0bPhRZ+zw~C*ieoUyywH4drOb%300^<7vaE(-Qm|5*1T3%j`tvo%{0mQFy?Un zG<y6^ws9b1^@ulO_KEBd&bX>Hdd@X3YGhO?vSJv^FYNYHt}-*t!T^|iCGW-8i1DGW zq#s;t2(nlq+*QAenRYIE67vrMTyV=0W*^xpVE)&=8MyPL=5m6Ft>3ZU3zM7|d8#@s z#B}o$@s`PiHeb=mJl=|D$Vei`>Fb}GkP1Qxd@;QW;(rSJAIVhkoIM01ic;o3UVHev ze5e0ZO%GFtxWujeo+1WVXPSKY9gH4y<n?a(?4JLkG~SPZ5^$=+?_UqNu+G#zioBGV zA7<N23@bS5fuPpfw@B`IiOaYMd?{AIL(4B+ZMn_i0h!<K9{6Bd`MY@}&g2lR;g0Y4 zDhpDf*&k+^?aWw2QiN%hn(T&E3MeU(EIUsQnjDnx<r$IjfoBPQ43^XH1uKU!pL<T| z`Qv=lm^z1PE#)BX_4CvO$%So%AppRQ1p7o$1>WJ=VyaU!V2eUZ@azZUZ7{~;gk^Yq zZlr~Ja?8Ua5{FW9R!jwdQ>Tfq`TTd=%}|M<mqNj=P@xh0NI(igP^{rCw!wOClLk}= zSQeABoA*J>dQ^1+rOEI^i=c;j3$Abn^l}xi>V)ST&M=>$lpC{JZwspRfY^az!Oj}p zUYueI1ujZa(PFXD&RTGOlWMl}Z^EPyzg@&;T!J*z-f7O{#)Tub(!Ks`XS2ZZSDxXt zySSfj;J2!g=3+iC;XV>GAbru9i+~jMUOe~0m`2hl+5x0*;AE->dbJAGHb_UW6v+lq z&AmXHNwRiBV(RPEc3#eVEg;igCd!Gb)I-rtn$sD<sQ`LZS59z-oV6w?`0ZO@Cqt&m z4hxK;j`k{GhieI`y=KQOMK6kaCZ$t7w{?On;x8YR<tlLoD%V2^@w}yW%rpqT1)faP zo@LsGiXr=j)}GB3$>Y}y$IC`JR0O>+;;H7QAoWa~>LSHd%L~`^KYvcV*^HnNKUk-i zs_nk0w1c<UVHw*=SbSrtR<caCS?W$X*<woP<1Wl+^;%>Cr6PUMY_M`UQ(=!H2L!-l zN<A?^vH5CganYtQCJ#lad5Egk3vM<pY?e7ojK5P_f%6WbItGFn8x;5^c-<a$Y6d5V zVd`jkJ&a@-8Gs`VS*ApaZYDSoldAL$Y{q#4mQKK-_VA7YH_fU+I@SGb7;i_C+xb_4 ze&GQwM4a3@6~0bYQ=*zzGjw`J)dg{gcx*iuq%^{ZDye*}OI6!T1Dh411V1-<`P>|0 zDbMzK4p9~Mn1%4quW#KkkCZYasCa9uD9ti8wwV}HmTsY^KY&Lo7hl;>QSJ^tHSqzh z3s#E+Y0&U&cB91#NT&^Kq_wKlLbd3Eg{iFj<~h2QgQRr9lA_C}BA7kWtm|qMdt{I{ z@z(40YPCHIYI16)B-K2I61Q1ACc{$kr-nCh=o~L;^imc57m%p_U#s}kKf}Igf74vB zS~b%Y!_q$-)*r#&A#>TEJHfN`tdh|nvy~4wB0;BG@D>wbr9-L-k^aV?PKj&Ayqpd7 zrJ#1O9805G7>e3@S@>w5KRNsB1Vyoz1>UbV-2+MO*iD4r8XIDLthYrEvf@T?4}uq7 zkJ{Qc%NcsC8F+!z<f%t`Y#^@ZfS|hBB1mN$Uk>?bIssN3p_1*`ZzEDwi&fo(w<y;* zRly>^sx9jb6?_Rl-NaG~qo}QjYg;Yo$onN$PfAW&YXf-E7b&)z)f1zA)*CF9Hc(O_ zg0M>cSk2yx@XBgTQ^CMrLV>q3H%tv!`ka|+qBBNX@C$h#<oK+LHksZ-cN?cz%9(fr zJFuAtxM}kQ_dJ@Z*@7>1<vD7*cmF{1_uhiV4qkB&q@0W6u*b#rUs9DG|0vHM<+Low zoU=Wc2Up;*>K}?t324FXpZn@QL?2CeX3#4oJs>~{lYWF{_WLi`d>!sA-Lf3P+alGg zo=ljIP;b7v&r60mEm7cuxq5Ig`2gJU>;B|lO@g%2>1r^toT6wz{j!1cbf%iK8TTn5 zl=+atEJaai*?=}#ZKSH~rKPE+X@`<54fycB6{oiCdR0v1R3qZl2pHu>(e(E*3Z<gA zZM9>-BmG+YgR00_R%6^IZ^9?uKVmvzKpjAjNu(9ZebqQ>WAc3Km@e^Z^-a}9oZQ3- zOU)l_)<)JAbTV>cv4QOn2327eXR1WKYxn_d9JnA~?pz~;?w|A=bvf0K*WU!|aDs=% zz#NlQO@qpaqA(*R#3`pxE}>qd5j=bC8M=c3O`0iT8Y&}rhjY^yT`%nvoctlng2*xn z1{q1yRvUG?cKSQ~zgc+s9%K{D*p1_)J0Dl@=5Sx_84zPd+FOOnwWgutkJqVhhE}vH zCH>Fy4C{|@nE7Cnx%=4%8~9H(c=mR<b|%Xx6pyyLS6B(bMh^Y(Wg3V|?1$dNR8s^K z!5LBIkJO4)Bf&b6Ozk!W)kD^3X6n(m$gY?ra6UzI5vT73GBc>}O+2wR=&zCy*0dYO zCy0sq_=6uL`JdC)DkW94a9(*bj8#toX--rcc?|uH$R(BZew?z6h#Hd1(&avb*Z2Hy z--O3(hEUC@Fl@rBuxZn5THOTIc!p{rt0o{2{WNUVVud2hkF$sYp_Tj!R{k64m&&Hp zx3p0d_lgs{_>?^+u00~hDzx9Z=*RxQvbf2DsXc-tVA)TI2L}$4mvf2dxzx6qrcLb+ z33$@Vy8!oxjbl{q_k{NiHK(e<Ix8TP9k4|&Q@dqN*NI0+2yL*%B_uRyG0!6CR>F6{ zH--_)go)P90pUyR)!L?3A9Cm^tHwFrGK<?#XqWy2W%s{-{Oapb$79X?sb~yd$BQfz zp!n<UMg2C#XZ+2jrg-c+MTPfG@zK})MqRV{%e?B2@1wvfsd(Xg{kl#4765C5e+)9h z0)+ISO5051LZ<TgKq(pVw-Pj)`{Qmk&0Dwaj<AB}AQ-s|TwO(7Z^M;v;j{WJc~dP# z-M5%ooMwyH^vkV&h2v$4G&xmo7By-Dv^oaE?s4Ng9@!aSBB?4(RHG;ny<UnAq1CqR zNyNx!!Xiatnu%ElOZ8IC4-JyMaJvQw{ifIpd96AdRi?V=UJb50>FD`hz6CY>tz4#{ zB^&#KHP`Y|*<qM(zq60`Y;6OfCcs#WCyb$!mM<<k=LXuj@4Ih`eGE+XHImU+uckcN zEA)ICm*({NaBjq+2PYv7RvrOc#9Z@6_IvM9l!*+Vk+Y_7-@~+MqX`Q1BKpqSx7dpZ zx<d1&Gc1i3T>NLI;<l?%|G<+4zWl(0R_uSw_76e&y{4Fs;DQ6;U6xW;jk>J9MHfhR zhk9lFp9ozw6ERgZjcJb2CT*WL8Ut&!tefB-g*S&QgT>r1S5~znbuyP^xz_re>dfV- z;v<Wm{TVR7TuXfgepl)Z!87(Ttay=D>E+Ak9rrG;Muj-PH$TqToOQCBc$zz4GyjKb zVhKWQgH_o4oLro_Ryv8$CX*+`;yy9D?2K3C<h{(_`Ol#`c=?R1&`sUL4#ioJsTb}+ zOb}mmou=B^{BM;vh|Gs1Z~T2-fRh)Wi`UW&9_1f%T}R4doq?8G&wX#a1_-lI!pZGX zRg}PLv(BnvRHAIZw<hM=g$08_mgM0ekySZ$=Dee@oBm;psTY~+vrAs_|B^<cwWVUv zLvMd5fK?`_|0^_Jsys!he`a+V>=QznEn=Ay-C`Ly_G=~o(YQ6oacELOH7r+G7xeTi zSdAA)I^4VSU+m3O&%y)n=50W?^^d2=g@9L?*KTe<7-DFQES3a|k`U=ePE@$~{6GJQ zHkK~@8y2c!8guXNFO2RRZo?Chg}<AdvxEgNON~gm3b4%mV)FXA)%<NYEgD&~39Rl# zL22O)4Z4iNsOAI^>M)I1z#-=eGDJOfF0g%i?!M9A$MiUmX%Eol)LE*ejVpe<oZQ_7 z{#MrWec!8p6cO>r-%$6l$*EKU(vyGOvI9q3G+rM(AHTY4mIBWINY$TLKgG*3T~sa2 z4UZb&J`AAFdw>$OFxOsZD6Xr}qhFv?aOnAB)85!0g{DK-{OY3d8C4TE48R-Su#b=b zj0%50sK&@pVW+<197j)^&=hdIoSoax$4~y)!*|VyOyx+hNeWJ<>CO#;s&n8kV#arH zJ4J1V8(sg{R64OmhJF8W?fmtOd8dr2Rl+plWa%FNa9rr?j~pud*MwV{wTGMUHc?N! zE2{@!4_;7Xv_I<U;75ZgPg?NfVDr`j$E$F>_71~v11~pt%Ws`!+6$J7VXDFJu;y^8 z9mA~O@|wLay?1R{IjfW?^HU0V&}AkM3TGPm*+MfNeP|%KHCGzb_21h0K!f>3jo!x2 zEyLd9EKMFu54Q~U^RKV13#!cjvsrC%hV{1{tXt%3og<+aIMY?+XImhLO&2vT_P4*O z>eA?5G3n!2w*7ah^4h(H7v>df;nU3zWb5KzCa%8uXIsKFd2UbrP2;%xM92`$=1l3s zQuX9t9U*Tz4Noq;Ysk-E0ySJ+xOZ+ZHFk6^S9{8FdXMkAO<sie^B-{m_XZx!y-4^3 z;AnkU=A)3fSexMX!lT_Vy1nzeVws?farCh-pWoB4DfVd(n;~vi851&n7yrCtApiEu z@^Yf~n>enSj%t%H0dt0DFYDLOcLn%;4BMzn8mYHwn6sC=@P(N+>St~LKNY~}>TRKW zd0lf2UAn6sr)y9t3Ej?<%kR!qcO`6n$k__4S!jq_Y$gAI<y+i1{t~YqjE*_@Fo3>s z?^peue@(xy$X!#yondmRw@fg3^p5SGl+J#?D`!WX45)Gh5Cf{Z*P5Y#2dP^T+Mjnf zQY-G#D%aG*6HiF|_gmtnTPu=KLm8!xdqc_+$r?h|a-{SR!}k*`>1nb-gHq!a3A#&Z zHH_m#0o~VK^%+G8t@a~QS0<c9q@(v3R=25~^BnYRhoq)E*Hy@BOx|DH)8iIEKKCd8 zDxkmILB#--#hnhL0t6GABvtyvp6<3k2;7V6D_JgX7t%-$-GHP7mTb144%h<*h$dK( z9pUcFE>==1n#vKC@?Y*vq3j>Ge0h@q13O7a0B9Uj0Y?m2)zFN~-8<1oOB~hLI)_%y zU^GwbmIl0gmLYZK7?|?Ja!C9A{I$uq6AjnDkp>7hL`ItEg)a7d()slSSc;Fw%H-v5 zYm(5Cq|g&9l$@ItP+l$|$*=uEOB~tC?);jIMwPENIYTPv85mG{ac%M~3ebgxi6s8b zepnUSCB#vg+`kkc=@aZ1AmJTH3Mg?21wvB-A}VZe29FyLJgWO83A^=g+jrHnvkJRf zpPHLn=Qg=cc|E`f&&Mc>lh&ID#4c<y((F`EydCd2<`-r3hwai+i(PKnKetUr)2+)K z*X-YDCNDPo%Xa9!^gmVf-xT!b%U59)HTC<XRbe|c$^T}2{?NeJc+5a`sTD#mP525e zO8oXU?v5}y=dlFw6t@V{&&>}Z4?o4lKK`pJeP&pwQNZT_!BOU2xFq$p<KJzidm$Z+ zfd4JzpPW3c2v-;z5c1v)!AJ$<x1^RT+d~0m&b|2RN?-lSw5SN$hbt}@JlJQkgmtpA z_>HNK#@By0>9(?N22ot@+c?C}MGljCZ2pbl&xj3=4C76D*7eLQXP-V^gzCk&V*k`B zZyj=|$CCt5>%P*|W)AgP`Rv5{2J6&m8*?vmb(j)MytoN^$oamlMGfrO(w3&S)~@(K z4G%wR>r*H#DRtkVNUhbqF<K{Q`FpTZ=To36C~{6xTZU9I1^OZLE#Kl!fbQFrel&o_ z<x@gMv<*VkOI`9~y;Q{S002fzV2X!Up5gNFq8w1tt|dIvP`1}f@tDkYX1fmIYkHEQ z-Al+x3iG@EY00560+T2GE6jdy8rj%Cz-u7gaC!b$k-4alKxlmcqIJTyb>yyqPc<)s z-TTvu@8ko-_`yx+Z%kj<6l6gH0|LA}A$~3bA*t+iY>%?WA*sNtni8^U#{p1b2>iR} zQut|a?bNwq!}qyVp%b{Zoa_0#D5pA+4kA?R(RbO~>v%ar3sgBeHEXMDFyabUOeL7a z^WbnTzPDmP%VF~AV4kn6`|fIdOsyl)haxwRfvSbJ=Oysgm8ss#F^4;}cniDfzL~XE z@nu)}Jn)FsSq@z;rhH_JqRgg;Ez0+ML2N2dwb}m0S;JZcAUIDhhQ?uXBHxaAHKVBW zo9)@NBynF_2T62K^t}>iz%Fi28~;s&7j(LqI`-nFc&ACPA0Z1Ibn&D@nyOZ8n$#Hs zuz1<vx@nCb?{m|b@Hc`3y7t`Vq2;0t8ZY~kGllqKS14j#@>XWYLisUXH${5b7d5>q z&&a?$!@q2R^!j9$OR)Xz=NM1@H9fur>1E+EVz06Znb&rmDpmh^_=2bVeT6BU@c%9e z{S*2`j3gZ*Qk62Lw!Y-jyQCs=yD3liIv3lXTJq5RW&si5Il`zhXqe1|{oAj{?^_7A zEL#Ly0OUOZymk7*-#N}2N?ranm;X5ZGemI@%f*%qO3%YHLT;Wu$qnG`_kfO#HgSeF ze>-f_bad%eS$9$Y(iWh}J1s42=pvvxwko-=3zdr0D+sW<@GP#v@x~pxY&ImWO=!N) zxK@a_&r8u_ArodXXOLOlS|`1>*o!v(vG9w(V$l8ie?|Y}xp^u0bL`$CRBIE-@8b`0 zU7oyh^IiXo#|JlUP5sl9OY2K-7}aIIOaVz3(lU2998kaDX^O$^xa2b{^py(OtCVwm zJ;FD8+5~OPc35x(m4)~nY^5(HbS8G2g*{N)twWwcMa{9~wt67gxJd!0YF{~j_3!aJ z=<MzA4-vO;*>GZ!=#8WMu9F*9yuN}I<V>ApR5+~NWHRU6NuGzQSaUHZ6c|thJFmNU zc+pJsvBjVGr?O4*;_3!MynsDL@u%^G`u5x5ya5lUp7cPKiplw*g@Z%W_lxz{vD^gr z?atDB=REg|cnMvu>U?gx7YO^I$W#C~Q>nmt!Yt2;Q`xk;!|oPsotv=DQV58NH_ZJ+ z!d}MfEqt=o!qCqI>ne!<mCsORJ{jc>ty)nQP(^zFz`F9{<lZgXYRg9DyK&Zy#o7Pt zzI;v-`WSj{1km?_{yqYRx0SoiiEXJ%S<tZ07A+{3)3lo;<Q|{4_MiS?C+E{&9eMP8 zc<rpg0VBt)rLKWzk7d!hU%*va{Wbj5P`$TXo`*m4MC>@F-*_{dhoptS@U;Hty@m{R zZ+0Ep{3C3!=z<l&i!L0%*@rPX>J6t=J^e)sQjJ^Q`e83o8$Zp_Ztp-O>4N?h4az+g zEbZeuQzyN`j)=F$^K*PsRET)`=c_R~q&#(5tPO5u(GAQi`-!c))0nPr+0BEx9$@{0 zmKNnOQ{{SaO?`j}wKzfwEWf+fEemaIdP>jxJnE;gR`q3W516-2@!2bv&oJCw-oLf0 zDD(p(Z`^|ozfj1WyV3jS1SmKJnJ^^KB>_Ebf-@o$D<ex6@Uefm`B}0CD<{A7>92KH zCn?+mE4PjnaeWY>MMx~A2<MX|qe-&T4Dl1Adu5IHZ`drU={AUa0Rh$I?#~)v?555U z$lQbXb1Gfvfbl#qw|`hkZ*xi1>s!ni7I8$9l_!hDa040$+<jas+yoJHK0I?t8if^= z#Y$ENo6glQ*qwoQ0Clt&qPx(m<pcNA@rh_<(<Upqd|;MRWcM2OQ!!3+4kB4O2t#Vr z9!EG@3Orw@OX>pqN31wq9y*O-;m&lq!7cf9E9ohkY->2T;pEqgzD*d2N<B%!hAgy+ zgm(&x?2=?r$gz9mhw?x`=Riw!-BlCdk7$ZiKGJkB@{5MGWXj5e8l==F(yxUCpLif{ z6GAGaNM`oZ74A6z0H+Qf%AUN_@xYC9h_r9LaJD!kN!S4auzJgSp!lREA|`ajNKXbC zK6T8Hjc14%kR*neL=#BTV|5~tSabffa!N=^-|uW<gk%_5*lWowoi4cv6fq)<IB`9V z=M=$(Nqviy{Y(;~WJ;wj39n$^>NZ#*?)?rO>urTdc+pe2UE11Qgr2%sWGjpF<6;l! z(&cSJ2r^;9MJ6ix73RL-U!;T&mKcphjA8RS{cqa<??eL;p!AyfI(i3L^u~Jn&Tv_q zl|<z-DQU&pGVN;hl4J}M@&(Cv(@~_HZakwP=RxXL(ouSY2kisJ*Mt5LipS;oh5o1W zw{sFP0c0~n(I?rB=p(X(0YfBMKqY!tH^T|=QAp(wE8>NeG$6}ulHf#=<2|hOCJ7P4 z5N!bi*3v}nmL#lfMdQd?FQ)2BQ%yJ>v>z3p9@`O)LHch}>eeHLcIg5wuIe@cQldel zR*mmlSA>tVQ4fTaCn-V)$oBNYehn02lOfWNbrxpoOw!S+bX_6+)5}*>*(zT<>{>io zE}9%xO4d2PFFVK-J4_KlV?_*rqJ>DgP6%l0vx5f-yw%Tl2QQ_@Ffz^l(L|SACy8kQ zRkZ>&T?0<#{`bF_4axajDOcFu`4Q8UAm!gIDHKY4W+@ocA%`J#4Ts3|TA#L$d3;Y$ z<s=iyx2ZhY*dkjBL_l(+oVdm9$V=QUh}~?5LA=<5shd06*78e=8=v`q+>;H&^7mq8 zOBj+fz6d3(Ty+ylg(B-k5*;J!a7T@oB0ua*ZRy5HsIVsqvZebwVxt*Y%#zqxyVZx8 zD)+hq6Dt`QQgRz8W<!z^50b=PmGhvB@E17%N)U_Lh|InRPG3P!?^;<RpTTD!n!DFi z8331nFhnRp$XS8Rm+M@tAdeD{rpr!1UVN*w04yTLND__OWGz3FUnF7q`*RAQS93Av zb=3aBtW#l2auXy`FKjdFNB6xY>BMxG+fDvHg_=`qY)3U@!_8qbTr?3Ydm@T`yO<|j zymYI!WUOuFM{7~J3MC+y4=FT(dq_gRAJoZP3!YgLjb=zEX-W9rI=}iPZZX2}FKO=x zD6<LV(<Mp!lpI60q!(SvwPNkI6tXQ<EG8S7Hy|RP?QNlk7dptYp-WI!wD<(B8&+@( ziDlJJa#;x2DDPc5y+1yo^a8H<VuyuDFP6RdpUz`wAb~D7MVA(>KUgyiy4xsXR&@HM zyu=~aR1P_Q*dm*LPC<L0Kb9iv1eC~E$bfO5Eg(xd*Y`#@NZOE2X}Xe1$Oscss6>au zUPDEb6Y8N50Olv@YzL>j3m*2DZdgLp(=89^a);@1Yn{PUVlpR(Kob@tq*VmKX&uCM z$~#5?hd~MtEXf_F2y0}IAJBcXVxN_e77;Dh??CEGboo_^DJEO?a4|jCN^XiE2OwTe zoyh_$N=`g*_(|${gz~sy_~HO7f&hw}E{WYBi3F0w!$@LQSkXw0e_sD^R$`%t84cT{ zlk!G6J7DPX!^nnH1W~t@zd*#)qU`QfQCZUdo_m{u#53kQROyO6cH(q52x`sv-%+as zQ&Ic}P$KMFxWi*&Y=8nAe%_|((S;17k>S2T4Vk4p3{sqM-|-k%N+638kntiv#c8W4 z8hErlLw0J((-a%|J|gn&Q>y-omD&0~GjyqEK#`L;l3ZH{;sCp(a^XU2>V==WPfL(s zbw(E^Te}%6R)kDnR`+vybL!kr2cPfVAZqS`Uu7^ucm?Xf6p`-7=B9uV^>9QB5U@#- zt7h8{*^>4qMD?nrGYLL|lpdi=mj-?{#pFE=SN$hj)P|H=MxM4qR>*gBa7QOWW8v#0 z(dvVwr#Mw3hWHp($_n<Wr_R?oKuRN8ys^`BG)O^OROIMAf*c?>hLyCV-`*V3Ip7(F zIOV1*k0ZD+{lKzqvfKe(Dl$Ygh7O-%$kqImWycT*q>!1zQk~xOr|V^5B=|ehFq6*a zo9n=?NEef{cH(Pn=mxPlh<vQ@$=X2CfFcG>PCzv>yEFLKm(ss?neLP+jnfgoSYmc7 z@M9cEF;t=yTfSCT-fQQP-Zw;Ke0!xC+`LrlL53d!MTU{mHivQuvQ(sa8P}XaS9sN5 zy6ka^=n+W*j+Nm)BP^Z~69+^+uaK%PIZowyLSzW%FA2t4gC_YzV<t5-BSco@<+?m$ zEsPv%;yqfhVQ6x}AKzVB2T6?|n>NF@m#H`6$r6J|1XI&}|80i{S>)Z4XLW!y2I*D% zltxcfj+^rS3lu{vMG@#y%pAE$qzLnx1a2e=GBO&?BYukXDVlj>OF<EsLUOtYuUV1^ zql=!W%SL0hhZG4X%52t`Z(BD>u5wA(1}R0bdFBkkG%oq~bB1pem+uN9gmn?YBhPCY z*$G%-6QESg-4N3ykxun{*wcnSwT8TDqRv1sgC#dHg6Wwm3E!KA&#!6=JQt5aYHntU zr{uryzfeFPYeB4;Eb5<b^_85t=rD?x@FL5WE=fmIh0C#hwME^|5I{tOY#S=>W$)|M z$Fkjf?4Mg*!wQ=t#YadoN>mZt>6aFYS7uk`l7MBsD{eoj@CnB3p=G!Hs^nXA?K-gT z01GF6yWY54dzbOx(Op}@>h0rNQ531F!T8}QRaD~#rw-%R8eQ_xIZW?JxGAa+^hT$* z$$X~N_~a$>MgNj+3sxFKN;3vt{6>ODJG=}y{;KwM@FMOmngq84O85e0Tm{a&Tau8* ziaL=cdKn%m)SAj**|=CyjGO2R^0Iu~Guldehb^X)VSm?Ft{i(hU6asvKGQx>6os_} zx`f^Ty=nQ-?7U6yvyXdl)@K6HM`Q|Xx_9+XV*kErlh@~$CYfy4u8lEJhVY+xD_z=d z%10L{I(JhdnlbtBQMM>aoQSP67tR=1=2c(n@jN4E*_6fkTy&A~g6!b{y(OhlDXRp0 z<~+S<1uM53WPK3$jG`kpu~I)X`ceFqhX<nQG5jBfw14b))*l7`yE5Js0*$T@V~Cwl z2u*$LHPbA66eQt{6u<FQw8Km`9%!(EmEP3=<@_#-S%Us>3n!F0?8S=}0{D6@MQFeb zRnS{#l_bimn<bu&21+!2SIYY#x|!CyJa2q|Nl*!VQP+8UabG3p<<j*yJX^guLz3iQ zdPo1X+L+waPo86?FY{=b*2b9b4s#Wej?g<$vrzaLkUt*<DIunnV$15UTOTll#Fuz) z3r*h%etq~U3``x(X}-}-ey(ls0^Ne{cM(gVH_N=*(DtRyGN^0EY*nAc;nMSd_70!C z|Bf2q`+l~zwd#JVFH2FIccSx5S5i7j&J_u%m4|g$js@1hewOq3i#$B3b2n)uIlim= zk3Q=Nxqk!A|JPZ-V(n_avJi5ZEK^JpT#UV2y|B@@Ay-cd+02&a_1^Nv>U7IG0;$QI zJgD28g7i%Bh{2MMC6hR;yL=pc7|1UVc-KahUPSy)eOw4P0`L1<mr4?af4O~j>K%zR z0sXsIJ3Xn)4%n2)*&%tt(7Q4>RJjO<O|l>$MUJ0mIr;Tg^1?e~WDEY)?=`YS`Et_T zFK}7pv+iQl!~?Nbd9h*3$gU4%G&_-Cx=17Pk~U6`yBYzkz4(+2;m8)TZ9|xOR3BRB ztZCO;MK08OS7kKMo5!qTD8K&+dGq?;tz#f23*9h$OY2g1(g~M-<4A?UmAMyL`gg}} zn_eI5;1E?i9k=$kZ+La&t-8m0tLHMul^NrRPxrXAJi<NAF0`$g)xnHfX4}WpN2OLB zF6)PfJ-+=wIYP@Yd3p0K^@9C;8|mXwgp^9Y*!`rArf~4b3n&l34E)Z_-CUuU_o12s z9o=p8Cs%||Uw;nc_v=bt8Kf`6TWjiVj{jEpebMjS{?Kvd<Ey;WKSyb}4<CL%EtocO zKSF=K{|}!x+I7F_;*<HjkLnR)qL&2j3%GTLg*{QPQq2;5NqWmVkSV<~XJoz8^8M4n z$Oop&p3PF_-LKuBZ~lmTR_P=e^9evaX9fuFuLydt6+dcRzrs8bFkW@a<TpOv5q@iO z($jb;L-q!zZ>B<ilkinMa9=?6hnFj#Np&XJ*<inCmlt==(?$SLI8t{f_J=$;+x%m| zbguaz@ll@n(NKnj*{`J45!3pZz7gdk=~9mZweV}DsC~|u!T_~%4TAV%53qA(Xlup1 zx?pMCT*$FIb=dr7u$^yB;<uroJIGz}8N$i@=V7DvLwq(W=pA(ky;qo3XI{25yX@ih z$dv~$9Di2;MT_6R<@;r|_N;Qp$YTk!`rO(A^ZFFr*;r4XyT$j~lGGPdG)8A9@HN(u zG0HwC)gi5+B7Mw!v)Z*lKeuEhsAJ06G5m=-5HVwB^PPEOZ}F#B_>K9Vfk^>o9ui+y z|3muxhDZ4d>)k(HG3Wwwy2gQ%Cu{w2j=~(L+a0AnwK@S!=4{o~=jt2!+&$|Er7_bl z7gyEr>tUUX4*@Cq{06C3@Sy4qcNW*_8h^BC#=F*$=r^dJsSgMzTFYD-`_(J~^>*50 zzh_@QH!XL6b^Y<yw7czI?u+t~$0NG8)~e2$-D+_i*QLon<^${!qLnA{r(l3nzb0(O zVmR!*MxTjYc_e^YufB$u|1y}IZ}={F>WuNg*n_9Wl`EgeU6gJc%)CjL%RgMw`@MYD zq}l*|Hubpo5uX<G&?_$BDCx-1<LbsWV^qmZRb)Z3_T!UW)9e+$A;$kIaE|%6@07%v zw*~UwJ~yxBcE-CqGWsm)*-r5r%@;2ej=!^LKMImh?5Hj68#|w~i~+s7!|58TW63`k z{*%-{Z36@#$NqHTxOMg-MT}wqGt4tz(n)AOz>h^rR`Jiuzwcjls_o|dyXuEHkK=u= zVf{Rz%U5FS&AB;Ib_}`K7f~^b(+VSHd$K3fJ5vU<*tNeiPQHR|a2w-qlL9y3If{J_ z85ZcMrrM;d=>{#N@OW0&Lhg!ieHX|7adaPUN&Rmhzz;(aM8S<4_e^nb1)RCkG)Gyv zS88ZlYFY@0yU;X8R=Bm&w5+VG5S*2TW~F6?Bg59$m1S8z{GRLL58#5s;X3#IdB5J) zkJZXD@bi)%$-?G>NIu0dO0}t7$l*;@w_vIk@D_0WR~cOc*^D>-%^Z@M?<u3^v1QhE zQQ&|ZV*7UHz`<3!-;&iaqQ29SQn$N>G?oZwbNM|gCl{j}h6(mzT()#q{Gb6HM3%nP zq}rBAcY5W2#-+EFWO=Pw%UJ$gjgYHzTlk=jr$*T+fQ&j<>?;XpmmOn%EIRyU(%#m@ zHqJgO=$nGD)nY_ZD6LWDak!gKSD@{#&S>eGZhxZmjk6JgcD}CgA(J$<GxBATs`o|T zepksfO392;8d@H~tqmZ8!`V`Uej~Q^18|^HBfs9S!0C3uSmxsw^yx^Y1v(pLwAf?* z7w>AESYDKzQ)Jqaq;9}rWA6U?XxPYcy@s5=t0@+#@Ec${%Jy}IBi2o3Fhkat0%TIS zO*<<6T<EUE^3vFA#-;1+`PvVmWZcIt#kVY|wV)H})YmBaK8%ol<OIssgQGOJBABC^ z^kwO1bi8}9=wPu3-@5_H<}+b_H$m`K7lyu<IiEW@TH=~C?|8CYH6+j$5%jT1u4J@8 zwZ6eMzX6(F3;4bH%r5axpU3zYA2xgcVzT<ip4RG~;)u(jl4GPKGp9;njyVCbr<;SB zUMbK?n^R~_Jbu%N^UC47iS%i76ndMi^32}k?6LGF*<R}*o5Av`TymrAmo=}jfi+}G zAw({oG#Fif{B45-!|p|myOw93sG&k^yl(k(T|tXf`FC}xMr-<CX(_Fc{tcVHovTQz z&kgXvdOgCc6=Cb&4P_xrf}G;KyN$NVSUKtV!;K$Ox9O8-Pj567Oip{K@>9#=SDNH6 z0<K2a)WlCcm36u;Q)0%jMutRFWE;6cE%6B#g#()8e*ms&H%&@o1|e|4vE|T@p7+hq z%m=+}FR(NM6-Pa7DqV^Q4*g#J|8<OauRNACOGOlfXtHF>C$>lfMZv!~y7ifwT3<vz z>V6W|)tMXjh^8aWUE)=@{ru|+Q_n2tMM}4YxJi96LH!X__icoHF#Ekw4A-El)-n0P zxE$rTR}%L=9;M^@^5n9=2|fR_`lQZX?TqDhg#3nw*~F%ftk8Eh9-3XV6Y-?7B->sy zBoTqLPFsa%;~RbRIM<l})IJ7Yt+T9~lC?F>LuBy2wl6#oHm?{8*w2`g>}$_ANH0es zUxH=Z7|>mrCMXh~8ZpC)B>gyNoa+&(u;u4gemtV6c$lhqGiNhoFIz0u`<&cGrjXS= zxA?Ct_9=+XSc|a(I$MM)Ri~2XA}cLM;&N{N<qc`sub$mKrE&ABQQttuWMXm_QEDDL z;t*0^bZS~mou%&X<UN4MWN~Cy88B1Jf1<h3zx~yHgbl<MCOD)f*<0wnW+IlwhrT*j zZ+o<#3fZd~);BL%Emd;I!5xwK6rzB-S$YWTk1{WdT3+xAFyGuEAf&oD3aO5t>5C^< zt{utM3KYg)wQy-KJS-x+jTw0$1r<AGU#<G-SCrM~G^O~QO2tnK1xBO4j^!Jr%jKlF zl_!FVBlcC^_H|A*+a$o<xtj)Cle)*XUX})ITE8F1+nVTJ>Uka(rP{-#IW+h99{Rd1 ztC{!d)t>7a`VddQK|f(b`w3M0(PKUdH{6_pW|i(eulers`rw<-sYTJGC`D3dAa!4H z(PGM#nd)#ii|t@|Zsm_pIy0hxDIq_H?|RDro{NIc9!ADp;)~wH_qyqMMb^8WmH+TK zvh=mOlgv~9LSHZX_2w5Jn-V<jcf!66tV(a1_}z0Q2bSBI3G&~MwVY<j$a6$ZzzoqQ z8M%c=RdH4Ri%`~yz;N)WM=W8<kW8z%V@Hm|^|jDgEv)1*#Ky{LFFC^nhB)ZsA(<Pf zzhrn5PI4(+a$|%lbmH**I_i2ilFJp@#3PPYA3Y*TzGG^_pvVYnyfR{fB20`_Z^!mw z1&FpB$4_jPB-}|9Q)|a?R$`@IiT)f2(~FSR62bC*9;_t`U^#^ycZp9p`_JJDmo>#U z@xq6=3fDnE$ZIOq`tasY)C3u^!~360*~XRby+gZuLPOU>`*;C-KHTjl=ft|7Q;L7e z2FvJVMA$`~3Z@-1%SE0IM*t+abQN9n92{8L(dEf0|6$|+xPpX8IjfggHVLr|SPiGC z)$kC4i1Qog!m-iNQV6hF>AbT7KgvNcneaGbs)R(5PmRF_L-e3YKCwE7v8p`w)35Ib zva?ZSjcofwOD>WM?-h*P*DT_vR1MvVss^Htnj`L!OpZrcdHp=@3(6V9QCoUEUQD1z z;<F!*GHRsFT+2m)Psm&zVu4X|tL?aV=Gl;*qwH|K!JqNjBU<;uwPw0wM{u@pfP@>? zqMbNHY-kj)f@HFgzj3IWG6u`qvKzV)c3N28ZRCd`#C;O#BMar8RcRw*IM#DqQc~wL z4mm#rA7TWGB~+~j?kSZbS&Z(8(z;PwujFT}v0#dPGXsgJ(Grv`Vpb!5<HYRLy&PXV z$qXS!{KZ0Vh<!Z<hc+SinTt&|oD->%{AqRy1m64gnB>Sr?EP-hHl}nJP&;U;Y;pso z^}~K-ufk^@e1RLYh?jhtS=F%Ya1bVaSx9$>CCcHVjLi|^4K(=~CG3wB=>SwMOEi92 z?v;f8I9hYoA1C_?85)g0S&s6+LtIGU`2nNZO_8?Aq<brRwH^irsZLE?rI1y#;+JBv zL86yfA~j_AqZQE=?4^Y*(Fa(8v?)@`gjX{~Tl0u~Kzti-wu2Y1CyRCUP%mrM{jIeQ z)pPvB71_#19>DD&Gn^#=kqa|{A^&L~)lWO1pe?sI62a)P>8-k8VTt6Dk%HQGA^=+H z&iynDi>@>may~F=bMe59v==z}d?B$Pc+`__{Q^8fIWTO71h>tvT|}P<@;5FC7cJw8 zbhAWdPgJ%6VqdXhVynLY;4M3F-JgNdW$41YB*eU$Sa@yOvvRv1=zQJasL&|onTfdd z6_H9m)Ii4xHEop6N`o4JS^&wGgd^(P^#G>wv-2nP2edqhDEG=F;WR`O7p5fVWcpj? z1sVS3oKJeNC4N7u35S}R5`Dmg*W!?0x{>T2@plXn*NjAe&npJ!sy2b+?Yv!GE$}BK zlMMb&$(Li4;MAH07BWMoLEct&7M<T2i8#-TZv+D=pBsqSwpR?%4HA6gh8`4hkw}d^ zkaq4jK7FAZT>~I`{m$KR7JI`?gHGYW69*?ituF;3C$iWES@cYYC<867BOzKeD*lgk zxh3)X)EZS6diXOSA~y+J$BPekr~i3{AK6IZ-4gXAdPyd#{2;j9XE<$Dq^O-2yNwfk zpRg4_nTM9B3yosqv8vo`w~b8rOgD;)&Tl0n&6Z?tS7By>u0x*ME0*GH{PBMnq(Tq! z79M`G8<kgx0PcwY^z5Bz+}*N;YG)L-lMw${Vx9L;@#<Pa2G|cTb2vIq<G3BYOKeX@ zE9MLl#V5=C0Yr0{sApW|EoPI5M$gozwsCUOJtn*hpZ5-3jktf+#4Zcb&@q}Swt!0= zBf=|r@bP$$mf+r^3p(ycQ0s3{=NP>`q{`PM#9J1Mht*rab%jKfjFNA4rXzasqCt)4 z)5>wDQ*9!Dh`wNo0cc|(j(*F1)%`UV<2dpA0K67|XM>ykjNx}j=w>y#OWXz3`T36M z-jjT^=zT^ozKXG@wQu5&nv;k0?hA!ybj7yusCtIzAFN)|2CcdWH6Z77cmauwf?vSv zE&YktqC;13D0a6pz(oQ$1a#q6@4VcHp_@zw>g`<&J3)Ei?GApc#tvYKo+&gzf)zG! z%mb@dMU2A~-3Kz)6hn)Mbqw)3oOpIqKpj)iSSarkPo7AXzoMCQI7)U4FI-an=y!zi zrvsv$eu%YU<s(6&W%}oyzLZ;QK-ORpjSS@e=}fc*i<ijKQtJ3{%X=G-+_{r=dwJI@ zJfeG8{7W}O_S(>mRq7@W)sD9Zy2VLpYPe0UcS3vny%3v|Mg;`a3#L#bSv+UeA~V7K z1P&z|lRSPtNBxOYL=(P}g%G51?%XAt97xaq;j%N3&|B?o2g%;XAx&{&ifNM4{X?}# zGs0Zy!B=H}yREjFsEaJixAMw2Ls4iu71GD#guxxLRxF}*Mf06yJ{z60wIUkFK(X=q znpqK9)vg=(a3(jYBJKRzIx^etLU6gy55e#4wvSJnw#E>=*<WFsfvR8>hHRtO+QvSV zk`A3Xy!*arGax=n6dxXiUkpcRR9mj&u5RECn$sil3tYNz2arwOd3v&NDXpiA=Vd}T zku<u#H|o}k$UUa)8=jv0t%}#H$e9(@XC@bft#dZ;BDar-dC7_Wn-)tShVO7g06;Vz zhx#w@I`7)#eYIz;%R`@Wh`|@A)HLy*3^=?5ep}Dzzc85%mT2YY`wAG@8_`B%40sS5 z6?*UC;dL4EMAtem?lD6^ha=t6+Dt=t2D!J<!4P@vBGJ|rmu2lKg<r@wfT&HHBm~q^ zB-`%vMDWd^mT_u*?c#qK;`)_hwM=m<4vLnIxWu^pzJHSXSIVSG?LJ9_1DMvzixTLp z>Bpk)x>4_O@*7N1FGyICn#np#^cD-zEcipYg?=A0vNDl;28&XCi-fH^o!cL5H>**8 zN2~&^sd``eH>*egce1|3M0ArKBm(;cYrh3}_2LjUEYW-2{nCku=5D)7D-!NSW-od0 zCk&DAF4Hp?ch4uOKLi0Ub=6uM+<W{`gG~4P0OC3Yd6#tL3F*~rD|&WRlr8W#$)f&d z@*e5%uhTX${;Gt?<RrpQUa=qI0vY!^Rb`zaP}UKN{*N~9i)nc&E9OfMD9XKhjN;-y z%%#IhNga={sNNN?HJsQu9l44|-NPeX^x@YSqC7J3wZ@?ybm5!i1ub^px-HU|={t$l zdEFMm!z0}~ENULZrGpOMA|oGg;Weyc=EbB}IFpWkbJpzh!vkVtSh)Cm*}E&qRV-{3 zn;RK_Z*2~7w)+N~C95-$#KfXjo6Z@mBF9MZMf~1>=ixUqkkWmQ09pdG7d0O)_6`tB zypeADS!9a^Z)SN9c8jmP-1Bgy*2;Ie^r~7N2@z$lc8o1@c<T=N<g=NRULz}_kibYm z3GnZ5xh;nslb0-)orbH8jjjnBBG<S*vpvd>amY1nP<v!?+CZMj!E<Z?SU(`hMCf0; zcK!?~#aQ@aX#S-Q;DAp+=Bf#bfkiH*QPSN_uCPV_0^%>oPW9aB9iC|S&*sWQ%a2x3 z@5WKhGVl2~@r@;e2_=a^tk@@X)sJwOSG?2i(IIAb=n4iquc$f<Eb65pDAY7w$0Al) zDhv3fC;}?(5~|EZ(}jq0*yq+87FCibc~th%HJ0!LR{ZW><UmH$S(fNhnv1qQdjEh- zT-x~9JJ=<LIHBe;_v&|QZm(;q2n&)e>u&!ED}jozGBFi@$8-#g@EO^l32Cyjtz_S| z?TBu?m3^~vqS_A?e(1m*Eme_D)Gh+9hS8mDP>nTKeM>?xS%?SS@c1R<!#}HRc`ar) za>=v{Jb|nQ$X=gBnL0@68IgB9_(yW0-SoQS_1&&{h+_bdDI&fJuzkw2q<*HiqXVoe z?C2j~94W=TZU|F8EcQ!7^WA`~t2+E1L-RZy-ZJ`Oim88Aa9ifa%}(6g@WL^};~LV8 zKZ>eKI3p@a@O=(q1hDGYg<GMfsBYk3(X5!k+MrjQRmFp02MYv)JN~NaSIPCEW}B9O zWOYkS>eeZ>xyb+CleYvGx6!?)pgr0L@=iEaYrUMv-RGd0lxi~`Xt4#Lf6ML+UA0Vl zYncdNzMEaS=kkr%nHwOchreo<?|QF;*Ys*QJ9&0#=*?8Z8+%~9#=q{)w;3})Ip$Qe zB`T;j`z3SV)mNR0&l8_~zGyr2{LQV@ANRg3w2XbQ2}`p68x{Ag{!wx0t(1>%UVaJg zju<+lb>P+4(B6cXT`@;qy?=Y>-*(UXo$spGy)S*;z2I&vWqV{{IBPxjTl=ltTG|BU z&9uq${I>m%o5O1B%r4Yyz>m23ANX|eOs_wLS*Bv|`lBw@-ukFqOU_%(*dwp*Mq1|H z@}7XOe)EpfHfVXDo4qt#l3y4#<RsMI@Tq^o%vcC|@Y^(HBmLr)xM>~p_-)~fpGS7C zt28+R?cnf{u5TxQt$uvocKE};zt>1}@9&R%S2YJb5?U{(EiH3&2d?Qot&49Y2!u?` zmoXiL!D7NCuiFzNHlHrZ3p*cFxxzOC@EtLiXmp8K6<3#rxSE*yIc-Hp?Yd<3PSSm- zymTB<<Yt)5@**bpw!fR=o7)pH3U%#sqc(ATwT~6`SH{k$WLKycC>g?MV2Vj>xckMl zUlMLor*ia0F566UKV8n4<s9|3{nEScYrp*B=$_NR6Pho37tY094oI6BQ6x!fA(dci zl`B0X{4tWV_=V=!niSH+*V{!)4KdO$_bR!mW<48?tBGizfJw!wRJ2=m-ClN4*-5eg zU8ay-kw>di&(E?@&kdU^SD;yc9n}umELy5hjV#itj<TI`sXUauOp^_8F^Q4&PMnLW zajV~I>pvBe2dz5&>dCQ#$KPiBeD`aUcJ;w&zbyI%r$2L=vZuQ4wh}lBIXL1aee+*! z0-&Hp%PTj1cr325pEi1}?yiV*uFCn{7qWSJuGYCK12LBpdI^(@le&p+wI%0Y)J!Mi z4rEm3Ect6IYNopFRh3%Knw(Bvs*S4&$h4tL`h`T$q{0|Q?w1laB823C#h(2t(b{T4 z6)ESkT$N9Ggv!*Me!2xa)cYdn<hP8EAOGt-O_^A{9MU>Zt3K8R(jf>}Cr8)qxU2mr zx{w<ppRZC=miw#asfy`L^m(<s7I((&(Ab(B>4ug|Ugyv0#=YH}=%xrXACKWbIn@l4 z_00UM6mzjkPeLyBP?uqI7IUtp+DGN?U{!QYZQG@+#0O_CB;e#>3c@1|ZI`ltjYZd8 zaGP*FcQCV7^WgDcQGZUZaO6Jha{PPulj@$X)i}wRXRFOB10qLo3Xz)=G#(tKGJE}C zV)C>pY62qF#~tBgtx%pd>Vdb3RgT%I^h_2-rTK!-WBphY?|5g`Cz(a1_7*)^q@|1& z6ZsT36Vu1DR}}tt<W6&<=nz&QE`}qm>P_m-N*kzFGYc|k!etRtRO!VI*p5~B0DL!# zqS`LvHlsgzY1P%gIDl5&KW|!ndXX*luN!8VUS60BrQ@PD+#Kkj5`F&>qLlu7t&M@Y z8jOM3?DX7t^c_<{Y+b4{aoX&L|5?w`IqB&V4<YxB+T^cb=?#)Fkv<?65#1>3dT(aI zTi5{brpb(TtNEB)pNZgsrFT2i9XIk=(c52-D^P|a5v@}3PZ#9tm@t#Z9@MF)&XP?e zA?y|Z+gC=5iaDCGCd-=FPsM{3|N0eZoBN|4XnEGX#zh%si*yV}!zATT4)3H`p@RAZ zsmJ{iMs5S$gZ{CY4P9rESv@-Xc&p{@j<T;I{-T#%lT_}7LqIoo^6H;sx-HLo32W=R z8-~Flz}ax2a?{q*b^;|Rwb#4SjZm!rgQhbz4b%4RIhzs!QQ#E{8D^Rw9Q!Hy!2`u6 z2Y>IaIq!PtTTj7hzX8$Xl?BLq`~nNs-1XD0O)7V-^JyD*oDxeZd(&tk+>jR2^8@n| zUJt6g8=*y}gLn}WYbr_lP3=gzpJL6ZyUubda(CsL$NApqpd01L-F{c()g|b9Mg-9U z`{?v%EHT|1bDG84%{CS``9|HnDE{tqN_TlKPR*+!VQK32<9-mmZ3y}NaNx}g@2<(r z?X3>D22tFZ7LvJ=DjxYYS*bMAGrhIRDU}qZ+ZLtoo)j;&Q%YF$SmSX<=?$J&C!?fW z$<88?tbM5>&KM8LFAM4AMOpTxDs9tE<)ls9%H$XYLkYLz^kc6lKYq>VOLcV&mkdda zZ?e#x9JJ1yD>^txl)j1{(vEE?-1k&nYWx>e-?zNzMrV^)0n`27tGt<~X+Z;`=Nsex zt`~<*3#L?<L9M<#@kHXfLT6_|`kCVHfcj_h{EuAwYr*)!@OC+4)1dNSOq30ah4c@n zI;NG66^T^FG+F!m7@2UM9}JE=Kd1>HuAovEBc++>wyV>><=5s#tO;M#0N)8w&-yvJ zu2GtH_&{k+$S&1hrYq>yNYQ?KqGVsDkhw=5;xJ=pTnX8F>>}q=_~{j@)E7R?Hsx_q zSUsoh-+XrgYFLbRH!|Y(&8MBmbtPirMWp)+yLw*D6i9ufs{H=ts%3dI><wnc>^C2p zveC1c^>k^h`2}LR`F2Tm-+WhV^Z0`BZ|k-5x60M#=v5|@@E~%eLa((j&^^V83-b{4 zeZtm%rJgw!A0<75nb%e_f%`JPv5qetzw@Ex@+S9*)Ls6FlXgS7qaRiEJ=XltWG4Ue zwG=sBu#t!T8uCKDSz<p^V4sThJa#FPkq5DGX$_@Wm60;+ftk(=Jz`<qkt%H}^2d9; zY=eSnF>@~a$Hnh{zIaz%QAFO|qQ(T_J{>8&(?5EZwC9cjL%KtLo$O+oh^fqu7X;t= z!VdU6;r*mM>0_ZI4*j|5&8kwf|J2;ne^-hIZrn}z6P|2{?Lj$TpU^Qk-kW@X`B<3s zGDh9`V9Bjjk=W6teeBT!rBgk%M52Q8Xw7${;f|XJ4%e$Qf~qtO3C&e9YZZ;pYMlo| z8UE>PnOh_gE9?o)FmI~jkmo2T*0J~?1Cq^sTj2Q5RQI$dRr)C(qO%=Pbyvh}`D$G5 ze)~Tt-$0HEk4Lk8HgML9+^AG{cJcmwkRa!-ps+Em{qbX;{EauwQUGt56E&>%sGc7y z>7U|wDnkF`Ltj;ZH}_xt_F~D0c$Kc{9hz37aCymfg|mX{zg_q|cyv5Tk!?MBeQly> zj8m_mUR!XSix%C}u4v^)b>ma4J)nCsg+e^2*}q^u7+P?53B;@W)m6MGwB!y`uMb3S zKTr@5@;|CCBfdB+(=vofZ_=+xseyTO8QD$9T#AtQ%H7gwdaOqqxe4YY-zGUJ&kD^y zyIS=eP2XoD?9DBmxGUjxPofAQYs?4-Fld?6O$mJ#j0<7{S=kd;l*EK-gkDuqvdJpE zT31u>#zrWlP+)XH^+&<R0K}@0YP|xn8l~75LM&Fm7ByfC>wEz_81Rc$wfBLjp^GyV z_{%ap-dzIihxzCZ?Alp|HR>1p`?WU_du42eeq8B9sR`|$hNfmqF8pa#?jamFU<b6* zOc#*n#$Z8xP=61LHy)4b8<?l-U|A$+X#~CR3Onofkc#2O@EK@8c>cR?38jEr&ppJ0 zR@edYPz#ozjYiP_LA4j5+Q!p}A~Yg@*d>$W=0S6bhvG&lP9&;1iDG08&EQ=s4uNHs zx<9pb$-ZWmRbJA^5Pm=w4$Qp$&HxpR$#>)y)br@u9q742A)2S!<74!U$1qEb<mCwc z$T8#v|KY62`<d2|EGFHv7-ljJy-@pb<w9BB4NR~=fE_K!!E}wcTikAR%;gFT?%3## z{L*k@*p6LA(c1<uE+jD>Vh2F+qf~n=&5jRt!+N$F(i}!9#9xpOLl!O`nnrWB+YtJ` zdNzI8^BR+tjeJsFA$r5m%jh?Z>RjL^LP*EM((nbR_yz9Mv@oE6;?kRfE|`{V<V5H< z<Oz9oL+4ZJDK}(P?;>~i*lG3Nimjoi*5nJsH0fhdcZTc5L5quXcKh-7b3BAEE$43? zcsgU<VlE{VJz9`}F{84}70WLM+6h@;p++lUBG%Jsg=)p3I!sgFLa7eA&_<{)UKeWZ z4efyX8pqR|;%PV%)olf=ji(*(sNRF28h87;a39}6dwnm}gGIqI!l5St^HV#z1!>a- zxeWR`G~X*+C=g4}X2L%6=nvBKWBZi>mNGyV7=J=RHFw<hRss1Ht5S;E+e5*tPi0M7 z_6v$o)pwt(Z&Q?@Cj-E4T>iHxVO+o%mo^p?=onxvJQYo!YR)g!t*wuce?3Yw1gJOw zYGqG*w*kSksP=v1AHIU^(7tnm{%#({4fD(i4Yg>0{1Hhtu7To66yrjgiEf?*pRB74 z(%?Q${^D!6OZ)kalHg3)J$$ot{GK#^LF-CE2v;Zwn=j}f;}>=2ig>(d6d5$o6EOKw z^Sa)==D?03tIs0)vgx%hcDF>^wVK6lpM%*H7UXcj1?Yw+JJAN`1+c>Br_mnt1iY|S z+LY#?STa+{lXW$rJ219;s`c*u2@|c5Uv2_40Y5F61Ve1&_c@JH9hfieSyXGm_2La} zw5PRhfbk;Gj%_LtH{v2fbBp(P8Kqi@P-S&N8u4IlYp^08a3-HK91n_IGrUO<O2MDo zm3R9X_QkFK2Z>~%5RBk;CjtYrR;Iti%N*iCqpk^Ecp|BFwf6%T6UTpDogiSPX;O2g zOOa3CSi>{p^Vgh<`W0{NpAx1;3Hx#LbC`t*eIbXQ!or)&vRL_hVs?9py=24)l^t~2 z3wYwNo_5pY4($-*6^MOdXl)fItOa7kdwFO_>#++!HS+WA*zh;T(TE<j$Z@J0nx>}< zl8>iY;Gl$fibOl*=0wnyWSoKNg+u|Dh^C`+p1ge_91I{2C{!krWcT9oGuwrNa7|e} zp#vfL``hyaSTe&Q^w@?@+9-xyia9NFEpA#(vxj*5x9i6@bTbw>YgFiP*3|xJ`Lhnf zN*#p){xrn8HrPbV8-F0VJ@8rQlvoVCK=iyl6sW2Seb);yYM-#iy{j4DN90rNfoDW( z=*$mD`=T4qo2Fj~`Itm=Xa`?~LRu^+s=vT4<oz9;`#;KD{x*B=3SQOtOTn(%_qm1n zDeVQ9_o7MhPjZ<B>Fq*$r(rHT2ZR;ak}UvYhD{6kb;nA<uy7fB*-i%sy<0CKoLE@k zNv3AjJUTb<RK>+Qh(voaTYR3D52j2fb;I5HLI8T^*^k*A2CXhH-<iDc@DGR`cie&D zOyoke$uz5wgRiPMk?*K2NZ*SsZjJAT@uLu9G%Y3C7l(ry#OKMzQ`8xG`uIah2M?+K zQ!!W*@Qey?k9ghjZp9XBzw~6};$Ks?;RabP1M;w^cI}Tdiv-5Ll$Y>o<6)v;&&-Er zGN@?%K&{yxdJVnPgDwf;AimLjt;b=fcrW^|x_Ce=tUc}e#*y!RY-YzTnnMX^sPCXq z3qOd81I-D5s_qEw#s8w>!x!fl-P}gO1QDuae4ZjBPw`itqAtjw=8dXKOmAxU>1miw zrts}q$&7efG8bnmS(-Wxi<lPLntDP76@Q?1`5T(Zrz;tsQX07^o81oe`qld{SDE%j z$Pe!`7PC;yEj>M15Zy=f#rt@P&6EsH2TceWVIdX()M*+5U_Uv;&N$tsTI5izR;X#W z_t|Gc06(gs2lTM=GoInAaOGEcKj&manp-C1SY@7f3dq+ePqL7vq8&qzm4lhVj>pry zr%P^Y!cL9mhgeG=zc0*Y#I#Q5r|MqH;=!p;wU5*Yd#n(Pk#%0W7Y`Hsv@4YlkeqT! zBCb1R*af&iOA9}gx0HbOFZQ4(g$wQP7PKc^Jj8`bX7HW~-AovzS%y>Igv~f~Q;Vm^ z(|qGBNO3^;!P+67dC21#8DF<o&I|U>j?PjAw*Ufm#JD|z=Ej$0f$|?t(jOkNukHB0 zRbb96*ry$Q%41i;{`s>iurH%A1|6`BTao;$`5$%V*=A9*ygmMC9mLRKMVCi2_&)zk zn%{$IVexOgIr;rH{XXQfoRGxUrP=Uhs!`@a2LQPG3UTfHi~|5Q_JF(;A|H6L@4N#| z5bK}ok8^wGeEHy_iwJd*7ESmC!3q47c#3{FMIQrEIF;`@c;wsdbG!b+f*H``J2i&{ zmg~yFN-fz^wn~Bp(cHUPT+Q@M)uzq<(FCrZra^S=)0X^OFA73QPyy#G0KPpI<Soex zmhYE@yQVH{U)^_i$>!hk<>QIoqZD&2jliSW@e{9oPZa;}bIm&l&zFj4#JztNe*Op5 zLi0<j=Ckl`ZoF&J_;}haOPXOk$N&d*VGQra(Y_qwfBTo}(4&6OuYkZ48c{Du{fl># z|LRg3a|l>2ANIQJM=<DcDZW-TN2)(eOZeOb3+T?LgJW5DmyeMzC3PQ;CP4v@Z!ec- zz4FUK6<<D+nJF0;bKp_lO+jq^Am_&s*M}4Fd@xQI3NYfXKYN+r4V~PH@toWRH7<O& zp!5dU?ioD}QPc&?qoB?te-}K>A_U?uoaTQSWiY?jo134(pr_{3u)p<~pZRCMH=w@Q z0JwGoIisQg`qsWjO_upSHJa`*@|k$>u4%9-miUoe=byapnc?bBg7)tv**=<P3_*>V z5Mn#k4g)m~8L27@E&jEBWjOiWGb%|n;$Y_|*URrbHvMrcp>i-NF60P7grZVN#gX1L zjZ@rMt5)q_{85>|a9%gIVUZ*uH-H?sP!NI^js@v6ZwQ|v=dU;<{atQ27HR%zrGNFY zcWEzX9viAHO^+yqEu^(2_|d&X)?+@zCSDJ`A0^~jSa4^jVzU}%b_he`36t&kSws(N z#`cQCN@9cRV<U9xtaQYyi*d$&8?JF14gfVGBULp6;*0|;hEQF)7n>|-)+=BaG}J`| z^7RnxBs#O#N%T2I@iZ5j!lUJqy<#vz8Qk{+n@2)O`K6PWW%TuiAI@jth5Z;qUJCuM z?+zTo3Ar<18p{J=B;j*s!D`IBLz&QGEq}?23!X1w2SRALCrdE#m*I1i>1&V|Kex<R zD9+5!4LaGyn8&lSan9~P9sH=pA*px(FfR0r9DnEB1(p|~-aby1m!(<6)AUCnF1%C& zmT<TCNxo`{Lr+P7A3Zf3dI}rh(|(e@QvH4Ba%PZq0kxMA!*3r0DbN6&>W9Rddb-av zR9(W<<1IatOkSYm1;xi&oz4=1nUPtG@j;fcFT{PlT5&VINwwT55Xl`iWSb$Jx0*I8 zt^xonycvzOW)HhllkK41kp*{#(Sp+B$btz~!MmKXuM|OIfYS(>-|IROQu3i_AxY_Y zPc?#ISplMsq8qKs|8+)nWEi~eI`oJlW^mka=0@!EMxU$4cfGy2`JSEs<*cgC@n+M` zw*^-YJUGJp_wT{^XH{3TXRl;<UF$n=E9MVwpw2zn^yA}mcl;q1J{K%w9^Z&LqJ2-E z|Lk{2@(qjs%=p~#%7l^=TKn|XZ*F|sA=Z%Q2BLpk+T3t8Q036>pNsLbZ1+-jkiC2$ zEak@4CudYvfB8GZ7^-Je=L2E#$F#{r>*xP%Op2hnPQd(V_~d8;(=Bn{I(NTTdBeZM z-CHltlOd8J%siNS4U>EngnoVC>o#Y%(M~3~#Hr5y#cK=2?1i%Mu5RM9h?fkHNUK@= zO>c)TzIttp@iU01_HWj3=n<=X=TWNHxE}kDH0HHFw_e~&dFlevuip~Ka7|^p=SQ83 z?1z;{ye+%ZCx%r{kP;-S!^GKwp&z+fX16AYG<n?MR^Yo60C^6kVR#W%sT>Z~s`MiO z62m!p(27yj2+Vw?S}HBC5W8>ZU{w|6EK#AO`P|+svSDKEA#vIrQrdIdHd0fW&YzHl zISXZkTe0>Z(#@Ky@BEGxJJvi1sWn?Ko%cLjzxvo9p3RLa!mRT`>MWbIG?1EWy^SI% zY|J2o_>>=2tg+Q?>ghP5Jm~G%mIM-38_$3rRHl(qN8FRL7YpwHcl-_vd#D*ym;rn( zcYnBbyjd7?ESvU1&Dw<Rs`3p!PZK+uspg?h7DliX^KE5@1ODYpg|{dko9!7<ZTon3 zR0BfVLwizVkJRaAB>I?70Jt+2+x0}m)$7{y5X<VP&R<G^r1es>-*_<D@xhxKvFnfd zO(n8xN>Ah&L!YT`#(q0bQWejw>6(|_x#gjER`)@Ym)5OYWWtEbxJ_J_Yj%3-y9d86 zg-T)%PW@5NoO{sWCRYTYM}4e8`wHdoAnvHN>96H{MNhq#A{d&&=V7@3wKdl!?6LQE zKV5eI%yd8-amJjcH>5;0Hpo)r4CiOalJU;@(i+R^!iAeLZ^JE7MrN-Hdo7t3O+JqM zm731thW`9+!u>9tgr{x|YK$0fVQ(_39wg2GFsWQLYf0g@HH>(s-1PBRP`DMXU1u<p zdg6g{K9v0M=Lm?b5DKV>_);P24k%G7a&sMKF$GEk&`^NQDBKpI`2Cd_Q~;PJ+z1?1 zVU`!<@)IkPx<kP%c?iyx_UIq&Pf?lxU=F@&XR>&uChtavb+dyE5?9VB^i9f4mdaRU zC$S|rroB;B!?jsCdsN5f^X+-5!dW6wYFq6?+KY3$0%|DMA_QO6J|4Z8c~(6e<Dzh{ zTjFk3bBbyYM{Py8(7K;sV3g(jsDGt<4ZxAV9HA*D2{OyTJj!IZOF$)92fsLi4*lhP z8fij5uuY{_)N5)vXxsYyr3UQagzc6l3ih?E#Qfk5+7C)N15;7b_jto%siXI^qS=M) zg;LYoa}u7ww~(h^`;WBd!Mk=r<$vqC>LMyib2f;cPw~U%mW11yADhbF^-z_$FlC^( z;m{6^q`G_7qQY`%7wTw8(S@~7!WPm*gHIr+#wL%Y1Rc;J%17_5P#3ZC`>yvZP`asm z@7QUuIaBmTf&2Tlv!{P?nDy<$w*OX3Lj(uyK25uucS)3ma~H(dYYK{_oz+tWW9D6n zAEWyQO1!Z?=3XygMuNg%-mTd4<JMvZg&cIOuBK|SZoXw}gQ&@1RPBp)SJ}3q(%3L{ zU&9XPyR*j&Y)J%^>fGa6zO0kg=Q1thBC6_FhHzc`P2W%)o4sZ(jcad^_yKK}lO4r# zd|LdD;M?(E5?|jh)-w9p2cunyxR*8^CHVtgpzSw+l5uNNVNA!n%W=wbqt#8juI+e> zXS9oYUmGrL@mG*kRy(_&e<jmV=}`RbJml_0NZW2ty8U8<Nao^#WUt`F;c+!oz*Jyy ztsm$7`9vRMF?G>&?4ZYO$qI+`#S1Apd;Yx%R0g66sO4s<>{6CB{;`=vM7y&F7-oW- z4nUW!uoV=xJoY3Yu75sw9d8V0AJ~XezBHQe&}&j0!gW@dV2)rhC756bODO<75`84! zAdK&vV5R@wK9NwIg-*^4xDaEh*`RsTq&fQ$f5`m!05W!vD)|&>#o-!+I}$(MnFv)? zd#E94Lmx?bl6!8JNYv(wN8ST*ijJ2}zGH*5P!1h&xvUlX7GDZT&86z>Oh<@s5^Ww= zMEkW`#@suFUy%N+JL2S~R+PqQQfUK%qNF%wBNVXge5PBBfmvz9(*?=<9^FRN$}-<l zqN-i<O{0@qbuZ$t9+~x|C(Ee8vc6K}Mn?;Dy&DFj*vVdDYlX$ZPxH+lPTzgmqxj&x z$3ohYvFJ%|Dhn|&f^7$pzHPy=zuco8Pvu2YFo9um83err+t(M@vH59ps031^D&N}O z>6!^VaLO6;%VE99H+>0sO;qA=55`;?DDh9?6po|mmP>>Z_o>LBw=5S&4+F157Ey|Q z_;0c$H_^G<Y{|}eSI6|c(x`M|&P>QN%e!kWr*}@GH$GeKdtSLSo7FOis(qFIuP+?7 z_lcQEyD)@j5AMOY&!HGzo+?uduiQeeITf~pEz^_N&K-M71^6SHthuuRNUADl$=!iI zAnH+15o};?*FNuW+_(4SjrD0)vCwm6S)-8WTZ~Qax>ElHSXBCX;AF)bp~Nd%Lp3f$ zXfx5Ip1yM6;DH`(49C3ny8UZgogQbEI?;tq*I?3q325j#?|Sh`E5Ad2R5ioz(kt06 z{h^He8ZD_uDm5Heh3+-me9uD!ZfnT3`;FMpea@WXE=c5zx;Y?^Vd9QaRe)(BgVgx& zeaGDt-8q9=X9%d&k*sI;T@+rp5mH`ydhPyA8cbSHL)q-G1kGIS`Sz7P_3wS(+<CPq zsdkSkJTH4E*Jx}*<$LeA{gk!6vV=v4RF5^F*(jdEu=Cn@b^<T-484!!{K3KW-^1XR zvE_aCf4@AEo#^DKUP2?)HhWOD=O8u$n~hA-i)I@M;!S~^n_>qo?IAHMXUzOKX5BOP zc(7@bv>BP0$PX1Cry7w3a$)&Op_`)z+a!LXf-kJKLA3k|MzE<rYQPRpA=<bBwL;}! z#zmD`kbDN{L?ztI?*n@a6sSxI=8s>99>De$xJ!dE7*};3O^$KdeVc&o%TvZof|pU7 zJuV}wFEFF3cIe8#wR7^tL!*VI0^HNooW0{zPc+<c284Mw_0HN%h#8lt-A5EWMmbDD zfJN|gfEDfYHhT84eYAw(20>?oXvXD4+w&}+LIjB3ZTOxex{XbD6_4hW#i=<bFH`IT z!4fQjBq>h;V7+D51Oc<vg%c{hAUSD@a^_HL&zK5-pd~ebGyhGyO@yjV9(ECQG8%L; zUWnPde@H9;Zy(4DLsZf9{LneDuYYK+A;L0IqqS6=#soW9Q{6ovwhRrMNQyOsYMaB; zCA0OIU}Hm$7ME)MbV2psoPE8#Su{ms^p%Mr#9>AJKR=!&A9A-t8lEPs#UD;de`2o0 z(Fot8`<-I6$Wa%`L*s!RX+Fla^qu%;(7on7_PfZ;OsLw5qDr{xedeO)@Py>&5Hz2> z2kk4175568Gu<D?iY7E<LPvLbo~GrQY;#(YqWmvKgoRf)NQ0fsi4II^x7Y<+0kq1b zS_o*%dWg9|I_;xqCV}F6z!Bv022)@S9MN82qVgf;fm8#b#poQYE}t5o5EMUkC`Gy8 z{zs}FmuSjoo4!16uSr0PfW*QEKp=A9N1lGr8%*i|w%g0NLi6F&0IIRMmRshLbUD2W z7J4@?Ysy89tJwh;!fv<(K;QTG9-e2&sq2QyNIMg&8vG}<|8_Kt)_5BYf{g{EXa>Ya zQqgd+e#c_eyF-L$gPb>?rtD%lA7fJmtgHo+<A|5Gwspow>S&z-8$OM>TpqMbnHnb# zJE}_)T%y|HsPNBha~4E)kcH*~l23Q9wO|CR5&47rqZO*X;`3GQt5gU5H_Myb^FGYC z=j}|5%`sX}(g?PlRUIGQ=gEYuA0vuDp~Gx!a$@^fxi@hOLR%!N_pu$em%4v&^pI_b zxAU#gam!zw9lmmG$W(LhDeG=6hiD3}Z?t5^mvAQNI&NH>OH4D|{W|2G23OV;&^G0< z^;r;LG*77#gpu}%ysaMfoyn>#-{sl5IR{eA0%4RWZ(An*GNb>c=c#<9`8U7Vv6Ufu z;_KaM3BIy3gE+<@fY<0G{ELXEr|>Tm<*RZTPVF3B2E~dAQEueuzJz>9A8pEpq%Bdb zNt|a62d<I>wO82o9=w?T7Hb|QOn;g-E^S0U%M>Jm7pYoLgLLWYuC{F5Frv)%fVN=s z7D7?9*YIk8V(>6>{T*oFn~qWTpc?l{O@-cHdpWt@8Zl&4$OApow4wJMGQZ2JFPbu} zEhGVe<5w)sq!^q$SRpWh6*AdMlXH%mM2Av{bv>eaZyPQhV&0D^;vru2N;;H+ccGu0 zeOCE;M*5|4z%GxoSLux}Gbl#PJcU`1GM=IyHel%kb&p&=R#?7sj1N-AT|FgkaGJ8b zJ|tn|BjdRyn!cPj2zT|76u&gM?Au&5`%-VnrAfw{-B{RgF2OU5_T|}o8N%{4n{8*q z=>c00NX_3Ry%1-IYv^z?$NDSB2=KBh<V@{NwwQvLmV)uw`Z2X}j@Hz&U!i7;)Iw0e zQH*=0LXxg2$E1dBY`=s>vTZuq^5F!%kZ0K5vbSML%3lfcAfn6HxXpwm6~hA0MbOx1 z(TB6oRcQMqDrHo@O@APE1(jA`W~i#}V>I-GFy54k1o5C8gXhI5Cx`N#fKF`&TOjNO zZBj{V)MD_kHPhJ;5H$}^yczl}CZRKLnexH{6|d{Oqh+f=<OLq(JL^od%`t|q^YYqc z(Ayli<|s%BU<a5~xd8Q;nY??3a@8rW`@~XeO27WB(^HYANR8qZ0_U<S3lz-bWhknc zzP$YeU-dr1lB4TLhLQU0SKIbk!LUWENSr&#k=?#*-W+9E&vxuHxDrNvLF}~HejOPo z_^`mbU%O(g1%xozAUbH$qs-K!D8-|s3cau5-e+_3{R7dkYCqa+BuMreTP~*@W3lfy zYaClB*jdNjmo{3^KH}A@T;B`qSgT!}9rX263a)vhn56d0W_9H6fSfsaUk>41t@ATm z58&9Uu)K6D0B|daa#POMTwSMV3jLbyPRSZXZ;%p^9$1u4wR92g?5!1#piHoazm7{A z@LCWmFEo@m74*o;X(9$^=*mm3o&{;J2IO(zx0>1p*}GBaC)`Nag7OAEN&6p=4F48F zv9vrfC_&1%%cuLryHp`rNAcgG4VN*+=HLGtk2R71cT{e{^iw99yC0&J4z4M0((Zmn z2j~{<5bb)RgLk+4OR6@XeJyEM46C9?mwGnZ`P&?u=qa(w<GD%Sm1KXgAqfQZ4Gg{^ zRadfQ7$7bFXO~J*OrEA%dcmJ&|96EhiptMsGe_PFppKQXyi=~gD)fDii<IJCvn7Ho zHq<<u5LPyzGwW>iKFuh=d}p*>O&i40Be8AC)P;-0eWuA)D-dlS#q<%v;~>$L<lL6B z%Yj9_bWw3NiDSYzpmSWzw3}eBNgePNR2qVnpAwGt(A2-=b$L=W!v@rOAh3_2R$P)C z{;;;)>)NMYs_oFSgRpmtpwJj7;i#*=9a`!{JvdJl8#s`&xU3jBV0aSDf3H0jm>zbr zRN;-Y^AOPxPt{rB6rD=%uurtw;ApWZyH8GmUpcE(t3XpY!uN?{f8#CroRtLsLuYpB zPQAVQJw``>*`wJm=|jit_t~Bp(CR0seBBi=)+jf+&dx}x{YnV_%e<dC7pPXPD$Sl} zR!N)`I?0skkn!CiI{7(t7RZenVm3z<`q@t1oCAM4!t8!F7oKtQ20MvRBfdd&x(y1L z+!t#U@THB2|JY~t3tPnxuZTRqjn%7K8UD%aHqvyq4`CbGQ}nZ4weAy?{U{pP0U3ZG zNgKe17$-Wl-Y4g8mO=0R%Cqiyaw45J*WIBo?T^2+93<^~b>A1cOSjx{>0zB9dN$*k z<B3A&6ITB?2E7@EnMB)g;^glkMkd7iDMXLUGrcSV+v6M=@T%{n*6LH~!s)4sOfQ|@ zD{s`PVWz|_ZrdXh?W2SNbUh$O9ykvKD}>c4m!1oBl6$8_R480l1lm2{({RFIHM}(| zUFall_fBw)`yO2(CLoDfX;y2`_@uyAXs6yeWlb&obxA{HZ$-mDS4h6#au{SgCXLcv zAU3mSB1RdJG?ghwY$=NvZ}GfGTGMFzSGE@zakfSm>%6NHHT25rZ3t8v4H84=$tCT6 zYkpWEe1EiX#G7|!m}Y`nKOy0Z8Q@WGow4a%vld*^>VsP~n=F{k2>bBys52xcY00K= zed{JFFw9)qoJkp50qd=RJ8+$iQEcnpVx?e+L)Zmtk8riU!<~F^i|C%omh*`0k|eF= zf>5Gyk^tlwxI%TkJ3F8<g%?8(pnE}T+`Q_qjmj>nsJJB+G)1lkS_@U%1c5_42s>}( zuhwthtGjx)YqG#ce*-*rH*jMFV;*=@N~`yR{Q+wcS|$Z}12IPv9qKudt7w}fs!N%O z*$7yh%fY#1$0%XSRw~Zipu~LAa_+u!^)W=TkZr&6Hl*f>N<2u$B|&ofTako-1vYy# z*LdG>1Z@^fh|5EgUn|n;RBE<Dzd{YIqSO}$RMUg^Q*%DVn2ded8hh)ozd1)c3taTi zS(`+#Vm!7^_iz}bnCkLQmy0+o=4ie`Ol<R4_#CZp+oPH;mLeT%M&~rPi7(Rg{0fB9 z?W_9HU=12uW(uUj9WeS#dbLhMzZrPh2HK3sP^xM5hf=CJF6nvu2xh4}!5(KmDoCnk z%>^WN9XUg2;^w~l@OSOp5Ui&`JA`9fLwy*_Hrs%hAjcf*i6^Q(igX`7dsN%z2&vc8 zOlY{^I0a7JEqa9lHoK-{n#4B7ODL1`0zuz{f!VjSAjk1tFCi|M3=fIl1(DDZL?9Dm zIlGSbt1~BWDwRTbVoYPp(s1aa&U0nse1x8TC8L~8D`K@LNb54N0A+TuR<CeL!MX5Z zX5`Nohx{6x^T8rlBop?wc-2~F{FY7(><H)xx|J>SWs>>j-@b)KV<jiwPq@_2I^Sd; zdH3-5ec8Od-y*vQH=(#$y8lq(^F9!!#rS|_GW7!dLcv(z!{`?~6&A7QpUbpIZ^io; zSMR#4ZFG`v-U(s)#!oc-H+7ezJ5}X)@cY++rrril!OaKA8wn=9m+WmQK=wNBPMuLv z;CXZ3QQzHFhVS}I<=Z7{jOio=@J(R}vWer2#E(N8@j<H#W7SrtRdRo~yUhGuuY6Mf zAb`CY@z~t^phHMMKegn~>8^Y9R5#<q`i24-za@V+9J_9!O)5<KNGUr<vz#mIr8yg; zfSdef*xT|QQ$8s912b4=9OMs$d;Jrv$(+QC#Tup+Y~xXO_f|B{%+8ZXMHIh|F1Wu2 z&}aIZ5fPe5oWj-uwn98oue2Ik)KRWK%M>T`(@mqxg8zl?e7gVNl%3SL`OC0#;~i|p z$EqhK=SEZm?L$W{2ViYnmE&<8pPcS2Ha;=x->_xK3Mncjb?4ZQ6_^YwG$AW<j5^X4 zVteI>M2X+I8XXfZ%KOYMFy)XlxOozXSpc+)jLbwk6f(?N*3Bcq3%bz=c~)PtCD701 zSZlrXa7OFOG){WfD8LuQoW)I>i|vmiI5pN!%x{jTJoqa+OKMo_a)|I)Ex7D92^zVS zEh!&U?adDz-qpvS5jvOkU7w+l!k7^1cCDIemGhR1(w2|C(U5=MCus~emr%J(6?ZT^ zR2=B<HOndSH0)>)mi6_31S=%>OOT!WJv3VE^&js*kn%T17w!~nXYLY>ta8?uI3PGw z+f1A)gab9uEKBjvP!rA4mJW?$2U3PE)_uOx>Gq%Q$!U{Ms=kHg&uedPZnepJ<NRYU z_kGn$Km6c!?I%g$Tks@Y%n~T365dA8md_;(M9M}>M;WU6a;G_we$L~W<|RH<nrOun z3`JO7<i^6SV1o*a5I|&R0ww<w7!*4L24T<A_rjPZi;RjJj3R`;WqifGKFJdVM5<(4 z^dmg9+)8~*C$ZzYqsrD|mDS@*RQm6+%Nh2o1&WS8_1x=D{ccz+4_E?CJvzCbY<K;R zUM<}}xh_FlG1uFMZW7x%<5qK6T0&@YsI_*-P0mR25k{|6s%q#vzR<Ec&)tJb_;@M? zrZLWszP?H&0jqTm&1bC0AtIl17GYLoH7zea7g=!$kvBqO=unTrV<fN$PInxAS_Gnw z?77$}^W5&qi#hQuerE%~wA&eVHQXL3$`w35d<5K`($$b5;S}k0pulRd&Dgo>s7eLE zvQ+4G^l;FZubCOrSBgORN9*q$6I5N^<8=(`L0!N~RVsW|zTK}maSv;dG(gVZ+dqJ< zYmy+k-MR51|2v9sWlSY|kfD;r72Un}v4~eDo7&8^af8t0ns4<=PppWtuqxt3lg<H` zB&$NV)Yi8rJbkA$<YH}LP7LdvGa&+f>lPoXS7B0`%TiYq${sd*Plp5X&hlTL&`mc? ziXY*es~fxX?OXGT;Qk&M=|7e8f$HuPr5-4uuS7ZVIhftXoWyxuAtfGG<N|*n4>d6B zj9I(#YHSo$#FxQDLM83{N<G*&AR3h|nrU@7PtDyfm^u!TFsOzMi+nSgxfgl5)KvFP z@qT@qH~wcWg?zuQ=4<~lX*<TGDs5-FX+Mq-OMmK&sRdkjnGTd>lc<X8Xqc7oLh;uB zv2-T>Oh5hue{Xi$^`6^^%}tW~irU;tn%tu1NC?eU=-M#%F(OCG<|fsYN>a^{5K>e+ zKO;%$aCAt@Z{Nq`_aAJJ$IjR5`FcKMLY3C0cG()Y=N!oHmANziz@*=3;;?(BbdUlJ z04lgrL9!Pc(7P>%B9S|~X%?Xh={kO4Xj&Tu<S<9)7>=mvjZ$gAptMIuvKXmoWsE<P zoId;$wBzVx5u*TmHNb-o$f#LI8TKc*BQqmLGXgl&eiDrBvG?+FUFFkg=Nj$)--~ve zX30n~iI)>QsZJ7+op;O?6O00TWjdH4`pIm(SALpG_Y{0<A{#?5?UgF$-8Y@1;et)= z70+}33z4hKH}(2lz{{z#Kw4&Raf1Q3UZyK8GO{!@A()-KG!;E5rESevEK49ko@7X9 z!+Hs%b(~6SsZ#N(Y=pLd3FGuxI#tlGnSb5A<1E62^ir^`{Ql=~#n+<uoI{5<Dl#@F z5(7T}R+ny`%ChK&;F%6}s^>vvF&~=k7SX#QSLT<oB{447GYl&IAp3#dJPjA7mtNTg zyz9Bz)6&vg+@)wjMkkon<pS~2Clq=?ce+H%+BC=__ft?buKjwj1#Ns(C9DG^<v5i5 z=ImvNk1hLDd?HeWn;v&BPHpy{7KTI>rRB{qw*8k9bwp~|_8(2sjjEpWUgT`x9)~}i zsG$6giqy)0;3FnORsZmi2Yrf*PK~Ck#Jq6Qf=XBPz8;lL4b9wc0Lip{P3xjvs8jjG zFfvFs^J(vua1l~7;CB4X*wHj;{7eQJ5Td<x(r|ZyY|F`sw3g$$V~!$B-^=u3PFK7+ zU^LYGB85*hNja-@^;)LYL`qNchTN~tR~==id36}UJQCO|iF5kgM{0p1ZC8!5BlGJ> zmJQFX+?R&K6<QU)E5J9;_1uk4CQ1)Z{nvY}IMeHp><n?MNUn?b_H$P*Hx4c_m<a#| z$|34V-5%6VfF)Jh4QH^P_?nczaf&Sg_wF60bdkT9$k)Eq7jNLs`fzr*9Zmky-j+5L zlvo#fDFx_!U<(MZ2lFU7PbxI^tK#q}MdH)>DaU=Cj|(~{-^p}t0_g-(rm*db;wx&V znfyP6yJ{I;E#a@T-8|nvG`i}-Ox!Hne-W-9NJHpb{>FuoC6oXvLNfw_R4Tc+cGaT9 z?PH}pj8Efmt<H?ceHPFE?NTlbD!#U|S(|q)D&wusYBvF_9RRcN6jx3D$Krrl#OcDA z>Y2tPOV(3y3;Dsb_Z3$daDz_2o44DcAsA;TIYhg+&&5<z4JehgJr;@5s=t8B8S>xF z=SUB-W&;hOSBU?mm26C#X&(>UL`9(<uH@f4ZE3<%YM+}2r_P(0_RBBIq`oUt0VKfs zj?BZ8Ecs_N(j-mEkgq&XA=OTkRw?^`@)x=<lZ1Gg`5r~=L8a>HttF9$SA$6gkW)JK z54r)MLvjr<@A*}HrOA89g}&Q=A0Nf-7P8;~IV_E_1nxn&jiL9$zAftccJuI6qkl{2 z>AWw)vm1}l8)Q(S2eZuJ+<3%c=wJbIG8pW(zUMm(#P-oC?pJJM`9FsF%5xAvRM1xo z*;GQ2j(@bnU{S`HOI@~8y#bM#Lwq4SN?msKBvWwiyW!qnPWR@3H^^9~<~Qz47$EBI zV!-^!VNn2J&65b=spIWlyk*@jEVvt}g(>CAlz}fL7trUK8Lfh2|5#_3P@tC#Zoh)L zBPi_$<$IVqt5{ja71dS9PxI)XbEC4IG-Xj5{>ykw##Ytw!b+*xsz!)h{y1*?LHNEc zas6oA=baanjnY23;!cetN_j|sDxylXSRo>usK2YMOW@YaxE2#XkxMQJj*>T8!Dsne zjS||+z!+>AGfAt9Hu@O<n4DC+X`N3B>5<OpQ3;{QiAMV_2S1Kyt0WfTor6`($EkA= zIk8i=iXU6mB1aD2YdLK{I~eDpsdO>FdTof%<)Inf|8S8(hzEc)A=*hKMJz%`GhmZM znLS#ZNtVWp5n7ri7;%%0!wcmw+NMW#oprhbQV1v1wxh0&;Y&6<e^dR(|JXG^q6aH? zO-o@%`(6tO(XIOp#$}yo%3l|$E<LhPr;}B#cBIhL7Z!di9Mbf?#2ROqbmk|7FB1=h zdgIklX+lK203IMj;0eI^w;F@_v>8#j3re?)OMG(p=-y(D-VKpS?wkPDgSk-@8NP(+ zci4RM>gEGyUJuf<ZKhR2_@w5s@rbPpH!g26qDwq<7X9m;=m;jMII4V?64(Dcy_SFb zNLBX_p~*dK;Q}Y)4@wU=b6GqTJ`G*Lm>M}^ycNnbICCe{9(~5{ATVum{)_1*$?#Gq zaK8)KDKP89nSZ<1)0_Utl23Y8AfHUJxDu=yA1njF4U&(jv$tCQfWV#_NS6>4U2yPp z{W!$*Y3KwR!3IMvS<B8SDfSXlS=wyT^W=BW0S2tY?FFEB+i4zk?vmwHk#4!8;PR|h zt$J;<F;*)WyMJ1R=d^jr)8$*+wNGs6&R*GZk#g9^Bc*YQoN=(KSbuu-3jVaoR-3DG zcJU|Y_|g%S)1*4WBoMc@w@~=;cWb^Rf|kg5zZO-Z6_c@h7hYG*1lh~e_@|o`*odi} zy>e8Gm_ME|x5v855%f!ozy?eHdQ{6QC1*`~Eae}znU-0ni1nw^PkKH9EF~BI0*v#^ z6x_<vlbak|4cVnSdx&(Dja|$()hKkRP5_&);JFg!cjMAS#PBUZi4`H@MF^&de3yrs zYXy@tC{q|L!*u6mtax7oLS;v5HT->>kLmS-QnY~Z2;BDI`R+xJdu2V@GpeQ#<#o1L z)GoK560^#FY!Lq|khb5lg!COEWxWv-o4aCZqG^I?2k#8UsTEhpXIQs?vky(bVBUg* zPOE+2d1YDTsC)w*#(JJTYqozeF)Y@fUk`4Na3ZE@tdmPZLO2)h2XxJ1I=^5}u#;K6 zay?HEnr*h}o>8rzmI;|Ac1-Jw$9LEcC9&Z6lkwKfoc$|&+V@}>@{sX&p68mk=Dv6M zP8OMQkZ}i_7GX?@Zp4>LJIU1+Z}+eODA;Hb;>pAGCuE}X&m?@B>m)C<E{rde*M9Yj zIf=at2*IwW8~c5Z*zVLBnI^~c%@b&wT*SgXwmdHpZ-kTUphVQrRCR)5=Q1O<QhqDE zv;P<WwWHN+jfIJA7{qQ|i$Z=3Q(N+3%o0721ja0`nu@4k94oo5D@nmldj4Z+5uM^j zeRMF^A8|sKoZ|I^zkHHCbnDiGrPlaLB);kxUk)MmCI>6(ah2vF(*L$ZsFr)EILPZc zZcPgI+u7%RrFD4y!(TG$oh9<*3rU|DK)g{QQ$utX&^$3W2QVa~$*8MTfA*Z<v&i(k zA^%e=ruyB^3!0d6C%N*>WP?wem8RIL3TZu3`dQ^^9v@XRgQeCXa`9}{uM~N|9%3_u zzFZ)-dn$EK<5izeU?rrxON}}x(n8*E<8p^jqRCDXJo37(T6PrL^+M)*^Vi?aqI;cY zM1;ElDr`e!`s<efU}=5_0_tY(33)sH=Jy;&0<AovkMxn18)^4ed#bVyTT<kIPRoo_ zAkQIkfJlJ{Q8tVL(_FU-eu*+@s#M5tQk^1fX|j1?vYUsAg{xmayPK$%h*vC@_V@7` zz$i?stw&M-y+pNJ>39fM?HS5YPPZEXYZWMdcB3~Qo!_qmRv?_P!Q_3?`My>utdPJS z1NpI9)eyFv+cfcLu;OsAOk=QO=1`m_J65G%c4z$Q<ls!-0+wGvD9?O&CP(+}WLV&R zEp;`<icHd_O6iXlNq8DgFe(`hpn8QPQhGb9>SG9M;A?7oICR%beZ6UYtlzb~j~n@A z3ooMX#(xAvsz0Z<yXZBHQ}8VmIRl71gDo@9m-rxCv2C|%B2Aurkd(~F!RAB0l5qo( zARdyCU&fGCJGrCFIX=S-+G>4dHY`vRQ@9wNRfehmLUxA&_1vSl!?_Y85h3mWDzpeX z3#u6gE?*RzFCl)U1<MCQNUMC6HJWrhB**3nQJ=4r$yS-8smcWy<|dq0v6p_rdOAO5 z>Q?uAo@zM60QGeKU?;qv_$F9u`zb)8Hd$qJrhGm!ENeBuRL6%$8^O|_COFIoJGo<6 z%U6Ji(`nh`b&H%H(0=>9_S&@S{?BKxYVTi#kS^0Ui3a4NY0^j8lfZ_((s!DQ0mYL` zQ>y2J^Hfun8T`Dcc8GP+{=r&^#tqzx{h3~G^Ol*r!}k1J6k|0^$Yl+l29Z035K^_O zJCmO5q_=N5cFsv_S%k@cr+Rg7nf$A+hodTIziNM-mO()p276p?2P@Z#U9q<YBBEr+ zSTY%G`3#Dxo~G(DTg7<#WKsRO#{h1Sf&ZEfhKy&${iu_uzCh}&UT@+CjlEYU$o$9^ z+y?GR<)Q;_=KPT7pXJmvn`!;z?fm=<^NfM>lKX*wweQNg{^zioZ$0hzsZ#$aq)Cc& z$TyNOSXCidv5l|N*u~i$EEnD**UyllQlt&|n5#TYCks2c!NRNo*iRz$XQoaDP$~2c z#>5rIm&ioaO4NaaHaFLCC^m){eR{(SktoEE+&U@^y^F{TAU?!2F5`Ic&9~DJrr+#e z2()$Yww-57uALFTV(VvOEFjdKA1U&Q!76VNisOKM)by50p-(p}`kb;5r#RfCe6S)7 z>|V!bJNV?bF}8*r?2Wb>U>Oy#h!@HlHzph7)bRU>9uN`cs-w=F%@OHWV@K}Tbe!9K znT?s_tJcz_KTVUeAquo<<@!YB`MuVv>|>yKa+Aq#x{sJiW2n{B{JxXmlLvXstP z@!`xHc~h4^vodDZuHZKl^Qnk@5n<p(=n8}7xbZXMWxn-Y@dk>K%qo3m|44`V=D&yU zHv1CxP}x`>ZBt0Ff>^!#lP!-YkyHv~P=zm6f@Qd_N(>q<Hk`tMC+NR<S7~=aZRX?x zX1L+CQ#R}+HG5B4$Qhvs5zXk^@@>x>s_K8#JWLrTv9@VJ+UDPz4-e|f)bfd@v`v{b z>G5D?@dge-Q&qXEqNd`tg+u#5kq&=;(faMXn6j*cO!Gh&9G-2sWbiulo!TS|b0JN$ zTBCTZnCOnYdzI(EQxQ&_Qa#e6!n)~kdjB`}U92lb&14$depzlclpZ)eUPDnOvuQ1C znO+gMeft73Qg_VP=csm+{h=s(-z4TnW=vg@u9FA9m5N9s<E7ZKk=u`@mRmz<)@swv zDcfy+?*G}MHvfWFqZBM3!Vmw&p8Br@YBVZ)gR=E1Z7ByM?LKj_Yx9D|U|4swkKivw zzcMU(;NF9`#d}W)DwB6cYx@5a-FwY4It~B2sa0}76mgY$r4#xy=H$;;r}f0vYfHAu zDvS83ha_Z^jDwrz*h*^v`Md4$v)@YYMy`-jAhQn$z_w(yoz*TLYOFkktzTbsYS#@E zu%0AaO&UE?*`f5Vzs1i8Pc~ynZd#si2YGq^l7D}v8_~&H=4qXgvnE`!#eNt%b>-mj zmgDrgo#%I6Z?&!RyB76k`1-}?8&?>8xtn&~XnS!jVxlqV*CXkzK!y8{Yd(9VZ>A*s zqwAcwC3mCOOdEo;OX{ZkvZXhhV;PV5`ui1(enu2)s+8|X$Uf0qA&{M-dNp2td`y>B zw0f<utgGXuVqegjk@Njg>z7v^Pd~jKy?yiBf5LRkuTNJFybAn0Xjq$NAlH`q@Y5|d z$0AWf%!|3mz4poNzwRF;X*&%yU|fNe8v%Dmbn>bk_HEno-MC7OMgvl8NT`F8EUjRk zI6z9tfDCAC2-07r?G?*En4pu+bcT#i1O@oK?nzMpD_lkyd;+*=+lQY`B$HrbRfXNF zq~}w4o9?5;sN6G`clM{iC!CFx<ofcbDq3*#tSb(}%alI{;cEDt(=6d^+Wz9$0ZK~p z<7~3$pco)^ZQh%yca==snT9=^GF=(b*fLi|yxNBcqTkpJTUCEP<7!?s;<?*mt+V!# z`5Ma@m&ZudczY~c>nxGXNHjv(D@ERa;zUfE<ZQ|Z;yq6Uck<7a0;^swa%_#gF6swH zxI1OObg1X)w~FcpZRa}uwPK^^S{E*N|NPW=F8ch{0<GKCeY=#pczxO$E0*>I-RtWu zXoYj9O6NnK9SzH}e@_cg*qsc}A3NdB!?NXfrg~?q`g<*SsJWO)eIgY!(_m7qvw4rU zz41~bY#W$7deQriT=e2b59-g)g)1ATYHnK7ymYLrAkn@^W7yL3k!GC>Cewc3Z{l0O z<Ixz@ra)%7vvP6TVMXUto&9iy#akE4<Rekb&XiqxmCkN$mmZ@@;T3WBWm`HEa%`?J zq!)$Wn)*K`y?jT@&TWA2B=wsYC4@TXCyk2|k_)812qtrns}~=>8FY0hwSH-7I7Rdr zw6`<Ynte;X8;4TxH-ri)#xZ3m6`!=+V!Nn8r9o1r%Z$rKUuqmj`G#dJVE9=^-Ei`j z|CY7+`jxdkX&d?JlG+~@&pb3;%eEWR`7vLI-TYhMWD7ZtA!Fc(pN2e6m99LIB_H$} z;_`+X((q(ue8+$48!8-Sbd4`7W1(_J{x`%)Jzu6|aBmoOrd982hLohvIhc@Yv>@}2 zFpoPMyYY8*&)`|>llfQimKU0xZ4+q-PgJN%(IC>ycv?Kl=sza4l>WxRxcdhHfJuu` z`6t}0&k!EveV1Irr*IAJuv{(k+YGg?aRiN#aY!DLaYn&I1~65_rZf6~znw1hqSv1M zD&e%gZnR_k{kLovw~zqV4?<9OkJ4XDM}6UAf^VSR(TH)RtwKeXWB^Q^9Id$fGqoNY zYe?9fC$ZCb88H(Su9-YFs1(}^w+NHWH0r3t_AvVLMeQJinNH4^%2vwk0kef!iUB|L zEJxG;=mx6RHkY<TGhn%-qJQ|Kq4?MPl)XX~NY)RG!~131NeNcZHD(;Dv{%$qKjxWE z>SCGfpynDAiRDV#PqtZzQOBI|$;Q3OJxOuXMK-V8$S7LP!qdEPztjiY0-m<gZH$4b z6aRtyvqQ0|(mCh)$9Lr0=X$QIOJ8Y5+B!YPof3-ymq57u%kdVQsV8S2)lDjWi`=Dd z){2P)q)2^9#VTe+M^NyRHyS9wmdVFgN@+<RQ5&g-*|`pNqsl4_x7(T57G|UDiS<2& zC&dY=CGY`RFtiuVc&A#bKNEA;b)stSn{V_-JDp#GqSWeI#dp*Jo%tTz)(k$51k>4Y z`%FdIu@+<FR?-mHxCqlpHaNf3r)1Y$5)_b`ktBj{N*glS{XWja_&apewCeGC20xCi zlR=j9;OtPC!8xw>+xAWuO+fmTLm9feWXDaTD~1}gcYmIAe}GR|PgjnfhiL?gi|=8z zDlfSimKnvI^WA)W5><jU$I8?XV`G}$_sYz<B8<ON@Uine<)uZ$8D{;({S7GeM-j{| zh+d&96RtKHrFWxOK<o${B`ZxMH$wna_38ub&%qb>wW$mAud`(<s7ldp#~O2SSCWYX z_|swOSYBuU_Rb#t)anrV$$1$rUCqs=vj-Q&?2}(!Kzv{Cxga&`(vZFJ{r2mtvtSgn zmpqt?dIY;!5yh}uEh!zbgU#TmO7-NQ!VIVW0qG5K8RhSEUeXB)U@f2lxr;^nx@TnX z8n(q4F7uXNt`0;jXN7vO^LFuSuQrLCwOl;PF=_(@+A@*!i(K4gRq3(^S3;8>w#boD z!v!wdk1o#}h+b-7vJAaBXHqWTBHicsPxWb3uz25`IQ<JKd-O{wmPEIj)P>dlEn#l5 z$RPLw7T%O|s-bXKL>=aKv$NJfJI-e^R0@+Lv6B5gOmFj~#-6{7hO7*_>C2zEbo-c9 zgC`8pzh@8gYbj0-0<#ULXnh=*y^5AchMi27p2l5Aqg*5O1|yLSc&|R#oX^H3h<1(- zy8k>PCx>$%x5Mz<zU!0}W40RJiY4}ZF^IdkCr0|wh3iRIi_Md5&oL`&_y4@0`l_|Y z5<GazKe<n%N(8TT*L=RP2vdt~NBokl>!-IL`&+tuG3|_IH6}Dm+t33;r$eQuSR8{+ zT2>k3RqQ@9=8fs*C9NjpLt(!p)A_D};pQAu#Yk9~Pr_rT#W<<PFBdO;4Z_MV{FWBF zP=W33ql!xFAE@$q=YYi`PmNyLcVM5vJRhCPNDFu!zO1zE>p=64D@N~i4OEPb<Ec{) zT7e+W=*Jn31GpDtq53p>7vVQvhi|$&Zf3qeF3)9gV_i<T8aSUe_UrEPhW40X2irL| z!Y@BfUVyUSsTCjBx(|_RxNu%oP@TE3yJLa1x>ee4?Ae8STVnXudZo$j=T47&`|jXo zOMKpw`s`2IhbxN?6ZAa}z-r&O&PR8gGyfGunWm{$3-6OP_(fA!VXyZdTVE<ZAqAM~ z;TpPZ=2k$|w=cA(vUgG4Lg27{XRu_WQAT3i7G_JvJGq+Ge!-i-&^NdL`^)+O`{G0^ zbdFZTMd>&==oN&`?OWR@|LGVz4i5x?y0Zoq7V+{#B!;bON<_KvWgfoYWubw(-g63j z6+Z=F7bnQaf1M&v9s4Yl%jcqBgO~}bWW5Ns!C)a@OoZ+Gff#B!aYQ4M#Xv?SA=BO^ znX^-xv;w1qaQTCQt|ch=6OS|o>L?ek=d2`In@U&UwEhbJDZsbNr}-%)qCWUlFQO`V zgbF$#6+ozYAgj`(ChXI9&w;0y8Vp|g+|TswsK7N3mi+yw-^8uyUM|=vl;{KDmtn$p z6Ip-1>{AaMqM3+cLtGs<xqx*LcrW#^j_&1aQB{Iebnv#RU`Y-p?LTHP?(6oVTs1p1 zc>7~iT{+5Kgif=}zGW1YsgQS~oC1s^i^zmH;=V>>lp5bBl_#~0a?t&#Vwsj(90SQ< z8SLjFjXR{PlWFmtHUJ$Nw5YPd7MR48ss4%66brl$h)7f}THWtdx=ZM3t-Sf>==Tly z3NpHlg}wkvvqaMQJmg8%L2t5m5<OjSI%z!_IW!OVry>&#qpFj+RchNALbx#u*j9Y< zH1()Uvi)la?98~|o@Bx=df~^ZVp=(6ejF7oLe(=-u^_59EO`Gh)X8xqsUyG}Kp0NL zoqJ);W~g6-sMAc3MxQOVEvzc2Y9QCL@&nhf!(<Htgr8N7YVcVxJS91kt2$rol@o3K zlQ7MY^b;Z~49V)pQ2XUm<Gg+HsmMsGr47-y;R!8aD(UfHdgS7+A3f6BXrvqgGRZ;4 zX*wP=1p5JoY<TFFeef&GsEmI9l#nizJj;b=Ff!1Q(u`X<y&Y$)`MTSea>6;>>OqsE z<8THOW$ju1vt2reLEaSS5m62g7Q(8=eXoZQNFQ@KR_E9VS&~)ax(Icig*FM*tIA1{ zZPXnTe}$e!O|DiN%qG?9>aj}UKs@m+QgJ`Sovl#TlyH8k^8E7@;)d}2E7x-(-Tl+E ze&4x>N&vmB7BOvKt>NnvXI9j&yM43_o^I$u_^oRbD)ZrqC220c=_&FFP;t_`&{OdO zLhpiNJida8=4RUb_O1M^C@#0@U7dx8a!Q60Ym7|;F>$H|fJ>kdUM1fDE0$eK-i)lO z-C)fTj?55pgwPX=4E(1g9bJCW@3Nvu=_s;A2CwEEyWpVac8O+$`FA8Bg$NSDB1PE7 z=egRS623Im?u`l^2*&sUh-`9QhXc~stFHMd*LJny8(MnxLsD&a%}^;yLF;g8i$>#9 z_&<q?pX0u%H_7<;CeNy-nM!hD8AhK4Por*Sf!<FekSUDtFhsR%_|X&*0`dZWifozW zA6#oiisHhPgay9wEkOYKsi^98eN(MoL{n&Vz!2;h)rCzzTTbFCho#SihC6szys|?M zp2<(8qNM!Fohm(?mXL-^Dw&M>OfWc5h-w!Qpn9B<fa7&*ZR~K)1{uBKC4?n|#oJnB zvZ%;ZDzedWOQb-3KMT>3*wSc*N;O2q9jw`A)pF3WZpQ>Xn2s8Lib~<a-MR2;DxvXE zv`%W1hr}i5tKIg_iT?z6hX-hVu5mD<{`tIsbR*Bw3T1f<`A&U%hDOyd*Kj8fl){{f zO9U#J8IZ(7*90iFSa_ye3G}z^pAO@^Z-FIp^J7H<-O3uNigt@N-P#xF@z;Y5J#>6) zWeOG%O-ZOcpH?*=2fw;w^2CNcx36y5cKtuow5AE<PHs5lBXZNeI?~1V(yr<zHB_A8 zE(Qb1GVJh`LNqxdn}nDFkInx`0<V2H(;ADfFB5J72siQj|2Q{4Y7udSA;UkEo8T`K zVnvE&B0K7Rx~ejOW#q*dElqU7FJY5MWFb82W_6z5G)z$VG$c?2lZY>O;@Iq`qJF(c z908H14KE%Mbj30*UP?tBWoioId=GHpo&dTI#QY^E+%s;v`Jt`l`K`gcQ21faKM}f` zAyK~>l`TYNam9uzrK_ggBOqcob=Ma=RODgQ%te_v;m!9(s44&#T})<MF^B%#g?;e* zC%~Q&!G6AiWksRRuuv+`P{*ups0`e@wM!-#6!#lV!i17y+wQP+cOvE<sC=*S1EFsb z5x|8}8TSGi@B@p8!vaK41@hIyqtW|dzjwkn&Ml&=>G%PURtIg_rfau|HhsgJFHy|# zw}j}ELiiyToXUeyK^TnzqX}U#BAA~5RS94+$+*9Z<@rCfAkKxiDA!F-+@HSgy1=DK zV}Xx6{0}Pry$F5O0zJ4y_{72w58o{~h$p#*wkygSeZK1#_`u@E{RIXVTX$ZwilV-% z<;Sk|iGGj~?Fm18T!HP$8o`rZ3<ek(a+HU>F@yebg9=Nx0ABIbM`D)d(1kX?Q9U{A z@=*Qysq=xu%_GN-Rt>kkKITg^yrle)ihOuA@FBwa!Hw#NUEL46Uq8IN{!pkq(rYu) zA2>2_Vq~y-WVm}|<n_qd`pCHQsLvCd(aFHkXD3Fdsz+aTkG_6A`gVO(q&zlbGd3GI zHg{rdzIyCa_t@vxV_(<DP}dGG+n6oeJQ`p=T6L3N!9LPokofoc5qjkj^d!-SK92Z8 z+!&FCh+7c9Vel{j0QBVmRp2!Q3k6Uc00gD%BH;C;qonl$2L)oF3RK@|qwq1fFk=T| zZr-T9?m-dRK3CcGYW>g|9naRl%H>R&%2s%x*vh5#@SJ7Br`JQ*njY0qk?vB>>FT}w z-GPXp;f|JxCh=GU&U)A2!OleC4_Zc!PX7N?qX`cvHhIY?G)BF+$$U3_e!=u&Up}-c zdP{QI<^S%nBru2<FyY&bed^wnY?N^3K0tD|vFW_}{$WK52|{k>`vQj`u*#5f9{CE5 z^odt_>-xfT0p(}V%f2nF7wriPZ~w|~omAVAyQt#c-MRE`@XY1|W8Jq_K8)Axs&T*5 z^<!b`+Ts7k?%e+MP1KjSp}Oa8_wSYYiHipw-M#bY*W$Z}HGA&e{rhKi1zGmw?ahB1 zdp1GR;83CqT|=2g-V_TrBa&F4!TTP#bOhJ#m^tOUBEiRDetM4zK!wsYP8icQq!W+z zIjY{6pMb+70b#&az>t>x>b<BY&!%-2QdlGVJ&i3wKkzSdsqJ9XB=_G$;N6sE4wiVW z4ffCsm**q^Pk`wVg|zj1Utt?msR<xrxwUco)L_ziVFR~3vwbBq)PY^bH|wfT{QUT# zhK10Z=Vi!6&GWOhTIXx?%|Ff8ah>!&)|dK3eQc-*Z~fR<ee~1ECSIoAr{<x*q2pU% zZ)P6ae*}a@_MgCw44iqplb4$n_(JUOmcezj+I@y?)^D*HFv-&?L&>1*-e*X=?||c0 z@@a4S)AFcO3Z-b^sh|B`>%VS!Tx}@P9@Lw|dKFRYuo;JGja8x8ZT&OHa&>|AorOE# zAEk&IgZh(uc03g8-L>H<_EJ_rbpjsvrZu_8TINq5?xu(v8mqB9iJ8~!W~GmJ!CckH zO`q2v=k`I1JqvBG;Jp^C=6Mq!30rJG);D6_ZP54ebppm98fALP^w;Z^Jv)Z5lm4_C z842PYm7=UqhIR$D4-FSA6Z5HerX~p1SnUo1U@o7LH$-T<1nOFqzcHg-Qj;;!fyULL z^#F$r&l^;Tgdop)eHKcU2lAh|s_)MrqRsQJGhouY1zO-!@6*RH7To~#A$6^-{u=cV zru3+Ox3Osv_50)+U4LPJD0fJrz2xEcgO~)m`Q!fTLFz>b>LArY!-$JBF6E`iR31mV zTb-7N?Q(usJ+{?eFdlfB%43Y0*u4ON!q1N@j)NVrvaei=H^~^*4%BV6k-m46_Qsk} zjtN)%D8-5IeU|%IYVC8wR%d*1is#q-eqnv0^HhxvyZi=3IIrs7BoxFMhO5oz80wP% z?i>5p$3P!!M(|s@pT#N!#}*w)Zvv<$0Hc#FvXc@gM&*T61R$QC>4Pqq4b(DW1h;6s z(D{}+Xog^q%uv=rf4erCU5?IY^672+^kvi>vl8PpipG%$Vo8oU?_CIh`p>Et$=c1G zk>b&N<q$m_gU=9<u^5aFFm%xJqJWLYGsMl}7G%UsK+QrmHIc(5-H490v3iC0^Rp~_ zQ$1-CM3ENZKpa<J@ygzQwUTk<4wjfwAlsAN6*aehrf0cPpOS;@jbplpy)eIP_w4_% zjZL*vVtqsaJQ~Is8>XBI6PjC3=Q;-V;DV;?<OhXFqi6^&Yzj;HB!F*WiaRxdNR31O ziiY3$<XeLrO`;uv$&;uAA|zgtjV0Y&94fw$P}WqP4LM)8tK@Rfh58GE2HIj}3I#BE zfXcC|hXCoF5}U?(h)ie?ItWOYZx&~0Cb`A4Z6js@5%j?CP#{9*CG~RhNE|AGe1n{A zfLpc&c#kMOOj(+P!r7<AZWOrsppE`C%2~jceCp7*=?ODy8@84Z$V<oH5peXA`GkGU zUa`*!&&{0NdfQJP)#EY2o|UGIi(Y)c>+6%{MO1s2x64c_%`8+BCU;iYD>p@cOpE5X z1kLw)BWK`tOb9N?O+vPM(YvRDegY7)R3qBl6WsLrf5s@(F<Ms?>?x&4AxCS>9G|=v z)+qTA;VR#oA1T)Q#*5N4=EpOwHlk_hDUH71+W<_lJ{Uapl+V~_m~)(Yz5M{qQG3cz z(w*)^zHB*2MK3=~iwGe<ogc8_Mn1YBSD!djfwIN+PSm&+QFzTrl6-I0Zm%?4q2DKq zTY$Im=V|=O`9AwILYVP51s7zQA+5rPZ3U<Y2jRmzz83eVuZLt3-(`)C8Tn=~-!)+U zeUEAy7an9-YCQEuXYN>Po#uoo7foes&)^gE$-%Pu;s`kY5547y@4b`URw<z&(i=)8 z0L)%Fmayow$hgPG%J{b1$cv6*(=#^joEGnT7OkX?-9|w;mh;6qLHWMq=cK`{Tox?Z za#{emq*qOhBaM0N4ZM}P0MFi)*=lTu*%txP{TGZsKBXS%61$Tk6&IAofX0gao~PcN zD2Vk64Jv2At@YNq*Px=1FHbh9UM6R`)A_i=+ncI>>^flmnvE8p_RUmxc>o>$=oorD z&o?A2gN#r9K~<nNPFp$k&pdq9;>6i1H-1V#fbz;O+c1MjF!BnKb>5V5@x_Rj<pKyK za`hbAtG>_@Y3Rh&qf+_G`d7wC+5sX}f$kRWLCes92S44rv+e|N+G3T4-pT=u{36HF z8DcbOZ}Xx$rrBu%?M{cvSCiBC{Nm#xn$xe}WRA({r$72IFeE4WsW>&-jydz<Sy%t# zf@IYUxuOkO)J8ImV5F~hB^RIqn#G8%-08XK2nkgf6j2@1b9&!YFJ%&#HKp623uw#% z&)&=mC{;>gXcmeLk@OH=5+i*-whGhDfVKshg(%8xC8;0)l}-x1k)icr9I+8c!|rEX zqpGA@s`_+{digc0h~wc#3_g5kVCv3f9N?3P1(?!<187Rjafyj-ZGLZZAwYC?A_#O3 zI+=fG!#rL>4@E{u$aYY_m~Qhr1A##SJxSnj>yuaMR0-J<A!hr-fJH5<%)3abempqa zEylp^TK=hdY80xZAD*r}D;|lTTB-VAWBVq>tigI@Q$xbM-TWURQd1*X=JUMC##h(n zTWPbQ<U24HQ|JY*LqyAOA9J=>7rW-n<ADdPE^0G{ps!Oa^D1Otpb&YI%p@eSqRf#W z5-p>sF&LD$mk7?K!d<9vN7GY!Mrh2zP-80CrVXwMvBZ*S2|jj`j`pLYmsp6HECk`$ z$-_6oCFf!0hEbR0VkJ@D`*_G8E-aUe>Fmc3aM<dPEtARMaR#WG4gT^~jn3H7Wsh*+ zp>9wyNsX)+@}979_*xkP-w?j60sc0NI>|ynzSC1IP`*q!hskj8lX6CR1X7Q|9<z}| z!(?^)?@P%r58M)6qCp^ek9BC-YhQ~!BFOSsj0nCQCSkd8%{%&8DAU{{OawDHi&$SK zoSHjyL`UkP6X?juLOwP<o2jbmOn7L4smX#9o+6{05+X!tfC!#_A0EJB8uMUYEWei@ zq5{VeahbaT9?FY;e2x)z{aKDmaR$@_`3worV1PN<q4f|Zc#g6{Mw^kv!v7s>W=Onj zq0@7O|9wR4T+}|pg6A2#cO0|)-EbgCh;k93ipJ5u$fwQ^=0N$0(jLfUE*xeAg+E6B z7GiSyvo^KkJi|9dJAk8xlA&72J5-F<I9!yR$`jW>cre=zRss^XO^X@X7?qS6^V{)& z_|HZM8Nt$W>HKg=!2-+!0PUwJXdLS3h5)3_Az|%`Eswc+6ucI4(;^ZWVqtu#uzL)2 z5g9>17W!xJrF|%kMiv6X&8_7KiHdLu8ba9-`Q#`45EIeB#IQ??<`BTyMJw6&a2qRP z78(56FEuoP+dZhvKLd*GUk-+t1|}jzi0qCpzR>_T&_UStBZE<5J>LPHB$m)6uQm(e z&qEZlU;te*dy%lfJ$tRONP@NvTI`?nyy%fjIkes2hhh07(fSS-ciWI4P7d4?9SLL> z3$qa|{m2MGLbND1T`^2TJ2Mzn=+RK@F8)Haz?|hGK8XkyZY91m1sNb>A6&`}%q%~I zULH5?MwF75Jb?}R>Bq$I+rns5I=TS>8prKL&FK+_$fZhaAOC%D3W7IKc3BJD%Q=+C zg56=DU3rA(3C9(kw|W_ZT}Lyt=7>_+mJ^^MpCh%PhUVL+J#ELV@ldRJE60@!v@DY) z#TqrMik}~&S`t{1jb%cGJ(sdz59pW@kz}LPc`@(WHjZ}j^GM;IQRic`vZQX`JUv^f z{HhlFf_W5?VEljuYhb~y@#=hYydfGj;IT4j&*rq>baMf{`xbnojFnh^praFI#ze0% zIDeUhp5@H<zw+Y*shjx7U-w}rndhByq{bLvuK=r1rPPoOqJ|EyiBR$5lJVow%MJ}o z8!~yI?><OknaIz>oFP78+-H=0cuf;@<-(SPl71reiMf(%=2#XP+-nU+QBfn7#MGOI zGs>kMKaqYs=dMuGt{Z~Wbp!!O|073m6<jDIOF|~YzoO&x2h$Q*6~4C`YM1ECIko&} z_BPL*02Zul97FJRh|x<<o<N@)&jgqmO=u}<=HC8e(yt6J_8XN-6koigDVaw{52fw! zb3}+L+KP78wwhKjc&V#qV8PAs2nGwvKMDvWxd0}eN<h5yV<Q2Wr5Li8x|yl6ss)Nt zz*mcAVx`A#7UmF`&>%qF8-lxVOnPn|&9-X9a1QMwBLb*!i!4OY2AG)u1CD_$@m#_Q zhGZQRU2S#hy|&H^7FXL7Y-H{QxP<decrI7J-4ZFGQ?o{@Dd~dSX6z2(+Q$wcbQ|CY zNQoBOh;*))#qfht{#VVo%tS9N3S7b&DO_Zni`KPI0eA}b9uwg!klZsHetYn!@1N#B zx(JLmLbs|xqBuR;;+n<nYbGg(7hLpZvSftd(1WDdHZF|w9(e?<Q=XLskO@OKE&?nI zQkUevo02yKC=)H_AM4v{JK?6gSOwdz>;1_6({kONWumni`I?Cy8Amr7qJJ{*Z`Qn> zCX>^R?a`1s&|>Uwpfz3~xuAOu<J~!wT9(`hcic$79yGk!Z&#d83#;pWuF?=9j|X1^ z&}%};6NacCOf~>S%xWCoBV7(_M;>P(kL{CM11-y!nrw=3!`yN#8@nb%&<|rSvbJV9 z-X44zYV;~K_hO9%vF5f?b<$7fN#6g)6^9H7Tth-BNI1pC5YOF9c$uHXyo~3^AmdIU zXy{6$)aNQ(xqyodPMZ|sc6$=GSA&yWSH~9VHC_rf*lvQ0yTL<Ui$vcOp<EdazK6^9 zyY7beoNJMQ5zMX||6=+NZq}@<Im?7g45MBdO8ybROL-1FE2@GF?BsYW7J^7#2cI27 z?lu8WM}xY*PK6_-j_ZNx(I9cd)ShiEH_8=1IGf8np+QE<O9tjJig0!u<41)TiJJ8l z_H_4p{C;_VN%xQr=VXg=Aul}B%n7clja(cTh%+ROBGlZ~?gO$dCRpJ3YjCflbBZ45 zvKb^}tkw90m!LIYonTi9GKGjzeK52fd}k(k-t&kBKV_mC++Bxqm+UO%!ln;5EDvp# z&)?gwbK_1WJgDnRi+YP+)m_pF#2^)MAYJnJBC1+=$z?!1q81{9k*65mTA5AQcJG%1 z*yTmkk^lp1BiyPY{3{`tpO9)#qpBy^0o*M%!2yKFT*uqiBJ@=r55-)>G*B_ln(b<- zV>cWxS*nA%8%i}%n7DwKosCVdW@qg`pTphHKo9aTm$}HlB7#$CzQio7?Gw1Y6`3kR zK-uGx)7|YmLBzVOkqq$<ouK*?tlvhAHYMDR0wt;mk;(~&D|u7Lt_LVxg7=(zgM?)q zAM^i|3nM=AGCb44C0yqbN&v|fP~4-z*uUx>t-Ap(?MoHj14IbpZczR>DEui|z&NN! zB+y8*O@{TvVjL{c|H(FRV*Dn+8@ge5_9lAxI;Udx-0-DiW&HdGwXOvJ;myI>2!<ti zhexRA5gw2cG2NJxyqww6EC6gG#v%Jm3dT^x5AuYgjuS1L!LKao<{3=sLD1xlRnG=! zOC(B4#bJ9zmx)B{Ivjwl_B}N2RK|rtkBzB!U9YMitLjg)?RdG8W0ICqw!fkw5e4{? zPq*<1T`Wu`3;mac=re4cg>j*5WQw6p%Hl&rJKdlBbgB`#&+#b;VFDnbGgB%-v$XeT z&<`elVde!k4$dTt8axSn^%-!<wuDRYJM)xdVe5*ugc`m4&Bacz(#jZ^1|I57;(rD% z!-Dg}>jl@ZW#50CTD&w_+w~^A5}j7h#SIxsZoe&l&gi<_sk#}|Jvy9Jh&;v2NPz*{ ztuI5Tk<SjD1TSBcfS@t})Ja2|;ux@y@e0m<ePFlL3cWuYi<#cwm`&(MYhMOG2#-vA zgLlan)Y=USu)wXIpl}jBM7?vJjP&IV^-bAZ7MO&Q5o!VdwY0&RIM`2g+zGmA^6m=u zZ+enBh7JIC-(bJpCX@>i%S_av3GYz}%=$Ux-EQP5ZpN|O$k@d>6n|QZ$VU+gt7ix% zUL$(#TaHWKsi1!R=>(3`gL}Q=XXv9Ae8Mmf_s|9$Boodt;X_a$54i2ERI}gzzn1MF zGz$?w$5Gb<C%+edkjad4x^##xsuzrKse~>v`VI?ino9UbovSZ#J_RD<02JaV3K|1W zG$RmlA~*$kqSXcU7+o1VZxuHPE_qsim43d_ApC3qR(o|F64fs<5ohV9tEpqzm9N|j z_b%N@c!zm@<5KazgoG~&17To-<h>Ew5zK^8+(N_L6+Nm<Xq8|ikB~v?&n1M%2Pi)^ zoC$?JMtAGmL*AYGBNs58Feu&Ces%crZX1G0;^SQ&DNuHO!)*+`8dl+t&Koc77)2hr z^v%5xk!giI0c!H22ZHiGWna9W<ODZfD5E!_8U@zfZ~N9*Xx1f+Rxf^ou~a$1li*9x z$jYtqL|g!-A1MiUP5yKlSABm+Buu8}J$T~V#n;05-lDG*3QV~aU!C~0t_4@dy0q`6 zWXrqzNpg9U2mVU*e6l=a|H11}zy|Y^)Wgm{y6rJkge%L0FTj1fopO>s&&)$tjH4!A z*Z_fGtE%R?c93qNsge_ed>jBks3L0M31I%PIepqL6Srx*Oy_P@RthNZbGY*g$tiD> zE#5(GytLN_=zM&5Y8PG^SRBJTq-Q=--U5tI_3JLqDFb1vuP1LE#8g_@B-KVrPl!g% z(*-tr6C2MOxUFf8oqI4ZQs4VST%P{r@!9X{!O;tj=X}1r%w)lQh!OSKRJ6X6O@G2X zNMYN2!_LB~7wivW$~40c`zXE4%^Avtvf?Z5Qz*df!z^@O^?|&dWiz$!wQKk`M=lH~ zCSZUIL1C7P*3vBs&zd%h4a}yT$a26v^T=Wg!V{a5K_7y9XFpvGof|#BBWtXC4?pt+ zL^=M<gFLFX#J39yJs}KLcG9P*7Ikhu)f#GqMrd;7XELShb~vOkFBrHUy!pl%Q^^TY zm{%~DX@RNehqpUmOmpq*F&7f;zjRnlO+j_^!bCIL=K(()t3G-r#~gS9Mo3%j4AxS0 zHviZl-RAD!c)>F{cvki3)GcS;>3<MI7fP1KRsJT~muf`dGjkBX14uSDP*<J_A=v%| z$amP^Ej=i~C5qXVkuW=_bN6$<qh$OByTW*>GBeqOCjfBZPVbzDwk!%!^<H7im=1^L z+2MD|p;50xccalN!elT<V|xd#kyxO%wZLF(%7GWU%-5(%9^+-I?sf5ZK665Y=J-GW ztP*$o9^gE^Wp5q-P)$)dzIRvAOp7$I%PHq+-O02qd6k7-{t;)rh5=sr&hU@*O_dqO zTdq5VK5@lv>7t{WFF4riy|x<U?Y_AS!VQ%Rb3gB->Pqe5lzOh_II8Y{vU=#ech38p z2Tse^+L3L>#W%Cch$q)62J&5DW2aT+_9_G+N}OwahFvsEIi&zA*9yG8rSV6{dsoCu z!NJ|Uni3MR$^6MwZ;7J}`-3siSZSh4*XZHY1iRnTF7Qjt=!~f2Uwd%jl#FB@c<ITY zIvzkq4sJ}<T`|Zj<y_^9|5KDab|miFiH767^(Dw?qyAOP>)eA-D%yNb)Q2WNv&T6A zKBpFG=bjiw$pUh0=W{^@?_^l1e$(ly5%^nKWwiB=A6(kDKB(4rP$pRt^oOGO8FIbz zgZqRx#%vN|KG!uV#=-*hmDqFrnw2N~a-zx-Aqr{!fZNE&FLzqNKJs?U%jU_4aUn5< z+q+Q;K-JCQ`?4o3gHFo(8a&RFj{g}vOY;7;`_73Kh@ms(Q}5Imu6-vRb&4GuL8#4n zpCX>zwG|#Et&QD#Z6kS&YZ4SL|9d_|c?=*}o!CjXSFk&f9MW9@9K`R-R=HvG?CJ%< zmJKs?W8%uVX6}LcKADP&2Q6(^^ER+)GBaY9#m2*G88V*fB!NjtW6EXOhPgAkrti&7 z=dJ=Q64YNBkhIK=)Ua1MWZ9>u=Ya+oG>lmfbeDp0Ei&?Otl9#G9&4wB(#$1<c@gAy zLV$h!q3%2vzQ*_Vf*3}v%ET1ZKzw!RG~TDmXbA@4ifu{jvE-dls+^S5W+1|ma+;Wp zy<x)Lgb#CrLTc^)Sqz?{q#uV?j!;MHxzQT$Jj-<8dK8m0MgC%##=kVD0tzUBa2?mB zp$Ca*i+e`>1&u8ACXL#H>Cfr1g*xI&baCq@c*&VZiDg;<W7GBdY5bQB|9bl{BoH{_ zN<Ac%c@kKxS)p8{DBV&Pqfe6hyuC#4u-!`iLIj&0M^^bv&b-kK&ZW2nN<`W#tx@5v zmqMhMn0u5zS`y<%LY3+*GmMSf^Y#J4%JKdPr%mylR{mcUUPcT6@R@w|C>fu`&nV-o z9yuCr?NXN$VFr%PTzWkOdrvyloooiy2;4lNt`Z!X5XqFmbh)8%L{l^SN#-XBsfl@* zcJdOswsNx7*L%>RgCaRN_%*v!VbHv~xMt<f*AoMKGn4_t`~INg5gjFz^6+AF$CeC2 zAh$=Z({jM!`sk5uANzI-1JFLR_A0yzr@as^E~g{MGM)Nh!*pJVb7$4H`rX%e`a$7k z_8(FiqqgAeUA60C_L3)>@5_dpJC65X4KUWtRmV#8kj7<oF7_z7&+96keG!H^0Vror zk#ovfy@C>#wlO(LR;FaV%6f9f=K5m2gjMxx&*40r3z8Uv%~X1&qYD%}VgOL$Fk12b zKYV=7X5QXQXUVzxZ!$A~l(G>}$a8lV0K3;19h(zXsjz04RUXI2HPZXH8WiJ>zPCU6 zLLiyY4$X_2v{&7ylcg<S2jLH0hD!#gQR$H4l!$kVlc;aM$B6|I)uH6M^>X7*b8d9o zLn5Gae_N7W=6@>hO}m!tToyNHZb_us2hO5p&u;XdDLTJI8{1c;p&Xp!J>Q$d2zrzD zMIHY?M`ZJqvn@V2H-LVfyUA&#uQ|MU7k-vWtAC&wMd2QHu%{TFs&K(+6SfTUrQ%VJ zTXMBCU;7Bs#1{V}<h=uI!>zh8ub^+%SZYAU%)m8E6cEKPiWZ+|?+O~R*>53f_$^eX zg2mDP+Fp13yUys9IbZaw^TR^@GExDAmvSYpVA~FT)kCc=!7ED`jdg$gA{S=stL|if zVE(4brfeLnga#_khQ>s^`Zicc)35F!=7}nG4furAc{}-)2=Q%h&->K;kp1(P_iaib z=+tJ(XII=`Qg3h(ZlYnUIU?$8w=icz+K9iq2|VZzy8En5|K8q-__lY*>UOjYlf339 z)&LW89jEN1!bD4ZFTcO}^mRq39Q*y5;u&!klO6anV7I1#fl;8Sm(_LlYdRSbqMFYs zt?;roCwu%azAf|DC0%Q|?A!6W7b<NbaNsS7GF*oM*LPxt=xGk;_i%7$^N_#ObV!}) z9m*sVVZV1B6cnyteNh}`pWwWjFdf}YpJBNvr#+DpJlHY+?Bs}La`Z0_HjtjCP-^$+ zhrmPTcLidLTQM%^wT;}1&VI|n&OCm4sABzM7H{Q!QC`)Xde@Z)l^COolv^`o&PT__ zv8&>F>$CfD#($}AJ@G*DMuFj|rDsQpQNc|KhTP#1`c&Co+6C4_%8WnimcyitDT5gk zKDkYGat$*`?voi*@Dz9H3BK9A#9lEgni+?VPwaCN3;ERdFF7Cev-tJ=q&20Bx(V=m zV|0RD&!J|<L||h?ZP&r9KZmm|jL<R(sQ&CCaZMwf3bmX%?@yI5;9jYrmtLQiNR2`X z&tbr6C?-Hgdl7B7u=yoV`|Cy96kbNMi@v7<`Vh0&-H;R5oVlwR88I*35y4N3#3aCu zqsi9rk+ySC)+2VIt6pu}ldMQG{O@m6tP9nR1q(`+zGi3VDaeT98D+bmio38LWT;~V zXJ;KuCDeSQ+EV?4bhcasgv`kP%DRi3mM|WN8qYTr-O3q|Mk#!T8@0p2xX7%>$Y7z( z?odvoC9J>_=>;OhO%W@4;dh!{o3)9UJr!3;KCC*Z_iC^eIA*TdsmZWwEcl=1%vh!+ zyx&&L{Jxw(Zs~-=h$v^W@s7`%D^a(vM=GsWmf!)_?F!6%-<79+x$z#7vM02^Zp-{j z*=l6OIT4W=4r;Z{!;HqW5&&ed*xW5b`mr*SfD*UvR^=)!wkS=!#L<??Nf|^KI5>Yu zCggQG0rP}CJ!!{CN<L&$Lhsr0WMkr!0*)nwO&u^8+Rm3kMQ<Af6;XY)oMwr88}7H9 zWNYhE1TYT~Cm|W(G>?pLM((!cToF{KPU>vsk^b$<XSZj=+%R!uWCVj+=7loI*wIUF zN>Sj9O<8*Az*&Lj_Qy@_BqaZjqH~XD^8Nq#4mM|FW1G{M<DBQ%$Z2!V`4AE^$B{IL z3Z-mgMh<gGl(Zp-Qc)_M4GE!zO2@A`wWLBS$tS=4{=EOZ9`}9S*LA(G*ZcWgs&ugv z1H|gMw<@wcl0814&t`)L`G4>+vCtg(JLBh|UR~~~En;bWXo@Hn(k{NIt2tO$l*tkI z=NIfUaA<hI^^er))RwmI1M79OPN0kIax4q+dN-WK?<q=KbV6cAifXIC!|Z~nPL5Z{ z?K?p%O*~zvokn9}G-t4yY~VKu1;+rAt(wG|GxMq#U>;umk02wqeD_iYB)47sGG8oK zQ#`P^Fxb;!pg`|Slhy5fuN}ZF@;AStJy_zpGV-HqHDyG6KSkg0Mxn=yi&Lu2!*`M* zsu2wUx_6oOeB(YzP;A1d6^bqfdTHyWEphlkZ-A5eh~n(CQrjkGB5OQ>Af6Kd3hOP( z9EK#!7VPiZwJ4+Y<uW*JpT^k`X_Tr2zTOg8b|wo9*b@WI1zd5fE8I&lGR5^sE!P$1 zUx|GnJ*mi2lQ(RMku?>{*%dhIN`UTF*#Nu6qWYBAyax-|+Ii01QGD@(?f6h3BS%=Y zzY9Zh_7a!X(gQGd_kqRo<P60CLBfJ)Pd}zmN;^+3CxDrQgXrK2_u>i<02ExlT;Wn| zA8$!EO3>AMX*+OX{wjr5{m$TwfN_8Q{_|}gLp(alnVCIPaP@(DOfnRD1yb~ux!qor z!YK;RFAPRQj}D7b2?de8#zqgZt{F1>ITA&h`ny#nJ{tM#$&(|`FniXY?vs}~)sOt# zOjlJMKGS^OEt_Mw-Uc(MygfpH{vP{X44__z9{JMaq{KPY2Z<L#`AtPW0cx&FOm9(; zBpezt%S;+BI2C^DuGrpYZn-P2V54jL#&AWHr(a~9Wv-|#ejb|p0D5xfRw1D9#l6rQ zt18g_V`n2EW~H(RmCv3NUVlK8%54IwwA0*hfh!xewu?w)FK~~YNlsUxAHL7&rFeq; ztIXrf9nulggoIE40TPZbJhk~8koVeZfJdek(85&^Ko@+&%>khJ!P#5x()(`nnaRB% zH83EsOU#gJ<l@p(J^%Wkmz0So1Sii>{X&0jA%S?IOWWK{>pktxE=tB1MpLvpUNS|9 zuAG=cTgz9c-HNZVpjm)I@6Dn}j-hkOn`a~RS+V?Io?;I|ByJZ<;6D^a(@JTcO?k5q zDS#rH^D7!bTojH9kC!v(sW`zY3IrhY&=A{Ry7X5un*e)}kon?bSfd-mD!|A%0OZOu zgL~DRQ0O#axh<a=#}@Zy6ZJvQuKXNn|ME6osVIR}m^=F}M;;s<Bkqs)IOw~7=SQVV z5rGjMz$)Q5&;TxvttW~IH~-1ADCo$bnZiu@r(ye<21lOeWEWTlh?!l2q})Zm(rnE0 ztyx#cXl;h+%<$d+b~I$SC2vCJ?VyRh1uxw+q28>(7}1mqujwmv`D)=i1If^Yo+K1n ztrkVDiX9cr`R%CEb1hS&ZlRkM^ANycz@@@jheE1DsDeb5Sk-Q40*&*rJ3!noLWL%L z_bHn>vbi51Ecg`x@#YjdJU}*cK=NYBatX3yJ_kG%v|-7rwdd8-3=KnB74g(23h(X5 zcL(Cs3wN$U(`Jgi`4Et!2rdZ8q7)oy57kJY757sYJ0w;_;nO^$cL2ltMJto#yP}h` z;)T8D-TZU3zFF1&nCN$Uh55|gdZ&@0yLAos(L_7CfGa`0V&ZqnhME`+L~w6x{DwLR z$C2-yWAs}}SZt1;%PEM)83HKicVtMYyr#svi1hqegVs6ke8|ZzX5MgN)G#z?ws8Mu ztocy8d0=FEE{puRNC_ix3<8Hh0LgGxq`U-$ASjZ!bc8^nNGW8Y-_x?++yLm&I2Atp zq9-%-o^yr51=(~3DOjhxK+@l$mu{2~vK=-!Q!JU<Ttj1tM*xgm8X_bgs1LKdQ_+yT zY-Un;DGoZDPKA)!P~>iLUrtdlt1z4|QjRD5cw@CgMhj>$VhsEQiIn&UUv!EMrM1WX z4-5$VQF&AIGZ9`$)+|bnK3xJROlS4d0+>%~7@;!-`?AG!*=6BcWevHi(mX#8YQeAE zPc>_j96x1RzRZ64!el;Vn-~??3MuG|@Z^hEr7#E2#B$~fBPAkpXT{xTn5S07+~teB z$|yf*dvDAX7*lnw!CB#5EQL6UdujLNLZv;!KgujY6R8kOWf_8Sav#4>p+nL`!j^4* z;AcC>L&S<j<6mhuKT1AdA0Uy_EB4cB(5Id`kyckS5D~EY>7SCYOvp?y5$8D+F~1ch zpbMfjANCC4d~tEiP1^!Es~DJ15d-YJPm}nN$l`g<*DW&BXCQYm%pO&PJnDo|AHSS@ z-dv?wSgvTk2zEbOa4Zz0l~31UvqcHzdO+hj++a2fnXCxOldn$B7R#AoUKxklW<ZmM zmnW}@Bw|p{S@B#JG{ckWoj)H%r5}ljd*gQ@G*IG8?!Ds@^HoSz*9=N5iFJCt2=pBv zTVB5K%^@&S6#CiioiBc2Z-sZc{6We3A|0^d>>C|TI+j2)5;9C;7<CbM&(}#Z2n@er z@dyff`ck1U`$96I^AHjm)mW6q5$C8DMi4@D!k|8)@a!rxx2`CBR-7s<^3E>YZ?j6w zO=NCn-1PR#&@5__r0ht&3Np@)1k4o3)6O>r+)#%~nNt>|mchtl>BgF}px~NpcktUy z$h8ypA{m!20XjNg<IxWBM2iJ@`b4!CUVX`&Q4>!KhaU8VUKV_(%!>OCLkJTPQ%b9; z{*l;ZA;M8y=0G9~hy)Ez*RCq*vdYd(^}V)O`x&s{GLWg#2fB|?m<E^v_#pG}f^4=p zy0R#K7#g@ru&68aZ5N653J2k$5f(*nLPE0(9P3I<{|<T2e2>v&lCjXN_M+oLMzY(x zprqfTy6vkUb62o^?eCy(a#n)6ARhc5QChP5&zT+eN^O{xymiCbh5~+u{B9b9G4BH% ztZ<04h3@PL5Zk{RpToLWe@G!1UAR4yxPKE8*(>JT>mEe)j%6`(h07U)qLY0PFHI=> z(C<1F{6QkiSEqJ|(;we1rVPzDTBTcF$V6250EF!7HKf%li2JJdU6+l+`}61|MpxXA zh`xe-b%pmoKoW%oQ>jfS@P&I*$K%;zxrDGtp_pf10Ulg*Fh9X3Ts&DQP97G!>*rN} z=eV%0AWb&&6!1E0w(u;#3P1o`aO6MCn(sfAwE8d8)K1DH23)pZ`Bk`7pZSYtbxe^8 zC~!4C0PPx&cil6)B|sdyCK*EJh~=S~WI{13Ni5vCD5Je7a#$>r4NZ0y_nj5<pBdk| z|0(a2#C$M-*%mDRQCj@b)0Q0S`vCMF<Ln-NZL4+JxzCDQFsp?XKPkox-7#DF2|^+f z0I}_Y<gnbm`ye?0r%)C$F(5Vv@T>&<D4A36oYdXOC`_gny0Qu{b!TMt`hJE;_|E(T z;wY<{{RL7ei&Wt%c8~?v59*|>X$_UC?9#JJ`gY(N;~$~w{q3uqM^T=f&Im}!XoC$U zaY7+ZUN*np@)ls$B~e<Vfs`DC4gNgJv9&$ZR9_8E;zc*v90KJ__n8H*v$4;TyhCi_ zN2*4?)R-K&nfSIfaMI)J*RGtp*tIxja)^W9z-HyVxXCMf{}pJpaq1?1ZfCFrWf{6% zp_yM%Cff+cr$r9L11>)_sq<I76dD$~ugMjXKV}2DGp2AZc!_8c8*<-$z@rrDn8Cq$ zk(keGP4YrA1>o7S*6f?kKmv0Gm7g40U2JD_Xr(7kB&qt+C{wk+cVlT%HSBv`i_ONg z*Sn_`FCKZ_{de_z>W<^T?XBNGoW>*oRv*J%Dh&YqreUSqHR}>eCwj0`YEHLmtBDaa zuT=aM?}Y}aW;zqWvaYE>KtLuA(x<(rX8p8%t#gsIWs@k1X7OsDmcPXmzPiGoXH2^^ z;*C#cvE%axi=~m>e6Xz5{Fuv#_UF}Lm{XfXH42~&Tn#@JmHS7xZiig*N8aEAAZ9!t z<`B%*hLmZE!==`F!NI<jME66n4T)@YJS7_eNbRYF!m%Z+PsI)fmDsFt^-Q0=kuPV8 z?O%T#E~!XPuJ*MUF7S}8%6u8@YyB+08m7^}pMp8vZ2<KdT;Fz?sk`+y*XY{a=oUFZ z*Gguh%RRJJ3Gv5+oF~S(5_0UpzCU+s(7MR1cL4!PgYE$sx@Q40elV*E>BWNk+usha zf|;)KCnW**h5g#NKc%;t4LSiFAInkUfRyo%2X4NRbt@KfyFP@tJU4CTTZ$Y0<`0ZG z{>@&muw^877!4^Od|-Z3$cYO$S8LuQqbgNa<ch1EnG~VOENtH)03j@ekYLBf(DOu- zD@=%D7)8J;hI}?~w|}UnEmb!0roY7go?3I7{`%5zt^GKFQ}&3{3(B|j(A($Fd(R(` zHrNiZeC<>p`2%Li9~(7)pZ?5YmzOXG3LwD7gW26-HL=CG>_@GN2M@8amH@rWHcyc* zN-Z^aD9&|IY)0Rjgockn;JVftfd5RdLh7BD*?w&BtEtz%mSqN%MWa&3h`-XW?K!x8 zvb*?MaYr0xR|mX|@16iTJG5<QK9A{{d}#k;eBe-p<vBorGN}&0mpO9+l~ruBHA^Z` zyWKfg5G4OEzM=5V?N<@=#Kri?xvJN1LU5j|z{l{N{XNOjfW?%TYC=kZOw_OoyiL{H zF-zfkkChAhmNw+|0~@JmJ|hI$?4g$tSdrGkP>P=|aN1Hhy<dJIc49YHDj2Pot}}=I zJ1n+Ks=v$|;H>c=9|TCmmYB3a_4jv4jxF3Fyzyz*wC5@poSTG*UEsl!H%GLkGD@Qd z8BrCnLt*EbGMzo;%C7~L4{Nw(C%zs;-2}gUE%mAl9ZO<RNaDB#e#Mc7dBuP2by7dt zpE~3wD+79=B+mqSpGY9!O1qSA4XIFj()DB}wf1jlwe274C$3wF0VQJ|M0W#ta$N`! zViwhu54r8`p+uEe0k7xGUfDebcw&Eh&1^^K%{4l7zq`ZR@Cu461M`b5rn4=m2oGU6 zp0L-ms7_WufHc(rY<H&?4~KA|v)U6-pY8&Ob$|f!zl^QC^Xm1m*V0lR0MHZ=AA7zj zykEhqT}-|a;@sI8t5Uv4&a&5{Y#~yd#_5#;pRa`N8C*Ac&Pg!t3oVl_k41kHAs3ry za`7x4;tSyE;J0*GLPk$BCPBiMqYP(iuENjsmFP;XBMzr?t?lYZdRQz(tuL!8kIh%Z zV2en0{RA6s(<s2XFQUskXiVs8AKGT;Bh*%X!w+$E=EC+l&U0>gw?kmi(`1o3K|!|& z-$0ZK>pJ8(`WF{5HR_R}v!kOT@%ggpZBh6Y7pr8B0HZ|xYE}!aMW=6$BTqI5rN6Qw zJv#?RZvonHD)A)`sjl|rMCafclHL7)*SZV0>~7S}8K-!8hqT!}yYhB22EZ!R<C|+z zBjYqmou3+HypZ)9D^X8*Xp**fIFzj(@B8(fxU5p3q+0+NmKRgvTM(`<1I(BCaQU-O z6@@!^i3<zU1i`ENstqs$immJ-oQr-%RAjBvm{)=$g;&yQK~=ry47HBW(Glt5xUGwB zdYcMm2O|em%yitH?0K^O?D<1?9q@F^q0@}%r<xj;5)M)sB|aN-G9>|`92&1sFvf+^ zOfJeJ^i`b%I@UYO@yLTdHPE3voU8V^So_G3=I6k^tg~kZr<N|kzTcSac+-BtXkxQA zPnLm6v6?bnKPdYz0<7LB5`6R1B|_?~d7+PP)TRE7=>){^ssVj?DUt-kxL=`%?W!y1 zB`K(5!6H|KpXoepllgPY@5+mVa}h3uBn2AO=|8o}Yo7Z)Qy0;lt8>doUF`t&x0Ia{ z-Atsmt|#|_Qa|)=@Uko4>Us=3?$&g(`_(NIG}zx4?r44aXWafoLmiD<SDrX(a#=wk z2?LNdeDVBygcS~Zk{Db<ctXVjLc%0tHA%80SIKy^Y_fHRoa0?kencHfHO_0O9D}X+ zmZh({#oBpd+KWAqLXA_ohPT*d><J_H&8d9^JWUu1lnq&7sQp(bE`plm-)z12zkhx* zM3rvYVYDl{ZB`ucD_ttDZsTy0^FRq=R}<aynu~iwy<Y?pQM}*#dI+aq`!=V*q7OLq zu&Y2gty_Hb^G!q#ztb=syVv(nib_3uV}EaDsdxC+<Oh!EW}+K*FniwO-;+VYC~(|| zLRVLc6Th-!^0VWBm_QV7chDqOtW!uDC)x`Jc3a`BN+tA5?jzr*w^WPodvG@|J5pnY zQ!sW3D_#3cT<H)|k{kWx{{A-*i(mT;yf2+q+>&T#v#d(V=#WqLW_5Y@yJezX!A%d; zp4y5S_2n7td9@viYsZ@B&llAg?FWX#*Wspe?m`!tGj)Z!irulTK9L5_iYmIz_X*@S za)7E++u%DY)OMR5X>qyIbT07B31}m7ZO<h`UvsIvStAp_3;*VJewHTVj6byWM>$wz zmmkarH*Ifj*xCJ0bV3zmUpnQqZ9p%hd-|)@^Nak#1QNy#5AR;#CaVHGZh1}&5#NiF z?bP=bsVtiA7)f^!Y%)F5jP}g(EV1tb-FLodAJD&N98n6A(rB?c_&3XIJM=JPZ* z$#e_0i&Z3Z*9zEdkR&pF*ov$qksz%V)yGdR!v1M4>%LD`2kU7PjY3H9te~Re9pc4Q zV!CUjU(E$Oo{ztpX7`60_=)Oh1D@d^Lv0W|i61bJgy`1M9nvAoGMJ---j29|-~?HN z)C<4&GOQ&AbXOVHbsi4<0sDn2eD7>RjfMjSWSi}CU=XB(8|a(?%iA=;mitG^{d=jR z!z%rMy$F@}B9beyL}9;A3op0}>QnDIGQ<4tP~QD8>f-jG`JjtYO@FVDKD7bTO?7iL zcQMQAPyFneTi<WLS%=@A!LiR7^^y#F1`TWamB;!Gvp}YUB;zcwU3|Yy-+m08aq1_~ zYPIm;6A`t#QJdNP_zlB}-Rv+EN?f3;qz3A)Kt(fEDT{YiQZ<FO6E(L%yx1~STr;en zt5sa%pB~85^--`N22Mu0-R*j2${)7k(@m&*nrJU162Sl}*ldF?ItChy720Pl=>JD@ zOg(Qz?Kc>so3McvxF`pXm(|LE?ndF$-lzX5gPzo#BYcd1%#E|=4j3DQ)YJsZ?LhSw zAVIcBX?gE_=W{*BXDes?GY_GuLf(a0kZFK|+D3(Ot(zI%#qn#u6{jJHykDd?xeWwZ zv*{wa%)JFLV2t5Na5*+zZt95vtP1QGM2~dbn49TF;jU@0`5FWJi(!NV8x~;v^z<(8 zD}4zBIOT&>jX}v2TCh;5QH>K^<=OZlx@dz}@=!E>eq81nP^qgQJx3ze((PyaP4mlJ z8YcEGFi^g-76GCWf}!^!J!9!M3k-Z}N$^WK)3FH~8HQyl*kSOQjbgJ=Hpw<bvPNmn zmc@3nCOK_`wGCU3#_qF4i<zbpbwfmOAR5x9P+ugl$)cfKfU0VNjpL2Po{;qS5q>@j zBIT?|+N?DQE@jb87QkUOXAOidvsXnmR+5SQnPgB>#TX-kdj3u~$bvdxSvR;p6-?D- z<nUcAdqH~BV6#3D;5|q7kvL$1q&@xW=r!S?<mpGst{Ss+_%IL<PS?!>2HvJo?LGMq z)DQSd7X_kjq6dr4r~~R+Uo`Bzw+aE-H@FEOwA#zWJCV=Z<kNNQNMZ7r)-L#+Lwi<c z>4fcPg_8riK8y!@!B+Xgd)XwX_p`FUz#acF^c4}OUv+rMGEak?kNVMZ6rNJ#j2@eo zwA>yPf(k?qYOMhk|GnkDeT%ezag)t6@KFG;`g{9;@Rg9gEBz)IhH0#a><f^p>uk+6 zIUIffeWW9}n`FcKTvyxi;A)^XVZ<~5XwvB-+vswI+V6mCprsdIfPTTeaXAV%B4*>% zL|!8t36)P&$pRkaK$WRProCYo7kcCpE&asQh4+#a65TZ5#mET5K!PY!0FbdSYXS64 z4ku>S6l!<&+u(NwZuv4&9YH^BRgPtg>k-;3x1}@smr09$)?)*Xo*>I?P!wBay8&yh zGMobHOQejR=vCY5L`ECX)nb79jR<4|&vqn^C_|dpDId8!<a=xSYT%V<E;0HpsB~XS z2rvJx9M2rDVWGA+NJ;F-4BcfJ{Lrr~%eCz1*DJT8`t7sI>Y$zVax0gLWewN^_A(^n z77g+cUBva**>r)0cD`<u*FHHI$s15^prHms{L!y{6~((CzL{$Q6Q!O_8$7goC{dGP z&~Q-3m1sg;Ot|X3XU6FB0{D{a(?queCTh`VbDwS)nDl|drre{grx`{y<BlsJonBe1 zL`kd39go*1O@tF=Q~!bWhlvI{z??~7w*ZF=U5fsSE3LYKM!)8~4@v(}qxiFbZ+MEw zBuH(TC*MK`MAb$txqu4G_fiUjASM;l{3Hiq1pdsGAymElwY<Fpj=dzk4VQDHN=EGi z*iIKa*D1T1cwyspVW^CLc)yY+Pb-_I65bj}*Xq7&OnG!cGzZm<{f;P!Qv5`H!mE+u zN#uY1#x*36my|A^;m8N6)J#<F*~^c92laC~){8x6#c)(?W<N}s+G^m%o8j8Q4)S2T zQgLG;$(&HVx~jSLsOvpJeK)6HD;xwDDyj2nC@aW+7(<`>m8<H@TtlFe3`t{QXRm6A zu2SGDKpEDe*Ao{IINMFfrFQ9T(6efu?2X+2@Tlk`VFz2Y9b-t3eaxnYE<Yb%Hthpp zV&kk<8KwbWoyIiuJInm~@tC+V;Sfm==xpE<IiKB{1Xl%6X{b%HqHH}}=<5`gadBk7 zzLIQcw1QD8-LaFTTN-9jN(v*8%ya@QocDNUtX-19ZA5oDmeNhL@IPxitn*hPYap|R z0Yc3ID|xU}DG0SPVAttl%AuPtcH=)uHU4vf_r>nQ8p0eTin4)9sl<^U-n*Y4lP<ff z_9)Kx&~!o)jMlFO*ou!<K2siav6!YGilra%d}rV_ek-cv2ebQ8;ttrzYG7k1?5od! z(e+BlV*~c_AcyIJgw@y9Ed$yCAe#+_Efs|KS;6nhs+0fXunk5AfU;6~nrvefhvwTr z^Cgf*Fa=5zKvWh_bBu|UPY|2%EG?D;z9A*5yEv*fJF+Lv=mj|Xf<IHGP@g<aOuwNI zfi1E?4wQk%pq1?SfvUcBUL>hH+r@Q}>@Z6*(dl>GbTNGZ0(1_j@3sp2;$i!3zf%_& zZXAc*2U4d3N990yQifP3xxmqRHJSbk!`jL%JmgQ(p_6ChX_@z^hW7TFZl^)q#ZJ?J zQ9-Queh!3s)WdS@ijLy+V--neBFQm);P)l-dK<4lXLc@HuYwI$NNb)9Tano00p;jX z>y-JYF$LC09Ni=p^t3h$C8I0K5v#L5XliKUmd^actg+-Tna<J;_7(|a0;ko$W-BDe zu?VAZSj{!d4Qzl(=h;^Kc8lKExG{!J-I~M2&wZo;UOb&p3jRZ^+121;>HLP^L$Z?r z<J)Xb_(QvquI8_)_SBW+Re5!Z3>6_>Ug1)DN82HApQdru@+3X(C1uUF%oGnET@1E} ztTh?t8IDQR(EIhjXKf_xV)GmB(E820GK>yV7XG{!tzXu)2VU3~>$SMp@m;jH%gvpk zT|;-uP|$8U_doQ0<QNE9x?-uiMvVNCp0lGD1?~%wDnq<ixoKUrX;n1E{-OtHhx`Jm z^$l1(IP3TmWSE={d~@(JiDC$AoB#JrqVYWB(%M2J-KhPQHNo2KD?^XZv0DXcuYmBU zzLkB?ai4Md^A-djjMi5~p%m}gf2Ij!#8<hrx1c`tRTY#X!GI8IZ%>LhC!lNPEC3%r zXZ0%t-E|DC^^5Z;m*+a-ZU>iD-buIEHT^?knUqXhJy%UXKQNn51sS*ePxOIgUS>4@ zu<h~~Jn{FB6Q2a%1|jR7Ay>KtXjjyU_x?4dm<?hTV<|TSXi{+SGXYdPN1qB1_k5)H zg+e<y#P}?R!KwXv&~mndRq6kICvx)D5Bn98T5T_H?B4m^M^1fpG3I~{I0qZ!Ne<LQ zU8o0c@?TEuFia^lTn*jG6NF+{C_KJ^8lxd3E-%Yn;$FU%u&i`bxy-~K<ZY=c+N(}H zI;|bvZ*Mi5{okQ!YIl&^UbBFU70O@P4=z3U0-EgLNFiYcG9RoXp=Pvk%@u}K!L(B! zNJs1@Z`VWDv0b}62e9EFlUF2-02)e$bgIHQ;(ymQRR^_OXb5}y?cf)B+o1L2r+VA^ zHIq$_g9BzOZTE*6xLMF{>8nw=Uvnw=$MT<g0|)E}`-@B&--ho!zq6JY_hEplZMRXV zQt&Z!_rnGK!4qL)$QinJ{tihmo<!aFee(M*SWfGZ{*$XCw-ByK+$~R<#4*NHzg{W? zfWK(ZB8q*JsJ?dzH$ObBDQ|>7b3b!Gc;w05BV~pEp4kgeILJQ=Lc#Pk9bJivk3WHS z{VK%g1D&?F7Ix>A?>{+un5569BRDksW!iF8X9{35xU)@|3A96vn{ShZtjXhn53}AM za_sC^7BVt5!SpVmbC*Jb(SaNBQ!*-J;!<ZHCBD@prM4RXuRUt3J@DOalenRrd-#|8 zp;z~hRJ{~Fq2H=N6V94mUDJke{wHFcEdONGeAd_va1yak>}n{1%^sC{d+*gG2e<ii z-Ot#aN!feF@9Uemr1G68ZSQi!HyLiN<C-SU;^_wG^<+gih+BX|H-+eH(Ey4`)v;1D z)12F`BQ8uC$|K9iVwPW&blq9#3MouYr+mnxRE1j!_dCn>wdJT1kG0sqkjA+$FW0+% zD8raV|Gaj0<JY<xAbOGi^_@rg#nCW_|Du!}8?w{qpH}LJU9<o4>Quu*c<%J+SC>qV z&w)NnF1Dd9^0xS7Z|0dx(NA+nz%hm&&7+<Iwr|w<qi*)M+DW<($-HKxNd@_1oMZ_# zc~s<Wo)0hC;*U>HS$lF~V_-oC6fhlhrKmAsuviya+oYV-aL`k%2;;tq6<5z{5qM~L zT5*>y9yt*)F{GNlGZy$%J*UCY=;}Y>Vrh_Z_a&59KDt28A%DH8O#dgqOct;uq$5LZ zip9^ysntUOkNV!Xpb{m(doW(*3aO|ZDvj5TrWB{DB*I6<5ur;jQY~3GUL@5-2o-#r z51mtBVgd@@v^A!8Dz~Y=?(1kfNB(8|ROR3UtoiL6Pr)ZOr5AyLh+I#eUN0ulckj!+ z`wsnV*Z6uj>4K#V&=})w;WaO3E$nTEne`#AS6B%*lWR`+j09nV0jy6Cf6qy$cKyYT zh}TC!ck7+87!82b(&hJ1{Prv)FJU1!>*Y~tjS5+f$J&5}2zQIM1x5ck1&Cs>RdNfA z99>+jM)lk&P1Fd<_Nr_s{4)YMlS24YWE5s_ZD#JY`Oxyy<KGnKQ9c%;Om3tpaJk&3 z7Z5WV^J25OD}quij!*2H)^+sgOc;7}u`Ye#Y%)~U=WL>IpKi^G1!eX`{5ly@lT-5o zVL6T;`BYD~m}6qdM@Piq`_(#h>%+4Zn5ZOSeNk$3Ny{aKZ}jJ(sX8m$OBxxY1|Cn+ zwSI}6QMQzeT;)lA>bCvlEExC{LH(?A(du@4bGcQoL}&tFX;boSwq0>iZQ=(oLOJkc z<FB>^^A~19-bq@UVxX2cE7?aSNYBz?d^}NQ&yqr7-LXP!0wOePAL8t>H<y^Iq%*IR z8oifxY?JEZe3T1oB0Kl#*ODiB$Dd?w30&(>TCFW!?0?~Z;J=?2=|?V{awWT*K4C{( zDvc8bll5!FJ8no@xfAt%zaK@4Oa=!&&Z8XV2eSY%?)Ed((w7hujkEdUV%2)PIY;J> zj`K_J>NUZ_L~7pmnzFdT7Mb?(=JX9dlVf*7HZPK-@r*L<c$+63CL|%cogq#UikCB2 z8K}lp4^zDt)hgW;#lBf{vxFhJPqY0Blr1-XWVh6~sQErRfR5thSw8X7fO~v5N3}{_ z%U_FT=K&Gmda|VV19QrKPbdI`h2@3BBDXvxEZ2$B`>ApMb%9vD$iVYHsdFfF{f?*Q zZJM+XpP`L!VcI12{(qY@=6#GTfm3N_%5T=#28i3H-hlbB=QY}9-TWKT-uosp_7-`I zV_k`+9;_zR*}7`Sla)_5_+yE^&hCy#F6&{zgjs8QDE}xlKbp{l%4*^0&T{Jy;IxkV zsMfnEwv-ha$E#fH9W)nmVGhZOs!w~xbT0r0L;^GBc`L77?oC|ZIy!>iRb(}cEn77K z1Gf2MyC*!n3r%adgS0b>e~2u%@K{tQwZPGsT*44lVZPC7!O7i{-kq`aN4%IO-;$iC z3=%KGBR`n7+?C8(r6-rvxj9B!mPPRSN6!g@ZE|yq^FF(11P;jP>_i1hi|?yy+{$;i z9>kU(&u~#|lNYzJGnYJ<->h*LuLU@P>(;fY=}fS`5{M}Y2w~BbuEj9X>k6L1n$0MS z4^`gjWGU}KFyMk_tNFohR(ALg{V9>X#F?v+`Zd<Kh5+@;!NRhsQ`W;;+`EeLrg^FT z3RC%S@3z_u#CJ)P=x>L9Y;>PHew3m5moH|#MTCVq&+Yol@z9&*%AKOp(Ovdm4%3dm zTB5okDx8OOv$~6YMK$&qM4|SA0_-2ZU$I<M0uW9-4W1*JPmdLOOJ@261e{g6tU6{z z0q(x^RRQzXlWC8uEIYB_=YRW|xUQN4EKMTrLf!b-k1X?@ilmxQtBGbo@a|%63Ka}! z;X`a$FDjz)J2iIr1&%A-a#YS7W=Y~(5z*(F;NJiu9#Ci+iG_L0YH3UjKQ%TaN_r9K z@HL{l#bmr>#V7;0)U8KeUyIBOh{ea#^>m>|%BX>6`1++MW)gph@+omDo$ZAN>o0;k z++2@6O+nFi&)ItttgWwH9U>g9Je}#vKrgn78%ew<P0I!Wo@lP=$6LRW|6c!`!FcIZ z(k*E`JdffKhO|>EE9!0}duK|Wvv18TP2Q%TTjxI!8_@}l$d6Syi#%ta8+cmAv<x-8 z?dGUsUUqR$ysA=-re28@Y2U%nDnMPEu60udV5ga>`aZxU<u<oCH+){@6>G?j4J--n zo5KiJr**ajFo)muZ(sWD4L!NeKNUkW{WAlKLeXUMHs<QxZDv2)RqE~0u~A06f6iSb zK8}$8g)WbCr^&<L>{~h07M#YsX3mw)%L4hs*31&KqHdJt@3Y##dxf0(P^Mf34!+s# zp5{)J46OnK?rx6vTvgAg{3N7)w}fbH_Q7oUv6x%b74ycs7rE#Wcv{x)nDy>rM@$%I z#$x?jYGoNi9v8Wm=4O<I^@D--Y7A2cl^0(~wkmH&YKAZ+$mSJ^J<qD1%R`GsBjNsU zgEi_ny}KS@wGM|5VCp#oj^6@hPG-mMsJE&7`LH(8pz-iKI)o$0bkeSfz}@+5bi^E| zNG{oUuLh9jWw`lp?^(Y9B~>fSlK}YB0eo%My8n)ur~!wQrz2hp?~Oe+>pq<``&PU3 zOvp@_w`_QLij9_5xI?e`{QiyRE7#evA88sV1e=Ua09(tB50HZ2;9{rvPmL9MCFXCE zHr^yKe5z?C$HbMN&FK;Hpf_9H@GcIJD)p&Eta!T70AtG;c^a53g?l%#QFzWnALJu@ z?R0BY3--yEu!Gfv&x#W=UtI@(4FQo<n!-JS#xxIMXv{4*3^HIFoE+So;bA6c6(~TI z1@Y-QGMY_<pCl_`1PVF=g&k;r=DqJr|L976kVkz+zIIr@3IE6fAS#usSm%u%Du(4^ zHNG8ES&vf{nl+3isJH{GfB6USnTqa29nb!;THY<k0yN3hbs4K7lY)_1M%sNle4_uG zVVBIfJg&>vNPZL%0foa)!|@&0mbf3j35U*M*?8imP;s^^PjP!#lTCvQC8j}f$xONb zRgo3veCzdMF|Gpm!UB4o{okNLLk(G#%~Qm6NPd7IBL$?G?>e<yOfE&E6R0LfRZG-H z5x5$BZrVRGyoFdi(Isl;++_Ke{KFzO$s|)QW-J*~{w#tehXoWX#UvfcBCEtqK&ydl z3Jn>ObZ%$(JM@VgDut-JL{{2E)VR${E|C8rVfw1yOKXFRbf#5>KUZEN7qs93SGZE% z<~Gsvm<b}<oreh(L+Cw0oOp%=R)KEP;|zVIeaILc8fplrh~X~IKHsjws#0ml&SJ-s z0?Va>WK;4-=)BoUreFW!_6;DS3TwH*g)ak9m)(+}uFDq9YJbG~0Qo=LY3d#n4R`vj zZw8nzG)2b(SH9fWKAvhwGI~>>N8n-zK(&A7ninz_{s}bXK4JdRWOQiie1QMN3q=YM zH3$L7kX9!LvsUNp;2=Q0UIklFilZS3al$mb#?d_*8CcXhQBDzSw?Isa>`dPQaM=AF zBCNV{FHP@Ih9WgXYTQ^i18B2c8PmzTRf~1&2dZZa6#qfN7c(r~(liqmZQEyapyY!h zmFr9&tZ;&MQcD9PKz}n~<A{p<D!;yUO=yK<U0|!lu!{8!Yz9qr7Asbu38l;?DK;T; zc@pHH27nx3u2|2_6TKwp0Cnlyc1OHgQK4G|U*lr3xk{IaDiZ=V0uW)p@|$4k@Ym;E z4_W&50z8JMDw5scXmA@KYLCBV;;;j0RI!|>(Z8tQn9dyaZo6E#3!$Z&JMv$FK$#va z5t9$iC8A~M$~xpnX-OAaj0FwVdL6`qK{6(2{xyEV5>3|FX(H}sOzJKZ(FCG8lDTV| zh;XDKU;c0>8ehfhBdWMaya4_Qh_J!gEIwBZSQaa5c`|VwUt^|ml4g2zN<|^|nuHs= zSAZe`ps@gGIaYbkcrqaWKRHt^DK`xZE;2DAfO>VMZ(?juh$<ea#yYgyO~=BTY!O$Z z@e3<E$Tdjc@PD?<Efr`$fr{b4XG5hJO(2pb1(+4kBRmxRe9^d#@>ZfVO-ud<7bOQa zJ~*X<0s%Pgsx6tw6pjoBAjRfc&wdF?k`+0?(NMWo<h808p<6rg@}QsoT_EqA!1Yts z?$_6(D}r`S@HCux3Oe!u^|!b&5YK3y;*JkZ@fT3hl&qn{J=#O&5n?eoEH-UyJs(8D z(SlD2f^({s|MdNbAz4x=m=NRS*gY5Q4*UG)Em?dy^tB>9WADn)x5mif6~8s}BDh*R z5nVocoX^GJ1xnw54(F|7-BvvQ@lcxGuyb6D1rU`&3$)%?=Ica~*2|5pcPWq1X4kjz z-{EY5?sYjh!9rtm*n<7TEbp?KnK|NRpsz`XmXGJHJ)k*4hcX=K*3A7CqVQD&{<jcd zTF7o2OxE%fjWL17H)3q}ui`!5G-9|IEsEO5QY9)E?j&5sk(Eye9_0sxxDn0ND1Pq0 zD$YR_r;BZmdr82wFuldfJC_q)QbR?u5Z^;eufy99<{fg)xvJBNy-+Yd!$#tGG#&|( zGD1|(;9gB5yKCAUv^`6m#2bCoN1(|VXQIxs0IoyB%p7)kj#PL&`NWPU`)%&yH<PIE zMydeKV@w&RhdtBAWMnQ-F*S4)lsQ{YRLe#(`9ta*K;2l7y4EF?4B){6pwcu=W0F_H zga<caRRGS2(hTzYke(+E1E(42w`RV4oq0-(+fI{SCQI*W$7IlCPjdZh1o~s4lk!?R z2M{Qz7QRL=O;U`lCO}IR+IqE~Z}L{yLsqexj@F1(i5YjXq+{GA^f_464PyHk4k;&) zLj&RNG^L%lhRDkTWXPZ{M{xWKk^HEQoWWJGBJX?sn`yGN?<;Nd8&7)qYJ5;rs3}&t z#}D1`J#{hOnTqnxB{Qp9Pnmt!6uN4Ja}gUvbW^MUjlF*P?i%HOYE7-niDkAPl#Z%n z0W2uW9jM&t0i$qH@-DMW*h5P+WH}Zy2Snm&3MVp@=|uHkSmcWPi5G(4QQ{T0XR!^c zNLhJr){HHjY-I*SxxQ2?Sc6;8@J=<u5-m@xTu>AmJcZUC!}~bs7Egoj!x4|{^F?X8 zU`SQYd$5WNSKz+>s@Kx0!VU+-v%cIGD1R(OUHe|<aAmBP7ByEK5X;51V1t&)n4MOU zP$fYzLK`syRGT2~Lb|KRU{Nzf1cz9HyjwYv<AJ%Hl1YR6V3D3gH6d9sn~WK{ib!Ew zmnEZ04IbhI;kSvQ=7LQ5ETJ(GL;b@Tn^w9v;^+><B$5%=ve9WaH&+(QF$LNL5a6~z zu@`=?6R1*K^wU!p>8E|U7MS{*sG1`1#FN!yLi~eUG-9#ve_RZjm-6&(L%NDb%oB}Q zTtrGKYRvR!uRv7y#^mx8hhs#)dW0s>cBeXkB!TFXAx4draoqjuPAeJvV~2G$YP^&i zuuX?ORNoq?pL%n47pc)n0Wmm!R%!|lgP^GXyxeh>VKSyiwEml7k(*ezpyY3x-1#b& z`$;Xs%&o3UZKI}jDq!}61x<09te6E<JW9^F%~O__QQRtMcWl16bHm4rr+k?IMAQzn z{$tsK2OU^Me?F=jMh*cY&U%G)K!4M7i12N`>P>D$BMot3^}^!TfhVSyBhXMT8$B&Z z%br(^<)v72RkjtoFWo0()frm<`ic%sB?OB8L^}Gh&uY@JY;4+>0@=>G$1Oe>Q|{4( zPmfv!*ah188!|n;os2e`YNMq#AfJb!DQ^JJK3_{_0<W4#_WnM8c}Pw-8wi*Ns>F~L zW6A14EvlRMG?uXnok#Ck+uOc9*6L4FxIxyqEP(I06TjH?E4v=F#m1_fkSuwkt6@x3 z<or2$vgrZ^t4jGz_<Y;+Ct1mcdn{K<;F*YF3T!XZR9lH~;Vb1En`&!1kBR57I+yHr zNse1^)mUVWB`g9*ll~;9wkg15V~f*r2gdCU<vdDOut+=?xwVBJbk>;c(L2zxF{%J) z_mTJ59UU$xu@13&rli$IOhngcJ+Q+x5Yf?at!rtDH%ztXI`j)SE*}=vZHOJlbt?I) zzmLMxzYtNTMD<c%m0x6(9u1Xyz2+Mc!6Lq$*nZhDN6lYAqyS}?xtMhtOmppO5plwM zy=_qCrDj!foj}2diz(gXa_mzL@H2epT;0DLTuKD-$nU|(71z+SWc19FfFG_de;44I zBlKNbQ75iW`O`7y$f#j~imQ%FT0dg88nKC0dqq<`q_Pm>@V^6#`;x>^7?FvItZXkp z>0qN8XzIcKT4Rg)RMhh;GFnO@iehpPt+kKAIxMV&XkqOm`(gYXw>{S|X)5slH8C4B zSz)NMqWZD1(9q-O^$-h+evDB_mwu5zEw<V3FO4paRUhM_`<CZdqyATX5=S*RRJhCt zKC7WZbDXWm<f_9@I%us%p8CX7jNxl8JX2gBe*VAnK13Vew|_~xBugeSG>iwoRtLXs zN_7H1J{a)j?X5=ym+XV*J9c`AOD^g9SJ(<npiK|L;)?*I!-f6hYV`9k1g=`seWCgR zTu&JW3Pfgc)hq<oOEj1}@nFy)%k5{8A;SR<w%51u&r*N2X-ew!ubs66TAR%?RG!cO zebZJ&J66M0=^?YOqi<S;Xv6>mzG0ZLCzm?ZtkJ)e0gpc{TB%qZz@DO`<d#!3PHh!w zU42D{zrC#7PF(uL#q>HVAC+)En<f~j$x0@^_Ms&#o*1q9cJq3pQh^`VHStlcpVq$& zOd?llNbvCbH6$Q*+CHt{*>~!-F}Xig=BB|r=ChX%4ow?IJP23d8i|UM>0f@C$KNU6 zh%vb$F4wS&`Z~z{%FZXR|22gDdX;?dXT=4-qk!D4ZAq(kKG*fMibIK2$K)lS^LBYs z)|aO{e828{81dtxzT<|)Vt>zJWvko=K7lHi%$gk!z1#Tw&ZZ(%fB$*vLr5Q$d^-`K znAV(S{Qvda1qZu!pM4(_a|#!)6c}B^lee6|o;xcGx6B*uF^GSUKkw-Cr#*0xmAn6D z@J4S=)(3MNukf<Xecr|A7axT`SWX{>%+|Iw?Cwx;D!0G8zBqP%_pXzB+nlH&M-ON{ z>3(N%@MmN_{E5_SgYc1~Jgq|SZ_UwvZX0~OV)AHvbA017NH?2$!|y3NxA8gK;;u06 zwC>ibg^a~np(RY^@z{@@k0$`-wX!M5Acp+WmstbkBK4{kZ@q2j%yGhe_RUG_zpHb_ zcE7FqN1WP?tEVz;KC<G<?Y<4i1%-d^nQ&tF^~1EAQ>SFD=BO_I#<yn9O6r|k$tck) zD77dvl{wm4b_$*X&QIE!CcTaMGrca6G=9SCfaM=yv!^}v2;JMEv#zNE&&e@3kasV} zqQVjtJE*L!Mx5ss>8xdp+P>;(fdf9(WXoy)oR0I?D`;;XaRLaZ<Jz0b_oQ@O+F~p_ z+5U%+R^Az_76ZJ>8uWGOiYGm{nCDNuwcnU_d2VxdV_N@w**IA8_(=Q@Z~eNfBdsUi zjDh`ix8C1_8Fx{UI~o@e{ryr7bh(sD$2XA~l%|qNZ5a_56#Utmotr5~-}an>>6KD4 zpS3lflcM&4U_M=eVI7yJ9P;=Qqqx6-u9mC4a#Le&6RVJXod&@f+4E|@&-m*-^|6$- zNZpu=zN79v9ANsR2Lx8YvuLfyMeQ;djk?BMzPT;M_P<~*9}T~vGwM?kYxROdkrf4t zZphhw+GI%TG@KX>=0zMHKk|BloS?LOX?vhp?>C<THU4Ql5YO7My6Kbh*17-9@r!vw z-Fck&>Qb8{>BoP6kdXvC8)66L2b9kH%<r3(vTlXx_HV3Y+VqApgnYGEC0;fQuGRbZ zn3OT)>=tIv??|FXx8wX?ML(81zH$SR00WS3&ih;CO;32~O_kmpv;WZ-#4SAdVqAB^ z!N3xR>xma-QlC<9hmi;ewPgqy1)8oh*26C2$3IToSu*u#bieC30{Bq5bpCammF=BE zxe4!v>6_0#|J=?jhVOKOFTatb=8MVH?M*#)|F}pv(oTJA6KP)hD(g}<DhJB!Ar=pn z`IAI%^SJw(PJiA~Za?SguL4amTPm2Ss`J0PeCDIZaWG1EoAuW@sA3|o{N!xcP+GtX zScXKPit^OJPGnf0j$wN71n~?aP)Wx>o~~ZNf!+{lJaV12G?1=kcXfb(1cE6xPXS?R zR|yN)*#KF7REdk;P^j4Rz(wwST~Q<QCi=?}FO5z<<T=hmHi;jnnDUpE8h`U{)mZaM zTuRHXg<BO-Rsk%M>r=<uUH4v@r&l+u=!Enoo;fw$T=IYgajIKm9imjy3r3kkgY6F* zXW9^x;P>OyTGUed912oZibo<$UO309yvO^>m@Jg$$lt(x{VShJ*$YqEkPqUjin^}5 zVN;T8YX9{;(M{u4pUTN-STIiVcOH@R_XQyzc#1h?+^P)JVW`gE8@A~&FF7Gx^L~aH zvQJ58Mr$tQz6gTSFl(CLWBuhOEftPzpp+<}%BD4l8)PY1rBQl9{|a$kC!a`%Z7_B; ze&SycI=kW2a7)BboVe|tqVi*nbOkGw^R|aera*Ly)VSjiK%|0nuDpxNPqdpJ+q|M= zZ+sJAW(cefQaSTP|L|~jLG9p7Kpgox;=(LMO{o$#;<}e4`J%|kod_#&)TY<Rj59G% zz~KfuqJaQ0%;ud=?<2uQRtnQ$pj<M0+LiD8H2d3H(4KY1u5+v6-!i1$4EKM_f5E$8 z78!Wj#~7@}@6uDn5zFoX7aN<~8}Hlz0#5nO!*7d9ky{zw^jxMzbGEBVFR)>6fYz;k z;pEwKL}edzO@?3IkY&x?(|NAisD}JPTxeynFomwz&U)hXH($zECr+_xhXc`P29{<F z*6bqow8;N4mwDyW-~Er>dHjFgT^ij3n4SDW{1RKn!`c^9-s@@xkiT;XFsm$)vl#y0 zJTd@~sKNmt4#carZrY0}SIN6IzOSjU9E?NXC0up6O-A1iXg=L;p61rD<qY7&BAWWd z4EndOL`nK*_oCgL@*!svOX-RiIEDIYfv}*g=}R>$MS8-@4?DbLBR)ta+|!}cl>8>d zGW(^i$cCNMMY4P;|I}5g)8G725@w4!WMIdW0`LdU|A=`%8h>7%F*&Dj^t1Gj#1~Sz zK5-Yz4nke|dlcYtgS~!Vp@2Co)MLB<d0&M4dpzjuUjRCjpU>PmSF|fCpo^<PY*}#J z;z<Wl7L~4~-01NC&$?^PRlSTOt{2kOqnR0}(Tj)RQYud;@Le>dFITKKn9GEg_QP-E z1eU!#8J{}u1a9)tpFQM&@2)-O<sD+jyF_LkwRpwex*|^S%`#m<6QZeW)m|-cE-th{ zb)@eJp#XWla<&5Vbe5sh$}K;#I<L0frK8Umz`S2dyc9Fr3~3Y&YNmtK^7;zwSVWON zAXa$}P-_!ImJ05rE5`S^d0LxGMbz~_?w=pRcT%M8Kd|k8{bk1VsJU_GVvt5p`=HIY z8Tm5?_w^ShtxfR)sT^D!>KU3DJaq_r^olQ~`0|j&<sBd(lHG(<g$+4;dsz|wU=H(g zRxGcQvf6d}L(FBrBs?1ku(NVeQP6Oce0K+yi<?)x=FBk72A;n0#w~k*U~7FYu)=#5 zWOm~M>_@KJiv?XBjUVlUjFW$swx+W&h$usMF#{Q&EYOMZcl#X5>Nny=aW$W?u(RGH zu(bCjN_|3)aQhdqQxpgNuj==|9^OG@-I&MxX1STF*mUI1KEyDyWRFFDJ#^sKkQL_+ z%iw+FL-UhE7caCI4kcVeE&WGQ*cukUO}hdM-VFReI{^iFVkIN$4yr_4a|{0Jb@CEo zhrI?Jv4@&hP-@~dnh9cNB4I~epY%VD$g~^YTeOpZ`%dsLw%=WL)Tp!6&zSJ$E*n;? zOO3}a0AA({%4NtJhHulGY?IFxB(>MTvf+6gbD0{lWcGSq8eMX{PZn_`3kk$l#7K)6 zBn1Ofx14hZtzk{OPHmu6!Rhg@yR5cXW!h#X?_*PzXJs3@j!SwLLhs}|)1|J~N_NG- z+5l4IHS9}Gd+FGdXOiq6<RiP4eAK68lAENDrh7|qMF>NgGhIm^Vgvf!VQQ?{aS`c? zDj6{;GZJUpp1@pa%G#j15X3_MQdRHpVEMfTlk#%^@}+`i?3MzK?;S4wex&eoO;mSG z{M`UpcZ{dnqyoAfw&Y>@gCotBcRze|$6*XCB_N5AZz_Nwhd<7+D_v6ZlO|iUyDcfq zgVvtq0V?dU&?$iA54_C(Y;bvJ)xQNBwaiN0uC(%vlU?tF-d%+)&cYsJZR}}=7bxXy zw|(nBVgIoucf@7uoaO4BWwn8Dz9#dBGjp2Cy1JpGwW&NcC)Mi=)5N)J>u8K>%B;)l ze@qIvH)}khNl{ohc^KraqG)l&GjNL_HOdau6jZAA>pV!8<1kcTt-|{`kb8Z0ukdcY zH;X?>RPVZU{Ii&JRKDD@e9Gu6pN?VKteZ0YaD{^qfJdQxil<{irev=LY(F93fCZtZ zTMDWr1J*iO6P7d4C)>=ElGoaCOeN^S*K!u-L|h2T!(qA0TBW)PL3#<YpZfOR;lnKG z#ZMHfkKFYNPxrh03-*@}ksXBHrAoe8P5X&sK4_&m?^77auQ(c5`4|%UgDO*=j~#H9 zdX!*%za4f)Q@{L$q&2#xpQ>)5Z*pAV?~KAJp7A-`S2^BdyD4FOFj?!PyjM3zn!$(t zo|XJtZGAcR?86RM@d9UV4T4xDnZF9-t-`JWB>x7S@&QSoHOCF%vQywD<PDmrnqLno z71Naw-QL6xNeMDkNPi^qwPXe~PdAbSnrA)ay=<Se&n0%)b_k_XB+nbH$<*gpH}=8) z%4>g_JrA^V&i;((uitTA6k#6oWoP(Gl!S`8E*<b^57Z=rz7UaegE%%IRl`RPXv(c9 zyO(!Z%!Wzs|9sSuC=35A1?VHBOPH+B8ZYd^ZBqV^qI>aY>i^>aes(v^=00=V+~qdc zkjpmr`&@EMnrjq=RPJrIxnJgz+|pcfDHTdl>dO$7ic(1`w`z1lbX9)){RewIK0BXt z&ilMR&sSBag@n8h>NP|758mK#hY5dP8aIxVVGEBCxK6+8PD`uRCJ6t)2Y$};-UJ$- zb)h@);)c_bo~AU*=hP^eaBMhPxeq^MR#-VDQh-N4Y%gskquU0n&9A0#iA=dzhiWQC z6$IEl6(^q%<`ZrE6H&Y$!ha^uF~*Stxh?s-_K2hqzfB_kO#0LSgbX5zKPkC=LwuGl zZo5z*vf-8~v-cZKcwytD|FW<|qh?9!?qlufi&W$Qai@*088@Su8U2nK<m%1q5(!Uf zws)4e6M){xR^hFpMx2CyWTPxhklozKg4NE7^M@`C!@7t*{RzU`c+mz71E6V2G<L{< zq`q<SsT<LtCbZ~vahqevd-&SO<8Gj&n80}%hZ~i#<yh4D#)dOxIxS|Yt2Upniq>K} zU(7pO2m37!q78ZlCNTWtTKQw)Zb(JR=`HjX4jh<7w<mO-@hN;fiT1Y?U;7}rxY}{_ zJBH^h@M}>R7cXp&!<!o#EBB0ElFXki>I$iNXAU3yuNU>{7gI|8)W6x}hc)m`QfJAu zN!!{fij>$kfUH?V-vv&HyY)8n+Wi*<Sl<qE_g&;0TKNia%=Ef=R*p^m1w3X^nRivh zI@*DJuk{)r{3<AA3nX%pi!S7%-*=(MQ;zkVM*RY`9#@xL{>e6rEX6%T-D>K)#PHXU zt9wIJc|jNZoQ&3U5JO+>>@@D(`=H;_sQZT9fi|Mhvq^Ls32hyT;*-$*YsVT*#kDkO z9;2uwS3$Zp@eJLM;m3UGA`+)|)w5sra}33~3+9SP#>nHQ%F$2fg?~?;l!D3j0m2`M zqOSqnpT6k+L6O;8w_l}qZV#g8@utt|J{vyhVk+uy|IzJ)Q*YW`&Wilkuy4<hoZ`-) zNDa-kg%dJoDE5RZwkZ&n2Ze79?ucv>BX|&?T3~qbg}pn}^+aNSR-@OvQ>Lnr8oQx} z7%%}Z++pe;=c5c-Dat~y`tT}Sc(GUM!mN4Z^)BJ7UBc&q;k7lPIwG=|%jgI0d>9Pk zlY|GjVg^x`+kglQFZyro&icg>vyFVYi^zViNbMy0HAntujQ>@lNG(R>R@Z1ZUNj{a z**qA0jfjHJIW)MSbf%FH{8RRqqiU&!->7gyI^_(_NqIu!H&OT&7wvGS41yHyUqjrc z9$6psbZ^Rl&nYq#L^QQzZLf>|g;#&XqllyEXY<0<-2B?Uk+a(hH`}DQILP<jK6`bM zgS`3;K|NK`=zqWt+CW#di#9knDH_#RdJih1Q)>l%Ci>7=7-ueO2Y~X7bt4Om>3hT@ zUK(dV!3|6zOQ<3y%R1@-;@L?_S%P|uE}b*wB4hYC+X2zr1k{r?pRIY52Wv=ZUw^~I zBVW+{p?Tz7SJX42m|BO*0EqT_O=m{_B)?09Hy>r&-O9`%q`O<|{Rms17m9?-Hd5hV zsPOCb#{Wd(Pnn7T!B!sp6kkt6o}`G3jG<m(s^n0zm$@QeW#s>pkQu-y?H?2gI4Smv z8QMKBf0x$sx#;PakP~9*wlU5HYA;P5j=JyuoqR<+B}+|eT#A0`)!nB_g>N*xIcuT| zL=l;)3sQPJxCMfkyJ@pblyGmC$R^yx@r7~1(CDS9iyc38=13v}1hGE>{g?E}(-(d0 z_*0AG7hc`I<nT*=mB^0(YMzRIGl;IIo^yZU-fJZ6e0sWlp}?ufNPZggQCs|pv+#Wl z^adWWPUrZH8vWuTb5aNiVcuN2$ShrMc2dNqy6i*v;MU3JUKP=YLc+B~(fYgSA3Cao z>w&4CUqzld!+k*i_73@xC>lRFti538C27(c;CDv+R@FhmCRJo#2X>$nbs>&A+$H*} zYu|n_kn%kG#nl0N(*&p0wJibJOOktUSwxQvxonL#vy`|@Mzs*dwmG6Lv{%@R$OnUB z6{MX*!0%VE5-IMsu!AtNnj@w$s<X%LtvL(njFOTmKkL==V8}${_hio|rs4e)QADHA z^Rve?c~;GMOvJro&)j9IX~LgwqI7(fxr3sk(6=?~vj;6CG}lMANcO+*$Tm`1{XF{5 zJaQ$04!^wIf3o-cJbIxk^yMJp7DtTXkx`8o6A#s?A!g~=%to$c_MC4#11ifTBP9o9 z;aegCl)0bY&|{vLHX+JL%FAB%@G39Nd~)?Er|dD^>&m6JXOpe%R5a$K*w(y<dkQKQ zr)o1)=XQBHK>p0h<9cmfBHL>c&j92@JqcVdnll;ST{tBJk}c<YadGAo5yCXTod;03 z$lrF%Kp^rW{v<<Ed4o1KwLj~A^7}`$-KEAjQ=3)wXn**Cg_4}aO&JkjK5xribh}IR zfa{^Zw17^?%8NVnf!saEFG=%>!rk1P$BWf!m<39SVv<=?Oe1eWrQiLkfy{DDWtnKJ z;B56EYK)`NW@A2#LD!+K=IlmaCW#FBFi&g>r8J?QavHW6qO|;K=8425yx7hx&hEa% z7Q}LeC>k=4{5Od%>O$9k<S!<FPWhW}1V&vUq5e!F8kl0Ul#JD$capA+5E(Kr=lT>+ zmU!PPyUDdVLDWzQ2Yzw^UM_N5ed(1z-j%wQ%@QRb1YVwUq>4VebVqzxa90g|+oUVH zOjTLJ8%$23n@Gs^F0nt8+CMNP^{=l6k@ug>kG9RDe-VWrB%rGkgtv%q!^SPHIOv;s zy^cwI-7Ht+f4sJJO7u*^>hh9C0vP=mLwFtj=C@D^FbFUD(UGQ>`+M!!Ccdvy)wwxg z=G#3rui@r?kmW2*DRUBy^gI)HbpEF7nQkho7~}gIkGwb8dWn3hz}jo|k)K<?h}pMN z<yLe#Z9m@*T{|dzy+!sl5}iau|DN8r)g9roCCZ~|hOcRupK(gO`-{Kv%X%rdI>Gi@ z_9y%TZmG*=bxq5Sx&DWa<Y_*rm@ob)`p5il{)fqsM*!yC^v=o>Q$+IiA>=K+PyUx) zT@9SO?%f<%h69QoH>}*M)H`R!neB->-0J?;#OB(2?^kAtSf@~e9T@x4z1qg@?0cl- z^Ufd}7d?>4#oYxScj9@GCD5R!k$NHDh(1u-)GpJ5n~wb#K5!OZ<Sez8fr(#cgA%4X z&+a+Cs(hOqZ}{l^z87Ei52S8=dH3qY*8_tL7+ND_W-V+a^|M~|MD^MKLh5NRRmZM0 zXuB>+=|d;G_8AAvUG}g4ShQqPLpU8@@gq<AcD`Q6!&eTj2d+=6xa@kM`L$>ujOYI` z-1O+HuC&gP<)<%<PadkMKH{&K`RwI@ciT<>rK-tWKcY7A?=Ix-$kgvXx^y@8LeY^I z=e>SRsJ9+?`!93**Vfk$S8gOmoS6A_@T|9yAg2k8_ah{I9=$9gq}4K_&abwoX~_Fj zm)~oNv$SY!sL}|JRdP>gbd)=n^i8`iHCj8WEpC$#C3_@i=!;gJNrq=#`6ehzHnaU= zSJTJqs}~wFr$0t3q*agPDZ8f-KIk4E$k)K7jZfKQkMCkS6erIZ=AKReZT!vM<f-2= z596JP3FTAJxhT$&$uh^<Eb}lJaQNmzPU9gJD>m=q``H|&08&j`O<8p<LY8`2K1W^L z3+kXOby6X}EkkO>p)RA9VSg^{!o9Jw*xHC|Q*+g`8a3Y6kv`))tJhQE7XF?ubCm)^ z80<6ADdJUU_Iq}~Dnh=4a?e38C05l(doJYGANykAPyzZIc5L5~TU*~>nZ3S-0MfzN z+QdVj^dCDHmQsUwowhC2Rwv{_m{z$d=5eh*t~J(CS$R)QwD(J`UFFj5K^~V{>(abg z79NLcK0J5hsKky<{~JADkyhXM>_SyvV{YBSw3U|PJuzXUGASixAF3nLEHsp=4w9G3 z9m6dgYK~1><W^^zbRf<qwe;tTdji-B#e}*Ozhm2*WnMIx@7#M=lGQ@cbRm5Q(WN}! zcR1Del=ny0ufBhhqvS8O6;PL&+;6X*-=H1XoJxz8y7A%AZ<ljBuF+FY5=Uwq50(TI zpP`mGCSRb}JM?=F2~u<ST1tbWhtBtFTv~{(N$nFqD}Q)(!9g-@vx6<OPs0M%pA}9% z@0NVR!>;;NbxGREH|anA+L$wC|23QvTZo=jWBV5>Iexm-*6@Qbr}wrmcFIXUvmA6@ zGK?>GH)1t1J-IUVO>~Cu!Nm@iOe(-_tMWb)5#o>;n7<m)*}y=_I-7OBtIn8&$aV+j z8&j^K;^Ug-#=`Q=h>hsOMG(cQam03yWMN=rvBEMRVE|t*nEUI=QdJ8>t{C+u{cXlo z@SUv9g$nntsb(*=!yau8i8xO;%S{K;@`#Jw(VRSsn|#)ew%YX~m*V%-=9#%SKjCzC zlpVHz(n(v&urw-WQR3VDt8KFp@l@xLU31mBMvjR{-|-0fZ}VlPp~f8tsjEk1o5oa2 z3`?St5x99eN-w4{KLnr!FAL&}RzroSCdOEWk&&u5*u12gCFS@$wq+5Vj%|2{o2bpv z(OS=YMrA4inEm|vsp2%MopKYGtsU4{IEk{;0w(kJvb?)nle>@lNIBXp5^_@}A~54W zotu4F-DO%4N@qwpeiw{H|7tU(k5!B{)i;%T&m4Bf1ubdyEXXCYF7Nr%?u4=!Dok2q zD)-O83`l(?=_60ezO@{*MqaJHxvkj{9-ga--{~$*s$?pmaEP={!7P$yr_>6Js)sBT z1Pc(!F3erCLm=URNQ&rxG10}*sb!@g680>$-pf7Bry^U;p@yETV9Ahr{WIP{jlAN# z$te2ya5P~UfN3R^q0M$dcB}UzwLZNQ<*@Tq4$qBhtq!3QCkhD<FopWp7=`s66;gkk zM~Lvv(sU?ad8g}O(8ILnlAd~`$VEX}vtX#rX&0QuMi@SlK!vX{C6~*_4ARz(BD?aU zp9<!3Rf*!tPexVrri67j89w7?s%Ib<3D(P0WZ4te(K2?YOF|j4!@WSseqh?{d$do~ z+=$d{QG|n7p!kvTc;(j%B?s->PVdBw9G5Dl1;8!DOXgO@E)A=Hu_E+8KQ*{2oo(fy z|0q#?lRk{w#<KMJWYMJQh#XY+-OJpCf@nVn#)J04y_cED{UMJF2`guIf9pm%j59S= z8H;H<?+O-Ygn()QMm^nF^kH+n{oC41xQ>JP5jCdHDX_>%IIb{_9-%xv4mI#(h$XmZ zD-)n3dcmJC%pb9HzX!&`)$SF$vmPqdPf8m$H8$vcZsrLsJmSk3S=z@kcb(`L-rc%z zeJk6(2775tb<w-P|I?Bj^m|=_+JojgTDWW_6Q-_Kg=+jVuJJoikCAI%CejZEz9oz^ z!J~zjLSusl@T`5|4CF%Ej`_&3)?-ic{nf`4RAg#sPP?5OUw;eC$MR$BjT~1_f7N9v z@tnVwNT*9DcJZWdEa)Em#>gLF_$wt<!}I`-DC~mN`KIspOj?FfE}K8Pi}yWqPq!~b zE_~fJ%*|E9Z?}C_Q%j~m5a!cYOEV`4GCQPE&GF!ak(#geX;m)kr7*}@CfQ1i>pmu{ zgrdMA30)BvXKN!%*8zG_{7qs!$0G^JaUPS~XeW!(FxdwNozJ)p72AkXO5H}j{+Iq# zU~>G9>eQ`}6<VK&ws)L5R_}E4LjqoNf>99Cx%Z`HTgoZCoR_CUvFy!xnB`@L(&lso z_EdBN^P)F8u!y3tGq3Y?FKeAtK5o)8ON9f0jC?_Dwe%d-(JBTHC9nXcIZV#P!QhJc z&1?y!>@wHlI~S&te!V>)bJvPAb^FoeFz%bgYa{BHg5>Ja7fbEA8aJn`d}ykD(g)LD zp^Z%!UM?v&I9F*nH;N?Fw{`!}j#*cMisLm|N-vra4?cuT7te7dqUujdssCB3b8WI1 z<{(hvn9WAn+w1+G8dPP<c72#A4YTPv(|J<s;@Y&T%q`3>Vu)=~6n#lSzGcmP#83<f zSy5=8S@ow95^o?5{5)mx#rFGxOai}NVQ<q%)5~X(|JkWd&2en*d%q|;XoZWMsWB-q zuXBqku=vo$-N_-=Gm3Eb1Yr~Um{C&LM1_$<L>y-<;+)vasgrUY(nEK~TgD0nlv+SJ zD~<+*M6&E+pw0r|%^B`IelZr5`)CFc`w?-33kh^qTfo_feH!e?8tz8wgn!!=h=&~S zf?rGNPBe!dS`)4KW;X4u8}vZ<kGDc(lf}j1{)2dSgV2=>T29J%t}z{vdRSW9=d8zM ze#4}Aqzdv>g|Jc+{7N%Cln)J_XW7u$2Y$j*QlOb!1>$t>or2sH8k;<RLoi*;3apCr z$<5-z)cLvQFG=W5yBo(O&4Wa{Z^AtJxu=|2?&johe(%Z?7USY2+o9eHCfi+WV7vpP zyyF5dYd5Kw&B@@h7zDOUy3suxJdvJjJeixp>HO)|I$+554>onZW)hHB7CjFybIWn> zW4Zlgr?lI))aC{PY=^7z;vMjnJr)9SD>Z@bHV!3SQ1l$^N}q(;uI0{wboSKWotKn7 z_6y<J2TM<YI}gH==s9WF+?4_eAMilP9*Y3dS#X^au?~LkRcB2^Wo!bJD*<;MtkiUC zt<!=z%^-nhZQo89s}UO6MNV1PMcvE&*{Bd2)7~Ej&rE?sBrcRW!(UNV3IJ?q1w37q z9h_nu!OTggvu)PwESeoF?aeY&&g=+bTrR*p*ATHYu)sB_oMq{;7|p~TEelf6h~wOU zD<I(Dd`@Ax@?Gy%H>wmc$@=oZsT`Y=!LMv=cFw6mY~Rm~=yTFNENpNA8D9-|<>u}m zgu2tt6>?Mxmc<>Xa-B%<srJ*UoPiwdh{H#ilYr+G$_=NNI}-0zZo5VK>VVdvSDuLZ zr09gN<s6HF`wTW;`6>2MXFzx;PkmMa7{*40!-5B!WBZ`4OCx(bEVmX^=4L8W+u2T> z+zhI~yqSowRMxFH?F6tr24V5@78j;D(o=|RwHjfvR6qhJr#<IMW3I;x>-Npu7>*do z!euby(IS{UhQY*|!_vpuAykC>8ua-1rN}`j6lry?a)Po0>M&J-g=pOXE?T<xLDQ)4 zG=Mz<a^Am)jBjUo%pe_83mgQNrGR83<s@A+FevZr6K5Oq*&px0A2xZR^2MV!9<I(y z2h8NMh+|QtTmk$j`~aGe!Va5fp_=XZy53hQ1P~b(W1f4*58;A`WdVpocy@alXMsgt zsc{EVbRQ46`$O`-7_ys%%J=b{H0CNpXRoDnA<tp!&(*?JaHExnD7A-?R4(hl46A}x zS#e)ob5ZC<+@;m|ys^!K)JZ5bk$q{N?6_ukY*I$D_-RiqZqdT##5^mEnwyyb^CBSt zb4}bHCx8x{2KBv9;htKSZ^Mh5Rabx6VZd1TDzy$3q|$S#?Kw>mZm`$v3>r!GwN-Ci zrBfp`xNq0kZ!h>m>?CWFs3?&+&YJx#c7&As9%Kfpg@9cJretkIh3^6B#?vE0Lu%L4 zNU&IPZrKFEc?O0{cfaB`rV!;+6$5{q(R04t(l-H0PrRK<XJyxGtBQ)nQ=#6Ix$%?i zf37)^eJ0`H7h1DYLE?icSR}Pe>EYGqArigVL|AGd{J?Ufdb2`s6T(A)Ns`plV#-NV zFpn8T`1r-d6jtOo%nN_9`}f|W{c4A$I7yuHJ9GHsn4HiBSmK(n514+$tv{x>VEmpu ztNVGRaFY(|?9x0ugu`;!Ay8Gfue4`i1J)?f)j6>wczHOrNQhX0)6)?>oegC#IzMnJ z*3OI>&Bq!Cw&Xl}#SY}ExR@7&V5<VmEwb?Jc#i(3n<Lq`*>l<zMe+M+$0e7u&3&jj zStLYU`zs4Ni^<M;ggJX?&C<s_Pc1wsc$dV3InG&{`cmM9RL-@rCqa=<5VGCu1LN@M zzyL3l!TA0Hm;~DsuW>voCj)@_YBg^ik_u^uWwqxV5cCFCYd}Vz5#-T`d6s<)%W;r} z`r8~Bh)5dj>hUG&ui@s8?OW=-nizJk`-xrmD#DKr+u#1GX#sJB&k_*FnQM}d0O07K zd-o;^++$pQcUstPdBQLD?Gk)tj2+DTW2~+A458Kq%ba0HR>PzDP}AD{+Cx%tvn;B2 zz@LW*U-KNQuiGPuU4O|Qf?d###!BI{86dl$sa$XIT)_n+u%as#AVv4t1NYeifRW0F z^dEb)WWC^2i>sQmd&#(%L_#D5=H?}#{BUQPs>)ooxsUXA)-Tz(3)S8|c>{!wT2<5W zC%R$WoCAR{ngl#FMUKT#sX1I(d)4A&Sk40&ExK>a{<BYqx}|d>)TwXOuudrJm%$tC zexHTLr4;zkM^-Qg0k?pq(fdxB3-;jQeqxx^m!$+o%kjPl&-NTLSWsjIjhaCOYQ253 zle#NZ4)zu4S~S?Y6T*#4fa!E1^5gXKbz3|{jmoOW;$qnT)o(NUSR?EC%^t;d=5U*K zc1HVw<7eN+rm!;TA(dckaugf%1?HRLCADyadRjcNyg6T}NzMY1HeUCA0BRd)5AgTe zHoP|_Po0|2b>rJzvd9&?Nn}tS2G7H6aC&F@gd0=fC+l-RCc*+#bW63d1=a9!US0*R z;O{8;>_?QtPj&_$_ShbEGp4t0Qn0hKcRX^ud;?MkVZPPUwdNhqx^B4fS^pJ?2X{gB zH|~t{{GDxxRedPue-(cBbDe%(JwDFbgO#;ujjp;|x>Vj0NQLxeFJuY2&3DYnJ$1qE z<Ipe+LdJatG7Hzj8PCvJY%n`CLHP&~zfb(>jEb^`I|{tF^*{nN9^ZN(kQG13is&nD zZ?#DO2%SRB{#O5Z{P?U9FW~$nBKbT&V>~Ak^Ey~7m>RFz-Y5HF7VZ-$uZznK<Adda zY`hQ{FQAR{B+cVvM=zJ29_TxTh57{MzSKdS%P~Bhmy<kePNgvqOx8s4;fLw)sqad) zCTs^9Nv39*E2I3!+iP5+w{<etgAeP=arV(*?>j>EH$;A}f$LpA@MrIfsb@DdAzi=J z_X9pTL7@Q$%v=Kw_nzZI8{u~Mrw~W5exdD%G<r@5EnEEO7x5jzae_XOmr$g{{<uwj zQRi$)P}tQ|K<=melFNNLvRC2ZoSe++Tn{c=%9y>ki?ugFe1`z@;D2D<K3&=*wYm3z z(yv4O>fmypfUsZZlRgjqcGUn#IZl|_cVE_yo3cGb4JNNr_M689Kgv0<=3ZN#pZ3Q4 z?Br}9{muUB#86`1m3Ig)Esz`ytkDHF=wpZrF`cnf-#m}1{t!tFbFr>$aZI_mX93}X z&6z8N-?T&@=04MXncMF7@J-%*fh3C!Z@yJs@9@u0PvlD3IP}bVd{`O6L1;9DKC6@% z#e5VlcICj^NAqXW4xh5{@G)KA<CPOv{qgZ;{tg&xmL2N369XXu5QDXB-ElCnI+@4^ zYdSM61)dW2=<c;_D-25&3&KxAWmbs*?Ukz6)*$wIh%+-YB`GZME_1av^c&paJ<L`- zzLyR^$beswX9w1ucQV0Vgu=>#9em>+*9jlV<jxIhQ<Ol`hFo@_{$cc$1F0NVd#6AS zhCLhj9^{xP{Ug7(6%`o6vP;>t<bw@<GOfm$6o7T|%nu3xvC?AM(!h$lvsJXRcdZ@K z$GSPw?~?qFGvA7=v^+h9huwaS+nCK2aM7iEL`LJ_LcT&@`C_)~W+8n?K3~oIIL^xM z{CM}Cl56{kINKZ>K8kifcY5)F_fJ^7P;l+e<8MJ?v!OGRGGT1kzXNqY*2piAr-GUV z$R9Z&*^~-N^*U)_4&9x?w4V7t(_@tfv86KgX)ODhO~oCM9G{_pW#~_`5)xnrdGC*F zZ7>g{hxJB>j<W=`dm<m<o{)2_559%B&zfXkq6B^YDSTuG@e6w60;jha3!`2<+)AhV zx1V_X{^8Hq?^z1)@IfQF#uGvC`NJQ27OQhSgs5XXzr+wg@Fen>I?TWsLZm`$0haX| zWKTP!)qrK5$810Mdp0-IfCeSEXG_F@RQo`3M6jF|Lxl=S_=yPMu)+uPQYgo-m;Sp; z-5A9;*uERe!tVRDw=|L88?ys^^Iofsztx?IWd|pWR9zIBr5~CpI#G7xSH?{B*|jnP z9gO2J87nNevUjAf33OVOm!Do{x#fx*9RKoKq?j_rz3S4L_SDPY>By@eILcN^wh}(g zIg@o(=^OKg`5#bR{X-I?W!_B=g*C<()qYPeC~2w>000e<tTol-SgPW2AzAxrtLHgN z@vh^$o?Y<2V$|DqT<1ml$A76$+B$-5!)kvA$?yJx+n3el_<7&+c>UM?bKe<Bf~J$+ zJHYSnuN~2n7gJx>nm%n!F$^Dlxw(StT_eyvZ*L;&oLura7`ykM!J|cu!#U#0o)OQH zFIpphJDw}C_E6TdNgL?fxn~zsI%a(*b!pvKQ>4*6(MAQaJnGp<2}_!6iEVbRx4i=X zbge~AcF(a-Grxv+Wm)~&c>lQB>r{izpG$8)mlc{$JiU3Ocsdl)W{b1k-?9p#2JD}k zUMkR^qYlf`rmenBn0<@nO_<F_Ry+(ZQg>{$IinB}Z1k%-{GJsr($PhfG6Fc*#Nk!F z;tbv|<*AM>LtYh%p09eWe<q=utw{g$T|VK?)_a6()^egkQp!jfLUF&Ek25~sonVIz zrB68@c@gGRD(gA2QF`)wdq8W=!KRwl+Lhk1XX!g!pU1@d?FtwDt>rdl^B2>0!n?ou zsdD#ke&UJj7S{jy!c2Zg<0>j#E_5c)`1kY^7n}1Qs*hElE;knue<w>Y+oNWD3ay@| zq^KJIrY<_SwVXep+IBf*!2!2lA>8Tce|q_2N=(ebkSiXmQ;q~WP%b2Cp(Y`OWyi_U zukAVCIHCho3ncBsNv|&5c$>ZNjsI-VkH<D`+ma%huSc@Q%-`5c9yQq_ZnSZaKm1nY zE%MzIty?|OJi&$p%oG`Qo`}J<ck-Ky*ro+4_jRN2eld0(lxeEjf95_9&UejLciZ&M z1tSPIz~Q-x_P>SeomisfcM0m5ta7JRg+&Qfx)c~H`H<0=q!i+LtAyar-S9dYSuS_^ zsh6FiX>Bm-S*!oQovv?>wQp=ggaxtP2#<#K=M_j(I((Ow^{`O00d*S;r|X}A#w`q% zD4KblH??dj)h?yIuQmfF?YwNx2dbbAT29OCvuSoNQoSqw&KRXZYgx!uGCWq+({(%R zT5eJ@(36{Z?oX?N(!+kk{VLk&-V#$!N(MdE_7<%_w*5G><n`1CqCBuRd@!mv{r$G_ z2kX_yB&7APRLIwXfi)j5?z0x_0Mo6Jo(GLbhcnG|FPm)hUza|5iqt!8%$m^nwfq#z zez|5;s<rNCRA_T+ByHAYJccQKcCykcB)OJNw8MABK#qJ*Kv?q$s8|5X=h&%{h-(;a z7i7W)0Fc^u8byknS+a5SWD=1la;U51S}+zsLLuVTflPycQ+qCe&Rfr_D52B&!yTsa zA)oulY|Y6fSu+usr=(od?{=bDec-qUbjR=T^CDjvXyU6G$NyB4Zy4A_OX}bEvyl-m zjW?e-^6;mWR$y6a$~Zv@ZZECqt&Z`<vt(M^y%h<(qL(xkkwY_fieISX<diUsVpz}> z{XBKlZ;*>7vP4<1Q5X<aFpfgmcsftWG!g`yOK1eEap}9dA|%|a!7paQtO);zRXz3U z{@Y;>_Pu$c6toYn8P|a}(Tz|}?SWf*5^A)=kCHa&qxu_LXJGMVxJPu3{w7F!K>IFj z=Xb)Wl43d9KSdNM)SfZhARt%YMaUG4Besa6m}r15(=?uIWj|FI$IU6ZN7poJxP}l~ zZ4_gxL1p<}&Sw~&$=AUw<&38-r_Wy&WJIBu+BHjn$U_HVg8{Kg1~5)nywNwR6H3U_ z7Ro;SaZueY$o0V)o=L0IOPTaL-%4F{hn2P_N3>Z(=+tKsa&26v-F@EE%`&}80Z_W} zyo|>YysG4H>QeLa!LIxBi#~wRlvOJO3q-cdy-I-T_mtr>Sxr)ZKAzj1*nKC0xFpe5 zTTe=!V(ViT#nMcdNg`=f0;p<t7RF^orJrmCaLeiQJp3IRlc*q~b$?@LSW^^(42P0{ zbM4vU)q<NyA3@}B3T#ix4_AfzCcPJm&#&M7RvMGSQ~I$sVn$;KUrSlSec&A0eZgFo z8zN55VrT&G86r15mI@0%7tQ>R8UA?JOd*9$m}w8)h+Ly6CGkhkvkYtZJi6*|4WRoo zc;<rgFK#NEE2z&xWaF+yNpFwSo&lB4P0Ogtq86N(Axz!`fgx$LaD!_FUMY*xdO{@0 zP($`^KZ0o9__)0D;n{%8X2Uq8H?dFmqE6|m%6z1aX#FM^ZIi;4=K9{y?~2bIG(TN9 zC-l(o^Y>Ag;-k2iB>1mI%}0rz5lUR{RLo?Dr=qDn{x;3dYUf0^NNW30Ein+u&TN`( z$zNc6j{mAS|Ela)FcrN&P=W@UCmBc$30;vS0z&odQyGhJMxH$&HD9=Un}7+$un4@h z9K($8lh`-JMiIr!0jo!p>$`F-tw3VHCPRF?E61mTP$GS`?}qDEsP8XRsWdu8w#4Uh z1nKnNkRp|=ht*%^=|*VZPP7@SEY~Ku@xT4sQ%Pf-G5z4pJTMrx*YCO!VdhqpKDtTd zBuT59In3T&|40>}`3O|r+&#%4A>Y8ObdWegKOq~rH-<vQV(11Liz30oOoDSvo<ZPD zN>0P>+fO%L>zY(z+xtdsei{n<bL<qmXb#py#U1>uzUrq75IRlY+k>Hf(r3JD+R)4p z)g|L#c)FPddixR+Hf|^W-~20;n04Do_h#8vXOFIhdqpNGjWc&`PAJ03h?<pMT?_|Z zppSM{T|BDW>?aRVW?HFhLPi~}&eps;2`<kfh-bG`@S^K*9XwCC<@ot$tDm>7Txs(# z`;5?hKJ*~VIYM!O&$LNdD98>_B_T9J5@f}s(#+>-PhRAhX_yM{8()(6HRH(c@vda{ zuKRQZ*IUhZ3#Dd!%N(!XHn9vVcmX)z2j;<{z3$&AHf#R<hiV?Bo(?<*nNNPEBphyv zWRaxKK0G(U`^clh;-n&0Q;*nV2Wdj&ou6{R0pKzF2JHKi>VLbgsD<m7-_6hb1X1`q z1J^bIiKOY;DFA(;rb3b2BgvNDqGNxCe;jFaVNj&LLg)*nO{mnsAEoBy3dZlJ3jDWu zJ{9MzjLnAjKZzXHpLPvpy!il<nuwju@Q_c!B3-LTAPvxjZN_6E9syrC1%hD#5`KXE zHC0AZjRzObjzRLK<tX@02I~0!jc%HVJ}jM6=syP$_W;{+c-oy13uil9&al29lpFZ? zTm~BW#MIzB{2WCMKNL7_u6wOr*+O;}>kRouacYKi;H6pr{;6fI@CkN^x`2P%#2FFo z^a2B7`FYU4lIfrK%759r16^=^WLS3%#C9^lPr}aPW&lYO9_&ONodHsU@|63?*cf|R zfPxpIsPr+uno^WlLu$aF+NYAQgItmDaE<rW!%-gk^#Us^+p=CDCNfR7hqczo22`B4 z;De7sV_W~MJ}vvrz0z>=2|vATtx2YlmYqz`Y?8X&_I~%f?hwnp6a|Zy%kS(o`=%({ zrI*YnKPc|2Qh(*_hw%>N$oiE-T3NkvPJ~E?XaeX)7)^yvmNDTeFApiJiM+3$R|b^v zYeCp$kjh{kcZH*|8X*$=@FYfDGtW+A0%BXq6x*=V?aL-cf_0}M*2&7^CA=*{Sa#p+ zoXNztROpVG0BNK1v?jrN{NZGRqhmC|JhLb+BTsviqRj$Fa>5J-O1I-7xMT*Tf5GEA zfgBWZMVISM8&LvAk8+{Z%O#S0Ao3TXP8zI4AHrV`IyOJl0Hfg78onYa_^y4=pG^vX zi3rF#`)q=%w+_)<qv&o9TL{`a*6i}u?Tk5K?GcJ~;IP#+Q|Hkz(O%NQe_6c}9nQz@ zHi78Gfrsgoq~2QTXhOKIs!@HU&23+!1n2RG*>gfnos@~uD2VDc5J9@!M7S~(HGMi$ zPBqh>3XTeAke&Deu{M56bAYViS1CMziNTQX$ONmXx+rpkb~qtr=<E6$d3W9pj;iuP z?p%P%!P~E2+0JEa#DFcicEL>$!8@0=GsM;%q7_N8Sq5ADbPN4GN}XWp)4|aSMK(0J z0LKIP!&Y&2VPLuu7WVe`fzIx|_FcmIL_4by0cXn8Co<KOh0;sFp@}sIJ)2{`2q$6K zN9WF%`N%Va<*`;(_764S;ZoQ&_hZ{b%GD8AlWdhk_vE+V;C?n(!-Ln0-I97@8hfSm zGe`gPvr8_ASORpN3Fhv=VT(0LeivAW1J;}vwo(%+^I-;de<*1@_-ZKIs=uthNOO2o z#XGXaC=LRsxhp;^BW=fkL8H5_@vQh$|6=SkMifW{{z2RmC2rA<;u`$HG~uxYf2DEc zLyCRx-=S0QhE6YN#JkF9sZ(<QfdDm%()`HYP<6{kOR{(hzG%pG>rvr#e#_<OI;mrp zG@f=l(}Xi@vB}i*oHY*|wwZ=lF7piPL7WYWzSMmyDY5iWurX*wcP6`iYS_$t*d&%h z-c-pH8yy<VKF@WG-7eeig&X7TuG|}z^P{MXQuHPu8bosK6NQ*r(EW)<mV^UDpLPYH zV6bFD%X_wj17Vtsg<jywP*fs^2q94_CX`QDFm=1tI*oTSa52$m_0FB?+o=e{WQNTe zQ|!Cl4`SJFx?OM}#A4D;LugokCR?u)Y_<L1#pb~s?M|@%8rWJ?n`Sjk#IlAlqv62l zP*L_6w}nIn>x~aDf6mrlhDanh3SHwFB@97emFb}AM;mcfuZJF*PG1(vkClLtkyx+y z40&Ma$OSSEO7YpHj-87pB**NzKvu=?Qu`Nr&SmCShhN>=;h85-Vl&xlRGuwB3jSiJ zK_3q0=V!%1)IQlQOxjsbGl>Grco`f@gp56c_^OY~nC1!O&7@vsnI~-)=N)BTJ?)ku z?hOh?YLJQhaR*rx#TIhtx^%Cw6kx@X<qw@%X!QC5BByfBs#GOe$>2qu8h<Y!dTV6k zxZL+aN|9vE{pSULe%b8?{HGd1Cu4`uPO~Y9U;jQC8&zzn0Ji<aOf~~Ex*Rs`A?6bT z+HklaaafAXe0>69UBuIu8qGF`SWok`Sj$N$2e!h*8}|}BA=VDz<G-OeRK2s%xFE<3 zQWVW5EU0;&_=5i_y>j}cceQ@Fo{ItimITO3bj;_!gt~S2uc#(&c%`g+eqQv*^BfR> z&$doN1>lYfxjnp{iP)&8C~{wmz5hJq`n6r=zB%^U)@7^-X_#gr3GhY!6NOm!fd@n8 zsP^~Gk}15O=(hRn<DZp{#yxCkWU0y_%pjSNF@%ql`*1?P%K9GP;fai<zq)wB2m5)5 zr#yZckOU}7bB>X}w09bF$g)_TrSKt@cE(MQ^LV=I^AqJ?K|rFv%6h??vhBmd#d43o zOl&pJI^>`!mnWEh29G?jD58X14&3iIY&1QrZX(GXd}#6vtcT4p2f^N|!wqQQx7V&% zY*Dtqyfv}!w81k~28Zxg+46Dvy<mEJRQLVCj+(O?W{V*5UaAs5Oh$^L6!P)uU8PSl zJlfQe-1~-kyP8z8LHQd&GQ`ze@#kB>8)nM5jeks?B8vVR-ZnBjc);yQ5c9uLu&9W$ z`U{9gWK#CpgC?PdjDISDQE;u~r-gi`mNP{lAMJQktVHc_fjl`HNWBlF_oC;Zm;;mn zB5a>#KI+&JEDp353T%^QX6W*PuLQRlMIv|)?(C;{sb?2-%w5ms<uGs)7oRaeDu99d z1-@9~H;<DKVz)~AM<^QA>b8~YmL?kwbD#Awd-v=!vXWmhj-9gFHh$wAU=}Z=KT#H; z!BiVz?lK<M&yb{ye8dyM3R*nEWYQxQJ~g=}?bnbzRAx$yeYyI`jjR#nI0@)Mh7ytT z>G(d_ji6jJr(-mUrrAW9di=S)L(16f7mLkz7Lz0D@;y%?_HZdiUD=kKkS(Hk)*2Eh z%C=M4+B0T6#~)62l*Jg|HNy|vJ_x?B4AG*4Nne$F?lV>0Lvf-M#Xhoj2wC1a`%%`L z9leMeC4gOh`iPVLlSvr|HIM`7#e@q$e=J2&7yvmh9XCQ_8MlX^h-!<Q$%-O8lXJ9l ziCu&ukO%WpMDy;n&Y1pou7``A?k79c<<AyH5OaITzHy`)0JLt&d{^5-8Jp6IG=I5k z=V&pjOI{SVz}2rgle~sCW_VVcjDI(WWT`xr5VCd#8KfldozW`5I~96F9dux1k5`A% zpm-Jo<s82XqR31SIsf<NTpF2c6V>oAG0#)|Yk#t)1%eu>NYwpa(0a10P(-xplK;<$ z=Og#DBf)zjDaJxiP3<3>lk7BN>`pyp?}^xW3s3p4$ZL4JDFOg=5(37#jyvZ866t~9 zsVLjVgyOOBRZ)Q_Hx9yol71)-BPEu=Z?7n*j4G1&<p4!8`PvGeSoF2%ctj;Gg{->S zd-KVgy^dF#Hfjc%`04bnvST+lj=w$`i84>&*<!<tQoy#$F0Z~obk}(1o6oEE^{4^n za}yAQ`Rr;ZS7X1DLw_FUQYm`vMsi9Jc`1&YluuPZ1J?<b$s5vWXUNlnKFGkJugN`A zpbC18*Kab8^9Tf?)TY)Y4x|*JS8=l0iUT9c+)XZ+4hI8G*Y}u0NC=JZxS}EJxU{y9 zxBPV9TGMZ8CX8wQ+-#usm;9Eu!=0`=inbCt6H}2*#7z7Gk#_V3%vy;@Y^Hf>@Z_jT zo>>SOo6t(qyQXHvllJ4u6E~|qr&i^^RHWU?aFJIuYfnlU@=<YmGCL?G6j-i>IA%rk zR?B{DYTTGjuChON?j`x_WwMs~ciFgi>R-~Q({Ii&5CZJ>YXVQ<6U5LS!fQ3w=JU*x z&+U)FX^imR9_b;g*}b(0WAm9VMq>8Yu6L*z=1rosiH!H}Qxzvc1V5hiJm`QnTd5r+ zTl6OH$A-6nN=YHhZ!^m0+>vYsJ%7*mMZ=uya*{tm&yuv{4}89*qk@m2Y0B|T9&BQZ zZWjD2nZEkZw_ZjZl<}2D(QvQLT1Ef~yshiTF&`m2MfoSfvc1`?+C>NZ)`XA;K1zBa z;I^3%lcbl5x|<sKYZPM>pE<|(p%FgQpodG*H~uleABI*`x^hBo>QGp$0uTRh>wwoy zmC$#52n?ZNhCo{!>izdu2ZlT~>UmnG1vJu=`TR0Nwe73-?bK&CO$9O2H|O_%1E^P1 z%4%&~o?eT3`dl>9xOBqOBce()$~F3zdrf(+s76mlRo2Qd%+c$S<(||p1H(dv3XUfM zpwI4FjF0tx;O7wY;Nyli-!=^x=9w7YAXJdmm;A7D4(})|{a4r-RZZCs>g^47F0Lh= zdjAhZZO2GDW`oz`q3??c<cwi}7#TBhDgFBnc6W4~bW-HK3hjXF8FI&>AJ$o%{Jt%h z95dywc;@<8$!lA$D_^$kju*(<CX8I3+T&2%Fr530U%Y6FUUE42o0K?xLZQDWmFxb_ z?N>%{kB6avHe%}>xb8;#J~#FB*g;RzlfnB}R9%X_t;<#t2x`)Y{C;_>+CE%W_h`6s z;9Ev_+34k#$@?ne*XMQ#bL^+rC>&b_QH=f_wKz4=-8c}5<9K0w7-Rp2w0!Qk`_+Tj zBs{FdN2T_Ll#Nbqr;6Xj{tX*DcicqV$uz`Su0<(<OU|tfT<ypiSGgq@eP&+2*6ED* z<~m=stjD|LwD(3>bS>ZKew&Q@Mt&^LJLcZb!P>ytwUu_0XUTTO9ttkul2#jQ%(j;A z{OpU?pSTxxjq`66U<`!vRZBaB*Lm>W8$_KFkO-7}=`!9UVF<2#O-G!_>!b3ldWbFU z|J@;ta7<N#CY0p<#+E(v-=8V{JkU<Q`&#<Hg?E*wS{5SD1}Eg_)ThxFV8Cl7FbNy* zKGD$y2m!rwS>`;@sPpuEveBPGYJ8_2xoil#6?rX8t@!KU9$C5#z6>IeKi9%B7r$Ux zg?pM7uRgx_W+@y^`7!wwt(px$J1K7yrb#Y@y_h0<{ZT((Dnb%UCqj*NIl3Akplnyh zuQ8J#2c??ja*uzVhJd?WvEs3R3p=dpQ&h&?hQ#0W^XH;W8gmJ+`EqcX`Rrpk4Z)<E zG4t4O_u3>sG}y)BQuWtmYKUX*8g<?S{4XJENlB_Dt}$GOkc=AnzLx3D6ts<v-YX_1 zOXRjN8lcmfI5$C)kI|+*G_?g6koHK4<!Ty+PMS+#ULh&$h87v9$=GiUKTlB~dE)t| z{@Ww#Q+uDu?)(~4PX7lwSbi#Lfu)?4w={}#PWkeSkd`vUQi?XjIVv=NXuPhfwMB+Y zr8eZ;tZKdey2S$M`4lm5c?!0#43~okBfl1H=oj}6@dA$C7YgEVb^|H9N{Mm6QmHxC zA;o9twd?S@Tg83e`W>+0j+!V*&1^(Ofii*>EwjLaXnW83&V%J<NcTH;B^&mf)=Zj0 zd)7xNuLdGC9YOL9i4nWE@?h#&-$e`6&c{sNcQnp^AsWSxkP2{fsqzmmFeKQy2ZY0c zYi2?#j1OAJ0jRtukwxgDOE}!ShaczWY>bY@pSBqB7hBJ<a(;&n>Kc-t)NFHnHY8G7 zFpUKb=IPGCfIN|rMzv|#+@LsO&QA)#8Af;M)7@)8;X;1RIN3H7`IoqO*lJ9b`f{6; zpWqR;d@{`UQ!{Q(%YQdtT*O^hL={L79ET4pczcNx{19{3%5g}zjf{}19CtF1VVtc1 z@N%(SrqZ<Ej@!QHVdzL2S&mDGy6Ng`X2w7W_2AKrU$JNh3n=zULf#eDc_9aC_1T`q zDnq65qLbZk_Y14$Q8pbgbXqnI8YW~L$?(hT0uxE^t8MQ{Hmt{a<Gm_yej^m+dg_?P zB&Z~7*-oM*(9xPZggP?Gl)pTli}VVVI`RoDJ5<qbwvm`0VXo&kemGx!F;TrD5(4b| z_6W@oqFZh^>Lp<cP6{#F?5^n*oF+gOS4nx4d-qVJ7z$x7K&k@(i)IBDZr`nbc+^G< z1B_3%ZpwNZaC|W<7nj}{$r`1GN?!~b6}9$_(0M+ZjoTKS?;j5<cAthwv{WP15UT}| zI|)lF4vlxMPJjwy96ICx&X{9)*;M5OM6yb2^vMY!AUd)c9XpS6Nl%grzPTWBu@5Y7 zHl*=`{<Yfwm#-UWA-4{^7k)@<TKY;Jf-7tq_I#jF_FAm$O|8AY#W5G~ye_zCl$Nz3 zZtq^-*1d24$@FbT7TNw@K!$R{6+hseELO{q@t>L{&-Qs(t86^)vy_rM!S->k6;x&Y zls@#b8YUChSR6UnbLHvGsP0Fa+dd5kkK?ooH6;ei)qP6D;H<0ByJOP#t<;ZXt=So^ zuOT#mp@Q@^J0F}hoYMKO_Ney6Fts+1NbF54UgOE)#GQzpjdrbzpCjn|!X?Klb}s7M zjcPfAiZh+<aDN4J=<f`%sN`%J!Rz|Iv)!meYVR6*`*eC8?+N>c>c~G8B<!NQ3sOII zUD3J+*Ra1Ih=0?l>8XpBe0<ViZGW^N%B=euFs$kce1}3Tc?OLOb+oiIcn;bu`8S-r zyMGr9j`9<7-T>j`_KLHrmg`*PYYT~sMgAQw9=b;2g;|{A$`9}k)_L9IiOJ>YKCYAX z{LSKcbEf<_#;7uHK*5*Kbic=!05%0JUhc!GUCE)k-Er?4sw*`uW1q^E&*xo9kvmYe zZijm^dAgnZ&KCOT{+}K$e9*y_<TB(&xZcs{q5jAqF=2T5`8>=%VIt!5&U8rQz5QRx zktaFzYtSHBB+7Am3HKroZvNdH9h?l7<j%kVu|t!Q{Kd--FX7e~)X>3QixP8B#**$X zTLnful+M0jnv$Sr9fIf<i}H(AnFCI@O=#9sfevNK#svd2q-!pz!r47kgyS-3wmkpa z-%oSXy8phSe1DpScM*<AD9+B2Wzz~(gqo|mRTcNoj5ZI2mAZ4Ym7jBdn@$>vdJ4GL z&he9a$sma^Av?MIn7byGiJ~FqJc)429Gmt9QO*h8!d1^4Be=JId9Xv8#ndo<4#@Ed zA&Z{nURCVsX*=zvu`4U4Lus@59K}40mTORubuAnrq%36Q^g4RSTd2iW^zTAP;`Z=$ z3$q+Amb0T>z~5DGzfIZ3yHU*;$ezJOvEyqhG9UVKb`OxZ_S3Tam$<oBi=aZcm_-by zZ$um4c=^Bxv)Sf3LZsKw%4JzqdrI3^{u6Qi@?MRlv=?@BN`!nJKOXu>7i8hZxu89t z!!TKa`;=t1t|-hu%slS)K4^gU%j`b~6mKvL^FbeI{HCT>j6E2xrP*PncKkWPG0+RF zNj32)QWOir{v_kN8gWE|f`I>QYQ(3EbNd=`Bn*@tCOguoA{auv2f+=(ezz>EZVrui zJx=wcDC0n=MXp%#;`70yn))S}n`3C8QJOQ4!Gg|j?nHX+Qr%V6AtFY$#l>a5Z`Ep8 z)CC52!XNFD8WF*T)vZy0I$>a=s2+&%wi=NPe*ZxWBes-q5sZv15yL$pb&i7+jR>-E zu)^RFZjvmS!cgK8%H0zbQV2079b-lmc{Q?fB?z#g$cG9^9%8s(yK?18cDGi9kU>f4 zmwD73lGF%*>>?rS>1&UiHaM|019b5>fUf8y{L_3Zwurh)(o+#N8l;LMyR=rhnAw<9 z1GHCg2rx+V*1xOZir_C}aLwz65-8K>3(7G=;!5$%@G#}OVG2z{xbI|1R@jLX5eg@U zqyd_I1EX;>O#bo}xq5PND@d}MtW>ZAK9t;eU-yxbP51deZh@2ms)!FgM6XWhkj~t- z4365q(1mG2V$_cA0v5!CmTOyGI%Jk*6`^EZca$jk6nMd)q%0gdNnCEn)|c5gm8l2$ z^sQ<u{>BR)$IG2TiX@D}K%-I)K_;b@kQb?Zh#<)y8q-~rvqDLJJEUYlkiV=hS5200 zpUBN}7Gidb!NWx6=$Hm@JC_bW1R$qLe|b(BeWbxPyx1FjTP;_o>Y>ge4Goadxc4gQ z-m1F|d~J->P>nCS_fb5$AJs>FUpcYS`<N>;%99|O9Hw}8K`M>)V<1d9g&_GI#G(kv zlEM@UdOp7wR27B&=Ik`fT?fh5B5wb_@TIkU(QHX9_`=L8pvSlXzY7=s4#dqHEvpTq z`P><+2iK-GMK|qKmXfqbgua#YWECUzEsd_LwP3W=#JIaK7ibdyCWKqabHcuRwAa)< za<R@JAZb*xFHvDJUUR6z`Q{Lm4U@|AF;5$IsU%pu2aVOMBHGBZvo!QXl&Nt<=o6aA z^^NqqPRK4mj6+B16ZCfM2`hFw8xNL5MTfdL(v1}Tm2%lV8~PA6Z4*&ZQn^6^5A}~0 z{vCeSa@q3gu{{CF{MIs@?~+swL)@PzIX#3M04e+$lCB-XWl5+AG(0|8o;7Stu3)>y z@4LJ_P`*P@#x;uET)I8kstlrsKAE@v{s0XQL)i~WlyfB<kJ{i&b}dF@Hd_bps$kMq z(=~dC`d`fn=P|1!Kyi7ZfPxt$p&}n75}}y6`Rm_Xg~7)}yU6MR<qqiHxlkihfn_<l z@H(Us-7Ih|>B?#Zxw}J7FP~cLWyd%(q$%Ib+ef8JK>Nzc%6M}3z*ot?-;^JO{~ah= zn+A|qNJF21n!A-^&vT?fL$+&eZGr1AfJPD4`c4z-(LcZ-P25XfvxB$dtD%7mg| zKctCxU+J9`^X2#~NhUD_VxA;bu<}P0zJp|Ff@O!QBoLe}Dq<XmT>3t`UiSLZDv0nz z-@AQX(|8k)f<~cfl4d^+qaC}Y7VP!@e%!SjQ6Mk`dN7y^gYY|e^qc?Dbl(3|{_+36 z&T;l|uEVj#u}7st2ua75s6#3;Iz~d$F%o5*V;=k1Bk34LQdt>M9a~GsNYXk&G~Yx; z>wM1V^Syolf^)7PuJL+4ACLQ;TXwa7^$rz3^VxYZduy()$CBSQYWohd#yY~faof_m z%^<C%_=NN4B|DhWziLHHu;SGAj}O-rwbvA>YzJ=N&Q42Z*^l0Pi+^cj0BuX9KbXC9 zsmfc`v@%u0Dwm%xzn}k=>L_PP6i~xMpB*`@7xtM>Q#?oq`r>%@JeaNj3#h^4Q38VE zk)^uBw!{xdGka2RJ<P>F@jc;LawdK&2LOyhQ)MXW%D>3c8!TfHsW>e{C9`gq-P)cx zBSUWo<&eIjn$OJ?2+pl-?{?8_SV+fyyKdE|r90(H8UwJ#zW8YX{Pn2r4ln-RJ9-im zt=bya@NTO(BpahbpgqJE_BS--SYuVfPJVi?8MuxcuvVQ@{xuz&{OFS6ywX?J36nYh zXiHpgu`Jt{5ZR}dk)lMll$*{!G`CY?uV0bGm}yP2+`2E=k+wIPVNg}#_!=(JD7`?{ z6Tg#36n8@x@X+GE2V0@IF6ef&ZG10JZ)I`YXL9!WpXXRVvnSYUS?>tnA}FC>583@7 zh`1-i%-H91vG%gpmxIrHXv)lTluaxpLaLS7)k<D0P!1ZWY$;25=WP!G77i7yLnH$l zZbkcwfBkCkgL`2nP{e<~9`&3`98N<N&}o9!E1!7;)KGgnJ8M0y{hx;TRknNlIRkOq zF<p~u5`9>UBAYMkF**o97U}keeCB6K%F+zWtNlnr>6WH^N!pyUrmy@4^Xx~FX{yg) zOQ}qhWzg(coX2P?fMq|sj&(bnpjB%$Nyfrv$|#@aS9o|}4%c)N#iWA;83*ogGy7D< zp?#>jVCQRA<*fp(%xAi-8A+z3jwzAfYxvse14=I)?*KpZ!ZP<mS(#kJ?!S;NCUZ(9 zECo4;^ae!UYtBH~Dy7KwobkR0xy@7tL}n#_-#!)mEY@3nUOThjXBHs)Iu>pYej5|O zxO5bUx*{$N+$uX)u6d+hwcy{s)XR7MGS|7jCpPsEpBW~GmMbKi-HRSN!(gL;@YOhX zUu~JzY$VCZ$VcU<Nwxex*5*eRF~w4m4Ff*Tk!BB_W7HM}u9#e9N&RVzm#fCFP@UJG z8GOveSacRYmz(*+#Ww)hF#(3en!gv_HwMK8kWKDylex<U#rw|b8|Zwd>ZLsA>UZT- zHrl8l2LW=~3s%kj*)lP-(XY7^A5~-=s+BiX6uelZR+YMIa?%D66DRHT@0PL+d2&iB z3KQ3F4ciy&%&pv#C0@yM#GkoTXyUudoQ2N)HwZ}ny1nhk056Pspq;Td`mpHZlBy~? znhVqPLd*4*agfcZYW)Ru2pw+$0c>QOJYVu1{iEuB{x3E34@8o!lDuJwQ|ePvy{7P< zr6ii3rcB2T<fhiWFPeIU4Z3!KGQjS9@A!PPY~{IlyR*dOgG9r{OjQkH5)Um8iLd&= zL~H0x95Ikk$H~HE3zNbt8h23hO2vHLsBmI-pPaYC{aq(dq;%^CAbx`T<jX!0$(G7v zeJ4LyO0-%A#V#KzhN!n&Dper%HwVaU4E?6mVyEp6*8N^F`xCua@9!Hfi34o&B<qy% z&;eXzc79ezm-ZV0A?;bOTJ6>;9;4u4NtSB%&5D2>n&CBT6aY~8c5xJP?S8yaFYrH> z<i|eAA1uW>ma;(~Nz~_KBr9#ut26zA)WRiHyd)yPQw|WV*;5zlrVd&?JT6u;uysne zK~=ZinN+|G)viVH-p9R)aOtHsEZ7@}FM=gIM<4<~zi!8JNsbVp5d3K`uZ=4FJ?s;4 z-ua}m$s9@XbiN-%`Ui{Tz>?vMnDvmGB#-pN^8KE(>Ri{zYQy;>QulPrv6(p*Q?XBs zKFuSB@aio10V+bI8VTh+7YV(>xFRq}&d1^HlLTpax&fwd8)0cXjzavg-eD&ana|;& z&&*mT$2<Ryr(TcxHz!4zW5@){YO<83AOM9WC3{=xTS%b;OIlUv;@Aq2X@yO<`|j=< z)*XDh`v={UGEMj~_=u|KD;yM9-VE9OmFUi#^B|*hndmYqg26<4@eUxiEif_GyN--u zEFVwz00X0U;eB|Xj*fele?Rk5*QG_zMUCgIEzuCXZiCV<h-9UTd>!kVbRW?!L!ru7 zA{^ofkZ%>K?8oij-BmjcQ2(0<AS?rTpTD54bmCg6<qrS*cL03!-$YL;I)FS=4ghvM z6x6csO|MHYZ?VcO`-M8OVY|VKAOEi^F5xgZ&GVx!VqIGoe<#>F$>xc^vE}=eMlH8Q zvq&{#@(ozLlO@T|Qel}TZ|9p@0ImD%efP8Ye2_5M2L%CUdFWX>n6k6bv~ru4^}(wR zScy4=BNbT&pbPpDxn!Ns(D|%>@xko2`!qGA*4KF|aP~#Goq<jb28Xi-%bx#Ndfc`v z^L{5!ZmLhVQALu+QsPw`FPxY6s+RPE$jL&2I$6gGnr>Cv%WPA8lx=0fW8%8FSVZ-~ zp_l94ayz3BJ^sN%0L*9z6>0~N?EpHIOIO;R@Z&Rtvvi=uhN%kGb!hQZHS&>{nssjw zT;7|(>mri0!F@nZ|6sLtkh82!+H}mX&YLw)E}BGseD$EM{^@0EGG>cod&79GL*e`O zk#-&CRj22F2c9h+Zx?kbp7liEP}(7M`~GpyfJp7yd#I;m&&B#3mpeLo?trc_BRLlh zgSxn@2Fv^^lkgRRi*{G@Tt6T_KNpOol^Vvrdj)Wk_hB<NLPr6*4NZlb@MrLW7{bXu zLo(bzqI`MYE|1)o5**N4^Drq11_1+5<7N8{i!sUvdb?KVM+>)hqHo8pCBB~t{x(JM zzIkZ5#&-T(h}+#0gCEB~k@BV*T-&_z{fr(;-E<G)#gy-`dpv)S2_?L#?Yb`<GT*F5 z%4GMpNSv?(_)u)oYrYlQfYfIrpFoO0k$q-XJ#2RC7Yx}czm6h0vS=g+HC4IRiz<f~ zeAz1gkKHCC45x$Ub4=cMRSF}=S_a1U{EVu0+AFARl`{E`i+pI#cN=it(=zCK&~qff zPeZd-P>>-*56DkdO2%2Cf}+XmZ_6_vGlf<ujA{fKBSnHq9-s{l5{&^cg-D%YBon<- z@?BIFzQGXW)UIiw?e)cc)IKe^#IQ0+PQs471M}^{-p|X+AL_Yjx*v1Rt-ceSg$of5 zyFOL6W*a`wZaXNdtxi5EY!acnfJY*yy*clrb)IH$sCGp{wNAiD`ClpZnF=hV03jp! z1>yi|ETaL?a)E1Yso|tDs^Du#gn<S#ycC%;qzU$cR6fM+R8g3lt7U4;TzOd6-#K_# zZ|a<%)7-|+kHS8bR?|v9yckoQ_ag=>y{rE7&M}kk*{azl2dcy{Ti0o7-;8IqC$lMQ z0njw%6Vg{fQMB#%wu9kN`gTz!H(&PPi^f%i5>wIDLD7jqOu-vJmO}s;AO=WZ9s7;6 z&wBT1=&sb?mi4gi)ILwAA=$?(GXbTiqg};cMmFXNU)5x3u5%2s4X0Pcu-m>f4n47G zV)o*Vo`x1W?R=uWlaR@fM?^k;g1DW&B|VCmrW~`d+9YF6D;fweRYy52#$+F{w@Zz4 zNhO++Puoa`F-fC#K5iRk_9{@pj(uCC3LMCZz4;1fV%_xjg|Q#U{8$~;x)nEYrS-;` z_8lA)E7bbqE;eS&I6CRPYi;UV_UKg5{6pi1vSVzS%LBb8^O<Ok(=uF-Dr6!tHEdI< zWba-3u?xK{l`R?*m&onLspMBwgek*HYK4PZzm0J5*l!~{#Z|p|357dD8T>ElIm#vu zLhSRXLfJd?AH4F!{_}?YwgdTueL;T8voDb9X)3v2K8Q)KZM@tm!g!u0g(+pn%qGCv zEPj~oceYqfmPf&4hk8F}?7-&GB?{nHe;{Dus8~(ZbGAte3vEW7t*WxCk&p^dZH+C> zpsmC4&>gtDo6e~H4kKo>`6j__$lW!y8D5WT@jU{h;SUzZonI^ej6b5*QBBA{VJ-1X zIGQ%+W@kFInjX)tmLo}8vGp3}z}V3Nh4=Q3>Th6))B%)@x?iCc%<o*7$(D&wT8d8B zoK4Sfl&toUL{W-pqG<?|onEQYf902Z&grT_X?fux)3x%kl!tq!=g`r-BrM;=eout2 zgVy*wscTflNHp$r(6v@BbPywd28N>Vter5v=3yIngt(iMg!QJ|jA3e&2VU7wm@X)C zKUd|**9Fz+ax0>EmsY-E4N=(W5Jp+Bd*h~(oYrimU-n=;_x!p}tkc}q#urGv$McGU z(LwXZmTZq4)qu4!g!23RoWN!46CZj4h~w*pT2=aZZ{{G8P%C+UYzMYMe_7}ZE~f5X zxJr!OcsE`!oU%=^AI#x9?^B02Q{xyCZ1-fh?4RSU6^CPEr~EOdkeqP3j*Li1wL^R# z!DsoQ+^bQfX1mIR*t)gIYILa853QMgD32h8c0RCx21X%gRk>SF{B!CqdpNg4oT=@s z+Fs^XN$Mx~IJnt3SzX-4gq$_lko-h>hPv@r9AMF{B)<;AY&M|fC!gF1lNu&*zOhd) z@CVHdT?hx+{_-(m)8>eAhmgl&(s%eH>V(_M-@Oa!_Z%*1Zw1hs`h%^TFCX~51Ld!4 z-fla1(LrU3n|5P1r5$KUl93Kch9y;Fm{gl1`0*6!Y{7lu_I~|y!u<khvhEEh(_%MT zc;+n;W#A^$_Lj)ZMGKujvqpyNt+Na&j~uPX#%h`C^v|eGOM>xSs8z*G*Cha9O{Wj0 zjXhE^cz;T@_wno$|2exXuFuQik)>qG52RcG0%=T1!rM_0ujDr#(2g897T=z`&s<G% zu_0YsQ6G1HTdmUVh9UC`%RHy9q=B^{a^+0$>vMY1D(~Pa@|Ap~i|W<*J*FXiOtH_p zLBBZRK}#-n72Jt=SA9l%c07!ELt3#KeW|=3RUuf=_WU&wgbl`2TVi}@^@rp5NXNZ) z1cQrmPnMD;D{p0;Jde1duQNTM@`n29p~P*i+I`9L2M#p|Gb&4iD{gpCLtT(Y4pG;A zsDoXN{N*Uy^Anf)+uQ3;7fH6N=?cq6bWHT~;@ADfZwg?h>z0{{9|vw~h^hYKIt&tJ zhA0tVt^9RIK;F!6s(H&c!0*-4m726*4}LjUr>2K8)dy<sGXeT33h&|}Rwf)40aW>* zxxt>5eHwER%szd<OI7-#;J`LL2oT@wCpW;i->KJvFS=6k`e~*q)2ZBMguBCFW4e4y zt{?ofSy|K&H=xqXIk-*twyK2Appw&0#tiJ8HODc=5fBX9xmClq2lW$&>Fi9Q^*o($ z!PX?9G2xZ9WGRql*3g%c(Dly0mudG%h4tQsCR`q{K3sU+=tJ7(**<JKwaLmo+xsH$ z9`tOkA3rCN|2@f<DJFD~UXr@@3jB309g&<rnJT6<N{1yiw9nY*1?L_r$5y(JSRByD zC48PIM$(6Gd9`3qD}JRJx4qEFgZ`&+Z{OZGw-u|-K+DcAo$?WmW!!==rzC7GjPdDT z{zG|>Q<;4jyMJep{ZhuQ1^<4Re!Vd;9hmF(gr!6r5Fgg_&5UTRk=`VCnw<<QihjTJ zU&829g^d?arAH*kA_C<fl*(5fMzS<xJH!++`0(RgJJ+9ZUb|%&c*Kd0$_LSx$x;B> zSn!-RS9;_hE#amJ%_-uHF~nv3)!UoV!cabzq=^e|mesH$L8XvXID%#Gp7K+9w+hXJ zfy}1)@99Iqq-+XgR1dWguU0F#JV!N2I?2|Bo?3ANz|%@Gsmijh|G4Ou6+%4+`<o;F z)kXXj9h=8Q-{E1W`UCA-_HxG&9#oaf1Bv>R$>UZ?Zw~6OW{N5CSVv?^LH+Kt9K<oH zvyXpj9~AwxK!HaTf0Lfdai`PfJoogASf=9M0Pu{5{s4#%aM8~Iya>~|O2$<1;Aa8( zNMGcORB%)4q))S+e+1dAEqS0`5^@{q0j5|L%EQVe={&<`2)kttnd+{ZBtXzPhtI$y zk29R!)5ZVsSo!WbLPUx2zh?1&AU2sJUe3WTQV2VS@PGg_b{p$SMFjAC4obS`9M)WM z*G!j^C$fkiQKE)8%FJK#U%qB%v}FFAYzPlk`8})Zw)RsQHnTYkzG?;t^n5v%-6~GX zMGCVU?CG-nJ5sLiL46T7RjTcLFaLBYBXF9B{+x;k6~Mj75@$qGCJ94JF<>Z-=tV`` zkw$U#9ls1D$Nn&kX-Ky}DcR(PddS{ktP-06B12ZRH6c1GtXOST)V)>o=Vo#3fK>VJ z;uBYbg#v6XA6?$OtCxwM=i_@Bn3uFbC<--Xj0|8N^f4&)>4%?YiaKV9p{s@YE<4XU zL<&t;{X%#!OOqlS9byIt9?nfCu~L+Y5?OL*yIDv&&E?p9w%BlSMRz`#jcukP+BxC_ zR)PIw^cq=wX${HBPfTa1;6{9!uOap)YfJR`Ik!hrkx|Bl7xzBDSfUmc*6Mh#LDHRs zisr+`Y>W~&h%Dfkb0I@LUm_ZGBFY^hx0lbnDE>jsxWD+n+}KGT!nXn2L%ASQm9#V) zq_Nzo*8acP$Y_3I=S-djQ48CRwDRyr>?^_sA>G9k2pM*5E)w0VMLtZnx-b0hD*U3K z`Bd2@@R-$AE!So)&XbFq=b@*Y36}(zv#D<XM69BsegD)WJD2^!X(*vL51vC)37C>( zuAD?>O73&e@mN9fH;c~j?e1IaJq$$E$W&YDT1lQK2s!ANd~^|&kPTpeGjUBkd_S1I z7HRhxUAD(1ojSKSgm)(GT3jj*eulck?7e&#g$t9vB%8wMUWL1LBQDkyTbtEKO_^&K z(W?M#3lCQ&!2ISA%6a&N6Y^#<@^yoeT^S9T4=)~;_q&sEsyPOAbWmmawwuJ1&*8~3 zR*X@Pm`?W`!h?1;kp|!KE&KRUqTd=f>P}-op)s}9{`8u@PBLPRMkr_Qx)ylmdxyl& z>Ff7?UB9PGnyx`87sOc*i5?(#mr5*)iS(c<1ZV2BT3!-{3lzvH`Aro!9u(RyYKf<F z&~G)-f9Oi<Obi|LTQT%gExGx%?!r!Yw{$MTyP0^rF;1l=o9(*W9)-fEAk~RC{`F@k zku9<3on{(upk6jAejro==y%P8bTVO*yR};Y&$lF+t>yh0HCZb<^JAwOIOrJ1mSn#} z4q;S#qf$}@O%p$hwB8}kkeiPKh(Zb?AFM-PY(q_YK2}TkLCLZ3tE=FlbZxMAndk>J zLJk-4+x^Nvhsa}Qq~D!BK0K61QPjx8TX`y|-woFsKfuGN3RUM-y;mIX&%;lFM*yDA z%WG|6Jrwg#jX!A#>pZxf)s|d3I`qYE^NfqadoLo>D=ust0vQNW*&;I0{?_+d$8;dn zm%8KEv04B`KF}@KoJ074PRBt+AqVOFp78t!>CEmsy+ipLGw>-A_KyG+$G|yAA@{0X zR%>k8?Q(^yuWax`?sC45d38?;Lpvjhndoo}PwFrYk&ynqJB<T(Gez9ub(rtJGqF`S z7_RQBf@6r?tfJt{1h8nb<KCS;2R|J&_dRp0-6o2v-QIn9rT^A(D+&9q%A3_$9>uje z;C^UNtr1pn)+A%{_x-6)lnaC6+5CDDzLvu$qzhnlu5Ihf!kyOlEUWXpfxQZTDxV(R za~Qeh!!O!&%q~E>4103NgIlDA&I*-CxXO2ge^{PgliHPUji31h5fVO6P@hf3cLRuB zCdB5R#Jf6O2;yLhr&|(4-uq);abq7zpUC2CnjrcgJ2thupzg1=9_D4I(anr5+!$N! zr)R4jDmfj*L@a6gdf<T5eE8P2Dkl15Z}|nY)t!<oVlV^6qH&7MTK9kF#EKdaYD3C> zw@j=hdi;l+lieP^ghew^M;M;w62k>fYKJs)8hD5rrZ}S(UHZ+#MoWS?ep|CdvsSU} z7z~Kc9{KJ^do&V5Y~cm-QSPK}`{k74?!%WdRps>aFYZPkU+MkCSH$mpFleqAem#|% zgbkpGNV0T7wQWW-Qb;X^bDQ#p?1>lBB`Z%L*TP47Ykjizw-U#x!2mJPFq<4fe0;IC zJKW-{E4Lb>RwDag$m{9wT${OT!gmHH6cAxM36d)Qp6i3b6y;%Q$Lgl*g`QXb?Hp~$ zCVKM`oRuf>9V6y*r{*gWVZ5>v@@!v6RLRyGq$!F1Is|(K!E<{0qjzFJKS%HH1lKd6 zlY;dVpt_hCLW`}ZIx3xtjAtUIyyOqoM(!N}WnJXg#*voR60%#y-eqgkX~-=qq2%5( zouLv3_DMXwV|kc~iUkxEHrjUFWo`4GE+4++1kwM;!;~^`MRfe-x=BT1ZI76IBp<oW z6dv_JLntDt1oMz_&8IRIT8Arc%l!pK;a+=pRS(=HbuakA2MQj%v(D1f$3v&fa!AuZ z2!#|(1%R$yffqJv?<-~;ZI9fSI(oFOr`~sb2c~x3DN24-K649O#Wy=2uQPPD_xOtC zn1W(|<%|A!5(Phr?s$BOjMx?ub>~yn*q2vQUuM(dZ&?-<k(<(oAC0AGHcyWz>^haI zcbC;@_G;lS>GUVX`fqI^hX_Fo+$9PsKp^*Y&)fTU{x;(=OOr)tG&_lg^roYZn0Fjt z$FjlvBz^$W^9@Fvq~(?{$UxUJFb4$i^PJ1;r{9i0>9L+WmCDz29oVnEKRZK!2%+5< z7L;c*4D(y(9zES!@82n)+zWsCf)uh{Y7IcY?5N@F^k08H`2ER9^PaI79{j_n@ozmd zF#?#F!i&0Mr01Uer;S{`{u_OtMT38yizDb`OsrbpF!Xhdw3Uv`*QuMmw!sYT9?8+$ zU&g%!$k2~7slW@VVmKwd?MT9s%^YRhA3{+x>M}*4==uS0Jj;J<a4*sDP$bf;A2n9m z>gt8EB(-@OeaPX#)Sf6<sOgljmnz2u(8uC)OvGtEQUijDk<A8)uVoWR`_fg842|D{ z^t;W&!+{$G<r0rf^27MB3ObzUw0KGBvw!*`x2p6D)H8(x_vRw6<l0*Nn-$s-i6+NT zh_39m<Q;w3{#)}q`M(^|Cw1^63J-!%XBgN^(9iv2ANcEM$D#<@>N%Sn*b%AGBnm3A z9zk9u#!{~R3SKtLN3PFax!SVZXX~g25y7PPL)TlKxI-*DJhw@~{lmKtRbNN8Ie%5! zl1zmMh_2R8BAKjAXCf8D?WDi_=lt2x?1e_q*lrcQ(VLc^P@?F+0^(~cqPq`PW`LG@ zyLR-AVhA2{j04}WFq$}r$`nV02#}Li*G3w5$HpPydsg)FIF!9#?gyX_6f-o&<$u)- zH5GO&e_gZ4dupgBRSCcnI}a<f)~v0Yyjs_D-*E{0j1=<~I;>H`HCE!C+L==ajL59+ zT>Mhajb7-0f{;$}Klo$M@eJ2|!~xoev;1R|xwYiIsKH<7f+?tPhh(ptvJ*?EF7Qyo zkIP5z&!&=<kHqzA`Nd~YFC~(H7*=m&AOB4n7YGHg1I-#i7k02vm$F57@*F&BUug^l z70*Rlot0R9S!OTJ&R9Wg>0KyGf5u`MO`)CG0z#$V?>A>8hny3B@(IRNxcOW71t7Nd zpSJGa57*DwX%s}QekwzazD2ly3Z6}2k(VSNv;!*I6MKOlfTB$qZO$qUzeOZvb$Mr# zDYe~au*_xNE_chG1Xwx$jYGkY$FHx~r(|eS>8&J*^(Em!l?o&516a|adZ%)vkh~!0 zrtMsv1e{nc&<-S9I*IL(S{U9>woZb{MXYJ^>k>cDq{0-Ae0Fa=@ubT3V#&MFWOeN9 zn#{S^_ZePghESRoR<_LG3<ll{t_Z4k!KE-_?{g2=J8#*AnY==KcHQG!oc{XLw`R95 z?MXyzIkq0e4~1-8*d3v_cZcmCGR8(bOa3ZLY^!?ZZ^EQa{%cgo)Qpak<pmuDOwr<_ zi~BwsU(nd%{VVF@vm2MUn|^!a73y7?0^y@LrG_DYC|A&A&cP~l#>e;Ng*se{&-$O> z!I|*W))#u?9-P51w4&y-j{fsVZ~G)I0%;+Yi}ZG15YAYxT#js|tKxUzg6lw|J2Y$j z^$9U%v&7t1Vx!sAXi}C{(#suoqpiRo2*JAyWSKXa&@54jFarmb^f+z36k68S2T%UF zXkpcO%h0Z?nAIfnUEe?$a{y?0pveQ~zFga70kh7de#53*t)DjEnRoYFk1j~*r}^WL zgD}DM4)#LZ!M(!lF~fpC`b(D+06~)N9&O1KqIC7tyrZQAI%UFYI^~0F!@rIGT*YTy z$>8;h2#oI4Cg?yG{zfYiN4dvN=|8&;Yd_+7W~g{u$K%x{<pY7ApxNe}Hpe}CKdwL> z4If6;dYrs`r8bMg(S?B~{-m+Sg9?^68-EG!feX}I+();)BA?pI)a1|T7)n6@iq#HZ zao?T-T8Uq)#q3zWk@PlRPG#Y-OWWyCw_S}i|JFlqsV0PjnD6@D8Cq9orf*Hdxn;Xr zSJd(X(ocMza_N4Ow{ZQY(X$rW8@~o}Oc!(3ut%TA40WHST{k&->0H=~a?+b$BT7%q zeO0sU%n`M@MhN4xPhQUqM&GX&#MR!TNSGb~%LiiA3c5`O%1^e8XnNkc_%|Pc)8Yj= z22x(}o;C_*>UzQ&_<vM$b>DV{Oc}iaYBP;AA$D!-M|S4nLr;!<yL=Szt-*u|9dJ0K zH-d|;1y_nB4lKOkIOgcy1IwO0D)`$k=`W14hzoyyJUxDUa_-~FrGx!+RUAjs)Z`ic z=SIzo9ZBcZHYn>swOPgiH>Ws_+G1Wg&^_HlD>Ju7EG}dQ-u|1T6ZjjSZztiKa!<Dj zRr^-Azq#hPU1REp&Fj;n1G)72n0cvC_q{g~zX*}^&vDV53o%0{Z<WDh@BQp}EC(fy zS=+$67kSqe(-RWPCP|-H5FcH%Lm{G6Wm_rvvfR8>K5Bq;m3vDs03KOZ`&J&>lC~IE zjTM$dpHHu394$+>T9EJsQyq-SO0ZCkxFIdoxim^jHQGruO1lam);)YNE`O4hKdxsS zBsUz5m49xTX<}ng;&KxGvG{54J8X~Mw-u=d2S15!RCYKX%nls%S0avxkIC{+3cE&> z;n(agx;W&e+XTFDD<s<)M{H@^AE2&by3g^*L_z6bfTmIRz5~${g_mI`v~5itT}vj4 z>TOQw9`1HL(lJqdE9Jzt6Q=u*O;40`4xZ3E+r8iC$3*FUSRf_U)X7hJvTVdA(4e^6 zDbRSb{Ao&{;S~`Y_sC?$b0@Zb`?V*^rz0=QZM8EQ=;oa9o2)RWYMCh)9f(#MME;jj zZ#5wY0xFv@cmMzZ+t2_U_zuy80w^H>LBXhWZeKD=QrBy=xq2WSRCBC!XsH>>lHD2d zYP6+xB#&&JskpDT?m?mUp+>I<tydnEQv4rQ?rXa$+8t?W0(A2K-yN;j;sAK2uJ^<C zYm@b~TE|O{w;P{bcW(=M{qXkn=eOtsnOpXEG`(mGnr!rb)N$iwCu9EMrTv{ZU-!hU zeSH0>^VZw@OfjsIlW27`z?R(V^SG;JeuSg8zsjk*b@5Tz&Qot5cegD)<yvPcIp1mj zFxh|>Y8Tu&`*9z5dKujCrxQ|k#dW>OF+=vhM6wb$p@7MM^CfEN$1a}L5t^n=Hc2_X zci!!4mwQ8Pu>MK4#3XJA5r7X_Jh|=0_4`@gwP&UeH;6SG?4FQkHA%id{`9h*WX7;j zwW8G%2&2eq7(($$#7&&7qS^x#vbER&zf{X+XZ_36Z(E`UlYr4(zRBu$hGyf%i+5Ft zA1*q{mls^Ie`9419(|WnB4xsf5nE->=VeP(tFf%0!3+5gn%5QzoQyv#6w>T;7K_}D z1TPl52VPq&@rwSiSV~XRd0!S#68yfrK!Y6^EU&o!0H!dy_}c0av+MmyMbTQ;!!97| zBH3S^6cm2=)n+*o7!0Oi)FzCUwx4=MslpTFG4e>IE;5M7fQsr)>P-L-9#b9krm`er z*s=;B7tj#$Ho~s@<4?*fLIO`K6<wzuRP=>h4?{;-r=X0&uLmh|9*QO$V~tXA0A<eK zYEtQfV$IkArgqI~zw;b10u#%Fim`xgZr1Wq7sZQ@^>|j1i?9GnhWraeWrkh3+T%F; z=)d~_a@z_ICKI~y|5iu1U7uG5K>Ka0gQTOOt3$FUn^ud3QHum%C^S@NH)_+5v!hcn zCEN0cY@Il;NG0V`^-Fi|w4Hc`8{dOl)u)Xrio>$4%*E(W#~ri`Q?tcxZ!_?@JJXt} z29;6;DZA<mBTe-a%{i1uWc4w<+o-6vJ^xbHFq-7mfrB%cOMc)s9Ls=X)(3Dpsmiy6 z^Sd4$Tw26z1?q5s*%pN;oYmFr2uD4YTmF2FJBD>*X3qeAh8E%r)Y*PX@qjq6W0%|5 zqR?CoG+kVHvd=>L1CE(<gexE8eRIK;VD)!hY|J1^CIPQir!JYjfX?4(225}#pMHa` zP7=%>T0f;Jh+m2nH^Z)q0j2`V{XM|ox@sEL*FSQ7q#xkofi&{^!#Bv+lwsKpDD%&k zpu4Uc)O=t_uVkE%HW-=+G^9Sa>IA=jnJ1Su3@vLeg9l7tTVCy)wRG&<9sJop77hb6 zmyh5NjBc0JS8y;#NQgvPP(XCkYg78zhH;i);b<O?38t`8SOMzu$327*zByiiKt`+_ zX<c+wd^(k;Doa9%`68I-m!Wt<bvku0zn{IV8Z}OJkVRTye5ce>?VLu9tY%PdI2$>D z4g*LKI6${VLtUWYF?#ZsIMx;>sm8s|GIv77CXA?(YT1iq9yQNbxdR~ga>MZ{?gSNv zdAbq6$kA6F<Uk*gZFs&p;iv`W3J1ELC{E3&RErB0V?H;?&vOPL;@-<*GL^KX<aW9> zfT|&1j=*yF*vP+mdCBtQ9PTI`D)l?2PWvyC$!Cdj$TRAOesgF$y#@Ii7*pr|G#Cuf z3*T@Y%(h6}3oo0H|IJhYw)u{_qw3-ZWF7Ww>k}gMX%N7hSxt4MB}s#B2+QUrGpOm~ z3Q83Da_cyiuElYjQB_%_ELqjeJz!D&x6EF+V%atBIEhcWQ0zHsrqb$~7t^M)gu1wu zUhm`*)lb^TNs%38+8WOIf+AiSE<hk=G(#3~d_ApCC*fJyH4!pThQ5JacM`VEOK+8A z8!CC^4?3q@@Vc?!96iT5!OOwdf+u$&TC)-Ypy=uqsN6CG>A<MQa%5pDh=Np$C>G{e z%z#yDw_8OJ5qOEJcSri&4R;+>*q%CQYATZtHTENyGX32eUGV+*fWle<VvkLD+D>{O z_H386GM}He-J}ogjY`7tIS4)B3Jd4WfNuNao7+FDj*9{v)aYydES}#Dbjz^mkLt&! zfZ&QaB=t3-)jciLHD7GJj^^I?EVax<BIRPbI-86%Zf0SF$zn32<TO)GANCwiO=?t- zvVEC_^%Nv2Jh60t+pjJ^2(m4JW-Eii6&9NHc?sc%Nj5p6GAG7UGaMgEhspLqtKS}M zH?d_$)hZQJlT^3mBg|;N*q~*xE$e(FYZ(G~G<+d@y-c;$Rzdd#q?`7BJYGEbj#aE^ zpQ2%fgOxfLmD-@py7Ex~*?kKi5WO^1b8^Mu-Dvd1rvR656s(qr=Y5ghAS2AyRq*k& z@KdKbaEDM8A)Z4XkS-D(4Fld)?>U0r4r|>V6*WQrC2Qb8Y<&>0A}5bcW2@r|9C7>A zCEpZ&+u!&JJQWb8a+T?Auuz@4lP3mv3HlY6$<GZhb`#DslJHZUK;RYRf;X*SO?@se zQDFL1eltaz)Q5I9bR@IQQ5sc`@a(#?S!>{SzyQM3(XuIDr@gjO+QupAP@loc!T0EW z;cOMv8nx`iwoGu+ECK2(T_qa^i;LU?LbFm(L0zW4pZ>l3rD7||)`zz)g@^|zKX5X% z-N^4lMkK!^UK{D#Z53QV@+4PjbGwbK2>SuLQg4|(z8N6wV6emkmCj`$lRQ7O<ni7@ zS(yA+z<P&vAMt!c`rgm+|D`T?k}Jz%7Q;#oJhj`9BPg@AfffIBL;vmT4myDQ+;Uog zpVGXDc3q^MJ@C<5ZjCl*ezYaktleZGs!UAk{VBTMDDU!LoRN%p%bV>{R=85Z_T807 zBGcBRRanjPK+?+$lRH+GSBvVYxd}31vI#ee7(*6G;>4#=x~wC~!Qf-~y(8*#xM*3_ z=<3$AweAgaGOA6QaS@^GP$O{?Wp_8&=VzfD3|}hCwisr;PM)bDHgk;u*&U@}<Xxcy z@6+42SmlUnRpci#!#l>B*^Z&rj{$9c`IW6<KqcV`K(m^G@R3HnU0=Mq#Dv?&sAvAQ z-un(T3#^*-L&MmjmXEdt0REHt^`8&<b#tQCpngpJpr}K^gkR^yMUoLd6jU(hc<nSY zviX>DDZ*F)+m`Nm!w!*5MNpgJkEv)kKA|%$L97p+m4?L<FFY~^H`T#){yE2=GQn4D zzowtS`C>EcaQq{-$7tx{6;v*FzaJB^c{XsN1TnJ~2pvCqeK90Zns(h59!kdsF|k6v z=RaC1SsOey5?`PJzNFcTg}Xyr(21S+r@-#N?`2ZzZR=L3<pUS65X>=B=vp(zorbwW zMh7qgwT6)=HNmm7pfP}0utR$B5o)Co7Rj(00j3tf35E33quO9EfX?HeNkpFCp$X<c zr;}RtG4wG*op=T*R&pFyw`>ss05vOE$PjX4C>_7-70d+p7-roGVBMHTo(5qxJVXf@ zlS4^eDm~du^8)x-PzCpdOZXcYbg2dVi-%pOB2G3(0er-jqtO5b+13Sykip<#ILZMD z(TEo9zA`D;Xu+O=<>RFd;E~Dw&}vPw4)jl$Y!`*_gc3&@PtBto>glv9reKAoeu-@G zm8=)VFza<!&iR!Poh6t%A3FkIA_457Wuvn{&kb}~J(@lW)ra4Q0lr*=HO^sfK7Ndh zyG}+vn?blQcp)FekDXxmX&@|x9M}QI(Vm54wdpxQ6qFYe-cH99ap9LZZt@<HLL~4O zg%HyZ-x!CNYk`wz!HUCjlVnhO<iu45ychuRfu3S>UhRus+ci&m@(@%oK4FG)nt2>J ze6ogzxkJTfF|hrpq_Y4Jj|P~{N7b~z_;35=3*cADh|y7;pAPtfA*XX2`-+d<$3<PC zVM9d=#f%)pxSuEIcmOpFVHx%+C?c=}K3xhc0kL<O*Z?s5eP>bE5#$8`h!K=}0l;~3 zvDmm4s;?}imXH@LSLtqB%=8DEgJQL_cA`_h6bA<L;Zy-kN3)_Wi214%5z4eJ;o_5% zaU$B(AK}@^Jx5T?W@KkKvV1v2OeGK558Y!3Zk@zl<fo355)IfgVkLwoCajH)>7X1( z&v`Xu<OEZYuS~#W<dhn@ioVo691hHV5I4)i#tSfqHVlP=!){l=&THT~5ZT=gUgQ#b z1liD43u#Myn2F32MwG6u=#OIExtUE2pF7$h@?kubWoy%w0|3Qtf^e#1SVHk7%szM? z6@8J6e!<6;3$PuU20s~u80nG|1EByFbsG(MXM*wNNaQ$-%DbpGj!&wWiD1HAt+B@_ z6|c$=OOn>q5YU(m2CSr4n#N!45b>{3c{EIs4xyQhKD$D|9zG>^=n6`>ijp~8-~phd z=8%YLkKB`>ZYEJ|8sEH=9;%Xv&c|Pj#u?Hu*XbBxdo9kxGwNadOc^((kt3#`<sKDy z$1uyCivD*FT}C6sQwee*`q?4i7TY8!(M_r^LJWc)cu@@P!&IFoezPYK(rY4!u@5=8 zUv#t~XcS64IiAjSE~_6~j76*}>s+mELtXEfg`Z|1jQH41S~iD+tDs`ox)-G)&moBj zdUKVuCCZc8G@yfC<y(9cSSVDZ)4%7Q>%;zH!Xf}dNi#aA`2>CjQ9FWkhvmL3<5B?_ zE+!1Inm+R!9>7EFqhi-6m|7;*jZ5HAao<byw+Pp+LRsG708sRh_@dcF#l;vkoyv8T z=_TXv9hhQ4?93#S>RxX#fT(@J={yVKyWokkw5;aVZ#=g5H2M-P;mZug=LEJT1=+WV zRBj|bc9ggV1DYv>fo8mSmvnS(_CtQ^00MYG!5?i#MbOZtWQ5Ifdw@=%#_mF8Y_8@m zaK-_7nu^F}!b|wrW(wvzA9a_HYyhnWLi8PAKo}Xkt#e({7a7e7NhTM2q9ts1$GoKC z&;FJ=vz55X!EN%8Cn?yY6l@fxs3N0l@nh`v>73DD>B*)M<dI@`F6urPdy_^;rV(;E z=x$E_uV0jI1`6t%RB;Y<O6W;MHgIa2gOTId+l;fgYEjy^2RC=m2eONF`@*-Mxgz1_ zOD^`pse1tPeC|s`Bo`*rlhbszMdwpGGCweY3#SIr5z&6T7sIauz{wSCKZyO#MSo{v z{Q%6Nio4<i#upjrS6INWu}QL}?M^wkeKd8lxHuOLJmKPhZi2JCyc52O<(MFV30tAn z{$S_Ci@5k~L?l=UG@nR*k@I2kpd({YCX4IGg?}A_J2s;L0cw>(IEciqH)ET~=mm}& z(fS;;1r=y~N1oNM_rq`W4!FCrCR|Zwid#de1i$z<P4aNWo}Oc!sMB<I)$<la^<X4$ z%3$T7xe%UmGJ15T^W025>L{7H4xrZsm?|FrHXqF<pOcEbCZ~`3f}n|oBLmIA8;?wC zMr9^}`*9b*XthQ$1bl@7&wYtJ#=M;v(;_++yevyeU~?menO7bRR%WE$XCuDTu$4SQ z8JFNqYa>b0m@A0m$B2m!s<z^YH?w6-9%JK|z<wU~8xww#hRNieo!J$L!qoL+t?z8a zoqkd4X`IE%4jgz~d-9LyJ%ZqpF}+mrI;N=YbL$UA|0);e%|OM1_w;-*zXW&V^()7? zW}7P(|5<1Da_}7t_!Ukj&<uBGbJ?CedoQNG;d%6GPhITb3)2Wcy33j<86j*&Rjm-} zK<o<&a)RfN8Su~2lsHenLu6$qgpasqJp9J&DPbVYX0SN(!G(|#dt4#q1@d2%MRF{d zqHuHJNBcqtJd20OqKm|cs9zL9E`X^Av48m}hwm)J<Z%`mEC>N(n8*u^Cy45P>F^#{ zN2lBB9o_Kz^$no)2<{sbdteU-s_(D*`jJ+AP7s~vP8-x*g2y$VxN)Zz8XgY_U?p5s z?h5vu2JROh&0Rs=<`L@oDAD*<Vp0j0|75laq;1BA#(@K9z_YwLZuf}f+`~yGdiz7- zQ?A(y^0>C;fKd~;HKnJBi^`;-S9r){Jf!=lv7*z@;6ju;3<pq|_IBCzDc8HYU*r__ zpxVi8FUW1*o3U;Jf++v;1LhEUau_=4CN>8P7VvT79LZJD0N^3OD?^8;L45_%`f(%E zR2?(d*CM~K&)iTN;~^u8-Hzi^=aekw)KzdIA8ysdR*VYnJ`>ImJxw>_^xdApL!Tl3 zT>YW}&dkFAuQ!-#pCK$D>4m<!9X-n>#B&MjJkg~N)iVedmna9w#BD!IFWBCx!8IfL zBF=*}lsK@q8@xukk$#$JT{VtWI*ncJ%qySW<R)TUc26!|&>6>VC^X(Z-SmrwIZ7|T z+Kgrz1v<ZcwDjKV7;XM*<;A6)FU|<NbD(b!QB3;?I=UZ?-V`LRQ3)*owj97dS;1@( z>lYT-i9zlqe5ppQ=76hySM>;^bo3|_Cvwg~5$$*X5_j%2+;0fJX*)xLEJ@B~NQB4z zr(OBA7Jp+aVUmI`2D|(|ppH@DsM$w~3d;fSmoSj!#L=A5m*s8(R2Cn-$srU`7V0U4 z-(0lFs2D&Y6!Hm|cT*zNkS+8Gpb9*X2a;*Xj`)|@mMUI6*pHWN<$%rHgz>|sJ^nEy zef*!JMBR^xxu&0VLh>R+c1?P`BNY+HZ`Z;X#x<w!ivumWFiPx%MPYg{FI{=>^}kr4 zgG`tOzy4xi`h~Qw>%&Mc<3npaB_iM>nE&!DWzpw6vgZbP=1-^?5nH%&PR2;$n;;+U zVvh-bNQPi<?<dZ#e9Sc+xtIp0cVpTZ=qF>y|KbK`FTEBs12y*`8(who;=q&5=x<y? z5eL6U#nkZ#%^>yzhmZ$i>zNG^U-bOwnEN#C3;Z^s3$o}uDVeg4TYWhuKaqn5{%ZzL z@E2wCclB|7k6<Occv$Q$q9bgzhl9V*Sz24i25@1aoYjKug`bTI8%zuR4z{*se$h<d zGp>WkWgv>kgiY$Z(x#YR5W7qvlu<CvG~9$Dg+@SlGmx=&pBH>YvhRb#ei!xLZ%7KO z4*@H|(Dy+%07n^@&@~Eye9!4{iti~6ao=2!L4U;H1W2-c^SFdB)-wPFb7Jik0Ab1j zz-$o_#wC;++rs8fSJ<Xv`i+5EuLWy6Cj~>)9tqe)sz4ElGrwBCQ|rlSo`cQMr2RgH zyDm*1!~JcZR%pc+uv^4_xh&IaY;%-sE8IS~UUj}?kt%<7S=!=m>!4-V5+2wA`x)@P z5h0pbsG=vX&5slME$y7ex1=^#xYfQ|CTbl1bdv(Cp(Z{dxFVOe{ZExg(WPM%@qoLO zje8b(ThfyXNLO6Oi}v8hqzC12UWtYV;2^P3R`9rFQuKvrxfAKE@S;I@SmJXVoT{91 z<tDqJl;CPnQ5)t{Gm>}6z$^7%xqqko|Lu;Bk5ol%ueuQffL81gagW+Jm-_d2WHt0U zqi%bT>5)i42+%?NJms#lD{p#3jGV0yj>;ma#Ir-vD*RD?c9-`995JTj`Eft2!TW}w z4r7Cg<?Yo6B5RDRC%8FvxnruM1&-SJC#&{XRA&^$m+Y&niuWT9EA3d19aB!k{NL(G z-BrhY#YFV10yaZ*G&0P@09Escwz5t*7>^{<Kc{lVvep~!T_p|R9#^+Q$TxqlKhU}u zDy|wNpCs=(SmH|UtHBxuwgnj*4pJM8@(xI<<;-j-W(e~vjzFn6-9fUon*IW3puodD z7G`%e^jKQad7fNaVS?X>d1WBZaOdH}M^6}C+w-_h3}~v*{Zeb6G7)H*w*aBboc_GO z#o%yf_bnaQby1Yv&~tl;M_>#@AY*&AeNY<cm>E5oyAk6?ONpv|QY*P6NWN{s=YN^C z+a#aMvL7p3k@cKuCKbB;YI#oz<FPb}2_IjmmM%G+=%6PPlp=2ACGk~IKqx&^JVhMB zD-Hm-Hl+CI;9;rX6)zC82T(~np9PdRE~z=98Z~)+KEry5>PiSu<dg9CS*`baOPy<s z;-<!Hs{iDubqe3zxxxC-#~>r@K^yHHi=t(iP~5itar#i4O?W_2te5GD%OM9`(v@B1 zH?_2Ze=4%Roo~~AH<$$4qQJaLkq4tzFL-}Y-dFG=PekfPTDU8=92|4AL@=G|{{3#K zI>FWXmRWO89c7+W;1NLFe>B_%t>?5>SeKFgP7*a?8%5$5QJmaDG}N!vNgVp-izo_y zU!7VUWAmX_I-zb(y(H0Z&PH%(KJZ@b(q7lD>%BSThGa=ca!B580Ak}?J*Chf;~V{8 zq@}uIZvV4_OA?ch`QlE>fKO@?1d-yN0Ww`f`;u^zM~=$4Y;fU*Whq!=K~kuL6+$<t zTK(2_lvPYJXxgqS`HMHC-&&nlF_kP-y6B#=Y8alG=$<Uu?4Ew@^QyUY2gf1UVUVW% z<B|zbgMn51d<S?*lI`RWrSaq~Q&dzNAPx{J(n?S@c+bbkof>Od<%5=-*wCi!&cT=a z{z&BI&E%24aR=q(UANo1vkB?%l4TpLigL9XSmR}A_f3toy_-)BiKI+f8x}lfFjcyp zpKjsaCo<C{OWziSe;nqr6PWX)-WWJAv#KT|S{*%`gQ^W%6`92ig`vhT(#imKdsiP@ zDPPvAM5D-`^yqXg2Y2Y^x=bEy*eO#CI8I3iJ<0yqqwa9vh;N1+gdPm=lRC|7hy``k zM}phI&$P$}O9(G_T<Dl);RMN~iWevuhQrOGSZLRkTIKo}gx09#gZ&+omkw@1t^5v? zp2%H+`*x`wI`3iun7`A1Y;CU*o<Wkefr!IcViF>wn&V?joa&r|?SYd;*lLzb)J&3e z&?J$8PQ}I3GVENVaF%2CoRqqK+lMW4<7k$$e@AV%MOa!z_D){iWt1r`uOg+KP`A(K zLH!^176Tt{aDd5Obv>{(=bY1nE$&@Vi9xt?ZR|q!gKYvxClzi$4x`1`uxn87Qe63` zq||Sx>NJ{+#>U-{USg&tGxRg#xz3U^oQ2uhG`D+Z2T#LXB*++1l?~`Ox9Og<&*T@K zPY6gD<&Ow|{hHOyi?vZOja1wrO}ye!r;0J;LI4h9I6~z_PNX0S*X1a2=CFE=MCbsy zh?3>_-Sr~Zee2fcRh;)qlF~D--HaCm>z=J9a|?KQT&u@x>2D2szm<bhf-cF5Goofd zX5;L*q_&s^KY&&lP`+P%my3&ni#Zr4?uIoTe}{?lvfXOM;%sHQVf|=V?U!eqo=FWI z95%;`KsEHc+uzA-((JYari3#QVlwx<5qs$QSy2Kji9YucEt-*!`2Fo>%EbMyk9Q^! z>3QUr8V=%CUZgAU2PBF%Z)z85yb+hlP*_<-<-+^7K7vq*gElDAuaQ)XUU-Q8{-erW zLOwLd3ZFNtO9t%fwe!J9$&OLPj-YD%t`C0lQ)MH`BQ4qS*-)uvYPzQE9Kmgy+G(S- z$jU+k{!X;b7<B@<-N2GlI22LLb)T-&g%BQHnu|K=U@I2_2Q)r^2wMF1R<UEnZYq31 zO$5q0^I10U@Up-BwmVH*+vl=F2K{92-$*YP+7b*X{>lv-BW7RCKZ)kHWLAu$61yh7 zW?QuO$4yjD@aaq8dRwzzx@&Bm4aiDs@{`H}Ql&FR3mdlEeLLxK;QO?<e=aP<-uM9w z{SAA{SxoZu!?dlfEjh8g{?1npM!G*Bx;|aMNu4vFn!j(kd~jk>Jjerc>C{z%@HE*Z z^F-?cDIJRUytiG!{+S&`YBkHTsh_3!;*j=`Em#A|WT95ALfs9XJeNrEM&-i*W8cgt zPPLK|4~I3rK?1!$`zi9d=}w<~@d?>Aa<#Iy>ZP4$YI-ISyH-%`#`d7s=YpqNTg}c^ z<`3oJ!erv|tuK*?^8R5CIg#{az}b~JO{>$^KvHLv*_^|n?_@7QY&TmiGs>UVcJ6u_ zs}~*C5x8P4S?Qj>*Fy1Ze-90*M6}&pA6Ht3k{4ms!xU23gOgqn@;4h&RCV>Uv|IYr z7bccnsyghF*p}zte(SjMcETy(YMj(16FUp9IZS+4#@8u9T2JEET;Bj;jnaIBz0+@f zoWbMyC#m)cSWiGdFKVCM%DAghnkBxmhmz2rcF|ZnfAg@m74iCLiS_DMOAGgRqkww~ zf93sho<re$eK1}=%$5_nkStYJHe%>kMTq{{q4c^88Ny2u**q9rgdIiesBEhH{(FdQ z1#(P59$&&xN1Bp+CuOJdsjj-X7}$SmhDowp3K--orhBXBl5KyZghbPVQ8u-^L~X0` z5#Ehpei{<8^PB<_LPR)_sbc1-3GB49%TV`2dPu{5H+}t2P^P<}zFLs>;X>NOQ(6h+ zv{QTnP?q)nLAuDXq(7l-vH{;u7P}=WX2G~2DlOZopth~Bg~s%IC*=F8m!WF&U9L=| zQ^VdPD;1#*d9n0PcR_0SGU827%6WEL&`kP*N_ql6#Rlx{+uiS=DB+`k(d6`R&Rsvx zgk6CGj4njpsMY&$Nl#{}>1Jv$=C07RV(ot@x)*;Y`~MH%J2;<@o8xR4bDm@4>$Ewa z=a3|1j&r<`gj745^D!aS9FtT|6-C+R9GX(;cq7&7R!J&J{Pz0`uI+j}cJ2DS53eVf zq~<K~e5r2VLi`FsEHF$cutzweUL=oCE14D*6dRL?j8~Fl$;%GDorTeZBBzP8FoD0f zAQXjh^lF<xd^Dgq+Z}8aIW*Ir$YLatG<;e#G616Zf{Wv^F8{*C_Ptua^)nByGi7SK z`j4^q4aIM^O21hK`Sj4xu8e}I!r!R2@C>>D<jG&6mmFr~5k=yL8PNjDNk!!Ja$$5Q zecwlnF+d(m*0^<2#Xc#8W`*Z`<bk~-O03|*oGgkvvxMQyOceap18%jlq)te<!4Zn5 z;E+!)67zC8wj`>zN+YIQO!1?QRWw)-7z!Yg6$U3N07^M4iqFyF7S2VrDi?w<)Kod) zh)#Meiy~l`{GHYCBq6_CAw1kt7AKsK5}axn!OMki_QC{by2siSN1bj8r?EkR`)%db zLL>(wH8@<g+4IuxV<PEsy;jkT%#6{*L1zl9fy4#5VNd{)Xiacymqmxeb4BE+DZsh6 z0!7B<-QPEa@7^hU(kbQ!Xg-P(4(y>tjnbp!gz-G#uzJS9P9aqd#C{O5jo4ZE#z-^^ zFB*lRhp8|=Og%USF1|&eot9LXMl}%+cg>_qMEf)_eD3{T78O8$9b!}6HQ-!1@5dRP zt+r+5OEo|owv|`5#OwqWE0s)HnJ<GZ1}Sqo9R)1mBfP@Yptd}WSy)$LSfyyNGdMg< zu*OgrF)Ae3<Tzbl=!+?I^;FNv_Yc1-3Lr{G{CR+5`Cr+V@b0!t+g3Qmqc?ZnYvnW2 z2d70sqy&lbgPvlJgA^k?Efg&rJSb=3sR!8c{S^Yb`JLH5d_I4TxwJ$n_XN9Sg3K{s zM}ZI+Es_u|9K6ikY+%?d=;2lwiS>oCqr$$U^e~dh{!pz*61vcL$~I)`s?6&H*2Z%E zylS@X_;+uSLt&LvR2@~Z_%2b%8*}p>8h0dD$YQ}<2*C_=uCW}Xc#C(qPfOd7oXWv- zwoDgV#<+}1v1N>!JxJ-zQkVZJp~$2blO~1_i=9v}iq8<v&kzZ__8=24vfM3t+PN@$ znI63%8o)0sXbr|#GAgFPNBU*@2Lmg->N0cfrygj3-4gR(FHub!jn6HP>?Xs6Nrzc< zw?VnrV(4GA#-bQ9d{kY02?5BcS73pB&d==sMp@(30B}8Hrl|L*VAO?luAUL+$?(aj zNv#(RW(kL15XX1Y^GApBmcjV#LWw!yeZTF(LzV7_jY4f>MJcL65f3QaQ=-T_T2n@c zuP_6X3*-cJR**9#Xgk!0MK@V4vncRTB;0qWHfn5G<Aq5Jy4|&vGq*`f<}4jKB@@81 zHX!$ZK9!>6v!axDePMoKiS<Q+qr#^Ti(~_YLzij9!9oItetcOpU|aM|^!c)pe$(Zf z3hk123?#5fiD_0-GfOlHE<zJD!R-g3(i#zRtwELGloiZ<+nHaBAQR^%L72Vb-RlS9 z1|B2MSti4+_@<Y;$Ni=RQ@sqo+;G8+M<labI))y;Jd!5(Q{vGxi4FMzb#H?aj6M=D zNI#h?ti2v~lWrL=OtP!j-|t+aI(U|}){Bgj>Y}3U0GPsxWs%gsOruv}SO>9FDynXD zs4a^A*XyoRQb0KvZSKs55P|T~^NIlRkxY<YZhc{(=7uu$H<+XV2&eGrzXP??mOAqA z4AZ-^$%C@p@voCvq68I@!Bt^jPg-7BVb+F_*9*_rk*2{#qvP9GDv?al27$JxAO@@c zQB-KTBxKte;t^Js5<YGVr|z*a_A&R=@Iiu$YQLr4MuAjwy(y$uKagVKgPI(I;P>_K z0k+Vojfp?Jx%^HMV7cw-9zi{aZW1kg%T}07C_K51mnj$E2hW{6UF0K6Yq3mnr!j>j zG{OpP%@E#4PsCI#wIA#gI@Kv`%)hs=<eNQxqnrpoS$ve1p|Us?Ao@s}nM7`vqC8?z z+Sgozm-G`*m%^QGUV=$8F0Xy@UCDe#z5sV!7QMh16*T*k!bBCjR;^)XrW+JH(#v({ zC`tzX=Z4s%t?;C3EP&@6WLnH_E)*<{d1I)#8-@uxOox@l-1q><7t&`npn3+#zLC&+ zP@?d;FnY%$fgh|kY#h%LI>mC#i4~3<6bC{?q}mIKaFNp(pVQl-0aKnwzM!!^<)-43 zAKKp`b(tFxQ5DMy)}|gg6AHCHOb--&u2ER^G4uP$01G_mguPmcC)iEwnn9)zq-kXz zxC)X@l7^rtMOn|Hszkk*BXRW%4^&e^hN2fQVL$$Mo}6fAr$`F=K(@*UqGx|Ewy^K) zP0{xsP82ueJcasrZ50^WM?(p^3*+P$;k9=c&R!Eqa}!HhDs<UpIs_LI`L493#2}aq zwX7zPCz{8j93G_vEeQp(gseeEfbUvd<zh?p(S?|E3P946%{R4hra}*S568Uxnf@~G zML{LaCW!%V9!X1QgiS5K*If2p63qvQy1EJ{uF>+Bg|h1>n$kyoc-M4r%#G6O2_UJK zEc`ko>Yoh}n&)%{$@jta(8m`=^W>-pN#G-$A^Z8YeLBUq7^)hag75_G?;00L*bZSc zJ0PfDhc5<s%Y@S$;b3OBAYCC+%z0m#aoBG)omEI+(*FgE{<9<+#S=OvR~Vd|DiV@* zewA{~S*#Z&G`eN*m1o`R9A%xO-Qi=K4HpFf99udIAL%iVd8W1eFZK#a@lb|PUT2|$ zWt$}+B^O1X?2+p+gullBSJ5eELjq&!2_=;S7WVfaFN5^(7a-9f{bg!_Gb4$AA$5Ba z`$&`^CnBRJ9NsQ+ipU5nUr>3+2nIMlx-J?ecUJ5j6?J`m^UGEH+^>4S+kX9I2D^&w zb;_CyeQI3!ls(7@cV`Y(CMFG*oY9s@B3Y&ne%P)*DAy%q%Pib?V^ua2srr%94^y42 z>O<O6sa9~RkOG{-qn3vW<t?S;Z9MZIb*1>4rD@aiG8l<)Oc<;1EUXm#K{y-b{IqPn zF-I<yH#LCV#Js)rHDBn+G9!CKY)V(O!=0Id5w$9zKlWEmf{SJlrSf@H5r#zBO@rgk zV%FDX?)SVfTIle@(=17a2Xm$9kRglp#TInY>+3+nW$ItuA{(*)$>x<L{b}*%SKod~ z%f&DY_;mVIdtPVJe^IjuaQfZRZvtS|<31zBQ^q$#L_!$gixvWqWGY6td?yW@iL{X7 z=5yUDrlO=;A<@I<uMBpIQUYZU-&Z+eR_sq=$X*lO&n89D>J9t>q>b+66NZzIAefl# ze>zwqpSPHaVUT%oy~Oi$e-=m{D`t{Qv+<Cy;eQSt23hrdPrhSC+ZOh1VuTZA=a=0` z15#KDJx@jCA0?5sQI31SiEOyX<)^f~<-#mXu2rS`u?=~xp%VqS4SwFMj$Nil^1~P3 zjk%46W=CIc*k#I&d~#5?1E3Pa^~C}(^v8P4M#ISn=PvoRLR3Xohl;Rjt1JbjW%`ol z?F`E8sjYomR*n`Qe;3l$>5WvOAUesq@R2spb5VR6yP594eKu}+)GSRTeyR}hhJk8h zwB0WOWM*e=h-9b~GPB*YoC{B9&_$>7_phJpk79l}IVJ45EY0~`n88y$xltHkb-3go zp{V*o<rs-!ZDtIB6#H599!Qw5TzDt46kPNzp^`(}UU3t=<O~RBf4t?45O+40u(iXY z;1sn%P-`|8qAPZV;PU&U!s(#6S3qXmrd|Al%YH{3y?1Uooa_it(anFNmv!}A5%f;V z@@Vthv(s-Jlm4qN!#%0c{2u_Y_c!?CCUUmkBJojo(s#Z2Cc6`x>mQF@ZasfdVWe%W zU0xT^AIi?klYrc)AB>PWnJ4k&VR!iLdEIekKzktiJdjma`otdJZan?_;FWU_3-oVR zL%-W>)A_u+#vDppkh<A{KLdF~MNh5vBLOhYnsdhLCWm%v4O~2v&fg<&Z&^REs!+e3 zu58xwU1a{HEun4wg3%!v&C9_<dkue*|JZzab?3yh>_y^3Z9pDDp=_x1qW#%FIaf+A zTMYS}vFM)`I%Ek6dGq4-<8Jqgb1{i8LdqLI6sI9`%a_GHTC*fC{XD{W{0ijMgET&5 z+?;vC;-3QR=~yqbS-2(7{IPD0tWn2oji2R9e$WG)bfAuu-WGsYM*KmfEF`HdaK$mZ zl`b+)Z6Vwuv;FPwE!jpl$27~VU*xv>nT&TT_!#x}$NHJfiH(++y?*<s5@R^6XlGUY zq1v%_R(n$Wes_$d>YfS1UHw=kP|I)s7!xa^mDip*p?WB!ngIpY8EE+C74;T*pP!;i zSpt|X(w4Knu`}j7#F{yKz#vZ6WfA{)7PXaOxnKby#D!Zeuxh5!pDK0yoQB5wr1jV9 zYZL$|lRU$&D_?GvJNz6SDEIYxvH0mwUzgfrTf+-ADd}%&+r<G7m^Eh|i6MPVB!H(7 z5*0UV?h$#6NT@kgF!sz{ov58T0r^`51e`M$?tEl5P^w*FI%`!QVDWf2iO1R@aU>iT zQ-ec|x!GXAfd^79vPtS`G#S024IOEl4`JLQrzX~>thfBXcIM;CM+&|L+#LlOVb+Gn z9;QDYwwm{U3mh%BFCPF+>g``;ay}32Kly<?mDvX*-OR9S_LR1gV{^1a?Ej=Tq0L>2 zyzltBcu_uEfF*`!_*{vRMSGoj$G&gJ<{j6<ej%KmhAB#$1Bf7LJN++QS^Y<ytzH<p znqu?U$6ucMRefEdCCKU4>33x}%s%&<0a!};kM9Hc+Qm9&!}=DD!&1NfdnP8?Hh6%O z#uk3)B1Imn=iOOM)dCtKioNTs7*ZA&;H}Y)fKrRYmd}Y??*tB7;wkcdpM`|ch&|^4 zW_N>HF5vEP{x8;=xD}W8*H(*Ooql`D;pg*|OErfqhq}~_>z9KL`Y&dH0hTSVhNp}H zLeE6cMLwlZtXT}5izn<yg3y;#^tU6ps*m6r3!ndqF#9bG*vy27XXCU0VR(}Sed|-} z6zTWcLQhVcmmJ;#!R~KI+e0$N{7PGNcljR1m}Y|{R;$)9hVJx*ERiymmj3cCLgpCr zfWOcx(s|X-48Uu<F#9&*DlsB|o+SoQa!>e{8S1+OHYEaySur?}5)%OM$VHqv9_aOv zmD?Y?#DP3^o|yKnk`-1qRo$8rG4{oZyX|Ug?ckLhJlQ4rm8CFV=Ol`Tt%%ZyRcas! z8(Xc&CN+7g?GkBL0CaibYi@|$u&$nEk)e8vwn~q;2L`|@e<=t}Xah9(fC?48*J9;M zP{IK3X0d&rCUVhc3RrC*!**sU?sP%V!;BYraorxW?2^PY-{nlHIA#kpQRu;c(I<+c z!desu_;h>cX4yU~m*m!rar;}n(ur0&Cc~^r_fO{15%w*zJD8QC?abontys-YIOCPo zm4~M`j~#R>mZ;7MlDSX|4qXeLw$8>CB@GA36f-Bomq-sdRw<6?q?nT|<x5FJ27aj- zLboJhN6(GDRap#y1IkzI@<KWw;q`RY&r=f9ajhM~1iJUw@6s~_ZOGQLoE5XTB4Vor z0yPjVj=_$cmIEuF9UwTh8a}!5h!)yTG5jYR*jKiwYxrtOP%)FQFq&dRu13ph=}KHS z!|hk;9bI$bhXkp(MXX5GZQ#zwDJXeNy;bQz3j;PnBs=3>+Rw_3Q(^TL;rPxD0B^#| zRDQk>&sF`-Hvq5*WkuNngby=mW3?jwUx<K~^PF_@Uy)`8-n@DJ)U~u6bMbQ;ACWMy zvkm}%E2WegXLIEo5{4)Y+T|!+#nW^)K&BCQK3vOOtv)&2MsKtw*M$Lm&u4kn>xsOB z&R4n0DaT5LPn9T)u!K$es!D&%xF|`2NV#yIqKxpVzWOCM2iSOXaRg5F9pA%J4O@KN zH%8;XutIB?$V*|%L3ZTpLWdrSn&1#Hfb@782_uyFrM4)kJG$uCzI5GLNNn3z6g0nL zekxdCV&s!Iagq0aR67a=PkaBPqojlYRdW=D0ncUR=9($lQ(NoSG57d2^P>#=*1mH; zlB_X{WqFHW#koom^H069c+#o@0L?H5@VuaZdF%wo?~Zo~4vk~lhwfeQGLGO#h@|1< zH7~juKo-P{CITW1zsV|R3clqXnp9c_O=nR^M5P2FeM}5r4CFmK$})|d?MaEPZ&tB# z#KUV*QzNN`rJJvO0v89@O|5j_6^AuwJcFw{(by8cyDpl(<KAh!?*Ae`$c38qPC6`- z%d$t;Tul*8KHZ9n$wHIJCvw8bwVq<Xfg4KMwt54dJgpr$>2u`JeRE%pDw^7ED(@8D zt6&Gtu$%%z!N1+^t`fxQa2NCb9C6D{a?~ljepEMa-2Ni=@E=^>lOF(Q%PINNHwvv< zcb2L8+f_0ryPiLDShb$8Ebk4x;;PswCsLKwC!5l_HfMQQ<bZ20(=x(KskokgCPN%B zH2M*FbnB;CGhc6IgDiaUDp^A#QpKWjMII3Cl2yL)t{|JEFbx76+aySIBEhF*vhndE zXCdLdR>R`Hf4Yoj5r!!->K~RrV|@Fi2^*X%`+O0@Hm-tC^6;0OhcAEat)z?tN1;|9 zCvC=B*3ZR(05eOIau07yO&EY+XT!#|mwSav_kxOROKb)GU+dS6lb21)H*DqoNy40A zed%w_ZuXVmVoxzC{w)}WcRhDtsX5>iaoVognSDG_YIj<pYSW$%luReN=ydc>I9gPd zCtJnX)Kt1Vel`6oSV}o~t!u8*o}ieHUe!A&LUQd2{9w7X`mWA7`dy<By^-7IWP9VV zyCzvkO{!U>7*B=H&(V*8S#8e;=tw5z9s%U7>8X#V#@h3&vME&#bx+AS6DIYU?ekNA z-<)3H8t}N*L?KLww?k*BlP(vY{o2S?>&FGS#3sXOiCVc99uT53J>q(R=kgW>0)%o@ z$EeJ2<cP%zlc6!!l}Fj*qRl{rD(}hhcJfE@ed+yoT=Ow7G7Mz0b=IIhFdFHh&#Leq zkTkNUPRDVrqAB3C2^*9|SD6bDF9aCH8Lx9Osbkjge+^ulzKwFMGB|d;NQo~9t-Y~d zYp!WSV<<PO-Rx7xLE0gnOB;%#T932G%)gbE8$@BvN5)*~K9Q+d*+;HwC=g`npn9h| zK#Fs08F$f`V~z%!W;FUtflZchHrrko@ntLH(72>v7iJBHUDdi#LJV<nSjXvY2tGix z#updkF`VE`ZyQ&p$HQy6w_3fKvaNKnBQ^ONgKc*~3dR(B6b?BnAoMf<O!it}In=NA zz4F9d+#<9c2yMb5b;-!teJqp+)M|RE(ku`16E=aD#pqUk$_~HxcizUq%Wp*{zDV&v zrR(W5vBD4)fy-wX#udqrw$25uHj6n)fl&O{R*W{!_aZljU7vT3vB}&p1CWJabbI;v zp5PVVSu#6M{T#7YujQpL69|PjHf~{WuL&#nfGo#c@Qdf0u%duvoc<J89mzv2Q@{=o z0H12Q&It*E96)oC_G=7#ZwEdHokJbnc<P7-Ilz^RXThqqRPl1%hzVpstuDZo>toEt zY;ios!S+)?KnMjQhS!qQRK^}6SU{EW*#Es3j=kghSBjz`kha#f)R<VUHLxj0=E5?? zRCh9@XI}>3%7ff_0Me_phy%w@Nn(Jc(Zh40Iq!aZs-izp^hl)#RAL>%Tpc=*w%snq za8BcNd&W$B(~zr^n2fJ8*J0c3;sxyCxq7`v<5^GE{E~r=loI5QD3k^KXdnprp43Ry zH>Sy%Xt>*>MB0ahEYO-Jyo--}s<Bos2d=!g-?->)@8VKUIpiJ}CZhwWeTON4I}nRs zY`8#2L1RkO8K%UDTVrWJXSsJEfYL=8$T`SYSYZ^4xrIaWD7qQs2(o@ocniyb4V?>+ zEB99y!y_Zu8dC2ImO0u>AV3%>yC=pdh(oro^xi$#ymbUCV97Mfy#?=*qk676``px> z%LiP+%VA)rQI5eDw+Iv9v_&zX6~io0=lo-RJi~l>T>Tdu<1id@2?yCzg$|1=OBbFK zR06gO>#PD%F(uw8kojTG`yLQ-$?MPPn8nao#XFaaQ>uAY^v}+9aU-;mSuV|f&DGcS z45MsR>8RZx2i4<Z-61VOmM~*_Hyppxx!If@EfG>BYd5RV{=3~En-U?V*WfD;1d<?3 zplqMk?zk&7cU9FG1Z^Xu>TySbqh@ff#S@MmD+KiStWRYJ0OsnaDfHN6Y-Ft^FOG}x z6><&bVwmwuRtD4XqsHqTyC$%mhOFJX;A!omLjrq7z3QC!4<@s(<m;;NFU!k5m2$Kg zgsQ}9EeX%hKD=~=c7I-XVXezsjHl7Yh8W`%;6R8jS;aoGtjpDKrretqh{Jf?MNL_e zDE7`N_mNbi46wD*l@T6TkI!LizN}`H(ShYjOsXD>I`_i(yFhI;=IRPv9^Nzlp?TR` zs>*IT>7F6ZAf!2ZfL%bW^&P$xQHEk#bnF30(2dfEO{6?c>d_}0a}*;HCu*qyK3Y`D zTCMfga6O1)F$P^{uBSfuQc~^TWgU|I?TMf@J2h7gmKfnUWZ;Z>jE5kTm8Y5`pQ@0$ zY#q}o6MIf^HM>zpG+?!~b%c0(?IE93b)m}@nz7G@H?hT~fbxqZiyt8CQ`fxljX{Qz zpEigfw+S0tcym3-sFeEbUCT`0`YrFS+fPjdG*wdWlw-Ev*-h|wd2#($IB8|m?=8^| zqaf3I(4X2%>lxyja++$D?Aw*GQKS5u%8l<8{A|Bmx<gO@i{+cAR*qYMqYdI6o#D-) zk)Y$0sodtND8X}-YFQuNS`Jdn3~hU4G7b1@ZEt42Zt{JdtGmv%BY}UUCVh9$m~h}k zM}m+<6%%8QUJvf)8y)3R@e4tVt$qumpwXQR=f!T5c}fh3E>J@XYw`nR%0oR9d8#)? zEmytThMdg5AYT9z8eptwe!DRu#%<2nud5CPN9Cs+*b4o}4O~0FViEe$b{A|g#wi)* z81N%Iy?dbdpE|vAQTh7X9uLeik=ICFP)H*~Fq{&bj=AYIQv+iaWOu9ix`wNseXWv- zZi%U}qLHo<5!VUG34gLcq3R|NNSMn9Qyn*OhfH1CC?XCUV6R>7i`_4nO24PR20G@l z#eA?HVDwBT$aeT0^l}#U=9pC+M|Bs6Lg9=eigen5Dg_UCYoF>jUil0cMO$<z+@UGL zeUO+*9hTNQ^1%h6(6Aq%yCIQJdO;?$+@u$^j)Nf6Sr;9rO(c(tSqE!j!I%w-ejEor z#yLo$TA>B&99)B3VaqrBsdp|??3Nm>@v@Uw`W(4WC8{luEUdyVXJ!E<3T}^J{`0<W z!_BtQKkG7p>;pxy&9>t07bz$eqi38qK3n2Q%sYrFQ+MhM7R9xnRdQIrVH(3gmvU@b zAbmc?D3xMT$w4`Tv?@V88C(VdXEF>jOzkZqS^V3=xg5iF%D|cSP!E2#4EA~Qs@KKN z9`rFC^xL3B$2S2gH{k+a(HOuUnHF*{0%{I-dfQVJwvO6cMfJ!S0V)lSqrXQxSPsFt zNR@^cpl_%Rfyvf@nRBrgIE=ebP(+Y{v8UrK*ReF*X)WP^Ah?YPG6~Bt8>U=q5WCFc z7*+P^#_w|~tZpWH9K1^UWV?7)rwM4^1O#KhXqv5Opsk?3^K;!lHMy>8qZKMr6iCy} zyEkzLwK%W8-^}Hh&%1<n?~GAq)vRBJ_`TzzDijYexfWv_6aa3(ciFI=u{5SyW`Ipe zIEUp#YiDW#x!*AkWLb$@adUCn;w}?8N$ueOMdw_}{+9Ucgv?*A(eNYHXtrUKRM~X{ zm;OsW%fb@S3C$b)S#f+?3Hf9_(WEWpsCK0(;DCQ`i~Um3-PDyopE#^V|CU>uIG$jH z5QNOenfXeag-|WKb6u>S+xx~naBrw?(QrU>*wSFrI7(_K*eRD|M{{xbl{@wPK-GtR zo<m5rZ5u>=%;m;RH4+1YuK!yMVMNypKp=Ab%ui0xB7gCgw<l+(U5R#kJTE7~5__Sk ztZ(=FAxC>bEbjx>Y`V!h*V1>b$@bRpI%Q8nBfjCGsm9C~|1tZBr}nNcMT=mwN|2ru zRbMFGwv*~KMxiL%wx>L-Dw%QOk#$s%zYm|+L1AZ`u(Op|=rHO^N}igMJ2aJi?)(nw zUJfyQ-E5R>Qk!>ACJPkEF&n-~i38VxoCk3KEiU6sqA5liIW}Tc%K;e&BKVS-t~Edd z5VADjVF;Mz!e^;gAv4xZDK>bVmM+(c#;v#kezgr2I&|mGQK^oT?BBNg6q6>lUNlah zs9s#AR6M<w`u&j)dTZ#y&4q?^`)*F=%_9~}+{u=}i<OwW>q}N^MFx20-(;#qwEHDW zH~2{ijc0vo=-NmI)hHEgg+J-KXFbYNe1ZM;ViBY@jB~074+T_ol0M#fX5Td%S$%@6 zvrEyz*Jyik^zdW_({7(OyIoIP7w*5IC0=S$xUz3RwM-L}?VPutIi~f8ny>2{k#LuX zeD1|J+vH-rjGlKuz2k|yHW}~Y@^)=zUG(C(0f=u)b6kT(uKU!wyQ|CDA&^nGi_`9* zG3o1bvU_FGc1Q74-5wBVq)l-cMRCeTWdR!oex9XPQEH<0@cZP5jK*V&fvBw$SM3m& z5mT02f0NvXf~QK>m7v0SOPh`~8w_5ELu(mu*h{$T?b$#S1Y}8pZC$DEsmre?KxgAA zmbBis#|$LfXyw3}G8IR4K#<A6Gv!*&-tiy2iupBROx;5v<+vYv(faEMuGtdGa?}My z<m%ZYh!!qpx<;1W(DT7_)DU-hFN#qR(_)b3HwSi(cx3%m6+i`a2EMd03%1GUN#)cm zU3=kpsBJs%ZjQ9ZAaP+ksrX67QPY5TJ9(QQzDE0;Gb2pY+SVlaoj;KIesQQKG2oID zSwz{c_Wk`c>$AN+Z#yquO&i&~kkl?Dm{B+-)gf4e+n=k$roC5*YyGjT(HF;;dV!-$ zl5zp%n*Ce<sgMq5**S2=r4IjFa6TXCX_Ko)Dmd5iPSHkIRqM#k+Hp|jwZoRw=jexA zTFLnbG)c>M{W%%hZY9?(azajBi@F~6aq617@bte|5B*w_e=>6Z#6SPuCyPQIHS`{} z<)ePwv8p(G&-+kkuDnjiwNSI9sZ@jxLki$1G6y2MJoVA~9&!gfs=V~H<Mu3Tj3gf$ z>=-#!uUvN^Eu(LY{G-8LE2#Q`UPG*}dADjB+S2oUlIg-EEA5s!zdui|zoSvw_7zXN zw0mJny)5jlV61YcD&ayzZu6wvnQDu|LDi)0g$eb{{n<=Z+uju_Bz&npu{O^8FwM~J z1s_B*8AFRnTJThEv^!2&h)LVcf?1Ll5mzLk0N>y5OyU?!tk@1<FaQ?pJUw~;!1v7d zp|r4Op@xDlZS9a##wlLsMLilO8zf}!$kilSDR~5D>UQz9PXo4zV-=rP+!asr3_fTG z-~%Cr?7fA+#Xv8UCyT+yWAqO=Z4v0wr*s<<&boDGxJq01yqJMoykI?Q@4wYjEn_u6 zG`cui-av;?%d13-<>uRj0^+nEBemEa2F6<6<qea{!CM6PR|US!@v!*aMfXdQ5et)o zG+gh_hA@5=G0@%bn6Pz9NN`$HK1P+Hl{K|r#kiEI3w(F!I6iG@r4Uh`>yfhyT&wq| z)Vkt4#zsL8ta`kuGG>FUz8S0h3kqwdgPvdOqsnitnGCKPfElP3wA;nVj*o8Pdpi#< z*ZJ_TwAU5Xn==~<?5YZ}vxX1cRZpQ+iM%?6#zbh)PasR(?ZZmPf~>4aq0W<T@g&_W z9(Hp1G|&0nr8eE`FTdRVX8Hs6YN>ZJCU~28P%F@Q#igkFV`sIb)lQ{_(Yc<M*1L6) z3T{ey^=A_mbC<>A8)GXQ5^9c0&F1u^0Hf*3i_+DXp}x9JQkF9iZW{#a(3$`XL)#{* z5|v)}EaWF+)0$5I&-<k^VcYidXQe0mEAf)?@1v5w4);Ec`tzBLlK{BSAd&NtuDx_+ zlbz+362~uqJV`6Of9niY`&o4<b^wFwISQ!~ZHUeOX5l@h11sj!_f6k-u+eX`Sv@q9 zMz*9=gEpSO8Em;_E)h3N#f3e7ZR#Fakqr0;*1j@f8)hzXJS<j6M{U7+9w8Of$<5=# zmuzts%+nh5lMY)e0?G|=@HbVZa*&431xiGOeF;AlSY7=n5q6YKlc|0Q(tNR6OpREF z-UUSW+f~8yLSi8G>U4ujk%73lR%lq*Yiu>y1n*15o&u3<YI~*QvMI2axrapGTFXY3 z#%MeMkXnXqYz}p1SUt<wZ+0JTRz2P`#}NKc)F^{2ab^R>ys)*VA2?oqrV^}J4tFy_ zCrOy|sj~i+LYgvt^q5Stm*1m<*F^}Gj<aNmjOGRdV?+huXFIfxS7D;Da^GXh1-94V z{%9+c;m_B}&hQnnL@&UfTl2B3<z=6~_r;J*s`_`-ifh+G?J3}BmFb$8wfjPa+O5wT zf92fucG%*rr0Pq5xAZez4a$ajEj~B5={j3L3H=ChqvVgc>g(UH)^)O*>yHEg36OKK zzO4lhOFbOd0J7n%UZ>32LLH?l>CA>NjaR_Jfc3$-(9HMAVd{*8tiT)Tv}@`yZ{6** zgr`rZwZYotRM`7s44Ko5I*K2e?z(`U=`;RkyAHl9>e~Az5oixOyERHPNHs4`>PeO9 z5dx?_$|y9v<!Y4hx)?UhqQ}lk9ka7!ngU3^v+Z75*NAQ=eacI5Ypu}pxmU0fv6a@1 zAm~oL=7D~5S^TRns^Sein~N(_`5IL)(}pRFDI3A0ilC|bQ8eheyUcOcs!b1^?(~$c zaCN@!)=lMAyS)|hLt9v_n>>at0A3s@FvZh|4-R?j-5(QAF-k)-VV!L>zv%SqpUFOe z<A{niUFqJ9O0cQW|CaojtI*|x>)5)dMJb2h_de&jTL?<l$%8ap!;dbs-AT_(U5lfC z?o1F5#qLXIH)%t`F3B&q7o-AcGm1Ab-s!381o1NpS35g}b+>voLIH4#-#phmo|;?L zwAmq(D=})@qlHnq2Cy|{y{HC)<PXC%=-ts*W<QVlaqhGyd6nn@`r2W5H1T}U-M3aK zHWn9Y)8ELxft4%r2k=X@o~lfq-9K*s&p^j$XWC20ZFW&+cdJ&-vZ$<nQ-bwBvR5y{ z$C0-dMDw#_<n=F1n9kg3GwHrjeCj6$D<W@eHgMTAJujM&O^)<YdI7ip<A(IEs)&@z zso3F<sh@hK5IXQ*@40D)BgEk7PE4KpbcV2lonlqG?xR4J=Tm16aU0_`aGH-sC(iu} z3<%j@!@0jAj&b7dCJ<!RW9%D+P*ctoIb|`5Ay?gO&{e{K<$oka0)u=+ss;_S$V%sX z=-Ab7l7VO=(l_+@yBzjwubLC`-<HS88uI5p_9;zKie{r7Uc=*wj6PxZ3(K))NqmU6 z_O9kd(`cXp)xJ9DA#qIi!GcZE_qVE-H$3bB8O4W2#W-U>w<q1kb^J?L<#7tRl>&+K zp*g}NQtUzQ+PTpF>&i8CfYCiA_G>GI4(vx@_@fSXu^&%Iseh`_(HK!2I{s{OZ#v-N z>iG&MhfsBuxN%e6fwf#<1hgJNS_+L+D_#UcIuBa|U|u2VaoQSdgU6BLbqW~(_`c@e zhN~4sBx~gB1^2L1bOTsbX`o7(?CdL{o9;ly7LX*99BBkt1d#qmEK&jh#s@PqOZ|8) zrWgK=HLKP$y*Kq%VSp!UuSEE0lLUp@y02S)H<vgzCn#TsmD>P%)@X6kkU{60OAF6y zXO2*}$IbRIU1SMgui-QyBQI0_n~HoQN2Pi7&yU`R>N(3l6<I8rQAe|6sC^4m{2JYU zXH1wM<8`R?;X7>p8_D`W3WO5}v4|_ZtOZuBUol*6y>tayTYgte=SclTQVg!5j*3(1 zxp$F(=qrMCtwiyXRHv>()(IMLx)z!a{!P&OxuVoXsFs=iokdU(urB*OK!L89&e!`B zjTX7#U5jVSy9#_4f|997L<HeZHbG4gEx85o*%`eC6U{zNP+V<MqFgcENWN}N*q3TC zv%#Ws5n7>GnN@P4%|pL%?Wv4rKSP~JfO8+}ssM3SRpK0J#Ddi6O?710r)JnTLeUff zts^MNG|O8N6x3E^9SB;cD@r>+z&2U;eUe6PfF@^U*1lN{<|~5CR7eCFECH2yB-M0L z#n8kC!6B?pL}42)eZ5ue2u^XW*|dJ;)mpQ|o0ji3GxCDP*)KG|O)~U4PeEyAT!e^@ zs&I<A5xFjA*-@UHL4YZNq|I~{I|v$T?P_a1Fd71~ud<?K+^j%Ez&5;9Xb9+?DyY<$ zd;(ih4FQd6R$C{7*@#R0X01n9&9(r=y%iX$7xsApZaC`?6JT{%srTgGoY^z4zyLTx zI_&*J8PE;Ptb9HhA{e=Nq<h!5IVq|IT6d+P76H>hC@mw@P5sELo;|nd<<VUu38FcU zvFh(jaD5^)Lt(Z52(TEovKkwbOok4ym6OR@ErEf2-~&StM8L5zR-masB?~gNg*+RD zO;?du-vcUB5DH&=4GFxj&IBcNGmHq7eouzH(ACoOG2JaxEeAq*7QOYt03!RP>x%LX zNmT*&hZj|q0ZFC-lSJOiZ?bRfud?eKr=k7GBqD+9`)I^b8u|i>JQ0AH>G|(dv-&53 ziWOT)r9`!>S^Z)&ET|K9k=!(8V2Pxt^9fMeipFTS79Rmk1}fQO)fnv6o)t~m1w~ZH z+ir^kKjy#cA`IwQEgn2VE>^9Qkc}d%W*|tbI0p%7)o@uQC9IOOzTfJqqbqQW7zj&l ze(o>YT}}{VkVJ^2hHagmZLZFPhm-;FiUbK&^<%#bUG+T3S}_R4Ff4Q<1*S(+8^l7Z zv9xg9dN)?xf*`=Gj%J_)7ZThixgNF_hb;dWsO-Ojy6$nnymqO_5V`|U+KPwWa@Goe z_dI_>zOUDA|2|**gg>l@bw)wj?HyT~NIu?y)*`O>JQag(_d#P=9t76mnaB1GScNv3 zU&T@#GGM?~b6-$3@;pM6fKaq+KGKEw^#+L~tRUbND{n4Zw|NFOJ@bljwsb~IMINS3 zC=5ZmJkOqcx}{|YR1&!&xIA<V>v5B;s@vvRiM0*fa;#@73xfHvm+=iN&;+bW%0NVA zLQ>uM@%LQcdc@?LG4z(J7B5~ZJ`tOGqoT1E_&+do%vt;{K@~6!H@u2NV^h1f;53ia zF|0Zos99>}I!w@b#DH2fL*&R>(O0#uv)QN)zas0oa*85`46`7^V89&XIj1p&hJBk- zvsI8&Q;m2c8&d7wsv9(tgG~YeoaA(2UrHlh&{XpYj_Hi>9%N5_2YOF8DzgG>AqEix zNgL2$9V=ITo2BJJO`TY+TLfEol=H$Bbyitu?|QDCwpv@2(jGz8o~_7Z!!ba$=(tP8 z$72&yYS08*?|J36cmD14B+i_IF<U8r<&67`0%`?%3;F$?*l+^kLj*`Qhn!TNfL<ds zY`DO@*^qFA(yf(`zJ+CtChA}KXvHq*9RgmZ(&@v>+y?mnnZjL@6SuHh76cfrP&@o! zE+0YoEu3c`qcM+Fbg$Hk04ijyXmw#PVRF(h&!9>{?r5?s4|{aK$<MV0tcpS$StCP2 z5wJZ`Sm=rmO+;z$!<{vt(mWj2#xwIJD@(=o%+N6n*yZ=YACFKyb?@KDOk!W8sF6z4 zV3oj+WT>f0Uj~`jxT4zk6uCu!p{3MZEw#5(Qq6!tj+AXZq?*vI@+UT92dL(c5a4Ud zqbqEyy7cA)OshJjZ4!*QBEO^ksd7c3oIrBcH{S+L;S>GP2xXvHB((YPX&JyHKd3J` zLe$6O9ocLXtHk5CWvoN1jJ1qArxFsOKWSdSYhYnmIQqDHdM!2Xm!*SCv^hKF$iWk~ zZR!K$lwsg!$5kDh7>%D~s6Rn-o~$tg1b7nU_P4O<Pp$F~4%WC{fi*3w{ATr9xjQ?r zyxImO{^6J&(bj@B?*TfMi)!x<N+#ZpPrQM)wYq(ha3kTFus=#H_!8q&_k7fo3>7{? zRfKSS5Uc8#Rvsj+7oG*xmDBT%RgYfLFkMPz3(#r;)Pk+mMve|?Q*~!6&X;PMX48Mv z&+Q>pYonoySV<y5Yh5w8%GB(uPT?Qz2*H-=D*1?WqVm;@8)L`_7t!v`W_#-j%-1mm zBHOv%OFqFJy-8N?V2`Z*Na`w2?jZb%t5z<@YPDdRD+R3U14{sF+Mk@O6ZS-p0=o!= z5TB&Nl7i+5QFRX)QVcBtn+k~5+;>f?XtzD-Dh_?&EU?8CaGp>YRtpk)HDSxq_;A(b z6{sCHVz1A!e&vWP$L#tuzl%v~Dp^~%EX%eAl)SN8BGj^uA`6YUPt0#B&RC6*YM3+G z4A~a2MLrhzE5wARW>uo(PSDDKzKo*4FbL>RY*6uUHE&5ZG;;M-!j-{g#m=n8z&q&~ zJ|UJ^&AvxXgNM}j7L+trpcvai6I<0VY@)^#MCo{wY@DLrO|mO6Aa&LspV%Y8Y>=X! zyp2^2%Bwrv3>hP+4#zh(u_=bJ&F8qP41^xM5#~u&awYnlYS4BzQj7s=UPq|Cm&t1Z zYFag`S08Tp!!El5oZAn|zoF$`+d=mENl>~qYFUAet^Mh5M<6M1O*3sqh-`(9s|y|Y zss^%j^iu&UHn^LprlF8TDurg%m0GAm8vRrux?PzSXFm{BI`Uz)w~%Ntz>ah&H@wB* zMZaN&mTQbw^jvByK?_evLwT)^A|Nr?OFc6?+xbHt@qX3<ny(qML&9|?oNkX#DlSs+ z#a5kqFLnJ`c(``qv8ShRxJ?>cYL%1CM404@;(+UwXEq5(*0ZsOI%l2ypmoR9wpo!o zCoDF^Ttsks)m3V_Sk+g&=#vs^#(2dX@@-A=&k=l`pUsYQST$F*D?5T<FE)D?QPJ>+ z`;U;p4q1MGZR_}n=B6BMI0fTW4}_&+6<}BeT_DUG8(vL-LWZjTS%SMZ+p0`C3HtN8 z2NF+)ktwCz77(lwaSw0Xb)JwM283ALg+~0jdEln1jE<^Me2yd%A>x`kH5m9PA3D{1 zd*u#HszqzHUgN#E<`_b;&pRF9JcJ#dPZYW;gN5dhl|9+Y@39>wk0;0?mLMOm_=jhd zY!|dnK!js^h}iJc8&G3J%~4!HVzUyd6x$_pQ#Gy}O-S~=`&cDTy_`%eRq6)+RJgdZ zE?4ApmB2o+q7lw?jpD0e!W17ds_{OW_RZ>h2ng%pJpJ!{X39Bel3t2!^lz3Ugx|2g z$#s%yRm@&tD84qE5&h+wWw{Znw!~^&eQxj4puo~gMzvZrvPV+Qa9#88TC9V4>+SB) z|Dtd?ipA<1^vk>?7h|+y%&Dg(&(+;s6vqhB^UcdHVQLly3VR4mHMVf(u_Z**f!s00 z47RE%P_>#|{ETkqGm|}IiB1o%x_{g+VGHiKhq=-|RR)>b1Vevd<*TItG_uOo`B%T@ zAWQJNp|JCNwtYf4r$k&%|4NV4YRaW=Pmcc&qOtq0$J)`{W;I7SAxXz8Kgo*AftxXe zbiV!SkRxh#<^SbCTC;368D>Ss4YxZ>WS~W_LhM$Kb^Sf2fiR1VN$Sc#@9R3$%spPK zAw$>L@(_gc{K&{fd*^x5%+U6tY|JO$6KaDik#V^Gt#`=(xmul(_;})fYI~BLlv5f! zG86-(VbNE3%@^%gu08>3>NS74bMFV0;t@qw+CeaWk(ESnp7RQZO+}ykvB%{itNK@< z9Gbh=5Txzh8RozniII`VSE1fOSSPUS(!{H8B~mCdjE2qGOv~w<J`X=S`T=V${$)L! z;xb6ssdZG7S-p0Ms+EIPTyLJ!PgluhYxJxP<XbOAoY_ByI|x{PGlKm)w)jH7wDw+J zee%bvPmEp;6e-rc`){#CwXbXnF!gfHGs+R53-t9#s8YCAu<83_X8+vmnpF*;I&kqF z@lCh)cbfI%I+OD@X`J`ZW2nBDELhLIL1JnlT1F8&7lADIxhuiRTM=b1Ca;B0r^ih* zB0~cnUqANj`q?d!1C0?`!~Q>X3QcdkIrd>YFX)-<%ll!M_Zq%mw(eaWFIE5FX(`*j zwdq=;Blk*e``^zsA^T%J9vyYE+B2={@-S1po?jm^_gHjBzOO*B;qY*6AhbVeGwg8q zS+k>))#iEU?erd2o17ZIFmK=RHOS)BrlI+RXWfVKX>(gueMs-4k1xNyU=!SNqvm=Z z;9}a#j`|li$u|dz1nB_Ad%I6|TAwIAaLgKsFSC9V2A0Nf$2hWfYs>HUm#J%8$7YNG zG{thK&f(36i5E_Z#W1zYJ!6XWE~>OR#qlhQ^*a5Ic{$wVYhQG{p9-2We@v{YFuG7$ zTWWf9Hs*o(Y{QtZpEa_z%wVNg+spCp0&UIeR{Y}!$VIW%3M7E9Q;K#runf@eSi(K9 zpQ*H}4St!%l|t>zo;z5u`SF<e$tV2FN5h`%-VP-{YXZyIE|Ubqq@Ms!Jstkm2Fo1% zu>KbAG@lXUkNMPAGq1b54OS~|Dfdpk(s8jkIquT6@3N}DM>!r2uNE!6O$LR|Y68C3 z#|WM#i!oki=d&M)n*d7NbiGg)tQK?tyv?`A!avu|9xvDEFSGc))v_;E?^N}1M*FwD zcEEW+y^q56m;7qMNiOVWeZgXMi!9*erdQ~hGf!*80e^HQ<}E<~f~2jR>SH8~&q)Q# znm=0VmvNH*)b3?hvI!nVm%-hu3$L7(%9_%y@ZEH}JIYBne#>(yL!RSPU+3}X6d(Fr z*j0FFc3)_6-D_ro7UXy{6+}|`7G^8&<@qu}-sEQV<vFXZ5Rh#BbN;be<ZqruanOv= zS(T8TXo}=XUBXS}(9OA;BFES3(|!jsADaBSxLXNwcDPFf`3UYZXWC$JIp~;uxo&k4 z;>Pl-x9M8|W8UH7*k%Bx0wgDCs98Om_u=9hnLBZy-tV$zh0CD*V*Ra<V=_i1vo#fX zd_486AQV91uEnfxQP9_sfb0dcv%_2c$L@Y}_X>U$`Pav2dA5JfzM!Y2Lf49N?Fl~S zS+(?m`KGd;2a|&>D@@zEqvq^it?8FzUX4WtSP${~#1O5^k4kKQtjm%xPZz;}jOcU? z{*s47B|_F;LtF7KNyPTOxdg!2TXT0?RG&pqDW|7XHP%_8fdgG<MnMX_%j2l`fzl~_ z7s*-tOh8}Ng-gCvg~gb<uXV?(-%PtGm2bO^Koo2KtEc22ec&D#js@!qYF#di9%gpH z{?9}ga~JdGP+r~HZ&k9;9_CT&7m0Q0rLC}+BsV>{e1+eB_k=otHEHoi)C2Q~Tlxv^ zZZ(A{1KsmhY*G<M?)Az@U5VBFu{@S&|C8-%m{nDpTIw7&F0Ek0RlW-lwc11!X(a`q zUf?He@Ruvz{*@_IYM3y+WiDyEOfi4h>sdFftVCD@%b0h@D|lxbmohzy33tOy!pvm{ z7Q9L}i!K_)^xo+Up~C)<7^YU{%JDp^`fz>WbI(UwLr<=${XpwDF@Z9JVQ<Ux+6wJW z*<$GhA}#<7U0+JE%YEk9#Vw%=&R^Ju{(K7bZuFSr9rH3qHqLK`=Wk<QB!wSs)Alin zmub&tTo`xN^9p|9nu96pP_cq;kzB-Ra$sYA?7pDBu^KdLGhV%1?8E9zh+!6;&5NL@ z|Ef}V`1DOGG=if%2|sGx)GT$VJKcC&Thbv1D{(sPty-bP2h0SvG<r)1ax;UjSNBc! z%!ZC;BYyJzCjlN*d^6<Nu!oc0io~JCw+b_z9+q&ygk%$5#Rpg%a&cmS@uE$8IHLt= zQzaYaYh`ZpT-t<WAZ0M~s1+v%Qg#n7NkR!5^0h1U8@^d=*9vtc*BBgHy;VV|Ts{38 ze`$MAo|m~@WURaL*dmWDnKd=8?sv)%b3L#kJ!2KdVbcHUZ<L(tb%Dp4T+ghy+Hi7@ zs#S&_M=oOPPodt%e_x^*Eb89P!-Jp>`#vwCR2yaSvm7KE*ce=JPBvogV_TE!Lw{VL z$dOdZ;@>L8r!LnA_4cmP8sDWRsvelzE?ZT&Szq{S$47c`!qd2D2zq#|SIVFF7N0@( zIU-~2?!M>}qjPq{Ne^2pGp;zKYua0MA?WFqr!BI(DBS~nRhQHFu}Y&M6VEo3s?<Tt zxr*Y*-ieM@w!()KQ*y#yO@x2fh3K&P9ybGD;CZt5!o3ecSt00N7+`qv{$hsvA?N0h zoa1HFU!SiRaEz`#UA^4dPoX(Z5m*uro~!R-#!VNoGBR9k$PeDDqJ1g8!oSq)Arf6z z?|5<WELDkjQp6#HEfJ4*L3KO3@1HQ}`(MoxMWKh~VS?_Bt!+AS<FReG<7o>w|11x! zip~aYv~6{QJ@S7c7qcu(5ss$!|5IJ{OtH~5FD~G5{lyu9jo<q(6}-MW_YzZR-6-)n z<02K>JNSUQ4U|b(q$obwPG;SgPS5M(YCy8bkvwe0B9W{7YP8rAa;>`6aPiS*bfcdx zPST?X2b*6KF$&fGg!uJEyOv*sP4wsp-}ThGhH`uMv~5Af+upEJMlbQ>)^&a_Na+G* zqDPsUDXjI<V0%?>WGQClRs@%`%oovF%q$o6YSs8dg6lfRmuLJ}@Bub3>BJ<L*lxsV z{qekNDk#Dy+f$8Xp9|HF?e`mB0stT#J=g91HI=+W;#v+2csUaJoafinRO?AzHp>Xn zdgZNqsZP)aJ9$a|NMe0*>ti&ZT<W$J(^wX$o@|b|x>wm0(4YU@cEbFF#DjLDr%RL6 zZEfk}>r^FbC;a0c`}=Il>A1Zxk84)Vi}{sTUmw@kvea$X2%Kt#-r9CEV8%=4&9>I? z18>ycx%aFfF3mqhyF!V;EiPEcsStlPTQniuqWZ*Z9@qb=Bg~|P<Fy00D((%R2c*-N zwN>BBJ=kHsxP0>y)np+(*^0@o@LhU`b-l6Z2wM=(0y|UB-?;zR?aA-J!4}C~lDm^2 zKsTMPeB_q&7E62+zAyW2R6$Hd)~nAk#llTWz5qo~x2<(~u`HI=r}Pn|{5nvwT+SQS zE79L0)+6L%URw~vme}G+`Ai<38<pOv6z|^f*#c<I{|X|yNZgUj-O<kd*_Ud}kzSUQ zHh2cfl$ZW9DmgSN`+)_`%ar+xF6eZYVPF-;j-NT)Nxy)#+X0BDi^%MbN)*7Q#;qJ< z`z3eqr{;N5+zqL@$}s(H#d=-uBhUV~lcD#$N9W!FX%V`9-Gt=t9`Rdf*<yg~E4UPr zOwrG^7I;0Me-@0n%5q5J19;g#*0Sljr)*IvabV|bZU?fz+Z@}<1cscxZ7sta70W{) zWGOPcJn74<eVNM{lA2ioN0=o;VXEChlGUT)9684I4d1NW@m~dLJ~8qA-*HX4vf;Ol zBSqD-Ru%jEHD8-cjKF1WGNnlEvKx2_k;3HjO3HWP`aZu3syt;`faDK2@rX?oFh;h! zN3tE0Tc9m7+#_}SY_7q%BMp@@x!-dAJ!L+PiVyY3P)Ef{Z6%V^mF3?AU>f8uEA$6i zcGWr77-jYlEuE!ZIG~s5Z6jNFFp5W%sO|AFbUXYKE?eCb>(wVdLSjBf+yBPnr}dTM zK>zP5d3`9DKM>2lEs)kUFS;t6&vjdbr?7g|o(Y|v36bqZOMDV!^{e=oiAr)uW#t~7 zzJb}7ssR9YN5#I<Jf*$rq`d6@MvLj5mE_~4i)|#_z8(GCr`e>NlS3D`O(=u_C2C2U zZf#6_pxyvW`fjDHUAyd1C9}Ur+@Xr8k5T#{AH`pxj9Z;BuGafMithU_$+isxIEsJ^ zaf=JVi5oZ06r4H2k*S&C9;rD?Z6N}V9JohTIC5v&G_xKAb6c2JuF6?jR<6pXFYjLf zKk&Kli}O0p?=ibA+C<Fynx@gn5yqFpM}44oc!e4mJ_$U4w~Qq1v&ge|ggyaKM|xm? zm;!GSU<Zo=)P9lggo?+lRK%|A-$elpir^n6wAmK6yTw1ngt`tvA8|~k(S<41h}ks! zI7jt0RZ(rb>Sz;em|2NN!LHg$4aq3vAz^pH0N+=_^CV$rW4LuSQPf^4cSf<(mJ9Sb z)JW-11Jw0)vg&@CHq5#={XCF<i#gtw4qYLMvN)8R{M5f(YnP5HT@?676xk%fVH;Nz zd(*FPbHzO{fEl-(Ah@s<Rf0UbHl=4Wl0yg%{YA1+NzY~g!T|((oSpcoY{b1S<6%0q zgXD)ZfN~|?c8-MVQt>goY4Y;<Q*5EKMNtO|qLNvg{2Kn%(5sSj;iRevublLq9k)NC zP??B4j^puV4!`?8<$PjXEkNWi6UM~^*B9dudCiO9+Quxw6Bzg{46F+&GK~@Gp$k}! zK*vR|UTL&m?T#_RmJEfS*ahHy!cH22t%er)Wy`%(QLso+1%;@SMgxcdRpDhMESBWw zIw{=UKp0y*K>Uf;IBp>_#)L=MF>bW_IKXX>gdcwZ5@{_K`OTEEcS?a79+i<3`NV;> z&_#T!nkNOL6a)d`AOW*fn=Xb;RGm;Yz4j4PwZ}00yOd-~)am)<6kj7tkHl8vD(Fa8 z$zz73Td~kX2CQ5ZF~yHx&&+*>ss4IjsEDX)v@L<)7j%=p?pSTAvUZb4kTPRj^H8q* z)s|0dIx=C~2eMQ4k|a_ho-F=?QrZRk)TQ|wBk+v~pVqpmeLMs<3p?QOKN79)We6n< z+>ED%&l9?ea$^h{p*ti2=@w{*tzL}b)wp_VLqP#Auc{*3);<biXe(wj7r{VQKMl*T zBph5X%(&i(YX9qE)4&jF0|CAQo5b6F+`h$%?;_W@_g$jG-xmd1Z0l-Xz><C;gL4GO z00w`Eus$Zgj&{$m!%g1p+gv^J2S&Jx6TQH&nI^y<Z}A71`4^6y31bO1*~)K(tN&Wm zJ<<(d=!RATg!(guW08o}CG}l`;2n;{$DL~&Bb!~OP!S#Wu~+e^mjC;l8|Lfb)f@+5 zTI|PN;xb36F}mghLF9$42!|wC%iw-cZ#{;5$wa6g$%XZVT8Q*D4(w;9AUBt^gn_fx zU>_`dHspOD{Jb4!-dwfCzrH0b_0wkKKK~WE@SVtqKaSpuCJWUw93N4v4{IHq`VeyL zaTS#ElYi%9y~513Z36jQ__3=5p}j?Nz$kbvJ)u@IXpYf!X6Mm~0h`ZwmYT3rhLPZp zErAziQZ*d@t}f`@;=^n5LAQ!?YncL#i^fkJgqOxNFYmxwY|THq4iLZ58}Gn^kOp%c zh@^mH(j8b8Q;@r@a6!r%WAA^>mDqt4^s$4U#D|0b6o1&xc2mC4>Wc7H7ycd~V52I` zX23RYm#*Mp2jB0Oy>x+P3S8NM-?0>Y#JTW>V>4^a_;wt|0YIA;`5OU(ox$#Ra^-UJ zk*~Uh|49nJ;K=+TB=2qYHEr=1C%|@_MaD)2o*+XU@<$8yWIu91W1NGKD5lUznf^Ch z!50*vS4V~BJ_)lqG}fZAb))F++?j>yu=U{heorCL>vL^a1_PC?vPaayjLs!HU03Hf zoii{E-@WIwan{bn{pscQuSSln1i_9ip)#Ui%cNU`m~=3uex5Gyjp+kn`NSGramWVu zEDC^s!o17{nrlaS{@Se!iex7U{y=)?zbEd|g_6}oGMok9bqhGn^#<7qU29j2jns4g zUF9$-+Fw@|)d8RN4Di82*~p>!Exo`@fhtD!lOgppH%#ugg`4x+Je5{SRH@nWhK<k# z_@u3Sx1`1vvutKGhRk8i!^ao5eD0KsFht#INdk|E!dV6bTG|I3|Ig-p69Pe7uz4o` z5J70$DDTnY3zr{y8(^acLPo#45^q^{%3U~l40z2B)ulWEpJhmtFFtG_2}{2g{ss{A zxY7`E)<mi@h1hQTRb26QeXQ|4*h|3GAEEAno<a<Ow1}@y5?;HD33EGoe1++=mmpFa z>bpWbTIM|pxcTy?yWvWNT^32M76U6G)&EWOIcMc&A=J)$NB9{@BYHR}E`%`E8s-(O zQ;!tT8&LcqHPx+JmM03^rVA`|g@4Kt*q0i7*#heXxW%{3Z1D@7Fg82q1sh{{Gms|L zQ5SX-W{JW2wtmy6+0fq@!D|!K_0T!3Y>~fvFlrKPCE-9Yp8*qiC?fZ9P5@zuoP%{D zh5vGkc)950_W(V`+*Buxmv^AIRbD5#`yYBCRBzj=&;z&gy!DGHbZ1MbwhN}~{3y=5 zQY0Vo*-vV#Bx@zqt&e^@$w=fCL8uxdI7f8X<uAI25!{|C1I9?-?GsvK*1&0Lg1xY6 z0@Pm<`X>Q43lO@%5ZY>7JXxrP%!BgLL|T|a8`(l_CL-O8`IKgd78Ak5H%mWKuj_5| z6PGK~-$;Is5hMU0E<^!Kb6B#i%C9`V`YQy^uC-aG>9Jt95sW*h3-+kX`xhp5%Ru<> z2gH{Pt0KpJZb=EP1Lm4%(rO8D0NLh>7ZBR?0csEO{#KCk^(ELENuZhF%;N>i#R$K# zg~jTftz8R0{ny0Wa`5Rj7=25qGU4zC@!p>xyh9!69v@Ev0X9w0=IzJ_zf|m4yqE9c zcDQ?}LnW&U31h$S7Z@w86?v!TIsM~>67ezY*VQCvKUg1K;4iaJT)g=;Nq{aYd=>JE z=aTY+5uwavH*nb3Z%C0R7ncHzVfo21oBo?V@`^XXuRpa(`8rDOBEbeoJ`@1r9bPix z*ZOcr@;<xP<(P&U)LR84@bIa?YIW`9C;q8J8!AIzKEH*gkwsPjasTDzeIwQSkL0a# zWF935UVDKu*VuB0DR;0QcaeJ5InZ_61Hmqmh;UKjBU92mgRpAx!OcLDWeekyzb-G% z5hgdmZr}a3Jdw9x7rI<S{+kSaZK6F9e)+HPxSb$|B{+%SRjY$(6-hmJ`OdnsdU^^v z&k)%Dw`+6q_&P&ifnI)mR^}yB;2-yxY!l+~^=H*K>;rOuP8Z@Wp)`mJ1s#G-Fn&<< zS4+B7Qf^IpJF53GK-(C9w@hpJEx&0|SR@is2LP?SG<nh-qj@jpuUz{;*(twm;oJ6t z6-dFbBjTn(5n1{+lgWbL$onxg{k;UipJ`Bsb*OAR<1Hqxkr;Qg3JrQF(##ZKGU(Tj z9F*HxtTF`_xZllQcmTjHB{=9#y5aine%!RAo)1=kw&nc9-SDwj<MsA&()Z$~n_`2k zbn4#=oN`R$uI6ZJdhvA`Ua=u;bG}{HXnt)KK1=9bXz8xDIn3I#K1VBAnxwMZ)+F$` zhzG&^Voi;LwoCWZ8}?FHd?!ws08TzmqTY{vhxYm1nHg&N>@)WMYmR`*y)O#pN$Z@Y zwPSHFdM`E0{rnyI?BvmbTq*sCg_-Tp;bOHTO@XsJ;p5dNt`S3D-f3qvJAb|-JyCP- zLbYRogu2v*)v?Y!%@x1nDo%61{NipK>mDDxs-3kv-XaWW57<ju%RB23WD|V%)R9VT zfz*RIw3xDWZ^7G6_oAkW<o5?@s8_DD1G-;cJvn|a{2Qn3@%xD<4<4*^I?Oi<$o-cz zIw^E3`PULf=K1;vU)7~oF0FSal*<xug4%btaKc9R`HIQ^mcpt6^;{rwr#;%6<qR@p zvn^w~$PT9YO;<c*DfT?!ayNY~G!2$5UVJEtzAqb5eKevwOf~o}kL_TARnm=$^!u85 zPum+Mhsr#53_y=I<t$HMbKU8tS^rop)xUY~3;XNMzrT)iFYK0APazzC2}E8E7MyLy zoH5?pJz@)#N+H-<{vN9I+pi-d65Q@Y)W#GVP)pkb!uU;nBQ6)a#I5(Qi3P5<J6wN9 zI<BLVUseYx^IVsuUGZF=bP_vA>lLHjP>UOjsM*V}_d-SXOlp*R>@Ahc$FzMcX=`AP z)2<CHXd6B8^jP{(^J~-cb4~Kc;LA!u#v9oR7e}oj3Q5e350XBA1csF2;hxR?Z2o&c zg3j;0e9gM_&u)Yh0{@u}^W8Ux*8HQ)LdtYMw0hMkT}a+AEqq@+C`F*xMasK1RXf*5 zBsp|6mt34uE3F%tTob>rm+4fTPQeSPT;6L1No3UcM_5W<t&Xg8x>)UG=4(pZ)Qa3l zhv@+3PW3*%)lxvcdym-)QM~v}_I<_8y7V>4lzJ4c>iGAK53v_NPBtpUc5O$>n(S-F zp6vZ}|95=f!C#2f#WR^<N(VhTv(4PUEwfHaPBCImwV!E|P9?SIYdQC;{CRH3#4Ef7 zh0noDyJhPX`qf4|3T0`P=Os5Blu7~&TU{==O{yJkZ;7QL!Yrz3sa1@?S7Xxso5lgr z?^b9CzoaFntEaM2gAyKC&2Z_DmjfFs)9ma1m3doLtIEWN$i7!fU3hx~%0!NzyYPMf z?7Q2~0G3bX{2Z6oYNPhY8n?m+CkM-17eizhn1wbL70_^1g6zZ$%|>T1&tpb8`8nLt z*U_Y#eq&WxK9=TW>S-Lz36;DpMk8GG6nM2ZpvFH<vqJY9X_;psw8w@_Dco7x23yOU zC+LjDWNW<6vuMq2!2_O$lLZ<4Dl+USipIrBfk4cP<U@v&)TiJcZ*;8E@eW6wG%=yT zt`N!O9tVSec2$0);Ghc`C*|Ml51M9x<*t!H`hf<8e{M7-1R4a|*mCo#n`HT(1c&iG zyMlD#I2p5fimt`C{2c(%Zyb3v&WqKWABC4G!LAzZ@#IF^H_HC3a#CAFiLA6VD)-hs z9lYoO&FCVRT8ul|+|D%o{71xqJ8;k^+QGVX;t>nBxl?VEP<CRLOz8{-O{}{d4j^#> z!))xpi~j;_>-B$HW(VzeKTRj{O5Uv+&}iH)@=IeWDUw4i-~4=bE*-2`%E-oqED2t; z2Pz=F0?rj4^b|#Gu_W))`IM>>4gA8C#oD<rK*D4`+64p<v8ygTQ`SCLWiOj^<qc+_ zKkr0Xw(`wPC$;y%u2*}$s43!og*OrfoYo1{Uq}a3`UpJe8Bn@r#>s@yjYXXS0v1Gv za?^s%efO5dzcHGy`Pd4>0=!JaVm7wxrF5(qFz_1Sn0shqq2GCy(kG&d)kKExT}OV* zE&gK`hM5ByIxCVICB7ydelTC+GP1AhgVBZoECZnJkIr2Kg;PA|jYF-<04Ttje!~@l zz3fAdlUi(lZ%MelQV)|4K-(5>jLk+=5oH0=GsWqodU~<(5qv_OKrimIHlSq);~Xq_ z;LEJ{p6j7tD?Fi$yoR(dOEm5Jy6dsCk-G6qnsZ;w^Q;;}I}Wr?1>8J$V$&Cdd4Qy< zD~t&+p+IT6MTF?p(Sm;uaoq0IK_hWZk;s8cv@;LLNS*9bShcEgacT%d;~{y%?Wq>& zBL>nuiouL9<wJ8+cED;4m2&5<Y?-sE?PPre&nZMN(!r0xV-io00Mx>t;(0!~1PAg~ zttocKeoD*@<T$y{+y)<-xltJZJyeNJ1Sy@Lyp_7&&^xP^RJ>&FdyHO>_{*VSI0pHC zfT=z^YlQ0Ue$gOS0_xWy=)=~PckkALvgf0!h5h>lYXQhCH0p+0gdHrLap0pgWV?Gt zT>KrCi|<zE$hz(b3GRgTpt|<ejBWA<E>MK>a``@=@#<Taetnd(-70rn2U?hn#s>nm zAcy{l2^sg0?L-WdTHT>eDH-*0e-<6pM~j8jl#GgRTO;Td+oRNBjKpnoUG-yF*kKOu zlUbJ|hmX26r0L+4#QeK7qr}u`SQS<?#yR0kJ?t1$nM1zjq+WQeK=d_UriwXWAl^#< z>6MkLMT=?dHx%)!T~>JI{N)03so;WJvC_F&AuM1~@NOFK@HdOpeyE4p^Yu`XQSTwm zf$ZF5ot0+RiGcDuJaY}Apq2GbVy?-zwdF=>nY{$sxwAZ%<KULq1ICn-riDR?piKKJ ztbr!1pP5^A!)ro1v*5medsUcq&wI9)xbd@YA-Aw)c(ss)7vl4j^CP%)!6L+<&{E`g z59s*4wJSk=Z{4}dqeN*JjXs-L^sMFU;;G1UGz)f-jSpV`8<Wq-Q0#TC>t*>JPjIJp zIsWqU*~eu72kXOMg1pk)45UXOM$hO)BOgO0JGM3lAM`_IdzG6|pNdT_0wo8~1IH@z zFzOV~qPVE~FMGtm&v4$k)N|O6t_?#npNdmWgFnelui9IW7FRx|Ys+M1f;34>McoL; z&vB6#cTL!JmyAPTKj@B!)(vtVJ&=#NrvXYgeRlP8LY6E8dGPWR)<G;ZQ&|aqFstc& zZ{PD-gX9h85SySXI#pE74;z!~kQ1uIt&Ksn32GT2!%O(k)!Fo=8=MSd0M_^{&@5w- z5(misLlP2F$d*$9`2k4ry+SG2>{MH--&XcTBsCBq%uKM6j<wt0pnFFF0d(5OWKdiH zZFxH{0}CR+A)1r7IeBV<n2O)Lck<^td?!&cY2bM0zKWifHoy8b0$)0^Mr{`BTmu0R z4*6)x7L4ZAYd++B68WS3FpR^u@PZZxBwa~*ES+w_pWmC#u;d;aFZ32oVGE)bv%@)j zXBM;XY(OryXS*@MsaudBG~Yu5VE_^<bKc(hphNImKP8?dad92&!UUZn8eD42rYILd zfGolSw=jklHzTP&i+(l=83*3{K9y~P7p@S^JIbJREQ;KK-+7bUA@vbCatdSMmV2_l zCnJqdcNn~rK-0<UY9O(jb9-0JsgY5V@dEuxKh+a*s3(Y&wROh?bmgUCP^LEcQWV&c zNxS6t#5r)tDgXK<EaikBWC;lJ<wtoeSdy}CeGM(1T~wXJ9Ky`EWOKlZNskA-O9qL3 z=l!_O7+)e0snd|{lxDhO>kPt6$-Kbv+6$VNnMSri!r&lR4D|v-Op)8m9PM}}ix!f{ zOk`3$d$KbYA?PtG4o$%>^0^#TQ-9t89j^lU(jh)u6nk6hS5*6@7I2%k@TFj<X3D^& znc7rBW#BO1#bHV?smySDz_-{mFbjHf-9%k1ul2=n*}m*-3;*+05kM8FDmU*BzHc&D z1idM6MT}Yytjlfex$a5F6iY^p+~85L&Pg1M9Pf{TLlXM=636)nqSUluP>^5Y{tP5| z@ybQC%xOQGns|%5Ey!bwa(qT3#b>D5YU17};Zy+m=sY9=%N1!&&*>;<<WOf_%;sew zZg8oRC5A{1<XKGh^PO_f9;tG?@WB{3coCeI*7r}2MqQ-2lEia8^DFtga#;VtYqEp) zRl>qFPsp)%(|T_m4EL+FLE@b?OrsiuL}@WqW*J>Ht&E~7SxN>8e2N5iT@muIr6ys) z0mBq;TS|)a5DM?kXL9?T?W04rz#wM#MNy@c7MfcX<YosL6AgXQP!h?Z^^QS2{E;Kt z(g?C@1`=f30KLq}%h!_P)FE66g(z8?YzAevD#y$JVF`wD-j5dP=hz6RWe~wO3}*&C z+l0?TN9B24Oig!7_FNLxjWq5@qTbEC8yeDWKF+6I0A6@Rb7}>9VCAb<L4-8Qaey%J zb1BH3VD?lGZwGRmsZYgNM`N=&B(>agn$Q#cW??xMi$+B}MjUg8000%t`*`kW<LmBc zUI!2LkL`oFmT}smTMS&a_MA_lUrE^vI=>n+HuX#`zsqxmFAQ_Dyav1(b+euLq6<Ju zgtvK<_*RD@8Gc}!&l)W|c~4uxN2Wn3OpDV@={P$G?h_<s#4W0a&)Jrm5GCq$&O6#& zTO=6bHOv>en4L=G3&%oEV~gFQXc9}_|LqnA3>P~owx-jwot#DLi4}gMWuQEVl2+&n zmy1n69!G<Guds>js_Ooe1#;BYtx?bO@C*#dWf(F(*YV}IxtijUGu)mN`E0*MJ6~t8 zqxYcj%cCA;73l!|bH^oOYPg?U^SI?n29c7G4tkE|L>J7O8A_fca^oeplMk5EDS*<4 z^$=(0oC~Xklf8`91vC&>o!;f#7DdCf<`gg)uU#0GJ$w-)T5uKEToe?*q@I|Pe7Ep0 za9gFW;o-U)my6_XsN@zbWA23IH~2j`ey@G5kIx$m_KVS{4CAJb8+1pR2`f?qhi8BF zJaAlsWoMN>;@Y=4AfNqwmmaE7o^SQlg&zizA;Xjt!&I>qP)byp6OXo=Xtt{;jj<*Y zPo$z27<HK-PYj40i!a-+_KX&gK3Xz<+tn}aVPF?Hjh_dV!z1ShnqujX%+bm-??XcI z*K$kV3<y+m3MSKqo3kkUd|X3OBRx$}hkYnkrR_(Hw)DB@Ck~9@Qwc%|{IpXoT5iPb zi#?FLKOsl9DCfFpt~pc@1IXyayYHEzDRST=gzWenP|9${6g)c|4l>>n8UHO6n#t!r z0+ta2dCq_`ka_)lfb0EyS$>mkQJzYZ)Hfs4`1KPgQC>L?D26VwOcgkmpvLc-Gd5pa z@lf?-Bjt_f^wagiXeK3N{kA6o+|0VO%lr>|+3@pNe=!!6F?{{>!sX;vFJ}_fuPQ|A zt!fAnatTgziCRcyp8WfF`4Nw>2MO#$f_e1V-ydd2wLom(l;tpsFA22NDaiFn$d)K5 z4Bo_jI@RI8kK1zm>~$2r@o!Fpi^vdubg&!|d~m=!JTRJlo}+!RT)lP_>^2N}ov6s+ zkqF~Jlt9<k7idlxYEp7lwdD-IE4t5e`9`kzHQsCuOKP|>#k&jixtlMoiyHWB?c_d4 z&zaA@%iSfx--d^DktZ~4u<}ycwd5^I7>RNb4ZYB7b_!`9$E3O<K__gbnHKu>I|C@I zW8N4Lx|L?#l*iMUJ%j#FA@yqWiQMyP{OLqCzB3b@LzW{I2B#@r{8vy(8u|BYQm4UF z_FBQ*OK=1yuP$Lesv$eJhtD7<JGkClcMNy50^7-X)Y(%%IS0a5QGzhklf$%k<QL~l z!Ku#C?_IJ}Y<nN>g95nBN*eWI^k~?@lMTCVNJ`X#8xquZo8}74J~h+-cpmP{;B#}n z9Uuxm!324=P+fb>uMY?&k~}88^S$}R71S`Ybvf=$e1h*~6Gg!RRbVXz8lP*cv;#wF z(sYu2$hi&T1rR^;q@Z#gM8MRP!N;S{fm6RwP67tG_WWXCK_{{^bPm#qe&XuK=RI64 z*Pb2S>b^w=V<y-%?fz5@EfoOLZJ|1o7Mk2FtDZ(rJ<IR@mF<#N>Y4yz3Vf`yp^lq3 zCAKgEIBVyzv^36|7hEb#Zob_kpLOP~J9IMPu*l~Qr1Lr`qw2p5LsO4pNQG=(_upZU zG(H-1wfRkl2j^4&_;Job2`Y%rx5EYnZCTO?O(ItH_B$^#qQH~z50kA_!jd4boO(P7 zEL`s4C=e6F8tpKLT*AyIE>e%#4s|QXfy^eR;uD5QHa^3kGgy!tiI#!%JuUiCF%X<* zseJMcBq^<|x)$QjuY<D58(=UJ<X8$%8?W1fzqvk$YyrcSa;N>TiuXFtcge1bJgxa; zdbp*IZ)`R2r+{s};@Z>OHJ@Dl<!~d~s$ce}Q1M+~AJ_XaDI;SLzofS4G)iJx+m4p< zkp)o7I&HNVd~T8INgwL)grscorJ%EqrGd_2BhGYXr*=Ug?{>$qWiI<%2c7q@%ECQ@ zdUJ{H%7$RVK|2_zinn#xhK9;UockdC&A}zAYwryBu@>q=f~(&A2d{KRFmK7GJwNIu z=(s(@_E~vBJtb_hL{%w7R?aMdlT=60E!p+f95Red6pA5%d@)q;?#=c5)n>w;P8^Im zO7p~KCoe+oW3%J8DCOH^$0$BL^Niy<*{q7sahT5|hq|{>dFK(t=FktwPzbO!`_fjH z1y9WV8TK#pY!#f_j~NIl8UA_t_MvZuMp+K@d9)Y&>ZTt~mdqDGyei+OlSWi@`j>lK z0USQ?-z2Vjb)bABEr(1A*34{_UINE4tE?QQ-f&E}6+);;XPeS?CnBhbBzV}dF#ug# zbfDPu!x<W$2l4;_ZP!7*`_wczWq$!Cq_LeyfCQ7W{fBuyawz|YqmgIN<oJ#_oV7XY zbYvLBJtMgcgDvyVUL;Z9S}NauzHaCbkIM?)dlnNh&lqT{E?s(NeUTQw4)O>P2u`5Y zkitB;7AF97UBV*X7Q88~R#_!`ncz@6DO(89l?b1UbbXjNgARm{zN(CCO=f4TXL+Cv z{N^}OV}gFzV!WmLDJ<k23*<rs2CP%hFXqL}WM>RNu<w?Gc0gi**)>hs_A{Ww95Wx% zubR&2wiX%w;D%IWdmA>Qz0&vjF!j)X+`}JV((sm}3#4ixJLBC;%%SXs16<IaUhH_% zxxyZPgHL>LT+U<&EskC|+)i<C(a2AlJ5L0G`>b5m%Y9f<&>aU7kvlHE6FDyu-{3eQ zYwcT7vT^E_&hh&Zti8-6htu)^svr+(&pB@1Fr!yb_oK-X1r|lwDSqmKko4pDmldh) zuj4A)UFjLKtbrpnCW#BNzU_|s-knKrzZV0CippeyYM*TKOg}9^;bUidwhh6P%|~wi ztNZ()P|+E%`Qpjn$ig>|@1Oa)Jkfqu|J{>|2fQLWX_zGz4R#Pd^z6FE#fO3JV?JNx z!Y_6?zO<Z++kM}7wXz`TXVP8g$X!QhY*U=csW|Zy-eFm83Z$&(@Q4GJ@ezMhy7=yz zw`5TbhTdL2(Ljw}v5VO)Ddx2mBMtPmUkR>t6pcv!&}=a>rIF8F@830ik=*op#VBLc zIWF(4rjl7?gJs@y<xSY*@RjenKp~C$dr4x}dx6TrUM~~a6NY2c4MOT0qPw{oF?}e0 z8MjrQVfj<W%TFcGA(e*_(Z=0F@RJ<|gL1d_$<l!2zonNon{q<NbPu{hMM4ho$~MyR z;{J`r8Qh?!#=|`cSL>Qs6?fxTBz6JD(PYNoB;eUpetdoLd(Y(OVL$<g*R6wdrzUFO zk6J;NhTLt+oFOk#0INpNb;>#33a7ZS$`RuQ?r=oENZ}4N{p>+!M5Mz!Qew^&<Y_T( z#R@dcv-!1krs>q^>Pns=-^)SI<M(qL3e?N?>YrN`33CI{!5>SXt9{I8yQ)`D*Tc*> zk^}G2J^6QTM1GsTLr|h`*3snCSGS#1qA8QkNHSjtKa!ZBmV?Tqh&dul`IU#^p>9di z0blJ=u9mlly#_6lM$#G||5(0q>&fq5E6)!-NvKyfI8tv^X!dGaLda}6ZBVvy!Pc<o zLU4&GOs_KGSIsH$8v<zcdySB0+=r$5lcqPLRowLYCzTPY4X=0s))Nbk1vX)vr0C|e zz7S^Wyh5m;H5<E|j}vwWx;&fOdw=}YRNzii(6MJgA+@H1^*aS;N-*q#$;Q+nsP#Q! zl7RN(Gk3;uh>2t`>oN4vBPK0jyn_g0Sn;q@=ATJ3BsI)4``(PYxU+OH+^Z9nPC3P| ze4-#2q<k-BIo`7Jzxii|N!{O`Ke?WT=v{Bfn*OT!QT6t?MW6BQBgT`{$$1eXmK~D% zjm~b{QS+*=Pu1MKnya8)=-lUab{AlqJMtuPVZ7xrTKO8La|5qo2c859>H^R!=%50x z=c8z&OA{P)(QxuceS3Lx>h#<UsCm50nKf!$Y1*Ku)=f*N&-CTv#43n`R=ozoR7raj z*Opf;%Ph=TB}@1N*fJuC{Elf$r!VXtM*)gKvE>J!0&<CDdAT|)z6B)|D#oWQ+D-Ec zw3BX2gFxSH>v=D*6_Q(pHZs=PO1xqi6Eax8!n5!qku3F*<hUvAXqlbZfT$)twMx+t zr;Gz7c8KrlJ(>zUQCU(!z}z^u<lGbXValt~TrA11=x|5<5!MV?FX_E_Mh~y_*qG}s znq2FOY%mp+1zSfMC{-Gq_8jHNsWnDaM!-RmW$<CsGfglzw-s3kCAX>tRTvE*O7s9g zdNdmIR=PcWk3`i@TcWY0>P7Pbd`P$$*hH0A^iodvJ8>~E#!p*Rc^oedD8@d`)P|`A z0F@(nAZI5rlH1H|S>JwGD11ftz-~d^?2&ozC1<w8H(Su5VT1C(%`8OAq9ac+?h!hM z<?b8y+~|GxWw(U3%aJS(LqEIgUQ~*F56Atg^cp%CtAa=ZJX1d5*%rrXkYH2|$^F=A zj-Am`Qb`0`8X4s2eICDjGa9UzxZOl1g~7k|`02hiM(AG~mzs4(YB=35@Qfu(i>89q z97=4bI4Xud0K5Wk@tDY9Nkt%I4IJv9V^2cCW(;E<0+y&r!AC_47>lZ}w)oPlyruS? zLDH*sMLu^~3NwNEX7e9kJrLPY>RzO(e?duIti{3C7b(g28*el&@Btd=8d^88uw#3N zWn+9+t^CC9&E36$>;oRCI_=F~*$E7jx;#_RxfkrswP8IK9*sq{HVY9Nvm2&uvoz6K zUPpLf00zLnRp&;L8(|s#Nb|_hUVmOJJwm0kD$b4DWfYww<~9unTZU%#W5W7j4;$5V zfjs;TWIO09s6DFZk(p%}s>(Z#56L3rbeOV4gNDgM{U7zrkvsx@i@Z8bnT3dMQ0K2V z`j>vxSIMotlp|<5S^r8H3C_X0-fJI>F7b4Dv-H7KIE*&Zv;TDPFit7#?&V}+X6~c) zsmT8(vlSLm4rb65*(pp{{qR)Fqq~l>4N251WuDLrdv=nK>O71#$%b)z>MFzD!&+uM zdF}%E0_Ie<+kxw@x>riQG%2Ydac$DMa`<p;H<lv9+M?kS`b88Qzob66oUJ1nQt9y* zh-3ul1`B$(r}wlikKQ{vGJzBOg2Tzih{6QWB*jl?TF5VMPW#i3|DM2~q8XkZ$?wTh zW$3)f!jO%Lb(N6OmnY^i5&otw8Qy7=t5$jjbPJcEr?%>_q(#r%^Re}L!aN}Dfhntx zR=3j?*!=eV-*PIhxm-U4W~SS!=YuE7;*Vwu<gN_a#P#4BrlV*x9^JX`J_1dpqE{*< zonfysd4yvJ@rV}ynt}K0*4wHvXJ2;28z;+9W|P=5w`;KYjyk~-AFA*KlHy;61c(D5 zmU)>6>sc!2ul(q7Dsi?G4A}}*`u+bwVIAc}7_EN+&=JY|w7~txt?rHl-S+Nefn^>d ze22Yk`?*Xe%Xd||+|S;st@!ed^Ts26k4=h9DhlE-K*?|8L$SL8$BS9dBilQ_bvL5~ z2-8j8hc2GE+ghrf8#9z1*f?w)WAOR=y4C_|28bAj@|&au_lAK7P%#g)^&|^V$Hd=} zBMC%ePn*Do2HG;%m|Q1SlvFDkXk{Tv;+B}ngN|TV<p0xus-v(|x@dohnJJP&YEYsx z?M>I0UeBefOr5T2=6%l2kL##W<_^HM1DcA0YunWLagJ)=>W^GrRY4pB*y`m3heHok zE_^%$mee*TYlh`~@OTGQqL+%9WDJmDH+*6n(jKk4s;;0*&N$dNJ~4QiMOJ4I+gIM% zp;?t#izIFV;eSZ+hAQ`jUdP4M9MJjo!_Z$|i>t%;pPh|gB8eH})G3+za0CzXnt^c5 ziUARba4Gter5?tzpaabrZ1YXLItQp(OI}c=M#SdYFj*brrI>u)DV<R(g)CJLC1aqd z)d#AcFxs|3r3Me7nUh>Yj`oeV)nByrxA;sCuYEow2$NUS;rOB!qPq%gzDtezD?;DE z(;N<K7%#cH3~(J6$7z=S&;FUEe)%%Rhfn)aVVMXF>vyrN50CfV&4Pmk?kaa*HRkFu zq%rT~&x-HXn9vj|(l65({&oq4Fcl8?54(s`4hcrn4$<-Q9K5*?!`y(^Y!g2_jqlbO zwxRP%Wd=T7CpYa+Hs#|qdh&!y#BkGtR&=r+z`w}f>Eltp(rA_ynrt=0tBI{k{KJ6V zrn&8xGSG*gPcvS07jbzl4f?W-Vx6ANgq5?829j+>m_3zV95M-1593iB=$|Q8{8dl~ z=f%m*^y}O_(fh{zZye#>fH)jL?kkXauv&-m$rN_8%Y~DrMDa*LWgviULCiv_hj4pW zgV2tL{@@47fT{tDnyb9nX`nihchH|bc$94}{L0Z5elU-eZXTfMS@G(|+D{HYKar4S zm~hfzqrSn)y-D|q?y#K|mhEcL0IL{ksjaZxEXHUl8oXMK#^S8#wL4-fgTqxeNVe<@ z>k36OJq*Rb0#y<+(?8pp<<%)|W-9IX|Gau)u3Y6$I*<P2C2;rBgW>smlDt<npUKZK zCHr2i_+|14h5+CsrWDYW!nR!w58@@||6yb3{|75oci4toIBPD=NgPm%W!u;SDXWv~ z6Q$8aUh2<!P5TuL6LB)k)3EXFWgeKfxV&~4%L?F>E0#^z32_hMi#jUp-CG|SG_CLy zD4l}4u5+WUPT(tvr4oy?iDkRSy&1{RJJ4#&l%w=364#FYvYT~R^CgEWHfGMHhNC2# z7cy_W3*)I3z?}_tRl$zEUE{Xc5+wR~l>gK%so4S)nA!_04Y&g8WB7S+qxqjKn{m5= z;w<AWpnfgO#t&#*i>HuyHOARk27cSF>C4QJaa5k(g0pcFTYZW8XMkwWVH90>KZ3!J zMFGi7Hg1h=KfX$+7j}6w-uifX>#A_~1{s}$yM+~e-k6&*E@p(~eFYHL`8Z`Yz(S^F zA{1DPVLT|bhOeBaZ~aN%1Rg|wwcNh~#j0Z#O%3|3c9=JB?u9i!FwTT_*zq6bQTDMj z0Mr;b+X6Z=_3g<TUCl+qkq1{y7cV7p;ZvYF5r2rmtI1%0O3N|}M4$tCH51rqj=d{4 zN|}qdR^TdwB`(okXWiCKi4m<(zHi-P?$@&MlWcSsueBdbU3db+eC1G%X4KlLNTFf` zuiK9U)%MiUt89thCcT(9dO74n69Pt2SDNz=GctHAzwn^e`@IY_W|#VXny&wvsQ#TA z-WyJ^5G=Kbzij#CoiCL~nUX2&XSW<CWO=b)+c@)FKqfOdtL6#LpsV#t{VA3mLp=&- zP02Fmy0i(rhy2(kBsMk>IN&d=Ng$)Qa7OuTEc~g}I4~=PjkP_g+r?5(;iW>M0$ywi zFVko>tBJCHaCu_Yd4uh;KdR@9lh9*{+S)<UtioAPd@l`CHpjJ->sJGA)aM&UW!dDD zHCKU#^yPMzR<sEok7XIJ0*zLIug`mq&v`4}RYK12AoepAb&eLl??*7+P1BZUug<^I zIfV*4R`c}5o!hcL7y1`Bm6pQ#<z|>-t93|<-Gkd~xI({fW27oPOTUV3(fH|&vI5_G zUezw#Awr-Io%gXL5G&egCfsR`%F-0BK#z0HVVn+=tT#>8&0(oIOFFJ+VTT2W*Fg5s zZ6iMR&o|_TS~gXB1g!V$ZjA$_2S}paU+SK~>6_2nT6J_uyy#)z4`Ro9O#Z95EX_UK zfsGqppEz;qYOE<g(8N#nnj7AbUsr80W~g@DDgk$k96T$AQ%uM_>Jk2<aOnq4Wnt25 zzC09#y!kfmGZ@4|1ipNeTB%6xhpv+zr;o|_^lQU$5}1B%NjpG3z;vG%un&AIj;a64 z)<wta*()3x;I$@Ynepj_69%y<KrQ5Dn_;|_8xU>Gi`vVx8U`A1*f#q&ObPhl$M&1u z#XG|~r?)$s!?KL(eeH8u4<@pt@5b{t@)`g>w3)2Q7|iMqWW}cxHSc*kv`i|14(qPs z4TmefQmU@zFf=j2hJM|gAeMCh^M<rsnXsn_ow!*OT?qx=>BFC8opcd?pAS;ZH};e4 zUXPxzkjBC9uFMFQqTK9+^6lm-#w7bPrTTa-pJ(x`0sspv3*jw*%$D+}*M~YvHTKx% zTR@E*Ht?(Fk{8$-L%5Uz4CnW=-o#tmW|`On0k&)_0O1QEUvT%Co`V0@cD<=;R(ri+ zlt9+#H9L`JvdOS&QDX6^R>#e<d_ydLiW!@ag0=JM8UX;>d$`ZgwQAKN6(n9lgKg{v zG(x^Mjs*?{3c}Ba|L|CQ!TX6W^6AIL(+aDZih*(RQ{v#Kb_?GMUjHhQcRr<ZJ`;+u zqlJ|(Q(Pae&TH>w=_7HfEg%(@l;ctX1$;m)uA9BZ#UX)M;V%b|3xP|ovao^V4?Gp_ z*x?Fe=d4(UOL&+o$-Z@)Jc53;{%=dEb<;FfxtVlWw~VDj!J#*+Izg~fF7jgRWjb6X z^vQT9Kv<sdt4ZV?G^IuRK6N)X>*l`qZqOamBS5`%G1&>=&sm-ya-ZPhEaXhVFO=rp zl+)Ai?PMeR5%iVYZ@Dthjo<NOiwPf;7D!@$?BIJwz93$B3Ki9rgT&ZL{XrF}rUXNZ zLpYIq+jw>7BxSc0<4w)*%~lU0*>nHphsWO5wUcMKHwt}}r+rB}2Lcm_tmIm0>xEn! zP8N1OOL>Ou<~`e{>t#d4jdbB|-jJio>FVX!ZF!|0m|oKHW*0f+3>AQHN~xG|Zj*(B zC>UX!47?qCNgw_@ru$3guR0?{%XQf=nU??U>Z;)$wd$YsKdSiFKw`lbVT_x7fA4`? z=G&z!e_vgZO2b{0{eGd;V^!Btox&B$c>!TK6T;rLFB_lMDd024LndxsT%I)wvXSc& zTAqKZeq_BV->q)ve3zKRLeiIDI~!rV*ni;H<}8CSydi-l{rLT$LiZ>FD95MoOx!i5 z6klwtvCkhhCh$rC0cdv<(+^omJ%Tz_$5Hvg$Bvl&Mn(PzF|%lYcVFkzT%v!qd3);3 zvx+2w%D7698Lp>_a7Z4<-KKr3So&e{M|F|N0bd3SgB~###_Mcm^^5jop5?y4_at75 z05-|$L{-ZCxT#+qbzAw271@x$_L{B<xgjV1$W!w!8LR4FgN2dDon8mK5!guvc?=bw z-P0Pt$;6YAgIjvGEA1h>CdUovuUYmtA1I<f7oYnIpX*1Z*vSEKXDol3Hf73TaM|_` zk8Vt)P1XIJyNYZHm+*5{UbQ>mCdht#yQ6}8fH1D{wtS+a;H;3KvyV54;??2nto5d4 zCbJ!n)sRut8GEqfnPsV`1A1;+Lz^MgBlg{5hi&ZLV2IP%WBvL$*+z?4M+I4~Y<^?{ zDSTEeX&9*Fb4TJwkJOlNz1efCD)NB}zpfE7mF=2pgWg0pn#`iiJ0E4-d}q;Fv~;G~ z?(Lsn??`rvTLrz_UXbt)_xS8Yhp$u|*d4k;KM7$~{Ybrgo%+W29B1Y7p$?$d9@~0= zMXbv*2{c~vy1OuAKBVhsX6$T@T<<M)WH3Cx-oCrbH|p42rM-x|takMWe^&MfydFu5 zp$e262AUdiU$IuHInv{?toeCR(iqTq^!{ieE)NoCDrA#ndD>==jM(eHdC6)dk~)0c zY~+g7=z)d&$AYofCvzyDD<Yix1jxVcovl)NcIWI<IXLUC(BBPMZiuRj$~3+tQ26oT zEfaW;V{(dD4*RoF{z(V1?_zleUyLDk3Bc)fwlV*&$PkDjy6DybSv}$Tm`Q>BJ)E{5 z@Z02>r$A=Grtg&TjTD_1201)M52!^`J?N_Z7~_g|vRBcm-P4iDrt2)};djfWR*3Q5 zl_NKPEnQMjXjfX#lmpnKY=HvOd_KcPH8>$zy+6Cn^edQ{FdqZS7DBx(89+5q<qvbF z`wN#F|4b}6#7#HdPx&bx;Z|)F{pxPIM5M=6%k=Mi=B3<XsDo=yc||*eYGS@IPXIqa z1C2A@z$e?!+^fOfT<$#c>3#<SePXwz+~m}mdDEDfR`Z6TnCZUQx&KF6J7iDvp82Mh ze52^fopk#9m<Ds5N>lUy4)z4DJjglvBy40S&Z6l^bx>T|x19^q+DfEoU5&`lqpl}S z!{>KA<)muXj3XMFUwTwPkJad=eP7)EE1#C|mekwGqiU5_i%kP0ZmVz@{kRiIo4fxs z2;a^8<1r7>Xv=-aVADLlX!Llc3)w^YSJJ0<z1Md)UO%{`bm`(>OjhTVq=(|A_rr|} zr<mrLwv2&?_6kvL+k&k4-j6f{z;W_J^_}sI_tke_Xq~!}ZebT8|44A9qcfHg?T9dK znvAT9kKu7p0^Bxtt2)1Ijz`3Jbc0AEJFPb)#*Nw9w<gx*KzA!kiglHIGiD=9E}%6_ zs%Ii3;%Y|rf+<3{Ud92CWc@u&0BdyNP8N1$Yd92!UCS?hW>#}f&tgMTYqdA~wk0|T zIXa)i*<QeWwK8GZuBzfiWmih~zh5bPaai}Uq<6)a;15bZNx{uZQI456lz_K#)oU_( z9}cuZRL+-QJK>k=$i9u`E7pxkd#HL((qu|UUi*^RkSyT+LrQhrUPf+b`Bn|>n%ChG zNNH?D!=`v3##Mag;hwqfb)Aznj)(}05hr-ePH>iErQ^zu%LToWdJ$YtPs8}zEx(cR zi@(=?(3cCnB_6)ZQQ@;#uXhcrw{QDoRIC%Q71e-aN<4>RYz&{%tyocwp7>XO_!n;O zHnMAFN1kvO;YsNSH?E%xngvOE?B{~}GkRKMSjQf>(GbCgT)kD;q_14=!u=6C!ppDP zNjBc>)SzDP9!gC%gC@&GMWgb2{VQ4bJ*yR@y6vxx#H)B+kM`=*z7<h_&8cKKpe^pk zT-YN%QpEjWyyS(5bI0!LJQ|OXv6!1_5V4+X0Rk+)gP0G>DWTCYlbKcbcjRgz?<Ff9 zmjNM+!k6Sd{aB20;}*ZvDhwkkrCRLR#P7fAa@e=}$J+}B*3GH^%t5stCzdn{PV5_q zDuDby%i=nEq61`vUymMT!&<8$5)VGK{Te3PwNlrgygTf8Jpur~qSib8z_mJXuX-)- zeA<$l>)2twgM;C8g;{&0VWfiVwSj!Jb=--}vH4gyR&I2YEOcUvt@xb|)>ptKm7W?| z+gXDg0uarw?Yb)fimBEVy(77RtPS4D=FJ5r|3&(nr$Ilm9WgwjcO(X65+ZX9_CwAx zC6+~Va|}J|SP}<4jyk_QVa{923IkDZ+XB|^T<6YC^KHTYF)tlr5>#ZXIZif&6jkna z^m+SFqSk}2wX6RemM^TMY95}<OW#yh>gf>;+J7J$e11%vmRJ%+nHHGt3YOj#B?51y z_MAxR7oxNPLGw&1&b}~7Zd^5CKRnxbe+ha;5{2yBsy&nwkEC{G$tw)fy#>hvrd_2n za-Ih{n|+<41ps_H_B~A>(`Fr<<{*06&n*<Ot8uVDL}2y{0QRyZzAX-64Glz+0`W(m zCznfgSLL1%owyvq!wgto%4?Q-e{6P!hOx-JoDM+h?uvrdGM+xEP|!3QVN&#Vy5S>f zyK$#W=dB7e)h4m6t|RoJhk)jy6FH8E+mpxXx9cu1@7IZxD)7OTHA~5#`$dRbSxIFo zqwmn!=0s;TEg0^wEpfmiw}mVm2H`j9>r9m|9v-w0;Wz8!sZzJ2U=D&s!VpreE;n5W z|CVwCt5hTwv5-U0`g6nSp;}g-z-B$$TJcd-dG1*lJIS(6FH6)P1=!jkJcTk2Vu66? zi*jgUu<8V643q9TXywO~7dN~jW3}v{o;GQ7vbD(hCsRK9+Fs+F0#NcY{{mj9k~0{g zA{*n(MttG;3nm4N8nh~C`~Z1jM3<q-HQv=bTTR$jlnAfCa|+xGm(6c4n%>1DfqlWR z-&I0e6tGuWAW$9G384i^&vj=|N;hm|dY!{#^h)4D>f|gg6vSt?-<|K8-_X8WHS|32 zUfBsE8F5#+-Cu6kq;)%7CUzZUJv~(MU{m>mndhWcl$}t&0iL@iPBs4|@Z{y)b$GP* z{9*M5v)OgFv>%3wSG1helNFV|(88`ZteLb<v4ce#PJw?o1X%5(4jL)L_)|w+HOvj1 zph5h6uE#%u9Ie7oWHe3`Y1oU&*Xvoz%@KhH7t?PBS3N8EQc|sBe`aPysdgQrh21Vn zre`Vb^$ci!>_;BEa8%*=-&yRQ%e!x0_|83UqZYRcDm<Y<rV#lKQ^9jAbZJ?CQQ`{n zcT;5;X&Ig&L9=>B(`)OWxG=xY7d24+0GT?{Kf+|`D2x)p^E6p0_bj=+t`f_2p6RS8 ze2&3c^$JPhr$GR|!`rrA$4bl0rC0e2gz8>o1M0=x>HT$p?QHu29^rxnMW}o+)ppBA zHJ<rq_#diF{gC{e=8B{~!L!ht0i5@{KN#JXUY?#%E^mF%p55`bx5B8wKsI&KwcOV3 zdHQsvS{6#|<*z0i`8O?ZkIrkOqw1jZTgpo1bhZW6Q|1|#CJyj9Zs@GyiPFUhm#f#t z_3>Rcoyoj&^`CLe%Y-@iCj%!Vcc6|ByFN-^w|W&+W#Z~01I`vu7M3zsv|px!g8%Cz z1S5Bj6zSwdILWWu-SQy-Faj4b%Ul`+V$sOGU!ju)ce_T@Muh4T!?MoL2z@YJEiXFX z@w<@0bfD&iNA{2N1GGb~pYRP)ez{fYnAISx=j@qx)OO<YIR~&h>*Wok!TF__sUdyS zenFN&t?P*wH0@pn7(nWsqHEa8-%jAKL1wQGnLj+Zyi&GP-rz-TVn2h{GR17{R-t!= z4F_##=silXwT3?)c~LKA{@oLs+6<6Znn8X_*m1evGeatF#g{LffAmqj4WeBlR%LWL z3t@B^8ieD^bLBoe*ysw^LaI&InuGe$D`18}`~CBQ^%;490t`jW<ia#gJP-Qk-OE>M z#=K0)d!&gl{_1?UM`U3%<fN~115OvJ^;~2Jq<*nM4WlLGs3qbiXb$Kni=$vs`C?2Y z)Rx5`53p2Vy<R3�z}LaSaVTtxRrH<+D3m3;hu!3Qi`6JENotbxOmT3SI7UT&Za< zSBhpA*{hZDo#$^))MG}G)HO%h`%W^LgC*SiOx=JG_yEtp_x*7dAoUqNKfO$8Rh2p# z<=77D*<L2%ZOko1oe)reD~3&S>lfdtleka$CoX8#v$!3o+^`ic+Gh*puT!UFCH5d; z9_|#cXS~sF)M=(@lPx%~^N1h{<|puha=9m82ozjo?G^$R4XzI1NF4H1$2!1`d8EGc zK#p`PCH3#0p-MfgL#Q{(eGk6QNa*0O@VGF^l5j*yorJ{_e7z1|-=+3GQ}W}-V?nIX zTV$?+d$8Ise)p-tB15=qQ4q7_m(VX%9sF;<$S^7sx|1pW%t2nhgVYo((}x_eXjil7 z5CLZjDcnjjY*lmIJPBa(zz&w6%Os*zHt!>5aFjdr`yw=!DCqW;I}CV9))5uA6IEUA z!M=x*v?N?Zpearxwqh!wgzA}og<p0O$T~y<0rGW8l31s(AB=G1kw^$u_?U^{Vsu<g zj%)B)HTqgL%BHM|pAnNd@7b3?l?w_v_TmHFpZxiYuAdH%u|hjE+D`9#n=lRu#xccX zm&Cpo{hKD3o);5&gwaO1%d9U>0c;g{NQz$>L2rviu_K5>=#ziKSD8$%nP4`)`Z7rO z)t~J$zcx{#D<p$KwG|z5{y?xNqjbTrw~MF=m3ufxQLKTAiV--A+)Ch49jQ}D*iyJA zBE4TH-*i~X@gVqoQYQSnovf|hwc1SG`~9a|^z8@jCUTx@^tVd;<1mIiCcj!fyAAkH zk4ilQy||{TwER`CEE6$`1QU_qXABvB^l620)0j~EDjr!qJH)k8Xmh5_d(xCI?=(MM z@f&jR4|Do`H$qkvwz(*JcxdMjargazs6JhPg~=b*is}qaapPB2FFx{wgo+#*4ucu0 zmD-vli8!lmaF!Ha^-EbKD|GhDHRj5N^h<N8Ibx<*;BDa%viy6VsP&~cX?0?;b>g<c zmvaWyO(<&Dg5}bl+S3Qn>AP<`>`7sG=Z{SW(|O!=Z$64Gf2S=%a4ZvWddYqTjzA$+ z?GRB1Jd&yn{dc?T!92Psh`N=l)gwUG@*>nWW?<Ezv^T|iYEg6tP-f9gM012hx{&}T z(kG{h*nA}3o%&}nWIVLzHWHSSqxwIJ&c&PQ|BvIlZ!WXVb?%!xxy)Uz+uWm?OD=`x zR&Lb@xm1QRcM}zgHWW%Vq9khW6g5&wx4Bd*^>r;$`R#Yk{(zmc%jf-izMrqhLm^V? zqPwQ3G$s3~(m#^sUycg*yAps7`_-$+R#OmXsPaRxqK`3W@ls~Jml87NsI$^0LXay^ z&VnPyaOpliQ5cY=Ld}%+&dzx0%1SW}cEOv-9#=>sNiKoh*EvEEr}Se1@;@f>1%GEX z6mtX!NF=GOK64k-QB~1JjwAqH#h<hO)^FHkYZucFpxV6vr~-RE1D5vob#%;~#7$S+ zo#Vl>*cg>hm~9iL8w*l69)`Y(DcULApQKG$>ln=|(fkvNZVCOu2P*yGU>l>AhGvNr z=+RA%{J@CRK9XEOsLT-(w&}ZcSg6X^P}O#zR9u_vvoOt0iNF9;`S0Irt4Ss*c+NCM zRX<zDM<e`WsEjmTrQOFOD?&p4*6mf291AEvM~gHa4{WXg9PYaVV2i<K4{kyCx`?4b zFmZ|AY`>*LgXTeNCYZ4Ui69PwjuVrdU7wRyTcTfx6AAe*F$6Oh68Q|B=YIHuUvu@Y z$0k5P1JLvdM=^|}f|ezrA(v8sQX?D{*hQ5fNelQdnbr{*m)V>4e$M`3T*AEbN|q*7 z+NeYm2}L0l``_2W?kMe$R0Sl=t#ZXD6LccpBrRFtQ`3Lzuq-v<RqqRZv1JK9hS4Q$ zsNHCo4hA4XpZn^U2OxI?1c6eS9}~Yzv=IsOX6R+!C#_ano&c3NB32QL9O50D^-C|! zZ$2K1UY~`<b5(>8&=w(dS>}vaq-p|CYA95mTenMa>c&^#GhTGhWSsOrHKX56ho(Nu z5l<;yX^_*wD~=%Ct2Lz(GfnnzB$W!}audx~XR%7N*wcRWingTZ2FNZt+Tw>zs9HTN zG~0M_fHI~z7k}!EBg*#}>h0QI#;*iD?yH||I8pqkN#E4|mpRq<#0)`cr}8e2ga zi!e+`FP*Ne-6<lKm8cT#sMLKuJ>g&QEfl-2SFc5f{7_V?y*KJ*?B#X5)Y~H&Ws~1U z)dO_!bqXFTxu&X3c+;R4Cukh^W*=3(P}y#N+cl0z8A;`|p9(Eg^77O_0;it6p}9)i zvq7)NaoR7u^zcbRt+N+2_$L9lp(4xuI1D1-Gddw4uGJB}#Aaq-KV=1I{Pg`<fX(;c zYPvity$`QkU7{ky`HtN?fr4DR0F=FzvMa4>*L7f_Azqa=R5&>&--MR_fh-X;$*<2^ zu1xP#?iUlQKL)DOtPuXTaVli+B!H-@)GNK(d-PN&$3*T7A@q)gp_a*G{qH;p7)R^} z-Bx+$ezf*clt3PBn`da}x)(sNC!~fJ0T8Q1oNZv-9Wcsei+Lg@`KwICv_*PgU|p(f zN=u>i1y24mAy9IbTHon)8+a)fD4Pf?><LQ~78J(6k4?3tJ;s(?zgDHoap{O(1}y57 zE&RbE6F!EzX8B?n4YE<3QiA{$-<KBcvyzoO)X`H~L<7bHw#3i-T3_Q)i|mT^RMm1v zRf9mhc-CHb=C$cWyNkc9Eyxv*z@Kx!iFxkUSV~gcWm2bo@Yenz)e(HP8Ap{D`Zz4p z>%?xoO_Ef~Y=K9b?!HXvsFk<Xnf?`_31tv>+Qwfel42XfBqkF@o<9Jj-gW}g#dnyq zEIjYv?4xy#loIK(L5hMW{xZ{Cc5Z9MdaoAlc8x)v?GCGa+KH;~%BZN%xi5omw>Zx~ zFY>Roe00WoEUm(SKYEJDr0%;vgd6>Iuq%C7)vR~MDpc9lM3xV1xVq`P*?Z|A^z4Hy zMWu+-sO_;45!nFz8Ht-kdn1fm7O)r0RcG=NUTFth!?OmR>xA;RbyAyjtenOywn?gE zFXzY!N4ZJB-SGr1>nF{-n#2Hjpt-KrpPaoX-()*AUAaR=AMvyXIfsH^*Cebf%F`tk z&)p=c5gkC77F<{3p`pDlDfU9-dpg!S=l0c3ulh_ZFJ12XNI~~8=}yC*@*SAezX#(N zQcd5ZJYv)vKYZ7@`AHIctnOb)qYO}GH4`N{mQ|K1Pvb~Uy4c*uAsft+!{=-^sQul5 z!;A7->s7W=a}t0|&y7^{?*9e>xN|?faT0iR*eFsVtR<<lWxvwRY>&aDs66GIrlOP~ z^)n6(vckSzmB+JaGg%pxb%h4(0p205$4tYwQ0eNb%F=84ouP8MF#oC`qp*W=arGwp z9OIWqHLJU2H}@&NyXvtDRFPG`TnYr_bxBQ96n}EFPpYA21CehhwaB+540Spzy3xO! zvm!ijZ+(Xzo1^~_Qx7ecgGmr6<;LXbWN}W~n|ZO^QK;s-cPsS{);myzKeI9>nW_q* zs$Di`>Ve9LSUtog6;UzK{XKqf=ggKKzvv*zUk;)j&z6n*?ZR_yRpK0x`tSG;IA9M6 zQ=KFyepv`wFa9V5kaOzuE@-_BLQT@e^ikS>a?l#Pul&VbX}-`A6xR==i|uQ=ikpC4 zW@8X)=;`%XWKT=%zG=VP(|)HTl%8Y%t-rfs@9+<3{CigQsfX06vXX=>sfF{w@m&G0 z;H*0*zQZv66HvM`)ab%n|F2mt>B?<0>6Yd;nmv*>isF;3Oj$BVdYyChjD@1-Y|tvu zQzO6T7-;o<Dnp8PeLM0nrDfG`EGNm*>fr&%_<_5S->CLvyv7b3Ag&B3Nk_R5H2$qk z7maT`1W1`re8wq%J+z~JO<$>xqiWcpvfeYi_3p#H(WBfZ*#Ud!XJp}9p#_@HUiwp& zidRevm0Ae1oc;Wl3bOuQDoMkuNYBbGkTQh`XC1uCI#9Ng-OoFzB}$oJy83#2AUmcn z`{@A6VsFf^`!n|y*o8MS{#iI#GV(2ZU_KE~R>dhmCC#{Owo4#P^k65Sb;&4C+}*7G z$hZRlYZ~)*q_uvy6z5o=<lfdWTCU@BJ!n)CV3WK<`S@GzhpI-<*Ott+AyWn8#Hy5u zZ!d2iG_P}e5MO^vSJCq5RNbE9u49VkN7o3Mldn7v-Q9_s=_^3K@f7ax4`2J}IHXl; zA9;BGtlgW~8MC6~?;y7!%fs5<V++0I*>SH7Q?EIF$v%Hgn8=>`3ZUsvwuV~=5q`XO zoRm<pjh9FQp42J5Vs&K&;5Po-6kr}A`4K4XR$Qc;50KG=xSiryCxc{uJ9ek65YxM` zCIJLWy<U#EaU9lVT!SR_Dkbdbt*gKO6Z99V?tj=loUs$~Z*Akcszt`FyZVkt4G!)P z`;#?kT5a}a@|s_uxy%8-&>RuN6Xt6#0z%KcD6;RNo_lt%L;#`_#;NNv08|%fkNucN z`K!G2NU3LPr+}<+J<ei%q3t=P@>01Fv}9Fe3F#ANrzB~q%tekq&3S!9@%~)}l}pXZ zd2-PeFK5bIltC_X_a|UZn9TLNhfdHnyo1$-a<<?JAqeS_swfGF3;wzJI@C#0Bx^+O z_MbZ?sVSeDKi8iA`DMZb@aJTK`L`BFlx|c+KgxK%Xx`^6dF9m=tGPcHQRX0tyygRM z7qav1UndUYvR}vbi<@i-=G=_dc;`6<)M)im^^uX2a`|eX28WEt09=oo=UeJf2G<r( zx??TgSI#S!zn*Pj0f;X05$P!;rYa!LWx@3(kl-eFRzoB*_C(V)7`AAk3?XH)P<Hi1 zkQNArr53oqJ)Q(;L!X4m&kd>`GhBC8my*wN+rcKi|MIy{+;VBTU$JWK8R0&FkFu*; za2z76XNDJ>6P*uEd8tbsXx=sBd-aR&IL$|F7rW%KAbW%Yn!Wy;mgi-9ThA1=t7V~l zm&<8Pji>#!N;MQ<469XYU{(>|C(~d>a%+FQx~bnjc`%u&68IMLgM~}-aFa`oc;Fi2 zTC#mGE|ZQ2W3x7g6i)<aafCDa^tS8!lqC<o0Gw0i#w$+o;wEM>=1~JISHrD^U0eN6 zt*<QK*=JY9==YE-keo-3R4uh#@oHN0-)qO^l2N|9JUWneEdui1Cfm<X*Rqa;u0AnV zJr2GY^qSgGx~r64IToUEA*D!jE5dhr=eaQg0}_uGuNw|$MZPnSRQke!D+eo)lig;H zyC9UQXvrTlw~D_VlsloZDwLB=ArT)A{nRq*IlFyGty=)=m3Oi@P7S&w?awV}U?!l8 z*bv=Dl_~&FwU#*OaE+83wA`=Y(98JZ?JE7EwM2RyLAeI=l@VF-JQAi`*m{<OJ*K0s zuULlHq~Y5?8lV7a7_V`Yz9OF&1u`!Rd(rO&u$54TtL^U*<)<(0i;4_1T3W$49t%c{ zDm=DdQcn1ZGMylJL{5s_#g_qy9;g~Ub*=wl<#U9kjzoN5fKu|3S+D)?mC{u2QZvd# zX-0~g?AJxO(I%_-EP7t4dM8i%E2|F~)$&8Ss?v4oT3u;y5Lp$Q7Ah`Nfean1my6T! zYf`FsP_zh^tKqxmc{g0_Q9?#}^dn4ID{6-Z1ZfmH1i)yhA0<whD5Z|!I;n7n(^_X# zMAUJW3xm%p#ME2z9hEGk;Fd-4MJBXtg;z~i4NTPN89Iz^kT$}iCLdS43BoF1xWv;O z>dD^_HemGG+23m#M)zGkpH7q}u(MPJi>`J-v-u~BzzR<UE*V{<<~lxD_EshHaoA_^ zncl2jbqa++>zra!#4g_%e$9`z_zUfxj!sJME*5E|{KYQ`7nxsjl*oAIt~{ZYo7VrT z#9e+l+UfKH7_xIWH~*oL+NeYj?a2MP<y_k+DfOADYpVOo;g)o~xXB0z&}O#J@Vl1S zXGVSZ9G7J#d8=eCuH5lG9kGNh+IRX-W5}<^uZo0;;KDKl(9Ov|%W_m$T!d@5w4#n* zo=beo(y`Qwoba&KNmhK}Dnzv7{2n_i-mYMbGw?;wd}sCFP0reB0UpKEP=m=gAJ<Fb zMaga;Nq@=!zB_vC$JWn#@|k0=ySWZF4W*{e-o;1k=ixT=CslF%M`GHW4FG=-2p2b} zz|q&2^cye$pfp2nI)-PuTSHtl&dpN&Tn*KhdwaR~w(5)i{6jjD3V(=9vys-4AYz!@ zInT$o8aoG(*D9fR{8C*k42@CG3#Rn9I-RsVS0-2`n(8RB2kO@x#%J31?gLL3BhLxA z5w$^DxPhTLh4ZzuU8!`HxuVj^X5KvVq*E;viSJw-v=!h{#HV?s%x<_axj+#CWR;XV z!3k-<JkLn^;8)qOT*C0~P{cI34_zY!xZYkx-l<e?tUW}_Qm)P$w0<gVG71w_W*@|E z2tV-;o1?;_>SozIF7O)gYzU5@P*3BaC{~reoIS_%9nH*&$EGl=L>PeB{Un-_g^C6c zDY~H|8oqTmuv;q9rfLsKtY@cV)bmR|C*@r~u7w)0J6^UTV3G-;$1??rr(PofJBHx{ zCvx%}t0pV77!b9d>Cy0B2u6fZy7ij>^SSlEUXfUYx@_*Twa_h6u`5npcHZjU$d4kE zGx}hkU6+Etzn653j0;!krb2bvfq)_ltbU!X0U-CI_rvxJ(ZA8o!CJ_<%l2gP_fr_0 zUOd!JTy5&`oA*r@H*RW)L?7C{uUNI4@5$%7bnXAzA>N5Y6fezW93~%C6Q-n@=n~x1 zX0pn)ek+1N>b7X%-KRoROFFMX;c@^|Yl>8I@^Zb>2^E*nz)X>lrGAAMc}riD;|o&F z>h%Jir5zCVlf$hX<*ARl3SB})gQHgEFA|3=!pvoBfjs?DMD?S!uy%6kPME^EYwLw7 znJ~rB@Aw-OCrSE@(@G@r^zO-i<xV1EvudF#-RhEeF!I~uXESDpHXK#5s9=C}-&)s8 z^WE~sx1E-9tpw)#xL+<f+>>p<P$`IH?wZ!mJrT%<0J>eu)9v@^%!mCrXS2=F#DwnM za#cF6cEYlNCql?P)_F`eC6(TYRsQDxYN&C~o1#>G7wH-z#XQ#-6-?O7eb68L<1!FH znTm0`S(9t4(z|QVe<rFG=xl{0oPES~4!VE_W#GaeL4(F8VZlU1Ehi|lKFECz{<$u7 zCPG62n0kE{Vj+MQQ4_ZB#1^q(F)T#wXG`!pjKI{2hWL*phwQvE#)J#v9?E5#=txE; zi*^f0&dkI=T=8m}!~hPt!4nhG>Ka&L>wFZKc&3kwd?|+;Cy4h8)UG&rKj(=G8GM}t z)EYtj8Q-glB32`_D}E(;jVN}Pg)I7cg6JgHPCxZ?SbUfVj}yR?1Wp-^up2n|9<Hdq zA5&7!x!{z=t8+1$WeU%yoZ~5}4tMjS!Lc`hfDoEuY#rvPT3YP70=_cs=Q%6rlv0!$ zBDsM$8Hx}tci+7SD+gqob{4ecVU`3akh3V4C+6lVF>~$zsL>6A!~jKNn}Y1&iB{7@ zZ}CJEErjE@mmkJ!4)A{tS_fN9rA?$=IRCBjk^K~zXUpP4CdgPhx%xWPbDYR3;S|yA z)D}go6dnEZ6qe0{qE1B^-o?c55HuRBh-LowGZTU+{rsFhIVc}UK=?(b!U7{=!HC0D zuqOo`h|7|nP`ogr>7k~i_Zh0yX~e8YAE$>T9DrJ0B;2$*r?DluK^H0Jp%y3-$6P4Y zeDOtqgiSnBAjBL3@aK4NE>W~cAj;)3o^Zu(_KV))!wY$$9W2xn;!)75IDm-!I7|)8 zv+4GUN_Z8eFe}%?E2)41?(*OhVZMqO->U+ji@dPhQ|b?$o&8TrhAjkbho@rWSq?A+ zi3RrdhAZY_QcTOXPa<}LsAXr%HN!XZMLAk+!)We3t5|@P##UuZ%I=+I(UUmw*SQjg zyOE1Lsmoi&6U!(rTO<;TdK50oV2d<^P>%qp3xM<M%i@aWGRja<>PWJ${H`ENkL6Qx zuHm9Byb{Pgk5!s@6yU<!e$1eT$T`*_I<HhxJ3Nhu2%^9}awNZ+8qtXdR4-y2?!x1j z;d=>|`8;R}S5YY?A%vFJ)R>k-hZn5vtDQ!KvMQ%nU@_G6gt`LO{VU<QDp))v2O@Hd z8ZhKasbY(NMk7t`vjsHdB3rD1i#mC?uxt=n+=f~pNC+u+t<AcA@gmQOdUfl#>sM`0 z$Jc$XMD3hIqg<S#SC>mzT+8H5Og!a61Wp7uqR$FVu?J~*CP_Av5Fu<>W2VBpNsB|$ zei<yKk0NQ<_=J$vj749>3-bPDk^QMut0L0^RBy=EddMI7Yu2YwzW`F(EW}^lk>f8> z&M6XRqii7%_%rR;I)(FA2)HFs%MPH7%E_&Fir3I$HGI7gjNJWjM}tT??XD)*=OT~p zdo+eQ&9E}wnAR%;<&U#rmuN6EIz$@)xu#|RRI(<R58KX;*WegTR>6HX<l|YGDf3uM z3WQFK^qs^!@I%B<;3uTDssj)q8wsLbuBWE7f-Ep6)y{==3B9k%!m@e;6_vMfWM>{N zwn#&s=o0eM8oQ{-^Jak+nt@_DVsii+pH?p{IQKEFsWDRa7WZILSJQL87)!R<Ko8YH z6p7-($5t`?Ed>@2>PUcS(;-YE-1QT7z8}h>2Dv^qXl{k05wI5w_^WoztTzI?2%AnY zymGX5fAtNj0Dg4t#xE1%(n9`I{Qg5T=(Q>0skZbn>pNkeS}qe|u18P*VJChOAg3Qo zIiyQeQ5i|e#qO=vT(;O-uCB6z%+NV;g0yT;dBw_OxiNYM*fn}o$aUqPday_G6cNtk zLY;_UGa8i1wG3D@2%#b7B!khhdC@G`m3s>CFX1TwL?FS^51PNz;dc+8o)C4QZHSY9 zIUs@17<}jge0>0&y9^7Z_`~kN#xI;SOTT|+L-HS6B3noh<{kOU78g>Cr_+$c*sjl9 zj&rEV9EI%Ki>$}t0xfY~yHQ)z(44fSF@WfEp16_B?Jc6u7EQb&Sx<=Jq;lai>K8_u z>*;}Db0UO7K=_|jubfCZ;gLBZ-FlW7Zf}vvUb#*_qUec^JM<CSaTlX)8L8#c=`D*0 zA)JhED;v`Cj{#tkJ7D+NS1R8;qB~uSuokUkANkA^a+5_D2@>xCjW4;Vi(I6;mzTP_ z#1kG>rCN8LF4FND*QwsI1`s9nNAWyFI(X+B)zo(`5#Uio`87AmY(D%L9d?tAaHEQ( z;CzpUUmu4!&>r+W^Mw;Z4+AwH-cELbZdssHYwLd<xQ`*`EW-@oS2Ee1V5cj&L`%Z9 z)xQUW|D3K#I*NAl5$n|QzckT)3d-Tzou+M`<AmzD1G-nTsBieiec=biCS^t`K3&aC zr;UBg4`j5RN5vsTqJ>{58_6_E#BmCOBa~K3-W9>#z`w${tjZs9QUFj7Gywtr=MC=4 z?sFAabXO{S@YA6>%7|yZzjj1xpg=f9g-B*1DxN$F3VMQBK>g!N)Dk4BS%?49g`8=W z=wtSq-|j8DdYxNQZC0qK+~Q|!-3}Yu9l<niSgP;7iP{)V_7O{bgzD7ALbdQ<bu8$g zw99xePn+v-RI7+toJa=Sl0nUUlkc32tBK({RDXt_pf+4L-n*yz0DuqO7{O?}roFG& zr-6W-U^$F)Izt6zC2z_?3J7wcPh{;56M97wUn0KnP>n3Hs4?E>WnIkME~j4P20>K* z#n>Aw91N5j93K@@W@_6${AkyR`2nmI6wt#(T$l7c{9Mv-2*IJi4&(TIO$YH2%(Dg< zanjTA)Ae`(oGyS_P$3z(7fj;Q^yYzu1!&*Ijh|{p$N32HajgelkIeiFmNXIJ)cbPE zucRST12oYo7ttNAcq37D=h}^-moy1f+@y5m<O{C&<07)x#AMrU)I~bZcs$vn9jRHp z>*Omr{>b@vw!2n%h-h}olQ79a4STw4e*vK2O@)2Ac*6DGATw`7GF4%FjGhiaII|;8 z2vU*=`H-3$@6DC6MG(P))cka<Yw(u|8*MOC*cIZFgm-Vnz`Vaiw;i-t9}%e=s9M}7 zHP1y=3dEg58~22|GyBATFORA0K|W`R=x$6$^qT(Wix_rXdIA>RUF_2lCN@GB3&Q!9 zwn~=F>X)o!Bmm$+JVY{W=JkUb${aj+dFJ;Y82_q84)<Ot0D;+72nKY97?gbuOXK+= z&Y}kgJ}DiiKzE9tpfdnZPIWw@eSd5C?`@=Yl}ta1#TM_TBE`no8O0(~lu6Ag<Zm8A zp~HQRD|SU~{BC~kvS@~ynpz358)t#MMvTg4!#<uKp{A?PsmGn?M{~HaaJm8IToB8Z z`O)V<^=E}twsS%`G(!NJ-M$`7gy+y>zCIX8rWg&b#AXOmuLe{OXkCe6h2$<nLkS}B zZLs@)=87bYcjyv~DbzcjNb7^bnRhzsf5j`LZ#i*LEW$!-d9Pykdv#~g!sKyFq^PRe zp||3q!)#PBFJ)v(QhFG=5g<z8f!uhYL;TCHxATsbE7VPB9M}k-%F#GW(>yRfI(A-( z!Jge|&`-mb)t;%Zy`P)53NrXJi3sMx7$t+JK8oz{m5W1uob@IR@KJx+5~p#fKLTX& zq|QsCL?xit&6w)miru@*MztmRxsu~=w7S-BZ%gH~O94)o_+sg^&}_Q89?(8ljvvi} zAI6CW0KiT(&>kKlUqAMB9p=3}e9}Gkqqm_82!Y*%#_KM{EVK4qANceI9;^29C+N|3 zztQ&v=tjd_E&=wC_x6*@x`3l{n<fgNi2p;2rEyXCns)+PBgpTl&Kc2GwtFl1#Fc^f zfDG}p%W@BGJTPstUAT-(RQwD}B!u#GutD;R(%m9UPZk?uM&u@NVaMq+lye$8bQWyj zs<4q{nSO)ctD+D>H&nrwtw_SI7d?)yfP2~cozRS9{DWS@YL9EJSE{-ZS|!Ta65ps2 zFW4gY`N##HPO&$tA1$^)G?6TtY!HZ^?J{w$6$vulGv#>+r}p7DvH1D&_|}Zr76IAF zhgwZ${Hsy#hl;!#K<q*HI8tD_XpJiE*e~<&{#pycC5r<FU{6-fYiaoNiie#unLVVm z1Idp=>u%(Nw_tcg3}C`A*8lL#T-D*755~t@(PE{h;+J_SK<1Yh_OYLbzDvp82<b?D z*BSrq6ZgH2|Jq%z{z{B`k5|`v<dbWA7e?ZKTjMWX@Q!SY*ory!xG{ET#>lm2_50&w zZDg%Y(pLaL!FN&EO8xehWUVtUOHKzYWezaKtM(M!@;$hg!&0?L=|1~+PaaE-7(ci0 zx*T4r>Hx@sq|R?N&se5@P0{t0*1-`0o1iepJ-%um0|)^TJImxOi5LfoDTF7EbRH@% zDm}zMLW=$K1*&{-J!<mm-YYIO2RC9~-VA>9^2yT=)_cE90xO+PyvK!pX$f|0;vRI0 zpHoYCGyGVl=ZJ!-{d0K!>tU99hxv2=Z{80hbRU>rdU?*<AoY1b{<(|AffoM3KiAi{ ze3F#yHa6bMPvw+cu}c55EwWH*Cn@q#)KKAdKho|eH@x(A?aVxyu+wd|fOO!k)}yuJ z5MYCypM+f!M4p>EhQGObgGF9K>!alk+l~<klJP49l8#4&(-S?@1u;uB22y5hzjai3 zy2Q!EUGri@o4fV_Q(+C1vNcv7^!xSqinF4Uu#54yxoe&CUniX9j$eL~rx>9jRD>NN z#t5bG#L%1v6})eTmqL`vTx<7wj%s&DRLeue?dG=KA5NSW6@6G=@wiSGkr~4;Ho}!b zB&;MjUV|{@0d)yWiCGZ9;XMF=68nYq%GDRmS8r<f9q;eyF8KZJw$l`)e?Tr)U!P@n z#7P|RL``hI&?VVypx}wccHhN}+J?IaV{Z>y9D4QR{!z)ZJ3>)e`PtviuyQZ<Ec}Ak z$m|iT<DZ(3SjD?wVB=<Gql~V&>eQ2mk1eD+T|M9TB=^GMg;t2x1;7Zi!Vp2yo3rsP zpKc^|PNSMomRbYFmU}YQ^Gz=U=pt@it9lZ)>q3c5r|(cW>R%j94dvstH_*wFM_m{Q z0_qNk*{tfdMD<CEI3kDR5?jmkLB<ioV-}7P#qR$?T@T&7_o*xP_JR52nv5{cs_b4q zUYPV+;d5#OT$<r^^Lgno$uqUBrxeqOD+rB8z!8_KWB>QiW;TXu$?x%ey&!icAk1Cy zD!TZYnN!*I|4LdX1$*X;9lBq$D7kD7Oje_{-eG44@I|fo;rl#r@}nYdFNzpal5KDY z;MFfCweeeiQC~v$WmKQ<`dq0Z>W&wh*qt|H;;8QonF+Jswod<k?{n?J<A1A;ojdbq zB0~P`Q~YO@G}sqL#hDBFI{)SkCx+i2T|WYqJ5!Nae)w2hm8*71ycG$$EPl7r#hwMc zA2-!!R}nrHeL76_kN!vWk(J9CCY?;9ZjPimwhtXZ6R}JglweRC<vbhe$jh3TKo$uL zn2<%Z4(?J{n7Ns^YU(1~*?$DyGZ9e9)Hkbhsfa#^HS2HDBO1iSR{H&FuyWS(D>GZl zo2+Q4C|oN8EB$eU8z{AwcIJ#)NzB6jE;$$P97BMmx0c^Ltd3Vcvs5Sb(M!birD<^> zmm^pDZ6EFuFuw+ulhBkY7@Q&^IB_jy;vk6pJ|blD02v+Lgi`MkK(qingl0Hd=NOMc z9uUfgN5O~UDxnk0Xz^q~SeWQ@a>IBNnh;Yhw~Fq0f^JRA+XR)p>@8^toTwajy7nq> ztMvFrIJSBjzMG$E5xt%*eXR*<#=}bx@`d$3#UX-OTk)~6aJh;~_|EU)+e>kcHoBuj zW>I)ik4mzt4rVG5+Y2QtIfuFFjt{8)lp0UU6k}3ZEyPBO&jwz^okG?V(4ihJq2g4b z>)HiCmn`Dd6I)5aU)AIgvpch?(R}=^grqz}h}zX54+wUZm8S^JaydWhD04xxM`Ev9 zOdc=9B*)sf&bv@K+-A_)D!yc`27K(#2*aYid_0XN>`sixnGaN95}vBdulv9rebSNK zU0k>C-GqxtlyF~s#8J9KAmQQH2Q{DmOkqNh5M=Xxi?~_z@x}ehm*+<6B1W8x=uVmE z=nM>(4V6C+1jJFZWh>ZFADw|_rG?$)$)RZ7cbtNMXoU5cj?U0__TjTB9&$2sF6RR4 zA|+>Yo*;B3y)=$^B|SLwzV4IC^B9J;No!G}XSvb>#Z`Tvw=}gAB=s8NYWE3P`1^IN zN(cLg(l-3u>C2Fkod?vnisP^IJITkb>zA`sf6)B9L4d5hwj04~j&L$Pr-6zWRaxSG zusofKVe0gw>1x^PiER<KEK<bZEIsjSqNr3FIE37PabBj6Vt(%G1jq|+ZkCnGDl1xT zxMzw3nqs|{jujl}o?}y2RC{?&<{`bM2}+j7irB+eb-h9UiCMC(0lCN5<1rTA^YTxp z6_e(zijN@bOV}e4hobSNsZoxq4P23hg|0%<dV~Fc$j9mPQXjUt(&9`W*o$)E6NfdW z|1aJVw?G8T0@zR&ex|tAn=GZb?1&6{;MkvVZ=*_C9rlJ8e|6QCD7~vc2k7LvLQ_|; z8%m`Lb|NFMQ{Gqxjl1c?lA7}Oc($&9WLhaqv(hJ}0Sk31@3}*AUwR8YD`n)m=`NL@ z@Fl5Mj;hKNOpCjm($qyq)h7a|ou#puKX%(Xp$@VKBww3*wO8VwZ3N_w-H``#!(t)R z1*-NJ`TQvU$s$Uh$R1u6^SCcaot2rne+!20^*nMGs{&Z9t5dd6h>9U3qKjXW!`|r_ zRYW^Yn$$1}6`Nw(vPlD)$DPB@DabUk;SO<QrJ)0JO0NLJR%cE3rY&Vjw=Xgbsqv!z z3w4TpJceZsC&8beC36WKZnR(=@$c_`)y|agIow5}%lfR{;aqn5py!nbVf#>9fep<& zL*G?x@;;64&tH&bWHF=?*${c;V+Ec`)cdV{AM)Od;UX4t1Nx)|p4(jfNS}uzeHQsb zF}qRw;i-p5Z_l{~yQr;ug(vu$%3c<@nvv}#%7)XFCU1sonHh^j(CefVDxGzSnPU5> zYEoSzuJ$hYxTM?$jY^(#YTzVKzx!y<Qm{3otoA-Bt~aSQ=E>)MYgg<DT5#fSvPhQX z2`*fX51_nWTc;;;D4VDv6;V%l^+SNlCXCIKL>%E5g1YC%e;?qFUPh?j^>70LEJB87 zw=l7^c2%WUow<&=rX>kW;i~I=SKGKURBDBf(mI=Y>NS+&rd`$~!CHh2c<m4`OvA3G zlul<88`kn$Q!1z93y{{xziBEWU{S5S7Fq6{Q3asZNcNpd8L{SU{lzMN6z3rTK#yg( z*xbylH_&Kn4kF9cdV`&ajD5S#u|*%@q{&*N2G(fi869SVKsa6Jq~+zt=H*5$=juY> zb7*Ev=k>^d+%tSe0Gb)eQ#{Joi>YLK@>L@@udsL}o`|mhDs$tka^NN!2x-&C8(;@F z@T>d0>xYnB97CTAz61m)6F{l;HL_SztB+;}fMJHnmWjLi^#ONrSM|YFf<{}J!${U+ z!i6VISx$7>|DN2$YYciPBIVW~F3a#}UT)eVd@mYKt0V{9*@4Ak;k%0RQb-b}w&h2c z2ag5_F^6zZw_G!Z)b9I?aGp9Wf#}NV|8>1IR-Iu+1Gy2-2Yl%_d%!vItx#yM!EN^3 zLlodfz(g+iu1@dg-3-|@d%>uTjJ`tV4X%HtjjNABttj|PTeX_;;Mw)zsgau*IB-A! zJesQKRtX=v)OWDmIdyma{4{)OP3yA&c7&I6EU*5|*6vjh%GN#Kj5c(%sI(xzv~VKZ zQQ-KZ^LFL^%A4ro;<ijhO11-4?9npbW#qimNzxgc2QpsZ0k@m-W<^%ZAoYW_!%+;q zMX@hiSu+K)(%ZvL!UGkqBLk4*LA`D?2Mw8K#?y8jeidHiihCSyg8NTH3uz^(e5jD+ zX@$R$O5JtFP3b>=t`{JiwA`36`J|@^`(QPT#8-|RbGc1zHnd{k)C!aqP1&1SYBZUL z=ra9)hXRpWC$XX-1bUCBfh7%0BFK)QAxq$bklz@`<=!MfU$gIcllaInE9kyTc;X^_ z<Bs#~M29r2#MT#Be9E=23XQ1%i*L*KJ%}Rx?jj*XusPa2ieX2d28r%=?F}j>Jpo&@ z(N#ct*JidYx2nrZjOcci90iis0ojZcsn(4NqB$}vHEij}^X|2mu8R+_iY(bS1f6l? z<%d&2<Nwx&Ggz?w(@;+e^Q<7pXL^UZc%6BBYJ8Ie5A9^65~Yr@nGtVuTkF)>yKXP@ znV!p8@Svw6S$4f&LH$8ZFA4aU?%+#h@+a@yzD+B@06~g?Y(kWnwEMG-qW1ML&LLw3 z58I+k<RbF)z`kybQB$q?GDLs%nO5<hj6BKxM2r24@I(RQcmU-W`2KM^>|IMPyqIFF zp<P7K{%ve${-?t-t+8Sn`pmijy&+=Ll3i%*`D~OYhb*)qjF~wOi-{x4(}au1mS=r* z*|TCY@+ub#hVQ)bvgvffAA^_+A4TVij1kUFiIbj4aypm!_8d%DYIC9Iq`QIja~$;6 zb3+AM%*EVUs>EGs$6~^cHpt15#jf{Q9*GDj{YkTXxc=gmB4Zl|F>LbT;F=TGd~(!0 zyFd)MP4V3kFtRKYM}1H?Z5fO&b0Xe!z^V}lbuSO9jIxWuo3k`(AOIFJoj;YN-1mW; z6B@vDVKXn>VESypXk3`^kd_?%!Y@hjjC1*y7z=TO{BVlT+PTYSfQh5+yPV`-hH17; z@{Hhz3eDVZM<^Fth8Nn6fXopfdA0#Zhtc2d#|CDr$lO$gf=}4B(~7y<Z?7IHyAT%k zs`~qbf^B%zG9v>4_ixJaA;N!(?T#IRye+zDET0p=q7>6|Q|XY1C@E{<K?c(`@05+! zG~K2>H3aNHPKN7DG>x*k_zMe-cd4cmv;woW(tZtD)RKns%)K5e!+H@!va*_wzWMcr z*{iz!MgiH2#td7cw_`xIf0NZE=eG~nnDu067=d|q5e(9V4Jyufu$h~)u&99Cd_cgp z8aQP-=PzF542uzhmJS|gx<qB?6!SK}ijZj_Ln`CCqNR-t@;=~vN90ROF1i?xEC<mY zx@8(#fw)Z&PT_SAqPpTTNw&>NsaY4068NNPKTbY7L-1_iMF{1P5c83fzA0<ZhbIDd zpTNSSxNqOay%-;7Jngx7y1B$^A~zb4^E@*DG#hNqJ7{tv+kh4P30e>iMcz&#@LPAL z<*ku-HVZzBSOvt7`QJa^4^cRs?X)Km)7@EC9aF700{$|p`$J6Y?A!Mk3G=Yu2K$<r zp))yNMCe&uZmiV@d%{5`|7{wfKV)97qlj{EK*DbkLYzGClU7>0c_6>F)KHyaF8~?Q zAyE56a7QF%rN9nbNTSIXy(qNYM#s<3)J)wYR)SU`beTB3OTg;@>-NsSSrR8PNLk4H zo@Z7>1`!JeaG6V*v$mgZW}so-o6HP;j#t!SS~D{q3q8ZS5<@-wYY=gq2My+pgkP2l z3K)urA`<A8ADyhp0B{j$bmo9NmkYkomMz~VPclPdRzT*9@<z8F5-NARo`b3#>4G}J zOSk_0&&)17g8&Et;4fR?8Zv``leDw=Bt0)1w#p<=Gn4p%XX%iA)67^a=FK34!oSH9 zE+XOUb<awPM^);nZoKC;xxs+ZZvDB8uqs1>3}7Gf<QfY46HH&r_Vqrm{j%_~aiPP) zXdO*g9XmzN(>*Z`b}b(!^RnwAs>T0-kCv$%u4Nc^8rax>DtLc0@-cLO0P}1V<m@!u zJ1-~R?P36Ld~?e?K#=ob_PXc>!fcG9V|w`lpTSJ+`3RvGx@U`d*W@`Px%_EEgp*kF z=XP9-uin?dR(U}U#$Ps&v<y;2fXs2;FWVw7g%x>>Q3n7!U~|A*qVQ7jA+)7+vGt`v z#wL8fu#an%6EGbW!hP$5%gM2tDgOj*AIM8cfF9|Tu$qATVRKIN$|FYd%{ogHFI2V) zvPcA1@ug^68JP>-*>6@@Q-T@-i~0#%;Ix^A!(O#sl+Ko@Bcg-U6U3>yd%lcj*;X=) zhzzw^-?rRioZmtuHzOkjdRL2imd*4OfFp?T&FB~9?{iFz+l~^nJ^66)^HQF?M%&Ds zM-7e-yl+eP^tVTv0#%Be!RNj2PWx~;A6^VeHhhfHM9M^G*~~}o5wBJfFL>px7V^~y z7YGioEPhq;efyT0+;d0>6~2#nseKmi$%6Px?K}xQY0{1N3CN>dJS#Q0GP1GEw`18& z-zc@?gN+1PW;h6H3w;WPwCyn3sdRb$t`fHWobtLxnmjM^=Da>2OA!H{lr8wY7W3<m z=Yw&OBU^XB_&MVgXc9Exk8Faj_mMaO<Rr_#&xh<rJuW-~otj_<VA~!THU<N3l#P^R zJ1ddBvSaHnkL6=`D09rfI0T-W4~>^reK{g~FXh5hDNC_Y$afJi#L$gl3s}_MJm1F> zkL-0~_*kiU)wu_N*(Q=n%BxNvRKg0*1z6>jJb)*-k<;jmGi>vmCU_{(?HKRUt<~2H zLkU4vyQb`*CN%J;(><6S51-Tq(?>hO*zw?!*I6U7G5*hvN;^Pg9Evk7%H-6ZSuT5a zNPWK&v`EoZL)|DEbb~lGfe!P+oteqEjAz|xFc$$l(XB6@2Qdjl?Q4ql6y$#5<z4Gx z@RdcD++6;n=AITXm|F>r&%xiumXEx{F8y0JQ?<En12H0u-I<<F6GIxDB{)#<k93d^ zn?8<A$0_og2Z#!a_sS|CXV+Y}xq&|t*7jf2tCVPm>xXDLtGc(^^M#mNwS>xCuSJGy zCG-3vO6Z?%YP!XwGLAF~vs+yKO}pKYQfjscGFb!@n~X>|PTdE@7Yv?yCjargbJHES z;@gO7x+1cC!_Qf2kw`oAv3Dn1ja<|s%V1bA_N~V_5oCqD*!^!d?|fF6YJmog<Rq|Q z(Uj{xw9qKGOW{=Tr8haDY`Dn)gO9v%q|<O!6lJjiQVY2)H3P2wFUtZjmhoZE;?;52 zf<N(Zj+)azgMKyKzwe~~163e}PR`oe%uOdQNO2^yCc3EldUHef`6q~M)h!T}_Pxk; zd#3S%gWo4I4th2vJ&Bf>7}b4zni(v}i6G<zMnOUl5oz4EW9YjF1tSqe*iSaPR{>(~ zmaUKTL!SEctZHr)o&kD^)BD*XZ|$}GUU`(^G$va>7AsKMC?uwUhZD1IKZ}V74FoKf z>E|u(2Ot0-xTOA0)H1G*Au4AQx44WS$dlCeZi!k^8!G&@nKaQ+^7dic<*&txpOFW9 z0{XtbxRG4+Ld&>?HaOW)Si39u_v-hlS8z`SLhuOtOP?zePfWjHa_sB+7asuS%1rP4 z@cxS=Iw0u#SM6si+_3(0$`2Y@7tQh^vSElOG~O^%^l$TaBbt2=q$pn&>crw?W=f`R zJx2fpdYO<jE1!+j7e>x$``n7#GWj&}?O$2g`hJD3_@bYIU^#;sd++W=gKvH(uH15c z9d)xha*wpU`$a?2++N=z1?w2VnT_zHdI`-V7cFJ5{^J}gPwgMThHGN#`5_2Ry@eX~ zJK}NPX<&l7=Z-olQ#^A;3cGU2sJsPzI?l-S-=E*V*8cnNFy7|VpL$pQznAZn?pmYI zk4OKBkQB3fk*FSOQaNRc%3WK^ayRJW)fE~xi~&V7;uk{SdZ!2`Dhj-e?_DN(VA|pM zLn)XV)$|}u;mx++#T=EQKPwb9vZn9FQ*Y!Y-46Qz_#>(ZT4WG_Okd+s#XQ@esuzRP zwlph4K|BeYo$kqD`)wibRG$+Zj&!KzO?q3tEy@<xnv0tEG+kQ+iQ2tc6w27EQd(V= z?SH47FDSMar5AvlW6D%nRuhBx6Wy~irQ#iVvREbwg20~At;kb2j;N?alKx<F6#&>U zgj%5fjzzBBw-$A++daR3@8Tj_*QTv2JG1sVGz|2Wnvd7jyXz+=IHF80Lb{L~Zerat zvvJQm#d1m9PBkAJlg7(M>24jjy1tXU=DPg0fFrU&?V2oqR89^vDY!l9wj-5ZHgX7{ zSOF#Fn60{?Evz!#RQw_)7?@Dsl~IRpws$|C0VFEvkKhY!6I>!|$pzYf6U#^J=Yz5p z+9ykVLfQS|rYQZE#pj-;zj+`SzQEerY{Kc$A+t&S-|+~!pon{4RLZTV>JCsLx_mrR zCW|STl6sU&q_ag`NQFQOL)>$LLKacy9_!z=blTJ8UDBH~_qaQ>c@f=)f!7IU0|PtF zPpsbh`V`lS91mZ!t<<PTKC}OzV>WqSwRrgBd5>`!ToBcg@=)Rn)*JxRK4%VSG8%A` zOVRLtMWRC_hk3rDS|f_bPviR$1|zg=@$Mb!(+eqz8MdpB+V03}uaAt1>HUE`L}^<p zzen2j@l2jsOi}7fW8N%xBekeY7*{2~16OxXf<slx@)?O`E{X9AI%Nfm7bRSh<MMwv z<8mulP7$O7kU()D5}()6L4@z!?EMizEBvT=J4?1(aCT%J6-EOAI&o0FpYhfI7Y1Rj z``8gOi&9gb$**+|7!GKQ$25?TdNWhMr~S>`dr)e-zmgS2Gap(B{tNa9-Kkb+yCWmq zAddY21T0Co33JrGWRP%0yN#Wz`Hl_Ym6K$K(B1wK;@L-R)fILnl%})3sO$)w%%^)r zTpGZ_I_EHffZ+)D_j9@`hfQm}iX)=Ps;@_KEmGo{*BjiJ*0u*fDO|lJ3(S%Trh##u zz8ChETrH361qW0wGBfT+?s|<^B-d3!U78yAe2sR(cC(3q#0kV1c`)F#>rn93){77S zTqVtHqM~R*M-rA{I7uoxvk->XV7RCnuM86lgvHd#Vf;qCs1cwKS)ADLF|Ctzl~o{; zJ<^ZHOE$Z3qyRz7SxvH&7c_t4#cpp`_kLAF5b};0|C4r7+v()y{z@zp<^c@ckl?|g zKmAI)(>hMiI$Zz+Be@;=AU>f?;zU5U^xH~`+0J55s$foX+Ber;0odM@xmH#Oc2YRL z00%6PY8(}n0aJW)0R21e*UZ6Jb(>DToxQdBo7%FYrXG$E4#a>5lqz9mW0r~Gm>xYp zgHF;uaVeQwbg0!PsUWy0yY%d3rfE}eaYSby>v1I<zr?CPaku>pJh~w0@A6a6swg!_ zbv5kLmkvh+Evc!fj?~?sW9RE-=NrRN>|^uHaUgL&ZZE>*QlPw3T~Xj){itt0hk};t zG2c3!w5BnpcS_XcpI~7ex0TM7@3Ru0uEz$y%h|bqwj=YJR@WX!tNTVW%6*rMMjS)s zy*2c-Ug7c)j!jJq0eU%jl&F~#_C4W-8-R)oCqm>4<z`mS-SfZH>>A@$CYEgLC{@iL z6nU^x6hP~jXJkQ4?v@oF<Ao)h<sI|*V(nv;$dMr1PIziwMei@r^bW>q?#Gjzx|Y{t zBNg|{$Yt|4=%ltR001au49)#FuL{sHHhOYnPUh68D(Lrs?x!-7vkO_M76Eg%YeIYw z^Hp+$?_zQK0+hIb=DCMQ7c2n)l?g!cK=nD|`bG3O=MFk>x$mG-f>ED%oZF^n0Dh7V zXQ;u9SvlHdk?cH6YMk<Y5IrSO|MTvhd8X&3i2+k9<I;rnY?TNu%ltYA86fN_+dVyT z#e|c)qY!xVdzdKZ+v^<r_K$kreu(W=`fkuKGrZ%0Y#drlrJv3bUHL=E>j&hm<H*Pu z1b8Sn5|wV1`}FR^jYtc1iG92*xvw~;mD!4z&%&J2%<>|kiG)%G%ioHjM%OEwyVs5H zLIxB2&$$kJtArhoDs%eaZHA;<(?gpMz6V<ZkNnUpdtd`MW5^z@ddH{^fBAFB{NdWo zstop=^hCLf14ZbuqJ~LxM+R)$;}1tH&fm-qNNhjxRr&^CP6Be*QR};<{}|`CSDD7a z;oi1K`lXK_GZ)*bpt2k?pkikXa0Z-)zV7|__q=NRt)$BvH`i)R7mRoKgSy?MlC!k1 z!0kM!qW%O@HX&Sk4A5qwB5_Pz{pht<E1*RF*5cK~?yJFa_x5eWF**0E7Z9zhic@Q| zejre2#4QlO<t;xjz36lDBOAwmUZo^jmg*uFCj6)FJiQE*ZehFFC6*P{)~F$!eohoF ziptCdJP>ntYAi6TF&Y!O*t?yUJ+i^hO}g@T!9&Xv8*)lcOiBZjyhxULa(a*ug>5^5 zfasZgDovm7`SnoFjSdiq7_Mh4J&78yzZEYL5|!1^(K(>g34dsaPTkEqD*AELIfBsr zT!P6r(^)|?Em^xVzU-`Z<<HR&&ykRiaa*qr{ov)?#EnwlyE}PdFo<3DqhcyU$7Ojl zt5z;I|JDNE*MzSNGdGYhg>>MNTQjrmJNvAbvhC?0MLx(d%2A(M5U&LH4N~=?3%Y}H zI^szRQ$XB8@3km}O=l&WPzkKG%l7>b#06)yh0I63?tgdt%MSE<b(|wQ$%a8-*zR6z zXI0PmIM9Ogv}|-Yt(UL~ZfEzKFZJs#WW_FnbQZw7h~$G<*N~{-iHau&7N9smrV0Rx z-u*s*3Aoim9Y}iTEltKIW`4DE3X$$pp#k@c$V{VIEz?iKf%G@c@b7y;Hx2Mo)*SUo z`6|eW!%kEme!br+rB4Xgw2lB76@l#rvQ+HAb`2!Ol#&iR#UTzyPjWbZI<w<yrtZsL z|AkDk$uNW5D`InXhM&}oB>eF~@Gmtruk!ZFiHqZ=uH2tJ{GIjM3xlS%z@?fpWg4=_ zjpx)u<}XLH@@oPdx?d4+szOAjMxvVCGC2zYwsZ0eSqG~6*2=MaZHB_VQZnTTnR2!u zg|SS(g`93Q(;&<FGgKoxzP2+dQ)=rOxk*jEfuxl8_+m$`0%hW#h>Lm?5UZb$r>nF? zivJf{@A|%)-hNT5vu_s{VpPeh8OSoR0^3bzDn!j-KlS1pfU3(th3SaBDo{KRpRf~o zu01D5HA-|CiSd%XDtxsAiE=GUq^1(m!XTa<s-6OrLyv7&DTdH8Rhr%ri5IQ|T(At` z!*WvcY(pSf&8DeedkUl~4)$0eYdIn8cv%GW9yJY7AqIeQOW<$|m{4}OUP<#eOLa@+ zTByP&WR08b6iMZrBsmTm((OzY8U0#yC|G(_(M<Lb&s&xnp%T%n$hvA?s~KJL%IW;* zE}G-fb+8pZ%q}m?KqtG+oUF`cA3I*KS@U7PLgd7Pkg~sbUwo!AD~MqDTJNE=@(488 z_gZh>UfF3<xCrQp^7$TCpo%Z)sP1e_nR|5d=ajO1J4U}Qw_lS*cGy_}>GJ#Ad3|Py zU?W>a>XG-M$u;$3jc3%Z4$Sr%B>=<QprJAhJq2wAS+Yun;(2Lp;OlZ3JWEczA`K$I zR#Y;c9?VZ|%*lFrWT4MrtY3*rzTDy>$_dwBmeR?A8W;`}(`pM~8veAw19a#oC9*7) z*_DY@5N(Q=%~A!hzO!nl2Qn2Pv)^f%Ng`Q$4rJmhD&LyT<yb^Jofnx%0&7>2wIi}D zI)^k{U`7mJeX|=SS$7is@r2>ypf7m^(|F;+sM>nzedW*eIjYiI#PtJ}Cj%GGHN6W@ z&1?p`sC4#f{K?jMTwE@p=NHX4AbOZmz*^isd;K>t10c(ty){ZD&FZ^z5?a`lO<-@Q zZsY3Ip>Akbuor21kOcwZt$=xFDjgyl6oW4Q;8hu)*DRORyLphW@cOlL8OVPxSZmDD zE{JTB2W~iyyy|l36%vD+%9LB)ACYkVk}TQxY|JaAsQoVnolIU{xAhCS22alEmEHug zP3F#w#oW9QyGlE%&Jtp4=~^tH;S$Iw53ElBs>;R&W3E!_p64T=cz(_u`)>rTJ{4?J zh|+-SSdLtjKVIp;d3{gWksvID`Zh}YUDb`jI?Sn6M+HQ`brIR3D64p-UzgUax_GT8 z%g5_ej$%WO<lk?_x#Nw7OW(dY6W&8Z2Y}Zj<s){yFw`cX6uoyq5_dURe<Ezj;W7yS z*3s~CpWPpj>=Ic&0=W53`-R`JGoNzy0slwWz5g@$|9=3#c0OTqK4;EnIiC`n^Qnx4 z5OW?$bEr@>v(236tfc0UB-I>qs^*YGsV0(2rKnW$mUKS&?(+wHf8CGUb-VVuJztN< z{VA%xa(mx^0p2-A6&f&1@J)SmUbb&I;!j0dz;Ihkbj7EK<pGH^_piV_UXK?zX>oEb zqv^UE#E7BcpZl*Yz1IG9(nX2<sWTy=E7S0z(PLGpF#P~sTW~2iU&(nL|3Q~ibpRxP z`^w@&!_^(7@Xrvfc8InJMCQJep|#LVP<s0bBSekYG9UH{B31i{vT4KA^@w@n_2d8) zX>7K&ETPQ2S^o+%%~I!dKj@vM)bZ+=Ro82u+abHibh(X@PV$KHiX$mhDd#4rdnPW4 zes*fxRzc?qSHb)q74EphuI#_7jU_3>528CST@91_0}5<ut6JI_6p%wX*1QGhJztQQ zCx8t&Nk#^_icqk6=!E9yHwCpXJ0#Y93&NG&62mwlCSqW9gLUJZJI^MRJ$bbA66^4u zOL-g#)=^b>+8%=~w6Vx+@oslDJ?^kYyia_8&T(_943w$-2L%63{8?~BJ^xz%!fQob zP%wLsD#2(W`|!mSy)X@WPmUa_X5;bMPf!0AX0{Gz0@t=vR_=*jA*_UooKL>?BUkvd zXRKebMJ7hefYpBx-#ij1w!Z%99`<7s13x}{+3=9i**Pw<Je8$~T!#6)_n#M;l77a- zZ<AeO2mDIu#2wr-{ITM9<@yRoOs^%n8jU$>@g2V)eSufEL(?YkL4ND=BsrxdmG7VB zz{$dYoy)o%GKTj)uDyC}_xbgJLHAV`*~B;h4t5+5ZFwN!NH#F=QI(Q2aCP0ABTdeg zyJf5$*mVtP6Y{T$UqHLJbXV3R!ls!@l3>;J;i?`G?#=orh$+h%CJjmE{2azBjo`65 z_E{SNKdv69o?loY0^()|1zJ|OUyLZcS21609|B1N;J$>577l4V3dvz(xUm4NXRtw& zsMdS&(pMR*Dl&q{IXXW?y4RQ=XLs%X*m+#3^Y}@XFsWtVsuYvQ*N(SJ+3lYqZ?CCD zTMXZ59UkQ_tY;ZHV=Zd@R|%E*Mq9&n1hC3<4*o}%>a#De{nkg;8+z7Nka1r_>;e_2 zc`NtLP5l;%j6AB$KW8@YtdgTELW$}?8(}feSF$Jcgh#&otb;LKcL}VXn3J|6%HOLa z0MV=Gs=4r5W%s|kyYqT#3=d`gn00oQxjrx)4z$rIo1x*~PFYXtoNN-FF&`r>k(gFh z$ySnaOXR+<QdVWk2Ki5bO4T1PkG{#N_%phG+9dYnw^K;AFiNARb4C)Xn?vuV4z7KS z{^V<-jgmEMiw5<shu;+^wc;ynP88KWQc4Ox?z``s!xl)s$T2p!JRW;JeY+{*H{8)% zvn-SG)m!!pS#G6r$y^5IC==RTwihHhG?ImEi;1#270A+P%#~n|d@`ZK3q}9@`<m{c zudx2|k)gq!Q=&5e8Km{z{`Y?C;}tjclUjmm@#EjF=Y5}u-2!8%ph}T(eaEB2?cH&g z(*sWI0WRbe{~%^wKAzI#G7?++R6gE7d8B<IN3uPqJiCwcJFlKdmuSvWU6uSOweat- zo^`2}{S&kG6p%9IgTv+TDgTB|(2mcTo>8igI>R2zdJk)yUC2j$<y`DPb*ok)5hTYr zb8npzoSxj}dbw_%x${(8^?xd1NEcDV#A-9`pb-5w>aa4e_dt~R4%*wJ+a^RAPFcw1 z{^mf}(BDoDe<1SK!@HjED|mpPuR6XnRc|HXXY$_9zHf5&GG8S>{vnNZJqsqW_FKzH zOP50YW&Cqoe2?5ayxjbKAiC(IgTE8b*s+4>kq%UPDKsmL5dl%x)<ZUiNn0a3tmNiE z^4%c0qA+RI?;k8uT5n4|RU<Lg{Q<Q~)iEMY30&~gb})Q=^H1)Bfaptjk91s-OAAOo zeb@*8c=%sx#k<Xaw?SzK5q4q|BVu26Yajc2%tV%ZC93CanM`Z+Jx_9m<LRLNgK<OA z6wXd-qMSF_VKn2fmgDgiCSQcP>pM}jOfhYSxT|7VC2v?&iJmrZZNFVcwMIB9vo}~C z?;`zYI<LC9zQ|lmEE-q25nT(}CFf{v>8Lt1+iPVC?%8_Gp6INuQ+jMpurRHz;ANVZ z-7-IRSJYMgBoVlO$KE1GHPN*|^~SR(=lp}YO(B6fnZzBfVd}SBQZD9oJhNl$v$$`S zthxZod1UM7VwZ-xaffMQdF#e<_}JiRh=O~7OXTx;M5g+wZ~K4$<vxDdv7OVoSy5*D z-C=*U%o0(3x<Ju<SVbz=!TI&_M7B#M%6R%X_JQX@@QcVL*yHav|I_|%Vl=K8B(aU3 zV^wAE_!0g=5e%{*u4h!QxotaF=4%^+qO(BPcYt$p&ZI^D`|p&)rERfsmA>H&ZSWzL zTV`G-%hoHzhjKpFe6Ho?Zaui=REe@YNi<s~%E{eQrR^rrGSqc^8y#r>H2&;s<v21$ zBpuUQjX8MYsk!u5<>PzQoalP+wpw>i!|pKtlCJLR9vQ833x7i<N|b>*tK_$H{S|RO z=N)q3(zcZp-zK**t^EU)@%t|NG=PhL>J}*ylRBkLyIaas31mJu?TdEVB!ec9F&!iw z<~ky`g|^t{gSwq*0}S6;9p5Gn9;A3j@|cguaA+rf;Ohew+9_XEw`#l7DKU3zOycI- zXU{FW9~we}D`DR1oGe99ieyWntVPb|ACrRt(W8Abm|uHVx8dzIM#tgD{{9XmH4TUP zD?DwR@w|F!d(GvgU47=!kB>Xz9*3pX-#Qgo$ASKy;7pdC92MDgjNL28OWJIol6+RI zU^R4u5%1KJE%&6wP~ocDY)PS0f9V?ab)nDt&%Bm#g=c$5P`X0Q3!@qOP9=N<sa{CX z5{4glP9E~oaEkRBE8e;0lq({8Ll{K0iWPz2ZWfIC@<FfzPS}U=U+x^^p<1xGC@2Uq zs(Cu`;goj6n#XA1O#;-wN$WGc+s@kz%LBzNW8BJ9pi@J_HBY*no%{lI+?z~q^}?~F z&l4(|P1E}x?EblC*7mOa&$}vPk&Mv-JDe_K^3Q<z?DpM)n<A(^Jv!2t`ZhPIJBzKB z)=Uiap&4)bk8W(u&IuEnU;R@T`rlxjczSD1RwHQjQqx;$b29|WzQXCN|0d@O&H3z6 zUg<muBBHN#z*|c*-f#cY_)AwT2X}?kJ8}$eO*+}!`anPx?fe(iWL=1KJl^b;Q~w`k z=juiz2mk792gZnSbiM`I)HDC`6i6&xH?jEiN}-1Ws0n?<*ZjVy!-!vRTSw&O^kOSE z^sd-Tv5pT5I|4s$6uN&%<N4?K?mh6PD)r&UpdQblc^<;t`dDbSGKwj#pIMFMSlsOU zPyLL;on?%}9CEo3)*;`cRoze$oRIL}*19zJx^mI>q{%$(3!%_Hp;_O0@WUOR1?~Pd zj78hhmQ1{ySIUR}_g4oWyt|rxRDw7TsJ}Oco7PYoPdF<s3ol-pM=i8|j>-KO{q*tr zl<u{&BS)u)Pl)QzBcWwCU>y*VU7Nhdf|x7Zo`Oe@CYwqv!**@Gbq@o*?cepLH}w1S zjPqh&CX#+a%P!2gj-@-3KQ1obUzQL#Ow#t9u6gHe-~at%$Af>DCX`NGl?%7aA6wn& zXLX&*oj^Kq+;Kn0YFaK`M3FwdzxMK9Q^C}E|1&51Z=c#$H$j#E{ZD4rOdi+_EV`(} zvmGap!IBioC~pp3Z0IG-1S!2^bqoP4fv{=3VKw|8GQ-7q1Xaj!l*lw@D7IH)$#PCA zCpj$hMGwSz2^^sM6AFt40KfnRz<^Y+78pQo10W>Sn9Lo{MM~<0PVyQ?^Kj~(XWcs* zZx{YQKu70=yEVp9cg}irwcM+-PW`Yr)pgP53>v`w@aS%xX>za7J6O;O10dc_p7owR zZI3PobtOE%({uUpHS%bIvR7~WlP=0^+rhiNSDsy`F5jv5x_<TfVEUI2&+lHp_VN}D zg4yBS$9px(medcM?(0|<2E@J2dG~j|xm#;?=*4t@*SiN?r@|e32D;zRw(h$ec5k5P z<6~ab-E(^edp|wvOa1twxN{Qwf}g8h4E^jXmb06oA8!9ucqD#s+UvYnYB@o9N;>#R ziu$z1>$%aw?OWEa<T94M*yf~>fHR_I4ZSL#u2hBxCMG`0hM#M!!o%MK{3H8l2!h<_ zJt;3~=)b)$bLT8NxXzZ|Aik79e(anm#s>K+@7EgyAc;GGAZYBDV;}+D79_s_m3&c+ zZ9bnaI0+z;1l+#9;~e}K(89T5XU})9JlCWzX(V|xZjEMmx$3^D^bd%CQxz0@=}mR$ zvG;Fk$SmErwb9k_Z%<QNF1<aI*!%u%9d%sy-PyExkJwX%%JJ{cp{~#z5#T-Cz;gM` z_*Ex71prVn#Q1XQJl6qYqmjWD6q(xb?yj7Twe0(gh=?<Ef{fDEh&cE#RrVaW*OpV7 zBeu;L#sHy9AFeQ6Hb>w)_&snjjn{hZj*3)c0kq)hnd*{J%a0uRg)nX#QPg~c1_8+W z9K?+j*g>&rTm5yycnaCTdGXkVcYSM~X-R_{<NE&%ZOtG0@5Ya}m;bx@=iA5sZUG2` z4L(#habp;%-M;ZZpMx5;4bbk5x?EkxnZbWLm1$iBxO*L}?wN2*Ao8sohi@XyCQkd= z?j{VaT^jescGQ@WY{kveut0~7vzga9|H_h`0Pb&R^)OOH)Nugdln}e9;Jf;kxdvsA z`a=CGZ2yRii2`@soy1JEjWmh~K3?7HGlTDQI1V3xr3VgPFNFhk)TJ&n^B&}OchSys zMQS2XaGwk+?!7x}hI6p#QYBdc?p>R<cK|NdNk-qi;ZEWgmbcR$D~1@Ld&-_;`#Xqn z_n|cr0_d&bH6Gmid)APn3y0ZoBuawI%yxAg&wl2x0vL;!_r6o**q_#B-2d{x>WH{D zfX^+tXOa_z(+Ac@eaxFeu9_IZFVrI)ISXnyQ9wf#heQ62^0_lo6X5Oghm7T0K$2e< zOyGW=CwveW|8+%7d46)req3lWaYm_N?}Ls5TDU6_IU>1oW&7+bIL323E$D@z&XeLd znPZI%a04DlQRU1PM=8CiMOr7yjMllUD=Z1l5kjpvZ$GP1?(ohKwpTk)ZX#nC0Oy49 zG{#-*=A%Y&$UF9O3SVQQ6d)aA24^oi<%{Ghuiz)_k=C4qwcJy`E08<=(<{3hmJcm{ zJV!7F0m0-5@x&!MVUmD!qz&8b1<^$5nz&R!X~EeBvO~5OE^Py%FzU{76S*i3J=US~ zh|3}fXoH!8D7@S#R6KZwW!Pt!3*g5H(Il9bfQa{}Lew0htmidX6rS#jP-jeXloVEQ zz$*OfL$D}CFoIteQXOwU_vAE3VAJ|W@d5(VG8zPgQiv*Hr{RfUvJ}5ACRU^jl`}*y zMmHd=Js02rcSH4!(xm3h2nH1_CKW_t$UsfE*+~UCB9S;Jg*m_>F{uG_O^U7kPuwm! z3@!ssKD$d1ECvS?vNjWuA2rJI`)<FfxB&3g0OLGjVh%c#;H1#})6*6pmI6zo_WgXg z9$7W%EqOv!`9p0c$3*om#ob2I3U}Ltq4bCX1tyW5vMrhgC7dz4x5)+iI*!q4RIq$6 z@18wC6U!pxN{T#0RDii>{L{xA<~#PC3t%Na?W=uhWQqpl_8Yd>))RPCUvq$rp{(Xk zE`EDtE<#7clSlAx32-BP0Oozr=@5NLzp`Vq;`3Sr<bC>MR+@S%H5n?gLMS|StU)yF z6GR>gp0}SP;uF|!36o2Y+_nKO4ltgG{`j!;gtLeoK!$2UHw(L-NUA+*ZFl^ZyqJ)- zY_K{u>GQx9s_~~0yVp3;3UkO4NK73h_l@cgF6}q!?vhly`y}b3V?oYZq>}k^gOjbW z^`91?`h@KDAX`D4#LnGudf~Qqo(YzH9|Al@>H?Mx(4>}zx|la$`LO|5P9hQIy+oHC zSc1hg5-~MAL#Jm0FS^~2;CpWzR%>704=6ca61j9X%pOJi2Iii|UD5}7XGD}Bv>hk^ zM+`T>uBFTlhAp&7{@}0}>n81y)Dfkp0=TA*1<H5MFyBk5`UGiH2GP(&cuQQ4arG@1 z0bL2}KDL}dg=}|;JQ*k6Z@~_sG_C@zP~e-#f;~gJF6U9y0T95jPkekhnh-Aw7_$%P z(8b{m8a4MKmv5CkIdtdjhny1zwRc`GNFiF>Tdy~WlJE;D1v)O;N<_FRcU}Nkf6D#) z^JcC<wc$9`0BA`@nF`b+MeEIjGdno1z=Y|%OL?`+HsZn52gmOI>5zk(9>#dlF(HI2 zX0V5F4YB6>O!wSpcP>M{=jiBafM)V1x%4Nh&Y;h$!|_L<9OaNRt@<}iQBO5b=0U?q zXl-tw%302*-i1MMKLn`6v(kC=d#_G@4`L*v?AH_ko*-EQ1<GeUbW-`*$98!+QgB!p zdH=Ru;vTAx$d8`P*x??;RQG=M*uFal9nE!8M3&&RfrbkZRRdtl7@;SGTzWWAJV1@i zKMs?nzyTwUAx9kGe}LpOO`{V(9E^4y2PgL%za56#=)A6_a3Q_hKgnfJe&L^wwVj8R zvpPx~h3R&u-SkgsSI1`X={t~^W0f3^qT*U5Xi$Ta+@CYqAk`9ZMaEf%3Uq(L8?HMl zH+tj|k!kDjOE6P|z4rCr>h-gpL4gtz93$!Yvt!oCamNbm;px$~0)XbJcqrra!>qxs zb%<o5;C{SSwMc4EyoyX#0Ptr-{5_oZ-shV1zFm?c06Ul9Z-dj0e$|uu$9p>)gwHR0 zEG^bv3sV^2J+(pF>4P1pyzXxUh6SaneCi!tm9p+2K!vTBtYLSz%i7bAi(6cks?; z&x=(-kmNm~d~_Va9vqQX*MPal!3J~Vz{4=(m<)gy3;+=xy)elZs0NeTp^3Asp_ssc zO0MWt0L|s2UaiC+*wV+B5C9LcTP_Xq3ZnE{2a}UtRu(Sfj;*FaGhI<3T-bBx7+-68 zL=TMi=9ncHR;XoKb6xl$LZvsj##pq;7(K;-r;Lm3`hxvXmFqo>%w9s+uOb$;agNt< zV=R*iT<%3z`NaxsH%D}e22)B8P^*AXA!uz!NnuAbVA~gPhAd}y9(j|GxhHT+N|&~i z6Zh`6^Vh~L%gV=@Wl!N!ZY&{#0BkoO!G3crUx(^XroT9vk-&u#sTqh@fd<y}U>-7V z1Ji`VbP&*zT`{LyrPA@@-W*6NF8#cTXpgXmPC{QWMtgEj%1j(ay1~4U;m9P?BTG79 zO^2(Zs!3>n61Ikes-R*!mXjvZC5NOWPLp>{FmN^Q@~So1J_57~kG{c&hic-c@`5A! zg85b@nBkMC9;7E8Z4#68iv!1x9{(I9>D7h8c}Q#qxZSswf3jgyNrQeSqbqqnx@>j? zGd0Ww{+z-7WFCN04O0EVT<Npx+ulHyb3|*oDA{~T?bt*`kT+7bvfdXG2LLTNQYke9 zoCgnC%6?|a>|H4S<Xi!tiG~vsk3w??v~3&?NOm~Ee!UfEEWs#*%GnK@nd|a{#@Guu zFd#r5xKw`PZKcK3;ZI|#E9^peN9uqTu00UbZj3GGqONYB`RWHE-b<|E+}a7@yIbMl zSGkJGs1dSlU9!zACp<O~9ld0ouai-eR|v_=P_C^?d$)fY0hDfF050k`2X&Q0)Q6N7 zdq_UL2(OzI_nnZR<YMbN&|Vts!cri6^&sg9Je3ANyc8J1hbJR|N?qK^jkx%w%6J+l zYw56>G*<3-;?r#cyp<3&TT`cJBI1Pr%KPD7Zl|jch#%w@O4p_UB+Lzdl*ml_FRsTa z)u=>ETonl&$PZq(I+eL~7Hx~zj?ReZ6l=W6-hLZ5oCl|H5osLwL2hP$p4ICm^hW}k z!pHn0n~by1sYfK#^H6=#$SGvDWLZ&>B@TTZ_lsAiD;xMkAmX|z`;&qz??!`@Vd@t2 zU4fqK@6O_pw4Ep+7)K%L!YP7;U|OnhII@>4?17<psQ9aVOa~3syyUBsAW<a0FINlq z;()lZkcfGF<_8n^1XqyTAo9-!_mcn>wkuNz$Lstf9%SIW6OzBaEB9!Ic^XGh_=xrG z33!FuDSu97B2Wh&MxPN_WbsIQ0$VhaOLMt)a=wU0h1&L`d4x7x6IaxsP42up%3=dk z4U`oMj#<|f=VWHg&L11mhD4H?GQo%0webC`me-n*fduwfKJt7TdWDZRZ3#JBAmLt# z$iO$rsCt1x*%rTWD(~gWE3xjJ695T4`z`zOqrIzWdabr80T1`<4-R{iJ$<PV`p&wF zEW{lUTQsXbRP>fHI$bh(Mo*%h0}Ue}lXWE9IoR`TxjuE=4I0dGz{Q{y7Q#ooZ{vF2 zp>MmwlpeB?s-|sK+~;HP0v_@f7aK`H^-<B6nlK$?#2VZVyo)EdEuPpaC6UX!A~Bp< z(oy{c=XV8vRUKKCeW5w~G~NH{nXP=B$01y%C6<H7-r~W2)6gjpl!1no<z4Z^NC4wl zsh=#;rY&Ed?~>Jq+#rPOPqp6v*^5yKisZs(=Obm>IQ@MvH!WNt)tf`LNyMWcQPE#< zm~%X_eRDnX$t~c9EalIccDry`p@%AatP%s%EFC>bycnK}O3U=M*XMdn(YNQ$-n-O+ z@q~NwTK%<f3y203s0y!Bao;UFnTZnO9OY!}?yjEZQC2~nI8lK3d_W=>@3Ax`a;qOV zix=5#D_i4^YWQ{>Q6@5o$Hw6iO4f%XZ?~pjK2fyo0t+T5Q)tfq#;00O;|_C3aa`mF zNuL@Lc1Y;55U|b0=xs7>_>j1CwM4YQ1oFB6rGEkVl}J{ZXz_&b1uOECbhe6w`cTpO z=<P9i#ULOi9^T+~<fFHYY<s7EyXjBlCO$XC6}?Ep3OnOf5WdCWEo@mz(Gq-KL843_ z_j#iZHDp(Xk!uEoY!5CI22628QaC<W_`3rZvZ=p&{oY^Q^ZPJGaF+W023Ym#FB+;L z2-{3UwHu?a@<@hjBO*CHK|IW}{X<f|h~wlo$>B`!;_iw`*{WUG;C&|$W#K=KL#bSH z+@pf(>%-y+@oLLgH7-C2#xcH1w}I^?>uH;MNHVpr3A@V%+swr@K`>wW@Sl9l7maaT zPKe@6i=1!l5Dkg@Dmz6(#Z=>__`(AGfNT%yQSX>SNLs~pxBFu?4|H$8QRqZ8AR$Q9 zt|9Co2lEGqDZ+~tFJZr|PNB;xduYzd#-mu@QI%I>;0R|#1Nx@E>^)xF(W5rW7qFA$ zkRh52fJaE}y8a14{}erNs;YRPbyBI3lL@6Q%LS-VY$`e7&3yDbya;0uTWE>yU75y+ zPlRn`W%JHS&A=A!P_B)QOM%X9@<zc=r;nIi#FUk`;8MPD;|h#1j+qhBOT9TC&K4c* zfHZI{sn->M)A!8}G;iDD0(qz|^=W{Qu6payv4pPQK!*=%{Ugm4)ydvS$CVV~rgWOJ zH-bCjaL0M$m!L?7AOqWQuYi~XIvZ}<5?G!F-yq`_txE<M6GTDKYqI;)bWE3PPg*EX z{SA#0+C^NZSThMzBSdmfYklL1y#lUei(?kApGyYX;1P%<+#^iRI4%NH)r$L!ue^Ll z*1-Vxj1&HZE4q>!SANO<79Q@8_pOn=U8D*3Ie~lk`vxrocjX|ukPu$36!>XBc9DbH zqKUN{V@LR~KY(3dzScjQ=<Ox!ZJd~ksND0F1zg8<5nl*0A_u|pMI=8tkrVd?7kIju zj5NThZp)@`kWn8}A9yL<Tseem_(@k?tpOGW;8QSGZ+$cset{#R{jR?<F$yOwYLJG_ z1$=FeHb%b2@|Q3-X`&0X#cb7HbyZXy?*YVw23AGMQE<B7#&a4(R_#P*35gXH=Mq7I z-}GV96x@F;uzMG-V0r+{3U1tUDuf1$B=0}Nd0fuLt}dakE_pQbFsmd{jsW|GfcU96 z9`hP|eF?jt1m31DmNY<!)E%Wd5WziM<!Ry_b6gAt7!g<<e|uCh|5b*#%l8bM21-Ip zE)>=l_j~2))xOrWkMo9y>yfez`F|$8EiZIXI=-NQAbxBqAKgoZSCTNfOXxq_By1Ca zIVg$wO2*bw?FYV=fM003-xLeS0ahDWK6j~rsOCz;nHxiW@i-3WP5UF9P=Cm*;`fo0 zf03SK5^tQs9fp*3O>&W0378AUm>ZrP@5Rf!XD0xQ*T~P8<N2`dw1=fbH=mhdGfs+h zZy-x(=s!znqY&&>4(2ZhQ%oSZ+H2LEdk-Q*&L)|-Da*M6ni70)P#)9(fF+;p!scLR z`Iws2QbdDD=Q%kp51DWXb&H3TdG;{7ih_P$<1^%u%17kOkV4$g^Dv0Z#%R^Rl&^er zEdj#?P&@&4m4m{;#7^HOt#Q^PQ!sA{>u<8x-^I%X#2wY%HU_U>Eq?79l(vMxmEZ<> zqTOWlYmvh?e`KTIKF54U_D_5SIF&MIiv5N*J|rafO(I&9Z%Vt~%s&0}7YQRpN%$%d zncIO8@4|d1i12V2#_VIr)lGw!n|z*F!nW*QKr<)~x2SzbQv4&!WDC>bLgC)n0G@d~ z*_-6m`tne+nhs8f^7MpENp@AY&s~w9d~}84VFn6w4u=`Si+(4d<8B2c&{y<TfM%ax zbtR(g5C<nbG|RU61`pju`{5U#959Ldivbq2WA63C76*M=20Lb}yDtdL`=Xu$OX$BG zR1FRFmpVO4LyJg#C!4Nc2>)eB6FpM8DYRM_w;vEM``Ywyl9ryJodARy4A_4^(EmXJ z={#LlziQ~i{$Se4lg5YruW<?taMh&dJ)>v<<f#JCw*dY_n5Yt9*!=Ina`%68w~j*p z{#38^U3M)|-klAV_gir<*W7c?`Ly2~_Y=?~r+-TjVgZ!0hWD?)#DjOMc4z&Ao|(Z+ z;EBaMT+WzZ(x*@BMZ{kyLk`<Rr`WI5B}8e4mTwbh%B#3?ra*6Fd{@<y5|Gu}4(6fG zT|L<jh-g?J*+DxvUwu!p3L|ap^Dgq|FE`Fbzwu&a2iD^3%PU7sG~JOKniqG5-{!f% zl{1^p?^HUR=%4Ghl`!A1E1r@1rl!@iV7pNS1iag;XzEYsgb7@mY7O~j3bHqo#pH@V zm&cgJB>dM}G{`uh?(QjfDd=L#C#SEa%7gQ7?wxnTk~?qdqW`I)`Aag5?&p)T_MX3W zQH8Dv6bW_`KyH34_2}1Nf;gZj4x=fwfC>3FV}z!*l61+YVjBS%j5HndJk*3Ud)-uQ z-m3=#ykbFQg@BbA*Ym+t@i@7Jw>d3mG6Cy1I|5BJ-t6!hkmtFpmqMph?yq(E<N&zg zw^jG&O%NXXM7@!G{p)i_D&t#(QzyW0jP643#^tK(O}ZytDH7D?7RvPUczb$~36eCM zhwc!-2>A;J97f*Ju1idq$=f~?*L(V+0&st7tRm~1yi4(^ND$f1$m)&1x#p4ncap@D z@oF^je+})81-82%V*iOfp_CRSuD({!2)g~K8H~Ea;+oyZyNm6k)i*g~90t0A%qu5# zY?gi)-|y@7US!J{Yvz>Uv(7fKW|EZdtw?3BUV2x4_}}L-xuTSq>(8s~v))t$zE#H4 zd`5haA3R>%-c+&+_;I~CitnveadK;_<#bkRJzNqfpNgvvf8`r3W3Z*c#+vrI`>HSh zaNp-++RLA9FM8>HXsp-xK1G@&HvP8D5rm^CCM31Hx)py*zFieT0_~q==4oX%QIm)Y zwLS$Ajrmj>NUNi9*Ns=(-Ni}I-Q^=%#;fFGP3aR7eVviQHp}`PrPb;uVblufb`E&c z30Rvnm4uu$Q8Wgnzl}}038U4-e9LiF-qV}RtPC9wDLOQfdJs`ZZ5?`3adzdl>&uA) zS%&KSwx;4z0}hor-G*8`O~9Bg3^b~13Zm=KmI*M_-tM5c`+@-lD7QM;T%q+@#=v{l zxj1tWzb-3%>cWmaBwx3*_qz^OaU)+}!PXv~tb5_91?Yf~z~)Z{VDQY7ffE{^HhUz} z0Zx=m`IU!iO;NH_Y`CV9suRlc2VTC;+|=q#>jj^z$XpFm3ERWs42kq%soibDg;_X; z+`9$1#=I|f=LUEi*zXsPEL$l(3M|Xq<d567X*(J{(M)@yqk@5%i)I)!M!CC-*DW>M zmZUX^2J%Js|3Mgj&Udy}9I2r8;kAGTHT7;h)Benih{wvZJRrDjgmx75rj07R0|4D0 zGo`*FbTw1wD4Ktt>(^!z!qEj}*dnDl%mfNtF`i9!WwE+yrwwpmnp`W@k}f5FG}F;b zEeE1~S%_Oi%Bv6wW#T!cT*Z@@@|plXJ1b~e;j1;w9M~we4@zRDI>%6qBE|1rFx@?e zpL}83hzUFwr_gO(@A?qTfAq7=`K!Ki=OUCQp<7;-N{Dr%pa5@LJbqvSBh%xK3j!}G z%m@eZTIu2?*<*B!<K-CZ+xf1CqoYXj@#CiBx@Y2p)M}#QAxC=gGTm30h8{oIEIZa% zPo<{lxNf0(rnnd29;xs|fY5g}DUGE%$qvc6S&V%a3Bs*ZbkN|of)1<)kFNHOvS{mK z>vx_8DrtD)sAm2O{pUFhn5$)}+qwHq%!vcjlM}ZcRS_;jJFUat$Ea9<O*Omu4okC0 zjHzF>=!K%P*!NB;rrju;m0XDlj+?zmTWJQ5F8!4Y-%akoWKyGcEYfb5TrCqndNx;O z2+uT^P`5ZU|LCe}ne?G=a10ql4n#u<W^EaP&6D0cZuB{7no8)DJ^D{Qv4OrV`ez^b zLQ*qK-zoYI?n%475U=Rw!A4ew(Xo86d`%y8XXJ39?^2`6Ja@wQ;Tb!?-&h$~ax;h= zMjcyR-obz+QBmcO1!rf=pflr^42%LyHA3cc`g!W4z$^Si8M;Q=W3sorGY;f-G>bDT zyi&&mu!qHO1>H6X_RW8He?+2u3A&TzTN*Sss<6D^tCe(FETZVOlr)UsUbBk~M!1xy z_$KA-Zxm%lj4%^95Mjp-9WwpehqB<P^0B{)m;xmzoIZa*LRYDSV<_r1eaFDl7qwat zDT$oTGn#HI&7^^)CX8V^M#IRY4T#dRFtj{J6ieYk#9uEl<`%X=elV+yl0P8PdFp90 zAmShK&YWH0)2Sc85W`&9XF%)&Iyw7m@D!W|5X~#Ye!mzUJ7W;|5cfc`EJxIX2DVcw zdvsDTA_WlOW;;N@jrUPf-K~h-y{biftzS#sZFNg}?<*F+wJbG*o0jhxir<^sd~z)} zrrNAiR8P1#vR=!>9=yNKZ_&^u;Zj_!_dH!jZqotK0Rur?hW+~_gUmBdD!n|I%Op|E z#7<xmtbz6H^H=HqanP*Sw{(6lL@E~t*Jcc3Q-t2tIe?(<Jhj`u=0yLHHPv-1A`~D^ zENa`lyJDGaV!(Im_!`wVCFoT(q^SBp%lIgOc5wU6+0*#jC`+J~3oU<Df!{=$bBD+H zwgV^R?$m2IRI6fx6N$3h9Jm8=vosVJePSj1_?_FA6gYn}<Ww)UYVE&T7CTuclR}OA z2+;1flWNo{-@@w(z%<Ds!je_({^7q;`?V)&u!a3?x@SHSqP^AAD!O$oH1i8HsX{iG z4AY{Hd|LTAD)~_Er%v3>V|(A{;FD-ks{V9@-NLX&@EDA!7mW3zG%Gm!WoV_tXcUPq z3FTZ2&{FrRlmptM_<=6sX`Dvq@!?6!$gV!Br3rNy?sH`Lj717Q*jpm<?QEWL_i&O2 zn5??kI$>09QsA}nTIEd8_=OQC9JO=%`S;l<8-Ow~J(zY>eeK!Ie@=d>#d9I*S>#AJ zOGX4*v}+R}2=_U7UoWDnA}xbbC1@MFIV+=5^#Zu*mbfy|YOkLA$oYktT9J1xM5Y!O zYP3Fs^;yid!~aDL_}v8gpO0QuF7AT{wjz>s^7r8^QlqR6b73$Ljqnp@SqpJ2ziG&+ zk5y%h>wub`B6pAqBXeY~Bk5|m^SB}$U8k)D&wi<j4B&`8dL~^AFk{-_hq$*=35ZNN zrZ<&&sxL2)4f~AeYbbFD)S|tdTgI8i-ght@YgjQ~tM^%<6v)h^?qUh|CNEvGn3E&E z3TzN<drS&NRoi;V;O!ZGjf1l}b@burTKGO|mWw*utMv+fk}-6d6~luYKgmntv9f7Q zUveIGDbJOMIJLT4li@s3cA?1qCLe_IZe=D<B9Cm`I4PhXXcY}HX2N~zPf3cItXg%) zOK#jjYT$*L`s(*}kcnq>lR;(rDv0h*fAt0LWzDg3zNlz`B(*ZL`ZO|iaM?UK6%Rkk zfu0r8x#=*CqOk;na!1~-vW3Du#{8mIn1?a@5`^aUbgYyL&&I<K-C_4QS`4|fJjyL> zcuYTI=APEuK^0faa+-_XAvOYgHFx@ZuTf#p)4_4Hh%BSE>I(4BBm&GZlS<YMJA=$h z<iWQoea&DZ;%GY}6c5|8nnx8tkF}NubdFaHmFt*aO<v6-sIir2oI`O#B~;k+1MD6} zsQ@k_SO896)en&~-&usS7w}7jA_F%EA6aL<V%0;gd)7dgux_(dR0+W`bCC5$U-aqe zjtK&|;cIwuUo$#*LOGck@19$H(x%dBs@Ja6nhgN}1_xQ0HHmyNv&$U-23L@IQ|vk@ zEt!zFFID}tSHVeco<|$Pm#0c^h02?oy&^y?S4T<-E<hjsrl*t0U8I|_S#t$Qoeb_l zD({;_K+KuU&C3}8%&#^tVo3&|GF>mRywDbh23V<+Oy3`fKmjynb#VKrvB!0dy%zvR zKNJ`|A$)3)E7Qn{JM0_jHtB1~H1~;R2yNBIr~;V2Cx3RLm6<{9Fzc)J<ZCwk!I^zz zw;`ECUcIO){z4bdrIr;AFi*<K(cR(LNT!D$3oH+-KdGBQfwwHdlO|6W;qxeLmNF3r z1m!(%b36s;YU$s{7?#SJ!V;G9YCf{PtaEeJ@;DG|%K|fXBQLTwFBPA6g3R|%@Sv~m zZI*+>3v@#`xt>3mC91hW>bY+ClB_MqSRz<sLHG@uiA#2fW>go|GUJ!(WA6BTiGXGO z@X1;|ov|bnL}%V0km^A+STS5pd?+Od5lhHrlD)P?V)iw=LoHU>=tx+gT&uhWyLt=1 z^2*Dr-SH-kL|@7?dB}Fb!6L0SOVVL20Ik@(=h&;Uo;$X58ho#Fe%ywjIEa;+z>=1) zI6!S|+>&d!qkT}3F3g(SxaS(-<zG?TJEz$8s>l$ea!eFFxDT3P%s(j@4HF+v@ME2Z z(x3<3j%gr|wsw2DGfo+^KKJFJrFoXjfQlawB`6TO;FHjXkWYgieJVWt6a|qPMdZ7l z)9h1y{s4QX2oLjVbxhh{(_{Pi*y;1bbI8cu`AW~&iF^j*49tyEzX$Ntqcv-}n1z3- zHTIxivd%HH?s$q4E5X4sNS1?wyzTHgAqHR-{>aPY3M;FR5kx@1VYEz~Qd#O{*H*+S z<2=p6`Rc<WVd;Wh^}4_hGdiEO)!_^v;dClY&x{eD?wc%~Pn~2x&|zH?XGY)=BU|}5 z0A@1pbTJR=rK9ZI#}|2m>@-p9r9w4y9!c`)rn@lDW-j)+L#|IDLKdKeD3-^_ejAZ` zT{UEqdu5Se6e1b`{0J%=gpWicQmpf`sZ1kby^!J@kn&{A1-+NTD4|vDUsA@>nL)K$ z#X{r;L@SrncKM2OC!a6s>x)}p>ICClkTYoWzTD?cWk1k11p4#}{nQr%eO2<_G#k>u zXdBhNmf+COoY;;_XUz>V47^C`L#&&ch_Fe<%h#hCC!B9H!%EYkt~|)?U)Md5fhAO_ z7{w<X9ARC#azrtI>PqOD*Q{hAKGPu%OfvMc7zaquKOKy4+I>TJ$qsA9+`s+yGhhRx z*~Mu2Qft;GNHUr>ajk)=x1U9fuf0LLkkj{UXUt1Cn->&oL<F0e4XDR2<OLC6&qAJ{ z_ZP(#zo6V^yN1d(lqsmKur2<w)1-BcGm8op^;}5p-=9Epc8ggU<lAt(y(sm5tMpgT zrk7XypZ8Z?x?DI&U@;dxzx-5=BN^#G8cm)Kq2u$GcfZJ7f>LlcDY*X7CFmI53S;=n zY#zCN0!gU;v9B!sMWx*RKebW@>z2*@mI&O?EgO_xR4>%mWFJWg&_Q~MYMp|Y%RFU( z%J_GMk^UM@d16%Tp4*A5n2~_}8PY7CWW`oItH(S*KV`|yGCR=$?xT_L8(Q=rmMUa9 zlnrD4%+vFYGIL!H*5ajdA}07x)(ufXrpz#kr3=4lu*1HKcK^IS#?`S<#dATQ1n!DZ z>`h*=I$_-oG6z-};ok7V!>mLdJKZE!1{D^jbGb_>`P_Yteu3EA3NJe$l{N`Iy1|GK zH9Z#;6*B&A0FBtBNh4#zcHMOJJn6d+7~*i@@abKaL1pM?(0fD5uSoSy>yF#Pq*ik? z2%uUM?d99>NWGwt^}jA3=8zF2c>Lglx&!9(Y5W*#lKUtlXen<QmRAQw9Pjn=VRvf` zBGLEWor4?QhZXMwU_p4V@>&Fg$8f2Anvq7aj?y?^VekAJVuZ^zOUEgY+He_dJ?;>b z)`XZQ=3b7bH<?=>bw24n+{0Ze>jx%H4i>c99FwNMXA+jS0YAk5SeN9H1~lz+H#OOT zJ+*P=#JBe&ExO70S51?HyA4qReAtC^!9NZ_T{gh>nG1xG;0w>ZMTdFz*13{8`y*{J zy|_aAOWNPm*<Ysj-{h#pOtOTiVFnJKrU>g%hD8g3l~x$(2Xos^z{te2QZ_oo-ZHXV z;};uQ2i=7{3UqDt$|=jWRhdgZ<jW}pw7Y=$`s(9yV;#VKC)p-<4=&fm6T`J#xtRF@ zH4L_<(G95#i52#H$LE_Ju_e~6hmkL$ak=4q#%?k!n4PyjT|An=O8>!3*Ac3AP(N#! z9|fL03ELBdP=NyRB*b1mJXJ0)zYif(y^g(hK`%L?jQXx@DevX$06KTB%$?vC#4x_h z=!q$GGJ4xXt0)7BVKV-kxlib|mZ1xG)3zOn`7Hs7m5QLkf~in1cHSVnOzs&xDTozA zV<olbc`q@u_&%Y13~%zrDSW4`JuJ)^p?cbN8|RklAFNpnApBQ%g)JOtUSJk0A@=-1 zLfTn%@~ljemUqDnu77j*t{@?ODcV5arJ9RWjJA&~G=0Vv=<fcz#&qz4+qN@h%NSn9 z%ycf(mzx(${gk-sI<Jp>d^s<3GS7D-G;%dB8_7ztg`HZ>qbwP2%6&GUIQm}odWdX( z5aC?+EYejI>7#%${KTrMTRX4-?L!`!)2;p`{-{DV1W-6qap}Ci@y>2SOUCPpqJFvG z=bGcmtat%}v;+~}klRPWjCJFgQ|#1%#$s#IHK)A2txWG9<YTKE{z(5c-Tu!@UqfYo zBzwZs$OsS=oj@*V4ug^w8J<CmZ9Oq@&dgfwbIxmbr`Qgt0Uzwe?rFne+B2Xrzi;Qv zAjn~iut~)7QwGsPjxJGIQ*hkjIWm(X1hx=iG-#ll`W_v`(V)EKB`Esql^m;IWptMH zxBQp{tE^h4i;m>+g3n&7ni_2??w#Q?FE0LhgCut__9y15{HJuLo)taFI7wjbO=pC! zLfhq!Cu$*?zO{+?gY<NG=U8Zp2GV^}2w<`jm6@@V%+R2`6oPD~>yM_uKj!oZVB;2* z_UC*MTuT8-S%5xRoOxW!yh46BH-&arTlucEa(ThcEsUWb1l>u={h71h0YpoeBl~h; zu>^QV-xja>5$`^G`yID`yK>K!<+=}(?6ap4nSG2z4vWGQKAiA_9B9yFes&*ABjm}8 z#y7VovcKA-)0Y_g()-7@QEmr9GTP;ocXx$|$XikkUQs0Pi^<2w=eo3l6!2gfxg(UH z>^)Sm0V=~2K!!}VfOLX5WP6|q9ec=C!0n<x5E<8-yr;H%FThXkKDHjZ)ARa#RY=~Q zrw+%yuRrOE+t8e@HH~}N9{)w_{#o1On``gCXbZTGc@l;RTRMKt+yA8f<8d+o*}()v z2`CM}odJB%jokOX<}Cddz&)J{=bx=T8D0HcP3zNLOF-rk-n5w|S9|zA*jffl(9Rer z2jQYTUl?s4gumGh<=+VyjupeqKh&F9x=Md!0A}|jF83wRG=9z<yY%eV(dVQKNvF3g z))qSBX0IOpZMnYK6L>Wmv2<?O$N75<m|OKxdf#UmL)(4EhT(=LGiz5$WQx;(kmfoV zKkr_?sxx5iSpf%RPuEjS;J0JvEpHcsaA(Iwq=3WsI%5ubKX_sZctiP`9doJT-iy?g zVk>xr-+kRPt;?m_{Qy}ExcR<UHBUM7hbmjOz&eunowr=)U<5k4haMWy;cizIv?(n= z*D&K2_Mq&xj7muJ_woaWyNBTzlF0Cg+Ro3PkwEF>>|?D-<F0&Nj!7zs_)BVRx~d-F zho9OG?*#KL=W0<jAxoiFWL+okjNN(HU}4GPYx+D^>-54GG_Xx}SL5cOZFL%$3VKr1 zYxQ87_2L?YpjkNC#a8Q0+?0^_=R^n&oRrs)Jq9~mR(*g7=ChPyHag}rtQ69wO}g1? zrRsV4V8ArQwOZsFF!#{I{*OlhPUB1EPZ5g;cIrhr0Co0W*J6=mp%xG{iU%HV<QBMU z)jurN{`(_J;F)*kgweqJw!y0nU(fpHYkY2}!+@^zV7X9ORZNs(?AN~cEh)oe2>AkX zvT&CSX~vBhxsr=9Yn*)QMGSlE`O<3^7mL;jeqZy_ygamet@Elty~2pQVYZjJ{W!GC z$Dm_F{hmYrSmLYmYafKc``y3)r0!V(_*j{gX*EyXs)a}oVl-~r<p9OQ(D-PqZ&?i= zh!zFpBZK_9HK`_{IMV?or+nQBe5$u0T(#n|&R6+pPvTSm7=g|g=k9x!ch()Hfk$Z& zpc}Sdadzn|fZyYAH(J8W^D1b!&6}!_?2M!bf>f4pWm6+tt=gdTcJN7d4y*XW)5(bg zyY*fvhlW6wpg=XRjG=i@O5-seIu(U3npk?cViLMuj@7THTr!EE#id>kAlW#Hz68e} zo3$3nbb4Sf)DQvNzm(YtTX;R&=GXhnx9oqzv;LbrQ81Yde;(azGNH76arx!@l4cpW z#sSYqJj>=`@sd8ra=G41!K+~T&-{^{!jkksVP-f`Z?Zz<p&V<&O@2g2nBe2If7r7k zaVEKf*mks2aPk4+jSh0z+Lv7k5K=x3s*0tyIyowjN~QFT7yw+hUoBlCMDY0NO5*_j z`Jv<R_j`%!*EMYT5s9Q(CRG0w`y^@2vzssS86e1w6nS{v6Zn{IfzV-;_nHs-xZdPs z)X_9`b2!m$8lZ}8=q6z}qnv_cI+H|+PL79-v&z;?q5kA6xh9gccOL<+<M>%K5nn$~ z2G`7AV2b%GK~*&J^W(Q7B^!B6JDpgZk+g=!EJqPowZv{m*kQFVa@{O&8j`!fH1mu2 z+q*yHh@}W8i9G(8VQr(TlWEuK`zKqxe<cgg(GMjGYK0McLEfK+3*kORQ!U-SvUQwS z6~X|i?EE~c;P$dy)=w95uLd?)&{#c1i`svGp@?p<;vMHVY2HrktC?HQgw4DVkU>>+ zkqVXPOE7Jgc)tQ%;*87<9oL!T>?{ub%q`q=gJ>qpTu1!W-bICyPOU+0Qv<^*ec<6< znlRSaAR7hZZ=5r4sR<gXj~t3~l<0ggh=Rz>RZML}nwA_C2FhOajZ=hfK*WZl@(Czl zBS;qW*?{1dCIzNudh;FSRR_-s@*?jO9{9O$x8t)`pN4t=D!1Qwb;WJ*r4qEd=8O9k z{6XHBbU6>H$sduZn_PMtz1eFbK92AC5gE<8gASFuoVoL}ZZ|rvuV%qS0VW<xWWa&F z$mQtlNH>?eZBHL{Ry&sjF$@EI(GzR#BCl40i3`SgJzLVY%Z#bNoYp*jDF&R<%1lA4 zou?<NsUj{3myQh=jn}FjxdTWNgM2Z`&d!XvS`RBY0%*C(P=C@mp?R}FEKRCerB%3` zPH*L6b#rgew;MaND^kS#$dNK>sm}TaM2zKDgXoc&XsL!=8PK-}c88vvQMgKiC=fuH zk{^Y-u|1(7i2|=6FwKrohBMynqqvPB%6PAK%;vDJ;|E&<tZpW}xK{3X`3>%q{f8NL zHoz4Rhw=M1^;c9SpJ?~3Lgl?9^4<PKN;g`=<p=mMgXoL-8vD8YP0b#2UK{?TwT}da z0F}eZ%1$hd?M%^BIUk7&lzUdLlYpx5UM=<pfob-YW&VYP%L)a%l-#BjMR$qksx%rR z1K7!>5#A%tt%jz}>W1;PJbZj0#YIQN5w6Y7xt^k``wxi(43Q|UX9gC*_h(u5i#t*O zqs67lhUrR9CX-nYVb5ByCvC@zes<I;8t%g8I;s!7`r2h=I*dIu*{8n7ye3${(6YzW zWIz5uXyYeJr1lIvdy%w#<;aRE%Wu+2Y@_zJL1qX0`itJV@4K)b#}TrYTl05~#hp}s z0eK|j+{hhpTBH$7a^D}v`+<$myv{U;SlK%*Fytpp3l6U(6sbSC`!9jQj}ZNKPEC0U zW9ZOVhC0R=-BHYOW!=28Srxu@azV#MqPI05gWY&I<@4LYcN<ASGf~6}@la`eKJcb% z8M=!!7UY@#Af#VZ9vpswsIYm#KzhtH)^wI<mUA~WrRn3{)(LahnbIU<9rMQ<la0Sr zyGxDDC2y{}Eo+%vJ=`_4eoQvHAKeHw7#kID4BA^U#NAUbY2Rn-=9D=`bv`UXdKYSh zltm}vJgg%yo2}6PZNqulXaRlH`11x_x9t4RM-Tgt-u!j^plVS@n)<{R4{qLWQsliw z+`GhquV3&j$zD;DHB)S%e0qhNj2KmU@-J`qAMuqzvs*uFqdbZKa`HWO95E&C13DU) zEb85S54}6^rzQAT`Z-0$b>C<?t(A@flE2{I`n#{*XV8*1P3IIwYu&VtC6^?m)1`)Z z{!c?46{8_WTaJe9BL>lQqja#|7<kuKZbMlvv~kp$OW)m^YrB!FrSWpp<~$-BKWK2< z&zyP0I>(L#meDEJ+@kAR4;OQvX1MPVUY5y6i+WfHVTLfRWKj(Y0vLnX>45F<izbt! zJKY@}SMEGZ+XkCXI$e{3K3^Rr-GD9?;Vh`5c5_ZzMI$-_us#K>x8h{KaL<T0VzWAG zx0<V91kvpS>rjYx>0pzsTw8DQZtoG;zj6H`@aE4^Bpr{3HxBSdWtQlDL|0Ar4r#W6 zdZXK{l5dXq3p(n#*gvE!3B=ElYw3^&5=UzBPO-)iqxPVvJx<!ux%PAA&sTHxx9HZS z2bR;Lb{iwQItR48Ar=D2ZtAG1!Kkr6#E49PO@Nq4EZgYZ*VM?>k9K6Py|7<{=y67E z+aV4cx!U;i_}C^(_#MA)h7B**o-%AM7}3(mCu$H&09q<QkX;Oz<DO|P1IeB|p!H@O zrhGO}vbEf<o36A1smli|>5kv}iY6{i$d|qFVvibkPnGQn*hzETy*et~l~=#NUVmd` zit1#PFKZ=$sLwemZ-RBB9nCcM^-4Qi|AFk}jrR~=THe&~PD1Xg9d*DvNvuG01aw`I zvKk%Y$PhHVXIO^x`r;V$a>H%Bb&d?XXxFDGJ>)3VB==O=y{~L<qFn>gAoTeLLT7c< z6j;`zjhJv7h?LRe!((=5N4f-Knrukn8pL+h$sp9xaA?G|-O0KY0yO7pNkK$!Ymnh@ z6Z^&;gjZ#gPKI-iekOZX@}K@6Mdu#R^#8^2ZG_ooW^<X#F0PYHbHC)W&HWmZTWE6+ z2}vkrGuK?E+*7&bmNcR$mANZwE)}Y8Zb>D%CF$a~-=Cky<MY@1@jjo+dB4u{X%ORN zm?eF}PVg$fr_7&BsqQ>-zeQvk=pcC?IypM~9akY$RCg>q^?hZXzG9!!D4&im2>Hb# z#j(mMlW#uLQ?E1Yb@1~UdY{%>uYw7~oN3|T(x(>o_LopytY*C{YMHh`c?$qMb_XqT zju(H1jE^zJf`<~R)d8h53jG$UUJMglAHn4Pv9?}Pw_D&i=-34=`eds1O5a^BMH!ds zLEt+TYhg9W)Xq#zc-(KoBS%c}8T#@;y!&Lo^eIGxj7$5BS$*aSlvHLBOiLv_B+SWI zMkfrYy-q&FrkD_&yw-i=LGQETZx#c4aJ~UP&?C(#OHq3kI7Z$=u}_V|M6KEA3t8xl zrYaa_MK&!TTyRer>{lY}r|MO*$Z<=mLVQNP7BjhghN67I++G#J2V<zk&BFZji>js1 z_>=$kePH!TZ1+n3V8{;B7Ya^5^<ik);K}9{-^WG0R7%Ts?}?R@CIpH}j+L2j4w=h% zzeG4=<)KgLV|ybHYQ8h83L&RZG%7|NeS5cvs*X$+=`mApolliVxtOCUclVk$_o>+S zy-RCsVtlsul~D=nHOb@<%0Z@uz3BGE{Dhmn(d3pj+==m%(viF!1Uk@#)No<&f3#4Y zW@!BB)$NA0IF6j?zA|VMapq&H;DEfE3q{rF&0X?AKoE%ichVt;qQmVgkY+A)QXF&A zQ^F{_?iSe9eTI1@C}P(-`A*Z5!KEx;8Pza~S%s=*4@D;uBooFPFPD~%%Ow*yy&?61 zz5H@v8SH~0C$=fQf1J^UWY{oJhoq*HfCmuy@&ZOB$5MMwT6u+od+i3<t4Fons~jsm z^($|;-coz?5PG?rU(dJKm?hw$-e+#v3rTzR1fxOSi|Am}N2VD16`VIFjKmeP@7!_6 ziZE$M^}b9_FRFiix;Jv3Virk(_LGF5oS{5VGnZb;T-UpEL;B4aRTqXv7?_YVBKUEV zy#i7j?X!H=ufNVX_1|)<R-^HSmkt%sgSbrHcNXd_kjfGzR$k*{RN&KpeT1;y^%aIR zcz^s*7*M=a@MR-iKZd?GoVW7u7@136l5-7Fd`0`rz{gXdLO>{qY(o0#<mZ@-<6}2t z2qqvM_577%2MR<WgdUJ7E5cDWbIws#xHTfRpZ~^GuknQ<-CEv;2WgIaKJn1po%K7- z?(4_}sm4(>6fN{KN0nB3y=!aglFL^sISbc^c+2WyU4NoGd-}?$84+@#1XE)hM5YGc zJ;|p=rI<|*>B{!qSvh(^xydZ9w>tW>V-Ur3X?bipgv`Ee?D*Xw;Wfb*Y-FNfwB2Vy zr4TEMP1#J-KeXM!==Vk62_(>fE}zm$ANt+Y-xf`|+5>&vjpU_pX(+?Qe!o}VY(#72 z<dLqUh_>D*MP#+%)Fb%YWZhyDTZ;B5pGFSj!7`slCj$jK9;7Zy2pTl^mH_lnlvh)& z@0XI@`^-8)s_T4C{h&h)?~iGT9I7STR~9=wW8?1m{<^|YP-L4;UG+gQ6W0&OsW-<< z^S;%Ihr^fOZBtr=;DF5DLo5rW9zOA*i96I_N-4vP{jG)ONSUMD0Lom7%mQbz&TZrd zcWlViM+m;%c+qQ_vd#Al-EX$e$9qEw1uWvQXCC-zN*XiHPw>TRMQD&I*aV<V(6a@* zW=AftZxuB#4LbS-WOx;(!%wSx)~D>7H7Lu!$?cUdWt>5WtFZR9I@cy62KhBk^BJsz zuDw%tG|6_FJ0bUksk_c2$1qeP-~N=pM}eSW4h&6SM)u#@6F)dOD5$TJE}1}Io9a&_ z!S0ANl`LJ{%5(ty2LVh5{$Ver8-3TYPnmeetbJQRsp9$OruVac!H>#<Py1`wU+a4L z4Ws*1rDl`vlyIXh?jv|L=s`KuezfFR*Pm2P=soIsua=P4EUwR6$Wc0ut{-?$|8YM~ zN=k$6E$a7Li#VdW%5W%Q=(A5bp3ssy&C%-KDpu@=AyvgeJ(t#3%W8>--tj*I0T!O{ z8%I-)X-yHeoaMQEs=kW`W*tFqJ>7>u%Dxmc0?O2IpK_=|?^g#$E`i?jPT{uP$NsiO z9G5J^eQ}~4sg}b)KF?5?rkJf#w54cD{d`LOdgqlb%&7FuCHrKTh@e{Kg3Tc%VxQF? z<d?BNCH{DF&xRvv$C_n*e?w{)aP$1hevGyA(Iff^21kS8425AnRThIs`H;HTs~gt; z<#pw25a8sI=E9T6&kOk){T4t8evLl|nxiq3ok#gTS`geRe);1=&g<xvK9aAC10O(n zY34yw2-#&|oA|wKieed=9{1d`@_^4Fj$?|np3!=rP9)X*0>kp7W5R<3>%V-OmB7&F zEoSTFL;-7TJsp#xc_KHrA{_au+y>Ec#pwKg{2jlnOIOGAspS!3>B%Oe!g<YA(%~`4 z#*1NmAHIye67MhmPN54pJMFe7qWklKJ&Kl<0T3sJIKF(n-Wrqg%R`Ae*I$}XF>)p; zreRE}ZH7r)ua={QavWK1n_jowr1+I{(ldwPo1?mG)bnb#8GMjO^fh0bRfF9nWP%7n zUyg`dnwfye{KFf|-zeyQb6DRTm0>=~RAb)`9q-3axAF&wdvui?Xh}8HWt@9%bQdXh z{cG=)&ZAgvpFEdWGQE<Y8OV1WZ)mS<3de!VkyCs~A@&)I_n%-7)f{S7GU0FEdp16< ze~3M<#MBKjczpz64No3n|0(Y++s6RBh-Z!qIFkmB$S@zd@hJ@N@wZ8uucRvP^63j< zvDWc-u@^+{^h3V()@?J)f_e!D*?dPNU!LWJ1#WptG6}x+hg_h_GEB{!JD*hX$u1O= zQHttPs+j`cRbPAGA^wwtmOAgyrrTpF{k(e^3tWDif?pYevvl|VW=NcQ5J;;Kem^Gl zW*n~9z;ut$?f#NnGufw^3DT@|ySWI`HpxeB^MENj)6We6Onm_Rwuu)d?uMAN>YMMx z>y<liqkeu?lS7kzh3mg&58DcK3PT*HJ{0q%D6_Nr?amoQTHikL?qzCU<=Iq7u)+D( z660>kkvkTqVGJW~$z<rh*|P82qJOW_RNu}ZpIT0qv%o=37mfsL?E;@mK$;5R4``Bp zL1oj(vH8xu<vx{{sftr~N=%LfnivYo1)0syP^RlXTq@D8lst6drB6t)_3Vht*VQmD zz8`%U^BfAbWZlfRl7G`eFRa&?YOyf@QrWeGoiy9?e9`fZqU=J^AR2~FGBT|k5wCj{ zd_nCp{2iAfdxDW908221O15tY$SPz)dvrZI0E&}>cV7{FCWV$GGPS&i82tBwe@{1~ zIj#>oftB~KD3MR$9v!<jbVtVN+Vd}6jI;3fMi<S;Hy}yQa;mhi!%9xsEuS7bZmr%? z`+3?;^V0I#``?{K`w^aZPjJ%34;M#z-wPeDJNBsf)bR(W=Ld@pmuOC3+6VlxI0trm z;`Iab?b$iin<hSW0{14Si_ki0LwT;*p~8T^p&=>8LUv?jZzcexab;+A{&n7nP&|lr zw^skn-43T3e(DU5I{aYbwm{|a@8PdHkKMM(#{z7717O#tG84}@FXCDm)-5N_#(sKH zu$XaBf_(Pxmy-d4xCp<kPviBTPj4ij|M`8s#$ZSjam&ADrK+qrzo_Nprg4Eyp^wy_ zZ3$g$A`Rye@+%n0h*n*ZO2m9Vz+u!O(zF2y^GaCtxdIzWTa$1?bzYs3wa)8uIt=h8 zzKdBI8m-n~jV{@z*BL~8`CNeUH!)f&aSNdfmYj@5SdS={k<)FxNb~$fwB1Hcg1_#D zrtJCH#E&;OrpFIH(Hc>o9Mu_jJUXU52CPK5M8_PE(+{i45O)#&dJE~2L?6{*pxi{Y zgN(g{#e?$3m0SVQ9ILi`DT+HTuZ>=hvf7RbE{rre7}MbpR#uOD)5-X#_6{Yh(it^4 z6I$XWrIjY`v$Vl~J^2ed1C!J|e%3Q$XWmNYV*1Eb5#a=V@Me;WtIG9@&wxD`XYNMm zSVZfX$J<j~--=t#`*&HoCrxLn$lGt)DPxaM4~LGMgWYr$0GMq@SHI1fezC;(`EdPQ z#fP<p2}}DaLj@-`X#yRSE?1o}S9}@YZn+Bi3=S4ol&K(T%b)9RM7e0)Li*$((r+X# z#{}2S#lOv#iD~O%%0~AfvP&<7k29|(Yd6;4jGp-QqTIK)eF$^9z}e^Xt+J>j%}aap zOJXto@A;1aFy+eV#1}**%z?!smnwf$BYzDO;NsGA%zyS-tKikLkaB;_$R{YiT4+8e zaW8mThY?;SRU3)B7^CO7%uCi4OTF9`^WX7aE_4l_-(6zd#|PgiezcH|VPtQmSDvX= zt;cxzcJ*Jqw8l}chz1y1NuSJ*pWS&I^V08}-V7Ltuvwv7l{%rG3!q&rwLeNac$5jC zEfx0NiRd89nc6D}ETBxJk3Q#O6@xVsR2ft{9*R7=Y$q>($Jtty`$_mqr8tC-+n|Fx z4>n480H)J7_OFriT~{f{{01xikcFI6qe6f^f~~<5c@coEypL{;w{9~cH@31*Jgjm+ zZFS?`S(3t`Wuniw_!5eE3oA_n<?wy4KuBYC5p|>CfQD~X{)Lq4i-H`qlA|l+DLz%V zn$6T$7ze-P7e;Te`<Zd`57LGMJpk*+&4|FPlPi3XuMoQIHV5+54xykOfFRqtbpm4- zFCDB(*C}^}`;KzNhosW^B|F6hDGc6#{EQ=@tLX}>23Nh6zS6wW>NT2*Dr4;rnm*%* zIEkJz(QIE*(kip7MZ?l_qM2qq3DsyyFa6O9)680;AYqzvB43KB5JH1oEnT1#jSnbi zh7AnnY)D<>3hLBxpoz91?b($86jf9>x#znjOgBwqxhjWcnd8oj2k`AbfbGXv1QxR` zO{YtTT2>ZSD}E237G{9sP;PO6&Otq1uRZ2{pp@I*ka05ye2KltBup)t1EpQ)<$~#5 z(-e(eV3yA)A99j}Q(I$}`4JUp4?9cV3AJUJ(GO`q#tm;vP%Q1KmJz=wqjX0twoZSI zC8i+2&d1&G&5DKO5%0N$8?CUH1@c8hUcL@ySB@t0$j*vOFys9P^3IIzt?T?7gGK?I z+*qNH;#b*&=KdSm^r)iSem}y!r)hbYEG@ttD;ZMZu5gde1*>1wR3*3V$9{WGk|Qez zloZcGhcc@rrO}I`jl)l0&h;YH-=~?##z2$XdnG<!!Pem9bFOqZoEq!-;34%>;b<fS zz1?X^-}@vUwJtANeK6Aq$d(CbSs{M{hRk-yVNMAFvNt=25^{Eqy<aPSPzL?V<Km`A zt_Gui7~U|u?*-8xUQE2!=%^jkh}fU5rp)na0K#ZlCt?ZMo%uJq#;%Zz-WsvJPECL@ z9rD{rKcHAHM|;~<CVZt(CeN)b!kUf<tq=yZ;0};oe(x7VMJ}R#1A6dX6V436E&Jvk zri#mk(j~9k55(`Ur(Jt}c&?f*{+Y{EUa87=RaB5En<&|OA*1ig1-bqrTG6f#iHEH4 zBBpbh;)k_z3G%68o3`m0FV-Pgq+$!=cV<L+D=7xSlpZS`(j{_)lUFRHW~T=TD^+9C z$+s{@d-eu5S|PEPHI2u!1hn4qhz6Aks&n`Qs%xqm(3fQ|&Msf~GQ|scPNkyG?D}f7 z809<sp`d{F$35i(7lpFqX?{lPGJEz*Cv7R&05(6xxG>+lP+q2+1WQ8q{^$BQ2vgYu zceuEe=|8F<Gr`}(>xTxhNBPd)gb>LAZuv*|c^G2=K+v;=N8*+Z;4t~+jA!Sv{+lVA z8H>N4bn&;aS$jF^O6idP_Qs4`1}|}ED;0)zgZMo0Dt>6Y5$@PpmA5L2yz88v%D-?j zF<Jw|6Cmp-a-;!{NI=?o1TCyRH*pn?-ccA1cIpUjaS6oK<E%{Gz7~~FDZHlALt~i} zS66LourF77H5E;0!sgeOlnfHR*G2@duU5k!a))~Es`_WY4nW)&4KQmf&`d0?76b53 zG3v%2+#xQJMW$vi8E=>bRW3`-xJdolcFpouM*`|9OSQ{6r!$>Ad|xC8@DS>np`8!W zy*S&aJ#AuwAd>q7%}n|uWNz4nwEYxY?@)4xpzEO@nh#Wd{{8^`o`04F<QekB_Sk=C zF6g96juCSZlXCv9RGP$w;kC2o0g&;qrIp8>LKa?lg{M^n?2=Qd2?2klb#xKk2RN{| zS^{%BnToEfOg9VL7JqB$D=WtDP@MEvyden$Sn4dI1EYC)b9tkiyBVhIpoGsyZq7*m zvymBf&i3)8U}r1OstEBpPW20**Hdgh{wT~pBgr(+0~i-9hFo6$?}rYjUx<Ye5LR8h zd+PYfbTcA7u&oO2zI<`-u3}u(`$A!L^<{&kKD7j8i5=QnCuOY%EWX3T{YGBr;!Q?@ z;_{I*4X63-SPzmuVgAu2_n9=5fDn?MBfV0EG;7o%f=cV?itTurBp@m~M-A04@$U46 zVL<>1c;rULU5OfjOOBKFc<knw-fr%P7b2(?vJ{iB;|>pKCri33t4A-2MJ^h!n$&d3 zAT<^U4B|n}RE6vg2jC?EbK=bba=o=C_Uj@WqLr`bvCgyt9LL<6hDoQPmw>S4vFxSg z|D*$nNmW|<eCXNlfBy-5kYboSpZx3-9<e}1gwRl{HZnn9^zLVhN7H0{$ubSAN|rE% zSr{OlJRg-REuo;4z{lvWURYX#-kFyrHSZQLtN|)9(qx~`#T#uD$4w%-NGpxHg4L#@ z>gExOEV2DK8oHA%v19pHy7%axbTOjB0L~Q^LNh<;BtHRLS^56iekoEy4b@5BA!+4C z69w<l#Y;KjLMmU|h`G^gVt>-DJ#MS<i%2@&QtMw=(56Yg0N&{CmDvGG1XN*j@>SPF z?(5cLUjvcO9I1jBwCScoN!_^}7E*g2ivz~`(#0)<QPEYBN#qE#!0k<-B#GX2zq$or ziBfFEr-0FlWQ;QNE_GAanO|?4CP7S#UTG~S6&%$DO3poxCO8E2gh&B4)mF$yd#Vj0 zTNj?Gb0+HEhlHxV;9#6-3Ov6a4lk91P<+3s@%X@jK$_?tP1G>GsvWp0k$q>Ib8BB7 z6dJzy5T`|n<k0^tZ*Er!eZ*sp$<M66w>k$(dXPmH@K`2Iio$Rg$_ONop_?@NUVgc~ zywWE;?rFf&!CnJE3Mye<P2_W<h?DdVe)poQ)OWn>9_{cH5U>l@Ox`kh*&nteDlwb_ zKSDFq21<OPp^|`az3@X}-zVc6Bn#IP+pSR&oEo#-S|Ntm7ElJVc-rjCq}b#i0{vMb zUNH0s`aT)cKPTnIk9yR*8ZfT=2!wqQYXe9@7Jrcz9lbs`A~V-0?OdhO&A?g%r6+(g zujgfLIZ|PQhDvdi4}Dnfyr^~?VuyxF0LECW%P`4UOR`uPIipz!u)n&P*njAeJ{}8L zo)qq-ulI|~R+X9M(xexpE>1*Yc!hSme|sKk2?UJhVe(g%{2AgBTs2uCWSHwhWI^cO z)sPFhxE_v74_-P!Kzce-{t*hWH;>u`$w(DSQdpF6U8nIytQfg%0v9`VaGQ16_7fh1 zA)_wRB)8|KjPd$;KuJs9rKY~)Ql#0K%7KLm*{=$jZt?^U@>7-A9Q|3Ho$1GUvig~} zKc`l7Eo7(#YRmNe$QU(QqW!)8>lbrFx;fHbMaQbDFe3Bloq5Seg{&PqqDfJ%4kW&l z_x+EZ6J5`1Bw*$tfX>5lHv^@&$zm@itJ-Lnx927IBdd@Ens{v#k0Xw}h{ss=Drmm6 zl&F1_L_cbhb{HraL(#=N`<g?F!?fLgA7DSl9d2VUOLfxhx+vH-yy!U#D11Ufr3Lzv zer%`;(*u;-n?EcT?_gMkS*2qq$b=U_*&O(NU9wEGmE05^tILsUzIBDE7i6`gMr}ZZ zK*gMCve66_W*+%FU#1w3O`=I;^J55KylL)H#HKPL9z!6DjXu|vvi8#?KW5@3SL?Kk zYF`1^l8lBAlrxIT5EP5dFzdkWT)u<LGr(l3b<Ia4Dk6E2$6>r=6J8=n>D0}8NMDZl zl_IGgyxJ}&t{DEpKhz<XBl?eKwtw+#(BJr=R(r7|pahYQ@ee`ITJ0SCF=r1$w{uph z?qOQ}<R%r`lOorvWSL01*o{c3rbvl)2fIR!-!B|y*GBbewPO6d$zx~rwkrX#OTeyT zwc9jw|9oI94NcXM(5^yI@t72Y1W!Aak{Uz;KH8rq+Z2d3#2ch4%l(;0$w$iVt)0GO z;H9@JP68qqmJabe(#H65?W5vbWPSB~f_b=!jGoLz4x)cZE%QoOf2a)GS!R=rmBnLs zs-#zb7UG&dbc05Gf+S;C&=Nyx9t&r()okKxl*2)WUcuOO4o8%Zzy(UL;62^N9ct*< zfU3lfMcF|b@7xHrUpR@3;$V8oJf?hTHV51EGby-~@{KO{4=<rPk6;2Nq$Q+_$&!xr z!ig<CX(34>-p`qN*oZ+$wNp?B`kLOtz0Q?zzq0@DrFbPkghfKs(P8VihDbW$^<tO! zGt@03W#R%2!sL}7;tR^@(I@gHl7eJ=XtLpwhCTP=(N@SEpmZia^%+ox3zUt^L21&& zcIip4Xb$OBh$o7Ns!yjY%^2vZOZWnjibQ0*lEjx!h-ZRdso^qVk*=59jyif{2{go> zn1z{qsl2?*ZXu=)kFl5%do2ihHdnUI`O=W3#v0Wl;n6MM)Y`#-9SAbgGuQK@EU$st zG$y_uP5<FcHgH>bZD<3!L$^P#lsZh7enFSUaKsJC-tN<whp8q330GdtDCj|DwrL`9 zRfL3jSt3wkg#%WSH?@<0yRLLm8)0Ruj?N)aQnH30%3GmQ{eR~MD$<ezs6x?X8JE+= zz)m$*q>TI0nL&n39Szmlcp|MvS~rd4QWvjqPA%vG?#BGnL7J>s<gpq$>IGfWnu9DH zkewnU<FDe@0<I_fpwDN><p9x`dDJdVX4lZ@Q`MoXQ8Gby>4bS(XK9<m6hZ8~q+9+4 z%@Wsh1kqcnI!4Qg0BUm;RSW-&?(RB84UF^N^uPPsI?T!FsfXc1{8?0>a{CB+-%uLh zJF7MreX#+*JE|`I5V-b-j=e%d8PcWxkjE0P%2}_~D_!G%TPE&ENAA+FwzLzpD%~zx z2E|=!j<=Spt@dcWHjem>VR1+Dj~5}KGw{bN^S2*3W4*`-3Qg!g`i`^bkESd&%0gxr zP!C~9r_sfGPRcfuC9TO?E1ZDNYVnZ;u?D=u<LYDnPI9%tfHXYP1uy4JW~-d<wsBc{ zO-C|0$mldlFB;1DcW!l-(jA0kFWf3&b1=FNX-RvAp$+#VE&kQ)Ea3&=Yi&%t%pe_Q zUxnJHqo|z5Nn2qEC?IUK6j3_j5z(<(MLkPKdf{cv>Pz`1%=QhW0Ro&i+-NmR8+YyV z@$&i-&v;6flJ1ii_I8Mpu{6;ybO&#`*ecrKKLk>fCcW~u8#ONQKuA)bjGA)5hF2k3 zyJ{{qNK~zrys{#tP+}K{Ma{cmeHE8F)ZWSbO!=Z;I{KSfg^34>`Qowbw%3YL)<=!i zd+7MzlZ`#(H(%)Txu*jU(V=YeI)K_6-pzGd!+LFbg@#D)k|gcV{Nxw;VN646KX@gZ zttf4U@*qFH&snu!tey0ff8q1t&mBdnWGzn)B9ea5kJ<JRgj~;v$-X9CIPYATiTSVL z(%c_?M@Y}R794*V=Hi%I3-8;UgmeJ{LWXwj1$o&vAasv*`r|0K@$ue2pmgmW2`*52 zhX!#^myXYuUb`Yjs7jJ%N`!GFJb=}>g4Y%S-rv6KMCmFRbHprz+e$b0HGx_ZTfz(T zF%|(w1yx4E)MISB%^K-1F?0#3HE}TLMM+#r!wmgYFa5Z+tnu6HW((#YzzYu*RI{C= z{{ZbPPMbCTUHTk3V@TfLlOik8F;k-{PbG3Q-uW%i{#(|-)a6{Px5KVnD?GAiP9XbD zUskka1cuY$qt6pjH1Xy6o-IV@aTvgBbN0WaC&e`M{d{q=q1MY?Y90_&&)}QC;*D+# zs3bY{_*ATr9ba<6OB1}rlYXYlleP1Z^nGRWek}fFBGB3XOb1jdx9ewa1u(C?YW=%l zcn9#w_T6#Pd%qy&#YQ``z(52*;D^3z#`1>kH8&X{1*Py>>-I);XBAqT({?jSok~2_ z^I1Lp@57;a!<iiU8K|QxN5-FaHeqrtasPJlH*qgIN;nQ1z)|Ull!2B$v!2hfru51P zAyXPBe2laj9I>>%HYt0poo~*|yv3dWe4HPXyShJn`1zktm$cO+FyvO!{60}uU1CL1 zUQ<2H6`8%L)&i8?!y`?|Y5;~TAZ`T!m=+wHH1|)PKyQZ<tNXK1YCheWS~Y{YvWJuY z2x-?27brTEn`CL<dR8R;=I_>i;mH}*q~8IjCX2Fe=!6S=`WB#f=-T}d%gfSJbuf}n za;Nb}2LZsB_C`S6$Mcq#ZxE|(ABnt=Uv)DJ8L4wEulqhNpZu&m__;u3ge7fD^K<#o zB(9_TeB=06OR%P9rQF}P*<<-KgHi9H3m_NGg^ma@6&aI(+c!DMVqa$>`oCfi9{K_( z4g8sZ>&vU=<Bu-F4&Ps$X+J!BZ%E{<k@ZM`tA*rcPgBRq<!}6RNaXRmc18LYP3~Cb zqk9DBF_o;O<5}E};K_`$>hUgH*$)^)PSbBYxj+J6<yW_Np~*i%mG^UJO+2noNA-Pt zX7cu3Jwk76g#riU`t?s+zP4T3&ovmgMACHUOwI@!|E@TbXIZfkn{B$ka>d$kpM6FK zp!#|+;Iifup}-vN7h!HuKmX|1Xg^QrJrcdm)ydX;=duMg=*IO)xV}Kw*17?fQo%Z- zQkKV#&3FaaGn_*L3$M0pd%n^tT)CRB{q~O=xNNLj(p6_|jL%-f=f9yz|F@%CP&M}G zq8y-d=_uBE2h3+@Dxl|usP4?E&eNMq2}IOx6Jte<Kz52SK)vnJJo7$c8{ASi&py1d z?nZWa6Y_oWHHR=<-x1}Ht5+Nhw$~>z%w9q*UMf9`RG2#cEwRI0qtHa$Roi7`YnZSX z89ZJNaH)m>Y~3a<o6Qgu_8rZ#|7aH;r|A8Btuz_Em}B`iauI4ey6*biq_?}|B>`Y! z@yR+81Q-i|NW0J02$&vR*JEWbW*L9-3RlgL-Mso-?Jsrfh~|x@ko+d;)1xs%m`jd` z+pEosaMiLusb%@Erp`bU&&>`<od1U2mhfvYWkenuS?SABxX0}aIdA#+W5}V>rPNVf zcFq;}c<+jigVN`$^M%(0lrlf0SQ;;0RT%1*9Vcw9yz;bmQF@3A%m($q0U)G0`|bGZ z8GFq?UiL0zL~e~;5bBfIa26p18atnk%}ZENE2y}v{B;Q=tjeC^^{IdKfS%>ER;uA{ zQTiiA=l0@a9or6HYug9w*lByC#-A<e<SK0vuDxvig?i;^w&yPP^1kJ9Sc+euP5T;g zp+93Op2o+DvT0eT9MJ=~D<oS^9eo;q65*`x&HT>`3Df$`61!|X!AceB6SzKk<ozl$ z&_%r!5S_oU^CADzzl^&CdGnn0dvH&xyhPS#0Rt}yDbE##(KqjxXX@}-^@NCnl`Bk> zhAL=hbEy1SB}6%rcIN`i`FKnfddj{^oOV_Ty;DBye<3#OMeC4Vsi?IjsHkAb@rZn; z+gnE53L)B;H$F{RFzn&vD{fjyaj7=uYvcJBYx6B8=7xyUG5N6#d@_JJrV6xIMEvvV zoFMfY^zlNOi~B41tQj2Nc1x&{uQ~-qI-c(fVBh$j0}6dKY;6`zzcmkA(O4`W)?bQI zPXts-lt#Pxx)b15URH?$=z+k^SZrvt1-g8CZj?Z?a10MJZ_V`AyO3$$VU&LAHEzLd z7oY28A86CCZmF37O!vD062D7I)17k7BW&`?Rj{nhds{^=UZ}&>8`bFC1doMfGv$_d zZSXFf{EMR1h4mFfCdDx#iENJeOsU`lp)8x0PB5x@I76RG6F#m8zwU9(`-mkOGX1en z>_|Ao?LY0D`a2A<O*i<fB~ET=vzq1>Pq`vHqv)Fwpa?d;bx^!kKPEFU`0|y7UoIQq z<C&Cw)KkL&f?*Zdy+1&tWsYCPjFT1F*^8=7u+lsjpM8m{p#7C-Tj!xTRw;b8;YIDT zx$bx-Aq3?9t|8svHZ9kW%8<B*8#u?%)}(}6U=jUk1bw>VEm1K|*&sJ}0;1?7U@pQ3 z_NJVAP9QP*q-nEMnscUQE-l(ZriS$V{J*X{r=}PZxH4;HsGjK;IpLzMIRS&De(>d1 z3aXafWTxqmpLV?lvz<AhR^*kR$X!I$28YUK#wbvC6eM%jGa535-%dY!9oPj_2<Hi+ zFRrJeSfv?;((bu2s|#YkUD7p-wS+y^7tmu;>DuW9mwkCz=3=h{n!I1yA9IN7$o(1W zSznr{hb<4;cks6Mifgv_@K=qFi2oj^&tDaaQV1K<8ungQuxB+~(VD6e{21$+rPI^f zwAC<V<^#^X==U90V>m#s0X_-iSCIW9^vz_K3*IcV)#)Y;m<o8loykt<SIiqXjk1JV zb8E0g*TDu*q1-6lR8&HhjlMNm_;_Kj#M9jY-q3!wQx4eW_=d<iRZ9CQVqo{=%7FYH zxI3#<6?1vm#w^myGbwTr{pib}?jEZ<Ga=9E8QPlGS>=J*69pV<u`y-FWIMALLd4eu zbQ|hjQwj0Oh^%z7GGCscQ#$t2lAua_O!o2SRJr@=tu<KK=b3k5q9f}W`^xda%fXTD z(t=Pi|A`+8+I}AAeoezQMjI(ytHiLkpcKN5pyIEwBSufpU)GMTf;&tvc#Dn>X@9AO z`?K+w$Y1X*!x4y|AxxErJp+a<p(MW8zNfFESCo=~DM@qkNPw3>AnFVO6CxwQ3yvFh zXRO6k)JR`#$cQ4>UOvL(h|&~&Yrp4yzi^2u_s>O8flA8<zTiW?T#hrnkS6*29ppq` z*lvnu!I1vE<}=6HFS;ar{)L|A;UBq~U$^I%UU1||KWB=}c1f2N8%2%v6`h~xPiVR+ z*33yHZ<xi-XS;UFqyLLL6x#BDnq$4>(aMzpa822C09EP>$;NzYUrWT(S6-q402t}t z&7WF1|JC=U!BgNI+&>H?SCeVgOl^gy1}<oBBR*0dw7xPo9a4Cf@Ul8qLpV`S)hDXV zMrp19<`x#=_qI|{ZK30ks%KlItevE~XzKXUy6fib&dG_4ai~U2NCvcNP@fo+7vtV9 z6J?Px4U-q8L;J)7ItR>0Y2RC(U))iOdPUJLxEw6X!lbS{)SoL@|0BKR%m(ztPT0j< zCZyiptV}yPtL>4+%p>rmiY5o~@Z(b!GS5@KD-8$s)x^ESv8e+UhHWjbE*7%6rc?vR zc)z46!7Tub@Cl)W7>Ku!Nd*8*h2rCCKk3g!i}Xbc|B2ogk#2(@s}*5$4|ItJ;H}Ri zZRrz1=WC0=r|x-ovyjhuK0?5SoKV{>VysqRBzi-x10ei(J^Wuk;-xs;b6u#g2h8nJ zd$=y7xFoydZubf#Hvh?MkpyQ)gPSYiU~OFgA|4G4tT9Nj`J^9dA-v!sGQlPuz{5nV zz&W_2<>&x$p>&#;bytDR1XZiM2mFHzdvpNu?*M~iqc5x?H#sL4rF{_z^a_#ZVY}4V zfRZNDels}e53VpCz=wC?`%HqhvQjO8nF7GWxr!GgtD<XgB3w~ez)zL!N|#qOEYkqq zK@|SYb$@jRF;N4NlSjnx0J$+|KHeiPvG?J>Ng~Ji0o`2NI(+)0;mg?;>8q6@Jo;1% zOGt1Twp|I{ix#P5K`j_|!CO#Y1@MiyjD<JKJoZ&2fRd+cp*<;^QgkYfz)$G`{m0Ma zda92YAVBSLhqbaa`}Kl7;e9<kR3B`+2j+8B#iZ5cvTpXROvIFqNV7}ae*jgWA>JxT zbUQOepuk{-t5D0e;w2RxhZRV6X?ednc-IA<lfqjO`@*ZpR&LI(jl4;saPovwbDy!* zJo!qGL}WE(;*FA}R^}}LkRr;b*TaLD2?y%L=<zHTqKxmhi1TE4StVqWs`=j()O#|& zuU?N$<e@(75A7Thr+c~D?k7d-5MQ(5WdIm|RW^Ss{O=sNe-7S71fSvq?7Nstsg|5E zQc&0u+qM<@LxmNRMGVp*lO*h(A!6GFLTV)^NNMW!DQ$5f`9%Fo1F{P?>MylCt4Mso zRDsxa$OS;51YZ3JNcgywzLXa3kv6=X3QjD^mz!6APtBI2;YAl<#T&S@e1PHw7C#66 zY7VTJ3Q6s;ddeHzv#S{REZwyMzsvFq>VfyOOI}lxx)_>vhKNCh>{++mga*vsobdDl z=Da7ue_Z(@BX2f3`Tm^q`}r~hpuez9R`NVly-(oHK(I8TXhzgj25-8=m)3^H-w^_| z_6Y5;RFUL;k#A=pNBBi5qFLUd6>#CICVIu!XyH`=cn@cJu~;gA3VwKndA2wBEiq#u z3-P=jb{!`y<#{5X5HdCnrQ)$)-FQ_1`FhM2Re*XG1D(4cd7cBSp8;PZ=4)D(BWR&} zM(}Q`5ieeruZ{k}f`pvAwqharpzGQRCTu5K<j^hoR>`Up!gUzD_CG4Ld>vj!68<9! zvucNTlXyd{7TZMVFS7nQd2pQ9k#n`BV?Cw$(a>MfRa@Fu9T=sytru$hU>Ae|ceuhn z^F}Yn#jE%Lk4QX|=OM->rI!n?bAfac6<t3g?w&;C&?U=V-~y>pA13Yjz2GaA;H}F2 z<97T7M^QOk?$H_Ev%=yu?b+?eO^B{>_@P#43jq9k{n8u2t%@GFqY?7!gru-u^csKT z`y%I(w7?Of?C@YNGdqaln%u%N>g|C&Bns_S3aNfNa*3cDReh!;qj6mv+rcC3xm=Jh zfLD|tCUl@B(IUn4=1(b>53QhGL?}1qJSQ5`U&-!I5&6k-;?B{QT%aSh;DL3YC)urN zhtsRk3iU3qPU6|$I7@>Juz4?JS{wSFEjez>NdN3{(<1q68${uwlS{QmXAOc`3m@(g zEIF&<Ujx5iDfD^wF!HCOsHa@%tma0H_gD&e7ywY7LA=9Byj~B;j_DZR*$)t2xb)ix zK28$pD}+1%z%sc)H+X<oBE;MS9P#M>eJ-RnTKFalvO)wKh+BQ>f!}1MEl0OXLpo0+ zDSTW9Pelutli*0uEo>K*ngzaI33-XTbm5`y^D4^O2geL(!tE@mF$b1Pzb;dySUm}D zXJOJ+^f!s{>=euwvIorll16*vHwL&6aPHXn@y`o4#9j664#UTn%d2OlVDci*S#-X` z;CdeHj@x+f7<Ib`K13DXp;GU4!uv!auEOwJIDw9J;psV_KQ68R*3Z%-o`_~k|LIZS zyAN3sg}Eeod8&!<sCp$XkXIx)>=;DLNb{UFd<1Z$og^7JxvxoXgH4trZdgb*uM2^- zTU383zo}Pd*;oHiDeC@BDHXMtkawL{Vn{_|AI=G9(OgZZq@JcdjT(fUBp$t%0_i1+ zRD2An8h|~YbJrTTH@YAqB$f0x1>8cEy0I?2lOi%uD&2DSiJfCb16?@GFgmHLv+#`l z#69>PQMeQ!JPZI2%sai}K)M0KEGpzSv1fG?`ZBia8SDD{aOL4>-WG+Qn`oRBb9r<% zws-E~7c|yK`NFQ=smheRdm*A?Xfbxrsqkfs`lXPr9&kGqoL6bP(&J5f5c*e7Sj_@~ z=w<UQ!{;ht8sd;zqEPhAQTdww`tHlaS;DoI;D4-rFj{QjxoBW62S!zecCSOSslwG< zA*%++I$O9o8d@!0w0^)p>0Igj$)FD$;fFYpUJ|?o;BW7G4(AE>RMyNF27GIJgl)F# z?GgG7Nu~f9cE_cD)PvuL)P_%nycdQ1$b>w-atf^66t2%iZ{pfiEw@R+cZ^SWx$qvD zU;&!Q*ST8_Io$S81=B<*mkmE@+x7$ZyzloZOI@Y`0+Rp9>DOTsSBL9ZL#4Ob2svH2 zk)ZB-+%d~V*@s)_HW%b>)W9S^W$`cExX=X6bE(PlJdF7}E<=Z$?CcPpIB`<t*fmkO z`Rw?gYDC-_q1*t(8-Q$AB{8z*_<I1jEP5Y8E#V$_qCYjv>57Jbe+QQ(44~u?v&G0g zoJfUKaLGZ0b-)D<1JPd%7fHi@YqQ;>>gn~t)`{&8u8!@~4#{QMtt%bt5!AT%8iIT^ zDLXHGweQfMk0<&nIo}GOx;nsSNyEGLh+J|UU@jE3QQO6G2Wee?S}Ve1Zr4zur@f!} z!rmVL3Eztb-vy9Z>!TTZ<C1z&@xg<d?T^02CS32U4*W6kmMt{Ih4qnO-Bf0agY6g# zvPA_~lG;zZN)EZe#%iJyi)u*@C%yxPy~n2|s-n+UNqtZj`2iTb4uJf^iQG<X99zHY z`y3}=39smZQMPXip<%jOLR&ri@PcvuC6<UlDWrjV`|c<B1Fecy*u3Iv_(>wvu8_B9 zaAKy<GuyN~SjgjpHHDqnVHR`7$m29#?tB|^j|6TydT!#ug`rBJV2WNR*LDbzku(4e z;6jpAbOBuOFb*eEAUQ5&^2y3{D-(Gx=Ay1?Af*H$*e^6Y_oVTQ>6;$-BR0g%U8JoO zzQPu{(F36k39aA^{iNqlng#sh!YiUv=D2WJdgt`jB2E#sr7~EW6C8=K2p_Fp_$gPC z0$CtJXQ>Im35oM#N?jK3%@v>)<hMO4h#yt(Ew<3_+o*F>x{Dq8JK*d!GJKH=1Li_< zf8_1*azodOq{#b$mEVe@7GYMpK2G&<(8Z<}Pk8w{xB*cTzV?-E<pf}X!$_6WE^t;f zSo+DAf9Hf3zCd@|9-&+(UQ`bTy{bNMFIma$>0=|`0>DnGHgA=96$jf`e-ly-x!yAw z(||2wKb=)do(_Az?TSl`QRyZc{m0gQ5g=>0MEQ?-NmA?7<{1(AL@fmsR)K&l&k^M| z9eP>rLzco_IQbp!+|#@biA?DSJr%9(BJ31_-|V+yc%Kjd#m9+#i@WmSjaAueOy;Z5 z#prj@4H3@b^SXO%@HH0<=}FDA`<hn{3;({|@*zw#ri~?AAXz1Z@~VJWcwtqs9T%k6 zB{;5a3;P75Ha-u8J{H#*`Onfd?%F;8ViXMhCki<~CssfH75#E2h^e)o0)9s|`_lsp zOM(1|4&7Dp5q%SHZD&%JQZF<rm+tfC%i3${Pc~}^jk`Lqm<|}5M;tX{6uU=C#N4e6 z|8IvAT$TY1;*S1c=U=>wsuzvAOcQ<N0{O#*AsH#6c5(c_p}8z@CJ~%M1n08O->rnE z&LwHmMQ+R`-F?5)mv4T*1YALdukgVpQ@~*vMG!Y?4GX4%<+ZIpU21_5@5)Z69ol9S zmZwz2$*5ZbL0iwxtaY?)1BQ(Wh?O`f6Tf%lW@2}bU|3N;)+r(P6z<34)l8`9`-c7N zvk&q=bb9p}qQ3-(OPKf$5es~ZzaG;J?!Gv~@DvtnJaYHNOseAQO`~{#drQ#F#7Box zt>726-jmBt6-H;*mS!eD9jPRzi6{wQeQ!=n-FtOdFy#%=adt4KMmR;r)W3Gyb<y5w zSwE@L_j81YM4f){UVJWyG&W=J?|Llcxxm$yHrfVi;M%P_U+u%UaJl96&1KKq#+K>T zR^RVBw!AGK?~BWFdlEWz|J0+I)hUzWSC*FrxMK%X!e8&2Zdx{tH+ny1f@SW1_ceXh z5#AV><SgA4`v>rDar+<^;8Yv%Bk?R8@Tk!0){%Pu_j_koXF5*b74cJwJL@+%vn;vq zP;uXJYK46J^_}C7k5;Z2ZGAbWY~V4}{>snp%_V)>^7sK{@-}d;Y;1XizvM4~Yb{e2 zG8tO@xbvj)y;BY7^c#V)<Mo<Co=NLu!9(Pb8!c{ecK2ZQBmF3VCM{j&xAB>e?Gx^? zciVTqG}f1UIdUkd#8_{E>q#rBxd)>xkFqh7fb~I{2tbNJMUZW4J@zCc>r;shRZB4C z(rfe!%=ylvXPork#%(znE>?g|oMPt%D=uo!-@<xLmxfjZzpDwAbX%^<uY=>qZA$xm z_Kx&8`z~0QI4qCUkC)iG+m&5lapZ5((qq!^^~8?^Vg6|+v&tN2ldP3myqXHs_LHcs zOOjktfndsm=x_lEu1D-$nem4+_1C<l5mu<6@WlKZ;hp3=?X>sTGUTJ%f<Ko>?2HFV z#c}8BZ=U~>XnFOhzmc$#(c7~>{Sp?7N*-PM=l!|CSC`gw(}4-hxaq?!74(^;;+s9o zD$0h$UADE<Ed@JN9j=|SM&BYaJId;jz5v^fTY_UCsuV3xEx0I&Ii6D<x`|(u$^eR% z-Lm$JQS$P_E`BMabtYODJ|A94E4mXGUgvT<JvY80shGo$bY0+uQ+;$!N|#5~`kibK z-a#KIK2r@8Oo?ebpi-WkFdlUM%r4mA`kA=#v_jV?{1)N-r&s4sKl!~Q<G&w2`fCX3 z+==!?(rWSPH;)c;1-azYE%`d76;&!%ePlh-TM!+HkZTvLPwtj^dM>1wq?<acYZZCG z6EPkrKgFAOid%h~6Pdp{Z?$c6g37DUM2%=Tj1!g4(EtqxkV%#USvt0Lx%Z{9fxwRu zr@j=#O97xyW|bxYJ=ujxgIfC+wmutuLWS-YEbB+VAgh$bwcyjP9{;y7G&*1L`}ZY) zfJ+Krj@{$6ANjOOd5IM-8)YW1ix5|X1)jIQk^pS>8d*Y*4fB7ZY~voT@JT4gItqBk z3VZd}p1HF%t*gs{C1)-m#-3Z59<<0GyKWT#pb8Me3U$Qg!lb&cTJ9ebzGvavE=<$c z;wrf)lq+6eIQfukW1!z4_Pk(0?30(ZL%i;tL>~V8x9GK*PCb!`DGO{_r;WM$L_V+C zhOH2l)e-<+K3fr_B%nye{@t}94US;{?Pll}UcG#Aogw*&ovv5enjb=vM}C=0Bi`RE zEopZY6WO8)HPVFbR{}AT(l^X-TCjYw<FSmgi~$$DeEa@B)5%VLzp&U+nW_d2bTj-8 zp(wZX4nLCp46MiV*~GZO@y)~ohnBVAYu{p(*j!J^z<~0Y=m5zj_F!QPCqM4p=M&}8 z1DakSh=0(6*Z_OT+<81R>5oD*VdOaOTjG%m%Sb{hGtKDtJ}uX4HBi<)DM(EfpOqM- zoT<?&tD#w(%hC(f>FnWGi~A*(#AXm5zLgtRyblYp4bZ{L_lkzQ@Y$lQ(dDsVp&xjK zDDIFMdI=qjDab#iYag&z$u!bQy=p}cz`mMedKFgHhLyW0J<2>_TE1;n+?gTsW98HT zjZd+>=x_bpfa(rc$mw0U(t2f@#)2!@x`!fqgL?q|I)wCn<!H;9TVG8Vzg)i*#=ul~ z3Ap|w!%ulHUfUGq+qzI(<#o%}f`)#+oYDpJB`Ra{W^&d6tVsu7`y#a*DWQ&Wh(dUz zBqft96hMMx&<+M1#24sq7C=>=*thz5ryGWi6Zb`b2?83rBXh&V%0f~CB(GD`c(~ky z&pP-m(iQ|-9c%O&^&2r;Vf@Ac^lZy15K7k7n`+{kZwMmE#VpyFZVQV9Y|CS>iS{Y_ zyNXb(>sz*NolXYs=0|h~peq0{^X3ALE$=LB8Q_4DZ-GfvWQfk#oV`x^2GnD&nzY9i z(9{HGkH{0cN^Vt{m0K0RXq-qrd~0PGH3*py1`3FtvQG7qZnbWuD8XM)(<^`$Zd27n z4Ub?AcB!xbUa=Z4-{>Jbo(0fQC_hnVqfum8F6TOM;m4en#&R^+$2I}IG$&}3o+j?K z$|tSfI%t&Hlo!+3hj}y2)KJy}yBF^F`F~~G_<lPdYVyh3$)?Ii9zYTfuU>o_$VXE6 zN_V8;EKoIEE5-m>ugSy*%e1rBu-*`Ikxj+iI%5}ni~$BeomPq~2s5LAt3sDV1hg{A zs5pG<>!vG8CQbs>kR~aALxx0J>#d>qH)^+<2-*vkg9Jq_3#IerBPCn`&by<{n;RhU zBfkgKUFfw@nHCYRDqq)*eabDW^t@ebYop5@hhM7Y6L&l_K=3E?aKn9<HbO>B*EmDh zcP(E2UN%Vn2)=%)5+uu&ax@k&RyufVLrkW3Oe>6srtD<!a^~0iPjWJxT^1zEBE$x$ zZDl<!Uo6_Jb4J_eg?*W>O8alQ0w$=9Jom!L0L9R6`g!=pve%ymCs|Bp(fG}M0JZc~ ztGd=v_az_SYKhHZCOw*xZzdZ$T3ux`8BmbrESqY^7eDao$?j_SR1=RXX<am`VdE6J zc$1xSK+_kW?yAlwUO8u>FzbCci7a?JVd#AM-rsXQd}h(9=LgJZVR=aje6o&e+f^A= zrvQa_yEfPZhZZ(&<z<50UjbmldiQ80zSV(h;^QF}0x3bzEy~+zVN=^G$VsmNWY_V} znO-vT)F)4*tL+N{nB#&W(b_Uie&F<dvDKFL6|p+jkV*Kw<A>Kw(tDx812*FV9!oWL z-PP9WaX^jmk1JW*qWc0WyW|`m4p)|U#Go2q1y&}>OFXT7`tc(*>-p&*q$9~vJ+=VS zO$YzufRiC6d?r0WkYT_&^U|Ckv9u|I)T!E-;V31*Ueu40%1;7hM9Js*l;+Q8J(-_R zyZo!m|1y{rD}VgxW!K@13oJpSOu;Mj>TYL5r#B&K#w?lV8D=SEH}64C0n$!pHu}$^ z)8w_2i1!19BwP&B3d*viYXrRJ(zU;u*|C^@T)`MG0Ty41r7M`1Ck$xKPM*7+<Wgx3 zNXy%xc;bYN+%lqVGm@m3ez@ACEcS`vjGZm!pZUX2j%NWYvOtz3in?WDt3k@ubh{P7 zE13tZv(o|lTLQat=|R%4ah60=ro;!}jhkZRQZFelqUb9hx$+qS4`Q`L_~pbNrut|` zVoHYnbgRVGvi@oOwbl;)`81o%4C)p1f3D#Bq-MW^6t-x(a}V2}U&1*R%I|vl)SQ4* zC%=aft8amQf4I>jv3fZ`tPYK`TjBGd9`Gy8P(u)!=J}IIHI#b-XV=Rkh7TOsWqMWe zX#!GhGx=@9QV;Di%t`zfBxZto_mi4?<feOP4Q+MMwPan(^hjGndY%d8K)|k`b6DzD zYJUtMB_bu?{hno!5O&<FhUj(>wt%rE37nWJY%}Bly4njr%ZG=hCjru2Ml*ax1*HC@ zS?$y0^1ZW4gr5vcl_i#@o3V(r()6+zuonT<pOiDkuJD<Y5{?i!zE}PtmBPB6;XlWB zwDQ0Y+;#DBXcR8Z&qb_hSQ?8*<<1HPGXzcriZ#g}xELn$0Vk_B%=7Dj)S^@M!uSsj zGe|_Ho-IFb#`KU7AE%w6C(1mO$xr7`Ngcgr&YzMNXZyT+bTuXK{N&w>Btb{11LWWO zb|z`Tr5QWXS)mrD9=rGoQI^B5=!tEDplkXml7M|m6|_9VZ}>?ci*=%bCl^ek?ZVwA z1%0WIGB+z4l~18O9T}H(GeX<~ZT)+tOtF@^>~O=$6<miJERkv>#vX8B^Skc5wefj( z!S2aAR;DE<r2ph%+`Ntmlw~ASnL#dMQ>-Qohd(Uy03adNT!@e8#Yb5Ik%|0dQ6?#j zX}-?T3S;t}Vw$Xj^Z+TgBqpC+Dp8bq1dyJzalle4HQ6`y2p2nQ;);4KvVs#lLe21P zXt>P~h{#MIRu~JCmxzkU3U0`7-R*%kW_f`je$=kFfmxGp;mft^UWuv)jdLW<4A^@e z@K@-%%XwKapMF6!)eo6ITT^B|lFrjuwP!;6XQ7+t`Ts}Jy+1P9|9=3#b})08&3R6< zIiJm0B0D)BnnOa!914k%3Y~UxOqpZoWJ)9o9d1c|woxXkkwmF`gd}xKDxLW5`yX8U z;d<|SzYdS5RHTJZAvfx7Wf|2x``XtsSD05U6C#!Oe8XU0Df~Lw$oRt5FJWm-GJEJ2 zzfh>)6m5*%Dg7y#{7onW4^WA|98X^;9)Q4hh-FSeY;qy+ASxMvI#Jmt{`gQL*~iK_ z+v8cvi;M_8rUssq?;jG~@#3O*>vpW{=P6l|Z=W}*FD$okA+$mFKIKMMfl9AjZ9i0F zpWX|D+qd`}q`TTvs>;bUxsZ|~2Y?ZvT)!u`<E8t9{qgMGsG>24&|<r%w9+t{Fyzi2 zs6}X@etL<{7i*cY&OMD`Y+AwZ7)(Ckv1?c>87-4WFW9nvK2M}w9|cPj%c@*1N~RAV zYb}bDaO97%t;{&yaA?gsq+Fd7-~<JH#RL@8_b+REkeEVcn*dO9?o{Y8wgDQXlL9u0 z2ODmpL0T&^qFXyI{+&7t^z4+#91_b|uw{rhVOP3F&GJgFO%}uwl(!v|1DO+@y<Xmn zRMeLVu)VC?-{X<od3i@C^i|^X^hm|{tQs5(dU7^YwxUGp;+*?h+Hw?jObiWcJfHWe z9p%><{MxwP^--!>*<SJW69pxgF8x118!WbK(Jp*~Juj-0^{Xo^i7oWQLY?4jcQdFb z1mgKIvivWb1dP;Bsa2=OD}uxj1P2d?oZv)J)|tu@rfu$&6PKw$J!1!o{`c>jTA(LE z0zE+}NTy1U<a;TM@>gy_EwQjG=U&Z(psA`}dt?2I?QH_<aG(8@k6~q!T$Kzr55j^+ zWxW_hX{f@#(md@&nU1^dMt$}7&&&OL)k*1j8D4lRk8tvuQ)nLDU<df_o<`ZpyBw>W z!YL}|XQQraTe(31?BJ{091Fb(L%j)|rf32zE`@Wij7?gPCje0I6_#7$xF_lj1>lr< zy{Vj^^!1`ncu;|!*g7ZaoG()c&oW1|ojREs>zoTRak%fXM?MyvV3-Ec3y(*_yc=aR zn8-AAgkEa&7hWN~ChknG`6j$;A{3U!l?A8z|2d@$i3)rDd&@CK5jD3k9j_Q~UtpZB zuw+e~-Fos(Ldla({!u_iuWDzpAWj;M>W?*voGPTX$|@LYKQj;R-%O7GJy|xykOWUU z5&E@KvrqDSG;HW>{5sp4T7ueOyT?QEB9=D*1<<kO2u{cjs&v^1z;mqV5VBcRr4#2^ z`;5*6(}WAsLql}TKnJxF5;mfa-1~>-TEH<YI*uv~BNWXW2bp6|wQD&HVz~oNa-FF2 z)41Ewidyfi)M`PBHI2~U_dRX`s5nufKfd5R^hz+dsO}XvS^^1aPpoA`)TGpSs9#J3 zWBMcYE?lm|$Qus5KxIW<3W_8RCh)u$qPd3u3!H@Nzb@P{Zf9`wHXj`z-7K*&gL=D4 z8B+!d#(@RRk9vLZ|Hg7(aTpI0kIhe_w~5^WNZsc7D7{6H);h>g{Dx+;r!hE$@~22D z#dgeA9v2mOcUq)w^j<k{5z5tNbm(R*LiaFkBP;9nte;B-Wa3qbD(UByZ{E*LhHc@> zR*uSkYOu>d!FGyd9Ud6Ji0;hC%WMNoKF#U9&@MPlw7I_WJc$0@E6Zvkb?)4UdcS`A z35C~w0b8bob9v}tH`hRK5zEaCS_`LD!l3_K1H-;W*4RK@@bfjD^Ar)=!ZminiR01= zCK5R2W=xH`PdZ$tG9Q%KI@0)de<5YSodn$}f!+b#2#i;_a!MtD)8xM~+K{rZDJ%3s zdg3wZox)*zj8)0ZyRH{s76i9Bq1gYO+4P4ULro+xpgl0<h65#YTD^6FBtO2nw{l8o zxZE+<hiU8XS-CK3=aP{A`s0p|GM`JY(PjJz)=%VcISs+lGqCNA5L-IieUj}#h1j}& zsxkY3+QV^M1bc?fkE%m$I@uNbX);bwcM%vG8%sR}Ijg}jFarT*OsV&-)yhgRQ+@k1 zs|eZ?!zhq_C7aDHJT8W|>cQHz`d5g<t-%uwJ+)ND#etRbJSmjf8vk$Fosgc2f4s`P zwP49y>6=^c4Lb?;sj>c_@%}p49;dmoG&G#|cv+)fb^H~+TQ`yqwRi<Py}B>}teiO3 zN!;Qc-++!j+Hq2@Ml``Wy}1D<h}cqqoX`WY<uBI~=25{=`Jfrn%8K;uwZ%`3MNB>U zo22e3cIjmK;aNJZ;E0_gP^Y55qghdVMJGhijX=*FDbg%9Ye_@4YX2`pQV@QwWG}TY zFdo*kU^fw}SfXlxot3BcC=zOe>bs0~QK9*+&40gzSv=l%)>Sd4xVlh}bF%(W{bYIJ zU2dMMjDI{Vjc)ZcL9XA!;t$G0{`u3t=!#To^(&GLsczmqMb7sb%cF5^#3VJ~3E1;> zPQ~|0N^WeZv>TDZky0ElU^`smrP~(}%3|&b_ZKdVZ&CU``Pa_4zbYUCn%M-|n#fa( zrE6(^L1Ef{R+|xWR(b_b>hG4+%kFA~p7gGZ>^c|H6OmkA(v6<>H<LN3EeU8<d;3`K zm;{}lQg|JDs&SWfBO48_m(6PA1j8>y&Aq;h-Zn4bd=SbwzL9_P;asn);vNPkUsQ17 z1|<9u1c2wdiy-bRIpKvRBsk4>@rc;_14+bIUzpsf#Hl<58R*L;qS+dCU_}ox<nJK9 z7^-WU_vF3HlR%||SXuFzLeSZsMDtp`tnxF_S|2*B@)rwkYzpqh-{1POs4o8yP`BE} zXx-R<74`F6E*BEtARE_HcDhZj7i}WVRCb&nd#~&Crc^n<6EC-~(B`&6e49)Y4;pKC zU_-11-yAARH~ZWlUgA@}!Z?xR+d@}3ToT|CSdm=fxtJ4xU>EP5@dhBjY`;16FbxQS z47`yDMPwB}SpW5p63}0$q)#d{%QARas$rWj(wb#BcpBr$QZ&yt@+(~)0i_rXVO(<- zMPCdl|BYeuU$kX?jOfsLmUp=o)a;$5Gn#iPCw2Hr&{_NBuk_di@9nMI3Mm&oUOQ)o z*%k&EAD7`;pTz@r=5m^f(t{tgJ!weoZ|%?mV(OQ=?3^+iUiK*ed%WP<Np&0l!8Ji_ z+axbxzi>hCfYH(!*S+!eX&n!n19S<%isWaRX|S&N{PP^YY9E6}(xE=6#oGJr{Zl6Z z=4M`<85jE^PDM_Bo7h(g$lzlwT92OMoiM&gF1I=6_HAk6Mxx7*5&`f1`{`ZIP|5|j zz)O#q?`p&Ldc<B|*bm9Cc-@**TC@MTX<Aix8&K@Vd2!;(Tvd?QDG;#J{-(&V$o+a} zQ#n&^?BHk&P^N;^ZW0>?7SO&u6h{U)eVsHrz1Uoi7jk3_fPm!Z7oBU(?8{3Zmwls# zPK{KR>BrKEve=Ae<%X2Tf<jsB!B(O&wj(d3IQ`ZO?_KCjfWHe1s2TX;PH{km1V|9B z9}Q&+&Sk@neJLSL3A9?y9T<yhIsdGyKiG3q(LmADR!}YH_;$qsX>z+P5#i#xdETMa zaxLX+8CCtsO$C#$jxR>sN6JViw@oWTl&Q}+{{Gg0SrytVv!?YKZ;@~4WBoOEvB@hi z)j?k8rr2;IQZ;T*BYs@e4>PW_c&^D(Ki#b8G#Hccm^QT0T;}{MWmX1#B4_lGe%7+` z^`3VNqgtAW)WD3rNROdn?X>it;`D+!khh^?^DcO1fl;Lw267C?RzC&R^hFPK_=(Yf z*AKMxBgwj51FDB}o_SuTk0H0{e61S7zbAy1Z@ZL2(sUdi?|*!W*tLur{@O{BPnZsb z_=m5#8&(`0o`aNd)PvWqF<)WXL-zdxkU`sDX72)>e@^~t+Kt$9=ajqOW+%z=_7>RR zkM7r9yX9;GEniHIKbUnvnw5(n0ox|rjB=bUlqw7KjsTSfnhfs5KmRs@P=mOr^$MGP zWt@6A`KI+oQFVOI)n;t8bEuE{sdgGf6@c%Bqce>H#o8CreY!rhT)NP^l-nJ)U4L;o zOlix~oKV5-Weg<P^Lc#bko&upORMfrJ7e638(6E8j+fGBKe+QqMv@b2t`-whs-sRn z40`~=cJpiDmF4(8HPP+vz0aDTxM!!6o;ebH^jxBTsU0e_b_IWI64zwcAb~4^hB{C1 zyF<s{%L9ZA<RO5fIR?Pp=LEje;tA9=(uUBAQ!I-NqC|(mZJ?V%=kV?z>~tfH?4Fd( z^c|QlrRo+!2T_?TU;~%|cOHF-cI`C|d1R4X^0$8r5I^X-GzyPgA#2~%@wUp4RmzNf zr~4i#F!$|3gz{OKC&lGoBCn|L=gy)VQ!Z@F_d2tm3Jt4{*A`oi>F;E)FkeMb>%P4w zk1w+$67v+ukq_INFI(uR^GPflF#3w?L-q5bK}Q=9<7m=<xXdpN=4LbI#p_*Ke?z<t z`WkJv0`bf^DqEim?J45I*iqE!-pLo*_+@66QWpZ-Cuz2_OWNIL$3i>;$TQd#1l+P1 ztF&6`@)uwKIL5?*SJiSN7p(fttjO_~vVv4z*4})%0t1SbPmw;b)av3N;vey<@*1nO z7b&JL17FG_#R<yii&0MtL5(HcQcQy@w&2ww*H6CFvs!vr&izprK_Dv8xlo<oB8#Ha zUg)(+j&Tae?|&;@I4$)G;61G*D8*3!7T~4-epOs3Y1z}nmF+YVl<f!hGkz6&Y4YiC z_hkXnYqkF#rcPGgdyW<8zteK+g&*FC<$v=J*<hT}To@RPl7=6sN5{*kkq%<N85AQF zx?x1@&H4mA%c$X3+`aj;YF&#(pQ+3zDU?LrY&}`K;x6QI221VA;y_XY=w$4Q@WyfV zcgB&#lDM^{6bkX(2_sfbl5Z2EuzK^V`5Y0E@5{n{^YwxQD3&Gtl2zD&kdmXMlX0B} z#4Jz*rQwC*F<+L-#&aLj6rRt7TR5p&tN>J2l=+0Rv~1IAom(qPtj3v{igKEmKU|no z?m{&Rgm?>of0?u_s4|?kxi6&KJ_QxI0G&+b*>3?vfREY%AHdgqElA+JXkR^Vdo1Kf z`7S<7O&Toa2{3{Z7>U;x?-mC2-Mo5K_mXnGm||tmlX$OzD}PG{I$OIYAC_8}0TP&% zch{M!jRKn+^AC;J?8*alsZBgMQ7wTXqh3>R8#tzD=@z2Crzd&G@o8_<Kpt`?m>m6@ zzgvIQ8_|mGKk*<4=CHY{JiUK81=AZ}sc%sE+;JSo^6bC@u5gA61%-;ia%SA%#^$5m zoUaxfO(o`A!hne@5l+JNeMH6g;uHt0;0BNICF>I|ViqRnTv^Cg!rCSMRx!op(hMR4 z3|#+)8Z;gNol1#J)D3MPbY03ioxcpxooMx8zvt0T@mZSGJH9vD9~HHYHz9W@!(8V8 z5N<#se=A{Byy5rGE9sJEH9X`cr{ZG3I7$D1GJyTWBJO&H$lSESdmC4P`q%mAkn5O_ z37;-YV1)KwoFeNjQIp4tU*r5&Ni!y^mnjUKV(GQ9bO4k|Xxv$FDxQTPoRJ~K*BlV0 zQZz_=H;bJ(0^Mdq$9|p9E8Nb0{Ud1<4_|@85i7Rl_8iB{#%~bblTht9lPmT;#8t$< z1II9!N0;&T$Ve$%w12vFJpM8=Ox$#&jyvd_aJf9{98QfMIdGk)r#a#prTG*6&@Lb2 zDR0*tdb*gNd1AOMpt#)YxSjb300;I2LY60=78!A~I`+pKDC8>q$oWDoI&n6Xg%Dh= zjE`DSG6+U|&Cr$mC@JvfZ$X^`*otjf?qQi2R~8V4K?zXvYd<v@$6e<wGk@Of?oa4< zEpP+qFC!x%x;^(`<R;K*zeJMm)|sIoEUPM?57xYrk>}N!JsZ0|XwcBEU^3?_|9P_n z4m?|T^w3a7nwjqLNgOJws%lpVtX|6xKQQ8+KT{k%mpG)T_3&z_`q9K;vP!$?xV;c_ zs4x(sbty%`HccMh*bw^Wh!~>TXH{`=;;)OkIY-}7bXXZivIb!?`<RN3Aj#E$jOi%) z(J4*WxP0?Lbk7heCQc?A%X`!Bfrlz9Lo5J>DZuwgAvvYTIN~`j=Po#%6S_}Rf|sG> z6$-gA&}2op0+;zjgoaQdE=lZXbMRE-N0|NnU#CQlzN}4Gj(s46C?FgA`cB1H;}`o4 z%64yK2+i=E<fEd5zTz+m3vG3ZZmm;Tt>*ttWH>1-Kc=_a9co<$-t;&}(&m7Ac0hwi zFaGs{R>o7SU5BdhAj3cUz$6UFW$FYf0doYDVxuGvR5N#W)*K7Xf1wljRwjDZxKe#< zd%q_gyk(hfvfQ7`=r=o^KsJ)MYQ=0X(*>p}AG;Eq7Q^i8wAUgz5e!my5d4YX*fjm( zRS?5wU3Onb@wP~o*|Z2#qhX1HJBa!_Y2gLyqoMBJw#A?qyxnAmu=^AIl$Q54Ml6|e z9t~z#mVwRiptp-m={@zp8(xYp2XlqFad#JPJhZnp>K*^Jjw1AbTbd+y1!3oR()*Zs zJnkZvWSo#dvPeSmURVMQd_1X*2Z_njC5s`tPuZImX>;D$5RVnoe-C}Uq&4bJ(iG~o z=jg-47?SBY#HmLp)j)mzR@vVwFc^SLq2b5*!mEEGY;(XAEW9LzY~M+=ZN-s`^&AKn z#~UAuTuD_OG}q&?nZ{AJT!Ak45wu{~ZI+2iB1)2sEgpi%W^!QTntS(E%nHO<`B{A^ z36smr9|F*7ikXfqZ824z_fiKinmZ=2o`%TS%*Cr*SxPss%ViDlgl5aaZMo#njg22( zK)f@Ol26ARVI)0W96>CM3_sM3IftZ-JaOz4-WHQhBy~)B(CL&hcgGpkUj?)e?AuOb zC;s^F4h&_@6&X<`(HH)8B%CbnE7;sN4z{Gez8%z`X}&jmPrnTvq=^Tcof>v~dhuYE zF&Xa{auC%w+T6z#E8b-)1`=oY`(X)B!5V=Y?%25~ft}nQnsDz?QkiEv#A1@XWu?S& zg}hi}Ko;$=O1f-8f`0r&c8*3X*>k>dAD5g8YP%(J7%SMe%qrRf`IhtW<SmUTUz%MS zBCL*e8$|d;+^u5{BPe^BQYKxxd6^#|W)#tlTZ_LsS~GXV7Mnn_zJoN!nOifGUsufk z$pU%Di0@A8QEnA#_b~JRUcAo)<?%GbJH!(6tFwqWa{G`piQ(Ae_qEyP=hK@^2Us4{ zWa+87tqk(ny&=g)%F8k~z5OXp%MeQ=hzlpF(72Uq1^I8W|8?tQGNsx<O@TOCnqI%X z_{H3pZ-d{H^vN+avYG|?a_Kg#j*8pBWC_?NxZhpPwE6qQZS(i1?7^CgAYj?-;EpK@ zUXxqdJWYhA9;NEySyo!+o9CrJ%G*$liRfvbqXyR*Vekb+bRan2S~l|j-ZKXKy0`hD zlt=OLs?KZuSgvr3M9DlF;z<{pkM}QiG?6b$E9#2W>8jzt(#tU#mJFdgoO{};Fi@`+ zae-wMSx!Ow7A%t8!&%PhkhHwS;>QpZD3|@KKpZn{o&QedG%h=>Iz%j_o~Hfe=~t!p z8{-9f1n{ONH#B9f)k~~T<}_0-t7r}oD|*KyzC)o;3b9E<g(SiKl_lI~=7nT+2<&60 z|Exgoa`)2m)5-xqLYULHe)ANTbD)v=XHD~Stf2M_lpNpxocetY7SChOPBE`+K&xLZ z3cnVUt@(4sR0_p!#-v?n>nbd_GqoOIQwO$(b_(sREOa6)fODnWVunrXSWK&^x3&MO z1h;E03-lC8nssNrIk3N}@Bcnz>NAM@)@UAY&%eXJ&`b#)etUi{r?OK1TviX0yfU@h zz~~t(W6^uS;XcV`QSM=daImbwDaO*gM|j8P6ZvwC6<4?%1sG?N%*d{ZuuA?X!7 z-YmIay;gDskR$K9CA7dogjfDuKcDnuztkPQNGA@U<+pdCir<bcW?J*E<$`eIOw45v z8YSH8IPhp;1_RB2?ifhx17+ZCqJ?Ms?3Co@L3!$=Dtd5U8`Yl<Ixw<4M=?0!|F*02 zGstiSwO`gbkkph1b{c1!(#akGp!NkaCd^QLZ1Xr?XfqNw4ih;@1!%x<8c5z3Cv0|v zT3x<Y)ERw$)z?zQ?EYEn`*X6?sNhms<u-R#dDed}&d?uVz*tJEHu~;J`S1Gz+eR$- z@m2u6P1F?Ayd`RSis0YD(3BVy`dr&R5dY8T^ZVf}<!K=7pg;%P$oC80L@zee0|keF zCWA~@bPeejmP<^_*q+m1+jjOg<^C<5pJo1+@$q4XWkkPg3QKl)kTR{BZl{lWrR!C~ z-X@YY`cvyU`Y}?9RF{F>+gZkQ5Ze`&dpfBy@8Y=QNvX|fxc=<tL+eup{RUfv#yet# z$KR-AdRx8#r2!<(M9u-@ow_Mgm_Olm{r~<ZX?kEjSLJ#erUZnRPz@cKibn<V>IvZ` zI|Xo|rpPM4`^&p8_3FSC(DSS<mLE+P!0>#q=?cWt9ik^@J3{+q_I(U0I|mz-Kph$o zah&Q8pD&TpPDq<jJ*rNM{S%LL3EL?r@Q~MYYy&>oIk4Y$gtQshHZgHOViY^0(xg9a zPubSV(#e;1n6&?)(PfiM)J6&Q76q+fg8TPwy-tfZw=<Z&i+1lE?a189RuCF!(qwnR z<w$4|VR(Tlker>H8=Ji=m~S)%juPK7Z{n~dbWh8c#BWbkl(*1@ZX9_}M!#DR*eKBG zj!<aXopAP%L^MivURTn5VKA~rdR8Kn$oD$A1ojXc0F;MZW!uC7FYhyN4F9qW@M9JO z?B`fG8TG#N$)eMQ{pk{+mXVIVmFe`vip^z#9#xF3*4cYlfTc(E&hz%Vic`vxF}?rc z7{s*jfr<yr2P59tK4ul{Z5DuW_Ss>`eRMckeG}j?wcGa+%ZQ{&a)jaG?hFHqIWWM` z1$_J6_+TmU?U^DpOShDMmf$k~aSH6;ReqTgk2WEMdLqP;zM_y3h`4XMxmw1gB1P$1 z_ID|c+D<YbVB6(iOmHQi2!!YiKzw%I$h4kOxj@uD)Ybyaa+a_(Iko{G1$$M&nrqBp zyO)7mp$F{5sqb&u=?v-UlH5P*?d$PI2g-%1gHTB&yEIrjx2zU0v-*_Tykqreyd*nJ z51-Eb;0YyLwL?rt`X4d+J;uTM%j}PPI$_riIu*;96_byq?9skU8acm8|M|mkoE7In zX^jEf`WCNwv^qZSFvIW49D)EG(xw?z=gAu<VC{+*RY%8)^jXG^>7r%M1zmNc-2EWX z<B#RU4S=1v+leSU9k&fTXz|JQeV#)WPaZu8xj8#BtTQ=0oF)e(392873DH+~{?*#@ zF}HPB!Ue0t9#;L)OxZ1K5Zm|=jj5ZAwu3%}&%>=&DX#r5lY+vyz7DPs7kbAsg6#l^ zCgMt8ZXDGA=40<FTwRsXc~tsbZ!Bh!ZCw9}Vzzf%9m^2V-{aHnEFo!#iF)o?<Z2!8 zL86Z&2=W(HxOZKq#1+#U`c_nkMPbrcVox5Hv)NxFFUK<FwP2+@Oiu42Mfkq-mtbcc zs)OyB1Ccgit=jvy9F^S!B%{UzQsq5!fR4APlRLIf;Ctk6I~9fnl1<x3zfM>EqC9*K za&AM*`+bX;{25_eEi~az?iWsIGgByY*1oS<w?ypo_p+-5B+X7oO7)R_`e3tEj-D>- zcPz!?s=&gow@;R&oAR{kPV?R*5GLjChW884jWogfSophkf#K0tTc;hegsuZDwYyL^ z2E=n@;Nuv1>y8De!=Ax^M#xZ^Co#h3@aAoNmhl?NBeIY@?WWsRL2_u`>G-;QG^MJZ zWIF<(6h#19BD+6Eey_7p|Js|0g?8?opVsyN90uu8)+xE6KQGu){U|-~U#V4h$lOOb zNpqUxbxk~J6FX8Ly8pfdWNu^6Q0;mea8u0JpN6&_`?^a)>H~+PAj`|-TrPQ;Msgl! zJJGKNhm$?<3$jQ0hL4`Ibf1}agji3aJ32p{XsmGXwQw+!F}e6`=Lp2uD)WUkPfE3( z04RO_Yw(Qc@BJ&c0SchN#B~&*`{?aR5PnC+jN=|e#XS2(!Be3d3N(JVpZ-kfVGe3H z`bjU>!*e1Ym3&nJFz(Js=9fyiDVabPI3^evp2iXiG&X)h%tAB>iZY;93uy(@C0@}( zZOzGoOin~}eEDXZ5`BB$)SZLBH8NuE9{4bE`-o;{-2FpST{qvCS6_+wBUXoX-oRYS z{<Vou4UM>=<C68FcT}}D731`zK{Mm6V&jxMb)-A>?8|nI*66j?ExURU&J5aY=(AxM zLC0_Zy}W(<?sQJvN)j3dCpHh)<B#o>{+SrGy)};hiO%5EDFQc-))D3tCq6{>7Yr4e zJ}<g9EUH|>O^jA;GzXvmBKKja8};m!dzMnc2e4xY518_Y;lV%O;aY%HqmyoJ`DWJ$ ziXr_culN00dQc#;Pb%BB5w-UQ%1gImKqbgs`Jvj5q~h}@7PJOxj$g*LoXbY-<6u%B zPsyn6T#$}#iWX<)RVLgo!5D_LONE;LYg1RWA_B9FFXk0a74jyfcx6NIl`kFj|6=7g zt48qu5Eqn-26h$K255vTm7o(Cjq3hsUu?FX8b9jW6m6B-s^LEuCF0H8`n_m$8|DY` z{5iMl+5;;%2z&Y`Yt|2e2Ncs<Nz<Lok~Xm4%2i5VPilBuXIhe_!VdKTg|0`WIRzv! zM)_sT!8bK8<BmN%sdr#Q3#xHErM==}zV=nqh7>^3awgbU>q^71LaS9#y33_O^`JFc zfl5T%QIn3mTu?Gb+T{M!{I+{^P&s<Q(ox^%^r#QoH4$aNq2g(UTFa$|=Jn~vv!Fl{ zut<p`85$rw+}7f6c>I9-Nwbodi}#fi?MG}|Yrb#g2q~+QoU5d4IM`GMBDV?Q%Hl>W z!ghB2^5>c-IYE^z<9@EZY%IVuEH<4g448~u!+)PlvID(uNNMkaolib(m#h}rdbb^u zc44$g+s5hLo(uaIcze-t_%2HIhs7Bfu(xx-&vED4PwSCe4a$2kJKaWoXiV#-<O`|a zCrpEnhiUEA1Yk}%+n2A{eMT3|cO^9t4gD9yHlO3=7!<!Ta=CM#E60fY+<>EG`)6`{ z(u<H+iAhe~lWWbv^__xKggS!{<s^A#)Sg1H+~o><4{Pxn!5-RZdEprB*Wyyg|1iIo zzb+{NCtlUH=%$KsvU<t&GP1|^DZTT#81f2Zq(RG8F4V~fa=nkoWtVIgNcWAVpuksA zVC5JIk%5P({4zt-(<>3OX>6@VLZJlUB4b<)^p(c3#%iOb_O}u+{mf#z$l+X~`z)IM zSk}_5;*^TFk$x`#=$U=5+<Gnv84ED<lis%iOc226^t(h)Q1xsTAdA-Z{0b|JE!0xN z0|L1#%UG{>$C`IsjfOvMYs7W0Eo=PfsrfF7^me!~n(x;S-MS==DPKv{-_CAu>B~ZF zjfUthN@PuAW~A}wLXBH|ieU;<A-B3o?Mv}P`vs;}S4V;NSH5(!n^!iy3^TnqqhmJk zuq8EzRau*Z1=f_$=W<vYHdZ`|s9&*QBw@SaYu)#&U7ONMKP};)I5~QaUP+wWYup`h zQcr1A2CrtIlqo7{_DxVFFhB<j>f|YftFlfE3uSnIN!SJo?#|%lJ_>ldY6HD?9%rC< zhxE>EYAX0}tq21U263==-q`>{vtNot-xr`-l_7fd5-*SCok-~n?{O$kmiVy?8BxZ< zJZ*f0pGZJa0~2+$!vh?Eoy0w^6xS(NSTClPcx(}@0xUk%niD9*sg>5KUX>wpnPowW zkKLxkUYg^bsIi%(GeBgx2Gw-rwqyns#aPg(zN)eJGgtZUuE+Wj5%88<Bj(Ijh-Ug7 zZhMNcV(k3vQ`b3O?gQ11)EytAaoOcZHlZK&>&4LLqS5lm0hWF)MITrSK>}23)q9PD z_H7~md+?y6lQZw_kwYvk&NeaYs2?=PXZ<rhy<mJPrr1Q=`-1#;7P983C^O~@oc|$F zgD3Ll#}%JHnnO|pxIAGBsB|eXQF9m2kD;8Yjs3+zZO!uARs2B)4<vY|j+Qvw?JR1I z?ke%_Bx2gzf+WdKO41OTh@NX|E|ZFTX``sMiFo)@m-_t=J2JIiektFX)TABw+h<}u z#Aj<<BJL%SZna3P&j^R`Uod?C;wz9(vF6rK>tu}%h4>w!sTkZ1fjJ$g$^FOmas3I% zSg*V&3z0X}spD$e=2Rf18ONLY_prPMY3@;xh^z8^#*4B>EVj{|HOh}4)`JTQo-wam zn@_Q|R|xlf9_}^$GsMzw@(*fFBEo2J3g&um&~ij^-tIU3hozIt=R0VK_p$%g4aF?P z-TtB8DS|pq_bBaDv(#RM43gUg<^1nw>{CB@CwpAd$bcuRjhj`~VP*-*xoDu8P}l&j zMSc+X(;uY5JpyT^9BT^ZCl%_xYIklZZ?D=2I{aPbr~>eq?f!~S(azn~U;3$AiM=vS zn#E6F`YhO{u%$k`>RdPpFYG18_@k5X1q4N7>uE)fUT5E%5Zv~>1a%4qbBniHIyEvi z@%;`tr~E{tfo97lH^ehn`DA_>`{G|H<M^k(lUabP{g(yrq{a|L{-V%_8+39iKiu!h z>}9RTuD*w%rsauhky=a9#l7*PB>`+T;0w3k&h5=(uRjUf)zu!_wmKk=B^e-=K3E55 z)S1~d2HWTjqk&4D>UoQwFUPAF5T*QT9tQ+Oq(82?C(mdv3u^~*$rw}@j?y=yI=S$D ztp4rV?cB4PGZGH|7xDBlI#_ox;vc<BQlNE!rJ1Xw;s?YaBMIS6>TkT0kx#BSLfuD= zZNe7<Kb|F5nd?`gx68#glt-C0HTQ`JO?t_dpB=STp2+YA#+!y4uka8g=cVZAGgW`* zh@!fe?wg;!ufW_<!h<2_ABWZ^K(Xfn354-2K($^`DrxT8L9FQxMP--^7My?6zh&(F z+av!v-1llF$avV$%CpA}RVAIadS4Yzr_o9FFBpZc1H?l|c9XU|TOSGFIwB)Gn<}3$ z@P4|j=Mr;RZkz^~$!XrHkU~H7+KRr!<OgbJEtoSTnQPWJXqMJ4RL?aUy=CR(lqry! zM2s>cmK^dAAGr*m2w+rMy7jr#Av9>JAw|Avc@j!NMBFf!Y9<l?U5lP40sQau|4ydO z>pxxk5r=}^exkoF=*woRj?;8uH2vD`ZvcsIHAwX-v$Gdu+D6lAB1`(b|Mevayf>MZ z8`d|wd0M$3755<5HG!HN4Z|S@e&2&h!`%W8-W(tss0lP?nTR>w6*U-eh=?)5x#!3$ zqHkEU(!TT(22HkGe{ZZCi?_hvFm~RKiX|cPEs8mxl1n?3IYAA5jYD_*a>pg#uydA4 z$i6lb;w|ta`$l`NEzDC{ZM5ya2~A51Syt2ZTzT5v8M+IK$NFY;3z@3F_ASQ=-vawF z{5`)h2F@37`YLewERxm&bE_MokWN!mOS#p6`!An~i@1ubWNOagFm7i06L>=adxw4v z;SD~sB>sXWA+r*Uzw?oO5+wkHj8-z8gP{CPklr^?t9)1)A@}m8AE8^K%rsSLA)RbD zP=@l9(-wB5ZAXODttJR4cRMwmG2BqG-m76%SAqUAQMFB=l}o!=o%!)8ZeWS2^JiG& zhd|w)hnX|+LzT(>53d!_{|PG;-(hN<yUa03P-|t20Y>IRIbu+}u|QLwBOqRK5!Ti^ zYK1SnuYWm|8WOzMI^EioGoo-ssGI6zy%KN1Zya)axK`^+00hci{<-}4m+{Dxdyspf zM8vHUtLyvAFe*0hR`Y)e^(O?XLYiJ7PBoqv**>Gap8Dn~PYVw++SjF_$<lcQ(p=py zr%!UY!^Gg3mF^?PSqW7G1zNd8oqVPWfYnjjk6Ya|(J|u9et&9OA#J<R)GdgZLp04a zdFhOos{Nu$Up#UdWdq|G<)-L9>@sc}J9wzcMGI_cKG0T3LN#C?D}_uJlJwb4;k{VT z9!tx11Iuab<XE@7MuqB2tjY#cZ!Xk*uqx%3!38P}JvoC}03i}+`paf-nr39>p8t<U z;bUfhbrXMcDaLvZ=?wxumFq4!>`RB3Di${Sr-_QQpxyGHoF{K=M9677HL2zk^+`On z>mjtbfH+F#mz**j-N9@PYZNV1BJ9!Cq8m%2dKf9ilVHoe!UcJdViI4$jcQidr0`wY z!2h9h|IqvHSp~Z6UTsiuSw_CF%Kgk{wcp`puSX#D&ph1?kSZRhSB!f)x2(Nz6VK+r zW!o`Woc^tHM$dLZ3`p&>_n);Z6@ko+If1fOI66L5KVP60o?2^WW}u71R1!7YMm6S$ zn*JRQu>$GB;1`TRtL}CW4X4%~02RC@x=>jM#9xhfGzEyEmp>riHe!NcQyK~8(~RDY z3Y?me#UF;-Rn@$VTf?^!lwIZ!?i9bX;}My+DZgeht~gz(9y-ob$OTEC@XZ}H_`Pa4 z!ohxlrq<1S7B{O^$c#FOyEKiw$ubz<_Czfo7wg#SXpy4rd(+)MA$!Tz*;42<55hz~ zen;VHR`QV3<TDw?M(E8QMrpnii}6Tmj%!F$PwkS)r0`pJJo2(RsuX}<Fo1YDDf6+4 zDuVFCN)~*=j`Il1Zi5IL&W?sQ>n9(rv(%HwwYJf7>e)2CUp!rJfx4qg`RqufoP*K4 zwY{Y9##5#JB1f|eAT36hBP%QRt&FBkns(gD${v)#`W`h4R*jjc#!YZbNWQa%Gdsak z)g@wj{{K2Lr;@zSj}@m$a{29aaD^~o!mYPS_B0S9Yr#OeM4=9>UjR09l(}Z&Y;N^E zSDPnqGHOA^E1D2ddme5bB_%1mq`za?Gz*XuAf096iB<C(;`hlFPEmJhZ_}Jr%Q&9D z9UMP^)Wn+)E8A}~*O)4wy)+3!|DqQ+(`Ho4zPOqBstNnu4&k&UOc)0XOKDW$W0f*| zDO02~4XY^Uh4k{Jue}VHBVXrN`G{?uwB$y4`g@#7ZAM2s>aB#<FK5{;R~)>ekb%qx zfb+)}=)*6MK4%^I!&L31>HVQeVMhJnnW%P}uE{^!s?-6=qqm2cYVDjD7T9?sS*Lnt z*Xx2yfA(OGgAhG63QogfKq3WNZ$clLYO+-F1-L!`9HJ56>kpN$2oJ}0Sf`gMnIzYj z{xD|A0b|&RKYSCDXVOgsL^oqc5<`waw@|?$Fn6r{=JW42Du*WTP@Pc_GPeHXi@mpb zSZ3(Q(X*2!nxx1!koq!CuNHLUd$Hy^6K!(%?SnPk#z~B?z`d5H>6d_4FLuf4|Ev;( zNt?Nn{*IYXmZZ&Of=vv3g*AaQO&Z|%S9q=COxX8%C`O<(&B!@^*m|6;SUQ5N9m-{Y zsQ*JZH8YMMti9@6SjZ;Ga*8s&)Gfv(w63)9QgEis7@{l}!Hq->T(cf*Joa~{BysBK zCjrJCr}qn_=gQQ7EY)*y8oy`(o+<#4jw{Zq`?Oz8vB^%0<gmb08_RLgHOqVi1tLLe z`9!q~l-Rz5)wgi^-nfGA!GD*Kni-|#H`!X@irk`jcrjmPmX9#n6IZjT(yEJ8%<&B^ z5zSL`klh4igS_XX@AGe!6%W0aUN1_vbyjV6LcIlwZ!KDITZ+qje5FXtM7&Bg3W%ZB zZq-hD^HKc|5A%l~DVCa@Otqs_H2i>8-}uR*pKv?eZ`U)prW#Cmgx2nCT>C+7l}Q!A zZ02ZfW*|*<(e@pNq;JF1aFmVzh1QzmsbWDY7BlkWjc5FoD%h++f`NtJl=UBMQ8vr< zqKehUMbpXJux>&w>r*(pD7^X1J%GRCz7Q2WbrMBWtbD2;KXvK%uZW+oYJY<~PBrWP z0;$*&^(HcOd)M)rP118+ZD6LN@tYKrR(&w%yn(3FO~D-6<f-f->Kg@}x=)TVZejU- zFkq1|DMZCStfD_rxiVgTTB0CN_jm=S9K30hUy8Db0?}B9rm<Jk(Y*6kS2-=ot61e; zKH_wp1=m!e`=*6Zf<2IVbd+`DZ}h!0;}}Bz&Jf;`l$8C<(~3`0TjDjx_G)|tY5g<j z;QB-B0@FuLwCiQE3p7I~ov0W=Mq8x@u3X6+@XGd0Id@Q?Hp?s5Z@RL|MBa)Yo@OYk z&B$MWW%QXJ$4)pCnF~H~*4pBQvgJ?n*hv@*fVTXDTE-%vAn18vc*E9VsJ#LQU4r1K z%FqyLHJAR`HTbSu-(8@aFr((*s|yhHI5>rCn>5`Gg|~gxH*$!oWkwHvJa@PyI1n}C zC>)5rOszB%NGWv2U^x!&r=Lbtxy5AdP6?`x#<Y_KAHC$7mXw0?)Sm(h5rXd|*K6cR zmlu4_JCf<s5F|BY)gFm_8;=Btz496zSzwEZNYrF+ht{0Qt(^}MUo0Y~P&wXY6pikA zXwdUM?zixM;31W|1>L7i-Ep2YaaE;zW*XeyY4viMK+_%Y-USVEOd|$;dGxnhfW^~P zXPKJO*$pjIVqZ<RA6$DAsYaR6-ff^oC(7~TQ5Juc#wDmZf|5M5(8Aq%@wU<;5Slpa zGBf-2kzRp*!Zz3)nUqN+_I!i(rt`y@^WRSIhbAvfb(*z@H!Iiew7UNKIWbn^`9=S; zK=r|AU3mW~0MM19-pk>pA8A8uqozYloeU4-e~3B+!Qb|8Op=a9pg?1di7{eEJHdsA z3<Dqa9o)XvFo&py`eSSstT@0(T8KL1JR^TAUUi(0;Ky<fn;WB(cR#E(It?$@j=CHC z=$kNp07NKpuOCg#;c2-kmF0$C7hbys9=17_sN8M!>ab++0d7-pzZRsPOVgvC_Xgti zY-spykftN=25TVuQ;U{O+^*12{aj+qz%!<zfsU_0ErqAG$h$ce{Aa8V=lwy2&QuI& z-Ox6T8ABSR49j5!DBR|(veAsZ8V@zj_c*?E=cQq5Z{xE!2|ZY`f>D&Gg)uUN5ASU( zolG!0ZZLJFon$aq3dJdY=kMSfD7H0OJGe=PFh9>eT@LHgUa^?@fjc@uZ2Xm`8xK;w z(yY_oj4|W2WX3w26CCgp2(s<8?0G9UX_%Z!j6LxsNdM;LErAQTXg9=_Zae+J8RZM- zjiSR87qqZ|R4QmWeRjvrJ29c}7EWK-dJy{dt^<nS=oqW?^Qx#T@u3IyuXML@aQg+1 zyp?k?C83S}hR)NiTO3i`!3IX3qE&eDyNjMo;ka_R9k-Fd)J~QQ58+~)AqZUdfs=1~ z&qm%%d-M4AwU?VW;`>YW0`9a=-AsAj7W=wF@7{^l?5riz{r_&u1}2hc51vMM9s5e} z>ZO#v+!i?16SAu>_w}8J&sski7L>)^NotQQ`6a`6dz1Og=F{Vrjw!<a)({1SQ<nOS zq|Pc({P+A<j(%TKAcP3zDM#P^E7UpH5EJ8ooob+8O|k?53wjX=ZiJzHw<i3UoB;z! zO#9of1LoCU-r7!4DpOWDi`ys8MV<ir&&@v>{SAD64|<-`7)Cs?2xZ`)r)P#ecXl;P zSc=Yz5;n@)Y=#qgcfQ>7I^AB;^ZhyYOSclEuxCz^NQdApV<TY-W_2qe3Qn(G$q0{G zapEP{e#NS1n})aRz@<k28*q5$4x}539W3@VZFhcB2P0IqI$bK;b~~pMnGOl+A91`f zpD1s=x-v29*zW41oP)Wm>|?%j#7;y}1p%W6l;4a#A{^n!r~tHFV)5bV84w(8?<j!l zeE<RQpvWh(h1w+pgQ{o->fv~^-(654?&rK|F>d!!CY)I)EiAG&sI5zF?RS=zu66n^ zYIy8lX*%sVH}~q9d0!b^$<;9b0K)V4_{|~P5<E-J{Cd(J|2-{S7EJqpd<ft)OMf@% zaM9!DsnU`3swX``&RcANYa!VqHQjQTjn7Q2B@8(xteTiO+)n2`q9`lNw&>8RyWuKl z=dvm{F>p=Jie8=)v~}m(JkwCL^Rf38{?b7Wit@?OK~eB26EF;2GMDvSzd$nMb;9e- z`$8Qng|$?4UYW%U&5M6jKR$K;vHbNJ!B%v7%VrWu<Th5#R&x7YraHWBl%aat1)LYQ z-Kldt(a_`7nhMhWe^9^e9@izINXJuJTTuTj#x<4OPhGwe<P{cC|D-mi*AnIMlRBnw z|6a-6UE5-EW?~|8-ewgWP^Ib$B1c@mq8Iz8Wbi^9b50KzJHYhOy>I~P1{{Y+a}Z{F z(lOPtKet}s;^#)Id_2`FeKhP;4_*}64+pA!2CKtIJikw>u6+@i-uScHru28aBlj{n zcyr6$rm!dG-y#nnUcAjU{I;ztDfF5Bn{bEku5-%=lw6;2KRtFAQV&=sLbf;{t=jt# z{JXlzm&$wZXgzmaWu6Qcku`gzotHIGiM6f}w~JUuwFqJ36q(WkmQ2<iJLf3%`;tLq zO@L-sK4-2Z-Q!kF`CjP8Acn+-=xv{^D#rKVLVwylZq}YDa9V#KmdVh%I)R5l?fxtF z4Qx_5vsiKBPrvT6ROXzR!Aa|(=z46?_uiNHQz($54QPEwsPL41#HF$~0N>32ozWu^ z5}1~M;y9r0a@x^Pzq2zm-QA$vXA!K$QZ3F*!xegr^R_6b2kYsE2o&7FLEz2$)7mli zwg2S^*t%bo7M-`4X(bWe^Qe%a=}YPawFIPFeXP&%%3>>id)N=VQhn!dWU_Rmt{6?d z8b?z%`L%k6uV`}Z^Gxjtyjc5>=!LpN$m!O<^19%k306YUsk9Nc4)}w&%K%P^8Bfwb z`N7xqeb>p5kwooQt(|T+zZk(VWDIDzc-zrxq+sf#mZ(vv`yCLp2hQOX&-TkT;yK#k z2FMZOBnD3^_Heh_8ne=`W2IqNDsQ3WEU9}BjLJB*u6h_4MjhRt_PaO=&CY`vAuElr z;Ga)XJNPtaDUCvVwRXkz$%n{4qvhU7Ed3tRpfu?TaW!jHCk~pp>CsmIs5HF)XkYw8 zcj1Q$ty4`J0hPPF8hFU)$P%sYlAwF=#bP|D+vQje)(f@pY(|udig9J5=YS$NRD$af z32WC7Nwq&H9NT!!?87PwiZy$@l~KItqw_-52|u62EbhNj*R)kno`gVD)#F%A0pv28 z%4U2~uus6NvDr1uKvI!sF0&+TjjbzLlr`sMDgF1?qQSpokMr&NM`_D!wa&W1#A#7Q zURi=>W@1YOs8JeCo}l&<__%MNq3l6@(}jD=bG^D19B(?RGMb6SO-NuNW?;G6$fsV4 znv*KW=eL4?oihR9d!MPZ<eZD&V4Oo`ZP${zFd*nrV3Y882TX|Mlg&fIU%~NeljeoF z^-oY=3U-Z;-$Fm_EIjk0b{F43RRkTBmb}ofNvgnvXup$1)06ZUQoW$DD6x2#GOcHS z%+k5Dgvolvz?f9+Az&5r&P#52V%TMHlBB;z7j*`5lyZ6?dT8ZROD+>dPp)eav1Ca} zyc|Y$rhm2p+gwd}fE7wc(?vB=Dz4j@R5pf=9&Q<+CEs2Hhro@Bos3fY8A`VrV-NC< ztU=W0B@_>_02#+iJQ5SQ<oIwh97y?k^=l8btkr)9bEIFru}=2%yDNz74w#x4VV^!b zBt<<lun%}LI(_sjoNtyD3eVX(52*5+K3EV?Y(UYo_(i>O8F%RH(aA;WWUY?t3^Efx zmD}A}RG#IPwC^+$pxjY@GrwX^TPJ-6!VBbzW>oL%-s*k%<g-l2JALg}-X`OM@;okB zZ`5_k={j##-SeAt@0_!ZzopDY<A+MG_}{9Lhrz&FNWk;vjBSLO;-iZR&Qmf3Tjwm8 zi>`{n9%7x&3g5(nN(wR-u=Pnrde@f)CL2L_`fX&3g$*OdXTGxZ+hZU5N=5SmfYRj3 zs)pSVG+Q`P(Bt@$?aar*6B+-Ew*()&-dCX0vOZ`|{ep}mkn~>Nvo75+GP^o@X;AoS z?bU^f^32NUjCT#8w$}sBdMIsjw5s{0K6O${RIv#Os|bryJ0$zg)nH2roqY(1m-S52 zuxz+DeF!!hckaYzWFVKRJwWzzV=$GSrye(TV<n|MO2FnD$V#zNqvl4ZGHvp}RfDXV zw$~fq@7V6KS_d)ii^-~gIv<4?2L&;9lFv?04w}Ufky=`P1{T^6E73Nnae$x$3{*z` zaH&hh(w#;87V|XFyc<7tW#MAgQUFuNB4!qm$!&f2N%FRRomlOhM?UN*=SB!8!s4iQ z0N@`lAp#T1V3Qp8to#<u9H%)LhNhN>f}InZ2ZI3HBshx!r>)3u=N!SJS<4ZDt^9-E z`0%w(g<<Nh&9``^cZ8z>w-X@DqmKvWpR^nTcOlmB^1YpiC!I0xnvf!HTI8zsZ97CY zLm~f6>}sc64<HxM-=3ANvFQjmFp{gJ%TW1Xt41h$Wv9)L?6}T6rW2~MN*1-Ae&N7@ zcOW1il_P70l8b~N#QPBjRUO0jZlyT*zE=aP0<?227O*T%WU+Qc;6SJBMyJvPf_yz! z;hTi@#^KP6p?C5i;u}LjpsuAWus#ive-0SGY)PEL8#hYi50hg%E0FDCIR?acgs&)N z-WvEa463O_T|?%}c8;Vlb49j>03j2gRx9w~h;((HUmjtLd5H42Z!jVX`owHMq*!*- z(2?964u8)Jy|$*xq;EBSsO&?72ZRJfVUHvdj(p@=6i%N0oD!A+0-|>!Kg1({5oEZF zUN&{%eFS-ce)QF?T>u}^*@$q29qW=fKVD(C@DPtB^fR5tZ4)-1!E*lS<1;Tg_qoV8 zx^Hpy$rw<anjJijtDGT`O{ar32Ef(QXs<KsSt$P(GjVoWvJ7tCK~%na)(Ovl)bmhS z7uhI4mC0Ix#fgi2DwsO!GO}P`dHpn1t7haK1x$2⁣8MARhJ0u3-_Q64vhs<Xx1) z8Xz5D33@r_?6`miB#K*$6*9lFFGrS!C&>Sz9)3ModWK-zX?F5H9=TaBktwV`z89pI z59~ZBkv#;!Q}9#@0rK;U%#rvl-+n0PCCff>MI}aH;!sh!1{g<>c`UIg4rQ)?F#mKy z=xm)D4F$7$r`Gu%c8LW~WWaBm*7Ve$9aJr^A}IY8BPTkoEK_!kVr!FrhJ#X5-_U~^ zf#9{Un89Xb_SM9#-#rI`B$7s!@1(-|ErsWuS@#=}En=A?416)?xOntrDga+Al4Ubs zNeoyAT_&<qj=3TOH0qtH@{2X`XEfK_X~FFI&=ZV3tY%rTLH=obf6viIM4f6)LX_J$ ze8-Bc&AeKNBlcnf*6q?+%rD+`QVk>|@CKu1hN^g%irB2jBj3j(MprbS-$D)p2%xBT zt<mUNl=3tlaR!@q*|{{d3E3lY9;-Ri;cI(|sBjX6e9lE2#;d&d(cr2n$9Kvo85ZTO zz_?gB9w3`QmrG0Vtz#bm#33-Yic+&mCKp1KsF-)Dq)t>#`I;9<8e4qg#dqw>jUBx0 z%zWkc-=&<rqjeA)-CFp{eN!U$p;2jrD>sZ+s+a7tZ3`c!AFX|ac*94SuWw5mtex&u z@F&^qx~+Yks<7OB3|P_W0eq*h@^`Sv)kekZjRy{7?+a}>zBF}GohHj}l-*57mC|Lh zxw46kDoO=g&N%4WrP`T)kqt(vHmb=Ei9$Aypo%avvN0(5gnuZo0xO~J{Rui^J+JTo z1E%eJb_=<+sQ3D^h2thy;RaU|;41uO1bw9{Nww0dh@eM15#R9gm+{D_gUbJs<a;_1 z*_RSMT@lyKl2l%n4)G6HcFL^`C_KT#>t1Xx&{F<yNG4~!a?QAdvm&#vQ!bJL_2n1r z0_4X0{a*X-##^Goun^HixB9&7L9Wd13V0e9X7~J52h`z6Tc}@!Oxv3I|50`B|4jaI zAHQ~<&Fq@voaazT7&%96$RW~5j?oAq$*I05Y-7kFBP66bBt%ULm1>h?sHsS$B9f#+ zD(SF$_Ye0E_up_`kI(7-dOlytv=~^(7S)$m-GASRnvwr8EwL!X&rVDHVMu*vNO<K* zU1mu5z&KD3+%OGa5AsZ&oPNuaKq+sMye#=jsP$h{?(YPNhFomPGWHk6=p{!&L<qaG za6ZkQjFt*Zmfr-DVJN%ha<5o4Ax<^<NuGo*$Oe%BAFijRR%!tn)t~(;K-0;GZ_E~G zw$cC9*uN83_cB}oO0bodKTY}0b!GWS8JM<Z{A<3%Z$PSdHTXO2^tLS>LR!aF3TBOw z0g%PB81o+Tg{HWuF1m8CobmxX%nLfURH*d1M^bgjh!G(FAKxl67H!a(j?b`)p`l}G zRDcW5nMQ$VAe%&T=feRy+~kh&u?n5HOzFP^Nj8_|s2>pdjDm)rsBgjcZ@m3@KM@KW zdh}(z9O2>KLpJRv1;hgy&2my_`6mm@-Tv_Ot4WfV0o<RcQ=<NxN+=0ngMLUnEM3yh zJr_)&$j1?0oe0{5Sp@^z$2wV7Y%fcdNFE~V+5O1e{3IHxfD4D2!NW)>f{l6%2?o%h zT4d-Z8Wh%Mr|~MNvIO<_W_xO_THK%vWbm?6k$OG{;XI^M2L&u;{P&(0Bpw*}2`C)+ zAn}-Q`hkS|5z8v4;Ad$~@4p@UMv8rK+~E7SNZ(76m)dq3x8SeF2EM!;wW5h^U&g-R zZ#s1j&!ZsKKHOb6y!k&qB6T{6aOmC_v-C^`GK7NkqhWFZR6GMgq4WW<FcUhgD}T7& z!aDMHbYU$QIw5nM#z*Ct#PCual&{9bmds(0qWNa#S<aTeeFKwj1IGmTvqJo9#?4!H zQcnQj4+(QYsPB`}RK7X((GcMQ8D9=ypA2z6nr@2DyYTEt++iAKgKN=Vgy#;2l3vIq zuBzn1fDYe#MJQ<!Ru?UaJ|xZ~f*5-M(BcgL*beRj00R<;sCX!KNG6Tm8eh&ZxzUQ7 zuh_y?-%HrOQyX1rM>;aiT&x&1|9j)nH;K`4^tJs`9~e^iPD>2(HScOl9S+@dj)!|R z6d8>QoYS-z<>5xAa|u}Q+3VO!9>%&m3Z@~+n?|f`7i#zkfB6+J`9(|qO@g-RoDfdL zM4$>{5do**R5}b62RkuZ5ZLV^dRBz6`EX0Fh;ceL+RtOVV<lSmy?Q#hPi~C9?ne>` zZ&=vA*qi6S+9>gXEAfuw=9(ZSw%h9WWBc?aiw1GoHnB0i#O)~(oM@%T%AJWik}o;< ztJBQ`d`zMacwHd*5MX=iP6QNL#&n_FxhVFPhowUop&rueYe#g1WBa#4RE3bACt*;6 zAL(^^5FNExqss`CDfyJ;tWo0R;#al_eaAe;T3@a!v9jdvo2*>_ukzSU3;t@FUW-EX z1_}3sk8cwzFF9EAcjm66#3{{}mwsf_nd3G9Oc&X3g@idn$4Xe>i>H-WN}79sq!SdK z+ml9WSADWvqlYf!i~hb+_2R+}h4<X~Q29}4*QwVA%GY6yDK$S|GYy`k;XE-@1QrJ^ z*L=IH_i!J1U^#V;l<WU*S-uU#CNTBq_z@L6+$R~_1?J8M09#0F8rXj5u~2f2-|?<i zGB)GTH?Cwk4|{`*X;{Xta`DFTl9im?|IXp7I7r0by8>Jnb{vuWLUr(O(79RE{%O?F zW|*6BOegmFx#5dXtW7r6aoNB}_FoiTDC4-&nqz=Y+kG|V#5U7Z4d)$;q$mykH0C@X zH&pNDa|_Rr$MyE$1}Mk@JIpOIXNn}{@NW7$7jM6+J;lfFuSK`>F}|BF^i1zeOHh1e zflHyFL=p*Cpevxl44gwbxJldh>+y6gZSZKtb7=7E=X+e(M+&rY_HP2wK@1bb1fi%; zeg3H4yObJk$Sr2qoTK~VhGD7eKfJFj*0w<E?{YA|sc-_6d_u#o+TiK{>=hoSL5L+I zCAj>pz)4B5p7=f)!vXQX$oQ9JT#wNGHrJ`N3fBT4?<#!`nVHFM^1+o}j8e^tR;{Q} zfV<J*P5|IUgL}2~74=E4UO@)(!vh596VnGje-S@r>{ju(Jn~0xKSlOx9!b9YtFKY% zqdKIMjMonawwx!`V<Gi>ewR_1;|DT+V|nH3^34b`<{Vd|T!@w!m=<jj?+EoGxf*;O z1$%jm@&OZc(F5;JB|>)SL)`v%=g;c=98gW0hAH3xD=y5M1A`eu9cd=Sr>f0$sMd^G z)gp8t1NAb+1f73adPCOeTg5KDEzHJkE9Kv>i_ScP;ZkE2JRXTx6I-#3?H*ogcp39N zbB~br=R4Poe#gvI+y%R>eup)<Ctmr~2i_@r%u%}YAq^{F7kbla`N3RNp>&Cb2h=MX z&Wg9Pc#aSkKc3Z3Y?Uzy=Bw`rvOl?@=SRP~|KQX1`y$eUJP`clV8gzjkBZLr7e2k7 zGOfaD?=O^XN}U44qqSCLi<EB1(Ie(=uln-7#TGp|*Xp<J=*x<aSIoAE)Z0UcfXS+c z>@(HY|2hAIE6FaX)@DAr0l6_CrB<_t{pAIWFGV5;5&KS`MJ?cf14daz1Z_!1BfC4v zWo_W&E{X#7mc-eKj~6LH|Ikp9F8JndTsQHy?jTJ~9E>cG`1bgXe}94M&MXzb)zF8f z1_%4A{Jw=hx?p=OTwz1~uIcx67p;L~_|7c6R!{uRYyLN5w69zk&UCHX7WJwlFwqh3 zb^YiI$DomhYx`QG%`P0)LiC?e8$Q0cP?IJO1lc9MBj3%>)~mJ;Tv{K?z5H4EtMARA zKeL;23bv-d>4n4&#syH=K$k>lt3waEj!^sqO5!*+N9dF7`9v7tAnIA4yLf!Z1F}8N zVvc8z-w8K%z}esVP~y0#r&HsWW%WS=(2U>I5yfb3sCJ{D|DYJfQes=qo*52T+CA6w zu{IKzzEo)4Fl=b@i52xg!nq!L&7_ghJgd2Kqor88<y}Ocgt!<GE@>tmoWB#mG(Esl z|1rK@wws4*6O5)n?Y(!`qIz*;$?gc=7HyRWGAAZhoE&y3gx&CPQfHfb_W%3kWa?!a zcS$``sE900y&6}b?&I7vQ2P>S%&PH-J>}>GG}eSy2Re>rUn;8ba8&oD3|)2x%EvAj z8U7iR29~OBT=fMOCPTnW_j(_jwEPijVS%Z<-MTGZr(ghC6b(T09X7DdR6r?uc*G)u zb=L6y@{@#Xcll@`mAp#n<ru~Ma`H?UAuQ=kRN6DOlMedX=X@<cW?%F*^~f%dxO%H! zDN$S$<n=PDGOp5X?M0T7k1MOy`{;EKJs-E&k7nm1%dMVZt4m7rb!%JhJiuB@#o2fN z*dl}9Vh5lf6b`O}`1?jI@zyB%6OgdS>;+UC>sS$G!6Col>l+orA@vdzTtFSh0aQFx zyjx~d*U`?mS=(c}T>gBJjWZp3U+wEYGf)xHy)s{$a$+XDI!5YiR!4Nhv+(nWoiSge z13Mxm-k&=Y7upbMet7dm|7Trah6alF|2Sj)Y?>u?NtE&?8sFRn%pD#mo_JVD76a4n z#TcvJ`%PoA7U0dyifvfRs$}eA#~vDt*DW~&eQQ(j(I@89wSgTcKidX;xESLO;Sy40 z7m-y*`V~<sz=GAK<rh--8x<YrUo`B0OWr+S{4W2FuFt+umZBJN$T2;DGO4$xt0LQ4 zzD(ChB{6c<^BvDOIxlPb56K@YFE&^XZNdbfe$X|Mh&Eff9QE(C3~jmuP5z^2^!?$m z`gNeu=I#tO>z5td@P@704`KGskvFzqRtjB~52<BO4`_5jq>eevYAnfQJGvtnG2$e; z#-}}hyW;X)0g`$LloD?Z*%tmMN=f*!N6pQtU362MrxUfrQp=y;b}>%RgeJ&P1%wEr z1s(iJia%+E<ZK5u(LcFh7Xa5#Keoy4zYi7u*s<QLCjvj?Pg8{0b03f&BpNUU<V^bH z488+0R&v=PY>V9ZU7uyB%efqc(IaE2BQ`~{id2<mYbcf@Sk!z~j?#}UlKywsLE%D# zqRVwbj%g#o54~oubeooK6?1y4V!h<P1tB}nAuK=%zW0V9T74=I7Z@$DC#vbm-UL=P z$s<qI|GncH$)X7d7pk{>zqL2*$2SvESGLZ>;KE=IQ|>PVDN{$lrHmX?YrloI_z|bI zA&7F~hxQqIJ}D+IX2`WT&(Cvekd+V-U*}BQ`MqB#XrpLm1?@$K*)_Q0kz(yFcsNC^ z_oJ+Jj0E1#vUk~eRX|#&W`6LOIWV<)_Qc;B@I=qk=Y~(v+m2r+#8fyC!5U)viSa83 zKQDqFggoqLP23yHY_opImXre_YWNET#~*FY$(9c+e!g-n^uPZ69NkXAsM67-ya?x3 zZ|sNKI-&Xlyi~e4cBcGvhH}LO+rD=OXM7<)y;rWpp-}^64k|p`c#5!aD=ua)yK2#s zxQb5_wz7QfEt^r^FDE8CCb2lcF(Ee{m{ku-g4;ftafmftYi&PY<UnQC-6?ZW2=qce z1cdoVRbVpPG=@x17^8&eOH4%irJFT=@SawL%iv=MGZg6A)n6^=E7MIY(pbgWc5?!> zNx7W{Fs8npyNSJIx6doRmP9^PbM}OEZ)Rdr0McSo0Ff!si5bHm@9mK*At9}EJf>W8 zU{|xxMr@9PFn)h`^gbtaN(`vYKe`63Hx>6Ny4PsKcR1p6ch&DN@pKxccNioNMkXt3 z32e(Z;f~Y{%l13GwPhW?dB?u>CQB3T*riAI!adNQ0BcltOb#DJwr4ve6u1Cfb<9)8 z&6xzL5Te4>p;nZBdEWEn-bQczTRHKugvk$6H4KL)Kh+IB+mI5{VAmlDhwu?YP=;-w zKh~Rm8>OdpQ}4n}kpTCMfr{yH)jeLk`+2wHG&#`(qz^t<co<wm?tD3ZZNlwm{{}uH zHbnJBmxJLT74O!IiBqo0Hay`mrV62}ofq!P^?M=-pk35XolrFF7Rs1o*oh6V?3KEN z+4hr=La?`?G$iUq5B-Em8hy6{X11I%`5fs;$~=&?h#2qLXB43^l<|f$-U{WG@Q_L3 z1h;IuuD0qAM(_GkoP^t?eel|(uf+lt=O(sB{#5R_p%g`jdAX~10qh-OBdl8zwP0NS zb(?q`Y$ja+rukwD&9u~ZE>U+EmRVWee6l&gEX&X>f+@35jH)S~D;6csRR5!sU}t-A ze!^9vh_~{U>GOK=n%aB)px{DZuMG7Ciqlq;xVn_BFs1CeZ1U}-xMI@>a=KRz#5+^- zf{sc74~g&vHwD=z9v}LT51K1HA>WA5u(nAqIj<fYvwpK%hwwE{5_`WCW`+)N7vXx< zT2#vUe{LLMML5V$kWX*nzEhv?N?F{mKF@4CL~L6?+5OYNn|IZ!34M_-vuC{XdUBNq zxemnidXrFaDC~tLLh)IW=hnc0HmgrPB>KOj{TBTd6E_}cyqsp+-MGAQ#N+Fv%D$X7 zQ%(FX4polaB>%%+F8Sn3S7PQC^v*^NY5%bAi{J03zxt=8P`!-WJDHuzM@BAWC(~j6 zjUoa)0ojQ;|9b`*j<zZpLTW(}{N~fqpuF9}>CJvtA6~(17g*1VNZ3_L>)PBlfKk11 zul|>`9j~JLh-44x_T31Uu>^c3F3)0eYv;6#MfqigEt1rAR@3Z#Er*^o=>ivCmalJC ztR*UOQZ`VCaEnD`akImxZS!6tXZY;DRK-*-+pzX@r4VV&&4BkvE%DFWk}?e^S*C+K z41ety1~N@2Sr#;#hl7}U@x{dDY)5(h4TcOA4O1S3*g!IO(&2_^jrCcXv4m>Ja#m_P z3**w`_N;eb2+BW?E%rbj&#_D77bI{|zC62_Mx^YgyN2DF!Jb*A&Qi1m5u2ZKJ~|e0 zc3)GTbJKRd)aWZ#q;;mm?S{uWr0veCt<HGoLy|w1<pJWkzr|GUq)|Of$=W5;f^vWF zVv8ZIwSG7+ak1WlMzyEj-QzHjI8yy(h<$*9h-Wx?hGwSZAk(<nzKsa)a;KQ-o(`pk z(uk}%G9r|>OF9F7_GEFWU!83ujJyCfjfGK!O&81c9+Q=fXc<Q&>K~Fak87Qdl*Bla zW$K12DEtezbu-89s&@~|JOCw+XAYI;R|<Wz9eI`UBvc|O7sbelpk${kz)i_)UtN`r z^C;g*_PYp)Kx#w9q)L!8%(h(Wsj;dpNjx!y*`2kgFsu|tL>zq$xFHR8K~vlIPhC5_ z{)U6=h1%Tw(7XX%{8JYGN8J`>zyMZs&Z4GSSyRFY$T0cF{&RLnpgrOojAC{nok8Rt zE3xJe8AQrHvYh1)Ww<Y}_wW$z(};~Y#D+&!_|sC?i1VR?D9;Gkb{ff+2)E<G$P}2} zCm5M&1)jG*qF8VJO#V+SY_dpFL{{31&3)fC3?0kk^J*Z<vT`E^&H5wriSGE1YC&{( znq_vXFUoUTEX=P;nY<g{n0;UYv9A%ahYJsP?noA*01`Xcx-L?P3WvgX?t_Wlh2{%T zYZCmbw&S7R&5eWij@x%u=So%tSpAL9-#I9PIr1`gV{?zk!={pVQU_Tv%yZ;H8T*A^ zkB~<n=7dt8B~Ngx?HPCbrw~5VsF2A=VdD2EUt~%nD#cg)W3&Bu2oFp6o^s?4Iy<P5 ztv1?6Sb~~UV5Th@!Ctu)SPPs7hGK~Y&@>2J@{iEm)KBL`)HypkOPhV&Zd%|#hU@c~ zq%JJ1#==%(z=a2mw7l!FDl|X-bOc@S;7@k&0_&+WdQbVLT)pip#&_}?QNjF7&lyB; zCEGiK?dQu@Jjym;z{xp-5-ckTjFLfLzCFyM!8v1xXLpQC?oF@Zy|%*@-^xazLofqt z?qv6lF^IA*XD@V<JvwvCpr|>Ioc;dP(}2G5LGDmG2Tof@MK+?`8?)nlb-#3H#_>0u z0g?WSS+!NjS5LFo>QQ?D*wy^p@_i*naT#Zpw7y0ZUWk&62+lN!Fm(;UzG<rX{@aL~ z)Orzw8~-YFTxZEgLD7C0>65|(<Ihu%=B7`xse|k+Mg7Fs+BgPMC0YH9B|G?bS2E8q zwHz5%o)yN0ndQLB{i)$goO%eu6oB=>I&%{xM`~|qZok~`oVk_jwLa~+nGW~Bf)3>@ zc`{T?0!i~<$O8<FF){7?i;I6Hq-WsnJc+%Q>{MP>?hBMS6QAO&lEt``95Ly!-b0>4 zSjT33ZPc2w5eb?abLHUL1;-^@E#YR<4O|l+hy=_+c<uPE{hca2J6eVjk0~7iQH+2n zMEtLGG-Nru8u60<+UJC9){a3$nk739sLCO+efc?FFHra2ImtYLs~6pI2)U3i_X@Y- zA5+1#SSX8z!owrs@yYoc&E5d9ddvRTmO0p4ruq3*nPM611zVOT?Yg|MrVpHYb9A4E zbnVk`@E8U>N|>3#%bI(iy`L&K*q6C?t{_4c5zbW!7G^(s`Et}&5Su&LEG)ENeYT9) zZ$qY<#SVLxp3RHBuk%}iR;lgryAWy&SJ#DfmohbdGn93iufM<k_gy&EtQ-uYd~36Y zmPA=;yq<x;tiity2YcALpDY*Ooi4Af10|GpPD8&8-x@5Jx9O_rNm8P0RVXHM$Y@T( zyOtv^x4R`Xey&6A-MywqhW~wkP;@i6r(U*r9hF#~d6JU7BZqyjjacvC{ek^Pm5Gqe z>pMD$ATR8``d+e;kKg@`Rr66k_LAO81UAM*Xxe6K=nNK1<|b}|ubW94iI-Atpc<KF z%rH=rA5kuw72GH}u<YaPe8oRRJ%!eXNDJEdg)8i8Pv*nV=H0@*2{N?GY<ZSZPct21 zC^^#d{*eP)hB8Y2$`FvbDkChDvMseQq>9DdKZmJa&eF4FNdt@k060-T>r*Cj8OuRB zOlPNY;GUK_5$gq-K}cZvib`BovJf6<sVEjO=N4cvS?`9pb&bUO9Scx1dgkvz%rav9 z$c|wPlB;zrbaB$?jn(+CsEST_t`jD6!38cxH-#s4G+V?PMy6OAEJb8W=YVh6?@xIT zq^*lrFLpWw;Y&n#Eo2|<%1lYp&03!g9<&_N*c>&uT{}=9S=6MZT46|sOEya%F3WEj zgc%ayrjgj#YN`=QLH6I^Bj_yb{Fd+75{vbEu}OLhH&Q<bp8m-sb>gF&Y=N`oHWinQ zqm9|AZlx*f?+?c!fi8H#?lb!qwD{XB9(CPY;b17_SEdnp$NWX}7fG(oT&dcGyf<T^ z@kqEKL!)Hkf(;!y`CUnFB#-QyL2lf?yXMn{jwAnug8{JCGL;C>GqX-3JY(7628(r4 z;o0s|zRuc>|0Lx{>Zni5&DLQq36~x2pbZ-{1~Oz`D;{aqIIVT)?L}ul2=>sHVOE(b zd^3<~l!Wk+D)2x4{!ZCvE%-EP2ZA+^+DCx}>27CFAestF^LHDk3NzcDy&ToO<^nrw zJ;>U!+4b|y9Su1dc7squ%VyXf;nwxD|GK(sugI81v^LJ<bu$c_a#|3TpVuaO-RDqy zX-FAFb~-(C$6)sLZHsT;WTF3*N0aAmX&Eao7jM$3HoHZ+4UwUv2)ypU%?8Hu_tTUH zr&SHnGYu4jV^df+Oo`EY9wmu$YZNBvJ^WohZoFMKNC=N_MAgf&57ObO)7b}4WWBAE z`}YR9oz~*yZaT0z?^{lTp)(BL8s7RkO5?0HZ+?0!$Ko=*=85Oq6c1P{h9lI6OWw?` zQd`kKc-MUn;m)|5%E)rnMfogbhB7kWo+<rMksUpm<-7j%TltOcJ-)@0#b{`z^|aPb z&Y+&7>-BQUdWqMj=*(S`hof5hmpv@%?II_x!|Z8T)0yR+z8||m+nX*W;J~VD=WX|A zC}(s?ye>)y&Pd_1w^_1NxLI!>WF`;F1(MZ{iTiK4N#8?Cj+eiCXkK*QKGyN#?$`x+ zjC*SQV51||tJ9HKef+NxOn?<RXF?=6z{>Cz^vGoYS|q-!J0^^w22UYnGbxBPM%GCN z+?$68;%5JxK!$O%+#0<_iAxyA<r9|^b`I{&kH(56u_Mb;z@Rg6%UZ(S9P4S8y^uQo z{Y&S%%(_9QBb_zx2Lslj6fTGz@`<{<PJXrDgvdTlnF=JKj;!ws1;2SLjG2Bwioc%D z-Diu+%jGX&Hre-DyXAwvMvy%+XjkV3I6qN)6Px1vw%sd(8cUX^!Jf8@?RP1@zq1pF z@WqyF&&#M-Uu5nAdfz16yBwK95@nvfcq80<zT{fnrNNAPUPi@NmN}(4FYH<#qb%C< zw{>>Fgn`08p%EEeuT2OrLcb<^bI8k32hKV2|4Qm->vT@}+yVD4L(?abZn~(MhX^-@ zM=V3apUZYDhw)!stElvH!TFU9XsyL&9DTT(%+0VN|HWzM{p9>=AZs@Yw>nzBSi!nJ zeVy!LA$d(glFC`ONzOAOW}Kv>T#f$Br1Jtl!w%3<-A&nFGyhD<Abq*n$&Co(LFkU# zdoMAxBTJk=Up%w5s9`H5!@Ln@XZiP7;PNoXROfC^`(J0HdpY*8P;27)1w5Ser$42w zy9=GaH3ue%Km$;e^j1;CGN~sMqhJ!fu&mLWBdz1v60xG$pRZ&QzqBwmW1T(@Y<h6K z`OS`?Vqj~=gk;%{)NVeo`ZRm*xvC&x;>?Ra*NdjMcNs%H^{y4BnX7*UFaTd|k@SvM zP*=1?jgsA!80>`x0UllM%${eP+_aeK6aVydo%ft`WTBDLy_@p+j{5+TzmD+j0H1}D zF^papw~gm2XoU|vdZWFk+oVX@BKnz4jA8I-Wp=J>jb-vGFt|+@ckx;C@2R;uSwMqw z{oB%uedEoP%kKJ~qkA|~40|?amz!83UAyzaiw;#^UHm!Q1OyWEY+>}ABUAF$3JXo% z&ib)rY<TRSjc8+S@p=2+oo|BH_r5TpK0%$is2{x65;kjN<gJk23n|@q4Cs+%rRQf& z@4GYZt<1dRml$vi=!H0|0$s+O=tE|qRZ2q;p1fT?u<Ypn$n0H~a=h8<F5;2(_mfGY zKTp-pSS@yG720mB7abBgY|F6@cqUeOmTPZww=g<>B3CInrvr7A;IF75o)65S&ZR{- zD3|+JJ1YS}+V85O@tfWu02XKwk^uipKojHKENEK6Nn?XbSqqVfoj~TARt;MzMYr~} zdH*9@QI+)Y4zDFo_pRMR`$95#?16I$Z1?2!WfZk9>?o1SmSffzls)xPx#u!L35p$a zR%7alWOEdbOhsNHowU@*AsLwn`gB+uv-srPEqAuIk6Isz;4qiBJ(RyKeCllbt-F42 zY%uWd<K-H8ubGUF8ONg1`d#0%l@4?T*HW%+E}8eG-;m(PcJ%)a*Ek(plcjNV+$>g} zJ+j|feqVRbBkLL4-{f9`t4*8JKi;>!hL`!CuIdd86TI!6P$=K#M3O5#g;x5hM12>o z7`-pf5I$IWx{>J}pl$s#T+1)CMim%`xE=^R>h00jvjjLAKi#wa?~UG{QwdAfXR3>b zcATO0?6JK=f8wV~cRsxu;!~#NeJ64nTNM3gLJu8)#GwW&0HWp%3cuMSN8@P7&xboR z>_oPfGi>EYvweReicgy@T0TKp_mJ%#+r$XrSCeVD(EVywzv3DkLLh)6QFGBv=wlA! zgj61Hy>;PjFkrYobMsZ&_AgAoKace@@>dJVEkcuA{a3=-tj^@Bl&c|k_ndc>kCZ%@ z-7PgHS*E7x{Ww@Nj!`t2xUsp%K{X5b)UVK9cy9ae&v!)s>=d>oxa_<|?-|`xw|xEa zXj-pE>HaOI<(Qf+c;Z8r0#I`;hqnpLU-yZJ8duE_wFw7l83*Pyb8gQ`NX8rYDs$w! zLIu|{H`~n2uoBUpoD7)>-vKR>G2W)iE&0Zf^!Z+ghWy56(~}I$zBSU7CHAI0pofS? zdc$X*+<%xgF5{3jC3}w^CQf(yUQlk~-uubr<puqD*FG66^`>n`y<mEml}TK_(;t1) zVf)fdQwz{aI`a&whI3gskEqvvr>|N(s4g9xy_HUm=!n;(PRvnL$2a-9EpsV790dQx zp-6hS_U3Iajm<?NvQt7hKpx9axe<&F`R$##tV_Wf?<HN)&e>n($+zKO!iuq}g`Qg1 z)4Y#hLeryrm?vnXKW-7QBXF6e4r?PaHMQc@X4AU!)uc^5a`lbbWE%lqEOx~m05a5p zn(O*SN6*Z>EKohyiP}k|;ewWX3>1SYfhmJ22WJjlY3@`x5FUIS7OCAMB1tf|l19}( zk!nn3nuY9?Iko*K`?S;qxFB+^dJLbW!56Y;OB|~x_0rA{>YF(mWVgDI%aGU8qo$_} zFV-Haq;$Nao>#56{`>6F1=c*mVr>)*T4xzK4hn0eZ#GI7z1-PD&2!4HRk_SXS!AC@ zQzA;Rk+B(&D-Q1QSKTa-HXOAl0Ft~w#XtSTSy;5%#+zn?OaQ)T{7IEv62zceS}9OO zN8bw7!2clDY%16?DUkAxQm8|2C5gq6ErW%ou9@mjcmt*mAMp|Fy3(kp8gM`Nx`AI) z{*D<Ffz?+vq96JlIJfPxT_*D~>=nI|&-K9?3qUV>-Qa{PqJS)GBv37c>$z*>`*sPg zr&q~np;z3EI1tIit{1HG2W4ZVLMc0{y~i3!C7>Ye2A=w<3fb1{c#3U#=|X_!l<+w> zQW$e&@oZKu2gUc2?!0r?D9!jIF}-9~x~&Voxn+iJNBr3(?bb^|i`{xlMLMA*m{^oL zZOEY(2QAyPe#_-_dG{U-1hA)fUuk!k-sSd85F!VRby~R1Y)_Ay+*sA0RjiB6zvFDb z;}Ji{3jOZNTFN;5cRAXQ!U8iaSBo@^(asbokk6q<8WnppNr;#yN2LNHymJg&3<=k6 zR;qRhb?h0`%t34Uf~PI>(zz?@Q44H6wXNtIqK-WpzSZ<8dEIh{X{K&a@!63{Xeas9 zSNEes`|_5`5L#23vAf&9R%jVS_8?r8{CR!ki4qlcQITyn-$#?%X)Oh_zB>j{I&NN$ zAeTP|_t5POGnHmtp5C6=lQ7cfJC^MWLYdF&+WkjiKEPyfBD6`aYOXn2HypByxqO`> z3CX$G(1>9#J539tKOIdt84?mYu!lT@y!|9NCf)0kE2_?WdwwZswP&zOnn}6kg-X<~ zfRg5=v&CW~$3h4{Ddp8?ri_ip(GH}X?+SuShFYE=#lEus9C$s^S~KLl%$@NvSIa)! zK{Kra)a8VR&y6+L=CLrD%`5mkM2BeFF#T3xN`P5l^vvO#ns5cfC0}b9?Md15mcE!a zRBe)qa71yiYM}(lL>NT8Yzpz03@-7Rf&qnDRuk=Kw3=|e>c1mkGRyQZ>GTuL{2!dh zh>+govGyDcJkwXe-6V1E<3r?&2Yz!sYvb>0t_pHtGVe$@Cm+vGSv$K^SZj(VVtw4N zM-NoZH$JpqQ}y1VkXI(+)%=$ddD7#=8KoZ9(~k?S*ktEng(@Lh*-X-}-O*<0&@rOp zUs#VHLqDKf<)`rJh1F7@lZ2CJyp2#H_^7(2c8jT%$F62lLA;D#ldm>gwB9CUk$Yt; ztjsP+z@J<f?O3<)H1pLB-jgokt@?M{d^ViYSo^!>+SkWtuGwp+8w4-Fe4c@Ww+{ST zNYoqk{XQ&;bCO@DzJ)_&d<E00&pxp)!gi1x$s;>ucWowt8<!6L%%mzWjg6`lb6mg+ z2tUm=4~=dJAY``OfDnam`(Ff7>kq1tiMf(=Ql>yb+wN^9lMvd|w~pXbNgz^V7ktP7 z5U91de2gxS=H!spJX9h`o{f-?3~JaWXB86OgFzLyJt!sCc(q9(6pL5mCe<Tkk)L;0 zg44<>ba_jGemSfFU8C}-#@^C#oP3r<gsR4hS$$MMW^f=GItnV)q*9e^h)S^#r6sCr zCRMKFg+>x$T?8*ke39GQ!j@qN$MX^X(HtFl-2T&h-kyTU%t6fgPMaiDRIh64V={yP z!i>lQ<*K0n7T#vf_&t(zkood1mTae;rnEkYSWyfd7}}Ez86A~{3QxT|kjXR%JV<h* z%Ac~^^lKO2%1uAKPDQEg5LltqGE<QRQEOCZx;$@<cDP?9;gQKSF%SF%&wKxjs&+<7 z#uQ5Ks{R>Sw_^v%VpU3pRyt{{0_|g-`+jjG^c~y}J~qAUJit0o?_VjzRQe9&m<mic z0)9dc?D(SP)L(tb^r4smQ%l0GQ^p+cLe@*_tdRZ(K8}1C8gK6-W!&_vtU6f98&ayk z6H7wIMJ*Xtu^vvyOJLB5zU(d%&spZ`8OLO?6HX8{qZSo>-YR}-RZ!}6v|Kht@Z?g? zrt3cZXtaO%UKQ;Toj<S#q4l(eFz}z8Cis%fWD0zpv?c}HF9{T$y(MOqV_ydT?W4*$ zmnq3A^SZsqs?e2PkR|6QvTi*GRb}Zns{9=rmTc#(PYDov?B>kWPMX<ib)Ch?`?L=3 z(l8x^7X%--3D8=fQKrpUG(mi|q3*AT@1lF6CdSWq4P7zoF`$jMaRwZBZ;lOl{bj00 zsh6Z_YNzl_z>lSA0npVo$cgds2wgOb+!yWaBL0Kamx|QNNzv8i0S8bYmzduXIHJfD zq5+)og94$*%P0GT9(1$h;C8utSh9ANa5GPtC%cJgf)YoNUJFs?LXOlk86Dol5~=7N zp(kGty*70sRs~fG<zzCce$sDFhBv~3BsE)@>Y;)YriTNM4j?Zyw8qY(d%}5etYHD& zKXx<khWk?kaJ_|Dod}6VXYSiAO-$<PBfIfiGdNMYMLlXAyL!~!dbUII;y|`U$0I)P zd7xn8z+ACT7XDi7ygKn+;57BE*jqlWqOpr*{3pZyb;hxO;YC*?J8kE8l2~%Y9tH6P zcu_m!J@YEyDpTE{^Y5&o{GPG7;I}Qz?M&v&1<e|kK(<?;Lw``P-gii(mRH}QQ|Y~> zlij=1tw({>Q^sa;SsY(NpF-8!AmgU$>cu9z*$7`|Lfnh9)xJaf1?s0**1RB?|CXy! zuZgc&q!x%~*FNIp!=S(cg$04{_;{nIPNeJy^%2c{8_k+AfpR|N@cbTW2t(E|yv}y9 zb-uYXByfD4Ri(+&n4~I9U3y&-#XlubhO@vGNMeUTg$udcKqcif!{kTLJ?bOU<cX&Q zM2DV^jSQ<l)17K9Gm0ez4y-WE9&O>Kj|&gK?}^S2I{0RAK9ROW>=tB^`V?BI+TC_m zlW1DAUQhK>$9|kSc}dxF3F#6n2iLD|`1Bnz-0Qxi<n~EH#9*qfK~(uUq|9jJtp)gs ztq;`<T8C6R*!J3?gzDlWq*H?KEV(QFEn(gQS(QD3I6LLc967O5FCU`W4JA+II9`2R zui5(YL}kI`Amz{a&c+A&ZY+&_fzsNL_FU_)7OK|kJteFrQa+WG#NuNzAJl(-x%tbC z9L#)e+Q5OO(IQarrONpVUcYG#OQXK`kIBB*W3b-SC+lFGA7czKjH?V6m0$qJ@MA^H zVr|SPX@^BA_^0bvKi&JXI1%&l-ItF_4j(l$zr6XfwD{%Ay{n7T*OqHzzD&fd{xDos z`nqCbv}Sniv-{U?N=Dy1u6{>e`(APNol+@&U3|b4KLW}!2`Ui$6dyOp*yv#Veh5gl ze8o-jaaG5DZ2)+Vk@%rXlx2kfV+4qfiGCadP_ZIu2SBD5$Tk9GmqlN`LM?bO`(9|? zH5fJ)agdDn;=vWjaC|IECl+}y7BOoiQOJWOEF;pFA=k(l1u_gqp#Xr!FE}C;0D!F$ z00OXu%0mIP2!NpB6gpRsftJ~FV31eyARE-$UFF<X+m}b&7Bw~4RyR;cvd>j<xn4hX zR(D_XfuZY{hR=}?J*;wRZy2q#Ojw*6+7=82kSQ3|-8UM?>YUGFN+4XulgqTa-4}M> zY#zVzf7s{$r#^=}T3>a>&OW^0+IjW$ouqGzuZKIYy}i$XVb$Eacry=jWb}hZy4q$3 zI9jgNZnv(#A1>c^<ju&f_79J__IYZ1Zr}L$v~k~+pwZhmKRxFi8m<o9a3Z|yO1M}B zAIp+r?o7n0zcCqjpw@d<{~XbUer6g|xos#o?AG_0V`9yG3@sa<A!ay5s2H1>dNUyH z;K7~N+xxcINGjbAWOq{Z7ggVcKi+97V=wz!d~4W0clovF-%UhiDVQo`Ea|M51$a#S zf>4u+R`sZ+5VtJU9GQX8s-^a4MhKN=6m#BWZ%yl0brs&!oeeW?@Ny{FHs3gV#^%Su zY#{}yH^*_1kDM!V-rO`->}LLP?kvqw?|q4vcjWt0-|(jQWd}Sr?K(%FKMqIBqwASL zJDkgd%J;^TA%NHy*;^T`SmPmgq-C(-(7*M%Qj}UWg+)<7ubsA&+B!Y)-^m>v;yZ6k zog5125^wS)P~j98NCNC?avxnfT$lB0pQL%i)k9~zb9Czk7$90S4M6~wl&JF54d{pg z0Kga*gHxY0BbB?wx+T`s^mJ?P_vB&QO>QfN*ZA?rsWnhPl74GPwVZl;@#~&PXh^<s zYyH8o7fr}T>t)6rKm}{p5TJ1xmN9M8@kn1(0#bm3e`c}U$NkN&*|l54dys*5%fE)C zt$zA?AM)GIyA7MX%qvOV{l};e+Mck|?{7W)s8_u*Aio}QcFDx^-_onE1L_ttc=E!% zmUfR+D9P|4GG9oQ=={?jKfGP1b>E2EFoy#Ckx$4o($_!w-Q70t6&1TQ1u`V>p{0lP zJ6kf=#v_JrJbHF<YIR5lq7pki<@KTJ$7|zXRyTJRkwhVGD2Vfsw%17tZ#+j5?(gX! zL39CzQMj_<uiZbqVhW#KTiSg>DyL-@YYt3q`?auz8uiF}vb*QntFViEHa=-5|I5`W znqqBR>Z;4!xO!Zs`uA6o?S?LJ@57hF#{8ez`P5pUzHA5nzir@l&26S^=FmZun<ey; z)+ps~*PEw$a!oRBKkO?^9_rm99klWMTe3}PBK=+yT#z=--4XY94aPU&frAED1rnax zv!@(qP{1JM43j&nCZT~^hu0STMYyCDTW3)>m}hvshe)4j*$yh<f+<dh%6m$Us9749 z!Ld`sHuWKYLKu#mLY7QZkObR4mzfXSY62HWQ3;y1*^|>G>8LkS_(K$cRH$ta=j+4c zr2xjP((^`)WsdO~_00~Me)))BnF9Q8mwIs$9s^9aHE)s+m%l%V0_Mgz@u!Yy3VjEx zeoXS2u`t!twSM16)SW&6pcJ$O-?cR7_`sQ$gDRpslOoH)gm@sDhyeP>3Yc4sG=l(! zno?xBW{|zAbO{`2P6B^Pz-7K}&#{18fzIMhx0>c^)-1qe_|8h7C+5flBorB#mO_2( zp*$gR%yne|E>~Oc+Y|KfIlDC58%Q8L89Y*zkp(>u17vjxG@^Fi5rU&Fsm4W&yhzE! zK@}aXM)}irq);MSUoKvBW=BO2Dd>Q+x_XU-PtUH(GNQBc53(DR!K_9nJJ^a$&g|G6 zO2io-wyo72VskT;PXmDEF0@phw>0or#u<PxvNGx+=OsMCl+YSkr=^iffH;D3LIbSw zcaYHx8{SEHf(R=P29MIwCY`aU@Rza%jSCK&t;RHRVh@pCp31SD7vNI5p5}rz1KXzJ z_m(JSVndx_s_-86p&wL@$EW7^-IcbQ3+yRFzR+=6C+q@Z>y!@r%{WijAc3`+)|}K& z_Ojcbx1!5rkWHwcF%kq1bbTE*5*d(4cy>B8L~S<0!DQZ;a~<<Q!#&K|ReS<69^7A4 z@H$sp@-)X)L}n4PKWYOJR|0a@qyafuXEL?;*|UE6Eh5I;FQhTYb?e-Xr(&%ed^JC2 zNt%bP>8Fx+`!lOfkR)uwcP%o&P{ViNKmjHcVKS1Ow4ZeMQnpVMwIJ@mccY(uhNf?~ z6XF1d(x?!%Io{fznG-^Ym}XfTU!PbDy3_&_v{I^m@9(WT)b+V4#~{TL+_ia@^!SQi zg6b)Sf14fKRjhVx?+gY{L-}3Wj#zCKW6&oyiIhQH@vb{k)N(IO_F4IWIo-J^8X)n{ zP499)ew(v{Z`ps4iP(!WIgrJ-BkKP9kZoHRn3=?EqZwk4LVy6P%?_xyN;&QpGp|P$ zo{9P%F2t9=2pRmCMkDzxJn(NPbI1Ufhx|1co?~<PmShqs3cX1UZW6+j6<}kCIaapz z5vib}ln<|O=QqEFc21{M9uf|80pX5P^%5OIJ0qmYv*BnhdFYE>v8d}g?w2n~odo!` zL&FP9S*BhCl45thEsRM#ZzA_cXVZzXz>Mf%DVLi!eKC+6+pQ^h5CL3Mgw6y-v-)(a zM|OT+35aYD8zU$RDD#kjjFH<WHd3{&4SyUG9%w%&L_$Gi+|t+qjcy}qrs?O_BHwtp zjDun49fJq?8N!g8`ik2GJD>Ep^UiAnC_umbPtAT9NnIfOwpZ&(Kl8vT?Pk$jk;c9q z@deI%u{RpOJ72G%Ds)cm7IE2>=(q?QQ{rpo^GH={M&>qjCN7j=zFTExC1vV>_N@k( zhRy2h$2spXy*9s|mP+FdR5tL*0N<bKPB6@TLh4g<Hi`<4%!2z2=DGB2=~@mwi-yV1 zTC(Y#hDG)Vp?4YR?QS~KC?+MbBz2j^MO`m&k$E}kG~w8FZg%`@e62b-chaszm$R!y zPT1c)IE}*>{kKoJcDjkWr%H;E7!jm-e^aKqi3!>^-}CB!5o^?>d~lznqKN~*&<Ynk zL0p4Zd1)iQ9()XjL2H+ZFU;NAUxV^TvaouAE_&sA3Hx+wu-SZ==tW=%CY82sokzE~ z8yrf_pcTI-joD}Dyj%HX2?27sZIqFbjURizl9(j0wqJUM99R*It)(DdbV_&dV$8+^ zK3l{B(`qV&l-g(DU-`g92Z_kbMBIOA62_<qAyUhir9DXqpo634PXEq<?i}RoIqBg} z@F5wu--kHJ4aKZPk9kY~%tn}?fC&_EhknW+DcvYI99bhV!Vgu+CQ_drLo$(i<<edx z5V(wgHH|qG21@^z5N-<2pi;MJ;BV8S_1EJ(bBIs*k~kfdn2+h8Cv0s)i&Nn~W|;l` z|IKNk+Q6g6UD8*?HN-T$3!nIsC*e#&wZ_T_L<sEC^EBy>6c_<}cA0&8jM+|S7{(#1 z&_GZhrl>L5>^pWp0GuSBG+&XrkPU`$GZ}=S86+N{U>83~E20h<paI%6Eie}K?mw9u zMEqV|u$5%T3U<H4-M4%r!3Q0u&xDt;!QZhi_(N7z&t(F5jN1+1t*m1wX}(1bAcJ%= zm3&-EP>@MDu-X9Hm}e}7WhPAM*zS|%F@gYY?lEpIl8HJ&K7-PL1pw&(ct@on_#tu_ zS_7}+lykx(-?|icwiCqld1~vjv^@R;012M6$z)D}W3bzw1<(Y5i>ah^Z&yjeDO6m9 z6#{4t2m2Zo1{&B_rTCX3UKT1Cdx;yXTXXWiZ$)MHvM^^t1e{PPl-QpHUR+0C4+pOg zW)&U=OSuUsDoddW5djpac<e*R?R~{KrKVT%!cvaPg^3?j3>c0su~1x__rB~xsNnP{ zIs6qjlxJ3Y(gO`$*(*0EW)ctiM0jIYY~J;jDvrhY*q7P6$o<UD6syd2K!iQ{+=4Dh zF9SEGvwmBEJj$V0Kw%o;#I|2x1c`N&<GH#(I6uU4c~D*|W9>NuKhXnK<;Fk-P%{Sn zZcgqmG_dOyc$Xx3hvc+F4;+onNQ*m+t3fy4tk~R^x<O0dZeKW&d|}@h1mIq1Mgdz% z;K(!7e<B(ON=3(C0=v1m4gga>E}2=Dl_of7uRw?<qlBlW@AEOLzf5=%#mC!lj28;L zBnjds0;b<{aZp;ZU)<kYt__2E04THuX2a)H1c$qYaMtiC_n)4exe%&+U8(mpHrhPV zfrjk)Pi6q*jzG6Q|5ZDYEPJ_8`5_tKvK%nTMaT0}0UDA_0$pM+ZY7-Ej5JhP<T_B% zfE5@etNfoXc!lC-KV9bolz;^IZlO2kCgD<Ky_0{L9W!R}L<!nBy>+GDRCpoNieOH= zsJs%KXMumjGd`$PNh84BC@S|!C=YA55PG6KGZo4#mp0Bsj<KI7)n7j?n=B$losCFZ z*bF;-4y<ibY;Qo@U;wi|RD!tZjK(&jz@*zsCE|)QbHRZ!{0s0ve3{X4Yq?oH5cv`8 zA~_8LVi*ngi+ipt7+VTn%6RAv9jn~l)u1{S`;;W{tqFuU*v~oayhUQ}t8F|O4AV^p ze}Am5p&oMSL+Ul2iKJ&bIwRzXgkzWBXUo7BKsr)G@<FWBYc565XXJ0!8fIL8G#BeI z6tB=E#Ci{mad}n0_vL0VRfs%x6LB#DEPc5r#mxQtLz_@N`Jd0BPWAYU^$8EjMd!qw zT!WzFU@=sHGBD#wYamyhvp<~(J;%YfzT7j?Q+{M+uVV*pSd^mpZ#O}D3;2rYPJBri z_;LO9aVZ1S%k`^8c^G-ujkr1w2`hbqGpQNiurmAzf&79zP97L1vA}SL#yLfYTt4A1 zADGmRxusYmJkyNeA!o{3e}Rj>HGq)!>gH~MA_)to-SG{5N^k68G&T#|@)&Te2M<=0 zhROr)^CXmH2@?@uU00{!B>K~A)$Mi3UwqVI>@nq{vLi2`C~8Av*r^2Y(o=po&Vn!| zv;(FkPU_r}2oCQO(%!xgc|>ol4DLc3yS+VKiEb-l{|b3=j&?tm;F~D*K#2ZC_v9S` zcPGWYqTje!)P8=WUD5;QFnvdwa8(usAYOK3M1oq;d&O36LZ~o9vS=^AvJyH2H{e58 zO$qT>pl>@Uw<ftu$%TG}@_~;p0BOaQxBIpqQG(k~pe|Nw)FX{~TRCOO8b|Ihd_tM9 zw;ca460GJPoIVK#Ot=#fe9?F_=&b12iNQ@GFsHy!VLhs-Y!d}>S@FR_9>~!HpGg3H zWq6gm>c7jjNv~Kvyo&($8Zxd*x2EG5q{Zg9&8JVG1sDwgx1q*O__#dO3VLMd25x5G zN!KjQ7(?L{XwutvrbcqB_#C9-u0p7l8iRWNxqyy~dn)Y08B47_NYgwVbCQQ@e+llM zkNcS@h56}2V!A(>PKg+EFBBcdm^R$Jtt{<Ay6qWF5P0E*(?NLy|E(i|Q|7_;BRFp> z@UwQA?wC_A-MNmDf0)pZHGa@{_&UY|wv_`nArE0|;82a*TiporYdrePG@MQxhlX7v z_ejoQ{tgi8mIIAk<*zh{qak=+J}9HohpJK2(FM)_bNGq{yy(R~y08Jx5WYyF3#26u zr=FvwUlq$&V-NoN#J<-{*e`!8!FW`r=7RK!P0ZFlm)LZvkztqzZjB^aPLX;?alMly z7(^YxLNGUk=_A_-A-{%C+w@{Q_SH8NI+JRSs=$AqyF?6rG_>_-Hg8CB=3p%^=`I;v ze>|=5(;>96<f2GuCvP?;TSHM@<3$K0>p1w`mROG{i37{gdIE9a9p05s2tfM&8&7+* z3$NmX$G{td-Y4=nS5Z{V6uL*5DV2IjK5)0R@f7HKmoUoBcugM(Ha~uh6g7baf(O7W z6Y2g1*k;*@9yvc4MC!xzxMG{rF2RHv!EKF>@s<Rxn7gfZ`LCY>Pumh;CZHo9C63b6 zQ}8~Q1hg_#f&myuW?VD?8H-M{S89+&QbGC;d$qu&MUZ|)Zi@eO^GX|$a5SFIxVi+| zMH4b@<NLy~Qyi(nBcPZI=u?*Z08F$A?Yn7s5eX-G11|y}AF6q{=`Vqy_)uvq&qYKl z8ZDV5x=4pcA1R<Wz>K}G@-eIZ!Nt;9--R|drLLBez+e~tFL?TlP(sK_#ui~M9NaDU z$l|n}mj`#Ltw{d11~Hb>2IIZj0^Iw+h*MS|?1W@DIqVe$A9fR6WdM#}$HwdJk@<`d zo_t9>g|YSG&eQR@#CLngXn*LQurGvOl(av$LfK8aCl*scvi}KY;dH?naff%7dp+rJ z0UsNw+lplFbcX}|bU7}?Q6@%O?OYG2aT6AN%EgDJ4(Sr3=l266K3HA1e=niI20OH$ zK_N#j16b<_u#16#uG~EmcSvsqTL$34tAwBz(s$;3p3I{Qc&MAAi6#y?q=Gk(qVBYJ zdWiNQS0MmL^9cz8HvWr39gmAz8N?TPT~gi6{YSXtHUDvw?LW=|7}X`sB-Z^5_z$O$ z(kk6|CpAB;Tmix>okl1JN{^m${u$Q!q(kZl*#@U!D{s)IO!#y_!}%HDHN5<cuyVcZ z2<R_G$fGBgF_2zv(t>-l#cih;7d(({sk^5LF8oS;>OsZe$M4(~rb5Br+<>KDAkhp{ zY6x2VBaAx3oR=q+S7Lw$!ey>-<&gr9A<@P7fN%S{`T2X2H(|ds%z*}bT=to0jDJj$ zDz08GYKyx02#oJY-TRv$Hw2Z~&l>NRuHZ@O!dKHoaT24dr_uMpt&S3_(^d9Y(b!i6 zT@2uxTwyu(z~rlZN`O-_>%*1Lp!1(^3N?4Uay*ri30?XGm-MxhHCT+7r({j&RP3FK z<HrvJ_>VheS{N@0#<-W9+XUl4bp7{ZZCIkoCu}I#8~Y7I{oLw{spX~SCKGH=f)7eY zw-d0}=s)Ar<-2+KA6$DCjd`T`xz5z#(FMd#eW%0`Y12fBlzZ!;W4K2#1gX}zmvp~T zbPMw<!FT%FSpQv&2Id#AqDy$i-6@}W2>+8SHOUwxQgP}5;`}qOZ22dtChc%G{GZb9 zLf$Kw$Nf$t#d(@-1p{-rbU;pk>%##ZqR)g}O4sBYaFBDmO!#*!op@pcZ}s4R0-O(H z@L3j95y7Mk`+yF1KI{sCks43USE+tnzV-&83jl!(z(9fp4IV_8P~k#`4IMs&7*XOx ziWMzh#F$azMvfglcC;7Lo;d*j2zt_34-)`-2rC(Eqj3&^Ibv!M8Ny;wpO_5utpuR& z<4~eSjUGjsROwQtO`R6>XV2t6k`}EgR3vW^(i#Jipqa@~;6PeqpPogVR_$80ZQY`^ zN0byx0QCyK^avJB8?ZgwIP%iRpxL*D4If6FSn*=U4i{NU8Ww;SM}5c?WYbvlX3m{G ze+I2-9{_Z60GL|kw5P#ix(w0+9b5Kn+O_{}Pu!~X3c_Tr2g)NT370&=w~Zf1o?JQ8 z+yLa*N}A*)orl1eU&o$Z`}T*dB&oF|?-+ow){ApTpI-fX#I*n@>SYRmB~bv#%;~db z;2bo3JbpiDmRSsnCz<ouLoh)F7bFT6gHkJqi~WWYj0-dr>V-iKH{`HGikdSB4K0YO z1da<mL@`AbS0rejSP1%Mlhjy2BMkt!@Q+0ucjU3hhwwT`Fdv5`vPd0G8E~LdSYfD- zH0H1oqBLw2gAVG5FfvOmw?s?~03NY~mQ7~yZJ{()lZYqkxMZ_UHx26pN&wI-NHT?l zJX6Rw_vEwBqfP|i$%D}7f)79y($D`-MHgk1qbDDQGSZ09ysS}6FU7Q=90w9KN&vP< zgN+d*8YELwPvsH|$Pf~gAVDRhNKaH}rL{--66(}WiU7o=R$qVJaGEm|I+LS8Dg`!K zWf63QpiMvO!-+(frM6n^prg;(kG7y<pk9uN$69g6y^WGj=_uACUEd?OU3WnXOU^bt z^{5m8jxnVZ;s|19lz0CH7%ei^q_ZPiD2eBnfEQ-?tY60a)JuY#{D=~T2ZAR<>l)^` z<Bmp|XCN}V5ChhMyzpq%f@sOdW0zm9=ot6jb7GJ+4Z;F|E((??%z~i65@w-?W{Amx zsBlCL07@-ri%00a=oop-CA$A=s{zpD-b)O!MdE?f@U%v#+mKbFO@sg-hI_AOTj-Vt zI`AN<E!wzkyFHe~y=)5d_htYnZb&dXx*(&}xedA%?zrz}yjnhB8%P@feo3YxzyVO2 zA>U}>2Y^}LZanmWO#%HPrXzX@V$oNxl^u2%Gn#eTm5t|-jnJL8x`DQty?0<w33($M zQ#&R@$N|6wnO=QozFLqo8>sX?y7+sdUY2h@`*zEw$Zzex=lG6^>Z==k^Qn#feDz_* zzMxJ3kY_Gr9Rfum<=4kQ)A$NfU7`#JyB9M60E+VE&wyIuL_r*}IEc`~65u*u1RDj3 zg7nH1(<tCVHdY^oK!^W<5(MFj*q{$s?1Os`IZygRxI!*9!XWYxO7sZg3Wl@>A!Yg? z3w5}o;0@$r?W2fm9ypDP2yll-+)hgpl8xh8WO<u-$ol{=EF@NOJ*JS{K=u}{jpU<D z4UvP|-V;MBmJvJI(1rk~(Xu82Ko_m)pGWACGXR7D4t6nP9*=X1f{^hb$wNx%?zoG} z>Cup~IRz}rR5}0@GA+C?;vps3n0q9I8Ce7XCIphhNp_M!SD9f#yvP(}n57i6&_^Ua zxk}Ic&nX-vqCsNGN?I<4ceTW2)i9Y$UN&Wyg;54VwDHSc7PBMniG}TY_?A`})0s_i zq+yb=w`W%KC|>_)hC%!|OKWy>JI*jjG+S3m*Ll-ps0hkIxFO4Ah%-|!GN;g1Qn_7_ zV<6n<#zEZqlx1S)90SqEI_$v+SootK@r2nS3epl40$>`+AfhT6g-&%C#3Tr97$FFv z#A>ah92k8W_8e3YR@8!w*<hrp!U0mYF-aT2q}4hM5|>Y~lw&YG2uwL@s(t*EAS<<L z!*H5Y05oH$$tp%r0k%(qWK*e6oy{<pRZ*zAD;EZ#M>W=2RjwB1bqASCSH*f5RJ3ud zXKl+pl8RQgvLz${SjQLJI@hQ8V<7dTYhImF6}|S=uYUz>U<Er^!WP!Bhed2+{~Ao+ zBtxQ#h3x-9nz0K2m`fi=jcjDI(F-VM*0bb6h%i1|*kMw0AnhD&YWs*;)e?4^n?T0f zve68uwwAEmEGht`YTLtR!?!)6DsLMmiFinEw>?_vFbV;HuL^fV75z?D-@;lSz38IO z9c-EY!HHL3w?i+&r^{rT3mU@J6P5I?V1o+)bPgmg=~a&~GV#&2<-)A+T@N(cOSFHg z<DmFe5IX8|8*u<wuU9Py5{Lm#0|Pb&HQ2{a8_d>RjK(0DAc$!vJl5K7Sg*mvur@X9 zVYD(B0Px5siD!4++N`7$)KEr;Ropn4+NM{;oN?&ho8la^)gE>o$XxK)W46K*9iSv~ zRcrrz5DO>S$xl9@IxfLUDBJY9xd2L)wY+66ciGEd26LFjJZ3VN+05xZ+?jF73%CMc ztxIb&bJctnXjDUX2v#6_=ggK&Nce8#pf70>^42{Q#TADV-8ck141$1z9OP(np_Rf9 zSMY(sq6L77+XfDWSlA!ekhD?8ag|_#;=kGh1th`&<WLjE8wg?a-B5y%U)bUo@Bly} zTAdV54`gdvz1udHQDB1bqaViZhlQoFYdxNW*c%ziSDVZ1g1jiwdR+2Q-rHkP^1~XS z)}e1QVP|SXWXN6J_KZ<6Z2<Iohu20*x=9?2fw1}-?$#kc>Ol%}N2I%hK8Qd8An*ST zpPC@(05>f&SCBUtLLvlL@jC1YfX?Bs8_%vt6&gMehfib-24VG+;k~+L!Xm62*#i>* z(QyE{Fd<<mNCyg10z|}_$mdu_)&_EwXf$sgOudN94G{<ctfA!!`S?JXK#&q_ITjYK zxbL3v45NUdAVhaLLW%%@9{`}{T>b|i4erUTJER8#*}Bo4T+V{TI(yVON+8Nk5J4cs z2P5D?L1fT^Py8d>8)iE=d65f#ME!eN00aOMzY(I}NbL*hx<dGxV@~^2eO!nGM~EH> zxeui766t^r-t1(tfA0&4_X7aH5QxQd<PVK_!$Q39b%n4a<mK*I>fb;JH+=u(^A554 zK&&v3DiGxFxUVIPkzd8$6U5;x|AKp$Z$=|HUm*~meh6;>fG@!O_XnAL_IEh<<!=M- zpTY63sxWkxf1e<4IR2PNo=4gb#18cz2qHf2_cANdUz-`Jg5U*VSflhi6&)}LLC6D+ zV?cr!18mr{S{MgyI6uv(2bFOb@@v37lOoU1hj*}+FmOMDm_0#Yxk3{#0Qf)7$fi(O z7%%vP6O^<R(+AvIjAZC1cM*ixvpz}NDQLjA#TW-T2myj1wh^0^5zMuPu!0{WvzDMB z0O&W(m<Lm!Bj`bh-)a;q&_IJwgEcS&8RW8x%coa6h?ZC<a_a^jQ;h$7;0AQ~Cm<;Z z+A^wau)#N(0)kjBg=jv6Fgo;lvV&s7h3JOxG7d~@ls|ZgD(FIjV7DAgK?Tu=`{I({ z<Gg`Lgv`@GL&&@`69&se58v7*H~Bi43xwZ;IflT$fq=P3^srmt5Ly5b06;<`DZYUq zzva?3HG40^V~<*Fltf5Hgiu1S0{}x%J`W=}EYzdw1At;wgJDF7FF*t_6hGSN1Z6Nl zAIU@Hb43IZryM+$FL(n)D8_3nBSu6=77~QUTL>4j#&tBHQ<O(f`T{SA$Azm$32H|G zaD(XEM?C@rX*`H>49FF#0!2)SJXpnpoJWVuqdkDgGSbJ19KZjHw8)Iq$c^O4j&z8} z^2i8^rIdP;FnEPz3`x(h4q$AP=)1j?jEy@~5sZY%nrtm9v&rQk1wOilaTtdVL55ur zAgb{Znp{3`xQ2x5kWPS&hw2fdTt1&n5&5Vbmdr`yn7p4nq&kpCt-Q+f`7f{hO7K|* zM%xFaG$XD=$ETAdHE_qVG#@uO$54wuJ(^3n^qoeig16+j=xfL_dxd^T2XtTsQpkmK zLk|Iptt4TSEa1z6sK!FmC^>Vx1YtA0WRG<~$pyJggXlvxxl1v79cU;$4uJs}aFfuK zG<6t_ewerfiH8%20s!cWJx~MjX_G|Af&~0aGMmf=iHHA9P^f|M9zKc3FZ)IfIRlu3 zkWz@fLBLJSL=LvAHU>e1L{Wo19E8)+5<@^4=>!d^^pTDe1ij2ULrA*h1kbl%gf=<O z^|YJdD~RJ%Px$nhJaE7Fw9nP4zv#P%`rJ>3A;^JvOtk}0j>N0k`Ama2(22~EUkDjL z+l(Zzm)%p#EU8PF9K_DJPyj%JEm=13yd}?Y12tF`8aRPIzyq$-g8*HTZ5YwmkjR2~ zgy?k96xkXW^^7{G1M%rlf>1~ziHaL#3_Z{T+!O;bpdupSLCmBFZHQ6Xc!M=qh1{4? z9nnuBJq+B8&fy#q?8`|Q)zQ!3(L1<<BOQoMkVF3#iN4L$(!~%TGgX5H>=9p}&NuCh z7R6KV%F;cx8g_6(KW!W^6;zmk#es83v|OP{V2AL_KA$260APh`sD~gdRG3i*2qXw{ z=(!zo)ODPMVNjxah}26Rnp2y?6>3oNdrea%npAbwSe4a|K?FCgM`$>>S*@B7MHM{I zRhMZ2Ca{5D6`El!2wx@EhH1JZIM!qx8a&7YXm!?U&7LTv)@yAwOU2fA=>x4?HbPhi z*6Gul!~{?rFyDzxm?Sg+sHuVo*XA*V-t<UvfTwN!mynRDSp$HvvsZC>9Z;GCaqQP| z*@p@o*n_RIJ4M)qW!Q#w*oTGKh?UrhrP%+9wb+Zr*o@WKjpf*m{W3flSC8$JkQLdI zWh*P_Mw7La78n7QU0DE-0hetQ9B2XnxJ6<;g>cme42y<NMV@xCfyg6>Pu<h6$_0+9 z2d_K@#H5xMsDke!+8bThf#3voP=_>tg|V{+SS6RJ_0x70hC$c|Gi;bu)zV35viXzQ zJ<)`E9hb*jTSc)|Vx5G0NCaOL*tp%2Qxh<*)mtO!hiLEz3bM+-Et1i|RRDm5yfxe+ z3D?e<vc~0-CVK{cuqQDnFUi%CwmmX_)!ZEcM1xb*&+QSrK!?#liE+Rqb0u9L$pmuf z2DNQn6$w;?VA|Ow60rpUYd}QY^^vf5t%hz8EkE*I7KsLOIE7>w2XT<G;$;zEblxFZ zFY1b36gdWrtKJ=19!!wX?Dbwfg5K{vl9|~?@dd|%Fj(_Vk<kE$emEiZg<k{u2V1?6 zFhJJ$Wsn5I-~Hv^{`KGg1>gV{-~lG!0yf|SM&JZi;03N0)ns7MaJkldVCASg5j?sH wUXD2UJtjbfe;`y0o{iXhNf5S;Dewd!`(P3Vjk#6f7WP*cPL33Imw*5OJ7<vdI{*Lx literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_pose_batchLQR01.gif b/images/demo_Riemannian_pose_batchLQR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..648735702436eede4552630dc1d5c390878764e4 GIT binary patch literal 160040 zcmV)nK%KuwNk%w1VSobG0rvnf0RI3A3J48S8x9Q*4-pd`EI=JMR~{T7AT>!KLTMpH zZz5&0B%@p<M|LMIJ0~uTCpIZ3aWW`HcPL4BC`x%KN_#7hH!M(rEo7rDds#0|S1_%7 zGg*K$c)T@$dpA=kH-X(aH?}!Tra581JEogHJSIMq%|DLuR$A~{S6N#<T3oWGUraV& zRe)k<Tw-T`WJ$SXSi5Aq#AMHqWgQ@8YcpnRuV`s#X(WMZY};v^bZMz&YnMxGCai6T zV{XiGZqTT3addEdt8s*cafR}7YwvQjgmZTBbGCMLc6WDs)OgOwc-7T<k)nHzEqs%A zeuMOWi^YJjq=L!tgtUf*y26HrhKwwCj9PV!a(9g@6pf6Hj~}FuB{q+P^N*D{kExE3 zk;#&b^^)q;lvWv(TuGHlv6ak%mX?^8r(c-1yqRRZnY5aj%*dOXoSdBWoSu!G*VmoS zq@PFfp>^@1v3{f~C8dRcrmLi;weqO1%Bh;1s+GX2udl3nvaaamu%kb)x$?8pu(Y+Z zwa}fmdCj>hNV!L<x!2dby2rci?!3=!ywk(IByqi>VZKFozFcm;!u7uB$HKO*#VsGj zWW2^#Gssp^%yDzfk&Mi~!p+s!&&>4C(96+`f6|c3($ad;>DbeG(9@Ti)4A2t)SA=n z?$p!P)YiDw-t5+}t=Zn(-00rj&+*;u@88;+-`vCB-sa%m)ZpLT;NRuo;NRfj=HTJr z;Njxo;pXAv<>Bk>;@`{S;NIfl-{Rrm;^N}s<Kp7u;^O7v<J#im;p5}t<KyGy<K*My z;^gGx;^gGy<mKb!>Fwp>;N{}u=HcMx;^F4w)#v8s=-}w-<LK$=<mu?`>FLkv>fY<_ z@9e*M?cLq)kJj)wSny|C@T~ChYIE`M@$!3g^2fXK?%(qt74x5%^T5mV)710S^7HKJ z^YiocTch;J%=M&^^{J!wd5`vhh4zb$_OY}0_xbw!`uzR;{Qdm>`~Cg=`u+U<{r&y^ z`1bz%{r>*`A^!_bMO0HmK~P09E-(WD0000X`2+=I0000i00000fCAP500{p8n>CRz z;X=U)6DTC4ppYTMg$^T1oH!Ao#fum-YTU@NqsNaRLy8<p(&7aTVgB*s_phbDmoQ_> zoJq5$&6_xL>fFh*r_Y~2g9;r=w5ZXeNRtL_`A=LJ0~aJDP@teeg$Wg?DyUFF;X<re zuP)?DfgnS!XcclT$+oTAw{YWbys9A4KYc4%GTqC!uiw9b0}CEZxUk{Fh!ZPb%($`R z$B-jSo*emwf(c;|=?T<is{$KMIArxqwL$|060|lr-CzO-2@NPzJw2PM)d{gL#?EbV zw^xL|byMICeE4tN#(Dczp8R<5-o}L!M?U>|@#@i`V}EWPVb(48?CJkgNx8iF^XSv7 zU(de1`}c%d^5ZZefslLu>ZP!npvsFV3cO&00vrf|fd&OmAcTM%6v#mWdPLEn4IEJL zf)E#6AcPRB;kMd`AciR7h$NP1;)y7xsN#w&vWQiH_S~b-Jv7#6<Bd4xsN;@2_UPk} zKn5w~kVF<~<dH}wspOJOHt8gjuho|bKT$wcK>}ek(U}l&ywF4xLr7pl8(&J%gb-@z z5k>-FD$oQXVZ2a<5FE()f@#IcrRSb}_9;?UFT|+NKKtZl=%I)vs_3GOHtOi3kVY!$ zq?A@_>7|%vs_CYjcIs)T9C-GEA`@)YKz}y47KIc-gqFYsTI&C?VXI*bAq1PDM$yC& z98_r)Xr{F&?6AZZYwWQq0xIZAN;T{3v(QE>?X=WZYwfi?MY-B*t5qQ8R0T%y0tQin zwx9<#c<`SG31FZ`gW_^9paK}2iQB!%=Bw|%{1$6kpfVDg&%gv1Z1BMdC#>+o3^(lX z!w^R-@x&BYZ1KeyXRPtY9Cw^?sH?#Sq5=u5MzU70X{EBtsU?tFRkpPjbH6m#Z1c@9 z2E5OcJooJL&p-z)^w2~XZM2XLW~lViOgHWH(@;k(_0&{XZS~byXRY<r6%0|2&Yy-Y z_Sj^XZT8t{r>*wdl4{_90|me>Hv)3UZFk*s!;L@zdprL?ciem5{deAX3yyc;cn=Qv z;e<1exZ;jCj`-t}M-DmUhEL8o=840d!q+vjE&AxBmu~v$sHeW^0Rgn``s=XAF8l1X z*KYgmxaY3>?!5QzJMJ3zV<>#Y7jOLW$S1G-@{mCgzyQz_Fo5*XS8sjw(o=u^_S|<r z{rB2?pS}0ikI#Mh-;-Z{`rC((zWVUTFF*VNe6A9W9_O$B{`~jv|Nj6Cpa2ILF$c76 z0Ix&f0T=kY20HM85VYO=CP+aF)~_D?D3o59$H5MI@Pi->p$MG^J-(Ungn`?e0T8f4 z7P@eSFnpm5V@Sgp+OUQ=yrB+r$ip4_u!RONKmq?)_q^v-@Q6q>VgOVSqm`(HAJ~eb z6sJhVDq8W1SR{%8pGU6_c(DT`_#zm+IGUB2@r-CpqZ(C4n>D)ejc|Np0t(PN>KPG< zc%0w`Y2-u^`tgr|45T0j2^bO%Kmi>%0SG{#$VD>JkryD@R3>>cN?Nj#n7pJWGg-+5 zc=D5=45cVXNy<{1a+H-c01;hBfcL4-m9ETV^#Y)Q@!UgoxXh(4cgf3M`qEHaJY)wR z>BwR(GLolECMuN)N|I5Cnb3@;G^sMj0309*0VqKbh&amz%JO<j{2V{<L&$QP^PK2R z=XspR#bFxrofr5dCpSsYlSy)(oFo|s^zi?JN!Ih9_ynjxGpPXrWHS*CxWN{-paCT& zGzHn*CIpg@f&pm21tl0j3T{Av1Kc15(kmhYM=H{ilJun3yWlu~$<mg(^rbM3>7jy& z$ali?o&)`-C+XwKfOgUVLhyhAe410D8kL??AsHPV5QH1tAPErIW)YhTfdja~4L49h z3Q|x4E2O{yB}jn=QUHN1Wb~WR6Da~eXAhaW^{sG?t6V)r!T=z$kv2W1JpGANzV`I5 zmNbAG)G*Y(8upW{+N)m|dsxN-wy}`?D^-LT02XYu4@qFb4OoXj7Z{KLUM;~`#mdnD zJhY-I2!cV;I!grB@*lUHt88aW+uHxSm8R|_<_Szd%y>%nvA}igB!_T=Dp9kq^3<oj z0NYIFIybm`mE>=wYe~gwrJ&Y4zyU~Wz_eDibr9Gr3)}$F5>U^w0|>8qTWiwxp46mi z73b0BOW*q1_rCbeuYR3W*P0fSxBneYQ3bjMTH+z8!0luL3=mzNcJinY2B=b9r$7o9 zQHib7Knc`Z;RLcarSfG~7DpVdeE5TaC{D48SIpvqo!BUbG(gHO<1*AxrDf7orU9D3 zx)MYI0XYt`kcaF^RVs0$X+<)UpBKIZZqL0?ey@}f$V5KcmZh=1vX-}Owk%t!yVGl> zn8!@!GMo9#XbwOU5J-S6;35CaXpXa-=S=51$N7#Q&hwK~P$PAolgoe(w5J{eQT9qX z%7{Mnd!L%xEu?_6iH@|QB~9r`D_PH&=3W4X@Q=0%T9^M|$1<it>QbBf)TmCis#neG zR=fJuu#UB?XHDx`+xphHhV?So@x)6F!k`iS9RksS2B^9q*vL+{vX?zO2%N$nG1{-R zgBI#rAR`#q&bGF<&FyY```h3Sx46em?sA*^+~`iXy4THaaU<gv;(#rZ{?P{&X!qXu z&bPkz&F_BSTLtwCf*Ty*?}8ir;0RB+!WYi)hC@IFoydnh{z0gHwD{rz40SP*!SRlJ z{No@GxyVOO@{*hU<S747xyo10@|L^&<uFHiG2)G}8QEhMr^va^ch2*k`~2rX-$W;b zo{Lj-0_aFjy3&`<^rk!g=}<>HEm)F|Pwx^x>;MKbw$Amgd;RNR54+gMPWG~!{p@H@ zyV}>z_O`qI?PmuDuf1HUi8D_dy!Nx+nPPFP^D@-HScc#SPx!(c{_u!Tyy6$n_{KZ_ z@sN+a<R?%0%3I#?a__aJZW$hXc>eRC554F|Px{h>z9ptlz3Nxb`qsPt^{|h<=Q%&^ z+5-*naL>K&chCFY`~LU9&wb{T<oDtmU(kTRyz-aN{N_9V`OuHP@-v?)+gtzo*w4Q9 zZ-o2cd;k0355NET$KQ5l41fFRPrv%tfBo*0|NZcfzx?N)_VXX<`1sF1ZIdtk{`>#` z02qJ*Sb5Z^e+GDf#g}}>uz(EMfDZV85Ey|HIDr&cffjgy7?^<?xPctlfgbpQ6}Suq zcq!~xf+l!^D7Yi;M}I8Xf-d-iz6T8PmLz*ugEn}B$HNj?H-J3YgFg6!Kqz_C*BB{S zghqIT*|&l)xP(mDgigqHGAM6IIE7SLh3cn-Pnd;TxP{?oe@23XU>JsCNEtd9ctLoE zXqbj-7=1&?7*_a(a2SV7f`wdIhjw^}Z0Ch?xQBe$hfhL>co>L+IEct#eshN;2$+b9 z*h>lsf{y?Ah>#eGk~oQ!Scx7eg1okfnz)H^g>_m-h@cpXcQ|~Q;)kYqihBr%qPU8z z$bx!EB%BzFvY0mfw}!TOi@2DJg*Sqmhl;-Vi${oi?KX_WSd7MajL4Xb%E)fW@QOn+ zi_jR2pHhpuSdG?rjRMGvl`@9h*p1#8AJmAA;y8}vNPwBx7}A)I>S!t9SdQ-aj_^o$ z+PIGNSdY`VgO-?&`nZq$*pL3$ftaXyl>&?eS&-}(YQfNo3b~N<7lp)Uj}RG=p2(0C zS&>~hcM+M98c8Yb7>^$Lk=8hm8#$6BIXpWEk|>#yxG0h(*^(OBkt!LJGMSB;=#n-$ zk}&@{lRCMR&c~9Gf^k3@ltMX_MCm^o7jsCNluEgjOxcu9`IJam4D4`X7h{lCd6n&# zbr!jmT*-URC?ww)mSXvhWyq6ed6v!BhGV&wY}uB4QI=>KmvR|-YN;4Ed6x#*i2t~k zeA$<N`Ii?MkeO1Hgjtw|d6<WJlu)^tjM<ou`IwOTax?c27=x9Td6`e*dG+vlH4<$& zqKaJ^nxZLoUl}BLd75z566CZOx5N~Ql9O{8o3iPXs9Bp@23!9y3k!90tI!hcpb7Ya zD6lD;#EF))X`9G7TljGeNq`4I5Cm>E3vR#;DKK$fHj$&5o!S|8q)398`JLb?BoqI4 z3OB$Hr(gwJ&<BHX1J~dJ^&o|PmUYaqo%Bhcr3oZ%nV<S;JorJL|8NRP&<QS(0#={_ zdw>^j8EVE*oD52wb(t998KDxYg7vTkH(*)+kOF8R3ng$0o%WepS)U>*n&vlyh?txx z+Dqf14T*qN|8NaDSd)h`oDEu|DtVkKnxk%IcdJmIuw{32H%_2AqD0Dy-Pwy1nxsnF zR@2Z4`w(rO38J4^q*Tg~4tb(Fnx(2kPC<$&*jc4uYNRu$rDQ5wp5`btYNKlEkvQ5Y zi20^)8mDsFKZ+Tdc6z6Hnx}fIa#Bf^bNZ)%8mNMrKXtmNhI*)ony5|Lr-T36sE+!m zkcu#cs;HD&sg`=F9ml8_Q>L8iQhEuPpc<;8I;xQ<n4Nm6TK1)3x~hbDq?Hn>uo|nf z8bFhZskVBnxaydbS(!@OtG@apL&~bc`h@rSBeQy}$eOGdQ>(e!tj_wZEvKm#gR0b; zOR74o*t&(TTCLprR%yDX;98Dt+O6dJcPBY`%)kucx~}gyuI2i!se>QlPz%S9t@f&g z+d3)xxv%`%L3yzc`cMzn5DmakuUyBj2s@4siWtAzunv0<grX1Qu?c!`4c5>L$Y8Md zy0I--tUdy-AWJq8s}KG_4Ny=7eV`4+;0woKunGIJy6CQo@~|}Ps}cXp4&u-ZV&DbY zzzoB{u|PY29$T|STeMg=3(`;zYN8F$Fbm6|u|XTP-#4^ITeS@fc)EZK><|cHa1GRu zkWw4A-bb}N60&AXHlc<K$IuJ1AP!u64ZY9{%wVwT3bS?_gfg2b%DT6F+qVZ(ZOD)e z$1n@)z_r?N3}BnF$Dj<#0IiPuxVS2<eml98Te%B!lr77);t&a48x2moxQz?BqC2{Z zx~rRdwy4`FUz)jvs|3Vw4ZffZEi1OP3wQY{DOQ`img#;i>kG3W4xAtaoUjhEFuS#T zylY3cI+D7~yD7D}b;pnkvycs(pah9f55Uk1EnByD+r0pox5EF~ui`ttIT(%{rwqSv z4b7kgZ{Q5pa0|x3z1};&Y<P~0L1Oruzxuns{M!@xFsXvqveU~BdY}Z6P!8E}3&pSu zflIm${J@RLs6)}b6nrV+*mco63*}I~Q4k61P!70|3&D`C>Po*RY<b{&D7w4C1_^lc zDR#$D4B4;_k)Q-&aKPno47gwnP>Z}iY>4n#Bo#cwxI3gRI}Et64%QF|M-T;hAPeQ7 z4bBk4iR;71d%Kas!dmQ$6BnXn*RsD*4CPP`k>CYN;01}G3uAl@xPS}AfNfSRwwV{D zL}Iyie8+*xtRTm@EsG1ZkPYR~3V{FxM-T>i&<QhK4%Yu*4Y@!IZ4AE)D0qx3cqF%V z9CvLE$haIwc#PZ0p{vOd9Ll;nl^8?Bru-<?whR;KZO5Ps(ohcK5DR(W1xHW>hMWkg zfDL234%(0n*<cOHPz<>+%*0&G#!Sq`a17S)%gA8N$zaT};K+{L#=ua`!0>?FMylE@ zf!5s3-u%tr9M0n0%?~J#GK!>IoX&h0Y8Knh*5J<Y{Lb=x4cc%Gq;?JE&=2eo3xV(k zP(a9DV90&I37oJAy|50t?8|_h(7s#_42=zdJPQQ93C)lV5WUa{4AEoU4;#%6<$$x| zzz*<y4J2LC)6fjn&<v!e(yB(%@7&HVUD7WN(=`7*)7B7cD6P^tebOmC4JG~4K>gG6 zJk;?V&)N{uNR6{fozzUd)K1;hQ0>&(Fx1QN!pfT?r<~P`@}iy4)n5J8U>(+AtqGk# z)}6o$ITr|eAO=bR1v!udC=dg3J=b$R0(3psaV^(55CbT%*LR)Qdi~adEd+Y72Y7%7 zZeZ4B-3h3G3XJX8un^g24GTFZ3pt0@IVaYdz1d-X3bJr?I)~YvVA-QB*^vzkop9Qz z{n(7%+KuhnoE_U;od}0r+qQk%xSiX&z1w)O2Z;dIv{1svaL!s?+|~CFnh*p@u-weu z+|K>n%KhBS9o<>*1X*AOS>OX%Fa$Qx-8TOqAl<zn-re07A|MxH-9wNB-n}5=Z39Bk z0xiG+@XY~QwN)wL0@0lWLXZL>5CS6L-wzPr0{#FFpaL480tjH>2;KrW@B$3p0x#g; zHvr)hPT>{)0uvtL4}Rbrj^GNO;0JC113uyd?%yW<-zaY4H!uXxDcvsa-1Z&gGCt!p zUgI_%<4@JxtMClhd<(=)De4^LsklMq!4D+s4>HmcM&1uh-VgfF<W3IdO)jzj;N(;; z<r3TE;-L@r&=39q7~@e7^$^lHOVE*U=9~}-dGH2#u;y+a2x1WDP!Q*GPUm7U=XFl! zc)sUi;O1=J=4}23{k-OpkmhH8=!gGK(DlF$j6UW{?bHMF<$A~Hl-^bkY23ywkd4x% z1IguFP9vW#BV8^YF)}drkPkFcD4~-<<3uB%Cvm3!d3dob66+7OF6l7Q693B-lCBr6 zE+2e!KTOeQME(!CPL(gw7s>7tN*)su`{d6a?N%<agffu!)kMSdmYBZnEoEgZ0qR1$ z>74HEtzL2F4(kM?nfb7p^|0=z{_e02@A4k+^A7Lr&hGAh@AlB{r_M0u{_p=Djd(op z1Yht5fA9#O@Cv{14Bzm5E94L#@e(hg++Oh(FOd_U@fyGJsMx<A|M4In@*+R-Bwz9- z&l4P<@+!abNa*k`|MD;&^D_TG^E6-cHh=RtpYuAu^E}V+7yt7>AB`+O^h96u*%$Ok zpY)2@^Gx6LPXF{3WAsu#^;AD!N`LiOZ+uX{^<3ZePoMQ*ANFED_GI6!UVrvzpY}1Y zDFajXZvXaX;~09e>*QPac7OMHzpqHL5C32byv7b(E_;GM_=I2hhJW~opZJO|d##RN zi~snLANi6$`IKMzpV#<CVkv~u5C2fT*E<W&@U-%K!ld7S!>#F}qoAd~`aF30)mJ1V zTMwzgzU%P0aeVv9dx-ZHthnF%+-aip#rNxwv_e1%+Mo-*kg>kM{M@Pg_Qm_m&-_=7 zBNbC|p*9QJ5D7w14@m#pvZDO`;Ln(nt73W_{^o!FNjd%#gQOZ43-w^g>rk*R%lh=c zd?|d7W?29F4}JHa7XWcj;6Q=}4GR3nu2`>ZoP=C!M#~wqWymaE#F$azMvfglegqj( z<VcbwO`b%VQYA)U?EW2u8B^xWfeC@F#F<m)PM$q|{>0hxB~6+9j2=arR4KoE32`}- z#!gR|db4^dJGM;gR<2#Wegzv=>{zm8&7MV@R_$80ZQXJex>W95x^<7*e4AJAUcP<( z{so*ju3frBW!m)Rt68gu#GEZV22}E7%9Sl&1}W6=X3jO)-NYPP^k~whOKR?%`tavr z$70os5@_A6W0C(&-^QI=cS_W%eIK;BTljF|#W(i;ojmw4T-PE+VHZmoGOfm~U&r1P zd2;2SvwsI4KIit-gy%N>T)S7VYeHHzOXdvOF=iA4-^ZU{|9<{o2b%{lKz{J*uRsG2 zL@>d${u8jlrJ52anA)V7MJlRh@dYyRHsnw|%^U>r!QeV1u|y7m5$B~4nNlvo+MH2l zv4?Q!g&EsS#4$(G$m3465p@JI$lFjHsz=`lR3@3%Vq2$|+JuBMN}ZVD(MZm0Vn#|W zx8#XRm$+LI!eB09PMbi&5GNKc*JSgf4_AZ}J<!^uvrdnQya&z|39QW*XBcZHqKOnF zv`|A2U5o!gJwYT8QAZzzG}5jVT{J*GkLjhtC=$6Q8DFrHG*nSX<%`lvE&YsCRaa$I zFH-~L4$JwDNlcsPu367UJ9mxJ%Ob7x@v|&>C6-QKx$`GkWtU~PS%30LsF-Aud9j#S zsBw=OXN);!T5rDvH(YVYCAVC2&qX&~b=PILU3cGwH{N85amiVG@5MJ?Wuuk1Uw{7v zIADPXCb(aE|H(&Re8c?FqGN2SCyYGS`K7vIFE;VbQw5Y0V~@Ag*umuN2`(6ujWOmH z=b}i{7?WRyIcAw>rnzRDZ^k)iop<KBXP<utI%uKC6v`f8RU_Fupn(BqXs4fsI%=t> zrn>)XWQtA>&PE}_w3lXVXhoZ+G^DOov(FCo)s5}ix~uvuwkQ`|q`l@EYpBHq7h~RD zhHt*n20U<AU4k<o!w*M1am5Yi*IV^wiC7PDYVn2If-lEBbImvBJY0I8T|9KrM<<<e zh0N7zT3n7PryOQx(Ik;hXpv@}b*wpt7HK=@y?5V#7x?qihbMmV#;5JG7h8p>suyZg z2R?e~r>DMM;fu!}`{Tn^Cdp))UT2m(qA21BD4;mvh#a8MV-sk~xyBc1p|8Gv`|tnv z`s@)`_+DsFFGc`O_NiF3rxnZSMKDlii~u&!fe(aW1SL2@3Rcj97sOx&HMl_zcF_NW zALQV?*zv6XmC%IG;ui!_#<XMH!W!9lgA%+Dh*;!88|=77G+Ge}F&se&V(7#=wBd`@ znGA$SL}C(^xI`v4@rWWM;R%<;un1v9E6P~LYr+r+TwU;IwU)<&3)ailh~ScgO2 z(2Ca8=N7jp#xb&yjdhfR6M0BqBCN3vUjXAqU<9O3@H9pMZOvh2I#ZggC^$wol0RxA zq+Hsjl^69wDoWr)IkGVfUDT#Nhr~rLq)`rWZ~}dOXofhXk&CR9&5^H!<yIgW$)l7J zBgq4lpoSGlUg}1Sw3Lf27YPh)yx|Sgh+l^OsF7UQLKfLzM=QiogfOIH9n$~kWJP+p z&6E5RR^6EsnP{acP8DNY%j9M{EmNhV(WGIs>V+&K#s_w=;wtDgV=iXF3~}7z4M*TZ zDpc7?br#f3U&`8^Qq`4X7{eK}5XYIcVHL>yEtVI>C|YI-%)2bKZ#Fu{EY^{SFlZwc z(ZJ$a4mpcqh+`Q4<bx}&X$$(;$6^`9siZbq7b!05f4c*hGMq6C8MVS1%A_Cul)6-= z=5K@v>uFS*_0wcP&leS%ia4NBn|RGa87}>&9-0w8ZgmfONo{Ic)mkv&N!1@(^JrI+ z6bo@|Q5(+iq)l_WSH3P|ryRvgeQGlcYj7e85Ru5V+%i~aM5l+SR3-l{Y@-#6_SLfe z`D-L6`N^x92~BE3MrAKM+D2xUmRQn?Gn~<kRJf-ZPWq!->LXZ8H8vH~)WbExSDU_B zgtWiSk7*wSPBYT#PeKTkW5{Mu<_Z#_?d;5Qj`7gCl0t0C<jFDgY1_x9vKOmsE;rc; zUEp|UBYld>raJX0e1_M(-Fz;24TBep)Pfxn(?%?w^b_sQg1bk^?Mz$w-Y<?<z65zE znT(MsaZH6B6m2hoC7hY~9(X2BnJz>F!7~5OXEObbMm<*1Lp@kC8?>1)#tcl8{UvUD z-+GZRuHletECe!Z#c_^x48<1rSacZfg*6yM4P8>JTLkM~f0h5ij@uT251Gt{E^;xZ zvo2%DSH`lp^w;BmblJ;a26LGIF`&45Wf;bIjS?bZ4f$jRxNinrT*N$QI@j6GV@`-K zTGNauaN-)Z*sp#Zwq0?s;-6uN1UAYsjl9*=E56;zY-dYZy|T)p7KQXpwTYHYZ>7_H z>GY=;M7TTGxiCh_lZedQk=%)cqzXxKtV!a{I0=L)s19aAW|3Y!G;g_>=@T>7k&Qq= zK?!ewg%F()$}zn+7)*n9w51JgT2$NG*T#0XwY}|Z=k3|k2Dh|X@})h|`7U!NGcd%` zCubP;8v31%E8#qEQpvg0_cltG2Q=n<i<!(q+@d(Bv5fy|6x`qkM|i>&zHo*kd>O6d z#6O{sh*;FI8Pi~8!!^Efj(6PS3a9KeYBO?@m%QQE5QjFjk@A(RoaI7Pxi-pC$8z+e zbv19D&2heSo%cNFKj-<)Z60%&v)t$|M>;c7YVUi8d30a?@#(}xNlZaB3Z!twGir3? zEO*`Oo!hdH5!YpCAq?uE%f~*{o)3Mj;|(_8Ln}@(_fxE5?slhp-u1qBzW3elc%M5g zq>+k59H9t8$O9^5K_S5Fz43mBeB>oRdA{3S7In9ZFKST>X>{K6(%^+GcoF*11HSRA z=)@pYzxqKWg7vF+y%(ZjY%j>r_Ow^R?RBsF+8h6y_e!9B6vQxz*B77lu2(%Ro*}KU zi+$|u*uphVfd+&bPwL^KI)k%{p&NhQ``;&6^PT^XKDZzSR>+4NGy(l<RR3`MAXz6g z@B%9YAqh#ae-QGYfBg5~{{H_z{tLkS<G=p%zxzYL0n|VHvw|d00S;(^7BGMZxPdHq z0tCdr1;oG&<iHN}KnxT>4O~F|!@w*Uf+VoO6!d{CSV12Mf*W{&8wi3F&;S+CfE18` z34DMZ+(8i#fd}xx2WWvI&_DuAf*VkQ6i`AXOhP7H!X=ad3BZ8~kboA5LKUdOD6~Qe zP=O2J!Ys@}Eabuq*upOS!ZMVAC2YbJSi}D|e8N+h2IhMz=L?;GNCYdef>Urm7rQ=j zd6Cs(j8@PV4?_m<GsHuLmxH0hv0H^35QjlXfqz&9JRAhHd%u0~2X?R>YOot?um-!a zn{@!ib*P3=tcGeJMNmY=RV2k#WW`f#MN%ZiPozaqti?}6Cfm^lP6z}sK%XtrglL$# znp+2Uum)|ghL1ZrT3iQlU<Yv!hjp+yoogL-kOpd)hE+%eO<;sb2m@n!12M=w8A>1Y zIRY;b12OOdbPNPz(t|e$gjSHpd6Y+Os0LbeMU+#yx{0}K=*POzEosC#+vx|}v7MQd zMuIfRg=B|<)I^0$NQNXOf857@v`GJC)CQFM7V*QLn9v7)NCG$b2cs#kaN>wFgP16Y zg!myuS#wE^Sh39@nNzrdd{~7b@P~gGgqma#gGh*4z=d0gwqJm@Hv)z?`h{P3Ba<;o zrcuf_TFPL!1*VM3sg%m51cszcN~|PGrZJgZ=!Iu!oo3)gFMxs~$h~ijomHp>G|GmX zgUh&-OHFE>x10sGqy=q^9Zh(HZ|uw5BcB{FJo7mpFL;AIc*j8CgvI0pYN&>2sD@`) zxn?}bxP%60$Og>xg-yBzTu4f$EJ~<^%FVllS`f`!_=R35%~_zFUNFsD=mltihSaQu zU(h_Hgoa*FO4cmR)~wCjM9Tl9EQZr0&f;9ki-^gh5RpE>LrqW-rI;kHxQJ!A1<w)( zT394{)6Pf{uEO|-S-62@=z|;hhfcslJb2Eeh|W=Qm|~!XSm*^|B&A{Cgh<GPH#i@| zTc0S%J#h5T{{%-d;7=vsPh%^e@;RULF{b-e%t(lY_m~D}u!d(82f3W1Xvl`937};7 zg<7D6&YYWKcm`rf23lAkZV3imFovq4x9(KWFe5WGs0xwnH!n*!u{b2v$|Z@&lI`@- zM`60AqqC-f#1goHeQ<+Q*atLdzkRdO^(2*BG6r1;N;$HInS;h;u!d%EPzN<8zXa1S zb;md8(k^X<Y48PPm<Io7ghsfWqdBq$+CZ5%!UbKBGF+gATnM1N@(7fnv>%-mQWH`z ziwQ!7i3HOK^kN6~GAC|%$w#$_<lGD|>jd)rvYspmM8%PjOBve81!%a^x17sStxLMh zOhOb*T{uc$h$EEQFG!`ZUr~+m69=Fomp<_YTj4P0;W|Y0)n6qSjug9@OoEXtofrE) zuMjNeJ4$1)2xb_D(27=QP0>#J7FKe!kAj~109G9<h7?&uA4Aq~sg|OehF*XSwCdJ% zJw#y@yJwk0(izvTQ`e+Y*M6xoc1<gH9Uiz+x3WNnV#tO2ni$ynQ$R&n194Hp&^LxH zvxJ4%Raw|`8`S?NeORz~kr@+$=vanfh}e&PBtflMJF8JsgHn)1*+U7^iuG5sn2=ex zhCaInU}!VZO4*xbi-|pzlf~JdEfAfJ6HQIj>FR|BLlX#tRav7oj;bZ0P1>jJh@~YX z;>sD6Ner@Vj8$@(s^QwM_1dom+pr~?3bU|6RT{BH+q6~NwPo9&xf-%9+e{UfkkE?O z&>}9nC#aRMV~N`fn_ImF+>YSe-)Pygpe<jRhUZ8VrSsXw%~`@>+PdIb$E94r0NU{b zAPYLt^=J=2D~3K|ASV*t(Iwr|HQm#NAQ9TbaNVC2LfzMe-Po1g*<B*lb-u!N*{ZV; zc36*!s<i*g1zuT#+{m4a$qnA)bqk<nn7<8)$QY`kIx1ZWT;@6!;>|VYo!;yXEvW@2 zVG;?HjF><eqL$R&bmCr)^4{_d-199A;wp(gnFe>Wg<yzQ^)+9(?OOy}HTzv({LSBg zsG|2BCvn&mZD`a8<KK&s)B|(c1b#_8QI3(-H{)ff1!E6~m>hI<Gvqzqm6hNRzEKVq z;ZhOV50>B%Rtv14E0x3*39;D`zF7}8VV0#}7`9=skm06_mHj1&+W3WPP~2GPSO*TI z1(vS{CgNB#VuNVe6LsPzMwydYFo+TYKf48AP#`GQ;w|RlF81Ot2IDXm<1r@VGB)Eg zMq~d!RbD;8i!^rQH-_Ulmg705<2puTzZzZ;*<q6$iH5=ujm_X+OX6Z#V(3ERL6)#W zCJ5Y>EsB7cExHD1NRk_F+%;xoO2%ZexLmQD*K;AcUx;5J5I9{ZM13{oEaO+!eY!q8 z<yLlOa7ks-SzbQwVciV_$*G0BMPy=OUs_7vT~=ChvtISQ*t7V<#pttWkcPa<WRSIF zh5FZKmS!Bz<6&lsLk5Z3(A6|ihWZ6&JL%;}`sHt)uy7u(-vHodQ;C<YD?MNb${}BJ z<`P9d8f=#5f`VYeh334VmNRRHYXF<*-QZ~k)MpNn8Ybuw-ehrQWq3&vTG-}XsEGgW zdF6_}A4OE<7VBh-=4fAy<<Yt1wKyaS+1*}HrWa0V(lTg9Ddv>MWT4$+ozM_8BiJT+ z)q9o_dIlDI#%b~L-}wSzgeHqhx`r@FgzIE4mu}G#p5c*2VWpPl9LBd08E2HJTVVL- zfSZMz?r9(~=P|14t~RKzJ{2+XiEinIVkqiFU<VqBXR$63vfh}mhHLXpkyO)Ts+Ah1 zk)MA)wrsElKtqPM-I>8&ns7tx#Ev$?X6&DNTUpItxxI<TrtHeL?8^q4#|9Is2H>ew z?9UE2Jl!>Mc!Mgwrp^TI)K=`?+`QKm&2YPg&|-#Y&=zK}hWeoGiIB9}-Xs5H6r$b+ z?%x(}-zM(hzN^`y?cL68+eYr%mbB%5?%JM+iRdHMw(jc&ZSaazVYcR`<>9(!F1fCh zf2aqFH1CScNc2AM^k#306vd3phJN4#CD4Obu!nW{=k$K>_EzuyK1P59$d+qHcBlse zXNLnvaF#poW6XtENQGE%a0q|!2%qo?cko2O@C?`R4d?I<*Ki7t@DP9S3YTyZFL4qF z@euEC{$}y@cJUQ|@fKIP{l0DAT4@InYN)PUpfzEV(S#fLz#td$4rD+eOaT|LKqDkU z1<b%E$G`@B0u{`HBZR>ls6iTh!X@0m{1bu}2!SsL^Dq~4G3UWDH}n59M{_hE^EGGl zHh1$c7Xcd}!6B#fI=6EWw1QN4hN_b4rY^Oo*728S>Oo}~ZRmu#JM=_91x07{MR)W@ zhjd0Cy|>E&qdtYv6TMZC1x?p<SrEO^;{{mYg-#&#J}~t#7{?f}fgH#I6kzr8Q6DiF z1UxYHJ{W{YUvyGG^vm;fUib7<==EU#^-~~*Q;@r3H}+&l_GMT0W|uo(2X<kX_Gzc~ zX<r3cI0abHbzFyZZuj<X2lsFP_Cu$s?dG@cMv5E{^h&Pg2Ep8Es0L+}_k+_4cCZ!v z^dT`Yrr6m=437jp2*+^Dz4S33vxLVyh=j!ys23{61Gl+mOgaB?xCVGXxMUQ$V-UGq zD7cZ^_>!v)jKkK3I%ASk(}JspV~F>XqlQl6_>l{Fl6!fV7rALjhIpU%o5%ThKhaxo ziHz3hcc$H-7y6+m`q{k&a1}ePv4?tK`lfgKr-%Bem-?tD@P6orgxDebOvkNHM}!ZA zgkOw$$cKK|H+``BvoG+pNALqzd#ESyw1@ktm;1S=`>B8Xw|9EHuY0<``@Q%3zu$Yk zZ+enJclBI)z(@SVSNz3i{Kj|u$A|pLhkU|c5jxCCKX>YTfEIoDhs&?Cx8i)xHynE~ zoPC(!FZ28`Tb9$mv((4@*T;O<&q>+ud@!4R)pz~cr~Uukw|(1RJD=a5+=u<)C;s9$ z{^Ljf<hL_R?6Jr`u(cz7dszDEuLtSR2hu;Bd)No(=l<^Z{_h9>@E8B_C;##{|MN%x z^jH7&XaDwh|M!Rg_$P|Or~mr5|NF=P{MY~e=l}i(2z~+w5-e!&Ai{(S7cy+9@E*j7 z5+_ouXz?P(j2bs`?C9|$$dDpOk}PTRB+8U3SF&vB@+Hie81vDrY4aw|oH}>%?CJ9- z(4azx5-n=<DAJ@#mojbY^eNP+Qm0a_%JU!AtXj8n?dtU_*sx;9k}YfYEZVec*RpNv z_AT7Fa_7>mYxgeRyn6TY?d$h1;J|_h6E1A{FyjBM4i__S?D#R{$dV^hu59@-=FFNm zbMEZ<Gw9Hm6O%4&`ZVg)s#mja?N&7G*s^ESu5J4^?%cX}^KLBjH}K%XhZ8Su{5bOD z%9k^5?)*9Q=+dWCuWtQ%NUPenbMNl`JNWS8$CEE_UVQKL>esVx@BTgf`0^WKuW$c8 z{`~s)^Y8EfKY#%WI3R%qX5<=z2`acCgAF?PAYtc8I3a}<T6iIb8EUv;Rr7iHA&4Q0 zI3kH9hGrm&DXO?4i!D|MA&fD~I3tZU+9+6M_n5dNkGbi%TR!##nNN>J8VTBux9NBz zlTFUWPm;FjgVmJ(<g<^HS!ziZl#{t-Pd)!(ia92kWtw>=nrW)JCYx=#`6irk$~h;U zb-rm&VfsvYN*IAe(u_a-uwy5og&KM&qKPWHsGNAV<qxEhN;)Z}{^awIIJXqDDW{!! z`YEWPiaIK(rJ8yws;R2FDyyx!`s%5-h+}1?wc2`XrCRCvPcwPEA;u9=1hS4axEKQr zFvcir46MyM`z*B4N;@sJqRL7uuD7zq&p+${vkbW5iaRd3<(hjgy6LLBF1ziz`!2lk z$~!N;>>9()KimptsXz5(Q_ecpM506(saP{hGRGi;OuY>|{4m53OFS{f=>mhVzJPJ- zZN(jX{4vNOi%jpu`4YyhIJD$)%P;@ytP_Y5r(_z8F$yEY3^OC^yfe=|`@Bra8UMBM zw?7+wG}1{^9CTm;nd~hy#~kC!EbO$R#IUn0W3$p-d;PW1Os^%`J>3GcFxqLWy*Arz zyZtuYamzh7-F4f2H{N;cy*J$@M>$*B-lBa>F1=*aOc;99Gm9_E*vvQNkxM=~<&|50 zIop1dO_JG|d;U4-p^HBH-hL<7`NH5TQ%p10^tsL~Qj<PA?X}x}JKCm?l<lpTic?H7 z!3#e;@x>c|Jo3pazdZBJJO4cN(Mvx)_0>0D48HmBzCHJnUdj&e!xIh-G_EVoxYRgX zzdrlzyZ=7?@ykzqF|%sl{iOd%bsPTt{rmqv00St%>0!@O<k=tbz~zi$P(vGG$OG&W zrVM2au!0u6AO<m5z@(53b-4Q=2tz1B%W2LwfjisUqy~&%xGoXmsD(3XHo_Uwu!glO zA!JH|sbJW!hd%rv?sRt?53X$(#<+&-vbHrKGO>wHd>b%krNgnA4Qy7tA{KupHXK#a zT!ia|Gt9R*Uo7!vIm;p%)2PO9Z80r66x<WzD91U*O^C)JqT0YU3}CeGf$Qjn4CyGy zLEg@eAn_8%)~LuuGE!YZ!%Y{%g)?w1?2F|~-0!q@j7c`Klb+PsBO~)h6cVzOrtG01 ziG#<r>5-4u@In}_VU7P=JnodXyk+U|g`8F5vX{Q}Tq=jd%M=z)8uida6gWXFUDWcI z&U_{^g4q#77VVSPyrvaHX`4u*tCG2xg*XPL2XRbe7QxsgGg61mb+Xf4+I-9?p()RK z>P?!#87AAL7K~mXQ4BE?2Qz#DjAqiapmMb5M)dc)3^KH#4t;0<H+VqsK~HM4Fy_F# zu!?~Fq8P`3C`dypQvcP@N=Tt*J5#FCk-d{P+*}vV2q%kdXai<m=!7-ak&RsBqGp`@ z=^0llR7JMbH=Ki`L6fS~v?262_>7xO4;P3dK!Fdb_}4m^kqcZHi-$}7DhQjJ5&cng zq-H%US|5r%laBuffzgxN1PM2ba%h7Sz*52+5)lim9<CT%<*Ks46+FSFwXlXA;95B- znU@Z=v5t*bQDwu}b}cNX-^_+iBk=|=96<?Q&_g6pkqyk2qa4?m2I086Rb}yzl4g7? zY(o~=#V8bb)w(TibF16k^0rmUkZ4;e+N@yE>=?K>#=pcd3{C_>3{W^i5eW7MJ#^v} zv%qR;Wyw>nZc16mQdV!nE8g+$_P6#!%C;sO+x4;+Ty4~tdgE1D$LZo0#u)87%F&Ei zL?RHsIs$-;5QQ+jArP84#b^Om+Gb2+yTwqJI@>EUP9}p{<UQ43frc@*=ujM91uKZ< zDb|=^>K6aNxCM$+tl|~3xWz2yYAs@X-+$5d8mVYSAezfr00%2^f#}3cX>1K=FasAU zu7#0ZtmGv#xyep`GL&0fi(4SM%DAxdiB(KWwGCq$qx~|N!z|`8lex@h26H+W7R7&* z1f>#wGka$Xn}5_p8{*K0o$-9<Jo9<ae%3Rf`5b6G6IvVBFtp3q(T{TU15C|mMSp(< zg-OFQ5Tr=OF|@G`cC15Cgg$hkL(S)P5c<xf4)mT+9q3d4xzD98bgNq}>QEoL)`m8; zIC7n9cJR8><=`|seywUv<5?NYQr0hg(Tr6@qS?-VHngKH?P*iH+RpyPF@m8CIX5J| ziG=?%xE=f6zu>78H%J1y)2;4xv%B5ye)qeBfbJ|jf!<bl!3$atf(IDj0W1hYzFWWn z7X-oH^v(jj6Rz-uGrZweNW#IbV1;^9JPSU!!3}&6gcJz81s(Ue$K}m#6?{Mi8eqZ6 zHJ}0nJfP(+e>u!!F7uhwyyh;~L^F<|3|wq@E%6L7(49GAnEc}!oj5wuldkloGrj3f zfBMojQQf1%;uNw#dL;7Tg&gD{23!|H82F$ERA>SgRlj=GkA8}yOP%dde>>Dkq4v4M z0?4P}g)B~Cc3yO15@a8Q9s(bRCV*WCT<3ZWP>^`9A3g_Ocmw1ij|fh*9qF4```rKM zPWDb{V)LDs`sX?C`O$-(^rA04>Q8_A&UYdiXB@gkyj{(3(_W?H_RGemA<NxcgZIAg zJ@9`o{NM*)_r~A-@pa$(Y3Lq_%D+Z3s?mHJZ`u`{-~{BI3*brnnDWh#hBN>cY(@9l zW#&J>HmY%r^RwS&;^=ih%+Kg@WCQ%yI7K8l5eYqrT@PWH^mFkTr9puh_)39Y-}SZ5 zt<^(*&0lFfpfyCGEGZxJomTQ$12t5G^hqD{ao{v~AP6$w2Z~?_b|49!pb47bX-VHl z;mqxoMLZFg49*}8)}RgEAP(lB4(=ci_Mi{`AP@$j5Dp;`79kHtlP;YO#~A-16B^-G z9fL05LNP=G^_7DwKpOV_7Zemh4k!Ut;T0dKf!JAEB#=TRAVL|I;U)~jDkMU)nPD2D zAt~@*7>eByc)_G~RuLRQ4osR75Mbo_i5a%SHMBxAh(iM=VmWX_HaJ5x6ay{%!Y|N5 zEhLLC)WR_6f+lKWS2dw0HX#zS8A;$z{<zg)ogylxqV#MKDYl}md=LMq;_wib@E8Lp z+QKs=n1YpqI6PW2q+xUY${RcvF>W7K@gY?eqcR?W7-S#hy<sG5LMvQhGibvDDp-D5 z!)RFpGdROC+(IryAuc2XHT+hmEDyLGgE7dW^RS{T`h)D%o;;@13-bR3(X<oJR92cv zjk0Xw%HWJMWP>$4V16~=HD04O5TZC7Btzy`u+iT(a$`3#!z9vzM{S}yD$6mrmO63L zJhD;GsYMKaB1x8{NuDH1rld*^VJIp`=d2`55+Q5h!Y0-vC(;5=;-oFy!Y~X2k|h~e z;UrCJVldDoS0RhB7z1&!R!lafQ{G@p4w2wIB~@0XRbC}l=3rFr(o|-pR|X+dex+EB zC2?(~NVwTYrlluwTWG|WT1MD1s1sbOCC{+sLUh=N1)W~n670FeQ|%>SKGB+S<(37e zVIEWx66RqpCSr=>NFdTJEW@!)CS_KpWnLy`W~OFtCTDi0XMX=CXojX}jwWe><~L#t zB(XzemL_Yqrfa??Y{sT+&L(M|X1+*<P8g6+U`i~qqi_BuDgqZ%Sc*LeNlh4#ZrX$? z0w;4er&*O$Qd9(#U`5$DCPn-uV`ira^<_rzgQHL<c(NIkOayjnr+F4qVxHwe(Ah1p z=WQB<ThgU`f{k4+M%jo%B51-Y{6onALp{7FLB!{L4rtQUXF}-2KTLxQ<O43aKyoT) zSvjYKPH00VR#SA#!=-?O-ase(!wsAQTR~`VQYeX*C`qxygAxToB&dVd!VT=hihdh` z&gj<|C_|LZDck@*<fw;s=nbrbKm5%-(kPL3jg2})*-ZaK3Si0&<jdcj(0N8F4dKva z;0ceeLX)}xkp8GY*h4`;sg#CkSm_dO<^-Kd+{T5dh?*#ywrTuWC{z4{HYC9oU|c@9 z0iBjWET}0>ET^0PDWF1+a2ADh;>k3)ffb~{J=jA<l&6?J>g90fMR?~w%mNw&!3}h2 zAGm=A5CcEx!*wDRq>ifSNa{vlN*gADbxMSzlB%ob(yF$ZqpX61)`Qgr!7Tg(qmrkn zzN)WMj;Th3SKz3;S%b+ahJY5SvVu%Kss*0Z0v=%K4QPURA}c!>!?I?p&orx8V1!m& zM63R)xXMki9*C}H47m2{xUMVSl<Ph8L_PEbZwCJ=z1HjU460KYCzxDCgxagW{ws8z z)MCk~wiYb2q9$knXh9^a!8UBY9BF1Stiw($yg)2uC~SZdEX8i@!y>Fpu|qB7BrPBd zFa!g~o~%20Y;8y^%C_vdSgd7W$wLw(sb#}400T~zEJrfTGI*rR8Z69?hQ|IZ(V9!p z3WP}P!#?x_KSV+l;GuH`ULtJ5D$tlVSc5Te6+yA9xVq~}ge%vEt(v80NT`KCOvyFm znA(bg_VFQJCBi8<16^4IF62T`6)n()WYe%L-kvPChJ|Eci8#>M13u)VX%=UB*3=H< zHE0Ug^sTZUt!3~n<Wj8UBGQAcP}brCE!h7;G7RLeSp#!D7hZJ&z+{8U_-y6Q=jBoc z<*shSO0Mjw?$$_6eIXYwW&`#Cm{pZl6t3f3!md32EnW<%@b)e7eg!oJZ$1u=k>PG# zy+N?#fiwh+v7poO&SUGMW%d&7_QKN+-HkEO!gXmwHbjCKD1jJs0wUhRaf$7DQYqko zE&Q_UU~bdUrb|o(133OmE9Ai+Cc-qVgEP=l@OE!(eQ#vEE&>;+0y_o+tB<keLiqjS zbLl}V(4Q{kf<B51?Kbc_J@8{NFbL16<i4Y&_^I^7)n(Z#u!I38{EKn<RGR&(4PQ`V zp|B38aKGNL54Wj1x*}PPX!H=)7ft^IJNQB#OfNT>mM<8~1kvITPci(!sd%U`6=yMX z;_FawFTLPQOc_Hh6hmpDuljZZsX0U49&ia;lL$j_{<d-Ksw@OkQ5?rh^GXfp{!1$4 zK@mW~Af$p$9Rn>W3mD(695Yh#+J*5ZvgPV6TGW>R^sF)1LilL|`W8VLM8YLA!=^}0 z@TiX#k23Rcv3FoGDW~!&2JBIIF~xY(btzXMK!M`2!h+F4-F}!OtI-=b1_|$STK2L- z{Bk$(EVzU*E&a>r2Fs6;);0W<A)k?48nd?g><3#>^NLF-<_0kX^YGHKFH_MAWm%M! zvx{++G|*Hm1cDdr;RAI7G?f3=kmUj`xUV_iGd}0DKJRmi;j%w-E<pdYKnFBI541rS zG(sQrLDvHIE^=KovNsp3Lvux&)dR1+A4ao7MsKu6cQi+Tv`2^ZMr(tjHCi+H*QC8c z9!O(p*~6w?v_{)muF15n)wHgOG)~*JPVe-c&9qPV^iT6NN%I;}7d1>9HBu8bNH2A; zE!zAo8dU$<Q_o*hPjyvCHC9{oR4>|9Q}tBOUp6okGTZ{$76<*-@3^|FWLPO0xPe>0 zHC)HFT+cOK*EL=50UqE%AD}@D#6Sq_TMh^TAHV?`z=0dUL0%`eUgtGlH#Q#NwOzmU zV^20-Q#NBywqj?tW^eztX72$Ud^Tu@HfXzbTf0GNpLS%+HD04Z*Bu_?y*A>-wrs<8 zYu7ey-?nVq_G~v^4%k2|OeD{VrwN@kTKg(9$gfd}1Y4&zb2qnhn>HGFHe-iD7_{{k zxIhcETnLCj2!PxTw15>fffWeB76`$3TR~xqwrIP-7Kk@_oA-N{cX*F?c?UrY<Qsn9 zw|;-OzKOsCZ1=u#_X7y{f4khiX?M$szzw(n#xeMUH~51;w_8(p6NG^qQ25|cHyU7g zbw|O4S9pe3H;04xhKD$bb2u7!c!-yHiC1`vTX@bfOmMrTx)yhFAGZ{dL{jw2`z5uH z|2U8bxsb>7Lcag>ps<6TA)tS$^k#Vh9y+;mITrxp;gnaolM|p9h{2U>xs!K!<QX8C zN8TIcA8g%+Uy^V9HhfS(6j0o_apo-CTJEixd*#GE%aNwp5FEH?YVN?DnWC8^7v#(q z<u)^CSz2jXT4_9df6x7_`}O<_aKd?>$8~((*Qu^2Kg+L`OJWsfn7J~Uxx7-eno~&k zQp(^~Wy0F!@N4#Gq{z8GP1^N$VM6w2D%zt3>$dJVhIf&*(d|l!cZJT@|F~A0>GK3+ z`?Q!v{(fg;U5OkESi)ICKmGA-gfV00<21@fLrqzOtzL(oP46~Rs5dGfdE7dksJcBf z9O4gpbGHp9b>Cl--2SH^mrt!gVB>(P^VDCZgXA-IFN(+9a^C&OEIiAYeK-S8IYV@N z_?Jl)WZbQJ-Qf2Vz1b&<2gyB}=WJ_H-Pz~p-vcnM^mEaH*PqH84@@kaq5W0rI(P4| z{!A=Smb#kO`8g4DwOp&OuU>QN>!EnUBy5!j^a=hT_LTN3b?qF+2KTH_1B^!^$rqLa zwA>dOH;q&jpWCazI&Wl|S>;Z(4@^x&UcB#+`&P^S`WJiN4?4<@U)FV=MLu|bp8bW` zjaP4vUS)%#S#;~!Pb_!_UuWNQ=h)rlywT0}!!K5KW~7`tfBXh^@(kwqJox1C;~iw= z;{`F7rYq)+`MOKzoEAOC1{w$7rq3*ePb?1WzJnnZgwhmTbqlRdFdPFb&zg3Z_IqeD zYy3lNVtVVRhC;#?I$}5{Wc4=9hc<2Xwyw);z!2_eI#>6<lg<^`_)D{%2)&Q|_deQ= zv$I%6Hx7Mn*W2kC+8Nf{ofz7ErT1li=*xS(uOElLe$)H*cIemgD|VQ2^e?@A{^5Nw z{qLuSzn@9kXQrRK%z9uxd|<2p)0G}B%=#;M_*bO<Vf^r6lKxTp@KL`0?>oc4@9O_) z8vfI+|F>uO@38*y#PIPe{ge6OllS`nJ`Vr;rcXcAH`wFWD!>}1uyD#aO@8w>PUjFe zE7mIXGtK5#4w~sL^f%8JGbHe67X?_}K4stN)K?UE{thqyc(L~FpbM3n(H~~|ZU@`m z)yG44&lZQ+*O?c}@ct<Zb!@UFnU$O^33I;h+Tq~*xP%_=+U`Ro@SZD;xcD&mb)$2C z=_QYz$hGm3XBy#N{qg%BX8Z3%`V61`0p`;wi}D>w=RD;yP!{b!kuPpus#6{l`0S2y z@Z3Q8mEc!*4b%B_D`G>Zo9vrh1}oyi=i7ZJWOVLaz4W#x`s3VSWqjoOVLS`JUe(c) z;fcaiu0vJVu6(>kH@%}*ofx+>-w`}NRDC`E+k0v{zkbb)Yd=1|ZgL&2xq1EY+uFpP zyMqZg{~qptoFBfMltiZk;dT@tt0IlU%qeWu4Hk%?Q5jLF-4j;18!ztu#yqzhL1;gx z-Ca1nYd6YisrY&{Nv|uXDQVZYN%X2`Dr4?EwCc5)Ks3Eoc|s^|w{Su%9{$E$954K4 zQle1G;i=>u>!PQps&hIm#TPq1-tBa&;<8d|Sbp>DG<DPA`I!m$?dPg5cHd0#KHc~z zcJ;C{1clAH=lD|lQ`e7|Iy<9RY|fo*s@fTx%sjL+qMN9_*5wy*vNzsORePhy5m;<% zCOtS~f1Y<X*1?K@i)Y46;T_MkjlGC7%`npU;}qAs)af?{p$}%~JfdGX&wE|_GCS{s zN4PBbW}eKJx%f!i)@!C1jxPq2a$S}}?>(4X3h#K~^7c~Sm$|o*RD`SNC4BVH7EQcw z&~n`3rTKU9Yq_r8(dDe;o-MR$*Y`Jnf0=)uG^TWT_sSw22w6?xv~gQY8{~DX=Y@Hj zt!K)$Ev#oNzjWKk)&9D$k#ER;akJ3!^kP6hcwA-u_QlJKTX%f(E`BJtwYhfc*@~h} zdG)ogiy!ae+1<BEnWvYw>k4h$KQ)wJUi#FOf0|Iu<MB-3^ZkyO?mG|qzAo+DZ)i;H z41@(O>^^*LbKN`r!IbNlp0zxW%b|-kQ(yY_UwTC1cE)>l2Z0=(dvSk%LH)2HHlF)q z0+Gwnw=app-c880FMofg%omU*@O<CP)D%?~d|K6@Ta+uM5m%(5K5H{izU<MnGX zv`Ht>?LxcP;k#?;%g&l_XFk;=jfP&`+bFcHaZjHR{1>@JVsx3Ju%iNQtxtbG_x}5( z@7v1XZ&VJS<Nc>+-XH&XZR>OM$DPm<h28mlpMSqUwZH%Oci)!rLyebsi~R&dQF?i8 z<m0(lft+O+rkKsB!7HoG;$_N**QDb)yH>&Bn$!nQ$P|$S?6%q@FZ->6ROuU@(7<HX z=<VHbrPwu?FUnZptWrdK#}Yic%vj`WLAsTK+0T}7cD`Q)8K!FMoc%7w^UKK03$g3m zq-|B{HbSO-*E(;9?1)@vW7frkb$+VF$h~_ZrzF+Z1YV<5dF01(LSr|C%)7_yx;XRV zy6Ql`PxY0&E6l$+P$tZ~J`7?nDmZaRJHg#7Oi#ynrq9qVm`_koEtq2Rt`~1g?^syY z(l~Ed9}s1-pIF-FsU#D5vScmGtyaooWSgC~6oMzLl8;hKA9ZahMgJz9CKTQoJP3Rh zR(9T({dU>dOan5h+&Yk;TsAKJVaJp8d}!_0t5PwywZaPFK@qnFrVoM?lQbn3Zr-ly zx-XLs`ksGtJ4Iw?((H5|@IlPWA6Gu|a7cYBx1~L0>}YPm`v0hzGF^<4Ds4=;`<`uD z4JKcE|L$XyfPLoWY=OL3R^tOwep1K=qm7!PQ1coVFnXm{T0PYC8@T9)TMS7lu8Lwa zY7-qI$>BX|HdwReP~Gy{`NJo%{hVM25<9QJbMEXP^Z;ep)opS3QnTrqQbUJY8(#d( z!y20?!gIfflKWmiKf6)|T{`kgS_9R0F21gCdDK?&;8NU<$FqtYC5J+hVLQm_g?$2M zW`l2{m)jF4<VIyLC8w$H`fi+co!N~k&y8#4<h?GK^kEnEvVfrVgqWWAyq15$Kvq>$ z$o=&#rOrm*-4Odq_qLL5wcAQ4)hgwjAWuoQ!sc<svb9D3=F*<Q+$EGk%ByPj_*jIJ z*Qm};c1V{5TSqVCbX7-A0P@ab@r@>fD(&Yt+z=h_etwOo3VH8$JGc2i|9b89b!$&W z|N9-YkW;C|Jl`WffpOHgoBNeMCtrK+Z=KjBM*gNxuiKYUa@4}yst)x7P#dToq&d2x zBAdup_9W%uXWh1mH=i%}2F#y4-R%Cf=<Qj0Z+A7qiF?YI*YWuXYhSu9Hi9Ens`rVy z-YWj)_jS|{$?;zlvSG-sVy4^%ssn3|`cBUCNtheIP$QIwH>yq@_{8_~#oeRstZa|f zTD~sI*d3~HkaB+c^FWP<<yWGE)Z4E;_xP%UVZR=zof7G%Br{2AR2}%lxKY%cq@BUs zXSu2~`%ppS;9uL!RH7TBaA;s$i}>CcXr1z=r2C*jxjOWM&tux{AcFc7qh?L66Rtl! zadxUO%;^sEOp{IAeOJVe>;1&JwjlKfk(YK{==~KlUv}f}nR|s{=}YrZPG4<L$&GOQ z_;~h3+oOl&)t@7(&I(N|96ai%zH}+_+_a*`Wr6hhOeqkM<2S_^S%d{&GWhdSF|Jgl zs1O!CAkHy|gJALumBqypd#|2`6225>*tk)_f3cIpnu%G?vQ=xa_=FMhe^Hs{RcmZ_ z(#~`$XS=sb@YO>>sdcnejI20|sjSgc`^(>p+mAPuZ2O)$vtKEFwY;f;OP(|pO~Y*J zd_2dI^76Xq!QH<)o5mlnp(OUB8_raJx)A^P4L2w2MY|j8&P{)2AJoLPM&9IQBXsWl z1Lg?D`oZLm%ujJCL;32HO`%DmT}2A8OQ|IKz1Ns#r|PQ1G_Rv#77hY$9`!38Zp*ES zI$V2QoiKXFdq3Cw1`?hBRZ3?KqC~?nb5WT1p(L;b4i6PYCL^0y!Ai|HJ}D&q;VBmV zsgywd>=l_fKce^ZVesItPtxD%XDeWh0t2WK9YACD0gZC}+e=HjvBmxV==qs{A9c?p zZ`;y;%-+#Ecp!H2>g_5d?@(`pO24_Ee)o7I{#db*6K=vBn9$S<)OX<oeR31$OvqC^ z?+ADIAxk2y+|nFR<-Gs%<!ywYL~A|w<y9WH0Ev|V!PYgwR&gfjC?+{FlTyK(Rzo2N zCEg<ntQf#Hx{8ok;~|O*HC|eBcrZh6_2qA+GKR{*s&+!|7$FyoP?sU(0vQsBVe+9t zq6;ALRF+^eBs2=_fdLm{SWBW<%gL<OcB~zE);hZ-8yeGtJ+=-E>`@f#6b;w}tj&^d zFneO<LIuD43ek{<{=ovJB??!+qHg%|tvrJ;QLCeX-wsZ5oNPTYTF2-~F$Omwt*c_} zDG6aD)Ggl!9|G?0Nugra_^NzGT1nia2CR7oAP=hG9B{UUI+O+E#~D_Zt#PM_+aA~R zB(3p(mO|Mn^SW~K;>A$}63<5|Ugy^+H%?T<KJO<Jz7%oJ+iL>J9fCC^RPH{iP+1^T zS)iO#kVxVWTjReh&P#8y7reL6*S*Wx5G~lj$-gQ8{4$>N_YOH>oC+;eWq2pT6nGDS z>GCQB*Nj<_s=O8C7o)%*ATH#-hJdsX*{uXtbAzSEd!U^iZugasc16861))(@R^u0q za`;S?cn^rsJTwPG_NX@G&&Kn)DUT^aB>F<7Odb5X?@8TRlPVOaqqC	i+{Rq(z`o zcYNPlO}+>DC48m|LV$=dyhxj&@OS(xwN^hPYyNtw;Gb`GY-}}Q4gmhC5m}~$+7yXp znnxa<uijV0K^&fE0Jkv|o-!1CV|{Y4rzm6wH%}H{;y~OhQj%PkZy0+>FccUi39O)5 z4ps%{eEI0fK#tcc7-lmi&QD*+ov7|kg_2dooS|?liLc55BdzM8_*pW*TG+)Gd)nx9 zlj-O!yojG6JP&*3@AosOeyH^~sAxXCP<v0N5Qxq<<PRVTd-`s!7zmB7@h9S`5nS>< zPix*VCp2@N6OQpW`;Ln7<*UMrxEQMaB?^pE&*THq7dk6%{LmbcONgyimmYr@KouM{ z<cL{Cj2a3Psr)($V~Ib`>aw2tmLm?zm-YYXUj^0<_eCv;^Hy=6ZNT$cWa;`o9RWNq z?S_>Xn2lDEM7gN2QMABk5`Pf&A)pg2H*=>V)Ij;5lr1)+2%>TOiuTVdYQJOnzD8Bb zADGbFw~bhwdewr0^BT@5M00;$;|~%SXmk_+98@l=p6YdcZ}!=^+)>R^)#%5IvsZX- z*Q-crsk-L@`5TouiVZkMeFX!6HFiI&`b^b*{49IG+QEhb$z9Mt2EuK=e0zxV9Zu(c zYje~TWv)E4d?wCSjE1`#3J2hy#(cII3^k9gHCOn67*^9aRpnfu3SRy3aL&>8y{x5k z7^PVn6=Epy49{I_z^dgdQblT~#X3Gs!_+08@8Gh~1hVBBaCeccuibWhUBqF?<d;Ql zA64YX`3gGZI+PIEAFS~ce1q*A?3*%ey_#eVgWj*6)~>@dJR-JYoZSPez*mg@&Dm5s z>Zjz&D1Vjjyh9Y~>>8qY)kV`jc+bgsEY97|O7%XI7X|5E;K)}`5|zL^apTY2T)Q|i zJ3jT(H|oh<fIL^sDr0%G0j}C8?Q>}xa>ps__Q|<FV|Baq#8y{kbWd4m0ncOM%uzvQ zzhWrB<>ITK;Tz~DmSN84K;kVr&1F?8*d{*n2JWj}TBB1cBi!wurz#Lc75r?dpN-?t z5}%EwKGVA&sBFPVqs|(XisXq47W*#siqCW!3J`$&SyU7I*f7)cVNhk`j_y(oH3HU= zzt~auGO4Z>jjSgLcddnT@(NUipurB0m%4*xgMt@I!yZjKe+PyuFb9l@^UyaCH8E7P zo=~GtSECSbF5d~EjlyiZ*?N}ckUB^<E<*vM2h{FXx0p1}HS1Of&MTL|SG0RvXrKAQ zNPN9HvF3N4*~Q0R(2TQ<kMlT0PIQoQPov~gO!1|Uy|2prBZ)>`X`Ff(k3Wo0n~%@b zOvsK;z#l^XQX?b{8LHK%R+88PP&0B*uz5bdUGsWJ{PjnN3E77b>U`oD|Ba`v*Iyha z4$db$qMCjt-F$a=b4~Ns7XPhj{%c=)Ztc6?{N|eUqemxKEuNXxX(tZXv9<H~iPdEi z2gDaI(2Ey2!i#GqOE2J0iGLxYAvzogz635ALvD~Sm#`b2#V}RUEtSr@kjh_{I(<2X z1)rkt#w~;AJX@A>YAr>(EKReQ!yqB~S^}(fH65>&k(Q8=nUG;wmR_ipS(1<`-pdy? zg$p$*fF@)On_jrM4#?KZew2{ir<KtIU`JhowgMoc#2gPI_{|Hpp@iHuY;MnL?pkl| znnB*yQ7#pgbLtFC=G9NDR}gm!K*|8jWxymw%t7?!7-K<LbfGZ-Vul8_5?LR+W%LkV zEB-E0*1oNN?e?j@+q%DR_b0$y)-rYDBn3lW+G&?KUn{v-UNWDrc=hm<Z$N2iU+Jaa zrP11VqOUau1l)AQb4#otRsd{73M}g)`~Y2kTboOZR9>x(q!(Z0SV5QnoPy<)8)hz+ z8Dc<VXwYq&PZA{Fs=o3{lIRRxB%m)o$)PlEvGnb{=m*W3ErDBa`)a=YuG#Oa-Z}3F za1;0Ybv5acc)y=$M+Xt{hsb%B#G6PGaE~>g=le<nH9Zihz;kPee@fM^8(f7Jmz0&D zL8@o#D}UEo;<+nGyq<<4p1@ff8t6``&>UW<mLyn9W$ajj86-Zka#N^yQzo9Tt%Jnr z9+&yJIrmR<p?gzW;=S_6_p1L82bJ_-c9w|SSr7iWx0XqRjv{d4{BIQbkoE#CK=7pp ztgc^LACelgqflkOs8}E>M4TUemf!nl<Xt?fE0dR=LbbX2EcnS!29sATmU)4*sRZ$t z%z3VZ*TdHPVm{mTj#n%zSya9O#kM#+^_Wfj3ia9cl1-GM?XQYkZk(N#Z^=TH<`*5^ zfJ+TH?&^Qn9(AZ*JX^2jdmRwyVG`2c9oO<`c%!LBkc<~{CnhK)EB5Ak^uB0FYIdhG z+>3{a(%p~yCVuuwKDioqP9E%@>h$-qmqvdeQ)FhkF>CyQ`FYcaR}Fef2WI=j@X$yF z$$|NELn1rq^BY~8e}@LQ(_eO6Wqmtk^>-MkLjf<_*!=Aky-wlOq4MgKz^anFEBpE9 z`WLsU;-2Qx14SPmKH+V-%fJ3e-Lpu?I&D;Fm~N?)-8x5rca1s=XCIu)FuO74E1YR_ z9Oa`kerX^*sA^b5{&9ncbGnCIR{sS4??mB~5&h+St>wFN$CLh*r|R7%(>=-6$rB`< z3k|}Ol<R4mpU3;EGM@h(m{u6<zwtb-d935=MT$%N?2Q+T125hkzgW|Gxpm{^r-7GW zj$iKUy!v_L)$ik%g=yH!q*vgZG}b{H;)KSj`x^XC*i_<v5&kV&_l-0IXBd2=bn-@7 zcUpb$&29YEz6_BflAy-T8Oy<$3nw%7y0c1y(}(>=o+q=ux^u3^5dnj9mrmxyQ>3^8 z<|9W=C!EZ0FpbpsFJulb<en@P>Mq_EStuV|q*tFT;!jNKZ!R@RR=2#nK)Aj1=;qtL z!MDNJwS=C$9Xl~04#pltBuweP1A<=d+P=%TT1>x*_1hIw!*hNoO<;2-u<(`NgYWZ= zSA26;zKFaJR2)AZ)TZdH@!nb!SSfD>aeU4<UD*_D9kHsF#0ctbsNdSq9@^0Tw;{A* z#dEYC-y<mReHJ6S>3nNTXysl06RRmkVQWovfr<$7t@}gdXa#cQtcf)OIUs9Rx1Mih z4r#Q45DowY7ruHKtvV+Du^q^9i~12iB%l57^TztNBko_D6u5g;jEe-4|DEnC{w{g- zH9>S|wnnK{O5_20n@-*N^bWX+hEA^R(qG^D@>5R<E6Pz@CwfFhEaSu=Ydela(PS)A zcopJc@Gl_ZoA`UhycNX1e`0$8#F02BL>as*zR#=-rtR%Z>Ys`lJYcO8{pSmlO^T-j z5u%rntwccwoJbKC=}8o|G2}j?9$Xtfyean6dHDP5)g5ke);V$TDCyT)A?ow1!}Cc8 z@#}yI#8)r67?v)`p0vxj$+olo8KmRrYdnqmXO{tp17EHpoJf#9R1Js_yoC6<_SY+T z`O|w{gR8s{5?}3xpscqrV7+Y6nU34y)@+_0N;>|heFLgoJDSO(;69L{TsNL8d@k`A zs!~5$DDm^eLp`K)Bz*2)M<rdu?!D6WU9QlWg@XE*)jHQ>23XXZX(W?uLES91dv6-7 zE6;jOy;?CQvNxz4$A4=XY4Yq(JYmylUFZmSR-p@Hv_o6ztr|D_`5r9y#ZtfbXKS{v z4Bq(r=LDujUZtkOxQBwjt$4K@^PC$Be^s;gv{=DoC`bF@hZj}nuD{H7i{5C>J)fO- zto`WoY^z8AEyTI*-Nml(w?nz-dcM9Jxc>JaLZ^3cZ8Tdb^2?dN?_19+&n2<zK0f#~ zbKhe)Pq+Wqm*xKJbauUgqy5cimHPR5gMYT;-u5SP=nozLKG=CXoUcFp@8tOJUpfaC z$HZ=d#Y1Esc_*`-p2ViG>p@+7Q@Ly`eA75pVm%3hmnVJGMQ=fCBk36_Ye7%H#MOGs zeR#AUskHJ_LSOmic7Bvvty^7|HdB0Ep4L*Yq_=J-N-D?nmqvYo`S_$qk=eg(|0uOQ z6!QO}W|;uYfMBMl|3l3Jp~4pARSG{F$N@7+CXJ*c8Pu#rNA3Sk&34v5y)9m+*6|u^ zAqu!qOMy>A8vei3?AStmW<hcomaSDH07}IGys;rg*yh>$ZV$uWO+C8r+RiP=*yetw z8L)GEPX<i-ewk-bvs2aQd)mBmxMg^X(O0p|9c+Ajtu)QGcmEePYsn4~KUZVj*SYnq z%v?gYR{+4oQVqnNMq^?_0rjknA99wie3&QuKdZUW-~Hun@0A@sO8@{51mN^{5gnSq zb>=i7ov+s^k^g-W@sl^s8g7o0IOd1?`wzeMF~jLR95|h$|ESrXYIFqiVbaF4ySBr( zZi3kaSKsIR44=>e5ZP56$bp7~+?VTFNrr1cd7@CzE&u=)ixf}eW1<<Rp<>CTG|?E8 zM26Va3?LL;6=jqq*S0MI70Gg|O;;|G-N@DWu&|b+v))^muU5Lf%AjWNaYO!ZY8C=R zFV<!`x%92ywlvG!D)qejNxH~B28%0XoEl`zFE+ADmqoOFYAlWFF5fJ6alaQ-Wnt#K zR(WatQ}A8fce(AmQCHC)${Eybh#@nGxCym1`YZz}3cD!Rkl)zHXbrc77!|vJ&6LW( zmr?M|Wsk4P72Wrim%AU<Mz3gTC``V#UEBM?J)kbW`?vgqM^ggQEvMYIO`9yU1f}a` zw(U)M!q>~?TRVc}6(6;@D72FNONl!@tBsm~+qLrNT8iA;LVX{{#GD-ybGeoEwMZnD zb3#ZswW77+bIr4F<jWP|ewCwaiUn+fNS@J1jy?(!HYCmeb(Cjht9f{y-8$;__0Jv= zCC*WpG*)Lbm_q;7znwE3LbvZXQkpwq@{lt*tN;*G$zE~~AGjddfSrd2m(0t5>A-fQ zlQnACD*XA{oAd2YLmdEUqlSUz&WN`9qN`Oh_4dpIly)2cu&*^cd4kf0AHbSwrkBK& z4wntVQPevL{+1g|mjQHL)1lq70tqXr{4b?g>NCyN-sNbD&I6eYMSpJsEH3{xxZ`SL z_o0j#1G*MsvfTHfKKSyV?Sk_*iJzK#Z2CSo-T!*D+chn{OpClTzx`#P2eJH>X;4Wx z9t3Q^{<SxMzWF<qdvM_GnC6**Z*S;d`x6%C+fIH(Dv4H&GO>OfG<%tH=GM`6Q)EF* zcF*v?zd12y=*K;rdk+mr(`OF#jt|@EbV2Pj1GQ)bKyVKS1sUkUL-NP>IRHPKO;yUM zIUx7F<h+e^gEn78Fkl0PVo<ZE#`SL=FaxSWo~XBoBfM~S5|ai516i#RHYPMdna6_N zd~!t8&n)E+fTBzPT*xAgtP>cH8doXxEyQZQ&eY4P<?(lX5|<&#Wn{;qQ01G$Z??%d zQZ}wWDxRn8k|IFuHN_B=$21<>D<2}E%AYw2I;|Ug=OUmg$-tb@j1<9YEJ$b*1J$mo z<(qdi2S$?21cvqt3wEb;*P%FfYe_D91~pu~Z<4ITDL?^?tJ_c^QfNF|j25%dORSZ= z9iH<c%3lT5H(_J;y|foJrC2YXCo5$n+_hTE&nht$UhIG@a!c2k)EW<;G2%)lK9Sop z$O-rKFQra4X!L|~-?EG08|pPfKZ(lqw%9<8<oK$ziL=T>C3tp-W-7PrVV*Q5{zpe( z^;T9o!m#)av;t}>P)#zsEO<Z^-v<L?q7mXzwJF<D7AjfFIW{;$u36%^lJNSd55_;I zmGNXEmI5(!G8UeufH43A<5UJU%Y6}YdX(WQn9xw*i%n7#a#qB$gaFsthEj_?;u74L zy{-O<JXd*k@{@ymcG4EgfK_;Kml1THNH|R(*<`h?*Urg8*rQQ}y8oB}0jZ60+*CGG zrn*A=Tm_@(X!w;*Nq8dGT<L~AHB3s9Cjx7tk*rM3L2d9oB95Oed(9dOaVe!tHhP|d zS>6gk0_L_?6}uSs`I;Xn3XLGVfX;J=j}U|`{Z+bro$6~lE9Mgjj&kQcIO#SH=zp{c zUC-AL6N`}w#LbX1w5M4YapF8LwZ^$G2^4OzZDtMuAgYYgt6>dS>3TB+FeAITlsKRK zhnBAEsSJ@(#IrucP6$QFQv=Ag^{p0WDrK@<fdjntIZ=v|HZAWKZygT*c&KRD+rjRL zu0{BVnDR9HX8XIPaAFt03N=8d+ZYwWIT}H=AaTkOQ<pQfdRov}V9MwC2|sNwEsNyq z$7Noc{0>acd39g_SiUVZivdewem`?|tE*o+8gtX<8Yx}J<c?U>yBFFy_yzO`dR&5p zKU!mx?_ZyCof|*xrmz(R_vc3+o2ofHU-wD<e%ox^_k8g4pm&%JI;y7(tiYoT7AO1j zHfx<$En2gv!ff#U@tjb*Txccv+<?1s)$FVqDbvz=UAVj~UFU;g=(QXp-n`3QGH;^U z;>k~V8!0L!kD?Jl+kS#0%`I6T0}l9tGV#+4YSwu1gZumz>T!mdn)QA<3REi`g9It$ z+2{I_Ii-V6(p1_yV6MXcyxX)<EwmxT+ASIW9>vn|iF(PIHuAOwXWnp1DL*P_WVsBL zeo97{EkVkUtFvHCF3&g1&h;99X4SZ=%0OP2Tb<x*K(BfY)$p^-_th+?dJUC<y=jNN zwWirL-B82*ERW;$-bt`nFaqwM@V`;BJwJ~x8?O7T`tiPKX5usg5-y}N365c<CK%N0 z#mXc8>8P>Omr1M%2@=9<Woo+1g?TXs+|Z`jQxbY!99ONc%^Zr3mrSp*#}hZ+u9v3k zywuH$&ZvG<hc=f$b!0k6NN`@l_Dg7xpgrwOoZ+@6D?jz1L*WvfxiVm7h%Njwd}R-G zI{kmB*)yWO1?dB@*Om-w_TTriR|6lE+hJb2wLk8D8`w4;W(Xys2NMPlrb1ow1GD_6 zvedxbn?%B`V*m2qQ*}G>?TpIw%3<HDL6t|;Jg?Sd(K_Tg9U3+F7P;<o8~L%;=e1)y z3yBiT66UuL3j-9~3q{t+e)OaE{bPms>u^T{6J8pCMXi^_EK`6#E~ljOO8G)97n1)~ zqQL^KIFJ;XiAfgs-4%DnPg=GJhek7NW0|Z9n6-%@GyojA2l2yz{q`U{ZeWJum-7KH zHW@;uAf(C=%h+VbX<4c_`IJSn{6ezycCvC=vMMy?4F%CjL1>nxNR_ecHisx|rx-y~ z^|w=KNCZ=~%YAdr=owbc0+1al?Qot+bQO3Jo#ysG)U3M}$hZJ}8p)7yz<~u|m(?^+ z*)$h2!E%*Z4hdvJ1NbP+ZJW$`t4yb(m<`EHXYClzLztYmf&5WG7?O#D4B##RY8WsX zks*KRJz$q8mUsYbu^S|i2EIcBU&XSxV_67Mtapzx%W$l>%fO8xS%Gd4O(K&VkxAYT z;ugiML}QYm0EG>*g)tctXrM$CP?(&pgais;ft*<2Xh;qx1u)f|BSg-5d6dJTX5Sp; z2-)S%x#gBevD6f>zU|FjKFVF)&Mhlo-R#Y6vO|b<rRJ$3s%d#&7xHp2P*ED>n_K>` zg#4qB{7M|O4##>2&Ec62{nE@TT9*ISq9BvT%6g5hX*H#Z$a)FQB86cF^fHMO0RpSy zY-E4{h50Oz*$fSC13}t~A#Y5;wyRcReMMrSAcarNI%H;L#>o$Pn=x!3N-u!m3Ltr_ z(2r5<djJlGHfthKY%Eax&92yrmE(W{y@X`3MzS~pN*op;wxK010xZ#cEFOy`?!Qa0 z0;PW1rSA8j3~Dy$H%k_=G>KMv`FCm5)6&cLpxs0mfC&HGn<w0L$D{#~g9EByVQpB% zb;~ls#j=cRWm$c9rdQ1y0UTBn?rlU^sy1R4d!b|zK20p2N1IhH!sp2BwS8{)kt~-C zlKe4{Bs;Jm6wHHS&BER+!c-PfpfORE$x)R(me3eVWzSP6&7_i&X-%TAy+D_B5ZyA> z0=)=<FGB-g3RFAGgw0$F6qc%(wPQc&W(S!$vAQDO-gBFw18O!GBe&#g_KRz_`)W2r z5sP;0b9U_C$}eg`5CW!%BL+3wcXva(W;qJ3RdOfq3M{1FlWKtIL$bx;Orwd=833a2 zk!PjrwP#z=Jw*6Y0oz9$>qi{Bs|Fm@0-xH79{*)B?o!JTF#nEM$Mds%<Sj`e!z#(% zrfA4D3TrpTeUau$zgq6!#r_#x@fpo-e74?Xiv7+#gvnN&f*N9s$e=S}R3e<G6gGx! z=rcfc5gWLj;opBYeE$jOk!kd6fsX^CUsB*NqugH-;c{89F+2Du4mOGnk`J`)DX5Kp z-1LgvbbYDe7K56VZyqmzOSoRcRy1c-z_;lK4V==%N8HBaW{7E;%@PvgjD)sgd~eJJ zV^ZN$SfA-fY(i`tp8#Q@R)*J{kUX(L&nea2WY!O+Nr;w&2NV|bC{QGlbq3A81wbTe zz>8U0CMnJg0dyRjIF?vDf_51}lEOz@$GclN#eE7A9~daRj7K5roH-aQY8DOB7?tX8 z`hc0#qQzsiWYAKEZE^ht<GBhq)<Bwfn~_-I4c98HanLLZVwcQ5um`as-mf(9T15JF zVXPM(llw?EPwilH07wo6{u2o%FGA)D5?lB=U$4TASUA2UwzL5dG^FviT05ztR$&Uk zVs<|X37aNX&lW)Kh@gIYOTzprEY>;TIkpY{_hCneaqFIQ(OzT~5)2t{Uq&MG9|tM^ z44S|Mxtej5Vb~<z!U7+goI2-1T{Swn3hPYtP9n4Q7ubJWWJ|OI*&$iy(RUvgz`S@` z&V#yQD}}!EIz&*|77M%+#@HMC;L~=^9Q*K>1#E4r?91Ei>qHpt7c#USP9H}!S|(*+ z*-T2{y$rIH!s=VV9EpVOViAJ|u5liZ``5_d#-NEX#EU5B&serf8YIgOu}r(Bqkw$1 z+SqT$Ubo76z*sx!@NFyP^;Fmhvf^^Ew?`&S*r~s3ucoXXbS=tZ1OxNf>1wPTBzLra z=Vfz3!}jT>hz>iB9cPZ0dn|*_-O>sJ&kH&qli4fK93KHShf+T0c#P$RDirUxmprSE zzXtCH4Ei#hS#(8cs?EavK{mLMO)-2L;5&l!dAbUFLxbB#vCS92TCo-91AT0H+<P$` zH3jTDQMS}oxJ_)(jac}}IGgV?P!bMy0zt?n!pl9_3o#TtLzSgiyb3&T*F`b%6iDDP z9*aW!t4Fi~028aQL9|VI*Lg@cC>n{_!35nk<ESCBeMVC0;c&S>hV&rBLt5wGFgE(Q zB^3vs*c;Gl9jSd9v#r)+>^adH4bzu_&LN2sVX*i|BlnR}Svcs&IJW*(_Bss5S2_*e z3V>fu4Exj1K8k~;S|=s#!RUO5SLllxiioYKE>M+4j4<)4=Ttc!&OOHVJj(u7V8nL4 zpQ|b2g#nBTK+It#t<lU;WR}JPHgk*QIRK)P%zFE}w|@cKw`U0JWz*|3Pj@JNpykM+ zC|G{j)Z7h$=3Vc~C{N&obNlXpYO(z;++nJ^CW<}D&ig~0_pbH*=mNGzO7*nC$YYEP zLkaFAv$qjh-gr0-BjH}DZ9UgtfT~g0*q(o*Y|{paaT#QU34F)Sd<O&TC&NCjvOYI= z%Do4@M}#&a*-C{f04#_eB20OFbOH_QxzinKfLOAFk2H|My3^V84*U3QmSi$)3g9$B zuzAV&u#2I)2JGb+w&f^9EB1|JOZf6Ce9T}(?y(shNPLJztQSDd(UAKT_HH}aGxW5Y z$XrIp_$(2Qn`LFwHQcR)Pp!fSvAwq_EI$l5cCl=3{l<)!$S{BDa=J8Iy;@O;W}m<g z3RY75ZZ2H$ot|DDtPFd=yf(B$W8KGrtD=I3_GbBkMC3E}qz9mS3i~t$=9RioKZt79 zLHr9qa6Nxm_^3@{ne8*SV~1vh?&^U1c8-%5t5?CGR>TVojEZjG^;jCc$xl*uU#Ga* z3R&?El3K{@uP|^nnVE46tPH`au?%yWS;W)2JL#)NV<Ic*9q<G=BpK<!^t!`wht*7p z{hpok5)$T(gtSk=dofE8PIy-VY>{ZKb{~Xaz5gCDx9+v-v)0gxfwx-s4wF|<gS|bJ zt`sH2uARv>3am#Hjy-N1#~_x_cdKys?F`u3$n4CQS7r71p+he;%@OQ*?AdRlLD8?| zU-Vt9h9192Sd3!JM3X_`amp_o<n%V(#j#*~Ppd&7x{`H!_3fy^6gV0_MtlFFfQ8{^ zGc;d&B-jc==9y$Yc{kDrFiNo847$a8?7vCdgSVog-=v;o?Y<qfgOlWuu>&SwuEQC1 zfF*4>!=lBBvQ`0VzGsGenM?%JYqni{H$6VEVHum&F1xD>?9x&ghoP~3B7AYR22_dw z6np{zwzBj-8z@^I(hQbxH#VYJTMF2huxw+i@JFMb@HJ2C-G;l~a6{|Q1DAQ5*a3{W zu01p~Zk3Hx0H2}lOxXyWNMc{#@oDig&KTOAX+y0e&(}2|Kw)oZSH4`K>i0NXF4;NE zqg?{FzHHw@>0PzwG4uKK?`sU_*UG7>>a(=HTi@J#KNpX(@$s_#acNag{l@f)_nUOY zw4EFC-M!zpIOr61wVr!Ce0yyA`?{oW|F9hYK!9HC0?+$>O=Zi{K#rf-l{307(_i;x zlem5taQvdMO$3&EZrzh(P_r^?9ExY4H;GfzWV0VuKlH@7G$J{2kZg-Y*w3#I_3s`C zM0=dzT9vy@?8JWBwI4X?bDHJ3ya5A#Jc4IeG&|FOBBFl+0C3OYpI+Y<uy=oP+qXrW z`4L9{)${I`F2`Z457Hs&(81?0G4f+V(&6>?!{FiOB#y(IK1YuFM^R@EBl3?j+m9~2 zItu%Cl*jSgO6;gK={N5jGVk3_CeEYky9|7`M<MX2-sewa(x2wLe_DqBw7&n-M*l+= z`<o#4M;8b$O8VP-_b-EG7<m78i2j!%cKk&Dc-Z!@HkExG{da2k`1$+em-J(r*ol4Q z@jDP;mtl$1t}G3oEYshgtk6$Z#s019|J(HW_d)F6%=-(!DD1oM|9z$Z+Y_UI*QX!& z(0?V-_s<}YhUv%e=>Vz?gPLUq3iCj5B1UO!Fuhci{klmOuej*{FEzVmRjTCmc=OQq zgLQ@arIr6h&0ZI+VpZGFCjmkP5%S#r4!M^38q)4FADvp9AK2V1cm97-v-!tIfolIl z%?24i-hv)tJs!t>SsANzJ>%W^A2loNw#SfV5MpLkZu@@Yxgz=m;fwz#H9KB)@kh|h zYTYD=$p28Y7w(!>yZ;QEd*C%p5b^jGvGj<3=|5`r@bb#wO*%x>^FL}fSIoS|^LNaL z7uEXdqF#SuKhH9#*&46ESHHd+WKgr-#|huJUfeam>wS{=>&v_0bTOZQH~#$m^8S?~ zKZBZmS!ed;i~%sSKV9rPyH1n=nE$zwQX1}}%#%PsL4hIcjOQ0o1fBB~DnJj!Y0PP^ z_N9i!5Y8#U<r<*;@P@YzLud`Ej~?fX9OYDD0pje8#3Y|9TZr>ALrf)|g;gx2|DMgB z5KHn@v634(%QYs~KKi{u-uQXv`7;-mxNsc9QV*Z^VG>ndu)YYGex~#wLiMHM`%MR% zb9Dg(8>w%bSDwoM1vy!&E5N&Gd@Ry4bURb!83z3-=1exT3{CBFfV}Tgn+Bw;bxqr- z^X56)@f#N#q0QsIIGN1qSj?*1pM<>;1X@7m79#4MUA)2{J!<y~Z|HKJjXHU>;F)&P zf?`m!r56Ki!!_JPn{t0GJ`jAQ@yM)4UFB`7%Y_*a8bvzZj%_T^(l*v~WKQz3h*wYj z)s1%%-UYo43@2;kMZ8MXdHMN?9Gfqib$-!GS}K0=UY}Mk=3nTYb(YL)T`pnrzP)-& zsd1qr=cz8MKblb+UdiKE)qZ!$me0|v)Lu{adD}{Z*47<X1r_Urb}#L<lt>%vasNDD zLOCfNf)gMMm;OYjDyT=-)v{>t)3-+wJwF)ZC%DQ3a_<(S9=7|amwYB$zB!6$8`o&P z<5wJgXmOwWnZPJ?;&{hvAbYw$a+uz&-EfmV##G1?hxe#U`X~zDsZGx#Z?~NaE@AKu z69Z0;svifgyrO!C-o3dC1c=zGt&Q(tYcdN$$NwfOi`6Y~R)hpe2>;plFZ=KxHOr!x zu$F#mC}9I1`E)dHyD(Vz!YI|0ze(iQyECXz+n|uZV(mX=U()sTZtPE-8ou%4)!|L) zhsXQoLauX`6SuFlbx5NE-J6CIJG`Z=%ns-*SO8edfC+M5VTdwzx|ft?&j=`c0Tflg zUrp7YUP;^USiA%D{4Z)2<O?;`G8&ZTNa?|tsbrB52|4S6BYSrDHSWm3{(ZQjIZE29 zd8q5v>L&vCG(T|Z=@sk*rPMw3Wq)+l_>otzz!-8u_9Y47A*B>$3TJ2CB1qkM-DC-% z)u_ahvg306xORwX2dHrcMZu4*eV?nTE6|QV8DFh+ik4Mk@vzHIBi!4J;%EUWNBVP1 z?#Q*JgU!j3v@a7T>x?P*;(fTM^@vCf+Dt7+TsL4dIz04TfGod%Z6e0_qS(6l={bDf zIW0T>`yT6)Cfeu6L$=YK565IW?eqLixC9<sm?^nwu|>}?nO4*Vs<2AlzO^mMWi^RM zCEBxNUxwuG&?i&nlbd1w$nUmOppRHc69-^sMDW363i3OdJw*0Af6ppJQ)MkLbX5ZN za<91QNuMnh&Yt*2)?DEU5^`0_pKr<na=IegGAzV_Uu7fM<m3&>pAm%poJ`>=dY$8) z@jBgLU`!zwcs8@5UR2tY6+@WIzW86X+-s&DM9TIzsLR=l0xRVJ;r<6RD1aNE)j5gB zU1hR@lrl3+DOK+7KPRaRX<<(BQ;tm<kNoqWjVVr1Gi68D1qY+X)m2HEamUG(hxd_B zQ`rEo-;IbKN14meWGz@L0>Ui)A(&f0L<rhn@WsNI+EvcnU=wD+9>BQQH^B~)c3ndi z(ul6wtn8@Q=wH)MyuUm*RoGlMCVDVAs(!13Yw%yPz>BE6a%GH^kMcyMiIyhkY2V8L z3{b;IrWo(5Ii52{!gxC)L(V2Unv0~MXr}{MGrRES^2SYrR<Oc=D_8K55&zP{nEbXf z+cm78@CKA6VK|%h+N3{Mi`$rTP&mT>$ghhhd{^-^iAArMNpKLg!6DR}<*LVQ^Xvqw zIa<h?sK(4c&HGgK`DeDv*6aN>I2P??YHr-~Zh<xn^Rvr_`PbAUg&meh)0ne8uqJR) z7bA#$Vwdlp!zs9=H6gnYo$Y&rn<AXKB7L8V@PbQ9O}UZJnJMR8BTB}#0Th*@=xaH_ z0A@kncVnlQS@aXDBnLp=rfc4x;Q8Acs9qGLY)m*vC12qAT|u*on^g@S0VeT-1q6*J zM3$>KXa0M#6S7@$CS5f<<ES+jxoB#ZN|<Wyubm8)Dm)C5Z**%0IdM9+!xamVL|HwX z{U!ee7Ge<9y_YhfGw!<*+uDQrudBVAnG;|=A~@?daaL9*{NjAYT;~u$y%BHc-&}Fe zK5I#>tq>mI<lX~7K`<5K?9wKFBC1M|G;@2bU|n3eCVT7~c79vyJ-33)XOq8bd)P1J z_}^MjIJM61&^6{~Qbb{-ueF*Umkazw*Km6>T{=4<%j-Oq1|~x5lvKKgB59RHGvUbw zIm#qrou}t$OfAeSSLdbxK`ufwyYY3VO>45?lAF2uWzL*;cy(TTtughGHMqxivQP~J zp3bn}(2?VBsGT;~2M}3wGg43^sheiq{5c*W{=DDI(mAf+voE&=w7kklQ>gXavbRkZ zN<tlRl~O=$XO201SgtQnhxYJSs#)FnwIq<r*?w-4n{#$cceG3P!J!sciwulb3JuZ> zBaDP+SBq7v7_%i%67O8uy=O{0c|l|efhpu{2k=Jztp#JTH2w*BBm9NVmop2K2@ti| zHMYd6%OdCViF&3*wnfa?oY!QCW~(pTqw^$I1q&lFBnf)ef-XGwu+dDckCZ3EfA<M@ z&$y~}VOCl`e#bpOWht05x5s0nq}BB%&N?=?jF8M3Y`}y<b>xLF`+b^UZ3&1b!98}L zbT+w}XJ<2BkXB(T_J^FVP>alLAD`yV={c3~@HG4x$l8MCQV5~oZ*lRFN>G8;WjC;i zR)3pgYB(CgE~I{;EX^w_Eo>X?hatSPgaq~W3fh-e3u=4fAVF>{3|KUbR;OP;`N-XS zVF9#oy+2@b2*}Ce1BGCTgm4-m3<;71FdH8AUn~P(O1O9SHpGhzK6(m@r9mcsw4dda z?|+ugNG7;2_!uI=vllXr9}X`gELyQR%QBl|nCOEeDf`oefIaB}(r~{K#6J3*=R&I1 z!dV#ukYh8XXM^Br2T_w^xdvrXoK~TFXj<3xr)WX^_lgbKM%}X0oG6b!N@|(7rTO3< z@xvir0En}ssk6u9h94?dv-AC!RT=rAA(2U=02EDx_#xAEpv=(>@s(Kb)hpF054r4D z_u@^#htBj{At~@?CQ~B8-A&qBi$zE(UHn`+W8xuHi{QKs(q1^HjZ-@%UYU!MbiMsZ zD}<Ttcr?V0!Dxb|%IjZqvjk8Ku33OCW7M6D1@o~4?Diu+yUx2UgwQfV40<wVJ3VFr z>~h5XQMGp)2EI%ja`Q+}uAhvdLFm5y5DP_!LqzFM0KvDH;98%ohfRwJk<*<V^P!y4 zYk@HJ6LcjsDvj@1jHJkCq+FP63vwey9}&(cu=u&9hbA=r?SMqPu~=f6rLfHJ9S9mD z8TZQ1^?0OR(CXJhF}D|~2WARetD*t{gkWNi@u+43#qux{!u2e}Th%m1YBFw;5V6{8 z!@y)IW3o`@{)1#$*<?vAAdee>8_Oh+kt~N~>KAUt5TEr~r}h>@!Y3i&vgw(MlR=mf zW(8AcRl?2VJPtX62btij#Vo&_8lI8n@qDbulAvsrZXbg7iqeU6KkdPUbIJg7K($O5 zW~d*FHXy|=D$SRcM*oso?%kgjhD^6BNOALg5++N);>10pC^0(b`XH0?w-#OrCb_Z| z3E}$DS_FAmyFEJHiKc?SFV&N6-Mb0WwNsY0OCHo=l0~NczL8=9P5lc8*<_?ShNL;~ zy>h~&rJcibmnCy2FiQ|$Y3?OUVri1H$-=nget3$(B(ttonoU7k&$4vZjCzFBn1?~@ zjm|t@3rN^P+J%g<2plBZz|x{3&EE~ufM>CeY1l26jgh|~9+Ipdk`m|-!W5*~Sq!N= zRy8~Zhq<wA)-%cPk?z#%>9$Vk+evREGRRt1)Bd!;Bei&~^sf@?>;dU^Xs|Alc`(3E zIU&U$BbDxA0lpM9owZ5mP9+4AANXP+UKvO?Nejn<ROLO#6rq%NuqW;jV4L1oI(x~# zBWR2~AJc5BUIMvD#9Vb_kb3{g$l>VWG6_SmzlP_T>-^DYk<!k#hOJh{&Q4=PU{L1G z<r>$tS+|nei#MHxwzAaD6T%E^_WKEmcFNm@g`$aOi3MkUniT-t>2HK(wE;|W1x)hD z)VOVHhlaVZ!8G?Wa0qR7(<Iqu6=G@uYWq79vI_BR28Wx@$2!mZp$X1_>6lgW`Giz^ z93Evr)5!p}R#`BBN^%Q0LU-QXPQ{%F_S15W1w#b=88-6Eut{}OgVeO0$J@prx=$1& zLe?S<neL(m*0oE4Ix`88@to+3MZ7>EK*}jViXk$!lsDC}3>-!zcsCO!HW|y6FfKKG zAy+OvZlQX1hKT6n-(9q=cW`%xJc%)2&*^Nu<bLnUQuEEF=AX(QahV+D!@d|BOCpmF zH0_pw<<+Rxz-EHt!&Yl81IO*O$9|e^pi_vo^u%7s)zwstfejjvd<)B>x#i&+>lnT5 zL5Z7=1N0?MLd@Lo0&aNa5XgDy;h{87YRU32SbI|1Q<K*y8krGChS*qulnZQSk3dmn z=?P`&@kEvwi^(UP8Pr*)sWi_^WQgmG=lQW2Yia%T2Wd7~kfi~bZiv08U63rWfJ0yb zT&rgV(0IfG@Pm4?D$aYmgxLrU(nf;hu*{MLOp<PIR11<-F+gz)lgKI%M#IBtIQS%h z1I5Ha1By)ci!Ag@n<lH0y$$VBN=s6Xc|j%xsq~ZgD}f-By$gUq@b>_)BROpg1`g8# z#~QFC;#OG+Sk@YB3=Rt~#UjjD*a?seX9;A0P{kl&a~G7u#_T6M47HcPL`;t^OJ%kO z2WJohp=%j}A^=({+JZ@(hEpUb^P`f*ZIUH4)+NpSBwr>=3<0;|fE-6SI3PtZ0m#6^ zrN-A4U-~KBN)}=$=e>BL1OPJ<DBhhcPF|;rPbRBuGbv#})|6Bgi~mq_aTz~p8z!_3 zlY;j;IttGd1!SloB19&s1w3>TCy2zE^5Hl#a2!Vfe&{B84=;sEmiPtu>FmR0up*a{ zB2$noo&XewtSk1WC}{;ctuX16{q%?M{2@S2D3CJ&=k9`IF~D)q0MJQ*<u9Bd4gi(K zb0LE)M1z1@IA$VHkj5m4W>z7B&XZF^8b5^Ad^q0=3cd9qc#i4vN{|ZnL(m*kbkK(w znUAL#<BYNdf0PoSTtJFC>oW=AX-Iybl{`|JCLsQ}olAY@H6h;5qX*m+L<2eD6!lg? zW(%qEAt|ujXX%9PUL7#q%#K;00EpX3b)<#3Edxc}78!JA2H&UN8BpFiuv<YIqXDdk zOcu_-hggAZwn1*_&?1)*+?5CNJ5OsyQzIPGip)S}6dw(2%Hcbp*aE(O4!F$=GRrvM zG`Af~+rD>oyT~OpZ#vZxot7jC7J`FKP$_ayYczSgQ)5TNj#;jmNj-zvEF{GwgxL(6 zVolsRcSMMUvJ4FEoIip@(sl;McdnGB_rKhUl1)|DV!C67=bXfk5%6Q|cq9t=lmJAb zfIJl3mXi026~Lw!ejWS;p#|hd(cWlWLLQ|A$wIDirw>~^?1q62wTx`+l1-Y^J@&vs z7V2I|7Wze``hC^&Aq6_OrXWFO?U-Jc38z#IGND#|1b2gqo0*AQwU<Gq_!oF>cN0G3 zbzN8;mv-Kcqb*zCG{oPa`lH>g0$IYf(hQ)?vRX{algu`58c%Mj-+l4Oi|B~2g1B)T zUBaec$Fjslr3<|HaGsJ{(~4JFz^iGUF@u5~F=>h9^hC0g>w?GmcOIJW-m<go%>}Z+ z=Lv~r4;G7*02k6?qm<%lWW%ylLsY8$B*>PMdTugVXgEceZ28cGNzEWot(ozciAVQ5 z)hM%hX#8F3<Jpg}aGA2?Q|aGN(V6A)zw6t9Z0u5<dcP~Wf>;k@TnqNN7}V@ABrGG1 zF2n~rm-^8cYSi|H*>W#gGlLM3A?lAit0F=8!1-!%%7U6rx;Ui)C`<G1B|Hg-48^25 zhotBi=+;V_dO=6S3cz}v2mCpZ;1GEmOSf&csfE*<gZ?RoT50Z>|AVRfj!L?XAI8s6 z9Dw2mMFll;iyKW7aONl+nVA`=xl1%xo8jJ?l`C&iGc7Z>mU_o<r{zwq?r>CAR#sNl zT{l0z&+~iE^Zdg(aDc<PK72l(>v~`B_v`(*cxXPcIMdrb9Y+R1zA=BtLB^6=4(}d8 zcv~}ILC<eyh6?)F|LoJjG2e(Y%`g&2r*TR2tTVV5U!=1lgsnbvXAYN(S(K(&RDM5z zzbESHakyCGke+E&e9gA}k56B44GLRl=o05>5=o*xY`v@`L1t39drq)~sZEB-!ygw$ zQvuznrlYA+pT2x>eR7;Rd3-i=tn7I1bMce7JtwJ|!QPcZPH7tBd4{SdRw+n%&m(c1 zIV@sZd|gM(V0%eVke*ze34Y(`F$)QzXMMDj@YZt{3(t(C-FvQj+UQG07{PdtKx`<? zT;p(m&=spFa{t{tuuBy8WYg_tUn}Net7DvuqJIC7Vlfi^pTT`#dkWYg3Z%E>X*PB! zc`S>SZ}qYNxYr;gxepT7M|PzgwXS7ai>0*0zaxvb^*Qr__4>!NJD`RMM_H+<(_%@; z3*M65XAxUx2^WSBT^Kp?TSoV{%%WK0SX<f?+`Rl58{=yEq7Jh!7bx3qDZ?32<&cQ% z-nk;1s9MP1b*mrrD?cy>(=7g^h5g$6{98k<-cqezn0{f8{Y~tL@Jz&3&8pki7UX?@ zm;W{nUAk=aXZiwokAM|``?-04@t7z($%wW+k$(Lz@#Ru;!A{0@7UcOa|5yK;nza!g zwmO`AbMaBSaJLt4k@tV8Szj@qMG47B5jBh6^+eJC7d5-NjUCFCDjJqoc@6ImnWTGH zS!a&R>uM3rQCD&o>`r&lRwpvvms`cYAG&(%$j1oVxY?wUm7$!n8t2fm4Nfs}R7O*y zfowZhCap$fK@NC3zcL8W3F=l&FmNZ|B6qgr7@oho(iJuy_|JpGTjgey$GHxkBSxww z$IqpHes%uTb?Z~DOYjt>r8a?ZsI~I*jh^z)t%LlO?u!9Nm7UbdYx-CIeSf5lGU;l; za{txUK^f68&@oO(;!*hkqc9OQdph&?JMqPU#a_ICcUeI;Bp}!!Ht{jSr*tgUcGaSL z;ZCp2i~DE4Y)tvNoL06um41A|>3RQ;$(^;un@>kB4SwQq*P)K_!b^hKUrz$wf4W?G z`F%70AG%maD(3%Ev*~gkV>O2Vi<-@R3xbjEpWUUBOn-)Y8~7mRU^qVhir3{v%$HDu zMw%boVt6PNYO(UXtiWjhx0z8jDgl_GGWDv~S<VHWAf_0aUE-!w9ek!5zvK?e!{p<% zveAcZlShsSkHw&JbvkiQuP!A6&p?mCv0ocW@z<^)aDYh&tR`8jKHn^1^{AKGeZ?zY zCZp&pp5`OJ6FqAR7MrK*G5<r&UJd&7#PK@-1J$_VH9LxNT>GpoqGk<ZnpuK&Co%18 zj+@q%{GfL&7j@)gbW?*9bFkNtz7XAYig~VXjq0<}TQNKA7FCwzzbztqz{<FrEn`03 zy&U>Jx@GtvFI)Gh`D~8PMx~ncgM2bD9Zl$a*4iHlXm@tUjuSo&dT#U&N$c$NlN118 zFQ(#Q<OLj0%5VV3hnxBg^M8=MOox?@#eE)%X)-&MqJHLg`{;`VFx@0K=v)U$%Y$F2 zA*8lhc$$u*6<{VaEq+sW)6QX@M!lPXj}3AL*y-|adT%$>&We?~V@kSaJq)UguX-o# z3tESnbqf;nF8?}wW-4hUy8flzZyzUbtB3P-Rwit5mihmtW)t6o32Lfo0xr}kuw7g= zwYFV+^|Hbx{92B}e!SBDC=3T|TH7vx&Qd$Qt9-f^J1j^gB#x@{6Zbx8{b&2Oi%L^0 z;{i4t8R~|*Ck%2$1ok0@;5LH&&hk!u2qFYUD`o(P)ezjza(ed&5GY<m&B_{KE^dP^ z(EfbeLpj6;TBbcAsR;5kFR2(5pMdBTQ|kWvRo*9}X3MKB9RGZKcG>Yi;ck(ZxX^nN zGYkXiae(q|bf6eXZGJja+<?Y_B?&-&tFV)3uuAe3MU#9pm6-ok2A^pO`_@Pi<am$v zja#PsTIvm8J?^$idB=6g#FlBREh97GSqXVp#hg_72$}3ss!GH_bNEGbSKQKu)3xnp z<V4z<!m8pe8>}|gcL1Z@*)(i?X-pG9%g|S3XFKLorNeglnzz}a%&m6K1*!yk87pHu zQQ~ou>PFGQN?<7zF%OK3#k*Bm>lMDnH+p^AYvicQghb(Yinfhbg-mi23thkcc<=XG zh^+uC$%eid499q&@>jLJC__2|w#VU`Fva?)SB7pgGD4rOuxlSSGmR6L3)AwoG``kK z;21eF=U`{bxjJrkrQ-!jMx7NCUZY7ZY<M(eM76)|wbf7NU#Ai~tHPj@=V#B<g6^`a zUx!ayjWlW|e{{Ps#W{+*=A&kE&OM^5&sC>xTJ{k@TBWNt!y-;AkKoLfB#(jj7E-Sy z25PIFn}K@LfcXPRgY5Czy{;CwX9{9IYy5C`cW9&*6bAAYtFoQY<;A9DAd14Bz+t00 zxdW#g8dRURxmx1uVG&;Is#_Fs>y274j6x6tNV1TYCE0#77IG*m#xIPR7qL`_s=^QJ z`<7(y>0+EPZ(_o{2q5_}dW%*G@xZj6t67N9uX4E!5`H?MC+T~{{?ITt+wJTl>h0QU zS=@T6flm3beIrVF*7Zb^9O}p>v;Bfki*Zsy9%VNa`Pa`$QNc4}%8svc{f|+Uli|ut zNDoq|<7$?jkQahjS9#pGg|q)RZ|TxVNAs|FjL-X~7uGQyW5sW(@xKre$O%zrvMh}{ zPEJ+JdStu1m|~eAgD}n1T@Jhw0=rr~7iZJQ`(u*EHw?+%sviI#Mve33W~#qS04B*| zT4X!<uEb<1y}@|2b;81(8q&i*$A^t|h?4Bm+OyICAXDK2Q-LlJ3wr@bACF<eC25QV za=MO=+>-QFFrcJiBtQH?cTZc6u~6qfSkBXwyzYh2j$S0hkm9x0GgLmr1^AmFuEGeP zcTqEebEdhBy@2gLWP+4;P454tX6ub!>6`u>SU>C@Tvh@N^%vE?_ql8Nk2Mf1`MNRZ z$K{Tkd1cjkf9iCE<URo6jVSc4`DbiY`<oBeCH=E(nBuw{=y++V7i0RQ(JSPl-H4+z zs36KYU1wTJ+AoT)@jv;sU)a&6Ai?bS?60KT+A)B6);wIlyV>vJN&kAg`Gl}<RZ6q( z0&UXOg=20yUoe@<iCUV%O$l_g@fKB~|FlR$jV-(zcj<yZb_~Mlyz#;3<V)7F#$9Vi zT=IwW8~pl;MPV1oUiw4KC;qdi`@g#hxy2VZU9sgne-eHWVLGu7`|h;lAj&sBW8>IM zz*6eNpMT;ngD(hv{nN|M`+%U025J76w#)exa4N%ZU`=^+tsPbRwqT#LpN8oMN&4;Q z^bIfo{nEMzIK7qEIq>R~Nqpn`&!@gV7<g^{@T_Zn!PgsK2j1)#+D@}fcGwDoo34)k z4>fByUvKiQ*>CV&z(c#m&em^t&kVi~5!x;BO}@8Z8Qh9++_y5<`n|hz@WbiL`<}0x z{J1|i_%Y?-zJI>9{uul^`00{xp8#yS%T@S$JJZpAP2t||u*Kh>3oqMmXq)~V_xt<H zwTJevg%<aIPMxV)TQS*i5WM*L_a`UKSBpP4A6|;Tde8n_+S9U$6614EBmXSzxh@u% zk`Qalulb(%CabY8LHhEAbMt@SvuiY$p_7xOq<rMutaPhhuisOD@m&;A9x*FC7|il6 zc;{ErEZivyazoE;%Bvx<GBILd$RmoESN?pSNp8?q*qL^HR)&4@=ZV69hg7l_t8?&@ zApbU=mA%uy1tb6dJh5bUjMTz2X<+TOzZy~v5soW>bze+iS!RlS<3PUE7*IZnX^n9* zC;KR!tbMBfOtjtR89b`q!Z+UJ)o{lDYo^RQfGq?02EoHepEF|xnB_rd(`>MPKIj}9 zBP}glog0VbwSj=<Oly0mT-@r?AD+b~&!ELgH;QNXn`zSbQa*@1hvmm*vvkNr%{HbL zfKx@mpb|wpb1c~e*1m9(-KMy?J-<q_L^H%6t)*VQ!?VznP^xBH@AAxzD3~C19EN3L z1hy1iBii}0e-_Op<p8@>ZIc^_cBT%Ufqp)jm%O&<P-4=+vqR*;uH~ESQKdojXX%;x zkQ;He-g<37wRENx*-3w~ZsBTXoO9{kKBphze8W1-RJN;^zmu1jQ;dKY2Uve>#>$Oy zQVil3a<!~nZ<t{y7JaO}1gDj#kq9GxZG*Ex97qcX(%Mup<oHERW6U{1*VxG%hm<2W z9Y@W7gAB)bhc8T-ZfP&DwM;k^yC}W^+9^_xZ#hXqPd{?^3RfCp7~!=ocjp{WZMb$g z*QC1&<u+2sbF5_e3eq5?B=6Ur+SHtl8GVeo7~f)uXHv}CTTF878nz^W-7zFptovmo zU$a3`p@nHUFLqF8&%wSd>urC}X%G(SwEuyQ+lw`;2C8N{&u*IZug}T3o0+mRf9<Vy zGK%7Bb^*1@ncnJ7#zQ2Nv2-{QY=&W~?s#e-xN6x975srK*+AbH9$F1N{TA@T<g~eS z*%9fdu1zJ9DI|;9u+U2<EvLin@|k-@$?JNceO@fH=S)*cp+9CDID>?j;Kvom=<;4f zj2KfxjHIDArIyAmHj<jjW@yAQji$-AXlc&@@9+pY>30}e$c9w|MEk$jPuK#RcTDRf zlI9p6pD#)@t~A`_%IN{2E(c8dM$ct~CI92f<Cyw-CqtH<tu4WOH!6`v<8tXl%r?n- zX~=S#bglrKI8hL1?_@>5DvfcU`Y&G85H);d<qa|Pr(fC<_UaDNRcK7Z@<?kPALj$} z60Lls5m8HzWJ_Zi$HAwTc&3($zOLRH1V(A!UZZ(u>%R1O$ma7gSF3C%lSZ9=&Mz$= zL_Hawt8!*p4H4B^oaA4S956gl>lOQa)}IO?&%}!*zK1Vf7iP9InxRE92n1UqogCz^ zvv<iR+ne6Cks4{hE89c^cc-M^JWoN>a{%ASo(~{p=(KEDYTT++R+DyhvMlErbTRaG z_!jOg>j6e03Sv0TvL7q*2?0y(saL`}S?chubinR$JQIJgWpQ}Dsz+hL*mYN)nj%9! zo4D7D@4d0~Y-!zpG5R!&zl6YOMBOy~r|I^C=k!XFS{zfKz_JWX*NEa<x`P4sP8kh+ zTMExUi76UW6AD`%1h5TZnb3y}DB-dWV!<0EqaD(P2+?qJOVf!u+oUACljo$t>FpEs z^2?SumZUDoV>dLfGPeD*@Gqyjc`JaES(FoUgZpchq^rv^--xc5;p4}^Qr7%Tdlox9 z0JrI7(ZY0}B)Q>PW@x@z=0+6KBcxn^Ujt9g`MQb@PwJ{uq07nJ6YptqB~rR9t2U4l zhS47b9(boc@%M6}E6Xqr^p_pKHIt!{4K|A!G7I$KkXSw-fSqECt~2;Qpp#|shDfBf ztt`7Z1u7V*JAXqP9VC~qOfoKxvF##Z2*mRcW<?D6{%c-yPxzFsbJWg(f7`RI0isgk zlgmcAx;-B%xu<ZjCao^6K{@I4>nr#!9&VC^<A}@uY?K)pvx@>H9V9Jpl8l3I#~7K2 zDA&BDr!iz9b(pDHG$Vx@_z<%R8eJrnzosK~m?pK;9!RIi%?~0kLg6jKO=k^-1Zp(B zwA<iqMl^5bKCRMoDjES=%roQlfO`>O$yUDTbaH}$YYdeCs5fuKhz9P|wO<HZ-VwDS z#+3W~@cy^a^Xu$+lKFFIgZvM2&fN1IZq~oAm;u(t?bOlx_5XW)@4t_x!Y`)7a4-(d zvL>)38^iMhSP~<#+p`M$?ANvpoD6yxS`E%>y9CHU%U3Co72z)<12%gXIo`rDaz0IZ z{qCl3iHR8BTc3pXZ}39yH5%C-eqC-+#=;MgFlj^?0z-oavd)k76a(u{;N(==<urw6 z@_XCm=ibWOv@572v@fsYo|l_<8K~i3>eIcgHpx+(4gbYYAeKAWw60!$^X>yCW}c{M z$qjAe=_3S(VG&kMA8?zS@eB3lEhLj{Cp+|8y#|)y7LyRXg%gloceGtR`EgS6v%>P{ zsO`V1w{twn;03|lxy%?XBffVq*kVUF8gPB$`=={~pUmw$^i26ixe%!Y_sFfqy6naL zlBLa7^OujcYKl)+zUnafWd63X<5>gB<WmQ({(aklnVPPbWrCW39fr=NlF~utXV&Sa zhdND7(?L%RI@+D`x?M~I!CGBF)lP;E{k_#B<_Rl+MJ6`YDBguZ$!f69`FW$Wup0 zc(&<Iy2X5xKAzDo)A3fI4%S={;AB~=Z?9=-zfLlm1TE0+^!9vGivl@a2VePh#S~-d z8kyvJ`I=*@Wduym5<oqXZ+XCQgmR;cvgeM~^LcL<Fi~O0W8L5Dk-t}GlJ`AJo3XNk zZ!8Zz^7nLPxgDHOm+5vsT;`)`C3Nu^e!(-P6<fuTK8CpLZDHa!M=iR<r#3P|0$CPz z^}(yKz{}l%sa8jhvFsh@$xqf6efMnZ%WG7S(0!t=oLom52`Sn<=lIat!0{qrWQ?c& zVn%DYB>uUR!!%!Xt9L+ThM1P(+kBA2T%;v9b#{hw!aCy9H@j(Jg*A;7VtoKp%{#a8 z4ZAECG3rC{lcGuXpqI0#2-mY^qnW_F`})9kOFjFF!FHS0woSY}%^>?G5ba;<guhtv zu_OaMQle>ZVihm3ih1U1MV$y9IbxIC$zxbwPvN_rkLvwvKR7Kb)h%05X|}noM8~}0 zX_-IEyt5OX#4`fC@*33EO6TQaNLmBg`__6deNElRlf1Z(b?BwP$C%QQdo0g0-*ANa z^w;LWdLMsB2;6RfM9yx8CsBdUQ0xOBH;GUfP_q_@4ou59(x<isMD7yAb_t?aG`4`M zWqld3g|CP38ht?BGNQ^PE8}Hf&eL7d)6DY#DIFnGaf?{|XgA-~_KMBf{J-#`LL1d3 z04$vYULq*^%b+<x4cgD_(Y_pspE*uHHJtCO73Zo67>dF8(*9YU;90%CCwnM7k!Nz_ z<$clPo?u?h3DB=#(7)jz-Eg9OI8oW2s60=HmNB44=OFfshs7M2JyI%;aI<LP=6kw? zk=-qe2e(qs)muEMv#`5WWG5jBl!6g&-}!}TdvNF00|^-SpRormU%gwhcqRg#MPS9F zZkN2n;C*db7y(dzi!L|$XfRvM=io+dLAt&f17+Lqo<7v|40@n=C~xCOUR%9)0{GyP znD_F$$0J3H=VVdl0`##fQPJ70x8L-+Q2AnOj;qDD(^k&)T{jxZX_fU{gb`O^mv9|Q zgzj)lU*fNP0&-6zi1pEBFc-?MpS|)!G?u<M&X=kpf0yQ+)ieT14RE9}wj*u>W4F$7 z|2kXt9;hh*YQ_<v=>*9x0xXWGum#k_+pF3Gk>P0yn;d8wL3u+48hl7)iGgh?RF49p zbR1A+#M!R|)m?(>Hb+#61KtKKSO6B?kO=&F{SrCEBpp2oK(uhA0mPeb<q`-bpJf1q zMtIiy2kJE_tCKOOKvG|Fz#4)6dH?6dQ?AxL@#Vh`0#lI2bB8}Pum6^09hzp>_)hDO zSbM`sMs2*>>U{hp$RtWw@H%q;oA|%qr0(Cm{NJ1F$l7U3n>diR(X?~s5Db$chwj%+ z;(0eaIhHB3UA=<83Vw`pciaLQ`b#F&LmRL`ohO<G$2id<-)dkiBcnvC3$(YIN1s#_ z&0#)OF-`Q|iumeGe@V)7vCs@h3OU81_;QC<T)5t~U!O95xs8}@lD<Kmzx@w2d-?aj zAj{v(KO$=Oi6g-|@B3DT2}>e*)whqf+8zeL{2yx8@Jqi0;l#t_%WLI{d$Q#EFH`Xg z3ZsRhG*i>%`-;5>i_r%DNVD6+Eg^^g+CRK77jQ^@Anog>Re!JLiMd9Hulm0%UKcf= z`}u2OF7k=6#_wLp`*v`U;rwlKM`Gj2A=lg-EYz#5f*s}tk&RBluM%J9?J>XBQ&83W z;rN5Zw}>C_M-P@XlS>;5OYF~jRh#)K4om4Ao>6qj+1Zd<7tclNg$(Es3m)uL*(8C) zW2~zD8Y0%_qaWQhZuCrf+Lfcw3h%?8>h0e1#<=?acI;Mmzi(^sxx^!DmEQ5!F8<s7 zp|zpE5&}S(Qvm-_{beymUjIYQ7Ma?=evmvQ{7p?fn_oB5I&}NiUl%?mWGEdFvt8FU zc#LPkZOLzS6a(}IGVe#=5A5L+b~bTcvjerPLd4ZtZ3uD_p8!XOMv0=K=d$Ip)O<Nw z8Acz4W1rI%2<4<qrGR2$t}aerUcudjC|_#Ms~A17_f^H4D;`6&PD;N1<Gu=qd$vkF zP2`;Nt8n9JzsY3IobHqrKh|&R-AevfZ(D9&=i}okM{l7WzHLOPI|Bclxe-%$^vSf- z!g`kG<=^*5%l2H$c9IK#P_-2kwB(pK4mbF0UON;I)Ga^6_&I<5MCSdGN;1+1k#i)O zet0qPgbPzz=Wji}yw_|WSV~)YKq_ayn2%Ggl6xRl#uZZGtUz39JG^o%zF=V`DE4F< z5wn31BNBD7;fij>1HAkMo^6Ai#bV%kx6KejJD(s%6)VAq7jwnr-ErI#h=X`$HiIq1 z*GcM?;n%X6N+#a0w3pdB#qRRsIHe;&GmX`86U%1~In<B4Zp2l8&QKElz?;fJ%DEXQ zg9%f^nBX|-Pru+Oc1HQJ-0=$KWA=l?C`#`5@Md_EnO$`KnF9~XZ?Q9jP?SrI#(^)0 z?lBF3-2q<iJ+92Lt@d$~f8QJTxQFH$T*ELxvi8VO$*$q=s#_w=kS_{y0-R3Enokqx zl45$l>8fejqU)r;fC)vTM~R85t((luN2Z@hXPjDb4SA0pZH8p_O<?Nt=X^}HGv@qg zSQh8RHb<OeC23CsA~@>6{>*LcY1t%#cDB*v7;o3eM4w;m3DaktRqYbeFYTCYZIYnx z?meyh_5RKw^Rs&fB~JX_Fe@2VI8<#Psqt<3#LGY5SAPt-d;L1j75kSV>R0yrNHIw+ zsuoB;7G6NlUh!ZcsM0b1PV$s7h~bbN#36fKxf4J)lX(R_p~ok!^|_jp<fNr?aOv2x zX<c_@t|Nz}@TqTT56&m+K(VuYX|WS4E)jwOuus930P^lkX;;bi5L<n!<Wa6#3jK}h z5GGSsV3vC}-$}ziU*2JwTAtJvrtazQtfR%2Kp}`Herf>~8gUsmh)Jt>QFzhater4a zqHx!JIL;SaSopaat!kKMW!-3S(jJV|pL3bYB^E~_)}u#gLLCz{>VTVaap~2r26j(M z9x<*|M9psOCH@?D_6n6}alpmy7|{fhdZixy3S(I!>5U7O&!2Wyo3EA74_uWoiz32E z1W~IRI;8N-^F0Gp(F`vEy^a)j*d!K4m9o$`$DGxbi5Ygk1p$$1N=lcuS*U7a^~P_Y zyg3J;(eO1{d5mK>cmJTqE?q*o_?G?43dVyi4#*w(1_n@_R);9o?hEG;<tnGsUmLoc zyT2-$Y;x51Dyti<ixTSQ`sn+!r9|s{HA0YhaSyQps~&yefV8hweivL;o2OV?oaKmN zHd@_$t7%=5OQmd=I&^1Sfui6zoR->bR3<_gG?O2UXO)g%7EJ4W3Ze;Ns(#`Ei^k6| zhL^U=LahO9$wwxs+DYSZwS>L<s<TzQDB?_Wark|v;?IVgPHWW2U%d1}BVu#KYVDeB zt-kK5a%Njq-x0O)wsZrX@3sCvSvrzcd;j&XNB?Qs(zq)JkEO+hFC!rq8pwi>0hkH| zHA18TVH9WI?)}LhVyUruY|E^k?r!5#S2{~CMS%er;<~1y*_Gt9p^l>o8TtsKv_l#Z z78uCaZYAf~BDK&(*={x~3>Tx)=$z9TIhEU8(AX_46`J`$l@Csubvt3YlRi@C&)1a$ zGhED$hkqgm&KA9C(lPoVmv^R|B@Fo&(c5><?w<A56+ukPy6XEj*F=rULJ0*o{CnKN zM0%$>%!W_;=PfRaQC}UKkHpUj+N@iEYl`5=VV%VhOV@ls(c5UQm4-j-K2Z;V2BX@$ zH+(T)x{kw0GA+nVYb`nPgoZlR#}wBhAO{vf7K`-}wdukpS{cV5edMcrcp|X<#_{|d zjc}Kzc-(4^o^7<^o9UrziAh;Tq5|wR{HDffKo0&BP?qKH+^}l_NheABN*3_F)WW14 zn<rEkn=-9xd|<(2Mp(Xkg|R#{FU)xsTlF#NmcG_W&7#Wro7cvSnI$oY?^Q0`4d^D- z#lTMw0o%Qb{YULw^8<xCAi2gIUd}mAhDPwJTv61h-UFa)Vjl}_bl{+7cRRHIBT1zn z_r;WH1`7}{l^*mB<CyG~1!e7p=0EeMmwaHZc0MR>)9`}@@B9;p^%tGBsm9xPJAyXV zUVge{WAgDu{6!1jS%90(gDge|b&|w#?diJtaIiQO;DmjEbd5fAY=t6NTdS~^oJ*p1 zg<Tlv!kXSUv6iv$?+;qIb~>5I9eg)eb8T(deWbBqwfH1H5!IOT!4xS8IW?!nWb{ES z%RVFi3JXV#OJ-WsnSHUkTd(qwCgITGEStuuZ=q-CS{^Qu5n{9)PyQwC9$`0!FLqG+ zFK5_9!{Mmg87CnIAlcj0IFK~>>BgrEFZ;|&ec-2&DUMko!v+W0Qcn>?DO&;qb&kB{ zG^DLDtutD~GboJf108Bz>V+78fJWl$UjP8E=DHpEHB~D}?&f*thUy<rpVWM>S01%Y zH^_;?*Q4$dZd+YwhuwU7NoyQ8Vo~}T8Yu`xE%qoRztg!9LDL?czjeu~?L-(?HikT1 z`=7agKO#&ItaW?ue?Mo6E*&u(Qij&J8XJI{?ftn>Y7|m#<*<}jx|7CsZ5H)c_E-ET z<ln|f>oHVWQS&wS!t9f7UvDi9vV#^vOScVZjQDenr}>2;mzk?{4yf9NMeqpd2%>5t z_hazAPeOxY(9u&drP!aBfXFiH&ZSjlnU5-ESd_o#oAgh}QpRt9Aesq8B>`hFJPdLh zB%)@opPo|`Mcx|F2sV6YkF-}UWk3KAWhuI{TmD&9|L+sGq2M)w>`yP&@;8MadGfow z4gO*qe%ufY<Y<t9d(-ZyL=e$+7`Y)46e=qNG((7ghP%07YpC1_#^L|O#c~O-f0~qn zx$6Gxij7tDbB0<6_|OGnR5kWF<g)_NOwq7e|08#{1&b^svMxN?_nZ9P`Lhz$Oc^eY z3c0(c>~$!RA-5wgCc1qNVdR4tdpd{;jZtW$5;YF=mC*<L@OIRV1Ox*HptooUPg5s~ zxhln8<Drbv+gqr?&uZ6cn%{{&-+@{lGXHMXhc%K<cmc%zp-AHys$JAx5<|nBAsoZ1 zbLvqIFv)&7G|(IqTZA4h(Zqm|t*@1}HsMQbWS18PYp!+T9{MSxGwQbVN}c+7Gg)6Y zYJ#EGV63Lg&aKf`t((F~zJ={c+;jBHw_@&WB3q*lBj3VBCARKKFyDLewkCigjiUhV z0Ak7jN*Auk?sX@Jh5neJ@x{m6>kuT_+~DTy=rt}Xll>!Ipqk57DW~o>elg^lYwZ95 zzF5Q;48n`8G{n}l&O@C8s#H={0#?xz5*jh9I`Ja1lemZ9VJiGHt7SQbI!9F7p@^Yc z4Ta`rXFAZp+OQ7dgnwqq_K>P2L+1t2`x;OMa=^^C(*j7C+iug)aYvtHtE4}%@bSY8 zvo`<&l?$sV4qx4sk?X&@KbW}l-P|hK!iacAxs@o1UuDJ38m4yQPn0lSKOtMWO1=yY zdoD7Ei;p8l{WpWZ+quWjObw5fp64p%GMcl$+6{k&|0L>hz^d5^XnTf6gEsaw!*tYQ zzxJ%k5Yci7tGr?1_>7FkYN>x0h~6ONoz6)lK1Y)r<>paJ;#$_(n<8p-aaASJ#73cu z6j|i6wW{%a75)33YQ8qMhD&mpSF_6I7aO32=h%iWr<{+@zo|2`7n78@)9Dhu1Fvtl zyvI;TC!k~4Dk*WUv6k+p(b_?s$TG&G0Dt$ZWm1uBl_fUrJyqFg6Iq&c;BFZmHoFr- z{?_0HUugS1i}1Ra<mK({p&iA{=Aw!j9>+_(UX*EFThsWDp-yLO7L`5P-tqocHeb2Z zR2pMgLH+hUiHu#-{Ev%y>;LV0hkc(Vd2rrS%F5R;TDgVjHq2IPp(5M7d?l287+h@6 zj*m;SziqewUM<x~tQfymBb2))Gw&~@gmg^~h(1iFF8F`N!M+GoYq&`3Zvj8b;Ct!< zauxy@$%n#-YIPWmi>q#zzXgu^2MV?80`ruDUM3lxe*)>6b-O<kG-&l`+fr1_=<$Q7 zX%uIfgWctw368%Sq<Qstv_E>E)_5z>kF~11x^V2pVgIa!z^}<R>;9U%tC|ss>ie&H z3$GqOL8GF2sOsOv6&CH_3uGlQK%Od=LsSj13Vo;)3KUR@JyhEOo8biXH>%MgY_t0( zPq%;*Ka_lrSzBEvp}(><$RpU>mJxTqos2vjDNH0{N$3=#?<@0>qgLT1%HQ?}L>HtO z{OpXrcrEg!QcQDC4AwX3=Cu<*I{c>9{`SQaFN;q;dJ;2kttD?2J7axnA?4I^#R zPpw+VKI(~kqlo2yJN?-@{##1C@MllFh@%49(8N<|QoS_c;?C=9F*eMD_a<rTKN7Gu ziF;BL^?MV)DkmuPM%$3kOm>3tk26G@B$w2r13ymJ=c6p1M!lJTUD}g;{6{j?Cgo&m zN_20^sUIl`HmN6ngt1_N-`M1;fPnRsw4C0wf*)xmPtzEwXT{r-q*Q`6ub;h{dhTb+ zxw}8kwcDKUPCb9W_x#|G^IV$?!>Jd>doN7=xG-ZQYKwhwx%dB2v#FQf_Fnq%<I-oF z%imHj|Lnc|=f`DH;-q*QU8;``-=)jp8A@sY4>g;{)bC>&?=sEsEUPq@Z6C{FSCpQX z?vj>%pf6qMy_@cX&p4cxakNjQt!Gg2nJ3dSqx&*X?Pez6vy#)Y&h}-A`gi~T)NEgN z!ESa*n!SWxPDPqSo!qSN-8TVkIahYWq2USv|I>g`ytzDgct&%FO^~?__ri)$?}YyH zoa;P{<9pfLwa-ddQFP0Ki-Bk*@hHb>vlYSRIx4D|9s9N~OG-Y<>Mrs&QEr9)3{YFd zwJy#GoSQ`6A496voj$I9G`oaqn!KvI0+6fZqG&x)rl{<Dt{B8wrIc0W4J0ZtMHJ^P zy)~^=`}k@B{!^EMQXsWRzrsH1Y&JX2l(nkbxUKpzsqnmQ*3B0C$=xzP)c&HgS;8ZS zD%imL@?$D>tK-(+E8=%WRmGS<tWwf_a;s}q^b#3Jp?I5mY1gS9k($k~s6M(|=wJo! zo-BJNP!3#0{{DP)^=O6-XbkxSTY^>X<0`ID6uf}9fBnpyTi=;)8x`XzS~Kz^EB;dX zmGL3vk!0P<ia@q<t1f=&b=^pbuQ#f3Rd$7<nndhwL^k;J>1(Y~Z!Xu$RhB9(R2;8N zr`k!X1;Dk>)jh(iPH0!1smyTuhAIQ9q_FD;Z`%i<GV~>ji<VzAVKD(y4Y%4*wAGK~ z)QtD5s^yG4Q@daZW}`Rt+A+K)fG)R9K{j$<|Fc{Yo%}<mGGCn8bZ9qK=tPvEN2xbq zpDEh~|L|?DsB8{O(|$))Co$j<Zf8^3RduVgd(L<0_jedSJMQ?I{m4nBnyX3<x;a{u zVbiNpMpWAn9ck*-D?f{_vpt_FdztR*IeETkkDB5Fts6Srl6pTwf9y^m11?5I_RQN4 zd3RU;=quTG|LU_ur;<lnsHSd%8X*1P<?S*0F}2yls1&S8?|BumI_0*4Zq(JD@&19S zV?E*}v2$cp9ivSsXzjPkuzflkf>X@&@DAjvTVg9Mx#}dYVzs%_zJ&XtSRDL0=S0b) zws)PUfB>3m`iHa!AFM^6RZ3yNC9xX6Z?{amn{*{A9i*yq_^QHbZ<PN%`-s%&<kVsH zYpF+n50?ZCQ!k7p*eI$mVgX|<;-LdrUYJYy87WfpQ=-Dis=Pl?N5a!?#7JF0&E;Vg zHmM3J*p)J_N;qvGXF;n;sb}GA%pf`<`moojX8|`Wy^bHNsOKsMP>b$URWqlNxyQQG z4AL(Xv0bZ*6S*oK3~8NJ)g~hAi?2!{&|bv9R}NIT0@a;KYWVXU&C=|9y3bpwA5z%L zmQ$+oM%)MH-KrJLM?UCs#@Edbg+=OyYLmj3qtQ3LFf`)OajLp?nY<NIxst2Y!bQ?> zIae#x4jv6_09x9m%i3)y;$79Q#XmL-^vT{)6mS)Ut_-!03ekG$a3oQ!X7$-YG%Ei| z{#8}`S%${#F$Dot!F&c)OO?FwYeHwO`EYqu_vCC78|g)q2eGAV1(dZ{)U{WV{$Yqv zww9C30hgcj;Terxh6ZjGJxxT%VO2_rekxJztbgwsPj&w(kC8vHf*hRu9V4%J+%ArG zwdClF@i6ZMMp$Va#Ttuzgl$pv`-;aRq#=9oqHGTA3-u-PxSZB)>`Dw)3wiii3j^LH zQ0~H_(7w-9zK0cY0XA~hCtj#GN?x>EMa}D|9&||?R!&!XMgI4&*7w<Nad*`T>b|QO zc>)Q2P<J6h7n#HeTjHX=2qZO<!lD>zLj8G0&OGFO87idB-m+V@9IMhykZA(8xVQ`` zov7>|L_KG`=TQ~MRzs05@{bq2*oSPqM@1!ZNAG$~SbHl^r^`MLIRsOc3$G~Y-V#ar zbUR)7vRX<fajq_oS@liJ=#=UrQ9k>h?P0d6tN07!(BG4RE7CXKPed-p{!#U~kp8n% z13*x4rK($+IBWB;5e(E4R<2M0r>}#JO{)KtKSI|<ei!@h6RO@ooZk0>F1o8+$i$Z4 z`(4IXU1Izwp~J03-<*#Etf`1HHp@lurxBG$c~biVB$zmCm-vNumf71}VSVIDos?G^ zPDIV>cvjlynBSbZYIN+u1)-Eh<79>9rx(vspVT-2?zSo#j7}`Ir;nGuc+h=XxeRxA zX`xbFP~H)py<!QC@LKM;8w}O3fNVXri)EB;Cv+cNY!4HUesB?L(<-87-)BCTpdY_K zc;RPIRkGn?OVFX5yHJ<S(F$T|)A94ajh60GxE==J*G84C$5$$6_Su*`*GsGlj((;z zwQPDa<$qJNao2zCeDHr0S!5U667`Cg+!EYl;~^h?%sO_toi$Te5z{&De<ovIsrB18 z&*$AXw({*&*0CS9{)d{)8jL^T2&hg^I}6slq_~Hih}KVZyezjTgqJ?U=F9jam=k6z z*?!(ueO}7>Byp^T5N7evUUA0mEyu6KzP?W(H@daq`y*4a8*ZUFx;2td9RQQFMVb*U zbx%W<%ZAJFG4Kr7nThfa54BvH!jw6H9N|?mqSLhy)Vb?>$RLD}kc%%BwN@(B3&}Zo zE&1jxS;xE1^6nST4am8R@=u-eEclxp0Vbp66{BjQX(diF8fgN)Oq`_Fl-*XapSOwI zVOL+vX+fQ*^YcD%5MH(PHQRauU#}W_v`1+!pzM??3<q8{pKR>Q_lRk3tO>e(>vroz z%$?h%>H1#n*M_3+R>#=R8vI?$l2Q!KA3u()Zo4vN{HUY>W;yqJX2iS~z@N07J-82M z&VrorGU*7f7kX=X3}Df;zCzE__l-aEWkZI(U!4k>4V?2VaaOMIvYsjHd>q(HlOI?6 zM&%G88urAoo~@QM1wKz?x|(m5b(A(4J}*9V&}BWp&SP)qR_Kb!oPE7lHVAbfaa{MW zxG&9|mf<f=W$NM<lknD?o>P6lGc8OO06|lB^E!PpHt%<glKys;xR^BS@y5_{#(f{$ zYL;}yq97UHk)OO66hHNa80!s9S(<CJip{ZBPtP-c9zH9rANqSG7r(qy3QLyoiEPr( z#?*OR4ON5E1Pfl;g((ZTGoCA*;hi@SB`w<Us*_coXI}+<x$@L(j%MX;!a4*dEG@d9 zFX*a_JuQU)y_G!&+nbnzAwkfam{I+|Tl{vd7SlEEzNQ?T%Xf`BjxVxbAG0Vj*lY=% zFsZI++_$Nj2mhWJmUsNz_X9`x1y;{#e^GWb^6DS&uI>Krq+J{jlrdtuGqZIrbA%FF z38FH6bc}!dWu;R_J{fzu*wR293=kMa0KfipDS=W8{whI)klK_V(lf<Pv$?Q{HkCmP zM8a{57&-|`N5iV6y!G<@2=#jF%q6?&gskK;C$;xukU9brk)b#oRJc5>8-Nklkxa;T z7US0-SCRZ>lJYA-`qAJ7cywQM;<Y<<N|Ecbm$#f1Y$TZ~4<$!%xe56vyh!pLlnfQ& z5CJ5CAc!Ri!0-l+IMJP{)IxK$D4of3LW*cna;8ZX8+u(*LT7>_%7v=UBW~7fW|2oM zAXw<xNfL@hV|m4tf=#vo5~l?WtR-8@4s%lTBnB)WM;EhLq8lE*?;&qg3x+n`G>$y_ z2<l%8gr^a}ilV|P9S#76BZy_{)4>D*U@}-&%%c_<b&ViCYebZmk;*YD1Ih<-B5Znd zGR(6rs!w9}N<GeboOJuljW=an>3^i2q_uLyKI?F$w{o7Gf7dB>xyjYCkO4KG0jZE4 zi8-XqsC7_d3?)z_H~_7H3L|9`06hIbHavFopxRvEuz?s>!hlQ^W}mlnvFZW?P9aA3 z36AEO8=cfr&U9{+VCw^Nwfw3=5^h<JyLlX1^{K51RVEzIAm^z1*J~{_9q?uwg>&a` zd4S3DOU`N=Z7g*d7wnBBAwldMKT(0ovR<rp0~UVNoz>Kd$<+VnHZ*FCsj*W&YR_Xl zrG@hp>gibqn^gbZ0-#)2loNV|lRjilmCE&Qft3T&Q+sB?Z}MM(%;`rV&l7=|+E<cf zIuk7lM_C6t!6qr-c>}JjN1zi{26$|#M;pDq3po{^XW##Bu{G(#srVV9Y^qp++S@j= zZ6CKFv0=S$%sb0&7I=J9zE^2)OKY;QCpWM~OX<1rLu;xNSNhWft+Wl}c!S{fykJQw z0EggnPNqXO*bA&)BZ{zPc3d?$m7%xLmWj!yW%{)^sZ|lu_0P!_Q1T~`<AEbq(!GTu z>9RpbX-L1iL^hcKl)iz;vN+AnKZ%J(iF2EC4&|>Y-bouaI^CXk0=ABPls017nvnax zBR?E=dUS3VT_jQiFi=z+`$~X+rY|CP!&B|4q`3A5C0&We0jnUnlA*Qfdg)l%l1+1c z5$YQ<rlmeDfLQ(F%B1M6-DM+(FyCoe#^F@Si-A1(x>}~8fFOPe@k)KVIL9j;2-&|4 zl#LOHX#}#xjS)PRKr&dFLxGot@P#oJB~NKXVRKd2vTlu<6{V*CQg6u2YWDV)O)LYe zz2#(<-(z<bIEOE8m3QAgH3$s~G>x^I%h+jk`zP2^TV>{*S#9B9XSjC1>S&Xzd7)2l z%wY*sB^Y3#HI%R9xE^M@M`hoo&#>cdq3RXWLw1+gc`aUQC=u>p+{DQ|yj7?Aq%Fe` z)?XOfa&ib;MK&)pl8J3$^4tL|beCLC{8hfHC@uGhbACS4{=%B#y}n`7!q54!7uM0A z`bHgPz7(IRzNKyJYUY|;7U39(Kd3CG)PPHuS)zmC9J*u+8iYuv05vFtC!e~OYfUjg zjWIgJ1S94i5~^0SU&8*K(5^5c4K$zPFlxWH`pmEDm-?YYS%HH!h3y(gGKu}&%QI@m z5orF?CQzpN?0)!h`!dvoyEiV==f^yLUB};OHYlH%__b;C*~qlGarXP1qz$I`liEV3 zW;Wba<QTWKL9A43daZG?sxyJ9q<o+JV~Sy_eeatvOKo5s3`x=>t=j5fh|ZHom%ex1 z8~hMo^zZZcmwpU<8vHnQ(vXbxQ1NTeEX^5l2&HK&Rgs7Okv!(3J4u1$++f0599eqr zDPUI|50O7Drr$;UofySZ-N57=9%Cx8C0(oosj)}h8Wtn(J-llb2|W&=d-v52`@|5T zd;x5dpf8SxEz^W_b{(u+J`KL9%#wgfabeT7@QXL$?SNDBK8hkoi-M8bzfP7ap@?+1 z{h>qz>AddVbCWd8B27Ax2Ju}K%Pux8!lJIMp0{mc?Hgk`Y_j$vRn}-w`d)=bp6(+G z{EwAoSXOXfoAi@W$plVdo=b+v)AYgx#wtt44_ml`so%)58J%_#;8;mN*3)g6P6S-s z3=V2afdk=>$QBc#aA#PecsVL|40di4HpZbF&0sEV(pl~*TL?ytuf<z|)Wj`lUz`3I z8MZ<@C(fnxticvJM&q^68go<KFhjTv%tP6w2_umfDwa=|Zl~Z&%@BI)x%VXV+VzBa zo$h(vQF*=DdH2)I0fcl~!i7b|=?3`=^>t9GlJrrV;7J^moEDff9Ozdb7)Eof;@CHC z!$h0y4hrz)YtX$CuzC=Ehz#wUChqOUn0<vl2EdNWWshyABwhD23-BA~z{be=>Dfhn zAlRc?SVk7~eXVpwn@l?<b)t>Iq)V`i(-(aAXpO<o%|RMDXSEv>_RZ^$%)&ChLbL^7 zLxOl-yOb<MuLTMFHv^`XRjS`yYB*kMj7p?2Owv}R^V@8yilzN5EFa=6eZg??9-Hh} z`2~9lF1JZdMM}4{L0#)*h!)n$im-<O`Y=Elz#;#Px_ZP`!-@}IqX@}U00YQbcs>9! zP!gs~%y~+2TqNk3QxiKm(p%H8c!4-&8WM?d_Ai#aLBr6Qc<^V|VAfTJzI-qUkW0(R z6)(spT(QiN^oxolp(Jt<>dh4CpB-fj1o&(yaTov}q9sZ<LVL8z>km}6CZMwGvL__S z{5B~{ZSf<7fi4j>#kPSgLZ>m6hD4N)8T4^2{LVJStybb4LYhgr?n)46O-t?lhMdD# zq<_i6mQ?kc%lGgMv{*Nmn{Oy+AzDHW`)zfq5)t$I@-L%nrte>y&8b<}uX!g`^ZIDb z+XGq-7M61q>HTNR{csR3G9{N#(M&JspK+KLz?5}_T74MB>F;rCK9%rywXG$HKTFxB zicVd%P`03wy$yRpN9Z$PUls_92!=G)FeVi?D1dDdVBB$uW{T`9a&;s{%$*>f#*yr# z`AXK|1k1$%TJre$Q&iEa4Vd*|5vH+jrpktUPBeJGYw%LFpQATS5mJ@s(bEE`va|ke zd6?-p-?{Jg`-9~1;qrJL284PlDpx-|$RrJ$-bIE@&|pvdWEvtZ9l)`KQWS@l$ZxA1 z{Zh*?XzC!U*V;hWXfpNNd(Vf$XB*|UHqp7!(!<kdb$-c9v2`Xe>0Fd}NiqD+TzEbW zqMacYhmp8JhH4$P1JD%NBz1A35Ebz2kncITXH0Co75tV!=D~{8N1W7coYX_r7LGy7 zut&@7TB-hbGK24AP@e-DX|Za+oBeGl>-Fq{w3}1xyHAnuIa>Y<&Te!mtRCDt2WlP6 zY%S2sFWk)T={W6Q=9IdQiIN7akyWG{DfPTteK@SZwn-@6*2&d3y$QY3CSoY1nm7=4 z8|=D@!JBb?7bbKHQ8$e-MdY=AorPA~X_L2&Z_rJ<4P-<vYaH$R__*Y)TAvl5-V=f7 zTr=P)$VoKb;RV@$#mST-RDDv9`S%`kgmyhRX}0gYy<KcqO@Ms`O{Q}DP9@^_TYB*G zE2ikLEpFr5>|$v)L0B-aM?K!(9b`zIjJz^UfJa31_<F+Kuk<)7?3eO|jT7LsD(E=f zAlVc8w@)eXPVf1=tMl47CyPyMXc8+3>6!K3tg3WGwDf_rzJl|86YVOkPMSH>(!9^e zOQk-glxpogzE?&i@8Dwhvt+JNl5N$J_j}6h)Jo6nv7AEaZ`H!1mHXQa`@22++YRq( znA;zEFVpOLq<%Yk9U!&r4>6>RV$|Sc0{7499-iBQ1>%D<Y6XFPVqxS!kbmIvGf2h) zqzxn0HZ3K11ZC3$HVok{^egyg%kgfNzsaTVhkHL8J`8ApFDl`0v`Ht^ByMxyx7wt> zLpi#ZP;j`=9~j4hOp4@E=^U~q2_e~pfp!*?=uWVC0{nx7uYVi(BpH02E|o%n^xTx5 zV97kMmFXvhG$TUfzdsZ{lcIm+3Ew|tX!9-X`7ToUgW@SwgpMj&V2UpI@guP(Y6b9l z$oDYE7(~m>_t9Ur;oVBfF9lNN0;v=$>41Eh8`DyoG-(D|GQN}QOc2{UeH0_o1!yDM z<dJSMQ1$T9y@1h#3!pGcWb%O6uBF(UE)Z!NC}Owo6hl8|L%-WS%!nHc>~OKEb&D7p zySxE15rEe$#d3q)uEvdDP8u(WbG^6$EcGA1oIcLpa;dv8{?~=^v@(zZ1#Cb8s33%5 z0n={8VvrF5EF!ND217D22UP_iSn)acVxYZ9(*^)Fi$P}^4x~6Ah#HzqOLwb;O+E5D zaG>}AFzitNRSzB9NmBvPl;-v_PJHr$#8kd(nxz<t1|F>j$x{Hbg2#Bk6Ny?;nKpP2 z;mL7|L`tpr&g7FHUf|<2@dBDS*n1lMLL5&MH=v6f)IPStxfvA$_j3Ts|Fb%nL5V!= zVj$msQezs>oi5ogfK4FCS#h&_y|uozSrm!FbU!Gi9Ef{`4029(bQ-35)8|3`+`fW2 zJX~*uQVy|Jw!0z9_Ly~>nsdH5ulfzPfaq_fNS_6WM_|Ohklnw~gfcsT<6Mi*RvJ!f zHmtNwDjy?>$q+NQbG~8d+c>e9$bke6NSPW1+~Pp#U(<az4>l<douUL*BA(trqzp{Q zw9z1m1j$H@xae<W8hP8l7JTEFxG4Z+O9vv`z@RgGQ|k^9EWwe}%LKu4Bzdv^&;E4s zVzaA^0t4QB<H4afD?x6uO%X9Q%Cg@1T{ebYem1hA7-r%wR1f}~Ypmv!rYPY9V~<K} z?81h(E#4GMElk6@$uLeEu9fuS=~?K5Hdt1-^c><`jl9<4sTUH!f4VtDwu0P)HmPmE zz^H<(pba82nng7GIl5#A&GeF-&))z*__O(<&&Vm7X#J}#mCunBH<6HP6<~+&ySIVW zH~?51ut@3X+z&7y1%j$sbqW`=F9zCSa7f%4>nvb^?uaf<G7$h_QUss0rA+^0xUx(~ zufkozGEZjX=;o9++NJO5A(F2|;77=JmAj3f8$2gaPv#n8#v6GbHVz$Bk?Cff=Sj~H z;L&{e4o%`?Exe@|hJGM_IFxv<Q!Jr4{V_pr+e3bw0(*;xKSjt**Gh?8+b%2FZMw|c zHo5qpRSZ!jJX6yH0f{e`sH~N`LxXl=oZj<Qo`Yf$*88bTvgV4?mnnmb|4PJ0NQc$$ z3%VeEgRmKofG}mm-N^6aonD?TmS9W^rK_hE_Z3F0pNaEV+W$_^957~{(`n$wfX@GE zD_hlf`Qj^Xrf+IBYwCiESHV8|NS4V^UqM-zS-}1lKw$^&kqbX8Uy`>@u*N1p7ZRW= zg2neVs0$a-R}0?|NZqF6?f?J<k<H$h{GKQuS)@p3DM=9LvO5zS<#JJvX)xMH=?>hR z<idrWZ3np-SYm3bn;HB=sp(X)G(~G~<0Va7k@Skw{0!7QaZ@V4R_X@gi)p@O3<j(Y z0AVPgy$Fb(KwQ=Fod;cW7yD98S@UG5?p+S-@975f(11Q#VlNpwMC%<b*c$(vzS6qm z`Kk8p=a6qW_{cN{Ko(6Cg_2Ou_-{z1f^rQ08Fgyg=n1FRfC>}qmiajcxs0*g>n2Za zX9Mr)RpMkJmt{5q@ckd9!{*TbNr_$4(1mG}^T7T@o6pA=O}EW-&tf1Vn^unoiWvZT z;YOTs;@fh2KT~%j5?>YK_ph|=KY6ll-oaq>Zfw|-om)k}Sh*%IWB_+Kk~g)D*J$TX zkF)37+1X!6H5l2dX;iNO7JA59r$i@?jUMJWT*eTxr!7i+zE@B&a>VU3pY+l`&Oh#i zai-A{B`2bSu6~hLzK<inkwniRb}umCLC*+*c=3u>$=0d}i^rS)A6@Sm)x;aV>rN_x zB#_XnCP)d@fOJul(1H}{(xrD4P-&uuKtd=&C;|d%C?Z{|0-{oa1Ox>H1S~&L5Cl}P zcTV;>YoGsFd#&>=pJvUQ%*xC>?|om_h_d_wn;A(~?-l;?5DmPP6crc10MK1wCHKiC za=M^|cF_FfvKb4jY+vI(_1YpwM*rl>d_Lzv$~Sk%%D9c0T5^<<YokF_=|I?|TaTyJ zsfs@P+0OSHFm!1<bFB1T!|e~pD%4}$JiHPnF4vzaeCyvUDDqM-x+NY4fsbF|`uPuS z1U$^C*FQNMf~U;XqQ$yx|NY7AdbFq)F+&5z{6x-c^$%Q-(1_o1Zwu-vO$vH3zZ1yI zS3Xwjy%4v0?mI9OIE)xwJFr+Qb07sJqnmp3*nvW8=gWODh0{H8H|&n<g+92T_U2{z zoe!Q5IENZl?5Fms=t?WgK1<niD8aq!)vs05`apZYaQv`EyzJAe@X%(8`0hyb3!~V7 zHPc<W<>y*_QekiGTDOA#{QUZH?Z5waF9Hg$1!yN)+8&lgw&>KBGK-VoWxaFx!PjC; zuULtB#Mj$t2zN}!NJY2D1z&d7OARfGB@R@JsLhbfvC!uF+KQ?wkGG|jaZ1@uf&E@L z>mq_yLW;Y_&P8S_FC9H~$fvd^L?NQ;ib&}PaObC^njJH7Hrii*uRQ{RO7r-x8MVl+ zVIj{DnbczP+bf|l#v!T+OR4W`9bGCj_8j{8!uhhJ<&IKC>|p+y{Q3p&wQi$Q>U6Ww zJOwHn#$2f_vFS;LJ6rFDRW~asSbWU0vki~Cy0_7vso|X?7-HwXuodUF>lxYg)y?~K za9yJp$9h;IHa<3^;`CdcZ|*_MsTtSKyb{Z}?H!YEpe1wGdbQ4S`DmP%V-I7q+2~<u z<YgD91(<7bZIb1c6ToMi<B4xBC-^3BHjm4O(54;C7k}NjbQN75&g@K|4-#@sFHag1 zXUZ8c4ALE41;%jANh()@0HcS#xd*@f2xM=*4BdO-hfLB+!B^0dO|jSGrl5--bbbaE z*<4H73v7)pa4raKj9j~Rwk32eHEhonP65osB&fDL{#SV2+VB<5Mbs}RPGj|4a%9Wh zZ@(g2ha}HMwLdcW9o6~N?OgQj=kdRzyWbR_JK4K=`}fJd&vWNa-T(dV_bDy@bR{Kb z5NY@)rnzwsHIyrt@F$kHuOuaIOyiFCK2u<FEAH{Z@1|9iH&sk=|6@=C04U#}*7yH4 zsHr#t1R`~kBq1j&{r_uFBRDsBj}|BiWFcWH;)D3C)MBI48!tvXZa%qAN)u8zT2v(f zh$HUzw~Es+C|RR)?0k?Pn2uHnigxI1e0IxkC`-ZScGDyrtt9S(5hFoh65SE!53(uK zQ16M2myhn;`tJb^ax=wao4)kF4QeA`VIhPjZUF>-R16{&YbGtNf)OfKd+sHD37xL9 zxvo92cxK}n``9h!rJk<$i=D1(mWK`+ynofFfZS`}*S+(GSEzB~vFSDdJlSt~$B3^r z*q9VVO+ID=U$&k!^CzhHeg1seeytjC>hb-1zrW``y_m7zjd2M0zP|b2lieT?1OZ4d z(Ev&665n#i!hsPEaM@tA$vlS!(WNdkP;PaVH0hJ2e94{Xk7br3*u5V#37b4F^mY3* zKNdesc#|VuUkZ2`y{&tbYx=EpA6(%Kk;0~k$|%7NU;miP4b!>urr_8HBDl!jO>H&z zIH)%DFmZZ)wM0*rLjoHX8^660Qk(g<ETSO1AB>{`q>8wQ#;S;YY~$K%L3|7I6&id| zwJc3?Y^^f&!<D+qO#Xvm*2NosB1in(BHo>Q^0oe5ZAJV>eeJmbKk(I>>F`1Db(L@$ zS{_#xaWm`wuKH$Ul=9@ljqbM%k;ekSV{dOogKfgVF~t#40x94}WV!v)+ivXxw*{M9 zr<@+Wt)?xM{MYg#zI+~FdV0O@4hry#s#jT&X{z3DK9!CM$g&}L!TX+Xc7L)guW1I1 zmYx-BCu?l?r@$sRuOar9wcZjk^!`w{Ua&YYFq%6`7K_%y?jMrhw-qK9q30DjBD_DU z{aRG`k^)i<b7lyno;9pEp!ZBuvRir0_S0kTv|xXo>bxMOcUdw55NQ68^6Ao7Q9lM+ zT%-B(U`9N=9&Y#}a_+W4!h3xO$2E<3PSrIV^@dsgH-F`e0qC^Ye(K%$#remE4giGv z=j*GKz};VKO|(bq<N{NB%#Y>r3#ik88TXRWYb-YX4k_`N@62iS$1lFWt+>9T09;Sg zo?NTRJM8eT>iWrFXP}+0Ox9mlYTtcVpW*v!4Fp{#0czbkJkaf@zIQk3MfUf`7nk2K z1iqjB@aOX$e!4jc>?q=MX2tr*`L9#;?k~Up_vX@}@1KJ&{{6Y>fBfeeYgB-RkRf#G z>i5OtrxMPN-V*3v`MSF*@&!O~%yGl))tB#SMK&Bu7jYWgz#$Gc<u$HSM-n`$l%O1w z3TeXh{*~d<_T(%Hh`gcMpRuM9Z2cXC`v)aOiK@_;e%vIdOJ+60Nqv0zZJA+_^N($D z0C;V`>&9n<DpiT;_A*F`bwes9I?6u3Mg-5k7P+`GWMee5td-lA6KuMZt=c9amN2MK z{4^p9_%TH%cn|powSD;j%?KbOgNkah!T#_A+dm#2{^jWRXEKA#_8&PS`-y$5&r&CO z0F~EdCjX2;#bd2UkB$+tp*yg>`icU;7c%Bd(LSI6gt967ROBbbR8R9q1tMyshlvQe z`568(Yl`Z|Z)jgO6FP1R0Sfh~`YMXT(e8oLVlr>FOGd~0|Ln_t%+53l(ZNte(`8X= z54DQA?flH0aSy~1qCl%q>Qeiab=#XBx!CM%y=ldAC8}y2(f;h>=W78V_(7uLZnl5L zQ^kQF7P_5ej8f~e_+t0N1OGCgFil*PyN%!gM~59UIVkf{9H9@2xpX3tD|N{`!`$@O zWI>sp(rGA7FT_zKm6cWlaG2%-ijMn}p;F!EZ)NPqo?c5fzXF6Yoj2MXfh9UF5+!)R zTV^I)-W3=1gF!7^e%kQMg$?$HDrBhT61cHN@X7{jItU2nr<e-}2y*k-T*f~Upw@4Y z#L9Py{{t?EIx>&)JdvE+UvHU8)RT%a8CegVaAD$&M@zA&6Q=y|GfBlIKP>;08&o<O z))eB%6FHh$EeXa(k=u3HLvMAe_f7?xX2c@fv%Zyu!upA4V)MIpg;%cDX(5P5M^TZI zHQD!HHpRqt<pd<^$z23U;xpK+)WrOzgKhi58dELlN?_pK65Q-9KHplLE8eMZVZoU~ zW{E154%ywhu|;(?pXc9L6wGCBf?i(h1_MuVJY`@Bk=9?W_(F?kM8xL-PXjS!MiwRp z`Cea5q>pnH5L!-c*=pwGzKQo^M$iJ`EoK!ult{;}aNyQ8blg@9KlELRuKYm14T<IN zx8VIQ;S?oU#9<WxlcnHgE>_sx62I3rXr##u>*^4xvsQ;zIVf}g*h$@@$`>o@QiZth zm#H>Bjv~?B0oQ*+X>Kyp&r?}ut;gXs>H|$*fJ@$O0h80@5ba<iBv*)!*d|kn`4Tj9 zL1P{W3k5R_`}l@r0Kop^2m)uSrgE8INbNd7m1j!j6dqIKJCMK$ahZG%px-8ioxU>f zf!l*1`v8-vc*1w#BuQ$WpcC8-#T6FqfvET$!f2wnFbOP3z!S$V@dm;N-9Q4m7!cr& zgNXYBj=Ia4wth8>z_vM=o{B2H(0i$Ddq>nA{7&KXqC($xtmU3)zE~(-oZ5NAY6Ae& zfh9pIXHZP33bK!w4mwESN&PyANvwbXyTQDR|KZu`BIysol_MA55E%x<<q7fqTO^^z zo$G|EeWS|MgAd-1@Rfs7;NAMc%=&X^{%6_!dB)?R+Mmmwrj$NIbf~W2$9z_*WQWF2 zk-dG{e+-6X)vkt*=!1`@VJO1K1V~RoxXgO7nx1<8?XGbOMb|Zc1jjZ+3$(lKM{>8e zVRuPml_B{N&t%7%9-90S0yww0va38x<0i6as*B0Kd9KFjg!|E2A@25bZK{UUlOMy4 z1-QFkzi7LYG4z73B|(QC>d<3RwJq)U&q`6%4F=K;FzKJ*ql_|;-=#m(=W|<+TOFN9 zL38qaaI<`hw@dvqKj2Mkg8-nD^E=y5X<x++*iGG>N>m8y&DAG)%qTgTOJV(@Kqt=f zTWoChCIlkY-F<&|`+90h5kV5Tdh?yFRzc3^|85VYeXkBkyPH2M#g(}4!2I`>iuos^ zB;AekK&2us;+!h_F`GCvMIdmt6V(!A)k8wIm?I}w9fMX=)^1z`^X<oXj1{CW3R_$R zwvpeCV<rLgW`bt{6d;E9!tug?iI}4RP#=Si`i|<t*r*}srga+D7MRhq=#NTtg(>6| z$7(OnYHt|kjRA(Fe8Lz2DrlBZCy|}oUIw#io^=|POUQgE5Fud8!yMajxeyd8#07wU zhA$-6-l_{4Cm}#I2oeaxmfc|_^0X#qksZ&lk-^b=EL8C<))3(tB>-5FFjL|wN%O2% zy9H=40Xr0fYPif;QNlFP1R<%&VghDhm<9%gcH-QRhhgSd_(qt-ofTG-yV`0H6WS)& zf;$hcO#LJ-91)Mc17tyCQ%99BBbd~Evq*4TR&!#`U(iJWcfrrfOHu&+wBNln7<Gh- z88^hfU<-YK18YU7J_05mV|};lLUYa0=JcHPZjFm;>5pk~04H;kjclXYKH5&?tcAeZ zglG7x{Xw52Iog!wf(2EcO<vkJ;@AbCZ><K-6$|r)UH4m)?7M}hI6jhVA+f;eO#r<o zI9n9!50NP-4q!gUp}|<>GaB+*2qtk!XtgsJ?&#hGcnr6C@i;lG-PLHtp28CaC?3uB zA;#`J0o}Xp0$}_g1JD>m2Gn0jH3U7^>L41+0=D5$iyY_x-%4EQy&ykMN)VL@L9pyd zp+Z?~q0rG}l7!t073^H=F~>yo>(&AvkCHEVT2w!x3Ai}DM2AhGJ`*r^V(1d@P*bg5 z@>t|+HWC|NlKXDY(IOP3#EQ@EEuTR#*wNx-*P%%ZAD2w&<qKXvOKXhfFS(!#0C*P_ zTSgShYZcUzu)FGB*14c{=?epwS|~o10m0L%J<9u&<kP<(O^hAuLhbu&u%|{b2c;_> z*UMiS#s~`n(+TJa0CqVOH5-Ptit(Alp&QmNKG`+CHbyS7dskAWgw3I1R8=sU4z?XJ zc`L@(S+OF);$^K=j0Fe#H3r>5a_zOg4jz-f#)<Az!%j;v#RpIwIL9et4yH_cJ@bEA z)4*hurH9*<+0;v&*Wjt;JODKzQ>nBl^-T>cY=wHXhAo;)7>;pi3-VMpslF6TpJOG8 z#^ydMMUKR{uM)27$=1+P;~vc9QIczZSE4)Ej-bpM`$c)X<1WWcZoJ1@$F&N}9KGRL zCf~J`JL7<g>b?<RBEJf?AHsP&Fs_YQln(E$JsBbSTS?#(!_xm(ZM=}QO!4)E-kay9 ztQTpQQ)KJTPnkYrd%RYwW64UMmvV03y<C@TBKb-G=-FR&MT=s`T|^36g_@QwTwbgv zEsK1mUAtz|Kmyg&BsUP+M1HeHesUUaDY@BYHME;Fc6v76PHyZjYwYc9>|1QS|EsZI zwrS9$iR;<)Fu93W)-=}JG``sM_*c`UZ1c29^NeTnTypb#S@U9V^NYpiSHGH<WLsXF zw5)ixyiIOdFKgN8ZP{9E`S7b{TlUr`lUrXrZ+%O?^`q?8uijgalCQ62RsT6!-Pjoo z`F#-<+4?=P6<pa0Y$x60wPJoJij=pCX19u;YlCLDi8Zz%%G>tbZNnXG+xxr?f43F; zs7)oZ0d%)r^Le}W?{=bGhwi}+J+BUf-E$pA<sBw>J4~N<9RA%wlIx@#>@?qOKIPg; zE$=+~yY6{Ur~U8FgZOHPgIz9OU2f;P+{?Q>?{;}V@ACcK<tKML;Nb0`gSX@pZ-;r^ zrdcpM>TgF`q}Mdue6(@JV7B(;rbAfyor=Z!eaTJ9<+ra26(&4)<JKWJi9+C1WG|=v zc9!*h6D$7iCl?d4*x#MjXn%DW^Iom=UayE<(47l<sIf_8z?B;%kxu35$qg~R!ov*> z8$H(&3o!)DTnPGhjAz?eZ{3+H(aPf}9y+w)?)P--p2-x^SeGh|zDF}2edU)c<}IE8 zb(S}*G8+1B7WKf|3dTqm09x`Tc){Fmx&2uJhUS@djV4TCphRTv_d-$GCK&Dy6lVne zAMbuq(DmnW$Z<CET%-$ZKxm}({<lr579qexypeL}+9IY@BC_#2(eh)b*Xt3iSW}|y zjp_`6)+cI?x4t5$Ly?ON^Khg3y5zm8MK@w>MDH&-UhlDrwz=*&DRf>SYofKjM`+&! z5=di-N{$J&OolXt_N*8q6(wNV_2wJ|TDGr|znN!gBKn4w4bNwwEUt5nto(7p_b_%N zSB?+#a^=V(S5z<`s93%`tfPDANhWH<52<y-as4<(!1%g=toRWGTB!ni`>Rdc3Ku*O zAlY_*AQEfk%KPWV15>GLyW?q_Y{7!~#wTa`6tQS4hKFcsmS!0CsY8Xx7<zMQl=Ek_ zYHJi&8XfyGC|vCF81NC)!3=~(FSZJKbn{FFA5uVp3B-qzZN1y11P|l#V8We~f(15) z*qg=OT@F5vVM${o>OZS{pon8fxuuhnLZTqnm6XO50N8RsZpOp}EL`l-7g`)XpM-LN z#NO4n#JI*purLC94Mj<-7FIW^&uls?bhS#gbwg4Is>ehq${3#t=2r={#?KQg{pj1c zM}Hf!Jb-5T?h!cO8|vya#zoKcqi6fk8?94ve@7!MeI6N20WlG^0>CsM5ZUYXFY4H@ z#J*lX&l#M{lU;`gcTCbYaW`Jd*{oP#)}Ev863?xfVy%?>Bb2*dED7Dko$q2N6_}s~ zILBMfU57Jl`Z1_DRVPY`cWi5sDA^4}m_W-VgZ)qC#9V&&(}`h&<vhA6Q_OEppg>wy zg*~~TX98e+x)k=9qDjJ8b@yJ{7#@UrSz`GF7<<YV3LeAUpk6(HkUAXZ+*x5Z2F%__ zFRz3Fr%}K|T-Tt~NV}&<EC<Bbc1{3wppZ(dB%x`XOOaH7)UOMYSoDxNibcc@laN?t z%&Y)FQ1vML!87@T>hZFJ#=0EJT8MBH{yRAg%byyHIyR{vKc!WCWCUFeh%EZ?U2Efc zyBk8E3@~@MJpqjWvCF9ZnT%_eN5ynd*ZX>Gw*?w8lmC^VCf->vf5p6DOx&M9Re5@l zT`>L_m@^1C%4SJp5&Q}MDa=WLCUnGI_}1kUJ)8lv_xkr4HibQInUW!$h{7k6a|yl3 z@<vCx)fLW~1()EIzI3Xp#+>Ic6IR58v;|&|a?U%1CB9vdAYaBWzmQ2?f?*L<E^_K` ziTW3A%J+v?RlG(p=<^8AJs$M}4KErO?k1rDEnmmK*(e7=bXK|NIOq6OAGR;k@`VFm z4^Hpxe^_9R4V;AI4Y9sUu)X+_clYinZb-B0#mdF4>3*kPXkxY;hC}(=GP|Dj+?aD7 zjPqT<ebGvDF0lU75@Sc5vy&6O-|83~g_-AD4pVKpfai=0vW?B`<~(1$w*lTk-bl9{ zCE9LIqJHYH0Yn%SkA6WzSKbhwAqmy0!lm(u{01z0R`fq{G$Z{XYB^UZ0`ug)=;iqf z6B(}{sc75#sj7z?=lWNc|9UE}p7l+L*ABKlivo@p<w0YEx3oW~#>NDVZ$(IaSbMzg z@fedv+WP8-2_#|;wt_&0kS{9OI2?>F4E$3O5Xgh_mAQNP{#uN&2@&(p?HG6m@@Wpv zse#jR0<|S>fe*1gtwMSsl^6kFg@|1z39pkxG>&03j=eG3ovKM-SpJLOdlX0j&sHB` z2sUthnmB1bNu87_K|>P8YbgS7h>**Nb}%FMV?g?TQ0<s6YCBMmB?vwh=5`8We<I@8 z6O7mi>;xRJI`!3>2qn`ZWZPf~OW)j<zIoB$mGKa5hX_0l4BY_$03-{55KCa07>MDd zt}+0EI)cHm0EYGh&%fwN{1<Lm!F~)Md9O$O36LP{BUsPYd6FY)%v&TM2i=BUvs|5+ ziV<EW3U)lc)XA!I69(?Q4^vnUowy-LT?sTL?j*j%<{4lp=GayTOz#maI|l2t^wCoU zI5=r7ibsmIUFzKptDzx=PE7w526T5Fu&%9tfEXWGn*h-NA7lqzLi;E8jn8-xMyX=9 zcG2Lr>+n=CU(x{(!FbNDPCo`92S5Y?z!u1NbXcY^krFqu<{V!04Qg_Soqs@Ghk{3i zTHdJSRUQZhN<GZ4IQ`!SwfpHZ&i~7xCgs^t+v;l##8!ou8@w-bsGOtw7S5wcU1u%R zB+tygLrE~Mvb8I2+g2F?e}Sk7>2QAoV5R|m?{?H;3;j`?WYF5i_3pFlgbO>4F``4s z4x2pzBPS~x>E03%5RBo669aV6ygG00DkV<nH?Xaw^Ryt-3uvk<zyO8xSRkj(!x5`$ z0XP}EgsB@?oV~pp7jEZ+mC+4Rm21)9sfYtQ3r#OgYWcKb;Pvzb@{WU7>x=(wP%GK} zq4wp5OJ%2zAJPrd|7T8%aq3*LPs#W*E$@DsmL5}FhjzeHoDaV%ZIm3W#p`_Pt}pg< ztGtB^ECw&hM$hpDEKGJ7qWFv?T>!`zlFg`c{3Z(nT#r^jhp|>g1TLK@sA`_%?H#rU z;I%dCp6s^HkONYRs0KignC|5{&qyj&NdjzN83zz<szp}?X|&PnGA(5SIC!{JuzmYO zLm*DpQpzW0R9Onh(P2vZxEsS|^13_L2k0vR4$GX+R#Eifi+E_UrdMtj`T{Y-yA%_t z;7&)Yy*_%f-<@8ETn#AgKuCRSSymT!Sz$vm53uXZgiV8VZ8R)R)DS3u=(3J7Sn<1z zKUw?pa~u7eGvO*4*?^**23lk1lX6_w<>f#efvbMVcE0CLl`k0^jIVd<qhGVGl@^fL zu)9L9NQKi5|4vs?4Cca?Y(n_48)-Wb&lT^(R1<SZLG~(7GLtv$@Xe(IXs42xpTn{~ z+b-++!20ji64#j6V5z$*(;+3{%%8)4c}L*JE0*WOk5?*FA)HH7TNcOcJc+^UqdTqn z@NyUG&#X$UEd4T`3<r@g2I^Hu@s^UkOoiyUPht1`*dVyfMnUDT-I_RLfJJ3U*}^SP zZm*jye!v^wBonpp>$Frz?i5T0Xm~rJ6jIc7>ty`G<uJp0-{TMZ6}^~4Z}WT8-a#Ka z{WCOc#0+iadxhFZTAB9ND58c3C5Hm&K4UgMHY_n!`64U(*YNCNlb12G$Dg!FpV*H7 zA=28g93m4M=GZZs#i0dM@`p>R@8~A}(EiL7!u=o1BRShdM0S1fp-g(EFMgxmYhC&v zvi+mfsWkrsDL~u+?0Zno)Ntu<X(5%#-!&nJE|mRPUfaWj_n>HhTsPjhWNUxEPT?Pd z1G2-H5Y1&!j_iY|Y~^I)9ve}eO!5|kelDB}bygI>y$Iih1N~x{$23tDmgR+><s4K_ zf~KVUBZihH)dcKnG&fNd8x88$VeYi(xI$!CBLyD|6$sha1jssrff!mL`UEPCY#j8; zV=h%Z_RNRV6J8k}?N#+(Ukn~r<&!eyU>RD8wYZRUYd#|ZV#M*shnQE(m2=n!0YD7k zrCW4PG8ktDF!2Ny_!NynegyzzqSDpF{cMpU4o;bqDvh3l>x-us2sx&W0S=>dVw&nF zXG_gR2)fUD!fT;}XHr&UL<)YR^!(t{GJsYdtXXZ?pZM@VmSfIW39iBW>0q5}mSzvE zr%Okg>?7qNC0j<dI;dF2A)y2LPycRMHtb?v2N%#X55|b$QCGkgCR|LSOO?V)fOOD2 z*8c3Z4&08kg{gQzNyzMJyi_$JFJ7rs-8xjt#%#RiaINrCMGME;)`#qraqVwRGtS#N zYoP^OdzP^y9gxk^RQ+`Ka}47$O`Ub+U+1BiOu;Lv7WErYPt4;Q%}|)}j1{fOJd_BD znfoEHDb!9w`T>ArA_UNz5)9Bwmj*kDtx69<)tdU#HS#er_lwcdnwQkxUkM?@U6i>F z`mrv`<9^(ysKImz$1g&g+GkR=_>g0uKgN<<^L_3F_p6jrweUB|uez|G^q>px-K|+W z$PIpg5Q}8q(H_3P2?EaDGsW+sZ%t?UylcT3W6Wsc(>i)z+l#xRYzCZ6Jf~YeNKW=s zg~Rdr$`#`U;tO0A_uy-EL^N!VJ5La31%UNp<=Dv@O8d7b1TsPHfDf;{{oCAq^&rV^ z9Q=HQPWHO>t;|v(agFWO&XZSl17HimIu~M*J+G|JZ|=O()@U#>Fs7zNDu#y#4({2G zxQtImG*H+DmvS0J+CRZ!Xu-NSw`R<UKew$8e*@8yzYOCqx>Jpiip%tzRKdW~L1|nc z`v`%8y@)U;V|Fr@0g`A4qe2gh0zLwyGPuF^D%3Pk_HNCde|}UJXj=jPY<}bj{LSHS z1A&amk9(2zC&(Xm+k$}kyy0E<_P_VdjsPoZd#%2W<X=iz*=Hy-di0yFS#J|t$FOD` zwj6hKx{rOJ`pR&~g#+atIf1$(J&!|u50pQz2sM1O@c6vJ=WA=4p+|mSnK)DYU&6N? z5zF142@>;6jRbvtc426`m{~#DQnd?r^HBWRno+2HD8gw3I`b`N`w+`J!tG9SXI1>! zrr?(t^(TvScOIT?IeRbC_xs|r2k`h-#-XSHsps<}mhtVE??r_eK3{mkjPJa0C_3W! z^TlTm<8OD}i$0m~{P}<Igzn)(C*w+<zgV+O=$*ZHGXBo<mmir4eXEB~B|m%q>iffl z`(N*!y72w^f4lI+e%RrdUAokZB>}6%L5ce@Ov4w;A{mL?U36sT@fWW@RsR@fG~eAA zIR1wBP2k3(zFhaoJ8$+rIr~o9$+pP(w@g}OQqzIQjT1i6hMY@1?d8k4rt~vDMo)e= zeHEhFyT7R-s~S{CHe(#&*~Vs8znTj37a1tCQ;tUr4rKMlHN7d@*joudf7d>$FNrR` zx-E$wIlNgd!<PN$d9dy2vfxU)>4zI|ro+GB>ARbYC!VddjkvE8JZ|0&o57{D9#4J2 z{n#rzN=tqd-JG3$SWsc2pRtG(MU`r;Y!)1OH*t9<XEJrqv%3Sli1(CBcluvQcYE-= z^{K3Ct#qHVHI`O%7K&58`|A5f$de9n-Q@3_9K8BLhQ7<cbJmKG9kF+ZKI1Qyuj&nH zUv(eRiD^s8Y;waZ7vI;36`?sZAIzrRqH5tF%2B2#M1&kEWbWkMar+v1-N5TVrSv&B z*RRhulG+%!>&Mg)iX4O(qQRV(W}0~9XCsR+$_!7G-fa}F*eqt?h(dpKCKXHNJykAG zifDj@XZ#A3B65ppjLXygF9;79>!lLV+h2)Hl8k~mDg7)B?&&Au_d^Wqjo4qxN=_Xp z>lRY?OP`jbOjnh?au(0z%h-%=1R9yBiI?zIT1LeC%R_R34r1@Nuk!UV?cMNho52zi z)00=HThx^Y26k_E!#4VRf{l7Z!Uigc%<42_k1B@QPeN|Mo-Ed3{gvKGcL65W-1;+Y zyAtumi^cL2R$((ZEY^+&E3g$7>M%eeu+5qf4dJW+D%_&7$3s-h-c-%cz2pZN+c?R5 z+{g`NF(cMhJ-XqsJ$bJ<WnUZW1l~~qj^_UUraT8NXY)*FPX<=hGQhO9(H{}}?vj%? z%ep&Ds`DD1g)rw)vVl@MkKvJs%y2~bI#@Ep_K!?A22K_a)-iWwt<rv0;XM$K_|IGc ztZonq=vM{8;BM=s{2KmmKhxtCtT<G?H$gDgok603l>th#f3Bp<5J_B{!A@5@3g7)z zz>BXD6NJ*jyBUovC~gYg@LbNA%Q}b3WKbCebvIsOsEqC6;u+H`N)=y7xpYnwV^ZzJ zG>?uD4^6z!NIdMiHEQ9(VD@V<OY45)%w7@eo1GEI*BQ6W;8iJdB}UBI0yuMfD3dpY zFB%>65ct9Yt4mi#ED7Bk<5l$u6WL%qPa0q|=>2S0Qr7p;J@0#{KJFPk@~Dt4biIF{ zFEQ)4JM&fzt1GEAD6!y-CL$MFU$$NDS!Nq{CNn{kbrvfXab`g3k2b@v@M4qPIA7@a zt~*!GZhB=;d_`A)5ZuoX&P6c(daxom`)>x>yhktyG`1&4SZU?(?u8^WPug_QsHkUJ z_<;+8Kmaqk8F4tI?w?ZDdSRb)=7qSyw{4cz%kao0`;VQ>4@Ke#<Gf5>=7$w#81>j* zN3yRo^F$qNS`NOg!Se9CUNU1qn|kth<=8)S!M}a_#_OFa1OX*)R<*5Q{Ca2BQdYkM zV#fVQDQVD3Oisp25aNnJ-C*$p83`l-k*j=U5H?O0=4zBdc7XAJ*o82(M6{sPRkYyw z@!XoJ@P5Q<AoIz=`cQ8sDV51_5ezFm#55}7hfe{&^nLo%O0$LguHJJnatd)dhLCxr z)WE#MVpjjw=cWkW&DJ~2Mi`PHIu@BaXZHaZXG4<nt^op<8M9CSY}%pHeI}Wp5|*>x zO9(IzG37a%hB-5(8Kyp1S6X@r!G+300aUss0PN*~_YxpL3<w}Vq+&n{?jX@pe%mWG zb=xI1QBaCCBg=8IR+x3V>cWr))7@Qxuvs^sOcy_<o;WcCC7k64e(K)vlz^Bfp;fkL zFJtEzVOrBM&8EiF%y+O5Z-GDMtU|xsn+HlxSI%a(&eFFvE)yqaf+otO?TUWPxtBYG zoSxEuJS~ZV=<}eiRKZ=H!$t&_X>?}Xq2pPtApADOFwB`K4JL+x_wnUgMoNqrB}Qu+ zwE$s5K<wdU9^mIYOH+l*QYAQu-RtTI>=MA(PF0w9XSzdyItcJ%p6!#)R!(OS77Clw z3jfa2V{lpSl11*YcS>4*MEGSJx1!Q?J2vB}hrlhPftETa*9Ju7Jj|Jm{x$y4|0-)= zw4?oex*G@nFc9WE32VGpY~Y>A3drm_s@=6gO<xu)z&&r*_bMp0dO-1F5S}x_o?q@i zHW#i}#OWM#ua%3tc4z^{iDvaL2}M%cdwmc-!5J`TRtiZ_ARA+el6A`m0~osSc0J!{ zroi8G<pDq<cux$Sj)O3?SP6+4(GF-|Ef%^FF*938-v$%He4f2mn2Y8aCPLc!N8OAR zVjTnqVk!n>Dt3i3F@L+^H|o@5mtN-8H8gUNHA{;f6cm4c*djB`T$hbzQ+~$fsN{_8 zac03__<hp&20v*_(xk(Zgs>0dRS`=cph?p}2Uw{l%`7<w5Tg}bM3_0)z)Hdh9^s@h zix94p(0EueV;#!?MEfs|t-Y)Onu<H<LXivd=Jmcz_7Z%~^LGE^%iU!tsLaQ|W^SAw z57L94LD<)IH((N^G?{ule3_m|r%!^^`OeE$gc67DET}CrsbtsBk@NM>qPdHSL9Gc4 zr_yxWx-=UC%M4Q#&)<M9P0IviXIv3<2bTQ0R;B}epPxM=G3^%;`aD{?DXxIN{&=_0 zkLh0rJK+Z_u+H-YXzq0kcXuuR{K2a(k6v0L2B&$lT0Y^gd#y97juv`T;riC_2&x!& z)520aJCgv<SsE|uO~ZHpM|S|SG4o6s#ArTEmE{ji(#9{dP&n7D{?x2)I;<Cb*b~RV zrBS01l3^_IZ9uBOnU5@Y(q0AgbBq`OG6^Vb)9{n2QVuMoRs>WXqQ&o1!fD#A{Ll%Q zv{-#80HIaN(xs)_{0Q+Bt~q5nBjPB@2&*jBLP$mk-u#u5&Y9QnQ24#z2lT^#ZNb9V zEwZ<zre5=|%I97!f_fle))=d-eh69}(NTnud(81{liCjjc5isH4myRh*#-0^{>4vc zvO*zz<+TRF3HL@(eSo0WLg&HTNjZnHV&1K=j~WQi*20I2w`W}ub{sqGqeAOaT!pZ# z9l-wX4AFlHmIDB3hfK_sjB%Vma-yVbOu7X%%>*MMUn{f^BLVyX0i~&X*EbH#gW%gB zH~=64U=I)I@SR6FL^3B{$P!l>OQ810w3dIktaTi&H1$R^LNhnCA5OdJ$r{l@48Z|z zF_`O%xcqM2V12zPGm3Yi*>+LsDdLS9jc!;9wr_p?)NW2*zrwYgB$mzeZDsp9z#E%b zj{{c%Xz(!VibXAa(H?%qmo<tJPm+f13RJ;cNGCGcOG_>+>3r5%s?{QxrW^)Q2~!h` zM7tq064f#;unJVjd2yVRfFJDm7}Ge@;Y)eRM7HVd9|K<*xX)koeFeF!(loQgbb6Qo zz{*G|5+10__#5^ygiX4*EE~U+1su!y4;>?5BiphraH~!rc3ohI)|MQ${o#Ff|BwC_ zs$wsDgq~QiasNows>J1|aCN6LL4#LkdD78Ki+>$<ChFD2Pwh0&vobb#A>GVM7ADdm z>+GboU_ME3h8Z!R7fI0mbJwYslo!#hP7sn&d8F=!f$oNj#)rXldW;_hvAWU)2PdOT zcq>f58HO~pXn@E-v}6(scJoMai<zv@L>d1vi36Zp@BPK_O;+~=Z3Zgw+FEzkP9n^y z>4wC9dVlJkC2$rs1I#GMSS&lVAjJ+~_;KVm7tls)QeO%hKP?PZDKfXqT0C%YV{O*4 zP(%RchS-NH=LZZ=KVgUezA#7@QD3Fr1;M<fnE~!v+E6Ab|JsFxk|r7ESDvYsL_ItC z^O5|)BRzX`xh4K#iX$6R=kXtTPv3}LxZ*E;@AK5XP`~J*o~))F$yee6C$^WYjK^~p zWqs93vMU8#IT^+71p_b|`gbdnl%*jd?RoR7!s0>J=~5#c*<nBHhX(kkD=Xez681{s z!()buP!UV;Rsink?x8z^fr+x;3lQDa3nlLHM_mNzFAM~Op#K68$>K7-1LN5N*-gy_ zS^kLI(pOPdpFhuImyAq)C$fE}oig|F9)JGM;G}^ySri9EQkC!EBn*s%hiq#EN`II6 zoS3(lT0l=e>+B7<dok7-(NA*gud`14xaH^Y+(+@jwz|yM1wI&cf437eu)9e7VXuTy zs<s=8uK>0C0j<4{P4Htzb{D5SU|7#h(K)im#_dYj(3)*BunoJvPfPRr17UX-b!jqz zm2-g}9TxL@@Vem8p`sI1rY|*R!m9p$Vu46F%Zv1UQtI!|`n_3l(#+CNIVaA)=Oq<U z3CysBbB^bBohtrr@-kA~b@33X%)0tlp;zC1H8o#g95uL*?~&mlE&cG+KMQ|>r5L83 zJR_EPzEGOEdHuqizi{sEzZX=73j(#|02kFptiCc~NnadF4Lmf(^u+!Aen)sXoEbz= ze=8-4fFpn>01@K1jT`(QgPN$SQ&ZTE;=>$S!#F7JgI{y5qE&%r_$Q^YBDn<_d3Y1v z_+$(42h7%7XbV(N__X!zv+5)VNDe<RZ%df2Ia;Foo~ORt%P)pnc-?MN<I^hcoE*Nq z?Wqwt#Kymg_@=qoiPf2K-u$NZqFZWVp&;_R_N$^Vz&O-lytJ*4E+8iCX{*|?OJ_(O zkhHaX-r}P#=iCz2Q?)<MZU5;HeY5HwPpYh*U%i~<A28i;{Bvhnnf}(i^|8H0#Yj@v zLT`fM3sk@1$ECqzW3ngzbd%eA@(-NK-MRgFy{7pWT>EeGXTr1A(|2tDMtt8MIj0~V zx>>5b`TAMMsgH-lsKBXt360;s4*mP{>-%xNi>>@42pZv1VM3LUonh+TxU|>dX~-n> zQ6oH~=H=-;@?V0UEkhys$Fkp_ZAky2UHLP1t`AZL6tlH@>n<OL!vffv_q=bs$~NBU z-e>)D#jJ{~BYHqWH}fTTUxBrHk7LdQLZP>Z%~50J%jh=f9*^&?J<26M$v>4#cm1=B zRjve=C8?B!H}t5KNB91Gdp2vpSoLbtsE6vcq>Ucc>*s&{ROO@!nGh-&vdM(1O!Zzu z^(B*Egqr;S$Do$1R(mC)SMBE2<X>uam02e0e1lrDdP99fuX<y1?=SVHwlNcp=B~wL zjh3E`UX5G#e*MyD9S}OG*)}YDPP2Vf{jO%mgvoEs&Z(mZwYp|K&uQIWh`6hD=VkJ5 zt?uQlgW5f-W#_be-!<ITzWcuSw|3vo*unkxzG`b!QBq~ZZHeC=XCnY0Zv9rD4j4Ck z5hN;qD|6hOuP<u^IAWAXTJkNd-&?0E$&=EZndB)_;nU%@h@4ZDC$?#mI=hg|TOYCn z4)xg<?SJIuI&N@RE?aHVwCO-!PN`GQ2&o$Bs|UFfpm%pk89uHT%XOT1V%u?74>)u@ z`fT?oafYd3@q9)9*~;N0jG;idM|}5?I|NX?`y)>E`C5BH))2heC*h6-MAP8E=K&ra zWKjr^xU{TZhy$jguKu{wZwm42?}k>R{Mez{`^>B&F1)u>l7qG`s$cl<eoSCB#iZ+s z>h~P|i_oS=HcjV{Mz3eabd)wLK_7H)A4~jV`~K!89iunkU>beo`6vj`7&q-Od72sh z)@fs*y>LN43TU<0`3paJdHt2I@(6B0{$lTeSGsQ=nFxF>_)We;81K^GopiT-{|SAA z&c1))b9;xKtrRG#I8XRf_Jq<tafM~?yWj3KSChC3qN$wsXU=9{kQl)qtHJ@(OtyW~ zt&3ki@w<_&x$g5HJ=X!6HYNnq4kF2f-em}`ref-C)0m&C_EKip2z$Tk3-?8*j{MV6 ztkc^k;R;E!8obF4Kq*OXo@VV|Ouz_6G@7KHgX{ci$LQeFa|G0`g@jplACHZ~FLH)o z07TRh`IhV`=08ag1{KKK!cFS%2#Gp{kt~t4XTKhw4+CL~#g*~-1S^A>*qo0uV|)J* z9VvX(S13Pzx<I5-*Spy#*rNEGM1;!Y%FHc0Sl;vAQ9E87YS*IIF?T;7Gcl)%PMds- z>*g^c*WWfEeZn%~)=zXl9B6$-T9JG@$u#h-Yd&uZH4=wZQcNu+8wqAQT^v3{v0pH4 zJ}<kYY~1X2A<?)tA746Tp~DSh$H;Rf7E75Lce?b2=Ai!JUi&B~3opfCkWz4cgjQJn zov@}i`v4AD!aiwS(gZ5|m|a6Q?;Z--3Xt_wk{pv19Zd%ymn!N;G!<v|FW8w$CA#Fs zsl?|5XhteD*1@zWlpI%wH?kIbEP0bQ)4c{OQjc4QZ84I$vEGpq7tN_S?lQ{bi%0^t z$3m+!)ox;5T@-Ch7tM-+wiSFu2=`QB1*@dX4(+}xN6KWV^L8Gj=?vAquYPsQq#Hw5 z55m>^z2J%t?*E$d1$Wc<p}|f>!$m)5ky8NeI4DN^gnZtKUL)TiyrOWd1B8LpVG^FD z=H4c{;-6t^BVu$=Pjb^w2rrjJN(I=n#^ZGuJ}kZBQQeT4s73@?3#eG0OqZT^`R9Nj zccfkl{}Oj1^=FVVlV7L?mc&z<;lo>NCO@0O{_l*a;hXgmLD1?NrTT{^b@==r;ZTyS z1$B`iMU0ehO_}{8d_gU|mo@L8{RY~vRadS2TXsdZqm^|k)>&z(Y%J0^X<ILM@F>u< zC984J@<4I^p<*0VXkR}KZVCYUXB6djH-dPXH`|apy@C4y&YH1s6*5U^HCiOLjvz)C zN~6-x2$IvcM4cGQE_^i=K*|?!TG^MEE-l{78c{4_`%*m=Z*mtr+#@mcSFdSuvi=q; zzg^Or(i)~k_W%U|jZbI6s{tfQ;i?eEizP*E>S=R2hmGU@#3ftukeGmUydGI#-vA9P zT|h(dp(;5{lDS?CMiStl*gUY3BAuZN_&vS)YE+2O4z_TB$og8^X!G70GwP&T0rq^n zY|_mG1f{d8DsyUXu~{A~y}hE3x-{+aNFOQHXMO!lBe!|X;T3<y#?nZHGCkLMn|`K% zl}2v86b<nD6&2lf0f_E4MqEz`6^VcVa}Jq|NipC}n4yJtlQ2+|Cig9#cTPmnF>U(; z{-!Ns`H#T+4847lGn`>kZslriMRGtU11IVm9hgpeqb%+-5?`m2ZLhSFl=o&;w_sTg zJQNW;oA_L>!T*z>^AFrYc~DZ&4>oC>fS>M8uqd5OPwT`X?OF#VZ^y8u^@5PWb*Yr1 zR%TXTHJ)GCFqqzP25kGTT@wFj7Gs>_6BRP35oxKPOKGccsonw|gwq;g(On(q-#_nx z>$@0O)6|V>AMtijr$6O{HZ5woGI@?Ok?bQ|hwvj*OPw%KP9yc%IXE7Asj^5JE`T(8 zWW>?lRqw-y%yS?BhlU^mG)xZXi=<#`x3M2aZYfDVI-DiEh7G*=lq&hoX!!kuN4`K& zwY<~Mdva%W+1~3bk`Ip{v;_muAzQBx=bo-0kKZ+9N(UAkPc=SwtpR!5Q0d$rXDDER zO)4n<ggbT4mn$Rc72JFs2dYkfBdaKwrU^m_UZJB(`JfbOe?AMN6RVes&5@??$Z|vq zA)UexF>0htQ^hTGSLoXELqsA(I~qe=qVELf??2-gGVc&j^vvAd?^DvK))y%Y^C5{? zGre_5GflGxOM`kTTw=@%GAgx`cl@jcSDFhFBhVpQ6F3XAMFsOCEQn1CH^gUG;klie zp2L#%Qh`eh6{c&Z+l1PYfF5wL)!n)}a;EUr5>q@Hn}ml(t%~_YNnI^<pr9ajUHCn1 zcyo7o5D3uhOcf3S&h})<f3Ptp6jO3QVt+u2H59_1V;gnHlO4^*6Jc6^C^{rXok_5^ zlDN(cCB@bP-F$s+x!`~j`~dsOe60Pt{2tA-q6g;L=+*SKFITS<W+;ej$*fBnDHZ0@ zW;#oQP~Rbay>g4bhbtaOjRBT^)6l5QzH_l=vpN)c;uSN^3GeWtH>N}TO>K3=`C~_i zXf!fX!s4)u`Ch00ETz--&*vqRL9$BFeL#P6rcfcCzoC!XM+BLnb_4LT=JckaK1Y7a z?bvJ3kQQJzl$34m;cpJupZ13)8HtO_L-7vJ_S~*`#c{kZJtWhcEBgT%rEl?DjVtrX zMz+@90z6p{vWyxo-lVO77&YWNe@orrt2qPwf`u57ERUlrM$r{(=xVJcI-X{FMrm)v zA$(bswt~oLCeoOguCHXKFg7Qi$$gQME(0RvjPIowy`uD)2iW=&$(gU*D@Bx7>}}s1 zFd7Of+Dmx>CD0XZb<9tSmn;&P#oQaRs}H{fGa@CH$y^crqN}=;AuZe2`ocB6-R2Lh zpY5riC988?S5^^m?k8FxHnj22O59Xely@<VXfzb<y319n0|V)A!?IMuuhoVhPS@~5 zn{gdb?-T)fadW<PtW}=kARKK{DgW(}p-IREGF$4b^2^M07(DIx3$W5_FmW5H+wFHR zQ3XI%P#x^7Ld>;LLm!mQjkg2P+UdBa!B6W;nMUcR<7vY8B>L>QNsq;xZ`?Esqld|+ z!<r$6E@_Ci+B24GDotRX1JuxA=;B=Hc@^^o$H!x~5dHP^XWapC{4jC;t)-t_baA?H znd_N7=>}1ACWME<mhy6lK}r~1rSF<*_f2vb9p+z04oi~`haB|2noW6{{ct@yf}0!y z5}vLhb5hGZ2JAZrq=9-ixL+Eep-rIYRd&@3xp|08ex0V|v_YL^1?A${@Qi}FYX6}2 zPPrz=EY}!><O_1xsS4d*X1JW<vx90eFUmH`%VoLuUDYT&x@NZ-KetdY6=+5z%hgQU z1@M>ZYe55mGyMo@b%Z8>$N>PQhU&RM3a?*?-Cx6$6(pphS7@S9e6d|&k-a%aDfQZ4 z56qALYmA19%m~ps^+px$b*=QWi7QRA+@{wu*Cwuz`x?k~{pEP`>uu%u7+JFy9_H?3 zNq4fSv_^ZJ`5k;ZGO-`YDy6(g%~RptGDrt$LeWJ4P^8A6LrE&7OHKmj-UAX_4M+!B zpoWC5p&`xt%@8CgVwXl%TD%#;<@&rdaZ><R=;Izk`oI=fa4R0rob9TnAew%{wgx|G zWF>LQd~(000+3>6s&|zSiVf-k!)`nq1(66e0;OiJxwpzlTX?Hhdd;46S!r|CdCtLB zx@MFbzG8s?A}l`XX|8C#2I>a`fCvsM!0xv|&~Z&~%uE$bw_s1TwJ3eB$fV{Z%lBk) ztmn&3GkG)Xoor7h1)Ul@uL?=KI%ONn6MvyWM3*J9JjBgnuk7XMg)%AQE73Ltu4xJw z&<iq?<!UC{8Z-^5er5ltd!gT2V&H9dpiXL)3f|`z>?RA9U^h|50U)Yh#zET*Hz2%C z>jdx8)@8UE3Q#PMyw{=R%^q`tIPApEY(YSs5leM{i<x5><eaiJrB!8+Cl7f0Q1l=l z6`>g<l{rhUNpg<%mmo^tvSr1K1JWU8MyFJ|9UZ$Vnu)Hi+R$`!uGNpABXwy^Bd+cI zynY2(lTDGa00D^u<Si{=(pzcVD=Fp4hXNUW={LWJ|08yaXv>;wn+IqshT0KS?Y?A_ zUI+MnQ6UEn5mzKNj360_Z*^g5J9b3aQ}d`~3jr`GMEKS>b#oQU6Mq1rN6pE$p0jAm zOLT)+xY-sFA>f1N;_Zb|CuM+6uo)qhOaS%TnO_If1aVNT=^RCz{K|w&G~eZ!04GN< zE<3i{{6ER0L)OI3V_ppbhK_rp_1D}9R$jGL5)W1pbVY$<>Gnoz2OJ>F>y-GA^k;yu zqIBS3Tji7S{lL0J%6aHBpWy=pGx=Nmwb8YBeiT;P++u5vJU0+V|E0|p)HLt-S+#fS z@h55t;(XN!X{g;4MQ44m^pZ}TX1;!n!pG^NQ(unLd1<O!UVrL^eHYj|D}%I+a7)&Z zEivtH#e`i<p>C_P&q@EUtAmB_217s1lToj2Tf&Z{e5Ayf83d(W%9Kxpp0;<neql#9 zjRF-4`Rx3!@@aaNELkwjd~`_psVAsPwUPU3XXSWlrTMlSaXvuDWS7gWTqSy?Gi9L3 zWXMPEK*3Kn05|&`Q@Jxs32_O~{^O*aJe=?TpK%B4nfu6BQ`9vT^DOwB>)COOPBzrT z!g^GT!VA`UWS_wJgjx--NzRSA9qitq7ijQ>#)52%Gd_j9G{`ek*WzZit$&<yk40=y z`s_9XxLj)wkw>}!t5ZuU_PqU&oNseEW_HkB)T|Hc@kPNrEkoDk()$4DLl8|-`mFqy zRx&$d9%a2hCas9i(;lyOS53z+(p^}Su73*7U#_xo9u*4Y?w_F_kbm-V4>wuce3>3- zQ?Ot%PhS>SvzV{38&vzka$NM@qelq!{jZDDgp%CP)w4~XPFI22J4ip+`0##1Tle*8 zJ;a{$Jy5h(on5Cv<b&IhBL-1VZbv;ci2m<(^qRrRkGD^LH#qhAc5tEjLkBU-9NwYy z8Orw1;gz&Qe^|PZ{ybcI-XFwSv+v}sw8QIZtRTZ9L3a`^Cd4$39o~kh$fWD|+<91Y z=ONBqwCm2f2MMJ)R1)w%#bkFt6gd08roxCqeoRoF>cF8x1;iA+>ss+c8G^|FvzRO+ zfe?@LL-2AHk2QFE5C<$Xi1@J}>kbtQ4QbSTMd=bi13@4Nc?@m+akVHORRIMNoKm3( z)AJi=){oVJ#jKk=*&5_qZmF^oCS6;@;vr8PX6w#0dld^ih5ZWMnR$L!BQ*Gn0B!%P z2RI1$f6fyIz=0s}-Tx_2`;kQqjQW-^s}|ri%)bBgJaJ}O^49G&qlN#gKyBO(qQQlH z+bgU)YA4G7-vYJDen8=9XWdjawNTw>Ok5ExfDj^Skt9Gs{jqv`*!D~Vq~7mA)`XC2 z)O<(qP=UqWxhAisQ*Q<>Yz&)U_MRRYyLZ>{)XST85ab@)?$+i1U7&t53^BLVrY^Ou zJ}NyB`3j{Am_MmN->ehxJF)(>&UwG3A5H(+9K^#*f^g6vYVpnquju!^h9Ccf`O76L zq!>PHJdRX4;oILGNgvEKOE{d;+rI&TQNT+V#=UcYe$?;oId(tAuLLtC=kkB?bnf9y zzyBYfoozOg^C2eZV{<+;<{TP1%%RNrSf&UaXR|qL3L({`oYO?kY0eUwLQWM)2^Af6 z`uOep&+ni8wQJW7@Aq}@e%;T<<7wlW{^#d*NN>AT3;8@i(tKT^^3ee8zx`w)=FIoz z8o*iLP{#84-2Bs*(lCzdl^()^--tj2xmFP%E|C<%#KuY;$x>D&-^x}BjaCHwv;x1u z>vg8~31X*7O8JH~iXBY){%8nofBmjfuI3MC-udq;Yyp8QC_XX0=cc|^<ZbM;l1++? zxn(bXl4mapN`|jOj7wrvF9}sEM;6DoeRy{*XrKR^ihU}}UQ%-L8c_^`@|bsmQne;E zSs7?^zU@C>RlXw6cq7_bLq;>yUP@-0hJl{zP-KSxP78w_v2TvNRyE(UUR7INuW2tG zyB^!XDcJiR=9YF0UX^FI5KYTxGeuMjxj)n!a|fY;jfGiOog4SZt7SGD)Ne_7GDTB4 zYaBgI-iLhSXLEhB0+zN{8tK;;wmR2crDG}?UdnG<7eAeOC+2=e{lmkL)z=nm{{HxL zICYPy#_0u%o~|rW%K^VWhcL!nbC*#cc^SSCV^S1VnC7?b=xN=tGeYxGEgUs=H-;Zt z-2YB*RCK51snz#6Q5C??=^p(jrXZgLTZ@a}g{QzoH4M@g!29aFxPSlLxS6E)SL;9D z=<XVK06ZZB_o$cE$UHkrj*Us24$JyY-xpU6j@y;oxp=3!+o0nnGRG!>AD#(m-}&~& z4L5?_qq{9pVJC`WXrjs<x+7!|QnRNP#l<n4E|ggVa5`z%e(dTC;l?Y@3mNobPmSwc zy?WyJ2c-{T!hmaoC*5>A)eBA=O#FR=oUMJ|^yd?J3Wc`;GAdyf558SKWKdf~LukJ+ zyfS|9vGS^kK?kyRTz@vqhWGu&*H8a`e)yzx%x153-;mK61p{~E`&1x8v)23h`1-zI z$8C0Z-(PA<{k;xq!Q3S~9%L$Z#RVxz-=hR;geT@j@@Uu}xoq%W^&>>Uw)@ZZVCyeC zP^;)Fi5Ewh`ZT?~$e^&qPgjO;j%s$FI=30P9=1@F^NpI1^ph3DexrDiJb9Tg>^QE{ za4%IL$7?rKx^lBpIKOXD)qE%0<94N3&3frJ-d$m{0}2@O%vDka0WKOaKNe)>zrCX) zIbO<^dEq={+_i&S*~#2+>jO(SE(=dn9rdk8@-`WIQX>Ph+PBk9AN6gsvd&c<kgOBi zSt7{RE!)F@Q_v&!N-|H_Z2aHTc_Czi%-E4@KcM%Ay?&$e%ENDK`lVgb3Ya+eB8wo~ zm?$J-hmi(b${%#?L)taz9H{nI(#muhFCVm%1sFQW`i3B)?N<|+<8So~1cai5l#04I zckD5bCp;y-URz$u;?9X6PunZ*Yr=z-+&qP%#a6Em!5w81&4l!CxyyWOaK@=f?M+_z zedR!}R+JP_fJ$t&6<Ojijm2W~V*mqE&qR;vePbF&{(W}f&)fGlCWy&xIG7wHHX_?k z6pkHKL~pJSs#zDpy^=yJ+i{M1V47*qW8lq^^-9}YaDe*n)@-YY15TN)ZWpLE^6eZ) z<y%;EXz4A%TNsF`^Hlx`F*~vA7?}PE5uu1Y4;i*)mA>(1&*<vQwb9oPOanMw9=Ab& z3e(p{)*?*z=rBos+*fySDyO#T4V?wz>eZ*W`)_@ediliJUovpE)m(x?Y{{%!@`QTd zwu5h|gEay~U>SCxTbkZ54TL~JJO?QCn8(l+YqxyhKsk^-am*y@(Bi`0=_73mxgWz) zkTo;Maj2B#3=E<Y?I$%Y_JHb$qZH;va1O|B?1B}h3-f(&1nI1^5Y5|qLSd{=O0Gip zQb!KG`cnS0=Pd+}n{GHlXQ%Y^<bMu}Kka=c^^K?w*1^iRFUNRUL}qGG#-LT8z;4t| zu7wn`C6VG7bYid#Q^3hkb6Y_K?)FPfa!l6FcA3&9#Me{73gc|3A7(&C?Jg5uZ2NG% zIaFc`3ypE_9$8gMkQ$fT|J`tWRsPTJ2p)ZsWmeIRaxGD~yACz|L4g^S(qxtZc-ex& ziKtx>>BnqlNYx@NnM4<#c9x?%Wan*uB#lOUw3NRXe+Nf`_oVENkM3<L7M$eQ!PlqK zR5~lOB8-o8x`w~8yyr>w52}**ZaF-EqCU3*`n!fz(0W_V{ex@Z?`Nfxt<@$IF&+m& zlZm}c0Yi%U$^33_IlP96TRPnSZ`vi1q#e!Qwg?+4|4QE0{lojwwW<H(1sC1M$#mZe zmHjg}01d14%p}M0Rz(R}cE+5(4OjCc`T9D;+KnPFZKtcG8lthUi0S!u2mUOrd$f1G zm^cx7FfgS(8fvaD!ca{*AXaZxYw+IxoupTS%&C8aI!)=wNaq0=?`w`8fA;qoTl`(Y zT<W+cz+Oy&O{O&R9Lya>AXc1o@qrHJ#e2tXBoTu{1ADbjcV`k&zTBp~yAwlT(awiU z_sibko1BL{ADqe!J|W&l98sUe2pYrR$fy_4ji`$K(HlRcpYFy*8m&b5Du>BLtuhQ` zUVgi9bN;QV!u_Ws1)8r{XyTj1AsK5$LCxqY$@A7wT~=kD)Ghrp1GNrD_03-4qydQ$ zK%B-ge*Ihc$)wXG$0r|8?s^aPODthWWd1HAG}tupYRdhYoAaO7)2wejPGufES9vmU z^>=b^SjEC+&y-K+|NG9l^l&TU_3lCyLb6L8X8aeQX3rIn&52Gn(5v&L+b1l(Z2GOw z>BYzOJjbrLJ^Xf+ksCy*k}KxgX|@VLZEv?+zFPEd4{73J`v_GfHPhi}Vx68F*K_V_ zhRM0Pi<bX>zqa09TZc-R@@=xyeI3Q$kQMLkqEs<DZB8RxL?iJ`y98pIVlsB*L|m9n z@QBq{lfWNW(|^7|@{%Ei6jUXbpRPds=YyKU9CN#EpCI8qj1kgz5NhBaf98`sg+qBC z5qiFSRJ}CDRs~~sCmlbkI>Zt>SdG@?!hT^8wE!p|c*(+{zDzqk!JgF>vwCS@J_|tK zWcf66$YZBa58nEOn4Z0taxz#fBYItxFp6j(3X?d{e;mXB7Dn5K@l!NiRH46Zr2DGq z+Z?YBzAjZPowFL3Tg=SbRei)3YNR6V_A(*gsnL}HXciCJ$U=;B(>zApr&moXO^`ez z`YZqdyGrT8m_Juy7+&QA)GE9xWaDxsiH+`}Am@34UO1@Iu23mBWM5I(2nPxFg<s+F zGmyv#Lkm8X(pqeFcQ;Su3v!qpz&97RtOvDl(0uTx>782{IR1sGRWJ4Q=C<H13UXl^ z`GR5$V4*sACjH?2FX}2>st{i;x5Po0QqdD+<WnL_Q5}*)MosZt2374^IMfGF^Z*A* z^FuI3ga#-PUrB|cz^Dr#)EgXPn<vz@&2QLB>+C>7{7+_P1h#`6NAM^;siV&sadjh> z%ok@Q{I9%AFAUtfgQ{ooo7Pan#KSLeP)8Pgo-4E?c1b!tWsOL_!bUG(QBh%}U#%im zU?E>Yp*|dHoLwB$S$xb4)lMn)n?GjkUxL*`?JWySGz%TbKz@M=zTl$jzh64-4DqI* zHi@VXu8$S?H0QhB08S{a^TKU5YMyG6@j~d7la*MXy{{nPIUDtcjVdxjHQ<m9l(Mqy zvT`%z3pVPeSsA+y6%Zp7`imY}R<10N+);z}<03byXQu$D^Ad<WDmb2kc!5Q~A)=n+ zP>(S}TnaM8rKDZV)~$%88CB50MX%19W+{pEVM+=+iChYzoCiy#LYF!r(aYBZ0XJUn zY20{~4NaxOve|;!tg;V3%b@lVo%jmhn2LJ;o4=LgzVm=pY&3#|YIv71>;QMBUOUMX z<ZDbDh^QV7bZTAk^E71bZO3s|L?c&7(+~a<gIK^6o9!M23q;+FK{c@8iyy9^z`^Mh zzLuLljz5I>d2JR~wn;=2l##VK!E(xtWDbnNt4hTQUI8F`_%l>4dJ9(;;GZj;Q`~_Q zau1;V@W1)p)VvXk+~7d{iNeiX#AG<)8V?G<qc(9u*RZg796Q<-LgqqGa^ctULftWV z;;7GDiO}-!@v0fr90tK=l|BNP`AU~P=Ls%mL(lSkx@1(he_8Av9r=WUTEo<R%DSG% zf`x2DmF|E;*mcJ^b*^l%F&T6KTdzkEFlK=Rd9Z9Q@&ggIi7nIbLT|Dz&1?%*ooe`e z`-s&yKIYx9C4T3@drtuF&Is<z78gb$1~hVWyEsS{Db!O;m41NGH1B_c$4FNQDE2Cy z3*VT#=Inh*wAD#`<MJ}*$|o4$W*Q=u15rDJKs+E0V1!zT$j4-qLBP>+avhNkcA$WX ze3c@#E&&5Cq;TM}f)yOjU9MpIHnc<r>c9etH3&#A3lOMKUn-Q&gC3`N@v+MpGHRZM zB0oUSZ(n<gL;cs8l4jPRge==wGg)CEJN7t1;BNtVd#jn2Jj*{V;GLE~;6{fMVX!CC zb_RJL07$1oUJ}ub+a8}wL)A<x9${||;86ap>=)a}%UC#HzzfQO<pF9QcKTR-^RO93 zbYqT61t8e`t`8P`$&6n?T{epo>fJ`R;*q<qRoB?Ce`mnJKTt%2wUbO;PIt!|7TH7P zyQ$&w-QYu9a2UC>^bbr?7M6_@jOD?!aA0Ms0FndXJ2>ye0oCw8eO_0|W=0}bu=%Xl zH4P-+Z?LP`(9+dC13(dBfNim!e%ZsW;l)$SLZeTv4tDm8%N`3&D}ID|_{`#=pIOgr z+(Wl-=j=CCWm|250u;dBRTN@K@B$9e;%c$G5H(R%yLA?|Y=J_3zqZ|d?K>AeORNq# z1fgREXNbZtmapM9diNTLw^R@>iHPK7Xe!HRYq|Fel2TZXID>@(w4ewr^!G*K!Udt{ zESDzphB`oJA{VS2-x;<IyU2!D6NS&LA#~l!+9-$`EV7ezVUTrUgD-`}BfPK>J2FUV z8*pG7pojq~VSq>g@V6~k9}hml1s}qKl(mPv#=)`M&E<b!S^SrpVRdg0&2A5MV}`>l zh0eaO7hdnzjmJX=*(b)?3wVo(FuVAmk<;;bwu{9?J+&KfGJbR9yrs}Zxkq2RA5z{t zd_iXC>@5jau;5o}5PXO2H8MMk4ZYhoTH1K4wBm6MUMLR-=R0W4*`O;N!3MlgdC%hp zHrkgBBvD}ZILK?-NX-q1F$=`^MHga`_c4!i8U>;Cx7z-|e3rYswlcDo(O2-o-*AW< zEWs42U?~Ru8b9%xII+T-DB(<$kYNGa69HuY3L{v8pImbjyhIWF5D(SC@NYUGjtcSP zOfdP*R_?@N5J-0!?6C|AW<g?>;iUk01Q7~8&Vzr1m$0BzE+~czvIM|`$%0f4>NN*W zrA|=+aG{4&F&wzJ=(9UG!8>@kij`n89<K55nPxuX9v=OHieAP&|FDO9u74M8j6$2D z(ATvG^o1@ngH%8uKsg5NLYa2j4<;;+MX(^Y<Z1tHAOQzHNS*dQKSMe{<9Hn6LWbxr z10|?ng>3;13^?fgj0#}pAV9E~2sL7X2`q@qHW1AQ9>fB5crz#eP5WMl_~O7W%L4M; zE?p`>n+P-{3o@5ct61SL6hRhX{wQwVkjoEL3IMnHG^~In6}+$kVt)il5J4hDko5Mf zKWo7k`@(k_<i8CuS_VgKLs}nBl~7=YY#^En@+0y*w)x;HkV%C4ZNo`akRf$R6AwbO z7RUcBp@}bGSO6RgfM5i)xxldf0utPpLVIL^<$o_lIP)UJS8MLj0K8xk>($1~SD)OW z9%O-oJfJZddJq6QNQN5ofLlSYKjuLq$&f%Y1l$X0z@cm>R2?CJ@A$HX?Rq{;{F4hi zNA4~9Ro}#RtLCCHx@Gq?(F*c!gstBQ>sFzU3HSVZ;7tZQ{`C7rLDZKEz2OPH;i5b7 z!f%O)MT}qw0FuT+BoD9L>_j`}yjj2rC9<LJIPjDl{|iEIbH~?N=+-<0jR!kP1{<)~ z`1BRugHOZ4FJlGgw~^SW0JUSnzqW;c@PxOx0hDg|4GyXR%PXS_R$+Xge+7Mvo|_*H zYT%qtj7Lmx5tUfv>|QxMr&sVc&ntZs%Ibv`7QoJ8Kcr$IvCB}OWvCbT!#OrImI@02 zY@`A<_`8v8D*QTNJSPtU-Pq{u5xj_lT*N`!F7&tG*laK8pW>u^S!@y1Reag~4u1MU z2etSjqppmK9;YHNj<qSlP`+o8lO7+3PizfXRLov@(7ui25>Z8u5j4JodkdtCh1FDC zc!Nj1-~@+|Aq*<yCIEe%GZH*5R6|8q;o#?&n^So(&jR!(F1(fpjgJL~cHi~J!XOCb zeF}1bg+do}FKs_keT#6KL_Dr~mh8d10T6r^BzTKl;A;H*E)UUEeyN-7H_t)p9L9%z z_ZZs)B+p<mXPwGSURxr@t~rfe<BXv>W7jr0Y@u?81tR)WnZwLB_0y9+?c96LKbHZS z-2n~V8=UUYGvEC_*ZVz1sY-b-$Zj3)N59cDAL>F|z8c>IR01%lSvEYDgRC+2Ro-C_ zuu<P}@IZX#f;pRv&!hqB6S#tNRMcmd;DOJun>a)nexk_=gr~0YMaF`k=e_w}W6mS3 zoG{0+YdPhp6q^yo3!!F?sgnEq0sx$a5l)r&QN4%0%j3Sm4%01#CV9xSE_UgH=Cu!w zZK_~a?i};&bgK3*?!fb*_rJ~5zpYec8}Bc_C}8?TO9%Gfc-+4s!C<A^e^&SId>kTM zP~U#UD3o$Bhadj_6Z%?JR=JTd>N3JZKBM?=umo!`5nZ@zW37TEgK3IW*#Hsk(zYXk zP$SVA_a!6$O0ee&rypJ{?R<K7_siO1`@slKkcQ#N08$~4#VI5>U)J_*oNE>xX{u<8 zpFbTD_8`_rJ@$4$`tuAYaZRUt66s%B?-nRgmYwV3lHHH?$ImvR7kzSl?*@<Y)5y$t z66fAXfkxPH{JbB(MzWXj=SQhtSmMW5L)ZL1AL~8;?>~qfX`9^7Kq)v@ko1Dc<19r3 zt%<8ziW|-mnoftV>PJ`GJ<#*f4hSVbZ~bn2%60KxV0(B(Sc<EVn8)2cUjF6xF-z^I zzLAs56CHOOyw<zYH)q|azpRaw*+d<4F~9A`vb=r@jF{FUah`<`N+~aVj&@L9BHlgF zZ5jIb@=>Nj@PFrifB*Qp{pqFGFG3%e=omb?>OYwMM&t0(l!IjWt?Y=a#&1Zl@{wmU z+NFW5{*Zjz#<J>?nA20k;`TjReZr~3(oQ#0))S+yUl7Zt3#y9g-KmH_mgZpb(N$wj z{N%GK<x#AUfXbBvxk2Hwa>2F`S+xgK@5&=<>m08Jovc)m>;eNF*{$+_a_s&NE4R2A zJheA)H+nvO@9ux{1`SvJ=T?-2E=)>0R0I}Gt(C=!#VAP}WqQ8T!@b;Ru;=yz;GA3b ztyMbwlE+5kka)O<VpLIT6IGdCj-?p6U;ROdN`Ypnl+xA6#%$)($YaMHW#YRCDkC40 zw$QT2QWN*d`W4hwm&Gxq-$_O0{93z8#)eJn5msH3++%9)v<1Z78~X8Zc-eATGPpJS zwxHj$$M#o}bEZ_vCouv#<x|WRt<v!GG2hFN{$3v_N>Vi&5l!pwd?S+dEF|i>>)n6| zQPq+xLSb@;|FCpefdIELj3%wx7g><zb1jnX7A+HbdLGgMPX9HucrR<BE#hi0(=4*= z?!TIM{{ZV7j{uo5)#8ff{v-PjKbwyzj=3f9uG|z8^X}?BA%}M{1iHZRo^({fFP!}m z_6KmT#eeQ1@@HNV53n%)eQTweBH3Yrs&;yJWKQsW#G1l+p~H=#KOB9fA3gsP8`%d_ z>!Az?3vVf$rltopl0!wD1U+swGjF&JDk1?X?lEDaenn}+cgc<aMU-FCy1ORkL%H&P zpW9^m$n~Vz5H(?yZ_#(;VjAm)%a1HX9w>-ws)Uw@=N%PGT)P_8oAzELK@>2Q?yq`x zkL3^jf_sIDDo*wdhF$f!k?klsDN^>Xj7-@Xk_I%@wML&*eXLWF_%1!O!s2&_>R>!q zoF--3ToCVFC6k5ESbRgyN%jT-L@f?2-!QR7`0{9yJx{GZ={=0V>+Io|b7-dVQ@P0% zN}@B{b2{uk6kf4kY!+9lQ86W$8XhXQ!Wyw84WbtA08!bPOx<u#w1>T-5J=mppK8MN zUZ?pCv0nw?OdT|Rr*iyya-lUpwMUZ<$=uDd(=Hc5`Zj|0mzIvGF8gU5&kGT}&KtCR zn|@&K4qdkRBt$EzIoFmQBEBFMYOu@Ba1IKSNQ|cE{l|u%_=c7d&6SW)F>`VCy-W!R zT58ceE%X?pF7iShYDj6$O{$2Ni=NI`!=*#Dw$kMr)`N>0`v~&BAmJ;uj_$3MnQ|CK zv>xJ>La1K8qbf*hgmp`$xYI4t_=x-OmF0_L&+Z<}A_#}<@e_Jy3iBpALic~b!>mXd z1s3I@LizzD*%J07%qIlyMU0YjBhxh48^RY!L-n_I@<MqkmnXr|c!)W#@2!$Te2CM< z-phHbo?m4uFhKRQ&3QyS0<mch;#gLRjF#G#X;&Y%a;S$J8CHhi4gf_gQ}ScH=`w$B zKdFS9A1R-mt`62y_Yg*0-7^i7?%!vpRlR})xQGJYB42vG2MUp;s-#+jM$CWkGNT)- z<ieF87S&ToEy$|PV=&b-!QA(LNpkgYmV;G4D>M0TzxKJxXq~31Y=x34xpX2>!CEyp z2>ZP8A|##+ij@coQo?wWowVnaX1j}^UeW9Jdp0?#_KD5|5*NhdBaOP}HBL52KI?EK zUMm#J_T17P20)qo^MM7F{=UsD$AxkI%D0KLZS6zH+fMA@yErNypsq;cvwF?lOZ|q~ zb2QaY&4MaDA*t=V5W-$r;D+yuuH79cE0Q^Xo(#xww_?r&th7X81|-vRpS<d7515-P z5PgHeP@61*f6tm&{{(Oi_a!2(j~^&`&f$$tkNMW<sXmxpuj&j6u}=;sNVMdapI5OA zLF^6514s;69tUC=FC|Pj9Ws=7lN)1y0P$j!@w&JF4moH*rW_BFKNoVz9^)m~qVCH` z?g^7$yd%HB$uVLkBHY=k!{ua#(Z-%9)=#WTvYiVt`291~up>m&^E^Q;KoK2K)HV_f zJ;mUU|C<3yj}%&lHKCOurpgEQ*^#npo0@YxmP3%fla6LyA@--$SNlp)r`V9=!C}e` zNr*Cs>o2hxid&TfvZn{I@d9tpu=<Bv;LtD7hcO<Dr`r=l^7ZPQ(J@&B_?eIPYB?e* z0Fr}{t24uN&ae5yX+A(bxfOKIGjAnr1+}JLY7{S)y_h{9)lw_fRQzy@?-}o>j6n>~ zP37V2S5W7j!Sl-P1^#$Pw+E4@`2aOB>@6*$Fm)jQ6{|bG(N1!e4^Zzd2%mW#$Oou@ zl8ib&pW_46W7Fhg!2c5X0QFzmpE;*M%!&U8s8y^JbNB$Y<VfnUQEy^F%F?O=EN#@m z`sC%SOK;Vj(#CvxPnNVVtsTrv8;`I)RsLe>oykbrWODDR8$Xxc+rZB77}iO*BwwyO zIh}b{+?!Nw^72E9B9d^kGB4CEEOng1%$a`^&pbfDw&NX-*Qv51T-w_XJ9R_;F>@o` z=%d$n!we`>;_a<W>8fMSMmG|X<ko5#r2nYV+;f@q+vlx;dWYX67Um9_+}H^>u?*?D z%ubHBlP@h@{U@bo8ALrH)sC+;&FagtCJG2S<Nu+Fhat~fY%zJJ4n|FdKc8N)I#mc8 z*RP1ZaY1)4EcG<x!Zt%Vykzo@RL|?c1i>)x;j#A(<cQsV0rES~AGzoxI9;nl;F4La zoomBxce&q1s4e_}SOcXYP1*B;Sw%WRqLQ{5b~8oHPna@B);#j4f9{>yKfPg`uud7Y z`@Uu*i{bqQWR*&{BypkPc<4EhJGJV_C^K->V7Z0ab_g>x!1%j*Syup1b~2aH{BWOP zpQwGGnA;_;fC=q6gQO1gQ3u<Mg8XpJ-rK4v>(-~?5KBDJ49|$iWM05zCbOBkY5WZO z!+F^oaXiNNvo`zLK-+aNX&G|$S#}UyBIGe6idaI9E^0Z{6+yZg#M1AUVS2#9Rz%>Q ziYd*+5~zovCmm|Xu?Tu|H%wCLMKqdq2JIb!ZuB<e=nC^>Rz2ZdseQb1iZs)auZ-F$ z3B;BJMnipKpn<94Zasr;8RCb&4f-|P6SwS1G0*@2G72jZs$m-}g%kw?{Jh(2Zt>}7 zy0bd$7#Wu3m07Y|oyG<4XMx&mZ^Py@+-sR9YoU<<=#NgB*bXLXnGv7?`A7oeNf{0l zpc=<<zW_wu7IKVhuaO9inD3OexHO9&N%D63iqn<#XV|Ackjok{foC{lnI!7I?lEXQ zz`Bej=&uMngU@t#&QPtTSt$cCqv;|ffS9R(SS>9pZ`8P>#uQVxmsig`dm9>+w~x<M z9>=j`*U<_q=#%7qmm9^eWI*_P3vVjq6WQhJTePZT=2bZtQnbq}Mfo}@`PkCSH<N}{ z<Lz#KbJ6SCmry2|@PTnB+_m~`_h0&0ZP8d=xMp(eSi|60<FspIyikm-=>;A$nac1a zX0k*7M=d78GjL>B=%}EvGhH>BrqWTPx2qzZc+H)}@V|T+G+ih!XcvQJm-E>_Q_!>p z-DMf_Y1#4Wx#Cz;Xi=xx1y1Hw&iIo-x6+RBBcq^$RG=O_L+45686~??OlAf(+jRx% zZVC$?%&_PH8LoqJ<mh_D3<oc;1AjRq0bfmnG`Qfs!yO>EQJ^yysNIpSBL(F1s8|3^ zn&RP9>xg%zZ&=a|G3XU%x&r0Vz?O${$K;0C(}TML{6_;4_?!3BZ*GU<8Yg3WhO5}a zC$u5nc*gI>r=Lc}Nt}k~Zt%VF@h9I7Gj^W>b%;O*-g9MMDVg~E+fx{W2QTIcTDece z6QSa;a9XdvZO2&-EOi^4?3{t)F$1G-3S`slYhjMHp!T{RF*C-6Xf{+IVoxd!t{4Bv zvD1*24<j-2LKq<&D8?VAUI90w-U)0KC$58IQj5be@Q8Jr;%<%yho-}Qrakja+W}<C zp&dk}V=w};wfd&KXId|xp<94^hNUn959llfL~R3vqk$SMAd2u@XO6DJr3d!Y&F9kb zGXnD4=`y%!8Fi3E2h9-&CXfXPI_b_j0s`!5S8)Ic2LO+HgQ!#>6#%0Gz`Nf30SsuD zDqQOAB2INa>f@5^<6<?lFKcEWSwOsl7C1DczfL>4Hlwc&BB;|3?E=)KX5;_T;*)53 z#My{{KvODxhURNYosB-K6Z60~?yj#1k8^xx_Qdzu1jq}D_=^*F@1s|JPg&jTG8N5e zft_83om4Cpn_-4hpuRoOn=4=qxZ@EXgL6Am%(E(n1c~NA6Qh|wkOjpE1yP?82eT*5 z0F7AZtT+~U&lqp@LWvnS3MI`IdSRhDt&H%MYlUmF3Pzni>vUUZ|8sqkmeKPr>s3;i zbV(k)=z50B`jL_u|C0S+qYip73TDXxN=wmgcp%F;x-uLn!J~@pQe~Y56jEtA9H7A* z-H1aYaDmPp^msSAIe=k4nqeNDb6<sF-7#-lnqf~`eBchQd_Ys{cvf$f(RDY_fV0@O zM$?*G>|I-Y^fFLxd$DhAQJ$K90G}>5nm%|mNDMD9cs^*Pcu9^bAjU}-p$f=$fJ{5+ zI_p6O{FZ0jbBj%S#m6I8t&SG^%oiU$IukMPw8=5#!XxjzTzGJF(H%55^HMirXi@9R z-ug;rEQ=YxUFJI{<vY$GkzrP;={C_IzfnlCKLqN<pU7l-Y?nqZizw(pUWU_Pbt(~g z_xFX@_BJpAcDs{n89xYCwycbdR2ROOAbwX03%Y-e8~poWcQ|!C96KMtg#el$mtV>{ zRk~J(qLThXzOot6*&Nub9C%x)V4D>G3CI)6LMN7y@5n-*$m)x(4Q_oPDAd_-MHCJ7 z^<D`ftw=<!NS<DiiVV?vi==nqo=|g+kTOG3v&WR}thUE_-!c#6U54oN@8xNpra;b= z!uHosob_r^+x}nUq*^M_gbcFgWxS;noRDI;m1f>nhg?zSCU-zj6SMZh<`^ZM9MAN9 zag^2hC*!VqkRx0r^V5(c%NbT4467eu)&&{XpTa!w8CJUC)*g&VBJ6Z2;!;MogLN49 zNamUCQBM(=>xJyn(Qv_ux5>MQ8MsiQL~(}H8pj)cn8~Z%*Xt9x<{P<2xJ@jb>oS;c zKf9b650q?c9PDv{2D2ENESe^c5k_U^n8^fgS8o(&x}>^zZ%bW2$F%8~a#ybkzg-$e zuKg?HRgNvbPDOa}z*-amNdVn`H^YSpaiV0ns6(uG!KYLisj85gb#N@4L5$8)e)8Ic z$uBmCUTkBw7&3*^ijPJ^>5kDRrx~7Q+00pJ=85QYk&wL-_Ie4R&9_anVFN~Z8{Ggj z_J&Fm{|kqs?qBYO&KrbP%H8mSS~5zlu6`Q*FQoqfx@V>C!?hFr<?>_Un7)Vnv3AFb z9Tn}#cgOMQMxz3H_>42G>>cN!8jqoPDX1^$%_cVUR1QdE4y4Va);vsiB^4YtEvViF zyAvUSeIja!kmnjhtIzkb7Oq8=LYbOS(eEYqatC_}BVRw_$;+~#>QHV$TpTMlv~Z)G z42i1Ejvj>$Nj$5EM^{joQ8=jj*SH`!G=Nyb?Inle%Z}j;lFWqfsxwjOmA`adLd#h1 z4c8~Lo3pzNBA?~G{c)k~IC^|Jpo8&s?c?6pHH)|pH{#~xkC!suR6|1H5ZtbcA`TMD zVg!&NuWv9&JZqm_=pj7h))d316mor85$sxHx(q!*hQ^T@L^$(^Da30R%-2VLNG)jo z#5_y_X=7-v>rkIsMgHe}znk$>0<sI;e2;r??+muy&fbx^N5UGV)ViEZrKC_HDSYa` zG{ch!kq!c>u=z!08%F9h)X#0q({!V(bU7SdE=xf4;Eo)HaKIEOl}S??6<{<b4n5eB zGfkJ{vrb%)vFXv<$@6s^bgMZ~%tw%y`tT9b7w@nPTXKdAf7r^)&``*5AR%_$=nkw& zL-ypspI>mWQ#;CE^$&jC+YJKSkurSvgC=NRMi}fGk4Y1OxwGl=rJ!{@1$-EG6AKC5 z{%U;>l|%(QQ!`Dt0K?kPS|rdd-M~;Htd7cvnMSLoGkVgCSq^2uKq2ODVJ0wn4`=J6 zoa^h|#}`hdr}p|pefNFMv+c&Yccd#j1MZ+`fsc|UYX!`&QzhUu|B>(H6xv3T0HFgc zp-xxiBnP#BH;Vx7a~42#@Po%_gASk^mnH_MX^+yd&NSuibVWE#QHrJ}MYGGN?#BU< zxM`iA0ty^jLgr89-DmtCAU;7roS3f96_DBf>1YH_*oHbD&j>WiaFp6jcS@z1fGv2y zi<zl=GRrgBHM@?SU8j!J+=OYzXaVhL0fXptiPQ`&Kq~XS4`Cfx^x6mFOf88@1C3G- zO;Cl10@}6d;mI@^EQs)M=HbV*pfzC65b*BZKxZ7?2?uh<{;rHVbIa)r|LyXZ)w<V! z`kTM&+Rq4&Qo&i&GN+6d=lVy^9r?Pj_+_v)b;ktHzhz;eyV<Lhg31#Gj@$(E+Rt_X zx*ES=HcRtQGNX99(2sxg!DH@3Geg)&%;3Xzyy<xi%x^gZ*8vS(heSF<een<t3d0x= zK8~Sz15~`VOTxI&KN*nFQYJh-lQIfU-IhBJKiB|=U_}^qoPX-0bo*%L9x}d;<otF; z;Bla{p`e?;RcfHtBvm*SXu3<2;e?`BPiqs?Ww+CnxuC<&paguHI6R$yf-KKX=gUjx z#(_5Kdphc1Ys!1z#rG*q{v|4m<`X&p>1McMV*jYcHvgBvPf(ZxvJNxs#WhLJkIRi1 z>&ih&8^k-VnP}Vo&?$!!ixmC*`Xd|Tx4iB-mJBda5}Mu|a-EW6V{w=7G`~)^t?7n& zg?Y-mt-9y$pC;SQ2<mhdM0>_wH$Lua-$>F2c-45_jTOh+01AunX1Cs=)Q)f77T_kw z&2i!f8b8K%9||<?IR5eR7yHA7V*8K3<(MgDmpzD_rriZb?22pe`MxMOda{Q6$Z5E& z#s{c>>AxE<H#zlb>zBbg@5tWA=j|RrMfNYKE)9-4Vp1-R3+nqMUEtlvCJXk<4mXNv z#!VGzbQg~oYn^%D|M+=^`v*18TU~`-e(u)}*t?Z#hunWW-5S|qj@qC@CrWfq@H##` zulf6o)L<M_{%sH@txp|34^mE$*SNVZ;^=2Dwd*Kfk-?}ievzeAU@X!UHetR1jzlrz zkA_VcNi?-c8B7yT<$G>5hUI8gXIy?M73QV~O~H=>z=8%RaG(N{6War5tN*qcqBh$1 z;aEaJ(q)%95~xyZ!LZ6*|8dqRDK(m39;Y?S<~LhCnBM1x+Z$Lq`9wQvB2=O@raC54 zr+v5I%`nj%gu4C|FFH|?1T+{oTyZ}oWN`B%h-wWmyyC2UH>)`R;A1(ukiMrXs94Wa zze-5IOI;MD)x=#D)GJSALzPmAijR$Ef<%$7%(~V&y-ww?xq7SvN;3ZsP&fGeTxvNS z1E3tp;0wgxxalpx`<Yr<xKM=Nzl@z>^WJTyyX)LGv`+si2IPKav-V4tNwMJ<m-}0W zb;t^bGTJCYnG`aFAuQ{SYTWleg0lG0@x(*>e)LHX)m8Ps3YMQ(1hnGM^NCEDWFCMa zQ<!u=m-w%7puqG+Rz<zhbEzXj2_vR569#+deF>GGGjo^6#<Q^c4svdz*a3t-i(~gt zR;sxVO^^)%i{nQVhow(qykP1CnbUJxsy;^xw6>yGT@89sRfqJ3Dj2@FM>zU8ZnW0l z?Jl4qK2QI#)RDT|$&2SrUOmR=lr5ZkI^o8q0f|qU<6wHO9`(lgO&_XgO|I@{p1!NO zyP*g|$s2wvKd!mxWU2PN_PacN@A)xPPF+K<`R3hj-C|Dj>w%{>@ElR3cVi>aQN6l# z=jg$uXeE2i7h<bIl-VBXIz29cjM5rZKCs{PE}LFpxtd|{RJp$5a)I$URzFMTqsnDh zb=`iFgSc_SeWxEQ(Kf=C-#WsMnC(@pD>C=l<98gfRD;_N=T=}gc%XQJBLm_Uf}!!i zN*m7wkB!<%h*=J4+7;%w&*h06A_1S$+618S><n36ACyJGE8{*2(a7K<%FX+v3&3Lc z*fOE1>8KccxbD3Ah%TuwC!X?HdJ-VF`~wPb7WkCx(UWI-La%)?<FQN?bwsm`3qQ_D zN6hjZ^<q~vN!pGlqWy>UZ`2MO-EYo6{uXAl6(W2A1A;BjWf=7jBaGn(WG_Y&3_@3s zQ9-MuH_Hy~p+<ENqLsv6E)OJ;X_ZGUV`M(DM=U4x3J!(8-4`);O!a-C)!|W)XmyaS zTs;S9SX+s>xJy4^H<i8TY@ZG{GX(<7D$%0F1UWkmr<u0q{6avc$Z?Fl>?9eij17Sq zkO77+9Rm9RAr_X4=mJVchBW*QBadvao+^R}-s-nK5C_#Edk)miZ;NXdLbbeA?q3|* z(7V+9toXp{@cAEzeAby^14?CXQaDY%9#7X%7Jxd256Ild32AfsN`p&L*?)V~9S!QI z#{RA<@XwunO`D;VT>&|J@7j_#)U3#gHK{hti0n6Nj-Q*76hM6#*Q$qd$7CFx=0QtN zMARHpuX3rA%8=d0Wq&^EB@Vp<Gk>;%PPsjBb(8IAG*}5gqJ9gdzs?1^EgML?@%4+* zpp+6GQ^k94g&sXIzi$#pH*BRq@#~YPs{w}`wv!vGaSW2Ra?$l=`?&mcrnawF&eQX{ zv24s^3x{^8;oDo1y}JzWEP@>Oj!3@jKkaBhick<~K)Q;ODYnGU_o#^7--652zC9&H zo-@p6Kh!yKYICrF=B*IooS`+nBWV2%Bt)BI=tiGXdj;T1Z#ipPL>3CQVL+Fs=htv2 z``W@WFsX44OLcbO9>RwpIhr`6%NjtmuOE<T9UV5mub7M9UV%Gd2+F1_IWWdSi}T+T zf`fl$ihrLG^X*=lKGr-pL<?0Bw;a+)O+=6?XnlFd8^eUJT=oMi$$X6;4()%J`{bE# z`=076pAJehk`@~(>_r)B;e8>IMvW!adiD4~tk(G@5TJR^LASaR<+UrouRtDBT_7VY zj6S<-3KFn`A_xk8pWNU&MvLMpRG;c6+ad)%Yrf+UxzwK~rt;F8nw}d#td;A@vX|Q0 zWSBJeU!5-<K1ivI3L+QFUik0o&3`=wHcqR-iDM9>a>c_s6RlIVsoECvX8W9!93>dm zYFW}(kYPc-nvW<q3J4R@syFTqOsPkUE^rH?7<PTNsRj9mU{uwduGzNPX3p*YOJ}AJ zNVl&$*!*6GC5<CRs@EZgp+k4Q$W`*5>h?))u_(Y2P_yQ1lWA;-yk+Ap+X438#}8QX zyimT;dO_XE%(xP!PFX|ML=T&f>E#FVLZ3gd8@|H@3oXzD^*eVRs;9&A$m(IQ$zLG7 z*IP>q-3Mf-kBO;L1Er_Dlq5%pj`Kh6?vU9hW+lGw-X$Cpr*6>1wO`RLui@Y%?UKAs zEIPqb>r2^lxhhJAQZoSK5KcBawXqCR08Vv>*wba6mwt%7(*iaBrX<@w%CM1kT8#f0 zf}}_L8r@bu^+pOLY3taoyKe`ovSi}9(+dqq3dyTu7n<Hm{L`rTAnyv}?rWB`BaUi2 z6>1sr1i<gVDpLGfE_y*f+P-RqR+)b)&khlr<-1>5ao=${`ZD8@<-5I^(o+DgrzV#K z)$LG+BhtfA=dg@}Clpa6w@|TXbskpz7=~}21DkbA=Y73()}|%hcbEiy@!>jhw`5f; zE$i!^>D0T{!#kRE;fb$CN?!*SjenQj`?Zu;iwtr;vF|LAt|9h&&LS}AI63ye@6YdD z2uk+Wl)r<}GVim9bX&c&%qmcK^vpi&Eo>JQI^w%-o9PVF<<S_*v>6q;vG&0G$N4v= z`o9idGqeXPU~EOQY~=@OrbPtfTIn}Z1+NW-aT&|KcW(;Ddb5*cEyHQ6i8GQIn#-W; zas?JOi)~sLk;MVEa05nzwsM>SU1x$?ZHDm{&1f9xZ91SGy+_c^vK3jk)r317U<=4s z^cyvnm8eV_VQw0(3wNso8?XcQr)fj}H&Hhf9j(wm>wr$)=?D0^eN4X=E+oO3v9D55 z{@sfA+km#CASJ4R$cKKz);<OA0Ym=WK78OHp79C`O6bWpZtRzpOUJ<b_9p=?*nwt) zfo3?mK@#wMbKv{~V3$APVCvDL^-9g^O8weWi*P&9T3gLhpduAW`~X}|U()<^Kz^1# zNCC+@(~K}6t=quk6=2P6noz*dirm2E3ZNWYAUzc#HhN>rwohk&Uxmt8XEC8f(L?vk zEz|l!ncrn<;WVufkfIyVScqV>{@iqURd4|WXxyX8Qu{<R_|`<b%VjhRmjRser1!ck z4nA+_rYMsHytoEb1JelR;kO29BnmqK?rl1z<k*B>1{CGo8Bk~UVflQtww(-SN^dF9 zv0C}v_c=q$K2h)eGF!HCt+whJ{S7_@T>zoX>=MgpRKt6}e3BhKYvS5po^T?;jO^@g zi%#H`yIQN<<1STU2Xul4%*b})gSHy>LYiB4MoWs`%saKo@_@MkRk^FCqyf!npuAAJ z@N~LrlHI{Pw@k|cjc8gL_3b`i5N`Lnw;Vz5EseY|=a6$J#PN>)dcS7rll`@JvRFHf z>2!3!fB|(a<d|wf_JAQv8dsa6F}f!pkLj1MfW?$l%Wfaaa2tS!s>XE{=qDXDV1raU z`cy~Lv6z18ERYsyY~(?8LacYwyy9(Ag))Z5M^;Bo2Q-p^8Oi;crdf=l<phtKdw|Iw zWnrp=>2gItZKAC@KrDb*lln>`0Zcc-*lFbXmRTLXSv1}wy_7l})r4_!ilm8G0A)w} zbl)zct?9=ft5Msgbp9UIbp{;-SCN7E@LIuAa4r3eqbQ1QKoU{K*|l3DzYR{%Pt=N{ z*7dwWPkaRG?ID&YYqKMv+bY#MI903B^b7ZCDbSpyfA6zr*PE95@5=30RG+WbCXCFh zvrfM9u0SO&(TsT@WzL?h#%Q|o7Em4z)Z(A<f;EaSKyAK}{N?C|&LBm$om^@Eb#{J) z?}uz4;Y0ju^XPuZ<w(treg(V3nwRS;&M<Y}0^6NwSgC8*$2C}A=<mfVbb~;aWSSDY zKdh@CH|Qu|D09<zBRr_i8?O3<L6aMQV_-i}YQB;Bj$pl8XZo#Qa|>uvOH*4)S5B?d z;PhihZH=cTdMDV`!<znY`V~v;{O$m?<OqhPA&tLPn=!dI0BUy@NG}zrdRss{!%p^g zzplEN$Z`MbAN3Xeo|MV{1g@Q5r<gumKHqgS0oY&z&wab?BtZol?M^D-2h61;rHt0@ zjFz`gYBaC!5h?+I_MUR#-l`+R4XMxKtN>hNR=OylUzwaK{|&8$1Ikhajf4mxUmB`s zL7GK0gYbbcV^E}R{JDM+t0p^zB$~Y!NU;kVp8?deBzVt_^~T2MkD;5t5zHuRC#M`M zD$q}c)v~=o2mYc<fdE;Iok7pzH&~IzSB=@PDsF~CjMrHjQdI{ipz4L3DX%CS3P@{f zOQ8{@rx~yAMi?krpB~eA2*g*6A39J9oZ@fna@OvBB5;0tq!`l2dZ3^A|K|+1E;W73 z-iLhV3b|fNb1k#0*sXol7Rk}<S7@{|7|bqw_ugD;WMwF3MgI6R==;}Swyytu`Bq-l z-*@k$A>Khxd8_}H_5xAi-U(f5zzM^oVjXIXAzL?cvcR+`@U}PIPEcg*ckPFIovjn= z8UKkKVjTLMqw)Zuh10%lH0WrgzK+}a^Z|V^8TwwwjV>Gj8d=l%7WvldFUVrqPT!lL zz8z(#Ouxi0$cj9e`O3~9Puq}v(EA7JlEV~J>V=Uh{g+;CdB<m_gwk>R-T!(&FB1n8 z^r!V%_kJ-K_srFQtNXuGrMSKW0i1!r<CAYp?|n7jPWn=*ful9QeEf!d5W0wcW{1<N zup9krr%!d6Ys4YjamY*x$xG`mVpCz>uE~)A4`m_`F_1qg!UNmKLp~T#mgY$uk*|BY zm?-7Rj{{BlTL#*N-j)Y_++K?W;{eWy`#xVWotxgbpCh>#FF{a|`$e~&qkpDq7-DxK z&gscsOOU!rlI`A+%~X-@?pHYHRC?p!>p?vQ`i|U1Uxg<-3Sr70*DG`>lGW>p5vk3q z>V$oe`&eOpN89_#gthnc+VE>=<%E;UuUGC;?ko7+_n`)e`R$10-nYC@Px0r3mwx$F za$jrYzP8_v_@gfhY9HU1>1ua>5x=Uhxw-PE?u$O9MAy$j`_KKAiTnBoTXb)p)Ct>J zsMl9lz=`eY%a0Z8c%AYYOf)(>Y<ST?rDbRPRmINaQTPo5^BM#5Km(aqazD>pH6Ph) zvAp*(V!XxbwSo2fQ|5<;%o9G@001~@i)2d+YHZR1nbi78&#rsN?#Ri{2m^y_`nET* z&w33E>{|`KY8u!W=)BO^4}>^oep_*GmN^phs>0Cq(3t&AY|Tl{pZcM$BT1U|-@@63 z32*bgM_XT#m>xe{4?95s?AB`IZ?21MO_NXpeeKn`mJdmKYH=sMoRYCAU+Fom;*#IL z7e?Tp*4qEP?{h@K>FPJ#i$?xejr>QVyu*@z?>AHkhL~C;+XXVc4;utM{ciW-!O@ZL z-ftfq%XAEA`2O9+AXwNqM6xYJ;fLy~k>^jNDB_O)DMRvW8M%io{(fx{!N!qMZIKCk zZQ3;+FTu&K^wVxmr$-a(IsM-b*R;jnGmdL-i+f}oKhhT8{-XpEXX6v>f6*`|Q^x*O zTf&|(1=dc9GsbZUo8#Y4EH3ye8J{v~KV@T*bU1lqj$g--Qn2=g64ib>!6YTlL{_{l zd3E-r=z~zF_OzQOXC6JEoIKSOlyK&e$+?mCb8!aPrzvL$J7))y)12-{t{a8Dp0i!O zM-?_rm+VMaFy)_&&<>i?O*-f{rWsBh8Sn2oLcV1Ln=%QeQFBG<AS&}zN9N61@}f!h z)sAchV|>(f>djQId#yKroc?vXJ@2V${)=7hEBZDeDfwrUNC`=oHrtdRb)+2qh7;ZE z%vUhGtk#)warV=`yH}J7BQj0yu?*~;1pTzkN}@VTE+&g5Oh+6_lYQ{bdly%BwX^J| zS$R!o`8~61SImT87X^Re2QPmiE~Qm`J~B6&c4Ht-einGM{g*J^?8Lv#<!O4QLYKE( z*R6x*RVH0kHs-f2&fF44-$DMqXK!8^_&ci8&?&j7X76istAfut^Sa!w8W6s2uceOO z_2-UxU6g!-<gvy9^ZGzWecYK9$b0$FmMv~V(=T(t?wNaE&-kpHH?>c3_I@`X?EX*2 zqQ%Cd)v3Gnu*Czv?gzmZZBgBA2^Q@s-R&1GIx@REE?IP5?e4s3(N)vkb<d)^y}SF- zo<+|{ch6IchcCJxzP9Ln-`)G!;?d9UM;04ayoQ!N3)!O@{`<~FCrxvedN#+=^-s+Q zjyO7@5bgHfX47;lJZ12a$Deuntpv+R;$L$sUyVjPeM6|jPRnbmWz#O*hQ;K#dcK4V zEcM`?9CmnS{g^r4Z(auu6ADs){WmIA?B_GoFNqf3W;y3Kuyh+5W<Nl%n$@C`)(RIc zs-5=%8=Mw3Fx)%)Y$0R}Fp#Osr0GcL2GJMeeG@{@*PNPPN&M&B^3W$J5QiIfv+~so zqK}PQMK|txeSH|XIHq5lXMl5TDC*btCZzRiEeA7SYn@y@Jmlu|xZ0awP>~TbxMz3s ztzD_I$D-baw_iDKnby&{ZL45{ZjiOM)Uc-MfFZ?t?(%=7mwLDEwJ%k=Z`^zJzOg^3 z|H8+o=VcE=fv^7x93<d&?LIl3SDT*Ok<|HcQQv4UTEVF&s;sFB<FsKxn69E}YeRK| z?s;Q$mK9q3{&bw6C-<DyD_yrUAPwk9K~wY{^(cuS-=}m3;-(y5>Se%;mN59DGc%3S zMo0UK1c)815JIM~qGOS1VW>l{q+aB7M`4)LC58REflz$7%M~@xYVXd=YtF2LA;U#x zS0X2}-kg9uj}h@dd~?)Z^GM{lRG;4+e0q*g>w?F%!<CN3=Ea&bH~pF;XS#~_8fNQ* z`<UX3g~1QwqH1)yAIyFr+#O#AYLzt18y(|ZzV*iEXXzyQzz9^rvXl}6I4Yv%+cQH6 z8@Y6F1BA(OS97d6cT}|f(?Sb5E`LA0fwMLm_V}IgDOIhQI<K~JpH10DweZFE#MjWE z@|1+vTBl%=)<z08W6rf$TaO4#mH&)!@U<UlI=JgcU7%m@#4S9Cbox4WAT_@1bmYKP zji17)#IrwhUyNM6S*Sogv)LNc^6t=Ow!z~<GNHi3qt4MFu}P0r7Jk_lTDl?s?NCi1 zvvaMq>vjlA?1iuAaCc~t0JQX%vv#5t)YHv#NZb=l9g+;m({mJ!xm_q7SGuS1PBM0~ zKStDcj)*qHy^a1<<e$^GCN%-Tj69Ajx7==wt?t}z{LJD*O#$n%@1!H5WsfWB4K+@U z8$|rRYx2y|>-oeL=aYgHW(wWaS3F|<^&iDh)0ky(+YPE>j^M&oA*BraCNxee!W(Uu zQ?xo|Pxg-}J`!HGCOy&N|GwDoG7VA^43AZnynar4_@KG}@$XeXJ5Itavd9j@Gl6|? zG8N7O*28my+bLm}Yz_U_r2o#AsmjFG`@{NTJIWv;_9cK&rnqrwI{0|{-048+QutLt z=@Rm-MdO9qTPRz&f4GPfK8;ZkZ`#dtBA5Oex*B|;juCwE7mBo;{%bFJm`u+Vpw@=w zC?YuD<xAAxn9diGJaQ7hI}hiZeKK|6>vrc?B@O<MqWg?Wx?#fr4zicxMqHq#m?PXH zHE?CQ_bzbfBvUIND{$uuOUqS(nrW%wsLU3Q)JzL=q-IaJ%Ct<&%6cka-gEfG;R}Zk zod11a_wUlbr+Eh8VIQIpL11MQb7R8bmjdO?=8}7g)l2sM^{`j;XNn90Zx?z_d1%0a zNLdH0f_llWg#cFe#b_E|3{~S4Ug~8_-6bDJd*&X06h8apV@K-D^84F4;_33C>;pqj zA{af_E_QFWR?m0;Z270<F;F68qX)64h9TO9{g-s+55$qSmMQ7k|3c%|+?QvF=NZCh zdaCQAruz<ea0SQjPcMz{dFlJ=)Ueck#k51W_NOJJ&19F_%rUZxZGO=rWc^p$u3tI5 z9u9l_sx(hI?N8^uhM&J{c0#YKF6^|4-jFeHC^Z=1rNOiwIc3521AY#icNW~$P;z;M z7(Df35TSM9=LgjsrS$dvc{M3jW7jH=1Q?*(Fl^>5DNm<=K>R34Z~&9Sxq$29uep*l zCE|tO<W?w1w~f?RS{{skw=xyyp1#KLgI~_Jdf&o3scThe8gjjOQI?!*l0A<Jy=14f z?vV?b7%)oiBNN3-^Bs&ABugv$)eP;=x<=ptSMn{j!<Iz3KZweSOHXvg!?0&p)Yk9N zatK`n(dLIGD`4i@H;)yDd<4nQlk)YG+lmjl*sI=Q=FYXyF?o&la_bzRD4f7H#xem1 zH-Ls2LXa43r(U{-3^qi1vGoad^4+vN{TLRsW<pF05h#W!V?uU&0OfdWh)-*B`Hhra za?QeA<LBoucFu|61OS*hAP&Xg+3sQ8bEb<KoqJ*r+H+<yTW@Y&ys|4xtKuF^+n8Q8 z8K0?G#mKXsm={lF+Tp)@6db^Y)m*^7w|IIMX5M<?a*|TN;tv3vQcu6~rC#gjN}&76 z1?uIG+2MNGi<+k8C1#+615Z?JyYpP*3oxPZTb7&75o+GGCu<^cErc;^A-(PZ+*XRR z3X*@oFWb#vYA1P|J@}C-drBBBJuEnIaGQuA$Mm?0{5FUaMQpe52uedBCd&{u7zkP7 zJNzHkC^8L%9s+>W7*0(#e1NFm$=6N*l8H$bCsp+MKipk#Fh8?7Qm<bn=B%If^JIzB z=KaJGtUqqZx7B=w6&ftay1)7jY2MX)82ArF*UFZceM;2Y#F}=-^+EzR_~8dO0wmZJ zxGAYmnSij_IK}F?{7pBy!y~U4`3!Sn=<<;t9zm1qER50<kdmmC-ke95U@#JnB<!7? zyzyOb1n!s^>#LZ{kM3&gc48=3h2%|yXN|rQf@DuvzdMv9KSO|OcW)v*Q|c6j8~T<L zl7;pRHK`;)mV7)`!s)>z>JT#%_b=eB*@&6cH;lc8*wMGYlQSPT@ym3FSv#2cjA4^& z=6w>U8A8>Mlnj^1RVZNufN-CR)ZkAcqu6>$N1nlTRyL4K>_Ti#K>t+c1~iQ+1YMoy z@1<=P27YXHAFUX;h1<A3e3Z`_OU%}+xq@)bCyX{O;_dzR8x>_-RF_xCCArWc-Yfjy z#@Jl<lJ+ugaAeNBBX^fU%q8zkg9~Kv$e|KxJ9R??WB>Y*gtV{KuCFAIPV_REHy!ly zsqc@VK}T*9ax`t`^V&1BWL9Gwbi{h{%<O?khanb@1IV$hn3sG**>CAGUl3JqYh>}< z(bVcPCb2AhVs1Odlu=ep_xXV9BjW{Cq7N+N6hB~jOoWTjYX_T&y*532>q0x+mKiqP zE1q^=ZVVrJKg!Mt=<5}q5f?CrR|JYPZa?E<e1iM%n%VOv-NhW#u5dhKvn8Z}iVni6 zzY$>7^pYh%hp(vp`z_b(VFDKwED)1NFU~#IyDrTXRds{pB@>yz=$t(@^O)n?ee(L{ z5x6Wmx;^)FfM<~#+xC9Mr&i0Uo?;)31reKUEB=6d_{$@G+0VGay>q4E9f(bZfi8&N zmlhO25T^gM(d^-(wZ-GDY=u7Zucg{e^gaW1Jb;w`n%Pk7HJP)TYVmCHVfeRqPtsTY z&!-zn<x`?W^yZ63sA%z#(uMBBJEAyan0JMz{`BrB%zF9;mneqJA6(M9`wO<0$vxg9 zab+XN?DxFn)e}#iMbKp*m(B*vM^i5O$_NR$7Xnyt8%od8p&>hsMq-~*aF+6A_Mo{> zsW|6Nt?&uQwLmU0@z{@SQ%6<Du~U*o_lEY$Pw*V{J;uM@Q(DA5ymee30LTb;BKba| z<=n{QqG#N%{&L%Qjy_dW`tjCv8)n}2j~><2o99%Y18DpA7xZujgVhzA365GeW1FAO ziz$t+!1nTb5GD*2WD?w7XR2qsphw;h_|e5(#Td9R1&FJq+A3`TiDa=|46$AP-$@%{ zyF7>~y<&UVAOjCuT$os-7+5P4{Gz@9Afd2h!+-?xAfX!&IvE<tfF9vN69mA7UFv`5 zRb^}y=hkK1Sc^-arTJW0+t2AdqAZm4wS<CJ0|Ji4<5GbCmH+`IR7JP>Eh*lo0wO-U zSHn>gZPB2G%igxnq}q$=(~=bWd6+jm%-KES%M9@kY;iM3@waRTbf4-rS#@O3pD$!A z<R})=hQ(}RB@HA!K>&{dwQaUPpDG}o6HIXNGMQ6eREd86QonFVjHgrslusra4`Fe? z-Yb!T%I6{SMe_=$Gk?2@>Dy<nQ~-5e^5j@za;Zn<owJOg;jkT+>R<i&6K%NSO<bu# zim|Q#4U#HFeCb!uxLT6*&K5<Ygn}rbpuaGsyAzb#fk_u%>?xa<PwA0e>5=xjr4Yc9 z!*4*}Y%0$is4O2<F~9;GBgi*maK1bh?M#(Fo2o!5sQd!ZHA?k6R~5jNuH`=@BuF3Q zFO?9M)mYN@pB2~M5tIb9(^|@oL}@_}>`0H1ShB`}b`95dD5kDJMs34}tnT(@7yY~# zQS5V>GZF1&h}C<%MZn%EeO#jjm^mjb17n=U^s~j}Q|QW~aInbGyD=}v2I{A)DKxe3 zZu!Ci+og8znQv(4NDc22eBAve0yFr6Ga?m^y`iZdraE#<iJ~_+_hmd62uPX7Iko9j z^vGPNtGwfS@8km$%cz@MZbWbg8Pj1Z?oB4z`THd+VAaW3BLnF=@uz(T4{M3v-Sm_} zT1CVp+dkZ#&*ThS(&<5EL#k}oJT45V5aMZQ<h}d*x(VVKF?qu`!dpGj+la0PQSBgy zcpKRFqV>GZL`^CAVT7}`!fY>X>v{E~K%z#!`L$z~P2QGwn=Q{8?S<L-|82dSQfpaE zC6*i`^E<3YznWk7ra!-6dAlRxkOt}WJn}tVW@=tLl|{`Ciy)~*ylb%j)3MtxS~d45 z^_`={k?egtMpTCjI!@!VFXxTDrR8&b6lCnEdNO9~^D0|M{q#HSK*MH5UJ5Bd`6;e6 znWePT&ys6Zm-p<o3*9p4eEEB0dBkVIA;FmZg}DEi4-wE7ZolBnpehP`q<?$K7g2x7 zX+&VR94n1=(Ju)K(h*;z9jiJI9&>PXUeqcRmk(hnIsySN=kZ}wg)8)t<}DXRkogGO zb*59(gS;VSw>zl^&tYjlVc}2fn7vMMf1GI$d%+zjtMQwyoG#;-@BYD$swm)Eydug8 zq4{DaUXN=%Fg{*-Ch9&?ZVEmM?DH05Tm`>*+|oO*1K+fbzZp84_-ZfsycNTx%;TTa zWvZ6tQrvtKd^H1PbrMtk6?^{+D^;*p!`IT)i79vn%jBd<;NDCe%Pue})vnE!v?Eiy zMP{i?_sC&;18=9Qr=$k^rtYt<_sGfIE}NH2<0?F-szlM1)9Ju+qWMih@UkzFU+(1} zacGxsYVJ|FQ)>7cmTX9mvK3vXi;nj@=Cf%+SI7(u_Mxkr9GoxHsHN}iPLZkdRth8j z+M1wWkPYjLceS|Vy4I(13WetYW4fra13;A<Tzrum>6d=QW;wmjB??%+H%yPVpRV+d zg_|PEr?6birlQKrqZBWaPlXw$*}CLjj8TqNb|Weq&nsCGm7de(`nk3M0R6Hl{n(_| zK@WvymV5WqK2=G;3Q&50s`7l^`!?PFoDXrhK7M&J=2bKL91xF}mE7^8<I74C&l=hJ zepx%MnOr~l>zy3q<Yf3cIipf)fGaDgf`h5x<9}<ws{M`{HOR$^<GTEgNy}-Sr^?Ou zAI+lUQwC(z?_y-A0i|*&afVSw@@WUkRlieJS6K=*)IZG0k@_!3xjizbT#RU=!kL$A zotKyu;!BLlJ7sBHvvlVr&2RInQgrE7pgsIXSGKR@EI{6+N8w7(33Yi%7a+ct7<KLV zsTnitEw1WcmUK2pC8|gM;yf<Go77c@`3u0;P>D|7^4mW?&faBW%*|HqRJW*heFTZ= z^6htbw1(s*^IxUzKZbvBNlqm-O`<EydRsg3ymAl~4&W&4gxu=VFhB8{CS72L&)<{d ze>W#?GwX<`q(tptg1@SxlSD5?=`>fqdE@xm7xJC-plO!uMK1320;!sd!Or7f%E#x~ ziK}Ybqn`_FY|Y1C=H3g?<NBnoQ<c1^O4%IQ2Cn?N{Gn4Ug-)(?1QR|-kfOLA@L>yU zd+-nBwd>Ap+iWEdl&`k-?*%Kc5hvNVi1HU%3e5p4;;n_sf%j^+K37qd{w1JS=jCJ; za+2uEQB-s?6W&0;awu>$)`fDgzNTreUYBN3M>2Xaxyal0G*uxiYqgOm7e<v61+EVP zWe@gTV*R|7BWjJRyyQujiz3RcWa4kM66~`M@4&y5Ui;~{&hnq5OH6SUhPxEX=(v1$ zxhbMlHbLSqK_-B!G{urGV@gcV<0Du&KNc?CK6)hucjdTx{sPs$AJ+f`1T+o<EQhba zJeq-k2JS`IU2<uaGv{l$m-SwigbjezYSq*2bS-Bn#2F-7*1Q{6R!L|tsl+(0)E=vH zwX~7xs;V2y=p;&PQxp@a>*-vTEdsK&=buobY$FTb&sFK?L$Q&tY_J5Fm~7S~+yBaC zk8S?%pSktnvQb=VDXR2?{Hr0)Zv1SLXso(n#+CD<`ta2cMd{krQ}N039Oq@-OkGP; zJLOfX(gc;Y+SB4d8g%?5OJfb};JatcgZ6|0O}n!zkMt>IP?NJ4j=5X5q15fXXJu_5 z($9&=kRE(}51wR!Ze__#5F{h0c)2Pp+Yau<QvNqec8Mv1SdalfK4#MOTin%(=vS{( z<I|}(ergx%4tMgLq`OIynmr}?k=X607@-i+PD8!q!+K$u?IT!IqGS{cw>5<aK!UpH zK@AR=2@VF=b2gd}Pb2iPY0zH9Cn+3E=Y7nHyh0C_qz4P@LA<puQt@4I^J1`1P}=Ik zs83kXda|vB|E{C5|L~8f*#Rkr5kT|?Q%R`@{hOa*!G(y=OApYMl(^_SJ)#JU;v<?Q zTo<Fny+ohK?@SYAz$|bPKt8O`h<x{ntfPHYuwui!O!j{j2MYt-xJmc>QlnNDB1kz^ z^h?~)f%<uTJYCw0dgEkuT@?iu7FAUr73;?dsh}ac-b*wHCAy-Y4Kfkk8R(%%gs8U7 z5Z!C|vB#7TN(1yxWx&!n;;WP^a}cZ?UD0$&c8(<<+mh3oO*p+ro<Utd4a9wSux;+U zTar&2TKYv1)Bl)kJ@fT8A|p68N8+XeAfI|IgC?^wFEz_mCJ<FtSSlICSQ>HAYF=uC zplq{(58@)E=4VX7a)vMZELq)GdscA$TA8e?U&Cdks4c$;l5VWx(EXMTps_;k<5NA` zJMpZ#ybwNnVC5xId4j0y)T8_|65_`}_)(x${A;aGk%#!mkf##A`Iv_ElBty!$kEwJ z;=jw*vP@0c_V@qZ9eg$#*-t0}yEQlAXt34+1aAPbG#7f1>H|hkp3WuI>$4xK%Lk2q zC!Lo6Xpu~ahFpKKhast7!}{a#X`FI;$sMzFJ>})H$-zG!%6zWkh!7Q}`{;tL)Dkl$ zfa_t)QW>C2yySigBBG_JO6#^$?yuoRH0cH|{t8`g9nEQFDa2S6&j}6n6XTP(AKGkQ z#L{sqy>k8Y1FLhA8GHYBQ)Pa~U_^yh_5|>|0@S<Vn-5lRzGI@64z1tgNbStdw~&db zc0xl82gM+4d>X#R;7Fo-HWYglTLG<dXEs&mu_`+)Dp#8q++~nGU;gl+*)&WxAH=)X zq(*B}BY@PHuoHkdK#!zS&vPT7%tCdY7ErdGB|pK!#XkNX%)$v+I5c?8Z|Dc?9v&XJ z{m^b3(YyUq=V$qupO>!6Eyyl!mirs`Kr(3XOb&#{0oRDg1wJg32Dbv#hcJKbi-ms_ zN(B&5xk5<hZn({GT?hwiIfpoS7?dc|pjV*>0rkTqIH337c>);qFR4OfUOID6EN}Y@ z<XO3nd6$sGvdaOXaV|B}!g*FEOaf`eXVp2^?blUJy|?r7S|PV0^y5TlxU|*?mgw~T z<H_?-6xY~?=fv6?-evbMTA{bnC|X`Gt<m;c#Pw3H3h7>L|GX^h$t7vukS5l}B5AF| z!%Bw7RzAt<OSg4(6`I{Tq#C&WYvZ*%@9-nLpnUTp^P^$7JbHY$9Gb5ODANgkRAkZd zZnS3aKY!7dohxJY&eb->mbX_Y>%+&YOyWYX+m+iih0ES3Ry&e8o&5#!aY`@Y)w`$F zJ|&?Qnk`eCyQ5ly^baJ+>1C4OzFKC9ziM8Z#82x6-i{qzHHizj6F=4dXVv}&`>I_D zA+X2G9-(X*R<c4U1%edGG>Gh#k*ufY$Xp}$tgWuB9XHEmr=eog$&m2^y*A@xu12jH z@LHYwAHCd+*L*q-87~JIh2_19>6<qm59k}tYv>9?s@D@<KGm#F$sE$Q5kH`zW_3lZ zP{Sto<$?3OluTr4^+vCgmfznlgm$&lOT?wnwB9AnYh~?2riIK*O;VwGdqZk;P;^7} z(V*+^YDA&acc#Y&&c0Kdb`t5D&6tBR++3A{nA!sU?iHK=Jmk<uWs~jCcE_ZAJwU8) zELB%D7Nfb;cde*B*Zwjze!!-b#LY9Gax#iF=`J$J(P#wp`YAU?9CN+(Xw`63zuBV? zp`DQ*=GcBN!f;sUC12`*M&{OLpE#P#W=TXwNbNkgcrUOk+54fsuGo}l+Tm>UY^B#l zzuU@t#0a2dhtb=#l|E$JN3KgUxCfv(^Y1O$qR3FitPKOWV%Er`K2l$i(O8Ix8<_C8 z@azfx)&0#UW4;;OqER2aFGDiVNOdN=gVn?Hrb6tJpS;R&`C_@}Q25uJwfv5+mTQf6 z$+spN)x}L7-Z+L4Od5xGzMO21FE-V=RoDK){jlAr!3Y_I2JDcLY13inT+?QvuBN@P zE;kS*Z=cE-jqXk)*FMMRWSq~|ZFaIQGI;X)%ShuIr;fI}ZR^sI$#R6zsL6e@tr#Ma zlsT$X2sjTVOi79rSk`BJIjeOkLR9}%SERjjRwH|2Gg~4CLF$vLs!?mTTs{%Ap5OiP zizwNuaiPet2Zu&)3{!Nq0m0r=rmu(0A6o$u+|P|{4tl?^`ZkGDMgQp0Ra)KbDcbj_ zXHoU*sm7&SFaB=!-`W{5S}eT!=;w3r;xqDd^RLc3fA`iEMQ^z&{P}vhzt*7WFrZIC zaAJV`<?g=d?EPnc{g?AMvu$6Dd0j&E8V9xy-is~3nv8TkF)m}lwEJ1g!Q0s+<XEvA zHayA8duF#wo47A&MW&u9CfUnB>$Wv7&R{xN43Kk8i|En`>|T@&TTB;B*E<a8mpILa z>NfPGnh^S6u|kl#4^g~<KR<r)j>$he4>9;B(^ZC!@Imw8qa`WLb;_RuNKs&r{42H? zK81id6=A2WFOx(1zw=p>iCb;*+;@Vm<jb)`nCADQ$_UV1O9ZHa5V6bCBioFTDc!`* zR&uL6yLVfNFcYGbCOC=?8BU@r4yb;vnN5_E#JL9_ukAU57@;A(O~x3x+NP2)Z7ZPo zDZ+sMH2qxYiB`p2<E1xbh`4~xg8K7qiBs%mixH~KG10iym|9>zG%p_P)Qia#9i54$ z#0fDVH5qQcVQe@akDA-gH5g$cQ#fF~M(PvChcWhck_qP5Ox?yrKoC&k>`MP`2Ddmp zCR}zE0Mq`>gX+>)I}-JToc%px#V7jhsJgy_rX{Mx34yxu9Iw(eja!`RlBFmTQT3k6 zH)bJI8}0ROcp`$%9ky>UeA)=L?!h9XeC%Sc<G?BcUXGrV%*~)kO?5xd*7zclVl)59 zy^^t_Bjj*}<=yi6X<SqY4usoA4H#ZLI`LpN^;X8GxM`(jk|>C)S{^pDaeBVM7eGZe z({c>o;fv(Q&PU!}>DO-UDH5HD$By%#fU^vG=zuyLfTsfd^P?yR%r-p!@MdJl+N<f| zv^$+Gdi%ELB~DHE$vEfR>4~n(6Mu6t?(BY(TH?b<Lf`Rz{u9F@QGa9U6z(og??_zX zn~$-_@6YW_y3B5mNjMO~5YAoik$zaDpS`-mbGzKg+8_Ter5=B@)pF}p&alL7AT4^- z2_o$WfF20Q!uJKNo{}gMf^`Bajy&6M0}!H2;kM#5POn100cNH5c#qOLFK?gjoio1| z@08tx>9}db4~Xc+Z-BPK!{|labw}RaZ?MQO&XuP&>;|mX+s>Uq1NOh^Q?b`fo@Ev- zY3Q7M>XO)g;VOEW<a~12r?tKOR?)I<+{tGl>+P2wqu-GWPmV<BcT~P8dS`s|<Y;_i zNA+9ud-G=}pQp5TT>f12-fHdSi;VS-t2^iw3MyTYt=}o~eOK&t(#MJtJL^<2ADo=i zUzW9Y?p)hb{J|wIeY|G9^ZGu_sz+h^M7{p)Cimi1pPQl;Wa90chcRmb&(fzlTW_}{ z6|aT7z8lxQo?6D*3|YyHr9aY7D;obUkp=+$Gm!YbFzKJy5up3GCkAeINTfyp^3}bb zzTUWf@<15C<^C)$=hIzZ(DX5h@t%*T$$-<a2PdBGRakX2qa8;BLWB#r`^|TiUw@(v zKfwI^6{->`6NQfZPtmvpX*M}Ej|$)TuNd|InrReO>8-4l0<?O}xPbnupm0F667f~* z2NoT2ntQFL%AIv<gP3WADTlnC4K0;KOSgnc-)yWfN!)zU^7QU<`Oz|)EzfgK6e?n{ zVnFZvj!8;wUz<w#lPtv|gJPOX(&IBCSN+kULw-IWJZtstgx=T2WSaU1TTX>;X8L!F zLv~74ls@fdE-Gg=Og3S=&#;+Z;G6MB=6?Qwkx=DFr!|t+PJ(Hbv5VrYtk;jB2lT28 z&}Q+y*Qaoax-P)t7)l?0RJd0<9cdtb<&CGt+Ze{}p0jtf>g0#8GRyP%MZqC`ULB2P zi8ARM;goQE1I7OB;1zU>!>Rcr<1m0sTlORAaOImpdHSvI|9ze3aZl4KM-f2N7^c{L z8yvcCf-8Uv)Xo0Wd;DqP=q5}Qmy`VHWRL6IL>(qC;@(aDoeB8|wZ=hs37|LGNPzE7 z+OS6&pMx62!j5`ih8h04{zn%WD87UHb-wsXEOdc_Y8pKKH`;V;5w$>oBnpw;9@guS z-~{#bCxar+4n2k?-PoUUcO$cj=KfQ}jeAJk<WcWvWkz1G8mvRz!NObxh_#Ir^XsVz zS*N-LXo(n%VrOdfE7Q6`k7^;3&W5d#Q6{()JCf=1ubGau@L&L@($_%F%K)OO6phO= zYD||2NO~becXP7xJtXKH*f%oj5qVEUjOm_fXb8!Eje)$$hs!?EkhgUn-#}g3pVOO` z_Rs@8%tXH%^l0K>4#9K7obu_5nIq(o1%AFh59A}dWMe>ErVD)dJJ4hb+T0F9CS{G$ zvc7#MeH0>RnJ7L7oqj!wOAtQ|&wt26+nN^?w3}#dG2@xwjxNX^qvIOhBH$ICyiwpp zhPMmQql}D*!J@YV=>Up&B?mDlK;NApUw#F>BNCqltX*K6{;8s@g%EH*(TfI7#v<4F z;#mUNzDo=jqvNX{5~DmsG8244fOvB0v;ctN)+T1A{{N9<iy*PcK(3K@M^8hW38LQv zGD^hUA&{gR89$xyn7ky)ei28B5Yd4JJaGYyydZ>L7oa<M$XiV0H2~7yLbDNoN~S<! z35cU?<Xs^e5mWMmcf!0({0czgQ^m1v#tueeNW@>l4>FQpkx@P5qpYwz{j&<T7fZLl z2hXtKjsWn7ALvO2x{Zm<-hkK#mfi9|@(5+O2o*<?p?d+&+N7chza#+<*~%6PWyq;Z z$QjY25+mQ-9^(OkRI$A~n5cVL>myAUD@slOdPs~jkaAI#O*G_-^O`&!>;h-c{4`NX zszgZ*^I!wX*#KEFE?6Lf%7|5+nqd#8P5A2K8*D_~b)Wm=$L9!`Z`Ui&GSF*$^E*t` zLRw8-lY*LNSa}<=r4iB0_YjG+F>09S0-Z-p=p#nZBRhqiTAv_0!;2lDeF9=X+XntM z;dNB@O`iA`8}Y$I`x$S?BLRzQ5~7z0;s=j|=~%=|5Ams!=uVMt`}A@RG2pxC=`TiN zc7u8P1A2ymzQ^1*OY@b(WmW)#Mmd<%fiNBiGl8vnbtindA>`Qxx=n~&VIou!n5PVv z1ksnIVA|Q3j}%mr5Mlv<WMC1~WbWO%qy&u=h20SvTBs|0-RlI{Q6_SljlM@9A*Io? zwBu9!GgEiy!C$S+9pKT}hL`lTCk>{<(3}Ad3OIzhLXnuIp?U!4mf!EaO~x#Hh__-9 zNdSl&lFJhs#U4cccagg*O5!h1+z=x1WdqFNV8#IPGty|0eHz2TJmM8rd1A&qGLEpJ z)0CasotN=umWj{EMO{492fnVQFY3wu`r163ZY=5{8<RhaE}X4*$6s6CX!;d}-nw|M z;63RZP5nGTqQOod+3j~c6}3R|B+Q(@*h3xScr*!-$z<qZ0P;Q?9TXkE?RQfN96t*X zZIns_^591~XWaw-k;S6~9?f?<8lB%m&SFvd>6pg^|HSUvvP-7>HO2cW7#;=A<Ds^g z2xpx6V28<o5EabxL&&#Y+O!h6$pu(gHV-5lhuN_`I@*!ZF>q@<JiCi*UcnIW6n(u| zWVpP_#Zq*7EK0qgu?7nlp{br5P-iFZJ%a!72wF81vqpjYcsQ=H#lJFk#8<pfRrzQ> zv-Sjy#gW|C%5*6Z-Z<k`s~#Np>zdWeEVOih_1;xvWdUM?hg=|sSeyCxR$3)UlOlqe z7ue`hf$Dz1wFhKw>}vCfBWbq7<`LnZq_j%IWJ*HEzVbNhKUw=Ajy8uB51+o6@Inoi zz`;DBp}IvxFdMNhKsQs8j^{KSzuOQWtT06OpJLzQik46t$UzUx@7cK943yDc>;HNy zN-U6zWQlwpA{-0rd17+6)8^t)bQc3PK<=vHHy#8)(izAnHw<Odxt@jirA5?p0N@$6 z#Q9kDD37>_dORvZR<WpiG}K1*<2Lr=&;LD|ARCUdA4%Bn@IQt>O7lbB5?RwcR8l?K z%Sqx22e~HfJnVd<q2LCGenRR9@?l}wD_ZUCv|tHmg*{%FMx>SP-7~*om~IZ{0|)s9 zD=tzAeK%nDnMUq?n433}7RUSU%Ah(tnr8$^mO%BO2d{>3%_kf)uu++k>OYuug5jL7 zsD6(XRz2#0ZU>+mg-?!)4bXK5=pUa%qEXRS<j=2(&LDnS+rFCWeSLQRPmNfwS0m#; zkp3_+jcmmNN@;=-8t8=iN=Dumppg?TGLaZTETfu>=JS!=JpL>ne#8UWPM{6~I@+gb z00P2?4CgXU2KHKa*Q527Lf$h8fn+c^e<!zrc|j`-)8p`LuN5ZGzu70eb3Yn_okaj| zV%k<ap(8er01xKPRSqi+++qyym>Ax#k(rH=X{_J)Z>?!QYI+3qy1DxPz3Ol@(hjjJ z`T_Eh;IT`1H9(1kUD~%+*Bg`;@q;6=My_wzKp77uu`VEi1&FN;;=>KJYTU7<sUWsu zdhm%>A2xp!P~}gG`ze%|;lpoD!<reGC&GLEX!L~>Xw_cK2a3dd0>l*n3&eu`0PbGc zy@v<EXEtEZQP0docPN(JRsO>i0K@?cO=7ye^k|-AV>G0d-HmAS$(RQKRQP$#k&h$O z9C7y+@s^E=57|y<Jtp&wcMxYell1~*3j-PIiVpoVc^-@G74vW4p<bX-PH#rDevTf` zMBWl;I9a0vOp^~8uO`^t-5k{UwO7x{e5i}Rs2wUNVLI2<>hrPb!qENbR6D6~g<<vs ze+!P{HB1!~wtd~Yx+Oh5y7G*N_+>U!7DeLB+yU^#XDQAH5q`yA4R2W+wf&jhGw%0| zdHVxJoM<g^1uIb@eBD$A@nRfuC4hWAAYMGM?kL#FUdNjZ(E_|7iA-EJY#|5E<*Pr} zK|J7Sa>&RFWW?34&^I3Nw?1&a4KZ6RIAB98Kp<AmgO&r{eo=l~PEq`#_qLY(_CGzZ z$q1+IP<Y<N4#vxaE`p=u1&AsR64{D$Xwpow)rzq#i&jDw1beRu{FYzp^v~-Uw7Zio z7>;lZ)e<opi3{o_3%jl?XtgfvE}7q>Z=$Qes8g~4FtIh6l1RY9W*I2#F@@vHXc6tb zMHaun6Bps=i2}qpFTUpCjHnM57RsF6c<O+7P&#(z#`nwRB7y&<dgcZ=o`*c-_AWB< z-61!Py)ZzvP<)9ZUdKUh@Vw>;5^py|aU%qq^F9)Qh-5<83|OS_b)W}S#I)*(%AAB^ zcs4*}CF^iNA|Dse5i9=-kK%}}d;;1Efzo84q!5S}0u^|`<2;v-osh=oZVd8{2)G5R zP{j5C*4kS^w;p{kWkUj)Yq?j%@=mX4vn6*kK>-`G<^nNm0SGS;lf(i=Fs(KRsLh5j z#SsAvL?i`zm?swpgjdvANE|BjSa@=o48NF)e1CeqiGf^wzP`4;-o#&T;UP8?nV%o6 zw|IR1bOoMHhX1|-|K#==p!)gi`g$7{_3A6t<ekKQhkCYkE~6U#LfH9g13fT?XbdPu zOQ(QC6ZQ-pFJNPCQXtt(<O4G1p0KOQv^VyvL=^*sC|x;IDrN)tYLfKT?A%uqRdCA{ zaLfAFeOK2a$)B?IKRBF&IP8-#=4|D1#KsRn&oSVB1h5$gm}jsfCx2Aha2_+y|F+5h zraa?C|BOHyeqSVizal7&-Y5Q+DIGzBMRFj<#2>~~P$(0y%R@|@{X=vBg!hy-+5}i{ z0QOO(Bm@8@I>?lUD|~^gkpZa#Kp!4L7z9rS4}xX=ti1JU_7F6F{%7^h&&v|Os`vbI zW6Q;Og06lBUz7ONeCt;r6Nz@EsQ6TM%Oa~er`^P@Hv3+!3B@bO60>Z0SmBL?zD+Y& z&SL<e&jB+t1TEY^T0crQD2!Ey0=^N%tC!Vg1&TNM;>TY3RexKsy5OxKzG!hf5bvgB zv20{oXZVqeX~MXE7Z$cM;o}R?mJ(ma2KXNU_PX&-YC(BH`JLpc)w6Mv1>S^wR=-P) zQ}&Rk#`7#`W@v2Dk)&FluhgUwLA1=763}N}E<1asgguYYM%L_3mjpS?Dm;CEJFdm+ zUhHJE>{wKd7s5K|bCn5arg^j1aWdBT5U(?AeD=1E#VtCWg(>`09@u(lydV;F@rHir z@M+*SjK3cG;N-XU<!3+M?mPWs9XJF5D6~HUTqJtSC6qU%-XNFuWi<wMMpj<hwKzBP zwJm&%Q)%1pB-we$2hPnjY2mf^w?)2a2z~uMVeVe)=XVL!s{8I|-M$<Y=~{g|_D(=T zts0DSJLvA|H->%>1KL&x$`W3PkNkK1^YfZFH)MDI_>rT=JC6jLxzbe4+%x8!jxG=5 zJ<l4m#2~2G-LY4~qWE-1&$37iE!9+nJ_{V|fz6Z-<Ku7>nsRQ269OW}VxHG0vDZgK z>RQ#N1KzKl9$7*68;QcDt<ndt;3CUPmHpF>h$_a1=id#gO1Ep`59c1uRfukvd@&?n z>1kMbsNko#eB^nqrhIJs#QCbYE~}`j*xrfc{jq7_RlLD*V<Uci)eMBR)cYU`Z`p@t zJ99ohIJUp5!t)(2Bwds>1c1Y%FVmS8?|8sZmbx9lOBT5bF^sW+%bw(WcGbQmCkOOL zZ6`mHBZ_`5SD7!sFUXq8X**nukEtwE*rCSV{^l2QY%<mVk>!jS#(2YNNoH{hk%J*? z1m;x*=MujKdi_9Z;%JE$NeYc6_oFJjEkA%Tsv$#6n0yAg@7zI~BMz67PXL!?cW!Xs zU83b8piD<91YjKAs@{ML$sAjzbTy9dk`F1NGw8XBY18v`xwHZK&=T$3i)*cYkP2F& z0aiZPPhorUFyq6I?&ntyXoiQEJZ+8?l&~zKE?p{hH3~PslJ=gq{b%_;tzd5EetMyd z<w{-C<jIw5CpFW94xJpot_m<k)Rm{!H{tfg98liC(I)C(QdZNI@8kfq`#0C3>(1sH zJGunE!<#;*KxE^RxhAoX{`>x4(hfh)sJhZyvj-GlWgK`-<v`=g5+SPRf)ev{ktdq; zy^|g#%Ys_WA>~7OG?)f^J6odK$#Z{AdObDgvBs^U0R=}`r}C|guah^^?uY$rCf^m7 zt0P~f(@?1pT5-1Wc*c)Ar}(p_NB#D^dF7~kt553LzvPH7Z)`T^9+{zkKiV3LR!#WV zJX6BIxf0Up<dAd4V46MSpy=uzn70^y9_Z^MP|7vxigCQ5--o15%=@-k4x}liT7Ply z$ds-ZhC<a#f(drkvqJ;gRzGyC&|xr38d#^FSQ6J9ZM_h{MYbF*3{0_=&SJh$nG=oZ zR`{^`3t0reQn+WzqVy^!cgI9jnsw-bxQvyhBV8uE1L^2l;9Vbf=zE*QDF8*O`$U$M zAF-rEasa35j5ET96F!l`Wm_5h<(7aFp&!NM|Msc8wztFES7hSW*dW=1n*~uzY6`<c zF0z=DPWGDb%=mN|nLTC@mmsh{y8=?V!T=cu&{4g$bXBVl2h0FEWr=){%I>qU-5x#g z(b8;FTcUk+v$J9|$y<u*SrBf#XxT%7{vMgOe*dZ1Y_bDoP`&@*`#0<Q11=Fpmk*G- zMdj4b8~1CJZREO5?;=VhdzdDA76k?@QoDvArD;9+o`P`0S*IMM+8#7%V2{r*9ID?i zmTTS&!rx!9SBCEZQAdo&+@EX2P<2QZJ;q-y<#`4fG|+3}niugMoJ{dlUY-p)4EsyL zUdzf7Yq3Qv_c6~R;Mxl9j@Zi75+LSjrI;wRx@cSs)lK|>id*T$>4qtSuaj(EZ}~LZ z?TYm*UiE&gFj={j?Q7HvfRI+^G1cr?oTFE^I?V+A|IT-ccTp-wbUC|WFFLq%J8r|f zK6V0n#FSeY7Gj6Janj*ZF5Tn7JK2oijVLk!;_e9vx8##VSN(L%fh|cyQ-oc3lSlW< zr&RGGcuqQihw{p(l@fZq(aoDjEjZZ8-9<-B$7$`JXz;szGcqAA^uM6#0lzyP*Ailn z8ol1p{yU(5IyBIDid#&1Kt=CAAu>B(7KDtbX`f`;%7}>+UG`U8Ok<Aeie$+FCu7>M z`KK_a+m~7MU-AEKIp9C$7DucU-{()n{qrVH=jeu1Mf0f$gVUavv*PM9T&%ssuKB`X zN~AI%eOR;GGvA#Vj&~1~w9b+o@+!-ee@Q61YP;*jE1S04_|}9x>)&*2UO<0yf+jis zI68QwRtdoLu#j3Pid^cwtbZp;g!+mHcEK=%g7;PfZHNRw?A|kf)(ldB#dn_&&&@SD zl9t#|icKHxVU4WE+kYZ;zecJ8V(OzG{9cZTXb9>F7%;kW)HcCKedH;}L9cnN$gO$D zC)HhH;3V{?Fz$hvOd~%x?jm()G}}Tz(@f!FPQ}=31&tL(rPL|^iE&cz#^vflD}WmY zLD*ZYGlsGTN)fI$yl~u<6Ii8+TbSAflKv`iFjBEtqU@C4@2<!NRvLKQe&onZ4>=gs zY+eulz2{k<rs<(+&kv3;zau>XGt?VguZuUrFA6FQ|D<CIy?B~QXG&7;KKzrw$P1oZ zbTbC{X+FtV>eC<6{~;aut|$m_t*}inU}D=<;`33>u!5Oaomg75UoV_eV=<!a9FB~o zWXTqhlPns6MV&2or=_*-m=~~SKhXkizlgnKnh&)1#MY@y(jdlHHgy*!x6bXPEbJ=X zpHn0`81l~O(x;smx3KBt>D&2Rae355)M1{wl<kQ`i#ZM=VM|QD)oGAqMLieQ)qC06 z#0a=3$X$XsNgZ(l>2{W)BF%MzWVHU7InvQi|CouZ`sAoPU0M|A^NY2W;+h>zy&t<z z$7uiZKX3p1J<f++Ntk=B>~#;O*Rg-J)NUF7nxbBq+^L49#|)SV8OX!??c^_g=^qcB zN8V{oHO`O8(yr|(rpGLztwc*6sf#D32W|G0Cze|Nrd<e+->e2`$rh&nDToiZ<Alj) zY!;u%c=TgAuwC_zhvM7Ywthv*Cx?2p``dDSU9v`=2qZ0+N)hQ9hpggm?+mDlNZe2v z5PlkKkC)?OVkZiJe!Uf@&JCz8+GXb;+_1~k_K7yEzPMU(F{=maGju0zC}+Q@)%dA+ zIF<q{q9AH0$Yu)a0Uz0qg4OR6cPWbGQ&63S7dLYPX?cEKnunO6pb98$<LaSlh(9Oq z<c5_$4SIO`+GR<Me*gq9q!lv+NucByZEL;iy7bQniU#=V74MdxlAN%v91$DrCwxr2 z0gdCyKi|ID$5v1*;t@T|-h1j@zHc$gyJw5<!`Ss1X4GoL_ub#-?Hs8MjJZJ0&vX)% zVlaw70dfy-TPgH|(`gX@F6iNH2rjsY=Aqz_pVifrdkB|%WJg4d=0oCyy@w6$TvF^@ z%P`ps?N1bMjPP)ziCnjBF!;h9dZTz|mfYL>xuC6cS%IYYukC}fAGSW-2k=mMK7<S5 z-MWs*J$*Dc6<}hsk{$0+rv1|@**wqpb#{~>H*^JZ_ymO(Qxx0P{jn}b?R<_GAjhW* zTEe=weA6Mhtk~g8zl0KnHd1ngD*9jVh^gMC<TJRsopX4_1oT@yL9i>Dr-abm&#doy z$l|Y&OXA@WKN=)EBuD0C(>HR7PLY!wJ#WiXOvedguK<n8cZ%A6kiyA3%Fa9Bl=tES zvbY}W4bL&fWu@|Rb$aetV!@(LiT`duw0~-Tqz$I-`0SU=;HP$?8iC9+G6%7`2N6pO zv+#qDJPy`=JaE12qI$^iW#F)S1iujsXy`BGbRMklKiGG_cvpsnR<=@%dQNG0&Owy9 zo_%fvIX7k{2VQ-loPLGb?A*~&=@|j>0^B<o(DX<q#~t9}HQi`0!qmtk-Z44elss>b zJg0mht^yqE<kBAxNg?F+yTH8i^BAH@urRy72=c@}&o3WrA^^G3ATl!$5ArR)1<rpK zCB;h6>cGk(ATDb0;luk^jC3^&Lt3^GebdAJuyl@*OOa5fLF>llh<4?FItMw3s`oX| z--Ekp9Ie;$m7gVHb2JTUkZy?%bO>k>wnNK{4S?u;xbmjv>Zgh(f0;)#Z^ipHFLY5w zw*xCZb)S?k=%%i?@5DpAVw&7npkkrgAZrhh9@t2jNwD>Reab!9n4K1r=NOasSjoea z1TG))@T6SYL(1a+&hD9z7>S1jIt|4$hVtf|!g-@>qRW$P3n5tdQn)RC5`C>y=`$G{ zwBo7y$CH5Z3L-1C&MBnEQ!dXbM8T`h0=r+Rp+f;z{MK%V4DT|z=cPOPQu%|4>t2=K z`{iw&P?41?a`s}edEvYRmJ6u2ak&{8kOW>1t<K$2&$JM9{Rq>@!aMJX(>b{VL)l<J z+;q-#hGWbe1WAY5`c6=9L;ZIIS(;AZG!o3uW1=%|A~e4)T^*{Rly?-Db4-vONQQXl zXK8P^r#iuWoU-r~ve+jm=#w)TG}2oG?gvlExQ^{~Tsqt}x+d_Xy%`I}d4)a6A^w3x zozRM7K#%U0%a1=Gf2=K@Jr&a;f=s6_T1lU^EJ+VOXH+R|Zc$?YX}n_Ciz9>r_|QZr z5f1EsNGK|B$?>0tT35eHzvl13_dj(?r10h)cZCIRmoiV~9(YzBCGBnaDK`oW3-<7y zVOQQQdUj;G%Ccoz_a<zSmgkN0=%{x}05Ijkh;qY9vR|g&2A#WLJ(Ith=NBVJ%+H1$ z;3itnBu?hyo1iH>Z0bq)(_=$m?R-!o8yedPi)UvWZL_Ry!2AP<JMr3#6(}P>I{@NB z6wB+ig2d+M$OO&)cTW}BWHth1#$khbr;v%=er^YHGV^o1oxpcby}mmNGQhSj+<1MK zDYj=rjD!U}m<%q!f~@nwt~9X7BX$#<>z&L#AOH^}%=Np1?VU!v3DB?@NI>H&2LR;2 zZ<g^kOLZEkG7TJi!%`Kp6v$!(a;5@1bNn)pz|Jx_@n$;b&8t7Gx<4$D#jC{-n{#lA zc7k?}6>lf^GNfRx)4E}Thra!nA6lUQ`EdJ(hSom1W?{=A`&n43BGgNmWk&|tR1n=? zHWux?B#9<NUv?edayb0;8kbrDCXxZTp{xTH*=}KPzx>fCPJT`G$g$o4y9{OSC4qFi zz|Q1sLmrp{02>ZvA0t2pLPG|2%?(}#Oa1}x>k=L`2V<say5uaoZ7?<}L?L$WXTo7> zz?`%r*n}X~=#?pnW8rW>(Mtx-!oh(u|3_Wt)hR3$ah4<xs3-&=PB6i2fQBCc;RJv< z0kqN<5ZEx{X%=xPQ&&_;@AQB5kSJ1jV=^^2nBXC%DC&o41gbE^3>#Sz+e|o?DS-t5 zNkABx2_rFKL*W+xh8wy8#fJc*p#|my@RG8as9%cg7U6K^f$a_)WCI5g0RX9r2qHWO z%)K}_ZP*NEYIQ;vLz_aT)l?$-9>utuopN{;Ls$!qe1Jy-2s!2LV#d>AIs%R0hRBdd zk)aLCq3e-KFEwawVi<n7dBt+jzsn(_w8LzsCNoPffVCSZCcy{0_GBlJKu!R#-FEKD z3fRf*cS$OF&H$z}DcYIzKKU;+#V<N(BR44~Iw>H_PME19iudt>`Z4cC=J07#a1sZ| zgsy<FF?a$KWDc;@XX(>`&LohbIW2Ep%uqA~TM;X0h{1D2C%mAN^_aa~F?xU)Fj?d^ zGAU^+VgOToC=&$D7O}(fB+!Y(=wlnvb~~JG#}nBii^gK*i2n2kj7>ILJQkDa5pa1H zdJ61J5<2t6uCEKPn`T|t%#9UZ%Y29t@(MlG9r*D%;lYq<gSviU$$`q8;2=MRKSn<z zBJW(R)%k_7ZObbPg{5I(X<cy-?yPnH8+U&_?vV|V|9$Pjqc}bk5OxBj$OIY$<YcVm zoo-x{?u~o;Z`_bv9?&~`A1=#)7w5;%g<r@rI`M{<FPU~?AnEpu!iT)%3ZJ9XIrh`p zR-{%Ejow%lycnyU3V@|z)keQ$*~Nf`x#0O+ur4zj{r6dUl^|^ex*WB>d^&L@Ez#3s z9bPP060c3$5F_$f#1mkbuI!UL3~>4>h)^ApB6Rn0O-kiY!{(td?YvUGne*QQ67oOa z*Pn@Nj61)~x#j?ut#y6QG@oTQ+^0dpNYB!lxxOBi%@0sF=StyO<yjww@3d}2;d8&_ zmwW*L;@U2vcNl=}jWY_HVYs6bJB%;ej2IFuK#(N|XDP*GIx!!#A~$^-bA0o20?Fsl zJCHEGsFpByUw+mun%MFJ(mEV$LAp$Z=cHouT8E*50Xcn>AOqg+U3~aMlUB+Q+mDx< zxJl>(UJMkMGh4|z;FO(-L;90*uBAf8^)CR9LQ-QOZw|@7`Tk<>-LLzGvb4#Q+B7lh zVKD_ZkPraWI3cF8BV_FXfDc%qM8!if4|0d=Qv4`Ba+{E7@_G7p&LIl+oc5+j-p+*J zLK=<E9gzcox({!Rh467jZMW7c+?W;;Hk}vG_vDOp4bM86{R05JMyWMd=0e^-><3`( zb=`r-VZOC9q6cq^*I_2Y%FaK{dAkZW&Id{|SxVEp11b4GP8S@(sT+zx!y^q}Vz*q$ zIZoI816D-15m1$rX_YVb&|2()Y?jqDLNJ$|$bD<g1er0Sj2R#^4wwD`9LbTE{nZjp zySJ__YZ}*KT3r`%f)wYJFBb^0r(}<mfT+=#y8^@r0FmsS>APFG)mgazOinU8CFbLJ zs34_x=e*Q^tG@QfT0Q}uRP<qbhG1t_-1X--mO~q8?I>?k{_&Z?Fxsu?Grtf)_05j^ z&1Gci&rq7pS~T*In*c-<e8<9piXLLtL!fiJ#pP`SWvg<$r@@YFpmbxVHY3oy0!$)^ z5i7(bHkcwkyXYYJ1>!`s%C6!sjjnu1D0}8tE;7z(P<$}w>P#i5?GoK1x40Ra7yygj z&heejCc2kX4`<4X5OI8yQB1kfP{?1x=S!-A{#{!y45a|(Qa2x$Yep0WA!Mm^jn0!} zi@K4KE4RhFcOBHq4bMzpy2?p$Hq#F`JEq?GKI!hvM*Hrziij1-mGh8;__L@Jo3Nds zc^+(GLw-l0bzUi-_3$tN%ghq_vX)(0d-++`C&b9pEcgacnGbR#<QlcWn2nd*Yr3Mw z8!-1%Z_3%_++|R~ng%$B(DCM$#XE_iw__*5{!nGK#HAH9{YL`mV1$&q&yrA511@{R z>lTHT{;fd1xp21X6W(;>6*+38OdG^W(H?JbyJ}m!J9YQu4Y!}0uVIwAm*InKOOqQu zfxM9Mil@CFbc0(%hS-6{I>+_jbf<k@7`=IX&*2CE{T2H=C_ddDkt?AJWu7ot9LTM- zG=0#_XpbB$m=`0vzV1$5HnrS4+2nndddf}0aP<1QD+kU>xxUm`lhO4_z!~h&li!Kx z)tRZuoAL(*3cGcin5F91$D4d79>hu?FD85|R=f!mRv1h+l=|Kn3TR`2e_|}te$%w` z*aSze*XF`CX|3n}y!OERX)S>rhX+XboDoABkTwxsu&Zu@b;@9x6WRwpHbT8A)F?C_ zU9#n5DJD;I^Hei&YN5a9)Ti~5xD^Y*ZcWp*1-?DYY6U%WVlD<|Vtqv>dmZ;*Hnnc8 zb2a&SB;0lXL`a|K?wh|2o=8#Zk3vb;2$@d1Td~IqT;gR0&tIbPdZ4)QlE56iS7+%v z<Wea?1*FLTnI$<a=~bY??Rq(KZgMDd*mY~hxY%gl=5>^VJw&~>ws6Phwi=*kJK4o( z*aME-Gi@wgXxN84RuoVqx{zqBJAXso4}i`s^1RU2UF3DaVDd(D$IGCbE$yw{Xomru zx}<);Ftg5{zjXr(c!2jVG8n>LcoRMQvG<_s{XguNQUDiLLgFqxVjp@jVM7mLL~gTJ zJo?*U0B88-9?JM7PXv-~9(;w~V^VH=*lq9Amm{ZfD&t2Co|C>EX@c#AHyQmp07AL( zLMjRkY>6RlPvpaOYtQQUlIjLkvy|G04558G#XY3OB#Sxz7cJ65N!#&%8Y&hFbiPd& z89f9y*<ttYi;6|*8JA}wPZfUruRyn*Y=k*;??gI!qBSbycF5x$nssTf)E9s6oEhU| zXv01iM?$k--Q_#8xSg*OfFPj92>pU`!0}AD<HfuG{`2+CkFZD`(SA?*D@@O{edN92 zDSM-mVGU!2P~^*BZk5uyyzTREA5Y-$E(YNzBR6L2be^~wO>9^H`p_{SA+0~|<l6nQ zWBkxwADQ_p_t)=#{rCRo#~_i`dKbV!8U5bW!k9i7>h*T}sd;+bwUOU$wdW=6*4y#P zm6sp&o&dt{fBLmjH>vY8v$yNf<eJu_|33HK`cAD<_Idp0$BU%L-e1ShJ>J;?k$3xy zyRa<7uxI{&V`jSs&Yjk{9Otu$uR7vra?t=2>(ZAgry(>pzEE@|qn4aaP~yU!oqDCK z$T_4CE;4wiSH7E^OK28`{1s!K*~(JBGWJx5H(z<@Pgce+KGN^6mwnfhJ!cPw)E@dW z->+qBpbE%Wlf4<^Kyvfc_NqtH0CtZ~t=MTVNiTZUz-9lL&MI>MA5rHO)kGV%>q#XE z2~6l!LJ{fGo0KH9&@>b&ib@kH7Eq*#ej$VqdO#4QD7~uzsfrqUP*hMvKvY0bP*hM< ztl9bZT6_P;IhY*GyldupuKT{6YdoLGII0hLXcFPoHoqpj&MmarpUhHK`n@{Zya@wR z3Nd)$vAiyiI`)47%ZC^|o)g)yprE|=BNPfK|AZq#0RYfJ00<xyItl?$d;o${pl}HN zg0^(603N4mFdbBNDW|km4`<03Mb7iuYDV)2c9{y!p3B16T}M#;l~uJ5iuFV8mpk9A ze^_RI=KXvlK%*l8t#t*Lj>gFv%0;b1_l;H3>!~#^6)v64&suf}n-e*m+JMl3P8AI* z0HL*uJfa_xkJEkL6+Ii5;~IZ`{?@6F(~{@9cfY=K`YZIG{LGD4cf;DW4v+V=y%}Yz zx?XYXZ9kd`Hx1J>Uub{#xY90b$HQJ@+M`<SW{%Lp;rGuuA*04Lnkg`cL@rGqDvLjv zay#XR)W6@~qu>s{XhZeS9hHPL2H4z0_MD-`~3`ilW_$$V~e4=`a7H``x~udDi0f zW<9Th&(S~c)>|b+Gm_}IC3*O-9pNFkU)k}mXmBasM3S{8n?}d}id9M#c0?^Q#4IU6 zbhHDC2$k219Uu~bjm7iG7z&#yEEO7@ZX+8_1ib44MQxGO;cs%TUR(7z_iJ(WO&;-A zIFT+#=Yc52+6Gl8&33<Mk=GHLD}~;1Q#C|YIXD!xE0Ee>pb*3DXJ<lW4i|;jH>ul$ zViHS4^*%IE?5xhMqT9S|I(8*_Y3*GFvTtLw<e&eym!&NA%(ueO#U|<{SViDKIYle{ z-PQA@B}?_zG0h9YyNxHIm;D@?R+}1sQIzcuCe2nRIhgVzs~DQdW)hGP7)XS|W04`v zT%@+n-ax}fZkzZ_lTOJe#4j=cG4Ag_bNR%siMZ)c%i2J?$cK;Jwqk@&J#S7+5Ha0X zTAUAf{M7=Z7NA_w9K^?)`}(%`B5H19{6BoS2Mc`gk_)UK-01&<3EjAHPYfiYo#7s2 zCC$R<BHN!@vF;-Z=a3&q(NVSiYCh)CcJW>o6Jxd;aaI$C0QSw7akgUM&4)@Bfo+mL z<yMk#t=QnmQA6zx?6~o+L(eoD0B$U$0wB6idA%gxc;a{L&Wvq9`tm-Tf1H|}X<ua= z@WkojwJuNH^r6SLb~o;L>y2tGXU``biF-V8?j8Ty(>~<RYMky}iJ>gwFi@Fo81eh# z_M2Cy4cW%MGFvW2fOjf(xjg>v+dI%h);YT=A%_z+q1W2Sjf>8G`t`x|yF1%9sITpj ze*cs%XaofAWg7x&spD@s(x?6;{slk;&?cdX1-O5f+)RK#qlw*PU}(0%X#D5Di9Cr4 z_U!B8Q~!c#(#8ltT|*3Kc5Af&)So(@{O|Af9>*J+0LlQNnz_I<x#G(XT2+yG0`gV> zV&5N&jTHA@M=gfFDG-oKL;BAXsSsgcRfJB!DtmY;i|o{4$o9dA7ziQfHiRp8O}q+w zj3OR`W#Cx=U@Y^5DEDh4eRowFj{llUqKAe^&jlip5VoLcv?dxTL4pkwhumcn!9b0r zUW%k05R7R2TdQS8{qT|Ip&8b#FEC@g5v}&OkpOkTa-6~rTZaPg36A7YDM#dYP7bX$ zXkLtr8@Wc8{07jJ0R65b`kSdK*|qYrPqM-p`yy|090e)Qo)B)U1TT6-Y^U>mA^J(e zHL8#{YH6U@IiJu8IDW2;=}FOtCDe@{{dWtJL7pLsTB@;h{)V$1a<9pZZPe-&uW|od zjUgn+@RZ=eS+>vx+1<tzy~bit!Zi2tLUQ??PyHf5;h;Dm0|nY4z`qk@!X$yBPfx*q zlEed4Y=cdX5Z^qGM<#4hS-YztV{{fwF`@Rb%=zxeOq=WF^AadiF>|($*lEdloguZU zAe_$-DD`B*K}pf&N$azvTxdQN@X7E@@w-SEYaFqJx4R4vyD4kvH0{0kefS>&3RLwV z-hu`>CR(8~CXy^u9}jAZ4y@SXWs~=2T9zM{ApwnWw0FA94pj@0g5#YGPi~U@L*HZ# zs`AVl?)!MRL8Vs+EQxmfz7z#er5oV7S)*uI!lJL8z#VU1(gMAxRpL(sjX6F+nTm#L z%>YlEME1aqSBc2?hC43B9rNx_>T>B?K$@YT%s8>3Hqpd-(tF>@kLSO4vI?%MKqfE% zpHoF>G~rEFCp~yKi3eI_%5^m?*&z#JUA&?vuCBK+0GuPYbVh3~w@YAAlkCCeBi|k_ zo&Pk4QUGQcmH<`gDRQHJ?!}cPgyFtbL>}Qh0cCd7!tL|ibH|n;C?F=AS%g`ZncUCv zz2Q3k@PwNLv?}d5A{ZAL{o^jk#A%OcGm^?x<hvz##?d63tnzBGmctys@Zb@utjCHa z!Ll4Ob02y8T{+^-t5djwfuqLXhRnZb8@{qUoI*HDIKiuO(4=E;h=klIor%gVb}L<X zh?l!1C}BV>WlKA$T{CzPW&is=RsCGAVV`!R-u0FzXFXN95}R7uYGrKSo<e@fk=(EQ zdo0=OkU(i7Yp_iBbVt(MW#ztvx^kftMa4FDVPk$y@_;~jLutFK+$1;<H{TWOz@9K3 z#X55Iy<SE<A(TmG2ySzXyUVHWif1T4T{@W;`Rm!5hLA2M7(<c?BAk1s_CxJKSUNZp zQN3-i^+}T*st~UlK0|JYaE^za>c>H48N|qb-{5<{<^aEM7p}dZG3~plJV!Nz?QG9n zRsVKXW(_V~k<=ya!%<joTp=R+kyhM(m2c;FRJ2vhOTsFzi_AhK0sRentDXG8y}Y-q zs*f%-Rf!o52hHpGSr2tXUUyA7;xG4GXRv}2?+aT1!5lWJ^0x98-);BppNf8GrzFd+ z%dm>_VsOsJ44IJINK<J;pF%w`;N;ukIHl9Vk$J|sVvF`_k*)``2}@65ZOAEc8+Mer zT-X!>S$|^I|9!#Z4~KoV&-&+f2Q%gfEqBu@(FMN$BVByf!z^eqSWcmxRg`w)8HxD@ z+tOeXb*qHWpI$oPMB&ms8k@vEHalYKS~+HsX*_XfHARPXK4d%fiirV>)Tpd10rJYG zg$hE;E7omW9WAEy*q5Y+<etxbF+Pq0<gd#Er&k$&+hxB^7k?GMszG@gu9V;QEkx0% z!qKQOC5FD*t9(;^L@Rg_8|i1FYzhG9;a_O!`Vhb{kj}?yoOW`5l`nalVq!Pc_WR|i z{olsjkGl~|BKA~wLUthUFPgrexlX|UE(V=ff)IEbA|??75e1@!R%^l6`eFjJ_@xO1 zbdwee;xBC=iYrrSoRnMwo~93G0jNd-{vtJLGk%A&KBxzv0S;Yz8}GwL%n!i!fDmv2 zionC6L57AgXfy<U6aeA?U?&l#1OOlrbfm$(D`C)nm@Ef0Zrm$Sb=xe!O*Rm)O@tCk zVEqP7h)5bo2sVlGi$?hBgXYnI@d98zk$Or4G^PT=K@dCvl;Q#~yr6msbfBP-L1^qG zRN&vnKwz2)sv#Fe;e7m=q@&;xcyf*)B6KXHC?PuJX2v<mlTQO}1pvDP0}h=u{zt?n z2tfZ>T!<a68Hhzf65&<2Zxf>Je&Clt@Dl+CNr-|%;61y9;P^wI-hoOi^c5O<lZwVd zM81K-U4fW~(KydSOqIZt&9=*~M?<U7*+fhR0ZayfH!Pu(pgW?<GjakRIU(?41Lrpq z0YV-WkIDvfE4Vpuh;S(lQ$eLmLvYm5!&w^gT;d5BNyIZ&SW0pqOWL}dCVUUf7tat5 z^96g@zET+p>t_QBzQM3<A}4M-Uw0CLwh1B$i1V~ucop(AL7-O4L{A<WXZt=UCgb>B z&Vdf7Mpf`AfGVM(5u50RXR$5%2cZ3XGkq^|*={UxT&^i@GZxp@ZQv6@a;eKOH8vd* z0@`_*E0s8JO|N--oM!{>A#l!PYLEX}Tq(l>TPJdEr`KuC;@Do1XMwnR&KY3g0K$T> z%0>gxNhhLX6@%;+8$kvYuT495o*=aH4R+TYq;pZ9hcKRn6l@r7R$xF6Eg`Sb0WdkJ z&Kov{-BfcK+z9FCSn~j*heAMq<=Kxr%QC!#yV+%|9}Y+Cg*%DD+{<OX&fvWbVUz{f z?rq$nY4o+DR3<~Xe?j;j6+24Bc2kYHRBS(O&&eOfoP5z--dPELn;oqPf2`Z!&@4zJ zvd~p~;rZwOO8U5{p9LWps0SvOg90XS(0=rLAaO3*9vO?hX<9MNHRnwcos0sDzT;t1 zar)CiuYT%^`hdVLFxOk`uE35h<q^yUr_UgbDz8E(aVQ7y4;nz#;|XVR?+KS4E@0#b zv4fy+=Z5gCKXzoIQXI3FOQ;gv6q*EaL>IiG5O5Ma0<$OtHgI1F;MzhFq6#&wE@&zc zv2Fq@+33mz)c0N-FhOF}`ailXJfdDUxKVn<x7J$DdF^Y>3K|elo0HsPY{!|HIegwm zt&SRaoh$NiCm6$Vc?Q@bl!b>7Y{X(%5WlqW`NHKp;<mR4MrA9ddHX|-&(+`Zt`Z?# zDgOluyyNW~nIayzRvOB6<2<xYL`cpS8G|hvq<(si?I;z#O|>|C(|S%2=&x`3{;fu= z4f}Y)D@NbT?^1(^fyf(B1c65jAeYBRN1^$cw^P17w4=uL*pV*t;mWfI%)s|)*lWoD z?v_TZa{`euRZ=O`wTvh$m#ZDLuocT2$1XMrE8G4j82_bVTZQo5yg=c$cuSWXa942m z&Xcf3^f2qc%OUu^9bj|wvG^fe??jB8H%F!nygPv<QxDz(8(|)G=tU7sn}8ie)f2A* z3(c}G+J)O9YZowMAg-$t?B!GNA2xzRs9=8}?iq+1KXyaU^~Q_~xK2DVvVmon;N2#W zZXBp8IjN0cI~8(_XW60m0V}T!F45S%`k}WMFgLcaZM!_h@RdpaW(VRs{a$qaH-esC zz>cbeGh5ivm15D9=$rc3QMTJXDJ!eFF1jn25{-KlT`LdCFf;AR-eUvDBSXG6i5o=a z9PHiILB2x-&#Lx9t4;*1VDE(WR=0o>lE|b=+|Yt>`E9V1y|3o?E%c`F_oo8Uhp^PH z4o=za$Y<av^(FwK<`!<<+S4bIf}D7JvVDwtcMpERwXa(K7D5?b9*rBl+}(8h)}w=* z9#y0LE*RUL;1m8YzggEl?nK|uZXvBUaF#3b^?7loQTLk{T?fs;#3HOwDdjvj*39SN zsDH=ip1$_NUTD4$uNa(TTlf6Fmz@<k{7iVL6P$l@4`X$Ae`lo90kD&bRj}w+2mpUg z^b_X6KNE)05(E4)n|4*O{i2P!!o3A&aQFOxq1B*qz@TaJpn3VAW#6FH{GiRBL88JC z*=oo>V8}6fh*Cb}B2a?P5A78Q=M{!Mt%kh=hJBKU{mO?A^bKd6HoiYmAv4($kR8%@ zF>k<|SU|z$!tZR#J6>36KV>D-yNdqtJQ?xs=tma`PX-5<(j!|Y0_kkNUJNz}b{YLB zBxT<|{!YO&+`ZB)lrdpkK?ufgj=+^iX6i3v`YpdS`#$9Kz&tE`5Y8^ko-?lDhc}SY zR^TZRsr0Lg8VCk+g?#OAB>n+E=;Pu__sc?xkA1gVZjLY;+xsLkOUwjJ8OKi%g`1y& z!E+K}9eu;FMAKT~Dw@!~3H&S@x5CAEeTN~0ggG0SY)i0fqp|(+>GHI(D|KVyZ6b%9 zo1vuCQDMMsL+I%g7*9jT188Fu+7boq0Mg(FbhSuuWf+VA(_s0?BO5SfzlmcUR0Ibl zZapcC1C&dUcx&+cEI0!Q&(Lr}W?8?BMwbYtoufqoFJ#2rBtt3_U?f~3e+_)N;c{&d zL+Q-Cz3XCkF?cH#JE}ibnH``mk9Rr*sx4fB=1(D%Prw&pR{CJ*0#pkCm{ic22X;<A zLvR@20swA2gDL}3Fu+*@a6|!N*PbCgpa&Jjjx4~znA|u;_xPOJx2)&qu00?5{XCp* zL2$ZP8d|V9feumi4{icaG>~D+*Pn-wmZ-RFLbkf@DXs&qccary>Ik~O019E8WKTuv zV@?uNHQ5X~aN=tp@<JdYs`3cjLr4%#5IO-;E5Iuc!E^u!1Mue2hyV^#)B~;o02a~n zh@g2y%)BZHo4^4FqlFkkLI(q1&YXX_ktTFo7d+3O5K0A)EGoVN^j|HV*XroL`A~4m z_&>UItjhYRchyK(%iF9febY}T?BnC?r#ZrZbU{Ie>sfSCN+=ImB`UP*<o@@MfQ@8C zKE#SRF=^lIAe%hiNQC2kpN1!BbP5}pc%61C^3!aG_1j*+08=j43cSE3E?VzX0HSRP zVA};>zGC+Cs)1ATIzhxr&s1&~xaaUWO#hqgTJMYI8E^wH)7s^Hzl<`9xNw<-PWd6| zB>Y4r3cnxMc(ee9Pbl&7E!|3HO?cfWOr3S)!Ac%NNtooyynP>y8<&lf)P$>mcF8v3 zxWab{ckxvO+@_}R9C*oM^2WmVH#&mh8vms2`e<k7j+LGLLbk{3Qx)(<PN0<^3R#72 z*2h30^{_T!pQe6*C@fc=f7=MxBktd=U)INr=xq`{Wd>$=VJC>V3GSZ0i@25!mq$(H zS?bY8+`WU9AD(bATmIM~&ilvS!ecw~)8d8YU9dyk^<kp$5qqrc*a&9vnoMTZydK!i zt^%m#Uq6URXO#H`*^XWgl9>;<LlACaV?2_sQr3E(Rie%rgAWhluW;88ZPltIk-kdI zIYCf?yY^-k;lM$<1d@gGVPS$^Iu6o+4T}og6lBDlh;aFPo037yN%$N*zeK8SLLLX? zawoM!QQG&uI6@w~I0_;8o9HJ#2a`g-`qqIS9A?o5TDw`Kvra_5rtzu`_VF#@2+Msg zqGE%o<iW37VgY5HYaxa=OYgGl+h>bOf4BG!Q+Bv-)X(NSTOqr_R4g8D6%Km+MVL{+ zPqW`o9Kkzt=r&-gwmCdf52Wa)A@UJ!72h!=SWFL?1EfGFQF#Esx(fa(VoFb{q5IP$ zAn33Kfgl5QCkMZS12L}>aw34&*k?LSK8wbnK61d@fftTDgLPctc4A9B-0G43?~Mni z9)jr3cieg*pdxzoxDa4B{cDP5k(?-!&9Epf#Km0)=PI4M2oDcU1^kqGr6vjp(g(&A zyw(Ilh0hUy2S}d<p=8=x?FKq|;y<XzU&JKNp$U9Rz`R`e`kDXPke`c*`GxR6vQYR= zwR(VrqY;5N7KDf*9wIZB-s>jIcvK7}EvYvjEY^QRW-3}=fXhCqDPhc>oOEf7dalQq z1wx-9jTW_ljeo5&(Dutl{%Df(#cAwfTVOvxu;XQ4Hax0QVUs4e|Gjtf{%ePa1$D>M z%+6#B$sZ4%x7T1>tYNedB~Qr#r20(BBJYx1D(LuLLt^pP*=eBgYfDa5SHx4mPdwXP zjuwS#v8XU)qG@BUmIXvs;wV!INC2Y0yb&I7P;4ub$ljRitOuGUZA?GP7%>L<%t<7% z?Af)T?nvd<{lYVxg+AM9jHyn1TkymcQr256(6P2R|JFB|alg^P`!vlxUD$Ze4aIbC z2$z{dh(Vo!XqaptFgiF&OZ3ik<NvGeY2yp&6Cpxs(Zmbe5KY<q8N72pBU~E^_=-g~ zROHUYq+LGR(-t|9Yn8vN>dYhj7*a*-NmRv!xscV;$mX$?I}C|{ak+a|Pd*fSTNU)z z$eO~qC<enm97zWJYDK8*KPY)Wzx;@uVcGW)#R0LJ_Z#a=dPRVcu8>>{MuA7Y>-9^@ zEn3FIU-xOR$dI2lOYV&@kUj`z?von?0w2j36%E{Y2o>7dLA4Wg*y5|c_gmK}3uJ$} zE+e!DI;zMRkR27@FOwuL3Ty#{Ld8A7@G3X5)~;q_K-QC@MRZ}{-R-p`^LOkC4umme z0>jfEfdw#Sdw}L3=6%KT;ZBBU+LxU^g}1MD&I=G_k0^Wv0&u@xMaQjt3gO-Ok$I~t z;LKwOvzNJD!ehl#HlA;#NB%%ZMRWXu9Hf1xgV0rpWP2V6jBFMwyOA02svTuOWsbQR zW+%v`{9@T1Kb(lDI+6RA_gt~E9b2Uo1{UB+VDQeu!P1}x13<92dc)?7jW_@uy>IV) zOimOBUYzza3tum|EKz&GcB!uI3qUv!-f)#^`JVCbrw|`FXD=pE<@d^Absu1}#=3kk zQ~7=IfolA?1Y;fulsfrjjita?Kvv#~yx!#W(H4X%*X}F{56RHF6b_@Ybz$U|sGdho z70K^oWNE_*Xw5fyJEH0%0##Zsts2)Mty^AM7SKJI8bXz_N6N=6W1k;MKg7Lo<(9be zd(hBD&4b%}SrVbT9$so6Cg#?4!8+DK8YsNy;0Rb|s9`lS0Rr1+>z1QG<GT->c85=e z;~gYCem3v7%ujpN9H{BqIdvJiP<(`jX8xP`9Pj!w?|_iw;Xiz#K%nllfIBBhJ`8vK zaJ<`UMb}YnDSAvl^Ah_t!1Zd$P$JVN@BL0*;cNF$SjGTXh^-$I(c3tZ18{L7CYkcn z3Cd>eRau=q<2!HA(pJFs+J=P<$)O&_kXPwoM*<iCwO`u*$1qdPbTVTfcFg9xN9SQm zi|UDJL~Qve=mAvfuFO0=0E#s{R%Yyd+T-x4(DRz3!7>W@Co3vaxt_sFw;1Kt=xv$H zhfM6YFxC<FeCu2GV-2DFu!m`a6?`16ud&GyNR!OP>?6ycq`6T~FI=xt(ugb2!fb_V zIAmyOUZ_2$wCQTtyovD+Whf)C83rB7yN$OXa!dNzwF*<lO@4#YT|5UyN%d9ph@<YI z{+Wg<@a&MSHVygliV~W1m7s|$+(l4ZuF>i5l;^#8sFIduQo4BW#HFX@sRhBBqY`4l z<-vO@sKaV91C_bUbj`!>Q3nLG+}s7SE_Dovk~b!`3ijZAYI0<B(q5+ekleTi^0w&= zHPfe1>)(dZGk_z?HV4&SvRp&9(!mp<_R>%Rvvp-sBF<w)3N@J)FY{$54w_mY@Y8ee z**VXw@5Wj?RHOifHLq%^v)c8lO?oHuv2^T^rc+0zo^+&lvnB3qI{fhd&RhE%tkjkJ zImh--=Qp1X4T<myQuTe7bltOXU}vyZ=H+Qi-)nM?*9j3&rM+rmw<n(6xW1=A?=<B8 zJ*lqhNsSP1DpX9WC{^;e{RrP1w`Z1|KYXTec>PF=a>c>gCWYCF9l)orJI2DMJG=}U zy*iX@j$fJXq?R*&d7jC!PQ;komj~)+k+NFvPIog37>})f9bCG*H%%#KP%86wz(kw! z{+o+xXX-w56bD}ufBzK~&~W<@*+5kg<2#v<`n}|}{ug~a$x}%}4(i{!x&s<gn$E3! zxU|^S*70?CcibyGl*OM#hlcS}v<kYX7iNabs1`YK;M~F=`VZBr1g4FwRZ!C(7)jAW zR#n0ScM>QW*mi$Pv9(%)deq!i+xyvC=8Lds&CIY*N|e0mW~FpXan05`N=wbd{Ae3p z_E~sLj&18BhM$OZJ*t`w<15UEB~UEHeA=@_m#IO+RW3f+?a8}pS%(#TFE%}FXWvL2 z)o<xGI6-mH>PRmm6ekW{_z5$qeE)W14vT+I`vRACdx!p^J(hgwI<;rg8e5aEJmjWR ziO?Yfjf?v8U|V%oi|OdR2sVAQxi%`G`Bh|T?_)otiJ@+9WYXMlno(ygK0mWY*&dwU zcBuAp4=T;}n7;W>+vx)y7ez@|UK#wx`gR%PL$sJFxi;6f_GjPG-SGwwqN8tq-4huR z689)K;!NktxnoD7UUVEM^8D|dU$D)Szu9YKmO6I%<oz#&FCji~vnwfu*7wd`H|y*^ zcLPqFo-lYFne+YL({sW66zTbel`o_Hl6Rw-X7h{Km2h&$ZAo{>AB)ny30#A_F}Zdt z(~3fgJX_CG`Ni|gyPPa|wpUJH>YiWO{rvm=Ae%F#HQ(==j3&mITsd>)O_IB{P|`%2 zO>DLF%T*_*q$fppW9!XcuI)=tnyRxo+wA-Dz3*t!bm!f(*ITld4+;G~koEH$=k@23 zWBkO~o2T76yI+1hbu7MN(I)=2dikgLQ^D<<cjNE=c=`E1q2vXGZNh-`tBrK0<R!^_ z2_t5&HuKVxmv`DG-uHd=rFb;?t;xN_NAa(|UKKhokoP4$DSoxp;B@}|{{J?TS`Tlz zHm7ALD}S2!t*XSm99E)mPt;GHKO|!qLh%{9`?F);UFncu$B<h&)y|4W*RCjCc%#|t zz(gTl#z>yuQo4r?VdbAk^*X$r|M=^{y?4zm(aVp<?j?j_VR!7{G$R|Kx8IDed>6pd zQ5{G4{i-#?4LqdX(!Ki!yCHx2CX%i~jk%*R<ZKA)$pPYMmfmSuOdc<-lX?&JXOBBn zj;Vq0=T#hxW*&b^<i4r>xM8!9YP+u8f32mmc3Ug_0rB%v_w9V<ac9=BXT|R*()BZ! zu~vdkv8=EJtm5gbJ9PRiRHbXd%oZr%-;-NrN3MS(m(Mcx6-yuC4cto1o~5u<LRs&Z z%tYT1rOF2?Z!#Y@4X^<-K9ikFVyCL+!`xTl49eBRe%Voe=~AUlM&-BClCsb0x8)Ha zVkHneH3)$?G?XIulf*g_o>NwB%O>3Z`;}!qIAs6g=9Fh+N-)cL%kD%l{T}*q9#5VL zXkAOh99m;7L~2zLn-QBVpAfmj1y>Im%VWeE4-hy^mEtJj;olj<44F#|ZYl|&xz8Zt z0>QWvMPC<Iyfd!+CrWB9{T#K8F(aS1Ey+d+<!z5NHZo_3mm4&MP9#V>28|@TpcGol z^1??Ft9Qi&3MILrVz{I6wNA0I2yBG4FO+vHWu&2U<eWtISr98F%M1K-l|*5Xh$Fet zDH2q@6)26*g41kd7&cstQ6s~y2c|<w5nYAm1*XUW8S)gCXdugQRp8l!=mHsH03aEN z(phEc1fm3-r_O}4F)ve>!(#(30*15ZIK9RV#hisQH&I<Alx8?o6U?w|Om!x}Tgw@q zGxx7&=jAR?I75^MfU(~h#<Y^wmbu>`K%)Sf+A69j8Dr|_YRsj}EC5Ujtuz^sqyUoP z5Og3)AdSu=u^tmqq5uuc0rE5efrna1z`2&VMXf;;dfa5V5XOXCeh=NLho0NRFw|$b zQXu*IFkr%&p#jT_rspNlJNsc~GcdCai5Io*^Ybv%5_c<Fsx>W@&)~Q-XHsWFQ<rMp z7uO%|XIpd(iNvcljsB7YR+)M(sI!!GpAD7?KyzAnl$!u!RF=HYU=UdhEB$@U1vp@i zaQuLxnu`IeSTztg80r8lNHTi%F=uFY<thK{?N$9CDiAb5V_0dSNPt5dvG@J7hhAep zVuy>KHFt`eV15VFh4-gN%}j_$VtlDW;5GTDW7O49yl$-%a*WCdER?)68s6$8WnlU) zHq(FAA-^Oo70BqKpk6tntO*&a=5&<}Xx;=oegpg%%JSAkPuypoUSOW46v^S6DdO2- zJ^8U*<gGQ9C#T$#0N;iqc0hq0S~>c<II16mzm4_E(?A$HpcJbWdQ!@~gFMv{v}}#^ zyI^%T1veX58cstV3(pCy6o~94`0~h<>NLk3JitktOB7guxPcpHEhUZXGR$999%o|E z&=xp@kj5x!W0=$Lx;R2&HTruhf+nsy4yRqbpY|F897xD>%+YueZt$uHaRi0@>RB7X z>L_z&J)`c=3&&QK<UNbN{FA6wHGy27WFFFIhO(I9fyiS#W;h3@lq$8dK>$$5W6{Vj zGRU<BS;G2M=6&zxMxnTwG*1WC-ORKou2<d!(rbo5M$neZE}1}QOy)3kGW`silzs*% zdwD;QFckoz(vQxBvNWu!{rHTT+?a2dgG%nS24Nz8Duf>JT?)?dC!~1{KTq0jbq9(R z!co2jxii06-V3CCr9C&Qi4D90c7>kUdzRM%tC%{w8Omz^vdci$M<tUZn@@&%G}i0N zQ6(xF1#?YxbIo@wnx4(tqo3_Kfsmv>>Tk>mG;h*d)9uA$dhLqa>~432+-^O4^Maqy z*^&wd7r9;fJTJPn_!c72jpe~(?dKwN&K#`0nWf@@+PRAQ;89h4ORbS3aj*x`uNY7# zzazu{iB)ILd(X^s?^!_=O!*U5t~$+K&$<K+M(}_gW$pGfQpV;UtK)8{vnI`%E#^m~ z>Tyd4+o}-(J$J_tiu^gr-u>+PkAvOMysmhZ2nh~9>Da#H=vOb^T&&Z*a~7z2_3cof zUHZz|mt#?TpS<y$MfANpf0$9JzV_Fuiio7&K76YMc?fv@E$#Jo(d(ae8gJ`f{~mt* z=h^GOAN#HCgz`!}{++Ol;k?T0xflo@f*@}lUw{7bXm;^Z9o#3d{J}`+QP$kr^G_8E zb*d$)=1tI73w33NjYMNx@7KNZi%B3i7#y^GBH#dPPJi9w*z5h}_ng>3&a2FFyTLuQ zk9prxO$>jdvgGwbVC~?@EyWaOQ&Nzc$gLMdR(JyQ)0yC!+oi1(W+~#O)?16S`$1(S zItx}2IhhxkXwyQ`<{P|S8jsXPV0U)hH0d^1H#z*K_f`;_?VBH6SyLou9F(a;>TZq5 zK6-xosATm|O2yA`t$E0zWqq@72<t$&q6RTQaI0&uWq#PRR%&v8m`GEqk$0j8S~*9Y z^mNp7)NCH5GJ1RyBnXml^zO7gUzVu<_a`@MG4CJb!VQj|z&!5ovq=MJ1~UkoFqWx3 zO3iETH%ajjyE7_!G>YqVw$X`If?_UsHnD{5T@)h$i6iF<4>MKvff;*It_pB8&;s?M z*bZ10>#}!UV?)&zu&OhF+V;Mrlg8e5EE^E+NJNm#rM%f?{1T0$Jkd~gV2qwb0*Fow zlw{Mq_>6GtnMtM}^=g}1MT1Og9veI62Xzc^P@<p)%QJ`3=tE)QRhkS#0z83I^24g& zmOH8&4tRm--^LA2Q_E!iAl@5VmM4R+MWdBIu#SI1b+t+NY&n-N!z$ev=?XhM5VTnC zBevgT?@)TKj||XLqz(;@eK70jxU;wiuYdROPHWc&jiQA_aqGtLfH0O3)OLLX5#q=? z3DETB4gjna8Cs^r0yGayv*WN!q|kajPywGl@}21z&S)@)1C4ObCQ87evv~l(p<#(* z(Al7<HnDh-Sv8t#89akPWXYkR1x(kWf1*7M*Y#*%>QQEa8)^>#T+Ytq3sF#Vfe<MQ zL@FAyXW<09627Mr4y@Aq!&o~2+CvF~Od#sLRN!GaaD=E8_`&oLD{J(NFx{UL0WgON zNP7^D{D!LBy38oC2Fz{J?=ufk+FiH|!x^YDFXb~lV+IcFBgg<;34kR85YqX>VROOQ zv*Ao1)^r|^iC!F({FQY&JUiTdI&21Uw8|KuFx<DJ88Zz050w1^+@7#WZL}-Ohx?<_ zzBCQ`VA&4Q3`5<VmKmmlAH%?*K>ip@QEBC8j)KQR>b`|zOe*v78k(_ctz3-=n@I~{ z!LEm){3ez$66m230r~!z6x~s7Rl*<&!Hd~_377fB{#hR@kp~r>Y!aElel>!+u)GD` z%%Yj#5{)@3bFp2J5DR4xP$&JepGVh5B;;H7d&*~&OM6^;1I?H~W}M}e^%P~|98iM` zSrYf3o~<<9dqntq>5(u%+O$OS96oK=D*QlU`2p>4^8sJql1QfC2l*pjjpnkZgta`@ zW^8m_s5{I5VK9)uRJDBbSNS8mGK9&g)erifaRPH%7Fny2SyBCcw==Uy>s4!y=v$fG z8zo|`%Dy?enMVk|U!v{L{AVAi@%?Af;*Ea2A^mLc63`trnz!vPX^bER%9O4<=b5M8 zw1*D4p%fG7JGWCkNUWRFX-6h@1=8k<)Z6$8{w|E3;5*-0$2~;)x9>Iv`U43y6k-AZ z&^@Bz()v(A#6x>Vur8Om*)y$rOEfe(kQIM3u$SGm3YAP?G=K~nTIwDiwpjso;g#cP z<p$wPXlb6IX63G|@*=zUtbGgqjD#eQPByzlD4|kFfDQB{BH_W)*&EHD2BYep8>3-n z$4Zz%>nQyNcV-~kX9f`#z2zF8`LQSOVO!wMcQ;`%ug;?1?)=PJ>P0GaFs1#4ti6#V zFUwhEW+40OqV?iFH)h(~-!RqoT;egt1muNsmY!@`XiwgA3X<`1>48x17?ClwmeI*J zF?QB|;PjV%Fx^{0y#31G;@j!`g9(FMgr-xE&sUwh7}z_qu*-6_t`rs&_~u<NKJ4GS z^na_x|JEA*z3=|_Vf5en^M4=T{rmLe-)AAd0CnHo#s6Z)|LVlw^5uU!#{VAA|B=q$ zF6RGi;Q#98{~qQ4dCvd)j{i>x1we(wbiy|X0}PC`;qlcC<sp{XF3;BRO_h;sIkVI2 ztDCAkwu)1MPQ(|r`-NJ*?Z?-?>>MvKJocnD;;Z_ja?AKH>uX<kO;nQ8#dIULG@jJD z6dRs+zoj|V=&7xDa3tIRS<`{;(;we|)1Ki3j~3`geb<@mh<x6D;=^~{`5uRyv1?I3 z^bTKfD))!cbapRr9$fz!T++PzCBKFD4|!6dz`M|Aws!6G@x%}MM@4FM@2)4l(K-QC z4@G`={rYaoWlzKhlZi_$1E{Q>UMJ2i-Z_VeIw~(?@j@r8JDm?Vo%lu!pJ2$>oQswX zS$ZPtIC&|`GOpq|h>_lwp6kC?ar2^dgAlFf!1D7qZjzaDv^igdjkaU79A|UAtwC%T z^`OCseYaAIPDIE9eVj5BFn&yof0m3mfZPGJpu9zulETkq?S4Snu5vy>fpFts7zt$n zjbX^KXe(h<<EILYfGm?t`w-Gglft5$1Whl$qwqEu&B$7=H(x!KRnIo*1~^&7XN?J= zA&=}+sVBT6W%Etjq8Uq<_|d(=RVqjeY4uXkh?<9SsI(_<i4%1{r!7ZOa5n=(C~!n3 zxYdhl@cp4hqp1LMN;kcUn!}Q=>qv}O9#6Z-)&$C>HS2*t5TeN)b2L{yTFe`x0dRvS z)RV%rd~AN|!?R6<J#X$+yEL8Zm+XIiF64-)0QMlocq7-YA6=w_X+W(?sWfud|9DRB zX<zrU7l+Q|gx^tCt0Y>H<%>=N3-s(TJ25y`8>I;08m|aiCUl`DKdv47w>>CoD>CLe zq057dWA*O=A>#(46Lk;t?|l0H;O5pPNmql%*wFhr(^GaB(r-(wN=>^-EjF?m6Z>)` z;4-R_)IwZ4O5*onW5>@z^_bX_o$rQO#5g&lqvTh=9Q4RttKmkzYuF(dgJ&RP{4zGe zHTLlQ1dM9|#kY$*7Q+A5NJi#kO}u|O3j=1){d&;k9Su*Y`aU?E=>b00xQjGi-b(e^ zAu`2Oh|sBiXv75%8qHJkTeL_q0O&plUlGf>4P;lO5~VO(YZ<3t#2!aHxiN83eKBh{ zu+DvF7!Pb?^Nse2+vg<2r(ckGaAo|=%NgG}_Xz{`1sqZPChXEDA{9!AahOCMpqf5U z(M#U@Gwxu~EBI`?uo;lx+1ZORsJU#=0q^Z4&0vjfT)6N*!nFiDzNg+T8UAan2LxNZ zAs_v35(%6}EekKb@>O6ERAndq%Jw96fm@PlLJ#K{#;DUe#WU5iZJab>U<ygtXM-*! zvEZ1Q(vScF#7n7)K$j^Vvp7!hhXuJEaIgeqBKPe*{rbuE4&jI#7;s*OVq_nJtMga& zhgnGdy5H7S<hNHjD|+l6#*-tU9u2(zT++*ZCcRG~#7@%L(cq+kEeWe8uf_=4djLhV zU966Qp+}6aGj^o#1_@<`D6@Y<nquGTqW)dZ_}QM4!^5kcemjWV&53EI)0QMfNW(h% zLPL>%9?9ysJhk2m0)NN8Es)ssp=VQ2YG7?rcx}eKdi4&CBGr_QaJs~&=ybk3Sc@^F zu+BAB>6fT2i36)EyKN0nDH|k018N7b*8mKz)OBc$9ySt!3Qt*wmde?wXEX{(vgM_C z_-2}s)pRur&ybxY>~N}GxoWwwH?HBhGfqe)>(IKV@-tK=ae@TyOCS^e_6=ejy<Kw{ zWHITcAvr-EMVfkt7#yEwr>uoZ!>9>kA$FufG~kU|&cNlvcN-&ts6Y8G&$(%Dv#YdI zuuoO)5hzAHbMQ~!MRm*v264I4BXc2^&|;3T+;V0|^J>zeDR3umLJGZ)s}kKaNTe)4 zM6p55`w?6a2uw{e-cQh_knECZFrbkJ!?nSI@{N42TK-Z=S$Nbzp@He%k!OV1x)#xI z`mC=*(ChL0r4An4oaVlgjI-EWCMV6@VNPLB)UOKfK^taEPkYBcfe}GuFhZK9hIZz@ zKZg4P2MU#i>l~UL+BfJ}E27H9V4nFe3-%0V2#;*Dla~1cfdfRCh(^C1xsrA<xgR~O zdr}s?)q6_ndja6B6Ojh-*zNFYo8m{`v5rbmUy{Ez<~{>A=pZB6E(zJ`X2!4tHP z&(81no$g-p&M_(SCL{%@0`@o6|B5m0eV7<IKU?b*wKggD#L(M%DUq!{uZ&Axh40mU zmub>wr<komxh6q|10V^l;6qNgTMtShLI6IMI*{RdJXqqQ8VE$U5p{If!s77D*C@kr zg;Mzra*R=-%{JoUDxQ+<(X(iebYgwiNU%<QAZAh&nA@09zbg!|PJE_>g@cg_u3|EG z9G{=8vSH`Tru)QQHGoQLq`*<qdp-AMCYXVy=4$d!dv0F0@~KrRQa$$}y4du7oA7f8 zO$NC*M5L#$(g|{9&<uFByI|#Pr7Pbm!>qejg^QaS3@F!|QmQI+`U9<e4E4z0ot$st zcFfM4ckoKW?KsfU<c-V}ZJ$wSt#M>Pja=`mr#H?W!bMU)$c;}h2UzYQaUbcjPkT%{ zPQAqbv~b8?D;ZVPhdd1CwJG!T`H$!#OIXR^S+(yJ%6X&eyARz%oRR2jL;*vf<5rlD zFL%@<IOu4cla|>#fY4JfBOHRSNxiB=)guNlvJZuU4py;Vxtq?xg#oEnPMY37_pIU_ z+Eg)Nc290wHeL6Po6qJ1w-lK_rgy@CPnXaa+me1mj5L@~p1#Zfa%1d~j!g5FE9rr+ zF76C7Qy!0IM)Q<G{sMg-Y{E*?#~V|N_ox+1Qd9sALJ1Sv25m}H+xg_F&GAFZ3%t+4 z*9`0d0A}*0DKnT2iNB3o)$+Bvd12j~bIf6WY&Q((znz9<tOd(mkVZ+0?;8%$N6I2D z{$9$%D{G{WDM2;K7x+iL%X*KUOoH_~7`+t&ZpqlmG9F|`uN&Ws9M8MI-^p2jN-y_t zF9dgVR~_NH0^ZoKicnxatcEJcK0c9S|9pFHF=oKR_}4C4wCN*qY`8Ifp8NwL>)1XO z4t~0OK~2yimjOhR&9-*b*eHa#%73u~*r(T|w1$X7F*!jAUXJrRb*~aaLqEm7J9FiO zEfDwWEkO7tQK|V+X{wLM2jM#N(j@8#$!c)7vE4Kt{-l!q?r(Pdc*#=iYj-%z==i8* zcxhE4!_sZg#NJNV8w9qz^JRoq5*POVc_dHGB{j~FR_O-Y<Xi4n#|;F15ZRi<)Lfjs z9<>4+H}qbgKd3)XmI$)9&PdHB4!W+;2Pk%5mw8{+l-(7C$0;yny#0=4Hxi1(d^upe zk?k?*2iY-Hq%&zLkzu?^{zf23JHqz>cJg}}3cSLo0J|eBH<H_+?gWyopZV=&&|WMm z7qpj>Vo2LV$TFo?TN3sR`LqeyrTiCPG=s@K7(hqVfyaVL4Z?e0sHeOpO)+1;tl0IP z@yP(xldv;oD3iCm!W$p&S9|@kjm-8-U8|}l5>ubv33jI9L#!5az4w(hJ~vTF4V$Sl zkV;#E5I_GBB5h@wx6(C3MM;0?sS1_pGtS+zLn;b`MrtEcdsWHHRit%g$e5zoD<?Z+ zerkkY4KG7=kEO%zaWd(TvkD6)m}Y9Z2*=L`(OHha{b455X&a{fu1q_<)&ZA%(FNR) zJ{$&%Sg<1xJ3jJ$k@1SiQw}-tC@vYYd&^O;HN+{GVJe|WPGIfnT=vPH!Ov#sg~P1J zVF^L-bCb(XtmR&=8p%A6WL)0Ys6bUuGuM#=dQxngMI>|F)v*jimb4vb!Sev)p~qtq zgKQ=tZmxsgN=#q(h8cC_7@yqfMVyUeK(ZwnG2WR(u3ep9YC=vr{;#OEgtBb=PJ6$6 z;+Bh<`I0_6>znQiB(&bYhh&(MwVw<t>>0EIlq(a&Lr!LSmR4WfULgYf!JAf#4>F!c z>DZ}+sr!Y)w6Qsvg)l3L{dRv+OpHZyilAlSpe{qv(Ky{u#9`1{*^_A>jj=za0*^LL z_q@-@9eSxJ#ke7vx*RlYRjuystwv#!(ZRc@G0+G4a24+qB9Cm!pcB`LBtjX{Sl(67 z9*Y@%(d&+kvww76JR<4E`1~$P>{1%X-*9_8fivG8q<*$E&F*r)!<0P9o2<NDKqNF0 z1Kp~w(d`PVuA7g#z1sDz&OvYLfYEUcPY%|>1+KI3f~Gf|=H6%*J}CBgRNuHPtE<sb z!Yfq-ZjT<?<>p<W1Gmvkt3Q-gpO11o$}rv_TXM<yDnr`G`GeZVPl#$ws(5=#9=WjI z&YNjpWSMJkUuR;TI$xx*&u>SjUWNW%M!1Hb#e6aB-*XezU<s6{C~0rm$h+wBsP|{O z<rHY%K@K{dp<Ou0_!~|}ExB$$cIngAWtyuFz@7ZzpiDoJ(l4{UuT~ENP~XQoOF608 ziA$2r^j-A0vJS})4<tpnhI^9MA&d({zwq|L3PXg}BTBVOc775OhX%-Q<mybNX=R3; z16<afPH=;Ad=^|oB>}Y*2OR0Mb)*ljm{Lm<FeTzBh>zqDi1Id&6#sJ#=oDe78QZ-O zpkV6uCY)4*De`G8xXCl|rhh{_8W~_C00i)fv*;lyzy3QX74NDKDOUCqONxl|BwGup znjifdlz3ERs7z&OXEF?sX*H8!q!=>HWXLDcLy!rgn=uUu0J=E%HB*K~KniIbB0WyB zW0B1oTknf7><&S920#x$Xeq%Ya<ZBum};(OryE^hS3ag4;84<~y*J$MR@Eq*1>2*c z`&94R(;Xj4YPuvp6m|%3;G{k`fZ(3lEz<^M0OHj7oYgfCt8arB0|wP~c!|enh<zzC zY7C9-e$tGN+RVDMc_UbP$zj<}=2n)j2z*)(T_!SAN;q*r@w%z8-Ko}$n(zmDZi8+I z;K|;hF}a6NJAxi!ANQ`R12q17Qu6(MUtGx&DpiR&wn@&qQ*_&bSzX$D%R=Y6_AH{Y zn5;vE>c5XT(+4upeOhjIyUOW1<rwN(t~HdsWw~$yfss8^Y61nciOxY1Bl_88%?LZ) zAy)%pYLz7R!LUDlejs!)qZI9;H$g9JQ`EN#kg;%99*~_mpK0K>%brcf`8SZk2i4G~ zKatlDWFM5qd!jfG1&){xJM1@c3=tWIG_hY0K#_4A(Ap|&{iRK+y{d3H>rY+fdyP~h zx6k@;jL(jtTot%H0FgA0Bv*PF=@05D4C+fTWBR5_+h(_ssD3NgFN;?pas>AY@{*(d z4-CV|1<ik(mcGg->m7HpSUyEE-mrb^dju#6-T_xufQZNqHLDD%#}1f?eX^XNHTgHN zdx36%dL-|Fe@I|_Fd33fC?v%`uEp60Y1l2VL|^v~dA!cq@!7y-eb5Fqq{QE8<2eMT z)L)j|Jfs0Tq!x37dJ*hsMg<H>WlIUl*i_dcJB%5#U-FM^LmQi&{9UNrF+C^LK)KXV z+<2Z)@f*MGHe$d_`&DPnb>UdSdw@#2ivR*htyX?yf8f_aJ&hdm)<M*PLD?8Z(nkNU zF)b2dppK?%4}2z4A2`<z$X#uJ6HvGDt>MM|OWoZ=FEtOFXBjPJd^LxqJ>XIPB^&9D z+H1UKEC77Fr)^nRYRmqU`DoH=XR<Y15#wUyH)vTYZr`CKQ1>Q?3}H}kG#dc)X~d4# zvb;iKz#!Xdum~xuMM*Ud5H73Q-3{^_-$9Mr&+K`?@D&@@X;;Jvi*Uh)^WmX!y;tx+ zzpg>Q1UMwd<BA;z(8syhjV+>}Q6#&+emn1LJKdx(byg&!ij&c#W)DA9!gHA1*?H_x z>pSvHjPvKAJ@JS`Zs20$b7CQ#Wa3ff?PA?SKJc7v$vZ-tA?w68kXW5Wx50_N^8H7c zhOysnquvv-l>I$RK93o9wg-De7=ck~igx$)j7@8(;)n7uS`%kA-AwI?cBT?llsx_w z((<>X$GwaK?81HhH$=XBMt|~WT-?3=(u7BWTX!ZIL}&_>JvvRQcLomc-MX?&H&}-L z5jl2fqm$h8#g5ZL@;i1yE%lg6e6oc7={@mh?7C0eb;s_GPu@Oy`e6K7ukH;8v*2?- z;`hbJpNfyqGFv(npBNRNbn!=GS^SyXW(nQhXJ4GEU3gltCR4+51QB@l;jHjwzw2wx z`+2-vG4tDMgT`)VDXKkmr3AY6L;9|sls)elPR?m(1p6d$&BukQM&^w8?R3|K)T{)S zk@@+3a8q+n+i)>kMwSh{Jwo)p-edEe5A907+pwF1IiGu!J`DB>K%QHeywBU(t{(gH zqMqcym@9`EHe0FlC0YRYbhh*ZY))=bUM`mWv+$HfaeQy_e-<U_y(M`Tmy3HZU$rQ0 z=q<frQP$mCcF&@Gw72}RMaA>P(yL{cT%Cx(|E8?t0C8YHAPfMg@c)~#jt*2y!C?Mh z%35AsV_W5aQr1d)-PlCZXddDv)(Rvp2$pYN&Bx6vm+u$r3yVy!Rq7uW?t+xhuYIY1 zd=-xd6r0-_uxg5LoLGWR#FGPjm48`D51aO9f4?q<L;df?|ARh*Kmdr~;&1>0hyU*n zVgMHKg>wHl`(4?eiV|eMWhw*h08wcd9dlx!10ap|$u|H0+3)t+v5SI#6)@Ib_dnV1 z0%L$y|FF~qFEe4muIE;mCjMJ@<^Xgk0wB0&ZfQWFl1BH-|8Mr&?`Gu7`<>d)kWfh- zZ(>*L>`nBrl(#FDgup5;<+5G`L0*c8_q~7lp!>$_do-Bv_Yz_t6qY8c?)N|0?;$os zkO=N2rHd2vQ+eYSU*V0Zg6y~Zt&X*){*r1OkBfE^BCuJP3vTB&ogb8)`S7SBzS4V& zn<}idw=dy6Tw$({LRfJSA8a0W+^2uX^4q|avpV<A?ca>rk-;p!(!RTWiDO7cGzF|1 z``S5i<KT_!ia`9!UB;)bL@)I5`2bQQaQ{@3G6U(}2O{E{A%y9(V6)U>aC_oZ<@w@| zQfVr?LV2YBkO;^eP3=<nQpUfGVUjqR@Em@8(}J>?Eq?f2WvJ*|R)}Ak!>-x$<<`;; z5?5rGiJ*ph({h2EU?CE0`*2k?_sf2Z*P(`oc{P_rUL6|<y8)?0hRM-{@*N?6rk6AR zb*zPz{oKCzxIFfH#JdXbNmKa{t*ZTg7(@ySPl~9|cvt!dV6RqXo4OnZG{XrBPPuot z9@iCrsadNp^LfA4km~7@e@ZG}?pb9+z2&5%>`o65QfbH^TeDr)F~R{)=jA?J??cvy z-OzX?C~N2@h>y38LR;3`5A@$(r^QaAi3VfdQ6D?UfUfbbd7BTqw8!xH$JMV3hD7vv zwJmyv0H@`7+g+^q=RN>Fh&5Vy8x>Fvji}k3Q3{Rz)CI)4a(qXCXm=y5Su)OKR9`&X zaQk1>=CDjd>|<+a&FxR4YmsNijYnHO?~m2d=wCFS=woBrAB5`MJOUB*{yIJqGiT6k z^<(}-zimU|r#rn0;yF5%jeqWIbNcA_pE$RSpEi0f@l}}ggPHwxI>7e!=7?gd&i|q6 zzN3=-|Nrr`mw>pp;mAF3Z)2#bso}^hN4Pc3FwNA42!cD&OwFut<R~k&p_vteD=Wh^ zwX&kL(k7La^{V{x{`~Pf=l3Uv!#QxBi|bt1^ZB^nZ`W?v>cm&r-Zu0ox0ka!6!>(; zemeW%Sza&Qb}0M8&*yjdtq<B<&@FcVF<_0c3$WT(FO+jE35~qBc-`<@za4sO{5^BC z`jER0V@owoFL=dAlLaS1pT4bhc4U9H8FMxWH01{zlLJg3vOnJhZ)`;qM%BOlSm1TP zs`xO(wfy~Myx#e};HJ~(Ki|YZV-$Oblq)f2gTB*wy+}Q`3w9;(;4Ke35~eHOil}G) z{Qgk&^D6)CxyXB#SC!)f?tR2&4El`*gdTA0!`-oEe32XWW2r6Koq1cE$^RkCexDr* zYY*6LxhI06^;kS=sasE&`I2sU{w~`-q1hR*#MGD&H+s!%v)-kSE99BH_*EP1hIk_7 zv^H<E<Th9CFl5S~S%Vm?clMO0e~43m(6H-oS@qSwrEOXBCTt7!xr(>|ueg*fj%t=e zWr_@`nj43K&aOEdg`<m80^+y7$(GOjz*IS7;^ibDjb)U)Qj#n~95OOVnJFxldut<$ zVJ0<E0brH04L*d5OmwOHqMGO_+cD~8S#)=tQgeTTiDPwH7@w(jHrIRO1sN#x2c#~b zwwi56Dh2+cZ1_3vrH3M+_Wudis-S^YYUp5#2B6&W2-XIBAT~UOqP1cUBTVLcC-E<; zU1G8Ap0aN+6EZbxW=4$0ZOZa!aoR5d9nK<!$;=9o(oy=bW5^VGdrGUukd$p#Ha3y} zB+D?Xx7gzoX&vL?CDiQZjk;#bRIPMdSsWj%CE>Fzt_aXaBrI3k@rp=wgGk*%eG96> z4JF+rjY;u{LsSncKLOPA)fw)wP>s##Hqd!5OIT0nO=k<3x~p8c^KF~5tn4_|+Eq2f z&wev4L0+-|Jlk-URz~HMaLqWl!#SJEgfNQMduJnaz8=DH0VtQYHf%Z!r0(_`roUwA zEV}#SuB-@|ja<0V8<KoONN>#z!H7*=bA_SmqDH?MD$02|xxF?{`)SE$XZM%WaRK`@ zC)d0&mHs=zZ^@^B5R6zo;gxjkW~ug@z<L>(<&nIH>W?}(S`?d7OJbPPkp!rX^oI*; zUHg0r-(<wHt*|_bd+o~YWvF>n^-;efitdu{nBo4|@?Bn(@-gz+?6U{EQ`{HTAMqMv zFBc!pV%RCI&KJ2In379Tt~hu+aIa=6yFBR%5Rp4RN~kHUh(%j*uQFf`RwfvyhL_kg zB^P!mD59eXtr@fZqc&A19!2w6TIbZqT>6KOZhF|F)(`O6<Dpm)zf6wt+roAnCZY51 ziJFel;Tum(mG5fWH!$=4bbfMo-_I4PW+oS89x=83?}aq=E9Gi#5mRsr8cF^g4sH&! z;L@ZSny>k=4?$C<qzDc96oE+h6CD{~NLD&26X4o2F`ITThR=LN>^vEZQDh3&RX=7! zoy3`OTLtmzNioHzdm10@k63&#JI>~j%H>ucu8Cjw_BbEvIjS-~q;ieugL<T5clzwz zhofcnjsbdzO|(M!@BO0|jB0dP(BeIrUZ>qnEw=1$mOm_@=!YCG%`=Qs%oW&biY2?9 z&~dZ3`gx8rhHhHFt@MlX>UVP2+w=sH%1IvF5DhH#3n0tSf1+Ib&P4>Jw;XzCve~8g z_uI+uKh*9F=-4UT|Ky)}Z^L&4RCkFFiIz1%d}}*>>u2E2#Cv_3-CR~R$paHUctL4k z6s*VZpk+q23cpE<w!CnOgWAQbo)Qn^`Gaf=`4**<Zg1@UPx|-jiPZbn#pfL+3Q1uz zdgx#V8GDrY&1tX@`!Ux`epV(C4gygg#i09DydrJlklb!bj#+|UMqT8hdVfj&jgEg^ zE?-2NVYnjGCwye6mx1Qf0sDVuhh2ND4b(?)n@u1Y?47p4N34huhZYmLR7AeYMSQVw zSPyo$#dWpL?4FydIRR<tMdi|EmR6MI`_KqcRh^xs<-Y35{k1H$LJ3%*mJYFAjg>F; z^*(WVXkSiPgZ5|cn49aA{B(Wm*J+8DxxPY)Qwb2|&C64NPIyl*KRG`DxM1_a`}->= z(+vPbmSaF6!m9xUpmkh<AHHT4F9B6N5wK8v2IsF)gJww)XWc%#x@>=^P-z*r*&>6q zE1~m7G>3BFxmClq#5UKLmp!jK#%w^|-vC7I#UG4dZ)*U{$&!^_ICMAHv$htyN(*Y` zVr$#bQ<C(yj^y`Tj4ao5)i_($JSoG-8gb}XZ<2M}w|`DPWVW`Uk-1}57O$L>JuzdZ z1g>$$xarM@`{?K=V&p9j9Oob>v(oNK?5F5*A|B=~0cGPYH$V+ke3{V3M*nugl)Qz} zC9qrqB8~^4a^clt^s6MyE$Yso226&doM9H)eibbyM7_t$z2!$pxu_cD{kL)ZZ@xy) zQu8z#P}N*`-*$*U9+uBXUM6I`#=Bi1%8jkJI21wH0BT@OKeKLJO{>*(ou4v6lPPFB z7I2u+eHK#&9%m!m`{<af40wi&+fqhFN>gX~*!_0s8#1IzP&6z+-I1c-h2s8G-9K{7 zd{z?jh>HD7#2mtbz44GV0#eqHkX&azzEAENPi~&z)5r6znlCT(j#woWf8`;k_;NQS z=v&0CmCE~TH|JZ_%QfLkC~B}mG4fLihQXGznw1^#Dytt=XKVM~&Mk$MmTH3mlQ>M{ zBUpiyc^B^pc^NMdvr-6%R|J`HgC6xl_xPgDGBCTAkgIs?cUG`mrUlFqV*}mMK}Tgu zYvKV}Cv2eB*CFN-AZ1+)$rT_vsOUKYIwqkas~Ba*a@I7$J>a`d5d9X2SeZxEO2oEH zP-RPTMYAQ9C30@d>2-6cCfdRE4oDsY(IwdTgcxz)cpd3=5HblfO|?mxuG*RH&k5(| zxTq{M<)&pC5`l=%!o@EpJRu-b@I`%8_i-HNCQt5z1bYAgZ{%Z7FtG2baz7n+z=LV` zcr^=jzs&z-ZXp2zNTw8SD+YQ=VFf%yfw=MfFL;R<#*)Bf)QTY<-1e*H{$}*P%l4ND z>FjXYiV|APMO~z0&I9D1XJaqs1_aJ!Pm1NPll^4-6(VB(AQx4NLnP5)Q8e&g9_rk> z6f32kmeR4W^RQbG@~60nk9nxu?79Q{>*i>f5nTOO!`%IO^?zIxmxaYWC$`rl<&f-f z?pd2&@iXTL`(o8>ugka<7PgfEeJjA;Ao$A4Gog;<qmr5yzs3TwUz-}zp9pWF<&Btx zT8&^H5z62538%#H6fq=(3f)71wYoHh;^E0e#94sPBLQZXiaGhK=~ylH1RePT;I)?s zp@5*lM2I&7<RS)p5a3A+<VOOwo`|fM${Hw7$;wAPi0vM9XfXrXDnTw1P;XbFUC)NT zvB!RuAWw6V@48TJV&qAlT%&{Efo*4|0qClwxSiR-d0E!>_Vz046kiaq)S`CNU%wp= zp%yX`tUwI=;m8}8*ujP@f7)Sg8DWz|mhTmvt{=yq7GsWZAr%A+rOb&~w`oKv^uBRp zCJzx4hEa*YR^y=lVw8q6dO+Yhf&x?|pc8BTQL{;ne0YX*cOxCuE@%v;!}bYUt-BB< zxu|L$JPrr5{aFyhgUEQYBr4*n+U6zYpm%=q%i@sT{n$rRpE4Y>Nr0@zAsy@CUJP0L zEeKE!@{$Q%{DXyD_+B3J6eHAm|LM=fj_iSmuUupXN}hHNsjHg&X$Eb;s!nY4-nr_0 z6}K}nyVoQVeblw9HnD4phuFhMwG&y8Cq&}90q$oOrq>92TWl9tD>uN6JWa&PVwh(b zP)|JkJbm}UgkUoy=FA;PJQu~Ez)Tb6UXCIK6UYw$;%I2;u@dVbPKN#g_6-iak&68; zz;^NxJ~W6N4P?j%88I3|iKr$i{gnW_f{T44#XP4Wzsd+lYHV`qQ4vE<MBMo$1pQEw zUiDx9WVno;s|sv9=uL%q_8rUvK&eCsZwq7_j#<b+G|B287+B};*w2#aEdP!ZT%;6# zx>t;Bra6loj@Q<bUQ@kprFjV=y+(&oQN!Lf-<%(Pbtd=_Zv(Db+;wu0wIl#!Ee!i7 z;TSP--`yKG|1QE#@i2__zMEFpP&cHgqk;qHaj5S+>>&o!l?biiBdvF0F5?={YP3C& z$o&}2zKDbQ<B*TIn9JOK8rN>ZETXS+1tMyHy%Qo*406On05{;L0H{v<fk&<|=Lv{8 zA9Ri`ixkN>3NU}E*q6Q?rjEz=W?`&<J6aA33Ei~42H5vv`CkI;oS@Ld7#56!{r2B1 zks`B*@GJm0A|G)akIJzh&LY5DB*P!6veSN~l8*RDN3`&ULkCA9q7cMYWT_OHFGaRd zM-u}!%jB(II;#E(s)H85_>p`=oNVA2*Vc%h{BQ73E6w^H>i&Ty%R?mFLjhJ6qC^h- zlmPo^UFs;x!2k&9T=(+RQtV&u&P}P9_gY@QMCjJ57utEr=INw{Cd6hO;uRiSJ}6`k zPJDknu_tw0Eg}Cq5%c05l&Hq22BaMn!1r@)&q_kxi=+2J<qL4|HkZaNe8}0-Tw_(N zegJl#08xQQOj{sk-S0n)x<8wK9|eUCKwyXH@H84Md}n+7PJkj6Y$X6&;eeh3Fj@ds zC4w{rKy4ZTh6nuC2BNt@cP`LP0LYNFtKy*zba(?5#^H%;X^7_%Or>BX)B^QU0$2SA zFXqF12dC1w!#kQr@)__$JQy7S-vvOt7P)rWTjUQq{Qv-D(vu%ynzT-UTs;9Lai{%o z5V!l&p7*ES?r$-by>VgM=hU=}!}9llczR6R-h`Ub5lI3-*hiq11hhkD9^9XH!hz+f z(=Ix*ULMmsPeCc%M}E{<ulv(G1Y0z@pbY>Zl<~k?0?yep=Oh4oa)JLW9t6pXSS65D zfLMbHUT*@bGUgQ+^A*wH4OFm&0Aw%Q+NA;O_5hCuJ_gYN8~KMLcpx)80LOdK>hWX) z{>j-3k5%YEHSPmhV>Afx6hwcbfCnhhpLBRU9k6`T`0Qz8G)NE#+dza}KK!`;Bg7s5 zfcqC{ft%Y10Kx&l2bO@Lz<ytKqNR?jM=mOD5Y@FVhLsS}!vwj@lF_hPWSmiw<*(37 zvvQWdp1;?5agvYvOos<#p<cjVgc-?|;Gk(ZL?;8~%Ljk{FSD16Da3)R@w+?l&oQ@9 zr--PqYnl7R@N@u79Sd{igWU*{^$LK71nefg=1YTYB|;xhv_8&<?ZKhu3CK5B;7det zq!f}OftAYmQz9Z)0Q2;eXzMQ7QK3X`rZG&YAp>ZLpqLNvG(PMd3R}%URP&Md=MJ4> zAXez8$kW(i$?KRP^aUxrkcY^VT=JrWAab(HqzuP|9pdgeCNu7cAVV?4l@3p(!*_6@ zReA7TQm9O;WHAsk0f>F;1h6?@Lr%P`4gfncV27j_MjEy*V`V!XDhttb#E80!&{{5b z1{bmY*t2|*ytdul89K`KIo$u#;?|8x=eAwxh&po*kM%Ucig+3K`0qJ$@8u4mDCMYm zVnxQU<oAL@*Uw>}F*bk4?PU_7zG7`h9I}Rp2%p{d@F-+q@?#hgn#_1*irvQNBK}44 z3-L(owZ3-*;|p{05B`1lfNvgS!#jD4(O1Di638wZ(18bL-+bwcN4V&sMziIAh~@Kh zP!cZU88_>hRQ!=3AHsucR<y<wpz4>tj5W3Do@u?)bkCL#BI3aYTl;h+Km!7ZfCpKM zzv=_P=Ifijc}gK$Wo7MRNH7lmiGh+Cap!0~C!`1$HEb1aB;*j{3m#QWM`Yk&TQ9+4 zCAaN2^G)awa5<=nh!GIZx8HKm68W4GzdTuS!43~+axW06uQt&jo<a9d@llWHs1)jZ z>v#0r2SRKI<{cNgBt>0vN}nO3S-0g%_@FKH&yO1sNq-@U55T7D;4u1Q?bG|2bkqQS z_bc4z2hZjI;<0VgELrWu1w8ijRuOCK+9}3;84)RyXt@$Z0u`3H7h*CAE5e}$sxS>K zmrjE0qDblPPm?t)rQlIXjP@gVR4EaakuEn2SpCKe9edRNmWNuFep|kYJSjW>cgxV- zE?5WyE|YIF2>)aQnk;GFegg92ZA7rry4G<lDFD?ffwOs2fdz;tZaZKq==9*;1_H^f zC81J{<3Ehcqj&|JcHb-Os#Ho<>Im#|bPS#IkG>dxmkT7G2zl*aXBmB~NF(%3K%>K+ z=ffvL-v*ubIQ(z$fc(ZyfcA)<^J76LTO60e?w>T?8`U1XZ;9H>^h$$W@a@(7qN$3E z=uUiye>~-ow$soxNBxff>x!o9!)t55l-a%}Ij?4W%#HnU(f!endi5Ziw;sb8v~(&M znw+1#!&#glg^WHl+1DP`6L&ReAtiIJJ@EYKJ$s9oOEHC@?`1gCO)cwYDxi9k>UOVm zX@4eo4AW?tBKEa8@-|4-H}Mu`INNVPZ>1h@`r_CM_L1LFz+w2(vneOyi_udXoT$6| zR~O%$V#z;v_9y%GL}||J6Q|DS7hHV|CkWC(QDe9E_r{KDCe_7qG@?>~Z|YzLEqt<^ z^)P{gaay8Mj+Bt^XzmlANKnob27mI{H|}SwlRv4!KArzAbyU+?{Z6}*PxeygSWtF? z;VD-izhWGjN=n=u-utT+<)^H$$9}*6jrRI|Gdtod7iN1nDzt_ZK3aP&DkL{jWn-L5 z5!BRp1eQP$nhi|S7Atf<e@IXYPe6Ltx7k-G>+Tz#8m&#i2EJLZi`*T&S{GL)Ye-DX zd7P*cqWG(=#$Fr94xNj6$yQ6xol3eAa(s9DiL}n^?Hb!-*pF({+fu8ww_P($Jo)9; zuQ#WD@|e5vov$ckIuYYGjyf6d7GdFgqVi^sCuKkOR*Oz=eyy6^02Dm&$sF3)5IdUa ztrpIS9Z^loYG$j_E0IR(@oya7s2{9aA?!N*^L5{@g7s&qXAXbrfddZAAG{Q?{Rv^D zHf+aAn=)1M#ZXD(k$S?ZxO3Or7x!Q6NjjBEe9qR%_c0Y;wYk)lR3G?ctyMFntm~|5 z6bE>qF5fp;pL@z%VWUFaKoe&wGHz(&(tg)G3ex&{%GuL4BOlV%?dvXGYj2FnN#&dj z7M_6D?Qe`d+mON}89k5F4&-R;>5V;G7vy^<taj^wf}i&OD?J>wh?r`1$04}!AYBxj z6&RMTT5v5hCHnED%suD!B-KZ?U;Uvj<H|T1i86fcL>!~gN#@p(x`w8=_Ni$kguhh< z96Yw;+5Wlhn{{Z<4!pg2;6*{bUnlRAMt|qn)g7bCUN{@5<_;R`_2=!&UzUyrzw;YW zOXg%AR!<!ER#VGJ_+qG&oMZ}B-Mz1Hw9)wqKfFF6YFE;U_=@VJQ|>Lk-c8#$v2fD? zJ(Q=c{Z2H`c9^KH^euXcpyq;&yY;Y1_g<-rsLK5d+t3e84c0Yp(%9w;Hf5Pj@v85~ zy)BM>LB|6YgK52^Psy36z(XxK;(M5LTxR8+#CUa?*<@3bSrOJXQPNC~TdnQ)GUWJc z`lNFj+PpDIYjkxb5Ruhja}nmfsMZJI$ZdwB7fiwB*W8eRs1DiCa%RrA%R2r$lW$~J zZaKOJiqZYvzuEIg4_OffBk+Kj*EVQ+?>KDEhiw>;8>hG;9yP10cB^fgjCwx~ah=tZ z+fmC@yJO<7g=<En5y6#f<ODk*j*~>Cs9xudTDC->>4(V5&%}`FS^(R<Nof7JA8G~Q zqZ_<LYL_%$I!k&`d*<U*uH?edFI4+N#h8@7bx5&m#8tWQh(*=gxnVZ%obJUdx5lj6 z`dC>VaM^9YxbH&1qu&d8=o-MHnxLc}R~bBJK5Dgb=bt&}zs^*q>I@Hl_>N`zTXb?; zoZ3E`mnon0ATt`Py2}~rG^tP(RALabBLF!$Y=g>;GEki-Dmu<QmVs#^jg;0iei_Y` z5ng)ouXr#*h|nro8KG5OGNk>6#&PO5&|Fx0YTuwRK<C)SOs=ubb6y?|Fj3km>YTC% zQtx|3O=n2(Y}boD<(WW{nyfG{X!-a9)ls=K0LC1lw3Iq9`{?3<k+j>{JEu}VbYY9c z>YC-vl^!V|zxTey#&1Ynk=;RR{SokW7uz9BWIt2w^f1Tt3AgOc{>hvlH6yP23NoXH zrGAqLv#hYe{MSa7r#h3>^@k|?(YTZ|z7W$OQbpEATdj*GV^*F%UD*{vrPbWy4mszM zA<||oCx~XmRhM?Zo>v;JTg+9z4Mcy+nY;1gWBre#!Ih~C`i`HcIacX#^d5AJ{1ZUa z^_gZ=fY{)spaf=>U47K8EncT*9BScjQ&ImnR#VI{wf*p@d<Wk^!CzA3m_#a1O<-*q zaA&H6rcjv)iyDK^*p8fLEHM8n?o7W{ne_-Fd!bq3<1(x)jYSFetyfR1nIZTjS4{s> z8r%fi$7TOnOp`8dunm4>6TS{CTa9IzzVRQmV`Nqa^^>&5aD2PAA=I8Wmf3r;x5e&4 zzx-~N`cT8DId!OZTlQ=WW?+}~@RU6n$RqY5iojJ;j&DT2_Co@!O$KGh19<8pi5?)J z6}z8tT)D0DtceW3)b`YTSaEUmH9+7LZg{TiyV5e(+hcb~{gaFT&1ai})NXF;xt=%K zFlu&<fH{baP<`kdYkLJKpO-GQK1Us)Z#?_X*@US%oXdq}=~bqu7@$kXHy;HJ6&q*| z$>q(z1lc%mwx7M!Wi>cb)9~fot4WcL|I2+PH;RVxpx=U<De;4gDZBIMo<9FMIp_Ix zN<O{zmCEJZI6K}DW<8X^%)8m?W4XXDOYOY;qAvzspCnrVmyND+#gM&<Q^?eaMD=wf z_i%4!MZ`Q2nMWmGJu`}wB*kmq5<_*j>hEndFwhhejgTwV=XRnE)Nil7vZ)Ea-6+d` ze;qyWf7$Q%;Em@dpnwl~on*(oIvHZG{0l%p`k;P(9_N2cu0>?!SE%A#gffo@+2}<= zr0;cGXcgqhULxWoS>}zwyx3Jx6Vfw(u=ORnD`eY=C@{b(NKKagK2mvfbF1d`c=rFY z--o+L#3y2{&s}Q4P@hor0itr><wE)V1~+S$DU{9kMbpm>UYq8Jj#BwR)lHRNpIoZ{ z^S!d(l6nDfudw@N`AO)aItH}=E2;9(F?{P0R)LDgIaHO&yPp~ls7HQWy?yx8ffxTR z?7H)l^7q*1UC;l#wRRxDbX=dfP}HVNL>o|PRbJY9a4L?aD`b@Y(ec&npNFnQ!YhSE zq5ZJ){SI<>InXHHzVXZ9Lu}dvJ3sa|>WV-v!85spvwRnlN3`0`>yT3(QZO7+v>#IP zA}M;ES56pG%^p%q*tB|VNMi;^Q+K6io!Z$C^GX5vG}t}XSIRUgKC;Np?o~~RfNv!h zNBgq((~CXSWzTbvRDnZuXZ;QaELje`$Cnd>IQ2VqXekYsGEdyj^^`xP((I-~C>mOK z%oaHniJWUG%56igS16}x#c{Y(ae#W7VsTIk$dS(876(t`!Xn3^G0TQAysKL@*|hV} zcmUCd3J#cu?J+r-Oyoq;P8?Gzejmbd3WFVNgmty3+h;?gBsN-2qVVjI?L{LIgQ6X6 zBMq_#dcImRRWp;%ArZl^6`1aw#k&OTgR=HA-!u0`>?9m9jyLeyhP|g#-Pa$w!vr3L z0|nvWaShN!6P;|(7`;gCq`|E;*|&0r2N3$U>$L_~s9jSW%dH*DYa7eIGInry?9j~E z;iWP1`H_O|kpetwPyf}VT)wtU*qH}ERAM?4*s%=QryjLbI%oBl-g<_F^YsoidJX!s zl$G9Zk<L@!W>TCl25(GZr!J4iGu-F$%#sm3sesx{d<{91lM=_No4Ipp>CWlZJ7*vh zqu}x8K}y)ub9z*u7LI8sVL9PI^GrfR4=06yJop8gWC9IS=NR3C1QP6MbauTBG&Mpg zLVU6l@3kEdOU}J~mP|_Q?+8)WQ>-bb9aP=LoA_Qnax;BMW$EtiLzLSA<}HQ+t4ivJ zm*D_Okw+wZm*TN-g=5YsrdhqGXnaohALm@6MurJ2ZH?ua!U<b;ir{j#@nJbQrVLHm zCgCL8v>yby*P{)1EQgfL6WO)JS$NL=6r(?=i5HN`_3?7|THK_>e)5dPy``ohc@6c$ z^nw3zTL4CkY#4xQ{HF}o-VX&3bmm+*sYG@NUHI>zcC^$z9t?;)2F;l-(k>|)uPO5* z!XGqf?>x^*Y2e60r>VZjlQT6|+^VwZ#U}aP4|?jSf%k4kk!lgAj&u<lQ>d?N#mLvl zLNBCuVc!E+&PhAAGYt}&3wz)XlUlGVRxjC2cgy^igiaXn7-t{xx>h7R8VBFeQ2b4X z(ea7{m)TTb=!Qi0HZf$MIy-=<p6gq@n|p5WZti0C!@O3p$?=EzTDr|#<upENE;Zz2 zIV{|l{a_IWkeG+%vIBUxq7a-U#)<XaL{3}-tUzm+5OI7*NpB=VX*<2TQyu;T0rwo4 z%HkDg^Euml>fRf;zE!&IwJq!mrS!|mhnv|mc)2oBKtOsrlv3OJCX^Eo5I7TyQt1}a z0@yi|;z|qWH-$#2T&Up}FGP>dUI?tA=s0lLH*v^!Y)Tu0=0H<#d4GSj3+iy3KI6M_ zHtw%gv$#0F1hR2n*6jvOrV{K2TpSlCQ%cy;czA$JG^29T*6u|MWMWtoAq9jr;9QQo zlY3Gvkq(QZ-%6d=&b{e}x#!n>=;0l^*+Y-EhyI5<G7mp2xgTBvLe{`CF1wJ)5RRT` zw*<C17anW_?WyP$3rE)pg03AVoa~Rc#5S;mWqcxF_PXLMSLN|xhsVb(uNK@a&PVjP zw{|r=eE7Ks=2gN<>W2n|KxGe~>1!<Kd0(%GFb^D)sD3<|2m5q=yNUPXvx!e!mDQO* zK-m^}P6^WsR~#v2r+CBCPRu&aL$;Sx>s6qOvwd=wi#*=D#+b}Ujr-Lk&a|_i_Iqq9 z?13MYz*C&7J*jX#U$*QoO0Atu5kt2xL(CD5JC=*=a7E%Mcq$HzP=X7(VBrBfuU}ob zd%?YsgtRIw&dUXR^utm@IJqKrvX~RB&bFa3W&9DD0sSvU(<4_ab=-evr2FFV!os8I ziAZR)34DDY4r)QW9!KZoyPVSa-b>p8^~Q73=#_~WumtS9TF4Ig*7RcG*@s6lhwM1X z5zugIu^WMP1o80X4QMp3IMn&#x;`vLog1hQvKEh~^Vm_uu2VXf<}#mteEs5|io^Zm zu1}jeN5&z(^Y^z;al(8zua~hS)Nw%#ZXRowBN4FTZ-%KQE>B`bw^m<Zf6zYv#?_km z)Y90IRJff0Lfi)JqO!A7VDMX`*A1R*=R#uufEwS+At^E`zJAG^bmg}MuNsHHu_0M- zJxmG?LDZ_M!ndn)r$U&%Qn?u4uDdJH?jrX6tU<juudIGp9lQ=rOTmZo;R1qJZF$_f zRVh18!0F94PVKjdNzrMubhW;==+<uT>;_AgLib1@J#t_V6Q({ww*I2X%W?*aIAP7N zBFnEgm~C>eTk`v%bL!j%k5BCMeppa03$dGnJrCX4-+DRZY7Fn$cD}0R>qj43m%?*i z7yK%AuNb<v<6LJbZy%o%%Y$Y%n$Py^3S(48x{0aEL)#tS#81{ohTY!s=Fu^RT3U7e zmn{Yf5tgx^BA&+HTB5w!^X3go0hP0+c*-!y-u6~}$^Dlf-pH6UcL=Ag(%?|^+uXXh z4S?hW;ZO2L-yS-GyfyRo$dBX(YS{G&&%%FinU2e~(mSm1l*6hfeS4N`qL)iX->wr{ zmdma!6Ka+#VwN8-rd0k|uJ~8XRb8nvT47>e);h1$gs&V=TB*xfspqUT)UBLoUunFy za&mN~X?Eq*o0Zc)R?fiQ@l@Y68@+3BeAnvpt}XoC*`#;vIqy0+?>g(=b+x}cckSKz z(Rbam?=HM~cX9IBp>g=7cJqM?PX}(o`OkF@kHZgk79UDUJ2(z+Zb-!eX+1_J*JDZ# z0;-Py-`|7*TISP^EWfXRUR)sXJrW_afl8TQP8CSc1oF#*#yJJ__lHj?0O&!02B^%C zDqmiz<ip<16c_l;-Ze@skirl4!w*P{e*0S|h`n;d(-}w<|5`DX$h?lP@I<iJyEW<^ z{7XNVi>;$JJ$f7l;7<oWIipX#5p;w_%mv#>L7mDhuLw5Krc$;XxcIHdE`RJZ?6dUW zCm+4NUsOLoH8of$<(4OX{*kno!~DEf_xV@*=ihaE=OLeu%<RoSfz;H{t998mO-ecI z{Wg>H_Mi_Pv{ed*e*z{;;RVv;5p?8Ux~!k%cmo}MiGJt26!eykx=n|VZI^#QhdY_f z^uzY!&)e~s>o$$v!L>W3P?@{BEB8xduri<%S}XYC({+M+ntl3R(b#t;u>`s&qWA~` zm)5`zbY}bJg6GSaPU50%e0c>qql$1dSS;-8?}oIs1_J!s!?lKogm3G3?aEur<ws8_ zRsp{`t*f8ts?RlR$<aS%@-pzbvXY^i68Z7BP4HDC&T*3Qsw~4ov0jb##aV`&^MN1R zd|=ggQ{^<Dlgj64_GE7vTlK%49n_c2)qu%vbuv5I+(Ly+0rca$(o;=)>Ll<kJxnIC zj4EJJJK+zhs2#<}A0PW3vps89)&92r{Wh`C+Ph#$$iDRXqRFEm6Ff*?u*pOUvf=&E z?{rfh2inNm!AqRUew=L$(70UXlG2KO8!CqWue)c6dVnkdleu8`T##8VGr!{}y0Z{1 z0Umk)P@@+f`Fuc5#vJmQ#%oNAHP8m<wW1dw8F~0B1+>1%T`PS7l7Vj?{c9CtYn7kD zGwiCWP5;Yj=i-0WIQ=@d`B$xRUWjk;wt36A++PjGu!b{vCyIZC3Vt=s{W|qF@3b*& z!<JG%Z)A#?Z4}1#BiMa!X*=O7M!YV4sT*)OPn;2x23RhV?T2;uF)zFTsYwd;#J>&a zS(d)cGE*9J?Dv%izpuXdZ9M<mupg)<lOcIvZ3fVl%HAqvS@OWj%RprUSiQ5zK?>f4 zU}_<lcy*>~E>NqVAs4~GMKBa(Y-0&Pt^@!S|GBTmkS}38r~*8=B-?2KPR{+2H5=Ia z{#6u%W{kmZe6WfDB;OBsQU!qV0Wb-0T@DZaKk5-M{o;?jN#Uz?#*6j8&*zwP$ww?B z{#oH!ulvAn&itG0JA}a>(KG?dvfm$n9{D&{2uG}cQCt6NT<~>{X+{6{f7$PXx5i+9 z-oKw61wV~hp(!xmJMVdju2=vf<Gt<FbdGt0ZPGp2Ueh>T<NwQk`;-FkuG!<6@uOUQ zW6!ABFaQ7S_vm0>Cb!+|nBvPFJ!DL)G0k`5&amW2joj7cQ(GFBSAqg7+OUnoV^wDy z(#*ECh|c1i>F)%kjTGaM2>O{n3qy)t-bMWio`{rYeeW8}$UhN<Qz8KvqOrRTpZ=0k zx<0%yENX}zTZECX@jxrI?60hG$VN>yfAgt*vh{>*9&<bDk-6V%+J3F?A5XgY=a^`; zc$}<p$*PO_HoBA&X+$0JK(2p;Rn?kM+!1+tps_44Lk{4`Fc<=>$fG+ugIm!jY;(pd zthd6BZCqUjMh~oRRMNulUutUJdZzO4@ATEVIcr}<#yYSB#Q>}NN(!O>4p43Hbcdmf z2Igymj5@l%m0OLPWGUL}<ge+K=#@F^mu_s#)h{zWjbN1FdzbYCZ6=%zDjl96h#pS> z{G-kV!(WQ4F7kywCf^6YPB=>Wi>PDD10rngkBDiM>9dlM5|d}cmz7OFA@snE^#Xev zCNhj43zS#wOa;p7jin-a-=<8MN_NPXJH{tpEBNBG8R8+3T#=X}ujejiVvZboh;eQ! zIy)IrUA7J5FoT%cy6Jrz1#5CC+w6{cvoHC9No%g+r1RoEa8<}^e`t`)2iiIL_Sakr z)}z}@rAp&?)Rz(sXWRr-P48YIs5fSCXw2p9u${l#<ZeHC*JWzjo~yIufl1eQB_f0V z6J_Q{T^r7cCS6aIUB2l0z58zbjraU-9|xBv@&g?n(IYWVvuh^<Z_m~)e!dN?KX%{s zQPj5zmgz?@!(p;Jbkb~~n-yfVvfLtP`=DagW?Zk_-S*DLlZR|4Ov?`~R<8e%ev@~* z3Six}+ViLS(*0R9g{|!?EX3GfliUdMfY{jj>J>w#$Qp@722}<PwO_Cr_9-M-9Owh% z41Qm>WwACmF7&8<Zxa)tpLt~n@-)8R!$-^9w+E`7fmZZ0s~!x7^y=Zu$=KNC=FNtM z_+EeGW@$~JW34}Ui|HvQ^S=4gpxp!au8aQiE(;0M@=neC7H8v9Y1d|DGNKuRE@&kP z6}+^+jB0s7dX1mAH$1Fxr1pkRx;`PSOw<H?dNpCyWq4-L{C=CT&F<<S<~_ow^06(p zBe+nxpMCcf?-8yp*xs}3n<3w|9yU=5u*9iezV+XT7*zTD-fD;(d0nvZ^)BJB{5QF^ z-%ht^5U@H>8%8)1E1(g)^mHDNdH()V<!hpcDva3dnAD8PtsranQGLtFCPIZ8evy&8 z9xAj`sMveY=Vw3s-jQZ>cv}mmOyc99JjIE!rzq~H59^G7DLX=Kl@-&nu)RDcB|BcJ zf>CVjZ%{%SM<O%`Ol|TIY*V&D);DLk>qKx>{(P%;cf`ns*=vw%Js&q;BtXrxdyCyZ z#L72DKpn0WUW!Tphd+{d84d%Wx2{{ky~hg`k4m8WxMpNYCj~?3sSGBzC~yQI!#{%J zAyV_PQ|@H!KFI)Xt+KYjP59xfpft>WQFCw_){V{Kucw5Wsr3_HkeG$#2}^PDW6m%_ zlWeHbxwT=cgk#4m3`hpVQ%o{xa;-?ElQWCTg;KKm&YtpZbOWWvh|M;(Z51jtmz&<W z8@o<-O)B_h8Cf6FyT|*24oz>tv@>8%0aGy90GieyeOL_<T>O_hgos$-xQ10@bBV7! zd<Y;Fbs<9Tje#l^CnE5|um=QSrG|crQMh2#W*Df@MPoa@1G)w#yu$A22M5JvVltyx z8n^pX3EbF<D6vpggp25I1dbC+USi5W7@{Vm>@5*33RTWt+n4FVKIE5(@iMYH@lKyU z@1Y!3Dm*Pi9D=UIwfAU8*mhQzN7b(HRqvjU;2aIEx&FjgPn>QX6DgDjlo)96Cs>M# z!SWgX2Ju>2qjs}h^CPy`dX7fN#&o1A0fv<{+lfUUnZA^Rw}c9wYoNv)2BbUSl`<_0 zBKO>&*hWgG{p8_IKPVvd=&v+Oa1f>0ai0SLpluKrs9RAVHZT{YX#I?0e6$&}#~!Tl z+fGu9h!C8}tWxcp_x^mPx-vDJsoT&$oc2aR)kawbwbx{K@Pq$2!q+b`@qr_zt0}XE z4py4?1W-z6pG~~FLC1!jqw!$$<D-M(L`Ma9WSZX5BojUP_xw>4Ni!x2&(hEd(csv1 zzr<wqi*zS_DFKR)8^V6{uK%fk*+*Rm8CblMJHk*glZ_*kgaDEIcp#(aHYnX~23j|1 z@OMd?P^|#HzJL;zen_)h#!8FEs|IN3QXw+$P^(-$5o|yQo=x&<Rg1Z0+E5T2kQlV6 zaU=J&R$?=9TLoEnQF7lgHyA4eO;nQEDvJ{~*9rqa&>qu#92O49?G(StzvJvfXaH8r zZS~UIaKyfi^Z^G3Gj#3>yseU|<AzcVbWY1w(~s%}0gnyLw0mAfZniMUA%Zns7lu9N z^bmwU4Akj2KAXZ`!uQp-Zg}Nu>iVWIEkB_}^JasOoe&SpX=(v`sf#v5OjQ)g_{~WH z)T->I-1d}sonve3936DwIeNt_ZP`MrX+~_>OXS|`3%aMx!>dvIy7QE~$dArtJnEwM z3pK9;IEPO(m-i_ilF<Jq+T`x2_y>!h>O9gP??zrp>t?pkwR4=yTo(emTUC{H-*)X< z(i_Y{Y&2H>Rje%x+ID&HwN>&RIr9qvI<J^2H`F0ovLp<tf~@k6I^!DDS{{+^u5)94 z*fne@Gsuf1{~gc7C^wI#yMr~a0L~QboiNN^7{YP-DaH-M*wm%nx*0x?oEMr(v(PPX zPy7CNGjwCswq^sJN1bC<WMEkcUtdc^gROCaG+aJHfRk0D2G_^~e93V4$T5c`J<OgW z68|)Bv)%e3)V|Q$gWpcCyDxjlZw-$$s2oe-;O7~YAw^`|LA>|I8Pc^70qE?oD#9vT z4;QytPq9ouR0$Ze4k+$apL>Qk{J=nxaC_AhZj9JVZelaqz&cBKXy~onqiL!7Ix~Bn zzUI6v5B(6W`dI93^}BfO`{fNjWpi-1rt05KmssjSSc>k$!qU_*1F6D;&*SXV04yG; zN(+#J(IXWOv^qxuNL@-crGecR3N^B2S_I3QAWBt^wv!0$sbISgLSq3y--`@iDs+~O zl;k3SznFxNAb^-Moh$s-4YnG;SFAm4=S3l;qrXOozA#=`Ilr)47FwC$2+AUR$-3~l zAIrW(^ZS)E$`?2IE2{(MAp_mzcq&Ohg=J4<nR@|Uxk8g#mL>h39b>rlIK*3g9C%Al zdo=d$^?RED0!w>}9~-1z3wjYK)GHzDH_cdTi|lzEw_M?BsiqkXY;01f8%0qb1Q-JZ z)~g^9gk^0Zf`)+mu7eG0Nk&Uk_G=)5`e`phqix$OkO$?D2@9Ai(^%zuy^mVZD0WNa z5@J!Sx2E-vxI4oTzkWT+pc0?~WRNa2OHn(*2(`OHc1#4h2C%H~s;!CYT4fEJX|38B z22ME!mHid6{PDf0dQ31-Pe9g5KpJ&YH1`Bpla3nqv%b;5OKt0gigc#wxIj}GWWi9f zvX8Q}XFaYJnhS(FwL>NiOvmnRR#xDbD=jV2ke3&>5^o7p1<czzB0}~!<#)^GYt5Rw zTb(9~Jl9zI!@#FkNU|TSg#eiYSPlf8t}w7YgcSv(p(@*gJ{fME9d{ezI!nlyt0YYe zP)euBBzyAw36K?<^>2vm8o_du3RMv#!&<US14Hppxp9-|OPI*wgN{jdnL#Z{2e)MA zEV7ZjLSb0e5W^*$VHQy26Qt+zz0LlwXp?)urZAR+mq^_LsNYY1cY$Kv4>DdO=}C85 z&Vy_jQ7o_agdn3tM?_4FQPP`@%Y}<EJuK6<bzu`1WxNW8f2X)a)p>Y`TyuqvzF^06 zvQoO@=pLqgQK9KF$f*)UsujAlkX<T3stIJX8L%}^81Y7EkK=lU8D$x<yxR2TRg6h6 zLrW8|m%VXLQb$fka*nN60*H~2-@%GVO7fqM$-@y0MGgTJZHq!x8?xgt)A5Q>bAdFr zLM9lh${jZ@_+cFLFcxwgY+^yy#FO;Kb*&eG9?K--gxdRt&m6fd-R?;(0mv~*WQ8E9 z_ZwNdi){EJM`xjvGt+%ov{4;oP{OiZC7b(!A$3giFIA#a+&)*9#fMXN1eT39_`l|+ z(zOmi83k~)(R_xgePzkDdtK<@1yaqXxXdtv{OW6iOpk-Qj>n`raav`aq(<FD6$DT- z!QYieQt(w#HW|_iBWa7ls)L0%S-P8wb)-?u=81T|DBF?cFb*;kfW9l7)TBSPz~iF7 z;w&Nz&4yEeHrmG>cN0D=+ZSy#nISvU8e3z`+LO+;$C&|q)#^}qo1AxnvUAc)<Y&uN z7IYlSp~&T)>D&?F5I*dKSnQbHT>xSM$Xw5KQ@|hzKF?6hEmVsFI!CYuhnKXPRy^O4 z%)RiWS+Hp~(NLD%AKtiu39?HNIi!Q?QYrQccr#aucT9pEl|pc7^7_zX4ieZzu`Io? z*1jUkko5-@sOOtwyc~}VZ=T;BL*m|b4_MNx3e=+zyhIKHjJmJTzMJg9_x6|pnHz#d z^kk9r{76iC!cD5@5@i#gsgh9WdW9T!PUyNIG)t&DbzG#ABJ^lb*x*CcT_S2XkZp+~ z!YZgG4s4ks!uOLbqrkPJEw+C`%yf6!X|p<bAnV~yYl5+n;wuL+dCB6{PM|=nE4tMS z8Oi9#Ei=xG`vCaO+LYdPVE^lH%O+*fb=utw3j)}QPcf<hxrv1~&TnlA#`AA1lfpl| zWg7tIMRhe~B`>Ba0N~yvav-ugNkzMpKrX{1ZOL6m2urJhX!rqSP6)7RI&J=XT|rke zBs7f5vSryCvTPzKwiStIV1^C^Z7)MF^T(a<ghGcUCTH35Q%ysRzT`y=*tH34BoN_d znYL7l!yl3gm1JUg%r%OnUqZ256WT;n{Rbfa3ETTA>C%s0NU}bD)4Zsvo6<E;8}<Ze zlwC4g3e`#%TG2#~O9HJwLzu_ggDhD#f0$$mNuLoKWCJMxf(g?4+V)r0(cp)lqD`9~ zSpN;N8U~qpVND`B&3_5Sw%P^vhrh>s{_(ZL6Ckia3yu28uFLIiDI&7~R$`B^>?7II zPzTKrIoeQc`(ME3_?V8OP0J#Wd5Tu&&^ddSb^5*E60#k4V)gKP`x9Ita$K-snSAtX zXE8uz4*+X^_zXW=BGP+expOHZ=L_TLYx7mI<H9RDXUgnzDQtbI?led<9jKYY^x%Pw z4jt<xQLsRuRs+bX795@}Eb7`gTQ;xJYNMC-S(7#6v?pLJJ-{A7ba$j!tOo056IGT9 zx$YE)nX?i<8-k>eZND&vJ58QXAO^AQq~yUP&DV7ISgr2WyKM`wIBhsHk4<36j|*kT z-94LT^GxUvM$$@PIdCaPMMGNM6eD4;?HnEZ4QzD<*hc~voP8x|zVtSQVn{pQmp~yX zQ%WEr`vs;}lh9#7h}b`DZ7BxbRUy1I^R>v*`?k(<P7qlounZAo%W07gx7(5rDm!JU zZz4n-6B;iUnwx;}qRV8~9_$=TpCJ76HO1_S(2B=07NDk|wK{U;#}3)q0YuJ`tbz*& zTZ=1xW02K1#-kU&x>A8gLZLw?3u8;M?-ro|h3yGUSIMqnfXIdzdgs&?YWy3y6_)1= z_(_8hYxRUc6z#478y6KSMsXchnStaUFKN9auW-Y<a18Ab(J`F&97I{JvP}W^DT379 zfo99qI>k%{-$H#Z%Xo$&t7Yi(d}-4b7xD9Z(7TNQ!HW%oCpM-<MYUiL>5%afQ8!A& zhJbTaMGnh*?}QlT{&q-m8{QhUu4)%RvHinzqP#HeF9gp4)Cr)a`%H&5h|_A62cWK| z(QdPqSJIrL_9v0Yhi!H?pU@YWt_ee$5TQc~%i4D@emjJa0!~~6?Rk1F>r7D~Rb<)? z^4|frQx-kAC{*nSJGB9|#k(9*6mY{sIy|tO7jxUuXsbWjS)2L}-i|8#r~>G>y8&WY z@I}Tn(v5pUi$4#oYKASP7P`6OgKBG|8K%y(QWGiAbe#DOBZ3Z)^tJW1(6xs2a^>+t zqX?2~Ek$;dvZ0^suzb~5wZHU66bmgfTLo_*l076z&uS0=0)>&r)XJqEJhPVdRAf&? z?I>ZIqzLUJSog25lYS>L-O}~6x|!yDl5v1gbzB&5vrsXc>8#DleBWPJrGC-T*Op0< z<1$_O<l&4Ms*@KX3aqsiY=;)rZTcx%-Qki_?;LiAc~{qMm9&BCYrM+RrYTtPfo75+ z-R?k-E5hw}gg)}G0&iV!eTuNsX4%~Xxj{fZ?@n0R5BOhk(HyR~b|2V9!9l)*0aPk$ zzp$xQ*&zbCp_Ap<ALBGc@mK(9jh8A2C`P>dnhv7$XsXM+V!=oKPI<R2L>z@UZuWuc z+9_~)Mm|yS(N9_SDUxxN$QpMrX=}LtGG;qQ=nw_={|MT#R_K}yQm>F6wVA8@2$0AB zO0--bQUugtmPi{eP!bez*J4k0xI*k7AHV(d_{4F0ix=A{xWUo`pA#NOIYg73DxPh9 zkmJ9=bY308r--h`yCvQI>9AVuNN1{RlQy6aJT3drSefj^8#2N@wTqHCi~|+d7)rT! z9hR9-1AvGMhB|`WdkJ)#UQS#~JaJqDuyo^=67^{O;GQ(FMK;-;COp3&w0Aw`Khv+J z4tbdDPMHzf%nL0Nz;10!HEq(!E|$IX8P`Lg4Go26xXbSTPaUKn?HQtuVNf3eX*>u- zFaSsy6?K)Qoeq**VoLryOAL77igp3iYD~R<NWf76nt!%P>zB6vTL<x9@A7;TzkbUG z0C;`iA9PXW%HHdDOFm-Xv)qa(2Frb1L+#eH5JKm5Euu3x`X;sfx2V<un7q?|20Xu^ z(1<T0pwIOl1F0&5JaUCjrXtHQu-iCZ9uGXi&2pJ%IeRhHlnWIDhCG2tEt^90(yU@P z#y<n3AMn#m!gN^P@>1)PSPeV{CIFFir$tcnqk_Mi^UeObt?U#zNH-B9ZWwVTL>6?; z2Hai|ODRSdJ{#C3r{-OLg+BGLzq-{Yego-<g=0;EZ;f$qd)W1w#4YvKz~Ne#V@ZK0 zoiZnv#`eDOJp30xcl|ng+&oHfR42Z{;>7(po2jOOALhy1&TsEYdNgo+J#G7?T|=Ca z#;SDBBY@#xca(*i<&Mk4-XX8N>#ps%%-eRO{mug&-)}iR6IXZZ^x39%HrX(XDw~4D z@1o0BNAFe>3SBeJw;zpm@h<y^FJqPXtvs}?yRt*EBd{s-q~o)l(2B^HPZrL3fC+(n zukAlsxcA3Li}1|Fk*+=dGpTu5Zyua-+Ir>Oj_*;kJx({Qf|{;<dU5sme>zQnJ}1ph z?xI}sJbdu`EMjy{b(81i*q_BV)0Z~v2w7hTqNxHPGN8<eHvIKm$LZB6I3O~-t3y4x zCT>F5zT3=4%gKJ~O&x@U4jxwUvzYR_I5ClYrr_PLqi#~?%bPE{Urha?xo3Vo*0`FY z>oTmfJx5{e^gj1ICeFuD!3%4~<&m)@TIt#2#9=82Wil)_s0p22vF$%Hp-`+7>RG;2 z<=jrw4|EtSF*v$O60q@jeE3S6QqXEH<pH6Vs$b?AKMrJT`;3#Q%05J8HcmOwK6ta* zHf4@CrE?}k-Ri;>s8;W|5Vh6qst~5NYVp0&ef1uz%AK|XQ3<opa|n+}JbYCt&{6NK zQncTl{c}-=KdM}h?J8w!?r!l5f1G$?&+Oym=E@|EX!V`2A*HM*rtPQWLfY%vR&Q{- z8Z#6+sz_IwQBU_j-ZS^?z~;fXx(5Mb!xBU3{p~LdPvgi;)twTjUFOVn-yyULHuWuA z&DFBC0%6M#6&rTbhu8?nngFz+6F@08^0~l!2;WH`f}3}*3E{>~YoOW?|2$}|>qEL> zrTrnPfTd+C=DkHTU;{uX0jF1_OJe|6bn~e|xc0@|Mz)nn^KjGop2?kQ-B-oTii<a4 zk?B3DCQm<HPF>dD)0ru0`FQP8is7ezt?C;YH?&?dYqnT457*pUzc$<?`1|jmbgu<T z`^)h9k2f`AI>mp!Y|-yH^mW4Kc2w3Ky*@*^135iV!2Xvbr8=}alF#=?nFHQhfeTXp z>f_W)&wk{5ejKO-_%L|&zzc^dh-wh=2v{Y;e#fV9b9~-Xb<XU1#9|X=g0UHEkTVZN z`%o1Usz0mgd11dGe*uxY+2UBJma>GGjPN%pgc|See91ycWf%k)Ev6Ox`?Xz$?Ny)? zOirq%&=8cU`@7%p8=WS2Ak|I*HgTD(VHUyJ;*4gg4&yZjxIo!HyDYKy667i_RA9(* z4e7D)eLRSgx<AJsPsSEep)NCeTMKh3^1q}Uq8GEIiSSCnrMk?Zy+!j9UEi^3ZP>&| zp)B-@zVh}=lw}UN{L+fP+SUG2>zv?<NW(?-`|~5AQl{2`7;2Z^r{wZ=aYIMssLq#$ zvBY~2^*Lv@R)b9?ZQ&@FZNH?K^|h*CxJ`Fjygq6_^KCqh*o&Vo8Fh6Y>hLW|)*0{T zIJ*|YeWUc1B!on_C&8sTt3XWZ8dLO1QoNN5(rz<>Z1B{(OD-WRAMY3G^wJUki|31? zSUA4q|50@3@k~E{9Kbj1K5XXL*w|bNu}Q9^%@ySs<v!YwTOlN=?_6_hbP?5tq@qS8 z>DpW&gpf+Lp&}|eRmyL_$HSjI9`o?<*?aHf`GRP*^FeVEFTFJ;bo(m1(m&d<(-Etf zA(|z=#OE0fuW${ZVo$FEd;H)=?w)f+=Puf-T=6)SPf_y1){w(=KUBe!QVK7u-2-p^ zU0#=Qvw$QYl5aIm(_BexB|eupTeMP81(7)_m}UcuRxvWJV8PO~)!Cx`gig}QE_JIg z$f3z{oitenwtQ8uc@uDVWvqDv?cB!9h>WLaAB?M;4=s2cu_+B_?jrOF&uOo#5Kh?C zdK}L<Sx8eT<odYH1{U1>;M1~mYua?Sj0^bSmm}!-lkP*A^xvU-kDqJVS4(_0-$T3E zQpAW5AdigXZcJN2Ke%6~byH!7rOPNPaaoEEYM14lN#xgJ=o~OUOR19wVPNc4s(6nq zsm0He;?szq(;>EfjItDk9U6D3c^iWTC^G4rli|MnLwzSuU%J}_xQmSmElDMNG2y!R zNH7z9dt~8wHvWDiC@BV5!j{OX=?Z#G&jtyCkz4Sqqj|K7uo9NB1EFiV=V%QL8OJ$< zmkuc&+aDDA9WCGVG4=Bism7b1CUaMQ`s-4C&+M%mj^I5_bl7lBygt!{t`vdLyNbSK zoenD~76aPD-AcTW&y#0R2VJ|()vuJMj(4e^YtQM5<$>K!0&!JSavI|!5DN(q9p5Nl zoR0x%;ESLK3KTX>(`2B0r^dF)C0hwYF}Xeb=0%@oqqBlycDt9_Z3CH1^tCu_tyWco zhBgTk2XA_r-QP5lcP2?3q5mdIZU4<DN0D=qZR*~H$5vb#fRC&;kRJw6ogI)!Q-uw9 z03vd^J;EEAv_!$i^nVp#&qY_Clr2>*f4$J7a$;YKirSRH4nsL0=<yr_cZ0f!yG=Wu z#0t~=yxeVRk_7SmM!_~}%VDpj7<%(&h?T40Novps%KEc+&UaltRvcJCu#{&BZ1=Bj zn#Lz0Ht0Q1Q)QluX?<61{>O0K_uH+9_NObO?>^!6GB4apx|YJOo_;(0Az*20&!sVi zvPXS+=2p03+y9@UCw8fhP-Qn&G|ZhPFRK?x1<v?Rjnes~<ByUG59H2j)Y?I|rEe-5 z2XhIc`%bMKU<u=F^(+Ze-Ubkjr@kcMrJA``F7K00UC#`eSG}Y8eO6LAe<)R4>9Pg= zyU05_8+!oL_2j-J@4_EjjD!!_){#_pxNnxo;I;?o4VTsGUc^tNf=~K9N^U;z%E<JQ zPHrhXIcd+S#eJ4r{f4z;Y`<(+-21(U){vxm$M4cQp%vKknB_J09Q;VV2{2|-7JRan zXWO*PgG=i>meylxr%(PV`~0o_qkHrDFQ?AH%w8-a_Ri;j8k)~D4$Uj_zW3qNp&cNL zkrPQFxdgSz3D73hnkJd%akoF++5CLcqspN3KTkb6a4cL785u0ExM7|7x%_&1TJR<H ziI`)li7oK4GyguBogkQ|(~70<<rsh5|NRv2Rawhc0o-oqnohIUn({CFefJsy7yu%E zb!mSahx8cDX`x&ONZW?^y(tsd{wgp5c?VK43Mbq6xSQ-RU?ETurMmR_cREA82Dt6) zb$o--#^fyZ3OT}*iGJD>pwsfw&7LyM0m4l-Vcoxf&0@bo$jBA%?hPNZ)?etT0TO@Y zqVV=Jpu>qPKaBN@7^Y)km^MJj6{*^TX2>ZXZ`hu=pF*$@+Mm@{I3t7`9oX<;UeyDb zHo{k|U}&Ut!F!g|Jfe_8)L*M&&3{tmCID)gj`L?|D9<1lgy@gU=!9&orCmf{hDP8{ zN+3oNl!Sqeg5F*neGrR>Ct(RK*o1r%k*1`Vq_nX`Y14`ljb>E831{7c+qQyZ(3G8$ zlwDht-B*;oXevHQDgiAjA+n55n(DqJ)tDC5gca2!np$d-+Tj+pqbq7zG<;qXzR=4^ z^)kMkMmUv3sA?gcTOkN&>KBvL*DtrIH?OF-&@^r(Y20bikVOZJX~do+Vt)&9XoWaR zBTXccp0|)*t&pTN&9_OK3oV)-S2R~>THlkjezj=*UC{!XkwM91SSuOzg^V?$s3gk> zN($)<g<__ym#n?9ReRGHZJL?RmSi34R-J8MbQos3PG(APp@4VMx?W>f#ys>Z4D~`P z(p393!LfW<*KO|?{bxN|DPvkngRs5YdWmKRJ=tYr?ytt(4a&_JnokVALZ4gEHVVu( zRDLlyZf4l*Z4_-{biLIvn=*UP470_|s3+N|r}G^^;=Cr@8umdIkI}h5^s=wwIDq_+ zll9{?`^Ww{HFJUDZ-C<ZsyFWUvbuAv&YM;-05H<0q;|5_<cxseJ(3#w2sJ|f3#MSf zY>X}rrNkhgmu^h9*VXnmjxjOWH=}k^syee@WrVHd%OEPT%?LpCHD*`jSAzXzC}}}e z)Oz)pl#s?&Yhb9keWf_<Ho9%Li5R2u4v6bzTYm;9DkqZcJ+!CHW>1UDBePD~<Pyq` zQxYlGuf(!F{9Bn~0x{XJ)ca%8kj{IT4W9*?X>8o-6PlA^m2oo8mZ369QS}9WoibU( zC~oo<qo(<aThN5x^UARaH|8ir=PY7Tr&=xhZ{rBL7`K{T5ws-LjF9#18QZ%O5at5) z4;0)y+iv}eSiOv~Dk;#9%_3kDH(wGcE&y>73aKcJ6baOv6FU~ys?~}$d)TVF_OpC< z!-pP2Bb!}!Cu_ay(Ok>Y7?a*ANW^eItHx7Ewm>W%h{Z?=O+YnUp;Oe1>RGY+vIv#J zChcJ>w+jsTKy|x%1KAwBpCKEkc`URzwa=<gvMZXLEOWBluFu%hl=Xg6#An$U*-!nU zs%J9PpbofJvg*z{lrqrrG!k&H=y-*A%PYP+!lA#ziQt^=ab%pdyvOqmP3s>+X^I1H z<e(IQe#73xYZQX6oN-bobH_p5g?)6KRJoh2p0ZnwPf_;<V$B#TzuBaJeAK!x#j}p0 zmTRa+7tX{Aw9LgIS&R3q+i*lSC4TssgiZWG_X!cJ@w5CMdxfsLVdi|$Q=&{B0JcoW z6iA(~FtjHXUC-RS?AWSlKIq?7M0wDJ`bQ?2QAq7#WnTvSpo6+imRd~~p-f6RFMW)+ zAn7yQuM1TFZ5j5!sqvPAHv>sUo$4Hc?ZoJVsVwzxGbdyTW0?Zn>A6q{Mfr;C#b`I( zGu@E+-EZp{Z0i>NTA;cc5c@);JY|lX%)+NIurJ6e!HmeAK-HUFcF_!?Gf;Ef0XISi z9zU*slA=E4eQTagw3QMq#I%qsLXBAMm^8YFc4+^1^(z#@daP8H$FA$nQn8UD&*q{Y zU;yXE2f}Nq1j{jFU0t6IG42ACg;+VZ%Tc~W#T&Rg)g&%etXf&@{_5oRYN@jMK@wNG zu_BwYCx19ms+Nf&4YP^FlSFUvvtV|`d8t~Bm|&N!A(cU;K;--_oUb72Nvmq47(bSS zo#VUOu<_jjb?t0I@1CEP6xJ<E*J|$}dmJJ0c<dpH3RjB1c@p1F8LZtB$pUKp7Hs9R zN$Nj5CuZwczj!vQeKki%6SQNFCXmLYMD-M+8Bnu58lU*Hyn#W8{H#Z{e_UxKTmSk~ z#*T>U%-%~A+cPlgv!T@y7(DR(@R(X8@cp`d7B(df_b-Kzaxgk%ifL+wZxXv-VfQCy zX*l|{-OR#%;9$l$5L<nDTM^8T?z<>KPDzmGyW!_qxLhMbwC}bnf~&eSY8g`16oEng z$!c43qAgp~nSrxmsI5_NwX)TQtx8AnI|hJmqFmdsoz&v2J5>9-vE|0e8_a&VYFrWE z@C=%rRqncS(ymw)s2Wm15OvwlQsZ_x=~p?$8rCdFOUSOc)mfpqyJB-y1?>)2ZSL>M z(z_=avL_4sGNb*PpmZ}^*>F%kS0tY%36D7Sn#Dmwd%!MySUmu#K8s8f$yL^etLGHQ zGED!a6p44Kon`Q+D5NoV_4?^g8dO2I3;T5B$Fso4ie)kiPXr#^2%m|uu>sb0&RRAJ z)RP7H0>K?S?dOvRw^^_J<=$-1py0`_T^0<?FuC#%ofp-nuE6lUEKyddRj<i9q^J&2 z`Ay+35j5=uNy}IDHyycsyLQv>TAEGWmJAvAQ3rFQRXr}+&BmRbY#I>Y44W{6oa!eW zjIIDRci`f0G0B-hY&u<FFuQZy5c?Z|j-a^CPvn$y(g_0G&efAgq{`<V(Q{<1xfHi5 z!K~4h<*t!B1f&n|Fzqb#JG!zRkO*g^=Q&sVGtfNe7$yM3;zM)E$Zs4ROHdnXq%mwx zc-MZ%CG5X-2bvRrU#9T+`cZd{50o8l45c|1xP$|LL08&euWva8Jw`{_i&X%U>qd85 zeHJaZ9Jyf~bgRr5)GQ?^W&B8C>h9F;JZ5&w=g6&qySGCA++uHS^PAz(P4vkh>MXic zbb(lViqfhC$`|#rr06j|Q7BOMrzlqjs{3YXd;*Z#*@5PDyRK1G^>a>#OPY7X-By|C zG!Dd=1L29}`i?-FB;bnvtJ|fxuvEw}9iGCHZ<K)IMT%xpB_i;~i_@C?yILOv)JX=( zZQ*))Vbc+jY<`=uO82u6)DEyMo}{Z=@l>zapCDl8#uzGP`@0x%%D&b(-^0qUrNs3; zY>nWJ-B1Rm4@l~hO==g=Zpx&2wz4g;dq<Xam!LT2Oj>Ft(RQtRo}uE)#wBLmxX#8` zs6s9@QJQYlom=Y{*bZE@t&6GFI;L%qEP>v%MUM0<6iJ}tS5!K4u#Es!=PXUf>x4>n zt1g_xKdr$XcvXqOH!#||DH`4sr82t0weIFrGHsZS(WNNcQ?L>;bWK(=mHHCID*gh^ z-vX6yfL;6Dl$cqU-_qfYEQo&t2NOkXW2iu->17*~Z;CY|lmwG(k&{4Uo^vK61_fs; zt^!Cd4ApwzYk=aizgRtu!u!#-*-snx?6{!xTo%RV`6&|Q`2FYW8l8CKd%TQVO#p!S zqBlWEf()`=-g$*=7ri{fK}>@o<|6rM4yX^H)bI;C1H{~vD7A?f%F2jBG5aZ7bxf)} z#!&qdqB<=mNhp2q7z=Z3BK&->PZrUJt?prTix_&Nni76NTyY+#p7E1^`5@&an-bbS zyY1gB!*0&$*xVzf@>Pb0l~nnp0Y(DDy0I_Riq)+uRs0#d!r!SU12v!w+yL-k&L+rx zZ^#BYwMsVWH&8K{EFW*c)HYJ}5NJ$l5XWWZ?N--_iJVfFLOdB8EZ9{K)R_DHukir3 zHd;fKf~o;v0MY}K{}AJLC{^jcGKj{!ohT>^w=R-S+))R$OGNKkS9}DM2_dRB6y*rP z=T>Q*-IZs}4Es6;p;Ahy6sXq<Y^?r#`R_)_wwE_{7k}OIM*8=YWmd$uqs`xTJT&Mq z4ESvs=)XOnat2=n)QQ-x6aC+hQt8HhGn(HhTEPqtH}TIC2CF%HJ*>pa6)qkH1#iFd zQFC;#TQo2*8c1b<>dEjcbj2^60-G$t)RmHh-739vH?OgA{+V4n*u)274P)83$NB7A zX>}h(TE2ngmNnuajs+dCkT>l=`Su4u`$bDce;Mg&Wa3#yV0+?d*c7$aF}T+-(41>r z>0J8QCSwh1R^L~yyX&lNp_!gb<RD#+wGJjX3|5)Py|`ESH1dAxi^*S0mkiKb6P{g* zdD+dK7)hNYUVPes(lBO}m|f0!fiv=KoV?lcQV-fsaE{kMb@#oYcbT<8*gZ;GbFg*N zV)w+|paUmLsTFf;k}QS(Gv>umLFehx5W8b*OAFzTu4!&P@^`Kw=jZ-uD|&?SsmoH` zn>bC*7$7jWBXNU!mYj;WJ*2nhdE|US$I)t!+w?-0q}YiM<6HbLb6Wy$8SXJmKHFFB z@Q7&BvG8<9z<R{rjI^bfJ1&3mAa#6Q8D1ziRZIxE5_$J*%OS-#e=~wU&OX|E{c*ZQ z(u)Dc_cwbve?QLb@&E{D2RHW{pK#kU=@!23zU8?;&OP@j73Xd~K%6bv@;pN4jMdU= zuKV6(mllU2n}|dpm_{s@htsaL^lH|zl3mNJk9{q*{W2&&XZx+vQg_>X*`lZI`E;c+ z%XhXhWt7*s4i_Weq<<OKtXg7}9d4{Y0XJ&M4TBp+MutZkjP-RQs+0RcVb<i|d&)fR z-2Kb895#&LG49x!dpX{owjXs;X~~V=Ww>b|x~?oEf>mGPVe@nwKw-0sc2#6xp7L3J zvqG}nH;PNc3E4HTeu=I<R5RDMC0{=${`W#tPIPS{nH3>)XlQRu>e9^I<L#<-_8vt6 zPMP96YV*y^V20M+ygrj+tC>FSbRlIuA8WJB1Gd}xi@I>}9EwZFS>5cb`X%w5eH+j5 z>tME3=@sFG(>w+@+IDTLNpx)hOB}uN9<>`2lPT@9dYKtsXnBS?=5mrd#V(}qSaPmb zXVRZS^<Mjjq5E~^!(0c>HQzh%c<syG&yNFnw9O9#Q?eX}Z9WffMy2sq4vx?jH+_2& zNG$y}Y91%ZhHn$`y41ZqH+@%ks>G%m-oe))O)LvHKjw!WcmJ_TR4_DX?i7;q*zjC* z(GIO6?NTt_cV6NEc3CFVVOyq>Hlxm@*bbAbmf7El+TGM#2r+s&TV>NU3#879U+Km~ zPA3%*@>eN4^$zX{1FPjHX06MsQMx(5RZ0^_T@-_ZTUPYA)B9Z%t#X&mk<3Sx^4LyA zMG!VjR<q;#jI?0d<&K>iw0myb@0%x2#zg&COrNK0#+f~JGZ~svI%e`{F8kQ;dCR$7 ze?C1_{BP~c6RmZJA8(HT_YXPYo%WpS1s4H^yEOsxj!I1&x>3Y_Pyk(m3FhZ01X5t0 zi3)^P8N9hih;+A-9m2MQw4yl>8xdc=SqM^*wHFQP6uHkrkkJ$!%A||sHOX0!aS5Wa zKU>kRz}~!j8RiPL$1L~C>oBuqKn+K+1`h<fBo$#@7~o(@wt71UWNeT_GFd6zH3duz zG!R2-UF22Q>&wCB1`Lh<WuVzOz0C9m9R-a90wpxL<8cgxIZv1iW8|tE%z;dV0MH&5 z5XFknHWg(xxRXKUd$Q!mta{vHTVt%4Sqe7K<z!_z$iLklevP?P^>oF_I!8U#Ps;=T zn%W3npZ!+!XjyPu9kyd|pDlH?EImS7vpQPF31s2=>5)}~5&2f<VT9;bdHf}ghUT=a z;+!_bR{J~As)6UoL$jpM1|Z599fVk8K{Tv#uwyC^C#pR>h1wOLsMDd{4F#<s8QZlm z*%)Oh)QPDI|B=l#uniL&kA^rr#Fp*ot|QgXJ6r0jA5X8T)3{T!!?vSkBz;fqI;q>x zky1p3=ncw<L%stx6b>>~J`UZ{xPUDH<jriPz;`xgYmW25b9ytDBB{d0Kp?`OHLLPg z<ZRu(($E<8x#~mXqb-fGK24$DtAamX@w;1eN{Dtc`MaVR@FdnZt#6;f<8M1RzdEZG zNp|3*Ts*n0=9k;`n+)t<Ou6oqWH8!d!n&?;hhJM3%#Ylu>>&MM^Fe@eW->4@goytP z9N=D@aMDC&u7(o3^lrvQt-l=P7X22kepA-rX>xPiA1_60OU}*o%gt85TgnE$ZP1wF zfi2Q0s2FHACJNAroC7G#$%)%_r$k^p)nsSNJ4EGjuI;c`XBR+D>Ck$gy*gD2^>nL6 z&kiYQNF?Bm<^q@_CaYBr{stqWD^Sw`Y8jk2nz@n(jkBg|Zifm0T4Ct?=v;$rLWd{j zs)i(*nzL!AVya7eC$6D4w{R2=znX(rdMC_Xq)9V5_-^&{RIBm-^RrzlONn{K*V)Lb zf*gGXTafxZca|8nxjIEdLA`>PO@1Tc1Wn~wOpHJh&dcMt{9K9&+bW@rf-ayt8Y+9e zwSv~7ywk}D;j-zr1`29@fP*fPG$VCo3xN16l$DT!H3rBNT{v>eEDq9<ET@H`EA%-D zq2rt<XU99A3`pb^+eMHwcXM<AvJJaS@nbZdoOMfsccpHgF+}25g*KrN*K}&X;Gm>4 ze(ert&sCcVm_a?*k&|WdUZP-KnY!%3$}vDjK0_>iXQhuU(hx_cx;1~)wSWpd)w0mS z7>gShKE~_$yT6F*vsdjnk`Q<3_FZ3>e3L|R$=>nQX=^NGJ!2HHJ3j3CG>5AzA{R4P zYgJo>APZ(zQL-ppS@T7&MZxB`$=|f&2j_GB%SKD0mBUrK+MTrxM@#+p%&InF@;7JR z%lBB)R(b6>gd5{PT^+R*9s7V#XP&$s^c1#)u5b@C`o*!E?NcDzOFu1AsF}5WZyRM# ztfX?cyJf-L{KatFWs$M0k^Ssq{#N1o`^nbRI-~_=&xSqH{B3(?;Fq?N)S6Dq)9z6) z9WBvLPAy)^S4f(b;=#jxC(x<guSlPm`JQRgqU5DoqG6<y1-Atex1_Ccm(@cxutWHc zce-^^%Vtpr^t-k{Sh?NkG@DN=4jAwJGH7K>v)hXdCjL_s`8&@7c}SL|TkBszVQEt4 zQ2g)^oB>USSBPdcqHZX<?w2$EIFh$3cb0fQx)bL@ms3oqg9o2kV@@Y>Q$O+1iOb#A zZ7XnQv=+uTQH%)1*iwa3^UIWV?ZI_<u<f%uAND>xc<xWmst)7dc4{ZG1XH<o1R+ma z27t`?GLZ`?*BGgV*|GEBy15?9Sq=b{8*z4ZfCVPfxFew3;Sl91kRBhTC0jqC%WvU1 z2lAbDT;%uFgW~pN>n)oZ^<{6G&o+&Q*=pyQ6~M46Xwf)L={wYN3T?d#tz3r6+9PZQ zXPa6bwgPN{itOMZXMQNof%D9PNEv)N!r!03f-i_SEsC~iR3N69a3Kc1D3KY;P$3gF zA>#=-dFWQht0Tw(0N^(D|2}H%GHhIgR`N!T2w?@wkOWqWokTvD1~wwg@1}wsEy1N$ zpyO7cutWv25I_dV>5DQQo)uKDLW=mr0=j-g7(Cp2U;I4SmkIu@o%v-MJ;y`8WfGd0 z>*&iPu%RwU>@t|m+ilI<ZQbL2U>RIPE@_a2h39Si2TZ>^qM7v`o_;CJ<VVRsJEBbj z@8FjV@ev(-yEZ!Vp$sogJY4!riME0qV3j>#A$$19h03xXN!c&}Ndp5^y^ydk$e(x| z7>j!sU1rQEdqTw>)#e>l!jS|So>0L0vf>&5a6CzEl8Kx!hdvvJ<cz?sG6Pb*6n`Z8 zUE`pyP!+e!Dej4a|0gO4=R@nF;f=hbF9GoDLR2voeu@g0i1sA6APRX9cA|o@3amx~ zPib*;@<N3QP|qbQFK-}Tu;3dnS9o5oFt*VC%SX581*KBZAE?@=Z>?KA8$pI%MnB`D zWpeET9X>)ceKHFBGy=OcqA!$rsfXd!Be4Hm&K$S_t6w%b$3uUjqmM0|8D<>%&$Tke zvNE?y_CegIxWBS=qtBwy*Q711$KceHsjxG@N{qk+ulMjDlCX3v!T25gI}1L{!Fm;( zHD~0>rrQk?L@NL+prR(I$Uc^xkO`M{kf)ib^K`{C%kW7ma#V;;q8{`nL*Ft{<2>vn z3-yW&Ct4t@F_46jgEAJikqm9j0;gl-caHeoev6v`R4s~7yed>P5B}sUIE=S@XQDzV z85}0kDC9#fjlk<!7cxf_g2)Q5_Cfctpi-(^=JGo1M-{|NQoNIwYykp&wN9(Yz%Gx# z?~>78sVB9}5F;$)=}X54`N&~%t<G=6>v^QQ5^{h~mM_m(@kfg286rLsM8o`D-QLHk z>k=th4b*KbLT>$Cm%POfAgOa2sH4N{Y3zE&Sp)aq+s%^{e=@@jZi4LRz(;w|b5z7c zB5G1{$|MbOjt{TGpl1_9uFb=%=_$J~kO=M5*O~Aae(>uY)D#_=$@Hq{pK=gG4`4t} zk`o<?0^As)9e{kWjF_LaYZ5jV|1RxXCJzb`gDlj^jKlw(LEWGttNjkkaK8(Fh;|9$ z{_<f(uiBjCE4=r}=K#vsybJ+dzno=>0s$!#7}-A_IcAC+V^uvda;3iyKGu%tw?bw4 zrT1Pbc`kwHK7wP#@HP?r&14fQ>2L?NdHhBCvsfa}5*e*j_J)gij>k!@khHYJIc7-7 zRJx=Aag~E;!XTP>h&R57ht&GZh1WynQNB~)YNmcX8QLTw)5;M~In~2t)MX)J0RWqV zpql8YaZG@&P{D^wjFdwk<3nl^&n5BT4NTMwr}|)^@^=i_o(~CPMpPxkZ?iDYY-J|p z<S7bzas*z3fy&fB8b%%nlJDHj{JziT%QDKmV)wRRU}L?sEDWp=0~3wHhY|&;+G^7$ zP!A-?`<!*VU)W}p7j_li#x`oR!d_H}KwY9DS`(3L6zvmt5c}(3-F^-BGw9J}w>X!S z;+}v>G9vjmyp5%NjSkP_2lSH(_b^a4pz#0()=zEBSG%_N2=0<!^{fpNkSN1fuJsA8 zRT<$#{0u9$!55eMItW0|=1Rc}I{=^~YSu1twj=Cm$F)VfEAQ><{c0al4fwnA7cvfm z#yURvV?~m(8*%p@{i%JV(NVd0$E)uSiq<xIL>4E48WnQ2j9`f@{eC9$mlZ0}1~r^W zTm-<%0E$f*_$VKh3;@snIcQ}Gvd4f915yh3&=D%?<q59NAGi|@vA7J*kjbO;b=1T- zWIqRNUw>rE(ehcYJG=y(NEY8{g*EX}0vQF!Cp66$rC&lFxwOG0#`mwZMsut=M+w^j z02mUFt77k)BD<)A_&*}W?|{++Mu;#Q7(E*{i$S{|I&Z3q%Ia&l6^I%hxy=V4#+FaL zNQA?GzydEHDg=ObN<fE&@SFkUE#Vd`8(d*_-M>{Odv%_Czmfulr-1GCwCUYBP`|Fz zOQZBgPj4vHepFzOQIOUj%Ir12@@SC$=)Wc;Ra^^Rd6ZRyJR09ui0nI7;+9~HOColi zAm+8x^Cn+{ZwntJGg0<Mbz&;2kqLjcjOd`E=4A>Y2bMYjkLRr`zo4Ur0~F6Op%N-( zH~=**LW-!@pNkL&KWN@3BW8HE&m@=os3?Cn>NbbCI5T*4#w5T7afys@A`lvQV!O<S zX<^t@<J}%Qa^Xbju13UdKH`yM-J`@udyVTW-1<KwpPXz}{6nXI;>qmWE<0N^-As2+ zzREQoqK)@>;yL&~QNR->@~II1Vguqi+0J7PR?ENimm{+^K|AOdn#pQUnT@?8*cBvQ z3pJ+WKBh<N8la*IM!<J5@D><qJn;@#ig?bHHO5en5@ml_(pw?w5EDJ!i5^W%AEF|$ z+YmGKq&onlr=eZqmFjo1h-Vm>7a!G3uAyPqkq_wk1+}P<(TU*Ei<2WrBkoWgf9O32 zJuL~Fnn#Y1>-162l1Ob|-RM5~=#-zz;rGMtQc)ckWG@HN!;(F*&rQXgzk@*zF;N#W zT=cfd)@4{8|I!Z;G>p}gC23F2Mg-LjCx3i?0rf&aqVwZxUXY=#w7T3(8T^Z2_aQrY znlk=+ii~*41fO6jUZta&Sf~#YNJcENXSq+|Pu^-T;;HN*GKFj=D>Nsfx-iId?l|?N z!{S85eF?IIJ~>B)$(ZiRGm|E5hz`yzv8cDU^z}jl?hgR)onJE9i0J-<D2TNf;A1D5 zHM=86#+k^r=g9U#nFGH*Jt=~}B0u-N2-$Y0B{>WEfP;9%!)joWAKaxX`=zuJWP2iN zPcNJ`0&4>Fsb|^6DRH0op%xM$3!DcgRj_Y~;_u6_OxB?$Ch`ecDwe!y??;YNXJktJ zP&4Yb1c5s?s{yQgxQq<{7$zKf<z}gP&5AfxaO=t=q!`elbW9o$I`(z&EzJvIyfSG% zikZ7S#vMYvJ7_ny{P=G*^4__Yj2G}CBXD)1k8RmI?dG?Kuf0EFx6!2xaaZV90sy}d z!4Jh_Vng9me8gq`(>fu#IT#}3p<kDyFYxjgF$ghv>|OeND-(Wi1W6r|H8#;~ndXZ@ zVD^{&N?%6~NJ?Gpsy+$3wixIh9@5-$t&Hoz%N$<hA4P~cZw!YN{^LFVnz8XtBC2Fl zt?JTCuR)mYDM$+${gjHBf4car?Blb4hyh;dksg`BIk(RkCB#TH{Loc=*diU8%zWBK zMz4%O3z>>TLim<Y+|1X<tsGPvZ~BG^-LHf0rq1;y&b{_;GU|mdjLiLUQ}k>JJLZ0` zhbn#Uv66frJIFdeVZC%G9%EHx_fu8ExrCOH#}W)|CtsnQetuvC(VK|;6ud$+{d)c* zasZ<bB2|y_kTr2-GxA@iFioF0uth#B9s}R<O0iJH`a(r7ye@e&k9^3-!d`uPz*@&l z4NZTLz|R{__Zz>irpqAnC&<ss*Qgn6yRR{dT}!3oe2r_ewC5WbNc_&F=|qaH`m3kZ zOXqH*J=b6d_zG+hjQ1P^&Uznve6{f5k0lgfScHrj;Kp-MU;)zh_sVM9XUR#JaOA;V zQN`)knr`B6CphTt_OJ&<^Y;LN{*TC;vRXp~J5jiNi4T8IZ-^|KT)?#7#e8QEE9GBb z74P*sEeELS378hb3pfW?BF^7j=$*-_7VQ%gc0ody!6oNW(w&&jCx2g=wr$ABlR3*x zLdrIEJC^Ktaw~jU1g_v&EXW=`pDwpZ;77MB)>tUY+N{+)_)joK=)e9k)}ln^F4fC> zR5se%-JT>9J?qX~J8R)LlmhzmeTe|zQJl(j1IFfDPj2+N7V&)S?XF7NuHW*kD?{%3 zZl|fP`-*~Yg*~EcJERR(-UztJbbZ<|tcbM9@NPb#>UPGhDd5)rw=X6Z{e<k@zl$Q_ z<uxkL>q$7cng6xmshz2v&IzwbJF4vqb<*-RjY1zKZ#$S4r|x{{+i<^z+NYPdd&|3e za&%3n?-i=t3F(@TRi{P`pWKKGdhso0{L;^lb(f)|7igEg1FlA*)L-s<OfMUrK>BR- zpZc(}K-=JLm^7Sy%l*~#uY>cW7ca=bRr>wZ@j><SgD7>c<-TN6j?a4RY4iQl1C3!l zJ3}a;pO|cohe!e^{0aZ#i?;(49q~Ii=4k}LbsNrZv0_J^3$c0Wq!wIMsDF0B@aD38 z%Wv0)v#CWC6o&<1ajOJHHu}|HSeM_Q)MgdrlH%&cZ}G3FH&>jA2Qy7BWUdD6t6&d~ zNsq&Tc<1`p1L01mQ=PNwhzWr!4(F0(X;`OYk||!gQMImI)p*vORzhrcRUT<uCo4)d zpsbv#&axX%@~}x&ey<vw$beP7O~xjY{LA{Xl<`rcdA&9`pA;`=#>}XuZzEl9(?<Ii zZl{ieO{BVBmGmOgeIV(IdaAG-)E<M;gPGi6l{efDXq7rb*Ave6_Ym6DCsO?uI%jWG zMY0Y%xtZD<)N95?Sf@CKR;T`WF1&KrqdIVo#mD(p9*(?;Eqw9qly}-fec9GA*L=m) z$<ZFQxRb5#@U<PF15e*nuI$5yCu27hxm<%4Sx3vOS{c<!D!6C7Rk8Bm&ExDHs;oVv z^spi$%>~T|*UB9s7P|c=-MrJVNcBCTusoEHZIWR~;C@2D<#@Vk;ikQEj&DQiyIptJ z1Y`t&S;aY;R<|Q6q(iEaO@}X{P0Re{iAn8udKx1NlzzuHsf4%(0%Av<(HnIIGs<!M zfudMU^TsNav&8EyF6Ej)55I4Ilb*)jsR}<K_5J3Cs`Y@H7^i~Bz?R-KO}PIiKip34 zk38o$)+dWYag1>y<rMj59vn7pDq9R_8U;cVECku*sTIHW;cJh@SfZR;33{5|-Gy&e zUt4W*I(;kmtmQTDbl4I;5HsLVLpZUJdDzBj7^K!Uu<_D~P4VgSL^~I+O9bEA!{CH> zU21!cV|v(m<tn`rs<Mn`ajK5xR7IW(_&~0&N!9$-ou-I5?`#t4GRs{4viJU{w}=Es zd*~9`*|f;a4r-sT1;Ff}HL+0(F|*1C3ha?z_~>l~a>ON89_>on1!w~^&-B;ywl%3D zLr6g<`9sWW*rl6m_Nz=3<khQY6&>TrDSa3Lts50JAR|j48oss1Pk%@|xtr~(HazdN zId`NeZmv_!3HSznzft8Hkgi@m)veLV&&4}t;l7XLLYrHPgOoQB27iZ<K2F(dz6!^& zpiV@LxP+yfqdsGAPbsGtFabMA0VAPDDptxb5bD${cAYY-DX)LEB}sLL8g3VcEpdD9 zb<!-reLDaH(;y0<K~M*haP+uqL9NE_J9*FN%y$MKTk#S=K}Ij=_0jWT_@4G&n}!y+ zZ+8J^YQ9%zY*bJ>?X7lawRB4)t)zTYSIDD8uIbrwIA!&56#el&Yp>+vnE;O32>{4I zxB@@g-KtT8c|_gM?ld{O`$Em^j_rTe4=WxksN0^vRIq%o<0K29BTG1PuIwH!^Q_OY z>+lC}PTs8E*5{=9Ji2$wF&weo%0YdpKyKq%uaZz|PR*Z)nA9IYPBP0uqba&)Lqt_k z95qMfi4|qn(E;l-pSm=ENFcPe5qNg8j{2jKyn7j42!CF<;x~McO-6Z1cw#Z3&%ZYv z4Tb}=zN@rlKQmUsgOYBB;a9aKo=1Nh02*@?PyJD_3KNuucY7V)|2FRZl{!TLrw+4! z#F^HXUV>fGHxahWTNxyyqUItUPw18Rx%_||h0NAZ->X*%N<vOH-@JY&Q?PC3%C=Ph zaQxt^)94rLz$x#h3*=vrt-)CMx?QHdhN$3~Z@B;wWbCE#c3HvZY!;&9t-htSMOSG4 zr}!<gODzhXquK3M96DZF*0SaOE+9Yf45{muM7sa*hDrPXgbvt*cCO~lGuCw*yHuaC z;%)kp@>56T)cTmt2adi~?Kr%Mzc1`<8XG`PR{gxx{OW2pDVTPwoktQxI~bl_fq4hl zsXA$JO|J>cwjupgd`k1MiXV)Wi*zl?qiPSye{Mh?`S)&a*qs~Ve|-B*hMIu+XoJiq z2vZ1GnQYA0+5;?3Nw>%OmNq1xTbskSTvThN@5X-^-P|<h|2XJf^1;B>;~9fO^{z&) zmEB5Vmaq<Y3XmTxloqBWt~;o8P`PI3GvBMb1|<5$JDb%2IpCn^9zdd*3;5hA2V949 zNMuT#%J<{{apv-VvUX@-l1iheJGa$0c2_wukVyu4#Pf~Zn(6_hbwl99V<)hQi#jZ! zWXH`huhiy*qjAA6)pgGvOu2rvl%m<(tMyx$Zv?dwM7YhWPBI}@H!V@V0ElKC=8<YS ztv2|QP1M$|PfwKG7vuATrf2@8-WmE^^8xu%(}D&vuWgYnq(n7DYy?@DF%%P~pAM%# zxN#Ce1jU-?s1Ca%xvd^e%-s+yMMPQ2%7Mg!u81}O-l7aU`sp)g1L2nq*WAOY%&onS zVDj>I=VyoFqu-11>#K*GU00juxoS4=HeWhCbb**u<B%C=Qg5zp!7hSfKjy}lbA_Mo zmIXq06YdP7f@&E1?ELRU-SI9Y0=MmNiV9f_dY{pD@L%fQUAr_o9b0bCbV8F)hADqw z<(aG&Cj#?Ll%h*P(Lv~g)$c<-A9;V|wfNu9FM;`_d#L008nJ47N;3K%GHtvtucZf^ z1u9SbG(^7BhX$iUzg9oGCs1ovxqn1+xo#a^@4j6up1t!hapRN5r(NT>9iG>2UtHC% z<3STJ@<}o*@cq$snVq+HRj}dc%AL+zF1QCvkD#iCughU+5%-o1Lb+GF67TufEI)ku z{@Bm^>qnRK_pZ%uSpV<W(0|9i6~9?s{9GhCKzqI{yk=SXUBTL1iS_B}lG|1t=g(v7 z{{fJ6AdxO-O#dbiV6nD?#*1R3x#9TDd*}7rgj}EWyoA2oSW#Z@*9Y!qbs3FY<&g|5 zk)dQP#!gp&+!!a9FTvzsx3WM1m3ff>080Q4GypMO^4<K+!k8U_#b*0oY~QkAfo0sf zw$)zOtuy$pjb6O{hD>{1g_~h~E0w0s3h0$%2Ki|(?1|kBX1mgU1GW8?U>gVR)oQii zWl$PbCymd&m3*)0?0xA|+tIGOTfg439(35IYiG3Na0;MWjy+LP4hDwhAH?S!<AB54 zE#ANt+jx1&>n?dzSwuxU2&hfQ8E@Y{?dTC-Soqi^9A6bT(iB;cmpYQ`M(>EWZwVLW zjj$o!%<S2Ikndy1Pg|=!2Ax7O3%3HPd-0_{Q+c|x+?2jNlrcWIow6lIPR|7d*0yrH z*%MOZ92-$MA%R5Dz`;~5c2txq;qtD60}~w+YQSr3uH&+t9_Ln6C8#O8OM2D$aLta2 z`3+(693K~jBmghWpIc=QG4_`?e+ri2i-CMlS^y*znoG5kGZ>MNh&d5$PS0p^DMl6^ z3q&2A&;KtvPsd8mt{^vFl4seMWyH+)mGEsjjtfA5JImRiPd<zVNvO;tP*C@2oz3en zw_MeLh2C}HkN2>GN{>#tB)H^RGUf7(b3MuV$vkedB$ul!k52BR8#E*f&#d4}FCceb zUmK`|>Ht<DNwSQA5pG5_$i4AlTzj5%xJ(w!qo?P%Sb>rXurf4OxvuV`+^&afyH2j= zL$5;C3%IVlg4jlG5T0wrHf%J`kFVtJg~Bl~a23#PaB%R%l=_iXNaCPEVY+_9SgFb` z6>*=+14qVCu=~)`2A8YoC-sm+^ZA*={0sm<6eg=}-A{95V@fojJ^!f7hBtHWv$h^5 z@g6c&Pg-L&m+3KI;;~TU@uA6M@t()hpvT8)k55Y;pVvH=k)A6=&oAr7o?mS}zqxsS z5BB^K@A)&+bG5|tSB>ZICeJ_jJl6(2|4w`UTk>3A^8}!nKoV1K6H|U0Q{kd#TKf<P z!~q{=f=ii@Q%vYNCZd^%yvRh|A3+Vt0>GGxs8KY@3!~?S-Q=ab%}ZsAm#X`yYV(MK z%GpIZKsc3)zdzcvvO%qe8wD+Y(CtMg;YDV}yJb_4mLjtI7{}ETz|6H8DRiF#y@Z0l zczYY|JJ}569Fu_k{6Xie@<J+k1;5&ij+TWQKRr>&-<o9UH<eohJr}#W+58k=yr+#& zwfh8B15m)VOx~?80mn^Q**cXzmuvE$S4glTUeOrm;Zb($h1^tXv0g#W-bU_|Wv_{d zJ<TI7yJvEVR&wqm;NZsUHp4=LU8k%E#^p%mtai|Tf5@}S@qk8DTp#Xn3C{ghk@p9P zOo==e04ZE*Rw7`-E5TAAxbx4b`~(P=<>NRd`vnB4{L+|qy@*>AES?&V>FZuf<xMsE z7G%4(gM&EEhZ)tk0u`7{?yI|7<w{$FIp8>IaZTl(3qg5-fuLaCq+c^Cp&P`KOa`kI z9vL;(ljO!%g76wJ-(M&u^{f+VWUCbSxM`|r2p8R08oMg**jHG?10D~_wqVI^x6dtc zcVp47<$5<hCi<_*ZgVQPCJ6H)gi}QzK*jpy+phwOgN1H#&G~Va;0xOdgC_jrD!FWW zV2BHMd-My!7)+n8;F#`H9usf|#37V}Ka9zzHG-n3+%~dJ3;<oKe*VeglMmEpCO+4v z9UNx>Hgsy?(ZQ_7(S!&@8<l%u{#mL^9<%Y86}fuX;m6Jq-HdbCC_K0GPHh)s3(%;; zD4_Nir?^>ZB&9;Z!l2#*`XY>8{lLxrLVS<yMld>QvWA}P<Db8Jr>H#9kF1Ba#OB*F zPb96Kdmsh%Up!88pk!Tq@?S?;Dl5-JmY3rXN?6Tva^$LS;)eC%-lx8P&wd@K3up23 z_5#L3mUlbT6()SZ!Fa6Mtuey7fY4yD(NCh^GZ50(0}kf*1dVyBx?Nhd;l^2M8M1P` z22aGagBQeF>mm97Hs$kGkhU=JABpKc4#w`j>@7fEfAyl@MKAeJAw+lCW&=oZH{WR2 z<$Xexe!Xskfr^2To|-TVNZ#u>Xdb>oVa*!k-k0+nm6OYp8bEXCeeyD=F@E_?%>Yi= z)3}x{Dox07)dPncatj!{(+s!~{@22Vc^U0?^}F6k%DEe_-VPhl-YfFCsp0_{k~v)i zyRAT5mH`?rdZrk8Q;w7#J!@OJOV$H7VCosP+qt)c76S6weW1UsUH~RIT!Pu~s&IED z_=U^!Ws%o-co=Yf5fs(VHL6vO5}x{Er5J+;OYq>5MwO6x==xlr%jzD$YTxnTSqq*V zl_fm}kR(gEBs5D_?(HeawZ-Hd-;-_WlIt_Y&W;a#+zkp$_sQ5Nv$;`m>EJp59zOhJ z0t$O-E(u=9i(8)X?E?oSigupnngG%JD|6kfAnsPXd=0qA4LbLQdM=KTJzVm30{{sl zU_fZT?4HBb`rK~3Q&KyaJC+wD@{59oC-uot%N%Q8Ioim+&`56Bh-qNoROIp)q)h(s zMU<`e$OPUHkeKf^h0I*I9$t_a2UXBZ1m7FW%h*`LP6v(DKzf8Fu2lWGj5ohhJR<wJ z(d(7qNRDP;`gwLcIEg9Eh?H+*=lYPjVFOV~jbN}H)_@K6=#w`vkPDtv2;ynVvZ{jc z?Z2K+S#f-0ngckS&OY(+IR((I6TS@W#IfvL+V(Hz44$}o?P5aHDAU;fL}JMHl#Pd8 z=WM0t?nwlnn$Ztv%nyL&1{mb~rGpX@Wu+!JAyMJ*55+VI_b@Micb{bhCayKqQ+3a7 zmOod$C&)^H8^i}+xCVA*<q|7S+H1eI<H<X-a(6fG$vhpE*2m2%iw*Y3W%16(;lY7Z zg2NxD3RFL#VPMYp>7nz4I?n4ocleLWqZZJt4`|lHgHQ27?vjPOSQ7p>JFa8>$E=5= z>Cr~W4VPTwKCboE&0?Mm$jze~$k9YO3@ea}E@VgIP91IV?O;gCvO?ycxHmRYU&lws zcUeV}KSnWQllZOx%<CyTdF#d~2c-{F`ry0s5dKiY<zw>hQ~L}Slw|LAQL8x{R015y z!UNqgLE8!=8egwa=h96ep)9UPL9WY)yd5*AF|N=0Us68ui%vndr6|XBPtJ!T1#hVA z3lty$1&Fx+dOjgC)Y_Im{rC%tKz*hgJ$P~%5<Q>4l?n1{-hAUA_kl{xMO!%=PS&QW z9LECC8!p#}nwNqH`7nEI>Yk|W+yG#OUEiv4?f2IpR_O0r;9(5JY2C7b$x>icCOT-p zW?&RTW%fA+;z6F*q0T!_DMWE99$g0ex#U?@X4eSK1Lz0orQjkI_}w{d9BW^sRi5LB zJgq>^=l321j@*^Z9Lw}sUx@-+>j&Et#Qyo+mY$Y<dNyRkzWnL$AI6d#nP1!`=M3`S z#!P%d{06miif@-;biv?FdtZl<553!VD8=*V!9%C_xzLe?LRes4q%3-?kuvp%)abU9 zF#_JcntP`>R{NPkoJ-jSeBMFK#GFmgubcht`_uCetp*mX23F?z@YBN@^GZrnFMNvH zaYkN;nmrj=?LU=!=|{Hpk8GYJXu1b{Iv?bm?tQ#8XLcm7d)>_~!2l99rLfIqXMX(v z9h1gl=hxyi4L;|(TK#s#E7V_5V7O#lR8w%TRB#^2ZH!X5{7m-E3Len3ZO~lDbb0Ht z*$_x_=$TpDzKm`DQ66|dDtZ<fi%E#)W%*wXiM|UVfZ2w%A)+JqF8pCP9vMjnYrs*R zil}I-%x=@nF0ITSzqPIdYma1eoegV2WLx5jZ_~cK)G2W)%XYIRwp^|(72kU(dob%? zpPdURA)V;cmzy#LnzJ$Z-2_Q%Jo@tC(dj2gU)}x-j)DvY9=+AarLqsJ?*K9Ub4?|{ z4Oa5+w&&Qm$QzKe4KUfpqT)?AMctAAv{r%E06Euno<aa#L60dHdg-y==Uh9N|15>s z`cv8Z(Q@XTb^WO%yLtI-F6+PF%iC4v{(Z8EBg%<7PR~9fQT~>svrCDKx<D;ioyp^= zZsJaHD00pPWz;ayDpUtTGS&0BJa*D7#Ad&7Nb8<w-jOy{7ID3Ey+bNb&fEPbhx)Kv zgIVj8qyDykSlN7EAAnwJm})q2#rJw(X<o6$ovn+}3-EW!&s)OBGO*dV_Mg0xDuk|7 zoNf-@<`GtwE8TOAc;9W}3QB{EBy5iKSJd%nN~g{CmT5VZ8ULbfKlT%lvNLSo=J&(r zx97aO*Yil1$%(b1%qrYEG2VP`)#XHQ{&8Is?aXx%NxTD0(RH>30G)Q?UK}cW^J}IK zS!}j1*2?o~hcn7-;^ECBb3;K}KfP8zs`#eS>+Z@&<2KQleb4I0Pj8NFR(nJI`}>{2 zt4GJ**!}mr6#4g3o~k+0MLr9x)CeNTnKbgVBaET!T#OxFs;3rKDd1`(rwb_iGNTLh zDB01jg}OxrGll!wZy-#1*UYL)c1vp!mW%1x!{+RbPs0PImb2l;3la86*(QFWyGh$% zMXA;EIf0{c`M0O1w!UbR6K&2>>AlDXC|lH3hF1hMR7H72%Hr#hV-3{@ItiC*a&#+P zNT~pCxM6O4K-9UEwyHke6#ZIP?Q<!eeYz*sq211;^yzYYgcX^eEeFH1IPmJ&oepZ; zVEbOZee=Rj<mQ^JT%AMpf)7?@neqjCH^z2q9ed3T%g;f2*XEHPsw*w&anm;&>hG=3 zT2gyzjTOggjRQ8NjyYe=f<7x^iscFQ7zRo+T?l~Aqyglx@6R9UyyJbd1xhX!X?&Ii z)!!|>|8u|2qMAR;3#=Nj`tpG4-!DPEqJMJJ*Tw(LYN%ZbrcFZ8zUh`7Hcyc`4H35i zoMMZ*674e698{W{$&|=@r}c7frkP=*LDgeg@A#L;Hcu6__ZcmukM;Yt15j>MbzI2J z(H%NN{@Y#@JiYnU(}8sBsoRY%bj9`cdljCWp9SlbSxiQR57{gh>^}Z{*WC(tgOWbM zfI*(}7gxPk1=?_{S1CA8TZ!m|6Wnkb0M^`TuwswUq5~N4y}T77!B|LbJ~+z^{blt= z6bqDBT@nElkxQ72dE}Z<jMQ!7*?iE5r)MwfR<az>)|E0&mc&cE3-fZM<f6QCSDf+U z_gGhQ?+zu{hUS}N$PJe(YYVg+mdt+G`1rl@wDvi3@V>?Kh_0O$FL)1ktxlelZ(CiA zx`FsLcVl+o&q~*4_}>@ZPtgCqPkkO3`~A%H*!m5vf5J1{*B9gf9<FD@WG-pYk~T>e zr(szpKxo}TMxIaHu{l0VxAN_}w%TLzV_If;Nvgk&qBTC(<{eNmZRsL$Z#a0Q1gj68 zq2}96Q+!Qy%7Os$cmPxzTO8dTv^Jymz(341o`I4jG%8<jcitSyC<&#@<0qrlJ?*og z*0LQ`yF?(OV<c~#bBQD!skU{dD7w+*aI#2lO2=}+t|l+d*-D7k`=qio*+S+wGQ<kb z$afePU=A9<r1g&N)S6we58h{B2C(d1XUUK=j$)Wqe?N|x1^r<2OyditU^h4$cf}2~ zA=s;QQ*0d}RG#(wU3TdmM;(m^ykZ)kfr<v)kTpy}Mnww<U*xRnEpjBS+`1%E_38i5 z#5bKb7}EQ#O<jLF-e7Ug8X27UwK|KTZxk;m7GgG2I{=qVdVdYFI5@SYksjMDS=9L# zjL}1Cug$Y0h<j6=nr$ujF>6#MbzWP=z$mZctQWH4ZMN!zcJ7aEp1e1Ujmk`yS4Q6| zYS|}m{EN8Jbyr|RCSMt_WZ-O;yWkCIAIJA%-kEY__xnq=1lt&{g+B$hF*KYs)W}^+ zH!JoK0+D4b57@DNg$J5iNFO<nZC7k$7xSGsUVE3VSqpbd0Yz!o%N}Zqc=!1So*H)( zdrbU+50izp%@IC&A&VXNd>bncADUPU>B+KhX`XdnYJWZTL+(K`=X%xidD-V4;LRYq zYAd~K9b~svRkgKm9KXe!8+M*@DvD!4V9dquiB(6ADJ8V(pBuExYAbV1*Nc7#rI<p? z(QQq$H3qmb^JI2O&|H}Mkx?h@*O)vVA`oOCYe{!v3hvGU;IfWDn0rIXz%`4zFJ77K zVV*tyUz0hZ-@n%^;!4S0EBX6_eKE$nM`6j0GsNX|P!oW0Jmr5C-TOb&{r?B>y*K1A z%+4pXA?MTBmSgSU)Jaa2Q`(SJNGeIVc95J&5;?S`1CmRnQdd5gZA3abM^Rf;3w5a^ z9ewxx2lmT*x7Y3Ue!QR0`-2>Vs2lL!>3M*%F-i!3qYPNH_ci_V1H->sncd{c0S!+l z87kj(J9*Qm3(>#WRqr>Oo)A%?yFu5mtb09$T3-rd`Hnp{(FYh+CyS%pIX#aWHSJSQ z>f!$msbYFqIz&a7!TT3;11XM2^*A%TQr0|hT})oPa=}@h*f$`;JF4s}K0)`Yzyzo| z{TegU+u<+5T;v}QAG}=>qG77*!<P|UsfC9}%#3(>-5&R)dcVECX@`{ix*a;H7e@|% zASAU9E?q0_Ux0vKFZ-M+qw3e<eF#m=6E>d8{4h6}(Nczwbstcg@~GF~%yMq#tzqqZ z0*>+G!5*jh1A6glu;H?Q4&jy}m-CfF$Z%zcO#lpqL3Ll5wcfSDr1@A(%|L(j($=cl zA&LW}y<^-5-8TqLm;~dTMVg?=1FP!nbTXm#z1F7ERi;R(-br$<D=ZQkajzN?q!77V zt;tUvkHrWUgfK7_6GfEwJ+#uhp_jap(r11!zdy{!(kiQDqlXN>RQ@`;{hjWiA~3=t z)!U*^!bn+QA*T|KyEhs=<Y`P|IA*V`@kLsm32e+8m7mLUnTT=2jBtIRhuUS1qL_H9 z*lQwob?HIl_?4(uSAXtJYEcwzde`ED_qsfu{=VAthFRm_)QLy=@#HjY=R#6=nV_(> zQ=si|($CeGRkEW^g!pC9?S36tkV3uw%UH!fJ0QqU&k=nH%(5Xfc9cZk1%q1sPuQ@1 zw3uB0N>aAdbaqK6WnmF375jwpsrpG#u_%XLj^)~O#fLA*-tKSH^r)rkT}N8ns6Jk> z>09#87i;dT=T3D!O8ykZtf*_-&i1jnU&{&(J58e+(|fI!;5xE=mSMiSYizdlVI)>` zPwIMgQ|X{O{ud!PXy>erJ5aKw9)fE8CaZw$o1SB@#ud|ZjphuY)%_;lemFk&I$NaQ zavE%<O}6@F5|uBa$035cAm+3HW3kY>L+I53w$2px)v3)Yl*=z+x~6Eepk5^b@KCm8 zVvtK8+pPm^LX;Bbg|2pTJ1pnvhgZ-cZfw~7b-xCj7yXM{*l=~b?xc@N2iWeOOluDZ zn=Xj1kXN1N*bQJE280_|bDYXHJs@&Ub;uSfN<F$DFE+E?y}?E~z~S{G`#v%#(Zq!& z$M-|8B|Toj2Sf1jA^JngxJfl|CR&#eZha4I=P$SI31)C#IOWOJbpor^#8jdh^#rL7 zvo)h%+IPcky*aeJ?Xbg-?FXJeJS?O0qaFIxsMB-Z>(SIl?C?q0z^KyZ<IY{!vuj60 zbnYvv`LII=fKFk1U62uo0<$tXsgZ3kBd|LpvyKzhccTJ|w>Ue?X&s?()|k`CxcfZ; zyjJLXL1^0|vU?<VO$U2ks3Rpb*nv3Vn>a2Cu#JWS<RAkzPuncY@C=TFlYEK3&AHLk zcGe8^OTG>SvI~Zwj6%7tkUXQ;)<yEw%S_`;l1Ceu8d`6qrp#y%TPL}F+sKMb?X!2` z97}~1T~==uA>aR4=-kG!R1=devJG{waUZ8Qj)~W*<m(<qctx2zS&3|EQsYLs4OGNP zR0GW{!$+*uBaefGMQ^fXmStd9KF4x#=4a8<;T8^khGT2RGH(;nK$8yhV6WO&u2yO{ z4(u^9Ez=>J$iR+|gfu3{u}h6|m|3ZG9GO#|HXMdE<ft@mXMvjY3w6TgI>!+zYa!+f zAc|T^Jp{JKzUj+{(77`%QLopYd}^}@;3p#-GdIJMUfH*ZT=E3)M6id7z42}A&gQoR zoiXb`OdFyAbBH~cFJDkwaiJWC93g#xgF6Iq4TaFFidWpr*wzZE`66JVX2q7J=w*Qk zSAZi5QFiYv6D&||0%9LP(Po?9V<Ksy(XH~YP_%mr=9Z;?4@C?a$(Jo3c35an*s z9GVlv$bf8h2<+IxqZ1)cBgnL?@%jbw0Z<pWc6(&qPBfowrB)KXXDk~<mIfUAwu+^r z^$a_?g@MdE^p&%Aapr6Axi>|mJPy52_(0=%^}=cpae^;XRZmhvRh)HE@-IhOkB<v% zLkTXfBKLWz8yC!I;aEYzC>01!79`fPPPxCw1q#yGdrWB;t&lR~Di%6SiuMFhSb^Hj zTs03uk%2T_wrLLg*#(YgRK$ugm-EY$;|P+wR2)zL>Ys76%2T~i*Tv4R2mcj3NS%4( zWCaOD`ZlcBeA%OtddVGIMn{U-#@a&DM$u#uQR}+U8L4hNF1C!Z@ZT%63gFPn%j{Y> zwje{x7P*}{<l3HRA$EIP7`d(sYz9r<nh$L0l9Gz_O~i7KbhaCmUG2=aY7^4MGTRZ6 zWqIjv%I4u;JyC5U*G7@M>*}e2&6EiyIY&tD11d}fM%;I}don9e86_R;r6&7moUlgq z`(T9=z;Os1q%XV&l~mhx@mv&5g8tcoQFg|s95qC&{!T#f7rHMCrWQh%t>o$U9IyYK zWo!~zbO=_o$Ar(I5T_!Tj=hnGxor6w1eC}Pzn4%=4DWBA@4ue-@KQ@?yXxO3++ED$ zhwB;{RWkY}HhM&E*(h{Rz+?LWm(0y{{`&qFA+1|B<dB3!L#SNybpVIfdgf=8$UQ|i zH6SHcvDP@Prou$#{xZ`MsUew#O6fvPN?rRz7AcS*?jw7oO_h_J+rGC{8`0THK`L!+ z7T%2o%1<SoJA<7))0dd`L9}5rWJ?)mn?z(D2v8RVQx%Z#@C4_wM<W3oih(fRnN3fS z`xtCSS;+09j6qfcJ0p=}#SWBBb5X}f!QGGZL&+bWfBZ1^QTh7ipfP0EZ+3Aldj-yy zTc$wlDg<f)T}`#ZAMft>=WJ|EIRE4$%?sj?Qsk2Nl-tQNnA|)SDzn@qv?*iTY75P4 z0oVdx?~$%Wt=u~Oysfv$(fs7@<ek5hO`Mixv?#gT=c^tvwq2hYOOwL@9<SLv2E5o0 ze$nu;Jm1!$_55M5XPnHnOGMWO=S=7aSl6cKpK&_+TCFshWRB3aPo<-(Gf8rt{u)vO zgnmIqEyJvOxS*bq3>{d|pH4BDTQK;tpx?XGP+i~s4sm`pe%;bbXAQY?9)`L@gj$$c z8SS!75ZP<wIy=d4ofg{pLu}Md+w*NFj5*E;R1a@9QbXt!Cbw;rtt^l(T4l1=Fj>%a zCdz*mzZmQusy=BRyQ_8AD3Qs^CtCVAZAxaRkhwi)m(5)Mtmd+{<F;yTqfhn~YoN{l z9dh>+(eDK}Xbt`v+xfeHMCa82w>{y}{botigOSG&uPBaJ!n@$>FPy#Xto8I&d%z?y z%hVgv^S`|Q%HwlA;oA!2c1Q@+1#<M{^@lcJoLvsOczki;9DJyIV92#?Fo@!u_spq< zy>3!q(g<O|z>i>|Q<aZs2{=cq^-raH+l;Hb=y+!c|3M#{(JsW$Shn}Tj0BO_IK*Q_ zbd#}bP0Cf=GC<@Da=2hZ`W14H%)+02-n`!?Q10E!UZF3a-dS8+e2dLF^}+N4u%llJ zw*wGG!1^r!LQF$AflXTunUdMr6t-12Saor0OXpL7A*ZR@6=~c!R1p8U$=<8+udhQ? zcfq!cKx#JIt6OFh82?s_quMKsFBdbS&U|=M<PsQ*ts+vjeS2RghZTMeJ9Rj`=4*Jv z;fO0=BTgMI-@~D*!AkB8D)N*phPBR4Xb1u^W-Q$Hy?78u{p&3o6VelQM0_Hgv(8(n zf5_C#iEYvbRF^lEU)q3x0^k-tah{KA1ECv1`fXjS7Wf8O!9=~(5X-7=X22_SVJ#q? zJ`l`K0Nun|?;<7l3Cu14hRaL@O}c_sG2zQyFesqI1?i-NQvWSk6}A+g2oMwAk{4Mu zivkOBfyW{6nkZxL$;acN=OR7`9df><&w=y6AuKS07Wz8l#<$PlVMit;Q@#d%AS~;} zw=9#C?745*`zz<a-wxb)+|^vfc*L%7zUT_$z;}OqN9DY`E4ARiJjMHp+8{T|6)>Wd zUDv+m9!x)RZ25#JJ@099+IP;{agJpmVAj5{G%9422~8Geri04PP3+gs3VdXhQex}m ztO1Fma-Ky&=!b;l5vf6X7mUn0)h~$MD70&l*=U@8rY0yK;WliYo8pVCDtakI_LSWQ zf=a5}%|L*pO^G1GIR1*}0>AtR=xoDxgti6=3Z8g9$KdL_Er2(+=bTAmpW6?%Ts&H% z65zGFb!mdRFvfv3zyZ4-<VGpE5$x6>zwi%aW9VJSMpPhEY@O)7$mDK;`7~lqd)^Oj zYS<dlS^Bl{NAryz%_8**gNXb#cy$Da<_h8Y9k*>Bv91LO_m(xaAhs!rD+fM4+|@$Y zxZl4`NlPk*&j21XGN-bGw2)&rBY)nEJ$7r~&s(v_)=!DOn62b6`R3xwYj(5IAh2hS zAxL%TpZ$-ELxTR<DWdmzbl(2ixkX;OMxXA)j@z<?6AN=TulFi?oS$0UxhD3THyG*7 zBKbo=ga2$A;H<b_;IFC@WJIy_v<2$NjwZ5KcK{}v*tWH7OMkXi-c@s$u)JXdcJq?q z1*zcz6QACm*!8eGNn|G0a36q})NxFXf-N#37BDaLWY=IUD~~HRj$@&jU^G-OuL3X+ z^vY$*R&&{|+MRDg1L}G>7MWR|eVn_M?B(-9o1FdD;@{`nyk5*n#s7BVyE;ky?=PNp zPW{_SBC~DVf^Dq8mfnU6$XfUReKdZ_JEbEuf`SSDD*7aNRYo)=KHlUJxF_bE^O@sO zVjJr=4*lfuGbzVZg@071vftNaKh$kBm=byYlDo_tt+>Rtg6+meaV#o;%aje&*=%aP zY~|r5u+1T1_WSGyh?RwRf7Ey{wH9o~XQ@<OI4IaG<+(L%+Q##ozBicqG5gaT#;%Y3 zq?->H3+)2enT7%zdRfFGHjbHx8|CYXzr)O>_+{4W@s-~%{+f#WPVkdigEY>2=U6C# zQ%wOl=YT$1`{LvBi@6AldsC1+AHgI5Npl_gasGjY+I5t6)uw(E!q7rWxUbUNj+Wu6 z;#u6sW8?R}PFJ{i=aCL}5bvfU-v@DCLU%+wuXu=Z2x&@{9zgBe*23a-D{v^a*8jc* z;4JBZ_<yYoJ%@-(O07~x%BOU-pyTwU%S&S1;-;wU5k2K7My9JeTYa(;zh~n`b2vYu z;IuU-6L&EFagE!NrC+#134;ym&oFj$U_pQF3BR588=saq@#ojnjc;2*I#P7^40On3 zPt2-z4Ndx|65T!%)(&;_l@l{Qlh?Pz-I1`m42+GUG_J+GNk5<pPwaMD0RLK4u`Y@B z53<=1oUOC#K-sR1Wk}X_uJu8kQwQt@g}IQudHfS5@dHxG@3mw;AIO-K!8rI&Z{Zsq zzP~L`GuU&vZo_lyZm3;E$9YXuaHzlsy|K&mI5Ns#k^^_RYt)Nh3*-8c)-98TWU~d3 zNE08(1R!uL1qd*367$J_)qeH^Dn>wRypqWT45JtL5UryFD-@A&6nI9jWXSuVgyHyu zUu3wKD}ZjicdZ+?@zKPoa<9kgpAT=bev54%2P;S~UYZ_1dpPgfK73Nk`)++2oab8; z2MWs_4)A(Yfs04h^xy-|lP}?-GFfl2aZx^Rhr@Q&ogRxw>O?(@Iy`myS#;KKR2Wx% zs~?Zq`H$b#j76K><sQ+%VBO&*e=|g4{~ljL(%4B_WK#e7Rj9<f#@i#4TCe#M(q<*T zFh-ec17h1)lOORw<DE;yFxd{j+SI`vmN2Vj|BL5R7yGyUy>Bdhydv-tHzvm@CxKTU zjUMx@-PbyCT<yDtUp{-NPx7wr=*-{;_!eUR`|<;xxRuK#RZjy`a?d9HuUgk^oXaVw zJNov{J8@Qgg8_T8ET)i>lg`pGawt=P4PyGFxmH6~a-&V=G1pF@GrCxs{`~_Ba3-xi zuI9iHX*bbNVUz=7DJmo3q2^Lw_<Ht(WB=Xz{pZDho!{bp@Y~ot%}=4h)YYgR=<VI8 z5c4%XsO?BS6eDip+S@Y`%@5K}vj$Q)i1pPv_eWz;giF+r$m+M~p6I%|rRPci8dpC{ zc~$rAW!8%EvSPpEts`TJtN2UpsekYIK2iK_YFu^EgfZw1z<ST@4jatXU$2PqD_cLi zpivW<c&Fz~WHRplnW%!3zGs8EI19|q`P)0Qp7w;V_#n*6xE$EyF!c`i;GKvOQ_LN{ zk9E4BSfhDMmb|0Kz4qh@(;N!?O`n#7L7v{emTAMSVSrAHB6t0QDSW@H5VM$4kf@e7 z2h?5jX@f;OR57SJ@d=w5W&Zw5GvXI<ucyq&@YI8b6Q9&;*G|0dqn<_uTReL`FNOKo z{tr_4WkJJ&d_aewuGWqTljHNsAb*FcU_N_tC?udeIZsIPC^B;&QkEQ=q#Dnu{BF(m z7^LOJ^0F6W{{>B4JsdWTAFcAGw-^=gO_AeAx#ny7)eYfcL*@8Kxpdd2qIRcP>=Ue( zOKnhppjQKaByjbPdL#W9$`#VNW4@MJ%9Y&qTGPned{is@qWZd^yY)_r)|L2Gc99o* zLi*-I_Z1zzvib3b>W&NxTDZLFSy%{Te3N=m?%C%3@dt5_e!X>#l^bT8&zj5+?4njt zbQtQJRx3zuyFrkj+7g553A{g#G%F78+Y;KUyVWUKUEky++Y!q3wsO7%<%*wd?T3xh zHV6t5m~w0%N6V!`g58OXHJ<1b!7E_eds;-s0|^|2XPeNgR!Ep=zOPqfq)jEVboQ$k z!rLf%8AZZ;W!Wm!pt2;M))3p;R~hU#0X@<IF;<aJc&LEV=4M%Q*v-AftGcB@MW%?V zFcGfL-Pau{)7u|-1*3xHI;}7T+JWk54{W3zkRn4dCXX|0dbfAJ96;S2@39Y~7VR7W z3zz14?81~q(c}BE(z5wDO}tHhZUOG8dh@+VP*s##fopO1{o?=A^Bn*>c<sPLn}LA{ z+9C^a>}Ku{;qANkFR-<*cHFm%v%EKTy0TVU96g&888uD9+<CAyIbxtGAkKUmH-Ys= zk5hD<>;@1s3BGn^*Pd=aT7g5|%%uinii&i=(9kmZl4;Z0cstR#UjDgXmj;_>04DWz zV~@<0l1sGW>1_j%*EC-<*sIZizHQ}8ZIn{e+Dzg56hfTAp!TL(5%IlMn3v6EJ@sE4 ztuyB1l=(@Gk%Cw7cVR8lX+dt=m#;;(`X6V0UeKc6JKP%Bc%XPx_qY}F|Cg&dq|dN? z|88*P8>?RT4vPN1ie*e!hfhTz56b-|><_wMXvvG6c#|E@=xg?|bibx6+S|~5e|)QB zDa+>B9`$Ud(|zh$YujBVAvNs<Z=Ekc*qtcE4G7SS;>)|Aj8*vvU#mq7Hf5FDJutd~ z@8{y%0^M?_A3L0`X>*--h7023Q~m!YuT3wC5w|+GzOJ}Za#Al*Y#Mb({KetwQ4H6+ z8CPSKr|-_xKym}o1A(7utwC;)iE45d>*sp^lR-v@2(h1UYg7TtWhTU+gu&O#Z=NiU zuPq#3UWqtSt`}b%Udu)t9pGRqK*!DcZaz=V;$UCcZ>Qdq^wsuhUb<CRoM=9c>FCq6 zPn8tLsuRIGF5C9%e8A`4c&qHK%cWPc0`qjYP)kOAZBwrlhd-LQE#J4?w>~=c)H%<L z9A1x&!Z~j(@+xwi*=yW>pfGg!Bla=V$2yauf9!!kcZwj^IPs=AiWVz)QkL7Y`v?Z4 z>cL-DLGVj$VC!xv@@t+i>E6Oerx{>sb?gfd#Yw-U@d1=0(yz%>df1exoC@kXLei4z zgq;dU6lrUiyj<wPia`qkKXq%%-v925jrY|m;{L6e-@gMJn+x7v6cZSIG&P>a=!iMI zQgh=|{8oGU|0K;{&e`wG7(Pe(+8ylXGNN2{U{SCtr|bTDmy>yiC)t?hTu0~BpkmE< z2%d?_pwFj1_t@VYIM$fJm@h2)$4)K=sWeCt9{H~A6oUe*RkYlb4oQI`!xLR>S14=S zzBz$9-OsVh<ZW1@P9NVG?Ptl5oH)8_trdmI(k@UWOEJL55#3j&0)%!MHeM>O+$5s; zW6Tq<q4TNieGN{wuY;e0|7qG*LBW>T=$i73EvB(n165VlwGIOsTVR@+#ZJjALYESe z#)73Qpdb)tjD`5fHO^LkvP=3Fca<2Zgbs<1&A*YbeZG}EJv(EY&1Hoattc^-l*lUH zk6T?ic~WHSe}>DeQzv=wssv(A9?`r9`8)ucJUdka0u96TpS5X&7N&-DU#V<hrV>=! z#pqd9*{o0GtzrVhnxO5|p8{Y)H}#NO)%7Zx2r9!s^f-fsKTFZ|XAwf*;M^e~#xz`y zW3=WZ!h@Rehi5V*v*WV}YX!(QKnE?*b?0F^c*Y<3q$mL6Fu0X3z^QS-8Fl{}6YiXg z&XtBZ$Bu^ejB>AL{_n#QT&mybWE96DMgc~Z3Pbl?y*GlSw-ouJES4|9)=KdeMaF>} zh_`If{e#3132`up_{R!3-C}q{=}^Fe?W1Ikyz5R_kzf-5jMY=b&rc7n<fl}AM0eN| z=Epk$oRD8Z6il$uHwqHqW`#a5905>6WF!~hxBH+Ho;aul*h?&8o<P5mkC9)*E`7M} zE>|HNkr$-g<;%fp@6{r~IEsg=;_D1a^dK69VOCSJc15ic*Y+Np!pltnOq3hJ|7<+( zU~96w5nUEM1}a~~4%tW(zhv^%Cn0o^Y<`hNot?MoEw>BVlGQChE{jdHCCKYMJR5-i zAR~V$4QK*mXaPPzpj*Z?Fy|RpI^p9tFD^nsA5Ags04iFE-n&QdhZuq95I|ihwnX<V zH~)WSq#<6@ApoOoMtKOQ;a18+Zhh95iAgb1JMY$`p)Rz@VY*HdDp^8WW~zx%eQhP4 z9Y~k~=_o*kQ6SVz*N!r-gn0>5D?vs}aH+g+Y404$fLV8m!AG^(CPthGVxs`i5M_d_ zlsO|JJuhL}=7*z)J>5=*w3i#hDbRKaIs;g&>TNIaQ$879`(H>$7!N%nfuU78=9F@B z>Mac=^rKjdn1pg|!ap({PD{oMCASlL$DDi!7Y6hdUAhVo>a0K>#X{3~r2A42O9A1> zE{vA#^$zH|?IRlRTBxQJ-Bt-Mfw$E{PYH9dPY(4vQsEaq;`i4Gy<3SsEBP8NfGv;- zxfGmmMcQW7ZnDIM&kC@?9Hq+ceTLwM`JC^lWw2)et~zLEMG=aoBs%dLEqJi&TL|1< zhfK<Kb6Y<_XaG>W=-GqIRN_;vpqix^+0fJ4_sefX19uE(go#YLDVS~+$`>Ha@{Pg- zxMm*KcRjACoX{cFwO|ppDdCnk6>Y5SN(YVqOtA)Uk=PK6YJr@~GkPLL<mi$Hq)2r! z&mZ;rHGqMagxHAAYK?9$-S;JfLU3(GSp+?q-*_bD-S#twedYuhE(O5_91JhRcVBka zq8d9(9Vmua_gQS4022tHBlK|tyMi14yBVPDIV(X#eI?vi5><ec_<+vq6)xVj|DS@( zYpc~UkfySIq(57UZ3RT#6m&W8B|VgPq<tshmfbgs$q#_Q1dz*2;=se{Dk&C(R=N(O zym+Kw0Cbjz74xpWUWK})iNEwzf0AsZ788dAn;_n#*Yvl`dok`john7+-P5rcbi#oO zdJe;He|thCCn3LbKv=m)fZjvhpHY5m4-O3yG8h?$5{hr_-58h=v+K*ReB<*>!&x4> z<gn9`9^P;o<?#cPB?&j86gw->pHVE0?7r^$u)mU}xbQ|sQ{rqc$8rTQtW^K3;--c2 zazH$B1|UsJg04%Fi3x}l_yaXTo3YXEV$)Ob&6&?FHu)<(2RAMpEL?qP<B`SG<MeT$ zc4>adyHN90mu=8N?ArI87xMRwqK}|Hlm1ANe@k&)On9JmWD5^p@GRZ36>sB*_@Rgc zYare#;qwZ3#C`mU<^y!Z?j#nbO^Heu7^RfwI_To~2fhV-+wOYgY1u;B-+QutKFWNB z$)3i5LXUK$e8gt5(6hX$ZXUWTwLMC7By~Ig=SjxA)P5+~I1G?n=Q(N#e%u1-lf#5& z<N8ZtokQZAA3+GUFzOpm=o1iVAx)mSE`#qx9g-bsOK6bdd=+gb8k-v%mb<$uci(vK zx6!cV-J$Iim`s6>04mlVNl!`V7h*NP2~40X%O-g&<6Axk3rvFuJwvz>xlLN|_jti> z2?8rntDpMM`LPuRs7=6Faza)n>wG{Mh9S|fR6sR&f1jt|qn2~$#!LRgmVQ~zJ+8?Z z2e9$GoIdyw7%c4(0q)ls4PZ16^IZecQ#&sql`BKD#MCXk$T4NKOEr#GJwB7ZZSFAo zJP^lKqN2(l#3Y~?6oa%%9T+9Gnu58%{oCs^mHQ?t_v6kS-jy9|MyJJwZdk2bKz~y5 z6povy+MHtlhhhR!ARA$7ii3Yif=vdnuw-fL_p?`_*c9nWB=2-J+2A#EC(+)ZimMam zX7ER$inbrC8g_=k>!-u(->p>F&rQ^?yFssXvv;0`(-&Uk@DZ(&Ehp)Sb<<UbcNagi zBwwThOG0B}@v=j*3kZHUii!%oQ(N6N_(x%=mT@luaUDu*Gw)r6gI%?<J|yDe_Ollw z&$<km(m`DV21&RyB=?vEqs@RVKf~qt?5#mdL_ZdFQNe;U_<H4T%u=$O9_Ww&x3&>a z(+VA?5LE0iG7Vc{h|+qKe0l83zxWn;L`(14mWR(<o<6_Alh-cuvRA^kvEQI&3|MO0 z_1dPa<M_X~Jjv*02`0$Mz&+T!j<8^TM<E510z|#p?bdsH^a2YV6A-4bJ!AQz)%wNt z!DowO?sb#TL!4Iv@Z$o*MFqY<ieZ)>)^Yhe<k(E}<&0kx6D$DD6`*uQ9m0p-;f)v8 z=VupCqh#e{c7zVmvBmKtHNk<B;h5?ksSDi)ahiwjme97`*y`FN-umM1`qsezcv$`s zV{M<df18|BdH6P-AW%8qO2KT9AnP|#qn>xZ@~Hpspro`W+a-vaf^Yu{dXm9vFOl5+ zo6rS3u7&TS&$HmKHLIgnci2G4r6u(vHT7JnppnvM8+%Skkh}bHa)?5NH^~2Lx5{D> zWD5Ou3P!bj8|m4#J#%IjFgm&KN#z$5Lmz#Kf=LZ4Js8#dmu*rH1v|b8eQ$GOkJ4-U zAh>B|&!O<B2d6jsZ~fH~{7}1E**H)mUAcXWCqHyN@}Xo;O~DJEVM%B=#fWTXZbsvu zAwK4OQ7nMJrg@g)CTdCL=<5;00I6PuI4oa^V>*WZ@p!!Q>n{Bs&GnbO*cGYgtJ@>K z&@G_0Wi%;~17<shc+-QnQ$vo%!;Z$1?O~TD@Sq<olTDf*!N5+^r}TBHc+X$(?Y~{B zf5I;-&31H-h8vIZ>c(P!k0niwhI5|n+%Xo}@GRDAeBbY9-`t)R){SOmjUUK*HXJi? zs_xmYy7AJw=QTT?S7(hjc)h6WoB$LP|71<@I`JPfhK}2gc22!0-9Gi~cY2-I)J4nD z!Y<7CtGZ|Jr>36%e)++8>P_d%@4sJu%6j$A>m`t_(5zQ{^?DgDrwp@AKw^}uM12aH z{E(79OG#xuCT}CB>HnMb$nJSZxU(jEy3l8)lmOa9n!(^DU)}7-g!CUu(z4QIEaR%j z)bxJRyMxggWj<F+f7Ukpy%R;NPSmRkU#dz;?@vX)KU4p{=H>fyq}hh(*~|5_S6<Hk zO`5wAJ$Ji)?w^-)|B~kA(eu6a^ABInKP7z_j{b1w3JIj3411D6Aj)?Q%{Y+ygEttY z2kHkQKp^cE5TH#Yw~3`9ZG=r!Uz<dJ0%qn+WHQh96k_$^p&g&Ne#JWL&`39@xceu} zfeT1CGPAc*BeuSF{jfp+)=Zx5zH@N*lXGj2eb)GKO0~Jc=Qw-^p4Jp{kzLAud{o># zdSw+T?&<@SS%8KnG^fY<*8KRj_#SmNeC3DdH{+E;AK2~I$eU>|WSz$<9r&7jh~u&z zRs?`Gv|ugcH$Sm!%O3caw4{9w@2_0FrS+cMjdxGQoWk5hra}j18Qj3oXF@>tOJdES zAg1%~dv%Wc{&)50n)s;>w*)IEUY^FQj#DqPUu-)%*=9z>kL&Vp&Cl7a|JM2|^LyHd z{eOK~@v0#Q6@WKKK!I0;j@?gQA3T%R2r!oB+FicfzxV3M&xNU@OEL}B>Y$pmNlGJE znDN0UoK5Bj4(NQDI`Rti5@@VB_UBH|OJOJdT0Lw{%c@tq7V0{9ne*zp?i|hP6uh>D zf0zl#CM<79vfb<4^SgAiG2%!a=qE534?PJ=XC<o|{`#q&2Gr5=>A-8NWgn)FV};mk zJNwUaT-D~12Qw$cr>iBYq(9n3E$wiegqfdp)VOe^=W<L!{M#mzde4F}^HYZ?T$LnG zcpAIjDSY>3?=fqOrWl*e8{S{6jK6Di@pN<Oo=cGM0@$VcfQaDr=li{zFO_HaH(xre zn~CICme$ABHQbC|9Ab4?jO^QPFL7_$==^5yd{b{~&rp-Kq<bG|fL$}+KC<mt(AJ3X zT}fAKv`6eguX5);bSTPglkceNue9EozvPj8yQa(5vE$4AjsJD3Ob_*2gXaIa>eB&Q fc>1qK@6yw*RhYz+YjxL5p7vUDB?d7;Admk8aU?Be literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_pose_infHorLQR01.gif b/images/demo_Riemannian_pose_infHorLQR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..82b69d61788be97ca2413b47f0338841332349ba GIT binary patch literal 120036 zcmV))K#IRdNk%w1VSobi0rvng0RI3C3knSm4iQQ(6e@)mCaV}9CK)eD8W|fJCpH=^ zMjJCx8*LODct;#%w;wuKAVO;*MRFu{iX}&OB~NrFNOvYldM#0ZF+=e)Qhzx-vpiaZ zK$j#zHatR+Lqtt>M1$K!ZLLZt9ZE?#PcVE@S-4SigHlXWQfeJkm|0b5NmY}9ScvUe zgQr@vuwF&9U}IrmYt>_P@?;jiWMpq-X7XoV!e^T-X=-e0wR&r4@NB1HZEkLDq;PJm z^lq|madCEYhOu;T#dUJ_cCUJOczJks^Lo?9dezl`Fn@r4e}IaCfVsPXyn=yiJArX| zfpc1dV|;>u^@57BgM`q8(RqeUScZgyhpvB!AzX>Hi;Ikmi<I<>(xHw;B#vhjl2G`Q zo;{PX#gnt3l$(>47#)?C$d;V-mzI~Bnwy=evYxDIp{TN<*4Cn)^`obcrdPbCt)-@} z%Ba$vsWYsrtM;tM@T}Fmt<<cqs(Y}rud;rwvY5iN-Qu^Joww3(x832mpGUap<hd+^ zxwf;qYr(p<%)EZbyzKG4yY#)*)xNa!zgU03*22K&!NJ7H!aps=YaqsYea5hA#>Vx? zL{!Ls^vY>T%d)J@X<*Eljm*f)&d$-#>C@1gebCTv(OIz3)Wy@&gwxga)YPcd*VWZ* z%hk5h)_l*`-{RQlyV&UD*zE4vaC+I6*4*de-QVHe;NsrfkKWwA-r?rn?(g5<+TY;e z-{Iom-P7RU-r(Tk;o#!o;o#xn;o;)p;pgGv;Ns%p;o{=r;^O7v<KpAt;^X7v<K*My z;^gGw<mBY!<mTe!>hR^`;^pY(=;7$-;@#-u>gnm|>FVw4>ecM(<L&L=?%eL~>G1HT z@bKH(@bU5S%DD1pZ1S7V^2EpUUL^BiX!CSk^Y8QYVuJMa^!0Ul^?;1^&(QVn=JoaT z_M%w!rK$JH`1keq_?L(HnUwkX`TF|#{QUj={rvs;`2G6*{rmm>{Qdp@{r>y@{{H>` z{{8;`{{H^{A^!_bMO0HmK~P09E-(WD0000X`2+=I0000i00000fCBOX00{p8$(53} ziH#bAY!E6un6TkNh7KD_L<lh<!-^6sYRov%qQ{O3KZX>^aiqtMBu#$AND<^nlqV-% zbji{XHGlGQ>fFh*r_Y~2g9;r=w5ZXeNRujE%CxD|r%<CxojUa1J6frBwfF#GLWHjn zB82@)wyfB*W5=3RyOwNPvt`+yoeOvF+q!7M>XoZ^Z{N0V?c!z27jIy>VG;W^+&Arp zP5$cf^XHG>WXhN+Th6Tca%Rh$Ifwr2S#;^noGXJ)JsNXs(yULbPL0}h?ANnx)5gtP zc5T?ZW%s6?8#w9Vx??L(&ir@t;;wx|citJf@#nbx?V~&jNY}g;Dun<48os>v^A^&p zUteCm_zCUV%Qqih{CxWsCRErzpZ$CM{rP7ffa|?iUwZrnSRa1`x|d&m`=NK=gYGrx zAbb%fI9~=4e2@w~_V|+zXsfA4Vs#~wc%q3Zs)*u>Dqa?2XfeJh<BT@iNTZ7^?pR}w zH^PV`kU9q0qL4o(Ii!+E^2p?oPDc5pk5D#ArIkirS!I@7YMEL+^#B4v1sMckW)Ll$ zmw^czyr*9U6TBJ0esk*Qm3SF+WkCcO@;P1v2xd5-poC@^XrY1@h-jh}E*jyXjy}3z zq>4rgprsm4O6db)>=U9t`shR4sHB!^>Zz!vs_Lq&w(9Duu*Ux?>#VfaYU{1E$?-r2 z6DYEsKS4ln0R%0WF@*^cY;b{o8E}}v1{PefL9-D^JEs^XT#&4`7AOno2GC;asHT>Z zEAF}IrhA^c?4Fw*1VPvX=DhUQYwx}I=Bw|%{PyebzW@g;@W2EYZ1BMdC#>+o4Et+_ zupOGCk0E1L0Ivxxv;ct_Vtil*6TzAwM-WqpF~zZB$kD<Ba+tA!$YNyhaS#-g+`^mf z=B)G1JooH#f)BJ1Sv{ETWAxETC$03-OgHWH(@;k(_0&{XZS~byXRY<tTzBpD*I+X( z#se2zz^Obm0BQlehJ-wY941VmYy~8n9Cr(EPtigIW<39}F%xpj{XqmK1kt9sKPRsE z;*2{Q=ezNO8S3PeS8n;`m}jo}=A3u#`RAaAF8b)Cmu~v$sHd*_>a24<_62)x5G;bk zn$VS**apF21ycke2AXL0zC;M{25~_PW_~cm1r$UO!pRggF8%b>GyZN1_UJ=zKHPWj z{rBL9FaG%Cmv8?0=%=s#`s}yw{`>I9FaP}X*Kfc04?|jC1kL70cnBZJK=jDef(-<4 zS`^s8-Uyf{6Ci5?6vz+8cvZa$TJVDIT3h7m(Yg+L@Pi->p$JDv!V;SBgp+$+oL1<S zIPqzP5Eu&#W7wFkcqJ@*;*$<77M2$3(1$?$p%DLrNW>u;v4}`Kq7swH#3eehiBNpv z3-uE;?nwrPSj?gpx5&jVdhv^!Gs6eU)~pO%z>H-?V;Rq=#x%OIjb|)d9LdPWIHJ*x zc)X(?^T@|N`mv9I{G%WPNytGOvXF>0WV6or0qpU^iu1akBqvG9N?P)gn9QUmH>pW7 zAiw~i45cVXNy<{1@|37dr7Bm+%2vAam9UJZEJ=v~8t7vm91Km^cFD_L`tp~+45l!L zNz7rQApposrZShw%w{_Cnb3@;G^a_;YFhJ}*vzIjop}NgaS)8)45v89NzQU^@t6S+ zfI8R7&UU)<o$!pOJm*QzdfM}z_{^t1_sRdyb_M_j{-DP<%}LOL8uXwDCFmB?DS&M{ z^q~-qs6><5&x%@<o&Tf<JwTPvj(YT?APwp1j@eKFDBz?CK&eU<kWvL4;H5B)sZ3`| z)0*1!rZ~;1PIt=FnJT~l485pO_4&_x2sDzMOsZ0s%G9Ph^{G%@A4vmX00@M@0awi` zR=0Z9<}v20U=3?sTqxGEn)R%3p+EwHI@Gq-v#0{SOflz5*SgyEu6WI>UadA&13Ul( zfDNo*1uK>q8uqY=O{`)U%h<*`_OXzStYi`U00l79t(bi$T<L|6&U*H<pbf2PM@!n$ zn)bA)O|5EI%i7ku_O-B$t!!sY+uHxy_O_!%CsqGC*xmxRu#*k0aAUZE;Tre2ixtaS z1JD5j2%rNeKxRoBN>Oc=G@aPJu6DD_-RWW%21ey9ZpTaB@|yR&=uNMB*UMh^>ejEm z^(}CbOJBo^<pDux!vp49-~LK=xsQNB2a2$T6Ci-00YE?kI)KdP1|R_=a4rHIY=99Q zxWa4A>^e6q(hht0!yrcJdwC032l&>+VDYbiP0%;~s`$l=&2SNbZ~`7I0S7QZ@Cn`k zg9Mx)4rwsJ6?jkt1f-z|1}*}Q5r76I09C{4<Zy_mOyw$Dd4%tU00>MR-@v*U#>Slj zn8(c6wIYBABR~TXa$E!*M>qcfKqvwa48Vhb4!EHSsIwB73j^n3HmFh-6|M$N=t3L% z(1=d7q8H6*TaCEOf^~od2msj#EC5Xl_;P*k8w5oli-wBTG-E}bT*(%;uo<p%9Dr~I zB<pwt4dww35TJxD@Zii1MF0+zU|<+r0oG7%C=B)?(CIY#*vL+{vX{;5W;;7GkA}3D zBWvj?7{UbmB{KxdsO@gYFvIFZfB+PHT?8Z300-vvfj2CG3@6~p-HrEl=bhc_f>)q| z-mAX%&F_Bu```M`vI7Rb<$)XA!~<_04eK%%3gFiOWN5(xyfPTH#>KvcvAD*~nik7S zcbQQRd6bd)=Iwr5y43%rx60*>U}1;1VK9%m%x6yXn%n&5IM2Dx=e329FW><{|9K4k z27#Xk{pb()xzdvk^vVVSsA(|40hqo3r5k<eRZlwBtxol(BfaTH_xjb5KK8CN-Rox` zd)dVfcCkO%pYy~nTSY$IV7vUN+-tAi^$zg9`~C02q-`Ahd2))TyqXQ=0fPgegvC$v z@sQ6ZKj&_Dc?JLn0VNUOH;<2bQ04QW554F|Px{jH<R1Cp8YkYa;Q$l?s0cVgDoS4Y z+S~s2LJdF~a1yF#`~Fq=@W(Wcv5evy|M<vHzVesP{N_9V`OuHP^ruh#>RbQ%*w23R zk1-7q#Y!Geh<yKbVG!pI5Ml(57r*+~&;Ir^^90NA2kP^&_xi6__`yhq{`b%S{`>#` z02qJ*IDiCLfChMg2$+BhxPT1UfDR~t!7vT`FkAE>4_DA!pM(GzxPj=#fg0F>Aoziw z6aZJC2V0N;K;T><=z%P_f-We6EeL}z7=tu8gElCGI9P)@ID;FggFg6z9RLHc5E;_( zdq!9)!8d%`w}edCgiiQ`P#A?$czxXGeXt@AlpzqDu!UUMg<klDV914=Pzr>w2}-~N z1QCX6xQ1-lhHm(Va2SVj=!T^*hj1tjlyMK4v3Y#B57S@_4;YAoIEaK;h=zEGh{%A( zAc0(ih4cSlXu&5B&JYaTaD<kKE5AZ$U}A-r*omZ)gv2+6qBx4ASc;~2iquzy!FPp2 zGY_u#im(`qvN(&e2qyC|4b$)rw784B*o(gSi@+F+!Z?h?Sd6{6bI6#C^`Z~cPz=cM zjL;a3(m0LOSdG?rjo6rt+PIC}*p1%!jo=uL;y8}iSPavkJqPm++JO(jR5X3~j_??d zcr^`)SdaF2kNB96`nZ6L*fsAkf%X@W0y&TbS&#;)T7I~X3b~LB*^mx-fc-dISQu3l zS&<fbkr;_d!WW9D*pVLjksuk8&!>v<gM|ZiWhj}FDj7PP*o@@(k}w&QGC7kpS(7#y zj^_V3G^V4D>?n^u`IA8DllUNffcTI`d6Y<*l!Um5{?L<IGm)Mcl~OsCREcb$D3Vy2 zm0G!#PpFEqqK-ismSQ=U07s8Xd6sCImTI|w{n&^il96y3mvT9mbGeaRd6#&ZmwIV@ zBndwgNtb{bn1VT&mSmTEd6<Zqn5Ed4?}LS%MV62mnUWbyLur<4d6}4*nfMryTVs+Z zxssq6nxYvhE_sutd77x1nyR^)-e``g1C>=7o3c5Zw7Du*shGH#o4QGb-M5Ob@|T1e zoWePr#3??8xtqwDoXW|Uy;+iPS)9-rozfYX$GM!=d7X#JnC>GFk~5m#`JGkvO{M?I zn&erY=6RmznT@WgJ*ESk)A^q88K0a~o!D8Q_KB6+**@+mpZwXM{uw{?d7lD0po`g@ ze%X{xIhhK&pbT0y>}Z*q8KDw7q5LR;33@euS(_TVp&S~Uw@IKN8lq9?m8|%mCVHYM zT0Q|9qR-foEoyu(DxzAMpX`H$4SJ(EnxjlJ4f#i*2Dp63z>&r`48uSSMtY<Sc%(-P zh%btOL3(^ox(q?;qxl$tUE`QKnx$H*p!jDDUizhA8m3}8res>CW_qS*>ZL)-3&Fq( zyFd%OKn&6#r$%ZG)^H7Wnx}fYr+nI{c8aIdzzlRsr*m4Uw7?5Wny7BdrosQvsE+!m zkea5FI;oUescFi8OzD>3xv88AV$^_(pc<;8I;x~vs-}9XsEVr6@Tt@AsnlQ&+@KEY zpbqMA4b^a~)esGokO;fltGxQFz8b8+I;_6R3DkhA(SWPCnhV!JtIqnY&bkiV0ISqG zt=3wt=D@0{x~<%bi`3w%-x{vsI<DjzuC3aw&j5`%i8`>^q3-&w@XBn#R|=a@ul9Pc z_?oZ!y084&ul`!EkFW^=y9u073Zak-p+E|pP_KlL25~?IB@hEOPy!T-0WT1-F<=83 z8v`55u^Q{K9NV!X`>`Y&0~A{V7;v%{OR*+f10nmeFFOTnkOnjhWDfsZvow3Ngs`yx z+Os}uub~jMK}!lkTeJylv_ea?q42ZyY75NCiLSDrDLS=OE1yJz1~>o&JfO8)yR}~1 zwP5?TVjH$(JGN%4wPMQyTU!K000n1=11Hb{1fT!~paCBM1Z#EzC-4D#`vEjy15wZd zf%^nc(6&loxKL08g`2pGtGI3JxQzR_kL$KT0Jwr{xlv#PCSU_J@Bt+70iYYYp!>Oc z3j?Klx+h?|rmMGEd$z7ywy>MFUaJ8XpaB{{0Je*}Bv7}zo4Xp&yS@9nG=R3Ti?=xN z2-ENjQfi=$iJ%AhywDrH(mTDf#SPhDz1Vxb+MB)HyS?7qz2N`*z2eKg)G)2<U=OvL z3Wjh7RA2-~AO&1d2a7-nqks+MP`>Lh59hlM??4W;nhn{Y4%uK0)=Lf9P`=HO4bxD- z<$J&l{H+XJz}VXi<S@XoY7Ocz4eCG*&Kkh$FstYr!s>v&`nwMD@WCf+4kx@0=3ox* zAP?`r4cI%w*Gt1PT*Ekg!#ZrkGkn9;P`{%9#MltT%|OIKJjA0=#7P{)L2M4>zzyXa zzS-*xY-ypg<(ZwD#ae7oL^BP#&<nZ{#$r6iWL(B(e8y;e#=T$*x3CP&Y73!I2UB1K zF)##D;0E;D3>b{T(GU&GpbNO*3uSx@gxm|ga0|WQ3xxmt3%`I1hRn#1{0osh$-Mx{ zkbDcckjc343%9Tfv49J_5Xglr3}7q_UtGqxkj7?Q$zXiSt^CSi49llH%d#xXVJykc z5DmT1$9>EUxf%`E(8txl48SbR#GI?u01UqX$cC)Sz2J<`n3JC=I#{^H)_l$5Bz(oN z4CyJ2#So_$d<~@_$2wrgbwIzgdJWgW481T6yAY?v7o^=h&*y2R$ESb9a16tM49h?a z%b<V#9HjnC4A4Lf;kXRzdOBFTr3~HBKUtX%d3?mM3(hbNwwefLpaVJ(zpxO%>KqNn zaHR2k3{+au{r7zKETuwPeEgTv4cL~Q>AciC(=`8G(>6Vj_{Wezs?SE+ti(VFQV;`1 z;0CGC4C-JF%P<VMAkzPA(oU_JRw|JIdDB!~)mDAgvL$>ADbTzi3>sVw<SYe?Fbd83 z$A~(mPo35h8j)A59S;50aLsvIt&ak|3(>H_o4^G^AO&?m3*2C<w7}E=-PCGb*lG#W zT4R#fyx5GLMO_TdsX5Wj+6;1F1UgU$qfo2tY|r%E*`EE`<=B1G96DGSucm$4sEue! zD2mV6)7L-=W>5oCzzNM@tGmDp#TSh-y4(2KeX=68RU6#GO`I#Lea{%AajMRVKm{@2 z2D-ovUK|Ym%-htxl{C6O)!f+Hz1^Q<FYN!>otLA{HHqBIpblUy1XNH5w8{*+V5Fe^ z-tZmY>Uxgs`kcdk-}tRmv=Mx(SP#az+D#awzEIw|a0cj234fi*QCi&$KBLULolu+F z5<cPY%02!-2&P*ErGN(ha1(@}2mA1dobjR9_o4%?4z^(6TtEryPz_7n;4sdWB>I~i z#oac3<Do({wg3aR@CYY>;r;*v(+~$m;1BZ<-s35b#n;9tZs2E-+11bs1})!IUghtd z(Crx+IKJiEO*EVU1Np!WI6w$IfD14{2yvhUMs7KeJ&wh<)J-k~Pj234ZRK`;=iMyL zqy0JZFoALX=YYOTdidr3zzsZp1quI<20;iJ_n<To{i97i(nP8bz~JO$T@CHc(#fFd zhTZ9%j@VB*)mT01q+aR*=@0L)1*Y2p^MD2?km}uZ52KZk3RrxuT?cZ0>B5lDB)#c` z?dia-)@&VH8A{>Ce(beLG~DnAac}}GY!8#c4Ug!Xm_g#t*V@FO&bUqmP~P6U&CSpl z<Ko`i5zZ=D%;o65*ph)0C%_Gpv5A?}#lO&vyub_Ee&8*>)Ofz{{NByKaE^P<=QW=0 z1aHk?Vh(Ze4(z$`m?M1iu8s9>tJ}`v)exuse(@O3n*ToVq;u{C|M8tlG@ugjl+)(e zc<cCH@l&4hEZ_1q>6#?pIeq_rp@ClWHlH<}NApbcpeN0j?p)sIO$8Ls3%(xgMt}7E z$C-(Zj>_2dPXF{!AN5l2FAhJA#J~%^puxE?@%cX8F8}pl50fx|Fzt%$W`FjmP2v;H z473^wTo407-{SB*?sUJKRruRYdGmU|_q&uCm5HcvYSHRI3x;6Xaxe<^Pz{JW(n#O< zjt}ZsQ}$>-`IIl4mXYK7K)~r7$5fyLQeX%aTn(@=-F093x;f)fYv1|3`mBGE{*Vf6 za0XLQ&U_6F<}eLXPWq<5`-*wp>SLoi&-cPV{7*v~L&*hFa0Zxd)a$GZxs42tAN|s= ze~^!%s^9w9pZ!a<56=IJr?&75y3hOKkDI=qKESR0=%4=evpvEW3r6be;~)RIS^nr# z+LeF*_&=KfF8}=B`v5V`-#~%|4IV5g58*<F4IMs&7*XOxiWMzh#F$azMvfgRPCK?t z<VcbwO`b%VQsqjPEnU8Z8B^v=nl){zJSK4CJAe50{RA3R=uo0XjUGjsROwQtO`Sf4 z8dd64s#UE%#piEYGOk^{egzv=>{zm8&7MV@R_$80ZQZ_wTh`dLeLklu%$Ha1UcP<( z{skOZ@L<A)4If6FSn*=UjU7LRyjW|<o0TnJ#++I6X3jHn`g<(zCqB}pO`k@cTJ>ty ztzEx{9b5Kn+O_{}-^QI=_ioxhx5fn?T=;O}#f=|#J9jj0dHU+r(-&R(bn4ZuU&o$Z z`*!Z#y?+NEUi^6S<;|Z*4<7ooV#wUThaX@5eERk6-^ZU{|9<}c{r?9rKmqM5W*X<r z!z&+;7G$tN2OoqmLJ24INWp1_=`2GHH{`HG4`mugAO$m02s8>$L@`AbS7fopiY%n; zLm6kJu|^wN`fNmu6oM{2AAbZgNFj$LvPdJ3d`=(s24u2HC!d5eN-3uVut4W}952Dh zw&b!)FTVscOfknKGq1^RL^Dk_*UT(O$FwXnPC4hKvraqjOzccH_vEurKSgr0F}z$P zv`|A2MKu4>gUkf!Pe&hxv_m&Zyz)6qFU2%dO*iGVQ%^qyHB?bYCACyjPenCVRaa%z zR3(2wrWjdgrL|UDZ^boNU3cZRS6_bxHdtYYCAL^&agEi$RTEUSS!bVxHd={bjI>&7 zudOLZjhL0TTW`Mwm&Hc0CAVC2N&0Lfg^pymU3cGwH(q&x)T%uy@5MJ?efQ<JzXJU^ zPa)n0Cb(dO4@Nj)g%@VnG_8<>IAVz>rnus^l+%sda5v_-V~?lR3d3_pCK*y~N$lw= zl~-oDWtU%uIcAw>2I^spZ^k)iop(k{xvJpAGiafQCc0>&`3kvYrI%(iM9|)R`e>=A zrn>)Xs}IwYX|1>ZFi^%c{y1#0$NrXDuFpoBvy*qMt6{g_hC6P#=ce1XeWo#nXTA64 zyKmw!&aJst2PeF6!w*M1am5#B{L)wZg*<Y}C#PILE0^^r$$2;DymQY#2YtJG>aDzV z(@#eo%73xU65!BZhdp-LXE%@Z)NjW<cir9lH(-Bg20nP<hbO*x<Dv4&X1|wbzIo@l zn(KGFq5}GA>#xT?`#G~tyL<0x@_MoAwI{!P^Up6#D_@3TzkT=Lhd+M#=cm7Z`|rm; zfBpC8zkmP#2O#}?AtI>hh-?Q$U;+*G4s$fnfe(aW1SL2@3Rcj97sOx&HMl_zcF_NW z9|U0tFUS*hxsG-xL}3b5_&Ei((1jC157=HfLmJlbMd-s}4z0%#9yQK~KLlbBg*Zea z7SV`DL}C(^NVpOi(1uThVict~MJhI^hfBm_7PYuVE_Tt2Uj$<qPc^72meGu7L}MCh zNJcfb(T#6}V;ox~n!44|j(5ak9`(3KKK9X%e?%CMRyasP7SfQ1L}VfrDK8ny(UFgY zWF#e-ke&e2l9$9}CN;T9PIl6h%*mV>ML9}RmeQ1`L}e<6*uzD((v`1-Wh`Ym%Xf`W zhquIKE_Jy}UiNZKgYsoCg*i-O7Sov7qvI!)xlCp@)0xkN<}-nLOlnrsn%DotW;O>S zNLqH&o8JUyIK{a_flcpt=R{{Z)wxb~w$q*Ogl9ZeCJ$BC)1LRlXFm10&s9EclK%u~ zKm{7bMh?`V2SsQ?pJhvJHq@aHg=j>r#!!h?)S?%~Xhy}CGO9$=qaSr!JV82Ak`nAH zbgYU(Rob9;uGFO+v5LSt`VN}b)TTGZX-;*zQ=azJr#}U1P=z{Fq88PtM@8yS=kZQ? zB-N=;g=$o#I#sGx6{({6nLjO}AbA|at6v3cSj9S4vX<4XXGLpT)w));w$-g~g=<{p zidJ8k!$gO&&@kq@SHAYuuYUz>U<C_Tr<Kr5JNjN?6$_JN*wu+HGTZ-RB|F)Xq-$Fy z9FITbu{+Lo*0cTkg<W4~yU&)^w5R<~?+{d}Q)xC<u{u_4WjkBi*4DPS#ci;V5n9$F zQ7f>@ZE%G<T;dkjxWGzQZ%s8##rR_$l!Y#38yhvEaWA^pMO*k3Lr+!dW3#9QZ+OKk zAKqe-wBto@dO3SJRZ)~Mn#FE>yEhES8qK=$#V^UUn;7>F#<}?g@Y3i@-JvBdzy~hZ zei2imZ6Vmf<Qni}33Z_dSJ-4C+SZlEGrI4p*TWx9U3oz_x+Q_w#3zQ_FO-EK%!<dg zD28#2?-kn2h3>pE#&M2QD-ho~2EG;s@}DAX-*E-m$ZAsXVfz0om>(b6$!HpK(G2`# zD$6LzhG8&?s=Q?xMOaZ3=5m-bWLcD{OU!5PjF%HtWHh(=CS=|b58XWH%BUGpY^HOb zT>|HeC}cUk(d_dCJ!nE(EEwddBp&ynm0%Rw(T|4oTY^ECw%w+n5K+)`^}Okq*tt-V z<#eb|vbH{J^+in<b*f9^X+nWo)v4yQMXuP|4(r&~x6V&_mw01b_uAL1Yp<y(!qrz7 zTO_Q8?0t=`XHv_$l6ApKpd&qPYFGO!%Q!Sg(McNRS=-y+9yH+Ya@Vc?ciE~&c8l_Q zZc)d&B1;a8x!E1+C|4KH^PcmS3nSC0WJMm}26(`ihi(5voAaDmnMR`pzHo-$3}aLg zB&uHQYl>4`*GlAd#WfydV5e$b<#F!DMXqBJgYLH@M>&dB++y*tQaq!ZN6KYxVj8oK zb0oIc%yll_%dz;dea1Jv9g8Se2ffYirU+i@!5CB<ea`hR@V%Wb=A1w#%ZQyiozv|i zFlQajNS_G5ktgkjm)-2h$+p3RH;|tU#6n$J1~24J3}Or;86@F~NY1`@zJJAM5Z89J z|J`@O7alFkFh;@8$@WESr5Da{Ml{qh`D;x68PXs|FnD2ilz2t&a9@VuMK9>+W!1-; z_IjJ4UMG6c<2hO3LJVq9gBTcL3RF0Q8wgQ~Qe6L|^6Iz-=5etLUwAe3_|-RI1V<j| z#C+$^4{ymmH#%wTA{fCK1tsc`2rh6z3OX1<4X8i`IV>U+(fGYJK(Y&3=oR|!r&7<$ zGiy^#9RBy;UCnp>8)!ts8rP@>;4_D8poLLLggW2?BLF`k-~uz?1WuTS-<yVK_yzX+ zg`C5`4BQVZQ7%#`r`sUA(Hje6Fb1zm2F;_p6jZ?#WI+|&1!CX@Vn_zCBEcHW8xb@P zf=e{H$qUlZ3r4FfV%V)==!Ic`yx&uYX2?DS9D*Ux0V?1EHsFL(pauyHy%=n?VhBAP z<U*VQ98gjf%{s0z#1*fSyIr`2TX;bjd<Oq&poVFn25SJmIjp=oq{BP3!#q?6^>afw zgu^#{!xl_IUP!}2G{i#O1-VniMPx*|Bg5f>5B<Zq5~B}Up@mDNg<fEW{{ucHTm(0e z0w;_C+#>`|fCXldz-fR%HI%zyz(5Uzzm7u{mvgasc!mkY#aq<HT;#=F^u=BT#$Oc1 zU?j$2e1>NjiDSG)-<!O306uH5hFsW$P?$zakb~TF18merH^@eA+(vHf#%w$TL*RsI z+yrx^#%Y`eXk^EBv<7Ev#>taMd1OZ4v&VX@#|bpXV&unt^v8bW$4E4X12H*D%#UR_ z1{jP%P5ixU$c9m<15k9rC*%S-D98VLREG%^J~Z6CVSvS*Q?2<UusnH(QkX)M<h_$r z$&_SClyu3Je94xC$(fYNnvBT@G|4H<g<P-&o=nL)r~@+y0wJ&g*^|B5n>`yag7IU@ zrgX}ugi0zff}=#rs-!*I!vGyHN(`t08xVpZ7)r4G%C8(sIRHwtJWHUg1GHSrI$%kf zjLEo!%ek~kx|GY7jFHs~nklOZ7$gQ-_ytbn25V5lL^uN}FoN(C0xB?rI(URq$OUEu zKHtMUx??|HNJPE*s^d!&rwNUbJdDv<1|A^I(lpJ}M9tJx&DCVh)<jJlzyZ=Mf+Bzd z9)N)lH~|GvfDRY|AfN#acme+n(0~ef0T`fx58#0!0D{>p0wthL=cLUgm`x~v&gh)Z z>ZH!+WKQMePUiGY;{;C{paB?w0TUnr;UoYJIM4JvPvLY=;B?R6jL!^sf!K7-`^3-u z)KAjHfg<RIk<d##@rP&71z#}G14YmTRnP<Ng$C^fG=zl+g#}xPhHAJ5ZlH!{NCoXX zOa+`hA&`P8kb^`p1jvj`X0(REWQJ&X250C6UigJyFwh1)&_lG*8^zHa)zKa0(H_Oo z1qIR|71ALk(jqm|1dWm8+or%<j(xZX(rBBZ$clMz!)%y_Y^c&J%~C9-1}o)KFWu5G z?NTir(=R1cFfG$9{X_pi<OX|~yk&R<H=u%0Gy*AbgF1-NY?#ad1imZHNNJdcKn2u3 zw1z(X!*wjwH%wGS?L$L-!$1|(K!t`Yl?FY{hDx0Va<I}loJV>LKt8PoQ2kVO;L{6* zLo`LzGgVbHWmPdv)mBZ@SWQ)G@QSo+87Pg?(uh(i-3JCDhX(ppa|qU91=eDPpkSpS za^MDTXrOhd2YZ0ldU%IXXodqkOz#^4DUbs1lLJHO)=>c0W>D5;<%V@IR|i^$cUT8| zNY{2%S9N9Ab&v;homY6JS94|8cXiiwy;pf{*La;*f7Mrg&DVV`*n#C&bq&}EB35BF z)`o@Hhm}}|rP%+7t=NgR*oHL+yn!CNP&=n!uDvJ-1^Elj8U|tbh4w*Nl}%apSy`8D z*^`agmz7zTwON>D*%%dumGy;0+(c5{1UZlbA<zLSID<u?gl5oF;Dd%_z=aEB24-;4 zlik^tjnS)3Sy^EpTxp*ebw#a}m6#m{uYI2y3<hJ^*_|~87(51N_yu721!e$-xs6&> z1ctf=hH7|*yS;|HErz;VpJKS$n#I||CEUZM*~FdM#l2a?Wn7T~l=|9|yE-f<0t|mh z10}cu&E?$9_1w+{-Om->&?Vi?Rf5yi+$*?(EnwZ&1xp$*f#56v4Jd#DAb{IFfetu< z5r6^Fy#oK`T+ZMX-tFwp;+@UqJYM2eUgYIY<OKrZ4PM}t-shcO>K$I|jo#AL-qGdW z?e*U71>f)0-bZK@B^8XTBZ$#KgGb<pE#QRASqOQE6!##8T__OXD+Qqyf^4mWQFsP! zct%|i249H57)cxWSO)lrTFKhFi!c*CIDr#@0e^S|G~fq9NCWs?6bjaZ4))*=2H_AE z;Sna`64rw_&;viv146(AJ-`GOeqk0~;TZ<uIH-duXu=%U;UT~P;p|}z_~9V-;UNZM zA{OEzM&cUS;U#9`CU)W+W&=Y&VH2j}Dz@S)#^Mi#z>oktiJ-;k7#&+Ef-OJ;OQ{YH z>n#6-qy=J-!)bVgGuU4#=-+8r2LL37UbqEb2nm!E35y#@n=_BmDFqmq22MBuZfM^v zPy$@2u`|{Oa)snbmgGsM<Vv38Y*<!I9!zc+S1yI*D(zBC7UfJ{R&_83b4BG;jz@JM zhskSYR(9oBhUHm)<yw|ya=_(tP32wY<zDt>b1heAwB%tX=3+MHV;*Kqeg=D49R#T~ z)7S@v*n|@p2%kueXuiRmL5Z)DJ81wwN-zT*FoH9nglU+(Y9Iz-NCsjszAgN`&$}6T z2E80~=ab00Ei}8dBba;e2Tqt^bAW+t7>E;i-+OpwXr2aLaL|Qj=!SOahlc2d7KZ;} z2nJUaTlWzL2VEbEzP{^gACKPIVIagC^@Y6AytxYox=U%l%siEL>5lGbTF|_drfJRd z(VMo>7u5ypo9Op}>7NGbpcd+(ChDR#YM^GHv+as6w6udR4S&dn-_-*rRgGv~9<Qq3 zV&H~r2n9GE=TyiBJH`dNLr8h<!n4jheI6Ko9^`wNh7+)>H~@kzD7dQr4YUpp8N_S8 zVQSm(v!USUEzkpUD1w3}3eC!9ogs<(mBVJx0|j)0QK&o@jlp|vXS3dG5wum6@d<fA zg9z?`dUymSc!xMZ11B|#yUy&@_O`zpH=@W2MAIzA8;TH=7?bcS$fLW;qlEt{DB7e2 zz(geLkzj4s-fWfOXLI0$M>v6W#VT%qw!>EK;->CLb8V^kK-B07e%`^;u<eNftIzYj zMUYB2;DvXvhG-yb1Fr7XPQ32k4QS&Bb2#LIxCee_jc#l2{eGV4$ryrkWDT<p=#Yn3 z+!v8}K>)0S#jJzMV+LKIyN{eX>HCrAFb6{5CP0>s^)PS=_i%mTKxfVktDYEiIffS` zRXC;sN~mLz9&XI$Z@gCPf~gC(i;cU9@f>fSzOD^;yIlG8kh^P-6lcIu0KQvbX9MQU zND0s_nFp+qx+Om{^9_u0>bLJMj>RU1YlsFo<^m(HhBa<y6V!3)KJNc*)9*4@^PKT- zz{6F+gP6tM1>ak6GXQf~AO>bY$YWUZ_CE82OY=S#bcuPmyXe4CvA-#)-vC^M#T*50 zs0Jke@C>}TB&wGLp7cz=mt|ltk7GIT5JM{Y%K+?cBcKFzV1`~0LQTKFntL6CWc65g zk`SN2Ll+hAQgmX7%uz6d7+8co#Dxx*^$GvuB~lV$ANFMDk4~RO(8L-b#|*m5g(Q@N z7^nksu!g5CYbh5n$+b5n=k_TlAVF#5mrHa3p*vf!26Hfk7&rrLActNMh6q=7=vxK~ zzqyR7_kF*QW){gXEN~|ADp=u$Qdr7SActhIg=JWEet*7Vuq*%bf^~<d`1z2<F>*T+ z0e8ka29f6SGl+piActsJcw$K4aNn8+7MG1jc?;{}h!C7q@h)V~4`R3lIu`;n!1i1) zc}%bPoxAs9SE6J8`J$H(X2<y4K<vXSiTag1N*KRKU-*(3^r}C>y3V6OxB9IY4*w3E zUBwC#KZ`y_25C=1GZ2DAFo$Ts1*+$ILI3mP@d=K7`??Q~LdWiM4-XEbdHG0pYaoYe zcY|!mc3_x6qi^+yA2EGLe17+L^7uINIQRPadv=cjE`aw}_|JxKeCWe>&N;cxFZz}9 z9i^9t#0HDc(*<TwZYfytcff^`KY8M|`#zuXJ7Toj*M0xDm^7!R4IeLA)JutDcsz3m z1u5|Loo9HGaF3Svo+h^wWpn-qqjJE=?%Kd|y)%YeFy~x=<3(tOYsiJ=M+TGFecQ)+ zJkko(KmYb0L66Oickq4LuxgWl!Co-uP>4M<Xa;ovh+M>oEi1Sz8N!4L7cy+<@FB#A z5+_ouXz?P(j2bsS3`Wi$zK|kEk}PTRBubO}rg3cP@+HieGH24HX>8iQlsZMq^OrB5 zzo0^g5+w>$-m+uIiWQ?pESfrMkEH03GisecVoQ%DRqFLC*sx;9k}YfYEZVec*RpNv z_AT79%Z8crS@bU6yn6KloyIjT;J|_h6E1A{Fya5C)9miu+jAe}$dV^h&goCytzEm8 zQM-1H78@N#3^gNH%@{$0HCMB4?fNxrh8{syu5J4^Zp!{x#_sL=H}K#ZZ{{xEGi33| zLHY6fX^)$_Yqmn25u$_3sBF}t^-66}weaxb$CHmZ8(;GD>L=sdUH(1%`0^hTUthWB z&;0uL>#tXj9zFH=lT8|2SU1EOi9ExNGrAN*3^EZS^Bsj1T6iIb8EUv8haGzOA&4Q0 zI3kH9&Q%wGDXO?4i!JuWm5DLRI3tZU+IS<5A|A7ti!S2lQ;+%qXiq)OxZwsRv}6+< zF1HLM;e<I#IVF`<T6yJnbO9M8mtF3++c5uFia92kWt!RHFpF*JWq$JLQ;$Az$~h;U zbpmD2HPJ28i&F(b`6r-(3OXpEg&KM&qKPWHD5H%!`Y5D>{!$m5by|8UrkP?Y;55ZV z`YEWPiaIK(rJCw!F^g5IX{J3jrWbSa;4%<G1u1nVuDR;ED~VbH^(wHz=H(Z!#Tt7o zvIgxaY+m@Wso!NV7Nk(J)mnS)jl*!W=Cj?dxSO=tiaRd3Auj7}o7}P)ZMp5b`)-B4 zqB}2t;KF+^zSy2Sue07>mM_2o8!Iop1-~dT!U>PLFS_r5v{Oo#88aWn6<ZA4c@S&7 zF-p4yb1}#vi~LeBIB|SZzumH{Fw6ff=SZ-@^MdIz%{7~trn+qQ#Hyy3o%%D-K?^-J z(T+~~CeKMLjp=Tl7X38TQA<7bp{e?_^rb&CE7Vaod;Rr?$Dp`1*{>c9Hri=_cW&82 zx#=I=amzh7-1^KzHQssay*H`L98EXifeSu3-THLOH{yvazPN;`zDfAt^5k?fN&Cn% zGUl0UZr(?fd%p2Xn~Od==EQwIQp(S+tTyXli=A`K>k`{K?KLy(ZR+bHRXgu4!yLQH zv-duHz_)knYTH4{^VKlT55v6k&wCZU^h!k!*7eh8Z~gYiP!E0c;D@ih^Ws<Uefi>> zzdrfrqdz|P>BkTM`}BAJef$6C<3B(4^4G8b{l4dmZT%{F1|-TfeDOc(F|dISd>{lP zD8UI*u!0u6AO<t2!3}b7g2(WMnhf~1Rbeeo^?1iS)`7wmvap3Nd?5^DD8m`ju!c6g zAr5n>!yWRlhdz|yI_8125)v_K@>mBFlc>ZcGO>wHd?FO1D8(sKv5Ho_A{Mi##VvAC zit->~5p%b$1Cp_fW;`Pr)2PNZ1`BuvV<Q~nD91U{v5sw|*KzE_p40KMkAD0kAOk7L zK@xH&dOT!$3aQ9NGP045eB>YzDVetwv67a&BqlSd$xU*ylb-w}C_^dAQIfKhraUDo zE#;<Eva*$~d?hSnDa-#^(z2GeyyYhID9K&&vX{R6B`||2%wZC<n8rLNGLxyyWiqpw zlyR0Fqbbd4QnQ-Yye2lYsm*P2la62X4=%$g&T*2noaQ_yI@4K8Xm+!m?tCXa<0;R1 z(zBlP6r&sSsn31#v!DL_CqM%#(18-Ppawl?KDB1gg)+3E4t*#@BP!7~_5_UTyeLL9 zs?m*dw4)vkBV#5i(vgz1q$WKnO4TSiNV2r0E`2FXV=B{`(zK>Fy(vyN_KuuPE~h^I zDNutd)S(i!s75`iN$`o#r82dtPJJp=qbk*@Qnji+N-0*es@1J>wX5-Dr&q%&*0GYc ztY#g`2qCA|wX*-Ut!{lQT;nR&xze?+cD*ZJ^Qzaq^0lvi{VQMt8#y4IwXlXgEMgN2 z&z+*jnT~xdWFsrt$x^nmmc1-yGn*TwTD7yD{VZrhE85YLwzT?DsA5yA+SRhQwPdU4 zM`J77+0wSQw!Lj8M~K_q^0v3W{Vi~1d7Q=`5+C<CE^?Er+~qR2xz2qqbfe2$|Aa&y z_mBrYu&dqdUN^hm-7a{)E8g&ucf8y!FM7?JUhv{0K*tS<bmJ@E`98NKmqpJ!<e}gF z^0&YK{V#w6EZ_kXxWEQJFoF}T-~}_d!4CfKJu1gb&blb1t|cjRvI-QZTKK{q#%963 zY0;z!=pFy1I5CP-tl|~3xWz7haf&%n3Qova#wSiiDRQCXTvS8Hw#Y>(V4>m~AF0Sj zc7qT~U;`yHdC5+0GL)Yz<tS763`f2)mb0woBcH(#qp-1!VJzk`lex?@F2xdsIAT`% z#~*}<1DxY5=Q-24&UU^tp6kqpIHVyCduD?k_Dl#p5Sq}KpmU!S&F4Jh00%H|G^8Ib z=}1$0(w43?rYG&_BILQ#p8hnbLoMn$r@<HVFb5L9dC4DjOF+*60<2>#>mtm$*084a ztz(UAAmF;!vi>y>fDmk67opfnSb`FupadSM00uO800}Ix00mH60Ufw@2Vl@^T9=^P z-v0mg3pVhA5{R4J<1RP4&#i8Avpe1GUbnYj5Q1@kyWaAqx4q|G?-Ja*+cZ#uu6dnn zffL-<1s}M<6OQnOAH3nTR)Q|(a*SRO@TvaL0~#`}@r`r5;~xJw$V1NYG^F7Teu%>x zN{$94Twx0|c!3E>FaZ)kKm!CQ0M0c~0}R+;=QS{a89<%}krTb>Mn}WYkFNBkGrj3b zCpj86@r>tz5O!UnaE0r^4Resg99;K0Ik?evu5+X8WEZ<R%D(lmlYQ)LN4wh9o{h32 z(H?fUM>VVw4N6c#4rbtj5u_0KAxOauXW&8|7NPj;NaGpP*t*!!u8zr9WAf^#yygEh zuldb$zVn{vJmxK5dCZ4C^Pw+2<vG8O$cG*7U3Y!jUoZRE(;oJ=pZ)D?kNej{K1&tn z@H@ON{NWS7_{Kjz@*$u0vXi6h@*tAkJ;V1!n86KHkOKAte}?TZA`z7EJ~^<F4e`Ij z9w;<F3df%I;j16{?tef0hrf>a)4%@qzd!!pKla%f?^#%H(Pi|4FAN|77GMDiLoXyC z0w$m@ET8}yAOZG*F2Di>?t(KggEd&gHB^H$Y{Db>oe&s-4#a?H6rLL_!k1-7Gh{<H z<jFQ%Lo`$aG#CRiaK$hTU;-wfE<{5#07Ep`LNzdh4*~-)2%!-Yp%4}!5-$It5;kEH zJ|PoA;Sg2>5%wSz2B8%)Lp9g}Fl-?eT451dArSiD7Iq;K{=zTZLJm401h%0Yz9AgO zp&SZ>FbrUppoqmyLoeK*9QL6f4&W_NU@ts_HAF`>q{0W90Tt)~BN~AbaKVvK0w<^- z3+9PuRKqn`!wx2cF&M)H27@l>LNEjaFR0-ko+2uyqAIQ;E4CskN=yIgOiz7|<xEUV zTnI7n0xu*3XISDjz``c@9aY4D5fGjmc;6^ALo-aCXIuj_Oan6ngD{L@FbqRNc*j9B zgjaaVG7v*D6vHtrge{IELXaaTmLoczqdJ<SEi#2Qeq%8-PcjgMGd%y#Fc3pM9s@B* zPxBaqI}XJ2KnOBCk1di8=RC|!xra<lOF~e{Fz^B~JVOg+A}1Jv85jWxYTqJILNZ!j zo>&7kO5-T<f>R8HH}YaOD#XWpj6t@fO_)p{4cF;h#zcGvwPYhQJP0rB!a#HeGupx< z)PWgDfe_SyF`{60L`QTuV=~mENrp*5x};RXN5&*1Z@dIU`pJY015Xy><)wllaKR$# zK;b3AC`bc2ETuItLp0#RFPP*>PNiIm$4wyQ=~UF3v5J7m!=p6ME<mI-<Vkc)hfq>M z3=DxWdf($Mr87FigUpJwFpgwSCei%Dw&Z0haf;KBN-^*xGjRXI295$75G7e2<0wFf zXE4Jr=)zNKC1t)QY<`N>U?$JtWfARVq9}!CI7J3BV=g3u98duj7^M`P0SXcWbQmHr z{KBjZgi^#NbVjGB_zk7dl4gzyG4LccL`NzR0%;=NC_G+j>OymRg>;@LdLqhft{P#H z%~6EQcc7tW3<L%;V>MLd8I0v4A_*;|C1^$iGB9UTU?cGqsEqiEHuXiAn8-2g<TK<6 zGi*Y2kYyc&Cum*+FZhBr8YqX32+kZ3STRdI@Pn-E0xdu!L_UK=g68E_Ln#<SaEjm% z7=dw)0xhV+g(kx;+=7!3Xovo2iD*lQRnyswNOpeaHT?hP6zBkgBmy;%gJ<l*DEcUn zR%wQ?P4b{turLQb_=7ztrDuF)cM^hFVkBZB9!FAxIe3OO{6Ydcr$I!BmCmV%AZRuf zsfQ#3S3amZz=9r#pcK?WDx~E#py88537sbDg<xshq*YrDi9IyK-{q$e#6VG!W#QEU zM@|Ew!eBAHB`$1cdX6fonhJG3j$jc^(<Dk~?gBGJM=sPs5RhdeG=pbAgD&u7sqQMT zDvIOK6<)ekfY<{+WJC2CC*O?%HCO{`Mn^OhLuTybg7zx4R%@g9&1I&ls!qc%7)o{q zgET~kXkw%kECO=EU@)AdwXQ3>{=zh%YFs_WdMy73KLo{>GN#_e<E%6%Hr`4~&LzMG ztV5iKWho>|*2-M$Brz1CHG~3^UB@CU<25)#FYp3<f``Cn?B>+RF6kB#?WJ4Zqe-$W z$(HP+Sf)SF<|%PXw@S!E@<Pc_ULvT$5a_@ePy)lYWono#&r++q4pAkAsIYX6q84qg z2x$RTQ=Ie#EM#XyP6Oqof*cSff>1&WR)f=0snKpNhb#+-rmV_dih$fr&z7y(8VbsW zZ7IPCGkS(CaKhADN1%?vPo}GDo-N*{=XzR_t0e8#><-rk?v>c7H7%__2xWDc>D)r? z<<UYc9ID_(ZrFrSmbT~C5Uu29Znh9m;hO&tP}G5ydEYWd2Qw4{F3gJNrf!EYYT2w5 zAJwA9#;)vQL{-)lP}rw6bjLo1<Lvfs@0v~@ISg^xM|)h3?;bDmCIrD!R(t4SL3l^< zMsL7!tR(#(i>!|7X0M0hA%_W%_I|I2#G;qT<mb?&^q#NA)^1H1Ec&+ZR01y_32htw z3;5QrhY;>H;i>)ZZ-ub#YXybhG7I4HF9ACw=icee6tDu%1&@f3<uVKAE^q-OZGzg1 z1QW3T{;faklKHx?2e;%hEH7nw%m<h7=#)$^G1luEuL-v>=7ezP;8f_iFb#(c{NAP2 z1qt?Eu>JndQduw$+pqX`iNkQPJVgIx4JWaDi11{wuM$6Tc~CDR?TjV)Ox|8G-u{g( z9S#<EvB^3PCJ8Sebubi{v3S6+U9Rs{nlT###|?iD`Fai+w=o^ZhWgUfZXj_T?{Q7M zvFF4w<;*c35Asah@k}`}At$m+_%Y?IQWf*17e_M5rfn^)sw7`>uYxgq&XpBovL}~n z+G^|I7>=lZvMEF7ug;bH0t-;gLl6@%{#uj%zH;_vumEqcBnh%2@3KZPv1B1KF9&l) z)a8VwaUip>Feh_G7_v;wurfb$L@@HnSnszCFfD(t4<l3pU$gcOF_$1umR>A3Yi=xG zllP9Z=6bCIBL`(52Rpa3#6bVEJa<Ir4AV$V4nEfgdaUt0_cJG&OvmCfBE_>m7ql<; zQb-8J@ZttA7ql`HbI0cMWZVN}yfb@Pjzb%CJp)sF_(Su}13p{yMNfksXS6VzPC%Q) zJ@`Wrl)^r20U`LqJeY(oo3t=9b06(P9Gn18UmP0v!zL(!OrL}^+w?=jWc=ogfWW{e z<O2}IflQ~!4x@ACW;417NGZU;JJ`Yr)I%BwH6h?YR7>?aQ+4EebC76h%K8IS`-2kb zK|ahwQADs=SM}JKk$`Xl4EO^#oPa;X!4>$!BZ#$J<3(B5HP@<h<u0^wvGpVH!&A#N zJR`GFC-Xr|(n@EwJox{DU&p}{xEWzrM)OwoGuNd^uZJ#4MrQLg0>rfBut!akb|POk zA~jYToWKZlfIOIk5}ZH+-~fr%MnlW?AWQKfDHUJ)0}nv;JV>=QBevjLwam=JE^xvL ztb;$4A0g~@bCdOgLU(lY2*1FNKdi&h6#*xttaF36UFWdM{E9i8z_vWX7F<CZs5e=Q zGkYg0TK5Pz55-Z$!4{;qfZ)Y*?|0Esa2g%OBgg|k&^KHUsZbm?g3qa9H!9fHNr4B& zn(bvNpE8J3CMAE;h;q14fRm+MXNa%(WbSRyUJa(q!#rSSC$qSXD-OzzQl->`jQ0!| z-#C!#jn!b%Dx3ce{Z{zamNPZYGLl=VEei{)sm$^;xzS2@L2WaYTex_mi=)1kK0tDi zhdJJavM2`*DT_IpM@=frm0Hj5foD08gxz&elyTQL@FjMM4HiULIs^#?mynL7yOHij z5ou{zx>=Aem+q1-=~9qRNu@<el~Ufl@0oYr=Z|OR{eNe6=Gx!2b6w}0@8@t|3G#{N zdhSQG{v;s#k-XTR_EGeyj>x-vlX-W?&Kydo6tDT|1{AdxoF0fh$@wi?^n2iB&Y$v? ziug6-td9T-k+iKC6Tz!r{Z$!Ze%Tq<Qy9N2>d#3zVpTaGvq#cMsi_qMI#^#^mr_5i zIp$L}eD%?Q!nH-LKIdcc#r5L~-+HD_mrBwAiy8Ysk@wO!g^*63ABvx3JDVTHcJ_;G z%qY4K`PAk#)CkN<y$Nt95Ui_u87q9#To+L2<lbO<$KN^9iM>61_$f{OllTWPX=Pc* zs&>GKyMXZVQtq&qX7eJw-)=sf2dq_J_ch*B4WuFTI{fLy+RxqF9_h)x_8-dNE7x+* z@ASh?R)mHj;89(9!frc-z9fJB2Oiwon{afs-gb0~D5J}Ra{`Yq`^{h6!+w+a0qFpJ z8qc|rIA(syxGpi>sQJb+ZHhxO%0yHqt!sAi^Gxfgo42_AD~Yxz9d=JU78)Czi3A(p zc8u2rBpUJ$Wc+O;yJElZUR)N{`bH9JdCL!NUG1!Q|4#n2YBXOfX!_1VPo;a~(ckoM zi2;U7sbv2)m_DFLK71|Gm~V_8slCk*?_6OLA0of&eB4LUYVoi6?s11>!fstxUx3v6 z&YRtv&I9RymZ%Th$vR)9gTG(;2~M{keHnjCq*mXb)=?+*JtwUEQD9C<_i@hkK+pWT zTJxige@6sTdZJS2Uo^Lv$i7(~Pbo=HAcFp|O8$PNzFnt0*dytxeY+;dM;mun8W42# z$bE$A^-1fqod8n3ap}K{J%2Z(|LyhsJC?rtBaNcGCxWq(2_qtZsNaUMmWv`|QA~|K zq85Jh3+XV|mTaq(#3X*0V*tsLf6Jj$s^6Ysua@zIJUzFR%x)t7jCWzS^{u1UJE`wi zZ=>R!bc&RcA3p0yb=E7>Do{)lOMCvT%CJF<$3f?APpi(dFA_-SWoOXnI9-a1<-ato z8Y(rX6sIne?tFc^J0D=U&foI}kBCYl)6IGyik!osE7RR}B#A{SJ>EA{^v%_8hlQ@J z^L6Kuhf!3L*<Q}GWjb<FRIQ$lxtXTNLywP*UVdqH-&^R;!R7mV&_vWyxxVh-Mv^)H zbdP5!EHxA;^~CwD)Z2e-a9sS57x4OcBkl<u)t`2+5C49b8201`1^l{PAIgw^7aVl+ z=X7te=iM9Jh#wwAyBCk-F{a0FRZY7ONTaXKNWc=W-A}?*J=G5er<V2MLXeXKWHJz) zL2{MH(}VYP)OCjL8@o&oQCr9B3{MEI*2@IC-Hq#vF!&u!k1(Mjx}z*Hk7q_7B&+L= zv1ifG409Bi)sJyiRL^{T)G)65iK|E*&XLm#(HrL*dptWXFs-gP@pRc`c0zb7UhlK$ zLG|os@zZLeGM=lW*-2?UsQ#1;3D4Y=9Jz+R4x{C#k!dBC1pOHmu9~?SHNFY`Sq;%2 zbF*49&}VZxDm?RZdO8}<=ARkAoS!%3cuBcn>|8UyVCp{cY|-5B$NZw@tDu*|)-gN_ zOSZ`x2FvzYFBgnyB7zK7oGWS;R$eqr7<_TrDR8cR)dw|PbsytdT=ksRFkJIqez~~z zdMm+j-S41gaXsMAk?uy&)sMxEH+V3kO*F|J@6u)%xu(%p1dZ#`7VxQ={?{0;+NG~? ze4mZJCGZV9GbPHvjJK0jc$c@|>I}PU1v0uW?_^jf8t-N~*DmkoxVs`aULF5f-g}3J znd}$D@UH9^C2MA{IkmoAIVdYgG&!uOu+TBEYWQsOy{7%=%J;fHnCU#MiucP=<Fuyf zkLH>W@jqI(5>0=$AC&s+q@I2@J?_5x`Q<pib4dB1kL1bf$pE>Q+366Cu<+L&mL#*Y zF|NAX;}M=ov-1hj<5kZ`$N$VOrd6J-d3~s(GW|7g{A%sjqIJ?=!&2$gwclUbeL9U- z{f>hSDSGr<e{RLJ#yOV6Y32X)*86k8>WRHevba8|s9V4O-Y{u#^P~NE{pPrj%<}eh zY$G`TQ~mF~ytCz38-M?7C0YKv8hb+&q{C;ZTW)oEyn#D{2oxR+69N?6#3Ro{0eLZK zsMjU|ixbKMGr)BJd_>TfTn6fj31hg}B$7eM5}n!5GQH3}7u!klD~^od@!A4gBjo0d z9=@O^On|s&$}#-JM8z0S{FS}m!A8PPqagT|JULUIoi{l~!|Ut40)zsWW^(Marmy!K zGKV-oVWCvHkyL#MMZU!3czeNbG!0Ji6q?SC<}8NVyIWMEpOX{4o4zqry^pud{N}6p zK#eaQtt10W!9)la>!ssSw_{(}-}K)RkxwI3R5Vjk(wgk<XY>t`t{f#>c5QRW(5UJp z^2a{E&FsO?cvwK6l2+rj^Jw|KQua29IyD=~WA`jI^Pef4v1WQF<M&ewPEs<51a}$i z4-}<W&N3&wb_MDRmA$7m#TpN`o;GA@yv#4<@6e<2c5TyePkfuZ(*=7WA1<p&!k)Y9 zwI{xH(C@l%B5>NYCwWSf#gxMRMr9>RLYYPz4NJv3%-Ie7=1Z`mOf7(V@5?11;-BWj zgIEsLr1-LR5=b5LKUeN4%Fyci{&SOOlw+6I$<|G?IKv8eZmL?->SZ}hr`|m;{=i5w zmGv{VOj4up;j0Cecd)c_WDOVh-J?U6@oMd24ev@3@s7ubMtc>{nz><rvNSi%)2hs0 zZt*#dK6dj@tG3UBs5DoOyZ4c2zx4iY`Zh&<I}KRt-CV^Nl*Q}qs><o`>$@e5z~n^` zWqricBg@~SmBFkB?-aa`Z0Y>9W4kHer!_z3)EFB!E>vN1@A~d26Zgq(X6E5I<cG7) zBjq+1Dh*5B5=T8c)8!8Prea`>vty3wnxf~!o(rW8gLcy`m@v182CZvMj@iy{e%{&J z8k3>>t2>&)?ZXPR9u+y}%e!gGs9SwYGCGR^QYs@M%45F?F~;NI=XKfmPyDyOJUjb$ z7^<Ie9F&)BberX-lF)th1~2|@Sl!3{eLmy_O|Cv0!_SrGMDdZQnQm(dH|EMnKK6ty zcWd@vVe9kCX_b5QHsopzB|@E>vP!u&_nCAG0WVS&PU&pR6w{2u(@qo4V+`U9F!mx5 z+p*}}uN1S@Z#iLS$z;{T8oxg^!x&2=3j!A<cZ>TO`&?5Sj>hNzr8GOFxTg25s!N_V zd}M0($ehmo#1nAYx_|AFy_Ku>o$<%Gdy6NF;ditBNVUw@zZ)NwbvYLNJ)Mkr$o6`2 zepBG!+gPMe69bo-LxS1mbXxwm>{-Hbk6+6(c@Cd4Z;S+G1G48FWtzUFJZF6IHFN%| z*!_L!%5&o+$~<v{x1?%$FB<O%O=jpT8f(!Ll$P(8b((GWs*_)SHe{+=npgSV*qXJ( z@NG0%TJfy;PJBCy<o=hn+Uk^-s;s55Ijf6DyN$W#uHJjv-R!>{ELhXBN@{b~Ma+C+ zn0L%4;+xn1I#?ULHskWuJM8`^)aJY!$K93c*nQP<+Q-66^B2^xm01vJSt>(@wiNuz zkfGkM;hk(RF~E9!8TXg)pIcJhYSgyQQOcqx*&CNFLgYSxMSm$j*FR@3Y5sSQkx-Ig z?<V1claYtdrSR#u&Gu4%T+RAr8yD+#;znzLFp;gK073II?LQsrZ+<?>%D@Nx2^l7N ze4ZF&#sW2YP1f4O_$O60?`}-OHEFy;CtL%WC;9k$$12{&6y5;675^R~<hKkAVK>0* zgbG{Baoz0I3dVZvE!wzmlNsUUg=Hkso7dZxACsi8Da|uW)Rv@8H*zE>U(mNV+g>x1 z|K4Vm>=%D-jex<sDXFtkNsSqAduOzt-9!(Nh)tpW-3kdfMDS?zl~26D@2<nMM9M9y zsq@B*7$KA3mz7Na`c_TlGuw%TUED*x5p|3gzJI(99|d3CD2y;u6eeoM<S*Uj{r+24 ze9$<^)Mow5Nb$}_>+JRk-sI?SMD^Fp=Zw#7|80|PYuhu5Yz3~W?XY2XYLmLlkJQ&6 zFUi+)u})}o?X>rAFWxD-0qwsMOcr<Zmuw1Qt~u-R7oD#ike73D?@*KPF17H`Zt(y& z9lIyQ3EFW8Hx<`PHJ_ivdD?OPxB~M}k_xxj#LAzyLo1bT;MVduGg7>EB;+meDu%R; zHUT(Y&xz8Q3ReWq!k3Cw>U3+e?T|#qiMO%r3rEOHz~_JTQ{BTa$&N9XAJqte)0<*b zdRB0~kYhN}DVh6F7k$GwiUvLPSj+H!L_7<PV8cDh(|a;}lnU;YDh-qxr<6K;_n*1n zH*UCZetO^9o$@UUsrBxl2p^R@AGNnTwO<2u&?&WH^1W}YtE$f_3}Ixrz-5B_+TpPr z)u}G6I}Ho0`i}Y3fK7+?Zw-Yg`;C4LtRZ<F<8E~MgYJ6`SzZHeLGriJhV|##hPCbt z^BQ!*5p)OI3|l&D{qBmxr;KA0^pbWYMa3jTZp?2!f?qh0lB6*6ys{hx$s3gCU7jwV zxf`YOu^QLV+@1a{w4HyPvigu;@pr=mM~#)+sT*wA0|owNDGEhde)cEt7mn&aeJpNV zuYVX*NEk2yeVKww<u*_0Y!*(lJJv9G?l449j3^)O#A;N8o^cw#WVbA4&!gx;&PV_# zR0;W6?xj$fgIJpRA=J8-`|c0A-MLS}+~)FR6S~7b$UM6gbp-Tttu12zJ@1b*-qZKI zuPHd#HQ4TY$Df?>BY~dCzp{h@XTa$q%kZyMz6E>?=X@*z{Oq3mT#fuZvwT4;0s?x} zB8>u~jnw`u0x|*u9D0Isv()}*nnIbUS$#A{vri5037MWhHP%CDdI|<@@q5qm(Rd06 zoeQG{M4p^S$M-SE9EI{Lho|bHPduo7&{WZVqRwdQ(tBdBtZ6dQG}SWV?VjS@jpBXh z;zI)BHE4t@p4hv$V)Kn+i*Lp9&LvCqB)0@4%kD|}StEkCsE<5Euim~9YKX2qITJi% zdspVau!SPi_h0Bkk$cJ9Pn99p51^fsnLyKX&&iIV=@zyaVET*;eR7ieGF%t_Z3VK< z)|7YI)|A>_l*QHxhD{2Vf{Hw;!B|K67fmu{BZ{vCWg8u3Jt<}HUC4M+Dn&FYPT(P@ z-YXyn=-UcZ@-9>g1XWACR4bZPYf@Dk(RAf3bnnr$Z7gc<1nK6i)yJCDN4ywZWE8Z# zC>NSE<}WmsDK*ywHH)kn#xFEa1+{)rYW=uS{d=K>_f)&YixwUy(Nt+Ec0fw$twYnS z!|+Ro<*6>6H<&6-_klMUnFeXugw_J|aM4%PeSKUwJJw2{;~7bA-M+3jp}{Xgeq7H4 z3m`@r*m@hhY&LLyYDf|S(0%qSFX@?SvtigXBXsk=6-qbxsd1XOaaObOeQ&T)eCS>1 zM<zxYvg%(Z4Npy*y-nMjO}l@Ywx_`d)8NY1W+XCXpXW_T(4^(P#4Gb4L1qF$W{bUM ziyyx%PM=!-dPac6TI_gR+@)FIdNyjk=4($uD^IP-46N@_Sts-om!e?3-Zoq<HatG2 zOn9`h<wN~1xjK{SzV@0dqsU}^?9|fje)ZbvQQ1Fhu{Zv0uO;NL%nWnzv77fc)1iXa zT9Jle30<rRls7HFSdbSM6p01JTiMI`INKUH>nxC6GQ)0BWVgL!IM=J8<$0se^X3Jz zC6xU)th1Vsi%PnShL5uXl|$ZweNOtzMT3`XLatjru3yq!)6(HSTTfC_74DD^pr~J@ z|AgGq0B%Hv{~14n3cG_}yOU?Q1BLa8TJ^-e!KnL0P5=;b2%*nBKp7X04*>!GkcRdW zhWCO@n2B8g-p_<dORYTketBC9``Ews;rm6pz)W0-^>R0S?J4XXVCbzO>>bex3~dF5 z1H5B|{gMoQ(N?7S%=&b~{`U?28Cv}-{`i-@c8f!imG&V%llXezoA09OdsFH8Q|Ufa z2Td*p=A;JAw+1Z=2XD2iw5O^G%rTxUG7bw;EB3(;aanqA;z$%J@e=f328Dhq#rwX% zu`M||%Ao1j=sqviMoRVXhC$!|gbG}$b<YI@=T$kDRH%J}H(JB**8YU=EQaeLBEBrD z7#l^HipW{|M)suA#IjCd6ge(sl$=uo9OhIewitF<-ux(_&E6uX>Vvd}kb;az+i(U% z2nD>2X0%VOU?lL5KEsh01F}iByDhHoGH$3X?hz$jQ>OZl3-xJ{xaCZ(=C-J<HvjUi z^vIgdY<bRo4^g^vT&s`D2aU+>qaALd^<cRVk%5heklJiI5oLl`naL^8xDU{cv#8a{ zFjTV8R&LSyvf%y;s9X!EePyV_w|EIgg#rpv4|EaX=r@sQY9AI+qJ3Vv*|aF@5F=59 zhjEAjji5}UH2Mm?&u`-AV)J{8#tTi2^2^F<&&s>Xx+@UP&d3tDK~OpMJ$=$nD~qOp z8xwnN=8&|(sH`b<WoSnY8ERSH*05y76i|ENJq_za<g(Cuq4SISs0vx6-C0tVjI;kP zXDJzHNDD}N<A&q6s3Eik<g|#B_WbWO@6ar?tYU=$EVSGmg>U)_58AOWx2XN`Qf1EH zDfkzwbQIH^Q^l)~E$wp%^FEDb5sN`1lwC1ZXbK2Ra@1x{0*Z9iDp#o>c5#a~{F*k} znkE{L+TR*s<6jZOg1_j&AI(qEQy!JLm1HP~nQf<p^g&CR%U)k6FXMjvE80wJn%`Gc zZd*wiV#OcD1mB<6ZR_aePwRf1;j<7+_hX^CE8j}tGp?G%no}E-erAr%k)d73d)xY! z=1hP#Rjd>^zzGQB%opP?T%mn5Blz<=$?`a*My6^4R}8fxj^B*YnWJr!DbLzMxNT8e ztTb?l3w{;TLryCHJCJ@i`XrXPH7%RkZHuP<nl{+_-r;5=!A%Ug5knhZUJXk{fOUoE z%_E){#P@eXT{`3Uj}cZ`h+-Mc^m1LdF%h9SxuP{~$_?#q)*G9Sj)E`cRO%#O9%stB zaV4U8U$K;CS<?<*;EoLW5{fh&1p*<ePXnrp@TlEbO7r|V9AAu69dzuI^6Um6TxA-G z%zCcA^eE6(=dkn?;n5s+mcLT&+u(-Xb$*w-L^B=PaI(_T)Y7FgboN*EVcboK6vbnm zWz-|YXcPTwEKQgDD~){meM1A;C<)&0d3-RZ$CRP#stPC>@j|>;+PW#5(RkEOc!Kd= zBj)AYC31`l@|<Vq)H9wHH8L2jPTF{xHfg$Cq8y6szNUz5*5JN|7Y|Am%-R>~7lrzn z@(ZZ@Zzu5>(r5K*lC5b!c6C)*Q!{RrCRioE=*n&Hq{XmQ<Xj_uN;F6E%*I|RGb%)+ zh__F-)ADECgIzVs1e8spy2{Y>$SYc1KSW|*bgqAQU5$wFnl?R9$*WK$`DWJd@8Y?5 zkAgX^2s(#cw9HweOUW9|cSUm-zSV0k-dguy;VoXPb9Z@)wu)Jt*%2#en+(}D3RWCK zT8tvHVQz}*O}>Ywh_)Vx@NW;mqk-SfG`K+DKICLXLy2W<*bO$W)=Z*uLP$hFT{KO3 zOHg<wmC@gn`=-<u9YSp4n0@mWii+0lDccf)H#u97woOR!(!>Uuesz-RlI6{!HRCqk z&Yty-@rNDre>>JvyY|7m&L4JP{@Znz+Vc+H^ZT$D^lvw;pDk)<kf{RJwz)4Zb%1-_ zq2Bt&g{IHmV%W!fb5+22@|scVLPq!BUi*jd-T%J#NgWM+_^!tosBt@}63ldl|KO<L z@4gI2D#y>A5Av6I0zY{r?^-k^&kDEI)_)wZjP6ODWKFC|L_FA+Vcgzg+_yfZ*?1VZ zcgkYvBG|8k#NWBcboxa4{8)yO>fQOqhf{&jGjV)fB<q>R-36C@E#J-$ot|Ij8$L$T zOh#{hcOL(GdG}jV`=mx;-@E5e&>frK-Jh(Iv5T(DgpH5uXP0SjuCjWrGJ3w`NngkH zutZqW|LC`E-wLdJb5q46RBw6HerG()e|xpSG;U3MX3dB!Vw_^;HTZ|C((oHdagO%< z+X4x!Z_&*3EKQ-P0sR|Y=nK&GC#9)({Sgp4u|Q(J!oe8IM<!j-$%S2ES7QFR#Qeph z$!u!b5;6QGAJf?Ou4eCw?5w3Ct`0?;+NU0V%99AVz9kVXpDK`#gEe18M~&wS(;Nzt zKCRTpp8ekHjD1?QP-E8V|Cdy#da1$gQ?R#6IYHv1<6Clko6k&TtWGXmeuGJ0sMvD} zv;Trc>Noqs!E{pbBB$0FxfCb9{S%hD&;K2{Hh4#1dR{yIynY4|YjWy;rj#R<(D7YS zmgDRG@@PdEkH3><F`7JzsO*vIR4?bwvBlxmU>u!vVs7;(jR$6L&qt~T9=>rGt4Ak; zMjr~I0=3>{NOWD+(UoOOCj}R)WnTXFo+BEdk`i?P>3w1-KN&-g6a&;{ScKril&#R9 z$|icUo1+I9DG_z*yAi5?@%58b?iY(25AYdAaXI#v#ahv<iOM!H5A&mKV!3NaZQ^)8 zWPbHWaoXug_FRPxQ?2G|YmtZFwoE=4ztkg(S7eN_OHt(=vwN#4MPmP!R}w!=_Iins zAY66S6JOYH5KUl_v@dIy>X09^n?h$l=#b<3fy6OaBTZNSmC%G|D9=9^^swNcQ>+rb zf{V@|pZv!dr@~m?k4{C2Qlu5~LOgnVR4=ax!XiT#X8R;85BWIZcM7V{D@u9w*DES( zKkloS6w44x{@Wi=F>C4NPl_y2Z`7i9zVP6z>W8VhGz_O4raW=pcjw|*J$egqOPbSD zMc(Wu50{U)e!8oXe&GYIZ4lraBujuKe8RSG)qZmA{K*^pR_>dS;H$3V^-tvzzm9So zdj9>3vymi-G1^X3U^LrC0SU(424K<<_dz9639>$7OXqqiQnhjSk;m!6Pd>0Fse6n) zd>8NWkuyWc;uCKV#B-c~Qr&YxXk$E00(AVzb5iOK;x#2prr|ZM$duqUqxxjRYgSVl z>OH5crQtnqV42{(VDf6>>D2YvclRZmBn_Wshj$4+E6?jRY)pUf5WimanACW^=ChIT zdfoqc;`K)G9n^O-luXliE0QVE_iOBv&%WOhrD39L%mK=NJL#5*e!JPPKKt$EN6jtt zyCiA)AC$gJH1$8MtdfEz1A<`zNAD*!1Aeq@BnEJ8RE`H6f4GAMp7dvoYjEL;;*;X% z%#(rVpQXuyE@rf}f_^PnCI$Uoc{LgIXZ;OX@a5Met>CNOcS*t5hjo)5&UP;-;Q!Mb zCImR)fBmmFj7LnbT#xMwBjRB;8?7%Gh=M;*%~ftF9Ew8-JYOAcC>lv(mW!oV@z|#1 z1F)u=jlD1Vl!3JUn5)uQI+4Q@Mjs9U^b>G%y8jPvnAD0u3;mo>6A$Ydrw^b3IZS+P zs#>hG8i-|36Z#rKau4L%D>gL<OapR3!cALh*E)UA57*-0ylbg|hw=!C6Ryo(=PPcD z@wSF<BO>jx`ReWOcRpnbyjUM^Z`_;2%Ed8ibTl2zmg`knOmsAVUrZw#1u=KF{2(B{ zPpOYV;l0}EesdnF(baZ3j}MS2N4B+}@4>i4i21t3etn<4?~xkN)%oYxh9&xrN$W$P z7kq!V%J44z8^OuRw@*y81zmqnVGpV|-hGf%OrvW$=?f&Ja$;5<BO#Ot`jfSY3BLW| z*k?(3N+<(XAhcdW)BEff$l(ieehoVmg|iUDx(vx*<4eNj;oQMEYMAlipI$50lnf^S zhxz*<goOGRA&7^oh&~{tdLL_ox)6y)sN~N6rYt-^b3GitqPQeI<YmPSf!?TfKR&lc z!(b%9O^G_g#m6r*=VeP4d#+dE!FHZ61$#*%n@N^MEY(YNFQvj`6k5;kVWraxGUDH> zMd9QQa3Hs+Rbfe{LoDlSF!v>#(2f|6qUFKR9OzP>$Zr)^x2VqGANSpnhEz9lw}yD| ztXu<Xz`bJY1mD(7zSk1`ptY45W<&z<@d&5zp+u{+FKY1Dp7S)!+lW`SESsqPXz7O$ zR<&-a($!Y&mv-s^2pZJ18}Zw3;GHM<+D`!ZC}SP+F`5&3E{5_)C%r>EFHZWd4JZL{ zLrQm9dJ-?@Cw-KL>IUQwroS8w-!n}$qc!EU1`JbWxSSbYE(uWJgP42Ye*(0*pvDCn z)z2q{_RItT9E5K8aMNCR$Y+s77q4mMdo>r+Y8(?6vzkg87ZV(Y-JBdojtNhdk^m>l zf*mfpCS3ULHounrt_eb<U8>f|rEj(65}a>{w}n=GXGJC@07rKduaz#Q27Dy_s9i5D zZrE@)PQ38X%WoJZ-mCwgH{AO3`g{Ed@6A!uqU+6%w!PY$pIv``-W>N5J-Iy@q<*r& z|EVinLgo|Qv4qo@{1covZ1|*GVSxbIEx(|57kIq(zj(vjZ|?G>XDP$R|6cCZ-Tk}$ zbBvQNAy@#BaxXsZNeHnz7N2@l`pVCdb_A7A$f4Z#A8!~jjs*#i_We(9*kTGjJVpdy zcIv0<IEg^U7eE}9<;V*$A~%_!Tc6PZ#_N+P6r>P-H}G2S>%JWGZ(A%y#^~TfvC|ms zcpJPpr#6ny#329#^L^1`k!*mw;>m;2-z}FSj47w_78N;s7GI?VJ5C?PiYuzEly}>8 zohGW_$^*eVkaPq*DMUY3Dv>xu1|&zj90FnjdPpY*YBS%16thL?CaF@?z5-13lU+=a zcyPW?GM0~2kQEuz^(k>}CRVr?jUu*Ew@skQD&%rhp;R+TVFc8JM31IPc;J0hlL$rr zGY)bRe5<e~bqAfZ<RqDe1h6cUK&Wkt`0*wS-594L1;b3&w!L=NrUdDiBkLpw?NG27 z#(|?A8)bqVNF<xK5!o|N^{1bvoktQ0titaIWT%S2CiNgeR687h<{T?*orBs`gxV|> zQXe}-QkG-D5?uxNW)S6^M1@jld9ng#ZxR7u|9D_q0s@u*5~X4xRMkJH8RS$Xd~2w5 z?njx=GI5|D%>qx|{YqN|52XjVPdlT&1s6+{@_B!p%N!*~^o)XpKW~DR2%8WCB8q^V zkMo7tIjVNwD4J4iG+%irErG_@e;pqe3XyUFyX6G;e<DE+NV%Fpmnw@_6q2cm52|A_ z@pbq}p$^PNegPUTYQ)ZPyV1FVL*+rU5vv4C=DOtA2^aN;(YjVkq4el90>(<2xFT2m z#_~1guLc2nhb+g4&(T<3R<#JeyUne%Ovy-ky-%jGO%qHH?F&HO)?iOIR$?2(OXtOv zFT1+(ZHT}}02dk4FNg5P&l5jo4L+^iPbBl>WdA9SpJO(YP1UfXaV)bhJgdxW*OJog ziae`azs3*A%6L4iOHE;68c*F`#2)F~@L~gBt~eQ!@Px6P{L3uu(g(sIWyim2B>ZgD zh+*W9u$(Gw!1kZ_QERVc(%p@sJmmV8o$3RGtCv)%*bx10AT+s$bWiZ_Hk-^aZhkRa zs@CRW_6Sp+?7jpOc{xPKJP(_*s*GJ=T8l4YKp-D&cX8cT<91#zc}q^FVuerNTpl6d zUtk$^@rNOfIFzBuZ9&Vz_^!?^PC)ulCdsRbfME|KFK(a{=e#L9=1}U&8V<MDG$Nob z2=ufeq1i>gCSa(ER^qyjkE`aN>BFCX`9w-QmYGc!?5VuXdauT*J5iLjx?Dl*>oloX zaVQ<2HzEy8Veuk9l+;&Sj^0dkO812j&1clpM=jHd20eu|<ChVx0go{j@(<`_GzRIT zv2iZ@HksGw-kRre(o14tlY{B<61qPiwn#dFWj9E)91D`SVwsykG`D=o?y)-eoByi$ zOTgdyAar$-W`G$ayov%U#mj*6dP|Wgl?^}Pd7A#V*Ao0&hYpvb!=Qs>)i5Nf#O)^e zf^Q_ln=Q8?v2R~0?|6kIMEVjOy803PKJ{94G9=ui1vDDHp*-*LLacK;x6j#-{E2u+ z`uD!j?J<Wx&1P{3p(gygi~&)XTg55DWx%te!+b3yUV24l44WcR!h(2-`g*oB-A0#u zdL6nfa|QQihY48Y(EGLDy+S(_Eb8@iz^+HEjC;`+4>07r&X45~{YVgBuo$U;HkzVx z^oqV-Cei-Hz37p_Vf7E!j~*NN0Bewv_+V{}j|(f6b?I<w0(ruy;ypS8_I`waGL+$8 z=ytA>6G-c`qX(RBavlCB!!Y^Kq}rCjI~q;%z93fg2uqSP+9Bv)a8!ctf8PFXXY7?s zJhIA`ZY`SV?&O@FOw!7R?u$qmWE@E<FH%S%+9t=fE(3EGxeDfsZ0Gy^3Nkn#ajHTU zvb?8wRrG9p6Vir(sE<GgK(H;Mz;%GL3Wo4&2rN5<M0^uZ0t;-fhc4Aao2DSu+JOlM zp+S!Ba~SVgteglt{C4q8bcQc(To$Jn3lTdJD2skTLL`=O-f)<-Z-A^wxa<<R0}Jjy zAsw8;eT7#Q26iw7{ozI$fg$wLCfP&6zPXWn1&~;5LTjd;r@$jm;A9R?k^3m(oD<@t z`pBeSl3q8k$3FN29IWmb>T49LP6Yi7fC4t7LN23L?m+~MqK7e%a9@wlNJ+k>=)}9r zXv|XdZCUh=P#A|{bZT@=+GS{lQ%r1mO!iXDO-4+9+Z)kKie?VsS!`@|W@t@YY%L<L zUL>xrE%cESbWYn&!GLVn3#8i%bUh)CMG~3UgRGGx`BShpX8#{k@t>m|_uvUL`%s)W zJY7zb%}kPQh4$Z#UtfY{Vqg^*(mE?}-4w~Zc48d{oaY8zJc0Z)0{<k2oEjxHpFo-c z5dTr=?Gj{nGYN2PK6H^2}sd&v1Dk;WuV_L5HYV!$-XkOK@{G?|PmnX(-N<4XRM znSB2snf3}(eFEVv)9>_-W!)k(4Iz-2O5wfwzuxdciiq1=i92mVk$T)C4j$79A+jFt z9uh#%3t&7Uz##%$00QoMd{sA~Hcgu0388)kp_cZ4I8_4xN!ljRVn4z{8)VOnZ)==x zLqcMc1+>SeyR@f=X~W_H86Gql?pNvYy~JO&VPESr0uG=V+9Vh^60~S$s2@qBF-c@r zW^7hwv~fb>Rpx)ZVbQEq<E(U*tePoU^9gBhWD1)#80X3sie?uZXaC0=j>#@C&d!CC zmSDj3G^9mV#I8s}F*pIAHbGlE-oq(?yeNRn3ZJW<&=v)HRZnPC4;*a=I$42i?Lqw7 z1k=U@Gh75>*qphF9K;E}&{W>~avpASnD&mD5C^Qv;)=*{e0Dhg(Q^J#7QSRX!I|hg z@erUqitxAJyFW2NNhHxfQKDCy@9@MxfWvoKMbd(L=m8+7y&el)LDwH($!H7e+oAWw z3aD`5bFl)7LoDM*EE6d%lu&qItgsyp9SaG{ZzsRT`p=#~o^V5v*ARZ%A_0>kLH{DL z=S33PMJ*ylll72CoKPAdbPNDR`a=&-U`tk-soJD5IEF%-$k7dC<_5CaBoNmIn%5I> zZI+1F<3F_GqSypHtjBkXE#(R+{apckgawKM%FJ=N2dd1+1n3!3=5GRgvq_wYC9Q;$ zhLD#3@J+14CW?<hx9iK}?^I#S_2o+d=rZ%Ox7X!|%+FHy$}5#1y*RQM1x7~b7OFy; zn4z4{D$AZ%7L)2t0V)d*D~nXYIQ_Jmv<msFVsfgofVQ&kd1W(gWfQUz3DkR3Nki$S zJ}?EYriLycp{kX|hwz%ide~uodD1m(=^8fY1`RQRR!))Nyx}}RZ6205Zxh$TB(2hZ zvm65bab5fNc}+a6w>&p=ZVECJQa1yK1n)x#lYJDUeW&3NWTY>A5j>|9uD}V&$nYB< zu!F0SH^#b3D8LJ8Wtt2c)Epc*pH-I^m=1=3`)I3KZop$0pMiQXcPF?t1Uwp2hZHNG zMHNqJ*U8_-LT9jYBx>O?h7j3(oGz<J$R3ip+fY|jFUJX234phjHOZDYc||w1j?~NU zH)??aq-t=DxMsueO}d>;rg3m<aky<xvtmGtQ%=kC&K8$1Ev`2$Zgj04;;mk$tv&&* zzB#S_ovndiT7z#|L+IK<#oNM7+ad$nqI23}JKN&Fv?boOVd&aZOsRW@gszZesPuMj z{pUUQ!vD0%g70;l<2)L1-9OKCndgPB+*B@l$v9)k;00vAHapCInf@+@?X{9!TfqR# zWH@ZN<e{UR9@#&*y)6oB;@0IELX@ycoYX<)@_=lFgKX}m^Fx5P+dYxPDcIa4@!<)i z;!fL@ok%!LUgY)3JKy>)&<bJp1%cro;sRua(}+@OwDwLX*{(MD5CcPxkQ{ElFTC)i z6H=}huS*lFxX6G`0w9S<B8|-tw%RYbeEgPuv<ESy)c_y=VQ7_`$Jn5eTtj1E__Ggg z0fceNPWEonC+;mM+!Y6>E9hN#$q%`C1hzu6H;E2=!S6}c7)`@xQLwrxVlsLn66#ky z+D&im)EXa=nXs#JD8Z_Sp$$*r__^l1yVl0zZVGBvLs;<V`p{l&-0cZU*epi|Ivdg} zbNnG~K*82Fi4IO63`ccNaS~E5Akl)*S%=|YWj+_h(x0_o{=kw<001UwEjM=qI9)h2 zh@NzH)8XTGXL}l?2}4R-4QoPy0ahc9amIgaAp@JEIddxSE_52bQi`b{tJ?l^aBy_j zFelB&qQ_A4k19*@eeccW$sfYIl)y`F=tBUwX|vBQ2hxv(_SCB;osfzZYn0A?B9MWM z*F(3NNj3q{`lB(IxRD_YWTqF|e$tzSwC|e&dyIl5GSxXa-XAcNFd+1zj}$9c5r58y zx|nf{F^QL|`6|3-(F)3<1mPBkye&4(sqXuNf-tB*e}3~HV|)P%ThxZ8x{><838D4) zfmo0OGf~V5af>!|S`4~?nmP<ry8H&|!$2d{Vf~veW2(@@J8fu8FGvwiu+Ih5Jp{2Z z<GJ<%_bYH#3D68hTruUp+6y5xpB(x&N7xrog@yHZfty0Y2r>-`8KA33Xc99JmzTm3 zx<$z8pNN|I5F#UO;Gwo=YCZ7>-yB^OaS>`}p?7X@%I&Pkv<(GejGmZ<gNM5ci&y+7 zdO>nlgx*L}00Y!0=ULC@`1TZu?-YRv%KY90w8el(7fC4F3yefTR1Y1=6J&jrY-Rzl z6f5X7W-+Sy6WMPQty{YZE07p+VOM*atrOy>WRv&{oT9p%4h5UEf~Vb}->smjn;>0n z0{u-;fz?9sa|p%7E1&rJde3g?^l(Fcx7eNf_-OA$Zief&)fYzqc-sxyf`Qx*a2;WW z^d%4(wtCJnLpo59c{k{4FE}Pd^B|S@s(X$TIN$$3X)q*uxxTOdc91>F*m4N6YelTs z3+zL|K3jnq=*Wiv8_UeA^1UR+M9{Vn@CW9V`D{{G%&ab!$h!uHqu+7pyH@pJ?Sl#8 z>EWh&=t&oJlDUeo*2(u4$1;QODUcl3JKqzx8L8Z+<E@Z8`Vf9X`t}-p8wu{{g-}Y8 z#xVnN;WtO-8OjMO&Swrip3)voq&O)%XLYQ;#^PxUc-{)?y6N*J8!VAF3Um*HY&E8k zLMkr^93W6CS6s*N*_hjE_MHZaBaV1JS<L}Jtp7o{b7pGg*7yVAb<GkTC|E7d<qoo6 z6Re6WgXIkeFJizSX>A{NL-3nJr>vkHj`hTyiZ_nC0wo$FNa!jS?0G_9gaox~SIh}} z^@ME9e+0+%0$Z+DS)nx?8sI+6Gqq<j!Ucs)<cFCuAKpKLb1+N`Xnx~p9TQtezq>Yg z`N5Fz-?I)okZe8iu@y9E(W$V4_}t<cvFaqBj+wwlzyGY%g9Q&EE4Xh7+^2{+tCfd7 zfV)E=Kb2t>+C(4M_w}uaQ&04!#ij_m!N&8i_VOu50O8DJ;ld(kY?fya-<&;Uq6n9R zS$_LEz6plq?Ty@_z?j;VCAacCV=Iv4nc^rk7X@^LJG6(8WMWCsL|Hb}S$iP~!ORh5 zR^W<W#|lHcCR)7?tXl9o5N82toDi2VL$|H;^?!ovt-znL#j7Z=4mU8~mC)LT*jr;} z`XeOG9@2-3^6d#@Iu7&O_~TdiCK3@_-1cS~epxLXMyM8jYY6dD2Unp+Fn5<p8{e8y zRapNk$^5I#o~!JQtK7S*e5Pyc<QUzl>F?e+SuBB~74ZZX)&X~ubWra@L7#M=T%Jqv zC{yxEGzx%=I5OfKd-2PVq&CzE4#Y5R&YF*Pw_wtUA0d&moC*7=i>)Q>1LeSq-!NPS zBH>QE?C1+|3B2y@bN!vt$yrkURKTfOV!jXuQED&A5};_eH|b&$>fw3UKANPfV7FR- z2k5IY<}tu|!xGAHmMW9~dc%CIEnZ)^OFc7w7Ahvvd!lDAr)@_QS!Z_+efimxQ@ADH z%NxHh8P@%hPHyT0>DA1a4ElFbL57liQAD9K-B)TXWC}><AvhdguGIg+7NJWWpDvJx z`d_@^&^7!pB3Or)A7w!S7E-Qi-(}Pe9wdY_dOB~4s6XKQ+Arcu%xhDqOwOrOom>C4 zWPDc@!`*zgQ0ZAR&Y+pQkF)_0P)h2TBMSNn6Z=qi27o@Ook#MQhf+?=+NiJyI7<69 zDlw1{vTI<~%Sev%hB+Q^n^&fq-~9fOF>HUG&vozj_vJB9C9UjE>WQP}oB3N{N}%%p z^M-F6W1@1N<?`+F0B-S6j5d|+k-7R9f3_S)m-d4)+r)whg!fFc9i54V$}kOq5?h1( zz5jZ{^M@s=x*jUPbVCDYr4-dc=Q27|3l;YJ)ShEQL%J?B??;(q<lm?2hZ5?J>WVd# zjOdr2O;aUy^cCm%2%hfd@^+JRjH~g+41y`U+T^=b`5Ra@PT9ta?~9s>MtwGzD$vV4 z>YwHvM}8uA#5^XPD8zZg5d?RMuxb=u1UaoYeys8U#*2VfeF*@1-0y}Dyifa=GJ?*+ zZGeL7@m9aSz6Q@=%Hzgd+eBWw67L0Gdh+78I)pSpjE=6%_M%0UMud@N5WA0&rJhXs zvK_7#Z|D@K;Ipi0Fg7Od2Vjmwm=`8<+<y>XA3<jx+m5WXYFkdBH_tcWv+&z1X|)Jg z{u;&P`g~b9Lwl-%E#_7Aa>o6Nbids!d#s8tZ3IKG18pRWrjd2{qgtcvGOWokjYF>A zVVa>6O?kRQo6Iu3Yq?)(mUFptB)to65I@&-<<t(UI)H=JRTeO8a4g5P9fj6<CIOkm zPi@*HzNV0CXYNpJ=v@qzi5m-Xb*oRo_xp(mf}~;`(C?!36F!)%!%0)}!vUnboZDs_ zoMYMfXYDmZD%018bUh8pS-CEDpFy-v)uMs409i_Rn!%c_rEEKF@)E5>HF~weF&CZd z;TV$aKpT^FaCtHykhDbek=${Z>xD>EB#i@`5Z}AJj;{;pPV0Q~(eiC$J2W;JnNp65 z^7o{VYIxcHS?s-wlJY+o_-M!!bXKCo<c5qHdF#RL*GCcA1$8gm{lPv(W0y!WoN4KQ zpn#~zRe6|YmFwq_X5!>tPUA`Ze3<(h)5MFc0TW4JsX72pLC;y7HSXms(d#5U-wq9( zwwiicix&@qe!hDZ7Dh8JuLQNyFAD#>uh8mt%3{_PilF%#!57&VXTDj87`jw|xTC>V zqnbWF$VmNoa(UY(Ep7lOqluegIy*i##zr(UTAr<LmwbTg5CObDev<g=ei#C`X^YPd z9S`-6MiA&)Qk1nS3gNtAwn`<*eVL>n05jtrDuT_cH$rDFlxDiz^6$(}*ExFnkr`g^ zZTM1+UEnm$EQ&@Hha&e~C8UHs7!l|98zU=pv7aqxdXOXovAFH07L0%QBvNF+a`hx~ z@Vmj|C?$!fkvoA+>NYGJZEE?Hav7tS5rXCJAZ~aVZFgp&)=@@+&zcRUE8Ib_r2SLi z_JF_lorD~u*bQWY`IfZCx*h?l_~iHZefst-DZkq#*r(+z=me}N7|E$+O<Y8M)Wsqd zaT=G8y{FJRz9afVRKr4QM|LeXl4o?fQ^zO_SH@MLEYnS^vKpXiT0-a(cjzSgG|AsA zMM>YHB>_zu46AODyo7!bU(w_e+FwrU_F{TX5)r;y%RpgHmT+Cc2hmRwIC(;JhF|9L zCG(Ux>!xL=TQ%tvUoJ(7g^>4LOR{4OYc{^tXFtn#^X9NHe{M9yUH8&&N494QD5}U3 zuA}~ddX0aZzcm$V9Y0_DddHsrTiaWIfEBH+yrLpde5vp2e0`L;j&aWnkGYv`O$oEo z-Q%{I`xR3*_YX0HTyq8Bcq#IRckG<%YvoDKmlPRg3NN2)flU@#79I})K1KMGC$wH^ zGPJjm=o`hxnY#>dAB=90o8!D;+I{Lu1y>I}Q?p&63=XXWgD07MqynSpxbD#(!vIu5 zJLxwB`aX|f9ghA;U+mgpf8w7PU>LY*%kjhemH(u;<+a08jEVWHU|TV=opt>}z9Lx$ zA+V+$T-h#j{;{Lyj3r2TsgEquEu3A#n$&Qq|1b1=1VgnY>{yo(_A~wGC?8M`LqPQz zwHV=q25+e1w>izZ#oJ5R(k?Cy^9da#Jo{qJD6YkbVs}w|vK?<JXj=mfauV^p>o?c1 zdq7JF^GGd`u;(^h{%APtk>1>8&->c=Q|&L0%z-bq{6#}PXQTYG44?GwRn^(*wO2nx z79^T`8H~Rk_RRm)<tX*XZ~Rp*2=iCMNtSwLDoXJpRfjF<`k~zDNM=oP87jtE;zG8K zd042Pg~UypK%UuDu}DGkxo*bFT$!SG<+JYR`dYJ0SUc}(d&w6jiz^GQ!@vA=n(V`= zA|^P5IQ2{MU@GO`#)LJz-luiDI2g8b3~btCbN=HEe_09ku`SN&TTu1<?%SXpmD_L% zhWq_~<Oh1Gn8&)rzX+C@`QX#FBl*gox+Nk0*VD(@EIoN%FX*;6F9cgs)bC79jC%gL z{E4-AX~H19x<wY{JIMaQOo;XZK{BDpS~>**NKo1}VL(xZxb2F77LMxlW5c%vX94K6 z9rmx4ewO(slshZC@6(Sbygzv6zxB`f)aLwTE}57cXIl(pKIZ97Akm1YOHiI@uW**~ zt~~eHc}8?TTv(-@AUr@r*%8C{uO`OF?E#gJe*0Weuy=Lq+K*RJH%7d6+K*t}`!k%N za_2rUY^Sh%z_j(58UxN7UO$P7;^m`Ig$ZP$={v%Nc$^AgHUawwbmv!FPka16&(d?( zvx7ueH!oisdz=3t9e&NX>bKCk{_ARjQ`WQZlIO5CSfAuiF1z#}?eBNjzj}y*Psroq z7pA{5IJyNsIounfDwCsaGJ4k?AsuvRXjv+x5P38)?aQlZ>(2HK^HhRzxW;7Tc25as z_(ejjn8T=cQBtC*@8X|5?mp<jDzKX82jkq~yNi_W*P9<+iALH*gFK>%G<>5P1zPVs zdx^qPExx3+zCD+E6?WJN{a%p9)MHcTNXOV-IAtHXdfAa)*D_tN(`XMBL6oym#2HH; zBDIfrPzp-`dJ-x<at_S*1;Lg<P6&2*ZXXMq?3NzSa#8osw-O&8wHW!zgg)vwm&I@v z_a_vxv+364;3TjI3_&@Mj=#i6SM~30mGKD<w2o%vZAP_X`R~e5vOm?zpG7x{h5`3q z^a|igy}1<zp*2lb$ahF7n-q*?CcOu<`1258`Rsr{O}T=Xd_(!eFL)s?#Ci5cWiq<0 z7ZhFBs$EW_5w9^}31N|Dh%9KaTs&*FlK#-MaK>aYxGQrwZnu&t21J$u3RGoXzt^Rq z|0L&({Sj-F0yflq6f`!2o5GE3BzS6IH|)@rA$Azfdx>^F!h1XwszeNQhSNJ)m01Jc zZ^zceHAcjP@l}yR|F$q1+C&!nj~%^6Uh9(w*GG}PkI-xj6Lkt@V#a^W9IkmnH?#$` zDSyX67Y8>LkTdEnSivn&6dVhc^$j15ejKNqDh~*GcV}aiNmd9_>J1BI3+3aCa2}0x zUgE%}wC}M#c9;S_03&VHA{>;7VER!O(NYSjqd9|PUid|Hhd|qM1rH2JDKm`m5>L`8 z+yxL)^r9rcUZoCI{@e+~^ATiK4|J)Ibsde=zeI$88mk>2>zg6*w&8HXU^JcZSuaO1 z#qvJ1b)NSgKfw?2b|YY6j&$*jU`!1ct!ga2`1m1pG}BXXTn*%NrqV~QS~y4WhAqmf z7nt5J&o^E^^rb>xn+PWj66&K&PKMPlK7Ec?cE_KX8ZWabSFqxY;NHh0VpV&t92vkL zXI;-aGE?Z_8>vg&S{eYV2~?ik)=;W0YJOCAm)=oeU#{TXOTcr9e&|d1!br{BP2ICm zgx)05Ia6(v^^=cNMD!I9`(kjNFa-bfGYcUXrl07Im7vZI$yd?Zz5_xD=1?X?SP>hM z+6DXPZIbmyps8<EUS*ggg4>25$^`Xb9XyH8E*mS+_*hNL>Ja$8x`}sbgl`o19Hr`m zAIC;J^dkDBN+ZaMxkdCrq!A~wR&a_Us8{(S%CC*TL7SskFUkd;!^j+}6jJTN%x`%X z%T3Xd#~<ck6!j8Cq(Pi#j+|y?=>Kqy3>5_X(txhGCKN}Nh)6*_#*uM^v0yHc`Dmnr z2mym{xQTWY?SY^m{|rA=#?Y?S+cxfwv%f$o8{{aWNfSgkq|W9u!#+F{@tPC(028W& ziE?!UN^282PiY7|og;73YSHFcveDvP!+VS%Frm!#Ih4z<FZ^T{j@ZOEt&j3`iqK{z z0=SLJu|G4IEBT`WN+twIU=%N1!nqj6Y<m@43xHr&BGD=R4KX4wPN1tc$L_&r-TMm? zsq>arpdRZ;-4N{{LDl!;pywz)@GmNFCy?;e!yM-bU!#bisz*JK2dsaLlgK}G^qtlW znfb$pUlcxXGz2ulT}pF88Vo*9a=4EZ@!CvniK@Qa&SK|T87l?oBRRci4ZatYPSXu! z+607Z5K>|AG;r;d=%`2l;LhS?ICyBO-?JoPXDRX5QW9`E2^cc%6=^aK@*Em*X2a)U z4p&6dzc7jl=mqg2@I|6S)uW>f%OiSZOOv6??|>^<;EHvKh7I#d0#Kvi*-DB1N~!mX z>ckRJU}W)NW@YnA)zC`y{7OaMN}d(yEqj#nKCnRIlXKH>NkgO)He3uqAXXphQLo{O z%oIF}`MR}IJou$^-n6>Jq<i8^&#y1FJm8(Pg8pADCLcSm(4fyc#aDiL!Zo={HmjpS zvm-&p1Ieo+L#rRV%|11oeatf>Cs`<OmO3Aw)D4N4)i7r@HlKU8wrFp@<h{03vbNm3 zHm^a!Mgnp%inQYa-Wm7dvo4{xBDARM@hC<^RZj@qlz|2zAZH}~0J-uFNu(97*HONH z6cNEXX8!Y+g=t8{(fy56_6@6$$T1m9CuYzudrN0#(Eiih<gmz>aOpw6bq5USc4Fi2 zkmYUK09QfmGb<q8Ln{MJ3T}}Xp}{85VH2cjMNJ_$llLLuB+9Nl4m`XGS=fZ`ZsNRQ zC@7SZ6Q3Cyw`i0=ege4f6vEd|_{1myga|o^hTa#!qb=Q962WW7;!*74(MIEs^rD%D z@tBva8Kd#(7}2y+c=RpS?7<1NnoycV7zhL7Hb{Uug*=YjddvtwDB^KDB;Z}zkXu3d z9RR;iAa^%Yu(MG@_mjveUt5u2+o{ZNBBi#X!{5XgY{hrKiM4$5oXX2VfIKfXNQ9)r z@c>TB+X@ETiVoXKKHJKX+bZeXs=F)UTQW%pCU(k^wK%;VPLB<wF@T4AIT3kTg|qF4 z5Mco%Mritw9s0~+?n^uqUZck%pEf1cSeJIp)|HxELIaz2O!9Y(({~ILckU~r@1KO+ z$AlPs2mxb4z|0|pA^>tYUe9PK8#asvw@GajU;89c4Ni0{Lgb6u^HPlR!P2;iM0l0c z_`2@B)F#?^zZWpP7r3w&w7VDln`g|ORc^OuifunsXg^GGKit46+$YkB7-R`xH6td! z`@0qCjNEy}NhGEmic7s9qVc%lp#pH{<Q9UmJ_1RRgH*+XG^qpLUIKB%K_(8Xh2zk7 ze7brxq8#u4uyx--O~&26=o10~(g;0tLI)`ULW{J}yAcslL1|J1DT)XPm_qNM(gdUm zQk1HIpb1^2iAWO=5H%o5=%^?s@4kDVbMKiulRq+(XEK>QZGP)n>+^-teQ-oj#!nv$ zW>E$ecO4KPY|MV<5FGv!9O9RlT9Xh)NW6<Hs9ntK)DybvpX56uk+8J>G$>)?V{*#c z#|EwMEzd4^QoX6X^k@6Y;Yy8{i1D}puy}J)IFUUJ$xZ;o%UH2kSlyF}0AgxLJ=z<+ zhJnHR{?rVXR~ak>cUFQzB0g*5Ix6u-QeyZ}PSAK#P^sk2d~iTJIJ*lRz!>v!kN0U* zmUm_Am||nH*WVY)vKy)|jk6u9gD(;39?bjSqEGeV<LV`WpUZMTSG0eAw)nXe{{8qi z`&W&`n=XmW=Df&K_Q?G8(Tv0gz{CjS#Gm^=H}`)=gseYUONgK+1?8{bY-GP(lek{+ zGct=kGE3w}*5<d2Ai5lTM{>~LgrEQRH;=&#fFJ`X&tTDEfDSglIEOTiC+c=4;#LyZ zGNfZl6K@aYK?fPIZ|soix~Pav-SWifrNk)r;QgNr-gBn#bD?ngRIDpQkX<EZzHaYj zVq{HdWW=WE^w#ah#K^`(;mnFidYu((ik`;xDB_mPxouhBZMj?9@`>9DdE1KB+e**3 zPYiA=Pj9Py+g3f;R%7462=1uM?`Y`k9BW$cV9)Jn`R-`n+R;he(aqb@tKPvq-#IzB zqd&c4@NLKNV8`f=_#w|OUVhg^XV=tn*X&%F`JJccw{|TPcdhcm4p{*B;9cv%T|4<O z|5|DLgWXf?dj!F~)AD<c5_@x7w&$>~QdoDJ{6bh0_gwP!&R6eUc)oXWaL;vm&+T%e z9}grZi=7_J4wTsUINtQs+4nlP4>%QmB{=*zcK=`OzMtU!&7^%#`TZ+K;eofpuRh!l zd=(xr7Val;3-B%cdUbfH{H+^CxBQv2Et|nSdYa``2T{)tZVw(rPanj5JBU3vxWj%( z6g(u!ACh$rDc^4S7lJSAf`hxVZU-M8Cp^EE{Pb36&#lylhlvj(lBN$+1|u@7Bciw> z%l}4XZ$@M#9!5(<CSH!r{dRai@z-7XUpWsW^Y8q6F!(Fw)UW*NL*CQxqCme(1*6QQ z6(U4_S6Ke8+-!C`^II+8clE>P={(q)>fg13zYA|bf3u99|6cp-h;#RPM;-5<r&53V z75_Bp{AsoP^T+0CLvY*fiB)c3T}f|k!S~wMJol%AYR^x#wFT_m<^A)3cPHu3A6jt} z?N)owfhoLqJ2J#J@XS#gLqlzhomH<@UWdJRMFS)FnDvL|y|n1pmw#iXPq+^@osd|d zb3<CPFxbtyD9kC!`|TC=#1EN|IZb!ASRWs=o^Knsgi<Tpw5r>+#*X}JF`q2|wavV6 zlT7#>_H0#RXXQ>sz*2GmAu+(+e&fsNa^k<A@=(nhe?X1DW(|c<1HQQ=;F@K)DR^V; zp?FM)T16?V4S<LX0V$$b#PZ2F-D6)s(#63Hpn@Mm^8eQx2FiS-Z%GgRw>P|M7%*M# zRu^tx-04%XZpGarJKg5b!Y+RC*@n#cf4pIptGfyll{R@Adsf#_>Yjjdp6~q|b8V-C zJgr_=A*R(Hdfw6gFK;--`~82s;UDKcS(7`4oh^ri0;YnvO}`2X%`?5>)OpK8%*t_J z3U9`qe->)g$Ca$?=nE}yEy)nP@pI#sCVjm8lm^H+RaREXXHl<3>n3(%#)9+BlWQWC zdZVD?y*If(VEitVQNWkij&uhihw?O^|In#za9tH(EA!U7y0b9{7ykJ3?;j?$kZav? zMWqdW{drWn1oXeW;co$=Cv*y*_>9C&F8c%sslOe!kRZi1oRuVVrtFHUcbb`I2wnGn zZ;QSDt4cD#@8&(GH*7IEqcO^73e|I(EJG*{vMS^zsvxQ|Q`O(J6P)^YS<2%0UTRBc z8vH(#w(!!Uz>=NX%SP4o_rfHz>~X(V(+thc%k;P%P;d=plMdNDH&2&gwPW*=8fem` z!brJ7$QS32_qYn13MnTaaemS7AC9cn!@T**n=exsDx(a5Macih8%9w&=_U@ygf0*? zH_-;CSmpa;-&S*mkeze|(0T4Z-mp^6J-CJ@g#Q7SH%(J1NL#7C=?#uMUV}|NMeB*R zRsh*<`*(mN?4Jf)*2L;P>^7SlhjPn^BhDH7EX(vYUwh74UCZp%fJdk9Xbp`>Ifd}r zsSm+gRXW$M>k*vZX-g*x&FZ2))UAt87kB@PomA222Uul@_=NDjt^O?>9YT7mfl3c^ z8rsTGd99j?>F0lSYgzrvL{570I^FZ<<^J>f8m|XuE$y)Hu$tyk$BnyE?%lF)^;`T5 zA0OJPjd)A5%63GhsEpvD4K7XtMM`E$v-27<0A4P5-t|*P284zRyLT;59JvJArUn{1 z+=hOL7h_fXVRKq@iC;M%rVLx1eADp$=y|}Lf2f<z2w>lnx$3@`V?X<C#Xxu2?8hTp z?U>I|LJRR~Y^|Tcf2zt=&;PPVC=Vl7!&Ywy?C8-;k2P>>RS#lu>otilao-z0&gz*t zeawlNztNj<Pp#wo%afbkfBv0h(4d>Q)%r#5M62~EsM&43J-MU5J7%hx9z5f8Cq{e9 zH?w<x;l@Ka_Fbxx;jdAJhez9Qbsif2`SJ8=m+HXtr$?CH*2~97$G@Nyqd!NVf{%|h z?kT)<Qx)(z`SFK?W9H5LivR5m8)k{lH%jUa<1=8M<D#1piR`9_88_1yr0*`4;8TA1 zpvfN5dG}>#0JD)Szan0{p6$fd)2V0aA^hp>Amrv!k|axLk{Q+$neAdGwOGch-?xmo zsbDVlH7oIKoD?*m##|(*Db@9;T<{YO4%Y@HXkb6XJdy@9N=_$eczeO#&sgXUaA#oR zyfjOi>Mpw{2_=2MC^nqk#tMlSzBt1oj3}@&Q)<pm)0dHvUK=ti2g1E2K~nD-3D}Tr zxHm&a;b};`Y?9+WW^@g|OtQ6x-EvNY8AWbilJnT*H=Z}Py-HpwJK4s`L^MkQBoq7V ztp>9XLP~+6o*g;tt#PAZ)JYCoU_I>bpqWqQlhb~B9(>7pg{OP9N~a&_a4Dtb!K$dQ zUiUA1dE;d;A%ddv`TX0+H!UT*UDXCV$zw5dyu6*n0StIs>(`8(xk8JDX3bJfQXBjA zxUM9lqiimKH|4IsJH=eR@Ex{~R3Vy95jR$H%=(Q+1naI@^XkQ`*x@;`5sGj-V;1;$ z>my+WfPLr%B1_jUtFtbiy;*X^i)ROVnb9NLwG0pIt9bmQ@rz1uGUsE9y<9?f?b!p& zSi_~WbuJ56onG0THL|;3@3>%k{_TacZ5hW}wSiaa&Iiv<Mo_)}k2ie(>39;Dn4muX zi|?M!#1cwyl9onPdhE{C&tX9K;EJ8;6<@E}xS|$t{&t9$P{A7~Mc5XHX;BZ-R~IDc zaDq*mK;w9FzXw?<c~Pf`27lJjt6+iWT=*#<QeE1oGq(i~Lmn_|vwgBs%W+!9XjmkY zP0lA9D!<;Ca7Nh+G?+gScyB9yGGdwSb#^*D2-&sD&*U>~7q@Z*yVSzUp#2ZvK_Tb5 zMv$A(7k?K2#va6f4^h+k2VMFHMp1)`JXH$IOxffkXow(8oRIP|`zhTXK8r@mLt1&8 zqJk3QYJ$+CEO-Zy-gGRPO!vkQ$MZiRK}{mm)8b1(Vw0s{Y(_(1x@0_#kw4h+S6#j4 z9Z$Y)mdF&qLIH!Hb}p)TZNDEUUz(Mu#r$qPIvM%+59046S-+16*38Gl;3uV{-+b=J z#FA1yP|`}hOKdI)q|};mvOr&>rdrZzqni1GQQFW>$)_$TZpTxw>rhiQ0{G4BL?NoZ z@y5eHX{lQ5ow4q<5^AwczL$?yZUmRKR=;;mv-u`;5}=@o9coE)vZZ{e^J&9gQVH;D zz3^e2xL5CQpLSvJ_tdKYUPH`Zm@l7<51Ud=-QsC>rK2ALUoYe&YvyD|+i8p3X})$% zvFyjSGgAB`?#G;(_3Cgzu#1>WsI^vYcC(*LFYPg*?~Lp_NO00;QM#YyN$NYeep(r) z{ScnHGGR9lBMWa|Ytx)OO8xsmZEo8?uayVQ>hOhp2{CPDNLS~&;q_%+Ecmrn&Q@xT z3<cFixK|#8PV+-~3A;WqSJr)pFe>$0v`uH%rIsNA^`-gTP^O6M<8gY}a^8gp2}voI zovB_5O1k*7UHRFmJetK)+{JYLkkGVmvZ<p^LRPN;E@i$1iZCt=ERP{2-xz-Jddtre z_soMUGQWa1(~pI_-Y#q>>G_9Yx_Pw`d-(|J#rm9(?JLB0u+LrTNH&$OWyNhhFTx_~ zt>lZ@;{aNkV@>zhML!MwrI+aejg8_X3T$Y`B1LYgjC+g$pSZ>+K+)CSwwF&(adNK5 zxw8qRxBN9-Wex(Kj}?BOU#_Z~$vH+b{PdBK$OkWhyXc!hBYk6}Yx3a!e3bY9wm*Cp z0UdeSz7{xNX40mt`E5%_M&bxS<vZV=;#=v-`yitBo6&K2i2g%b8vv}DCWsB`LAjF_ zwOF(c!3Q^m0mkBgip>oVdo_1^zHwM!^LwTGh;eqklWapEDOLkI1*cFTXGNB4EY^)) z)We<~ZTbjXLu&MqRdp%*Y@k;^s9eK9@h)<(cQ5@ObXjkbT`ArSNHrWfr>zXi?>f#n zpB681x)&QlLLhri4%s_#j2>=*jLdRzemx(TMRY4ovAQ6;kXa>T%0_>t<{=mxM`qF? zT<$c{N*2tag$9RdwQO%f$S6{v&;34|I5W0so}?=3tc~fNxc~ODGFzDbkV5^G9I8Nd zGRcJD!SV|PU@(_)vp3)MXvp+dE}*C5`>{!a>&pvVSiE!>IRZFD=lduhWF?`>ny7AW zCWIDe>Ith0Txme@qmd+aE?({aCtpmoyea5*XN8bnEZw9e{h=Y<)PRpwT?T}e0qq{L z<#(+_T%o8qecD^b%co6ajeF^FY0YtIL&N2GSnqi=FMR1aZGfrb@G+j3>LH3HGk*c# zsMIkI{?iSlC&O~itb9<v0`F3u%-yG+kI*1wDmq{0-Jp&ykoK)jx9&kt_AsAhQPg!o z%zq^3CXl;+QTiS^!k#h|Gl~=Fj~{1ofK@U>&Cpm%$1iaf180ND-ajKCO?}G#o;wC> zvhMatbRGzhao3h9ve34-4f5Wo?8mYYrGB%G%7FH2DAG$b15ak%o2;Iehb4UB(ylT| ziOa_)7z>m6=tQA37H7L&RoDd_IR5?omoq7Eu!|t&85Vhtd6XZXi;CV?r#K4tK7gCz z@n5bXOVU{>`^vpy!!)i9qCgs6Vc3Do(9|@?!I<-y<E26zNF(ml#(8z)!S<>iAv)kr z92w_g>dzFMQIzd_nTK&)LAeD%UwsaBLD!z0!VZ1iW(9=`R9iZWUw1AkLs`h*^XB!V zjgR0J8Ku$JK4UZ<Sx%Op*Qcn~vu~p^%c(s^)}X&5B!N{b0tw`Xc`DM$`-DuaONBVO z|5nE6R?%q8N}4JoTl~?SmJO4~1!1XXQdVW$Lp0{FH=p{9QYFiY${r;woucih<m4ys z<fr6X6YoinZ#F@Axa{6{Q^^-gp6b!;>d_p2nDU6OIg=FJT=a`de-pEsHlUDhVY<CU zfAd8l^Jh)wdX4H5S`~0<o$qnB_~UHE@mg$xnb|T3P~Us%0*EK$3)ffK@Tmd0s|3)M ztlV(Lyo_wU4T{kuNGFUeJyY@O*TwG!CJJ5T2Q0mj+0!Tc6pN?UigHXN!^kS_j~|4a z$aC~Obf)04KoTe#)C{PUM!DP8ql>vJ*J>gcVJe5My*qnR4=aSzJ+J4zuIH*08lzOh zbMB;jk78Es+<m3T1I4vLy|s@hv8&^WQ8o2%l#*<?p=;v};`uj!T)nxsZZN#Yo^9HQ zIMFCj*C>3VNxZIE?nDbq9d@_hV#6ChNiiIzh|5td<$5s+Y4<NZwm4dLwDS_a$J3Ep z*O9`bRFxy8LgQgDGxn$eX0LPKaX?qCF=Xb%%f-5vUr)UH`Mo>J7&897OM}S#7!pAf zOd<*r&Zs970WfN>6aZvZ&ru2hB~kl@mHBFjydi;*u)x7*yo0sGp>irmDe-l=@eLI` zN|z*P#v&699Jc6r8$}vfR34pEmhom8+YcNQpRSbS*N3URL#TZGAUg5PWJ2lM2~5NL zsUn#O6Rur=fZeqZjtw7tRHlM{d<butic*=5ZTO%H6!$jO*tNCTsB9I8lbWhJ6BS@h zJaI;!#cGYTu&A=Qcx_?on$_$z(Ih@J>k~BV&jp?y)G!St8nhzyWJO!`v*DAKMH-3@ z6tZHGHYW2Mn?M#tUV0p}pm!S<VuO}efarE61Mb9`58!uov>G9Of2q0=PGVkrR7Xj| zbV+eKiRy8lM~}SuPn8iQt621y%C9EwPL`7i-YzH0P)R$6YNB1nJTjzRN433CDzu9V zn*r=!-GmZ>C>N7M8`9wgmR}i975RE}>(%}|d-~_4+R?z%qc_2FVHB<L9`!i6c~!7P z6I;x?>F8fz09Od$6#>XB${x6LT`&baod!1vvKlo;zozJSnW|LwD)xb@U%KHcK|0Zb z{A*dbkY0{DQ|<i5TcN#L^%Q-XQK?CwVEq)bPe71BO5Sx5Q#MgGvsA1!Ra`YuWDP}r zV?idGV2X}e5HIjz3R^3W6W|{iFv~62i(Kx$Tv!NRtSDEkh{QDsl$9h0#fJuEBRl?1 zbK3W6wP!<T38JKP;ReWjvLYM*tjL%;TYr;YeJ|Ga+dr0M0pYmvC3H@?!_OlVbRHsq zBQxer=7iSuEjn2}YXL!`NHn_L{c;iOeJLdefeF(HmdPwHkaOwsR31Lhr04@u&Rurw zk&-bHu%)H+Gtx$y5iq>Ur|q=aZMy*twKFs!nI7o#>nEm#lo>3_R5I3YI<}kDnHo1( zCZgHimnCjm*mT|)Xe<vhRhOAt{Xs6ao2%?6>t^0yK2Fnpps81_saK(it7|z~t%*Bz zd?9N;G|$gNsXZIh3UNI2aa=*_){EWkH`S>GaXe)Kz(9250}HeGa{g2Ai>_<dQA&GQ zqZaZ;U9fsCyAfKwCqs(NdRgt-`v%=iwJrtV?SzZ?uggEAYXU$%X2NHW#0^ds-R&_w zaR}6HBp5#Ib2<8|K__7K$+8u_#xGno$60C=u>?TUgQmn^n9Ra{?AhVjBE7<rJ+kFj z%^g6A(-}5%j%7PbaY3@Fegs91Xo?sqT`H0_i-T!BollxFQEH{gM2pY&YpE>R^~P&m zhQ`k$;^%4`xD7!njf9g$6qztn?M9Z{jeBN?UrpDMvJWXbaf_PsSFwD(JMPCGmv21_ zotFaGRTa`Ms}N036z$EnL0lyIJcU8GhsK%8yFM%Scnyg`f;3y%l`|gs9_*VRX`RvM z0?^5C#h%HvQV{k_|IGR@GMUWV8+oKnjxM3A;F6LsboI}(@PIxwz%Ay+ql8|iRuIn0 z<m9}jmOkj(Zy);jBX!nl-vY4{N19hYT~zf3A->$u@IDAXI0y|y_}?-eDejeCH9<5H zW@RIuJnHdo5!0W1mb}vAaI5alxx;XRxXNUYc37`o66mhjfppxV^l%Yab6t;WszWrL zt@7Invt+xVn|6nt?F<Gm1Om)Z^oDx#o3Ebq3whMj+g)|2odq%&K0drV)t)}qo<691 zcZ}VT(d%@zOirNBa08S^H}wV*OR#!*f<vwReP*-0`oolg1<LgqQ$Jr(gD|}Z&pRHx z(kmM5C>ql%p6)3Aq*wB-qhwR>;X%j4W4%)L&QdO1nP6v`1g>1Zvs?{Vq0?DmgsZgd ztUQIQI@eis8TZJy^HDIa`c`N49b8RfXH6#VabD-+hd8GBTl*AO_q?<26|R1;vwke9 z__J(-5l)RD9snK6IW$Ku{w@tbYd(q45bagjU@2KUf3{Pl@lS_<XL%AYSp`K=&417) zB7sHrKD1^F)_GBM>VcVJqR8+nY#MORj+EU_lMZ2V=;{ktKjtn}NzM&>@my0cjhd&2 z9Z~>j!fuebhnwLdCQ`%X7pFj)u({^xKgENm)I@tV8%2iFF*@TtFJI8EerWCuWKqxm zh(&_jl#Ysn!Dp2z=mQp2qPLk2NS4~DBJx_!jMBj!jv2xZ>FCK>uu}Br)N0~5-<t?L zj}}{s!|9ureDNN+*zTd*w=_Fk%-MUE!&_;b^;{#+^=n+&UVqE4&Ro$L-{8nB6yNPG zGfh5)fKF0?l7MQ2=JdJt>EOOofi2KWAX${chruro-W|<-*HdrTcI)e#Z}Aapm(%e> zs53$rH`Us5<6@S`zq;jSMSvfm>)4~7K`&Oi?y0QU<La*>nZNYg)ayr=Gt*9%#A)7} zFZJl3u|;3f@3D31Eq2p1bszo}EdxMZZdf$@IZb979FI?z1iu;E4r4zRXV`)=u$DA^ zt@Tfn(9_OE5+abtzn}gh(x*Q8RZ|89efLRj$Tf42B4c*#1o743ZIi>huQ*?d{eDi7 z3Sp5CG*Qg=OHp!pqMfg0H-;UjpHUktS&Q0uDs3!j3MT&F-mq@Ar+KQN`u}*tia$YX zA?K|<y8uovd@|k(Nvl^PZTRhr+k9X6>G4{mU1+%Q)aK^<IENga;BTY-@A=d&oeXjK zh`;~a>8gI1?K_%gRM>G{yYn|}{0BaMUR{SOzADczEzT`IZS8Fhd-W=szPC0lpaKnf znC_mqzbyJ`j7Be}H*DdW6Z$zPh3O6J7hJ#cHdRPMq@&=5@7P0pqQKvdb4{14Pggs4 z7v2n*dX)TbV(&k-+0;rpvgZqTeZYG3*C^Jf^mmVzuD@#?n5zExb)=)9PS$O4_rmtD z^{aoQC7nM%mYdsJYANCB=vj|W8428d*u1nvIbj~aUw5`H|4*82`h}K%$Ct}wwcY(9 z9~pxlqAi$>h@=EOds*^8fnR;ucn?Iqi_i<xn;-8*;EzH~1B!s|1@8#|;|-JdU;7mL z*A%=P5DEP+Z}?h$_JGK*imm67%|iWf#e|uL;_~rOo8ntT>WQM)n`sup{>*$dp^G?0 z**u4r!&Ubj#5*Wi8e`ZqBbFTME%qjJ$}PhdKO@YtPxAR!a@(2EDn$<F1I%+m(>g12 zY`b2Yy|WuQy<77%Yg?wo9#gi<XQ#Aa@!tOZYuVy!hALHj#<<g!ypHx);`xmgfZlx0 zZt;5`oPE>pJD(5jK6~zBWW$GP*V}F1QTHw>|Ccu$-X9H^Vb;V;(go)Hs~U3W0vbjH zKKg~y_s@&xCiOrp-V8~la=Gi`7kKp<l5G5rk|vAdN%S%xA9IEr$S=IKbO{W0HwJ)N zkHPIr%!Xp!Wgsf3eVGE%&R<HF4>|zz5l}!c=DevS0LY32k~FMTXT9&Dt<PUkll;|_ ztmYp3E64dlS+5Unsa?<a!L5N`J`W?O&eKbi!E^MIY;oalGOc9;0)U*;&P;Fk$=rHE zn4azA|9HbM_!?|E<xp;9YjbY<dd5nQRwEr9&o}?K3<$>h(c%;bLMpi}oz^M~uh!3k zg)a;b$mO37RAkF_5>1>Bb#YJrQs4xM>(BLjA~e4<R=3r><v0^}Hw!nMMTUNeNA`fx zo=Ig1v;I%<5Q(&*1rDJ{HPQ%!T}jr6WzJ=p`=@P$%(G8p?FS=o75#s`;cK~Qp8}63 zi2r!Q5+j5Dr3LCSyB~rd{ymt^{PcJCVF9xpH=ijj2R@RK&v#@X6IFMqoOz5m`LE;g zC+Ev}sik1Oc3S!^K7Z~YX4+9gDFsa+L40Z`BJ&Imhd57OnIbkyeYQz}t5-Zfq#t@& zw}&8Of{?5)6N<yIDRD4E{jx~l01PYIlK_##dP*r|_sNVV2~GKxYfa%ZZq|6EoN;2; zsiCC@`emn1hFJW|1;Txi6jW_Fmx>F?;zC!CVH-75_&v%}ccNV2dVRd`rotfhYiLGP zpO*yiu_Z{wRP&4GDw?}sDEVjw1MoXumDU1TTUzAg+-+U;u)87rpIRi%FHXGBI8Nfo z7;4X~(P6VQ{3ppaMXeSZ4)39t56P&aGlTre@6t|BqPYcDd)Ty4!?1NC(;M~yXA9X$ zA35GMw_{a{OxC+V^%R^PLa+wUc3iD7m7QL4)p9UN^JZ3sdfUy_Vu7&pi!6dKldh;O zB^P?4D%B%8-s=8H&dZs(Av8+&HToNwcZX%S<WJvQ-2-a^2|OwE+NH(>^m{Bxz%iS@ zjc%?!$NfIA`7ZDX*j-CZv^cC3qf=S6hiMQuhB*rN&d!?SI!a@kEZ929rg`;@NRZ=W zp;h{0)w}0XKC|8AdwjTd`uMdv(=f(X+mF~Cc;cb1c6)-DzidKH>)pIp?$x>Nt)HVo z05O4Iv2RN)v`gP5sYkbRx^bAx4>6soXVScdGhiL(cTisfpH!MqwQjrz%*Ek8s=d@) zEkAoEcCKIbpR%%0D1P8_zK;o2;hlQ(I%+WPeoJw&mAWzXLZQ$7)+$*QIa84fV^5sT zMZP>#6@SMXHB!d?w3O$!<7sG!mDK&OF6J1U-GWKPt&)1JpP?sM-g{<k2|S-+QycPg z_P6uueC4t3*c7m^;d9GkqI4jv+7|vkCsgo@*5-}D+i49_dC^`AN&Xq?>47pJt_yTL zFJqk3!J$_u%AO4~Njgq;Zk4X087ti8c5OSa$_&d2XHd|h%j~^(X^ct+Sxt1=qjEs7 z7nP<~dRwsAr$xJi=%L`##GyAy>ObKVDz>qdATZXBII(D^NQhn`ta?7S7u!-HZG3*@ ztnd&n`|XB*;p#i30u+tWh=K54Q9M=f=IpcW`%OpQJ)#zpPM_;cStqUlion9N5ny@m zx_G@Vlb7Sh)y7Go(4d)e{w;!~wkIA|Bbz_=X2Q~7m|G0bUN}zC4lCo1@iUh%e3zQB zRDl*-`*-?v^}L^jYx`-Dv$8!1PYg)VQxbHV3qM&NB&T_fon48#jC|`VR(t3C`sufY zQ;)PM)uBJ|Cyxo9(=Wd6Dmb+XIAbaNV*m@C=XDEn^`C`vpY2vHvt0AF6nQ`KEWEAB z{@S%u4?a#W?pOT<!FU^VDyo+&Rdz9Nj;>D#iKsr&Ov{D@DRYXhN6fqZF52`yEe-#> zfA9(@9zx<OT4FoU5oQrj#2%91Fy9E#8RV9FjR(vt$yBswLfmwNcJm6uL?FjFQ6?YC zbET&5^=U-1O^x!EOCcSCW>jXJo#+=WqeuapjGgQF9#`~1$Iys5xx|;mdh#IRH99+v z*Uy;U9ZBXcK_rMf0%0A@p7y!BH;w&^zh69vntp*$XnO9u5sNuF^XlbIFV+LWGk>;C zV@WWF+MCDh_H?rcAYLEu`77zbTr*r@cFGI7+wgDgu9O-QxL>VgEB)5dXS75lHjo6n zNYEETE(U8WcYX3}?-6(ch?A-ZFvq*jQCWxp?kpG^Mi4l30*wgEmlqEnVybhc$@+2q z8$On%o21}<okKj-Y`h1xXbiSzefX<8FHRzN><``aGVj>8A3vrW!5aa``)6HxB^tBX zH@&`yw5S>3M(@P#JOqiKFNpcGAaUn#?D+3q-torg<@CF$pH~x7VvY|s37(t(=wp9Z z(87I5s5qKvmbr`-S)J9hxfw6a06>%65rx1802P(BjIlA1%)p~cfWpHS7C}HE_jSgx z)3|x%YN2Z*n+L|mlfibS5nLrR(e5EOwJg40#=Z$8Kca;)jJduVLt9Isb4u*BrJS); z&K~2_4*sG`B(WtD*FFG2T|z3Oxh=|sDnHK-(^TfAMCN;{H83KF74pp-s^Zrsr05eN z7^?~7{9L2Z;_~bpMosLS>Yj1vkH+fgt2T2zM#?IwN1rDi(I$Et<uPzo(Jk)JJ=`Lp zJm@ABDRo@5r&#%Cs7^NTt8pG#bw06oLSWBf9z~V|cHytoLk96~8X5)R0<f;AGNi?1 zfV`7v0amqk=SIP^X5uo+C^W1jtPJIW7fkW!)b+=^lX!nhBEC{tlHJ*l!<X2vmqI%M zTt5L^i^jbA%c2=8qU9`xLH>NJ#*j2)$S44ra80<26EN<N`dN<3qP3=>F|oknB~DaW z*(>kYg5+iKcbu&p0k!k5vE|Cmo)iJrIFu()FpZQZ+>DmJjt07?L+a3}%jkYZp(16e zWRD*?G*lX}B?;Yx%StPKl$GHjd7)V{r!2eFr^wE63}Y*hN#bJyhWS9014uBT3>Cf2 zR1}Moaxkbh%z%H9BahHVd6kU@3l}GU3mUai7hJPC!Z9Y9g%+6fcupmWc$T5aCj?@) zl#M?B;4|5Tv9zu##^@&BEv4P%@POGoX1Cyk7Bcr}6Yp_!kEl(V7zSuCO4Bd$6!D`O zO_d1<lb~_#9PLD&!sXn<)U-(rfh&$^9uRuCSqi7ADP69qQmfft|Ko|pu$?q&)mAVi z7_n<Byd87`x}xex5)MBhwvjF%%Bd3hUUPj}$Lp$!ZPVKf^xaq*sst~rn{3lq#wT2+ zYP!b0{-nXLjyI6TL@UKtNg|~lyenl25KVC^TCDLdv$0#-f&|A7!7cEQ>+yn@NT`%D zS=%O^A3IX(v~CU-tvhI;QOHOXRjbasnd7OUJf~pS_2<t#ggreNuw6rRm~?)Bwy0@$ z+Kz57z5Y;MBo{cyQ3g#3zL!)AX>Q^UT;@M+ULI{E-6d0yNj<s)yt-e>0$EH~)I+FU zkvl30>WDV4SY{%oo!Tc%lCe@|Cfz8?u=gr=ERo|Xw1GS!)2hS<R}u(3!vm?ljYDEn zTWzI#B#t~x27h2WzmqOl3kT8!#L>j^GxrMJVP>_w^~<EyH+V80<@{J64kUJAS)r(0 z|6Ez)REA^}{_*u?SV<6fK3=S{4C|1i-i3AKWwGOAvHMPv)Ma2(NOy50WNay?Fc3BF z+bk^oC~H?e17G{nkw@U31-GfA#~zxBl{i|K#NFf7UFOa}LY0wfMmG^=wR{98n^hhF zF`#NYOsMM&Paj_Ng$F#q!{wN@Ry-Lm$P>zIoNf@{RbgkQ;<a~C@vKZ1UhmyHVsYt= zt;ZbzQJmXE?)z&Y&oZI#x5AUaP8{Rn)=hNm4T+;N-bbf#Oq90J9kGOcb!l0sX0`s& zTcKFIpo28#0%VTm46i$uJEliyXyT!0?}ZKz-bzXEIzR+xX=QtJep}0N2YuzNwowaB zK$nEfXRsXj3a5EAbC|Tylhq-%Vu9JWJv~Z;a_1eiok@2kqtODFNY_hfmfCy`C~XN_ zia1+2%IdoR0*B}kK=eVM0FlC<Rwg)=VY{3y)K20x)aGt3yRmI2kofExu+&fO>@&kQ z?%fk286@L_9X#)f>M@JAhzwfr8CpC1{WZ=5M|<xg&#S!zX$(DEv3El}5q;{02j-QD zex8?VIIXNNSJKZ$>^e<duuSL)S`c77wwoKWbzkBTC;<SVM3Y1;w0=4~M?+5N%K$~2 z(TY0)H#w(Kzpo1YRQFsU^XB%66nf)*TOX1I&~~1JE_9eD6>g>@SYqQBsdIUUBvC^{ z>8H7!APaOm@`k9_-aCjot-~g`^15hQXi<tku1BGeWsXR?dig%u)9V2bo@3Zu<Az6v z&vZ0!Mk<OVIv^#&S{DmK5mRZsKYOm82a0kmiz?j`QOy&I1%47Ir$q$vk%<rml1MpF za9oFE9U*m$pa^vF@M3`?Q6Bu5_Bf9{o$n+GKq&@bDqrLwT=bcwI34i<Ef(Eld?7{U z%IV<cG}M#3qN~On0%(!^GQotMJ01}!@D<hiu;-KLkYs$y;~B$L0YD)srfg4$EESMh zZav`v_a|lPBOQ57T9%S!!-!A~Mp38ljTb0qv2iIo7D33j%}TU9Ry#A5&+crVIDjgy z4K$pioa#NT|DL28-Q&S#(^7u`>P<t1qvMhHd4}+)Fks7EewKCQJoT0ccA4)P$#}yv z&bB}YULdhf5<l8cTVBRIFVnl^A(VoD`g0Fm(|S9}gR++=T2G2<gJfQwjiz+StOhC` z8@oulMiy+gi0^xdN3C!Nkc3QfWE%3MhK2<4m&I}qDGvv3*F+YaLJ2yb6~hdwPITC+ z-4th-h;N#py7;9$n=BqL3&c_3NobJ}kEh#uCA<*=#c0E8>cT8}0{La7@ZZW`Xqs3T zF$Fva4@o3yxyW3zoC`Nxgcl3CC7cwWWH4taFD%m+cw>kLt8wSEIH<H1Vm+f3uMSi{ zhnBn2X;tw^n#W6M6(&%_v@1x$vCC!XsOr;s7y#hXV-M>gbVw+^;69Fc0(Xa(B&uB< zR#%vE1tO@hy7>s7^+MR>Oq6s+#EnH-l?P6cCr;>1RLZYh0khxCR7k-v&Bw=|FMQhl zjqa=`JS0IziAKoO+Jnw(cqE{{RSb(xJ-gj#-CnLXhb%-3>lUV>PhRHgZTzR3bMvmC z<{#xhb7<v1VlX_1g~up_rNva_vVZmyS*9zj_4J~MN{o&)<Sp|ggw{}1h;`}J9nZG- z&w8On?n%|YPI?soLhw}qy3dZ%;KBEZ3L9cx$s;>JE@w~Sc_vBd*E}y0_c28@fkhH8 zW==GSh6xw!l6JBaWGOp`7B~_JVY}5jd%JDpqhwE{*gT-^^|C<ua?_?rlWn#jN4wZ$ zSv9*W+t>xE9zEe9kIn}k!cT6~x}A&;ri2LX#h-*)RYYm|RW#Exg2zK>{(l9cl_Yti zdE0>d=u003*8cE=Z}tDO>nnb6p+ozQB25&VSm$44bx|L^JBn&w4i_=g#Qh#T+n63~ zlYDtjI1q1p{^ILMP4(Xn@i%tjA9v|w;{|J&81@pZeOV|4`1rZ2W51myL`G~QB|e$f zIMy}Rb6%{mP$UffW^bbo5;peBRr~XiWQy&pfY-u7g2EwXj}7X^_?cexQRVqtpuFpf zA9ahKmI;OU@lB%Nh)GZAb-y?G`yOvFX&y6a-92glck;BshqEys&Wlaf4FL0U9$iL9 zhjPn<Yd?e<Oy7)|j_jU}`8#bCqq$1UIn7@(MC)3hiYn*N6m-uX7yq3tGnlK2nS0zl z*YJ0)$>3x4->Z+7ojCo4Jb?g|h)Ao;$C1DD?+g|`#4OBqFD%SRo0*8S1}KV{-hE0E z!u=9UX;LS4fBO6P6VPyp?cWEWyD%Aew(Y@Lxc4UO%Vn{D%V@(D(-@fqx0Vezv2|mn zH=O@saKYf;XT0I6x#8;LN6s%6N?9s>KP(Hl-dz13Z`ew&T>J<xUMVmd?(skYpJ)LD zWJL<0V(7^)>FNLI*-URZcCFy$TJfcKj|aY1m(_Oqq9k2;I?*CQXt{^~+Z&GE$cxp? zKwtI43tz4HmR^cT`z0`w|LJa-jLgfQKmPqZ-nul|Fd*@WR#t?5`2io@v@Ga~vflZ} z;5ORYS(Hu*7k@;$WceHsRfEW_#V*Y|e~g(g{5$s4$1p%!WPmJM4t(7kC^O-<6Dp8h zcw34rqN27ZW<%nc`A<3_glAbtbbs5tB=XaOx89wrMQDC!G~<+w;Pp=B>MpeYzXPLk z_8(>9h0E$4l3@X!^4u(;zSrgM6if0I{o=L00$dUb@fZaU-?3`iL-%~@mcW`x#pl`x zN(B_Yez`ksRN-{4zMaHBSH|Dz!2o*R*YpKIg!Pk<=;r_OhUrK^U)+Cr!|D|S>7pn9 zA8$DI-_eH?x@j{{yqOdCCywbFUu_Gp0dx2CG^$7c+Z*=l$vH~du3#^9J7K?8$SISg zj2_L^sk=~R{h@07zr5i$XC9g*dA~IjJ;_}^*B1D(liwzDu{-+5L}<m8;R4$h_`7YD z?>g%r|KklmO5(bVkHp^9i-qYmdk=vXC0?fKwS3J^-ua^0{>G)bdr0&}Q5vr8>L8m+ z%OdRLv%u8fed~7*^3>*LyKetkJc=xAywZ_+tkTYSzWt@y_Ui+7gU;Qxao}*vsQ!!n zAI7%7TO16!BDR()ZWv{Xuj*GycYiyPJpSTnbM5=bSErhnj{Yuw-bu{7Ok^1l%<%<_ zC%Ka$vD)qwglBk+J09v_RYu}bipcWi3K}ZI3x{)fCcTWQ@koZH{2y<a!z)c=)XFPe zdojr?1NU>tE7R~Fhj*3<!rD9ALi}+7&$i@$d&Bn}9XP#(cTXo@$-O|f0&882<@Cv4 zyGBdTXL`eOft>)!F*(mFrZ+6b#`^yjX}Opp?Zp3xw7Lu;3z>r#qEBQHnIbJ(si=lg zN~J*fWQN*LOAn?AC^ALb=E~Q170%TDUm~sU4Hganz=XAco6HnxcYTLB(4sPKwXOb+ z5L|^#u}xd;hdP&*s|#=LE5-dsr2VV(9tcJHy{|RDT~_z;dC2EC#kS9%EYy4LB*bt6 zjpJGZK$J%J-6zYvNxUbRB5kNicb1#L{yP)K1t<i1^1nse3gL()9XaoA<v);U#!w>H zTR$<_R97ckJbSC@_r;MH&x3pQZ@<wmzEw2?voo0?6+5#4<G2w?**h;f_rA}xNXQvF zyMNmJ6i+#pkRa6uAe+6|<&cZ=L^iy8pQ75!m+QY5e?Z6X+;PA20{~W7BBqDRJ74uw zug+!VG;gHx0cDKENPNzI%keWpXD1Wz%mL+~0&X_EBVAAOL9#+&()kF06NAbJW*sL9 zdw-ckC+L2y`AnoeZUx|>S#sl<0DWX-_NIYxVU9T>PR7JUyQ4D4Qp&nA`?FTTI0%wO zG6n$C+!M1;&+)Bh;(ykBEes5wsyOT3$tRy53XvfK6t~9lEb?^x0OvKZ61_BT;^w!q zq-H*<KxU-}l|M{CX|3{}GmiIE*wkyD65X(n9uD&~_qCeJT--T>oj@M|3rGE&5{pd3 z@l^nzVS<@e&4Mar7m;7J`Ci`!hHf;z5;#%c)F)mS*gPzCJD}w)PUKnxVBT}RZRWxo zPC!xEiyyXCfz6!gO!|Pe;%WTdADtUK>tiqev96C9{+J5b?B*S*c=}S~!x^rZ0Cr^t zl~pj1LF16GXY{~yHW<A~OXaOTzH@<F{V3o1tpU+n8(V{tiOSnUGE9;7wL*3M_8aBr z8{2O&gUUO@*y+HX5#4X~JEQss8#`mh>?*tCW`fst-&x5w>`vI}{Mda@uvFQbbUJr! z?}LkP!`_tZtsi^S?ujb<Gv0aE_GkU78}{eC<$L!(LXS_{s}E7HJ*RF$c7I|Am5)Ck zXt4Z>Iaqr1)hoh~1wDH3>CS%&^jUeenT9u{y?%Yk_H|fWE&?^`elCSR`9%-xd2sNp zOw-}_dVs@|Or!gkRbPCmpMLphK5WeJ#gDFY?Ofe}BSU+QKEdFlt-gaNT{jPxqzOBR zfXt)aezjl&;-GE`jy`?ssoO&5_n&_cXW}Icf6<S@FMq8)9~0SQyjbA>oEv<HDbk8m zFh$yn8OQ4XzKhU*etY@6Aoy0eB3M1CDb)@38P%H)){@i3b2|2tQI!K4DT7q-_6nsB zV5|<&ZT}IEP(`{*0%}6xH`~XB-?@Y3#qqtub6E)wsAVeo%P^nT@pz-w0oG$+BNee- zo+Q&(xV*wf^g#9nZ<&@D=iIt~Mbt~M)g6qy#+`y2B0-$SNvK5Q0gb|~G;cmH_*H;~ zl3f|%lB=15Np@<$%)9vY_5`hZG~6Fa5o|q_R4a-wdd1%yYRx*gdPw5}Fet)p5nxQw za@wU`6I6fcgZ<poM!YL#w_u`R=+kV7X$YPJhhY(H2Mju;^$5IY9t^(Lw&$<+=2n!( ztMUQ|%|h@HR}2}|j{+&?dq8}w;?O+mspn_566Xo*n)@zh7u>ffuZF%JBc)D~$Dhc2 z;<M7_)l<L2DI>Nt)2HoBOSv#f78!{E1B%cvrm_`W?BsS<VCJ~TSAXRmE~`gKAv-0o zbv)yJqq}AyJ~iI6LTDz*0{cw;U2;%`@W*yPE$ug_Z`V*nH~j__EV4OtCYNE3Sti1- z{a6(nX|U_1tnv!zceur-_{l6e&GM}@zoT-LrLq(c+x0X%pHtDGH90-S0ju|Dgm?oZ zL8m+l5q1dVtwLIyd<-OdaeS_Oj;wSUw3%uyY^#6C=vN5}O$%_6=00OpC8D4X&#aXe znJ6_^vhhfDy+`J&JnWM<Q%|-&@_^rIr@?hgT?Ul)o3hRZqW)#EzxhXNr2LIjHrwK~ ztTEwEAjF9}zh)Cc;W^YxO<=M9!#I=)A_28#B{&BQIG$+|4(hhRX5pE9fppp1@ynRq zyw`S)IYRoCtLO6G&VRWyku#qDgjwibSc81d85wyJ{@{hv_xaCa+ck-L8jy^jK56l9 zy6pNZWurdE6QbKo3DLoNpMDkgzMOA=8oTrM)1NofuZ|jmW2ehfaRfXhl{#QB<&i2B zUIvZK@0I9bBpY$;HyRD$1+PmcD_EKE@NhIGSst+pJ9#4SD-24$K_mFit@JDWBXasE z19_=La9&7{?Dc5QQ;og61&0g)nWi||KoVHC5s$ny&LYC(&PXm4<RXWqZic7uXoN+( zwnr-TQi$*@papxi3F0=fQr2pJqp&4A-6yN}cqAmYrRcNWH@%M?qgO{;N_GO%IyucG z78cU<fEYh4qm&~_mCSRmG0xnG2DzkQDkK?-uyz50jhV+ie>&anb|*)HLu-xYUw_Ga z!jm@bEPNNTfGqdiISrV)y)M-S5xqQhIjc_?(ZsIAN<xH5k{Y3sYsxSwPU}XN=KBpB z-o7+w){u#ul1IFa*$dct>NCNtk!#*}sUPS6J*$*A_<8;ANhsanIj=)03xAq1n?gvB zAb}AtGXEP);xI*RH*ChVP{ioQ{b$=Si6fpSe3i!S3JBE{eci5Qu3Hh}l7^wlXO32w zj}3ZwV;ONbqCZ2=9rjqG;eL`{ain9!$SYm^6U(er*MtZ?gidHm5R>Lrdub;7q?A*; z^@v-utL&|R5~uK+`GoX*4{1MLQ>}YMfO8`Y1Q`N~`6MZt&A~1MR_7oPd-!q>6Hc~< zrdY<U@cEtcMQk?iT42e@pgVCN^Zs#|>#raZBFsc!O<@ko3qJz~O{HfH4=gzT{fHSW zYj;4awxxdGT3P9nvmzxEvP@h<xccQxvUdskQi&yl6lrf#Vo;c=Ky_Zck~bc5zVYAQ zlXK?1^4W=6PR=X$+(179Ufo_eIe*Y~{P$<T@$V_YPkRHW3^yJW!2G>6zPwl-VEbYV zU%O#Sp5WTSmMl92&GZV>)7X!36Av!g_knoxjeQlKEj!$L*7CP)2CVy)3$g39^7Zq$ zo-~St2v3t1-C#Pa0LX0uM=lXER|@}0gs*17*9p+4A@EmPq+teZ0_ii8MVOGp&)ve$ zV(=5j_;o6Ycb7DU^pVIX-1df#hmgksK9da6L?ik3J%V-(S!c*c)(_4TM^Un(Okv3L zlB5x;kGWsmHRm}01fO4f2)M58tfcJ-1M%+);%r3x@!9xa_v4UlzLB|c*S=a(C5^@p zgpxpj-xTYEGcc}7BR4HrUkEJ58P?qhgMV>Qy@%)+M|{(YU6VcQ$bXiokhGeJpd+~! zmsm*vppY@ghhs@76YM24vY#Pv__}i>5#b(SSQIOOhJ?K`wkGZv4G<Hm@{Jx18P#&& zdrMPTXhs~TQ~Z(=8Wd7#nAG;9)aIlF8X+}E7g_7ajAM4C5~2OZ*8P&YRqe38B}+6b z+~kVSi$>#icc0cq<0e9SYiat&n)LZ3=psi(Uq~u+)shHGAE&3S_oR)ZOh6vySK5UV zC`c9=9Ost(p|{>39rgkVZN>PE0PcJR0EF%%gwAGt%tFjda<x$*w=iHM0^2<_d&LrG zHj>Q*$!a*xo;2=odllMENa=Hjjb<6l$LW3f?8}5O02qfecw-e#2W6qm^mqEK*<6js zXJCDxyT83NA9$M&X2E2vt<55#;fJs~Y8sUR8I!zRRmyI}0NE4S>)pZULLiYy4&hm_ zSR{M`2_JQbDNW|YKC?DEo0-%nQhvjPqbWC2n#XWWmzO&au$0S*&+|E-=l|LaTY$RD z+)E6#$q;B>n30Vv&k4noZ>g}i#@1*dTN=|bL}nK^LS~5fbH>^1iL6%R*%M1J(aKXY z=)#x|?adY36JE1+DwJ7F30bo~xNAR-^eJM3v88Mg<FFzIymX1RaEZl|dS8$u7wJ^U z#_G2V091Q}6S6GFmW=%r^RD@ukawVgKF~PH`{mydPZ&1?2&}5(1@*^N(^o`js9%vx zpV^VIqk=4}YZi2!QADQX@Ol`|_W7g(vd<DA=}VAY0OSXOO)-Skih-DvJk2Cq(~?UT zu3TJqhgXDvfBHk$L!iCmg<*Op`x(%;S@0PQ`-O2<w?=q05t2KOSR$~UB?>gRLSGr1 z!3wSZY4`y!>8-?z6-!_f0{c1=4(ZE1aDnvzd}zq>_Q&u<B5?@=RhnbR6WBN1q0ayn z3Trv)HimluzpxvyzATvTx<y4P;u$rqY{y>S7pCq4u{UPDfnjIH#ywd=v=~F~FxaJJ zS(B;oXG^e^u&S8zR=uU>Hzip!8Hh#(G^9PD|Gxd}W2O(<$SGvO5$X=%pd)ULv)wU< zyprUi;2^UhP|>S7v2$+6+pu;F%z?FHcpSQkfiQK)D4R$40@$l@sNf+a6L~+bk^Mdn zV!6a}Rub|S314NHk6_?u)-x(>Owx9Je^ag28{xB5@({5W>J5E24)bvbZ;mtHRL%Ag zi!tnGjUelF$Q+U58l&!xBqYiSHcw@9GDb{Lq0yc7qyekr<|o(2!OzCY>j1a`GsHFo z>_dgu>A_CZIW9D^>bpZeA*+ibSuIP?w_kx$$6;rv?3<-fFB_P1%F|UZU5W+QE|G&c z4(1gpO38u@G+KU?<np05-Nv#T95Yx?g>XEP1S_SoUX$byxJYU;hW9mAd__WssMdKm zjGVmnS(jU--r`1ZNZ<?0s1NK0wx#-SvsK*Ly@((QVzw`}z_kNXjBye95Y4dWG%@D< z>JIHRepJHOw%~=URz&vh8Mgx9<5}m(jSz$H|8bAwmmuLp4zeW2rZ>C;<I+KZk0W8- z?$Awl4ku&IX?JKMA8t$2eB0DKEZ`(9%YfP#(-s1MPlP{Mg46&Y931Rz?g)b~HSY+J zjEiunnf|jz1nxpyJ0WLMsH^9NL0N!Kn>(CFgcpTCq6r)!ROXBQCjma@j_`B`uZ|Ns zkPz}-`!ro=hA9#cnIZa0p{}?t`h%CDk6*4`>@wY9p1qLU0OnLYn>CW{bR%2TIOjAK z{#3H6VjO0If!x5kFul({W9VTelo@vVw6MG5hTg_W8sGd&;tkr($9eo+G|_pQ_z}&2 z?PV~&xn_mSyOh;Yk3E9=YWe{7<su2tNC-u;mrFvXsIW+LYZxDVJ&Pma4ZO4QVmBM^ zv{Ro&be~mGpG{Yv-F%<JQJ*ag(ASbGwIMLtn>^2e1v*=I0$?$du!+WQvKBOw%D&Bj zK5H!FjHXt&gPkytg0~lw^#;RS2g9QWBZ>y2x(1`?2V?6`DxB*N!Nb4KR!taR^bmz; z9qYTa5a2-rY(5zH7N;3gx>hH!&r@Nq^E2<vzb-j?T`KyfT>p)x;*jf>>eTqTj>c}H ztP8~)Qp+GmemJ-44pt8V7nQOHxxaM<09J|6SMK?h`on#$!voR7k%4c5vUTFXfaaw) z<S$X_M^H~6^F3+!D=J)1nBckuo-lrSlcV`c0neaxKOuUQ?mFu2H@c>54tdx5@WrTH zwtngNjt@Jn-(AOeL&x4I3+@xRhS&ypTM4m~Irl1&1JvHX-%Y5<;WNM<q<xpqTH#+i z4b62m5~ttuQfPN6RD1zC%QqoqF!3cB`Wy*uBHGLREte<Ns{WmL{Ck3zRLgRVes9nE zUbpzYs@r>vJrW!9-e}}K?%I2N1JZotz2U-pemAu<Z>_#JP7=gEI2wF#a{J&M^TDO~ z!-eh-t_vS7{r%uBHsxtB<?S}*6Eo#kJax5uDsW*c=<igB*z|RS=`gqH@R;d{;_0aF z>1Y+fS3A?MKn7%$nNphG4hJBycqY-SInADHXK5zu?@W%^|03x=+^PQm|AC+39P8K| z$KD+K*kqn_%#4to;@IQZBZ_j);n;f%nMIUQL@37=*_A|DiITU`P|^9F&+mI(=MQ*Z z=X$-a>-Bt$+x=bM+Hy%Exr(%$TBuzXvYe{Oc~_sa_SL)c#6tgo6)u&PimH|SRfre$ zT2|X^sf&8mRqUFKfaGk0Bo@7CJyCLD<zzXJbj!O&Yt=z4=OM<XZ-DLekagzUD&UZn zR#r_FV>=dQf0MoTW?&7Fw+5mfE&XKwuo=Sk)rb`^$ds1%VQ-Cof9=D;`G@_7ACA}Z zLAVc{>K{(4K5h-LenqjpJzoQ$^1#2Bjt`fZBGwo_tgQ{OGJaTRv|*<{Twk{4;JCKI z*s%uxutxp17Jj5#=&hY4$+n)dA#Ss|dcHcRxVB(z@E@`8_|OnFgP7G~f3eQ|!?@r> z&;)N93o^5dc6_Bd2>KS?)x#Fdt!;Gmw)yjI;}6>=kG2PYZyA1Q3rXs7pUiiuW@@#K zOkif=+pUfJRJ#~H;ln!SxoY-yIqPkibK=OSc~6#Nx`pCx_j$lo58ta(j-TgaJ}->A zmo$8S{hE2^@G{{HJ}s!cNHy9;J>SiGZoRv>`A?K>skxMl)0t$4;amxv+<DKQ*e3eM zz2JxH(ggHyaBxkS2%NEWkQIPnee~~3yYSbJnJ=w5G5LqMf<Xpc9{rzgFfROyY#vB> z9cZ}zRW}?w{v2#ahPbSQX0B~>3w$#%xL=}W)?oWByOKG(|J!R6b8ih()f{6Iim7$b z*6-E?OUwiizq4~~XHUs~Y4Bk8*1_S217@DVgU}tyy5?5@^gmIp0LGyYC(08^VCd~b zhP#JMFAiZJ4_T>)P&P3AEI1WPC!GXV4+jaYL!4^Tf)5!BYr>GI<HDc#{jpHVydx)e zi0$0*rMY9<!($~X+li{k32OFO`R<V{6{zkB*?$xI-#rlRvLR^%ScWoglfREigY31A zk%IsmksluHP@9^t%a?wfm;7)QVcchDsJ4aZ*xs)!cJ(p*>8I@Cf9YrWs4G7AXQ;=| zu&|$XhxCn}CdUfA9IKPL!j1MTziv@~C5fC84NsFrP7_9*pV<<8N|<s7>2KzJEzM)p z_4{I7GxUI+r5C`Q&&<-=&g90*JURGu`GIp|yYsyl&Q*C#O>KV~^ZwlP_|pjZ+nlsl z=FvwOdAhs~qX3xOjhJUpEbOOD)W1wEMt&`au(rYZc6J!I<7WdNY_kz_N6nunD5ick z=ElLljh^T2R20+u7c9$ptjo4EBL3T}=zqI+|9$yrwep-+t^fDmUFPW|@^$5{(HQFK zZR#8E<$owPK*xT$5fRJ+iX+>KV#tg_n#rfO;>O8r`5WT!>52=XT|vbcKG8cAT$CE^ z@YeF5$(JCqcLbGK^FQ<%%hDNUthr}XIavVogc|Lt`A>6V)c(Ns)EZ3-RUv=&@2gc! z*8FZw=c-V<JCX(rhqHWkxvO2SqIT2io2ySimA>vBt_qcaxjH_sE8KjY{x7OI3gJEF zPbevj^!H+y4?Ra0niNA}?+&*n2<cMq<sDA^W~%gWLkDy`p5ORkn);z1?;7;_;nhAk zlfV!BN*6Wc<5<;|U!flc5~+^{oKM3y1_MO|;0iA4IbEiFn~!~MOD?(&r3=Wk+)<ER zd*AK_ndX1w)dLXJeRHMjXzuH~#|9qz398>`N@~qs^dfGZ9j6?8ZhPScU4j{XhYB7J zQrRWhDPX<?Wz2`P`aEq$<q;H?MQi(T=&b?W-~cSwZiX-T0>4R)eqGa}0<>J<C|8_= zUCJH%e(Xp^;0%adwsB#~>anOUHz!{$`8#Y<B3rU^axTwdVUoeH;aEeqZA8^lu`9am z<qxM!6yLSv@*Vz|AUl-|bgO5BwXGz<4DR?q=W@P89w50mu$$kn?W~(l-4;zh`p{At zEvZhmGvVb~vR!t2uW0U*v5~^N6J*ht!`o@T$!YNuV8Rt`od39@%&CJb-NB_}N9hca zqT%G)ruXEfYuKp9+xK!$^0d5S_eLv%AMuT5Nfu0Oa$2Kw=y>={>{1YJ4U^E<x|ai? zGHu37U01?hG-kgQp-4Slb%}>0S*&J=jV)YQTUKXA>dB_CIoOudxj9w@no0yaO1&%( zp{PIgB>D4b;bPeQdT?w5u#WCn5^!+ZE2OLzCVwnCT7|Xxy~Abqpqbq6Ss6$!)D4_` zQ|=9q)%GjzZS8tf9yZ3Oai@0;-{w)T(@}H*uiXv1<gjOa2m2FX=HvOOJhs&H-h3mq z&mo9$s-^Pj4*zh)i;{=I9c%{Cnt{q1#u;(7>?u5E3g}U`aPulZ{<bs<WLGoCHkl`& z`$(>-gI;D;vz_f}XZUE$!+5prxaKk!mBBdlmY##F8Ha-vZ7AFRVLmho*PkIRfL;l} zvg1cCC=ZN!@Ltgz@qfw}`yPBAuKaH0b>p=AmzvEK$^M=OX2&n_BixqH%CEqKI(zZT zl|gpB+4#t3`hQ)2Z=|YGBf+}HD*|tyCx~|pUDUYi{?}C~NLWV#dZFM{JWto9!=LL@ z-;sNfTc=p=!I^5-fe{I=jb^KxerhC}O&0!+VEN?*mYuDcCGw7VLN$8Ou)6zH1qYlb zL-rQ`n&Pm0^u>JcAX`RxZ5$^ptXj7qHN&<6>(f;ORXN072>woBjPK0M^_0elYg!Ni zO{oUcl&pD^X0;8jkN#t3&&8cow1#z{%Hd+!!44!&KNJWdic3LF*K(;;;$*wUnC$fG z`6l>SZCq;8mb&ElJUYCDb)t<A=D`3mZ9C%;Az#WmoaoT-iksuUndyxkXKDL!g_%K+ zHUp3|Uvx;2;W6uZEeO8MJ}Q$zfjvzB&)@+XBjAP3^j*H6-?q(e0I*F(Fx0XVze8rZ zodj3+7fPQeH}d2^X7(y;<_j!Di!q`5rB?|8uhvbGwh;{Yq+_mLYTB5GqzSBs5d+JZ zuv1^)v5M?Wy;(1tt<#ETl%*qZzG;U5l25ykk$wuI_*`*bSDQz_heaxYT==Y`7GGPe zP_KD1pAU-8BB}1y)$kFudYxC7d$91k3?`Fl^B2FH&+>@`reE0Uod4UCb64hdw&Ae~ zw+Bp~1CvM6i{@at8<$7o+s^%yU|)Ra=hA&a?w1g7*CH!NaTDp}Gsh>ptO8bV-Vya( z4g3*<(nJ!IJ-eB7rKcg<2Q0AIo+8g`XXltk<d!NlRVm|^^fv;>G`oyi+g@;9U&113 zDPhW;XjZxK4SuC7W8nd%mlNS7v1G|RIG(=ck&gT7fVotvp3(_Sh*6dQPB@syN0j7u zb(2%qg(Ui&jwS9{9s8p}Q&)@Hj6m}(-XO&S!98S}=yAcLr=!_dfrCn3%OJ!yip1A> z#C)YJuVb7h(iZp8L|QHU;9kAq8@ud)Z6X(Wo#^Kq4%MpJ63p*0X5GnS3UV1n%mT=P zc2`*J%Xp$+7?Dfw5iVR41h;38hTQU3%P#HmRsISP)+)e>RQ+2Tq&E#G^7MQDpGbRX zlW<~mbE%#W<4M6}4??s?z(QL+blh*|QZ(I3{F4mO8(kgrOV{dK>zeMU9HfoEN=xBs z!j5PjHhTzv^y3dQf$l}3S#=n$-@EqPx1gBX?<1}CZt@cOe<JNC$=kVFe<#NEzMxs1 z6Sf3CYmaM>Z6u@EYniim=``+%N%Q=-!G5rADzhArS%ZI4jX}?-CW(;^o&;&=eT}Fw zRAV_EyKX;GGpgHUOCP*jSMNZMZjjOsyy(2Lz@%m)0?cDYx{Jfa|Dn}*Xd}}57Q7(f zSjNZx9LM$u_-jB`qV864clD#N0FLNKc7?_mwsHAq?GPQJCqv|^I6t~O`k4|<q}A%v zp8dyhueKG>WY@Q{Kc8ywlad>}UdtR8ZY)!hpKULI<$V?h)wm$`#_=r%URO4%03|uU zGoMA2agsz^(Zyn4o{j(GzS#X^BbSOtZ6PpvW2$AfnSNOqhF4|HdR1j&pPg1W$=Qfg z_38@DIUlyMcKpN#l<jdggrJ<JRA6hbT`#MLHzfU5aMKm#9Mfu_X!;@KL}9`mzW-?W zHVgd2j>#m=;UR&AL$QZr{fd=4b`|tQY%2C>>&=)QPzu5E_+fbgRUFaJ09CJ6$@XXW zisJdkF#Srd@NJ2$rnakz+(;5bRT1azKN~qirxmE=_D%kIq^~+rAA(f}E60{_E<F~G znU&-<5K`s#lDa!y97Nvt{W2nZ>dEAg1)Aw9Gr8%T&l0pgwDa{Q%fp8e7kW0gd$038 zF+8bd3)RE2Ct!`$yD?c&TGX?RZa}~6W7fZCFaH@10@4Sx+gJkfBm`=B&-;&>F2B~R zkc;@$H^pg?uz3<E^6?|R{+SAk`<ZXp9Q)c-1H@g+h14u{e)-qQ-$cbeZ?=0b|76?k z{`$>{f5#_71C3Ore-~6lkpn#k90AO~7rW-QS#GM5buJ1CNmO0yLE&}E&%-Z3^_p)p zLGefpt|*B>TU}QKG|&Y)-L7LHma`|DlJH)Ob=$~|L^jX{x#VT|05sQC!I1!izC!fs zLTcYi6UCft?<w*4MwVyU{W~PhyJBRwV3MN?<n7jT(KDUOII>Fs$!<}NSujNukrJS- z!9R>CiWCKu(Qm$lP|N-%Uvhbf4<J|nWv>kqs*Hp5E^0kmHW<^zp4(?zq>}><?>X)= z``5t5;_j<{A2!5G8a^P~a`L&(LFV$wICip>MVVASMs7M?KHB(pu)Nc5^3wdk)pe*A z3LJ&XwQXp*v7WjIg5Bz^$C-1cL_oa(NzM~mbqHQ(x@WHeWSk4xz*fpFjT~G<C$<iC z>QwbiXdK^6jTeRbO|(?2$<AmO4FLF!dq{eFj0Hi)0V9fTnPh=Jk#*)_J5;~-lxd`o z<l2{>3QO%lqpGhFy1ArrcQwvZJ{s#O6ijn+Mf-2<r3k$@lUFs^s4u7)sxcbT2|gTq z&euNJDNC)sXl{gO$$h3`<C22U1IxvwibytRO>4Z>CKKGqH(_MM$2^7mDtkbH-1Jkt z%Q%`2QwCGtODCuMq}(x*tQt}D(I)%23}_C*O`edi<;m1;n{k0AG;7FL!*i{pFA6g= zGx|W(!oe|VDJ|2=;ArT>en_d<%eph!cFFr+ZkBtcrT7~OrB0E-;_VR*Q{qJPz4A8A zLE1K{<&*EtecLjx51INrQ*>+SuJb?g=wYKM$aEJylof>jZSMswijKQaWvdtXCduoD z1Jw`~gKF66>3TY1(ZIfCrJ6NF!dl-;ghnEJ8quk=6WrMKw(4r$NQ%ErvvShrD;*J~ zR)gf$TE&a>paR%rQ6sv(LF-K)N$+J#+OeEe3%)q0eonCJ-+-zZf$(v(oqy4xtf7tu z38!61gjWGer1=lJ*-dq^P<wh^27;cB-ksoC$b#ik#MH^0Y3b_yzfZ&$<{_zfbVFZS z0ImuiO~2GVWv$_^gVh<FzBgFXm7`-3Tj)r+jslCclWgK3SD#oiSMhCer#VzG%CBZI zcQykkY)t2j94xgYFcgI+*d?J~!t4++2;t+&3}Y51+|<d0<@*J@M}#)xphn*s$n%SI zVO9_)%!K$Set&kdzd1yD7aSB`9^TCUul=HIae0EMHZZ|#PP@mWjBHXyq`IL@o!B!~ zA&cd*<b`<o>dXb1cgE4_i{-T(K{ezTyAYhG-a<Mwbr`-BF`z%d7n)2Ku&e_1)w2{m zEA^Rpd)XmOHhW>29&ku!!9cP&d}!E}K6}Wtu12qxN5X4QKR<%77c5!6D!v0~kq7`^ zLpGZSs=8?K9+cB3hNmhG^V+SGLOe74^E!B|L_IyVQ-h%&F;#&*m#?0~f44&ejEE90 z#oeGBNiNPnsnY*QsZMjrvCGLJ0raNJ;E>(qXTMXDGqcy^$WlB+<0Kj5U5t~FXjm~% z(tFq<I4NjNAe>2D?}no+zewV%V*FQ$8=~}4+4Lwi`S2b?=jCMT$|8jCgsb08#!nsU z9+%>uP5$>qE7_X+=JHebo;Nha6A!4IUv&zVdKcPEf6p_;&6Ym=@KM4$sMWfjjqPI( zb}}EAUL<k?{lwX3(Ahb|)g)e&=1ICO-*KR2OCv2dtn7SDvKfX~8XdX4L^E3K=&ww; z+V`YhUamAlYFuqMQN@!-rpYG_5Vtrd|HHy>TW*Szn)Gx4%@p}SR9lAez>g88)Jhim zzW1*0p1UVQd_+^-lTs~{;E^@Sj}^O|cOg<zsqu|a&-ToE>y^LA<>A+Pl6CZ47|X|W z(re+W^RIX+(^8y!-dQ42b>it=YTS>R$#`=*xe2k#T}$eciqoRcn&J_CJW^fyE6cXf z2Uk0mN|)m3xn%P^NPtTUc}>u(k1WOodNP_q+Mm36o}zg5nnJT)Um^=wew9Jsqp?a+ zT@xfUAk}h$6qJ-A)phl9Tyh{P^$zTvQ$?FZ64|#&d2xFF$0wGxp=YuyED%jklgTWf z8pv`AG?pPb#0cu5O}>sy`PxPQXq$ZPkmKF4Zbjrf=m&O&mTVa3%!WE{b>6D72I6F% z8e5h;FM#!Lx_Wj~79Z$n{B=yi$nEXp_wXI|dj3@&o2dt<uwki97LLpR_Ahn!GnVZ_ zFKNqzhdd*Z5X&TzY<Oxgfb7A*@nKVUL6!V+`W00=mJ{x~1?bJzBztQ+dcy*p=MZ_g zxlzvuvPD@kEz+;09TF@`e;ozUM$w)+s3$<T(umFkffM;XqhoLvdSw$*=(BZr-^xiA z5N_ay?EU4Py%R$YY$k^`ZS=Ngx&z35?LbQu#9)pb+yr^DE4>=bBdxG*`H$t{H<<LB zPiyPWeL-}3NJwD#b6kM)t8HszJXvmx&auq0yD?c-l)lm8tqrO}v4A|VkzA55vvKY# zqf@CH+>iY;8$R>Us;fn3kSKCWP#FXVAiJ(5Df$jS_C~M=w?hqBQ-T4oYohdy?y14y z^bSZmhxKHC+f--I6o*~bD`n7jhO5-*TV+vXHe}r{SXetD++h0-NqQHk*q$<CPL}Ap zZwCd$?2?T<=?|NfSRmF{dZ2jJd*^Gct~SNZ8(5v0UDzb-(<fNX!QPs7m;Z8$4Gk!# z(b)hpUbOc=7;{PUrcoXw&=cY|0hM#1i<yIXmO&#KpdqM~#TB|>&y@FAVn`m1#3h>x ze_?TzJiE~PbcW>$U6RKfB>q;4>Hm23Wak=a0oPWwEZJkdbi6SLFG}{S0eO)ixVe<( zc(TWupbMPNC@vtdo!K2VkWwD-40;zd5)ef$Q-_8uwSNT>$cEpNpXZQlM4w(8gxozW z^g)uHMd|T?4*s1|stNOz_!YK6X<D<2{0a@x$pe=piN!R%@kEe|R#%vR?;knpne+KW z4MN@{@_fRxJa&mfb3{|or+rY>$|$lkfPCGYp8YSKtLMH0kDh&jjEi<#xk1XN@K<;^ zP$3cG+D-OHLb)&JeBRkxN4V+<K|!B$>B79BZ0t{Oy}QaM4qr09_GdwSUO4fAL)zrQ z+#v+sl|Cd~_@)9ZK1fsvC);Ct-&RZqm_wE!^zY8Wt~DUJbzZN-lxqO!vvY|1;g`Us zl%NHu5*(zx4#sMy*te7KH>W%UlAqh=Aj5*e1aBx`UI7=mnv2|5W3Tk_xFe42%y6Q@ zd!i~s6KS=gROrdoefR$-(%wEHC7<a0$0*%@NB0*~*82YcMB2}IJ^E;({^6tfl_}%9 zth^bCqV%B?P}A$*O|M6X=6%1OM{kBal3u3^jiX=Kf(GS%$HzfKd)`GP(c7Prw98Ux zkD^XA?2=)=<FDvYm(&D=Pl#;=CJEf5lXCSV*<Li&E$>tCI$5MmK;sVdS2;9PR70rw z&NG#u$aUV_yq|$>ki!5d-xxW1nH(KXAM!ai?BmZ+w(H@af4UDsZ=ruhJO7IDzkVx! z*stklT-&?&((CbU?{LjzCH|5`5%|s+H0JbI68$NGH}00!X`&VrcLFrU3>}DINcDhH z)66I%LH(aprHpwq%;rehpHFjsoo36>Vbj10hX6JgkRC%k#x_33AB-8KU2>D12I*va z2pVN{_Q(`7+jwjqsaS?Cm-<^b53CUYWQ-%QCy^TNlaPRvn|v+S+K{H(bl933*s>cf zx9M!+lC6_&*dRzMhje^|)Q;I?tDfXev%j5GqH<Dl7nNv!NPK$xrgB<xSL)5)`!{=Y zlg$~DH5ig#P;b7VPk6xw9@0us{rd!Ees)Rs??vRz@mad@7jzT%6COV$Og$wa!ogbW zN(Yf(R^Rj{o^xG}M9KBDS7zsnpC8$`r_c`U9-g>-`+WKS`MX>hSVZ^L&Ti_(_vfp3 zJFAb**LlB~bhN1361QG}ww?cN`QO@kL1UJP;^x2tktB{Jf_&UR#iUzOE<~A$WT&KL zR(1l1Xv!sqWC0_fOgIRcL=;DYc07pkE}(DssfsQj>2QKXI04?1!~jTRQLLjQJeFZh zS8#$lVhBVam{n`YgvmeOOVXT2EM;qVezPZU3zQFwmbFF5csSIZ5{IT<Dyw)u(8GN) zDMD(87}s*8d}cNcH&OwaEFqE6_nyn1?<~poHQC>{Z<M>pEoOJ)iPxswm)T0g+Yizd zE#I^*>$rc8UaN4Nz26i0d7)AMqLZ4}6yWgN*I&x(g9*Qs<njL}((<a=z&!t3A1jce zN}Zi{ewxnZ4STcCrxrjV$`mSv{89fhR%-G%^xGeekJoqJJiMcLb1h`$S<D>?vxBuh z{NROG%?k|{f_jbDeEWXce9(=w%AQ%dXHzBT*x4Obs=@o|F3Q(1p6c+)v>1gGPqY(( z`Zibw@66r*k0G~y({L;x!kavG+pjW$EEt-$ahLBhofw@U#ui6rSAk7nm{p35QrP@Y zZOzF3OSLR%E4Hc^1wuq4#WQ5ZhnO_psh@bM4fdC1tH1JzlF(fCxy-E9b$aTZt4Es` zR($I+oR$B^A!=LWEy|mv=&dXEmHLuPy^ZFgRn(`FIb{5+0;;XsR+ffoP_u7|zfGZZ zv76iFM)gD<@cZCD(<E4R{Fh#tyNQ2(%hb@8<&m{Ckrr8(F82&sPgwYkY^c+(w^S~6 zyCHk8{6lA^@|Z%Dw@mhQtqGUm{vnp_Z+6E6>0loqqhzUP-DIooas~0BZo?s#)p5Ta z+Kvm@oYWEHxyh<`7|nG_>otS;M7sHRg0aAoc!XkCtjl|{s8n|ZU5`P}I)LGm*E)bx zNswSJ(AvIWp<(hT&N{!f-+oH2s~^*rKkY+eQ3qnNFvStXewNxi_sNv<uy!R(W%v*S zQ}1Kvf(?%Xz_5Zr_s1&Z0@u$vCSGt~&Kic!_J*rc#}E=(%EN+%N2sB)gsfqWK75uM z`{&9i6$ahM?UR_hg6cyuY$sEG`JLohgJVfGjn|G>5;fkq1`lYwy?XOpV;PsJuldgR zPGam^3N6-YF{IC0#*6tE$U1Y|_GDVVF?z^?H|qP^=trx{L35plSy499TkZut8=tjv zSoJ2l)#5Mox?Eq&d%G{dQf_;Z^eN_Nlf<8x*MpH6h)8pE3dciBJ2Rp5EY*wpJL>g0 z8go`BFtvWtnXcN4u(M3m7+{cDX&BLec08`IrRNPW@<3GQa-6*VKK1L<SwP-zN0(no z1dsAx+nFB!-q%G?`To{)QJ?=k;L^P1pT`Gx4Wj=3`ofTU{+CMiaVmTc<ebx(5OqTl z^I?G915=k{7Of?8j^7diVt+`HR=O_qwZU89efwBmf<rrQ5EMTEAS-Fcs`{`GUtA4X z(7@X<+0gci>`@q4G>T3FhU6%s4NE>+lne%J@idzYD<|OEas5y}NP;+bJ#y3x*q-6k zFAjg)G<viamU%C5g_{PK?s0tMeeQ`+3MFKI&8lNHokPPKL{rTgK!`6%8$ylq(sFjg zDQ|nWgxZc^F3X!7<kMVkarI;|^9@*f-c|OtC^J7}65or#l$T>olh%=)h1F*b9=Bq% z>^7~68qUh6ZOYZ`a~6soM*GS-H(#WtcBqy#^?#a0kS$Yzo~1fp8<k12(>PAGvKl?V zKZvnXYm+VhRZmlaMid>*J3xa~hsF5`>DGG0I}LGkEWPVwHCqaLsTC+OyH36^9crnJ zw^x6FW_DYrSqs|2%6ZMRiN}xc{`<}x4w9QAa6YMl>LW2M7X<+Q-a-lUECA6zv+4Fv z>N-^DO@W?lw+^wwMh$fPUqn;#3ySjhlB)zvjnnZoQR&|yz2Uyt<(LU*Jpz)Wqwrv{ z>exg??_4(cnw&!^Q&*FzzMOsGgQbQ)pBfV)f;=;rmYVHjk^~=)>m5>fZ!M8p9&I3< zeP7xER=tH?z6CihK6uk*PvsT~O_T?GkbB#^(Df)XyX6WP>)d_Z)n+$sW^fkCc4MNx z^+a32i%oa=<^)MN=M%H1n1Bnw_)S~MfP$Y|%ez;R-5NiVSR8caSLO@4pWM?|47%L1 z^18FT>rtX2-dq0tyM^xV?g7QnsFwF@$K6k#pDTuw<X1O1pZ1LDD@7KztbS5`+B=h| z6kRXBwrBtJ*_#2S*vBnv-y)y(eK=Q&8<wXrv`_nY^p$TcwtV=}`E=kQQ8{5t{^Re3 zr_X;5DBn71`FMW(^u@n(<s`7eI*_Yp5Nd!Ta#;<Q?hK10H;#J>{q-Doa-zVWw;O(~ z-MG>7<H66lLsQ@&+jBkmFjd;%NT&7~8*Pjh?GUHJ^TsvRJ{)_mE1o_hs&z{?2q8ji z`LKytq#MK1m>0P*LUp+8YwRK8Hn%$8f5~T)ps-sNY(rH!DG<q)VK_k4^hb@tj>=Oq zKbJ%qCBbg?8lZ;%En<{3QJWcnP?+|4u2%i(m#>$0J@2cyRCXke<%$A$dSYGt&vEN6 z&>7xd2-!M?#nRrsA^voBqD}w-HKXusk@rms3ZwYNPG%0?i!x(}p>sUu-Yq`TR583E z87%hd#+#iQWA+M;?0{V_L{#0!7Se!6&X@XS0|-F+tcKB7?dH1~KTYWcjueyiDYMl$ zvKr=<F)r%ni{cQfnck4%K}4Z|&}SnvseVF^(+G)uZ^Ah@&M(X2df$f=A$b6CyWVeK zHyL}wjNN7<$5-bO&*ww1wu>Ee5WomA)2=nLHPww1gz~3!oQ^VcWxK0OaG)o~272bR zqN9gbA12X@b#K(;btUFGZtEmov4KT0h;gj8n;Zp*HAFwz68tb{tb1(2;-M|LW11S~ zbqmLG(X#?RWwbn1R~sI>TPO6DJTCFaJkvvaYc5CU!tzvbd%!YL@UpqFn&7o83;I`x zr!M5&xPvIGrhYi9i0|@=(%PK8y9z;!tQ4Kkg0&(DcBerHsKoY!X0YJysgAbOwdnq@ z1IN=p#?`4A8_4HboxC$~`Ru0XJq$Ax*RgJ=a6>6Q_B4Qh05t|uRQ|ik8pA(XFLnRK zxE;SlVA|PDsiG2PlGo}GXG%JKmpcyM8YcXlp?<S8Y++S)l@NGiJ~j_mi@l<bWoQgA zMZKwx+mHa`h8V~*i?xg~QAB~IG|1b#%C|o(42zg+gSv!)X;-m~{4-55`#fZd;5D@+ zTg~ZrKWwW#5tq94v5I)CE<#Yu2dvQw8nT)_8-TVa=1#f7+e1WwiJtVV0<>sYz#K;I zJGyICgfk5-una11!m27@Rn{>$)bM9t?5+;Dc5js7rwLBsnxguL)z??M?Q-8bejo=@ z5gtp0Tn4qng0CjOn;bgUay2_1c3GGC;ylA~w^hUdGzZd%bOFyO&oK1F-7<ZdSZYL) z`awkPgZ}$nt#mjFza|zenswZaRnn`LmULGHBu!;`d;&V@pOW<588z2u#NEtF^@i0H zhSg5jIX4!*FL8?5b92J6wN-q|3F1gM*h!Wb@_;CNYf~vn9Qg(EJ^Y%qFqEg5jlrh0 zUdPRuCtq<HBnG*rj>pO&L7XVcc`<|f(nKb}=vSf#3dJX5z$Q!aI)~j=8yQm5EBw+$ zI<^L@u3nWVU+qYDQH;yfzL6<jRss8jK^bAyPemj)b2L1$)Q!m>dK;7dR8GbG0^lb` zd^qlhAXw#)DC-8(Fdr^fPnQ(h*3bsCD)~rhETRo0MbGmupoWb!Ny4@7j_Dd?KMa-g z!IbguZ$uP{fs$m*F``x&(KGbL8I$<5QT_xXvS~EdlO$+M(OsumsSN6#cPFiCg$^b! zT_CAQ=H`luT)<;&-eA-jhEcm)^S~0P*F#Snm>ol>y4F3Ox%;BJ3CuSvMUX^sJn2(A z?!bsq&&k8J8}}B+$*eD?Kg22hjMIY~tg??m0gQ@hmyv0V_yllYa)M+<;l`K4U}&81 zJ={eKH$d7`NqT=7xIY1un#LfDFvw&g`d_}Wa6?&|h59~~?_>_7oF*M;0~@ZC4w74p z=6P=bNYXqcXx0$%bwt^vdw4I9NF_1U6fE0>iBL!Lo)M6AAgc_JY#v5-nW#cDWDofS zX9NZyA5}!NmR=KA<4Gb7*slXH^C9<+*Cc~gtfu>TT)}XRf|uqTv9BGY);>f-X2s_~ zPelo$F3jDlpA$<MT)GM30E`@fc>5mlf+s0PVKeC>d%TTE5uOnp%lLVpKN*7@TAC=f z#mX%c#KI}u6M)n=0G<&e9Sed~Q=vfGu6X58dNopNcSl@-nD$^XvjmA?0A>#XdCY;S zJ54z+jbMNY?lb~l8bN3oD8=3^lm$XLP_YHlf#nSO>=D=>5m-%g*<zbLBTj6TpKM8J zb4hIAwIzlUKiQ}p+47R+@@m<Nf<45SB`r`AS;Io)H&n+5iy8!JR)W%ci1;`6WL=2z zk_=pF%*;(7S^T(r9>~{pI5SHYpkOt3CRv?TfRPgv86#<#WAuuMc|Py^2i)&eV39}+ zZKmJ1K(0CCL9-@CwkgQ>i?vdJ5VAi=DOt|t13`S1BBTfE5hO6L-eqo@YNM5;j^)~) z0k{N#TCzhDNO_lqd8FtNvVG|B#jiK+foiKM+{=T^(}OS?h6)2AxiMlzSREKfrwn6{ zNTK~?Tjh~8!S+vr`|GH~{Us!A2V!ptR;<6pZV)Im2b7pYi<J?d-jEjxmml&&!}|xB z0|3Jp_Om-#zanUVJW#A3C^kY69sx=R><i=(TW5w^GVn@yt&?QDQqz!v1L<Wa{$(sC zwjV$3M?Zb9Rc^3VZUR5Eus`zwKN}00dk#Xi3IWbQTBn6}z@%~(lFIiX)enu|n<h1u zS*wD;GD&H&v}K27fM6L=L=r>)aQ`azXBp8T+3lgoKQ*fXA5@DzQa?#*C}e603X0kf zt8!nGvz|TQE*E<<oDl<ppCzrcDs8|YZ3rK1a1z$#Lb*@}Y(*Ejwv)DPLRlM(m>fcB zImA0mE$xq}gKbWf?c<k^;s!tc8<epEweK6TwW1NNXdX{A*BKLsCt=fx!sbBuw)3cM zU+F)l(1Q<3hfGRvm@>!o0UPpw-xJN#N{N6ex3^MQJ<-Qd=C3<R>u&#T|1=WD|M$}d zBitZqQPXgd7<RQN>}uMOWDT0XNtwR}E!|F%$s$P)f;-|s7vezYAO6!>4?F+Tc7EJO z9U7kep{$z))=dVNDcIS3yIc>1zhAoKW6pNUj#W0dI^53zUnA*O64`r5)xsdsAW*J{ z80s~oFzDm%ZW4CPAN562ok4t9Td>LQ!B*Aqr2dd5a&?WN@n~Ay@f(btzJr}jg#&yP zN}$RZtfp})t8i&`a2XzPwJ{d^q+dvL&zrz1mXUJXF|qjZh-)V9Pa35A(egCQmk!UF z4B%-H)HKS==vT=w$`q6sdc4#jWXLS^xkC`kEZD*z@-;$)UNz&?obLfvB!cv}oYZPf z64xS4P$nXk9!OqkP?^b*nq}4OAxVd+%3SZ1xvh$fI@XM~J<#S@^jYT2aZ#@EQ);|7 zyvu3y6V%uW(y>Jgt#XLB61z{0n9B$Z?{^sF@BFeEl41B9JBU})!)7YTDKe0hb}VV4 z>TEo?PamVSZJ7lC2)bQdk9n+hJ1U6$SUXou=i`v__aVgwH8XKGrKGx&U5-jyYPz}= zN%&QiehZ_)=f@S2Sd~w(VTYH7{uxFdFPnItphcpas;n@xlSCFCk32PFvnSe7QR~)C zCYr-~pD?lsM}o_v5kd4*IUtdmA>sb7_AWzW6Gjr*AX8UKl}fd8BwrDpR1gAIpZiX) zaapam{7!sUp~JfZ<lZ>4d0cez(R{SBaF>Sh?xU-u0@?D?!@H#l!}e-j$^X=bZ7((g zh8ceh$va%UkHDgOrd={MT<>bkFo;Vzf|H#{b4+aR<6Z8|v-15h9K9MSJ<=i&Pz@Uf zom^g!Qx#|XS;VS|6VUYP6Vb}TY@qWlv|@ATj=GverIO9@3-@FLh?3^C@0d7@Xxxy@ zHbEf|qv1db(~cB563|yCsT<npRT5*}RK%&!5VO>fx80RH-J$<!hRp_sO$A1uLX97g zeBJzz(Zjyi{3MXqBU6W@!$Hx8TG5xZVlH3*@i3kHsd=nFBcwa6=ufO#Wp~`AxwzC{ zbXTLZ8?<h;J*A~anP~ZX=p8!n3^OW{ZfJp(mxm$>h{*Pah?hg^g4b+jNV$U`ktC21 z!bCR!tI>cJqN7~A1D=%3^;oaEr1{Yk08sl5k)HQeL4mPtR`s;ZOZH*%Tkmtds&fQ% zND?dy$vzRp>dSf7gN&wP3IJaq9=i}V1+dzgc3xPV$61dD9aSg)Bqg6-2NhnO4Sp?V zKpgu*D7vIm?A%*?DPB+##NMz{{FNfqgl@m_h&c@{(oPhwBvwBgdVW9=MiF^>dU>@e zED02g9iUU%kboz#?Yj|EO%g*9fwu@PrA=U3O=5~O0*hX#i!!Ryx={Bk32yxVMcQB> zJOIdNeB)jr1<_AIgkRuG`g8yGA5KpS9FJy90zjLdJs3}VFqQP+u@MVxV{ggm;l~@S zqe+kcyU_OQ&!hKADI-ZNFx?K`n;pt%LHvIL+muc%-N%M~k9BqHZ2l_P_H{Yyc6;d7 z%?v3ZvTU+vfhiS<T40U-v}U2t?(U-j⋘_$t-m$7+^)p4Id(qf^`zW+U_L%RxGV* zmux#E(wxU8?nZZWJtL}yJ6-hOz9Qu--w-`i-S5=+^`<_+h#yJeaR-it^^aZG8^7H@ z9()E*FydAqa8{mix>K6({t@=kV^>dNQct35O`=;$c%=mZ$0cp6q8qp<tVTfi(mlz9 z|3n%NCF8npPK@vxV@!-Oa7n_D>A;fZ08eES#$~{|67a@5@wNW|PgW97IDp=Gge5KU zUFpE`{egG0I`5yR-dG)EaXFAOq6|1;_|%5{QirA7lTFM`v`_Wdsfm*9!_M5#tC(dr zGcm#=qmpOnEyL$qylN^~gKgf=j_w9K{?z9?-nZNZ{Rai-WW-i*K6i#K#Cu<uqjt4! zPmNwp!%MxJ$VBBHIe4ofh_WbRZyia~(?TN>EcV1k$P-*P2SVx1zSZ$i?6kHnC*c)d zSnC^}n7ufW@6-z@*IykrSS9J`VZ}CRGWvK#0OjMl8I7#(TbJo}XymV8kU|b2!--8~ z&~z+OLYpYJbX!6lwBt+>++{M_Hx~;xLz6(Y`#s#qMafu#Xy-|Tg?*8vM2$<YJu7!# zgs}dQfL4K|MV^S=5NX^-%Ch*-K}VcNj<?5sFY?n$w_??Wn7!BsTg|L@Z1F!QG%ja6 z<a^rqs?5*wK~bec%ex}4kdi0VptpW*FXUM6I4Zb2_9^Gb#^Moxr(qjo#k!@BR=vlQ z8Rea(%hdwCfXfvo7mJ!M-8G)9&<K8~-gr9~$PR}ksQ@UI)-6B2ELEdPFB2`za^A~b zS?tkQ^-8|n9sD|$;|jbtH01r$h|g~Z?pzQ1_<}&sd+-z9c4a(Y#<|+PRLP|~T=B8r zw>54Za>d#1(UuvPVjRCt=Z^<LnlVfFuJ%FkD;J`6Ds8Zm0S2N*M8J<gQu6KFR4ULI zlyC57aMlR@Js3+dgArt^<JQq;f)}8ZUU?ViCg+O6UZ&r#iXGg8j$EcS|Esv{=q^_I z1qF7%;a8J6OhbceO)CWMQsbdzf>FlgGS9Sp#R=aul`%fAvfomgUH}Hw3F)e=1q-*d z+G7jZ`X{Poii8HdrS~8VYUMowi?UK7oY|Fa+;|_X>{k}w$`=^G*V;bJDdAfZP+cBn z<5i&ISLU5TV7BsX4cy_dHITnw72N|Q+gxcC`^+Ka670u+h3vDqcnQtoxMXLc_~W5h z_-|jnpw3BCUYngcVwy1j=|PVBwfu}bft>`ua-SQ42RxohIL;a807{C5e|LwUK)}5_ z2jzkHI>;+d9lja@Ay*p5-sA5P;QRr1v!VP^iO0<qcH4PF415jR68Ux&kwHQ+k81Nr z{al(q@$p^}j4k#Lpz`&+^r^|GNvnS{#t<@v=?H*lS;XTq9O@rrt55r2c`G+Cv&DN| zPxJNV_*;98n_g*qC(4F6LJIc~3~R-$Uw`zq!}r$S?^4WG1?}2c-Rs9~V8BIRRd>n) zb@A`n7`bYr{>eeJuw%yU>%-o$XJtjV^T`ztF2)-(EA%XS<(O8xCTHAicO65x-}r4( z=5gbWV!5vpeCd_wuVcQ~ln61w*F!Ia?;&t$8!4qetrV?N<7t#QS**v!r^vsDqE!)a z3x2P3as(#0g`*QPZS!?WjoN;M%dL8P<Ft4Dl3T@OV0$^+@MXAu6mIOjz+1O|MW4KU z=HEWVJ>Lrd3)Bb*>)cCVYNgu)_2aTDOC2eh2w1#-g?n|;+S$qcC8}1<2Ik+_>c)Jg zJGRr(#6Fz^&$b8FA8RqJk@$H@fas;fFtn+P*D&nvGBL75jVQo*#FO9%<9&I|0c0*i zvwRp6`L|AQxC=}Qny9-Thsjd#$uFGsHR10BF5+FB?;!ZMcyl)B<km%VSkW0g{j?G; zk((uE3C$3>T%wr9J<Ot%pKdMrTE#_6;I0_Sc{|TkmSLXmuLdq;5t*w-=4kNH1_NHP zgQQwHc++DPGal<eRbnZbf$N!9OEP(-GU`}^jV0h6dD)!ByT)igl*sQUGyP)<Tg<i> zytj#Js&pz@;&=MeqTkkC^y|Xdl;{IKvJpfmnjt6T(DJ5%xT(^T3X@tHjvJ7GI6hD{ zcbzFHiH<j2%bQ2E7)fxuu8Io_5)=a+c7mfipi;>w7QlB9p!JHx+qzRzFXI{hT5S@0 zbY8FB`d9t|23n*zoh9;FN69B+k#D<4S#VA)|9BeWq+kQKEp<r?k%g#hr_f(c!UVo| z;ZWR+&*~Dy^3KPliY439N1=v!ccOQ(<#FaK#i{X?gTsh@vt+r|T8?+?rkV}tVXtW} z5+aMNIDuva^vLml&$_ymp)ww1YeQdFKcb=ci&+N8UZ?+K&)u9K=_M3$cQb8VlX}mt zJ?{7k?;B4tcM~e(`XI5~>d&5I$At%MLyfcuTQI!cC|M}lKcs39u3liLy@vAUdpbcD zn9j={=uvmj6B5<;=IZs=BhvD$JY_3tbAkp{d|WjY_6x*#jZ9Uv5Om~u){fbTk$ROU zH6|V|*GolfIm@YFC}+Bujg@f8lg2J<dSDXUjniR{xE`!bnV3~T10E6LgTJai)!+^= zVvRUA0o>_@*(&~2rIgjrFWFw!%G%_A(<4>9g0Nh)x$cn8V<Vt=vTSDz7y4X-*UXD> zjb~Li??yH8H5oC|R9D2-lZWBW0v}If+esp=8R|6~S@UZw0sjd-oCp}EI=SV69|2Aw z+~4>sHO1L-rgtkfIwn&b^0qW4`4>W{@*XUAtO_YH%)YIZ@(JQl-{1rkHS*Qtvp$K* z{m@Cda(;tl*5&zcz@S<(#}=#qvZm?`M8_t@_@jd6<Li7-?T88{&7Mr=0EcnaXq5){ z4<%!c2d@kOo@=Z7aeSh16*()FcL^L4aM)j$_-v<<>${*QPO&F<QXh|P&x;EH*oV~I z9kbGoTsjUzBm^_jEELWN2K$=icxYed`m_Am@Yv`%e#^JlF$X-4wCUuYi}{6$wkS)c zSgP3mNmHu;_k>y;*4rsgV4s=Pow0km+bC87q`jEZ*;_^8-R&)?Y!aH<kU@zCcCefz zF^V?rtbIx7tAp}QEyQ<R+NB5v+8nIlVG>lQAO)s6v{KaVLeKGnliA<A^xY?=>oDtb z=6X9E)B9Fvbm_)kub@ubX~iBl$}u(M8i{XUuCo`YB)I)*2cF%L(s*?vBdES$8Ya;x z@alb*qaO+Jj0O&atB>T`I4G1nsMePnQtVbRf4HRSwTUIQ!b^{%Os_=3vTRd<%q15? zX%W^D&jZHzhj|xk#wd-}A#u|nfjQ(!+{c@|y*gz~p@SEdGwil2FIA0kc%xKq%rl1? z53^v+cNM}P<jm+}_p2Uj$!yO#3z_4to!%fT<>~uAm_4UHddBL&(#*k>+_xoIy_-J& z7gO3|wtD-&c9Z74>Qg?mqwT3dXYn4}%hV1uYhxZ*V0oP^3q#Ytiv~-L+{z9px^&d2 zC8}CBULB|h;%U-O(Ol1G3~wUAH$QZD{;*_mlUx!U5PiBw@L1X9#JYY7gi3uGgvgrL z&b|DM5kjgkg@$AGhYwR6|Km@1pgfECwap`DMaZxlG~iluv6H)C?c7@v&waUuPKW8G zq;K%ue_ihTgNeq>SFOy1ehoFh)4z`xlzp-r^zX}m^L|??)t`A5aBNl-&h`!N8JyrV zp!{6ed!IDi4Voo+X`ponfM#zo&uCaCA`&RPMWY4OoGe5QlCIfCxLcC1Y$N{B29G9% zhiQX-6(@k&5S*z61&i^N0l^`p^HsKgrfu!+;f${W>8fnc%TVjzaZEpOv>aU_@lQN> z0+)i~nGKF!V?%HbSX_bQS!mNlnZM}7{W7IEen2v9%vGLEb#J0R9|A>oYK12@7OZO7 zu2O_5aNH|s&VEbYB{V-iOzY(o|H^-Jo0k~BqBu(fSoaQhB#&PG+z_(Caj({zEKt~_ zQNqs%h>8uqaEkeg4_G&R;M%u@>O&r!3fwmW?tR3`5)2RNST#r!-o*)_YK3UVtSY5% zP|PlfKtAwVM@CSdy$Z;ggWn*S7e(+<n>+X)9`Sdm2y{gV^mYgg90~X;Y&}xp75PRo zXcGR8qj`sD<8=PB6!^tJf&c10Y9D4Tp?Ql~1%E_{{O%ArKN0~hyjZPMR1amnlP)Oq zjdV;9#%Bq4)|ylR5r^W{D*+1%$Kt=FGmwoO`Ruj_APKapq)DWtMW>|ov80`<lw+in zYp0aS0wSq()qzt?gvIxkltdV(RAyF82Ab#F(Vu@4QYn$h^iE{<F*4s?iX<le>XlSr z<nWxG@Mbo=xwF5HAR&@3*A*$>+bKVAEKgBY7>!iuiu~(yB)bL^`H7aRl9h0bq~vT1 zC5v)Qi@kISuXKrI{iPsN*r`lC??kR`D(9=BsEX@;oQhk)OkXJ?w97EPGQZ@(?af@k zc&GO@4i%L`tpF9ZPnIHxsD_b(m^>UqFM;Vxl3*-FMY&MT^+YSYLxXLK=?Dne-VlGh zFB$c<fz}C?jQW0{svNeUc#U2&eNoe;Q+q2|{=XskG=-(fNH~CCJ9zvZ#;)^_t7+!= zLR*mV$gz^m7oi)OjYH}3#r||%CwgCra`TI|@W%(wRlTBt+f6lDHKA%PQTiIJLid5{ zzOuSUQF(_173WUHo4`g+F$Q<YlNDOt{D~n~n26t^$UUHh#x6?8ftFh*f+!TA593GH zu62qb3g$%h_c42+EmZqpk$dQxd;0^?tj~Su1wIdPT01y=2Lj-aRr-#VD$%^1IBudR z_s;;mm~RHb>Rb10vA?3!n9cQbxf6FSwOfu%T>T|d0Q~L1ukJ+`@2Vf!G6OEo@bkV( z=;lxgcw%W{((|N4hPs*6BzD1*+q!&iphv~@wS(0shhV13v1LwyDS4Y9MS<yHy%TP_ z5L)BQL7?}Ev5ta3h?0#3q)?K_{z{Z)aMZ#|BwCG=Z)hxw##$;IDBW(e#fE49=~Sw= z(8{@tqH>CbIS5y7h!;lCQJ?Syu_V=PIGYzUmO5x8{!qBB;gS;LlHTR=nbDz@eJbcg z;-l>4wKVHH1STpREmWscAsXRKxP)<yxzgKpW#Gq^z8Gz$z}Kf}x%(W?_vJS4d2-No zHLh}9L5G{n{%{9(Ui<dr+L4CGkJtQd#ad%OOf8FgpiP$>V+IoFuGNQ|{EETxb>oD7 z;`%x~EJo!*Ub6#`4jd)Uw<#_<-QN0|3MMDsCT|S;r042lI3|Gb8FlaGP^OPw-e#J9 z%9s5De=@Eu`UQ6@^o=nn!r`mMzE^E6xHMwD%uV+WpUH7}<-!HAd1iKUJjnpxhz%CP z8%W;+=TF%Vf@;A*PHJ0ok6u~|(Y#i-=9-%JpuI~0rAKx=c#-+obn};Tuh6U$Z<gJT zLaf6s{o)2tCDrX91=i0w!er*Nvk1IBK;9-Jrs-O~TZD%>PT?ZlQ}!)ri%2c$Z<@{p zsLMQ&i}X1UHu&K<rME4ww68O=F#r^#V-%&e9G=EpeHsl3L^L(f$lmh0m;8}99FixN z4dowyJ>521cwdpDX+5h)%%bzZ>-DzQF`>#IGaE3mg4dnnUylo)()3d+dMhsd8<f<h zU!1y7@1L7WgWF1DygqYUs-{0~))qZ)eadIh#`lvT@`j)pcv*NABYaqz$aW}n_Dkpk z=JrRlFtjI$(d9N<T+$C(yx?`hc`1QfdRqf&afEBxM~kpJ5(8B){w^Wae<x|Ul<ZE4 z9OHzkadu(YW%z${ihd`oSL0HyET>$KBM0`7Lr%#N+Nm*dsqsCjiKnRq?X;A*wDg{| z?9;S-?eyZf^zxqcs?+pZ?Tp5_jOLz<ho>1G+L>K(nY}%k1E-l3?X1zbtjV6NSEpI? z+S#w;vfuS&ubpOZXy<&2%h~J6`F5Ifq@DXCF86m&u84Jvd_c^3Twd?J=ci)WwK`%r z(A%xZt@^%OCxyR(l7AOHE{DwO$;#9CeHp*co{q^aAVhf9a+~*ZbE7%98;UG?kJ7v@ z)DTWreF}ZctuaV+Sq)2Bl3|Xh(NC~Z?C+BIMjX*Vw^p$NT<-uXw4}IKDTt48#mJCK zhi12@L6HQW2j%c4-wO>mo**2}jpS)?MgQ4i$T325*SbECdI3!}ET3Ss&aPf9e_z4E zlpS6EsYp1%t6&(yU*UrgH%%<uFmpMK-rVD(Q!IGlYB;7->@5~qlY$`Q@;|@y3;XF( z`1bNextK)1`ft+8b+~BL)OwRY{%%^;Uw;EMo~W)4sXD!>4#tN4a^feVD-H@m!WQpQ zVZ4I(EjGvbYs7c}wWX7MjM`#6b+`-dIR282f<TEvwRFyq8;y$K81OisCcjMy4mv-a zFU02w82dcPuRp@C-~MN|5@$7NjL7nNIQvX>j^AoQy}UV?sRJ*RaSvV@Y)KWzzIFej zWza;rhmKgWOk6DWo_U)<|9*moW``59T7d!#rnUK=rI&RO!Z$B$?oEK=+ehEV@R}*x zJ4bgu^3Ndf$@MC`nG|$-aT9^?b{rRMg9Aa=EwaJADTY;*6jt95&_s7%qC6$s<Z2f~ zM2qvX&La9NO#7di2$#3quT`!QcxIyewW;sf!@t4bnV($p@9XXB8~EEt`P(P4)&92B zdIv2sfn(!5;K1YDs(~?xuC_L-NXlq$)q6#0ofjv6`D$?d$M0VN&tAy5R_#paH4u1+ zD~8;3>~(1VC5oPS{0kna8QtoO-*?=U1g|_N$`Wh2?Q7vKK(@nmKdLQ~?ad&U-loJ5 zZq&7M^c_J+5HvO}#_85S7Q8AjA~rrs5s<9qNzmg`C2$D)Oc-u+6A4_}1kSvE?iJgv zS}*x_sh3w8<r_9-YrHO;G4dyark<|4E}^IHj7|;fP4%tb9Xp$v>YsX{=bZZgSUc}` zHs3hjKO!Pq?5(l2irAyHu}4v>R?*lLtxb3A*g<KiR?JeWQKKjoo6?F|r6XpI4pep5 z$@h%wIzOBr&;Rh;&voCQ&-?v)VLAh)o&K=pz3Ua{L628G<f~odKfY4+`${rD4`AiZ ztCheD>1O1Kjj|c=Ss6~AFf24q;1v*`I`Vf?*LzCwFXKozw}q~}RRZq<vD6bglS}6q zprS-rN8tK&u+)?>+w564?hJQs3B!S}c)nOBq>srZwS<WOi|E7h%p3Bp6L^xvQ?fky zoeTxY*U|e-^kEHwgGk`8rb4v{>=szC6_vvZ3uSI0UsB-@fLEuMxJIt?fD*)|B;WR6 z-@f*Id(}V;D=8)=`Of8<SYPiu7k!MrH|odR0h?>6e|O*i_T;x%iu(){ev>xj`ByA_ zZ%NSW)JN*lk#|e{e#??xh7R6*;k}P_Bn147eJ=aLXCtR;y?>DsULx4|wb%@ZhC=xX z6P_jTZ{_tP05pThdGX{2Z^DPTf8c!jhci_6<Y(*_1k45&w!z$3qH_JljF;ToEI+w* z=h-*wa!f5XzF2~fN!ac<xmIv;vj7V_p3E&HiRlAgDVFm*2YB*{+(OknC)xQn0Q577 zkAVcp;Rf(!6Z_|QFCU%xh3&`=f(;4x-i94Pw%^#U!|ocEWAICu11d%g$0>V=f%ozs z5V&N#xvq8bKkpr$EFU&J&%<EjQv>sdi+-Cl{ATlh|I$-&#**k90Zs2d2s=E8IQ2c| z=J$xQH>XG9*8Nlx`~4&K&0a6x$zS4cOc1kW8<$`ctzF{xkXSFg44>czY!fi<T>Kv1 zzq`wRZ+nOi-2Bs&An=&)bW?)Z%==@t9)I8V{H;!8>0B?4u!+9$e)(Qfl*T3sF~I{M zn3T*(=k}4NWiyKSsm|z#XwCvTvqE%hrQgQnQQJxhO*IpegSfy+BON-BD3dR3K_(d< zPSs?WQq+C>Ong4nU=#E?fBBiBL^VQ9(%hx3G(>e-Ll`aD+e%vwHLvfPJzV&BVdnnn zda1#Huyd_Vi!)~(<>x|QHwV{;J&lcRSZEJ>RZ)$2)v(w!TVYyXR9}J%>?g4)K(I~A zgIS^{iiUNBRb40E-8J%mZr2w4C`&d9sn@bGS#|o($!xvWt=WciPj8@}YMulZJc1Fi zTYPPfm9!4ut(?V{fQcf*)3IW%s)X?(?e`pa1ynX?;wBSK6+6Fq4kXI{9?TSK3Vfb0 zm|?p8+99}f2-DHKWL9|U@sO0!3^Y4kNold=<NJIBRtHZ-97;-!9J>ph8cihL0v$pX zE2|Pmj@4uPtd6~K<(<`-t}Q^N&16~FXi49&7{~SChLN~#;Ol9Xo(8DI@vb*QS*naB z(A(@2d-Ij??Z^&kC1bSZ>3qw7KCWt`$5*Uxy*yr!r8;KkCR^w%A}FizQfMXXHsQ*q zOp$ZIs6WNgs;DCVqKJTK@UYlQmGX2KZ<b<>e*O#f9!5G+Edp&7RGuo45mb@U>3pU# z8$^Gho^SSRTw{(E;8dk|sb%4Y;@7L<M#UV*OUJ~b)(ZW7HvQ^tl@Ek{NBF*;R<&od z%ebnou%D*zfHH{EZVd;WQT#CAIH&Qt!8g}nR>mil&)8xKBHK#wMQd)k_8%ukNz z(qxdfk?Jo^3dTFmixe#5hA~loUF}HYFXTaJi7U0CyECZg-(!IdwSkR9gzoL~KA3jP zdZzV*u|J520iH9~O#?qYO3(NRvSSpw)2~0E)Tg&*td%am*u3!k*!}UH!jYK=$2GFE zn)=b+`wy%%U)lM-P!#ovv{n2RJ#DQtVHfq{c)E3Y6569()k^)1N58PrBa-$?se5j$ zzmI3sUmSqG=^61l;FOj~WRFwqbIC@!n$5$&37fdLvG2vtQLlV?5%>Owo|doLjCFw` zx7Oh<%PwxmN{aS0IE-mgNJ+NZTQd%sZk06eWVG2#dAZ&zz!;}gou7RexAkDSE;ra| zsN$aD)u5zJm8Qm=tDif+<kV7c95#OUQMW3{R?fxj_KWO~`s8R%Sgcs9oV;IYskk%$ zSa_<uT{0ORC^N<C3+hjgb=B_W-1wC&5_nqav)JRb6Q!`PRlg42=idB9|9yQ;rCnhW zYJdYrRQ))s&Rj!!H&h5O?({cB8=_f;t|;Rj3E2k8&LB*Z0BEd?^NW0?57tb>RxcGt zEYJDA%Xa(`^*!f#Xur_Ekek=<*gFLrBpthE#MfM#s#z<U<zsR*8l5$)_O3j~VMY>a zTWO-jG|Jj(&q{T=RnCt(%XQ;TrSSyy?8AQo#lG|r;{}BQxe;yy`NPfajL^_ZQBOgd z6Gw*gYcfQl1)r=-G7?C*3{fRZ%FfrZ^FG8E8Qe33Di7e{f_!(Cf()}9i>>l~>#Jm+ z#*Q|nqhc=IDzDsX;sQK;(aClu%GB~(!8*R)V*Rf~Zh9jkL)rOj;|DducZZoVk+-{| zE2-=Ik87E12zQ1wSG^?49f-^sWSSjyPsoXGkmkRz;~`$<E#O7@l7DrqO1lU4@^l6y zru3uifJiIX%?2Oj*^OSV8^jb<4bat9GUQ=Kge+lsOyCi2{-f46nvU~SDOjoY!roHu z;I**wx;^*#=XDI4&10c%te12PHRZ&Jk${2qx@xKF{f*g*L*ZR=@|r@giE>t=*eeo5 z=BwrX!qMm&jfZtMmolbHx1#Usf7-OkR#mwEgZ<bvAysJymlikF%x9lxmL;+x^SqWJ z{wiqc6Eb7A;htQ1AK;}L?=7xvA90gp=r7+wOwk=#rigk#)Qq;WoMsZQ>{^(MC-3N9 zAWMt1VJ2J;;q!EOEG=27!JF%}aZc~hkt~}apKFFHyB>o%p7Hl3M7a5f-)4G88I^0H z6Vk67#1vp=9|T{0?Rs-3>Bux@NXA|(%QN|Ov|jU&@}8yR*;cFM(GfHGWjt7)oLJcm z5Do5wWdmh`$s43JsSbR4NbQPXCmy0Iw}~se5cl-W;ity9o~LgKGFw9GJeQmrxHF#D zXbRogO@XFxW`*L7&%mS~iS))V{Mn0aO%Hynk=m5ygJIVjpi}iC?K#z>m7%xn%r(L{ zaS5HR-gQPVHAD=PmB)<)IBuD#M<+~NL;n!o!kf!QV>xuQ`i>X7pVc|fV)u^44{0<u zWnV)20%DctqdulYq@)kah4+~Nl*w12+=!$Ol+eUZit0hldxbc)R^dAkmdMAj-7XPj zQ_0#esKTv;yy2{=xAK6a<#k9#*EGYFw*{BEl%FVaaD28jo|^@8O%i32`Vhyx(*nqq zB0)7W_4LdQ6U8f&S&c{SB+V3sk5==>V?l@95|imyUXFw?;!QsW45R9;F3)t&4C@Wt zM%a!R!c}pgXpV=1r#mDekwK|?ze-N`{7sCHYHvBFWtF+U5k`MWODz`UPBy%j#Q%bl zdirfuz<|}&g_*{-)<>u=<H1_z9*j+v9Smu%vBVh>1a=ZIlMmWR6#4Qs>5tcBW_|vZ zcWSF?V#&B<5$h0c#dk%@SVaj>lNIqgaw2-3upQ#@(<_mu+^rRtY8$S@mmGVnph(iw z2V(>`voMmJDbMj6=zBD;+%bCCNhzo=rKL^zsC#|(4)U-}eu-K12`WSehpz}0&VnRL zjOrCtlZ4HGAD4XhNtl&wx|!vvWB?q}pf>_j+AOa)%mY}7b2>?^-nMacomQ5lB&Se+ zm$9aWVTPLwuiywPyHe!LezY`^>r*X6-GN*7c5A-3qRM5(zirVZU2$O6bz9zuJHw;& zb^nWY2ave?YA>`IW+KF%=6)_qU@-34RjFZ(U&p@CGjGIXaS%_L+@|mGi)gsTrRuY) zhLS99#~sXj&E%xX3*#(=D{h$A^me9_sCQlrHdQydCdaM1=F9cpSNY8^X<ykf7H=js zE1XQY{;^VApqKcw-%LS^-*k}M_eX+2q<4iMKq0I`AptsuIe{CAR`J^>_8<K~PFJs6 zeHHYSYG?RgBy#G9bJpYG6~G~)Z3mjnWFh0O8Phq^iKt>@gSQ0KlO1?vzQXUQn@<P0 z_VLIUI4L<PR0qwwig=yHtg9v?aOOy<WT8+qG>czo5FSjYqZm8#ojY*WHKiJl%IR0p zUq3PaBvL#`3)bpeFDdaRLf|zH9!mfn$AFD+97b5MCiRj7og)Sh6Rkjp)u79<uulx6 zm{XKRZEBT0SNg6!Oa`gQllTIQdYBS>w4KFFLo)El9wu_eRG-d(uGDbe#qjrGkZk}G z;s|Xd$WH(SUO8_av-HBC^xLHL;&@**KJR`3#2gtB>@Uz2hjQpctz-4(sD@osNhTKN zUv3@s_%O9uL4*bVy3R|8P%s*|lbWF+BZ?BM$cWCJ$WcsMo4QUl!*;Lg_yh)d%Mjhj zAhiu3Kg*_@k+NUcW-mhhL!wQi{7$^K3of-oh!r7Tg{uuS5Qkbw+e8*?3f<U_n#LgP zj55D(2!$zd^<j~pjgBFoXsa73PT>Qma2~z!=b~MaowSfUlOemw2Gam4V*}mD)M^8i zb$wz=M)Jfr^Nzssi*E__6HFa%MfLDUJRrtCAX~G|Y1{K4UNAGfn~?3{$LvybFO0bU zqH_JDbA7c#$gAm05RaAZ9lf`#9KL~6xt}CjeZ3ivi2jk-jp2{8OR}NCIE+z`!VgjW z9V}!fB7YC@Nyt1qpeQiCC>Z9|i${O2RQu&5o1Dbq8BXYuKc84}4)-l*_eaJw9$}wf zkN^X0UAVTWFbWNpOQm#R5S>I_iuCaZd<K6;a=+|FwviF3!&f_)-cvN>^C?*Nj_q2F zi-%iY_6SS@gnTz?Be_}f2zI9_*iw4a@UD(xt%fzsHzye)@3<NtVTw}kKmmA!o*YGY zl<TJ**FF{fiHQCH-2K2rO}~bh5YeBQoNuYn7Mug6U*|jzvSKfCHtzZ{A$T)B4WJ3P z*>M!ra8%<^t#s665WIE=`VNGY_4BQgy;Cw$MrpSsn`@!Il~MK&aeq6IGM7&k4xF3X zf%{T9?uN&TI|uRvr~&lbi+I%YRph()(hEN<sZI#hNk|3*lE`|OF*rZbD|RqkQ=6y{ zM05!Qol8d4(cyc+8lF?db5D#bsPPg9=+{iBrp3i<9O^4GsfNlq&kTM^I##e@lVfP> zVqOgvv8UPFR%_ZiKTr1(p#oHDXTMzppTZCZ8L7)@IC6E4j0{OV=F48tdz2-AL$p&} zkBCs3d*Ro^dH?MmNm$^?2<N;{gzfH>s&1i5FkBP>T~CMWKG%^_Krw)<Qzh{>lgK(d zHx?x}cL({Mh*}`P&%cHxu~yZ4K3A+Vp@r3dgb&SI60N#xpsmDM0~raif`BiH<$DUK zCV<kAk(=bgb;Jnm&Dum$(SnK4I$}lQuOo3-$PN`|sD5_?;L3Rpo5a-h8KGZ<*PXZ( zTi_hLqXB87A^F|Pa_OvZ3VHT%p0~7GpH(KcLalQx{Fx?%`?iLdCMs{=IimAelwQGB zxPO7kqvm$5-#Ag%SJF$u$UY)s%SUWFyaC$>hfQ%_2Wpifz&;qxbK&S>Ch8#*r4C0^ zXsDJQG$jhvQ*=FO*o6fF*0sAF#YA%^!A04S({#VG{6Mf?HSDT8;*Jnvkp_f6%I8zC z-9rj#ao+LH5t+H;yOOiBQQrg{0$Be0CiSTnh_lK?XNY_fPjOA&KB$*?)Ehji6^mj) zO0Uy+CF&u5G>$AX?D8F0N)?Q02cHi|ZDJ7*h}XpqLOiJ)rx;*gDx?vAx|Rw5YzLnR zN41h4EWw=E`D?uHoHsk6*65QzidU3Pw66vlpI8NkfICO|3phk2KJ<5lkhq!=z+SlY zlWjyt{nMvoPrJhrJy#Jl01>w(IH-j>_Y)3P!w{c?eHoy9fTNHMbH>7M*rk5L!9ohV z%V^FwX^=0;_Td<g6c+oI2JN7$uk`!%k%e$S5VwvZpD6ZxJ>Byyr008P&%tSxow1(3 zh@O2Ao$WZC-TIKu5lZLGqQgAsaq3S|`cHr3PzP3OYzK(i8K^6jv!1LG3qyUW7DD@~ zwUf(xO5#fRo-&@O0(M;UeSJzF`&5wq$FF7ds`YQvkAJn}Iv}9;>=1k5N4~T1hT$Mr zFq}$sur&k3s?uI&!p`E3+{8c=!qv6OAZId+mFT+0gx_bPMU2E`D)=1oP*_eWKm8$W zT+<eLD8zawG;1gTIgE`P@;^Qt(7^BWhW|2>-!l&-Wg&GFIg((Fingdru?|fA=$+Ou zl0H5{`Z$vLXC%uSRUW5x)Wbhw3rCtfcNYh7C33FsAjJX@PGiU`j+Vyz$VDuygN70v zI7FU~?`x*0&JZE3p<_?7#yT3to{o?C5h20Acrb?Z5*gx)<M`dl!O9RR(LhRAwuw*> ziV2oxvZ3gJ1o6c#H_Vv{_GWTkCc+kovDrJ2HGR$qEM)UIB$E2_Q`gH+<1aVGCcYe> z*wUZ)jGQ<qo!AuPyn^Grv@>xS`f?4)Vk9$?iLtq42Eqmo7l&8vFt|~Z+~SiFsqwt1 zNdcQl;p|Dl>-WUFCnX+Eia(rew)0G%42zj|1#l?JN9RFu)O5Ih6q)~+Wx2#hJKVR# z2MRDI8RaW7_C20!>*rXn*m#e}j9K=K*^3z))cEP{nKO4G?fSE=<1?2qhnzR?<2UGF zzwmKuEF_K&{`&_K&)~@+a$ensC1BwR40tgU>`Z(y{|1N(dnLwXi+}j)@{3njKfSsZ z_KKCHM-f?!(|HLp=$IXhOyIc9n7^V3Bj1JP-GwDEVP!;}f*n}N!`FAZ=e#k4RB>oX z`1Qv$<2S!6>%ta}x!$Y(Tlp}1q2b}e{qBWErN!323yFC`eFSv5llBiL*EH34ct>qZ z7sWy@*Z|41cJSCb-`Il=_HAT604y?|Kz`pI;h$-y*eQzjzel}WQhGOUgkB9puj2aG z@%{H}UEa{p!_QF=Ez}k&a=_7C#hmXmxp@&lm+YVpQSdC_5YCS7KE?#wQ9;l~ChR2> z@tJuH3u8yaA7Yny(eRp`_lMa_huLr@G4?G6ev64-AUFTALH8sq%imb;>E%=Tu&nZV z`TcX0$}q}aHBoLV(_J+&I$%ZT^NLH;%E8-A*{PLo3cty-6@z!k{Di4`X=&6ba@ZK0 z9ggCxO1vp4(JNx_lE1dam}UTotq<jk2ASQ2^}w9<;Kuckm+N7l*Du|;|AesKNm%#Q zl~!Ip)sB%4_>8QalA6WUos~p^kBSv;i~h>qNN?Q8%vt`-K(6mlTJ1WdHBl$jQ3I9e zq?4$=rR6ERvybS06sfJsoTIZ0VX`c8lDuWua`>T}>3&fPrz(XE{P(OwG;NZ){t_Gh z@bmgj(snm>d+}g9_}_N_v#@}d$c{>`t68YKEFd~=?UkK*h-pLz{KiYp`;YL5)Vjx( zKFWT|V}b>CVzA3uO%Lu|6$#N;&oY!>W^3xjA;;{I)PL}AUT0rXd+!pze82bQx9t~7 z1!8?q)<{EWE`>z;@wpT8Wf0?LtQ~#H{}%Uz@&MylirTu4o5-)_?Cr+gAJux23kts& z&<OnHjH@~CGh#Vbk*Q0&ZI_R|##g=u93;3te>Z<R`PY-W<QT9LkIp^1+Uu9U_w|&@ zKAr3_GFYvdt8nzA!ap46$+W8X3rNm(bGYT9H@dac-beFI4yqfIY58csvW-Si<l=eb z>HYMp_Yq26HJ9QW{=jzUuJ4fp#C`rEwTOMh8_d^9rZcYkpi=t)5t3=(FY>3)@umvJ z=5{GSaB9ZD&*+X^qj)y;so+czI||(MSY+=|D<SuXgPhYI*8KH>h*<mQvLlrG+0<80 zjKyV9ul%EOcJp6i5Hk#P2@$o(G=EI`B~DSTP_cbzUv0ej`^Xj513H(hd0h)8%@f`? z9R4$@3bu$v)l=67xvq!Jt2ky<&!5SZTsTm;ekOS14=<$PP55tuH}cizzZWL#N*4d^ zmzbt4=~bSRpS%g5F1z{a$RQJrVfkOsGOi3EAQ{H5>^IL?GA41$+E%$vE}LcvYhGNP zpRB+GL#ZhB_2UAqu_bM8h*ZVbs=2EEFRR?9*KJC5MU_`xPs<bi^-|EX?lT+q<tKB+ zEBQ~0%N4%xVGB>4**e?c);hQUdUo5H<~^9hzdc=SdGTmd-HK_}$8+rwYmuw4neB;= z%iliFF7nc+Y5?lRf})IL=LgdH&vkFV`r<Q^Cp+P!hjeL+&mResHVfVKW0ad3hnC_t zf@bQ>zv_#I6zZM&)WBV7$}g-o+Yz&EGq?Et5_2?`OWyY2yW06_YU>5_FrkUXn9MWx z8y&B#bl$JO^x?*S=z{>JOpGJvVWvRygSWGf?q~k(j6K+0JMST~J?m)6tYyQme>}Jb zuzQRcY_fo%^u>Sd1d3PfWr%omgS~vw0zq%5?;Fny&hQ^@pMm#whMnQD2ExbsxE!lq z8t|W6y?8V*i#tNp#@$l>j%!f@?4;n;(kwbPem`PlG-K&YTeHcv4Bd<OHaTj1;WClW zyAzwIw2w7sSr2=a)>RjU;eut2Vq$yOjvsAxQdh>lijF#dV|kUc{0b&=UHHNUZw@h= zE<<_om=dF}P1=aJ7mQ6J)T8YmU$B%Fv}OdamBz;}L4@3McDb}og}*t~DjE;&IXcAb zeQ>(DXU|WJSKDnC55KUKDsbpg6tRBa|H|oRC$Gi+Mi)ZvgS4{fHc9ilDk<Cnb&nEb zoTcp_U5j0~Q!6?2xVb35$o=9`AN!Gu{oNL}K&fwA{RWgj&NG?E^p<D5Zlp_pd_TYP zLfF;%xc6y0v$x+noPFqc&yQ+6#0+3_7OGG<-5;{#u;ylFoIIQI!zV>V`Gs<p;NXXq z>#M@+Z{F)^2@`X7Uk8>1ospX@lje;P_PxH(MlTD_h=>a?TS@+@l6g7x$Bb^&Ke$JE zfwTMAm69Rd;<(#ISGJCyddc~L@LBxZ`3FxA7W(zraC;$-$FzQjwoE%;4QpGB{T<f6 zQgroV=XTrgi(Oymu3mcf`{4H_B%NLGT6mx6Le)DW@P7-^z`zC2+y5g-v!GFXlQ<Qz z9wW4JmLN^qs??&Xf;Dqjzwl<Hsd6|MYyAHbq>WA?U)<4&+IlnEe1D=0&s9Rg$ka|& zS`-}feBQD-EFd5!l!dc<F#W#-X|0MTP>hI~odT{8+#EFVz-BD=;bL3(`{&uG;~L*~ z#(&v*G3L_vs)xvqxN%vspZUK9X-zA`Wa-oQtUDgBjZxG?{<k2_I8(x=q#}{s-2S%L zi_UKZHb8<LWAn7_(_*?I^FKja$Px9rUlO)m?Q^uD0>v*%*yDRuskp?u_nHRTfxg=z z?{5fc9SlvEoj>#-Sd7PH%L58aFQ0XP`U;8BE|p05MgIuy4-o9(NTqPRPv;~Oq5MrL zSD|tvp78|#WHUg%ww#&FCt{w!E~$epW9Jx^$AJ4xvCAZBvwbme5EPK)1=LKiMr`pe zOIaGWGL;To0F)U6Xp!E4@XF+s7~LVcRkCqgJA(|)<E9sAj7(zktmcB&3I*P7@P!_O z*pUGOh+2(5Q}naS6dz3hxPq%#Ez0nr4pB<<oTWVwtpC`Q)3o&HhcaURdUf#)=PEEr zCz@sgO3>QcF#0iHDFlLG0etmsxYN;UX!w=7YDy}6s}=-f7>Y$i<JK!1+Tg<Sw7$cV zNofGHXK}P~{efcG4`|CoBOP*LUjJ*5(?nCBT>Zz#<67Gvn;B+`pIT;|Lq4_62h@LR zdlS3;=?ODc@pJoXQOM_xjhgz;ogdq_KR?|WQvA}j|DPc3$9nyjXMYa1zx4cn5~Q78 zJ@Zn(ti^T$-`}DR{Mg~$pVZz=`cIH{w{XhVTs&XZ!R3X$s&k;{B*Q(<b4i_@+nAy1 zbt*&yAe@r6HXgw?kE<1-*ofSmYYy4?SGSbH9s!|;AY0{zhD0)p;J2d{aEqd0ZF1>I z<M;4?;WlJ#aCuaY1ZdM?3_ogTBg(G^<!0x12+!kw4cM^*DuaKPJGXNcpXBPdS}0@m zI5qppy6h3Y=q~_e<>{AR!Bd!>9$v6M@a6cI*Bb1W?7)5lR0gHw{!sksnbTq>x`573 zID;3@XMe-Q6yx{r*V?JcZj7v3Uh*G%oRg)n8}ocBKX)F^UKnDZ;7>Ko>I?fKmx~?1 z2XPS1!}}ytgTMe^Q+iTppEE!Qvx`?ilW+hB&m=@b%ib`dG!dH}KOpU(gW(WJc8;Sk z!Mf!nez;63doR1;4j#?}VzP+dXWt+Grz0ZxVDCUpISNT8NiFQaV+seKbUtUIbwvia z*T=AhGMLaH$yGrh9k+<USJoQGOj9A+4uRRhe$v@<WYUpNHguvB7jUQkow(w1I-UaJ zOT(qe!Ygt#LF_<Umamv&npv<N`;}?pyL~5ljAhN|?A&oPQCVS2z^}hxdfHFxBy2Re zb_F{}9FnRt%nr4X&aWCz-C7PBO<c9X&efVK&Hb<hG^9m)#4J=ejB*0He6vAIsj7F( z^?l)fmtQd7o*3zUs=4=4Y!y2!pU`1rm-zTLbKhUs^KtHZZX0Zu&=4+bvZGa2S{QKk z&^P#w@WfW-oYA*XeCBdUc1Frbv?JL06le+3a2c+A3P`M$kgk=LD6mQ!QUvH(K>$%G zBt%qwSr_9gmK6GhkMscynn)B{sglvOusCDY`qKV|P_Izk2fbJJu@y5yTVTM7W6wTM zr0Ra=RZ~@BFET)^Uw9bHvPdapSNDb0&GSN4!wqL?Y=B@3l|y+z0P!#tB?#VpfcN1> zBruHX9J&?UtL57=1#ClQ#RHwQ*ydhH%7`ywN3^CS$yau4)4)r{#~>iiw*xeRSCk?3 z47RykIbY$h%+N)sn%jUzV|b1_X%WD_9&r#52GunL8H~9xinLm49yYL9UR_A=b8bA^ zn-;ojZwnmiA3Pp|ZW=`^l7}>t1t#cT=U|W76KA*pZz>2N1H^P&Us19WWDXgKUwqbF zmGktXhtl@BZKKuJN1wuCU_9><Z@F}VFMqh~J(hoNr{b|>!bcSW?eV0bKI|N6NHt5< zBi*8?`}1-d@h7(~o3vlI*rXAcz!XQqhH_6tiVBe}fB-<}OW8Y8^|VBIP4JI|`h+%< z`5~=|156~ydkA+$geQ#R!}T7ZqdkaFXY9d)RMDn^M(*Kra2dhIPZ!OJl<|N+QX+q6 zBL-?CGE<zSA4tGBfPZ*QW@=HVRq8y0+4eS(sw{IK{4lurn(C$mdxM1xCvYVq%iBWm zP`aCZE9oX1(PyM!Ttqrm{iEAjTaMs_V&)q>wHzH}-7iEt0WB*)Zcx6lxj<F>g=fk$ zy`wKnMcPGGO3N)?i`P2>C^Q*bv7wC2S0n~XQ**g1pl->#B3|O865;OPw9U$aN#c+p zIXpQLYlOlHS%@R0GR|1+UTMQY^F#j97C`iA<CQ@t;l*=FEm*KDj>NoBtmm$igsr5R zDU(zK0!}wbY{(4x^tPGNPy>8mw-uGDJd~bbRUIVQ3^#6|>c<AWE$nJhVj=fcXP#i~ z<Sf*w-kGPqiuzpRg^J~4Qe+g$ug2?FCz;!G`-t@~ah<31i1wiZSd@;rL-i5Ody;K^ zvihsobE`gVR7Bi%BQ_MEKf7(H<wbwvHwN6<x_E=k(&UMXK!~@pzOR+#h6>D)Q=dMx zChJ)nasqS+@bS|=%b_OKF|Q!|{=nXy>*>pD0THi`2IL01>Qc~iUM3ln2=_+@J{#|Z zkK5(g0zVSJU=lcvfA(sEzc1M#o#|Q@ocJ+x;@>Vgw`*1Y%+KfN{_RmFy4JNPe!jf= z?<<w7d&B(9uc<r#_G`~{Z@EnTntS^18|}z$sPw;3ySRaAXz%q;92LLc-7NXu_T6A7 zLFLcF&0jxypLm{rKKdu}r8BlU_up6FGk+VqjU}E>k4(I?$6WR(`_0~a^6-E|?FMk` z{GatRr+)TN+}Mpe^5+BBsXuF~H`X3i{d{>N?ceu_uD`#J{Fxo*6$?C<RD_ymT0tnN z&Qy#E3v4`n-YG3oo--a}n82M7*+))T;7wq+M}{}EE(sd{2v-&7qS@Mosxa`Q7I3^4 zVwRbx4E2la$IMF`h{+pFF_81qNL?tPSsSjaU~obxS#Koi*{!5XJWAg+*@SdygpTY1 z5;eT9%3Jt*?HVGuA?Jx6wnUF}uH1tVz*{G^44dlj8tT0d3l=hCFHiMX!1x8FMnZuL z7MM#Ecn?$e4dJFdl$WOk#Tt+Qh5(7`K>)!%$%6Ml!yfF7=sd)r7U>8D^FUD!?K(1i zUOJw2<m+(oHeCFuGrSV#x=40Wu7wLrnu@UbLGlpIb{DVCr|C!<09b?fL&#M#<S31} zs)<Sd8m790q*HvzF_^v|TBF#kr%>P}!Jg!LVUmdqEJTXRMk6Unr{|N|^Rmrcxu-D6 z;5<Kj1>Wvq#|@4vA2D3DL6`|Tas-QXt#rq7^4&J&rkcifx(4QHdJXQ_UyAj2<t2kz z&+KpZkaYLyL7#vCGUTW?;xdv40yHUP%Go3C+F>I01FTY<AEpp=C$%m~drJg!AI`d~ zv3ZT*a`@_a<_V}#W<;%H{zRg+q8m>ujTn3AQt-Lr#4SH(Q2F__nu1-UOb)|n?qVg4 zqqn&85RI!*(B8avYDmkvTc}>-ae1UiAjwHsg}|;oVu!4A!u%@qT~RAMr;8y}I$a7t zkub(2Vu5s>Qh;TiY&6EwKd#GPIqGO;E!H1Bhg=<U%;a@xrCstYy3OC8W>$V~!PEid zqRP)_)|rG{)e0z!28(NCZ9l%vSEuLMM)V;<mD%&Z*7}VTP(fOlaXfj10kNREz7I&0 zOp1}5bTjPGm<>0mE%YPO;n76}ANq<_5~9K7=oPaf!Gv?wuhs2az2=xmpMIZ+VAW}I z35e~+ofz(g6pH>=*aIA*%rCC>5PZhGqgdBlqn~ievcu<t0{1tP#$&t8(ineE?vhNW zupOyVZAnf?JUU&+`@z>-eU7{lCi3$ElFlq#)4D5=<jvlMVBQaY;%4^S`5wS1It4>b zo2u|y@>T>~T<bux#9n1p#cE#z?R0&@cu|ZbV+Jksdqvst2(9PN7@PHo#Uuo;9>%T+ z^-<=Il%qG~pgc8-CCf?>tk#~f!=KQ@Fs31OG`LrtikcOV^!H1gX2rcY>(B!oIXz4v z|JlTy(#jOICjz=hu9PjAqHTuM-?U-OoZZ)Cz3<Y@b^76>KPX>=HLqk~NEq|$TWX&V zi2sS{$OXtPwK6PX?9i1v=9tePhidh_^Bmsn^U`s+qzfQJ)OR-wmjx08=dRea2d2xl zdt(^=V7IfL4*95qnJR^^XsTwdY4Eu?E$$>uTz&>m+J}S`UY$4q+BWD7V8JiwfvVD6 zBUYFPq$<M$PnKNw>u6>@!5+h*p>SWXhgL4qT#qX+o}-`Fb#(aA_E2Q94&?jbgrQEh zUcAOiu;jenrFEph12^AwWCH^tZW4%JP<dCv^VbS9W<{h6s}1{HrET2{`&P5Lz}H3% zevM^~yJ*;zP_Qevzr5BY9qxn0yl|!2R0aevAD}pa3m-JnN~~YHYr+B>4)!BFr5orL zO~3aZsU4OFLKFPPbkznExzEd?5=3wrqdaNfF)8u*1F$yh;>vRXH!0Q|foW{b>PQ{H z4YyTXe)F6NQJ-4Ce7RKt(BUKQj{+@~A89(UG=}=OYc;->9bCW|VcU4mxxX1zr*z^j zj`5Lj#NgR`a>mW<5rKg<nr^Q#48Yw23o#pNJLY(g9{<>%*K003c3k0X%x^XMMd$OK zIIX9=-8AzFMzux~MH~!7KJm)xxLb$NfX23{R-QY56w|HcaU`Wvwz{)EQzKmtV@-n- zcxl+_W+WRbk<8s@*(PsXg`9L;l!b<oeX_SP;)}>3pq*2)Kt)}nh1|-XfOt^p0UTnC zcUoHIqri#mb-b00s@#d}5l;~12oy<6?zB3I9P$Pp)VV`5_-fln@qhHqz6akhMXsL= zQM+5ud$T5j-7rSdSEC0L4Uk<p@{n{<Rn9j&Hvph^2M@|4b)?h{*g1E{tBw0(R)6b! zruJT!#ylcE<FxNoT<ObNRCjX49IT>lVi6@~m`Air-E{hIxjul{cq3Ca5szSL_4uy! zH5nt{#GzMkoXz1}CPlhE4F5J-hh%}(OAL}jMorL~Cj|k}!dpHvp!EXcJl}3*wIkg< z+S<#X>Gx*d3y0|y!oL8)x#8g;!$8?@(3|i|vHpRNnr>4Hm^>ov?cok`S26EihW%$b zOwwpK%&{NR#rx!f7eq3vjh+cAudBJ^<Sf@<e9e9iG2D^=1S;9<X3pB(oT((j0UGqA zkd{v+-OIVR_Km_lvva$vI?NPg4;E>!2{SiAA&2Q4Y^c#4`q(Ul<t<WtI#$I!B)x<{ z@7j-$E%@?6es0ypn7ybje|~H!^od#J7@2JI-Ik2tzE4L@>>$Ioh;sE~%O1kXT|6`Z zRmOMAFK_}PIR@HAPVd0Sn4|hJ&q2~%vc4~#1dak!4jtA~=q%NudhltuewqxX(avxh zK&HflKf`O_Z&lV_G4O_9zz+U6I`aED?xWV2@o=lE!_rX3&d~R3!sx%;cE-r5>C+}V z?6NJ$=}=7BK;|0);t^&Py@V_-o!0B-t(8Xd)lPv_t#|zK*RJV5VIseVV(v0HLH6(> z@Z-b$i7QEZkk^RO9kWpg;ETs_d3dVGhd@+W>Lw&(rESu_51r6uAn8qfAs&P}*AHmX zg<c`;og<ww0rcw~%!?6&Gii8C7&e;VI3=ap5AD4tt2)ogHcm-7w_IJi#-HC%?RVxn zpLd<ZGe+)jQ_aSZ+kH$VUzhD({fVPla3_EhoQHsZy7-aLA)?SRb2q^EBX6k<&#jLV z*&T{q$=2OqBBb05RF3X!?%z$vuvUP9hbC6N>RdAh7640=$b>5*5tou(V@)yP`xfut zTBg|}w4C4XUw?lP=BpgRu>Onrdp(gNjfueEz44f2jCdpg%61Z?E02k%Lc|p@vg9!K zUg$FvaFvR>9tFRH5eMx;C6qBSo0ww4unadeglU>UT?S|nZyF?FXE_1j;ILf*2rG6N zXt5ov7y$G?uNeGWG4fh21Wo}Mb}ax1WI|3q<5qwG7jc+2qGAVr%^3}x%~^B#r!<dH zFb(I}Vq3Suu7lXt0m3?}3C!t($=@-6QbAEz497nXY%<38Bqj)piSX>>0{}S;Xp0SS z#A6D{96W5Wr9%M5%?*`P#wg%Fc<pf5(ozc0K!MjL$eY~~0G|B?m7;-rXwKoYm@I1V z1`%FEJRz0<iz3)nP&q58_{)S8;RIbsN}xkAujU*5ZTj{pNBtMPmyqT2qJK}UX+z)J zna_r!)Z247dQ%aG+mRBmyl{3!G_Zv8KLG|JZeZ+leC(Amk>QZj!<#$ooF2fllfW}2 zIw+9I{^j52TPHB8C}2Vn^BoQND3#eAoGz=f0Ywn)7T>XZyMR^lV!t8dqEPpB2kr-> z-r87FoG=E#r;)j*XE)y6N;VTaGx1ealPWu`wmZwabPL)<fRr1%Fge^XFo1!kgtGv_ zd7u+^9z2uix8azd7cmwDPK%wcpYI43Ob`~!21;P-WD^7Ix=412S*#9ekQ9GQTQJ=M z#D=_LfO>(MFf>Pn8zZKuA(=^<r%If9>2q8{$Ph;-_S@R(K^Qs_xx;sNn5el0&U@JW zbO0ats6R&M81iGC6RrRIOX8bzoLN(vo{R9sS(l5*dT11bBX8o<n?}e;1R6BC0T6%w zbJDFf!I+OB+jo$aeyG>PF^)WVDJ|Lo0Q4BYT8?A1)?EN9`f?O1ZFT7TRSVNrdzQu2 z;_P>10>ZM;Ycbe!akCI<sbw%2)p}K@#?w=wuC)5C=jqd)Gr51~&d+BZ`l@x@5DJ?^ z$j+aSs6tm(>2<Gu1^`rpwMDGR%dT+5QvlIPMTmx7s!90;p8VCw1pvJqbiDJ68WcGE z(`>U#6Y+1~StQWp3sv&+h_zoC${Zm_tZvw^4(G@y<;-lTR*&W@x;zMlIjmckXokHT zD0ci{d(YtdKd^{~ymq;1_Dg-OkGFAwz482tX2{z^k{b8@o8`i4^a6D5xHZQ=yiFrO z)5T5iIDcBG=%0U<BKm4wwUb|I?xD`O63`|1Tj~#@z43i-9D-{gL~wU$FdBBENVHh# zk*B|=$ZN_5cb&P|M7ywp9~BKy{1>J)`RNbOJ>YIW`_X0Ze+klZ{@7{*Z&`vgh=j+F z@a4hmBj*3m-}mmmxiz-x(7IlmFu~o}{N&<_-u8I+%|~urf8zJd{{9q=Kl%6a!B$kK z%8~Q`Y_9`5Y)oy&y=T9)zOv&lQLlb%N-Mka<L9N59D;r{L(U_~IHR_Wa?Wyi+;jOO z*SD6!smN1*?2Ne0WtvQQ&zPt-{&VnaG8H_ZtZF74Sk+`EdTBt_Ts&^I$^6Jou$qNr zn#^Mh>0A>vOWE6gk1gfPlGUt^-miLWrT9MuX-`%kvjW^;b!*jOnPzMC2@`c2%~yWS zHrnr#)opb@R5jb4_%fh=#^C#E^BGnr=s!W4Y>S=o*f!>{+=R=&#oqi#ipJC;=2nZt z>6<3xsngnP(F0!(UYp~ud=};>UIlk?9yzQ2vE{4_H~*PQ*Ynk_bI>pSmQS|<SMyhy z*TkW&naOVp=LxzzbFN;u{}#Gs=fAZ*;Zv<Cu<)r=N#J$BqwZMu(6qM)F2QAgV_lNR zn_B123#=$=(fy{Otlst85l`~RY8S8mt&}*g>*CYj-#*<M6l5lTkfOYc=aPu`PI-^| z(VB2z^?fQ!`AUsXwsy|P<2k2TfVMnyxemXAC;O($1ul@wruVXhp>jompPi=Nt}fRI zl*Fz7l(LSr<d6)^DsK<0M6Idd@073+`E$A^Ny3!en$APUuY6%>NfsM9mD1R{uuzm8 z4dJ|(z+l6Q)YJ!Dbu7Zb<%-XixZRO{wJ`L1$~z+hLOcs`|6b!qd--$+e>WXc+<Y=} z{r1Da&iU|B_F37;dqqvxB44bD$=*pQN+0qiJN&#;l$|IHdH=#?!ePIJBAKdCTGT5W zm0Sb!2$+kzw5M-lcxAD+jyo}s7bxj96?%7j!XY$<+BBq=9X**M2GnBBL+^T+lWObE z2Hvab)fFil+~d^isokHxG}8@u7mtbr<u8m0r@!Noi}u5D-IO1SpSf%O;|VtfNppN{ zH*9!8irdSzO3)xdc-pFodo4x9_`ze?l3H69;3abyQ`TSlDIo9!`@dvm3VWGNY!f20 zfgv@(lmKwr?HI4n@HJ5a%uwh)`X~x$Bc>=x#Pd!>fB=3lp6zz;$>Mz*>F>=JsF?Xv z$w6F_1VgCCz3;j{$CHHYz*eX*HB&x;Pja&aGmR;s>;#&<+$#$Uu}6~G0TwI5F)L8S zw+g}AGOF>~@Hde^*!k=UMts0dsqly)f+H3M7+Wu+Z-UH@MS@{~4v2>(pp_9bL;^wm z@|qO}KS#L$LNEM`!}p%ys&MI!AESJ=1c=-7NNj9vl9>_PX|2B9><Hv7MUSR}V@_<6 zX$`Q+il7rR7Y2gaRUu2i?xVNs*hOs))jg+MI^g$P%TaopS!T`&s2BhcT?7E#2Fn-G zKK&xoc36wjje%^^3pC41VB|vpPhw550&W9GL3(z{L^CX;+v21@`3x`v$T(t>gryb= zz>(6T0)rc-2E&?<Vw@Dkeu@A=y)AjRtCjhxme^58#KnOqtn&=?7`i;$?IMrlV;WS= z(jM-LP8Q+4TxDkUL%UdrJ-<E#EN|pJP@M__N`nUQr6L*CX05!yhRIRANk_mMBl*5- zggeKMS1@a~#<!a!rB_KxfP!S|DTDY#0<Rr)IW#6L<tUyF4p32&RD9aee<H5YR3kA! z$V3+6lVP+o%NGp*hYA~Xs1CyqBZBQk093XY3np9<EZ*ocF+E|t;(iB7(S<W{A=62^ zQD8Iq7~%5l>*ohjO?Q=m3-#^|&z<?ZIp~Udy@tU>fg+v25O;1+R+h(c-&WV*Gmp|S zPS9Aa6E0b@Ee{RUg6^~b9FVlkLwuUdlOA?8bHOB<XDyj!j1kBAP=!e?m?h3r0Ki>B zJfFkR=J@x*68+;2h$}R?2XHm!zd?gY?E`?T&<GmXVdqd30?y7Sq-5)o;g0kDLUJG$ zo)dih5B=F$SN0Ui&^(C-Hbe;CLMV18NsQq_2V8qI{dq{Iz(xu|7X4=W-rVsmeY`t6 z1G+hfrK_@v!lSkUdj+?%&}Xue#Fq%>niY9S?i-xX8m)&^vJyNpt@}mh8AEuxB{<Hh zNcz3$$nj9_&H#_;yr}|`sLHa-U6jntsroA0hQPc~J899B&t6K5>LAnR3V~S$v{Y%C z(=v3G`^{iF7E>N<J2CLE>?KSJBXz-k#ajGSH%YhM5EYH8nq{wB*=^z3?i?)9{XDNM znz=i?KvX!gu{$X70t%dz^1H-tcsH^*fb&y>5#~Bskst1zXAIzZZvb?ee*p1}tBl|% z$LI>)DEq9Av5;@?sC}GNR)Ciushjv6b9s`UX`Li;a4%J3&jxk<bkcj}!MrXH$i2h( zBZY4*#FiTajWWW<WP-%<&{8AiV$=NW0h9PZ(P;scw!5$BGm{a`2TP}QocmYl?L(TK z6<&Esexec+Iz|=VDD6&ekx8PwD~)8TQ?r}ULmpv|Vaq%JXPLhp7-9_fT?B+GkK3Ai z;-2#$egF6fy`+Ay_G0mJLhs7c0d1fUoplypnK@>+8HR5?xQ@J1DQLQCt))i}4Kjy* zVM6T3%X3a9@dL5#q!>0@T7tEa+&$l;0H0Fsy)NJ7+_-CTSJXDL$M0%mmj;e!J;}2( z(Nvhhx1KTJyyA53me^~oxq8F>Un>vaeS3IH!aX^mukr^?-?PcoWzIV%@WP?YI=iK* z`V6-oz$YCkd+m{Wr&OK~P$|^DL+UGl8WWD6>KNaFs#^5*=2EMEZP}=(^WDhW&0dw> zFpxC$)49_ej}+eGx8ymJmQ}86FZ0cu^mFqP@;4h%czi@pR5clEmzY3e&%}a_$gnK{ zn0gHEZ6>Jz0AD*>?2fAORFeKiI%o{0#`*^^5;?!(m4uQqu}M7oy}bJPWLFRpnve-3 z2mycqnGHh+gaH6o%O<|sD^klQ3?|-KfQr(fqND^K5}TA5cQCbTmo66dJB2e5a)I#Z z4nc&n1gY5T4)0G90s(RtcvhcMgpV~!*cYl>BY1)m6x&IMvUsQl9?BmCz=cQ<O1icX zNs|bAD)P9voh=!fW-$U&+#nvOCGw6W^3p(n4jW)$lB{E*D3rh(4$5Q_Pj#7~$?2j$ zK(>F3i$}l!A=w!K9FUxu1WrI_(8<H}ESTuzWP0Q&DQud4H%O-g3kmiq98r)QAw&0< zMUt6HIYFt}$BfCwP)8sw1k_FtBh_uFt?L?J0}2yp64946?@__WEHD5y)oH#9BSw;A z;>-cSgpgvp(VdA;)Cw9-Xs@ydlI`u1?TN>dp((GHNxJj2Yzww*XtFglIRe+^w4dzc z2ez1jDmFikYEO?~K;wyn@pw}0^OVCdqAV+?7_y)oqi{bOd;gP^d?ZyrxxHp)ELHCg zY<pL1#?fFVY4lcUqfc^ccE#vQljR+gs!kYW|10?#8S%3d>O(wo`HGmik=7lB`w#mo z@W0VP?IesSNsN-DOF#Aq1e^_lT%@IDbwDn<vffOoSuhd&273?!9%Ky0<DqR`Q0Xa> zA&nG89k~Q>WUvZ-p=pjAkP<@4$!U`N*P&3Nq&qg%oyyVg2N{Q@HpizPTxAWqQ@x>( z>4ek)F{sKabUIyfT6KJUe9$jwyqygg3)c%$vzay_se!qI6rN||Yra)fdSg@DEg}2A z9+zOW@BhiE%(nvQ?1zfaA;ApzHxS_AD!9oG@dF_4B+?(l(gZu~1{=WfSi5X*s7$K6 zUPt3nDI_Rfx3&e68)B7A1!rQQbWv!Lk4Owv^zLQIU2hKea1p2al!v|?gxZu`W|{xS zox-P*f%H-pqtqnP)J1)WuTJXU@>2~6d@^0EP^gWPe(D~s2O_L<kE|4c?M_gD#3SJN zl^1)^6Tk??i=N`O(NkK>7+p>2jz8%^wyz~V>${cF9RKXMFvJ(13bx7cWLQrF$1*9_ zYd%kc=$-8e!s~aeJ4Z|dEmD^{per6iBhakaNkKlJYAl<Tt7x5lE#!U)Oes@JE*q9< zal%M_@^JPIDUg;DBsNLasfz&HqPwB$xTFtuV&&185CD=fX$@M|yi0`r{hB|oU!!A8 z>QEo|p=NS^gB@KXd0-(y8&sW#=?dLtax<hrs6jF@<7=cWM~CRXw~b|8ss~ZSNd&rF zD&!lay+9XH?VEZ1I-THpo9zMAivrowIf}c*<w@0sdP*rLIhyUJx$RbDh3ok;C;y1f z+!Y!sj;Ee}csA!p>+#N%%#j2ZOg5@TpUQhoh3BqGykyWf^t8g6JU7Pck(9`a6rd&Z zZI?53BZ1u*x?Sv8yhDP1qv%l+V;Cv^Qn`Y%#dX}qgm3B1#9~qtsj(L7{_s_CyYL|Z zrE@MjsU=Q(ky7p7!bG0GsA-0(E1;NpRk?XHPjpV+fzG5?!$NmTSx%yg6{nQKa!f{X z=1A(PL7TF0*GvWZb}&(WhdN^~b=!2Ir8eyv{qA`JOl=jG76!3co1WE}D<LP*e)K8$ zur_=M_xKdI!Piwbh?~^ZTO1kBbP%sqk#{taBlONvQ|K`)Dk??Vm&qaYOEA|)@Yy%m zv2Lh^?BYFqu4m>P_ZBr&A9mNG+!POqAyztmdgbdW-k0ujO2mVAQk-%H;ioX$Ta5_G zmTD@0Gv1oL=bh>u51HVex~ssUOGh4sc1UV^_O_B>t)A0`FpqS^c`?#qLYQZUPpX$r z=G5%l&C&6dF!C}8@wydubfh|XXJm@ce$=~btyXO1tQYU@$OUpnI>lqMx@22+uId(I z@U<8Bt`uR}<wMu&{kQ4%KaTdKy#K*?7oud}O6&Ty_Wmc43lMV6w%`m^hg;dDaaO$l zcb2e7(R#W7)p{<}@*+Log9(?&RThV~WmlACaFp9|dIq^6=Ae)Gm&$}>?hrUE_|F$Z znLM#edjyfy(YJy(5XhRPGD0qDDb3N4G<J7M6tWC4BqKUHkD!;^u}jj<K76`wWQ)>6 zWlJBlrk9UewX~Nj%85M@pOlI9S;wXw#U%&WX;bm(%33Rzq3}Zr)ghz(yn3wfB4zIT z-}&Q1%X^bP?^c(!YtrS0U=`o&3?P1$*z=XOb1e!hcr(8$Eaat)U(U#i86;ybLfY8k zev58qS<0&Qv)iROER70s7vhkP_4z*HtUI?_L6w=%oi%HmcbtQ2K;YAEg7%PA@SLyf zzw}TGN0)VfGKKRTBwg#XzgOGJvel9QBw`yz_2TORZKPj}9{5}6dH3W{Ay=Wu_0V^u zZ{;iUNHIwZ@I^+7FBSTf>=QP(!Ue;q-g3<p(g@Y^cNrq6nyh+`JA0q3=#797%s$-k zO4fpVyWH@@yLlh&^(WiaMJ7%~eg2U8jAY7$G>w`brqyg@Q>0>ODa(T&GGf<5=_%LO zH^^=2i2}i4>ma!D=8cmZ^w6bSv75ISHg2!4`2Zfpsin%5XH!4FHzkymH*c2yKq#(# z_|=`}+=w3iy}89itr51ye7D}lZ@qQh;yFk|SZ>u1Z8gkoJzU>vJlJ{!*`^6>H_2^3 z*4l11+ir2*ZVlLOi`{;by4_y1-BGjM*|z<3XuE4}yL)~6*}?xH>^+>CdZ5S4mmWw0 zp%+0z5$T3r1Pr}HC<4+9RZzfCM8rY}B!p_H0s@92BBBOGMFb2TX@(+#poStM@=@%l zD4XwZcV~BIcV{PmLLNijz4x5+;R$?`Be~h5ve|36*=M)e@3T1&xjC2|V+1PQm1s_% zlT97>4(nPO3a)5eq#viq1YrFoOBq44F_o4~pS?F-?g~h?E4TfwO`od^W1DtKZ%j2x zeBM$aZe$py81GJn(2lTU2F}54I3sONd$j5%%01+Zk_$yE0~ZEGgl-_dwF|y)n}pKd z<*#4aaJy2G;tJYtn8%iTRZ*uK8F!V`(Z=BZ&5l;DwJV4^o;8TG{hYOukWX<F7{MLC zR7n5(R=I!;@0~Z$)m#IOe5~ip)wCP^_iYe<eKTUX94S?)Bntm`Z|iq4Nv~G9dhPA* zKzPj-4Z05*nc|us)p)RIGJ9T0Ldx*v>#3_qx>pL+sphlnn|sMoS@v^K>$%UaDVbgX zMP4{IV2<vIByhxwei#bw#I2ub!^99WvsRE$-Rm1|^~I_5i=z+EugGfO$#<R;XtHED zO*4`?qq}8g*`YRFb*cvdZr$at#`!6Ur|0PJYQK6lCnkL{K6K}+dD_=#V)sMJCE}y( z?T--$&Lq@EHRndDU-RVu<7r+V%oY%&dHOZytHK<!Q2UYT!dwc5*qh6F5eK0VaNpCh zHZ@2D14?nmn*qZa28`2wS*`g@m?snVWIC33H^Xr5zhel2V?V#&`F%RX-uac`k5d~E z0>>raFQT3WPZ*Yac9w?zbbQZ00aFJsK+)U~)qJcAL(B@$!IbF7m~JqDTtylKkVFKK z{06DO${3XGw3^GXDmUyslxbxQjeo=N!P&NfQcgObd13{70v7OQAd;GFVG6Y9^}1cw zR`rhR;$GK^s}{olctI=*JjQ{Z9_#q<P}j6lTj8<9GbxCYV~HPXNoQ;_oxy;V9|&OG z$zP{Cg+X1n;fc=$Uf6;6Niz(GUlKczPY(UKqlmQGs(Md#N~Ah9HFTcg(5Ju371=ac zA2N?A|NZ=mBXiyD+2?Dfci^Y-CU^HSTC?=;O8v>pHMx5#5txHJ<eoF#ckXt5Vv+M6 zhvG;5M}@3#h!ew6m+AY?7{g+WX_kqIa#&Zk13W5fM_G3<3~5^U66W7DHlhsoZ`v6# zs=nJaeh_?U^v?J~&`i2tYX#ZbZR&d^ap*y)vn{UrNxX&+S;M~xmeBEg@{igs=HtBx z3VroAtyaU7yfW9Y2Pu^xI6|SlJ+1)E(K^j@B~mBPE+E&l{)IZwyFI$25)xZ7=oy@j z&0|l(Q}`4neONh7HGgWqu0=~g-CvR2vnPJ{+<5&mDz%V$YJXZ7417oo#)uxi*aZeO zrF%1b@^ql&7Qfc8z5)*yI6%-1?bl9NZPHn>D|lL@bqEg3+eXX#1}nd4si-S>4>%}Y z7vhYU9yc{y*&gHRM~-P*JzgJEovd#si|koT^3w?)FxDOzC|bT-JpAD9W^?Jy7o`C` z^uMOFwT^efJj&j-Ke!d}fc$RiyD9qPa7XITFaLWWjfxP{Hj~=dy<7SZaM4%!tUVfW z^pHOkcXrj`Y0;q*HRoIPMsENYQ%g@{0Ha8bHveAk)=FFMBkd6YcWq+eq>=BjhUYVP z*PiWHJE32(ITy*3SJQQOj*ks)6TiGqqsB+q=UJ42%23UN`qLAA16l9ps#1UDz8m*F zFnb{-q3`^ykvpe$E&lEN{`vK1NBfiDcH`oF-)3(wXFU#|9|kUVCVRNQ2rM44)o}oE zRH4C8w3dg6o;)Su^ladHjk6Df!z&FCp*aV1-#urHm8!nZ8IC?67xnX(k~_ov_qGz# zQgHr7nsssnO2IX$VI+DQ+vlQxlRV8b`kXm1U~8oF6$SL$ge#ZthUEN`G6<_Yt5O-= z9Q{UE)Ain%-DJw?O5a(4x8N{;iyufc*Y0~;A{C*Ruf_a+mLEt1H@O#{bn@cQs*}FG z)cZi5cJzCkls%P~lluFHg{GFlWi6=-VIxYPu=S&7u6F!ZZwX5lysY2GztM6|2u=#I zPj(Vq48J#Mx>?cL3dLNOPcOZEq*D&e(VE$rQg40kf3vA}Czf{8*VZyz2KW{qE(}D@ zsbtan7pYZuW8S7{b%uz7I70p{`s4Ucf}}iPduwgP_OSfvuuj;X9VLrDM4yU~PYI4f z_9-P1Q+oFS?uc!2V4K*92QeiwJ&0Vi@?m+9wF2-pxpdQMm)j}2XWu#Uw-3Vx3+InD zX=XXli!>Zp_6K@uesN(*($4EmDf}qf44)An5H(S09i7x2#)~y6{H0#ee-ZTXzVKWK z1dEPDBL)u!eYCatuWI1i^6Saq(ObuKyT5r#YU#&c@zud5+6X;NL|GUw&<pQpUkTfH zL`tU}dB}Kmhc+W32@s3Nmo+!OxcObO|7X&vE&=y{&^)Fn2+V61#|Err-h3SqnPG8` z5&N=k$?4kN2EG5f{=AmlTg}?58I<h*efHDSuf8L;VdR<7SHqcsxmxKOX@74f*(Ht! zw&LNJH6IP%m~=X8ucH0q{jO~#Ui#_9N&OkT9>RXU>0)8vu10la+wZ?O9Z^PL7$qo5 zIV~u}x-8g8Dmd!6NKpKs`b?P8t_S%bmke((1s8^}gfFh9z{eY@`GQ4U7q8GkkJQPY z2Mu6nfNZV0DK7bhc1@**fiNjj$QvkSXEiJjIK|NpueWBNh5m*)HG*?Xzb#*|I3IeU zvGzvy95oA&1_$2tk#wY3%d=TDQ0@AYvrRTh=94I0<%Ea14lNg_q~SVA2L?^P45cPz z3s?JuYVTQRX~G^MjT=OAdnY|EcnGZ6wzLjD5U;=B{=o?k0H`Ul&Bc#mZVGxgq-K8& zoDVuWPE1HBRJ&~>^_X!*CC%v4-L2ai*O<lncdcx8F$T4+TCEQ1DN6Sw8t-1VY^MLp zSwaPpv(H;(&?GKYbUP&5`nA4CssU_V!A`IAG;dJp!*LNO^?O%>)I<;b`Xcxa#F7p5 za638!viY2nnEY>B_|lH2N_2_fX^m*QzT|wNz4WNx*2&{WVttpl@nS$CQvnF|LLXnh zp~=R}s)K$X3cj5gSzK6b{`iZ&S(D~zc%iDp-y+KduDgh2y&zDvly^%xOR?2>#g-yD z^=8t#DtK~$x@@@TQd#!?MdRqB!@ASVqOXegQs6p^`@L;cyqc`P%bK64yjtf{pfu(z zZxWSKNCZgonxEf!Wtn2aOzQRAXjuCPJ$W~5cJ*6mX3-U-j-s1CuCd|<_8JtKNUsJp zWK45tffK2|$I3$YNZp{BK!*$6$=?+V+O2)tJQ%qyiR>2vd1CKEC-NG<ng4Y8pc}Ph zGU|iHYDPoEjHhy3QtBn%G3*cRjTd?Gd?1*bE%eeMfIarWHYuTU#AjrdI7bmNe)K#R zR{z<hV5e1M;vCq%Q$Zk!#2@ymUiWpdJPfSjglu1-h6{27Lk*e_J|{Uj5`MJD?ldT` z&=e0kJSwV}dwb{RdkFBG0tMuj6g5aT0Tv2^pidF9*F)e6Z%}u>OhsHjC3+&s^t<mP zhHnp1oCUlH5l#S69)wKxIdOFadMsUT?*1u+TU@ckh~L@Hn<~Ga<B=CS`p9@dD=yxN zWVUj9*zfk1C{26ptZ32$Tlvc01thISH~j_$O&1)*-iJ$-m>ED_<`1*Ju=q~q41@UL zKDlMChzUc%AskMT^Q%J`tVal)0su8x5M_f-6~B95uj)g~anDT|;Pje9m`U$DvuB~) z^J`zP`cC;-@0v_Tgy_SkOD^3GXKUVzqDOrnnQA`0RjXm1TLiPuSGm{lwBaM;#?OQk z0KVcm;9z~zgbG)^4jPfmhTMoZhb5H#LWT}Q6xP^5Wy4^gqMadTx(vb@P#~jm4-m3! zQ3r1@FaxJ3cP4E5WG*RQMedI7>--{c6zeD6q-50LtNZa(V&)>ii?Js@jGHK0ScKgE z*^!H(gxV{~emv?`B=)jU;?QbP#Jt_>snG?Z@a*Zet%Z^(XCZz~PGy5%2#gCY82y#W zlkAhf48jU~0~~Rwo0rA_fLEMB6;XaSY-AjIt)M+j{38pxAE02)F#F^`@g6-pI}tI_ z+N%MbBI=E$;}`~zGqV2ifgkMi8_$UYuAidqH>Iw`l)Qgm_O;`!=g{|<_LP%R%|pRX zr4Qd_7TSIni>1nZoDCpfx?38d`0e87TmxC9sZ<2Vn=h!Jln%?`um_2i1@X|ME$bPr zZ=xGBaij5lZtCfF9=q(%qUBRyX%1=7pm{Rz)zitZf?r@j*#rIK>&4P*N_M)q=X@FO zep#-V-RmwZn`kiW!mUkP{r0vqil!?cyWIcUmJMEe{2$ii2TI@m{7%y&8{)@V;Yl4y zBa>i!zjWZ#$z#E-`-?T(E=bGKbrhq0fvsM}X{$m0S^#Y<l+mry`qHE0P8r*{R3k83 z*iYHMsM^-Y0S;<Jnx@-w{yJE=_}k;98>1NJXGax!9DHznra@QXbOFb5mt)>@@F`pK z8Azx@X^}D2DaxU>kV<FRZ3faDQ!Zswjv;4RnBH8AOhNu1)5~}_z5;IethhIac4mDV zvsXb>cI;5lE>yTu-kCXmw2QTGk|g>P-E>4D+O@L#Rwkvb)ICH&ny%0}1Bqq`U2d=T z#}!GZ=0k4RM%2D)s14T1^9k%n%*H~h+H3cItgT#yWQYtBw`y@hb@x@vQn_dal{&>n z$0El*b>fnuU7d1G_IcO3{lTHklp?<-1(oEw1ETbEr=f<(LZ9<>YBix3!XcLUF>qa- zMt2>#DVMX~`%gJTs#j4vwXOk>Fl-srT2sVV)~UGlX%Is3d+TxkmR2|!RaoMpf|7oX zqE-V{$FAN$Xt{*~F~WHn1lJqogpg-Kqjr{!%2q@gY54UKTQek(;;ve$WTw3w(;jR# z+rFZh;OLW7Z~n0!-U}H_f{n8<$S+Ek1uxQY;vXa$tbA&Fx9uFbOICIbMXr6&`8u0m zWxL1*y9ptiIAx|WiJjSCU(gV7KcpZ@*|D)fSH^n2slmBh*=4YSskwA~xZyr`HO;Kv z^<%ioyokHvm~F{;@89sN$Qh#Oe$OJNP(rBZU8t8~#A?5o_XN$XWy(AFn(%!EpSb<L z$=7`OJ!1Mbzk>Zo%dQ=*+3(+Y&Hr|UO3>v981(-Ra{+vq>&5?qxgLR70|LMv04b*a z{||E=EUSY7R<sg)*hrP*y~h6o=9*U407QZxY&y36Uoe;Lp?x^js^zxk=l?s*C2>tU zQ_}FgR}_eVy(c?rIL55Kx$uy@GE(g<rAd+0!df^)(VucV_%PRAm-a1}R8;A3t!&|E zYjyhng1Npd+!IkG?BtYf9KC@$jDG}#P~T2BdEE^DuhnW^KuXS^jT7e}fIXs>QKMKZ z_{)|I)IPUP<6ePEDW`EXr_Jid#Faf)-MTuy-)y!2(mm1j_~$2HU+(Tc_wLSLU)QH^ z9(&f^_2=i-%IH=1Crjxx#Fr0mo~6};fn9|L3RnQ`hf9Zx`n{o|4cA3r6}GBNnK(<F zB~pmg6hfDyGpjRjbk$`mVFGD6TeVKQ2%<^hE$8ApR6!u6*{GHCl@VMpOzlUCqJvPs zYD2D+@|l%FhZ@97aTS-PuuFUQORX|>Oqr{teg*cR;uB^9Z|xPl1*~%M{-p4-sK#hH z=$<A8yX@e9+mj_ais?|Km;VhBG$3BPc9qf%dkMF+c^d&$F@;uIF)W~<YP{~}bm4;& z<sw*LX!HBV01svlgfaN2$)4H0{sIx(zRm$xJ=i!wQnA`KUTUe-8Jet@Hf7zseF8U= zE-XZ(aGM19ygC5tY~H+!ZxsY?qRg<j+RmB(;oP4F6JzfS*zOT|nEE~<G#kMx#0nui zMzL*U4?f)Xc&ai=<kt>x2VLSj`7qb)4NIgIVM}9+)AP%5s|R_r(Y_aL6ga0MWUtv8 z_z&m(xnKHt%jZG4Gn=1>a9NsPhLtbJe0i#Rz2(b@=0mwTy!KGw-NXO3!t@T$5WL0? z4*U<0HN3s^RaaL^KHmI0&Rh8KlaiwGY15yf-)8KUVoy)Ge&gDRohbpk8gh}-dRCTR zu@AcSr(4{o0M4|NN_qq9wA2F!Jq+*!m-yrL&dc3EVe{Elu-l>as$v20L;4<0TGQ)j z&a?COADb;oF42hi7X9LJ4PJlZ#D29+?y&m2v>sY_NKWb3#vPTFJiT7yJ}0dWN=AXP z`X*Lz<*9PL5fE`td#7<ix_Cry!$$0xv3g6bgBI7u+C`_&H|_09Vfio@ew9qg)$B5h zZKpoo8Ta>BWp}}-#$x#N#D4Wv4`;nzX|bfO^><ere%~>}T#{194eW$o$L_rUMEUQL zw9UmI9e$n5@*7*3QaLQaIBu`>#P(4x?x%5`!d3?A1P?!4Sm11&j^0EK>Rd$hN){lZ zove{MnqN%)*>%Y(%Fva~AuFlhT+`^A72~_=v$?gHd<D61mR?L#L9(%eSasAO`cjCE z@V~8`=TGf^m3=l1nK`I9gd6-Y{19^>l`453py;6)1BOD!qwkf&G#Qh5rcTy56LUuq zg~Oa9`bzS*C{~9~c;p5f_vJIrD;*A3$Z<FRBG$l!9Y}~DigbVg1Kcnx>g?li=?sar zbvq5^$$Wpdl~k5XgSuMc{f1~A*+;_zn&Fl?_BmAXdkotCD<SBEf?*0>D7emv$pRM# zMfv-Fv|p5;haipGGCg>@{<SsOH-g^T2C{r;0AcrRweb$Fe)f_<S$O(^@t@yg@16 zF*oQ(g0y!aTp|~QK7pOybI}1|<YT$ZNl{U*1lS9DP4W5u;@?>J*@J{y57+3pueCNI z0al(_5061h3Z|Ouv~4Db-7`Za&y>*hQ$1`9Lcd7Ol-nKhPZzjQqg&eJFsRq4gCUhD zieERTX$01K)qMOWa*bzmAkv?B66h;7%V_c}tm_KFTFcHv*%?GmIuy_qrTmrOeF*-U zb4>XT`Pb^8TC^bAtqLqb!_(A=tzN$D`?unb+*A`x7qqAf73)bEFlhgrcN`#8&IB}* zT<bWQWUPX$&ESU`+2_WlU&<ay+sTJWJ@(Vgkej3o?N@Ha#3g|xvhXnXSB01a{fs?% z)>>9?Jp5zYSHxcuVCrlBFT8e3s51K1gL-)&O4QzDHm5XOuR!EbQ;lBH2ju}Tt@n9R z{Z#4cCR;Og5Q13MD?ja^hG+D=BCYBaGho0$Mmmaw{w8xDm!%)PC*c0x<=bpv(4gsa zUW7|=PS5y3TlF$@eo~>#=|H;HjKI^QGlh@mQ=kC`A!Erc)I06l1LT!o0e$KsHG28l zCahYFZ@ZKP-I#VZH`U~|kKdEuTAH>+#%*E7r)5rOMjSaDl1m&;7GF)_>+D1rPAPTb ztE@o{{I*_>=c;tp3{3|<lF#ohbtS)r#zk+uc>P6kz)$i{ZdT7*?Y_hTo5c8o1)tH* zgF4va;SA02qeGE1b-Q~`QfyT4>6jTX;pvSwhXbxgc^@M(WN*jbQ4?Cqv7cL(c*Z+< z!Ti@-%~R8nNRJ`C7R&cezLheI<N8|3t?z@-D^je9h7IEibihon{5dkrB+_Hl-S4zy zeM*+rH*&UfcyG^r-k?S&@^vnGD(NW~hHtUNBtYx??ggDJNdx6Ylk4Y)D3N$?2M<G2 z(==b}VO3*G0Vnd6h1YBSs?C;h3CFDE*X@jq+C#h}%^)(1`L^oA@j2%0D>8T5!weZq zbN0($Wb;YvTLDfECxE`o_^$@K(&l-=-%h`p=D=ej4n_IS-51~1K5?uzI*+u~EA7~2 z_&bV@P2J8w>FhEsG2RnjN?+jM_^e0hJQ7r$oQ_H5^(nDIxt^rH#f@#c#!QHCWi#KN zLV|m1sX2p-Lxt)X_oS553tS!QdCyeocq^f`>h#}I9c-8;xd%;};b%C=SsHDvJ{{C; z@hUb=yC&qvNpzA-#SHEBlZl_*f2uzX7`G0al*IzvjJ*!V)McqB+x>rdpD!WOQNhX? z3KRe$O$OiuEJUH712<$tCCYIKD{QD(l`3s+yvsK(uwM2qk)|2Bn@u>cAevw|q?9l@ zVLGKK-M7Vm6HCuUrd3M~UtRLL`a?g#c=y-pu$}JMo>wvLKU&21=?DA*P}bHGzj>D| zcE1k2+4+3TQ*m_w_T@~^zaNjEY<JGVwBu^e6bW5z*nake4|DDQ<$nNaO0At?x<LxH zM;Hl;21vr6wuC-xQ9h7_M20bI6#u4cLTf~nsIl-5o^WO+630M};|0rj@LVDy83*H= z-8}J713Xk02f>HJkCWkXWOz0g9!o}?!6OoJsH+^IbdFFVM`#Nt*i4Q)R~om$J3q(7 z%u?cHk6@Z92n%C`KLvJ(0yF2(4zVG%Vx~q|(_`BZ5|Yk$wW#tyd=-r!0P*9{66R<@ z(pkPKSt-Vddqm6v%i}^jW)h1zUyhpOWYSX@S=&Mr*BPrE#?tOj22(nF!q<P&D7(xr zyWAnWG9|lG6%*z~f%{227Q>xbP-kM!_41s?c4*6RPNN^+?hXsU<@%CgQCOG{8`07Z z3+Lo^wZj4^a7!#$hX}S}fg}iEC_4{I1jhXU7z;Gj1lq#_?f(K`Sm6Ir%W(5WxnTaG zl{pupK>~|%0dX#XWdob-0D=SvFo7*U9Et!46Tsh*AYr~G!~sxdUlJpM{zY9v5pe>X zeZMS0f@)d_0Q3x*&z;M|-~lYYP#6!0Wfwy5fG8U*$^^gLE>xHY6dj91d7yoc(0J)A zb(ySiUXkBck&a2Ro?7w2=wkidUq$|S_@Vh?v!}(Uc*Rz~imhZyY<|J{j<Tm@*IHGX zOISoIw$#(4)cXd)_&S0ZUFzkCBy$i~NU4okrG7GbQ7ot#5lUo3)d5)4e7-sXB2NG- z6CnFoASeq2qkwcMAOjZlsuWm(020N4uv@TTa`^!!OqKxlAwYbvu=aMSB^#=Og%Y@6 z0tsvjKr0?q5ZDzeBrt&hsWYkcAy+p2D!()j$~FNXpi~-DAXkq<ov=_#0-{~bmqikM z94$cNUFrUHrB|SeM64P-TQw{IcLXZPKt&Q3ra^$O%t37M)z3`|UN}}y->9B7skWGd zoi#@AcGYT@WNKD^RVPvq1pwyn^O9nb3;&5-O*6bY&%w+Pve&qjFJ$4LIN?<eW_nBL zJVoF-0qI@=k7vT8*f6AEX(k?(Nf1n63q*3@1}~`AENUPRewvM}r(oO}m?{$T2p4*U z2(ws6Rukgh69oOY5H&o36^c+HvHqcyz-3DP5+HCHD|DGCV6jne?k`}TDzHLsa4;1r zB-d|}g;ux?o8$(*Ez8dMnjHht%o4oE#ROCe1$XctY$1|h;|5SSM{JBZ(RiYxF-EX1 ze_iMk&;KVu=p#uux1EtUM@h-Kezy5~eiLI3cX8F|;wrW&!?cNNdXdYv`nW42^$92P zkBNC?>y`Xf|A(U&AB<`q5`a4)qqlBwQgS_*@E9iR5?kO33AI7Q%mBa@5;BfM)i;6$ z@@0)oWC>o-I2rSTB)lGpO2NYqZ$WH`uzYsS?3TVh4Cp7Irg`VD+d8!1kk$BG)ocup zdFws%)}o-$b?&XjN}&bZ?UfG9^Bm+oYlqC$$c>k`Wuk;0&!9a{lcqR9-_<csq%iEh zme95%696VloIR?{z9WYIrjL#|gW>?_E*yG#Hog-dyZ1n=ctES9hD#p~{aYQ~&29ZY z?JVt$?&7v~Gt-nmIQMed(%(?mGyGiUn*!1)0A5%f4*c4sV6Tyzn^K$IWe^sRSt!}& ztFnmdjYK*bi47NaI){0{5lG;`yjc((X6<nz;?V~BeKMv*5;Kd#%mb)IJluQ>;*UpM z+Y)q>Htb@dSP!hsz0d;>QF>5x`*$>-LmYb<X*lC{pX(Mei>}Z++_r_zK%p}p3r=(H zPjHX*1DM6<zRU&Rem0vANDeU_2bir}C8j@%UDZU)#3f>@^*ieSxHwmsz7RKSUT|q~ zHvGBL!5(!H0OjDFr5sm;Q#q_C0{rn6cqX>=x|H_=R=_m=;)e%9@9{~s1c4X=%;P3R zW&@s$7ffpudgp_gB%)g>C^jDbj1^qF%Xc?%ArS$B9PEW>OmsKrv}BK^_8_W{d#E4g z9%SgsIpexb3vWV2`glLq61zG>y80pcYMRfnZ6~*q$gbyD!FsabK_XI@1+in-PM`Dl z+(!3uf)4csvDWTC;|TZ@podw;QCBddOtgqf%D)d!{;|>QtzI@Z?J*ZMO@6q+OTFVO zICc*1%}TJ_0+;b>E3Jj@4525usCG_}-CF1q4%%Hzu=h7)<EZ~M56ybe>sN)fw9zvx zzAqSvnc@iCAR!Y-aD6F==oswCsK6>ad3KcD)gQVi^Ni%_t37yx4FMX&L_On~vl@HR zmK{_x{>*=vzUX*#%#^pg3ODq<>CHWBihZiiH+AEw>w`Bx5l^l12!q@jA<&6qdYCIr zgD@U)g4Fwz@K|Q@QOn}U?VXX^XtQiNlaesKlEi!2IE0*fS3N<XjUY5j#(d!1e1T;w zK0nd~uPa4~$h!z#BOv>85Y?>Uvoj<AowGSoGXAo2d@;sGzG3{Hrk?&i;XmAgS?4i6 z_A<&t_2bg|S*EhyXufjuldVuU_t6vB3HNE_DSU4=v6IV1N#3`IVnnjebCK0t!F=vg zr;a7mZ5rz}h_!P%ZzFaZ%^{&GIuSp~QPrItl5fpZD6rJ37AG~sorQ7rt|`q|Q`-Mc zp_axa;gN#7pkd57?llycCWOo{S~mO;9AJ*kVMB2F=t26BKLz2g7dTrsb@1;DQU1B- zt7%5Wq+V=@;f3k%mJ@-l6Q;MgmSO05;xpT%-Wxlpo~@Q1Y_C5LIr##0T}l7&J#JFa zi{uM0QmS91cD*<sH0*CK^^ZNR@#>IF*QESk!LECHPl=t^m<CfZ7tHjAyv*lIg67LE z%$HZsm);sk3zB$KGEKcT)%8`d3pX?NK=0UB^cCjNC3!<DrTI$vg}depZ9xmI7~tT- zyq||o?W=Li4AdG2ahrqbWa~{4gzoT<vboR{uKDe1zX$TKrp#Z>1igB6Yr$`F;ib#m z6DH=`E*r6mO&$soTwZ|Ia)*FDDFme#&tJX%`1keJtEsvFB<oQ?SC~zGENYdFxK3=E z=OW{`AV&a{8VqBW_$Knz3&Db6q|We<*kR$<yqYmyrrgqx3rk&Jc?hkg3%8a~|CZ1- z*c$ye>63>#2$+`~#3!DR-!>$O*>Ye}ZyRm${O|ZH7wH3op}Ma63xU&n`$LalR-sy} z7IC&#HP4lUCBD0INk21x%tFJ@AvTy8AD0vJ=w+(r5?p?H|LYp8kW0-X*12X$(rwK@ zcrCbQ?fAvD@S3;CR$<3DiQjmPuEpcv7enqV2t4sYTr~z9^jv82(HL|z(``Mz+uL$C z6N{}jsz@3L{_x6g4x&av4FHDVt`4EXdCJB04BG_0!3rSt5(mz60iNRGY!(Z%h(&KM z%=o#^S7|3mK->(<?u8uc9*`BRW-p&(Vmc^uAwnWFi_JTGJ`}*M0g8d5%Y#JzEJ7~) z+JA`aTS7f7l+@m7bMyH@?S$dm>i{eG+H(uiN_+<%qZZuMMMOsy{P!~MIjrly9$S;A zLIAP}H8Av`m;7h|IP!zf2-5$v<bOM;Pa2x8wAlDFhT*=A*z$!fq1`R4yLq$AR>qlo zwST8AyAb@NibILLpxr6Mf^qRvl$to5^zrG#)2Kz<;u;pMcX2`KO-bo){j}~sJ<b;D z+XKWWKDR{f?f>_+MeeI>wy=%+xAbasVl|qtncs<xc|v*P*ZtAzQfT(=={}N87Zanl z_xgK_1+O<HLHWWMA(L0~=pSon^L^ii{(V<Ga}U5iak_*0WBy+c+1ugH`<OQ+uU7wC zmT-N-!5kXE+{P?u{QazW^=JObzz)av1zV6GZt1|rW<DFIUmE{duwC$D9$<N8Vf~u` z!#>t);uBtZTI{(~_W*9lOP<i_duaD3uL;7VcLRUpofE#3h<6AN@5uk@cl-12v3}A7 zTBHBZ;ZJ`^&z>U{emLFu(G$0mn)ZeE%-;OtPX6!t>z`1;Wq)5j`MbD#=kH8fY(SOa zrQd&7kNsOq`?r4e-^P=Fn{WPo-2Jz;Z}-dL-EYTsf28ehU)}xvWOwJyE&w9%2vitm zuT42|$%>AVx5$+CShmTL&<gG^_uwBT$eUk;%6P6i6zzAdv8nKU>r|!{)SW5g_5Xmm zyw{0!w)uN)E4|-)Ho8_@&}5HncsC!p6+BRR<b%)cpstIsJwBU$cO%AY{s-pre-Qhs zn|5gO>f!Y7o3mo&2amn(0=|h3NcpijoXpQMl2v}6LkIH_5Qn^N{OVI0!v8@G{;Snk zsf_c-PU*IH!zH#?{-Mtv3!J@$*|=$chGc%>=<d6z(pw4Il!b>uyYSaO$70j&Z0RT1 z#9cjn_QUK`2+lqA+m%nR1=<Q;{Z0nvThF}N`>!MA%iHnd-HXBIXFk1pbqR3^`)_;m z>$@jIX~)to{`>R&McT8+lITT4EV;g?h@*VB<!rcYI_1Yi98zB~+h7jKO*T4h@c zABO7K{GTw_qzy3k`6fZ?S>1m%F~d*SO6@AQL(pc5RalvDvcJmzJIs}3Mjz-7?$_1q zSnIiVIk@U6UH0T!6gXFYzviI*{|C&K_)OyDs4kKHt?+tzXxXo8yV4=_>@6WJc9im- zXi)<`%yn=;-^<nLZJU?-VVHrphyDKh-d^q)35x!%c-xU%AD8WG!pcAtpMAN%A}V9V z<&;dKGEKxO2GRQ;_=M%!{_qPsX`AeHJWG?|7kwrC!BLf)M?@DCVTzs$$DhC+4yy<4 zzkD+kE88f2qM;%KX-=t7sX$q7e02>;Qy#X@{wAM&EOWMMI5-{XemH&(6)6^yCQ+7% zOGoJ<xCsXuPt;Ifx~Nn{Qzq-OJ)7bOrKtx6&p5_Ko2xpMdPhnslpU26cv+SxOSjEA z^<#t^-T)dD(HtZmpGtJp{^eigd-qq=wL2s2(j?Z?#$prPe#CC2ja0JC+q%NQj+1vv z4QI+@K1NZQzRT4QYg1Ruwog8MqirM;QggO3ETC~|e+6weGQh9>nA7i5J&8^MvEeKb zuhNb&=TRB5_14$nl=I%5Yw;RGosGTn36<qd_ZbkYDD*4Sr(^E+@-5>(2aPI%b1E8x z+*%Y=WcFRJI=?UzAb9@Fn^Vg#?4zilMlsE`;mB{+mmhVlzd4&`@w<}b^F2D+RK^;G z%-2bpJ9X{&ji05-eb}8by~bdN@G6DtuUs3C4km}w$J#Ic`47Rn*!9WiN%H`F?AYJm z2ih;+5SEcSN7t%k!5sfuxxU$hbLzjoXMVMB-*kEDs^Yd{CqUYjYU2&y*Y2}beyPeZ z`XCMMA@}vig`M`a<;Seul|pX_(K)pUU^5<b`WsXBncpB^ucM#!RLx<S1fTiHe;2PB zPu7wvudFL)?@5LooQ_hExG62wHP^RyoCTI@ARw*z12(fNxE{kY53Tz?d4lg=>Y%^^ zh+)#IhbrFlC5{4(4MvhJwS{H(?H_DH_Wj@u9a<$Kj2tWlO{J;Wi7mc!I9|FF2miYv zrTj-mP<9d+TxPyAmO9~?wymUm1Z~3f+BjGmGe2rJ(_<Y+u9vyt&@Yq6f~Z$5UAU)A z$71{%0wk1Vt|~z?i!4poN<A~~C_C;u8rox)fT=vb`wMj#pyY<^)JZ**9@L9+%(Eef zAWiYsiV3wsC-K(h<8o7#Ikl+c<ock@CYnKBd>&$Cvr?&W&FS})o#pc9t0D9DR=#SN z!l91VCpQOlQ_Ax_+k22Yyk4a$9cO=TsLzi?)x*N&{JCYl%VYi+#>Q~UXK#sml7OAY z&jW<Z^tak$PwP-G^wEK<g20Bft$eZx%!&0`s$6cKzyjqHML|(BDe~PX1c})L%0_6t zIqxUBRgZ=<WX6bI*XHy!!m;(TFYxy28!U)poR$0{1Fqd}%TxldlzaB|$`32#zlgrC zad_j(u}8Xcox>2xHYQ!4F^L{D?2{Se9NCq8(Uco8RwR0yn=Ud($UUm9bShOtQTHOK zQM|x1DO<F~9&BoH<n7In8{>k9H$r+&FqXw0{>@Z%XblL(m9<VGi;Q|q(f5Kg<le5n zRZNJ_*B5L(t1=^Pu*S_$p^gzfGGjeb_4-hv`e$B^eDwaP8*s6uUiSI0t#*<E>c>mN zhaJ^0Ey)FR6t?fmD2JwXy9X0FV<~7g++;A*gKoI1Ci8gCPmHm}I7w8JX^IU<QMmiE zaQ*GUi|=obeN$b!{5xac%l>d?!{l6~O`qhwa@x7W3e3Q5YAe?du6MCEH?-=sxa4!t zo}A`_Xx?&lwBmbxQ_IYKW>&rv>l#_KT`P+Ymz4tE{l=nt-OF;JH<NpibRAu_{Ns7X zvX7XwbG8cn;c94qpqm|j;&*{Zxfe1HNuxa9K6)KQkeyY973}?-7b6Yn?U-g;UaJzN z$$p{kT)E-mVG?ysIZ1bY`WUk+9vy}ZlbHg53+HrDo{Pz2wfICmyO`W4zcN(Ca~;`B z9weY&=b7!A9?CsZVMA?R+Td(k-D!-!-GPDLv3OD40tIvkI=+9J0>5tlH=Ee+J2T!y zH?6c3FuJNBeyy9X9~F-Zo6-_D)(wED%^0>gmiMZ(vI$7pYr#e|Vv4DvF8Mnuay>_O zhR|B>DDviaWJdK2y+NjA!Fu;3S5dNu_vNOwRBb4a%1Dw(I-vwNGy8Sxm5W-8+aI5} zBNBZwfsrxVo|~^<mGw$)_#sT<&U>gerHdYy$Llm$V*HXq5dIv9;g6iAV>2%o^|LX6 zT+{Vjjkh|F8>0uIb>GtG1Z8>|>kMafq)sk)M)lO7;+PCXZGGu2^b&S&8~-_pS(eey z(HznAPAcQ*Qyk9hU${iQe6~|k@tGF=GQIG9Ouzel&Fp^$w{>!C9hRy*x$)Y~twN`h zz`{0r`{a{qFvoYOo`hC~lM{c7OrKs*`%Mz6`oVV-i5v>jJFc1IsDN6`v65_-rpb*} z995rLy8OJ{T7to%*_Z4pT5$$!FYhg2I-i|(9{MSIu;j`4HKVIi!&w)<nP2<W{IX%W z=5P+|?NV;YcJH4zh_vki{zC4Yz|QbP+k>Jv=Z<3`10jR|9dM{c=(*Iw4R{@UB;&J; zy_XRF<r#K<*OBpekF~=_^*8~%?(n(Cr{f86!*FB?2fsu=R}YVCqM@qj{yaLrmx1c! zAjNwGN;r{ZPKC84BCuXUnI1y!k=nF4MkIXs+Pz}U+0)-6H`Bw1x%PhR+1F{wc$D3B zvO}uZqPCr#iqF~~-m8+-dmyt{^}JOa9--c1rQWhX5i30CmGvU*&X17{wQ{O79<0s+ zYvI!+qS9ZT!|p~Av(A)@B=F#a_vof=G=5~%E+xa5kzvHmFwcV=PN8ZrGc|DimYV$s zRQokZP~Gi5iy1zFX6^8;&xq4^wB5#RF*7RadU6Nd6gptK3NKNz9n`Ze3Ftk8%Q_N1 z;FDx4o6Ynq893T7;NLb7&~F={oV6puI5uZ?xm>c?#EJt@VjMEUYzD)<2P47<Ba;S? zyFhdu?953J^X)#Ptqh~`Oh;rUew#n~1B(MxMIIo|1B4vXCH&HLxEaQCR7E6M76%eb z0fAL1=QIH@+y27p5V$-&tqOz&9MaLlY5hYN7wt3qhiHKg7#s+rnl74>F1ihzZAjnE zQ3lB(sj73seCn=Xby$@M-Y-3*D4k&>ondV3SZd=~=IwZL24Y5WtZ1{V%zIkV|Fm-K z>6MwMHLFjrwmDvzfdl~X^d^~V%HuLwyIK}ppFDCsbEK(c<VJ&2lQQJ`BDm%JNK4X) z{uboU`3xf*M0bvQM$S=y0tm1Gj4FV^0irkn#vTHvI55!ZxF)c$A4rf4pxP<eCI<;Z zx(F6@KpJ$w7^EQ$(jbBk5Yt7B(?ytL!zE)Q-XIOa*jV6LUmH~nKPEx|iAcL}lfZp8 zAh9SwtZ7)72$En@P<&jC;yR}c%qLM^wo$tC#=%h(N&ZODA$^x8KCz@cAs$6l_rtE* zOsu#}z(OY8X1cxeo>&W?Sj(H(IPbPmHQ}}m3-fEd%B+ex>QqOxQqzC-HKx~p#7d(r z>&#Z&&$g_+R+$!28A>Fo8VMvx2C%$m3ew<xTj@J(nN}$vQvhO`0#caE@Jh)f&cQ)m zh=i1^lTG}DPv#*`h8&5i-k!dPM-hT~U|*%<nSdA)Bw##=#e0ZjK*BgG9yuvpIw|y* zD{_m9C%Ewk!%`%wc6)|h6x0ky+cyBQC-T|8Or={y<s&pD3A0q<fRFcpT9B>!El;&B zPl0hyt%w2Dd{6Ch{v^XwTf$58mh1xm8I;T36%Iqz%edDvv(}5JO>8YbJ*EXvXlD7a z5HdV!j_z(+8#o6ikTZWTdSK_C%_RY7p1UMD!;}rNVP$$aAbbIs9V^3fn5x<iw%}yi zVcEw1mkk8FgUQAuCfxD!L-(q}Gk!ErGSrsw+zsi89>@q7cplhw#JoM@5HZt@`TQ8h z$KC<v!(c`-`XZZP?<kzTmDgg}@FU~!m~C_IEASJH`s3yFipLKlaPS~5Y#s7~#DxXp zd=oG)j%{`GzP1W4(}F0z$u!^4EuBEtiy)@2Li3Ar<GvT)zTjPXaUs_CynOdYVm3>u zH%+9Aw)M#9w7?1fYNZ~gRABw?(N=g=yWhz<y0<FLg7xfo5=fa0va$7+0YKVY>3Zx8 z4^qn+W>#tw{pdE_6;HEtplTYYtCIWOIPheDsjw}JL<4weM`;*`2KgpRHlX(xiHC>z zpD49$s-8vG(ve5ikI?Aeu9{JJdi{Se@_(>M08Zl4WFC8k;OT9y3rQa0A196XwKCT} zU$1j0ssyp3@3QBH;cc;3lqyQYQhN4zTS(0?!J>nN#JL=%Ul`dk^_uT-0619=Ke>G) zmPPXfpteyNhWxFAF;$72UI+upFw<p8>3U5Wj<ImrifezHX(v*kzD%eW05fLrFV{dS z8&KiE%MrZpUCqAR4CA^`vgL77&5=WNNjZ9(LCM?L*GbvxmlEmvwf7^iwfB`67joJk z%mt^9ARhbWd#1ooY}2|{q)?A6qvvLkYId^mZ;Y!%{1<(;mrS6V^tSJhzP*3lAB5~6 zy)a1ViNL>pS`9zVp~n&teyTL@l+5w}7L`&+$|SHh5<GRf!PGC)LmGAhhv<0>KaQja zuwZC3%w-NjR7H5HLZyl6;vA|g3ubbj-uVZ1xA*d+BgiM!m+7t*A0-COWrfafA$(P# z);L6n>cW>;1EB(Jj4F*7#m9%2O>huJcBqCAUeOPyHVaV`q8-$RMN|C!s^H-$(O^!` z?w>A$f7cjGY(&%%1axrDj0STfLTxD|<j2Jc35FpyLyrYk!&4QQR6Rea6Jd7m@BS!` z1b~Exvgmvyg1iM0htp0uK=uO@#;UODdN@$dJbI(iBXT8YPCKm}aUlh9h5++kC&;G5 z1LmMs>*X3MRJnDk`Z_hJ;D|jr6SqGT_dH`CHzH^vJ<MVa_MWP;HR;NO2JzQyOt@d$ z%V;v(qT0wQy1tm7T<(*<4|_+JJRV;o)30U4Z=q_|X2~rhe45;K2w<J<Mf2AyZv4d% zkZF&H8sQ;ISg?JnHzs-3eTGKzuV?GfkMrm!Q!;%>{M{TZ)|j>{u?0x4r+X0x96!T6 z2Fp$?hg|kwDdXmTc2bRG)6Vc9`o=IV_OcvdBKU8Fn<_0XDl3@}!*DZw2na_)R-!RK z+X27&<9+o+wCh~7;}+C?80tu&;-x3{u|u`yB96Jzjxbj>@@=EY^ph4Ap-P6%wMA$} z{`$E)cn+4hAFc@jq{Etv!1R-Tw38{cqPh=7&9L^yEB*ky15_75I_ckYw{1{&t?w>L zl@ah~oyTVR1N_xj=8zrKvK=0@y=>D2(PL2)b*WZvuRMsWpxm3hlRal|v{e^|lbM;8 z4k58~nL1klyq#*#qMu>WgMc#6ivkKCsr$&$yZWkBZGQEIlbOtcCPmR$@DoW4gexN} z89<QN;pC{S*g1GdEsVsb2Qojti_2QS{eJDi`xN7>8jGy>_Dp9==2Q|`T-EhQ^3q;u z2(LQ>=0+RrB}Ck!#SnaAS75&cEq;Z<iQeufxBDMoq`Bcu_)JbLGYWoe3x1e(%5Tey zK^DBc?&WYeU>zFufabeJ67K#W6uAC)??RWh+F!Lz@t^nPTf|W^$NzhtQ|P8_?EvND zw)#A<f;3fjE?$iX{<{a(BxBo?OMk5n58hrt7wU&dFGVA1DI9MvF27)sAx;DdGayko z#DP9ofm_Vt8soG7@yF|MexqmCb(`*_nw4OTNFiiZx@ASF8YDEqcFI;?H^Y1=nzr*N zg7I+2i*UlTuV%+#j&bnQTMwhzw8I1N_y6LI?6bZWWI8jT2Pv6fe^B?#fe!dVT#UcQ z&1sntX-5^m&&t!hSWt@;h&~UZ06>gcL8hz>We2L*I#9JAROLzyNCSzgI#8fL(yG2I zvyX;ehj>vScswlPFw}PoV!_L>Hin(y(qqdL+&FY!ZZfI-B(|U99~$~o;*8@jg@@Xo zMGxN4w=6yVsbo!takGwb+D;i?1U6#-oO$c_*Jt$v8-81xZm<z7wVT-93$>HZbXGyc z3_DA#r`vN)fGyZ=*z$d&BVL7U)cLurD{+VvE<Kr-agGE>L%$s#z8ZoL#-+mhMMzO3 zIDk7_B!wJ)wNa7Qawn9|T!NXE9{heE9>+uob)IzmsE|NLIC1G7_)K#q)DDZVYs%DB zg@j%oo#QvN8R^ohAOtsEnghI!p@2vLdmp7$>QC#PaRdc`6aU;le(wH03L*+XQvSdg ze>$=N!R=Hqg>tUV9!UX2QvgvSMHvU`eF(0~r&=<=b`D@WN`|@d((oI|VQz*=3S{)j z4m&CHAe|O{Cd-qIfC>L~8-(i^{+)7fnezSnJ>c(i_rKG}FU%b~JZFDl{xZCv7$v-d z*iD<u+7>tSyhM+chldz{SS`KGw!0cJ%;cl;QO5txxP|b4#+u!X(p81YRxscGO28ws zUpJuu97NU+v^NDT>p)$gf%fu`4@kQ|&g}lo+TBh|lO?6?1;Be%|K}({l>(9mkh1co zHaHI}YXJqrn9MnLx}5-62=7vbq|$^1wEWAXc=72VQT@FsE(%KxLnRpH6tnl9R-&ek z@TUzXs%zsiI%hUqmcJgz*0jtJ)T-Q{%V<#COTe)yfOnIt7M69wzzPZ$S2k|v7-VKj z;8OzA#rBVssh+D7SNOVOf9YZTyOF>A3gu!)QugY=o`<JibI!fdu7F@F@9l;Hl6rBQ z+d8Y~b1#Sl*yZ`@gbo$#|FHS%>$|~;Op$t@n_?YK8HDJ*#@mxZ!p6%;B_r3%cwn^5 z^5cJhjJ9~aSz-s{c8tHQj$GE0D$w**3z#GQ7k^p(@~zF64--F4n46~fbuf?I{DC&D z^@?mKX4lrk=?d2V<@0w{><e`K%jMory&V>z;;0PVzgz4g)L!p&d)X{GYL4N@b~;A? zF_0L7pCjoB8n&&2F<K8+>zocWH+ha5sx{V!nrbvoyBhKORm1ZBqd?panJl-j7`<xy zI$nTJE*3J*CMGBsIeO{}7T4q6EAJmC8}HY;etH?1T^;p)xXeHG*Z%U|K&pvKMMR}c zW7#9)l`-8Rfaji=|8!-K?&+6j59k)igrT(-1HU?$G+$ULFz4_@0z@*Ei!pi~s*(p9 z3Y|>Vu9f<yzCT6Q?n48zK8P`mQRRDkZd|K8F&|ki(udNSa_P%AZT0cWQHUef5;3}g zP^z$YJJD9+>UqUnO%>7h5%qcI*8-Dj{W{wi{%=YV(Hp9D;~6h)QpWY9Zl6W#000Eg zW^)r{blP|cGFs2frpNT#I;}?4?{fnVcD3o>JEix@LdjKY+<~7B27P^eigUj_@|521 z*>e~?)*0<$AYy%f$v`G-%tfDLBj!3Vi4PmspCKw?MpWH1bVGNuY!ju&w1?1NN4YcT zL|v_C=f92_enQ{V<C1>wsYy0`;G)x`>_s*$Y8sR^S?#nM7E)8SWa!U}udH)}&iyr* z3(3V)Sp0SoLuudH?8WT6O%5By5At-4UL_Vgk9D-QoGmw4?N1$Vp_g02km4Z#_>KiG zJu{6XbjaDD)zBKF-|tuNX2{jA8xr2D&mq7iXE+0@i|t_ywWjvv3B6g0pi6UpZ1Q|$ zPhrPe<x}>fg_>UDFc;mS&9g3xH88O}onF;bWB5MlJLh!!Sh?ET0Q=AS_gTFM3lXs$ z(SJfaCG`GnceDxszdC47{C)w(D=NQoviGI^`Z{{)(5c<>iRpkzI|%bU9`MOc4iCjH z<7tQ5d-A=>6OaH-<?O}D?p6;rRkDp`@-4n+Xx&<#OGFrIU&mOq^vQDBc81zgR;T^y zX$zD=!@BhRBT<gnOT-Lee_V$2Faa)YX|)I5pQG{DQoOIob`|~u9k#wKHCk?G$eu)6 z=_|nYZUGn)Hba5`Qvac8Q0)gvFqWgZXFA1JXHh@z&1Pgq+<7IreTmIp`D;Nlg!~gD zA_{RX^<tUZmV$d7@?&r-Qn`=3<iu_a+v<t}-<yU)zZ43m^7T!**1aN3teveHwYa=f zS@oa*PKv?-NfuJ~l=bKMb8_V7a4@yZBQ3i*21<#2+XDwvd(aW3%Od_!R?o{QFa=}} zGEN$1GCPU%6$eXvB$w(bBPpf^cPnQbNc@{QvoK>N(sNFxF-`{wjm(g}u(KlcfRz;y z4guW8-WaT?Jrg{^&5y`vz=_u)3EygklcPYQo9uSOZy@XqY-ZUvwJbeoI?R04O3`jI z?@ZH*>@11SNe~eX$+nWb({A^q<sJIWKd|hG;Gi78zN|t5q2e7N5_ue$la00fA`+(V zvLqNoUXgh6VazN;-Ft2G6LY%FYtOk>^fbF}kK0Y?N%m)<XkwqF_fC)GGI21pGqEZ7 zZ*xOVNP*34-@b}O8T{*|9Ix$NSNR|OT(4CtQqLh>(3%I9+F&aKO<}See%KgphxTLi zGOkh<yS0_ZL%%Ic%@5O$WD_!V#uS9&xf%N!C?g&vS$nDo0}695^L%#{Wk}{)C*=Et zFK$EJhMK%?<V~W&G?hq`bNwb?7=#%8zJ_aDYaw<eUAIW%{-C*b{9s4V^9Mfrb{I!m zRPBVUHkZVYOIKk};Gt?&mUoWcT(^A(&x_b}uJ2VG&}>w|hpK+MK$9EP56nhrePapc zMD;uGvqY*%*9wiVZytAz&w)0Ey3W{WQ@c!sZ~yC+xpzUT$7jhqo^U$P>^{vgwl+&e zKOG&-voWmcxeqNi?%CbSQ!?LC$WkMQ2<mcsuqU>tk864yrg$f9Z(3^mEEP$As)MQJ zspbTF*UOYIsfUp(?njgB1kAbMy=J*^{g`EuoohCRw+m5mCE&K0Yl9j|JvT&)9~Bmz z4?p_$GrCwJPxi(-U8S>jVK&@^J--emU)h4|#`NYrF^1n5(OkF8a4p&f2#Oo5b&m#c zMHboKR?jXkWYH?M)biy)_*$N)w1;Fv`Jle0QqQXyfy<W$z6NY@1rnu~1*7NMMDl>p zldIsd+sIpoI4$0hRps37MxMowR)43LN>b$<8#6P@koXq3)koxgJ+N~DF{WKGo&cF` zn#>Jdy_5gs->zYM>GaD1_JcZ!zkd36mjo@CO465aOh+1iMddk#Nw%8B+`3Yj7s^SN z8Rl*1?LG8nuYQl@;xJs{HWtD8@>67$Wv3l%iHY3|IsGC9c6}$PnVh(I@@Dn_M$x%P zGyVT@d>0$Djkz<o4Y^;&M(%Cy_mE0Rb0_yp=)NI$8p%D(ElSKaN}0QgTq{%}5>mN^ z%D4UYJLmJy&i2>N&gZlD^Ywf^9+pN^PH9AH<s4rhR1Z@NKd<<Z&nM7CXpi!}f!?&N z(^MNJ)Rpln#zKS{F)URL%-X&ruQ_}eNi(>Z5vb}fdSn5u&&WY2Zg?Zim>{V#y1!8f z6)9|#h&p=6<8CFfcKi8|^3eNlC9Th#d!c%IJoHCg=Ar1(2!^`w-7JG{IxL!|C!WdI z+aX|_E!MDF=Ltkaxg1D#GyOCONQ%Rq1hmBvVuod1vw{jw(1`9dooVU4q+`~|qZ46@ zZwtwABPa6SJ~NEJ=5{!DmV4}PA?I<oxJZ9?*aJw_Agod#YDbdDNG_;eDIelvVfy}S zg`+V2U2b>UvfwqQg(jt0<0?E@_%}~7{zsemset9ju|Z}EdD>Z)zS<)D6-lVN3545t zmPCo}z;Q+n(jznYYVb{C0En~Lh#xRwTJs+WCkR#-?DsM1mnZc4j#04{KyiiyUU7&D zsepRhygoK{5Cg?=fptPmFU^2dM@+oZ`i4vGG!C<S-oVakg7tjCQklKHf*-US5ZWPq z!qp_j*?vVkD$21>-weFf`RWnf1GmUZz{{CJ!!UyXlI6^&yz>MFjq(NO$O4PKtD@y< zxR*E%^sYHpjDNmZ(DcwK@!xl#ZmEcpuW9)D>mQrYv(2Y;Tt2=T18PTrXPm$a-81qH z{RRxu?A%buvpxdgqXQ{XO~QHgvb>j8AEi@rOjhtclVhNn-2Pr(e!!vN$0k5#PWk zXH%(EnNMFbHD<o(*?e^@AH?lof)O;$u?A}rX8(2zCmQ9e8zy|!>+|`Ypb_XU5z;GL z*KZI360!oSb@!|7C8(*EeKRUi&zun``>d2dW(*)I1opb4%4PHV<OP>gNKV*#UY%N> zsF(`zH{cV7rb@H!UiS)=0jzt;izXTXCT`??`CtK|^TY3FCOTH8K1EKN{3bf=gJmfR zA=hVMCcZ#3RTAtwUg)HO=`X9R($63Bj!2XxChBgG(0hxrx?t(;1kJ!|n=7Y-ADv+Y z(P(L)D^#>rwGcZ4#OrgbYhu3E3-XNuRkxh9_DnPi1+aAjn!a{2TvRa{7_b5g2lNv< zLCQqar|Y2byw5fkUcv3ca(?~7AwYCBRVu=SdCSe>;+HdxH9m!JWwycE4Mi`k`Zc*s zeIC&bC@+2d9FVoevH+q^CRCj?DNiFw<RxfR^288J`m-ilsQwKlZ-Y6L&bnjn7L|r; z32K{kvGwHx50-r3Kd3?anCv|<x$S;Ji1^v8lj?W#+=9Tz*ZNkw%@s^?2wdQv|N8Lp z!eWkM+Iv~p0itAKVuxDd__IW;%W!CfMc_qWC%yA%?fWr*h61zggKTn7IGRr6jbhA^ zI%FBF8TAeyNvPrz!lYmG$mHH$Us!&hLRf;{vn)O<k}?gfI@_nUWpbJhQeL~D0Wb~l zSdPhEszTIJjV&&@p^Oi~xV(f!<38DHL1B(}yqQ4Z>Rtm6EMXDa1C%JJ0g9m#^vwIU zJE<s9ke+Iy4?kGO`GZn-qQ>HV0q!;G+q$e=uY_czr9MA^(Ca=SpSJ`AteJeGnPOLJ z)T~$^y{o@Iob6MPk<)hR*LE~Pja<-KVO#5EbT)y~D`>yxixT$={T395uge#)-E^VL z#Drqd_b)6tu!dbf7m$KumT0tnwKDE2{*s`b+2^hAOV~2elDLl@xu=Iq)Bv~@zMh;s zl8(--ug;UHuB_j5d{C1x26&qYwMHdc({Oobw7UCLa0?mp3F_VHSG~pS=0Fk7y<)RN z@m8pU?fa+a`^u^7m8%b`_=l@oavJ|_44qDY{A)ur!Jgr%+#+07S!NSpMY}JD!i9j) zqRYi;a|VV9d?V6&i_3f<F#cJc=15=<P^ByXVON>TliG(*8daWxg0*XWTZX<(9J2Ze zipaniixP?3-hg{nmA$fgnd*j#`gtbjkAd`vvYK+Hn@*)FvrxZmZmkaw2OLxf&om5r zst)-#427u<$2JV#2pN9)aHR4rA<3)0dQ$Dtxe)%oc6J((KC6Xj5KKD1@x=t7wkc&; z+&H$@+3|4vpXvnk(FD);iR^|+p3@g&m9^?N342p*wY{?42?i3Nr;otBQw{l#&Pjiq zuZm23>?<&v{Ae~?Z7%=OT$$Q@?W6x&Q5(NcKL4J(8VLCfKE6o@4f-iDHmActxGg>w zka>I)C^1WvoJr6x99EgIad?#d?%&-*KD8B##uW$kFCD?}HkChI#Dq(DO8jPl71rL_ z+6SNE11WUB#7}_KW?b;134#NFo2!CviW4>)PlJ>^58Ks#tTz7mq5d=XyA$>M&wcgx z{_5NExhF<E&?pc#52R{k`q8FejjNv^5r%qwA8RM5%>?NL+9q2ihR&+@m`jgjYy8e{ z`t7h8Q5qfy05~>l{8k@2<jE=$4i}S3{BVW_dh`87Lk8aNr?zgtYy?TOi=<@eK^Oo% z6a)`=kas2ezn@X(DF61wyHP^B+^6nK^PdZl11PlVJT!$DGTqd@pb@lVntI-0h<RG0 zsE$W;T5(ezu-E5@gJ$Vm<S=D$*}gnlWpFjU^>%btG>6^ok9*#C~L*mYFblc^a(x zAz>=>WVfb8xA}Ii!*+mM<St=LFkss_tXcSKq)4KsaKN@`O5}H|W}zxgp|jiQ`_1Tb zP4RwBK<Bo^bhFTfZNXO#QazedKO-goYD%&+B|bI3YXI}^Zgm2g31w8in6t{(Ge%p9 zMzj6iY|3AEzX6-9ejF+vuB8ySqi|Kr$G1hHDN!kI$Dpu9xvE7O?yc~+1>4htecGZr zuBDt3CBNL_^PxrkV8?rFM-kjApV*?o+p5UY(v*$XQi)c_@2YFym5;aLQ+BXt@io56 z#lLX?D=mPdmQkQG<dWan=Pz`@DZ01COG~5m-0=pFqv^l<4M$o1Mx$V(8N89*5_GAb zuGC_D(0YP}C;p5k^2VHa+Deip48OS(p-3<}-e!7&U}o87c9LLzw$1zk!6Kl|BAj3u z*JgQ>V3pElb(>&a&}Lmuu({u6(?qa++-BQDup4f(8z<PmYqS4EaQNEh@RM-zpzS1! z;K<qT$gAz-jxx5)^%ZP)*3dq6{F2;{x>J_z+671#+xFA$7a3|648AsFyv5lI+OE=d za#_DzAL8{jEM!vJ-Ne_jFFr6V)lzM0!JxGic=5hgt?~y@&)ZR+pV~ct?p*k(t;D)? z{=|?xyyLvM4*9RP_s?G%8XeyF4sV0l3%l)JygKAl9fWDtFSio!b0<wJlQl(-Zy9Ir zqqTW`8=QRVI(#bjeJVPFAMZyn_Ai#}gt900O&uXU9ii_!j2B|3zsClH55h$bg2!Vo z9_WPM?}+#t8}_X#5`MrF7c1BJnV|Zu9(SS8`FLFGmrEKCViV)yZXdXH{2c0Qa?gEy zMPT8q2;oZ4<G;mkFE<^(4qlw@3cddIIAH4A_2tJmSaF^8t-g5;6QE8i%T4Cy@f9iE z#5=CRNZnY0(8QDR32KXnT;Y?Boyk}48oMUq+fY}G<9ybBBo}nbr0seWrxe;rN}`Fd z7xqdIng)t>vwEEH)h5!eQ+%iyox1)9nYvr6)?4|ZSt6`1Nbd`8Vn2aBD_)BizouIn zc5*yBsB7b(RP?v@`60A@qV~#Rb~#NG)jzv)d+tG;^Ko3hg0s=D1KdO(3}zypN|G*g z^tYRiHMOYlt9jb^>mn)FD56Vyvn2Jt-mKx_Po;}J|A7SD5;2%wNq~tC?ql9f2CFDI zpx~04qKUX--&75%YttuI;LpTjzp-87KrXjBJKuH9m0={{%}fty=>eTT!$*z}yJ;J@ zCLB|Ho&A_}TQ+&`u({6Gh7tPfr_-iCBkj4DGl1?j-WdKUant#Zw$U2ch}Q4kY;xzO zvl6PGkm(Jzc~F=fA;b5ry4avgoB-TeBSgHf^kfY^4EU36slVzc#r4S`;^;x_@n2^@ zfdP)DyhBuMo{3I3SY?kSuLM$`_${0MvQGDCP~P&d&d>lpC386Z+Wk29Cw_xfaf5M3 zSv>K$yqC{j^Jrc}$+Y!KG7`oHo*XWyT)S}8@Ry+9W2%wn>uM58AoMGfb7iXg2+Svi zvO<j=Ib~<NninEgbd;aRNkrbxvJI0xu~J50)@$y$_k<3W>GnU6B`M8-jt7-C&PP0c z^v&`1E*p6weeR9bP_I1OjG#Isi%HPtdN##U<r4qzqloT=&V61}en2TmA+Jv*{?Tqy z&^-dZW89##N`=#w;dnyV@SUHJ<awQlel--UuZ<t1Nk|-@HkruKtJgkSD0seJZoF~( zdc*}(^lz}`pF|zOgw35^rEdGa{f2v}L`2PzB&H8;uiy3g>63pkXGAc8s{QQgynz$@ z4`P+ngozHBUxCp7*keAdI(;;tXFvSJL0r#)26U&_iDASq-Ic3Tn9y$|^<4kx*Q=#h zuKcQoU=2e?!_}T4Z|*-+S9n;v#v@>&oPc7)xn94)bo*BpcH_cEZLU~7=k#KH07n6G zrZdOK^0qW7Sx_(6*ZPivQ>{x^t}NR!Fw&K$cgNqp<ap%k(SjyVqk{2--l@A;^Yl}5 z>|#q1g3{|ZoPEysZn|}O&}1r~Pdy)td8QT=oh)RK-(cS)`>OWz(|on}*Z!?YM(ZCe zHu(WEwf7POh4|&(*TT$_GsC?4Q}`6lbQebY4By6D<{O^dVRRIP@6R;wGI7)=o;i4% zMiGW@)K?yh*wI35v(O(5o8;5le(%`{?AvE02cbp(a6bi}pRCoq9sShb)FSYeC&_Z2 z*eaaqN~#NJ4tV$c-qpCDXfJPJUgm|%yXs&#$6L5~o6!%-v%b{Hdb|%awVlMjS%jN` z^uQgNK$t2`&If=AGc3@xebpF33E~nU&7(|F!IjpvPoBDbo9O2yA)E&Ia&m%j00#*^ z^EV#KlLIJsk4d&SfWv7>Ab{l@*~>7@n;aGmI%>8k)$fiRmJOP+Wczi+8ZhT;BLjGY zDoCkjzSW=sli*Ul+7~Llh*P7QFI1;T@soC^#<X%=f*ZZ_m*h1FQhXd~2B>C#ako?| zHxW#F0Bg{JjRj4R3cNS08lTK7PMQjtyU1G$JWHFb;XWTx&MXBD2}e21ElZxip(iia zU#Xv580cY;AaF)i|GPdh=+T?E?vo}cz_l$s=d-p3CaWUeEiaB`sp+hP(=1(!Rx6SB z{?tu2J$W@VAKW~4<~?M4JLOa&%^Hf1@`$`8?p`_?D0`xyc}>iX76^XLsvLZ?aCIB$ zc-Hf}_Fk3Gm9*)6!UW54pvk$qS@FDO*L>Lf6l}KZ=d{bP<N~i`n7r7@7juaMQ3=hq z=d*vjd?^;}8dQ}9Z=T0}D)6fPH5qjBqTqY)F#gtpfVw%3EL}txSU4c-+^NyD90#}c zn)g~MCHLzu|0xQ%(F-j(D6~#j;=kSdWyQEq5ppJ=F{Ih7YSN)(K)m1g=}2oY!N98a zF7(GMLdI`%tjUC^sh`{ob*Sh<l#96K6TXukk!k-;g0qH~F-bIMn{%s0acxV95<W@5 z#UFh4_>%8FpJ&v*?0<)z4i!b7ZLRHs4>ymX6OSSy2bTJ>%r90imB8-WrdWtB6hHZR zxSVr=rU0<HESG1`#Y&USR;&9YljZoE5l|ddX6-L}<;18mI?z)9oD=M(F0uY`!1*HS zVBN;^A4iI;L)j)b+Fz{th`4;91Mt%KBEG^PR9+mR3W>kB6Q$L?$i@I1w}YceLY1SX zcB5042f>6lGPO^57S|ON!Cs*~TwohH8w2aAcm;xz&GVblGrk!H+-*x!@pnx-8&>2Y zzX$QJg*aJQ5})ey#5JC^I&t-!G=cXo1a>2NZ$^+fEkyfJF{ngU8!GoD42MFs8P|zw zDk3tTLn9R=n1vkB|E_GI=FHc0Atud}FzQfKTxgm4q90>#UEnq1jPjK8LDyhJ1+ptr zPZ$0W(F$SNo%&H}Y3;D%W;B;}awZaK|DYdTwY4I%!GtJzIB`bQC1R!MDaR|8kjac& zggVWv3#qEfBgBzI6g^d~9ico|i8w}8(kyKbG!LcQ;%ezU4yaLxmExds^`zFJWNmzJ z+p6}QvlR3RN5VK|Q0=*1W}xpDdIR@Wo1w{V%jK14K}!%D-AZON+M;GEhVa)Wt@<Pe z#3l=eq6__y%P61N;K*{@+TT_o>M`!a%tBj#Z2_Al-(tt5LBfdFh#KKk&e<0)%dPqx zbFy9J`>avM`=soUIu|q`-r@{<6WEoRAY5@dMa5w|+ez*-!WoyqSBtx)GJzKflCY3v z(LW=+Co0AGVHSNATK%sGnaAYXH~eC!hyZ5p!vWfm2HQjFCAysS4{cRd8inxs0IEWV z*3SMZ5{gY*d2k8o|KG+Eui=0fB0g|H(k2HH(m)V5^Rm!L03xeAaCfRIlEf{<z!<hT zv5;}gsGOvH$Gl3ILdlLvh|G*hgE(uqeG7`Nw7=2qCrK|fSM(^!@UW^9Yp+owr1I%| zae-y=zo)~$_MHjKOF-I2kYs{^$e?|`M>%HSqjz1U!hV2x&liIEQYVt6_ZB%%FikET z_kw%ZSNSlQ7RsKz%J%yE2vY_X8o_{=xFm|txI)z<nw3NHPNJlaEs_)lS*Agx0;b+N z%n0C!Ja;Xj7b!fbV20&(9<3CdWQ5`?fOow%^Ocy#=1wI?W(4@M^N3CpxCemi3^`S_ zQ&f-wm+;{*$<bY5LiJp1curob<clv%jD4B`Q7cUlNQvOo>r_CvZYG>A{ZKD>kp@H> zdOhD*gle*zsY1s0k@Z^|CiiUd(=T0zir3SOHkzF!j+>&V3I|o${pWLrg}wapx76ZE z?mCZO$vjmXk<K}l>5lp)6gS()?J)s0tMfTIz!WROs`c3Z;Q;JmvemC(&z#3W&~r2k zuh#8!heKV?6RswFtAJUD03S4fVy;>kndNG%14SQFU|c!yXjYvmx*i85%+ss_cXmX{ z`)X0b(VJG5Zr1AcoF_(mVdhp(1=|4@p<_<)u)wEc;bpCf3U=`MY=iKpe(##AK4<u% zZV3d^nA|rWfAi(2vi5i1e<pJOba5RN+qyZ}1h?f0j*$^GWP<o^RNT_c>l3cXPgW13 zlA<yzdGs0Ds68@V<&=-m7Jo-nYeLn?V#x~LNsawQAg$y3#lMpEUX9aXCju)a3#}}b zQ8`)u?1J}$!okN_Rql7$C1V%9-@>QU`A$eKi*&{(>s69cg&Wue<O+zkYbLyFuVv+Y z&%M8AcG)_HH1rSMB(+S<6!jxA=ciCJC5gr_QMo=WK4(QB(rq!tv7t>YGUhbC7Kp4a z-k|90{(08w#>?@(zjXD(kWN$%PsBi#<TjC0-(z7XdQ?JU(P~hc*u;HWwXip`Y%pXl zb1C-w+Y^=TUwFH`vYc_f9Q+ZzlB%Mewcna>DF@d}1kENFz!+nl8z(ovUrqV;5A!rB zaNt3X^Xq`j1YVM2ufPli7F;MR^UAGy@%)*?PnPqe<2O<qG1+kAN0nmj5j`E{+lQ}* zWu?AGTvl;&*tJ}d5#*LPPm)!A?fY;H0O;pZ4re}CPo+xC(D^<fCkp|>o!E$MstD62 z%%3B6=6+$Dd2DLXQR7RQ5TI!F0Lr39gcyouT|tbbk`W7GZ!EZ8AbJrU6<jN}e4kTO zJ%OgNK#_|tEQk}|be5&KRED{1(H-}bJQ74NE{QEP33p&6r|9DIz+KlyAvdg4U>MIo zjXsQ>@MnZ*C3ZYa<#8oR<eC?Hv=^=8g-9nu+$b<XU{y;mnt^CY|87-zk@q))_dgsL zHWbGp6V446@}Q#M`s5cbO}nHIKVh$8*)DnF#20#{MzBH%EV7XdpP?YLF*&XzNyZW* zo+|PhnG4un$TPD}T^3p;Bia^)d?FF6WC7hJ;qYd`OjD0i`gB>c_{fsv%97+LRict1 zIS-V2O_$g_$uCEhH1y(^$D&yO0DUVB0{XrG8IMgDrc2b(1-ZOnb?RJ{WU&@%QmJ45 zbA<p@<tP7jNr4E_mISpHnUx5jQ~(UP9Vz|3S^BRN_|$ehho%@Y(PJMVUbiF^9~_~D zL|2m}G1Y=wWW<vUuIF%GU7-Ar-XSS0Pc0cPhvDE4O`5^x7h+Z7sSP_3s>%$h^Hayp zYGHoW2?aU98*G=_i0~)D3QvPMV=3QbD>zdz3ei!Bz~-ja#Uf{_@F9nI2Yr{ey@Lyv z7{a2|vHY`G)T|f(KMMRbRnU3qzZJTeE{SJ|409vH2AC+5C81oUe0{Lg)g_TV&Y6fz z2JsP3jV!vdSD5u@2f>=sfC%9Jn?mD~cy_0zN9fNZREN>K>H^c#+z-e0o3#cTMIwOs zuRD@>JbtMeuX#%3$E22ZE5Ux3a1dFYmw>6NMsWefUz@9-Hbi&QXs>gUBuKw8k(|j| zJX_?z5LF>AEc=ED8<|AulJv{`(Jf&jrO_gRULxHaV%5D5`AzOH@CMD%XyM6+sZ{-* zQ|QV&!tqo#l0Y;JYh=4EjH@+zzdQSxQ|ODpkgt|1yZgKbtl1=`AJPpsyrlj`OL4Rb z*HMXGOF|MrUj7-rnMTsn3RsKn(_*s8Lky?XUegwlw~|vzd0b#<Nm&*vVMdSuVNr}I z71q<Gu?HlfEh2mbQ#V3HJm(UrThjdLEOI4;XJHXJ1b|=LQHZMmqR9X>Wy6`w=2&oK z3tHdJv%XD$B)eE~k|8%{6rQR;Dk?aKD3)C@wvT6;wkU!>D1zu-zLx|+mnHSA2>Umi zk`bf!iQD#H2oCFQn!8gL+k}(9Vov^cIr&cWGS{#)<dWn2NnOKZ;*4G)J1+s(F=4|h z=}%4~F?7-S21XfB^o*mz;|#9PWF8Ybp9vK;S^=?Ra)eO0kC-SyFF~F9Qmyp_2MrO2 zaWNe)K7K4;h|pPqUR2C4z6w$YMO%cRDB{t+o!-7Z3NxJ;#+}<d*7{km{Ei4K6{vsv zCE;0;BkZ)iV3qvZw9+Del&Na`p3_5Q!0-r|P`4C0bLsrtugIyz^Gn)1M-=1~(Q}UM z`BexxLP2!oA@a$vx~~_Eh!DdH@+l@5O#z}}$)^DjC<O=wK+MSA&xjnN0Ei<6+=t~i zAt3q|p^i*gDSKg@3~8+3yn=y<lC5Mh9PF|Th79DUa1e-K8zLBo3Ahv+aJhqh0dN)m zrbKY{CWJtS`jdg)I{sc~g0Mu8IuT^D1Hx2X#4ZA4$bMpEj<)<@f&5@23?!Bqath-& zydUx^KV<AoNKOpw2?e!B<V{_?u-*~&eLrklC;XRiIP3AEkZ(eSAg8Xk5)Ae@0(lTo z0~9S>lCl8`IZ~avfTEzEVx0;wr2?@As#sy~G45}Y3s|gVGrWy#V*L){LA-cp?}sOm zD+$ngV<(;0Q_Y9!Q`2+hPmT`|!3gV?JDaa56bO-wwyz)NJt)>GhxMC2$DQT&bv zK;_>gUIBUuJ^&^%3QD!=OIz@FI)>5S8byWp{Z3N!*uk~Qch}0jqUk`uya;;n@mQVN zjrGSjz8~D!K7P~v;?2hoZvHN?0VO(?jYv<mpGO{2c;n#{%qz1(o=d+xr^%TMmpo+) zk<|f~p8)Vi3gQY8Vn+e7&u8pfl^_McVwcaXW|Lq{pdtI0T)~~WgQQe&#WP_QOqdHZ zIdayAPDWM$xce4UsJgswDXAHUsk@8Z39hNsL)cpk;+klBqOPwKCMEn38YaqZlAlHu z<&JWNkTG%@0PY1^W<~{Pd<9oJ1`@)^tPVgdxL)}jpS?`6{J4lHTtu*G7FGqfODMO2 zzi&hIXt2vPWEYKZj#g3uw{XM&;vz$+0*aQow$xm;%ek6extiy4qxr-gdIc9Lyd6{l zeQFe;D9VB^=v=fELh2xAMEPU;<gtDK7J1)dP<<43Z6C-*1R2NQlB58HiT>~k$Y=#8 zg96Sg0*A5R-7jL5|AtnJ`5IA*?{|4=2>U#%;9tYQ*D$a(OzGg|(*ARtAr%~+i=`JT zII4+xAI@=K*+3w?%GSHe)-MZADV1+uF8`%>FYu*s2v!K7FBC-=@aPh7I4KlGqKjRj zOFp4v|Im-=R|;LB+yAb#@5<BsBc$G!KW`?z+ACpprP}&Qwf%gM;~$Ze#p2HML6jVH zl9SY?SM3|Gt6|MN8%$&!lPjbm!0Rk`HIu)t0+LWs*G?pzCcT%!i<><WCjJz%q4Vj` zk%dIW0MT=qLZ11>9(zB0%zTK{Wn0%he=T|r5|OluA{s_eivCEN&L>5U5(J7q0E)(7 zg<_~;tTHblS9;SsFG-6(K_k6EZ?O*Ls}iTVMaP}S!lE@HCBX9J?msatN>5t~=EYV5 z;1Lu~-K(vanXRO!t>%AQ^`5pFh(qHSVPpyqHx`z=$Pq|x^#X9>_Tkm>`C^FTerCF6 z2N*>L8Z+A;Q8<)I{K_N=7XWu%n3Wj7n-2iA06@Bl-aQzff^$Xqx7=;+PoH7nZ3b`) z47{8C)SUd};ot6H_a{z^-4DfmK8iz#`_N)>h$z#$<h{40ZqKi)w=8FYCQP6Wvxfv= za&~hN7khlzFWbptrM;iVAUed0rtHhPPw85pieW!qqF?h`zuGm3O_qYW#{lapfERR_ zqtWm2$wcZJeenFzpqJs0`;qXKr9r&f^fj!Jm)G#as?${JBjgfdl)_y{j`hI=YF0pT zWUgu^a)T-P0V~d=qK?|XuabFOme8(Q9jlK7@%ExaudhA+D%L>fvCS3d&OoQi6wM>h z9dx5Sl^bxljCJ5^(xc}#QC~-cu6oyx-ycG&F3Xfs#ZaHGSwp6ez7M$@PH*K*s!dM@ zz(m66>!Ol9s*)n5(}u62r?sC=>;1=Gp`W=-=hP6ebSw>{Bqq&#D06-G=6-KkYUP{n z>u+EpqNg8-)p?osk_1HQl4e+x7TXU66xhrZ)WHfy;Dor`M3{6*)+m{q2>|<JO6|Q+ zM7qR8ub@QSdo}v|j}`CFQ+Zt}uv8D859BM7y?j>KkJmR}etc%`BwWOs&6N}d<7wo~ zui!khh#W8Eq`835#ETj1C*lnV$e8mCb6*a_>F_Q_^4}60t8&ebBp}GEYW(pu_M`TV zWl6e#1W?!pxMI3+$582>)xQ-d<1eRgd^z`=rz<@!J^($R85f@%R|v$sGZ~ByaDOEe ze&{P!+k3i+$`bY(sV8z$p4>AJ;))Wf`$pkc1d2D1Bt^r;3w@H)$UNv?^qM0&7ufK8 z7#vzDn%OJ5=d`)V2h0Gr8r>JoeK3AB_6Zk?-{m`Tm{h?Ec_H2Pdco5-x(RaWP-?5$ ze3P{wpVXW0vV0AQc|apYtM$oL(nUJb#|n4a<wkpbNy28lFWc!Jj=lVL^!HA^f<&Mo z6bsJ<1g!(uig%Ril6c#a_;c#+$0flJR8f8v;TXE>r5|YGNz|s<iEO4uYR_R7>oDiU z?_~&|BFAA4fUn}jpDGsY99@8CPv{I?_|KE3_U|I!gT&!*@imbf29Ktpudpx5Z9bQ3 zP<zo2u;>NWe@oKW7s~$)!~Shcv+#kX8yEfoE9ct--#pOF7z&wfx-giocCC})W$Fu1 z7JitjSv8a;c5wMa%6NIVubgeMYEfj-OLi1024`7hxHbp9?L7Z5KjaP;@9d43?EPX_ zNsoGMr73gER??=bI;S;uY@QHRb7;2IZ1(D2@JtKIM}D-h)lU%E;PGN|v!yNM{S*7N zGvD1iqrc5R%Q)V&@a)=L+39oJvkcF^QJp)nx@Q%gD~<Jpk7c+tUK~J4=legLR|#9a z_$>Ne<K0eMTDP3Fb3gJ}*vd>-na(4z_OnciQ3*8Uk(=jJ^7ho=w?e%4ctcn0f0=I{ ze5o%skiN_Pr|$F^ecI;IGrfoY?H40|zJBmldA7YavSfdA?&0b7>37imbe-?>yI+Pi zEH+*HeS+^{|Mq0!K|HAlJPX_JY&!&4%(Y421GBu6_*diXl7t)zKP3Ukic2<X|J8`6 z3N_E1wZuS@g{@<Xj){i1>7J4}zTtvLDkP6!Z=v)NUP+EszOC?My4;#cg0_4<r(9mI z?Ytt)kbO=I+Gb9|aNq1&?QqC@r@ae2Z@~Nuy|aJUobX=-GmXXd>ON_J)P2MN9ix4P zKILX-veae>(X+|oP%sleGt>7{r=;SJb<l+*Co?{+5%REN<9Q!j+<@x?Cy(%Y4y<}7 zVs||OfG`!l?~6Sg)ta!nBSjduI#on?0>mv+5W--DdQZHKo!y9;D+b?}eQc8v4zloX zd8zL1bS~Jl6Rt79%&*q2iSUMs=x>l&NzM-^@l`VZYs^Qt?|AOoYM?fD5XafW15U)r z(WTVP`u!bv>z^O5!h8ND7ij=^v^fCyYc{f3-YtZEm~ZQf$ygbez%IM;iSkF3C)Fle z8$KdNr3rYAY7UFJ>=nK=cx#quYuEY@&i>4}U9`K@(kUn0)6H(%q$%CYW7SWRqGUx} zXzxQM(=vBnN4}ZSRDT>s5ZcoojZcSb0z`LT;#VSCECrQmOCu^P#ArC1fhsD}qTPdx z`w$g8z<VN481c1ti~|f;x}?7vN0?j-Wp_aZr*m=r$d@+ig%!~b@<qDM76Q?X&m&?) zr>HUQ=`|3x;3D>$jzvwA7|Z*;*6yVz9??BKSIzfUe8wZcdJ1qWlyrJQg-m9cvLa!s zA4dtp=kc~O%R?B$V`FuA6mE*A|C81Wj@@+a6;Y5Szu_X#PVFtR)$v<%`RyBjUfA48 zSF1Tx<L>7f=Z_pfCEvYZ-lu46AJ-A{Aw9a(2bp_F68W)}emTU1Tc4I#{eW72R3Dxo z*nk1-kPL1Vn)0|5CWzINIm(Z!-2+@Xjs;?oVZK$-6Rj5Nc?w`jt0hELd>Jvs3sHoS zl^t4~*RBwR=x;LlJe-7jRZ|D#l$~Tn8#n=?u?kK!Z(%MyJG?J{4xf;z=ri09z8j2i z7%=7kN=%VA%t@4I#Q?8ubf#cC{ZiS{3i|QHJpa$s;TuIS?DiKe@pbG)e2%D~dYXlf zn}Cr2=z#7!#X%XOqPByfhO(}lg%<z7F`wBX$um^2umn9j2qjCBb~`V1GVSHfdoX~C zPcr^64;d7agZ&ru;-<QMrr$`da7`em*!X02Y#<4K5n;Z+kb^WGAaa*tIJI4MUiMT+ z70+zKjkcVgz7E2ppQW3trjoK=pJT`Hsl|dW)0q|a%Oc&l5A`~^2z%px$&^$R!67yT z7S}IQnc%3+f=yg^GIbk>NXChN?oj&?F1Ao_uKa`!3on(G`p$JrDvAcaVlOK`Iw6Ji zb>$A2?_-?=s?}S6>f;44WrAM;0(9x`tV|0-EWgG`*;VoN`beb8yaq9UT{In648ihb zyK>@1b93@bW9sc7cQp4EGJW=L8}R;0Jl;*sj;)pzIgbJHJ;7zT4NM6$7l-6&Q=<X1 zedYF{->fxV4K4vpi6!wIKQp(Uim6v7H#S4>w8cKS_fJ7qZXIp(n8B$gcp43ie&{3p zD*x%a_f6;}i;(B+LT#IDB{0)cpD~%Hxw6P<HfEty=7o^2uM+e~C9%z$Z@Eda9rY_! z(xgL!MI<TSw#p)x`FZ?q>5AOQl|k(fUa3Z#RId0=XN}pn4P{fYPvp%7j$e#C|FgPM z@FOd}RIai3O-x;tSo%aC?{jpzTPgCw0CUj(H5shey^QYSI{&LK<CEOJrnrqbL^X`W zW9Ifq^cn4pme#L=d-_Ro9r4h-eL#xzB1v*aar9;$H>GzquK#jFiSb?zpWPuzfbZD@ zv(|ZJ$ZS9T{DcXw+y_{&uMgVx4@5H-OEc$MLX1CblGGku!aN+8x|d<`AR;oOq4|<* zLa3IO=uu`!>1Wg}OrL~dfb~?6&4|ZyALGNx?0Cl*@h(SBy#*}q8AWd%*Z5{(<~yN4 z-6|2G^}A{_n%tkPUkdl9*8YBi2rPbMFJ=22p6X)4AM58MP^)OhyGqUoI*gHF)Bjl& z8rPrm1{X{3;4A}doYF1V=rFTcAm74KdcAMI82B%55}Rq@Ur6H0n7FU5p6j*ledQhQ zPKqaSPdfJ~L2Pc3Lz#yPxz_kuY{FH%socKziY^~})RuVm!cn3;0mz$$64YyH);=F3 zYSO_NGRRwp&aL%{i6(bEWgX)^_2*b`2>t^hWQqG!<`Ob)E$M7_;CdXq+ka|^>x9H4 zmu1Z7fH}t{!sjlU{8?Y@2gO^0bvW**Bk$^1iOyl4;~r+5VB>j3Gl|bQsAXx^8|m<_ z4>(u8D6%O!DwfMMo&KfuLuYgtD&bm@S4MvB$QLutJ16W8gcVK{1v4jxutzL1mnz|G zzIoG?4`oa8Pl<}?4XY&7D2_X9#boV_hCz=>n31>WJISkyi7Kih&7L81n=u9Mwj)_z z7o7Se-YgD&_{MXHtCyRF7en*da$;oyy|>>gIT<W<II^4Z;cZ~DM3N(Cm}^z`<lXMC z@1rui7|53^m?WjP-qo-ZvSNUDzrJ43kdHd~h0lr((TgE{o#?-D5I3h}JL{KiS?bB_ zR^hDkHX(RH<%9;tKZ86wnB^#OOW>!X#e~80qmO^*)ofG#$vaZH9R}#IUkOlLZux(E z2N08I@yYtt(qPkW(?_??^!)dRe|*10=%_S4>8{Ujcw^j6aG`MH5d4`VOJM3gIGKi= zS@hwEzu7B{ctV!?By!_Ek;5LP*;#QFwMG?p((FbFkfssIWDdBZxUqb=v{ekmGPJfz zoZpK2H--EDBG3F=Snk^p&`82dh0qhOd?&z0Z-}sE8A#*+vSUldNb$0Ip%>Ll^F@UC z4Cb14D$<Px&H^BKQxKid%XXbt)m?f2Ojxbt$r?Fx|0E(iDy|xGC7(VXIz&TU0E#z7 za9<;H*HMtO6C8Q~<GDrl_MNrLVRCuE@dE(BgLo>92pf_`KEcV1P`qxQNtG_(wM-Ge zhe9Mrgw$0aX8}n232+<$;W_Dg_mKJzfc-!g$lF#jNJ`K7%HrE~<YlAH>ewL3MQ%1( z>fHp}#RX0RAT|KVPRfmDF6vmyReEA(*<-fr%j_pP@kfMCJSN?~;?@TSBJXYH$F(f~ z1Fu5{?>8n)Z69pJ2(3>(2H(#5zLu@_l}~y<^B#^fp29iK;Q3b}4`A>FLIFFB>pvA~ z;ItsAT3&V{1Bi&3&<*8Sr}1_LOF8kKn5ChDazxT{#OiazU*t%x=SahHu}ZnJ*15-m zauw2YmFja<*xsx4Tn*SAO{F_{>pR*(caEps(W}2>@Zyfq`kfQ7Jd#qLsdb)tP@ZL4 zo^^em?TbA7^}Lg?yG}}MeCgfOL3hul-91--*Znt3BhV!00xaK4Dc?sgf0shr#qb8! z=LZ$#?~(I^^>`yM^X{;lP(cNk(hB103ogGXxVm0&9ab1~nV0K#!BxG&B(cKy%e)yc z3bWP=Z^Mdwm5T0I7v0s%_gIe-vL;=+;~aB}w-i=PKX<&`y0|i^_<mY(?eD~TvEqj> zitnWrotV3Mn^@8wRPs2jq^rJ!&DngmUQ$CrbWT96aHUp@pyA7<c8ef()@QX?8X8f0 zK7u0)2Mt*KKRx$t(Y-JX<d`E!XY1ZE6qxO*&}8#xF=bd{*(X@pcd@b`u=1Z`W%FtG zep#0v1eMPg-J5?={(imu=^8gcxndqw!J*HpfS@ZH9l05Ri^z=%UT!*{GF`xiF0@g> zhMkHw^BhYc*(dSAd*R=Gbs3^1aY?B`Y)g9uhtiWu<(HKj8<on+Rd{rj(iMpMORzW_ zWXk{zua^#YaTu|Yyg2sm5>SK*uztyo{{Z|%0C)m`0sxVWDmH~deFEf~Uh2L9QelAj z89>1;ptK`U&Jie$0rHb;_{ktoWuVFg=)y)#r1Jd;xBHQQYGeP@#_QjYQ@-!UU3U&$ zH#`S&Wk7rxkYpREEv1g#&T)^ZOS@8+X#@3*@MMEXt8Ud7&T|w!sW08AzxSm6p1xZp z_k)^0_0`3p_2>sB=?@BuS)uWmpv3KC#6rFcu9dcVyx$gsR+$f<Zv^!yH}q}<txP;D z8%kf@;@M~L%+R<)9ZORwTnUR@Hw3sgQBVgI>_P<y#{?>3fb4T1Zv;>n0KzaJb_~I) z3BetlQpYLe`w8TI3T&|;rEUvZc8Kg=<N41Gc}E5{&EWak!t>4%4t>Z2{)@PWXK+2_ z(b3F=h!c3PBKxhHe*_o^xNA?~WgEAfc&{?pOk<tM^T)0t-(70qbZ=39m9F+mtYOVv zEtrRmrq#SEr5@b6I@zM*E@1G!MIYX(_P+JRw-%nS$??Ew5e~ra7K$2qp{v-EfkI$y z+D`|!pS?<X24KM%7~M`s?m_F)Pz?MgiYo^NqftPf6F^Bo4YC5HLI!>Avg_|}oZI60 zN#p@LAuVE&+g|XJMeZB4j9Y*k^A*VVC<L3+JWKT2*_L{Z5%vKhSU~A<T-OKyaXbaS zrP;+K!bc~%+P0*=T8dw^M6^>8KrZRt%QvEhk^RC*CIuC(ql%z*AvFWqmr(87@OI#n zLBNxrPMW+_jUL8{LHBM{j{4zelt&xt8Lb-yd?pm#Jud!i%J$iW__OI(DCwxoYfi_7 zB6%Gm-8QY#97`;1I58@{s39s>dIX2n1mrxfW0TxbqY2`zsFJ6FT$#`t5s{{jCidGb z_ok=qkC}+X9d4Zj?pw5!r=2OWwn%0KGGFlIzX3!@F5-J~Oz3t%7`RVLM#5)Xi$Br~ zJ;^`3Bi!yRqPi)pywq25yicN3ShGQOhYN6z0vQZ|*S2RR#6MsAt0NsLW325F7$?la zA_kzy>lmnB1jo%S&Mg!doBAue2tiKNDouddF-tXr%imG%lqtJ*@#LSJ00W4qVWxGh zasRiW{ecmJ+JTp9>8A(}yaa{hx*A>Gys8rE^~T4Rvt?LmG)&)oWY2#jvHLm3d&E9} zAVlCr7Gh+=Twb@8CyT<lYR-|g#qBu>Pf#3~gaW1+Ivan7Z8i}zM7ZT53v|K}(t?3+ z(_jU(!SHV&p9ydvk*kXa55RC(EJEAJ0+TodM-9J`%b9UNXVSMccCdIrh0Em(GphV# zqXO#^$7Vn1>nYgd*2XIP$Kt#F-d!7>-_(B<#p`Lx!(=l`A8<Aikqrtjt0WAH&%C^! z`BHfab$1fchU2`98QdUpuVHu`7CDeKu-ybC66b=2+$7BC*-qizKl3;4AQ+UCCu=;& zcaNV(AiS`Arh3Ifz-QmyMs!TnCjrFwx=-yN=@-rp@9j&kCx}j>xG7cK8x+`A43AU< zSo9KSJPq1yh&<ThI>BeTfkJMW81c`_jZeTDBe?Ddz*kVLv9mtbuViEzr{Acwh`h0j zy8!ckya?x}!~4lnPly+5a7gv-DID^+q}xmUvs2JPRI-^u@D|Lh4QX_pM`;mgFagPm z;0&ZeOPI*LEv^q!cEN#42ER@*wy#TsiVqWQ-(MSEEfra^dtHv4uXr@qtq@wE%a|}l zKBd4<t}4^FPEW9*ndBEyM)*VW`;JHQy~MG%cMwn^l_?_kO~9*rj_~)3oPK#A1Px?K zhF@VoLQu}DOqj@l+n$I$lJBIuA~Knla-V{1ZPuPVZ4=_mXPL=wVdu)}Kd?Hs@csM3 zPvj>{LwWfnSLq?kUt5;`j+}H9VUz*aEkN$2vLIPo;hynrZI3kWcV{J0MPHNQm0O&8 z6OdHL4@Q!_dQ5=eB4~E;LlWTq1`R%+dwEYt|NhP?p5&A|6yo(Bx18nz9l5NjzKnNR z)(%@fp1rJBrvF(&{vVCBO6Ck>LKH@zxlzbV9PhIzkR(U=C|S5QYw@4A{I|9fN4*NI zICwb@HU;ClRS6S#15t_qVkqpU4de;{IUa*#H+<GDF7)*AKd!bu5tA{`_-t#!-y3V) zE&1vCkFPg*)~M=hi4JSGek^!_iuWpb-&er4CV1E&-T(~v6pd?Q8oxEk;f6!DxCmd6 z{Nn2^Uv7=ekCbdVg58YZu$<s*V6vvyP`qrcyc!CeM}+yJIFmVot8fre%L`1D{o_1D zNgHSC0Y19p{czaYi^k1YuQ$hjY<~ZK>H?_Pr;aDL0`>^U^Ob#jcjR<Napd7-75BJH zB)E64>E1h7f8i~E=?<-ns89{ijYjpHe?9Hj237*x_h)eVZb2uAJRMBLO2p;%SnZ^1 zh+YO_gO2QPM9z_sueRWq)nDj4Yzu{Ni`?E8Yg$G)%m1PA{&h_7p+SSlr@t=3zSFoo zaFDAVh`B{BGX`uLH`ZDFV=C<UZ%in>6&H%?v7&Kr+~s*R!EF%nQw3lZv;{TtKs<4b z{ForhS%c}Fkeiu+!Eds-egFV#{M*^bx6wa;UEtmK(%7&3Nc9AH?^YPik>Tu_mhS}j z+XbFW7;uQ=O8^D_qyiGX6~6AV>%+eR0Ca>-a1M|kFVbLl8Q{wlCz1QmAe8efX8Q(n zHJQj0HRUV^M9koj^hNGlTSIS|2#8L6o!y_B@IUu&|EX{K^Kksnqo02?KK>ci679h# zS|4)xZ0#2VcuX5-hX6>r`LXGVkWcRqymDy?0IqrlcZ!@}M=3~d8sdTi*^r^^;Z#HE zx2I(Z^hBw56_cHTiPuXs_&F0xjP}2td|f=YEOitY)cj8ZE0cHl@5iTqTPIVmPSSO6 z#z0$8ot!9U9n1P^wfrghvy0xPP9jKRhn`!l(eAC$N^<}pU+vZG<gz6VYo0B4ZfeCk zPw8}{@7&ZE+d@r))mLZ7Ywd6R9LWiOn~KU8cayl(haVh(<GW`3?yQc^890~-KPx%h zbbI7k;vuP3^Ifnjq$%RM-I=$W=h}kaH2S@d4IO$6n7I-YoZt8{J7}r$+11$abF>?~ zpZ~LUZS;DU2viv=arGZ5t*P*<IzqhD@DPA|Uc8iko8~kVWfYt=m_rC0OgHlXIR7hn zw%Kp|hCMGuO2*N#+BG`hZnv{rY91H=12-jy8uZ;O=Ess{+)7RE>0e4!Q9k=4!Kp;p z)>Z3{$lz^-3#^5s%b6lU56v{Dy8rHOeM$*AdE%etPRjvsE$PefZOtvkTUtR^e*2*> zN|9s*Vm2yFvg6{LYx&e{F0VfQr8N^_%44wSD1Q|&vI0LjKbKq@R}mz0i$6qnK<Jcr zCf{9?HA+9fn0>E<cxe6$fA$m|wJMrzWAf8V?)FiHwR}n53u(aW<=Q)rtAPor(p>9F zTIXYe<b~}T18XFes#E=o&)W2Yc%yR9g~}={=S4f{-}_)$es5tCmapkDLZOKFMBWz+ zQG7a#l2ycVmYDal7lnc;N~?vwixNuKcKER-2M2>+jIzv3szq_g$mN<G`5P0Jd@qyu zYKxrZs30MhT~b9-Nua)1BJFG;aQqZGQ7Cqnwy`u^=&a-AlVO+;?*$EIIC0tsk&EO- zlrszM3Ia2i{0c6lDy@nD&KRr~ZV^t$oyttTbnvlYXWO#OkER4IaIYvzmIz#Bf->~1 zK7J|km(mN&;Vkj0MXNm-k=F*y--`22SIJ+mz48NyL1GL$v8lq<jFr5&gvnc?-jz-Y zeDx9S5P<h<p%+RyIxWBbOQYXj4k%UI|NZrLAU_&#nKn04nRP=iS<A2uP^jfv)_e>J ztywfFVC;!j-3fAbM+P$bq4Tww#7Ewo$|jy1LUD~$$QO^spk!`ki>}o#nY3-I&$Re` z@z<=LxPK$g&2SN6>4AeB%SY8WmEQ2FwROshhnxw53MlSJ97{Eush6+xD-)|7d5Spx z-=1zzOOW)<YTRdp&4=w}6<5#ZFG{9Kb+Y3A$=Il(L9++J@t=R|BQC9^ys<3vo={m8 zW)Bv@aJu4s`M0(o6wP?T&d_OZ$S$@wuI(6@NdRuvSr1B{-H+fzpHHw(F7c?YE0MTR z3A<5q>8}Rsrrvi`%3s)<bJ_lFSFp<>&oDw#si+hOD^oNx)%2Jg38L;QD{j9$K$!5$ z`48xrBx?t=XYZR|?y6*Om|DCGBO%5kNpan+gIcLh)qW$Jaug*`-uEUZ7_D`GbaN5Q zJQIruGW6jwis!%;Pi8tAQu$H}`xIw#GPI30MFw@rsAq?R0)P6Y6$CLl46m$!BX6;? zhl!}y#0-^rT!0i-f)CH%iCy5kUH#Wv`b(QIYUeXsOyjIHLqfX6SMvK)OvOhgVQOpi zvpqXL$9i0EUjr-(y>%QG@^d|YX%<9f?s_TNTU*=K?wGCwd1_SvGc8agxbYPzR<xH3 z+u4hLCz>cs;MY72J(YBJB}pO^1wNh$I=iG#zP?#io$6;(IGr~ZZzWUa4e-%2J9i4- zshOejp(X5H;X;0bllsNl)`*?Y2|O{FTV{m*=<wYO3x87NF0JlboA(D;(pVjtAr8<e z-v|!9Ix0+s>BXB&8{X5=%<^_g5C2nLci$o2#Bnk~_`~9mb|p1K{K0Vff!z8v<ttM; z<h;N!+gzi;XoQ#D5H+{WQc=|FmdAst6VdUaw!e~{E2h?y02RZ8q{$3VM55^DoRijX zgk0+KtEFD;2H75i_IcX*p!?>`)Ml1aNM`hOL?T(|!@yKs?HlW!!yubd<*|+jryJLn z6|Ae$GJRcZ1k9LyDx;G~mDxJv>egB1T55(5?owk0@~!*d7q0F8xv5u=+;tMMNPt~9 z;#+*OT*DT~HpYZ6_~IRn&O)ZX$(eTB%8=mD{a0@q-_`>m6xktiG3ydJf$tm_=$QUw zl5V#*`o*kENY*#(aQ@d$r@Na!S9RxlLN~-VI>Evn9Y||AEbL<7kVL8@_eIfuQI_5J zs4)Y9qP8=)sU@42ca@mghdxrTBJMtP>F4WtGbl4~IEb%nHZx>^7}k_T8IJ8X&}kvV zgvg(fuulG-(p<F^l3(Ke7rZxo&7^l_h6KtLv;5`y#r7p@7Q^;W$}W5s8woVwH6bBS z_)<CY8IOcJ@-n>`E)l}3n${kF=d%xy9Y$xqI{xQ`bfU?;s3vP^=p#P+&pf<*!&DRG zUa#SfqH=Yu4TRY;xH$PgqsMh0zTUL*B{ap|4)EM9n)a}M^M;iub;Ph#_l^8&knvfd z9A%yxzz0VuIC+FT8v(|}`nkTG63!Ae<0Rr!q-SNs-5Yj-U;Xue<Mv?eO111b?w&&n zkSYJuH94h(n&q!6i*Ci-Qr$m-$$#}0J(*;o<?+Ujqs6&oZf!vF%0yC3pbSi|FhLSv z@xasNS64aD1J3K2riLaW^Cq$QRy8FH#}|ptjnxp1%x0I1j>~D2jMj(0?b1EgKm!x5 zL#eM?a^jX%E4+G5dD;LxCuroS-hrSJ#x|Vnvf&?lj<Ma4H8p58o5IOkD_T<0A20n# z^z+9N0n2M&jTGjDdn>ewCm-SiFh1{^>K+R}-{#;SB_mkp;}c~S73$;5gBPReTTLb- z5gPKz@z=$qUf)-miw03X!#L>7!HgDOfvPuR3b)j<Nx{Cl=Bv7=7JaS$CCZnAzC@%- zNSXBJZNHXS2<ICeyRP2XBGQC2IPp~ZMaS*Sb}P!`@le91XFgeUS)>Q0p`|Ef?C<(P zv;_m1KK^eYEAy3D9b`?TVS%gRFP2-5($5`5OilRb9;A14{`}j<h=~->y()!geQE9G z-0!;c%2`X>^9z;(_P?ZN=+~7(CexgW4}?DuWj}7e&LHoZh+2hP5N=Snqu+x>B;zbJ z3Uh*o1D4VBKogz?z%9A%3Qn_${`~6Z1L>3tN6QMVo4?0y{@eb$IjsFx{QiZXmcZAh z(mxi#%A2>j#U4!vYD^_!9e{B6cnG<ZJFJd-5uQw5W4KI1`h1?m*y{T`BHwToL`>gO z4+N<)pDR+RLjNo3?*EzG|2TkOySp|WMOcx$xrrSyi_+XSL@SxO8N-$#ciU)ka}*wJ zvt6T9BS|+L9l7a7%}qtop(95kD^5mt>xLE*=cMCwI>+}qKYjm+&*SlVzhCd?tEy-y z5%lxlzShjwz|q%G_vcb$h%Pn&7`=qLt5*5GTkCHA`A6M_GuVSHc}|r)N2LP`ODm&b zlnVTIv<&Zu@u6V+HRxCc6eTj^5!$GCI_|x74aLdWxb}!FNGBU?=qVyCBlN1e49N(` zj-q-N#N}RT+2p;gz@Jj;@4n?Imw;XO&gd?AV-3H1gRULJ3hPHk`{DZjZIeY1AdWsM zhb5;^>ihs;tyacB8!xnNHXI^Bv-EAbO|mo%B)~aG=5O8JhQU;TnepJD79Ft*LDY)Y zP{c;YMey*ACjwE6)rLa>oaX_1_g%Nn?DaU<@!8ZY1l8)(ZhNQ}o3E62njpUy2HGej z8&u-7Y<mazPPSI!N<qOYAww+<R$>ka<vYh9I5+jpAG6yF69xPl20+p8pkxMysla%9 z-eOc?Vibflq7e@Oy_zIO#$q%Lz-tkEH_HVK|I@ok@&a0MDXk=e6u*cqjycVjG$dZN zEqyF6)etkta>Y9cRuY+fIHf3su}TkhziVnEjB@hE5LOz=_q7s_rlNoqVbOjSxVvk+ zd8TaQbr~Cg*m<(ZwqLyyUF=4QgH19z&L7YH59}i9E2=fs-Qj2H{-?9tK{hU^Wrs<t zV^Et{Q2Umk7Ix50-G}iD)z{IY>t5^e(xA@sL0w~3hg%!zHvPQtw!3qtiBeL9YKzZL zh8HgA09DZA%;uD5Eyvm~_Fcpt&cm`gFhgB3(!rpL53-~VP^CK@=y)oWyrXjHfh*CF zq!1e`kn4zsXS~o>BGe=rH7PAJS%l#_v{2g?Lf+<6_bZPf;|Zk>1f(7pFj@dyI#4l0 ze1ihKp9S8r!H0=KzM|4~5@tQYL=F8DdgRmGqs0~7kl&3$7TWL3u}55aBTM^MEw|H` z&G2JN&%fJ48V5#F2S&bC^fZ490ah~*<_x401LdR|{mHP;-4f`L-yidDW!xF~Y_s`5 zM`<2ZqPm=-fOPMxR@Zyp4zl+Bg#jB@bdSgMa(D$&5vq}fQieT*D3V6vf<XQ7L~H_} z$W;i7YJ|Cp<e^3dHlghm(yf%RkmVw;0Wn?!fEtl0VC;BaH-;;Vsx1#3cw(b|;uL@+ z{S!uB9lqIo)Mg>fB|zdB9KJPpl#wc>cRbm4Y;;qz%ppnU(EKD6&Z{E68`Oqt9gPIq zor7z~sF(;p?+E|kF<<7GA17kxN_qq>X_Y{OyS)YLX#xXl*rQUFclJ>o=0+?BG&5#~ zIWfb%nGsG*3uC4+foYM)v=B+G70ehXiS>W8P6S~YFi?y1)S~qSF^ujaiIE9Tkw^mY zAGDi?SPe&KYefha@LjD4um1~}3Sfx<RvQVobL{^O5dJ1I0LBme6Pay3o*g`%=^b^z zJSr1EE|f(Hmm>2&M(S!KGo~W<PmN~`N5cCL!4iNcu!@2a(qQq&S+S-1F0>H|$<&q# zmb{r&(#?WysO864#|v2}IO>vNR`ClLE*V<aK4#ZDhB&0sNhFWQc8A=6r_8{!D-&mL z$j+?{N1uNYUEMsvR(jVAPec$gKRLzJ-N3{aLool!w7JC|kfkfTQ=6dlrpYjd)RTg= zgD2Hgq$MoC0@6^}uhk-*SYlY&1sSnMT;NuK*p!MO%3|$VMP4kFP4}~|`>}UE#u7Wk z9jn<LnCCEady`4;OOG|m6M?mW4(!9RVnxBR?WaU|GNL^Pv7UuopNDd!Jh4=ZNj<2Y zuyNZ_G#c>2lYsV8p}Yp3(2ZA39OFz@bDlMGo_BLz40B$-;4p>gw^<OqlUUd>@HcIJ z%8`jQhX;BXQTZP0_xG>bO2Fw;FK?ql=aTlm@7_C8zjy5mRf%@*!V2|FDb=L$JS2db zTZYt)7;c;Q%7-eYb1|v{8LtXTCEx?Cu+?F*=pHGFg*x$<*i?ih(hz1e`YjF@%+P>e z0As2e2O;c*{|SgEb|KcN#pX>C_hpT*t&~lZXA9AW7DsrvVAT#Aqi)Ej9#oj&28k6W z)1xNyXa630ZFVihd_LY{{<S%nVA&6L4&dMzrMzvRpMA4Ty=AJ}F8f18tD@(AJD6Gw zesLOgNiXuDVPaGcbLbOH7?Y)*NfaK*@0BIghVY1Zi)=UnzjY^p<5837c`Z@TmSfm( z-e;+=TJ3Aj#vX5tKaMPC5_j=cD&IGlz?C&Y++vyX9VU*fP!`By8E@mr%?Uz0>G@A3 z;m4ZZhJ;!qg^`lNeUic+6@NpE-t$k}WR&+AZ6N+-eu_Ng?lEM)u7P;XP}zr>Yll(+ z>6gMdTR_SzPUO>|s$HP{vnhVqvATP*C~f)59H#K~@w6rxUjwGkPp3bfMw%5LKGzec z4<_R7P9DVM+{AG8?@qfae$#h8kWs^~45}2qIkd(uk=DIY=V4cvJe?-{lJhEphDl{$ zQ-xrHX3wLn<kM9_HZQGRl0mLM)#Yw#X{FKPW}R0L-Y@ApUodnovq(G9-<jKjQ?!Dc zNElbA<VeN3wf@w6Qd;4?l(Q?zZuz0Ue8#Kz4Ac&ac2n~7Imlsy886ueWDCL1H)QdF z$j0Z8?08ky8Dd?7ot5d(<@pw6L|P03?L75{Zm`)t-0|+vO!g7Cw&|9NelVUCPUT|e zbiuu}tL>n}(&bs_H}9WPPMc1CsG-YZN+I-Eap!ZK`JheLyiHZGz@S{N*38C}qrVl# zk!qj@GL%?sB2O0N+~z&Hc5ygY=cq_fUjxQ2^L8i`QfQ84U+3B&-*L$CVlMoigOxrK zAJJ?&4T?IRZYoGne@S=#x}i$LXH!mU^Wp+Tv#AV+*OB#}1r2WtGn!oH=h&D4;cN^r z%^`p@4a6@iU*}JTUCj(l6O%?GQbDd=+~OL$l#HK)_@A=<(%6g-Hv=W1Y1^tESp5~b zk^XW2+EpLRCQb7%?XMw)3#!1BWw!*fCt&~MswCeBF>k))FA%Kf%hkn?5n8w9836;k z_K%D|+ZKFWUcTFyx!plv8rEC%5*(aI4Ms0qdRVs{nAs8<y}W@mlI3mcY>5~tR$fdW z{g+2ofP8hz<@rqKL0dh^o{jca?_1AgP4EPH7&`T%t4nm})kS+ttD_Z`MY9KppNfa* zGiiX<$9VcyKa{?Jf9=HIjJ5vm*dGzdOJ6}Ar{i}g`hI32=&_RZ-L2L6>NLkk34?)B zR}Uy5h2ii^LlSkp9rp0&mQI}lIA5X_CQK*%GMQGf>%gv+?Ee0$QZkkbi?ho~Faj#G z1Gi&yqE<2vsjvmgH~$nov^>1D`$z`c*)pEh#eu(5db#nIxe3m>iQ9Ach2)Mu%}M%G zAp-v2y^aLd026>A0N~&zAwZv?tnDrOfA_kH!Fh_(`hKyoEAM$KS-cZv>2C+PhuJ<j zX%}9}E-9}ctR%+`X74h*C_YEYnmHeBfcW)Cs);pC$n6!^(bf}*w<EqEZKT(^Rj)dA zdF(Q)Ze1|%20!w8)TtOXpz(_a_6?W601zJ@U)i%7T^;m8t>jMLA2Tl=-n#zkXVH=! zZVzPv(WMv7qL{Hry|)#c4QvNHlv59@7JY!<32iBTdN#&O4_PG9+OqKNM#}cz-;XQt zK<$OT96^r`;mE(S8(tgy*0b6`P<V$jjf#b@VfU(gef5D_)92k4`#%-MO8Dz(XFC7v zv6nQhSbgo@KQATJ2H6WMK66F^kBbN)QdIu&a&(mQh~=kvTu}B?%Q(>8o^j|2g4&x} z$iYgf0sG`}JfwD;Mz+d}K!Eb5`jLLP-8&J$&BcvTfFUo+iXYNB_2wwKpZK<P%k5K9 z$0*ZHqG+7ErtSo=LsW-s@czO&q6nUTT)xNc!@HA=!0)FjA|lhKPOhRH1WrarPSjJ0 z>x_EJXkoOnvP~P@8E28f?Fr}7??yj9i@&$4@vNXVnsIjDOlRZy!%s^TwVOb$wkrS8 zrPMQ}ZZq240_0ci#gv!|Rlq$bUfPe9c1O}0Pr7AmFO)#MnM+Lv_5n!T)k)qJpvTYQ z3cIa;_iXdc>6qDTfNJte$d!K`1j;@ne@^Lx0D>+L`Sm|&8>t!80qRrjgWJ@}o~O41 Tb9EnYO+2z8b@XD;fam`JcZXT8 literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_quat_infHorLQR01.png b/images/demo_Riemannian_quat_infHorLQR01.png new file mode 100644 index 0000000000000000000000000000000000000000..3c4c9b0b698546a6cd7880c4ad1e8cfc02b63b28 GIT binary patch literal 60870 zcmZ^~1ymiuvo{Er8-fN8ZWj;k?iY7=_u%gC?k*RXkO096?(PuWEw~1kCI9#K``+%i zJLk-qneM8Vs_yDvSM@|H%1a<4;2}UkK_N>?f|a4500Hl}JRIzM3Ke7H0TdKMsg<ax zqLip8iK3Iexs{C>6qICSYWhc26)n8MbMM30&k+GBQ{MK_#S2s3b!h0))Xc!3pha9& z2QV5MwAfT)X_qF{PtwAC7C6lsl%f2>s^Aa!UvHsh7MJ*2y>EFBc<<ah+&A9*&iB`y zU!en5N4Kw4jA)={JTik&88y6AU62UxFuR}tzyN6QXWrm*bj;n42^qw1c*N%*=fq|+ zwxYl1lW*3N&fBbuP(s3RgN`hVR&WrJ+R$-qQ$WBriEHe9<}>bkSj~4RE7YwKT=|@x zG~BrCowFrwBT_rK4Hzf|^Pj*-sDxLcqZ>LmP@$+ena#+KgD0F0=wwLVnDjUy(V~lq z-gX{|SVWWa4B~?RR)|aW+w>=TKi?gFU7-7c`Gtzs(%XUC^SPu9)<ktd967htCLv25 zQLTk5O{Gu&STrJBjs=57RT-{4x>xulD{n8oc^)^N`-bP|(va3MR+*X$2F_$$j>#Z3 zQe$8JuK^HE!91G%d!+a&Px(zRmIH1o8ak)Ex@I)!>zqXNqgJLtIbCcx(LR1EIKKXk zjI^Iq_}L9L>gLKBcOocC+kRY^XGGgPjJkXf$l;gYyJfKSH;^NWDht!lsEu*(r$s)h zI-j7=E<t@yFwI@WHBh{)e&b^;0K3ZjC4il=GUeKb7K%$3%6MBFNls376DTI<gMGi5 zyZWV8;B*z^Tq6OnYb!;PoTpXs`V?x@loYCOD>Q3@2a22ldP=AJGeYhDS5^t%{m(E` zB#4*+2vbnMy5KTktPN3e0zY0r2a+IxgRugTlZ5b41LjGvZ2%AXs3!n#VeWE3xG*8t zC;0#lhflfyjc#NnsI!1@Ltsp>h9SBSa26G~MS=hh#UxRaL}UpVBZb|C^Az$^gu_Jc z7l}kgK^JM6`dp6sC2XYNYdO&)77vVGP?d1-l&>XbR=~Qjff1%`n3<88CO$_XZVloI zVtDuH7MP20BJg@M*8x`-hB#PfOXdRk{u3XdGpI}vN=#&0@hdeMCd^(K0=PdPT@f(n zr3(EGQ!V(bh-<!=Vv{0S`9e9PC0$ljX;JLdt);ySS5~aNM76}ZP<qkv)Q>-QH}p5u zUg$3{qTSR+NK9@xl#~d`5n8dsgDJ*w#_}drhG&KY%)~!6>5waf8@jzrihd3+HY^e@ z!YrEGP`RP<hUNBbIUsPs<iIeX4)&OBUpYQG4mw~viZ(m0TJXVFM{y2%Z<}23J)8T` zbU^z<3x@c|K`15B>fzi%gaF|Qa?~IKQWsP^^a1!;uvOuw=|CKDSxP%l8d`RQMnrtX zxfFR4&u|*1>~<1I(ugE|vHlG8A);2;cLg^xMl!@<-r<H_`77TmZ-mf7ImgmIMHU)f zn!hQdDO4$w=&JB0@TEWr<6v+oxUw&y4__*%IITE(7h#xSSa~=(iIc)W2CcZhWVKjR z`MBgu@q{F@jGUB8$#^kL$!xK^B&Vc7vL9)1@^so|!q(94FhN=i9jmyQ5_`FwDu*lL zU%0;ruDYLTE6GMv<kIL<_!(9hd1<J~ENHMvo5ZU`&e~Stki}+8nXM}7LCf&Vddmx9 zBhk8_`x%!z%B`lS3Kg!R_j31k_7Hco_s)m>)$(aQsEesj)Gbv!zDKCfX&|ZV{_s$| zjM_f#uZ=#%uEWNr6Zm-_i2l8}8nduo{jf$EGLuppRh!OY;MsX)wzu$w4a*|cG!;D+ z@e9T`RW%8<s;`kpV)N-P+`ka{Q}xBqOBKG+RCrdx&wrbLoG+bso$H<FtmLc|{7v$e zi4C1in(Y@GCA%8?3%fHrK0C1`T0M@ol=f4-SG|DMv8BXU`+2)rzXG!A-nrpvt2xhN znQ7M<xrHCo?LWfjP5zYpA)LaW3jh1#Ci#Z;#vZQ=_BX6<Fbr&P7>=lpXr58*Rt?(H zP(Sr(`LyL+hWUv_+fwuReQac@RLrnlGEp*dsd{Nese~+X)^Nr{hAqc2lea~c{RBrf zQ>U%)&x`s+!)d$A-!ok->sR@E{IuUvJLlCa87j|zbNmJzQy#<P%Vle3OJ^H}(UC>` z44$@*{^{DVX6QX}8=c#rSGoq@DtH=uqH=<NVn8>oh2FV4l*Ihe^<$c7LvIAx8uRbV zgq?`wER4~Lfy0WrFxJ6`@@r>o{&drH69#)-IlT{6WqN`wOD#W~k6k2Myj!rF@4SaR zLcCMF`7TxOWN&P4a&Bs`w2$WxV=r(2uAlOcshZbj{vDGd#)r5HtaX@fC~i1yl=(gS z0XjeVFK!I_$G;Up{eaRJ(jkE}g*}7!At=U3A#&ls!6(4fMSG^}qa)`mrb@y4#Zpgt zW0GO5skGSZu;yUop%G%*R~zvdp^$i%*q=zIM5%OKXa}YhcP?5nabQMcmM|$z^P*d8 zb@9oZuYERiPd}zJsC!;U=*Oy{ov2RH9oF__`HX>&yMp=@i#7DkNUooG=gSV|lHG~# zi3Wj%JiG;HowS4N)iX#`#IYwD9Nxzti6JE~RU%d0Vz=sawqkm|`)yZ&CXl9qrf_a( zZlBFZ+h!Rz4~a2!p<UW+K1(gw2gXmppL~tM*Z#4%OT&Q;W<)b@I*%qgBU_-L>Vj&^ zGR;I??DxSuTBSl&qJFQ=Z2AvKJO7hsoW%sA^|bYpb*t076X#xBm9v&cJCQbVQ-^i% zKv)~{4t_hwZ(ER^^wQ0W`RsUqwxCVq>P%u;P7|~J2~{-&@0#N3!$YsmX_LCGsQr%J z@rK<`-?v-h4>>`{p{1cEp&M>B?z(SFCkM3<F<uO}TWl?C!qw2V{uNjErrEP!#)sQE z+duhVy|rcjP<)^uzO7pI{xMfu|CQJg;;<o^X`uDwH~!Lk>rbojrBh`~ds??bwWa-P z7J4GEAb8?q_P3Nugvt)0ZK7Wqr)q23MS3b;INn^x7j<N45?+2r&&vL)mzG=8=M8Pk ziN6wloq1(HKEjrS6^b`2Epj>9Ed31JIU8Kbj>-C#Z8aWBpD(s}b+xc)aGrO;Kkb_2 zSbLcAyJBQ^ZuY|uMQgWXQyt|MNpF{@O<V}89^oxv*(4t12Y;Dc)ppzJLm^@xq9-;O z+nGV$^@`WPK)Q|XcSG&*)?WE&Q)_VRQ}w<6Vf&HiU#EDP$$tItb?1eXs@#@|=5@E; zM{#S2+Q#9=cR$`W`?U?P*?se;fK#Et&7^KbQF+mHyOxb#UfG^c1Gxdb!S221>-hQ{ zd`|Js=lw5pPxi#7{26}DmuUM+-6j=-B?>8dbI(<G-q#U-haQyfraQ_C6o}(~4(h)o zUJf>0wppZDluW8Y7CM>y9qoFYjW_pZ(s!!wt4j?I-sB$bQ|(<gavo<NCOd}9hcBCg znhM={*J<0TUko1#tiM<u4G-4G&q5FcXnm@ldhTbg*{_bT59c==Hby#*eb4W=o^}$c z<;b_|fZw%f14Pi}C80L;=%G?9p~_(*{1Y;+`|6;_AMUjPZ;=N+*EX6kQz1yK>O(&; z0zQ*B<f7S{=KKU3O+Yo)pdJW<$hv!c<fCJ_WX3EK|Fp9}arI65U`K#wKY|O-B@)cf zVWu(#4*D$s(a)k*JrD3tO-ODTHo!M@|Bn{Fun1z`U##DOE4+iGmNOL8XNrF}w3IUW z#XF{jwNlk|(Ug<rF|oI0Ffz3_He>Lxb$F+Sg5vYwd4IJvb1@?Eu(h#s=JDVM{fC0* z{rz7uBZ%ZbBrewcAWb<%5>b06GZJ<NHU=h;00IdK37?axIgc_}{J+`XzxY9xE-nr{ zjEwH??hNj%4E9bIjLh8J+>A^tj4Ukl?-caTo^~!q9`tt3WdBvj|6LB)%-O`r%E86T z-j3v7xkkqJt}gr_(7%fQ*Y#iRH1n|f-!<7e|97|EJIMGihmo0qiShr7&Be<6|A*~g z&VRA}r(ge79pAsgcoeNX%xtv4R<>q#&hJeVU}oar;`>iM|3}vUZt4GE)%+i<%<TUU z*8h?9KUn{@g-5~3%IsZC|AZmH%*XhDr2RKNALBns{SV3gms<Xl`mPrN1U|<9rDFjE zBD=6cC@3K)DX_4r2lPq1l})ae7v=40>{G{iG<6cFqNHBkigsaLZC>v*j9DKx4|j0X z5FG`bgos3t5{?NTwM)_*V2Tc8O6a=f>h>@<Y&!k9rnWXeuc!A#Emc*yqF%9(BdQRr zyn2^=x9>UWJ~{7R%|N5PdPcE9rsub!1v&RQ;5*<y@Qpusez-0O{)hr%WyL5^gd>Xo zc!UWpCWNL4{O^Yw13;hD_y3)U0tkZ&%O`iZYjdKn0Oi9`1EK=nA17|W=Wat(xG?y9 zNf`HXFcVRK>abmleLSriEHCp}++bKVzck<ITAkIR%i6-vt=;9vy2F71>uOs~eDSz# zW5|j}PTAyZ!|UnvfRXP&nEO+m->SsZDiH)5!u$R2XefN2u(4wL6r6{#^&pSaXgSAm zY_=IgHr4}A)OTU5e+^%h20ojw8Hk5T&F=iQGh05Ej;^2QlA$|MvRiiM9#P2Q=h0Aj zTYkE|zma;b)AYaPxuq`HS*!cGY;jq&HhI#*KM=j}GWPQ9>9}(6Qvx5t{|i!mtKY`N zh_1e!=y2KdYj)~-9BkOoX9u$}11pY&jf?x|$m^ha>W|#N>Iva+0L?ea#4r^!nzcz? zK$=!8Noj-4zk=f_7pnG;v(_sbi$#3Qwoip97|EG!nzkQr+2r|G{D9!2gF%3Jkk}v1 za?!3jFm%HcJ+Eg91yUuJu8iCTGeUK`|8H%2a=2cgkACrE`~LINYTw{EdBfNp#iZ#U z_TFUS&hQ5v+wVx=>OdC*T?Vp^y1rIj8~sv@T}JYa*$ecVA*5!$?Ak|PNx5soq&vNM z9P5~5G_Ail2?D*iAH=E6G<AXI7P-zaLb5pCG-%<F(Ze7VYFsT5u}M%`#9$qxhEHT& zVi;Kh+n$9zZ(dI47D@L5MM{T$bjqrWc%`(xUBr#<`@nI-{x>)ty_Vqb7wrbDxtmZ? z-9Sk&@i*Fhmll`Qeerh(;hvk*gU7>4n*+pC#KisXL;~4^+uh1BZ?D20X+aUa_#k15 zy!jNLhF5aq;{~F%yItKJU-S5hwKD&mwfJ^y?-#b4It%Mde0=SmsOWyHAC7o$Cmtp{ zj>hq?v;?-yyP}EqNIwFdHI2<`9%=+iFcjeL(MXiEVnvc=-^Ll~jLq!=b&YIWP!bg% z9&&GxW4DfSsR&r5vbJ*I4ib?D9g`UCyP{KiQp#S}UU4RP`NLaEzuq*|8(Mh@$m^0; z%^C7>@Q0<}eBMuU*t389Dfw#NfxnK;C~`I;<pi5~M)y%@oyjSv&4*CtIfL?EuQ-03 z)YXQlv$cs}DG(~H=L1V~>HYMz2i(T<F`@?wZr?^~b1|`e^hchS?eIwM*P%@z&^@nr z;2p~44h0&U=CvEaL0ot}-Zhb6ZP~{}&ReMH4yZx<>BE7@pioKy+zPk{a@$Md1HB7% zOLL-*eii|R_yaP#IWLue6FD$9BH$odK>(gm(EGENUwVWszBFF-@EH+sfNC+N&iT|& z7BD0)A3}X-)s@FHyD#B%bOtW2)+*dUl7=6>2I=3JhJ%>Uvj)4y*Z`Qwg1uO}SfWQ6 zk_!X-hma&1Vt7^E8ET>(E<tz*ToZzdic(tEuw!IIJ2`YkG&u>m>OKo)8)`%Uk{FU3 z5^wQrDiuaXh*=^QuOR&gG0cW>g$ew`d{p-1kng2TYusoC+Ji1_H2S-9`y}<vn?3|S zlz$C|woj{8%JDPBycEfOeT3eUCZQtNhYX2dZ~gBDCSErU3Oatlb0v(T(4t26LLH)z za4pAg9g<?UKaTng#E)=k5cRmnr1(be%7|-UX$o|m5Rgy_3kp?G15$YYW9-~$0C|wt zo3a9o!FV!SUVKvN59&7Pdj+SfCoOD+rOd8^&TANk6fu9P7Pe|c_Qz^PTT1Z@QtTs& z&%0qJ2$TX8l|B@g%<%HA?VCTw@;0MLm>WmD^nO~uo#xp1sei-6003xw&yk0VM1_O2 z)nD*N<KJ_0Qtj_g3-Tii9)sH!Kx$@rrbo9pWtbWcNgon5vC2wFsVMpr@~F?zJ-HyD z_T<?Qzb{#q+vp}oSoU<}zhYx4+#9=je7-_VfP2)UK^Bnh9X;G!D$tU3Rp{xx)}*p} zlAL21VU_jV)1JcOEBOvhs!bkQ*9K8a7aJ~2wi?9VDYI7=xk0|oclz2b2~A;JE%<@c zUaxCS!eFO8i#0{w3DqJJdDQb@Bwp!hpxW_QU4W1hf<^acrj+KHnwoQQpS=Nkw4+n> z5(~q`4$j7?uC!LKBi)Y4(u&(&n4C^wqBFkU$%`2of?$o@l=k|=_4eGsf0hYyT0maB z;49b7)hHvG3=jAgFj2p_|2f<@S@bz01`Z)i>iKMKXBW*P-iexRlMV+=(vqaeq92Zx zdhDP;8r#7m0m4N2nE6GwGJ9va3ax`Kv2;m(ae(x4jfk+Hy2M80!Z=s5l;z%dkLqCZ z-Vmn+GEvc%)+2JgT1x77+F}M!won<XH?WbeY|Zmx>4z5Q!j4%Lg<n~0XC6bI=;=M2 zl?;*{gkS|Qrp|VdvnTp6Svm+rjE%_d&Y6-8xw?E}PO;LUYK}LZ?xp$aOeWt5%N!jO z`oVNeIZ8sFgOxjyvGWzxg5_JwnNrUK6EAyMw!sVPN5T8*O~hg*<3tXpFX`vTk;F=y zCB69(Q!NT}vXRQv(})M8^0f-~Kl#v*^48fcN^>sPRbo2L7<c9Z&0daR{%cVVq!;b_ z4!!zqZZRH5Dmd|xd3vRZyJ6)tK{)Y3O%;65_n6+w5%c$Q)sJGeOy`aFl$x+E0ixMN zP@r@6N(bM^2Oq-M^mF(D34WNJ#W_&P?>4g-JMec7xN0|1OQ*3jA8ILOh<<?dlgL@^ zy-mw=hNSUZGe)|_wA8>O$3oo>fn0=O7?v{U40BLR0e9VJ1wL>g6O~a<-}R;l>I3}) zHIE{g1v_sh6)J{`BD?RHdjfwDF?30{^H;#wrPlStgx(Vpw{El>wPMJ_5{=I_@vHS5 z;VV5Gkso0}$%kU65Esx7z-zjKG9M08(gT|xRCwnTOk7kUMGOct-GGm($DT2=Ftxb< z+JrnX4QlXmvkOC*HV&n|<i8+DLJXV@E;MEps94TV<e7&zkfo}B|4K9g1&7LS*J3#D zFC?a`!!l3HM-<&Aopu3~+OU9L-Gbf0xM0^Ld1V+;0CWIk*KkVhmr5S3D)U~lbbBKL z*9I6RGS$aHms~>dIoYPm77sa2dhv5|SF~WJZI7d*ip;B#IykBNOvI0<#^zW34lFM` z>+EqA>on2>rrK$aN(fC%!d6*aVX4P$X?(lChqbvM6TDNr9%f%8#|!3c8sa=Z(MuJ6 z(&EVKL!z~k{wgy5ob#(=Wi4>4K!5<zyq4kV@|5b0@iS$(=E58NuqG-!3UQZ#77W2! zJZ4p;_fx8j5M^0-#TZB|mDqKGOukC4#p5RGo-Z%@`X|me>SHQ$fa|1$&{6R-aI{%| zU1Y4z>}4QU$o|Ve)Rw>m=OOU;r)a7|rHsQCVR0=_Ua?^3(bdiFWX&`youHTNaCZB~ z03K#W+zk8+We14qsBEbL0Tok<co7hfz7l3-3Uihr5cY>lj{VtM<{=F{tMG|zV&=rQ zVxFxM>G{Te&_P*8wnZR@)|{cM-Saj2^KdRb=ZlUsZQo?>LPq)6-q0Evojjux<(xGp zeW`cpFv&y2syMluR)dx#tt{)V{K%I+hPpYqg6;mJRp;M3{JsoZ<1Xdnv>Ve-563<; zp%0OcZ1Uk3)8TK}3s`A8C8c#Zf7;>>TcqaN-tcq8%_*?a#b;s)d&=NjCW@&=X!(Bb zGF&NX0!@a(X+QDnQ30+xKAbo3ta$vOSdA{OOS_-1{tu?D6zaO(3MUSehX}OO0H@YU z^$QbBOo5iRzC81^wq>ceKS0&+r~PiziL$j9P71#;xvSC^<y1g-8GRE9h9NN#J^iTc z>ck3incnD~sBIwhD3MpNw#Ce*(v0QUq=Bn8dO8=Wvtz43wx@fzSm%t=z~6K50VbD^ zonivXd(S73#&Px#68EM0lJ$}^h#{Oa{M{s#JfoJa2wE6|53vs%C1&yH48NtSa+^TI zTnEZ*mw1Jy6V~-H#-fgy0CuBx-D^!AmdMVR-T3Jgz2M)q>U{UN2Pt_Bg_lpA6wVt^ zKT%TCrO*m<#v|D+jITe7(aGg6CMZq+={F}MiB8<3vX<VNgGgQ}TlEbT$Qmhn+Ko@h z-K=e-fib<?_lMa3VSZ{rrD)f65%CMP%l=p<GF3p@suD?PrG`~p2|@V}R~CxN;#`@5 zMuxmyYxZ4v$!yDxC<9U`k&BSUHGJZDRNhFP6f!4jc9!B8KQZfuB+%>^H#YTJi{9!p zEZz>f!w6&yF%e_ps@r8$>hOI!nVWl$+H~z&7T*!4xOKe#89MfWKY$jRlx3+h85U_! z>PC)zsre}$U*hwR-R)G{7N<yq;|+Y)#|#r#Sjw=(Qw6b&z3XP*bM$pu!KhZq8&;a~ z?9}b6y^&RvS$TO#Qx$_>8u{x*vc(@=7WMo4l2tADhY4Aen*)FOAAi2oFuT;xBBi1T zVhGw%xrW2AUq@F+3}mDB@nv;c*_f7m#%0VUFk7H#=}fA7E$Oh#)q<z-Eq#~Kv5=w4 zZ>T8qYNW#OumD8t0MYsnv<O6v$gvChRYge02w%p3Q2@^(im&4&K--D!xE!~IxYjSx z5FJeSIOVUV6rN6#Ijs5xtk*WXw2QcHYI?SqROI}JlrvILJ0;x`XoZ%%p$!R2*_@FU z{1b*)XNY8`lQ$~LfWh&Z+Z<|rxIp|44x2b9`Waq$#;vG$O#E1FQXiU3M>Z;))I_+e zKk_Qd5yiCFF0`p~JtLC|{8HKH-H#B|*_o6tx2w%DRqNiCxVeL;olo{kQ}@}Hynjc_ z8Tf(cml%t811rWtQ^kAg%}lQ0E|a5NG079!+wN62_O&D==W+z8>0R9y-w2N}Ohagq zvvOK<*#Zbww+4{?ny2?YV{Q~@ic9&vEHV9_=M7PbAWr|<m-{&~L4*<{gD^+)&p_44 z19NhPjPa|nW9G!kY&W`~rlz6W?(#4)>kV||o@EavcS}6e_qF00uMa95FVB`N3Q3P| z8Ljv1k{6K^7e9E|?c|W|G|X_r)3(yp*Rm$Mx{J)jD1Ttr3t8=V1!Ro&qqpu|H4`Yg zh&5EHv<gfZl4RyPL-5Uzk{}dz)$A^@HV{AXu(4y<3<}TEOQE4Zw7s);9UHN7?KTGg zrS)u*vpe2p)!w?(gy#Xd*}g5Wqm&P&1fRg!anITWzNO^o;E=*AMrkRm<INBwnS~E} z|G5wG-o}$FJeV>s>H=L&bc~`s0uaV`pg_XxuaU8?&j9ffghoq9thCXiI%cQe(x%Ct z$sZ2d$Duk6DhTfHzv#Ht9#hdD8PYsTu(4(v3cFh6j_Q7}mCQ1}PuceoxlWN7^}@|G z-uJEErTLu+n@&SR8Y3oN{k}ss#DcTQ04gqntY-UspMK27EqB+~TW8C?$_C?4gqVs( z1h_nJ(TT-588GaU0KdkVo)IB`(#dv3k6(qDSuhESA#$gCqsM2kTNTgr>A!}|MPk%a z&em0unna46$PSpi;^=xPpe9Sn2IodE!U<yxuk;nc%L-<e8krEA=Z$4p>H3Eew~V)l zi*is<eX#O$<e?pC2Ms%yU?n$TG1_*-QgtAr&@Rt5O}Lir^m<Iap_)MaLoTxgMfH}H zPIM4R8XN_W{GK|~)5m}CBQ!H->}aaRIw!XewXU5=6UghJtV9I(4&L79d<V}9J~r6K z*}9W^NJdbspp{LNS{1wb_U+AFyhoIGXJlzmKJ_H0!YEi^GjSYQj_%E9HuaIAi(J~D z2>m+pYUYmulOI;7{BwjDegJZWKuNEdtYlYrIHgTZHP$;`*`(SYA}r~?CQdO~g~(Ca zvUYpVpx!yfPH>fJft{!(`*(+XYl1@isFhp!r1!sYMKy)UXUUOzr4l$2Gty((S2~HD z6=vyb=-U9%Kt}d93)5RwVSnITv5cuaw5Wj6rRM!4wS$vChMP4`ZcOA|r_EGNN!S_Z zWslW6CK?<Ze;?o$V#hIv40sUox?0cb98a4<JOqoHyIEXN?u_Gjb#L?@k!Cp=H!Uxr zi}l}-sNT8-C61O1V5Frrg$XO<aA1pkX%B*gO`U96X-~BgzrSL@Lf5@Zq#r5Cw0!H) z&W7^*ZuMY&Ec!yF=g#ATS-ebq+%tr(_6(0|BO+&{f%`zI*k2b$7or_KcLbnQ+s{0m zx*HqHk7-B_R`$8UkVfD(t@v`_KE(gy?!=KiBIe8U688)^o70;u@`(69c$NV8TMkNY z1<THL0^$x^md4ovu_fP>&pu2LkkZE6LX%$`(&kHCc2zM^mxP=wWepsvT{4bf7IHrc z`}%^9)y}HHBgNfm&HWHtO|n?7b1jPq(L&Bzx{zUBL}Olh(TSc9*&ed^{4OR<gE7Nc zOP8P@<l`q!iAq_4Nxc-}Jyg~Yg*gGD7Choa6ce!^FUsu;;^Ee70rIyKxX7mPR@0a< zS;Mf#8`$%PqT}s&rRl+TAn}IC@l$7fkozmm9qMYh$lH0AW{*~^OI%`7!im_#TI5j+ zNC;SLr*qh#B{MQ&+(9UCT+}X6k$%@4rW&D-&~!jMu{XzfT%OPsjQlY%d$@#z1sT1< z)Cs*Jb{glpk*{4&C&{EPrM~VZse4c2T4mKdQwDe6e7d<h%Z+C?Vc{=a=7%|OheISR z|HI2!#X*YW=b%-(wdC|SHg2iz;>iq*_S`6O(dvH#7XwYxTxt18*|ZhYN<rXlRmlSb zI(kfXsJ3z3(z<vl1$HJWqjlBogrUr#j{ECp8h!dQlNGLhP^*sVg+8B!6r_)g!R@R1 zS<7tA>)6XUbqcsGF^&Ycc94tAG$ynrBQhzhdF$4QPJX(BD3!I%YQjZ%_$NARJ8dD8 zK>*|Q9@0Z}EH6^rDXQN3g6~%;h|8}e_v|<LsuBDX&w#jULE*;m^Ox#3?76lpZx8qL zO1Nhpu}LF%$ap~N1Rg8h)vM|+i-KtrBtYrJF#o47rujxkggP)!gmTF#v9dAw?UlLn zL(w-WE>#bDBG$IFPAtwy(=w^_55_s9aY}bR#PW0e`XTn53yom@OtMQvr)7=eD0lDk zo%IV74`~+aQzG-$h4{2aj$J-nA@e&JAOe>&vkNz$UfW0EB$4Xx%r3m7A&-R3Xw%MO zh6|(@J?LF~Ly&q}W*%gGz&Dp|k=0^ff|B}k*i+YG9{$9m++zMJUFoOQiLa~LAo5A_ z?-XcuooT4Q&M9VFXo?aXTjSzB#HJ+QiAkB**?c17lo(5?V((P;$PdVBUiA&y+O~Bz zFChZxk_+5DPzI3a=CqkTRgvo{ZQ|(V2tPG2Zb5Ro`V8KPscCrvlK+Ocv`S!H`1|$J zFqZ|JIL6wD4ds#goa}<mHHIKO|EyLHd+`lwBRn@NrwO^|!kGbUl2FTp{NzBSFO@7^ zi<WLO_D=C99cakh#!wT+j(v%YJHZum@eER;D?R%Y$&EwgY^O<b5u9q%*2E5Pb0$mt z4L`+2OuVtb3jd5KQL(S{hjqTMoC+!;LxGMp9YlFIE`HYpTUuo^!qFi_Sb=(>U5IEx zoDa!X8|~h?C2HB+<@LGu><kHK2W;m8cx&TSht4t&U;y=amaPMQ<f5a!YO%w!#RyHG zLPTuz%9tbZ>U5lv37=LYI2%8Yb+*NG+;f0WMx5C;v7bxkcGXb~&Mamlw!<aaC6lMF z%EAdJ-kXQn=>U(V%0IR=D)_=7tMkU-Ig|O94IAZQCcxsL-C4+x$00b}a2wDs{!K#6 zkQ=CJuwUWpUHA0)LqN19NjDx2v5*%D;gjUAJ~hl~o9I!kLduQU2e<pNxh+@q_SEf! zbFrDf4=~h2v>YwmwRaTGIhmO~4!1Z}C@v;8UPz(Hdqa5HLMn1t%2sK^PajU5_7dxr zBWdS`x-nL!;BZsI)_7jr=+M1Xfo^mFYsvt-tAo7THKZ%5@kCn*vu{noo$BbFFk)hf z*v1sWPCH_aY|-G9A*wAmElJ2TwlU>f%#Km*;1ai}+hl_6j54Ci_!+K@v&>M%q^Ei3 z3Uw_u!<~8}KVlt)uak>HJU_u9tBQ?Y=RLkEgNG6uTU^oLM$jE`$01Jg4X-ti9N(4| z533SA;cxSZJln9p%_e9GJk-0kQFuELy+`I-jt;Q1xXjQ*esOhw;!O)8<E{)`mQOq_ z8oPT&EMI!tWAm$8jul1@M%@V+KR-t56(YubccLGXWBcZ081W2}+Lw{r1=77slesd? z-fP^2)2TveaIYqkp$hIqW79A5sjf<Y%s|4}fP-+sXQMykoEyb0G#r4fFoza&d+dkS zo88Fa8R6ymsO6_LWTWD4ZHC!lFN5YhXkDPzbO|Q>#>oX8<(WbTyU*d?;lRGWxhEw{ zGXwSS%sV{sFCgxizx84ZN$HY<xbn`%MxQyo&kEnV=~LFu!A6r9bDb~8aVgb_+h)I* zK5|4ak$LoOqQ}XjM0G`zUK9~S+aL;$Lj7K{pHlCVT&p8OKe2=}+BJ!^<E1PeaD2Pu zH#xW<ZP**FLs0yDQy}sidXnBD%LAc%8P5cDWi-&O&vxLC0D4Q_du*i3jkM+~ydm9# z_4Wz$Lk2GOuk>UauyFB9ZOTDqN5_!5C3+JnD{uWyyyU(qJ>(fBU1cbb?WCwlf?1Fy zUg)zsVnLeS;b@6@7N@#a?<VGYuE=)H<<QG%{#e+}Pk>kocSiK(5{+FbrxhmmjHPaC zVygqe54*7QzXmWzUnwd}C)rICv3jZwW<!r*@m}g8;Uu5PD8qJjB7Jxpg_rwWI6+^p zeOs@-!qJhXIhm?R?J3S0C6B$1i1QV=Ty$@etrn^kKPCY%KYmM?RcH-vvYY)LLrnVc zsl_&T5U(a(UdRuBZPOmy&Hm|qS=VF*RL%h6DEw>N_tcXGwKk|!+7e+s$HnB@phWIv zJ$sNFbHnts^JfPB5QNzyWgqHaQt{dhRpA9TLctr7;C-BBxQ>rzTW)Twn=^hC8L{x! z#fy(Cu)A?x6Lzq{`Ow7c@T&%TX<j1W4h2^%4z<it3*F<PBNi0y!V!eBqf`cG!vj!0 z&xl}VuRn~m^#h#U&V1_I&5K{|tIbpLyPjjRJNP9*8k`qHm$HYQ@5d2xbG$krpQ4cV z8TIQ<6?q$Rq(X7fmE4hg%LAj5iXxB$KJY*q%4B%M{ELs|pndBDBEvA``}GR^@zZLN zqbDS-IC6S#(+5@bbQKh3XBXiO=j<LE#PRifn!c>w2+w3zM~c@bkyW_yG`=;)&30pR z7w!z@ui^8Vt190~clW9jrnxiW!N<;CSKmF#YLQQ|fcOM)(Z_n{rN;E;Yz+B?b4ynJ zz<RVZw;uE!%%ryT9%=I4A{bR4+yN?+wV?_c5t*+72v$+cvyKZVRs<s?q^k>K@$(1u z^E1MlO~F6w#O8`XHOZ)&iBJPcf{D+Oxt-&h=;$)9rtY7XjK_cMCc1QmuZY(%glD>Q zb||M!dl!k%aL%&A82m!vM%GP`({KtYCD4tnAXSSQT}8a+lOd7|0N(FV`Xv!g=eG&o z-~^v2iUhxuA9=;3U(qIlte+6B&_*OVlLUGVv<m37<_=4M9+_F8dVvA;RE@bmH>xeM zMyp#&aYbNPyw8km{P5JUu&4=$L{lN&82+y%4`IR2ar}FGiNa5%E=aB0a+ai6fv3WT zOEiX@!z(tn2JX{hSLt)R@!)Ze(zN2Ane1XYXAq7N{GGeO*c--nHp1Fb@k1p%yI4o` z@DPlvKa_sV>y0nUY#<6qBiSK7ao^M~j+f>4#v4asyq41P;ys*;-=n6DVr*NoAX>r1 z8~EW=NEOZU?Oi$U;u_rI`9h=K%o!XSU#~&L#y1=Lh2-QoUc}z=A2i~_Q`EJO<y=mk z7~NMa9+Ig1^}}CtT!?O0*4Jvj9%2QCh;QP;=TrF2P|a#XF*v3duv)|zFP0)-d{0pr zGJuawq0HW$WXl2-L@TXlKyo<I1%3`=7b8~*xpkcs>0IaH6>X95IyC3n`jjv?BG)EV zf}N8T9wO%^GP(_6y$4|(>+Tqoy}cC|*W;S-;=1e3$ro<t$-uMp15!9TI2690;rYJ+ z;DZBN*COjBp4IWc-4+J65FBitaj@UE*76NWUl#r-#>4GpWAVMT&Pv{rryd_yRYb(! zJGisUNf37Z=OJ`}14}{ed8hhm#dY3)Xi6=ve|xzbpNW?v^Pd4nBpzJ0aF0zT*z4I< zW#ZL`K`=fsn-8(YjCp{2EW}%Dy;b25$$iP1#A}%P<(8%3eA$|{y@JpM8Utyx6vkyF zTR_M*&4Kl?_MkMaE7MbmRuE4UQ~a^QnMv^z(M*|zgUdkpDgbZfWxUB!g^p0zuAfS- z)9RImhMXi)n{7P(-3Qf2vS}Cpy;v}u7eZjo^VLTnKk=3^oQMQGys_S{R*vP&g5C0A zt%pEloDG9iS@^O7%mk~|t_nnl38aS4Pw140FRxgFu6L*=_3IqaGH%Az;y?zHy=p0- ztXCJ9(xDL!>zjT_dtgO2;o1Q$;kU2`d1f)gGXQ^b)kXBcgbpwmc%e1vI>q}@5C!3i z5n%jmWA>~C&r3dKylHV<a6S<iLS{weL{%(vazy3D_#Mj8x@!{c3cU1b<<ss{p8NB^ zrAG-}kr-0E%zTPc10=pKTxM6(SF>7wAV%U78QiA3olh^Afk1B*>2IF#1MfJvW_ugU zrD5s+p@>F8Xfo*fjomINhv2NY>UMKCxaFI`Y*JBj$=ddnZa@|n8U~3-!fLTqHVMna z=KVan;GOD8-wyoPr*V<nx!l8S;q?waQ+0C@I0F(g)Kn9bBeBx3{>ub7GiR3T=gzeI zB|gEE^8r0O5kXF#ko{>bf?H)U-Ey$aZm=?kIL*FJOtL#Q8N$DzQe%Re;5PNi&{jt; z!vOFgr=YO?`HuY6?U`W&fp$tHC}Vzwm@>#)5=aYa^grv~iW8PVEQBM+1}Ld?&CX6} z3u^Ur(`y)=`rC;ohET!%%*cQY?o`mU>F8LO`q3{f#;|F`u+r@%%SysnT$3W_owPB( znBu9#m(?&e28<oa7BysRrA5|am?=$*+dK{Hk&2}~i#<r6AeI@qugCA!d+);Yc%6}? z?~~|fUXz++rJ3A0L|MdtKX?9?ka!D!C<AqsxA^Dl*?Y`1Fu;~9Ry6_H3)U8n$chh1 z`){Agr_Y^7t?}QV`Rdaa$Xfkznty*vNhMjFgR}Pvg9$?K&Q-##$CQffVpZwV4YOD^ zN3?(M#Poeo6tTU!hCQN($nQSfB+Au(CXOoCo%*w}E+k5#IFnNU&lL|90}PPwd)H;N zlxfksIJJEaXi`S#=mOnc9NR4OCZkj<Vy;t2U^{<7dHJV=OchBv{VWIWp*5i7GhAk! zXgIiL2}^uNvFzQ|2p=9$pFLwPsbi@}kt(`-cMl(F=uhQT>!j%HA}Bpjw)OIekH;w| zT4P4shD#tDr2_i1neUGkNDn5F1~jW3YX8_+Sp|HL(eAA6tZr}0^o#)c$PP&#fQ>|B zm=)X<vLHA{X%FYmX#h;ZFJbX3Ra(lXS5z}1RwprCGM0)Nd|7q7k7RoZ{%QAeld?u0 zb_l2OJPCKj#AO!Gs|Fd?tnm)M2IjDQM*W{=4H41Y61R50wCt<DN2)o{q22MVh7HYV zB1!z?pNN&b??2hqyp-Eg53YM^qc*$rlLq~upGFt9)!?{lu+)v}s)e&bgvLZRup;51 zqP#FyOC4S{w|vPGm-Nuq{PG??^mp`{K50YKhBLDAgO_2I8L}E<emZ`feHNcN5U0;v zxM~?Sn*0z9cS)9<yZxAp?|a9@!cRo%mr3DD?x(vkXhl%aVlD<Dtf=gp6seGS2R9MI zT}i@4{A0HrwZ$XP`^~4T<Kdi_)2rmSY^sGy5u0Mtz&cBIp$J3mUl_^ttkOUe#d#Sq zLld-!EWr9=`OY9^pD129Z&6YC&=6A;F+R-;>t%8kTnlq-0$Dz5i1Y4k1gTf;<k`$B zI)Zk~JRZbC&79j$Pb=>G9%6XY?(`l7jlvFkr@r<RB)6->5Klg4*4*GTg`Wh?<&OA; zcy{{v7?)K->OIAt_kt`fU?orp?5zo#^IS60=&Vac{e-e{a@HkLw_~}eb0`U9ocd#< z4lBYYytOr!;3y4j+G()LY6S+;r$ZsoB!}fY`|#D?+ON$BW+v?kI=b!B94k|LQ(C3l zLpzhzGvAvINZy-{Hq4aHG%x=WfgR@&ilmZSxWYwEd%*a)GpH;tr;wl9>KZdHpLAc6 zaG!Ye5Io?g5mBm(bU8cVj!XWx@!fcT{{U^3Zo5Kvns6fMV|h+mKQ>!D*Q@gh&4wH; zX9sULS_H@{1<aNLs%e?hb5$CM8PdO>v9bKXXAOT3@_YBYAP0VbNj_bFKGuE0&P;Pf zYpS49$-pfJ47S6YsydA0Me54?ej3q_oBnN95PG5|wIxsPb4#d2R>gt`$-x^$j%%X| zy0+Ap?!I&k!Y27t+wE;cibnd-(5F!1`&oql>@%?O8}ll?#{f-Pz39xDw0}ZU(jyYu z>a1qyfL5cZv1%52H^~ZR5uNcy>=?NG-D4Q&N>)>XE=2p{-PPc4AIk1;0DiP6vp}{g z+O$vOI2<^OHL~-V$gmiuo)jAQX21B*qmvM7lmsgQ3_Y7JPrd(vKMaiNs_OhX%Vf~# zA1WnM%UA@ZmdiGmMI`sU2;wbK+)fX$SE;L~fTM0%#LF<dm-{Z4J%&k-X0vxDa;jG= z?f^iJ#aiS&F8IxqD#kL4%HuVMq)2v}(osq8sgX4_A@(nd9Cbb<{Wi8NDE;QcNb(X5 z^7ElGK^b6j^zX5}*gqZRw0<l^Vn*D+P=5D{epdFAN33-=C{G#V_?C9>sseNVTai;6 zfmTVZHfFFF?$lm10$s3Z(I|35T{R>Zxjjw(eMbKd2(U^%+>i#s1g6x09XMox6?8r9 zL4|bN4-aJnVfhkG89FdMM`~!AM1l0lP|GMUuhHLM5D`mH*nXgP{#-GUq?Z&sq@6x~ z2qD+*!RBT#cqRPXhb|cXS9E#v2*)pEHQ{4fvx5D8@<%u<Y!a6fxTbGA0_|?!G$J?R zzJ1ij5hGbbO~}MqvHP&ZP*Th_0xD$piI!3KlQm0JdBRJa$5_`Y4&;qib+SOCDQ`3x zzWv4C2_Mvz_8po{gv+mD$JtqO%gx^SPJt`;!2<#VHq9k|!QFPZK(Y$8D(BKcW1fHC zq=#Lc3hl)n2$_=m&3G)s*0(l|N<LpbTX9jq=1?63&VWq1xQz!D^rPhe3ZQ8FR=pc( zotS_VRyz5#nuy;u)X`%qTD!B^1|(FST}xWU_ESs7ao{O@4vNx&;--5sD<`RVAx!|z z=byIPjs(BleJ$bWA0Fhtq+u~6n}f5&M5xSlye98JMRbH%7I_qY>MYH&s=SYlF=@8J zOKTF_cf}Z<En-}HiqSEzXjRvUBp#NGe16i;KzLkw8JJ4tPC`A#dWR^XS~Ap1x~toQ zg|P_`_TxDj86&o>nRmi0XUG&&dVNG89F}xUovm&yO#XugkOMc630gOn?yTP#lvKei z{kDH^l;->bN#LdZ5rti;bF^@$24SAleKBuXN)&yTDD`wNsGr=XC^E4k34I=SxQokP z4e^ch$YHP*87LAke1t}>JPR%>zdz&=B=y~zZitnLe+Lx#aO7VAZeJG>fF~0me%%G1 z#Nf4?Re~G@^PcPe4<T1hlE9Ys92;{+a>Zp{!atNpmGeFnP=M?X*eN{Ej&3Dw6T2#v zT`U1<nb*>fWy}|Up{{hU6IGH;dX_5I_2@6_`r>!(?d)JVe=SdUvW35BQIsD+0Kd*j z7FU4^S}mf_rp^}ft=6I$PzKrNqy=b9FtZ^OTW8}rSU8#>&F);WT`KU!V6dL0U6uH$ zDrz316wtXYFkRotoX@mWY8AmZZb$g-3!oJRS_07nW7KxMZH$fqBuH=DpF;P5q2p)# zyX0AxTe(&_hv_-ao%ON~8It*V>(A}g=_n4uM8VH|bO}oASo3pbTdcOd@Vs}Wag+N0 zJB?}R3G5kFGR*{*QKj9LDKruWdVrZ2c~LkmWq$?3Y?YRNof}ttyj$Y7AkkGuZ@)2H zk;%tZ1fqWoluL!;p?wRO_{of^NC%M`SD{6V2_+GEeJo}2^C!S6`x1lgz3~ubB6|94 z%^YuNi!E(MeCJ-|+>E^!y2r)y6UxN}Cg%~3NMMM@3Ed|5aq%HlM5fshE@YUv{}6}B zJBaU71_4$`tc-}svIlS#%tXeIIG7!uS;BNWhttu{6kLbwDtT_a;_<{06dQYymd2Br zaI2KwZS#ycjgyQHEegeHJ!W01O6_&N+0j`xlAFu*9Xu7AM&YSqbfw|<ZIzE>%Qcr+ z3?g(cgmO307J1VKA{eOz-zGbT>{|qA$ajf4+49iauCC5YPhtfgkQu@oE{Nu|zG~c0 zRKJpisKMtEtNYsU0@C0{vi{uM$P(D{1T8IDJ#XKNVWwdgP$>4WPq)J%f0_aaEP$VS zSWuqUo7#a{?=pWvWok2GRTT<RMOebvi<j*r=2jP_E&Z;vTkTAsv}>PUwc?;~7xfTq zeOI-$Zpj$el-nm|x0dF6Ocdm~bV0yvJOoL6lnO2-Tgg~1NssFKf|kF_NFihvq~@hz z9~l~;h1biW_>LX4Vb{6uWvCHMH&+#@7_ja)3-p9183iQD+X+b-Bv`BgW?girrSC4@ zbWn{ade;S<wW-@@EAoJC<1+uEA>uM$`UhtP&$H4y<48!%SM1N&4%e@)H$!QXV)I;^ zMWC@3Mzq49kNP|~^p`5zP1)Zf(_C3m4ZY1eJI5pRcUFCX#cL`4=1WM)l|RZkJFC_| z-dpZ6f2uzd?jK@v*s`W$=j<8GO^BJz#Q6B}rS%xK=ITO@_MWinjaTdT<i<YaS!ql3 z_p{cOMX9fQ!S1B(q`iYF6!y7+aBtqr{REhl&%G55i7)VAm-fQcl#j6C%jHVFS0x%P zAWFyyL_)5Z!=9?9qaWUr1JEt%4{?Khe6p5SbZf$B_QWVi|J0o<_QQx4el^rr!KuS+ z{I56(DrEpZ+WagRxSXNrCwJ8HUPdbV?_FeXX7YIJr_zt5%nZvNMxpU*)DLwb8Yd6P zai2B^g7GhkEjHU5>vX$(ur+haf<Cf)*VPi-^d!xfSsrJ;n;sh=fGA5{xyczd!OF;S zX29HRf7A4s76*dU|6|?z56$G}cZ4Ri_N72Yjumw+;y)f7MsqeXFu|{DOK>*w(bz<C zYXrE$qH!j@3Z?%2T0M14?E$aRFKAa(cfBx8xv?J2E~RaJ*g<qNoo@1X>t`+DFZ6?# zU$7Z=4g@8rsW3Kq1Vvv@ys!uh&Y~U*LRXD}i%*l|4jPg4^6JSe?@EfrqB^ztBsY*_ z$rGik040dq5&uM?D|7m{_c}QqZChTA^pdvI!N1|5Wfl`N@Kn@L1up+(lSp2^P{8JS z>Fe9FMX<(4C7<HOlvUY}=jg^{eF}J>ZX=rJ5FM1|%Vc}MC`I$n^6UiSTZ|oG2cyp( zcX}R2N4a5=cx0JpYZN%P8wdF`=i0z~xjdhjP9Qz>*Mm+`+Q6~e#XxsaSF&}%3z>`o zbidlg_}6spt(J{pLb1iyxL5&OYqQNC@@R_%a5ndtH9m$Sc3zUNUrgKaa$~-kA(=yl zZ|$^FwT9?+8XbfmHz-Q=Pk02oEnIwn8s`RLenz<K>;9kDpY-Mwc~NqF9u8fq*#v$~ zD11wJpAgPy`L~u*X2Ho}NX;%a4J{t_DkthtMhhR$s%^!vR<@7h?Y34@JafhvMb)2d z^9wNxmbGu?2s~tX>HZ2I_i?nd%emE|E_wilauAk|GqXg5Jq}QKkCNi;-vc($tkFYN z6K-%@3?%-I&n$r4(%5g+_I{x)0mNmW@<jGAW4Yg+Re;CGTfV34Wr;rt6Osgfle<QB zsgnquPCqQI)gzeE3dt?9tscW%J6$=J{v{Wu62Fi;*V|R!GxoP9ZoA__`?^UNgDOlD zX`7DGsG7wrW@rm%!v&pEu}%?}5oY;z4%f7WM)m$%iV)xVL;XkBjUUM?Z5HQQql9;Z z=z_dQZ7(%2FFV1OcKmTOT5(^jep3ut8J@d$T)W&s+nT!R@=pOMJ_2re<>FSqGH?Q* zJr8E&M;RG;iOX0&?Qq<wyfOKHX4E(r-eS7b==Ax}?JIZji=K%ohvywip)D!`EX%wk zdIlh&NF)5bPIzq`5kbKp>IcqzTzFf$Q(^nl>}{MdAqG!KscNwvEr&P&y?E4<^Wd@{ zSnHZPs>?OxPn;zW3Lv0Ob}Crw_jfxcz>K^O=+B-!>C=(+6oJh^OB^DcBW!c5cn>0@ zKI}-8Rd~Y^n$DlA9ArO4yfrtHuA`T^9~$?j6#7l&FFM4(U$L&Jh!;+V=-y9`CF-PG zi|eEj@XPsH<P0yPGlReE;X|^z9x4wU_SV(foUdRA5O&Efh9_f_!tZXZJVKtOL_zXp z-h>1<)u0+RxFO}v3wMi^svpwYvr>FO8;B|F`FCs!9erVIEtuummRu`m3ic2!1A$jy zcZC#sufqaO?z<T#kwS||f*J`UyuN1CM^C&TXQa=h*(|(q!ASH`?d~Um?KqQ|&sIzH zX3Uc|4#S+Gk|q+Uo-|ebKDlw)9-p?~TRt@QQQ!eL=)=Q>&jDebSl%UhY`Co?dYxt# zt(c(%$dKa3<W3?{JvDp|s#E97My1O8!dgS!iDU85IwJfWJ{xRVK`Xo#`-!AKUJ<b* zu)=BrDZOi;Lp~RjAp38(bZqM{sHn1Iy0NZfYjmPI0>s?~Maq5Y-<Odg2MaKY^N1%X zCBj!jzTWdH9xu32io6p26)a>vI38l8?$4H3hvI2P{pAkN1vZ)Jk6Xeg`-`#Nq@JMh z#4-o@w}p!lYVOYRVESZlN4Y|)RV6a~GE#7J$RHvVk)Mi0Y{M0i7V24lx7uG;k<5iY zB653R0Qk6!YTRmfgd9qIa^Z$1qCICS@$P@PzaTxnhAxw|-lqhO8<S+d@}uf6Q0_8H zqH`_rM`pPbn71U$c4Q0)mwwPZ)B1|)=Y4>G4@1M{eIjQ{_w(}pLNvb(DNn;-FCwwE zAcR@D!l2flBkL_UD1dPuI}>(4y-g*mWN(oK_?=DB+#O)Ef--F*Yv4vaaknaby6$w+ z>Wz|@-BeC4VnvclB!^sk`V6}#T%-i#Kn$b?;N)Yeo~_@C1mn;`=a>Vb7wStT-)g_s z#r){Z1-;Z2iL7v~7W`h+%R;fV<%`i?P84~P1Ge&P`5xQW%sZ^-av)@@g|q96ZHA(4 zCh755wZ9*58YM$z290<7X$faOtethlc8=!sTZbYKogBiz!lKzM4PNqFxSQHGRTAq8 znEMvO*$@N1S17DSJ7HQ0n7wS^H29kxac(TX?YNxx1;b;W&@x4y01qK+{h~t#lZGe) zk4F-k#q_;*@@?VExbmQvwGGmgJcM)abKYGAJiwvhAA{U?1-{3q{w=(=9rfEFs00HQ zSB&-bJA@7b-v~t9=!_h^(7O?}5Lno}FOeCyg50B(E$a_(Art}lqVnSA7Kx-;<VFk5 zRUgf$xIcW^9gKoI?Iq{cu7Je+UqroSP+U#dHH-{oaCdhL?!nzH5Zob1aCdjN;O->B z-3E6Jkl^m_uHTUBe%`NYs`y9u>9c#Uwbzz&x{JMQ|ErD&qfV8_>6p><^S8(-9Nra$ zOkX<?Oi@W_2>i$TSg5391uNHo%{!XJkbGAZKBBU+_^Z}@F=0M>&HDsB`t&O5ZuT?@ zOKvsJo3!3pTwJFT#SEk7V!7bDI!V&8+2HJo-VlbniYb*WItFeug&U=G%eDGv4tDKY zlJQTU7gF+SS(ee(c_|;@=N@j51SOrW&<N?vAS_q~op;#y!{WMh1`Z4y65@PJ!W%Gt zyngww`AHfRP^85E0?n?bsvebL$l1~E2E%<7$nlUIG(D;j&`ubPfA{G~p5jHc;Jffu z%@UeBeWjNOWwc=&Nzb1isA;;FQDBt^fhCE^RDJ<Yw98Y_a2O*6f8AG9kL9i*2wP`; zu`gOgt2^34h=^qOQ(@=ZyFC;$pv`jZG->|7;MzCgM6&9M0Q<yb^}04+z_G2mnVr$Z zZTqx)uxdAkh2L~U*s{X*Z_47}T;I^&H59_GjfIp2N6>R9?E}?h!17#(M9N|5GIK|C zElPj=%CJm#HW+43|D-REG<`}VrjqXbZ<~)EADI|8m6t|`l!muwg;On;>>*cGOUI>b zD19$K{Q-1^s>#NPqs<cooYxx#nrZxgy4o3OQRF12$6$CNZ~Cr5Kbz(uJl(11-A;20 zJCFt1*u*A=W2XBc@TG4vx2KR=qG@tNV(y?g_{_}ksBKF>OD=_}JSUo5O~l40LXwgB zN*)d-ETiA;pRBKfvg@C&FJEV9M>Z;nvQbd2-|*TQ8P88G?IVi{TTI;>GTs$9uuez> z`HS&mPmn+sW8zxVT~&VJd=&R*sB^zdy6RHw{MJtthIvN1iCwgMV+xan)OkS7_c9|J zaj`!T6Zx0D*GZO4-Z#9{os?{k$0?6UF(_N=8hqRzn7iDReAea%&`$LK%=JF4obgJe zOl9(XxwN<c-T5yTrG-MSp+Ig_;;r9<04ISjX4+C!RB}Rm1maL}Glk>De<x)_$2n7p z0ved77VG+f<xvoe@UN!d;IR(ysE@?BLzTTLKfcI8T{MOtfBi#E(YSGerrY_(h|RO& z_1tB-U1ZPK_A6GqbMIKI>(s9Nb0=eENk$fVwHB~>?xkgtn?WGPt%;P>Cz9uYrjFg| ze4<;!A&SdHNbX{DT^Cg%wG$=-zou^-%9|W!yF4iYmRh8<MQ3$Gk$LYCNII23zsk-V zQgDnIEV;V@Ry8a={yZz#ALLS1iN5x&?6(Kx1lSVV@<kMk=^9!i%8~d%89;M3>-(+X zWiN0NeEQ6ucJN=-7G^*)TD8@%0Hp^b=lDDyca+mzM?mRNSg%H>q^$;>&7c~on$`hr z#JsQBj>XLn@@iYatOUf@7lZiZ20vF==H!&TJ@Yta=XtFU7E(e-6C1Enq<u<R<7?Sc zZuWaqHuyKz14}fkFatEGkJqXu!z(n4AXknOk{#GixEMt=X#jwbPJw(|{Hodst@<Tq z;WHB_QdLt<-#RU$T+tn=oiTg`2y{NANWT1ef`Nc8`00oATb)z>RH6+96tg@;h@{L6 zU7KIghi5aQ-pyz9&rTKqEnTR_Uy@&h+SgqztWgbCpV2ub{<=RUpNVo=BQ&o0o10?h z%&LF0=AD^OVD$Nj#t||j^q%jyLY3~4wAu@3|0QQ?o)rwl-oYv)Wgy{xI^D9%<?o7k zK>Y6Q0a^C3^rTC&6yfiVWLs;8wd;mK7KCFkd11zFz7a<%rs3u-ZS6O7r%403XYnt7 z*5454PW3o%Usio~yw2fz1O$Ln^-)cg$UF)&Oq<7Hr86L8;zteeMR?Z%#86SmY3o$< zGZd|UeG|3n*Vo-|jn!dKa(AHv##tcb`ofUWt7jNRObFWmPw{0q-cP`W!?*H5Cr!WW zPa)m+_K9rPee|!B2HY1(-q~%g$X8D67R50owNRC9>x=#C{Z$rYyeK($yen42Io{T{ zx==sgB~CqmfBJyqz|<@j2~5by1$+Oaoe<OxT|d;9EbP~K@#-3W9HhO8?%wQ%z!;?S zqIjTeC#9l!AtB-QSu2{m5ftswTgjfxbGwM?9g|TFc}#K|Rz~ulN;gfnQ+*bw%nw#s zSH6=z&bO;lRtg9sQ49*@`Fw8vUU%yPV|oIzGO+zxKXQEy{~g5q7vMhTd8OwHoU&$3 z5(5-Q8y6^erl-n0tM6ve?c6c|XK=SP;bBK&y~`JHb!DiAZ6lNn@h}ITz5vB64)OI5 zIhI@ebbXcti5am{;Wno^%K8bV-zD0xklgbpuTKtp7dGE$aW?<Rbp|^dK;*Z%1@JX( z{P+R0T09-*LVr^yy|41Wmw^Db$C7KKA9R*H+I|p8S;())uUOkykLS~=d-3Y>3LBoc zIw2vS7~4b6%xGwCi~;e97HEks6AJm|UTAoK7tD^h89bJdyN;c!P-lkI=@jpLL#LOG z+da3DiW2UP%wY3>rP9eNL9V)EtS?5=DljBJ+6-FFaQs70Wk3&5lbrTNOWhND)rK$V z^i`_4@AapnBeKgKUki#rLr7*O?Y<#R`Lu8a-;wZo2rw`HqeIjdLfS#P#KgrnCmV*U zmiYpq6z9l4c9DH&;0QS_i+J#e88nfADMQ>;hT!|e$-n$-zRr&1gpt?dFN%4Temr#{ zkP-=sZ~<%-=n#+xlSOtI8hW2Y5|_z!Pe4(bL2(YAhETjt2*Ng;q8=@ZcIDzMkgM94 zUya5A%0G(``9rbISXudldZ|3x$@muRwbQKd8b^kKGQiU367y1rimOipG*Z=ZN6$ZX z6v3_bZNyzpsYlNlnE^lPX{;{ur6JXZO@8Somw>kc2c<LTO9e-oF>WK?1+Ug;Do=0o zfw*cZZs8JEcOMi~|G~{651dnuvS8coW1Y!OUt}m!dE^GiXY{C=?2z>i$YAC3O7QN@ zCle5F`)eqd2y4N`Hx8C~<I}K#jtzl6GDhd`-mtC;o%3BssW@)l6$V8?#0R<yr}O^@ z5O8t+tauc^mKOYqi%YitE<(G<>jfJqt8C{DhFwkyemFctE&t&>+o?kqhTa|Q*R+(~ z&50q*xAQnYPE0sD8XzR}S52Nzd!ZakrqvcE?)24m+0z}N<zT^G!}UB5!NrA)vX5D4 zt!6JZ9Z%u;I%vLpuJD2$iVp%ZeGQ!cqa=o^J(hjcTzZ?uQWy5!JJXkJvjbFc!z!=N zAP^Qb+DnF}W8d!A+i!w~0HaeGz&tfUE%!yKzt`yuCS`AbLmBB}b-KmE4W#ZEw~M}R zZ3nOqZHCi|TT=R7(D6UOoM-Vu11~Vlg&?SW|L26%g@sEe)FGruz`CpYZ*rd+`J0?Y zFMvsM%>MpaPg0FTz0V~p)ZZK78GXRa%m$X<W<82C7*SP#<q;5z@pNKQJPoB|39mMr zi$YC*>|A}3n_6v+V@u2xiFu;re~tvX0)tXJLf!0vJYLxALxVgFP;&?RPb1f5@3a-{ zgT+v*#g&68*brO`T!l`rmwRb6^C-`$wL^1AtK+7-BH5B*PvhM>@cK0|AnUibyt0EV z@`^9Voz?#^7M$6g>5H5hqGTLu*OXpRp?7+mt~;RRY#6y`X80HC0vHq{a)W~Yj}gva z0LAM=7I?YUIqW|qz&firZ$(uu&AT12e_!6rxeY^^3U}_nPguQZFgk(J1+Qkjy^KbB zcfU*PCmv2BF{>2%czyz6nAfR83A;_aR|(*DPv1sO{J&WM7f=yvzz7mfuQ(DvZDTZ- zUwvnE#Gdc%Ba;$cW6=^RuM&zm1d0N*P!WOtI{37~)h%WC4J}mnY<u{XHv&Bo2zv>7 zEn$cbD1r4fWo;3ZBbiID-sKq(+U(3hM7^|S!vW0eOZGF&DbFE+a`%t3RAT^~^N}fT z;V&5LmtO(7`~e!)4@7Qb?YQ^O*=x6R<l_P4@kKxYj)mfg-5ytBJ!*!Hgg;Po6xW!G znlV0d4nNMQs1|R{RbNbh?n}MEX<$<=ti?(gY6w+pQ?+{L7Yt$Zc?kaI*|?ugy<9h3 zWh?c4N|J0!p}Ff(A2cpxuN=OARUUD_p%?WLI9J}>6L8!<AgBZ9-F%f;r`X?1$uOWS z`z_N*GNnq;UTu_v8cPVv%-^%AEM_J=6x1)@d|{KRbo3>qMDTo<y-5D9%uRjz1f^tx z5m?->H22}NqXiQe7X!XdAVoDj6mG)n3VzSlwFlwocw|{&Rg*WF$?pYV@x?(!Rs2Zg zeNZhI+c+_xt<%5MgM>efke!*DG5s*vgMiBSC`7-P0jdof(yEE0ij`!=0GX^)`<7dy z6nKmX5Kki)A`1|#LaEsCs;(-+J_$m(=m%w5w4Nhi?j}Q)Dw1y(awtdIgwXRrLoxP) zeGL|5eauc$EZY5It$ck!Rt*!4xMDM5#B%Qx&He4|*DOUw$!=VQ)@WCXKBOwpS;rj* zoZNHp^Z%L=pizO0Fyn%|x|4yZnb<aZTo7t8<VL8~N6;ZaPanZ!=88dOb;wGA4kQxu z+1s~=T=KUe8AChhzyOGLQK;g$zrI{Xs~cu!+bw|K;JnQz8izsdn8LrYCqk?v&!Uvd z^l3ckof5Nkijl=MOxc5OFB0b|FsPqq;g#m&i!Y?u*>#umu%`X<{od(EAsP!K`naqI zwfR^1pOp56khAyTf)qJG>iiqF+3sdT$rf%IZg+9{Xqk^aQp_^fUmYol1RsS7Zc->5 zaKf30&~<-p4_%nz#pLV$5w7U!tM|4i6f&mO58TQT$|$9N53{}VbLLlE3U0yP2!oe1 z&5H~)S#yeyD0-Ar@j@-7?^#C703=D$KG%<3BD;MrnVPgrVvt)J=*``vR?gtcr?{6Y zY3P0|^PQ~<3cF41Nj>lTeWqLc6Cc$x6Q&kVxb8sj8Jr_qa=5EQE-DHJbZ}cZn<H)~ zUudzY5VoZ`FAWup$Z9H)NY2r6AM^3TRUU%-blC50%G>rwf#ZkdHR=mFP9=(DMtSsH zf=<u>NEs1usNQbG7*$~J6<xLS;Yk)^E}$4z0r_2acyxPk%QLRhB5}Wxp%HAqM#vHr z3Oz26HRnc?0~9kGDCFi6qFONZ0zb+@WZ#|SvoHlOoLVAsKUH&&FIbv9cy`H>2O+?H zq+~i~<=_EM{$^oe3C`48%d0-YmDTrE9eb3BWBYz@*{=pZ7)Ej7&>B&wm+zr~ZSidK zYPol|_-4wT;4kDKl&oN}afZX)DQtEoR<FMgp8Laa@`3A|0FL=Sae?=w)J+~qD+K}{ zeK1wf(F+ies5Vx@NXi_K&g3pHMi<O1`nWF<zSaW;w+0b-ch);P!a4fgxAk`n=*%01 zs-II5@kAbWrc=F)NHxEnG*Xz2%n-Kq7=W`^QeEB0B?sQjC~EjT3MRQU1EF1GmblUm zDU)jh#mk;w?2Ca0#oj$$UI(@aePUU`(8LeYQB+~Ym(Lf*W)`sB2_E;cJ0_J)BpxA_ z6W3MW*U$xdae8PvwZ5Il#zCK)IO52)?=1PD&Uh>|4~3LeoxU;E&af$HGK6vw-^Bfs zJC^+Y>&32?wQId6RX%>7O((Qisz+iLO<HyZj5Rv4g$%x7@k*5OoYQ*}Aa5E!!EpSR zm0Eden?Tlep$r_W(BSdsIe7X@MFph-V7V1Q)+Z6&2{2wxPnVR?&Y&|aa=@JY3_0&^ z?2Os$GTM^zWMcy~Gw&T_nIZh*=W;`+*pwqK`z<5kSz=RKc8Fu<9mP~p;~Omk>acjJ z{;mV($_=M(Elb<=7zee{STI1xJzujsf44f?4k-H`6M4T>6E%4e=N$~d{Bd!RN-$Xt z<z&~3Sl5PBWO-8o*jq+0=O7d$Z1$_YaXecS2EqJrpXUqY9<}61oUkTg7eI1$hHxa@ zUF?|t%!F%Gpsm6x>f8B)hYjTQ)U9wmJ+OB0Qku|nV4`JZ*gsCq_EPu`v|U^jhQPH= zC<RDI9Ui^d+HpIvBqac#JhAjIuAur%WO}WDg`f9_rm8Hdtz4gw#~|}{0cT+TShcNx zC5n8oMpFs@eRjHTWq=l7nw?*I$IjQAnBvcKg=Yi0UOme9t0EG8S;!ztuhqf0fMwmh zL~YTS7zipK6((J{%C*i=53Zl3;Mt99dm5KGFp2u_f|V#)S9hiCEBaxKg&CN7J}HEs zQ)f4_#m$m*S=%5iw%KhVgIn(_ePUZv^^5VEe1N;VJbVN2KjPDcUBEQW;9mRNH(+)) zc~{~5-6|FT>l$(4Gl+1#P;OuUGQYS11{XiDv;d07^<%5@Wo@tGgekyhX9CN#*xcwX z2YNRmnq2MDTxGiOKluz?Cdm(+f7J;$%$SR#XsAf5SO~L1u{A8aLcY!R3mltG^<Vr3 zka>*`ER_Xdyu$FQc2Qag$~p*eKe7DvKzVq(e3JeJG_-U@!w?IiE&B;|csTaQwn+Ta zF=Xe8rZKp0_%Xol)H}%9Rv6UeSe5WN4D5*|CpWqg|1b1-*F_THAq#0mJ4oNA%UHd$ z(7R6qKWF*<j$I~sVZFuSq}b}S%qxKxfe#W##;rNaRHIrUO6LS9r+7VTu5Pr*D?a6j z_<n7r^V#d+7_q$9(l?Gr0Dx)*C8cwl(;C<=z;u|C2NJB4|G#lRl<ZKFWn$`v7NjQt zjlGn-M`bwT*|WixBLmX6GZ{csW`gfACRLyjx%9Nf^#@~jF}AI0j7#ETK#v>1AW~Um z5J^Fy@DtytZd(5on3Ckm!Jux^yj3oP(5W6&FL7XHQ2wX7M0O#IbzMJm;Fx1d(Bk~e zKS;|^CCU4B^3~h*L~h&fy3~SUISSks5s^0riw-RYFlp{X4x+Y<#E^j4IT@ND*_1Rl zW0jzajVv#3F3~xb!|4otE;cXBuN6ra0HD4XF8+I_E+*kFrVDgM()P*}^zKFWwZUF! znu~`R=7hVc-295X0P%Qqk#u}@@-&tP@(hU9T9<5D5*wIW&d0h5kExy=nb)#&GOO3% z=V71ZXMw2HRh9oYMTrf{mYjB{e3+37y*tdN3YR?XZK_jD?v>ayQd~J%0=<A<98EYK z3i-Z0tqXm(dAEv#{R;0Ow_%5yTPW<;T~z@~DXJI!E&moXnQUqLKalx1qzOC^!jPAI zUV_{`r!8`O<d1!~zG=?-t>e#+wO`Mu^hH?#EC3-KOZ^g1XZZCbrv^#UZWV1{v_j0r zbIg@RvBS_Jn=L{iY|fU^uRAcD|Mx%jB7{Gpl^2Uw-)_52f!@Am?csOp(nk@ZensQs zl(!}ONkyy`S~5be^Vz%rXsF#4))65yhEq~lPU?BG_Sqf|Ooa-Q3Y$I8=vVnJa)$E~ zI~hHcGQ$7QaN?cc!&F_7Kf*ujqLh6Oz1%InOO$aw7Yd2!s8Fy)&$65VKi7z3N~l@6 zUl}yi%+a<9MQI5c423b1+!Qbhwco}~3l$!Yr;=^knHpoxHTMoK1eq&LM2p8a`v2E6 z{67<|CWI;=AvINYhS|<7NAnIFAusN{m^}CJfMt5UpJaK#c|%(biz8g>{tktotoEqU z#0yM|@q#86YVrq9H=K_#;8hMK_lrD+WlYJ=#_8Sy>r*T&pA2tr!1~@i%yO2uW%>Wv z4%mbDqE@4e6v~g(N_>~NRn-bs?F}J$^TJeM%-dZt2$5>cL_#PS`%?|fB7B)43LUw{ z9LyChj<bS>zW-)OSeg;3k~6LlaDdIbb9BeY-k17`Nu<PIsWCg6#r+AriDoI|=l>lb zxG07JDn$&4hN+PxR<SWdvM#a&ckQ|&IcV@oz;Q2Ez4!DMEN;&{2jkflA?x1TLq`^R zI2-2g_stiL4iZIwlzFhw&j}{#ttTCvJ>zB(HJ-n~isd90(=tkz8LoDP@%1UQviQ#! z-fhC(3@;)m892L>Eb8kNHnBMnQ*}P&_nbTReZ~I~JSy}F{f=Owzy-ZK=4ci%LQU|p zr(sAM;tmTl|JMiHV+FC*eEhK~i0h{18I5HEW>7$MJ)-f61%%G*YY*Kw;s1XfWq>YF z)0RwJ+4qMow0m$QdEN8M{Vq<k&m95B+B1CevLDa+rHp^u_Xu(2@H`FaJaiG9j9+{= zQP(cE5i=e9vF1-x7whP!D2PS|Unve54i!F1&S?Ct)d(wl{QQ4c5i<biJuO8QMD8w2 zamV9%|7DEuQ;5zViRRaxIF;uxzrd8FHwfM;zYjx2P|(@ZFap<h;dzN7LBm(CX%fC{ zNjc~c9S=r0vafkKBv}tq3HCjGE^cu^LeBy)O!A>YvX|ClAe4Ol3`oR*{AEEe&a!ee zxRHT<b>w4*i{tl*GxRX`h6Jw)uX5Kd6zcZoYa*mv6etQniclkO-W-jqg{HMJ6!S=e ztM1Dd_7*e<j;O+o5(INONC{FrwCcXNkr2ti_~@^{`5B=22qDP=jXw=|7h%dKo8#m? ze|W=;(|>_bdL-UF9rO!q?S#v}_|S=9_XR0ljBg+?0#$_f5V0ihJUWWp-?+%Z)@Z`L zmVDk^bRX&8TW|$J5wm_8CBg0?>PMza#TG*YPqGFIv0BG|7D!LuCQ-xsp1x*$1XsWI zf=%)^PC{1P2K_<tl^TBa5rTGzoh4lDH^WS?ETHfwSQEtbtmtEgCjq_lbD~J$@Lfu8 zI{hN7Qlo2TulT!4=Z_QU1w`7Wj49;R6sXlRZR$pSN}t{B&&bAJy5C}J4jgm^?(WW? zH|#dLR4Os7=RdsFY=u7K{U8-`jLRD8vP<P#88AuJfMDz(uRcOEltRtGzzcXE=Oj%H z2nJ@j1oDr3>Q*!BprrUv1-c@zc*=bh(jC9sDm8fHTznh!i|v;)=&fru4b~-l*p&fP zP_m|vv?qAPBtXzptV-K+GQIyRD1bP5p4bMZyGn+{d(BmOPdJr}gryc`;M?!C$d;Qt zqCMZ+x%s;rbIr>q<%bo64<oV)rjqo{a><fl-x#mjWqc{|zYN=dC^H=D@8zjE>kMSI zuCS6gvTHK7c7<QlzsL1?+gK}L0%2N?KP7lvmYcwaz{Hee6^SPl^q4X{W?T`F`S-yc zoKrByH||Pv{13AJ`x6l;91N5V4PHM_%}j~VFnIY2c<{R4C+>JYpR7Jx#Gz#>mmG*t zJ=d5^Kzt<nY68n1Nx_$fhz~_8JkAIq<y#0_f%K*1Ts@0^{=XRW9}a*GZUL3Wv7IG? zeWv%Lf9heM%NL}wSCC)G!-C~<`y&i|CvV)V&||8F&z>7CmNynLD~rw8Buf`ECk;jd z#E9I@BY<8HkwWvmB=-NXB|FGJ0X{T}Vsypg0QX?|@OCJI8;xHi=T6RU{Sb$w@KWiO z5nDR!me7YNCq;b`Ym6(9732Fxv<!X=s&RTBlPE+n?!a$jbR5aL_d3e|bH80zsP<>} z)cAe1x%NH|Scjc&28O0au-*A&y8Lfs*uM9jo9joNG1eJL-8lkE#es?bUx*W~C@F)` zpe(S3m>h+8{$l~hY=CI$b@;C-RN}TYHa^D!cTQfmPk<%^f?47U177X7Q!mf=bu**< z^)Ag6dbdAJ|De(h=`nZ^aPGW-q;73JKZ$!K;V4d}NK1~XWw)DIm1mtpC`pT!xr&c| zLVdDC`mlVB)S}rXe$(_(vW2w~)M9US{O>U+k)d44!=N9{rPHj5QRCA3+nRJEj9(V5 zyy`b7UvL~+ySt<EN{lcAEC8mFn!c_TdC`|YuPm5CJ0rzt&P|I*W>&KAcf<UGd#<5O z&3DP(j&;s4lOZgT@i=-op2%qK!z_V$V;1JYyDUjdifs49-k}qc(1jZR7C#mTj9sR( zTx{O%O*X^O4=E_5r{|jI*!)3CKz-yTNlI@~VI7E*ns$(**m^+!j4vl&_-y%x3KOP( z%nu;9f_WeVJai8!_C3=pXDAg6t}S<`vI?<Aww>UxUe0v(IKPP<+X%v}y+Q;3aEjw2 zSgP|QGIxqEhsG+zvfpB%@9T{?S03BD?}0QJ6aL|x3Q&6Hw6w=y&SZVV$6S3dk&;Z5 zoxSV%*-2VOEt=VttOrUAqWC3QUSLpW6&t5z#S-%OyhRE{1+M7G_mK*8bxJpe0aV{1 zXDTmUgg0wlZ_-K17?;wzjP^1T3Bx3`_=bS;acV3+i7eUCiysRfJkOU)X&cNu0ui@z zV8!G}iS=gCFMPn@@yk8^uXP+4^tnOO4J170m8I?DDqJ5^q`dn}_nnz9?=2URU8kbL zu23!BFcuUE=;&spfgy&;seFBw45%L0;ec<+<JIn4C9r8}5Q5LY6G$sDQ*=lQ)y#fc z9R5w2)T2H~5?|CBD^~dOMNv?GZSS_vNv8MOpzj!urjOa%skogVgJ~kh-E#1vqzN3+ zi*+fYWdgLiC6ahndgE9q5Tqu2Q`yV9&b@?$?_wCzTA$$@-wu@$+_pbniU$;R5ECo1 z23z;1pka1mUxDVmbkxyl@@b)X1O&#XmgseI87Io9|9c2CGE~Zo;YsL>jLlNiIF|mq z2V=L8j}ZXn@VThw-QB+-=z+X~#Ed)6VVI8dYbf4V3f`i0FW=)gYuWP3fSSf}I7@EB zpkwPWp0+LD1gEGrs-(me-n}X3teS+yOru2nC(SCX03<R0<SB;jNgg(u*lO=~jVwL? zO^sEE`y=9m-s|45=Eu7?Zv7vhLg|=VM}_SF;HjwFo668ckE-eDESLz<Zdp0KiUadl z7S7r)h<*lD3nviTC>G%V`e!s?T@)2wDEZYi!_6#%kKEzYJUVicRO3V@C}pYfLFJ$l zl9a%=m=yi)8{BTb*d#i5`p{;)OCkv5A3rQi3d``A&>kHNr9rEr$7JBxS^V|kT$DV- zbfi_<;naP3Z(@eWPa&@Lvc9>m?q~C+coq0{SO92;uRbMD$X{LN|1LZ9RyTefDHE>6 z)D=DN)<azDh}F>$lGI@>4ZGtYZ8~959&#bvkd*Afi!qilOk())&@K+7J8mecl}y~0 zn(+Ac!iI?bC<Tt?T)Cj=baC$P<62Tqp~IeKESr8kER8u+*^=2`MjaKsZL(kBDB%qd zNtX2QG$kfABylM?VNPz`Q=!aNLD$tK_%hSeU-;csQrLXIazE{Yl!`Zop|KTmWEK+g zUAFa`<V$r|cgz%E(WJBSNl620o|+1lo`0Y@0)q5O;O{t05;{{muLPD`oUnL<dNuD4 z)}}J#@uB3l^=zIJ)H_qLmZoS^&@&>82exPvrOQXXQJEp6+`V`Dc)5k{pj0eS|M7`L zoB)WW#T-T1EFK#=#ZNEUi!})8+Of*%Jyo@KaCcVJ((OWtlAnryGPG<BYIq*T_a@g@ z*)7{+I&Xp)hI7*_u2e-W#aUTphOb_pviS!nJT7%FNtjR5%GBGV`xu+qCN%Gs@6ZT@ ztCHX$#bEVFbi=WFNPG{T@KHW{Mcq78&h0pooz2Zn<nL|>$b&N&Y*zU3*wXK<Pu|AH zp+=@BhDG=_fwsYH5oG?ZE4fQ-uAlSE)Bn|ftiym^#C#7%N)E+|NB6#)X|+8`V`Z(x z&=gzEkf-<q<K9G;)@g*3!R)8l7)Ivtc5e?4C^`=exB^;0f2Gs++NfH2BQj-!&S#Fg z`zZ4GX|F*CQLg@ow|S>Kfx)>;zy7M$KFO}FpQvmz^vwJU9KV|_Zs&j8$?p#Cna2yV zO*Aye#XtV#jb3?%rMpp}wc?Fj&-vv3H3r_Gkt!HHOfA1`u5)ArH61FJ`;&|{EvMT* zKW+^HRkE|a|LG^pioZK&Bo><eO~~kDU9bf&%BAjV=EY#4Pl#i7($;edf{sefGRB^u z8&vQ5dff;MdXs!Y)a{Mm>*S<h>hDddS?1Z<fp}q!L{T>O`P8{T{Gfx%pj+@P-bd|M z`OW%QDwJFA2h>p^Ev5M#lfN|B0Tu_OGFj~`uah$Q`z;(qRK*;^3Lyy*b><1YtT8!! zCqo;PLVRHlBk<eb>o$iLMPk*gL8;AnAzEU%WZ{lZ>8W_>P}t}{|5J2VLj5^%<er<P zf5f)-i5jN+G9=1?2LYczx1_vYOJpH2pbI`!Y?~4p^V2wlH(pohOv<8G_+7BGte1y; z2T#Ae6Q8DCoE4=sp-PzTr1C6S-=h9|u~~1V?u5zKqD^Bdkd$LYu84T6$G>IX0C()} z#|D9gTD<D$$*rp&P)(oen(jy!Q~9%4<Qp=-8TCesABmIL%l^wIO&LR3w}nN@u9-e- z@`UQ<yl1ULTG=x5%omv+)viDOGdq4pLpSg7XB%9=g9nQ2gjqpWb~(>U5g}pX%bDkD zVKCOTad^~q(KN=)0?$rI){@np<+TBrFMaCWYiV)!vExyQFmcD--?yiX9POuiKoe4j zvba3Cv>v5Mlp9X!BRCq|S&`<svcR^~Qyf8ct>I~T2*0VDW`(!%z^QB|N=RjJK6aWb zH05cKrA*XNMH-7rT#?SQTsyx0i2qT*;=9;SrS|CGJ>=A9`cnFHV)EnihWF-vQHPh3 z^2P269{b^{GAqogn+Tn#ozkzSNMllOg27F`67j14gE|pm;QCxuN7x$X6?1*4;W+Ox zF`&Na0yUhR$hJphvL={X-@WCIzkuRm==384FY6d%=U&V3aOvkB_ie>#bh-iygQ#JO zRMH_--QLXo!Aoeeh)JhSjpqo;YmcJOo9J(~l~*3xy9^}+S4;&%d4On-*LJt+&)O<3 zhE#Ex_hV$iiuv1BS{H+^Bl3$Qaz%}*Ul<~Yvp=RYW(x%UUgn3j)tB5YmYay$7=?2v zs?q!$-33XX8*Jcsj}^uuNMP9aT?<@4`JTMMAtMc1kHCwR+*e<!IU{$kFFO(@jWn&G zChqMi5Rf%^-}p!PQ1z|mBI_@w!%2IkRx&#w2ougXR~;l|Cbg$3h#^%aVBudrC@R2J zWhBA!X0O-?f#w2%PVb7Z8Z9^uee&B(G#tK5OU9)njOJ}%9*bBBSn&lJh18}qM>IT7 zH;2Y|wrc46;X_xnF^`WIc-5nL<*dSNkmZ^pXoBYB{zybz@<tKs2HdFq%XFAZ2^aZ7 zD!F$j)lU=5eWu~#$ap&u?z%o!!bpkL^PO~JOKQSz$~a^^h(PZ7wsM8}ZTTX+#)Xxf zX$g0+K-Tki`9#Auvc5X|^XLXyDA>^WNBr(ZflKJa1*qe-mwR%?xe-AdFq0rJIzt^1 zjF)tKhUIx6`h)y66rq(Ai>YGPp!H;5dPDGKZ3v{3US52!z+cYGK2+(8UOGeO^bPXZ zcD8`_l5Z_dWY%-yMejKxa2TZqkXIV&pF6NjQ$!PEaX!Mr;i=gNck+#**{k?t&FEJM zMTnR6X+JLory|hY^+(E3P<dK8G~8HSy!<)ClvxH%SkyjTAB>ob&QItSXA4$NeK#}W z?BnH<>{h%_J5HOCo?4RRW@anSm9n|>hJP_8(rKL6nP`abKd0!d7C<r4D){6;%NKT+ zzNC=<^Wv(&?O(;jyd$89^RDL0Sx3}*XPdu<T{X;$5{72h9?wFr`G5=q-QMl~a!h^B zZaT<3?$-r@t&aj~W(rd0Y#|?LXH)N>Lt*W)W-c+#{e4#W<hF0SS0n#zI^h;CfqqVZ zPTR}U`NbvKYl@fcOp`-P)r!&b9+zNd3Mi!zgmYw&)9+OCy1h7H^wM^=;6yO-n80$I zBhYlw+}pRBbbi|sGrC$g#}y5V6&MI@nsan+n|Ci4y6ANh<f2wu7TMe#_av3tDE(#u z*Qpb+l25zgK8|!j;KP{fF4+|ngqN5X!$7D>EKBL=%;%(JJLDt_LFb~o=_w;4gx;Ao z;IeV8H%aM9=7X?&vHK`9&~LtZq-EZ_Sa`G1;TncXD9&gKi{e*-HgiT2=w=&G*MhuJ zpMRoqNs@7qcU!DhpFPgjpHcw+3IS+nfxM0y<C;K0#RmDml)P{OS(nc`e?M>8+n{cQ z!B7h^eXz7s*}GroLJ7F>HvWag@Y>v#kv`%R>arkxJf){LC*X%y>{e-YH2#~~3(e`f z`K*j`i{i#GL+(-=vwbwx&(OTYzi_PC20inC7~Og8u|g8mRPN&`dsMrrIXiKnmtC0{ z^`Z?L(UD65-yt#vks1G{Fe8Q%zh81G3R0VF>lYPmq_sQ8n(y5^zd7-0X|?|g${ENF zEmirIY9@~xl$pfFbOVg5b`tDA9c{NfEv}{(@^2m2Yb^~H#}4GCv4L1w;Zfjnh5F4Y zD@5UO%y6dI)k7DL<qLO=V#KYyq`Ka<$1WyuQvP+lj0_1<>nMu89Tr<Y-8NJ###%5x z1!MEYP&QQ%I*2!pd+V@P$7G1$OD<oiRKad+2xcs-<r{Oo^yXmNy`PaSoG<mFu9|;3 z4LfcJJG_CvAc%MjW!$Kf8Tzl?jC6ewW4Z}0l|L-<zvK+Ky{r`LqYR$-WSmsO-K3&J z1qy+DHr#^G7ZJH~U^yD3+<EZOu*Y$$<Qe^9!iVMZj4RXu8GeMU<Yqp>-SVle8}w3N z_8F+MiTvoeJy&X;A+w)GY*^{Kb2!(IoTM_V;&+tT130MXF=XuAFn_&96mkOVPZMuG zQ}gq3+?Z3u_wDy2^-qNSS0`ZzE>S$GlTTlM7)Gomz75mpKTesp;sxJ0aOW<7(ZiT@ zL+La<aNa7y&B82n^ePJvhJ+xq<G_-?sNodiLpplu@+d+Pk3&M&aJ>z_&1$=j1`g*5 zAD>`YSF}l<Z@md7xDVq^$jgqHLMEfc1LWJc;b4G=hnH}dt)+FRx8icWA~4g77=+FG zA@A?$N6~6+GfvXi4U~Az-%tzy1~Sw!*)I9QzaOQcXBP4Ha}G`qD-TZ(Pg`qiYcB=q zC!3Yx&MDk;CXcUJ?ykq8dntOrX<oLK@#W*Xv-|WXf;iCH&ZYhYrA;Nwt5DGwar40r z_Lte|8RHP$?nDK;RHo65piJx%(eIVlkk>W!SdeI_0Yr*j53hy|y!2<!xl|{`cEK}U z$LF5EJjqF+{=$jF5SyrZp3@5{8Gl8B@8l5w%X2G~omS1!mwktL*^Cn^hilqK!tUbt z)wBw0MMP25ACdrWVge^rOOwL=7Mljg=6Q>ifvKB2yg351-J5Bo_C{zSE+S{6X%wfT zxb6|1jV@dWcEU~@UcOZH`69~-im3%guBL$k3cNgDDuhinN;(>@EHaK7DkR$c6yToW z&U5gfI-K?=raSL-Kf`AKmfXBAKdcI@9f5P^4q4^y6!+xKRBww&x!oN(wT@X*g&YYU zQoTt}@3(+&$O@p4{(_aq^Tw#oXtTv<{#4!omSCFrResy3@KihtF~Ps+^f=&;%1LZi zn8}QCAY{sx{0>DtkolAV_-X#55WFYyYA0a1D@;hXs>xq*a3loDd@0*d6c{+0FCFRG z<IPXp#=&bjqe+>r&kqmsvgjEP3#^1us2gl+%f>Al8a4cxtfxD3%9;-WncC-F$euen z|D5e1*Hp9&5z`~u{W%>Idu`tVs=B3cLHmigV>|qAH(6Z2?5{e-CGnR&XQ`6j2|Ye@ zxzrTvdxqZM{{EC$_q1l8Xu#VN16J2i3e}0x7k&#D9s??WXn{}}SohIXN!U|7M<Tbw zhB~8u+~5@3W-RbqO~!k^&qrF&_JmLXyUTI=2^js3s^g_QVRm~u#$&*0mt&k3+MJ?( zM(}>`9|qibRyU^!y+phbO)I-7EGG#94-<gT^}78ppyGDOaIz%}p_lM}vbj#e^r27* znzgs*ath4?0c<x0qTqoZKwKE$N(lK1%2QpRRv5c|BbXojhyV{h%NqrMVm?_+Sg!FD zXH>s2;OiA*czd1;yJafNv@3c~TtPLoXXyuWJHgx_oT}jtmvvz+Po{*S%q!H;jIz&a zY;Wn4=GpT)S=#jnlO^ka<#diJ)kj74zq)?4o?~y*WoH8Uf9*c{XbqY<flSbF?cVja zFZ9PyE^MjZTHiG-RFe<}i0AnN-67rY1b4^r2iosdZ&bOG#Q~d&d7t+^h%t@yw;A(L zR&|-ot#d$~EOxmHiY;i3{F77l-aVs*eyax^f=2`VxxDVr^UgYS+uoi`O7LvB9~6IW zUW(!i_8yDRA`PvR#zZ(_q?s`9WH|6@Qn07hfa|!=BGY>SV^iyW25C%jeEECqF2heK zQ@<L`gtC>etx1>cY!-BMk_sKs-Y@7Uvft6&oezYMB3BW*A^>s2QMmi5rtc#9SrQ?{ z5`?9ymVsq$(37jh2bMIC^TDH5yuv0Zk6S)Qlf+wHNU<F!@HDP*>Y+1LEcegNXQ?kG zv<QG)z7cN3Y1;Ws#J*J;jBaUNZ>HcJP`*aBBq99r^v$}o?wUc|o{!JSt={3yMal$~ z<810l1IXztjA~JkQ=3Fu4IaF+c~t*%2E2oLHEk@cfC`%RoSLko?8V_KNgcrzSx6`* znEV0i<;evNlmfetnJ(mU&}^Y(*NS(y3&u5uz58{8E!RIo*b>5cqIWW!YFrr1&&i1q znfG`X1AZ{5rVvePqft25fiwL?7B0}7w5Ut4B!t&03dc55s!YG?a{L1Z+@V4dU-dWV zPUfmR9d%}tvMT=_*Z^5|aC#nZ1pT8mL%2WiPq=W47!hdMzDuDF9nJcASfxy_Z(rxM zj`xn5TCN1QP|8k&dMkMCh=QWhvPpZY{rA=lroEs+Dh~5HWP4WE)-z*5bu?Nl1`f?i zLJNVDEq=;`SoUo67Y;UP-1;e1LHap3>5?#0D47TwiHwA80%M#j2w2X?Wlw^FF8U%M zcnj9w{onYmukkpx4D(j^rND$_E=sr^&YlH2gjh_*zeUMfpEGm7ba?B0w}$SP9M)_s z55)lCHjMOkerzeM<vOQZ*K?I%j|pil>)x1L5Sp-bondm&lHCpbxvfpWh@w`gL#kQI zN51riXY17xCPgiLXfC!kcBZfm?$C<bvmAyG=!PI%T{+0aWtseXZ2MnE=%O%aV3!&W z33=B9z#zHiD6G{qtAkKlN3J_zZI1f6>57&|=~#fM!`!ovwRIM0gtlo5Phm%Q+bjwz zwc*Oe*>a#U|NUvKQg1ePQhxAm+zDrM-0QO7fbXIoC<sl0r-Oq6=Mk{mh#S@|^PSf) zNUk)-kKa~-X#YIw@+*t%T~`xwGiG8X5=Vw+Jn_uAN3A{|=XZdi!v_t=(pCPya$q}u z0b~KUcS4edbdQu2G$OkuD3$e&Ljn=Ln6ZESU@FgKcCy@8#7V`Iz@|P0oXqZ~UFHf0 zA-A`eMJE2V9@ycPt^DTTF@Yc`Ne|bcT&QxaV366^qT^&+DR8@El63mpN^D>_g(1`0 zhoocrf<<8$BMbsE&7L8kFTeI@;rnY7hdVzDwQ7wd{?h^MOM`&HmdM31e2%&IG0rzM zaXR(5UMakb^|{;MSc(z!Qo6ZoLu-Sc--C!9QAYQ=t`4CAeW+oxT`<QCFW&r8`SI15 zFc-vbRX1m@cYXX)?m~3b^ZA?4>>t=T3ULFDk50o<h~DQnba0&(MYt!Wd$o19dwvgo zOF6GX;VKPZzP!J#f4@ip9MKIak=+}tIA-DXnn_}f$u$4-wjio$*xv?rLXsPfo+(=b z0<!_b$qZs@#}|Y%y2<k<+n@8H;z&X=n6aKNr$z^P*fq?`ZJNi&dsA(dmVS?><xrtN zAL5^CV|LvjL}$f4*?x-K_>-Frvgoywu=7~1DSHKbYzK1EBb?H<iq=n6+yG1gqvA8) zW}(Q0<~md#Os_c>ECh{-b>WzgeXFeDAPtr^{jYiRSNfdwQ>`ywqCghLv={>MDwBjW zdbkGmGqv&t8LmOxJOT)F(*oC3gpvA094KK@S*F(KDy?6Wmx56&MZcZ(J#(S;gWw)$ zW!@jYOb3e1&&A71tr{Qoe3gfJB#Q?=c})N)80v&u&KlND07CWVZ@?k$C}q_Q>NXhk zc~y5`z3JbA1lI3+`0C4@`#fgt_ZDM%ACES1w3*7y$Z<U!6mgo=tE+k?#k6x8AIwhw zhDnX-%n6~7_}zd>I^aMg!(><v#(h$#3(D$7A<YZZB5iK;0NL(682nNlt&iI_Y;6{M zJ%ZjH`p2Dvf<AH96B4G(wa>E#ohddyEU}Fzi-U4WHCER-7`My^V+x(3bX}ll>Z85k zt{@783^>%<1U>bieo-hh6>GS~7)SWO8{WIuf`s(!%F>86rvIp<c78Dr6E47Y@EJm} z&?6O^D~AZzKBrCpdhZt^Owq6edHc}S!IuG@QS(Tywfdtb!tbnJ2thoyW7@V%=Es9` zZ>F6M*Y(W}u7w90|CY0&SqJ33O_#qo>XE%aT8yGFBWaB9hb=YVI~$islm_IdC5g9C zC*+Pv(tBK6@S39~L}!PM8@H}o`??dII7q8H(lvWC9`oo{Q%A&Yacr>D9H@!<*B75U zw-=u)Jgi78n_^#xW?83I(6gd3ZZ0pJu04I#=XoH3!XHbr5Med#_<4)}9czqa*V}?s zz2mQT2lDl&<p*k24Y%+{hv<=Fx44-a-R``Y3FpNK0pDMpt#$?;Z~TN#&|HC0`9DXV z?pk^Yd<xGIJ~+C|$gpzz_$<~IY8CDmu8$s%%%ASLrS9yudzU30O_o9uezoS>f(95) z!{SV*C|Xd(k3*DmyyHLkXIKGfH=p3{eB7OHbJA=>-GC}F+j#bRVPs5^Tmy-?-}zz$ zab?{Xghv9Hi8qYBgi$36D!k^3Q8xD4o&VSkh50=4c&1XgU0r!to!YqScdRgri<1bX z11DfYthRR$+^zq5EyC;F61>$;QtOipj;#>I2enh|801vYM_>L!tO^>`SFFXy=;T7+ zcc2=)AoH^s+2uVF2+-|@vfAP5e&3vhuQ6}vWXm8Z1>LXlRa>85a?8e@B!nK0ds}89 zesb5w0p9A>_@Du>hueM8G2>IIWZ=Bez}6ie=&rO8I$8vn6(=RK5LlJL>*h>QHT|D6 z(WHSqOTOA1LlBJQj_j!0+G5&)8S5N`OI0#N?x0v%nbrC_y)%wmuTr7?wP)N?Fnrv5 zYWHkn={nhR??$en$a?(%((3eEquSNTH_|CVpUR0#_Ag@X#e>sa0w%X>AS2gjh#meS zp21hzcdHiG1@1Ge=$>A?&d#)G?px$Hf$`;;_Gh#0sRyuwQ1T$wtgbSRhV0&be05@? z)|kEHNj1j#nY)QPh-<`=?oF9my;t4|ftTRTbQ#;0S<{TxL@%tZ+@}mwj;G=CIKn%- zM01~rV778%hKD)s$9q)qoj&e=_lW}+lKHXOg;+3B2-aFCH@(IIakV)%fB@6}1KG89 zjqfQ=SXf1|F_E4p49IYM7NL{0M!{1mpYC~{d2(;u<8l8avyF9c;wEc<N;p=brxR-! zR-wy&qg5)tVo1f~zdIY=g-ivmEX4FyEDKqZ2?xQs-|@HyDKrwcPesjDk?`XJ8T+of zAMUd<nfFQdGQ(aT#+N@;5lO9I3XKLk%IjuS|4^zSW`T9&aN$_^jT2f<hmo!rYK-=l z#q)Q6WxQR0Q-N<^p!E{;%W_jz{@r*FbN!!=zP$CT!5t+EtDV>QuZj)&dd=*Q-qEFK zW)3cUU!OJ@bqySypI<21I-kQ<T^s=BRDEppT(V0i=>$y?AT>1Uo4W}yauqd=^4BxK z#%@zptTXZ<tNDl)edUeu<N0j<!W3`CvcgImkx$_lUNG$oLj%703mlinMhSn1@REgD zWjf5s^Z4`jFy@GE2JC<X3c*&kZ=`A-{m^viMG!n&x$0rfm@_+N_k&Hf+xOX~UHvht zn)b_X0{utPjo_3O<4T$tHTknFanHGSYWOOCqHxAq0440<y4TNt9-@Z4ODF*DBiq`8 zd|Zq{Zd1pLjV%n+xD@uUs%{g8qki;1=x=-*d(5qo)OyIv>kzT599KD~Ck=XONmVFS z-+Ue#<<46!LpPJ3FntBb)^fQ$pB!g+k3LO@+_>F|;*=u-88LjmZQjh|`(~bYK@{G- z&L79Tp^2j2Wd^cbf-LUgf4)0O@^fjZ`=AtS1tVm3#BfzqNYwS90EGLXAs^;NcWXqa zixnria;%fX<7lD*5|!JXt&CP5Ed7q!ZUU?WmI_7$Oy9C7g5TY@+QI3W>|lDkxO~Gq z*Hm>DAvk*Nz+r*P5jdAL-?HQkAJgU5879)T;gbrn+`_HHi2(*aQA1ur0L`Q%7S9E* zc>bP%4^_8R97*h2*g8R2>RH`^C4v9^mg$(!ykJl=cR{zF5{m47Sp9cJj%n;uzNx{> zbD>7?jJZaZMnm>g^N%Yzjk5vjeD_BmRy?pr=hiq8j_#^M+`f6$%3fWR;DJBU?Cxdj z?+Dfh<^`diw`>&{S%T6~zL2>B+V=~Ux7@n9qa5{C=s5Or#QX$f=Xcg)^yRyr70N4? z)L12=lzI<7cCg;toLgG0spL(EFIN*{`pjsQGIBSV9!yXZcsu;g;Co0FLQJrFCbMx9 zgyaSW8yNn_N3kHE9meu|?wEWGPky|dqWF{_lFW?MYR!7>w(oDTMs_%*MW<7^K5*CI z`4s5m5<2%(Bdm5<*ekU0tn+`};PUk4yIn9HUC;Emit^w#U;7h6=hpsY;kJ<FGqDsV zr|YNT52UP)`q`9*Y7fQYZ5APu{6*p28$v+RK%|}&8oZ?YZ1nkU_vJMo^FwuLCEaEE z9kt&Vn%gmDl~6^|>Ciss^gXs(0z11KxoA%LkxE27cB*c4{Ct-hY1M|8aJUv~)4^E| z)4|#lys`P;ztZZeY`#tit~E`1@PV`TOSXCfrdg6r%D5fLQ-U|jw8`LzP8iS_2tg(C z6OVz+L4xvybs2tJCo$|QM5LZ~3WqC*%_Q~@h=ccFcdsp`o6vd|+(}~8Ms~lLp)QWT z<*7tAbD1MZToom}5%%a|M>5LcVL6R-IHa&se&<|;1maht|B2)C9LpDHa1iafDNnj$ zDt8;KH=x>=<glC98s!h{ix)<R7JlTDvTmsxFVAbK#(!Wyy_x1^B!TZF&~%J3KBaHG zzD5!|COST>O$}8CpdX!Nxb#}NgYGW>&Nu~NI9^|02#vI|w64RtjOk}K%<5IxGOkYG z1T_SK_L5L|(S2f`$5-2HOOw>AkqKN*PsT?j>A(wz3%{UQ=xf&RDf;#ggrQ_8OwJiV zeklk;H=HSTx+Dv|`YnR0Qm%3z-P7hq6nMte7?iddI1ZXbMAUREV$Quf4!Jm>yAC|d z$FrS_C~HF5jQizmN>j__;xLkeFbdYatSRhbx{_kxeDH8d-gGhS?8VQ>m6IVJAvO`d zx<7t-r_%vE=>9k?-9HSoyu&H{2YxuUq@n~eJ5M@544y1#wLwh{4yU$24PN9B^FdE( z*sz)D;|%o+^UqR1&i?%p*MrR*3A#{XmEM_Xr`l*e5cq3l6U5-xCPyqZFz41nY-hQW zOlOk?_xSek>9OmN-hvwGKj;m>#R!KNG`7zXv|iAaV_uWE-YeX*B~)!B+&`}0V_`O6 z2N=>k-ad3SBfc)S-dyKLi>N@KW#6rjuVps<kW)>`ozz)U&Wvg2-2~+QQv1UPM207? z#)h&K6s2O@5nG;1^xuqpKj1Bl-z1ZsEnyQ$60Bk<xNm|I@B^>jcVy3}hQ?-!eeEO# zRd9u_29|@uInwqo59jG~b9L)i60R<xX$X&pFr2%W)?nJoxR6yp;gdbv*jDjpOoyv1 zs2o$=kO;8M!IA;vNwn=80R%%IIjVbvt8xf_34IQ~1ZscAo%a+kYs6pfQ<3u(@vGC1 zC6)^a`Ga5Qa(bV=r`7?OD8a^MXyPPMN24c)h(v?0J{Ws6*1Lz%4Yy6&Z%HpH2UVIm zNG}kaWkJ`NT(YF7{!<^q_g^Jd=WgDeG5Dt(0s(SXJP+BU4NPH?O;u=%n$PK{C(J4d z8Lb4hn#UcD;$XQd^1#}ZFcj3t3f{Pf_r!H5FuNX{n5dpD$AA%FaVN$6ikz7q{iVjU zJZa>QJ0J@J(N8Q!!!ud){aSJf`;(JHLhpl=38ZCH1w)1FwNg|-X@#kAS64n9TxMVo zIQ?M?Y2z*#<i!YmfrHepgegw7f$RBP;Be?l65`eqN8Db$T-Rh~vpEB|H)XXnWA>rL z!?5^1x@xMOfxlkE32LX4iF(o?t=*sVLj?d#Ne`nS6!g#oq3!ayscA_<WMw7od%2^G z2U#mEQpQ8&Dtw^2xx;)W#s?c*a}Up&6gke+NgCw*w9ZS1qe_u*?0=z$19?+GY0Rw; zPxGD3*)mI~IBuyGqdHu3xgB9T{~vR285U*NwhhBDz#uIsok~inbdE?Vsem9If^<kX zLrbHCbV*2e$Iv3(-QAr-yeD4wrT6<hKfd?pw{7!dIGJ<B(Z{}ywU%9sUTmK?h$EU< z$@otC@vV}GubwuD_|sRm<!$l5gN(hE&G3qfAofpP0C#ZDNJ$2DGoBaG@dR@BT`n&B zgnT42$9iP1$m@_-I~5AuKPjt-jyl&(YA%t&-lw^|rulp&I@{i-OByqEG&(q@=gp3z zCauDO^ffK4i2S+SF_25CL*W?E8!c&?8g2e;iaUK6cLK-JKpW=bikDB+-z9WSz?*zd z*m)+Jl6Kz`WFTHr2F4~z>RfZ(TYg&TpM^`M@wMPq-)l!R!1Q#j_A`F1+2TwX-IxSN zK>FrAavAy$+wp!*+4$Z>bvI2k$-esn0)FLAMEMA@N^IfEXP#|gtIBf?5_Ll%+N<b7 zo>$7!VD6hlWo&@ql&?KK5{x%%29D2Jvtx?uU09wrez@qxsdcyf#Wr1~OVSOj-fJhH z=+j~NWlMHY1Z)5oxL`dI4RM?7HjIg$U+9`#*)ZnOb089Q(Nxtw%U$p4$h5!xNLNLQ z!9k%>^(9ogLU+z}D4)oEXe?9nR#<Lw+ODb#EqP8eC!XLlHSL0mXj-B<^?nM{w4W%W z^l##rfCwLpJ7#`yO`Tv3GpuS-%EjI_wv+a^wrcKJ&ytAvM9&PiP9%D+uDQDNv+(V{ zQ<H=+p$!oS$@6$S0qRUXhPk6}X};IzyfikPg48KLNXdkdJgKr5+Q@z9mM>n7bqidz z>6)5YGLMuD3aIj@Qs9rHfpG7^DfZ*1(L#T{1yE9C3|<>_n#DGZTm?qLkZYuk3m1af z+yP%F9?__zL<Sl#LNtupH-hLTw(3cacxDP_o#JqP6BUZKq+E|^;miZabBpx%F&`(& zq}ew*XSKHAKQ*ahJ|oJmo+eZFaXB+?m7?F5F5P$6Q;@`&fyD90ne}bqxf9PXyv%Uu zry6?)uJ{Vw$6jF{LEn`IJCjZVwyibTlZZu&5a+|>c7DA%x8IFfBPm5WGN-w42wg|o z0jcuzIe*F3>@lK7VgBvBbs1ZqY;zY6F1}+~ZdX!kzzj?QBH2h;=QnmFAK>Ck`;0UT zSft@Kyl#e(61wYCg}rxYvz+Ou$uF-g=S&+r+j|6|YK+(_DA^MP!H^>7r<@$#aoq<* z7Y~`;XZq-=54Mn(_C#f0K@-X;kxF6Bo4gKZ=hsQk7&1i<N>hV*4i<Iv9um6_`!|gZ z>@1msdTJ`4I(j$n@xPlh5`Vs{3t$)@Y13ko-)l3FzKrM)d89>nbR~C>Zh>gjZu9WF zK?jk!@uyB_`6dM4;F}za&Z(?{Iy(BvAM&6l!kd>Y$*<||Y~s{wxDeG6ZX<ysV<$2s z4L{gOh)3AM!|u9<qSd*qV*tF_rc@7k!O*Lq#Xii~3z{Rx@e^I;7Sp2C+oKno(+p^w z*|)IQnMY&Ly9s&ePdUF!vhTdN;X*x#!>@4PhNiGH=qtCI)1(@@8f&S5eyuhH&EAnM zw8&=;=MrsuJ4Xs>cN>vA37{BxUY-O_VV{W}I2vQwJATrE%cb9v`Oa&LLQ0HnQ}TP9 zIm&}^2k75;m_4uT4x?f2y#icQmO-k+o_=I(YHoEWA4*uu*NeBNn5%1;t592pmdY<x z7~<N;)1lMo&A)(Ut8>k`if)B=iCNNOB^zEi-F*ki5`_$VP9Ttb8DE_KB<I&1m;z;m zIMPTJw`FwoLLo^$cptQ@&vs`@4at|_0c?%~akP(gnZ5%!i>Qe=>Varjr&zpZI${U_ zrz5I(3=OwQ1>IPP>fJQ#mPS%(RJ`OOi=Xih1bR0lxvP^{X1TEu)KtBk=*+vrHhs;S z)GpP{mZhIGhb6t3ZG~!B9$V~ke#wzf$5Wt!OH?Z|X945U#NXEo^7>5Kl+`a83e(~) zFja>i*azgl+{eOceoh?Vn{rPMf>yg*{}?B|qll`W{!@<3@l%h6^$CG4V^h57B9Zv6 zYJLBHv1?8=^RhISD6hguOR>mHXYr${V#KUBI@g+S0g<~#N&cE+7y$dIDynltN&k4I z+EXWR`UF2KkPkU~ErxgI(}*%yY#te;OI3&-TDa&*Bs1&XI#6t>dr9m(WzlqGk4;&X z-1PisgBO;6F<4FDazgwiSLzu@ZJkd<RkEy1Wa|QjOlR{zHF;5!;X3X8RdBaiXaN>s zAXY)4TBo-%$rH+Cr$*2&@<!V$7DfLD0)f)vTP|sRlV~dEug=?+1n?`>&?w<>`qup2 zoWi>-y(&}C*(Jx;L!E$P??oD4MpcT6l?a$b8;j_v?k614ke=4(`@Pme8feb<HZqpx zG1>ba6Pgd{!OOgHpJE@P^x1q_iLehK_#jq%=DVQl&@CQN_tfH*n4gnVG3n=rg_;~T z&A60;vxO_oC9)ddiZ+6VMu$h11>JXE?u330BDz1!$#!rV*P2lQLkgBQSC+psz5#ev zHAXa+i3t9k8+ps9))$X|#W^t5yw<~`#iB|G<_&~B#LC)Fa|l0Re8>c5!rADQt_3Yn zgH-7Gd<WX<_Zc739xyF3`;re?Z#-?}P-;KuSgOkSrf)?lvJWggES6%#SM%#rAOy^A zdCtgU%=81=?a+_uK?0GU1fEam_5DZRjsR8$4`u>pM2o&RIvrOwEz^512vxdrbhmmO z^M&C~y$hk?Z2DS|Etcrso786w@<C&~ZwR!=d-mRJw5@1le2Z@s*?YIG+RI*xUyo?4 zn7jYuOERY;68!oN;Q#Tm6ElKPSV!IfKv)O<evb<w$lc>P^95s=hEl)yQ6}LJ`c2BH zcPwW`SpS{{aD1t{+mik!uAPq11~VPgq77$u34okN2Sb=F)x3UaxZVnv<h1igV<~T_ z0$G+qpFnZdSPrld0_6fVV6<B1woNSS-?uGC-fq+AU$>B0=-_gm5T3nNYBacfmJ$5g znk%icRZQT37LOBI8o7O|Ah!ZAZ6g?F>5x1vY6>?NWalg1d0!NPedgtR+}4!Wh=T5_ z3&dsb@%u~>Ja@U{fhRw2@4JVI=RySHJq0}l5H~sYcL8J3BMjbwwMdPATXm?m+`YyN z^`lXzsv(@4%cd_spPZmZu1`hGp(>lWfho697%k^7r8b!X(zi2EBUH}L`dtoOJ?baa zOSum^eU3KE_slD==f<_)p)(M26{QD%77jqd5M)G}0MkCow)6*POOBC^Q6;>`AMbP! zme$8J(>sgfqg^9pj?#y%Dy`D>ONs5<YFo#VXtD5<%(tK6r}&UdBn$1EU+;gzl2CBY zeMYXCx91Dmls4R-7FRPm>3H0_=7YTD&M$(vidw$*zXMasQ}3*Hv<^j`g(G&B*p;z< z2MoI4;mbEfJi|Ow&U>1`{q;t(Pt_AtOHSQ(MsFXFa_^ek8Jx&A7YL+Wo{zL$E7Fj9 zLrHV*k*JXTTJr`e;=KlQxA!PA-NB<e4ET&r`^_SvLt|OyhtuDWPVFc*N}2#{HD}8= z*>aOLu|E`u{c|ASJKDR82E*$wP4KiAEtRJUU){ZYAFzA*jk()%M6vC@sNWjU7989M z)h^Y{`iRa{6<rj6Xb`#|o<><2Ndl)}Q44Vy_}O&=r!m^H@NCq<w&Y}qe&;YR@lpmA zUH0r}nfG>V^l*~=GbZSGjBPBqKguS`R;<}U8fB{Y(<|jE8+YnVf4MN=Tgk%B&<w-R z*ymFm0RAP)&C@LI(fB*?hp^@*Z`tDfyrMcCOW!9$ICdYFI&BHh?p&U7IdIp~UKq|A zU9mpNeRlt@ECL&3-PlQ?^+s9#jv<uNP+54Gcv%4?!cfcOdU@qld;{-}k51nY$}RGZ z<E(BM^m-|l-}Hd?Km>Vlb$Y(M6TK6=ejV^Ka^42^k!UZ^ks*+u-gH*6`ldTc&XN}^ zNsoiYBYsxjoXe*>nL1NNeuF4IqDEE?2@D0iSF0D4qmNwNUo;<5g-juLfZ9{15$|BF zH$cxWr)FJjWMMuF3yvS2SlRHUx}-ix_5ye@iWiPFP1^fQ90=QbAw}gp5$)98O08Ij zDb14@V&WR(v4T9wrLkMjxgBh95(q|Ja>gbdDq{xO2m<fB)3HtB!}4kIie1&CGXBA) zcj)F@(S3eh52%j{3mKX-h7P%Zg67|}D;)a{Rf2IEeGmx%mepE~(IvZ<x1{3_ETg<t zOA85?maZ`#Uf6v9Bokr=LdJm0dgeU7OK;*mi9A2Ddl*StYTJSEHZvM9H5oD<37}Q7 zSu!r(t4@<mpsJkMDz&&51K5=4jSg_BE+bjb6U*d|w0wx!6QCvYw!&_pB_JfUQ3L|b zRFdy!@}&Ezl`TPrje_dHl824Mss;i3*!s$A3iJlMl;KK1{hZKf?sH`?rK;MAf-6Ei z!SfZVD(!a>lPuh+v~InHd&0-=DSk92F>!N5_EXFIr>;MnF&i&jj<{V+M;~?&<yY5E zpe0chMHfUzsbho|#Hu`UQu$^i58e#-1nW@D5<a+-cvA>(bw^u23AHMt#U$F)^kk_Z zq51Ce8n2I0V&b|tq?dJ>MIhR)tCa37#@6_pu6G|+^uoNIaD&8Abm{;)ezr8|zNej& zx)LKGxB1jX-&89WuY$Ww)<<Y+5xbhwl^KZ)MQ0xh)uX%^($kEd{3;)D659gcz&6)` z{7wM})7g7Qiy4)c>rtubqbsbRg|RosH>WbM#B^SQA0zSj$P)pu3nwk|T#0~&S;;AZ zd^K~~Y1uf;l9EGCy97W7^{GPn<f+&4O?R5~HXs8{Si4Y^MyG)eX2*e!>$V@_WFkBk z6NvX)g2To_Kyd8F_{=Tn@)ZB87lcy~V2xj+Zw?T2!PPJnkV>}Z4nRILK_91u6JWhV zW5c5#T<vzYN~&vZxG!_xtl@9FfJBQbn|yV~MZ)UR(!ylt0B^$WVm|sdHgW(_y%r@D z{17}>D38J~h;J^QvVb9l#C^r8gbFC*=u2um*m`AjS5&)m6^sf$qV;poMH-a!T4&e^ zjOaV&Nx)-K|H7KLb9L?16>4a{xfof#Yf`>iU^sO);`RhZ7oOT0&|D~HEL3I}0+{N0 z{BWeaN`bUPAPfO+X&)ohm~g;GuOC0?`A$yU97Eu>_Y$IK5Of1%I&MQ&A1vxvpIkk9 z_DQj5zAo9l&9e0C`}hWa^9h&t(&d>fK#d3B7%YFRS_#c^$c|3AK!k!MKV&Ha(uOSs z1r;G%#s#tf-iQla2gxDyDlk5e!Sj;E^LhiMP}D*n)df)lpJ+eUP8RW{MsSwMYXiW% z)(k^U{+dx3mjh=Z^g}VzW%DP5bD>y&5<qJ?z+O}h?PhNRMN<kkAT2y68r4xwtT5^| zTo&wy))sA0g<|Sn?}wDR%1y3(s%$25D#FR^Vsot@2>=*rYOwpugHrJ=z6pKSdRBv@ zlPD*Qjg!1%pV6G6*OGt@VFSoMx?=t&6(IX&1oYM80ewG@24lxiH}C?!OnFA0UCKxe zu6<#iM^GSdv3SIT9mzAsH^iB@NGO3qjvKF6fY-R?y6ZUWm$fh*9_Aq&E7iY*c=Pe5 zwD}wH)m8Q-54{76QELJ6xn$R<tPTji8XlxA;jFbh-9rZvGi7#qng^V}R~bK7yCE@T zPq}SN`*cQaX4sis!yqEzXHcLx6%Ap?5Krbz#1Blxci*0<8p^jj(bVGDPxMQ_6t0-6 z$(-R}{oL@3^O71=Os_D*+(!DDnf)$Z%6&91WUU3U-`?P8VBF?So^8z{;I^@A|MZ;C zl+5D!Jx;dg9Y<zgWVxbn8-OK*$>z5(wwG(KzGo*?3ofB0E3{@z4fSI39v_AixR0P& zS2YA!;a)zwEGxgOtV6yZjx>DsdySD>3LeD50B$i<>m{jL8xeZf{eZRcTjjRn=x)6O z`!_?nV8x!!jx^pr>cxFm>mNoG2!6Bk9^IIS2r`LyJIw+7u@%|A??i5?mHmlh@prMZ z5@6-?kkZ2L{7aD*NDkt>@F4Kny^7ULL!QkFQx6p;WA=O16>Rl(8J^eczsNF{A}Ho; zHB1JveYGD4+TZ#1`3QjIRG%do?*7n81T%}pp5gEpQi*BR(Cx$p<z`X_b`0_*zhfkn zZZ0HzA@I8^Zood7E@h1W{(}u<F#7_+k2dGfUw$Gn?U`XXO+ER`#c}2r^3GlE1;2zy zAr*wh7yOQ3u?eiwiXsDtH8Fhc0a@Zsgnk;bQ9!$E>EDl?IG`Q{7XJ5s*Z=+VI9?tK zvN|Gpf_@j;{PW3va%Uy&1eA#XJ{xxhp2hd6@&Uy8&j(1g03zj1r8fV4245ur+@ovz zuivmcFpN8?4g@T?<_yjQiT?y%ccV)NT*T`0cQ}8>MysF#&}(bcKAYq3v!V;|7mPgN z$VjYd*TMg*O&@59DrbCh;n%@z;=jMA2F1%!&kX9>Z;xlLrDOfm|9?gSypi9t?Mt-z zos-$`-#Oe-F_S=wjXi$lQ+!g`vp+NdzGM@Cn)Y$Az;FKhVE{UE$Zbf6+dI}fw*K=; z5d+BTBl??z|BxCF7XUHDM4-PHUH<br%<(Qwb)5b<0w6yBzWW+H4Au|@AfZ2f03C24 zcPt6#M*p3b0xdPJ&OdDZ&zsbg;9+zQ%Cq<7g#U644|X5f2}zo<?7x_MK%FA&c~I4t zlks=Lkq{tk{-2{Y0fqiQ%<2CBZc7R&S^)?z#i;GUUpQc&#kO<u@BLnSphk*86}_9N zo|KODK%PQ?Zkw_JV0@|wAm9{A&!rn7g==xZEY*$e{lqUVC~zFn{70?vq=JAr3kc3a zkx=KK#R;G8VCM9?vES22fBE1ckTE{Gqt8J>ZZAL|*nIlFe)u^i?>bNiNzDxqlRREM zKM)9O1)<R9J><vy06%^+BUn;X`8VA6FQEYiA0GRc4R^zofPy#-c{E0T+m_$_fI*Q= zD4}iyf4Ftm#WHemPyRdczuc#$#)Cj*!TEdMe`(z62joS?)gw9Cf1iN?@jj9Lw|jsR z-vIRqp1@WCwDONYfE4Eb@DrFT3E=a;%~&a`{Q1FMBNYGtXas~@#e(-&NP+St8bC}n zcFQ)I{+b*bfQZ1oSAWMZM$L9d!>+`4LVxE?{g@g#yYM&L|FI>l!BA=>F34lUO3l9v z33!ftf*gD_qcZd7O}$q@)=*rxlT-FDp`i&tTFBe$plwI=FC_!$?nLIWB6sl5Xszji zp(gA#Y_k13R6J?WAyWJQ_m2SZ!eB%h!1n*N&T!ZIQA6(NpVpt=wH|EQkn^{7dBA)g z)a~Vz{~2d6;P~6mS93T2ymkOkfw&J*pmwJ~zdx<t05Zhr%RrU?Oy;-Tp#N`4r3e4k zwtwxz{~M73!`y9AmGk6ZB2WXPyu|ry&Vfp2V36B>xix<VNeggl@89v=scG>4ZUlxj z{F?fb{=eEWgMdK_1TQ*P{c_X(HkCrJ<A(lU+GTjBz@=mbfXDckOrCL`|5M)o=j4$Y zkiLG_A(XOqnmB*^hb_RD@oMm3o?3ybEtd=(ia)go%S#BosP4MlrtE)-BXD|z)X>@4 zbv%!`j(e}4np(&#T))0v?rMMxI5$)vts=+g&scyjbQAN49u)L#0IpPLAvEKTDNUZK z)*lKAqC3cv&~;P%I~$!fJSn1qD|L9TP()dl{mv(@S|Of~BDD^ElS9TXc72rTF$%KH z0&AJM^nWOFKp##{LBWcjg7=|xFX_}CvDx5OQJLN{TkSTL_|XFz_<wtpcKUD@HgpuI zD)#BwQjlm^p<802{rB1_ch{}x+zbL(h^BUw*5A46$y3K#Vb`sYGajF(@mLk*_k^At zM+(ALo}K{7)gL32G62czM!d~fK1OrKufpwVvTPyvdE+UV`EM9;H{AYjU`i&W_jGfQ z>xg=qm>|tAM@PHg#B}s$t)kTaHb(gbiGmg=SP6yPd~ltnFPZqlVaovEZ+~V?+s^@h zM~9T&(~yO@+$I-G`7a|70M);*8in*>B<&ixR$XoTYjN=)G@?DP<~8fz27t0b6J#kt zLKqgq0%{$<z!sYKx&E%t?BDqS5l9j|4oq#@a)Hc8y!^o-EYX*!pTcI(8L0gDBQHi^ zkm*BDcXxP;(2Tu@Zqu&5634Yy9C0STMddHXzx^4FXySqcp?)8W?e{y}fwN7}G;m*Q z{+G{Hm(y_r;kA8Gw6ZkK&7eU`B*Igt1j<?dc9m@jl0zzxuJYA_Kfk`VA9X?Asx4qn z{4X&>f;^spv5!QmJ;xf`>vKW=`l?bC67M%gM?aQO%l6-Gsj|a904e#INL}OX){LFJ zjv8?RUfO?iO5qm#<>I0)q_I)>U{%O{8*_aO<FsS5ag#aqZ;!2Cq0b^@RBMFl7bZnu z4W2+LKH7%QH40Bc_Wl3vE}IYbp;)zSW${vS&pAw+s?JkUTDn4&vC0YARO>C>f6<9n zfdJIG8oe6#xK%9F)^1{@A5(QWl7nk0$LB9=Qli0MYSA1>>K)1MEt~)=Iy0nAsE!ZH zCHDOSHue5eY@8F+sU|ZedLb32eeW6r*Uo<O;xmTIya6j-r7@2j#vg+j0C&d7Go=eR ziFFE_vvR4O`4(^UX84{)NaP*f^B;o*KfRwFi}ZnOU3S~VxLAhSU}+-H6iw@P|H}?) z`ZVBM7GHRB2UbW|FjJnX-vw9@$gmQUb9R=C%g*+=>iHYP5t{)Zsk+<T(ACPuvW>n| zTQZ!cE^|HnmhN}K;U<_{7+L4BrpPxRf|q@(N4uZ-IdUVUChuYkm^nT4K(dJ^xocv0 zG3|*grW)Jjv)H$t<AoCr=1dgB0O02d*~SBLJ@EW+9}Df(q}DNNolg_6;}3h8pq$8G zz$ZQjs4DIM3D)_l6KO_j6XOmN5I>L<DED-dF|L)<bCM1enS3tyDFuB(qG5u$_BSxh zMdW$&`2y@ScV;nb3sP7tBz2|$#DAO(RQBo^g!5wiV5Q~pCEHw5a%E$U`wWh)?Ko4O zRV%e+3d8sOyDXTdh{+8JBa1|S*fl4qiGbUC&vHq4{kJ8ph((I`+&D?ES_(o4tv7tS zH``daGqq+mI#p@GN48oIo6`7T@H-*odQ`*&3ipd#_#hvaNJdroUN<WIZo0!?kc41_ z4z5mx)NMM<v1LR1HxxU&7230nmIMoVXo6Y41zG?G&xAlNrThncKH>U34~u$nUY7s+ zKPNJt_JMlg&%*S=dRi<)gU2Pmjlkv2>F`zi925+Id8)F)Wbr)*x+Nzkw^zG^1s=DM z(51Tp%y6cg_f4sMZwUpvv*4>1R!Xk`$&@N^RT_~eIo2m9=gE`8g|FqmjS}ZQ<TY%p zcsC{xU*nHBZ?cu$9|?dR3!^PE28F*3lkYQ^m5pwR9%ALlMh|I8;Q?AlqnWQM^P$}j zN@cJjwLzC?)Ad#oZ@UZGVfSIO1fJb6zpo2~Xx<v%5^NFfo&kuvw~+CTkU(1C!8A8( z$8mShfhJe@$#o)G%01?^J6c8Jk1HXs+ibQB-y>KsLue6R+T5+z20$O-rR*H0?J))8 z-5{lVYeMS1Lln@XfQ1JrSP&-rz_Wp*D!qE5W`9u!k5ch@QAZ)bSLh>rol<u3c~}9P zsdUzkTL6?Di|hv_bM9SFW;sZYwe}7KLOPZE^g8L#xKISJ?rf$J6y(k^g)v_CRK}*< z^TbEf11dDhJwKxqAx_-@=GI2?Gvg!vj`}s1ZTTp}sbVomlM4u6fUMHgEP8)Hn}W1t z&+W!ZH7cdgMsq~k_qWFQ<Bi)Q|8$-B@I`d!m4MhhP#mN}=!8u5NzxW5710^OU?D=m z;JF;g?wL!LRBW46qt{S*IL;+JPT65XvsSzqAyTp7tMWVBRX_o$(;~S&-+xN{t8Z;p zqxia*boj+9U_t@#8VHLVi<<6_q5{);Y=O{fId;8*Ar>_rM*v<Pi^^vEok_C-*b#^$ z4~s}G85S`-Xr*rJ5Cx!E@JASrhdSSitVl|@{(QxL3S0_OSnr0Y2+HuA_lFPa0!*!; zEusU3bDhdINb(Eplv;5BM*G2?xznkIIM$ZUUNM~-bvz@+pZ1Q$DUg$`{{CTVR9a~a zFimE_ExZJt4b{uUanc2P{KT(CMB*%RnR8w5-cA_>*O|MdHTDT(qNbRs=QBMK0y<M8 zkb3($Lve$8M%Ml(fFbfBGdz5#krba`knh9<`~VrB@lnwts#!@xbo3V@tMu8n5}D)Q zdAW%UwXu+)$I<MZss+o(&yV>zEDcM|zMVFN;?&{^Gg+FrbNOW~|L&O-nFp78dkVAG zp%$4&<B2MYXimi7Q=oTens6CThV7xQH5Q(D%wJ`(Y<$7t`ot!dl_WArzucdhFk=*L z0a=;OM?6Q+jD~P~83&d#e1_yqsT^1`kfJsgFFmcmk^au@u^ng0Z2T(2OkQ2xm?I!~ zS?<c@ha4>)JE(Wb-+xlbXkk8*;~2!>r&Gs~eYaADEsA7AtwX4e&usNv$OE6ap@kDQ zC7Hk~s3bH}wDvBtC~^YJHDfxy(}MS)<V6Aoom)nyO9C13We`)UX)LC*DobC8&gI#i z+HmqC@1c_W5m`}c!DBNr;F!dx9u~)!Kdyjw1pMLAn9#H%*#=EjiO)elYN=63toi|a z3J;~W3Uov6XxGpj{#E?Q;s-MgNFWei0fCC_FLlE`HCv5zNG0bu>(bYAo&gO37qqCi zBU>DU?B{7>2<C=XjX$lAyFF0S#m_bcb*|)ZUa7!f?cv@pjDQ;~^o-E<Nb&-5eq&Gl z3g9agRs=|^oxjQT=Lv2Dwle+$!1d^K+=q92OcA&?xICrnHsWRCoc5ejBwk^@3skrs zL#2U>(=)Bwy)o5pO8ji2A^}Zjg`@ywr(!W4qLfXOaGupw4b6(I$K~*B&fknq@H{(D z+}!#~R74&k3<%^fGR%AfWqqrMUYoR2R|dmIpWg`Wod}7%<Q;@4!2op`#bT#6PdEeR z<VvT{DMx98?a^T7fSKt$<4g({iI1}tyH-5vh3BdPn%5fZS@|&wf!Mi+0EyyVj)w8t zyt&KbDw5$9_n_PtB{sHXXkN=4BwQc+RPF)}SfZGx7Torkam)IitL`(${wN|Vh8f)v zaWLsuB=9_Up91RAPph=7j$YsAYq=y<Pa9>J%ORYk$ZH{(vedF~j6zM+u=h{}KS$#@ zBa<wn<}vBf0byqm4hYY4O5nJetoh~4j6Hff%*NL%Q(CnnWS9=1oGF6>03Al)m{BL# z7O4C(guD<Q=B7bmgKZ!{n=c%8&ZJd<$qa|WE4YynCg-bo1z6803$PZ$E_na3!TA_v zSY_jb!(XINS7o2GO*c(sUj-|bA3`qCHF;=x6V8TR&`f~^8DL8(0FTn(LEt-fpy<3E z65B{&qTU$g5_s+p-^JgiiWKs=nMA=Q>|}EJqvGx_huNoy4f&o~m%i;uuI?ojEE$4I zGHlM`UQFUp$m%9F)**=hw{-@Ji!A8E^-|FuTA=uzwHMcBv|*#gdJ=_qR8%`GqM3Y` z2Ix)-gMUI+eB&z%U-#9UyULtsa5FqcdkfLac&$Ig(IQa~o5fs5fCd{nG1vR=@+BQI z$UGmfE^9vPRJff}G@&aNqS$?Pt+doay9bWreHU(X2SJx#Jx`WbW&2p+QaM4?pksfW zO;YcrQUH!Eeed{a7HXK$;2CfCD5?NZAvKK00?#N;1sV|o(d<5oMUHe8qmkUib0QQ} zEt9bhPl<gLoA)<VwcyxZBP(~rqJ<8vA#QY8;&l59jv${tdF{Ee<9QsTS%`t1!>H;# z)gC!2SBgj64dgTQS*(;=CRgdJ&O+Ar!W2W$ii{!qxkB8!0sENp2QP{N3W&k`mHW6Z z-fj!s)=fyW$6oLI8}e9yWt+*KN|)JaP(0?RRn4ck9K5s5T(A^eo#P05GEIwFOh<BH z5deFwYtn@J7qD_kT>#d(qCE|ph3*}+d|5d??0PW=4<bU5UvL&rIRly4g;%-vDOuuY z<AQKQL9?0kI*U4^uJ?EQJ|s{yh=_#IlW?LGjt!2Y>qh|zd<qQ&4pJ`m&;mEJOym~E z6<aS}T|mJS$%$ic+l;iKArLK0zBV9?%zgl~a#ep^{gc3Ic|Ceh_%oBPFm~4K{iG&V zcAsazK|#C}$g&Niw!E-$h0hNZk!#zPb2XZan;!X{NrSVeTTSPp-0Meq{xjuiO0Iyy z+1+<kKq`2is;0TxrUj%fvbs`QFVKqL8ASmRDNtH4yA|VjJj5RFb8$!;{>YCBbX{!n zO5{-0Xli_AWt-P9<=t<+Wqk}3*B!T8VPd|Cjj}ux3J&EV;?gytqjUqnyKEZd+u-*s zCAFPP1gBnMNkBq7M_w0an*IZ^%j&I48H!tDaijQncSoDE;Pj43fajwm^epeyrPy#{ zpSK3g(1R}e0qV=pp)D!7m^(dzDuW2k$q(XN%GhH^4O+n9+<WEsVZx;h9IV|P8vb(s z)PDy+Um-;&@v9tw>mC^BGi-43&u+K1_9uU$Wdr|{oWUmXrBqE_nq^PxOgR=>=S|S< z9q}DkWvUsh%EwA^W-+UB2Qi5$LN#iCG1L8auJ}NOdv!ut=4$3(lk@liWh22pNUP-+ zHKE6is!*i7!CfHd3c3)yB+(!J=!_iHRxY9=A+BSq^HWVMWlIba`SJ2{N9Al!AlrG= z{Aw@S1lY1IM;)srH>ETbIaBA^#!j*c$eltsd}*!Db7#k1%MDrRp*cVnZmASv=Cb5O zmp+S`8e>_rOU>FFn~Z(h{xb}Xt#zF^jS4tcnSmK334UaBFyB(3Cdlph)vo%V5GFo4 z-mJ`ExVJInbN(iaV;EJ8Y>i)o=OJix0{gACSV|MdGA7@Xhk;E}v)IEKaggJVcVF}N z&bFfiyz`$xQwDGH6~7kHOSb`GTL2$&<$Wm=J_FVrR=dw$X<=G$w|&qhhNATKgRPQQ z<~z5Oj+e53xM-RlLZ!7oKoF48JtoLME;3K~p>eIK?PW#5n}%0F-4-V$@))`mNndQ6 z0gLl{|I}sF*4BP<e3?fZ{BmQu@0A||0*dx%UenCIwrSA?UzLyJ1DD&SYv~@-cui-U zc&z{rkt4E-%>i0heiuNXMadM-dsRufasx451~Xv{`g24I^6e+C9ZKBzMjRkAyIb)b zbwGkY4CIm!F9sce(R>oHKZ*oA&eyzSZ8iza56=@&b=qxAse`q!kzk+uKx7y|1yiu* zV~AJL=1NhJ1z)Z#Q%2R9&OmjY)ztIqe{}A`G1tR{Hu)3pa0OWTeIp3+&)08`2QaJH z7g4`|RQN55qtZGgijDhGt(+X?7Rvjy9Q^#_R4z(RZpp1N{(jq8XS?qy3trl}I1xU* zYey9qfVYe_&I=1rSQ)(Hi4=0Zhfng~E{LVPfpC^{zi0kh(#GTs$-6!(B64-t39!Uj zE!|2_(yk|VGqCD+N5#+nogkIddqxlYtZ<N+B(;og@+#a6FkX(l5FXg1wsWmi;>0(? z0&NtO*<smDwr1HxTNuQe&gIODQ=|L!cRS;+hp9XgukC&qI`i$CI_PtbNXLisS+sXS zh5CS9rY(90>b%&lOPux?#Gw>kFUVN<F@+Z$q6IHD8(l5FFMt4z&VCqUMScM6s7gTt z*Ch(ntYvG~9LBQhi{|xky2->-iU4@Zp8FUUefP>mQ4>vX#X{Pcq{Q}gYgJFvZ1ME0 z0P*+lK&1&l4Jz2Op2dLu$#%(XgBFXgQnF&xdCmocjx%zf4)mvh!!9_>=>0ztcNDk| ziQH(fQsB%&^*#vi(nQgl2*w~E=eB@pD02N{;z}?sY2fgRV`z(Y>T}ZUVBC7VniL&? z*y53aIzP~UHpIyDk7cjQ>T)jR!{&*XxO_%p>a{|ysR~I7+^U~vP6mW~2A`4m=7E|y z`OLQc9!{WSYQ_7eAo#9DsfyN9#6(}WPICf8OnMImrUeI~{n*~xE)(3IUFm%FagP&e z7g_0Ub)rZD)I^OZ!=tdL4^2Bcl;8Wvp}UDlPj6y!LQW4T1JdSwMo?-OtJA4l{7r{Q zd3<HOxdT<4@c^VG78EY7ciG*58pK|IIT;9%sgC%G`;b(AV|V_D81EAqTg%%qqKP_m z-HiZ1^>Z*DV;{*(Oj*WfQ0ck7OB@~*KbCEB%g^Ty7%Sf}7J6Vw;lA?tF6ix!q&vWi zwZIk|H4GBL?d3sKaH1!{&t{+3+MA2JN|Yy7I&5Da(oRRt-Co(m1bg6}8k_uvkWFdA zZ7H-1nh*PFxfJ%>_kL*BZeJHa<xz=7^Wp5rR(d0zLJ9dkNGvwGyb78IiUxoKb71U^ zX7)#!6BDH`m>9*n#HewKCMroRnhA_VZWzrj_T9jhHQRTNHst{0v8Ia{+7XplzO46f zSD2rRDUct#pRr-_NgQ%XO(@F%TE|a~<Q*|7k^2H)YG?{e9*|%wM36Rks7(PZfk3@{ z)6~I%DN4#9(x#+Z<}iyhiY)s8P|Fk;1Z*K<`^=(s9^J<_{do^Hn(x(iuck_fC`#aj z#B$-YAZR*)s+L;G`xXU_oP6_p-Es7}p6;-Y&{$nB6hv1e=gYo_`i;<2qGS4=sXE2= zTUQhtl-ZZbP!F^Cz(O;?CXq%$zeF3v3MKRCKD^4;S&VlJJ3g-BL$0=`j|m=Ptj<p< z6ckG-#`u1=UCwYuQL2Z-ZAFG6PA$vPHk<m=aPBgCLXrwqw)yz}p)0RN8;0=16T33k zgye5U;#C;N=mtj>2WZTucggvy7U!>@XI>gPRN)<?9EZhWtHusF+TN@Hg?!6e#N0Yu zO27tHSPwmt^2($TPGX6QwsZ3*%y>bJdFHJp1nMWmW-e^qWsTzbdR>&oBqMLUn>v74 zBYTU^wz+2ChvkCvi~z-_1Nvc9<DqJzVDXzsLB{RqrLNHDk0*Mn+$?V~XU_#(Et4)6 zGNIQ%@;EXR!pRFGk8W<gG_x%pd6ja$WW!sj@$!6s0Z!(4pr-(RXy?SYe{Mhx(oTc; z^r(MfD3aSv38Vpqyr3p2djg--d2=j*(?Hc-P{A!QJz^komg{5o{jKYu#O=@ZF1pIe z#s|s;AJt%6x{pwY%7MX^(|A(Z5b#fqOoR<?z2QcD^4jE?<!B-AKi#c0T)$jvrBUbO zeN{#PGwNLME<6L9=t!A2P`nlg+dqSq>C)l7lr&NwpB3gP_uR&!rA+iM^1P(54HXXB z&`pAVG{(87+X(MK{m7Zx$4Ec3&u_t8(8a!zU*)5$*xdR4$<Xpw0hA$=4I`)d%XzaX zhfPrrYsVU;Q04(UDL~dFz!su!65Z?Evfo&kzHaBi7{aRG_ac#ryFTwQ)Oh8yb<e@J zXc`7_wdOFwaktlj*KlxzW*R*zKRhimfkjxwn&;^?=4f?1b3$AeLHGfSRYV6KtSB?8 zxJ{XOVMfBO_tcB9;$#N1KI^H-y!?Tfpr2jz<x|n~RN8RApxgfMi-yy<TiWpOy5Ubv zhHSxPa@Ek<a?Z~`2%b9FmqWd!y%WE`M0T$Ef!<siWsF{Id_F!=ccc?TCoq}!P4e;g zSA{zFv;v-alNu_tRv#|u>Mb}~{OXgGGXhpA=NG`|im&H8E-RD#N^<7VbtVbX<S@L~ z-Xq$1y!cQyu(#J!@MLsq&31ZZPoGWu-p+;e?MSI)C2sE7(1wrs(FfNmdwZO-Ox!QB zMub)Mmk0M(EqFZZA!(z;uYRV|(Qrup<*@y*Nzqig@z)9eW1u8Qj@sPj8)#wuO{sM^ zAN&-}()`yF*D!;ny4FN#$83XLmt5L03LXsWMq}R=)7tlv{v5aBiAc4P^pevPmR0kc z(>%>9uoPNtk<`6HFJ!IP<MYz`r$fc4h*|kBqhVQABJxC8rqs=rdTfO;Nzc1pKzm(B zEhp4>qRp6iVV&IsKYR=tMM5In&sayiLe~icRedw`t7d>b7I~@=us;5n1Lb<zhvy+V z>|D|ZDG@6Z2Gatg=`8b0C>?3|%xRMH#z5jMh#ZK0v)_37h3;mI8S`M2#B=?vwaZ!D zL7VssMzD+XeE>=|lf=o|nexXOUx~Fw?9XNkaq-TZG~qX!(J-NsVuL4NaD#-XXYuSV z+ap=!Sop1pMhs;97A<$%$+wjUCW<PARO9PQC!!Ck<3bMKAEj0vL1W78E1#XAFA6K* zwC<;>8ZXg~{4iWQ*P#-7rBitLVlpcyAJQ5FC4EO@1nNzF#Obl3^f=YpNQvcYKwt=z zdnA4w;siJb3@m%T(J@SKPm3^4zdQ${sNF^p<K(Mkyk-RbcH^as{-{~~X^4pIlvu|{ z`wfe%^2(Pp3vm+}28jA<cbARWhc2hVJZvkG-}YD@I#{+79Q3WRP02Gn%**21xZEt# zFcPeYmYHpsZk+!WF0;C`__1R<QG~oy<ihdSO}vQIRLpI;LD??`^P9q~JV#5O!AbLr ziv$WMimj-mjWSWnYL2IMbXJXOXZE}_U5`xfWfNFlsCl0S6rAw4bx^3ITUzI`!q5fP zC&arxK1F$sLgiJjh7meEQj3^K7vmhldi1DitDWn)oaesETFef-$zV!g_+!t`(y0m$ z+l2Zfmwdj@D-!!N={x!-b^V{z$&(vlhE`@-Y%(ueb+eevV^i%-cebtc*o$~xBn5Y{ zaiGjiKA_}KC+||XXEFV3nB8e2;fuOv7wglbp#g6><Wzg7fFWo$M0j*RbHXjJ>wZyU z@D`}AX_o7ZQ=PQ1+$WpS7V-1D+Q8_SOtU#Pqx{yW8Fk&_8JB@w)6aWXRCDid%I7Z4 z<DDFu{pO}MPX*?7y(~CACh;aI{F3GLBcHq1vpYCc_YDo9)*kmNlTkDV;oDYjCkNw9 z-R`Sv+Fv^Q%gPz#SC+RVO@~ODb)|VcZlz(^NIQ|LSn@@FKKtbyOC!he$S;VGXy9F4 z_Xb^B#5ajwhq9V%%<4gXGYDXj@A>H9BvwluIZIb}E;Vq*<PizNa!#}CWg-(|ChMWu zMl);I1C&DGzL}3_7C7TWh_JK=B5O6DY8o{iyFMP-pSPim@=P0C6hRt(N=^FWD2cxS z>%Bq}dAY{bv3I%4Fm!r-%VXYnggZ%!gW4lIT(h5b(}`M2vR>^Z7=VMdWMeU%M9wn# zb*A3&Dx(di+_eZho&BPDb@4#mufSx(q=d6|s^Izcdgzx5`8foB*#!9VX(g(bPz=Ug zGr6uz^y+{^0#$KxFK3e?u^=Nl>Y;V4I-Zfoc?Sbed}(YalYsR;1{vQ;aL<EJP1E`N z%(J(SgsiMaJ@6Iry~s8$-!`umLj?iytZz@|KcHVapV``}15x_y(o8nlFJ#0kbB)o+ z?zDNG%tzTSs^sQk)JfoJ+z63-SJ4eei6WXe64LF4?57h+YthvF=Z`SuM(HRXCdqGL znGqc9(3;iY#5>LKjUu<K1Wx2-46;U(uU8J##_XufNbdBj`rF;)dgzH%-gci}-Nc`E z@7>f^)Nx{<1YF<^;RU=}e)IEXZK~4}!o$4lc9|-E=f%sz^E6iWW}O-=%G>B7Iq9-A zjCS>sQO-%_U7emR6_yi84=RI>kE0pbJww~P5R`SVT*}iSyg0r*n>x<GtmQ~nwv^EI zwU*kKC^7A2Jo*lM;{qOMxY&JX8J`xI9Z7p|Cihg66N?jARY|uJE8vyYZ|%3Qk1W;G zYFp_0&7R|GafUrvJD?#AXQCQElDc|$lP$=pbxgV=0IJg#uj6X^YQ6aD%L6O+wYUXW z^wz}gh?C5Y$G&@Z2-;Rritz_H^OM)*Eu({9t+xprEXNaXcTl8p9j4&@EbgY^L@bW= ze*WW)v@5u1?)~4t*Bo$HnpLYi)t($hYTmwRazCy0-*)Zza(%7;YO5;rVYtVVO9evY zeThxXjaz&h==F@H{p8gQN!OhB4)j|7+U6S_M@ow8xC3Y4hOV`sMEl7p>bvfYSMets zminPD6Qo)ySeC>HBm{@x2PC!S=m_2<&qVdQucg(EaBJJzS1HaD$t?}n-rA+<+6a_V z7e($95$&Rh<g;<50+eW+d=`y4k{EPYb$S?r%7bKQbzQ7Fvh-pY)LYoP|CFl6AXZ07 z5?!}>VDDMmp)hBOTsYE?HEa3WwIKU*litAfn^uk~uL8NNh#jbB9*w!1bb}5FuT}I` z)3@;FyDzP2EO$Db^KYy1i#lFJvK}OgTz_3DY=QROY<$_dXl4brRHH?BQ+4HF_A;x? zc8*ZCWQ5(5!}B$EN%eOs?57VpOqEE$)xBr)h_fX!Sl@A4<SPBG$+?@_k;jepw_@Q^ zo}HP-YpQWwgx}1~((Q0BrDa8->lF%F^F1U#GUWv5nh>ODg|^|l<3Vm$CjOY9S6#Gv zgm720NffHKd}Bybo_+9|b%NXb1j%Os^73LEpQB<fJmVu}77r3AMw-S?Mlg2CgwwS# ze?@wR!}W_0+q)=xWM~Z>VYGE&sKX2)jrYDjAF{uhq^sQ98(UTidq5v!w!kx6ma!ld zJ#S=H(V>L-GsdHPXq}0}6|>qund*M6+Pz}ocFH*8pN9;F>=Wj;ly2zPis}O}TS*?K z1%WRe-tVclJBbQ3mUtXp8d0vyp#c@wr!lM}V@rAO7Td*ZujM@qdy=)vZstTF$N_U| z^<^qBD)(jNQj=3l!}e$fhW+pflg=N;(l=)w-3<&C$DQoh?*=Sfu^Uy^6C=DEElY1# zV$2sC-6t#>lZtM)W+GV=G|L(hB5p=5bK4alN|qP`O#8z*Ocs>Aw+;CZL^&|}sP8rH z4zc((0{iC9stxuLH?CHkjvvXtnQ(t+NyYc$?$%Zjn;FEEjy|q<U_Eiw?cRrpm$r6e zCC*uqIwk8&ToLN_Jwhyp$=GJ>;r5N>5?=Jamgqd|RZCX>`5{Iv55NBH;$T&II#aC2 znuhE2kOPC-cIiaq4sd*^$YniwW}|N<-ig{sGXLYZ&<S+O9{z*1H0al0h5TPlu_yJV zdF8K5qmA=(xj*=k%_=8Uz6|2of3SGQqASAh3OC$$5L^-a$^W(>Z+uC(@KMl-mgrEi z=iFxO0fvCxRw!#~62_=aEs7d{^Z-x(M(3kwr=9m#j0*JAL9Grq%O2W*Yr7VTzrk%Z zb-C@ODgByNQJWpscRNTY$h?Rj5oDnE!uAX^^K5UvspviWT0i-l?Oq*&aDh`55BE_m z=+KU$w)3bT&f)>~!c3=ed@uV1fvT#TPy2(WxlFZdB+ay3*CQtt2@j3;{k+)e-0Ivt zJ?0QNORG4kh_F_2OV4f#^AS47hw$`Nw>YM%6eAzWIJFkP)L+vl@4@zr$XD~O1pDg~ z)}}XKMM?`ij?YNbOTOVdlbo_QA-lS!hIP<V9<x0rO0chYzb4q?`_z0&?lMu(=rY5P znP|V*hHpx?49C>aleWig-qKDGSBbGL-PtoLe`(%he{oNcs9)9U%iyckR{W0e6f$bc z$72jKMq}eHh7ap?cV}@=HEEi8j-4?sk^GXG+E?d2j9Q-GM0md-F)9>>-ZsB?RC?<O zU72I+J>~H28|(M@y0kn_>gHUe^XPj2)AzU?;5>xa&-EUE-ye%@dBIC;NbQS7C`KI$ zKChj}#ir>=mh$TPP8=K6qTv}XcV6BC^1(m19zwxvC8~EB@N6RM?ds4^Kue}%?sb7D z^&Q_dnXb^cG?%-U=tQ0Cv4?AGAiCZ6iN^A;Rm@KdJx<;WTw+(S?vo!qb3xTAH6BK= z&<EcTK0&r3sTSfO6(($gJ4CJ)BgKf+p0bv(U}p3&y4(jHr*14=mH%MsT6)8UZF!H# zGucxz0|VidV2WO<E92gSZj0u8f6go0oL+i6rdfYCYl~bf@ah{y^7c#2>u+27u5t1K zt&)A(>GS$dW9sib@(Ufx)%(gw!cspacQE%|lqgYtoHoi%dMJi8qrh8DE=)b6ZdBTt z5wpX!Eap!p-W-j7^X`JoK;<FTIK|qg@|kh$DefsV?A7iLoJN|3WfDtls{V$%_U3}F zW&1nvxiw+MW8FFDoh@z`ePr1*g400)hCDkeO~)7WWp8(klzAhKD@2@;k22U~CYKkh zG-0A-qPJ^of{ceFF&N-MUP0@0Jd5>36+<~!=dh_mN@&&uKBP0ISCAOdyIsZ#zmbq+ z)Nb;=rmgAGcwtk=qnmYFrv5zgyTij(>-0<Y=c7~IFvc5q8XnSSNHe+(R%pN6A#-$L zfha4ca#tBQr1SQsGrq#|k$7(1sdX}s>M@u0Zr9S*HbH><7;rwp;kTuu@TK6rq0_OW zZ;gHkTukB6ugLhU;aU>jcBB-f{0-N^vN9jBHOWCO=S7)t|COTXr7Pv3GfL;#*D-I0 zt!of{!Zz)_vd-c(Esok3uZuEZ!AhPFn{S_LYN!=$oe39voUWz6OAyraSgX!5Tb?tn ztVmCUeb)KPwB>tCD5z<~@AN?L6KV6Ies_^GjuX}1Mlt1a#)c<;Fq$PtTF1Lu`K5L; zJnVr!MLb&@j#GD>mLtXv4I@I5LfjQyQa%nB(AT=tv}r;gEJEKAFGQLcZ#6qswF+hc z5f^+UEs`SWVZ*kMuwXROIKK8HnrW%`(qnpAW!k83k2P$Q-=rt2lv2qGlZr^?9zx>G zzU13mR<l<HH^%<lqmO$hdv>9|oO^gCz#k}VuAphQ0&m%UM)^91#`TLfqQ-PYhonGm zrqqT<q%_p*Yq^2qX>%u0{&R1Cm3P>N3zym&<)<$xxR1+qRX)ts`{0%(T*IfHsb!?f zuxqU|c{kYc49NNrtj{I&O%i5?>mJlRdnI5KSjvzW@Ra_w7@bYCtFhWuG(Ig&h~QqI z!A|0nA-UFz!~HK><J`jC5@Ge6oZF*(tIQ0-o%A*Mx!|~_67&;}IQha~bh~(kx|4Q9 zChxP=GRxm6Fb1*XRJwZzb-vR=RP}9j>OUHb{N<fE=q~Ox5{l4w-(vsleu{8cXAKp3 zSDjzyx0cuyA|f_MzUUY9PU~HIUlV&&<LJEj8%g;`;&T^AFKpQ2?JgE0&j{W3&6KfI z&tLTM5tqSTxP@)TZdPNcCJ~MNdbgvMNtK#IOQTLK-Ww?W6Y+jN7ZPHusJO|<fL9!M z!FDUjq-hnF_<Beu2>YbjqqzV54OR(LD%q3?Qf_qNB6S=6ki970#j~9-YF?)V!9mA` z#^-5uL?1b(OvyI;T%E9EoO7_=EUXOzN6Q;dYfNa;M+Dr}UO}li%UpRGNZjcbEP>5M zN|VqV%7L&xUrZveU6!&SM@G$?O_c*3%qBm7p&R?Pm=bR1z39YR_g;Iu<4H3Aq>74B zd%^w!NV*Hv?8~`oR5E8b+{@k6xo2LbZuqqw`fm`>sitG&kEboQKZ#mcC<7IxTrk|e zi&Q-rXZ|Q`ltS!?k0OF_yNy++v{}VI#W|VvhFNG&H4@<#yl@B3IkogqP2m|rXIH!a zXyG&}yY@hccvrwhd!-5oScS~Pv-;J1-EHJ}6SEg5bXG~_%B=ah@luHNZ9^UGP@UU! ze<RwIbbxyC^H9Dc4$J^gBjdcgGpotX!>y{X!IYe&YyV(Gd%SH+vEs=!7b5HyseNmy zZ{cJMqm_yu+vae^1lH%tX;P-!9n{6}1~SMfmsY*<%x7K_&!^{SyjPwx^T=B*K8csD zCwvnOVG_~Cm7ZMUlp;iM&n+SmW-(N)VMm1Nw@{!|3eJzAbNO|Js`-dJ%&?E!5oGLO zauOeyxnfRShp^uv^&6TKMKEsD)K(<4vY>Qu=!8&;D0!EJHg3koz7lXb$&+R4R`pP6 ztUp-Zif+ooW}~L1(lhSZ^$7U9GO*`#t8yv;lWbZx6ZbvGWYcg8o5W!+aqO=2++R2f zsfRIGujHKUm4oSPBR%^{ZIJ{<%rwgN2Tbpv^dfr@9d1gkE#Yic2$)oW$_Ut*mJzW; zz?N*kH_Ihp4Z2pv0egi#a!!Y(^^^TFB8}ipz!(0^yEH^#zc7kEI^y#~lRvrgt2}iO zu7w(6!M*F)KdI3_pi$}*tmvf{ixBpGY#l1JsQs0e#A?1VaP7Mv;_O-?NsIL_PBxS+ zsOS#UBx(-%@0LQxA;?mUp|s}%1_94hJr%j|JfrNx+tM}lMTG6GUo`3qxQ=58w}_nx zQ@021$0rw;stC7x1~>_n-$vFqV_Y}G{pY}!_2+yi!na#}`Fk?Sc2uGQY+ghjy2r|v zX|zEV;T648t;!6C;Q=y18!CQANl|OZz}9CS8;r<G)=#e^PQavs4Ru!fqzQq`t3B}X z;@B9ky?&a~7;UybnBM>ynnk*CWCsfgcVMHylEY5>x>J0eTl+&rl+(i};_;Uw<_tHJ z4!(<fPvwEb`UJe!LI|;wa}|k=v)^XF)4KZBN9bs<+BZfrc2FfYtB<r<1~I!2n|C0w z7nzWv)H)Y;pK2F&TkA#D)G$Ih+i5Whh<W#^iEG>aWvwI`hY*i>vIe4cwZum59NQl_ zsyeg@BU9muRgQIX9X;KCehf!vU$Q@}H!*Cr@yk%$X<h!}=u|5gUCK`Y`?ZsYGYQ}7 zuO&Fb$lr@s8;75#>7+L;1OZ2)%7B5xBm=yzUnM!;d;S7VK9g;vKRoJ_qtE=4wkEmb zAE*9QS3miS1=S4?um#*Axyy|l+&^{Hgr2>hf?u|3bF%LW(Br@SmHF_DmptUBR9RP) zI&k8^^bINc`+ZVW090pvH19s=-h5iVtY(bv#5(o?*q@?8WN+#Ok|p?NkU}U*wr)nc zt?e~qi8m{RU=wu5C30uGzl|;Aad*mv8?RxDHo3wnO*|43b@(f>7fSZYxhE$!2Pglh zvhR*+Y76=eArwKRsUZCV!bPM>m#&D?6_jcSO79?{NDGJs=|wuyi;B`aLO@V@ml8?> zA_0WZ2{p+(crV`dzV+7n*5l8RJu`dew`XRbGc);JF-`y1-L<W@Dsaku8Zkw>kvq2_ zu}7;hPg^@gn*8&Y27HJkmY2^-`Aj;MQjp8#{t%V&vvE+)znl0f@5g!vH>tg!L)p=% zBqvYOEM^a9UNeAzcO2^Nl}H_x3~d{y!m0;W?U>(v39mfwcQ$cqNrFYq4bbN9o!|lY zs(`U+GrvrKYx%(9Ti?&+4wSuBV&8Eoq~mB0pn;LD55tA1x}MHanX9#aOFH|~$){ve zkac>qcdp1q|3VDRT|)QCV5!^MT83_rj6+-L&EuT2A+bA@ogHI9EfdiDtqY8wstSJC zu~|HjUH^l5C-mv{rOF%Ri?=dly>;mM%%Zjp%f)CF#H}2e{1+0R=yT6MVAJ9<x7yH% zNp2zx#o*rab>P;bpeB@`>~EhF#9`@O%`wdB!o)EX>svtWp*;^+{IWM^(>hi($Qnnb z-!N2b^CbLBl$aZNldd(!7Vpp;AYT@GI~qbrmp6V-pR=?*-azchK*U-oMy>{~AN!9z zzs!x?=}rEa2tL1gAl6k+!xtiK?Jhp`vp}=)2oF`*bj#zGzVTgIBiHG7w+@#!&ko3d z?8{GS;OSM>2iixK>OvIZO8DhGwRz%DUWy-~3MH!7e(B63#6_QW_U_K*>Q#-XDSDOt za;3nXx*1Xci$?#&GE2?w!V+C`8qPYW(bdMJ3ZawQnSLG+;w=H>H20a9fUp%rZq<Ut zvVqsX+M69M13<Zr?q}y;3p~;D9ev(bxlg%Y$;5`>#T1R0yya@1UkFpK+YgD-i<uNI zvM5LENip;J`Y)QXPsh#nNw41k&Y0*VFf;!(lA0X{)W?0y0tRKgL5Ti*R9AOyu+MyH z;MI_0M&9dU5BK`&CjWA*vwj&<M}*j+FgUbRAHDB#cjw@Flf=(O?$4x}Cf~#7Q8Q>8 zD`twF96eMoPCmWEX`tAI4syYrS@9_1cf(gm2g8PdaD+yrA!~A+b79#0Ek+VIpT}d{ zNmV^lulbktt<G(%iR_%ctv#PjK9+@`lkQDGk^bZfqp->*a(~<{o!MRn9S4fiY_V7c zw$BI6fvznbukuO;xCi#7`0iEz^JbD4n8+)s=-jQ;Kp$u{JCpY+CPJzLf$<!m$Q4Vw zO81ujL1dCjHQMES-O%=4Z+XI48b=vzG7Ww#*)S>Hw8{e>th^CLSn0cQQmomY0n!~m z23K)5h$HviM5m5zcIMMl+sJ(JgI8AyU0Sb20@tCZTFVQ0N;^5j=Zq$9sJKVsy*wO- zl$(g}`>f287h_b`v0Hg>t=>7WiCiAgOem(?Z}A#!&qeA1<#oV|ZaUz#{|vKOWK{K+ z&bO~w>$=b91|D7+7+vzbe@s|vs~uWg=TCBGFIy+*4x#rSclRZD?X5n?`PE<+ma<}< z-ZaIZ)Mqe~Im$#|5<Wi{;*Tq~&B~^)%DIpqJQiy=D43Q|Wn5x3_X74}HsY}`N+Lgy z#n8yZF}bM`pUX~rXw0`?uah^fzSjiJTXb6`kHiP^U7MX}JkS^!Y(6OtRt#4KhH<<M zw{IqKM{%o24o>)n8V*%4s=u4@@3QCB3`dSo>6_?x1QU9YS0|IvIwq1k%S-hhJ4bEZ z9HBU@g2s3WL<{IU0XhfmSLCwiO{>VcpH}$o=Fub3Tt+dbj+r*Fg-YZ8Ny7UhJa)wG zaRzkqjEdj-G4-sYrkn!xgS7MkRMXxXs#z@0hSDZ-vcqwFIpsvOk1txnsRp4JJ}9%v zDPMGZ6vkG|ZB@1Yx=FBXXGrwut5}5hlI0gOGv*rca(j9Bb1pv$&QeCMn)a!S7tKup z`>sO3&SaaJN}{9RUO^|-#PCL&8!IlX6ll3IUQ(B!O1U7t@@u2By)VKy<Vv$TmZ(D9 z;}<iTmw*A&zA@P`c|c(`P&M`jP>^g|@3+#uK(nA{Pl?gd9JQ^@Q2g>iu8moO>p~rG zp<3NGUgTs>=%a+T`qIxHXkWY*@H(2O5b{v}^E;8833I?YKeou_eOK)kgRlZ{B3>Bd zeed&z|C{lFqJ<a0u=~6u)Z6m@CKGl!ptED%{x{mIdF~2;phXL2`3>KsK8G9+y;7;T zdGofjY&#|qh}{`?8kQ+irzbk{#(<$PwoNcT^AjiOD@9i0b$$r<Vyc?bkKp?k)swPP zjKU(i+*q&q@lAr7FvUQr#=Zm$Q(&_?ox&Wb^va)~IOccrJPgPxMj_ph?7c6a4u7$! z?@(^_PjHUkwq2hsTiEJJc_Qv0rZ`}?{k(4`z4mMQN1UHu^4Z69DZ*!fh<O3*dTd_! zbt_1y?!gr`{HFG037;!p=#}?FY|<q0>7@kQ{1@Oc;a{c?yS74<#sebjiCeT!&Fd;> zDFela9ZL~BYQOs-0XO0f9`q;fpZ}cLdP#}3bLjoO#wUvvO^5AHqDMX$2?bvU;hskz zuC|GzJemFB?5SimIO|C(5>PK*CFn`pgI`UR#1q>)T;s7=xb;CzxT1aKehg5Yf?V+_ zwYpTRzl!1;$Xx)BwDb5j8hI?YsSLjkdvacae&rMQOhsI+#?@4<5~a7V7PBRRxXHT# z3K{mhDP@ZxpnX1tA<X}($ko`w#b9cT^{9TVPwv{REZwP-4q7I#tEjjF6N)}o3z`VL z?h`rr=?>nz+TaYg(oXC{nd^%DWyLfud|xpE-slO~Q)kCswBIjXL1KoSI-65<7LhDq zbv4C{W2xmT)%)xM@~1*4RdFr0jDI_UGc!}qZK1%8^HKZ?I>>+@Hmtg~O_2p*%=j_$ zX?+v2;`rW&ndRh|>n-F?G9TA?n*i*Gwd7F`7Qa%n74n_ALVoKlJuu6?tj>}fO6)9L zEW))nGuOB=7*_G9bK3_Vk2({)m{|m_qTW<BGY9^{R<OB;1FcYHkH9uy@dx$9^_K~y znZdGtNI4Si)CjTzf7Vi7HVnyq%rhr2>E==}^kR?Rljy~Xd-B?z|DjjXb)bH^EC^gB ztjnqCgc)(IB_7rkSe!lF8PYf?w8%P?mfAzt`OM&PlXhYrI625-Q)vAbeU<XshnhJr z;7520`}I++Zrt!>2h*MhLxv|+V{}Y^GY6O1rgJ4Fqax$0*iD!{T|Gnto{3J(Gz#@t z_fk@kZ^{BQNN7+u#5Y3wu9z!|%@v0J?wg;|17SNq9VWRtRiv^@7Hr)e+{ElmSLycZ zOuQHnGqEcivABK^FD)yr5W~%<FjtGdn6S|>K*D;m9}I`}OsQ}r)8ulVc=HK<@B-L9 z;o4>w<u{S#$X`)Mva7p-FnaxhRY4VrqfeMEi9UgT-HA1pP`y#%+tt6TgRA*kE+gvC z9$uqtsjjLup&{8~Z8Pj*oc8)fd(D7fs<CJTRo9GJ-cQS_apWu5xUo)hTSuo&c9%e+ z#m;C_i}QF?>ISsIS0`Mjbu!=|iWCzvwF}~t6?+Z0)V5}@IgN^=(wbkPR<%<s;;tR{ z(_O`>`JLBpJVQBURhFOQY3U<#N+-R)7RKk`wBqxyam*C(!bh_4xGt>*5kf*^9K9hu zIsyb1G@dmfR~^@VvN)x%bp#_Rugaj_lp^&y?Xs3<;3<T3vp4shw61Yt_0n(M)n6m& zHOqr<^Jm{Yf=_SmRCQjew1yde&@8mG{aIXInqOfO*KK>N1X@=k{Y}3(Cql`|Xd`>& zaP(6HVb!vWWoFT5HijI6@GAEOlR=`jW+%X^wFbm_mY4->i>`xSdQ@Ovpm%vn?7~7e zBYIlAulUj{D4UQbrqmR_@J{sl0<Zfp#Y513%p&j2S{-dESey!JJc}P8D%j-G#K@Jr zIf6o#b37V%n@fL|L15t|^@f1J)Er1v9g#`&g>eeQ>P-%Rd4ZKtuS;?Ymgq8}M6DZZ z=tRr0QqD!eTq}~)(fIU`b0q@%GM$_Z!XU>KQnd^&N&AE-wtbzPS;EDByzKYRukFK3 zl^@6Td1FIQ+z{|<DEm&D`AqSB=?kB#lKD(1bFhhu>L6fyMzfvdsxInYQEE`-xd+RM zXQ5of6F}c+9&fT3RgCVDQ%wDB&tZZ`ZJ<sbYsv;QutcNfn=e+ta4JpftNJtSV258D zo6nI|2O+h~xp=#H%l0@b<6uW;aJL6in^#}=CL9Fzr}<0=(&bB0eD?AV`;cSx6`0a- z_v+4O>dcyMuL*K@_c>}!_h<J7LzNL4!9JNgl6!XiKGK4zc=seu6jDiyOP@DbH4=P# z8eR8eu>)J{`o!v^(yhOOLEv@%*s2wi)LQ2>f={w;Qa{(DmuqjeCKtX=M&)))w5L2= zYUFA7YB1_5n;cs%5!c#k$x~B5TH|k7a?z+@+n^{=f7%CAb2o_RgqE5rOWK&Xt1DbD zzE9Hu=Tse`KhodyDx&o^Z*cI1JC5Y}QHBCpam57VK24W*=St@V0(Dr5Y#O9Q#zieE zTeC`PN+s8|z5<iRq(h3hJo!9_pGs2`r{z-H#-A}UsDeWFge@C`bm==LSENma6LFJ; zW_i!$J5J31S&U5b`{juzA|r|A>}hT#oXuBUDFShaqZIcMo;cZ>yW?MvH*z`!+gcZ; zQbPt46T?4V7)RTZqO*k$H!$G<_1U%yVehA`WV6ebP*j!iNAE_WMScqS$o}2`S8$65 z&1X(>d*ugqOW)!Mo(YQ0$5`$9rw4^lRWH7bWf^6zs|Ul6ynUwzT^T*?@nSxg?YKw8 z%_sr2w3O3u=*sl>Z%E5ly?908AV0zcCpemS>aLYrK$XvuLA+_y!K%=oJ7up*QVV9f z=M(0K$5DcuE}Tps^K2Sad&7_T_-toHB!Mc^xBHJO5uQ%N9ugDV$uA|!<^%!U7qu{2 zgLLC2Ge3!a(ni4vSVU$mEKFuiu2eYd1qi$g;U%+dV&UBR%(<5=b#&aX)7iUn=@PLX zzwOw@7SP+t9JewaI$TqM(C?i<3eQa--Df_9262_%1knA1QSP{J9q(7?1t}uRTvlpR zl3|4})*zFRjDR)fFNR5j;Fo}TG5R+4Ja@KJ(dQ~Z>y%-z-`{k$sBT<v!Mk})O{gTu z|5OEN1+ch7k=mt6`9f3teQ#U8;Cl~u3Ec(=h%!eAC)uoi(@ifZvH^{WijaNgfoN!k zv3^(b<$2QMT%X@zgdezinBggj=ps_c9jk*vte6L}LinlvvX$Bfi^TB(m^MbFrdqLv zwwnsDRtN<zS+?ubH;#ULxDe?0dU3sRysljVvPi{bPTAQ^P@w%|h1iqBsx!pi;b2!8 z_X97}3aCg;g{Z&pY})n>2mppyu#KcBN>tac^NAy7%{6zCYd}*Q7Ljj0;_PHf+inG6 zu%`~W1Ck>+nl-2I_Z#&}KRy~YfE7&%Bwp0IwnYdF@WYL4hzR7<x_$EMshx92B|k?| zsLy|S!Og-ynndGG7!3L`;nucSEI+^(+@g8G-6cWq&dS;~*>??~8)sc&R}P^mCb3c7 zFMpQ)3~dTZ-Ssyh6>l~%+MAHEgBmPL?_cdwZ_Quno$JRLd&(9rZ0=jt%lnQrPvbzj z2mpe1M!pU%bQOq_&j<G^IfohiiP!0a08X1{?8}Ps^!)s84P!l|AIASGlXjO3z<l=Q zgO2N1JDeNW;Hq&(#{fsFU5KFzRA?aNpeM~;7r?@g=ByVEC4>%-p!i&=7>qkdig<xu z3`DBZZD*@Gxq4P>l3uD3U?KS{CwwGm>>29r(J6~Z^Yppy*@mYdujE(39Fx!DrX(zM zm1)Qz=m$JZAV<|jJSDo6hi<28C_|{PQ|sy1=p)b8tmy5LZ@UZHjL?nxPkmBVSl219 z?IaCt^YomKp^Y_T<ILLtq`a92y|rTKBpEiuUE*rqHdIgj_?{~zElaVI_N((^LlC)T z5a9RP&ZvW1LdW#j6=c`eQS<{px90|M=DQi*#Y+`pPPW?ebRd-j{=cPj=<*$0SP*9` z5jbnoxnF%N01Uz)UqE*&y+$jvshW@M>NTA!_v~t2UFrQK32Ry36i$3n8!bS-Ok}$9 zzJHMuxPG+y!okrJW&uCwa^$B}dV60Rj!LFwQLjK*u4XkhiYi?`vdh^AT-G|YrAE7O z*--@}Dm)@=04;9z6d0tl8Y;n{&70!83s+ek$FWU&Vww~uT%ae%nBfa<>%+zy^iYEa zZZ6{0HTbgCQKUKfpbaT0Nge(93|LjE$cn@(iMYgW$en5j$nQ(>MFBQd!}(LRuF%_c zY<+9BVrJ(ZF7ncPZr|G#^OC0`^d~1-gDDIW?Ej$GmiR?2U@vnfp?TUte%wbnWhW=F z8S9Qh3flJ6!j6BqIJj~|iiS@HhNdFjY<!=Cz|AxhGDDG@=Kf6r1%j8Cku&Qn#yMze z9(ORsx$~d~SJ-YnX|)+%?bB6InanF0<W!0Hn%jA>jn|l%K120krDw&!^h4Pi=FGAF zH)D<2o9Eq4o4?3XbioFuN|zc!Rod5kd~Se3=(Q~|pt71N<4|OPzXfIgIrV2Mmpwwz zdAE6yhY!N68*Vs<+7mMn%3}4xwrZ-LbuUMVt@OY_ZjmID#XiNRUs`5ejU7W9T@1jl zvKc@jdJQd^WZ87YhqdbyO%1JCD~ExbH}c<iT`ifM7YItR9Dv6ytu`#Yx9JKz4+(x0 zCpeS24jc+Dnh6gCHrmI*Pjf6BaKz1_vjc4_cM=)pmcd@+s{XH>uKD^+OSZy{Z;zLx zssy5KNX?Rso%J>_xJh;ou`jAubJ4P>8NQN12<4{c30CDh^W4Rv=}Nr^V&O$auS$Bd zC&|0N`FoUS$)0jQ9}rZd1Q^bMs-4DM=EtlJo*wQ6wPrzQQ31u99&r|xp9}<;tw}o( z4XatArLz?XsW(x0Snwebb&^`RDuZWCmbx8p6(Tc}h={dXmyDHj=qsUA0NY?Ha2&|J zP2E!@^`bcrbzoY*JsZ7)^$YFILZNT6_@RU9UaZ}|jd4A&twcORx_eap&6(Wi&4YEn z)QYp&kOfoo%to}VwwW#;zZ+RQo@)pVe6O&3k`HC5b}J2Hmf;4?=^Tl0C$sR<h$q`y zy31X=6Ss5|<_yHDOUGID8xh<p=aK>)WTvPaJ=2uFD=dtn9>|lpZMDkeJBg#eHd%pq z!3f|Eb-QwSdephr56BK0$?*#jcl80I@|*|Ys_BsU;%j8rKJ?98>!Ty4@eLOi&yY;f zeMNbptwu}}VA{62jVEdqGq%DEo^_s6J#%ir((FeRy}BjlXVgNG)&fEYF<Y&A+z<qv zKk6MTn0i%=0l!R14jT(ES{O@J(X?~2`0!w4HTCaObi4=~=vR(;bNy@X)=S%x9JlkV zNP18?8~t%%yA>tHlK{tdrzILE>5^Ilec?tcv%k_XS#8%ip*mW01<-g)COA$laI&ZI zvr)O*phl_1pzTZY@MiphXWVB~($3Cu+A54yN_61rl)_?C$;BzlhHUqN$qjx$(}N(e zt269r`Be;QZ!cas@gn<is>kr|<X6gfG7nA|pSub`MEZU5ceTJHj#hqpMkxNP%Rvpn z<!f9n9KqpyRHN^q7zKEAspr9zL4HfV3yD9%dzDiXN3t@LrY)mgF)!<G+y`>?A53A9 zWYb*jIQ(CtM@6j|`AUe<b<V3tOpq6?Gv&4<Cfze#*h+Zv>dQ`fAOOmdxl|gU-pow- ztPN#2e{|~{Anw|=I%AYxwn<I1<lH#fHW}czX1_I@^DRLv)v3_!&``v^7mC9W@h%(2 zM<qWJa(B+A<5YVeU5|Il`XO<$TNCi)QmU<E;3KF&b4F~wDcxT{ChJl(<*c;FMmu8y zdp>!RYf`ZQ5D=NsbkMrr*Vq^2+Q=b#)1-0!l|oTmUUbwDE-wDPbu3|I^IGqlsax@e z09||VOxsMnqh{B8qUDb?+GE!3aeL!%;H;=}fMq~%`Gy=7thGaheYcX8YgpUVj}5~Q z0;1mogOCIxe!H5TQN&tCb32axBMOOzrHQEZs<k;>I`QLCS1s98>G1H3EG}<+>4EN% zjr_^S-0xJaneGgl7l*)h20ajL$9?_bA3ugYM3zKZyX(Q0*WP%oW_f2>d)lsMoh$T? zv#F9J-Z(*#mTIVyOXWjzjg9fU$*;Nr9Wqj@lea*XTcVCeir{_7Vq>4D_k6V~5i>Vi zdtq#YhkA;kfEa?=Z4c~g+14BG@&T6`wva$_)xC0`bxME2uLeXKBixEK%~{ELWM|Y> zi&BYV1LE{`AWj3QI8i6v<uW_a5?G0j2rpl(wDZZ@Eylc)GKeo>hvIuAwrg`rBofsC z>3~oKSoFlz)uLfTy=P3J7wX|ctb0X0Ep?%*SqZZzuHiS)*%(z_IhIfGgjDW_S6(YV zW%{_s5-4+++((4cS0IM$_G$m62As(u2=5BWabbF**|c(Edqg5`sy6h>)T2P@`NM~J zHz%xEW02Hjb%FA~q=Q>ZzzXE5+Z9v-E5=d^fyYM(%5@ai@v`Y#5n~bK0{2oL7Lxl= zbL=H}2#X33-+prn(YP1}CtGQ5-Xq=4AJEyK5Z?D>FC0)#OY9eZi$8MEh&{Ot{`2MR zO(27uZ9viP7cOt%WT*CBm!jRV?$9r-Fl<rD#^bS`D`Ia7D(<7ql(JSaNeuM=t^<X< zya?dZ%<%1TPDgZ$m|Rn}?(lb5QU1D7mXbDJtbLB<kA6a0qCxJZnGb<G$|~jyJ#BoK z4gXA1&6HpqVS84~@Ybm;Jm)7EL1PK!l|i~2Ma(J}zhUmIyO#zEwZfDnen*JkT8R>J zp9Kw4_^AXOgzlu3VD8IYfK!cMr5j0s#hIO4^#0M^cN&hrLGa3;MUsSAk!VIdTo{V1 z4pY=PHEjUXge(X?PwbAcN#%Z<yv9Bwvt49GCV#p=GRQIWoi*vu@u;JzkFHvCL28F8 z>$Mp1zaR)A)X_2Wln(^#B^fNUZ8!D|_0F~PCrM9hz&*xV&xUocgT!&Vvlh<~PV?6K z^#q;EE*nKFgk55V@im;lK5cS{N9o)jBn1Z}zzX0Nb;H4?#)l?J!z1y~wHLDkNLuZv zKeqJ)D>MWP_gpaD_fVrD8ONd#*HV$^t|4|e<W5rA-;mt@8*q~e%lYR?GJ<Rni{rMh zpCk~y`@5UN26m?+S^9)z)5>LhpBf(J<tEwOfgfk3Lw;NgMiX!uw@#JBu%XLyjj~K= z#Cm1GnjRy{xBKT`=R_Hn!8J}`*YLpwe|J@j*MFD`lzIMTKjw?au^GTlxy`<X@Lp>1 z@e>sLV*rK?gJ95LPme~ypS@*?mQ~X37bSmHIQ@tWqR7BQzSMdvH~jQSsAhnzLG$19 zub$FwAt$>Q%=M7}L)fVZ?Lw*`)*=C$KWN~h9;8_P|0hBzuBY35;;Mdw;{PQHB-q2z z;NpKs2a#n{vAn**dkRAj8u9;~$p73<$j_c+F&j_Mk<bqYe+~yIL=G676kx&hTAjn@ z9_1;^lLV*hNxcr`U?}aa3#V!ese{D#_4NUShx7jfA$f?kzJ3hVX#O8vg1{bU_{Yb` z=dVOO`49Mt40o=PwTBj~|3{CN!h}j(Lnr)?G6EQQKs$3+?%h7M0*?k6xP?_h2)OS2 zLuo?|Fz>5kb<RIRu~JZjtlIPcK3&p6MFv*oE@ARINvD1<dVHP-6v>#7`$raT2sJ3M zPU}14Db=uh!Jz+DkeX)^|2L6N(4l+cJHAt;G30^BEF)9S0}l=UJup16)6>&CIhp@4 zQsogK`v&?3(Udp^Ua%M#PImO9;2rQR;vdh?kO0upi9HVlrGM%0s)Ck!5_2<8*Qn}% zA;A)A24_!~%tojVb2NWX^!o!5>UN&ktI0hQ=WjBet^zI_)ch<gEP?NZf2W%Ns3S~` z2Zcs+-IO?g@)+pf*b@OF2L;v}d<UMk{rfFVKtTd`!vDmu07k%43tIP1(#hX?1~!HV zN1us*{71_$2%w<<v9U`nDLg`yr&Kp?1)t3pGY<bxYzbic%yJb!)9aM*Jl0dv!2Rmt z#PswVYnk-K`&ULgck^BU+mpl@`yXPc;bC5FZSCA4p465U>;D+otA<2H(V1FUBv}h2 z#ECWU-_R<E|5Ql%jN?B7+|j`i>qbUKKl|S*Y>{TF@wS7-&UPT+PxF?ZddUsTXa5I` Cp{M}> literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_quat_tpgmm01.gif b/images/demo_Riemannian_quat_tpgmm01.gif new file mode 100644 index 0000000000000000000000000000000000000000..f9d1de0554f27f5051352e93c22bcff263304fa1 GIT binary patch literal 115802 zcmV)IK)k<4Nk%w1VF(1^0rvth008m;{r~{~00IEX0s-p+`2_<5{|4g-2?q!XtyT&3 z4hjAa3JVYmn*<FEoelF54haPg3=R$q4i60v5b+Wb62ub{6ciTl6dNZMBQzJ;Iv8ti z88K2BcAy$7LmL|(8}T9>E=L?LN*pwS9YJ*;KV~69Y9T{wAwz8;P>mu)Zz4!_B1v^4 zKxHLJc_v49CP#TDNqQ$UMkhyfCrEZDNO&hncqjfWC`foHNqQ(sc_}YBDKbGWNpvny zfiE!rF)X7oEWI&cpE57yGEH<c=ruD-l{7LnHgv={^Ex{`w>w;kJ6wr7g4;WS-#dig zJUrw)LsUFmj68?sJvlx<h1@{RS3$^`ME*%eLFYz9Nk~AkNa9RPO8!kjPfb&)PEP1f zYLicVN>A!lPxDk#S7K7#S5{+zS5;hDShQV+w_hryUtH#2U#nsMWMg4rV|A5dldxpt zW@PbaWjQEkX#Qt(tZ8ZAaOrY#RjYJy;B<0yb?9|=bgg#&dwP73dwY9)-En;EfPH+~ zf9rLB?2Lkf{)VVPhyIF)fvbs<sfn4oiQkKj?2wL(j*oN6l9BV2I<J(I)R~z6nf{xb zou-?rz?>>qp6#HYu-2fgrJ^n<sQ#;|Gc~JFMy@k7udx2HWoNVQv9!C<w!Z4O{<*lg zy1G(RyG2L5r>wlgV!kIPz;1oO@xj41Ji$#%!GD0lXlla?4#dI!#Qw#`kC4jB)6Ixm z&T5p<@zK!!(9zfE(z&zJzt7Zxgw(;o)W*!z)6>+`{@iJ7-TvO*?d9Q8Q{l_c;!aBA zH$LN8Tjbv4<wHj23JK@e*5~H_=rA$prKjoW>gtb>>;CTT008X(0qqtZ@VK?{e17t5 zZ}Rf;^#1qs{{H#-|M~s;`uOwv`uqF({rmm<{QCX;{r>&^{r;$^{<^&W$;|%O*#70` z{`B<z`TqX={{H;`{{8m;{rvv@{r>*_{{R600|x&Y8viab|3E|kRaO6GXa9PA|C5#f z{r~^|?*IS)A^!_bMO0HmK~P09E-(WD0000X`2+=I00ICk000002n65(00{p8Z2|ix z%~mBiXA&x0$grWqhY%x5oJg^v#fum-YTU@NqsNaRLy8=E296?A(*BWi*RQ3^moQ_> zoJq5$&6_xL>fFh*r_Y~2g9;r=w5ZXeNRujE%CzZCmf?cgn)mDvk*imGXx+-StJkk! z!-^eCwyfE+Xw#})%eJlCw{YXiog0@(kE><i*iy;Tso%eV0}CEZxUk{Fh!ZO=`Y&9! zVsNnbz>%Y}<;$2eW3Iuuv**vCJ!>9aIdl!urbnATt$DTT)U9D>mOVT4YumAL*Vet6 z_GQ<(KcnXT+qY%lyFuSp9$a{49XfjC=;33}E^qPV{oB5{yZ7(l!;AkPPrkhQnSJ|J z#cBh(4$JRJYj&^0_;Kd+^Si&SANuJ2@%`7IfcnV?Ac6TAIN*E>KGz_F1wxo0X$MM3 zpMnuOm?35rB6y*N`%(BHe<Q*d9}YSYamFt5WG9b2?!+kLj5OA0<Bd4xsN;@2_UPk} zKn5w~kVF<~<dH}wspOJOHtFP(P)4aEDP{OTgAFvOFoOyztia`#D%4<uXYJ8vgAK*4 zrly!S;Na$)a9TEIXK=y^+L?9Mc_wFg=J}>+e!jUUn}NCsXrY7l8R(#%1$t+jh|Z~~ zpNB3gDWr~umT97x`pGDrlzuj8o}3nnL#3WxYU-z)W%?*<Ib8pxNk8$pDCMoV=Bn$i zy!PtrufPT??662KVwVdu5D~_*%re`Cm1mxr0}0epn**#lM62z#+;ZD$ou{opf_u?! zy6v}ivZ*b)f2w<K4SDkUZoKZU3op3!&PlJg_mbKzyN2cq@TvI@y6?RBcB^l~2&c=h zr4KV~@4*o}+;F=Jn>#UO)A{g+H!YfD4zVPcZ1Tw{r>yeIEVsO4WYXpEf+Ej!^GwY* zce4l!{#7<Z9HUrb2^=Kkz;O=mwO5&cZ2G4IWj!-}8q+$U0EZnc&`{rp(jpCAv`a&W zgTiE&ZT8t{r>*wdY`5+9+i=G%_uO>L?LrKcogqy*<H-Lrvde%6F8JVt7jF3BOol<k z3~0JQge~2SQ%*VXn6pb6cgLW44lR%}iXw|x5{3#nh)XSHIFRrHwKHUE1GOa-Z8{02 zzo3H)B*Z>$4kav-$q6gC;4|zlxbV8^q*G>k>@hT2sJzb83w^(#e(EZl1E&j`x$<5g zef4u@Pw@1nPA@*03wsah!QF?t{qxwbk1zS~Tkn4SrpBp58Kleu&pYKfj{pZqzyccZ zfCx-rQWQ4>sI>qN+bD-Q$RUq#sG$Wph(WeA*f}_qpaq$TLkoHkhS1qzaXzra5<s^E z(&YdSmRJNFOdy3tEJB5gP=w5g5Qi8_K{_N*#4i6bF^UV$poTUi0t{YY2PynPbSm%x z3BnM=8_oba;&T(H&KJK?>FH8jEEV|Z=Pxoc%#3i_BK0iRK1-nyW2zb>{!;bEfQiwK zb7UW(B2`C%-7$Za;omsoF^_*J@Q{d1q#_r|$VL*y9cP$~>vG@%OUxri|FA_5TIaRO zbWRN)B!vh`7(+{la0$;CMd&O+1Q&QLhM72n9f~2eS}tM+p<Cq=aJPtEEJ71@D8UkP z8ABb+z!szsS|*lY0vN7Rgc<^nG^a_;YFhJ}*vzIjx5>?Jdh?s$45v7+X_*)Zl8~1~ zoI2OZ&UU)<o$x#oIl|Bbt?7UUGCRXFzCr($JroUTl!<{4I;TpZg~0?bDB&VTL5dRi zU>BC~!Oxa30~grAhPzM%95V61U7R2cq#(i&6=4Zsz~KZW2we$O5CanE(}tEPh7V9c z3R^6p1aUY+3Br&G8MXj*@-fkdqS-SK1qeh%1rdfOWYnd8sHq})DpHS1RH|~QL?n`G zRfFm^tzOluS!F6$WAM0cpfjFmO{-eh%GS05Yo42|0S#!NxfU$K9RJ{`4`9%zx{@Lo zmdFGgRPX{RWWo}r*u^M>Ns2R|;Axw*gC&Aij5xr76eoy7NI@!6TOigFOAuG+SU?0R zo<SI+FhwR5;e!*5f@sEsK@3&^hf)6s)-q!Y-<o#I+ur*2x4;dqaED9W;u`n3$W5+r z14)WO&SM^qjIMO2OWo>P*Dx`nX9Lfq!5KWX7*gQmT;0S$QObY@tt){dGEo8!*kKeV zSVCi2zycq{0EBU9?`kjGf<J_`wnQLB7-9#9CA^?_mWUnh!mtY#lz<3oAi@ep5eE}o z<^?Dy!5J)Z!3-+*!ypc^h(}D~5}WwM&Usup(0Sb!yZFU0j<Ji~q1~tDwg)NzoeA(6 zEzXn|nw24eGlAC7CG27eEYKk5LKg=iT9y<oh{G<FHRTw_!FOk%-A1n*1`;g6%Aq5I z3P|yXalK~-VYqS+7lFa%6|DbmaE`N_=S=51+xgCT-qw43a88lE=tXV~w4et~=t8$O zl6~Tg4p!g;E0tzY8tj20MrSmiZB(_2IDroqfn*k(X|9S0+H23iW>OPjm?tR1LPd9i z9QdFIb}&T|TfhP;nu3+aT*T=7V}dY<S`jNi)0^{5>|z`H*vL+{u`^iKTFnE{hK{zh zr%ml@4~w2xa#LkqfF-TzmNVCCDGV-ygV|PVT=Zo@WunD`bCZAtD4_4VS-{ekq5uUe zP;%+2b-USBrll*WbY)<0?r)*^;0RB+!WYi)gfn*><9M#MCr<H-Tm0fa(yq}67B)4F zMsxH@a)9^*9gt^G2R#3yPYm+&CLP2;Y1uleo4zI~=)~-v<7>Fich2*k`y9nE7i7fK z32lrU{pd(fx?1UZw9;_(st^jQHN%$Fuvz`-SkJoFx6bvhd;RNR54+gMPWG~!T|Q(T z#XtJO9T~g*?QoB~+!I4%3@-5nE5Q2<R<MG-_dV}`$GhPF?)SY9e(;6=``-@_c*67D z@PTi9;ujxzy+8i)j7PlUA<y{4CqDC+|9s^)PkPWhp7M+*J?bMrdCrf1@1pN~=rKR~ z)4N{ts=qzpVNd(iw|?}NFFo*WKYY*kKJvr|{qI+w`Em1a9^}|g+viUG>RbQ%*tba- zmLP@hd;k03UxNSm$1i^Hf1mv1H-GohpMLdAf&JxIKm6lw{`qrX{_uDI`}6Pq`S;)d z_{V?sCx8P;fahm`2grW<2Y>~rfC1=$4cLAUh<^VEf#Ju15jcJoXn)^#2APl@@9+*1 zr*tG(f+l!^EK>$Nu!1bef;+H+FUSKi*n%zygEmNmEf|A3h=VzJgEPp3J1B!ZSc5`X zgh1$nLx_Y%c!WjxgE$z3PDq1Ln1oGugF`rlSEz(pScOT5g<BYeUucC)2!>Cng<~j& zWypnLxP)m)hE%wMT3|`y5Q0UAf_8X^c$kMyq6HIx0Dky~fEb8^IEaK;h=zEGh?t0q zxQL9{h>rjGh>#eGk~oQ!Sc#T+iI|9pM_>vn5rTU7iJ%yYqNpQUU;z_wil~^1s<?`* z*ov<Bim(`qvN(&hSc|rJi@2DJy10wH*o(gSi@+F+uxJ6B_zux0ec6|c%D9ZocwMC! z0TU1b(m0LOSdG?rjo6rt+PIC}*p1%!jo=uL;y8}vSdQj+j_8<<>bQ>Vc#Y9G0h`zl z<UofoGK%(ikN8-E&lrvE*pL4Bj{q5v0y&TbS&#;Kknm^<@<@;Q*pLqSkknR+r+APQ zS&<fbkr<hg8o80<NQ|anjDA*+5IK@0S(5N1k^Cr)!dQ#YIEyVwi!Zs7GRXiFK$A8J zi#PvCldqVQHR*~xsgtazlRW8@J$aL@D3nFHlSv7bsK}8{DUhe=k?$Zfe^ZAhd6ih1 zl`6B3(>MVT@ReX0mSQ=UWLcJGd6sCImTI|{Y}u9&fB<h9mu3l<bSal)S(kWumU%gs zaaosT3736omv<SMfH|0XS(s-DjZe9l{rHaYc#O>$nUXn~lzATRfRgVB0U6){ArJx{ z@R^<&nw&YBpIMrwIhvyBnWtHrsY#lv$(pF?nycBGw8@#Bd7HSIo4UE1yxE(od78EP zo2D6@uL+v5DVno+oU#d=$|;<%S)0iTov$gKoM{0xshEtJo#>d5{U9=i)DP2Fnd1LB zp5$4cMiC>Jd5Q?Y0X@J1E|6~U8K3ewpY&Ou_IaQ9d7mplZzs^7{`sE(8lVC?paO~l zD!>B!nV$-}pbXle4*H-DN&~_60Zb{A7J8u=8Ua#C4k9yxTKS<M8lt{J4(Zv49MA$M zfC2=%qAc2?F8ZP{+Mgz10x2K_HhQBtnxi_pqddx^DbNBl8lyrwq(oYzMp~pMpaK*c zlNj2hPTGsm_?RLiqEuR?R_Y`qYKr`5qAkEBNBX5;3ZwU?0wo{>Q*fqenx<;Hrfk}# zY+40EPy+p_qG4L6c6z5@YM>Z!o!Hov+WDv2$ekSeH&<GyhI*(y!j;gto?ZW{0(knU zcUq=Z@C0sJsg`P~a4M%>3aOmhsh+B&d^!Q9sFKl$0OmN6+lZ=wx}8y~kb{b-uo|nf zikXXgqMPcexXPmU=AV-K1itzNP7tiZI;_N6tj1cblR5=XPz5QFVM&^+&>F2oYM@KH zsD5az#ApFbT8&$}il&;X5%8_s3X7}Ct)g0tR2d^yDXZ+-u2;E_@5rc|>ZtU30`+>Y z_L{Hwy07}$ul)M2{u;0V%Ozwg1e5x!2%E49yRZzau*#aLrRAssJFx>xu@+mg7<;iA zo3R|*pDM7Yi~0dn@B!NT0Uxl5I{*QG>W-<Xl1HGW-8zxcn5`|zq_6*2uGHw5A1Mwm zGNtbNvp`Fd@T#7+>ZOi)Z%CW8O1rd7+q6#mv``zh2CA<m&;eBttPPvBTHCP8ngUB; z3v5QP`6{(!TefC<wrHESPkXeWs-Xz*2LIp)e)tBJ@Byaq0e_g1+#0Tb7_Jsz3P+H) zedvcei2ziP3Knp!>Pfgw35cqSvo6btD-pDmTe%H6v|P#p(z>|=nqda(1j@R#qPw*Z ziv*hR3}LGRbjrD`+q!MrhkLLMju5zX`vJi423jz*Ig0?qxC2M<0W)g~dyu<$I{_#A zyS$44M_>zRkh{}(yosB*$NRgGo3pL@4}J4zmb<;&i-(Hpl|}zsuWCEK<eRnyd$psR zzFDiRY5)pwU<!+nq$|*`<y*h@d%yN;uOJJ%jsOUi@V0fk48LFsrr-tIs<+Yj0eg@N zrtk}LtD(SP3j`dv5wHgY3<$uhyaH?rm5{hpPzk1x3U7e79{>mh{0n=40D8Ns6X}r> zBz@m$o-#bcG+e_n0k6^s0Y%%ou4@7YtG+<IuuU)pvk(UyAT%5RZ#=xjn+vMyxd)C= zyKkTgAMgt!O9gkU!n>;lm4F5#OR^ej3TR-m+N!+Gs|kSMhgkf(V2s9IfCdHpwvOP% zCR@Fvdc8cWz1_RVe2jFME3ZbIqWC+=_e-W$i?u-v#ApAC1f)O;NKgiukO`U_$b?+U zmR!m8s=tN12bBN;fDpxXYYIDn0Cr2kFR7Amz`=nVyi@>}(pbX4fD&nJxOWQy)A$R) zK)}JE1-!clzwifmOR7)$ix#j0oS4V!+Q-Vg%+ZFqI^3uo8_gR#&C)Es1}dpe0IZ3e zzC%0(j9d)6U<=gn3?AgM)O^m>jLzzu&ecqzPb{}|%gG<W3wVpNrrNT7NQ`JOyQccL zt*pWb@X06Z2y#oyc&ow;U<z;GyISx8Z}|Z`@CJ?myu%EP8oG)9kjKot(Hw1P-^-|) z%fwBL&A{3Oh>XYxd#oxgtiPJ9RS*YDU|UfT(jxy|)0|4J46vx2Ov-P-4yo_~ws6I@ zjKCUdvPS^L{hSJ8OtJ{jzZPHt1nq}MkP2+9t(t%a#_I^JY_bEL#&$f79?2ISJ=SE+ zRyfS1w`$Wjea$~S#FNkj3A@sAeXNu^1<ZQHiy)^o4WOz^umn4`_zI)+>eqkGuYzr_ zgpIU@{i0*4x&~U<0h^+)E5~n%2I0`b!7#w7pr|T|09ru6983i&%K%iM2?IRJAK(ZB zybLL<p>X^Ql@P9_J-~Z_w`efHrohiD%)%G_k?C62z#ZJ{gp!@T!)o2BV=Adr&;*M> z4R(F7z6#gdys&3l1s(8U8(;$eNwzXNqu&3$qGsFO-mTpP%H1b0-s9c5Wh>t3J*RE^ z${!$&7C^=)>$|pWjWc@$`t8uDdc3ww%KE(n+NzSi3&s#|yn{Qv4*k`NDX2ax+z=k& zfK#G?Y|WQ^;ZQr+D&WIc+XQjY4b+ecNbs;tP~s+j;wYZtDqiAG&;-nS0zkUD0?N+$ zx}r2Lu>^YKEGo@7t&$O-vJ<JYfSA+n$hWS%rH(teeXE##ySRQ>s({GgU|o!_D&bas z<tIbj(D=;ry3Ss%<I&6|WqPJgun43O1>LaRm%8R|nyHBGu^KM6g#E8`?$;DM=K@>j za-QdVzOQ<Y<9=@E7z?s@Y_pHsr!xQBl{LG!Ih&F#%ji<>;Dn0hlwRq*^3fvDsN{Xz zkUFC%5CbU?>Ts|N2!ICM5C=8twW%%zscr<V{^~-I0<IqGDZuKrUZeIEq$|4VUy9z} z9j3mn>qi>wzaFF7U9H%OosQ0p%kJZcZm!QR<%lkocvY1mY3bOW?M(8$I!pu*`t9Hz z?(|hW^u_`lFzSA&1?&I^Nld5nI>`r$*!0FFAx+rzzMlztpYOTv?kVo+#_#;@@BI$& z0zdEuU!VC#=+Ul@3-9C7{*6&d<#=Vo6kqWcPnnmgr9O@U8PM?_|M4In@*+R-Bwz9- zfAT2b@g9HyWkBlb-VJ+z0UrN=@-x4gA7Aq|Z}Ta?^E}`4KL7JT|MS+l+l@)|h5qo~ zc&;Bg4*y{7+Wz!VPbB@|4qg!7P3e_xne|$~^=|p&>Annrs0H1C28hY^KMs~Zp7vjP z_FTXAw*2;L-}Y{=_G~ZraDVr9FP06Sp)%`|hF;MYY5`cR5*?aOQGfV|&m-h8!UH~x zQTh0y3i&Wgi&|Rwk`MW{X!()9`I?`&S^)Nd=mp<E_NZuzrqB7PKl#F_`hc&Btk3$x z`1h*_`>ju|eJ_i`T>BUL0bZ~-6m;#0AN;~UBjn%+J7DzqO{#pFj@`QatlE;!kKdjh z41(wd<3Rd>n$zz{<d6S;j(+-%-CvGZZ@u7nv&i3#u9)oSACL{7>`2eDKCZyt@DIR0 z{Pr*WfJ@Qq|Nao~*#NN&!9aotv`9mPAi_e14IMs&7*V3c2^A+y#F$azMvfglegqkz zVn~uDO-lT*!_hx-{oK8T8B^v=nl)|S#F<m)PM$q|{sbCS=uo0XjUGjsROwQtO`Sf~ zxoyvp4-70`yt?q}R<2#QinOTJ>)5eiN17$e)u2Fy2&e>u`)}ME1ZnNw#hX{}UcP<( z{skOZ@L<9hBUm_sW|=v2@}NG399i;Y%9Sl&#++I6W~Be5?)YHA@JZ68Jyu+c;Ek<; z+Z<_ut)=d0)3yI?-^QI=_io-9Cs;^{CKyZ3#f=|Fo?Q8I=FOe=Y$=rr)eoVq1IL~{ zv~~;JxnBq0efxOv<-Lawf8P9f1j5m5+a}wQDS`~t-zSfM{eJ!Z^Z(}$K>q?Ha6khE zM6kdF4^*&01|LMQx*d*qW4M-{!!Sb)H{`HG4?ld0rGB;vMiW5ZKqEyJS7fn87hi-i zMj2<MaYZcvDF>WADxvQKY4-2}#TthsvPdJ3L^4Swmt?X@C!dUQM_{&j#~cu^#4<}Q zx8$<RruuouoqzfPQyMeRL^Dk_*JQIzH{XOa&NP=9&K6Bf0cQsUDgkE~IsXJSP(cSJ zv`|A2MKu3WMHhvWoPWv@@g*`RrL<B@FU2%dO*iGVQ%^qyHB?bYCACyjPenCVRaa%T zRaakyHC9<cednEc;vt6|G5_JUS6_bxHdtYYCAL^&kM-4?ZI*F{#Bdxzz>9gd=?7VB zuf;Z7ZMWsNTW`MwH(YUx?I%}VTXM-ub=PILU3cHrEZv#RrMF&t@5MJ?efQ<JUwpyY zMjH5}S!NkWqzMOMcl>3zVTT`vIAVz>rnq8@FUDA3N#W(VV~;-uIb@l175S!G!$FxG z61Vw>PK8T`IcAw>rnzRDZ!V5xoLwSW9D;2LW*KnAaYtU9k48FarI%*9X{SM)6ee)Y z+$R4Vou9@!Ypu8Dx@)huCQ}}(bv62Hv(H95ZMD~CyKT4MhC6P#=cc=EyYI$3Z@u^C zyKle$20U=Vn?iS1!w*M1am5#Bym7}Lhdgr0C#Sq}%P+?~bIn;TdUMY|2R(GrM<=~> z(@#e|b=6l-z39PThdp-LXQ#b(+i%A`cingAy?5V#2R?Y=hbO*x<Bvx^dF7X9zIo@L zhdz4gr>DMp>#xT?d+oR9zWbtB2S0rA$0xsh^Up^=ef8H5wR860hd+M#=cm7Z`|rm; zaqsu%zkmNLyW0N*I6wjxFed>tU;-7m!0wfefe(aW1SL2@3Rcj97lao%P?j<b)<pk< z2<+fXHfXgFj%<V=EFsMt^(z!waE1R!Axv7r!WK^Og}tg_3_<3Sf0zOgd)NaYEabom z@~ma^fnf?AB@IUaaYyqY4hGBhk6`=|h^9!Q?ee!ea#ZmMpgDpgmJts3ZPARUDq1)U zh5$ei=ZtSO)l2>%4NYj_15|kfo?HS)K7vY82K(Y2g?OPp7SfQI5>q&|u!n*b3=MC< z)gdK`DMxMN4HH1XO2{@zPDag9l{msL2qq0s216c&>*OI9W{wm&qhLSM0ytopO2_@q zQQ`Q&9^x^Nd4K~p^T^=>9kmQVoG6p#2<8LHF%MHXVjJe*RVol*i*b<gf{y>vL?w91 z%Qt+$QOVR{yIK+s3iV?d0)tHyT}Z_pm;x9UaD+I(Da>8vDqy9=RR`NqEppIl8GFz| zIMf-=kU1((dqBt@;v=nj8qhOSGQ|hl*iZ)M$}=hY1<OikP(TQBjJKoZ<-`OIi7w*^ z2SI}tfLX?n_HkD|{D32n$<mg(^d*i8h9lmvl3CVNl8Mym8vv1tZtT&ghYKD{cECs~ zyg?f2q^JP}Y6^JHw1njfhii_2MQd*Kn^xPy4!{v6f|ksnxdewPf)O7r4D^Cim8e^< z*|Im}Q5tf+Ag>nI4|D9{1Mw&q?V>8UTT-Z3zHIAY3FxSZIs&jnv|<0tDuD)`iV3n4 z{D&=mQI2x(HLTzWY*`EXkAtRc8(u&IJW>ePHj=P|0(C?vxsfu(4se+%+Quo};n#NH zb#O<OTpCTJBB5eYQow!VFds<;1SAFxrT`{#-{=n58bnBsTns9ui$6K~@VZ0o#&Ng% zDw>WLagwS86{e#FEN;@g_*-T$)H~nlXrdqCcrSOCsfi;@N4@<WVt(&O-5zS8zemsn zSq0px;mPA4P{iR?d9}@L?y-Z_>J=}06~kYJwsy4@ZHPrY;tZ15#3x4a$BepQ7Pr{N zFNSf9rJG_J*Vx84#&M2yykj2s*vCHxa*&1WKN%O<$VWzUl9m4qzHv3#$xnuIl%+gn zDp%RcSH^OdwY+66ciGEd26LFjJZ3UOdB|r*bDGt>W;VB3h7^W#oaH=cI@j6GcgAy` z^}J_3_u0>X26UhWJ!nD~+R%qabfOi#Xht{M(T|37q$NFRN>|#_m&SC3m%M3CciPjR z26Y_WJZe&x+SI2;wE{t$YF4+})vtzitn(IXTG!gvx5hP#WxZ=&_uALL26nK8J#1nZ z+t|lOcCwYdY-Tsx+0TY{w52_5YFFFZ*Ty!gbG>bDciY?FuAe(HJ#KQB+uY|yce>TR zZg#iZ-S38XyyZRbaz8lR_r^EVR-JEt_nS-0q<6ptK5+kn7u?_nM|i>&zHo*&{L=o0 zc*IpKaf(-5oEFD;#x=fij(6PSAHN>BMLu$pm)zu=19{3-zH*kg+~qHadCX-#bDA%$ zR<)9cV`{#0ndiJ#oW1$YbIx<3zr0pt%GIrkzVww3y&wLF2d~~y4yIRq<2fI?JH+u1 zVc4M;-uMSR%0V=p*Xku$*SXbae)3$yV;;h|!w|Z#h-df%9{-qnIiSgQzW3elr4qNp z1wVL)XZ=>U5(Xr?Fa$e*!XN(l2QuG*cEVTQ@|VYa<~6_hJlp$ujENiCj|&gCzvCIR zr~?#~U<hYGO6=uuaMsm6``%@pF)ook+-k*`o4fzx@ur_d7lOcsQ9Oh6^AHEl(@uMq z1Dx}if649dJCBz<ztS(c74KhC4!g(W9jJ!_6cRBDyZ^)cdFLhNt-pTux8MEmhrgda zZ@l!&gG}6@1|w*JchJkt?BaEYayUMCc!uDEf;5-}Y2c;T+a;ePE9T?4%L<-x7>9Of z2VKAfJfMVrXovn=o1EjN>f5H6a6oe4K7S|&VK9Ur*aAJU1#cJ!x6_peguoj78(w0J zc6bL$zyn$!1`DLXzhR7W@CJYQhJWw|P!K*apu1iA2dkk$8?1@{W1hy4Hnh7xZkPi< z;0A86KM&-apaYX|5C>jLyv1t+Qec^|(-r>*ltP*KzuW_!oMQ}gD8q38LuaEv3nT_n zzynU0hj!qsz(Kp50~2z12Y48V)2o9Y_<})L21tnq3T%w}i-{0~3FQ+(nNvQ|`yCLR zhn(XqC}J53#Kg4uyGh}tc5nwu;Db`21q<Y?P~#Oc=@p=JyMK5F#T!0Tc!mjs2Smga zU&$3Y8k1BsIjJ){lyNY&>zuK>J8!TABOrx#xVvK<FXNHEZ}^5Sqy}o(Ju49$OeB*b z<ScPWzJ8Dg)XRb&NCaEx6<oo(OPmKD(knb%xw0{rO7s=``$WfBCL}b4#e)Q4fCqo5 zl~YW%9Bc<-Xax<#I|}qf*m1z08@vBrc?KnP#7vL|44Xk3geGD519*Hwe+0RDaWG#| zqfyWVDzQS|;Tb4;hk+adLwE*jgcNAo!*<{VLEwZ~Y=<DsouD&2axe!-QNbTj0zLQz zaL7p$q&jy1yB`<;ATWew_y>77zltNuaxfPR>lJAT22+rPHpl`f_<<jo1$Y1lgp9)3 z8A77r6`C{zVK6^Lbenw(oceo*fAE7j_(uH7!`?YOF-gKYkh@BVL|*X*($mE*AOHX` z03!eec7TUYT)umg2P+{5aex$G0S9OJg-qxJFi?WDtb;lLg;{upTd9`JoE@wShp6iz z#H>qRa!t39z}?}!hRg*yKm`AJ=q>6So}&|+c;Kuv{DCywhHLzWc-X}sFo4Kx17R2k z<c!K}qnEz)m3a`$QBZ_CNQ1QOf;xZ%P!I-hU_~*Rhh5sr+Hr|6;Z9)a0w|~hgEYU( z>^-*GP2JhaQeXs107{`Go^W(b(?dNLG=yM)JYGq`J1_tP7=Q~%gkKc9$%9Q<%Q{Vj ziJZ&I=rfnk>=l1-20PJ%H0T1<tb<8lO>aoPtRy{nK$)ZDEIE7~UV4Yld@x`@%sUW< zZ<q%PtkDcjw(K*9zVrh;AO>OxN9EzH<KvYA1cM={154Njal<<$jL-r20aF0Gari%_ z`!&oYlXHAgU-5@^C<gzsY=bUn$MQ4;^t{PlF^7X>OWxa0+&RPt3x+xvzFBw_(i_E4 zBvNFfKro>OVgSx@NEd}P9tRw|@*{^?SV4CrKfBuoLl}Yxb$~h`NifAwVG9#;;Z9z8 zJZTusM@T&tWzlE&#WDGZ$0I$X3_1sc$%WxlKdpmVa6Nc{CL3k8oZCrSU<5=c1t1)U z+{-#(bq5=@#AcO;XRW{bE5vG@M{%peTtP?A<SbsP)|uff&H@Ktg-#_L0t9phyAy^w zxPS<?%4L9}a=^@Q)v;=Q*0YONLdCix?aa>Vm4hTvQdopKV1ps}fiCERI2DFx@P=wR zLAF%HaE(ejG>8AgBZph@(5$@Hw#hmioGDDCR(Z(L;dBN=_)~AFQ@3l3Le))@tHpk3 z&v%#yM34hr_(7S4Fjsk5KgvXRs1;JJ6=5O0$CFk3@s%<SS2BrFz*501P=Y$(1%#Z1 zE-(Peq)f|{*YZL}`0179L&Q=ASZCOUOfZByfPx{&g7SofSxC=un1^?eReuPF%dEr0 zo6UBJ2X}~vl>8NWO|o|YOAMnFWptEzDA^zY15gN5&{D@^+*udXOTNL=Zv;+7)Yqk; z6pIA92ZTy*AVO{p+FywWfIU^QwFOYf1V|VJf>i=Y7&~SS8Hq*O9DO`p1O>#*0=mn{ zcBM{(e7*lc6f#lNyOn*39Oc#w1K4F4g-I9$FbKaaU;{&F)fFP$xy=;|WJQbxmU8HZ z?xluqC<bXb26W&BUJyjs>(8@sz<CIVVn|oFj6NELrg>NfLr{XmHC4BaJ(g{o^rfAh z#6Uja1Z2&*!#h0OG~m32)&x#q1SXT869><gSSW(9up3&Ubp~nJ1yaa_Nst6RxC7@6 zzY)#?FsK7VkX}H|PMYah;&h3ld^|H$ydh`<w$+1nozMymJ9&j&9HUqY%$3lc2Y}s% z)0G4^7-17W&xOrjS%n7+1Y8H@-tML1ZlDHfaE5gFg>#sOY{&*>Fa~B2V==}DRse_Y z4IBUdHJe(A2Z34!AaDRUa0k+}$Z_BmX|UhK1v}C^${vQc9GqD>@Ii7o-&={ZY86xL z+uKtz7j)EC&wQ{48{!K-RSlj6QUC=>Fa$kdgDp5q)jP{9NKF);1X5sIVc3Q;G|C6_ zRsWqC;a%EoK)oT@0_mk%3GGtPC8JQ~vCYiUaE;{03(Z-`1U(R8C;)>L76yTGyT|K> zaP5Xi;a&j*hjmbgbU=r5I0t^X1#K_}WEkTy&If(ahJD}%emDnoNC$OT2XJ7AA;s6X zsTDyLh6^BoJ7`O{6e#b61SQCVN$^~|(-lY6n=&)#gC-MRx<6{z!g=sQ!G&nt)7byb zeFyAC$G)WCup3=~JxGEPhFw5i)fG=L@MI+bWfMN(NhoEuWmxQuRnjF|y944<J?NU| zrEnF8+AYBP1cMai)Gio~lEm4XChDR#>S8(4sgoy3j!|h4hEXttG%!sl5asjS1#j>M zULx8UJxFU#hjhS(Xo!Ydzy((LgG-2nOYnkAQ0q%r1AO3zY2XKJQ0H}Ehj)%Vd8lG4 zE{9N5Xs|r$z!sKCoQG$i$~0(9e^{Yyn1n5W0)Q4k6zuB?7VOH-7T)13hU`NDu4p06 z+M8=+d4kzUz7?)M$Zc@dUASaO_~10?<f#q<s)kePWl`2-SZ~-RO13+@3&#JW^jvQ3 zR%y<#tl3bdw!8ME)WvI8cQphBe8Pkz&Ze+dHC7&r{AEHO?c)Q7XTan^NP{#8zm#Up zup0+|U}tA=hGXc3UXTP_NQ6AdgELqIFPQK8UIPbM10V>33b+8tj8Fgo08$`_y{=+! za14||$8cC#jiv52ww1dxYywDwx`RB%c5Fz%>c`7$;+?kQ-f#=#!BWr#3-pF>@XTGJ z;2~D=AyyVw6$VU}ghA+ok=_C&2!bJig7O^YNm$K=Wmqs7*O<0bc$ma?FhLXSN{LnS zC5LCO5#HI9(E@D52#wIIy-sM2XDl}g2FBP1pF^G7ObT?*A<pe*kOu!!i19Ws&9pVo z)g*;p7==nmgg&r?FZco@$nX2U@BOZTAh-Z~o=z$Ua4IMCKfi#qBn8p}hjtJLX3SR- z^m4Z0tkLxhs@#HZILJx(f+2te3q?U*#x`?Y7=ii+E%XCwXiyCkyX}64k4AGzcmz9e z?Ha#v*-lOK<Z+hX2CR-cq6G(Th*7;8JD@!}G7+yz@kDy{W2`Abav(i#NXq{<fa;7v zaWHa{p~4BG!wP)hazJfim<3CCgf`d$KmYR|kUJ$vgDn7pcCUbUw`T$n^g$=|LO*x% z)NxYIb(VHjL0tB}VPiY?hAtQYCCJD#_yL;?JA~BOeshU$fTsU#(1cRZz*Z-PQILd1 z=z~6BgD<FY98cSPKTkP*hF$OVp&eZco4U@F;BXB(-PurQhw$KwPy(RP(U#<GG6ym& z#-I52<zb8&{0Cytgg6L;avy>UpmzeW`Q@(nr;kuWPs@YV@s#HA)#Ue<p1eflZPH75 zLIqygne?a|_yLf+n!HKUv%iVFHk>mDw=D;1h=xe`09A;C4G4lP2>E=^bzxXotQJ5; zbUVv+&~5d~!=Ko)Bg&tLoy;BwpM`sGm;|((f;ET)M@WTCm<4HghA8e%1pc6&e@lF= z!_u!qitS-~CB$oed(UqNXOIIcxPk=u0jGz01GsmpA7%gA#(KYZ)t2rpc(6=%Fyy?= z*?#a!Le`aVmEhtX{c(KTcfdbG00PSw2D}A__|;62y*WGfj8RyFdawss*aX@4{hPE# zw?lCa8<TfX&+R0uY^NUK?X7Oeg$Fo*W{`z7Kv<;&2q<6D^m$}yl&xLfy!~tF&|$oI z<H%8T_wJoMdF3{iGiQz?NRA%ekt~@pWJhx)SF&vB@+HieGH24PY4fJcjPm|v^w_Uq zJ6f1jiJ?dD0Eh(zs$A((r;Z^=lR$x*CG6_6h3(??izshi$A=9sz9R>cB3ZH)FXC+L z_AT7Fa_6p$*sh%}Ohp>hs~75Aw{qjcMI@P#F5>^hiWf6(?D#QcmpV0;BiC@-s5REE z(X+Pc)`A=G?*1(It};b(kyo>B?Hca9c^SubyNgK9-oDN7341mR)FeYse{_KYB}kSw zeH2+Tm2lfTu?}T>G)HlyyTh-ybMNjhHpzZJ|BaJIi4lk!zvwix2O>#;00j!9$HZwH zym?|T{w#Ypbwx30=N*9sx~APY<FxaRA66W4NHd+)14}yH{NvSR@))=whb#5dA&4Qm zL(WeBV75jx*H}Z(HTz(4NC5$0qRU+yu_YpoIdbUJJKq#@g91q$V2?e0g`&<w<^0pn zGgkozNgZ8uL7Z`05F|+@&IKcllF~I~9f1F-={Tl=hmq(|F}aXI1{P!x(@iv&R8x;A z#JJ&xQu4)^L=vL30-cRzktk0@g&KNjVPq=0=t>#I6V5-&XmG;<SfGPUJ@lkVp^_gC z$SA0xirOJXmt}&YiuA~$k1*``bBF>3aN$Nc?O-=5uDRB<Q9J#V!bp6o9Ma-F*2sd- zGV^>RjydD#*AQ3@iT8|ePYy@i4_Rc9#vO??_sf>xc-hd1VUlBxPA%Q2E4w9`qhC9s zU~<C^h*07WZNfxyi7fVrvW`FV&_W9qH^evJd}GX!i!{&9lW4mU=jc&8|Kt)!d~;Cp zPCNQ=rl~y?26iDiYDs+Zh~lZdGRyxhyZkcDG0QwN%{AM6GtC=WX5u7y$Z}0H^~jP8 zDC@Md4Lh|QP(%R>v_i~+8%c{Z)m2-4HP%^cz4gr?efSSJNhEcHKew#HPddmL<w-i_ zbOTSJ&4v@sIPv5swL|ax<c*V)KpEu^*><4>7<~+qCAh_a6VJGU0%%c0FT2Av<&|4r zb!_5|vyB^b+<*lw#EkO~JpOcJM<kI{V-F*`)Ee77<8VUB4Ims`zyk{if`~NiC>i@k z8S!*E@x>c|JlE2?WA{JLBw)n?0fg?&JM5rykA&CU6AC)qDCrgQ;fp{1hbT+@jyo0q zBh4gd$l^+0*IaXlI_$K=4LASooYTM|0W2T~A}$iSetgP&2ISC1c-0SDG$KZGK!i7N zA&Y&GLml`~)jgb18FN64B_5d@Ji-AFxasF%nd6u@ss#!|2xm%x%K{j<l?X|g0vN$? zhClM-rG7Y0HRU>>h%zFcZ*aq2)SyN=)&dW6fC32TxI}vb!HIaZLmuW>P(!Fe3`F=L zdbg{OD7>M*c`R`rKs;k(HUf|4*+Byu2u<uF(v5kjLmQcD4?ebcj%`?oiW)*AAOp#r z$&^DJ>XQZ}zOaf*^yMDc2*M=n#}0OMqZ{5p2OVx9A2zju8VkCWAVawt@Jy~9SSW)3 zh(Qc*3<Dba*v3E7p^X2vp~Gz$Dj-YJVh$04V}!n3qu$Db!X{ZON-pd|7TC~+L0BRa zzi>t_0QM~Dyh9w~xQ>`a`4~cWL|Nb9Pd^g$4{t!h5a?J%GoWDxOu(Zb^Qew^^p+rE z=)w(Th>v^}uz)0xp%uBf%RjvN&X-I^n}M9nIN<S)We7nH@!^6WIA*tUFytTnfQC_^ zkq>R);}ra$219K1M}v~Iq;1Iv`qZ}!NNiz|nX<<{*3gAnOcET~sbo9Sv5H&F2MccC z10~4Ojs%&ssB)Q&g5IGEQN(8qh^XW?Vu6o*Y@=7}z=t*36O4X{qZ~iMWupickF=bG zBO~nP2y^(X@r?hITEZx%lwQ~cHr!zlG_-{?aOe+zG|s4usg5}~=8=nxP#%j=!ZY|G zi)J9>5Qy+cIpo2^cf=!h<3Jy}@K*{>6f8zDq5ufy;D%y&vK^NF#!J@aSCn1EAL5!t z0<I9BMwH?%w3%Etz5x#lTB9$@I0rwH@rr#EqmS`O*J_hX(zNVsrCYefC5%#!d^}<e zhImFhe7B^2Sh5}KKn6aRRs=uzK@Pc~hH5~m-1VB|k3Q*#8@M1JUA)N~>xhLu@SzU3 zbweG)FiI!Taofq2Pe3De*GH0AlC+S7m!*5KbW+%)Sp?@Pas2@lzyJn4*wvZAAci{j zs#^BGB{u)q*$BRb0R&KRV;_sn#v$b34{C@9Z-9+WJ0|y!BT|AAN%1UwZXgIsNMk|a z{05R86%mD!SXYyYO*ghtJO735F7K6NH`c)q-CQFY>fi@5lCh6nScqekjYpHyJSy!> zrXht~V?3N;2qi$*DD=QbIwFyUN!*1U$HfR`N|%p(@b5jPpaf9+G1PGsG&=`Yb11bl z*mn@46?^i-H`-Cjb%bIc%s7UoyAcj{<ii@)u*WaPX&M4%NHGaC4Ou`4jvVe)tpR<Q zgoQ!jNmzJFP$141gh9HCfECgPCdoUM#0EA5Mjx_}#W}=q2x630y(LM|MeY(CUFd?m zUJU<$0)m7EOq9ZYn)^nA>_$MtJlfbGnheF>K?`67;B(aA#^eH3W4HYS9n3I_Eb_4q zaPUJJ$<RhHphXxBiO1cGAs@seUNhm9V~zg^#+>VH6g;P+3t$jNH$=>`jYLEr+IUd( zp5})!9I;nZlQ_&{E_1B$Bthaqgc;&f3L1r))BDIrG%8uia;PI4M%lzU{?QG+y*%O! zCdXiUN$VWyFgD?E>u&~u-Eqvk>%@D=2>(HfAPB>5`H%%P(D5MpE+}&_bF)_!-3}ts zq7-hx0zLx(+A+Anp8)*_5lKm4uM@uTHG|d_;Va()kiif0ct>oeHnmFrgB|*a5Iz4o zaSjfiBOl4ohb`7v4nG>c^u=>HVmzY8hG0Ah&<z?r?s1NFOd<$+c*ZyUp|{DUh2-wo zhdyqh45cul?u{S>Cv3~;cB5X98xapRa<PB~fPf4<$;hVvqK{gLqmum)3^*=-YF;GR z90l%<lFQl=i%`VDwe|-&Cd=;T*94{S$l)`#Ac=PD6(7xTg*rTlDDa#|;8Iy#ghyao z`jEpB%}&AO-Fx5xB9K;&1r(AA9{qL5q)|gLEPy@<St-;?f)t=wy$eZHlJ(ewgoMI6 z#0EO(Lo(#UFF;Cdj1{^tUk2u&V?@N8v7RBg-Wv2pJ=_C7_`^2X!4OQs=%D}GPKXD* zHA_Df+&Lh_4Nw3?!2>ne6F8t&Kaijf29mSf1trKqj9>yS+=Uzw-6@<yHn0LXR1)@O zSvF+KCh$WgVTiS@Mx)suvb|G+y&6SCglrVs7rFxpj?SDd1U#(6Jv4(ctOHS);b;(* zWKf3vT||N;NIR$oInWaqO&LBF0U0#HebmaLp_@kxB61btYG`6R{7QUa0Tv9P^1T|d zQ3m>0h%C{A(A<M5m=HSbLozS}FZfP3BuY=*AS*5-T%Z&=gk3PyK@hCL8rT^Ts>3{t z0u*$CFq95t0U8EoggE@eIh+DI7=sy*;SJmcC*T1i)YhW)Av2!LdvX86k0`)<T%gJ@ zggTgGIj#d7QpQGTLo@VND*Qt^d;<Y_p@;w$c9azc&ZBmO-7W+HD9l4Q$iq6=Lo>tz zJ7B{hs6z5>#c|<ahO}FPAlcv5-JML|!7PBnh{756N<Sc3f~ev=Iz}?;jT<n{0{DTO zpw~N0n&h}cAvMH4e9S871D8BZItU{^q{2GbQWaSu4lbkVWo6au1d8cLG)`kR8ihUZ zgF5sBJU~Ja7{WH}RhMj6%eYy;okBXCoGL`mc^wfM(8@pPm_ul#U;ZW5gke8$0=)@B z2rgPfScp1!0y?0BC+wGn+*)9)!!%^d*?dE75Rh9MUef`lXVU-7Lx{&-c|#lA0X%>M zH_U@G*h4k=0z0IGCzt^zz{B#a)z$oiIUw1)+yxQM4x8j1XyJh%<O0+X*iD+>XC`Oz z1eE!;L-fr@^^w;&aD#Zb-MBPF9Ku67U=J@crZ;rM=%fQbFati+0zhUYnz7YpDyLuO zBukuxIOvcq)IkMMqn(XqI_SqUw80R7!WxZ(GQtG*5glWm!(+w=Ba9>^%)yKZ6(zc- zuJ8!hh>Zf=z!5=Cp#(-c$mL?D136@*6}=1B{lh*KWIfb^S%4^nvWs?zM}AC#5(vXQ zaD%v{Lp@kSE%09`IF{+i<59`OMIf0<_JbC2Q4$zTC?@|wBVYoxVNn;V#EQyAY-r*; za6%x&h#UBU6fH^c{LvmB81{Wb9T~-`nJ0gZ!<Xd)G}MARU?!n7T9mS)Y7y2u&8GuU zW2Vr9J?uj|ID|HK!86#6?g5&CZQ2?xCORa60?f)?(35D1M=F|8oQ4XO3Pr|H0u@mr z_Qew0tivlLoj0grVs-;NM1y7SLtvmw!%ZrvlvUV0gAz<a$>0<(WJ)xE1319KArQh5 zAt02-h5bQlZgK-xL<hIsNmAq;7m$IUaDzfVDXW&)<C#(sOdll(f*IC`g3TXH@DK+z z1V4Ptu`I(xgu|wF9yExIk`P#I5Ms18*^QLN8nyp}Ep&kcOrsFi!#>o~9D&0RLV`Dx zPRT@MC8A&`OanU%13w@F7d*fXfP;d#10u{pofuMrxa+$X$R$#1DtXdSLg`7wW&J2@ z5($rF{e)1(L%3E0J=DTBm_uzqo}^~%n6wsO^+6gu!(QQ3W!A$CwnH>DfGVhxmHq0E zwnR#D;a6-Ho4BN&$blei!#8~_%^DcRIH#orfGAP|9?+MA0;tg%SRA&41<gt3*`cUW zQkJ1ZK5S1qd;>x<3uQ2)59y$GBv5>g(<pR71x#a+^u@kLM~Zy`6o7(VXlDJ%0}8?d zEU*JV7(*#EPyjs5UFbq7$blayS{_zyflU8tQY}@CIF&raqoaw3g`fi}tOF}$gE+*4 zM+}hZlIl71g)C@8V8kEBaxVG->HW>aEC9hQ{KL+QS}n|pGr)s5V3I0K59zkzbmk9k zegh>S!ja}3wUx|+>h4N-1iG<fAjAhAT&p1T>c>9hRkqiMSW?mDDLovC+sq9Lrh`6g z4>rK<I7t?6YA?K!gMN6!-uCSpT!Rqm13L6d*p0#vu)#BsjzXc2O~fucOalw111cPY zKg5S&TI@Wm+|&4K?&|M0h3G}Z*L*?EJ7llv_FL+{LpBTpImE+8gvXOcL^zbgMX@X_ zoagnOF9^RzM2r&{)B#wG5DLaZJ=p(4vUt}a+yW)&f*55lWMssYqT6Nd7%}*P8_>&z zQf&|KWOR&!*u+RFltTC-q={9>Tl}y^VU()a11~T{ZBWuUu!B0x?_a>u{eH(F>L7c{ zoR`c)sf?2;*lPt0K|KiYbe%)5%njH`<0J$uU!}y&jA}e!gD0%RI-Ei@_`?l6z^wcO z#{>l@0Fa{D+<5dcDt8^UJRXr|Z4$VFqT!8rB#8>IgGI%{I-Ev1Jc~I@9;u>(3a-jF zjNUZ$Whx(Y%z>S_NWvC8g9z!zro}=v+{09QmnR$oxoO)x9M9Cij(+rVvs@OWs*<wI z@_HgOd&1pdwL_)FM-hMyCeZ(uHcQ9h8S@?T7VT<-G>}K#z{AMY(LH$7F#m%%)Xlh{ zbNINMb{NV|>{9<)LKh4`A?Is8DDsDh178Wl7i7UKOcZXa1gj-3PQj)+gaa&iWFcSy z1>C?kZ1ea1!^)l4MYQWG_Ap~eS~ypcALLvB?40t26-k8ZIlO``qr)qxgW`6BumaXa zlOr^+EDI_ftMRZ+H%3|E9}rA}H^#0yyh1hL!!{@yJlw)9Am1b|Ule<3x|B}>j?P|I zH7RX`O1{Gwf-fhOLLig^F<30vn(s*|ZaJ*O9QFl0cmiM?qgc81I_v{Jcmh8Z!%rBc zNI)sUD%bg;9s)v&i9r9fL=S=d^aVcf13N@V#W9X03_%@0M?&4ms@6p8?v^?B12&w3 zI<!I|#7GD8&?{0xAW%XnA6Hek#yUq|?o=Oc`szz4$xySyKd1vLq(k?014$saqg7Hk zq(d-MRX@aEaC3(M{cs(y0XUcg+-OK8rGqOR3y#4<HoO8MAOcr>aCdvh^L>Yu*-ioI zH6ri<wUvXdIOJT&!_J%o8~2u(f~Z8;ujAqaD(u5DC`q#f=zO2gMeNKraCQY;z-QM( zXtRSmah*Guh$Fj0>D=OoyhUJm*BbVNrvip9C<PykBq-w#P!>b}aPfpUh9>qyUCYQ! zLUArxlrq3lCS(7Dxk~q1fYPR-Loyh}ktlS%g;!K>__sTBP0=}Y=Md7$5Ylachzf!< zNVk0Hj-f-Ok#0mlK}tG?Ze-|YNCAO4{N8iUTIZ~Hz5l^pYwz`}XW#edb6sEjx4liF zGYpBim{DbExT#_8Gx3cOGfYho1uomw*@k*cB!=`Y{6!mA5I+vmY>7C#^|#-019n{a z37|XaCq{Bexinr_VIxFfM;Xqm@j>F<EnDLi{LR_(E{J+#ILGPZgOEE;OQX>)RkChz z*_fG*H@|uD6e5)sY(gZxm1QDz$eTMA8biz+*m)#^%}J+!u(nqIx9mC3K`h_l7nv;A za{fBF9=SO6X*zg;=FIbPDA(^0S*n4$1Mvp;tx5&I)1_Pm?`~RPm;46G{rQAUWmh@x zGE;H40Dc$Buv_~~wlP<($K^(0)zlxLUyR1$@Zis!m6c3~TFL8dNl--@R4Pg0_i{S9 zy^>IocVF3_556l8FDU#mlb6HL*)0yg0ho3ak~tUY-ITvtvMp(PB?*6z(UghwRR($p zb9B*33qFb*vV<i*c2QoYiq7Qdjdu%vI0D(3xRDKvHN-wl|8NCL4-F$6J<^qBC1f6> znif^AhsJui+C!A`H*phCLWJS(2XGZaP15K?Eb5m3<M|Zyb5=^7o<RE#V3d*P_DUKN zE)$8Tfu9a-`nWhnsMWYh)|<yC-Sd);eU@mP#Zg7+sb(Q%U^oxn@8ghhcb4O@W(jo; z-bUr!9{3wh4&ZS&T%CrXBt%NZDRv4=!p*NP*SIccC&0({Y2w%HmVRkil3e^R>&TZc z$x3|X)iFM*_+}URNz3Aw{aud*@qCu@cD6tHkwA-xLns1qA0Fj1pK#QZMHzoy(t0KJ ziC|%Wq3<^VmflCf8&6}G5EM&{v*i>Xe<bb=b7VL0*uSgs!@mcUB+9u@3lptBUJc=c z|5bnz>OcDxq~DVCFa{8xAh*Xul-h4sef|+}+<*O9ij0`f{CG7^{9#-w7egy*HPvj8 zBkzJ8ZF~PW;f>(Cm1y$U`hk!V&%^dlezWm(qEb#zOb(h8t@Uyhf(WT)Q)~<hRr})X zXA@o);^JWRvohVS_1w1B?iNd`u%_~EbGl^$vsLTU6?EGpg>z$XzPs+mju&q8Ezi|& z#cxgjNdNfmmnz>)$lozthL88R29*nkxldkIjK&?#R4q3u|AdbFK6LQkjpZsv(0r1x zmGcQ`#^*&4j!QYY-NvqS*Zi3ur(dofvKo8a=39R*^m$f~StjI2HrnD=Z~2M;m0{Jt zS?U$JpWo}OXWKu0R69QGy|bSs`@{9;@|@&3v&h>P*VQeb*AhKQDX&$+UuVKKANvCC zeqIy7jAo)rzS!u#vKABM<?RCbEQng?xNO<>!8ErzR2qnD)<?S`F|C7-$%pDjcpG|m zBbWrEiOq1{m->|C7Wwb>w|U-U2f_vLCS|z3c=spuRqkK@8_RRDG$G3M&1&Jv2<YL9 z5Q3IfP7KCdG6AVrLwz7QA(sN%x&B$NxM0ED_S;N)&-06@K6Wtn4a)3RPL@=F*S^w0 znT=P&RW<Xu(@W=C`GpS3`L{WcNoXD6=cAdiZCKeGwVZ)_Q8icqriF*Pu2mGJBBvoV zJ&L8X-%j_pEQ?_FJJpEzQrG1Y!S33BZJj9_4A^Ap>9MRRZ{*!On(&$M`JL(AWk5vj ze$PgfD9Q{7%G$HK-Qs%hp2*P@FtIm0<)ZMzzTY5<{}A>@g@iRw6uMgi`+K=Q(Cg|v z#m(pgG$oq&FPO=&<nAYSpJ>%}%0N|E4`twF=E@dt%yB$?-N(oajN&o+W_i%p7SPpM zLT@yYDLCRT-`NY%#1tE>rJIjdG<s&aN=0#+O%WukN^0++4%aeE82?QTY-g=hmJy|S z^w#&cId9Ty^?FGECZh4+jH}JgX!tj_U(*SGeNZ<bym-(s{$#Q3zxV-b>Xw5}wVAru ze|iSqt2iIXBJP8D1hham$GQJaJn?h>J|#oI=-NfnM;EY~PfzLflx?fHi14Fzj;+9d zd{teFkT>V!8Y0W*jYPT5+){?G5wt^pu9+PF2G69w^PcnZ?`ibL`eHf>5^fmXW(G>K z><)0OT3xr;ZqK*#u?cT)b`|>;VH!=|y}lt|-hKY!mqlV<@7nmLFWK!D6M|_BELpkx zi%xiV?=xJ7^q^gibY#}Vct2)xj^OxJ+hW0t;E!-Ra)J1vlxhB6{dTwPY6}_Wup7MY zlO0Wj*mM+FT1G|uhfk+8;c}=9%N&+3FaY^Z;j!$PMY!Jf=5+M%ke`!4R(OBs#@r6G z%L|g0x7NiQPpz>m@%BAQVT<?FSLPz<z~kv6FUj03pmIfomJYKCQ#hSSYUC4(nxKV+ zo6#&c<M|MuwH)VL3%Y+-YSOE0@sjr(%tuJ*oopkyCQKXFZEViNJ{cG7l89t2Aol;C ziPx|){4@`%-ZzMj^Qr7+9*GPKUJ4fR=CxpmTn(|m52;p)cQrN2kIbRT3uIghB+q6w zy(v|U)89&z^Q2V!ebpI@Klp+A-<+z<)w5LJL=LGPl$jt(ls@1SGG!!ou5FM!-mejw ze9-yKk-rHDN0`&B+ib`Q7C*%uEsWTZk0$wHK=H1_LTm>?P<kIk0F_qf)2NH<yoHCq z)VC0Cbl*~#EKc#d>I5F~hY5cb1N-ix-Wqhz%BLj8?OJ|d>4s9n!#2hw!Xsdo_2G}b z(af>9DMkL7Qwnn(;pp1F$Mz?57TM+rc2~i$^$?VFV?OBq_r%Kr!Ck!u@diV<(j&_b zTp_HP3Q$I0Nq1&y$FX**Zs5GoX7U{LSScvJ&R^g3KylP^E(rVy!9kPw9_S}#B9d4A zNaDqHr0k4nf~$IuA&Y&4SyNBAwLgbwd}Y60w1@6-(Ex2_$A+vfdE7^2Axk7u8K?3$ zD8%%GRpV+XHD&orm-^J07boxKniFGEse*vNICNFR3RELcEtuB&sTE?!o5}NM_*Gh; zLmSxAb+VOZ8c+DF=Y6TYuhv-#iG$&5I0-qr8#T)NeWH5?akhaL{`@yY3MrjYh@VHU z>vMw6odPMj%VF%6>cRXUDH2?EDxt-!YT4B)j5Ru{u=!@SC%z#+cjm&H?tO^-I?A!& zPn_#i+jE2#u^~*bfb=4E_uBISYw-7nCKsVkgwoIP2sT95V{+Sf|CavB1sZTOq{nVb z`jeA+Hm1=elOeX>&&qeTtTUcr@aSC?L9YpPdRPN62|<EwjmD7_2_OKMjbh?AYA5H$ z=stlf@+wR=hvK0#8T!e=&)RQ#MQD_ocoNM-o!NY&qU2d-?q9Sk@fJM-*;5m_xZbGE z%{1=(LZVBQp8k_Eq7?d+LnWVVi~u?kCV8IVcMEynrmSD4jZ0%vprVV(rw)!k$$aV{ zC7Q~Se$^jgYMGeuf%iOZ3z}U_EM>&%5yCXm*~fRq7RTM7)@$;l@w{uF9uMm>ohUx2 z32*Jtkscy;UR1P}L!n73K|=E$yM&ZR^;1WlDy1pJq0iYlc?h<%kS|0x<<9YO2?7CR z8Ut(wN7M03Cl=MQ8fgtbM28~oRG2xe`Xt<kAR3}6iwbf4xuC=_$8)@oLEng>`=)We zX38>(1;+v^`J^C^?|-OE{?hYsqBJUcL6*elhPQzaKZhINS%McVB`%migPW8$!Vxaz zNoI1RkH#wBM!3Bd1--(qGumuQ>3?uK$&Vz{+vr&249ttLhP&pk-?dolGV@z|pcwbP zf6FYfft?4F8`tVeWQLa^PWtP;zmbBH)BNWdBM$30h)}<EOGd(XJy_KgbG4xLac7UB zN|xlhNXG!VavPx!EF=2f{Huyc=O=FtUl$Rt+}Fjt9a;a6K8!(j9vzeLwQy_4G(zlo zU3?m6<4N%^VrzGAD9vM5l7I|l!M-O%D!k8EUMxVO1d~2HAe33I)J+~6=f}H*?(G`i zM95VR(|J0RQvZX3JNBfxCe!Z|tpp2|a`Mp{5+Y2E2AHKG>PH_ty7#Q!Sm^G~#e1>7 z2NM`~NH(9aTpCXzj#gDT@E-tQr1qV$xlbY|*0Q$D8J!SIPJs-gNBbxp?}hx^`+RgL zFN0k<>p_2$KYMN9&WdSq`mK{@$1zru3r-;dx><#nuh(pWDzWd;g+0N)xVssR(KL~4 z{FvYR!zB1_hnL|Y<0j@@wH=^>f`GYVuCF85Cq*~1!KX{;)(ke5M)M$sNLsKp&sWRw zYTS+ki|f-)>P9xYEWwOeD3J!K9aVS!?G}pz8(AxYuGhTTrX*h8Qh|z}X-<)TPKW91 z0X69cm*76%6R>;+i5^`X!_w--UJ0(jG2U<Z?S?*|O?YV@?jkSeVQ^Py6Jgyb8mBXw z+Gg;W-+6_hoc}p~_9dEus+z`*AEB#7PFokcci44rPLYD3yV=4gvJwsEr71@<XKaDq zIWs7k!z^o9j|!+e$?SMT`<d-=<`S&mzAu%|w{9HK#a?m<1zU-&D#GMPWV|&Pn{W=a zt4K%61o^u-dhj`$^ce$!U@yn%x?|Xr)|^&xc7bU6K!S|;kGe}1FBfd=m)Kv`nhOr% zERZ4=R<$~Vx7v7vAlah2gD6-Tr_e$4(<O-N)W`hO_ks)<Y80DY2Pqv7=D400_^3;= zV{mlGoVpRs$O~m32xCv$XUS0{;YP!Hg5ELgq04btnmY62L5wMJcda<gMfh>1^+f?z z+(`iZ{<u54H7=$KZgnS4^YHe1Hu_6NmTGhJ#%Qq(w6z09xUy_z5Y2RsrcR5a{=PE< z6dL!p9@#?EFPIT?=Re-ryJ8)l8C30YvSh~cYsx=I(MIyEtnCs;1IRWunf}|hpo^pH z?*OGCh2~0z=jz4IPNx>E`xk=VED^lj*yI-za?gqtn+oD62^odrC&QnK3~&$4;i_Gk z3+&?1aKp#_hs9i;1*!l=@ADxO2*0)AzQAo5HwVmAkp`157{H_RHU2*{6;*C=sbV+T z-`qnI$#g1czNL;jC_1h=h!N8PK}7jEO^R9Y$V&^+HwLjB<ug1Xr5-_V_D}klitmrQ zz^p#Vls<E3rLYt1>UO{(opENyguf+>;C#xV-L%!3g2R-Q05cTVxe21^Mc~i?aHhv3 zRV|t5$duuVsI^dv1PTeKnt+u~5H`BwuDJr{ud5>B)I~vLqRq|h+cU31K_wGxh9Iu2 z?Ub@qWQ?_mn{riox_+`|u4RQbT4j48s${xgOP!_2LbbQi%I-C4KH=Kw3QkhT;TM`J z?q5ovAkA-U3ZuCSq!{cc<gyx%FJjChU_l14oOixJPLhdpMf}`5UuzIJu$3LHDk`d> zwvDjB^g;t4x@%<FN`)K2O4_9ku*gZBFU11ylxU^Vd{0u=&fQ<T<4A6(h<!wAJubYl z+<|rM@HMkavg0RQ;=aHwl9*KNk`PnH2@MW!%umBG<tYjS_d{3ppFhUueze5`%m;7q zw*ZAXA}z#56=?$T%!b+5v8zE$=UlX;Y^ar?7=5U*#;(E^4wF-!;!<8eG8)2Yz6L&h zxsEi0@-UhPv0RxO?dNYco8NAYy(H}8366iQ##hd)$Gr$3MX+i1o4-~FF|gk-yk~>0 z>^AMd3%ujm-}5c-Dn1hpek@^aViH8RLS}ybjW-4O?j|S?NUHMYtB5Wkb#_(v9C~j7 z&8=4<Vw(CeDj_{HXDr~-SCEv89b-QoH<RiTy6SxOs)B1d$a5*bz!g0v$*Jd+hWuLk z2G{HZ20;E^<L=7(sa{&B1StE8jXu0Hqf${=NfGw7`=zjwb(oU^?7(YJhq)`?N7bCT zb(MYrgO4te2dRx?L%%Y9t=`%q__507M4JKxQj#HS-YX>=OEyG9^8+|T9l4AoqC%YM zbQ(zmb5_h9ji0%zHn7mWgc*xHTUBH}sC}uF?EXaCe2k60Kg~9n)0x}L^F{g-pAtja zS$nXWK=uVwc+LBEtHBgDT6Z?6v^h6I+{@O>hsD9UTImkj30$h7qM6__TVqsmI*?Tj zw)yMKNlkAO$wE`AVaO&B80E8ELf!Ti7Cr<G22k{lv6yH&V!JGSa65u|>o|uQGl*bM z6k&5wVhcFhv>gX)IG<7Pi3GTF>m`(P_iRO+_+5(nmk8caBSivtVER_`g6snBMFP$e zBHChKCi11QNJ{J9ov=&lU^R}~t!fTj6~@7y%AX?6?KtiRo%FYz(S!YE#?n^pj!dOE z_%wMJjr)0TgBe=GD5l<@s77sse`MYxqrSp{A%oJ-6&b>n+XI?2e~wHEJ1~c$$(l9x zjqQqVl`@$4L;c<>Jg=omO7NLc#5I4<WYuLTFlX6Tf#nW`h{TjNHO9ES=)@OYq5<G1 znN{1>C^!v0d<fL=G7d0Z)6XELwP$g(`kXR_$E`T9q|O(EX}{)-k=V5#1)AE%zqM1M z-n8XQ6n3&qM8wl%rtGSymGu7xgh6gs?W8Cv>GG*4_Vh>w%w|-X+h=Ge@-e2H{!8pP z_k&Ndwmzna9iWam@!rE%fuq30=cv{la1oi@onOlhWfA8&;BI0iH|JimSgDR;?8SK` zI3dd{oyDiccawj(GWz}wH}VFDm*W+)lQicHjwUK2ao^E@3e8MM%#vpAGxaFzdhM;H zilr%=(6fZ(uu>WaAf){)u#LXpTentf7fc_o-X=d9<<7klM0u*0pb^c^9l|t$<3EW5 zqq-?fvwFY<6tzftHg$gD>14!k2*`#6+^rR+QfHT-lk`XPXM9K!j#+?z;nujxdNoQ5 zLB6@_QB7$jPm|vD1_7=&2;1HGS{XuQu3_vF>Q_Km7cMvHg1De4EW_M<Dkvkirvlqj zSlnJhk21{s%85s2AGi%r?NZFS$kHXvq~kTiF{EaA)Gd3DL$0FR2VKm(U6)?Cpd3|% zHJXPZpZSPw=2O0wv$Bb88DQ*TV_HMA#kB@(%b4#11=ECLO!jKpsUW6BbnjJirZtr~ z(-@b`fKU``tRa%o;LZkzVyy8;{A&@EMir%HD!G~q`y)LKzxTq$+l`4qN1gOvIhwQ> zt6tl|syi7nOprHvnTE;5Qj)L#djC``s?TNzNQBm#_aNR6L}U5|>pwr|-h>%Xn6-P_ zuBC2Xvgv4BIF8f$e#K+X>Z7Ri*=5!9`J?u6yw`7$%{`)K4&3#+E=&B7Q3d;<&pyvY zTq_?MaNVZ)v$I6pL%RxQ%n9IKmBAtIwwKZ=V52LO`>)U({@ULcyv?}!-h5OADY*1I zRlZyA3^vutT-iwr=QD2Jw(KgPCS`l}C<2xCbEuHVW2y^gtd{C-9>w<4@M%8RMwpWG zPd~@FQL8Na)xp1r`FVYzfwradK_#XwMF#H=6iYb9!#lrP*5_^sOgIPRaQ7GAli-tf z0N1#XqFpIVK~bdSOipw`8n3_{)^FfwK4XiK5^@PK=Q6AhrJSfI<rK%VqDE!DMhcH6 z@tbyW_SSr@RtDi1!d{^+G%6;DGT>FN?PEE*HoBL%Z?kaq-zwc{DnhX;=E~fbRVs<e z`!Nk{Q&L%-%!cMKGq%6sd^;%^WLYz(X=f!1?cC9{OyMAWQ9wfZI2?%OH|ZPzZIO^+ zg1x+Xg6h_|XzJO<7=nL!dl*i6nDtpJP3OUyXr5R0i6>BVqsp~>YHw!}cJe7(4QC@B z$H8bAcRCpY{8PzP<Mxm&(TcRHdO5jr>yO$cZp=%0)oA5ypLUY``j!%4^(M>1My1+5 zWG26#UcKP?n@t@?b_zX;N*Shp90hniQlcKVwL|In;k8x>(^cQoH5u~jLm%5N(Pc9} zr*jLBDR!%^=Xe0J+dPXh*Xhnd+M=I*edbjk?|CHZ3*Rm?Ge^F~z8seeZKvR3R-%qa zBc5!Z{D!#~F-8VKT9cJ8pWI5k%InV~W?luPl9KmtE3}Kt4-m;hm`n8`qlt>6-}5m^ z`Ay_hc`v1BRh(lLapI{8R8+-|zHuyXD88ehEyUF-I&P*q&8XnBWa1-~Nbgeiz-j-F z?qVv;5-)E;o~M2K$rt}1Nk4h!B+&CbnF2Da9{I%=09!#$%aa%-&lzT)c=KuZ#`mN& zP3<_$w+JY=N=DnC8~VqzOCQSSo<ie|?zCUf5_9zm*PP>Yed!3oCu5M0gy$=To^E7{ z^VGhU@|c&+{}(ZmDIaxrBXmnFR@9%!sg)(Kak~7&=j6u69%~(M`s=?_{e_==56n?- z>?J5>w%W8MoZn4WV)hvJ$c~jXL-D+Nx%naB%8<QK4HJE1am!j|LRm6bXGysyA@zdm zn<*J7mCM=TpPxREAqEHD#4jT64mj5iY4n!MVwNix9?cop$T;6rzG~>Jcu1a}tWiIX zm1(f5gK<^ITo^CQ|1u{@^Yc2Imi39;(qG>?db2#zXusGV^$k{nz`<=~SB-)Qy;pCT zunUcPIaBuiGmHOD?PqDPLsVI^v2OOyfbcJVSa6Qn^naMOk$W{thg}SN)uq5+kw-uB zHirj(_<J7x_|GXiutQ8&jk%>T$5-iaHjB4MPzvk^UYWu|U*74nt9?x2{R?)(uQr-_ zchIw@C0(R3H7Z+^eWv&61&ol!9qXM2dVKECm0+3rIMO1Xc;sT%dU~lrH#&^E*+6DD zJ4shAWi_AdQQgQ_ixk5wj}%Q~Dn%R`tr0YlR4vydbJp$;7tjO&UE5^yvs(`RPwVcK zy7C*hc(4eY6^Yd^pUE%c_4W5i43#hP&!S~Tz#h4p#~2x-ms*7S0MV&Nj?Xe~Z0Gtf zTT|GH*ta??bH4=EThA%OK0N~xLvH_$NS!zse~zfr#v6^?Y@AFGyNxXTQkuafsVk4! znbdxKQRKQ4S19~rTa_~ZbX}US+~#>giAv#XHd3*Eti$&vYUwfQ<8x&lfi|=viD=bo zXOwiF<~|YglK$j)?n=(o7rE4VzmLD9_hzj>K|A+EjFXE)G-Z=Oud3vg!YXX}+PL~w zbBo!hAwMlPlys!?w)ShRXw|N46@FaIsPi%FJxcJ+95B(6E7G8ug8xH2-!5kV`1ifk zfwr>V;|dIi!3VRjSa-kCuj`uP*P-k2`evEC^a7LK&q!Tce@digopFMiCIDp9@p35` z8ia6<a~CmBtK~HLqn>_6jX=l=W0R6BS*q8cq6bD)=W=BTsU%s5JhJT0dw%NKlup>+ z@Rso|jgq^-z3-0E*oF~M`3lBFE3skcz<QGD2#cx0VhVvW2I&@4j-msT&%|e@o{`BV zd4zgzX<)-f`Rg~53(N^L@kb@<<Qr_+ijf@DF9QGRwiT==CF2ugN2rf~GTTN+oh=#a z-CN=2Bm~^-)r<xFJNgCr@Ah;|4|}`g5t?INr!r|IwX>Yi-hwKF-Ja-C+@li%hCh75 zDzC0Jqa$Rz^@7eya|uKuJArFsK|2~+3O1dQxcGr@nEfL09$mE)`fizgJk7=9<6yaw zfQFq6<&G7QH|m*|FxnU7L;fS~VeLBpuW+|l#_}Pq+Ed6VKA%U5riy!3SxDE4Fft4c zMgT}%VoVR%q2q3>Rgnc!!K*zcJKWVS*x?Yv>{Vrfl^HP3{aB29Wg+a?yZv-mRDbm0 z8hNF}5V9jEmEEBXpy?1zwb>DV(ehaaK=<Qu!Nz;nT_Tz4=K!d>Cbvgx+_!=t*#%K@ zSSg&!);A)vp^=06Uvq@4<xHHuj$TsW4VeP6AL0$vum<e{&88CJc2vsHNV8|NT?OJM z;f}%-N-ANvtYwDqHKn0Wc6LlHmFsi<%)x`NQoqV1D6ZLQ?iwJ<8;OkX)dc|qK`ZQ# zt`gr*Bd|ieZ8fnA@S9jsfF+`5vvuo>-es)UQ&~gVo^jAeR*YQREs>1-Ur^%|e(Gfk zh1czOh^gjRCLjJt%ehYQ^K3k9e!vcelq|(SG>xFa86aXCfe3%}RNv5<gZ9x@V5F<M zUa|b4?NctX1m0?8_N_=F{-`yu$Z`i?KqTn~;nuSe%W~KqUk9#xU7qHr?E*@fFf^wU zk~%nv19kzHvEc!is(QR4osJNE85I9f`|CpxOhaxXUjUaq7@}oBA~kC=RA{3~#jc$R zm%I2@MxjjQzZ&|C5#Km>&80r2N)XSF2I7#d1Y6-9CYhd9bjj=n&C9W7(AdmRtr*0; zGDs&*UXAeSx6;XND+CdQfQ(matXZPz4eYh%-<Eqe_oT9rvt%aNRkFhnca=2%Iw^Cd zqant{RCX~j%LfH|F;iF{BKBeD{^A{6O1@_UQoV_(hQzp(&MAeSf5_emtIm9E_a}l+ z)~Td$t0eAB$FZ`e_G=orw`-o|u{5I?O*&4#jCN|t;D^MAeGw69H+w2$t+ARjv!96V zP!l(;Q+Dg3{8Hif)c4yrvwkZ&ooL2B$>*u~Qizev>A1H{H5#!5=1#xmk6cplXXB9t zrHuIKt=}g0)c}cLnxmz%1dUVZx7y!API=Lqvhz$K^duU@uq57(bkX^~^xb+dzvf8~ z#``^2j#dF_DZ9VSY=-WoHnP^Z7D%m%NyTK|!9)f%$3b@PADI7?YN-7TB~s{EFN#U( zdv^icRkyGbLz_ilt8a^5YO`^bEj0(>Hm^qfC;Mt*dl(ev+Z`n*J}37@bV7hilD<%# zlW7hSmT{rA7tP(vcxK%9sFIvaG$tc4IjB}ja=NK+>qgFPAVm($6iDQ4`!krAAf)$c ztZCjp3%%h<{V$MHGO~)PyT4aqC)wIJEw+(WJvh}!Y|NQV#pTbc>NDdPI{{N?lJY8j zR?9duv#?0mXkNn4&UrgG>2Bs}fTiFrKlEMox{1j+0Sj*;l^~0}_*dV)pUioHIo|_^ z?s2P%hv~Jw+Q)Ulk21#nGs)%%FQzF?;@pO=DD2k}jb*DA{%gF~y0Ieig#Y@o|8)0E zeY52T+RF%i!tR0{==SX#RU<_%y3&g=`5DMhjgyY9XI_EM?;A@=(tkF>NC>R8<?dxC z*2w-gKU~GQ;?<;Ui52c_!f4veLkCN6O<Ty?4GxiuhLx`s*S5xX$`fD7*vR$aKQY3j z)choLyaGEIhcJ)txI(sbX!A9DAi<a<IV%e9p^7IV?)g-<)Bs$kSc|%yXi__lJ)$SW z_NK}2+K%~-FMowSdQu+McLdiy{^-pxm9XqpR0E_6I+s`T-c_@k!NE*&KCP&;b#Dzh zt{EJbWtcAQGy1H1;PkwYQqDA~C?~}h^I64ZiC6V?|0+@TdOlUFO})vMDv5fX$O+GX zfw(RNb6CM}w8H(RW^x@2@2lqBD$%?f9=`hr{AP!6QR-(dfjBRy?<tl40OasFJ{<=J z2H?@GZHu>K=!mG*IaJx9TjY*Kk{GXGo<zopP`f)?u-hu(r)kGkjwj>YT9%$6YF9cG zINEb?eV8#c^f_@`rzisLuWrNW;sP#(v#emeb#20aodtz-lTMpK_G%6ARK*W4q_@sa zue#qV{|)n<6k9}tE%ot9o$;!~L^AYAmuT2_K8Q^ds;OE$@P%Lgiik}4piD^%dOYd3 zOKFm>3~Xdo3P`6mPVtQ@jdE9^Bu!;Vzw%D}9#yCwEm)^C1K`|b4bCNsnp8qaHmJ6C zU?s~{Ul-ZL;NrsV>i{@#LVX;{zZ_Io&lIsx5iJ+rBafH?^;ad<k#!Slbx1i8-UuN= zh!g@R&r{|D#mA93rpZnSH#fCKZ`}C{S(Gazg*<l2oX5J8vhs{#&ro&VTWa0d5{(;K zvc=egvP=!KwR3qU<H3Nr{B*94WaE(bH8*$M^1w6arVtBaMMi9PXyh9r%QkGz;5?Na zV6O;XyjO{`@43mxLE4kRD+ImjQ~g-Ww=*SSCW^qtCLK3*q?8n!8v^I(rOmktZGM4q z?56Q}$Oq=@MCB;%|H#1x?&chcAqE+euU>?y$WR<K%MLmVB(bIF^Kns-%h%^&A-!Ir zq-X`=WU!_ps7C^f*MM}nvZ~(%Z$Bl;c4k@Ng-XqWCsOR3BU61^44)RhV)Nvd6VtOj z0lzkg`maRQ%{$fCmP(Ed^2Ei-@GL#rhe!TBn8F3zRj9JEN^VWA5ghXRji(M}k;_u4 zcv=@nMT+-Rx)0b@Z5dU*LcYv8AD;FpFyV*PupMwIwct!YffL5qmhUqQ8<l(_Xdy73 zgD$(!)nL<EOXHj!+6=ox(z4<@FRunnA;Rd?ksz11Q9-<C;i7N5xYhxTn6&JX{Mg+n z#p`Eav>E$Otx7+g!j-!jl{4NdG7Fg=wKtGkC7q4c&vpooy3@#eKo2v2odeNxk!_=1 zrA;8(q-d#nN%vW)vJu3;M1@aZ<&{e*yOns&TRo*Zk7U#=;C0VoLz}UF3m2(pQ&mrY zHOW{7=c}+}rt&Eub+K|O0?pT|B7F*3W%R~RAWq*%w^3H{Q<>&-;H+<83<}(L60Xu5 z*BM3qKHU|Vl%Y^w?8!!j4m7$&fFGGq>=u!+QxS)^6th0;!py`IqOxtXIHC=}*C^nS zN6~@|)Q2tYfi-kv871(y&`#~m&77yRUFmnx?9JLjlm+-B14U^VvjzqbfFL=lw~LU4 z!e_tM1eat)mohyCU$K(0sy@G&DVtXVa|g3;AT7B1K1nTL$?c{dPvud(+AAY9C}`nl z#p01ySO7&t^Ugz<k1!CK8UFQxih<UONs6!Os+BwBUk3TB+(Vz*Hd%Fr`*Q4k(JdEn zaZSV#tNPxI&{PCU|9;55R_{hX8TPIq%!i3K%DuIriDRJNny+3<ltm-JB^}}9UNx^T zm@#$WOMpX{CzXvc7?W4pd(B_VQ4>9{<*1Rvb5V=6tK+>1x<hF0VZh0v4*pbnRQTE9 z{JeX#5CMK6ly6<rIK9MoXONe<x+dJJOZyoKSW(fkMW%S5CCzNY(M_~o;4_r^UtyJ% zK6{sniX7C;prSeR>zf5I&l;GoqEX3@;!A#}p*0rN=vu-OM5}6Te|}PD;!BfZRq^si z{eLH!mSG}``MfrtKc#XT8n`Jq{}87*0sqv8WJfeEqW!Bp-?10yzo^K7nFo8uG}C>i zEm<X-hzf{eOl6tNNec&`>f5*zx4_l}4-o-d5wc=_y6>kySbuK$US3U*r6A%0++zjr zdbieSDRlEe6ff0l?SG{Ay>8bJ7)90P&*i75(*76PSn2)axBbsS@49uglCpVu@oS3s zqGx8QYNG-)kJre~S2d4Wjqr%SaEgH(XtZ>-+Hy3Td2X!U4sx&iQ8b{LaSPhL4LMnh z!TYtE$V?}$Metq+8C6!}@%}F?SqF~1EkzI(CMilU$lnp=_mgb619Z><9Ikl75#1Zc ztQt}ciS4A<HYFMEgdKFU0K3=(yEwGFxE#88V!QY%yB>&>LI+(Uz;02&?#{B#M-S=U z*zSkmq1<ryiJR|ZV2`3;kFs{pQ-_{lscwzR9<AXXor4}d;O`MON;U1@FC2aw#r}Tf z&~w1>`^~}ccLx^Lc)b?dy&oKUtz&y_D|_vSdmRsYKLYz)1p8R?e|tFedByhmRQCA| z_kB9(`w!S3<k0P=-5=)A9}(LhRoVZ6tv~LdKLI$9=+GCVJ&@`!kRCgbSvl}|c;L&y zKrV1FUvRKcd$2fLA}MyTta7koc(92P>rw?AsuLV)&>l*&9{e6Vgd^D7GCb6l-TdQV zs8evbTYLDo!*E~h@IdA8(D3lc!SEPxWL$7$QhS8mU}!dWWWI7_ad>3;VB`;Q^Z`z> zu06WxFj{6hvRgU2KRkMPFnSCeI}sc^(;mBU82cMLc3nB9<)HEJU<~UJxGjjn(?Jou z=~i$+kyN3`Mo?VQC=h6zTxgsU=4A>*(Z-F_SB*1{jKdDcSwItPLK7T16I_lHJaH3z zRTC^4<3fiMBA`i8p-FL_$wzNYA&!$WRg-cfD1pOC*2ll)g{G8srq&$B72>8es;0C? zrgRRc^gz=FLetN5ro&C9jN-7<ud1eBk4(QgoPGzIF&CP7`)2yX;}MIv8QZEE8HX9i z!<mnuSr?&MH=S7z$62qq*?&K0{6=O!9S#P7=7NOg2%;xL9Ook9=G3!iV}u43zsx0o z<`ch|sEy2}ej3=cpU<qC|2#7P<#0Y1w2=R}H%Vuq*m0pGZlSDd;h1Zo>Tsb3wAk9T z(4e#UEpEOpZc)I0v1Mej?QroIXsOe&zvE%lShd&`w=@8o535=lIb5=LTpAZzp43?; zJ6W2ITef?%yg0JFe7O7vw1O5|S=U+F1O?2;t?X8<?2oJ*jtp*r{+tN?(LS6za{Tib zHlFhM&%ZBUe~kRWf>v>av8#BxtDcHW1o5l-QGdurS0690Lcr*)%0DE!Xlf@kZ9JO3 z8qGM0h8>|<z-w&6YaF_3+w^Fj__dYcCBD%$q3S^{@Vcn*x~AzLVW)Me`+o82b-B@X zj)Oms!5fOg8_K#HQL*c4@f#Y|8(Pfhr$-xl;LVpK8_#q%UodSN#c#f<-h4f}`DSH^ z=xEdY$>$fkTOU@s1)R2QtGD_Dwj7VPKI+;%YTt6x-L56u_KM&3sowS*-Trj6{om2L zhwx5_?oOD~&L4SnVD(PS=*|J#b_94gF()!kch~6kZhHJ~X7%o8;osRuy98{z`NDg@ zBDM;h_DY_ZM&0jLjAHjv<M(R7`%=q$4Z8c^oc6!R@3&O%i!$%G9qoHP-}@ze(EV27 zhtok{^=5+Z!O-ZzamYd7{rZ^j;iT^2wA112%FIah;o|7w^3maG$RS$zi2nX?v;A;A z{%E)QXn*wR&}q!<=twUIv88+5bw79!e_YFa{BQJlvFhL&j6tp(n=oStKJMWqY>vlc zn8D!VRas0sM%IZ8jme|_ctV?SLSJ*jICcU%K4F2JvWc8>=$&$XJmpC^<*PXr7&{d@ zJ{5tSiHe+w>-`VJR4U<2rshm;><mN&ZZadCco3x^&YylfS4%k8s5#dfJJ&fr*MnRb zh+I6=yLj=@_rfUQ;#JMX>#>W6uKzp8rMbwZh2G_dkC)a7m$o&R_G6ch$Cp+jpe6wE z1H{6wmMAdruTRZizp=lcj{p7#xe5}w3emd?`*;<Ra1~W^6*G1fcYKuqxlR<hPS(3l z{dk?8aGhCm{dw&A%kgzC<R)L_CjH}IcNXaXPsc<A_=(r?zjRCl#7ye7d7UA|p!V9t z|Fe!sqrPY$nfF<_=|Fw)P>KL}4~64OqDcGb?f<T03UA~z8>gU_kv0joSj&rkquF5h z|Ismda>j?MxC^pVaD*!wGOZ!)Trimc3NGS3eKrK$WDvJ%BEQ!EqhoqI++3$cA^LJ- zRe&{_uM+q5Eje+?>Yq?gp*V`XkT3-GW2TC?Bdy=|XKO8nJTr_|Nf~AQH{SH*Uv^02 zcF(a#Dw*j9aYmDIK2-t41w9Z)GGu<VUhK~`*#8-ATLZ$J2msi3)i$eEIL?G*f+A)E zu_4wJ^=5Nz?RWpK&i4P*G?aHx%A)d=Arh~+5p?E&*-TqpsA4GBe{HnnA%iE@=rB5~ zQgrxY*=iR;q6dRUd==$|lJnH&v6JAA<0~r~kW(>}PP+WRIwtjbGd!?pmLw(l*rRP4 z9XxVrBuJgK7NvMj0_8|}{?c|c)!1rRKN++O-Bgt6kuFZNOtam}v~g|j^0V)iQ2s1Z z3Ej@Now0qOfo_#;=lEalZs!IP^6%t@(%9|fM{<|%6vRsI?Gz$a`FD#_UfS&zXIPc* ze$Dn=;Kd`*K|)J&((LxiUOx>?EC<!ypzz5fvHTUvwWABD$|mN}3P1t-)P6O|;etRJ z&=^sU=%BE#1OSO+_8L&CesuV_`dW@kGcPNIl;%Abk>BU+J_~)v4bl?ECy({hZz?Yr zIQ)U>6-Xq)McLO7UCmS+w_RO+u4(&sBLMHXW!_LECgO>$?If1Uc2)wAL4$iJBFs*H zQ|VPc06o33Px_c2iXI43vPMxwj%PrzHck=2<01Gj(}HM;S%<R`>Fr9lD8VYTt}*Ux z)^n5!t>gK)IvK2yB&Ckia#&yO(01avk)y{1e|}&v)YR+nV%97|=yHzliu>Y0$Fz)^ zcK9Cm4Zu@W6ilk4ZT@%Jd%NoIivJl_2%qG|i_**0(A>jIw9!~qFv_(eP=#7gMfiFn z#mMP;Gg%L<LamhX=4v}nZRqO1$aE(OQvMWV`V3c{Fo2X(0!L=6an`AYQrG6~Q&PcJ z=9}XVJ<#8^o?QLglU|;L+tWcQ1uv2(p(m{XodhbWi-g7MwhdkRpnsdqZf}EUhSQI4 zueXd?Zf_2rm0kS9^od|^&u3YFkyu;4Cu8EvfnwF%D6<|IqM_UldVVeTN=L0;awlKD z`W(jO;ZuKTCA|^x(8|yxG1iwz?hy7PDtg#F!%6g6%}FyBO}DxGyJ)xv1K_df+sKk& zng@N4HE{?enD9H+!_o!UGUxycr0W{e$tQ`)>*dsq>>4bq#h-P{rz)A_A<J@dVxoI0 z>QG1aw3gMzfK$U2an;7IdgQ0x-y`gq7{y~V8U-#YVA{6fp<gfvmuN(rFjEnMGx~jd zA7)*HHog5iY;l<n*!E2I7M}3Lcw{VR0*#dX`75zc=@L1l^>h(XXI9E+49A{W)WGRo z#6ua#jBPnm9iJ(PE>oZDZ_oCxzo|(n%~YlujjRK2Z<4rP3VtCq#tcYH^HP3FL8_Zd zb>QZZd!b^jBzV-+Us|zK5+eeMXy$vwdqqWmE(MhW(2?)5&axRvtO)GA3ALOJ$W=-Q zIf#@VHP5@{;JPf+S^vdq+bT8W0%Nz>YBF{34*+Q`pFeD`c#TCFSLI)El86wT2H9sS zu?8YaRHgQy9&gDB9tu|!4r?+^iSahX;|nC^?CRn#DZTK1TPb>BV!0MZ{2HI{qM&O{ z$)5UL#B`AaW-p+`=h21g(>t(qUo}=?T@U?O#&=g;Q*@(;67eC~l%)OB)xI7TuZ38R zf6NXBGf?HPBrhwKrH_@jzTl}|dttaeINpptP4j-Sgp$5O_^u=;dFrT}5y>HOwyHly zZoZ}@wtI<hnMWu2MTuG#{^SkCO!c$J@03Gap9j0ARp;Fmt4+_3$3uk(wA2+zi}Fln zs++#meySqZCtLi56?#u)^{oT^1Vd;isPs)sJ^nvt!!gu@j!DTN5nvVGuql~tHTuEH z-ClBeQz_J1{s%Egzohxd_xq2j^_Y{cibr7HE-K<$05ud7?&F}$@OzGsNwYTihJ8c% zin=56Xb6|~{O>Q5C;?X@`QJdgs}5pGxQZAnln~O>38q1W_O0O%-r}@%601t42N9C_ zBLH$89UkngX1JfFgJ*&Rqm72w>}`8~uPxBTimnNH)$R4-cGdyhO{?9n>2UmN!}uJ? zfkLbu<U1g{`1Hzh?!M+ex%m2IqBVXVz3U$1-YNVijGu-4u7}=%r}aT%IAj>RVRF$1 zz|^o+P-7;R{o~t)&)b6AvcIlJ4}^$(6Av_P{aLH+xEo4wVS*3LQPxo5XHgBqHq41v z<H&f4ihxH!R)=$gQUUHNO%AppHYS6}OX_;Uu1%(7>A^zqbXrjM2IPt!C(BtypDS)J zM%`rcMZiEAWxY*zO6zz>(?#URPy6|ytz4AwQi6#Xz_b2ViV65x4P}G<e&{+&=V;T@ zHO;Bn!1<xN;1|u0lWdVGpE)^I(-BYvfwQ^=WBgS^)3(lW8uZ`Fbkk@Wi6IHXpY`)( z_4kfKu6Qq-K3rziD<X<^Ot@bUn(EP67XkbvTI+U=>ep2SN4ra!3IK;3Q`@*Cib-O` zU&O^;<1tu;gs1(u-4vGc(I`4e@H$_Io%XlLTfRO0uit`sIx!p-q3fQ1=Fd4Nc{P$S zdcJqNzN?=gJM|e%;q|k76}Mkz`uiw@tM`MBiAZi%O6j!j^QT8g>OU4{+b<g)bWE3Q zKJ)X{o;WG6BkwUkhdp6v>;BzwV0zr2W9F+a#(PYp-p@7Kv8!IW`x9is&y9!IHu(Df zG-K@NmeknwsNelr9;9tYP48yn^Zj|LUfZ70*v-t3`-|FywgYRue+!HEm(62sM_yz9 zR{q`p?SQmnBJ^(87_nFVdhMs_W4Bv!*lScm`+14p|I#s)ED(wq#DAJiDf~y9Rf?tU z_(Ru4S;TV3iVbkU0bhu7GaYS1QR`z2=ablb{Sbxwzbp;cXILzNE^snEfKV|I*E^6n zBapN?5I7eIz6ylW1yM)`Q5gr(cn8sC1Ti!RG0g=rUj?z!1+z;B|KB<$-i%=W=3v1G z3)59FoGwI6Iz+<wp?wu1oe?7293np#^5iN6K^Lkd9japdKO!dej8M(yQ0=);-K$W2 zx-diOu;<2MFTKOMwmpoS!zdNOdTL-(x^U157|ZIu2?byBgqwSNoIoLK7)W>?{umsB zhC+<IJnWjojJ6>d4A8+0e+&w~caAVlk9g_rfdN3yRzV&Bf*~vhvJQuAVm^h_i3dnI zZ(<<+S3s{?f-V3g#5gil+ST1C`aC=m!wNv7A``Aa>t^6u8*m}9NU=@8nWx7pD&osk zRK9e~agwK}SJc8+58S|LY;APBcep2SbbCLaBW>(A8?R4NUj7lLJ<?JB&7dE|(aEK5 zva_+p!2$oHW6B7Bb?J_G0>)rKeRGkWfT**G_|;~<GyR1B(J^HtT+Z3Ze2>7?f_zt_ z^7_M105NBC6dg8PW5zMS0nb-26O5!F>ljEZF~Ko0<OCHbM<k1H6PTQi^hie<y^jXb z#~G_e-mgMd@`yCyWOxIyp>7^neef151itHijopc}wMIU=j*}`#K+vcB<%KG17_CT0 zMR|uGmBwQb$+haS*2!*;88Lk}U@QWBj7ee4^mb2ovz-mUgC}RsK}<+enb?!qUL|qa zn)axN^U;F^ca!enQG{iZj^45F;KYk?$k8R_WEHe&mS$S!DH9Q3>lK032Tq~ltOvZt zq~q*lyz@5WaM5uXc;bl}v9cK%);V(v5oN86lqMq8uO-NXlc>T;v2civPjb+A&$nfs z$=)7Q$cMv{<PHTk(cn(BjmDb^zb6KV0Pq{25I6da*HJKb8OGjbP?jx#a24QD3%sBM z=kjH!)@2JlkGYVJx|jo>1`@ks5hTSZ@F5($ZpPiFku*(bLXjC24#oem3VO)Bc$a2R z8N+&|$rJzp6bXJZ0DK0BSvSrcxTZM8K<-vOj**^q8c*$w5@h~HOR0gX;DiDC3AhI7 zKU;FzG@wH*$R=sUyV59r8DgPpP<~_pg>PP!c~U)2%>51s>5M~&01#pbgh?PqC5b6z z6g|zJvzP8h>24RLUnri(>+vKW!y#(}B#mY{XHbYoQuwBKvGHEwc6u@Lx!bV}<V1tC zGBbK6vDoB>!N3T7ehu!@Cn5v@@SSm@Fu*Sw$){HoJ9Cf|jQfNc$x7bm&E_w5UPVXH zC|pG#?H-X{y4w$|4>#*>K9HoKBO~p(N~}yo96t$3j|@0u4#H5*uvL;)rx;r+{dt2G za)QW0$p92Or~+Qa&Sg?uM5bZ^;N)5Y{f?Mq-q^#*)KfsrAqo<}N|c>PW+)5!o5_Qe z^$wjyrrITYNf&RJfz4&V4wwWCnZRlzbBxsTSImed8NPUQWE$DJ)!9+3&_fz91o{Ay z6$E&_Hg<dPi9JzFZgi<>UTJPrc2HNP{ceW+0QE9MRR0Z_%J-{JeS}+CSp#e2)4c-o zy2^rRSTivM%L;t6no9`44`&4>@q)#CBRJSnJ=MW90zgkVz6S<)2!&vr-P9QrYs=gk z_y7S|IAO6_<srN{CMk`AvFz12<kwB~8PtO~hDVYo@s&|klui75(K3ahig_2es4Ga` zgO|%T>mCj<9%$fTYkZ^z_PYT_!SUa)0&_?q8)hD%b4_Ae8K>~5Lsmc!D=D3c8_7*s z6va23f0WxM3HYxYTL!=dDB=PH@DQ0=-_Jw32+1NPJwwI3>-^5Xhg`06<NgO315`_C z0zR<<D@ZD!L*&0&OIGwr6i@_twON=|@Ez+nisv<3fb1jZhQ_>x9hsU?rIt@*MT{De zwZ!3gd(m6^jax0C3>2}3GoCSmuoVG1$@?7R$8+Z$vBUQu=q6Fj%Zj?Hr9CNBz%D=& z7zzMGKUm6Pj@RH5D40f$%%QfN){JB^uicoQ0<;%~H6wikAV|iPR57M)Vlo6(ygF{c zt!CdN;gHp9w|gQ!me!ofISO}~A1ABPDt0*&2$JC1pO&kH+4`hC2#}@#?_6nQG5{ax zm)$BC?x+<>Y2KdV$5v|Gm<-3S$RcRMgs;P+9F57-_#wLyzdH4al+B38YMan-@Xody zuDqhSR^IU{p#_4h2LayB%)#x*kH_tXms4!Q!GAj9v1U1FR!}4>u@n;DX|<D88$`>L zCg8y1FqeXblPoTRbp#p<hq{D*x>K=vnabDQqT|8_QnKucrTMFWV{1!veaJ(1!p>@e zCj*4P`5@_hkRwdqE86eLa|0&w(z2NY83*8w1xRBciCZACg=u<1G*sQBWmBLINm4dV z-XH7_&DHD&YC{9bdMRak4{JfcSBboly-p7szz&irK-;ld&Q4TL?g7vA=cG;Nt~|5s zS<?0=ne9eI8G74!verZOz&NNWi%@pVW?&ryS)M;Hm_P~|x|d3jh)m`MZvvu`dHAnt zTfdM%Pz!kl4taIbsL6jawpZ?J>fsx!gl>6ckv|$v`ajX38_CVT(!>=v806vRjT88e z)4?d(96CF+fi0^<Zb*D%=V2D6t}WY~#qxxR(_+tTk~=Ju2Z${}MYE!^1;`xZM!GkS zfK4e?jnl9vP_)Faz)2LG3jruXIoYVwjDWS~ar1#s*}&+$z=~uPn45IkOLLq;C6dx1 zr$msbT(B+H1Vzi%zXojlwlpJ3M*d}Kz}&xftBkCr12s}Hk=+5BLQNPgg<nJl;8)EA zx|VGslQiPG!24N|Lh;$AjTn7kULFyL88HR`HX@om82E9O*se<IzSdFLl}98g3viW< z(AiD-4EioCzi<yHbJXu~mqpfSx%v$&y?=<9(u184ggqFP$!_Jw@O)D?tV%ErZc3g^ z*P9#};I&NZ1}Cyab@mUFU^+lTcVG`#)Dx^vRg75PoZO`LKmo|KZA3df?+RGhk%SKi z;A8M!l4JuMm)0s-tOmMi{y`d$1QoLQUspkQwF`9`u8&P)ALvyl7~rS8`aH7eYJnea zp(})P;H_7rv4KP>sNq`g_6CPPTNNxh%Q?h#Rn?^(LONsx@a5^MiDGD!kPu+`%ObL% zb{d#h*)pym2-q+iqmhG5z{x;waTx3YZ}f@QSOF&{tE|jxof&MUrC*U|-D{fFzj+5Q z=DJCqK*nl`t>nngcOk~FGSmc~+S=usj({E(!kvz8xOF{}LLRR1@pCV?-2%3~bGBWo zx4l|fyyDw@g`o;@s9l~IJUg%%Hap+}j8V)=>Wx^29S|1llZM&-uHIkD+vUU4bQM3W zFSBt*k%mWI0h^%6W6&2u3|=^#%zZG+|9-C)ydNmMFWHr{Yf2O~T(@XeXGGNWJf^Y` z`EZPrt^mOIfO^Sgt%z6X&S<oE2gw==Z0?Yu^Y*Zo(Q9fa|1m>HLF~>BeOlB|dR#n_ z_k*YVkgyR!CTX3MOx)Yx6Y<8BPcl8}Wz2dXAK>q;`y!ky3P7L|zgG?>b(8*T@nmpD zxcs{VN6SFOCV-TFKUWn%8f`Q7C?XNp?16`cuL_JNm|bu=?3p4?G~S+tF?C7Kqlt1) zb$+tgMV&hCc+~Dh?_jOnmTE!k@kGYXN8cBRx9EG#P1Erl^G<~MIQK`zm%;vYkQf`X z5DWn=0&q|N$AcB~MJE07AZ4}k^v&%FQ`bn8BX~@|P|6o4cQF&K-#DaCq*z<e9g|wE zp|<MaRnt744J8ilAVH(R=>LnT`~Ii;|NjSmrep7MaO`!AY&rJf*sEiYB70?rD0DcS zV;*~tj#UUDiBd0nC0P|E9V07*RFXO$@5|+TxqSbC=WoyF^YMH>9=H4LddRfK8sq*T z2C#qh?%(Rmxb$mpgr1b%d{CZV#TdQ)bgGuJ9gCa0fmn{ad-GH4Q$_D}GJt%cNe|}I zdK_M$s9-xPBZnFBXUmV!D#?|!#2WXm!NZp{{mn%brf<Sb5wtXq!*6b<hdj!(7Jtz7 z4a+z(Gw`pU>5k@>(Vd)-)AJB`pU%oJk1ggK4~xqYV{A2l-%&k_xA<Zrv<eoB(<$xD z(>SIka%o-;EV93EY<csU^!jJkzezi+#7ENY+c#Ho7xcqnfSL^u5I`e;-U!}x(TM#w z87F39ea$fPK+gUDaZD=o0AAaT|8Y#!hGn*2%!@C%<rhjRxc8MR{rQo}Grg>b#W2F* zxzM>1xq^Rx8Kfv~y>Xjzqw%~ByY|fvt?nb`Pb5YY4|<}#i5C4L8gzm>yLAB<InpxY zY|$q-N&taxAhAPV_qW}1@B9_4;&Be|i&I%IQ!%lr^@<c0(`4rT{z)qjYeDm_+~uaj zuoC!llx4^A_T4W(3Eoc+cpkY98R%bicvD`6R;PxZ>KkVB^~QkCvia5LBd0QjKb4(~ zvo(yqeqE*aC}Z~2DE9D~?{4I(0Tc{+X4(1V>(b@E`_$<_Jf-cc;rl~MG3vZxUYQ_e z_D4DYz5KgA^Op)c?2I%1v&nz6T4^KsVwSwAB$34Tx@zT2Uk=TnFswK<rPyo+_#WJA zQf%coE1aZhy(c=td3RehQ>YUsN{cMSdS$AHcGczR3Yz)k8Oe2QwAu_7+|cg(5Vxfu zQDUi}^J5Jd+Eoc(4^f_kpo3MJo?Z*=sxYo#>?zB)S4ISqem4}m7V3W~zp;HW+^(@& zzXhPT6xpnZ+2q}-piJp2ytsANaa^@=YSBg&%hz7(v@zk?-@bphd!Uv!z^7N7{jxo$ z2Q6<=f5e#i#nd|dxGygEQC_90oM?nQ7p#6|uV8P|By2>jVRd7+6A@%kYl3q)Zi1FZ zk0yn8MWT15oc!;l#x(r(Iy1qQO|JUgv)XMk;r4@&(VT8;Kxx6gYJDeow0{|t6DyhY zo)u%=f*Fx_9)6lBLQcyw=AZAWV-gUuxnXZ-8TYE#BgW;ve8iNuve$p1&*nM<?mb={ za$-|~dHvTNu~}jtpPpLgvlr-RUG%kMtolZIjdu~4yL~XjpB~eFzx-d`8-c&<p8}p` z5=rlB`{gF*x?+&4bvQt7Ug}l%Mg3n?UeCn@r<L1I!Fiwg!VvXi=B&(NyvO1{EySzF z<E}`{rV~Euouk1M{N`<}WZ)f0?tJwfcN@u~>)mu+U1?Dyt%wnDU!zdmv)@uxSPEyq z;1z8;G)}bL<3VM`a$Go8a$xyYUySuH$xqQ8iMQBIyNn}7gpL!~MtN&a)jb3x*#1!P zAvUpPgo)=(OC#!a<CQN9m;K5-ocSfW1KK)>(?QK;kH6eGo+SuHiM!wdU_@gbEj>3@ znA!5f?~uxSO1r!PzcaO7{(HUqingc1JkSvMfPpe5Y1>Vgn1WXYE5G(39g||}4}$hH zcruQmsX|B~{dErvDZY^24xm7V&n+4^&lJODltvS!w9|d%=2*fm>_tvMx^A)r?oNQW z(CO(_3aNwXzg*T-JxHy&@^SXv_Bw8b%z25FnpROxPau#LBDFTle2I>n!Wofcjgrhs z6gIPE|Guav{uceV<DuI@WL4iL*Yi8C58Qu6vcU-+=`lEOL<+r^g_i*vu+WTepxsE- zqbAF#C+q6s<Izgz7?${LywDbUOmh(kw_t<-^c0O%X>B0T8B1`nGi{-!Bgud(DDi>z zbd7Q6J?&anv9qtRONyTS4<rVd7Q>BxG<#;-w_lW!!cFc>u~q6R<tm%!o8+&o_CKt# zxzXv(#`#RKPPM&;1y9AMNTA?Z9;%Fp04?*!g7fBofF^)_vavjR5UMwYL7d}gOdUIN zqFdGx>gN@gZC4ou4~zuYr{Ee;zScE025A#IV_hGS2No0q_}<Kz8f{GmfK!;xEC8xD zdPIuYt9KQ#anwMu+mgz>C0!UztOu2tW8wE3RCjW&TXK}Xh_z3m7q5FOxG3+ru~7$B zo6u`?&<x}R!|#_GPgwgg-FL-Yj`S+iIn2vRK-&uJm2zGGCz7p+qDWl@7%9)>Wuj3R zYkrRbC`KeFE?!JmMLOUb!!CdCySHt(Ms6HgdTEo_b}j0!Wo-Sc$#fJ?Vsth&0D$`G z+%A^s)5aC5Oy^NfXnUCQVBVM=YEuw7vfhwj`B8ggw&DfqFe@<YBDJ|Bst9Od$yZ!d zNM6nIYQgiTdi!3l`e8(YXK*AVaR5G>jQIhKz;9D=9c%=tuoEM2-oGW=<w^hew}jw^ zBC)mj!PNs-WRY%xnfBx?Q)0Y<^+V?oG4Ul*{53J2T_hS9ic8h#5kVX%GWLp!<xt1* z-cm-=+JhpLUCzbFms)L`;fthL#^&eZc?*}@Z8C!^K|-d>zL7P%PvcR?h#hAWREi9X z63H0x841%kXJhe%uS%7~8>@PWm|aDnfqrO+Xq!hWs()Q5k=}9?tKlR1P3kGj%A8#+ zRl*s#Axh^=fk@0aLDVmbY`><B*#DYkd~kp8n&=DDbM{oXf@j2jXsGlD_;z;mi?7k& zZS#U2EI}1<HB9*2QN5`=%YD%@i?p2(y>TpLq&pe@;7^9mFURcLDFy<c6s<HWU$G=C zuZJy>L)AfVjr4B0s_@M&Sqe*OXuJq!D(JD$TAW>p>c=yx0|uB_m5Au@<RrOECPYM0 zhpnr$Xj&OvIO^+8X%s%~zW^CKE*BQ#-MVJs(V(5t8(%_$v;ISAOd=B%arYpe++Wc~ zs@7v9Nm~ldFp|Kp%1U&Ls*@dM2r$ji4!eElOv8A6-k3U&?RBlNBTW(SrJ>J2jflky zyc~z=PDhZwA7c=o+SAA@N4n(n`uF{zEZY4_9;$z0Rg-yTG;IB!s2Hq8M=#QttSa%| z@!k#?<0ab8_2Qtz<?sdCdDJtuoG2s)@adU}%!itr@;@U4-n5?R6ejI>q0f-jBes24 zb${e@5-~?OgqE!cu5i|yDX$c&HS9io=OQk=Pcamc(Y&UfJ20aGTl1lni2k%PJW1_0 zu5`Zd`>n}aV4rqty>UPLda;<r0nMIIGnnoXpGOS&bW{U-G3owrjrHg?@{*xvDkN)= zf8SZ-`a|omIhL~Bil!Nx`Uq$9@HPHk^yhe;8^JdX@w{g^DC%bflkpvD*`fMs*b5U| z_-9%_1*ia%m+H%N(4RUH-JhADt?AG6*T+Ts1BqJZz-vH{0VXI&_tEmDoKLUJxX+vk z8fR>zuvp|K)!9U|Gw;OHXNcQM{Y`+ZeZs$+<Nx8F$*0&N3C~jGSZN&Yz~h{WcX|j> ztgs+q8dh3B%pBB47_9DbkGQ1w@8La#h^Jecu>byO{YUN&;vgQ*DdZxXO5scwpuGP! z7$A&e*iNP|g`CXLgdi_40AhqG5re{ka>3@p+UDqoOtd1gJ(p%{bxo5Bm-CqorC<DB zMK_aKDX5H?04+UoN<A8)ft9l)Ls!~6Bl~H*DX=S8SXdejRYOF$3M}xj!k_}6@UmR? zDKOpr4u6rWZg@bGWXm8GUA`9yQ%8b+mxB!{WfR+3IcKow9@v9g;uQ)kR8jJlFf2%m z9%@KTFzvb1sCSi2^WYD$44t3<p&zX+BKACIN|U)fH(h6yCUH9j)k|;?24GN9G3}&C zILyBv7SK;1p2GB4an>?4v88IploWXxRx~GI3Txy)TQ-f(Nkr<)4$1eh>*UcY@BVps z*ZF^{007I1#HEBC!oszPcf*OH6q=Y)0*xt%)ijx=mf&>=X2RkvaR^QhJ|J1Eq;xQ@ z!Z>$^_tm(9o~N*0E?6C%5{4s&Aqh|<fXdnry10I(qw^LP=F?ATsLQ>y&aLoRIi)2% zIm>_xQWzIbr?dAMzs!0o*Lbp21F9&ekA$v}b23@QfIXeTjj)%2T~Tm_o@TlrOmR4t zXnj8HNrBn)J-78ybnc@IoPrOtnFbV^nRGn7pUY}mfOv6(Ko3tg3xM4{giWH%gK3R} zOJR{nm@5S`;+0|xhlQeAu90cz@<!XTitA|8Z!N-|IW1>w(}y<7ip!zG$h5~0yyht( z6h{n*O*MI}92x+NCWABRaar`Ru$ffb9uSi$#FG^eE6l|HN18hR@O_JHzad?XOzuqs zh_*0Tk4*DAn5baivZ`4{4L~S3Ty47<3w19XL%Bc`+dE@V8?{niZ`boLSt3f}i5H|2 zkQU(0IW*74Sh74x+^)NcBh&;FZkVP<lUriLVFQ+v%7tA~JyJgXB8`kRR`uyIjcNbL z)5EK@K?Bc3&7p;P1!~TCky5CG9epOs%)P(HbILNbCkeJ#IWG;hhJzW;v-g_eZF^T3 zXUi&jisvZs5)XYs__Vnw0JNR#;(=G~&y3B2UO$vDt$@uuPrcfRydZAqcs0!r@m-=& z8Zc~roYlC-;2&VhO+O2yQT6#)_Y<lr{u&NO#);3E&Ug-l^~?BDV9{u3FfGjVqw<5b zR3+bxRz^OmXu+V^pBaCB#-B>VvR@$DNT?gF^^GJWIX1e}SH!jgXgn>Ujukee#KbN} zia`#D=D$hspz-S`dZLJKr}X1BlcU1v_VIR1zpu#e!Xi)^zSu_bXAtfL8V9@AzQD=J z=G2sRs8MUnN+oz??N#`;l`_2TYNp0h-f^oDxElkby?u4jHlsW6ZHQvZ=ySZk2N=0X zh&d(1nZoQ%iAwu4@}jU<6wC?t<h2N=!R)v}d$M90-v3kyY~wIma}TNd0^dbv5JxNv zpNpXg$q9qKglQ%{gv<d$0CY+fLi3l4vdkpG69CJ1fysU(1g3F-G$(aJ=5w$UMJI2m z4El_d6!lC5*wBM7UZ<)WF&rsUBCAE*)p!(45y9+a&;wii*wlhJ05KOP&J3);ljb^# z=sROrh9j<&rsp?1fBl*!#j5~pG`gLe>Yzw_L6$u!w5ST4b{ruFly=XH(70k-L@I5) z7A-0n<evS0MV2TJ+Q8l|g?R?xlN$jTR-!&O*&nWm{X$%?ue~;89O_K8LqQB^aZn`T z<(}y50#w};pe78R_ZV*-=GshiE@QM=FMCg~D(BWe@3N{+AB%(aBz=NZ(XVn9$Xpmb zsWE8S6*N)#oT%Iib4Q{SzfMS1I-jv!-R@`Ey8&|zfF#wW8n8k_$pmTz>pL&5rHF7? zln0@vu)q%Wsp@KH4#%YjfJf3Y`VJVFxdn|Mnx^s+A&{f4I;83E*SAYg2A>@>l(D|T z&OE;j|DQQy>LD8`%)t&}aGoK?$2!P<r3Xid+}WVfsc|xggZ0LB=iu)yoaml(7M;Ja ztBaTMfYdk~<l+!G@^DC6nUH`qnj^PNYQi-8X`a`o&PUjWQ6K^q0JB({H=6b=Be^?_ zu6IG{x;so>NI5xVDl5TJXXk$?--C2fx`Dy<uP{*qn0;=2!ylq0Br`A^lPKJ`u1Lwx zo$mAEexd2Hjmkh>GL*;SZi>-d=zqU%=6_@SSa(VjR!XEsr!}HF2sav2qv6x1pA2Q& z(&wcI!rP@1$B8Ct1XnaHkg`JYP<+?7)^eCuPK#}QPHa=bUi2!vpcESxxn!@x91n*B zgte_yh*DgT5%!Y#2x~oIu%&R@vr9fbO+|NEiMyqcF;$#gX=>bfiZCG6R(m4QiWqxJ zGbY_V8QF5P2M8s1-ppX1L#8O9lbOS52sl_o+JxN-``%Y#)J2!9urJ%nms=Ed)>xc; z@!TzRR*CH8I8&mNDKRv+FFKYOgvq(&t@`egYhb#Yda7SDeAw?dA*9h(o)s502)17I zp#YZtjklHo%wv!)chWdqdSD)CmN1-=Q`R7LA~zo_JFw96Al{Uw|7cyCUqMHV$FkKw zj++j<{y3cTZDS450_gw%Ts)b?Cy0&|&c0|`Xd;#n(Ee_)lrcV<PvsD7eFGM+)AHZn z#p0<Uf5E^^0g0{e1VcD2s1ffEhhYK9W{u2u+m$04Q+dJWRe}1ki?D=4ywb%k*$i@K z_FiPaQ#1x-c1Uycu%KZj-_uJdQ4Fk%hFHU40Z`J*M53mHoZ==E<<wfDZo?_oAsPj3 zPE|GcbG{wESY@|dQ0kx2@U;Zc^^zOl63J&tzGfMaq6FFURHLhM5xJGd6{Sch)=&sJ z48Z<HocHI@HVw(!E(8t*TuC8No!|slQ<&h{wt#p^%G4fi&%W1!{kVDLc6dQ!8#sm) z5Kc}{2M>G65~B|x<*m?`dDWv219ue-p@5`M!A*OzsS2Ewe!haI8V8KL*}7%0wxB+J z9PL$F5C)!G^7>;y<E+lrn#7(<QQ=S<)>J9b{>_YUFYh~9o62gT(6QS{eB0iy=?s0k zF0%+c;65Z)7^bJsXiziG)7)F}>Sa<l?LShgYc3IAp>!@$p!|gB^n*R$T|&dhj)AB4 zU#_1XB{{R6CboZC%a^>NvR~Lk7shI;Mj+gwaNk}Gl?7J~!kIE|+Lf6$jnObflb7Og z1Uon(fc9VxSIK#`liJ`nVx5oyaDbhB;lASx{;38qEhQ2fBX=u&Zen5c7olC8L*>!{ z^{*A;px`IxmxEv!yDX;wOD-!9VCzQ5J=CjWcEY6@{9UZY^9tC69Wk$pKe(^c69>K9 zZc2Xlwtk7j@DPt$#95*Q?g9$kJfj}c9>IVxViZ1x{?Th=c54cF#C%wOjpIYih`TPz zxnD-n&0RkEq6VU~l-0e7^`#4uuDcx8`zJeu*6%7Gr{Jhl@eupA8{G*-p&bRYcn$-4 zs5)bbM?p<m{+!aqu&Zy6&E{e8rUbjgRC_EjOoqvp{`1oQ!mZcO?45m3=_wYuQP|TZ zBXPRGWnXF(Dm7~RJ0F*fLYZF>APGcPrUB{Q5~guO$py9#_k(T)g^~KP+FOWJ21>Vy zWL5|Od>Qce+a=i6)PP6lJ{P-oOuJ=tI9^;)U5l^K;|umvI9L`95_cwi##%KP#}zl` z!gj25d-^X*m`IatF_fqLWE{vD7p4$WaPTEOjbMlMkHiuZN{QjZg>yZ0A(T$uM_1+P zV>i$ehUsUs{7mArP)h(^|2JaX;YE=?O=uc%0CuIgk&DiZJ_<`?+$>0_F8|?kMZCx@ z*Y<7YBAskS*A>RpgnRW-RiC8gku@NPhy_^DWg0(40PlHHbu+V0=GvEuwYw;y9hOM- zJcJG~WSzeJ=_L+sf0LTMfz-((vKNC5OGSsV`7a)2NQe+Mue`hG0rtdNgazO)#S#dB z^g5rhL}6kO-2?j$<=E3Nj@ah_)>I7tv$$<~eQubm@N0-Ecs$eMohASFXZaaW+Fj6A z?@cL+fRwTGa=5G%8rK`gvi17Ldy*X)02~)qe&4qIUmW!;Pfl9V=V|EC3?24;>#~OZ z*R>*9lcO)s0#CL>)|}cZ`pC!D|Lz2wG}`2|SSb5GTWA6_m_D#=4f-MTuEq6f<bF_* z_-vfuXAxyP51?Ama^r;l$rZto2Ui>DTQqX2Ui$n#cw6^W=6c61>f{f8m&NdT>ac|L zC>QIui05N#ldX1774CIMOQ+x7-}|i+&<YjemJ2!S!p0q(ah*>*vU_p+=W%qCM}L2n z|KWMj9slWTuNSiK693#fSa|07WHF@p*PWG~Tl-N(bI7!Uk%)B&oRdOelyv+1AutS~ zs(N;^`~L9*^P@gM_)+x_B>=@hAdE^GcnJQoggS36w$+}kT(eaVgZjE!9h^VTQC?tu zj0T3#&5)e&Z&j_;_s=ouLQYXLV=DWnVx@7%T~9?bFU1tQ2K|?3PcLcak>{xQEr6#m z>s!3t6q7Kd9Vb8RqdpyYQ16H}|JHbuUQ@d1ySeHbD{W2;%l>?p+Rwvdk{dPrHTb$? zU4#?gt@^4>(Tb2~8bxK=<rrIy<z=)!duZA`vr_BfKzh^{v#3o+{W5X1`d(#SiSGNo z6FNP*mv)O7s(2taKWOk*Mb_~!n8(KG$9Ku52HR-q=7$pnWX+ZZZzi2zrkylE8b%LO z&(-no(^@XjAJTf0!75n_`>JC*m4D;ETd{L;CXEEW$)2Cq8lEwr;r^JV!d`a&_Mg_K zoWC5FJm6(@I*os)-*d#xrv`=Wq&qk=6{dhA9~waC1ti&>SPTuVuy~R)Hs<wwj<)kz zk`aeN7CSGBdO|Nh!u6(Ty`H))I{A2*RmHv7Sf7A324<~}X}>Hhcoaz0e<2RgdQ`b? zrB1Qr$nZnQ@m(?h>NEddQstId(TEZMeu(}D7sD(h6cS!#)a5ZpdHiMNv!Ee6n> zRD8^$`*z0e3UcTCrh-{h+l8zfBJ?-rc2J$nwBFt!$V%ny!Vrr*&%$jWa(}Pb8{6mp z<D>TyBL_+0$K|JFt(iE}2?XC0FY&nbQk8wZ%F`s6=u#P2eW$_hVwm|n2?PPqFajsF z4-K{HSRWUzvuHohKe5$ptoIK4@SDD!`32AF>cxBe?>n+qZh9TVr9^Q6LGa@gW_tVn z4eI@v)E|Ljm)3sN{kBPc`rSL1Z#KC%=7yy7o5n9)>m=nrm7hqO)J8I9dZvyZYo{?@ z!y+GNX2QHA2;xX9s<(P5;H!}dX!K;uO1Tmz`*qr%{<t)98>TR^IHtR&pX0YE#<hno z{BRNB4wY_Ct>$$wqpyX(%dJy<HA9p;OJ+%27yv%y9h6%GvLw)n%SN-otO$8bqXUEP zpgbErWT&cIK>a0dPTIlZ9|AVpYX<A^LWZGj(Oa}Mg3=FDKGV)XJ*O~ko5Dt{l1inq zh+z9~WPUyO0p{3Pu(;J~miJ5&eKaSAhk+I#i1gIYSQwEMJfe|ejYx$AdvdQHj`_4n zj#{}J$(_|2%eUuVpnC>h!eym4^`^?%;R7t6Spi0V<Av0A`wgL`8Dot#CB2XUZ(p^t zaqZjpIjSp%%rUFt%Gt*G&c;dz{bxYlf1Y_PM@ew@ECl>|Kz@O+xy{53Oz*gZ!(~GZ zo|@;$c-6Z=zerr>pM|8<XDLZ{u7gWQiYDsQN9iwBF+zjmn6C?`S+O{<py50{Y?Y1V zX;~-m(gS+9Jka-<(@@d5XP&7)N&HsuRwj3nAn!OUY40yhwd7m+N87!!EFpEor?W#U zUQRPE03iE1w#57fdrmlfC~+SyuwhwO7}+o8cTVQz1`(i{+8gS*UuV0|DFo?yH2bsF z*ILNhxq|L?N#(OKRK19~d7*(9OuE*FoTe)RrII<HwU;kj;(P8Mu5<2D%Cx;|Nr~qh zA{aVrEt<s!g@pCYr41P`C&RpCxz@ldL)Kb7M@)J>`TQ_Xk=xu0%zx{L;L0Dz)Xt96 z6R_(z_iTENh2s0e<<pjzKEBl=)C$Kb<~Xz^ztx#b%4T4sG&t=u`MrYGm89SW9-v_B z!sYDm6mycerHw>X*#+JAw}m*>U}@~UjS-NNC)bKfc~fTzAFlz}&sN`P*8`!Lczol% zjQ!^Bch94QGsN{TF`YYp$kBF%u-&}aM!o0*b=PoEYxw<|^Dh~wh#TO(yc%l${Ht4d z$gVnQiKd%%fG(zZ0jXW?sHa$)r_I$MOwDxrc!TLJ%U{|^fzjR3ixyR;@cI<dO*mbx zM`d<Z)EYuB&N4_+&gT(iWYoJR1p&h1L|sz&K!8trx)Oyyas%x@hr_gf0<#0_!9wk# z{F;e#%xR3`vC!UcHmVvv84a=isdr5Dx8ISTPk06YF@=f82jJ-82ExvhHvVbPnalnT z@pQEFR91W?37VxDv@ZDK&yM(a!oi5peuHDht}3;m@2}PW5iccrv<cyo^`0k<sk{s) zhU^iXwk_#2g4i-EN8b9bZwqMl>1WxZve_DNH}bW2vu&|n`7Ss^{Sn}G>#KWCzm_Xa zKdcf8L_qT5JBJurxsJqeuxW5KRkl5~MBKbcOyGejEW2qnJ5cz6*`YvD^exT)pv83_ z(DsT}S?jkZxj?m5Q-l86KsMdqbl9?+v-PAhWK_J0z*ZX5iyIxJ#|h@wrBfdT{R)wJ z!giX>mo=tWUz6joC(gS?W&yaudhRy9dMUFud4T9-zCvCX>NHlp{wiX#%B({u(KH#v zjb#kQ%8IrwO=~r(&?x7ETi7&OMn4xGHP;t59+KU@l7+LvH<&jLJizdajA}BUH9#KU zkrk16z2+yzozVThDuY6!OfO@`Hn6D2s`U0^5DNahsV1fFW$hN)AF+OfM=Vo_2Ri}t zc1>nl2G^8(bJmr-j$*G-iy(T`5ftBN(+Tx=Nf|dQtz-^$D@bvB-c?0zhi85sq_g@w zy)wMhelDM6fIbQTw6XR@gvp)x8pgkLcPmc;G^UbuHI&wbkhU<pO|!wr@wdIC{`wGA zCX0T!Oo0(<9c_X1PnyHJ#007pKdLgnD69OYjWmC*BdNOf^{DbxLvY{#0ntz2m*?1h z<Ns!%;q9j3m{$LgUMxlw4gj*E1+?+nDR@?14<QJU-zaNxI5UEAPOILqb%aN2$|*{C z5Dxh?W5lqzUm0_lkrF?~2}zPbXSoO%ro33DCJ>w=%;_~*|5t?AIFbi(k$IgCXelxd zH+bt~{XLq3nW9=;>Vrd$ZND@vH1^!vOu>7+tpEafnck6a{T=;d0}@2?7G#^G(SdsY z7HU9N{KqGh5-{36ysC0AJ@k-u%b;#r6?aeu79z~kMwAm6^=_w^Tfi?agEdcwb|LmW z!<=^+2~=LT-4XC*gsH~3>on_#T$Lf|qM}$Ex15UMe9Jc5g>k+1;S1}c*w59cs&jgB z7@qC2xP9X=I9UXlq}X1m|E0p|FIZvX4T^PCNO1H@J6H>jxopaDDLgq!pe9Dxm@#ko zPf_xgB@4eCemFNzrWqzSG1O_9YtWOV=1Vl?gxYH7nb6|Wpa9z3flm7jmF|KaX#%>Z zDl(c1&g@OrJWsK5&R8<y)jqMjoMx5tHzkAYa9Na_d&%843BZk*%BG`%yV{}pZDl%P z+)d+yJ4U`6;FcM@ROOIGFjk{+JSfdvQP3x#(JDwh4RAQ9v*4l=fY*%2h{{nc;xG@b zvLu^$9V!Jh48hamV5}xvNEO`%ZOYsUo;D~2H-cF&8&xo7lFCY|KD|hziDzOBt@<(A zQ^{=SGvf7@Oln?|7Yr0F0GZDg-)kw)^g%;g*l2<&XTw%wgH6kjTWuK)?3(KeFuC^O zQ)SPPpGdNhj{z(gh-?QtdQNqEN;uXVYrVuThy!_Jr&!8AamOIcSUmx`MMh~<qs@lN zB|2QvhUJ@K0}lBT2YM*14D8N2qYyCept<=ITSMOs!o5xsO&Hee;_*!dtM{{XcbIt( zS02tHE({@^z6_my1KsA7n~cL{WI|G^P)MW^jIcbOo;@*uSM6D-wo2~QF&^Pfz2S+y zLT_ZAf|n@91YR}?PfJhdS}ENzkPR>t-t+t8QDACHvfUK&Nu7%BG+R9Z7oX#$>t|VL zhxRu}fYTxE7G~tNx%B$N>myD{hzl@ts{uWI5QX_?c!5~pHBNy%NB}JsBmeJ9Lp?>S zWu$@EfPP~%G!1VHSjD+-W1_tEf*DWyxW4&j+hBRp8pJS>VD(`tcy#Ytz)Nn}Pm*SM zS|9u(s*;9<c<s&(p?57w1hx%iwpRGy5d__BWv*vRD})8*YmbH-+;ep_*9vgC6pPnn z9725pD{zjz;~a%X1QZ-^;6~}P+KtUCF+XO9)Ha4R`|(aIG=N;!XC6hQa;e*n(D;@u z%m5x`h?ipZy*LXDIuYW=0x$${{0kx$O{BL4chfE&a4puy>}2-S?v9g0wt4y6^Yluq zSpN>mLy|=H%yIo?MUxCK78%aZn?4G-ew+bG1VDIFE3~Dv)n^Q(dj`00K+dc|?~Uo< zu4?Z=*dw`D^(S=Pxk+pX?w)4QRRJhx^wl#6TC9+2fbwB(K5Z)RE4GaqC)W%$pA>CZ zVLlF+1hogEa))ljm<4w`8B!WsxS0xq1ifE?xjBK=DJj2CChj53n$R|n5FAsAl>pO= z+tu@WOR}!Bw??>=_V~QF;a*(x#L%QsBPvCcQ8cs)tQC)!NV_1(fxiZZ#`4$wD-9JT z=w<r{seS(HS#_QsvzJGp8d#7J`eEMoIO_iEQ%ehNaWMyy%M$O#R4CN-HQtV!qOCm? z3j_e+$?9k#;~Gg3Fd%#awyqMi8RltwQL06=?pY7{x6M+k>Iy8?-zJMJOtacLrl_;} ziCoiXT^JY+v}VlM*RL&_I|n0EIVHlW$sU)*)NP=))|mjT!2~U1ehg9atW~=jvcXk% zC1846J5AYeDZ5w9#v?HD#3-l1(2!j8g><P&d=y>JD7|SADmvJ>L0-VV_IIqWXfgg6 zjnUj5GWj{Axp85-L1hdx%!e=jr9VB;5peFS^Sa2*dx<Ly)>|6CYh59rM@TcS$N;!` zJlmB^j5G=tpxaFGw5MG=8+i<sy(<6BxTe{5+g4i`#Cuw<eJFSqbD?Tv{sc0=Pa0}O zkLd-2;S2f^{T43;pr(rwT8q$^DVtXoZv5S_-RRY4!}T-ef)zWrU&sXN9Zoe^4SK%J zte*^`|9M|Eo+yM(=9vhUa-#~G^~=(tm=+cvF4va@oP9Huo&`TBMor;`8}Pa$!;JQw zZc3_JF010ykPpHh5_av@9wPY(M*0wVtUdfYSIFQ{Ul!1WOUz_UGPBCXS0-an9z!}a zc(vTuHxo1Thrc|j@@TH?c-#Qd90#c$;`5tBzAldnQ^dngj2-pAc{fXaI7&8B+`nqM zuw6-G)G?~vqu;*_P+M%Q*ZEXp43lQZ^NZ`tJ99(sbvX2!=+!f5i`N1Hmmt>kk0>Pd zt^w|ATsQ1ft)JkP4#AMy?0zxARX&tj60ek@6TruHoIF{twlX&}c<aLJlN&^Pz73{# zr{^BM+%tgaNjm;X9r78LQgle2>jS^lWV&FKTrDS=2KVj-xoec-^ACm;k%uSjISPj? zC0>&8+Xsq=@|r0a^?J{i-Oh#85^bC`FKs_~xgQk|R^@YFaVRKgVw?-;vf~;VRKn=W z4WSx`-YkIW%4R(3Mcn$wIh=w@2tv9N=9-P*@znC(o{MMOBBIbu^J??$;-LZ$u&L#m z#M!ra>#tq87kXH7)Xw06zDZJzuyz;NQLIb|d6m!nrniTx0*{Aw?2zaw6F{yOb!cMV zi|73f!_7PqWO)CI;u<D8b&uQm4VDgd!lnkd1&k*pMmj~io0~;&{?=y~)ehy3O1g9^ z79QfckV@T^#ixQL1SfOX74!{%((>fgPi1mr*q3q9SkU;?kRC(M)LE0ULUF|Q?7%<6 zT5MBLj77Zh5`U1w3m_)!!*HReq;ZbTt#P_XQT(Y{K+%)QNy#G=mRsBTovf2(KE$gx za7e0UMMH6DG1pE}_zPw@=Cp~M>?hXTH@0*t_U;o+(~(K4SBoFV#lVyAHxx$eyhBQO z{Ob7?hZ36R#G9_Da{g=M^V#V^tn`5l1fkr4zDPNv<{uHSF!Koyst4@%047TO6j6vi z>i{Nf_)BWFz@2GVbF#~3m4McA)(hOSf&5!pj%xGEvD$_v>V_!kC>%R_&`qGl{F0jT z0M*1>+jz7KEI~VH5N{)vu$%C}*fzOlK0XT7Z26xrJ#q7EAbA(fkgr*pO`kVJKEgx{ zMJE1-5cpwfctct<zM7joF7nPuy!kL+2}mp;<*H6fra5h4s+a5fQP2LGt~iEcVn`GB zZV^3sIbeKbBDg>|IRB8|NtFB<-VX(YX!p&T3aS^)zSHX}HLw!JJshWwI@p$PyD$oz zb_N_;^4((vcQbx!>k5qgMSqueh$ojvy!2L(&6(Z|^Di#@{i6!0Th%Yn5dn$FvWG*N zE)ckK14PG{PvIC}Fyu*G5J&3s(c)Q+pgf5xX5z!WqC5Jh5)XW!oJn&`oJq#pR6jC2 zlKoh<q%MPsdh!jc3P?hvpeYKDP?hWey>@)~M{vaa_ezs*wLs$e37+AuYX0DxKY=X+ zpN?h^Gwf5q39A?-PAAR75$i%GV%LzM<DCF6U#~(jZnY{|?jKOO+Ve!A+1shS95$vi zuOp^Xv~th<I7fChM=no{?@N0F6b(kgEZBhg8?<O?;bg=q@X5&*88C+<Oq#|2L8g7E z%TG?q?~zm&MNF`<n|-r!PDtK<OCw3E(HW}MTYx#a?|4La$r<MJSAMoL)HH{;!}Ep! z;{d|}(Zf06u$=SI)#<0DpRXpbk?UWFEcwcaWMS+$2#50xJ+?bvwLwxx%=nD9luo?E zi@(JSnx-7sWUZgP4GfL~X@=8|+a?U&HP&VxuB`tF(gv_3w(S{PiEXUpot{teyf(|a zrx}2k#ffJffrpodBG2La_9L6~_oE%{f#tI*=K$cferWjVdF>sY_hIE>7VYC>T8RJo zYeiYd)apgt9nUCQK>i92q-`Pkc-t<n=A~im!G84!L)dCPGrGTGqaO!U9E9|X{UUkx z-u<`s8UzZg)Qep`>%FNSR&5LfZA_^6Td(|=F!}F^tdo4bafyQGOGe(~_3_+q8wva+ z5JNU)X_Lq--p38EBG&ECBJexr#qzIEB=6I_Acu!e9e!`06;W?EHLF6i_I_O{X%u&k zV*C1De!DL(>~#X<s@leE%(nm~dR7nS+Cmfl&Pv|L%_hy5PcHkTq@qXRpPr52VR3G9 z&U?ad3Z-t{T#Tcdm;V`)zxTxNXYvS#)Z&dB?;m-N73(~IGTLbRaW=?a7$D^)ltYqz z-*!<n+Le~)ZPBR`vgI67AuDBlrh9RoH1U-%4cEEdc?kUT>&o&qU>cpC(|^@}<4(Sv z{RaP%8;6=Q4~=jfPWP_1h<*G`6!M+C;FzMU%}j8i=&N)(r3Rq(3yEp*Ay?3Jrc`zD z^vy?-H&4Zkd6e682^EQFyn)R>or8~hizw;-6}pVVIGkoTH4r8k>saYudAFF?fQ3kk zB<i&o$c$AazKi=(c}r1qZ$SEyYg1JsD{mbRno+aa#-(>0V9xb<mB6Py4uGa#l3ZeY znMi`nk7zuPydf79sqv80Z6$E4aVeCYd@sBmDT;$e)ks!zmQ^S#ZQnO!>kN-ihdvH9 zNNy1b#@fJ?IeSI7#3l(xZ5&aPJARct+re+&I=z@PHBj$CQfPvDW?AHc|MXK>yc%6- z-z~Y<HdiFhdD7hTP4pSl{N}i1!bi-~R(@zgd|j+#QnNgpD~wKmBSe_We681FJcs2E znWQ5kAoFHwVgy8jnSootk_EH**#c`vvua;Hhv5blT`vH1oO4{|ejo}PmzM$b15Ept zY^t-GpKO;Y9Bk7F-kt1llpSA5-{g$$)9Ai8xNG%D=J|)&hQb%{8l&Dk=a?=@u(y0F zqq;EfAjw}mb4!ScC()rLu}4}mT^uFtdokI-&~vZzrzn`M{-2AB`H<j<<HNhz`^JD^ zYl5ZN_@d_)SK`0l#v3i;`VpEyQ<c}%-jl!YSH_iFxE>BXpF@hHUe|j7<<AvayBd0v z##r=6HS%l*-SCeqA{S<9xDtiICIa!h9rp#V%p|p7rd)EEM&5f0J^Xs>yljhCi%>d( zh&AQAqJ!<=dovkFm@o!}tyn3_bB<+x`n^~|z5Y;04h>i(0H6X2w>PQ3$8P~g%f?ug z6=zd>9R3S)`^$_u8>{>vArnB0)#do1_-n!&oE5^J3_E@Ja;$swn)w~KJ5}WB67-|E zM|XszIn+bRIMLHp{=~B^pk8hNVuX+2Q8-+56PsobCBkr@_F~+qM|Ue;A=J4aB!S8s zJee3Z0R<5GGq5;N{TKP8QWKgN#r>@Ttg%g+tTJm2okx%~p>YqGhNCj(VUM>qUvicv z!6xT+<*v{t)(ZLoTG_<`OP*2+lVre=2#K7=H{1`FF!;&VoO&b^!$JIW8c`LE-9-FE zx~aSqA-y%tBYDQ>Y7YYI<q#V}+;^x2x2KJG;+&fVCMjdy%!R^#eTMZf-84y=(nna+ zdMVT@ejb?8zf9=2G!)Mt)yCGB8OR44F(!@q%S8bB|DxgFaWE9l-y-*iKHUq*nBEGT zSxd0IKqJ~jOL@KwmP#kN&_{nQZJnreQEvVbM<j=Diu@wOJiiFfYd>41k;|>6$IjqY zU-I_2bZ>@Rt{X2ng6@S+8yo!<CLm++P`#8ofzYM5oI^j2QglsiKLw0wR`RkaJgev5 z43ND1tg*9oYD37J&nmDyBFFo*5%FC$@J{e|O#S!}%M(|CdL)!RuHBY1nF5Ij7JXyz zp|zgb3Z`4Snq`0Ci-Q6Py3}E|oRq4rXb*g@w(6Wsrs)Rrn^SmilxszbrbE7LI`QK) z@O5nCI@k8LpwuhRiU{i+WO&dzh~9%nuSFtWL+zTs!64hssXBpUGGu`99dlKHsmd2G znUGD|$;4c5!H<d%eMaot*sNDLv7}kOml9dV$u0G!GA-(m6Z#l5haEm*!u4x((K8Bx zyL8dw_p~~5Q1_m1d<aY_K%by0V5t0g*vygT&g;l5s8L89lQU&b%GD(eeoJFgpXuS$ zQhtGqqZd))l?Y;>Jp^8o#OUc?`(g8BJ)@y^tZCzm+7OL;&q%)XMk5de6$i#cizc=9 zL~-wG^H8!bVIp<rRQGA$AujS)g8GLGcASyRd*1g^x8O$Z)qg|m7{!!;W!0x!rca;c z1+r_}ax+I)4z`dJOr&(mN^b#70ihQ=cW9ifTSFwWG6|tQ<1_g^WP9LdXRrq8ch=>L zoEk(C60oYoES62w(<(QS?Ek@%6@ZeZd$^&?C;fo)`IHPU4yM)!bn5-NgY;PH)LI!- zvpxl~B=*dyzXUD|dN&B&jIutZV6q(dB<MoX_e~x1?YtVgD}!B}lKNz3Lvz6b)uy6z zJ+-_NKg7aBn2hy~&Aw<n{?+zN+53O7+{K`cE8i#(LD#&>FH=jT^;Hw)c5qqSZ=U7{ zpSlLqM00LY6}bgJmk(>7E6H2^GO2M`LTD_kPMPJsZAp%VWjx%e3961o^+tpMg5F69 z<ynz*J1>PsKWB1wKX~`XEdP%#N0ty{KY#}?f<iRq#l2WBB?CanWly%9C?i`5t8SOq z-7_jYR{^(~zUYOUCh=dyzB?AALx#LaiR0@k>kQGsul_cFTyAK%vt$>%D*izKiptvI z1;a+D5puneAuvjTX*mD*+?)kbg^kwU!j{OC`Nvl)bTAZ8g(DU585%O>FwsLm%iq24 z?cMG!>VtWtc<~|L?eo!C<2Co{r!wzlkBETkS)%Y1DBfeKx0iM$45&J9hZR!Nlq{RF zrXQicOQU1N^fM-dPBgk*^ja-KJJ<3k1oq(j5Zfrx<JRZ*>$Ezb4wDrbuAjY<uwow5 zj$upr(~mG5`j-(ycF%O)>*&(p?@@c6Rbi`ITiEP(7G=haSZ2k;<t^1P?*GMZwG@lo z-n6>+%Z~ju@}C;(qY1s~ql{>eXI+doGJ1v&?Qc&0{*Ewvt7U4JoqHV8^vqud>138o z%RTVsl@cn$W0%-F$u!@x8s&B7ITG54@24S|JgMDJ_!-cS2RYMRv@OF|wkl#JQa`NU zZSm3;#v^9#?+@3QP1n>BZrou;rloC*fy6Dk#d#VBOl!B}oVSHgwO2gMs|=IijyopQ zlQ(KH8@${##<XOH>Y6;-+@#SV(G(yp%>aM$rQ6R8fX_VztUdWSLkMZxpeM;eFSFp> z!T@^0RN^ooX`A*xqS#sUliYRry<ljSHw4<xk}MC1nz~}2n|p1GmS_CV%qrKys=(zf z6~5itWkpJ2xHdURfAdXWWE;PB4g(!5rsc5P&{IL4#5jhb`?#GQ)ry-6uV$Umhd|yz z&<N4><jOG?U$7ELVNpDpsU_&z9M)5Lq{fnP@)8Jo6O=#KJc?yF9DGH%?WX`*y>IWu zrFO(M(a05*$=_xz?hNI4-i$!a0>%AcL!Q@yj|w(K1lf0ZJITzBVnf?zTGX^=JI>eI zG}G_?;WZ$sjG-4A2*m_qMR8U75bX8H@Q^4;I>WKKm4d%T0^33<QqH~zk@Ojy)RLl1 zxpAI=%okhJHMM7iFNXuF2O{usyhC@pK!LH!6i|8@$TsC+f%6?Twd#gY?gi7+KeaA~ zc(mYl;hGux_BLPPk+Oor#gtW{6cJiR{Xxf(%F^|{4;M+x8g7Coza*6FPDg<=L4|ew z{0umqPXVF<3~i8K0a>raLs0*cE`Cwj46_+E>I4cl5`@>7X({iyE#AX@B@m*EeKkyT z6pkGuUiC>H9$&X9{WDM};wj?~@trMH5{sO;^C5%S7IGvw%YmBlmFJ4`oaT^uyCJiC zCU<xcVv%h>%2*yL#$5|UoU)w^UQjCm%1^yWXw1J*k{}`k0h0d(`tD%68-B=ucsVQe zZ*|G%SX9qI{WOy?@c56sAM?fM2mRjjpjM<Yhs5V~f#qR-zZx&g>A!sW$_WF{$;>Tl zG_CAIic@t+*7Yr9in{H-d4`Xerf5yGxX(Cn>Sv1B9XpB7tGwc2CRva|L<%CbiJ45{ zrR?)l>Sg;4w#p%)!!<JhZJu<23ezx#K6xC&D$i&_Mecl;K_&m1tcP<0M%w|?il%z$ zmqyMyl=?mOcg@T`h#<0nuQ(sK$AtQBe5;|Kn;WltOhtKLW?4`pKYkYwqyVYm9M*4t z2@ID%_SjWsXo@`AOC^iuaec7Xq&q;fn7zk+FGi0h_(dwY7^*Bva>pn270;V3ukKFn zX#YI6NwJr7XR|g;QLoNr+>zHIu>6;3iap=B<hv_wl1r2HT12?DT5e5<TZA^n6Y)}C zlilJ$zrnxh`*u+WT%I|4BMkm)VS<ehF3M!A(GyeM!B?1~jC{>ijx*UARRBm&nUYa4 zslpj!=<a<HPE(c`0_@EARhX-HHoQT+&6Ia{KxH1NYBne+!PRihYkhgZ7VJSx)5mt& zIWjZv^aqOsL{CqJ@@jdv+_x66_2qKt65xL<LWQqARrKdf4d=7<H6Pk_HqYm}>K8aV z$j=qZ&&T|_IG^j0C`z%@QH&(wh%cY)ijf4;66Qst_SH6W1jr}0w5t4HhfQ(~0L_m9 zsPG-Y{7F`h+Y<u}Wt~6cg6{z!Jk7Dn`!3$8Gr^s}x}CPRZLV68t8BTt3V!*0HHgI; zLl)afFOnHo_vw^c^I(z`nj)3>>YFf;|3gb8R^0ZLm7}h0t#zKz2jh?~8_x;J23J)h zmtvhtRoWXO0zIC#A67&D0lS{5>5oi&i)=;i4K6q<06a1oGwoH_yV`#iTD^%P{j`^$ zdUE!U@Hc{0L1XPxVC8Z;0rcapb|rplrepqP62gbzcfWJ0e#hpG>Z9o{-+^TLePsY^ z68Aj|5uktI*l0l((=NrR7F`(f@96mnUUnfS(j@g}A#f`{z>%ffH*jd{z~ar%WR`&0 zkCG*p?0M`4O_$_~NhCEhXHfZ}qF7{!NN;OyfI)vD#P~k9-gEzh?)mG#>I7Dr0dSZ! z@>^SvWwb1hy8~OIBxupGlchEJmcXDr^x+BQV9FJ5DY``?h&#W(iFq^<+41Xp@hGBu zl?F)xh63)d)%blpzUd<F>6DBRmH|2353HLmYYP+bULRZY6u>$*o{z3>mKYJe)>o3) z4{_?TwDE;g$nZM3%aIz%>OEADn8;;}s>81UqJ8+}Ww*iA;udkiYoQX$wFRZqP05j3 z`d^6u23Xv)EaYJFs_VD6-Yaf17m9;TuSGUp#t${u26I^Pw#y;v@ph~E=2<--U#@v{ zrc`t%@yq)m1h^7zycP2tMa2%?XWZ!Z=?n&+USF0q6BR?W-*_bHB<7e*Zgd7gy|-9@ zi8*@7T{aOg=W!JAHj{qp>pe(eejw1eh1A+r0GB=C6S<s|?5`qUc><Rcu`0;!PK~}L znbnA}28JSxHS_a^?oV9XPe!;}gufq5%BORa?TKu?0{^?p+f8BaqZ5o`D*S3{{$(}v zd0O(DlJ1^nJ^zd+s3dhNA5iJmf;vaBo7H!r1E-gvseFZ<DVIt&+`VEuliUt+Mq}Rx zOar;zi3r+C#(q_45?<u<Srsg<2|L&>=AFN`8lkX>V>f1!+&)Ix?_a^qigm#6ZDp}Z zC?Yln@@>s(6lP`Q!wDWi=i~i^ay%%BwuTJ}(bzWW)4$uDL=$Hu{KOw<lyef?o-{K9 zQro`%YsgZ#IAWuQEFaMDu(si9H~sHj0dsu?5GDJ}ux4k27V2Bq1QI(PfFoowrp<vG zW8Ttv`dw0&=^JyOgB|S}E-|FlJsynP8x+X$R_JV}u+p+_tqR<RvJjq7*xx@~y`6wo zEm<Ex$eB$n6XU2wX2e;sk{6|nF-72yr<gdq%0u4tr}JN9iKW#wLX-j1lqH$TVr6R) zKKazlf~7c>c`|5tgp<U_M@o9H`nbu$mg|OGf07g@g(fYDKmG?s?75v;TkuGYP=1&| zwN+S&&Fp!^iQ>E(TGe4tq<V{2W^e$t{^4W=RJL4$MFJT5T7r|f{)QJPU#nQo*Lwc; zfwaS5{$NsueO%__SR|6}=}9UF?XFX=%JWQ+k)!fs!Q@+{VJ|6?{+x>dMZ~wUEbKbi z&pe6Ue5X)2<i8t?8N88C(lF|=b@zyM&b=h_;vJ#I>034%62f4?e@v<v?#s*%GEq_w zb%4GyGMv=MAKlTA+c!N2q&<z_@;e_{^Q_R8**iZEjQ8yMBSZkc0*U(sx%5$)b!d3w zCq?oL$i^MbqZ;0>IVVEmo_ilgL@L4l|3vt)gIBPewgmN`eO{0f>=bKK8|7)ZWv8!N z0X8xKh)X5Yn7mTBHQb)m<>e)@C?eR{gMfc+t*YaH>DhCn|7SZ+laM*Ap(zO%e(<|r z^Gegmr=+Z)X3kK_=sfK?qS2jAAp6a8u`12l|IQlfOjHf&SX^^ZUVn;v$G&b3tf2Kv zWUpOL8Os!&!ShAXb8WYzrX6)Xc$|p?<>UBsn*dk6hpt|ZKd61ejbJnNYV!IEm{ok> zyQM^ZAmaNB$n0&RIu|DZktO+g6WTvSiHNo4zwk|ZFt0x>FfRN)^O|ncIBrIBfVU<- zl;(|u&Wal}qIE;4ON5_9Bj?ncdR0>KpB+#64CBjdma7RfSH23Yt(Gc>u~&xKtc78a zPixMS>`LFpua|@w@ygDX7J?|6&?_rCsEQs6Ha0DVCoWp&$9I&IM(TpA&QGQ7Lk(kt zH@~k{KdA|Ff-Z(F4Ih!<QKmP@tV)1-p~$Y@`@9=@)q$_O=h*gFW;5dM+M3f8SzL+L zV{M~7;c+^ln`6_gT-SoZ^h-+2CmgyA5|XYbF|3bV4ZJ&Lk+4Fiku>6z%Abeu3#j3w zLSzaTxcZnsIP!mQGwu*DC^|uR3BmNrNe@*hAp3e%fn0rl(;U6C>O4=c^|RFnItPUT zt;qgw+l%EDdb&GC|CvdXcC!5{zbEM3?hEUP?+fb^aQvodRP|LBC8@e0RKLpmO~E+% zjp>`*GAxjv)5^fC;t^3jq2vLDor_^uzcqnv!$y3XK(aATxN0kyW@_y1Fnarw=Mr`R zck2rF)sE0R&v$KzHZ{=0Gdki4&wXU?yOXMCM*uboW0?u{-|N<s7eSL@FWZ2F%g=8e z(DTV5g=+>==~y(Q0<0-oK?`UIWo^?<EACiS`TuiF(#I6^-GBd>K2X<~s{e}wf3D$l zIS~5KX>T!F)}K_@m&XhhRy~`cyiP^@&#@=5R|9~NHVnU}cjj8JJ-_{fuj9Jj|50?_ z|5X2f0KLX_hr7&VuWWUx>~c|7c72Lc-LfTJgll%~&9!G-WRI?yRb8VHa!J{`Mz&ln zBf8)F{RiGZydRJEc)XtHc}~*mYRF061-Aju`I)MqsPFgH{ZB-*6i-<esy*IgpS$$8 z;p=G82|(y_qJVTyDAz@A#a0qUK=)*3MCcaLp}R9lcC*L8Z9zLF?pprkB(0Xs&(cxQ zB)mHFM7Q_fZ$31c))fGXEC0_Oy`<rjbs}v|CJ9_@;L>aiy?6VYHlDtEDd^^Rp{}sb zPH!dIv-fnI{{Cx`68Z7!_KVl;Y9TYp0?O6F8hW3hm)`!HU;nMReKKqG)t3jsgdIPP zsy}RzEmUU|{A9#yu^vlXKKOSxw%DX2PKI#ZYODwRU%|S*g|>xApY@d`y|M(k#0>6~ zxMk@T`)IWVW{#=q<maeo!-zrtW2X}-f~{e^(|D?>f;=Xrq@|Qo_6EepG>(g_${`CT z5^zdqxsS~<eLmowgXa7|DMG=^x7Wes+8Z}V{U`~hxaxcGc?)hN@1mimOkSB2DLjpR zEln(Q!$tc8{gZ{x>T$25zDJ#psWMMv+&5BQq2G$<&aY*TQ@}Y4T>YuCG=ECxiGjVg zxVJv%4F^xtM|G`@Sxcq(5w&5Ry*b}ox6f4VTiLSWdPm?)!1QYB$$a3V-mSd!^!Pp7 z^+FwwsOyYtN?YVJ3uI)&E#7t`-~Y0lVu!6U-V@E|^E9a+6C@f;!=7e4O}jdLeEH3F z6%pjo!ZRZOwNR7yH8g>fY@1?D2Am3=i?Oq*Z&^mj2CwVG-f=#I{b0(A1G9Cs<d@g( zwzoIUw#iRFLOrXqQ3d^1XJuf~bwNhB(aos+i}2_@uL~RUpZa=lCT(!dT2UC9J9m2y z_2r@eCH5&ejNUE+`m~!3UPozay_PK0U_hOC$L7gR$%<>urC43lCv~`?@A!2EnH$#O zzvI3Gwr4OuB*Q^h*%pobm*SUmwscND^rooZuQsCwF3oi2Ul$xS$`sDPD^cbWKAHZ~ zT_=?=EVMo5Ulh9gYZiF02>iF2v0nQ1jn(9u!VRf>R6X0iy~(#(%L^NQJc#c<Mfu1v zy9W{qz-Ug?m_dE_<rpzWa5}a2!!zWY2h~}>HFV!UT|SqB>p1OF{QSG$w5}}y!vY@g zL%JS>{TQhBXnu#!R^$2*;-zJt8!Lrms+ia(XrjM=ROrrekqMmEpLM1(l5f3;5caUX z|Ki4f$zH<-1TNUb-@YG7@ywO-j0V^-(NX#eJW{ZO#&+i49)ddy7o)>#QXlwBF0`OT zm7)+sHZJL;<*+>|K(T|#gj#`1H8BE$M4c~t(9mN8;p@`z?OiwX!pxHR133wDPg%4S z7&2$$#JDWSN*>5WmPJV=eMk`W`Gs2BC`rsAU5z_-z7$|qcQr~b3ef1+e<gbKB4=Ez z#?yzeC(Wg?Lf+Hk=zgIy`cVRXG+RNw0Ew1&Y(iYBJW}_+wDe6FJD-1H=qUZC|8$u5 zgB=s6^~m@9etjkU)do59IYzHZ(!)Vb_U58RO9<VZ;=8<FMqQy*eUX?l-b4c5yI8wn z4~1l@uXw8BcQ#&fgHn2Dr|>7<rBtpDuHrKjDYo8&(EA7M4^}<q-8H!DpS6WqhKeVk zXHA9x5?3)ZxAV{0s#p?KknVurDb2%SJ&y@k786`A^F}vg_@yO_#s&HxPE(0zYZ->^ zT0D_cDkhnaCxo+ZB!23+DK!;omDS24|Iq$t`h^Fj*-|{Wzdw!1Q}J36IU!w@H$C(2 z+02dWXsKJD_#5lOMa+t`?o_)cm$duiR8^DYfbSGeHw6H;ts_gpp5e})oAqmiST#Tj z6i9|tVPq0iKG*W|ZNaJG2(fysk%orP<h7fb7fo3um*`q@L7D9K>l#s7Z^n{<aQ=p> zIAc3+W2S-0Lwu>&-Fc-!D8`x%8H<A=#!ROtR%4AkE>*>O_q_dG+!x{<pW%KjLT-=5 zCh{gQ17V=5r`2Fc$UbdT?wL?Zd&B&ZcN@C1#F{bHLku4<H>-FrfkA#ylMrMSOSs~| zy5O7sU8C~zCeshfBc_rr`Is-g9{8J?dJ-We^;Fn|?eB$mJ-3oLTfTi~(w%ItcZBLw zw?ap~Kb$!N%k{usT&TKf96xre3sg^k5WEki<+>?xFl)!k9s(-=B7|2^NVSkp4^Tg; zSrYBnG>-H{XR#OFDR3k>>6VCgS^Hcms%=Pl-BbR_O`|dMQB}<7p#$ZqVVj^0r$KtH zE`Nly+&`gc?c=KsazZlwmK&fmYF`?D4qO{@JPUdBO=4w|`{IAZ#vPAWcbpk=>L0&K zVN)w-jc1RgL^cT-ehpXGdd((V*$+XI2k6&4ppN0)D?X7jSJFF<%?oy>O&M9ILIlGu zpZ;{mXSdw{{c4zoEVgL1xs1z3DfUl<Q0djaKW2|N$BU)(Po~H(YC!J;E%?8TxhcF1 zTHUBvP?b;(22mnUw#q6iRKC-{!;4H79T^$}$<JTVw+B1!Uei`tuKv}^XE>P}do|H; z`1h-nU{u$RN>8kgdWMRC#G`9}#*Ht$>U?F-`{e8F&Bc24*ZU!Zkpc;VeFH!hc6Db$ z#KH3*!@C+&JrBYZgpDxI@pa)zrg3+I6@_>Do%~w&piQm98&=U;t0uEV7sy8iu?+7N zX;1A}!HTu+1H;JU=ia~iOesBoMt(~vg)oi{1x{_hjY-!1E-3Wa_?EJfE#q&xH+HM( zn}-(lzUk)v?MntHY8|bwK57S$dA66MG^a=FZ%QfN*>ZiN{ruV1AJ=yx2J&wqLu<+Y zsL2bvqY@2YPd@HbI78`B>#t<U+q@q7lRcbK*Rt3%A5mq8)6no^_kS$OSf(tqoA};K z8F@tQ%ok>z;t;H)1&k+LR(aSI1(d;tP2B;oWMURJpQHp?yb^`;ka|=N3xax^MOmLv zubfHVjl}|V4~Cyyj-3xX#A+;o!I;;YH+F;Tn-^HCC<z|;8=Kn+&yLmLvrOtXN}b(+ z(}?(9hiv&TojHP_kO?yEq(E+=GyjfvpBXS7KnVbF6*h2ZKlGmqgS##UaGMN*uY;>% z2wZYumnM)a;&1|vy%mj^rG$P5J>wZbJ>-FjVZx=2f#m>%8cVq1K=>o}kVOJV5Dhj* zN1*ZSvnZt4R5&#|fP#Wuc7@)yg8U@vD7!`)RiYpAAjB}hOd8k{&n^Z4j}z`I<`^Wd z!Nh3bWvfWz^{D%m@(dK>27skupQR}Vz=MTK@t=(Wg`c1hOqo7YqxB6Po-7`Xt&9oE zk>YcOmJ^}RDj_%MEP1qmw&HMQxo}r<beapxovEl`xw!NLVNw56%i_o#T;QxY(w^O0 zNiO^z4NP!_W)e8^$iW$v@inf3q5BVKX+VxC##O~BB!dilLSP2>07i7q#=iKs;KZ0Q zojefY6fl~qj_jt#lw&z(an_5c6366{t~KHR>kqGduUn%ZNYzN1Ur#!yh`=8BFCHX) zb4^~0P2Q+X-Wo{WSx?>tr|ik4{4`Ga?V7S5n{rs0@^>KRWIcreCbGyA*-VH)HzFvG zY0)Ec4ie!TL?k4YOFosyB$dxC^;BHy>8ezr!BmlrR53`JgnXKm3DYo|CL5O~UzMgf zn5Mjub`FxRBA<TVB>kdWx_Vr?W>vcOVEUzvbX`b>o_vOZNyb&T45PRVld6nsgBeV3 zoFydFT0Zl-N#=iUnYZFH?W!{G3^FqBZe-qvWId42axlqqa?5gw%W|vAdNi2zcq8ix zB-=|q+s7o^*Dc#WE<2zqJ7_RFL^IQ2Ejvs;C&DhnSRX+!%!zA%@=-!fXDJ~bk~^z* z;~QF^f#r;&!GEBTgwwgtPrE*KJpIrWdKb+eNQeCcARn&f)>JtOTMMwUAQ^O67AB9W zRGS^M`)?qx)8w8GYd%w0o4|CaVZl9U{RusfqW=7$+}jB*yv`AMJw&h-mFZ%H>FA4S z@}iUa3+7MT^f~eG(!^C&I765sN&u9pzrD94H})=R0a7%5LyAp8O_c@un5n-6Kvfoz zFJ#>xX2<TylK>a*163HPMT!)&rhcDT)I)<SaUrN{cLp^{X9G-!T~zP(NR0y^chKzb z4w0&<IzhLJWlaR1cjuO<7p+){w7P=t0Dwf?bJYiGm;NhJ927uZy|hGwU)V#$8{!#< z2&E5F-Aw7M)$>aVJQuu5)2FV>@Lb?=E@egCt9W|92+w2r;c1bEOlPX(4-8_7Dkt?T zgpRs^5%lIMN7-MvZ`pDFqBWx75Yb9uT89gN1Cg4k3LVog?%9U@&Wt!RvT7*_UqK=A z+7)!h5ewq5QZ%$R^;B@65AGmjQlFbkMSlScWqROz(VV|Cb*@cTq^}oDI3#r9qNW8Z z7pdpIzQTY0#E|aKy!*k;dD{4ah~C2+@A122cqbZ~Mg_T%*qO#n4*){Ry866&jZQde z7Y!}kmm8dx5x6MLq|5B+#XaJp6KN>&JKa)+xZ`vK+W*~eKz|}Q3(Gk~6Hi!Ev{>Yg zGet?Op_-2PmP=Ko->W9>BWJOk<$zi@6nozc&=&w9iNi(-Do%RE<`oK!4>%2IfLtnK zLPejUhoH*l$75=v>9Fs_ik%P7X{ObS;;<$(B%0Z<VJ<`B>NlXUjQ*Ev*}2mih$GqR zyNmu0x?hgdU#4L}cIaB>a&|g_JZdFP)W2~twdv-5{!a{)0}Hs1%RArw!ns$fht2@? zxj&b1=W#V{Ota-_8PE;=0h4<K_MkT2C9$u&L*CM0^E9{~02m?;+4=y_G?9LGi+fq1 z=H+G+V3q@mt`!L)Lxx_?3L=(LOYZdBh3p}H(EtP*vPVPyihJG!0QGegwW<h93%1tA zS}&mxbQCghNY^F5(U;t62jF0O76DiQ8?7;rR6m5uU&?C$r8fNf@RCM`brYd!=r${A zqlZ;<lQ>hC+K}MVG0=3Hp<m;&W+tJ9XtH8qqXIw5sr{rO_Yc_$XAqat8U`V)#hi%) z4juQnF*f^%>PKK*9E%Mn0DuAP2eIe@IN|_Mia1=kTdJc6Poptl-6TjFk>f5AsC)-> zHNP+|(x9cSkd8tm<l|u7&8Cxn@85GT;6UtHKq(#ZkBmsC0~Zxx=HWW8yo%Rrk_-Op zm`JV2RzWP#VN6ePt@hhrL2ucuSagXT(Im(aCU=X-$)N*=bWs!^fzwG{3*wC@lD!F> zq*tJP8X94J4RBu^M#Qq~(i*1Z5s$L+Nn1Uu1I?2lBn{i3X^p5J>d?i!ZQ=y19fDH; z9FOjR%#ZtQvUyaMdhhEece}{=65rYpf$0>4?&cX(i}Urs_q!TJ3Id4!O=NO9k6L1{ zFBN!-#vVpzslmZp14PmzpR4ML)Iyb>MHh=mFwQ;XL3$Gblj5AUM8pD>e+PHdfnzXL zX;9z#$}bayM`GS)AL14c7()g8wnA1A5z7?re*nZ>X}H;=k&E5ISyzP_7+3<14P=EJ z!NPxIheUX#_*KiCw})19YUlWb7HP-{fJzJs{0H@MlERs=30LcWE|n0pOf?@R0&Zbg zcqzyM403S}MkXLu%@BIs_${*(EoqD$Q1ZqisDOwVwnF|QL;h0W?5a&tJEO7t>N=8$ zY#q)!M1X@8K%ByTgoFRWAV+ZU1`6_>mGbOSU4z2dzTEk!FyK}CIPVx@3y1uI`BY0r z5dV|jR0`DB>S4Cw(g5t&$qWG3GAN`Qv5rH2CQ|?4kQHR)5J|B;u1xn*iZGv89fr@5 z{JGk|dyqQTNI-r>>7P;xz1XdgA`Sl*2rMB3Sg8M5jlsVX5i^)iBRJ#{5m`?{zNOz< zcPQ^ts&WrWmSjH{OEz<kG<?mA*uWzHU_L#^A)Fub%xb<SP0DEAKq$c3J;Y&-09GIh zP<X*){sqq@b*zSrJSM>h39v3Qq75b^(5rAJX}Wgmy50#wo}CqmVKJe@=fwHvZXniZ z&_5pVKSbzy6uN$~EPKZ<>^$m(kjEf{#cspev9sbhw*5~?PhPuC9P)xW@?!zwF9kMe z#koo6k>X&CnN9W#i6rf+m`iX2d@zvapJ$Al)IQ;mhnP=|B;=eGVg<91EbE@~V^R+Q z-C-)T>0kKE!davR=E;a@%%?9@SQUVIgAoTrSS^(*C5^Cry~y$Xh5ne7gUZAWJx-By zz8pE@MHS=`1*SSbR!l-H<76HOzKM*<Yr?W)$z3!eJAVV<_ad!;g?FlqhibKWz%+nU zKOdpLtkD9z8@R6aEPv8iz#G6y=nIYjnPCaD77h6iB-k1j`Nayp4}kq7il}jw-4VoB z+(^_Mmi&(gppIk9p-<a6-Kr@?900!jB15Oi%9~{50RcLV{o)yVElzZ;CYE+WVwnAU zAf_sLlQUIB<sbAf0Ri3_Tf@%9o(^2w@lugoa>np^5`Y{rI1HQhj15B3;*<FTHT50h zm_9W_=iH`9h39R)2((X*5K3ua+8oXn{whUH%%nsj>QV4bB65UCZJ{ORsE$YWzihLf zS4YjOGflkcOFMIy7Sa00l-XZYW=4y;OPoIvpQ|DxSd<Vv{JYbhk;#X=yA;TEF2Gd` zN10a58&&ig9kNbFys=t5B*SS9GhzKNlk_g$u(l4TxjU#e>8GFDARvd$kc~v-5Mhvk z@jfOX_pLZTQgkO>l2GTuRL+>0rz*9G0GKXPM+trZ-y$a^JoO|7g6IP`-GOX~BjzzT zfS2*@KjaIN#$qvN+PrL`66$>3*EBD}hUdo0Pk726d8q#TSxbQDsD4d_el`?)<`4;K zeGNd0e|LL(M*huGAqgSvGWr>d>;fpgVGVqcD$chDK;qcUCyXv}a4&U7Wi}wGl;P!J zXhO>6>R|-)mv0{hJr;)t=6wlGAsD0>s5Mx&-nG^l9hLoB$KHeZfcY^`M7+m*61#+! zg$ER}o^gug;yd?!?UA1D*ynxpjQTTVm$;hmFStL;X2~05Cuz1*@h^8QE`I_F6hE+d z$rX*X57+a43E<pDA!mt5Q*)%*W7Dp)c*P$&_5c(MD+8=>#u#<copoU(UzW0H5WBmO zd;Zk9!gjCumE!BpyP}r@Ykryhb@8%)|BNxUH<YbZr0l+H`ksf1Trw}v^!>gv{b|jT zq!)!ab9-Xl`h`j6S*Mwajq8=xWfo<(Gplq0mRDQ0*7_4ELh7zukM_SyQ$tTWd^xi} z^67fce=)Byvi$P;;g5mA442Ql_bE2=<=<|?`oe+YrejM6gZ7%mu+!zrljdcYUH7-c zem(V6?!v2eCjA8=pSK1b*gQ_yx5RXMf0N@VzdQTq@m#y_?&|#P{_cFlSL-2QxPBPW zac)@XR(i2j{EN}Lp4E|A-B2pVPwSTEz5BGqcc(7dF|zo}0l>7ju`}`5Hb0ky@|{1A z@A?Ic)lJv5)X%B=*gz}ty;l!qMM8hnTz%eh6gMiI|2`e34^?cY>%-1ZpvXUt79){l zPgG>O|4ai|v6j%|UYDt(=c4>%eC%c64eTdy7u=_BM>=<orZ29eQ5?l(=ISQ<W;MQN zQ_PE1Cnh)eN7Xg{V1h|pLGyZ(S)uR8!4$ryl?}BbO1>9<nqByG!^d20RJgXttF^s2 z_SXQVgzw=%n7NuyY`n6tPxAxk=Pe&hTm*=YV=npLJ$eo1#_58!BJMDQL{{tA;wz}T z1MV(rXR_@RgnjAVpq7ry(=qw}N{s_DUhn0N${0`4K~Y66N?U84ynKPOHrNP0Kih{1 zBdNuH>~dwPtgIyLCG|Ip?~5~RRNd=*Gayk`tkYu^xg9#z6{^BX7xyLNLzSbr!pM|x z0ncMpq>$%_OVzho+T>lHKggMuEpo;{&xm++G#E<;{0r!R-qK_3BIbBJ|1Cem?D)5R z;`uLlhh**Y)|miS>6k=mcAI1*_w0j#nd0h9mkD3un2aO;XjO%%-F8Exu-8A6sf#I} zYyT7xpZP|71g>Brg&t=7>lewglYxF^&~jsn9RDo3G`Vk^M2Yyo-nfbe412{adfJ&9 z7Tu@p)r<H$_NcpdY_<ON?0U4^AolQz-gX#6=vcgz@9u}R(aOxvsvwbDC8x<k-XAn& zPZQM^*MuVeZnR8xsjQ@q+w%jCqb1|qocg4YmesfT$L#(JJ8_S=oQ^iWGhQ4I{mmg1 zl4hMWi=Rm~@(I#b|A${mSHFChrHkA3wI*{HJFgjY)%2Pl^>9U)1<YKFbH{{7jS1D= z3hkQdmw$9Oy@9z8;(Jwv+oVF8DGGm@5deH1(p*}>6I%OCTfW=W<DLO2LmVtNNWZG} zMU^K&fG$&@eIKZd*MmKbmEcyHhhvDMx&sMUc4N)=RzIcKy<2v#$B{G?t|NS1rK}HZ zIntf~I}3G2ssD`ae>q?k$y{}Tdm2L+XXw-_sa#8W-iBEJsp2HZ0ydF@%J(C-D)pWd zk&+E@<~)j@;JyV?V$|4o2};)yc`H^ij~pF@<^}k8!(t@uRhC$x09GY|2HvRBuQqax zlI@NL_L+zO>GU)paVJQTOo@Jj@gIhizCE8lyZ=w)qA)l~H9Wmnqb)T{L-nevPNLC> zeFM^$?qIr4yQ-nko2ii(k-^`6vyS8i4JEEHG1mot2`RuueVd$K>2jflw0b|@)il=J z2(A+Xk$OB9X|Ta3HC+sIs7%cA(2TjX`2a5Xu2eNo(HZ+@FG(t-5&*=poo1$D-BE1F z41xYDM;9_1N2G)o)?>Ex8C-_Wge%hTFb_0CZ`Ox)NeRzK%=Oau;ypARZa!38yf74C zo#>q5`FfMu;b~=p!u7;vkmELU9_qFn8;A^Gf!d;SAH7LZB)>5Z^{&NAu-k-uLnKw3 zY!wNT?ne5MZhZxpRHU=}$oIqYyT6R3J@r_=v-rboHF$Nv2ujFmx@~gVzButd*&!Qc zU2QQEc(b|OEyLDiUA<M0Llqp!8A`h%&YylIe(t9N&F-4^#2&v_o|NLcJ?Jv4VM^G4 z9Qxx*k8b<)plZz;`L=XUpRvD=vR-Gcy6t9sBUqlx!)aN05!0V|bp7<)MvDy47tHEV zjdVs!@onJ~HS?sAjDh!i*2&)<KMCO!PRIfAn8?`y<gB3<l2;_!GfnR^CyzdD;iq<7 ziMLsE<(`j}CUhM=wvzV#=x7~|+`1AeCa9u&g%&2zM~vm(JIt{=Sr(=W+=o@%IKviT zAPH8yMHo-3ZIPpkw%`mO<w#FW_}%K}bSD27|EI>E_5h)d2Y}P4h0YxYP8@kc*GpQ5 zJZo2YoXv9X-R@0!bR$`et#N=V2unrYS-EHeU=jT^TlEIlC_IPr`Y$>wExIa#xrc1z z$KHW7Of5}i70A;T4S(6xP<HLG%}A~~J<Yq%JlrP8EBp2Fw}Kb!c021r{Bz9Dud2SW zQ^3a?q4tQ(9fpI|@_}KP-$v4Q!1ds{p7=1zuw%*ZxZygibKnX6g8TZz!f&?5F72>P z<X;bEmF;0&Xwdn-v*TFZYjNq%buL7=m1e9C6kh)B74N!kGjR%nqW(K}w^h`5i8=yF zt`MSx#4E0kMaV$l?qlU1>Gx-EbKdDZb=_f@=x5$&;t(=K)NGC5_O_LkMTK?v6~u6r z8P97FPI&KME*Dw?-(%RYApEX4oFAdjX!!+jeZ0gy^E}f?{(56_2#t+z8qD#=TksJ9 zBwRP}!cZ}TjTOk-4KGh;yR<K@SA%^bGED8S%~B$KuocA4Zdj;SGvh~ZtHf65Sgrwj z@g>nJUWVVdQWL4%vM=q9Ld&$+?V}KtSjW#2TBiV-^`BDeJNo!(R#R_*p-*2R(~W+T zu87ab6D8{&jqKnrU^`ThuO><|1al!_t2Wsu6H8k2gqdu04Oelm9&xayP2l46fZEsc z+q(khT8UoqPl;^8e~ncxUFO1E_^|AO^lAh^pW(4HYG)D*;Fm-9Ql@A+8|f8YKv4S2 z@<SF*@LQIPOHrUmW9c7hjB8u=UdaJ-0}>4;aj841+_!?-b#^e3r-=p$HW%jfJ}t9J zz5srBa?2^=X-vT@(u4TBWo%-<+NO2;J8p079ZNX*JTMiFhHu@x_jgwPp5y2JWZ(8~ z<VG%oO)|Fh0;tUC?TdX*o|mmq7pqs8kOog}N8ZbUw7Z1MoNp|?UO?hV=qMp>Gn$&} z^$Tf@74uUspHW0ZHOfqeqJ29#?umnBOavgN0;P}6fvpp^j3GHom$`)XQsR=D4>;U& z*!Hf4`;G$-245U{wZA3Ceu1j!nZ|rT6M2j4TVq86U85fzL>=dWO1J8!A0fl!B5m4K zEHzVpZngru1mX^222#&C<KB4UxmS7O1Wn)i<J9hZ#fE!Ha4Q*{*U6>@#{86fD?|dI z#Mw$tGl5LZY;5T$7!-o$Xz1bo%LRDCJl@o-{cj4y3IXL=kr8{)yPtq%doLPk>^cl_ z;a-!p1+3y$cyTZ`+94;?_kjQ7I^se&=#RF6jnccML1nhRh=3lp%F?Kx2JBI}Epu2A z^h5dVA8jWO!5-FU%sM4^V_!EtREUdB7cy>(>W$=*=VHkLUCCjKq;T)&U8SR1L+}YL zQ_<rkAlzn3A}#aZ`KvgXQOgWel?Pa+nWude9bkLPG)K&C6E4o#@OB0?pq+2I#pxfL zbeLCc?)bXGtM+LC=q@G&AjfSn)v9As&U=Mj>#qRhfxr`#Y;73O(**R`_6!z{@+PWy zZ5yZX=3%a%zEjF>N>aK)MQgs`Xxplt!=9GyOkQ7#a_DWxKg|gub0q&YSY&7_Dk*|Q z-9*n~5O~wG%wgImz0*EZ<myL*2#3m60=L^i?sjFue*@8vbK+8lP3!tl4}_EL1=y~T zFNO&u+`1qa6RSPH-c;uh<0GJ=&kcAVcv>J$;&C&`77Ow|T_~wkK9nyCwI#GmM%%l} z1jwa&^hU~VmqJW(>TEzx7~uII(G{!}$LFPNkKWe}n~fYN{2<1ZYoA5-NM-Uw_C;!Z zl_MD*GWD|2PKqGfo!6e|nAg{&?Q)(!BX)ZWzWGVex@(&)ImS~@=xd;+yXu(J<;0UT zq+JgLJvPe4R*+pvV#Haq&033UZ0<%Xn=ZBp;L2{H!L8}|(#g@}D?>og<8<_O8h>{+ ze*~*a>s(^KSLz4)1&m_(yK5i(>0B!$4!nQ@K3s^;=4vEPwYdP5tx|S%y6jn{X2D=g zXeS2SYyo*rwaRUozLU+hmkPiG+%etuxV%v8+2yBTjC+hPIyycb{<OH|E>}!IjxZ7X z>g6Hmq$B5^Je4!N6`=$}$pKV}h2?te%q5u(`L{#~>){Ewp#6ImJ8EaI9%fsNc%U7U zD)Y138aiU53@is9wFD4Ad>+UTKiD!ABl}<jd&XP=ZOOHr?^0$pdE*CcSh53AaWx*& z8$qShLfl~kwP81UCJ!=8g(c?9J}n35)|`KHf2yO^_Hr1bTQcE5_s5)#>HN5gka31v zN5hH~!||LJEM-LRh98bIbgGPdYkaIXE5Y$ipg_)D1)hiF@ls<}C|X0g5T~Iw_ifim z$*>;b27`7yM*lb^pe-feEjs8R&nq5<uD#*H*MC_mzfmRT+%Gmw64R|}u7r;X#lN#H z_(-RY^`lckI?(}@=NnI7`rVrrO6$yT=WxY$J^Z9BeW}P5KF~uh6+4N+#fk<Vz6?dZ zw2-jqHXWxE5;JmyZ`#Hrio<hFc|$6TXJKV7byFjb3Z))V(Lw{##~=M{vklRhRf-KQ z2W~yWaRVp*xmV+Cb+=AUNg#o8_~_<JyOke=V8&2+9^g%!5{I)SL4r!Azk)x%v5CpT zML*N1z}tczuXldL@-{ZuR(&4MkVCSNTP}@{0<oRX)+g>uOw$GO7+?^7ptt5}v7MK( zOi(WHDhH7a3Ti89IcNr7D#{Ey?|&cxYzt$ps;Rmji|=8x748!Kl*$H_%D4pbT58xn zj8(7!JsD{0cz*lCnRiW6$tw7Adt;=M_;u3<SFR91m^-Gl1C<h!OK8>TtUyxHVNRiR zOa-(^>l-NGfTKNkZkekofCx5K0Fc=&T@oSpPfu{$<(AJ8-NVi`4kq6Q<PZE;6+(&$ za^-ziYrm!Z?w3gxQe^;xip}_IYY3k9WU$@&>e^%tZM;5yR{C>Y;A}@b6KK&xpKT#+ zhk#mmz&dfVDBwBzbFFxkwMd+lXncFHc-+7x?x(RIcQuAgUf%=N>nzfx`4VLXo6xJI z4vTk+B7@b14+>l<!YTPOT20`|UhRnw;)#!A#GnchGoSm|UlP8tNgri|KjyjCC+37p zZOPGR5s2vu#EOe{UvgsCr$xTu0(*SAFY&nLLYz^naKoBUY<H0Az8UCAM?(L3^UlX$ zs(f>+wqzqM;fVm~zZcm(Li__mC4N*;;4yC@%cOYn^5B+%dJY?YoC-V`_29hEHu3O$ z931a@>q{cY&W%#|336<r_EzX7i~&8%!hCZ`M?V3?tna;uT)G<&{_c=3E7A+hX%_c7 z!@=4@%T6opk84}-e@I>MM16~crTh&zi*%^TXbVb7xD1BL;J(_9iP*`xJg39?H^$F3 zMcf)}r{c6vx3%@;ISXC14t4&JUm8koX{fBZ{7vfQQnLZ?ZO+qtei-X<T<n=MHSP~m zJ#skkww#<t!k^r-oVB?3Iuxa?H7_RUney`A4|ficadHm<bq~)y1AqjB`2YDnV9P*y za{R|TU9DDE|GVt%Gc@Rll@V%~a_@c4lw5+_BYx>ksLM(;Ew}U;y2N6Uf_-qmym~U^ z-p1LVm$lN^EY^9gUHLn-(n1-P7d3MhoxY%CX0-kWB}|ms){bKetD2NK_(H0&N+{=U z4~>9zDbE8Ai_K`uO_19|x7v^HMfhZYY~FC0fbK!6&YujAHzW5Y?zU9N;^l7TNM7no zUpj9gs<O5A#w|;n3q*fxBqy9)-calH#hrrK&KEdORF3kJi}vMK_&xTYnN^SU64`j~ z^j%nkoAGoa{d{cB60CaWU194lOi7LJxBG_$e{desdXKs-c3k)o4{_a3Dr=l`wQ|W9 zrH^i4?NSZ*_?@Ss!%f$}ZMgW*qSd-sG*%w%beYGrS?LjrOl~}0<JkT|`{F0CE=|hj zmfw0}%=zOk55{{qN?C1*;Z-`Vy~Ijs4O3e3R75)8IA^K+aV_+TW+D6;KTy0l62oWg z_-ks%na9L|(-$8V0?xMxEmf&`4G?&Qf6wM|DNQZG-6Ai>t;+JC5NGY@MmqLz$Ja-Z zc5c0K@fia@wT(j7pZ)qrpxl)6;R`^NfvnqNi(7;2!c|IShdcD87wFIBxPe>OBufO9 z$1QA(+9H>+)8(>Xnz>&JiE<eqApoD8H7u-((lzw^bX<|IycDx%)~&>l?bDJba@XIp zXPo}ZaW*TFpWs6&(J>b_x$UtwxLm^i_1@JqmDQUqLrV8wd+R*A$>mENDJ2Mzvh${J z!2OJPEpPR>q#7Zg6-HbsPu2Wmjl|yrX*Z)Qh&Q*UZ=Q3nd}=W2V}b0yP`d@dyDX-H z#2A-q_`Myvp;Um3TD)iS&c{QOW<ywRmn6&+WslFvqJMvSFWbs$Hh%Rm9#Hu>PQchB zLT64nt1z;`aaVXgDxd7f-zu~!KbbzI(fOrNHVQp|Z`ZHd$x>s;5{1@`l21u}^QA|H zb07=nq&_d!OX4^eZOUCubO!Ujh;G{$Ja=y7;D_I{NwaL3CL4{j94R0%-AQ$kZ<n01 z!kb+NU6Xo#wHU3inOxv}GF$g-6kj)yQ2h?<h~S1tuOh}QQQ%8jH{SkU{&Jh`bxHH% zq-OzMPaC4VK#oW4x1YM4zv_>zxA-O&0*`n7Bk5!u|G+=z+)?t%OCCqVub+OKPui@; z$!h0m%_XXJ!_or1pOlUs;iQG!HWJETO+>q@JjA_=#2v=8(R$5>pMME#oxEJ=9V<1q zIfz3IoWEA!+JrbHHqbewr*~T!e@nMAo9U97_co@dIGZf%HgiF`G`92#FG|Ys`Qt~5 z&v+u`bpLg_4t@>(Xr$=z1ekI9Jzyhv{M-ppsOfH!&s+77FHb@q#Cz@uCan5}%)C5# zsMUSbFgEg4$ii+2tjEGrF3Lt+aN<wMGV?M4>1|?HSDu8fz0Cgw`L<RRy4k;ezb14W z8BYKJBo5hu%&`MNNfZDA<gxX!0Kg0Y5G-tLMN1S0@+e3blW7UjC@Iqd<A#!V2?FQc z=LQ-|`%}aX;)P8bUks+pU9YwuY%CkfMms1J6r+vc;c^`BP1;<!3<XpppdzNtm1CvG z=?Zs0G*^A9uu?o~zOoXP9F8lzXzw^!L5PXR*}$$#nw3|&eyYAZ)LJ+D3b*{>xi(6! zo1Z-hOn=Y|?0#NqO5q}%k~9dDRlVIPO=36iAWB^;G;44CHk5Pzt4NzZDfu)`RXL0Q zCe4E70Y|dxMVuidKE={LB(?YD>TH|O*1|~VtK9(^jz(kK@Cd>u)_>s0^QM%uVKKLa z&wAz19QfFM?D?!tUhVJFdJ`C8mJ8|&VJay8xv1l(Ict|KizHI7KXB{ozq5{seci>( z;4=3v2<%xC!g?o=E0KUwG)MpG%g-e!;p`1EnDAjPX<!8F2H(waR+u3Q4$N|0ijym^ zeCTwc7JCZ8=_QNu>xGcm3}ElX34!O|qaqN`xvsE2W~Bif{E>B)D`{qG8!PFO)3nnm z7bmd2p{(mnLSAbfSC+&IH!8tsu3&p})Jy|D`#nND<;lRkmtQM*T5T(n!oO(Ze0BEo z###}9L%}uf+*7q)=mm)m{o=&4f-5AVp~A+CjGOKoWjW5(8|4Lln;R9RXobzn7g_F` zRh8w{o7J_go0~P{_Y8%t+U76rTXk(m{CawwY7>v@DIAI(&)+)VsMYUxz7U4txu8gC zgzL?2H&XQ-^%{GfYj#=-^>L}M_#`MhZ7W#`c3{>>S{Ps}koLWEw^8v)C;iLp_pXCL zl4r+8iBS04lOLS)w=93PaorpV;^FNu^=-7h(iNq>KHgg%d+!90{yp!7{kQk}#bbnj zBqOsueheDL)&BUP^u(hFB7Gp<H+*5z<L8LRTES1~@8a#BqnM(JAJi+Qgq|U3ag}%D zX6ie?K3N%wv>>H}#WC!kIqH6YX{;uS$0~3s`whwDP^jaUW~qN>++U6Snf2_4`_Ek0 zuvX{PdpPuaAvl{+tq*w#;ngq|l2ZG#C?d3@I;^jBH;RX7boOv1<NCdKJUO?%v#+ZE z**RP*&m&(EsEQghfXG(j^hc$CXCG}<_apvpH%?mo-MLp0+B%c7|NZYSg$)@%r}SH0 zTpy5qSv9Gw^l-?1w6D7x*O=n?>-Ut)%acEI{!gBMSJ<{VK3G<_zB=EV^7XLk!>irP zFJzlZtXx+L9zcZ8R8l&qvHNcu#*7Vmz6}^*zMAW~HM#2ZfZN{eYtqBKIz;;clbL<? z#=d9v3OUpV^yts)2ta!pOARIIF6@a<cW3J78{9B(2R$lh+V*=aj(?)1@7X^#@nLp? z8gDq+f5WFhkWu)6(?$*zvaxKR^oyfcMyo;R<s-dYx2X*oIC{M8@xAT7eFIjgl^{&~ zs*3n6by^kOU1@NJXL8_uMOQMoG&TZeOKIR-{GQx8R0>py?Z3Rams0hq=sSL(^DOt1 z$XN`4)l7v`x^~AOZU*6-F&;Ek1p*b&VNj)Fu-2E<XVJZjivWSk`py<Unc7afs48Rj zSe3ZfcZvi}!Z}!iDXgqGc5$V_p?hy$T)rgmPR#0-Mvt9UM(n2t;~cRcoMrY11|DZv z4I4Pi_<le_^2&^5<cT7&*8p!(1ERquAHCCF;0pUlDnP=pqv+$9$qUl-a;qo>X`8$k zsAzDI3q!}bc;yx<mZA>gW|7JJNdiZK#a_RsPVVeV*(JJyobas*a`X~`kxE0AqevNX ziM;VE7)9g70eLx;G5hpqjCG?;gv_t9bLM8^=Uk02OjPxy!<xB&{HG}=Zs#u<c~-?Y zM}wj-@GvJ;yos;$GqFQu=%nf!PU9aNUJtWhvDJs#h)3~)C4je2+-<uz|7(nIsnsXx z3B+@aiv$y(@5JBTj3Nra%zoG7znQ;Bx0WqlseKugnZs#|wq?Pp`m3(wY;q4xO#&O) zuMwjqs|d`Y;Ih!HoT2)K1{MA(QdI!F&J~mqHlFvVxttH<25PKN!2{T=iM3L1_QI|* zZnCn9Q78z*q1go+4tolpF%F2HqXlxZ4w%<_r)v`l+}UkhfNTtz&uW94oy7=jcqVI) z(?}e{Ig~?aySX|0BQIN--}Yu8ki786bf{=MVYf+!c<)H9=1rU9xxYVZzWzf<zioq& zF|0}p$YTS+CwHSU5qli$u0Oj_$z&TD3IT$-Sk|u~_XRpr3w>nU3(4g-Y?N7$QYvi) zldnd6#U?ztY}<oQ_Oichwu~%Il?Gl8kKiK5@RzcP-WGqE7-QyG$(ztCS-9Jrrj#mm z-<AZtN&tpSz;QYH{in`0X1xl|2!A;BUM`hCMX}gH!sl?<HFQupzr*>@?GXm+lQ-X< zEpM-CalRPwe_vLxU%Phs{Iyg-`T2q^oppWABWk2!b1~1z`c>`QV?@uVFT|AHv?~tB zb3QhgtM4@7h9f?a5WgSKNo?BWYpI@Sv{c_3*}U0#^qHL8QtM*Ab$j;cOWVhmdjFBF zdw-86DTr2bjQRFMp}$iD7OjohBiqi}f2XO*t<4qYJMMS>&P;u5ZGAPe;~DgKmWFuM z)^GmZJOA(8y2Y!G$&v4Voqy-)$*;QB%%7Y}>sUDW`0CC6$ZqIcr073H8wF%R4;K=) z9k2XWfvnGeh7MMpo9OBFH%Jb$EI8Xe_5Pju8-*C3;EBiEhSj<jKWyxd!Ga8b8Z&ga zeaW>%M9QUo_~OMuzv1K6+&rUUua7?q{~oVlkR8+*i(e%|C+o(R9pl*_f0b*WY*?jq zOjKC>u6}hzlo?q6{HjnWK;u}%9{Jbl-{Nl^#X<C5f5+71*=+wVHqpg{m^1&V2t1{C z$78hf&fIq-9?S+#ca70K4)cF46e{n2ilRe3n}Y9K7F!tT5jomJ_MiGk&+&)q9Pg!E zky||NSJba-SadipbY^dN9kiy$5@~l_y88prx#6PATiba_)a#icO2!)T#P;5wX5<^Q zgYU>E!HbC5spD@^qsQ58C*PwFx^%WJ5Hxkh(V2$VvtJP@&xn#>66G}mU}%{fYAg14 z9R&F@v=@liao~)=zt&xP0J+Wt=tV7qkM>`t_9PU-u_y#98s7w9M*yG^r-F`O5d?}u z{PvN#DE1x{l7>ch(%IP10ADncjzxT<5X9xUD);^NtOz7>z&|?75DVbIfflg-taQZD zsqhOqsGn#AF&h{t4mc+Vzss!8Qh^Ir{wZr-7x9s7W5^RgL<ku;ipDQcK}wbEJ*41O z|4?Iac*1`0PfB2q6(Yg~j9@~t;;?IYe^ohTLUz=Jb-!h5NGCaHh43s3%Zw(mkmyK& zEOHf#I6n{#8}O&o;BGk3HX2VtM|0r9{nijw4F4!XY^a@jT*JN}0~IogMf}8ap27h5 z0FZB1i1f<Hp;K{FukgiSB#jnAoAiGM0&t+g3snD~R)`SW`1070*@{3WGaJ|j(=`V8 z(%`IU#7|tp?0!tUK=9TrM6wHl0U&Je!yZt=-RLkH2Jfa3H-z{4j`cEah-O8_H_Jh8 zXdwPsfiMSbqxA6kn5g*!oM~mGg<c?=Z8)=y_KgJg6JT#bBWu=u4Fyto_LDf=h}T$> ze$w%&w?Omi5C=R<lNG}6RD4FIFS{lV)SfB~N!DA$uYhsp2QX&Knu8XXPDd`Hken5X zOvY4XF!kypfdPPW+lEUqDB(mjGDH@jy`Kg<m9DB8oKhLN2Z+%FKp40%j4ODNiZrT< z3;|~>$Yp#L;4Rij=`xOWqa#Pffl7Fg<vOx>-H%C_BK?W1*i6wXZkLVd?1O*>Di8qx z+{L8v*&#fcJHsY8kLfJsz2F*SXq_y=#uad*Eg*0@TgX52(P1{BiaY!Oh7pG>h(|jf zMA7KUiHFilu0boPh&c^Zu$@UVBv(k2D^5L+RV89+Dkk^<`HjNifkNcs((ngJ8X@8N zptR$D($!f1QkN9S)fCp^%mKH8_jX);Zd_Gu@l5V%lo(4Mh!t7)8kx?QFY#kw5DPAl zZ9ozq1C+UEmABH2U(YSv%q^^rOZ_H}_)bR##ic^V5(`|ydvGimFy!-O48KXyOuOWr z1B8YK#FWIIE)JiUC7e+5z)^Yb5U!t9k@NjwKR5Dz5(A&CXPRQc8H3@CmBDVV-mF}? zfopz0=^3K{h!wRMS{)N8pIiqay@|}@TJ-yck6s``My>q)D^N2=2_XQE9(sh}I(&s5 z-E}B0lIynB9=&NI@2MUbvX+@n1&VCKwn50xuR?YK`4>!0EVarlO;MoSz!0O{7gR)k z6#=-H<oPN-of_zm0RR9TQv(4d0_BDJ<xZxK6_DJFhea-Ha1x=+7X>TrFH>b4AYJS% z!j7`pRU#w~VfTp;j}N)P2N}3n67v|>37_HWs(^AYS>r3#*OWg6N&805U7;dKOzsm0 zY9&`L(aTn?O2LOYYFenJ%1DU~_#Hyk<BlY|{a`v7e%}g2q%!Ge#HxCn>WqBZW{!$; zUDt;!_=7^+cp?*wWEDp?iPw0bp}T<69ZFrsjcRymd_)dM8a32Y0fm=EYWyF$h45hk z+|$*ifeN2HYPgE)iO}L5llWb9o#n%zp907gY{If2I~EOHK!+4pp2nJzGskP#A0&hr z#ir2_A!}jmVYNTeP-bHNxh+eVI%2zDfkmh?Juo%cl-qz2SBLmiqru4)R}m=~Bx$Qo zT0w^}#9`5Bb~`{JL@4j4W+_nxu}qDz$*)<w-IT`Nw4W9K4}*A&1_L0-hFACz+pr!i zleuNrl1E4$HRXr5aOL^t*%rFD;iMXxZU(3h=DyOcLY2n&zECUZg~)lzB6v6aiA12T z6-0Xa`DgV|HqBF|pnL{BX*yRvuqG3(S2jNhia;U%(;_-fKKCHBv6I3a*YNDt?Iqsr zwc05VulijY0(y=6L+&eCo~m%@3p=9#L<MIF3O0d4v?<8WsFxOl>ql{Ax+L%@t{w|L zU8x@U4c(a)-uX;3{68(QpLnC=VVKH+Uk#%TtV;wwXona6EwXszz3)uE<wmq!!|zXW zydb4jy>I2~Zb0_dbE_0A5FkkaR&^_A2NkgcXnDF+#wwA&i$UyR5reZpT_U(gJdkrc z{aPM>m3rU_8D2tw)LFq8R76UkJj<QNC+g2qsF~#KXfG`!@PJJ=Ao~Q3pyegr)K>7^ zirvL!K<<F-$Z+}Fg)+r&VFrC{V=)PnF{P7;arFO7?v5B(A02su?n&*T5dAB4=^%z& ze&p6`%f&K{8DxoU(F6*{Y@w@TINC8V*3=s91o_t={ApGQChDqFm87xx{IUSMl3bXu z95P5z@r({(umczZhz2k~DFW65nvclP#pserWFHD<LS*+OfG2Q%@Xg8_*W_2pY4e(# zC>W@T8gfFR*iG^lPsO}%>)WQiWiofM7|0yX?*}@gpd_p6=ykOQGK~(L+bWxw1f9aA zIoY;d4(hG9sg_ZMb%Kahe%(CX_5MT3hR5%%uD#o#KyuJS8CKAQQ+44U?N)~b2D)CC z$^o7V*+J#i+9RxmdfpK^9SJ~N3`aAGvxq<F#p)~bnbw)jA;*CJbCvyU8VH{c;dn5y z#r0jQzB>`(mu$rRevx=Q{3q;3X56d4rRCj>^R4;=*AVF0rh&YP?6xG%4mwiHr5E8Y z{{!o{%8-Tm(%J3<ptF>KC0v2A-Z<F|5{_dtu^O77z|SSs><S^7Wd<){d6nF{?|0(z zL1A}rRJlzzv%zo@9qwn;7_W}Bgg0$*7Gu@%J2=pN6e8l)7)oNSN`Wlnkm<Y;_Kg(z zl@4Duf-}pRIoqH<4E)^PcSZIsd1?4ndUVM?%%~HXPDbeLd{`!PpO5u@Vmy9AMf6dj zq2?T(<k5K0<VICw!l`1?kL*z+{0my-{koX%`#`b=Aez>wuk=~;M4?hX=O-N|QXS*z z-|*z_7u@`dj)J#Dx9NaONOpT@4sNhz7(RzWN-DLScYhmZ)3pNdXC;>?Lm}e~QpF-= z_>3N6jt(a$f`f5`85qa}2EJMmX{FfOuJhR<WHuvwhNg(DIe`hUht2O-iO<0EZ<Vl^ zE85=iyDPx{f)d6M<obM+<2*CO@unv1_DtgtK0Rmh+8iRB08$u%Gy{^@Jt)y33X;l= z^VwZ?#IiQCwo~$`iJDFU1=PK|IQCl3f~3JBb50>di&g%}#7rtc8C9M0@eXl}7aZnS z8Fp;md;8W`_RC+GVc3;{0A`z=RFQ-}`-K+U!Y=v^Sg1IZ`zkDdGUzVMk+>R);p{^( zpHRQq#OEn@6dnz{CaOcQB=)$OkUeyn&jMG7@i^-kVwM25G~+O2n8Vp&Uo|vR1cTdC zJQV^vEC11Yn1FWuC1ejVodduzL`la^c0}kXwhVRjpAPV+;Rtq{CCLRTW|O<9_{*X_ zI~dLq(s(Fou=@_BRih=UPT`5$TJ#4FJz^ylj9ee$@^oEj_T1Vx;|R5aO8i4ec_#c6 zN&h`R@zY#^EE?E@TUjQ@&l17_R?)EUelwz<TOPjd9ZBUCL{bYN-^saAYu~1iHuW!m zbv|3PBR*l(wQyE>elRKZ3tRywlvaAG!50lx8mv?i<+8dqK5-T>P5|SHqoI_A_{;N7 z?ICHmmmEiG;%+tHL32jPA|BKGM`!jn&Ms~(eA726<70p!7^^6(V$c`i#RJjwuzzs& zVfZ`3xGjxi+=3#gHQlS)Dsq6}(r)m*6&$3+)!()|qzrZYK7I8o;%m;_Dqy@^Wb8Yt z*&czrHyxNClY5F7lfMx*{ryJ|cls+3vhfaxWeOi6+Nr{M!PGeLj~3#a|ME>H@Je0q zESy_!S3V&zmBRqTgyt+-vdZoE=O0l%%p)hPVCzYHvBXLCf=Mq#8=+G<#iCf=lf4Op zVCLWCH4%~{og~Y^YQ>|MZ!5o7uqP0!iq!r#jb8jZ74sF`f?mTd)E+t>SKFWaGaK&v z&knIjk6y+$TM?U&;kXpL$@J&lJ66yVG{}L0{>AF?>jX`I%=q2IN_~M0sFQ`ogCWk7 zVc!5Nvn4xv9q}^Y&Hsi{XVp<ruY&*H?*>R%76QV7aM3F{R*U-4aFNTA0@h1c;yHmG zKC-wuL!X_6ko0I{D{iF%)0RiCyd17(Dc^k)dHQ;}K^W^uZqR;mfzC5}q232pr?DnK z`T|6J?fc!geyo*z27R$F#IBtDD?a`+Vy_t>@cN<j!NuCnT&I!3tNDM#4f9uNr+>G; zqo%O1Z8oPfq17(``zJ>tH8<(lo~Tpde02Xu_nv%%$p`#F+G}`cDm!!qq?0hOf9j0> zJ$3YTZ7c{RX!!iL@3lVG_Yyn%$+q>HJ`6HZ!VrE&9sg~ZPdZ=Yz<udm(luV&`U3SQ z|5h*MPdFJ%KKM!F3ckkqsX*nG?}q-y$2r4~dwrrtMfXDV!!-N5cewiqVcMg#!=b@e zMcVI^lZt;^FAD-^IAGd6?W5=MOSwkp@U;nRdK~v_l!U!<96a-37d<w0k-8p(!d~oh zMuK=(t|*w&9KE!tZ|2aspx`W&Y)FZAsJyu7IL_7g`{_292IT`6rl7Ep<!Z;}$c8>{ zvkUEEuq$$5YhwO0i!$%=M~jWu8rgrSn5j5*#0_z8NRpVFBLOup^ZxvOWTv^MGi-R) zCy-P0K}MxP>J?EFN8**EbqAFG&iXO~p*_AXm83mmEM;TTbnq}inPOG)KZ@?ct;x0x z1Ne$<bmtgsltV(gV<Sh0NC`*_NH>TGY_I{NLrNW`ps19Jh`hjv(IFxt;s_BGl~Per zKE8ip$8+4z?&~?P^H=b5Z8Y1~?&R~Gnz)eK^>QWwC1&ZUF=2D<n4pGPGq=l)>aBxB z2#+}-<2bfeWaM6vnd<xPQH1>`Azy+V556y7%d9fsX80QOr0Q#om1WO_9=O9Lf;Mjr zxZfo^%&GS&(wo(%bz=LDYw!bgm&}d7PrS;byAP1*y|OSq6vWlf0I;d*?VZl7DC9$A zmk}Z-9rxS4f4S3`C^NkqM|z)_+J9F#LjcfU?1}yJ5s}cMa{3#)1U~yvp8o3b+6|8< zdoq-+SaZ?vp3~&2O*k_uO-?7xmyDurNtQU2@0oSZYVcgX;5<_K@kG7yk=FyO`~PZX z1XYSLsI&`^NNHq5_b(Z-gewCTfmJ@kI$w2|_pLkP$-#}N<OR5v4_NUCxGN47Oo^m% zep@3AeiyoX_rXTiF?w2QyrpKQVfHeA@;z=q6@aDH2yB6WBct}<-)M03Q<ux{0xnA4 zM!a75Yk4}KNNu|-ro&N-+5&`YdFP-NmAunfpLEq1J7l~Wj-I`zcqSy~-?l*fXUR_s zOA4kh8_OiHaQAekU2baS)hf=*<CKu9cX4k<b-w+M;J*Lo>75NO23NsnZd9?(C;T#3 z79dL(3*zfYGz0Nt*qAhC5YupT-7Y8nUl$@(_nWM>yZbrq;AtmfA9!(6#jR-|K5sWd zg^BV*zx=Vz>CAH*1x&orVnPo&C2NgF&U~uXz0j4;#-fD<+DdmqAP>DEN?0apVHU1p zKwv!bRuJ8XBXo2ohq;+;bjg9m+8zt+Wlck1YB~H;l=$X8nX$j3x638NmE)~40I6rv z{Na5fpjPv<3uua)^#GUW7KpFC&%{P=4{3XUL92zQ`uedMfG@OuVyRA0qEV9XJHtc& zD4yA)GlL7r1%QXQw&=1+2+jY7O)PX-YPj#3wH%H`|BIsdZ_vaJyD}9)xa`aRMqqYV zEC8PfX14~i45|W7RbK$e0|ocqB1oljvxSE$sOg-vv1xb4_v6PVOgAD|G%(y`o(yH? z@ELEtIUJYUMt$%bN6Smz%;U(o4#RftOk8hU{#92$QhOgvDTOw084l*lYN9bR=CaJS z+Ju_;Yz_w<gs(cwt5sVB=#e|~ofg;gt2~UEx+C+hwGu>5BaQTBMpi(2Eyo>zc~EgX zUrO-g9nGO&+b~P6n?L67zU^e#Wqvw;E8arv1b#tBudU$Pk*dhQNSbJSMgw~+mDsQM ziod0BMjUQk3Gm+JERBSj%G-%Zl}Knu*9m5bX1egRpC@3!Jem|B1$D8HJr>8-a!e3! zKSIeZ;2P?)0-H>}6nAkvcdZ+^pgtx`I>}w`W3p#S6R@#@sciKd0$Ys4$AbzTOkNgT zKIE=tQ7@FT?$;~khQz(myXQA#f}<2ls`d4e<l%J`f2jj*YLJ;mixZ0p#D?SiKCK<# zmVMd&iZ)0q$9;2~U(Qw&JNsuu$D^$v4pT4u!ycxGLBkxl>JjfSP^rQ+B3P<FA<4!_ zMt*f<keO0>=|LZ7#nxcJk)Noo9LzL8_hQnrl-$Xd`Rmhk?N48HDQg9fB{pUyj;&to zFzE8ZutUjf?ZNIA#IAQKfu|?ijy%Y9Lz7XPe|4uo?C=O;*jjQ1nrWuJqO>Ii(9%+B zMF;;E3Dug(VWeVJ2LCb(di^^=vxiagP=8K&Pxvl4j$tJ5k!-Hn*Uv7WhD~{ff=U$M z2VxbQ&z$TI-*+y#|Mb~DExVc7@p*0jc{V@fr!5oJ-TwUenGD_(2E?*llFgXy^na^R zosu8}W~ekny{=a0!tC9Himl}=R5DdwSmiXaomVl}n5r%<;lD%Of}-HnN<%3G#PS`{ z_pUjW-LssjzdOWg?O{b*Kj?qEHfSB7IJfRbL1u{oHk=$tz>=3U{1}WJZ5`47isQVV z1wxLYVYp!&2jm4w?QdV3c)~GQqqVkW1O?S)^h;l1`lD4D<*&C?+aHs-HuQZl<}8bI zx?2N{|GpLpI@)G>VhNdKBe&*PJZ7P*rGb2#2wyAKHa0JvF&8~qgsSfM=Q}+#68Mcp zsyC&>3^6dV_d=7ZEbo}iW<ac8|9Swig%F3WI?*qE$`}+7>o33t0Hd%>iiMfF@)>-6 zg~OGm2l?3&rXD@<Pg~DyR^?5spThSLNh~(K^}}Pn8WdRA)sw~31KIweYt?Y7_E~ZZ zNPO;S<X%%k`K6I_pZwdCb-QIO?ZsRM+<ri{=b|{TGHB)To#qM)ZDox_8SM{nSO!B` ze<tmDXW^0GTIvjp|BtbD!nyqDg{A6f*LJalo)PV191CpX4DX5-Nv=3O|6s-AoG+)l zT+^PI+4RXOOB_9eM`o4HRu$P!Ju}6c@S#k2PkMomBU5EQ$_q$05;&frMh{!D_Wl5i zF)$-~aDAd8*+`@m+xZQHP1ioE6{`7XuFVs)^qa@J66+#?fEHz+F=Bggx|x}cGq^!# z{*cH?TY{Pt5}1za-uLGz(FixH!Is#YNr`13RTAP8G@hI#nET{BT^*=Y@Pn*aK~?;e zQJvh*y?RszRKq2-VwpwGIkU=~V)ms%uownU6qyu*hX(b*PR(M@;>@dz%!;)fvw`eI zK;IaE^alWgwuwe#F!qJS>xrz?=>87-n@=LS$9+iopqAuCQY?TJKxKU{ly{mjJUNdi z#TGwJ-R)>y1!*p_hwp*~o`LXNAcJ2_w$-rG#1e&4MXu^vMq<zL>FAUN=I5Oi7eqQ3 zAcbHMz%6LRmZ~+^so}0wLLkX;L;afxm$Zr;`!W#ls#XgP2QH?NqymH-CMvg6@*eAD z5Lmyj^WQ!UnyzU?B*&|^Mlg7yD_f?SMO1ddA&jh+=Xr0rv<qCBA1U$D{YWXT&?~K^ z6mRHdve?5y(sTu>vqFm;gu7G&Pq)A6BcFx9XFMu;wj5c&UP3xp>$}<qbJBvPra?K~ zGgHze<Zu+tellS2&eOy$CkePMb0J54ZH2Nq0V|aRC%qkez&SuVi8+Ga4kG-r&zL$T zWXYKx9XF5UNT*T|lr?Ri2PR*erRUF$BxEQmF-0VrCMDxL8O0eh&2`b_npg!|G>pZM z$-lyYCkk4SlNr})5|IcCL1q2uC?+T8!Yea%g)(#^v!YO0N-+d)77;E0P!CJ=1(5C^ zz(OJwV=zr_*rwl-LdVYm(%xW;ip*i}!fGdSu0)Xw;qmj}OeV18Jw{d%3hK~gEM9jS z64tq=EnHKqdi}W)?En&sZ%m)D>gl|d7X(W<>X3*eD9V9Uuu6AFM@vuhqcdIpebBhA zO4i)A&8VX4Sy@^#>_a3hyc$*$JTW+6U9n3Md7E`|%{7x%QZ^n13m1YJ2fbiTghrE3 z6P!H_dgl~tt9oZL9pP0vhtNiE4LvEafX_IZo?*%b9pOH8GA1k21+!;3UEbs%Ucv(H zVOBjRp^0t5-lT)}%Io%h%l2{<C2edClLkCP#}(>w+<pG=CWrx&=gLGJ!hvZOw@|{O z_5ZomaKe;`QJ8U_K`WLu^8G~#Yi#pFFwl|#nL!CE7V;RLW^c(w@xRy++UF9nr0Zia zjpNKDauJ8sbj~y8d0A2zJ_CV;m?WN#7qFrYRnsVVa!uCN8JH8}bc>O6br+Sa#kBM} zD}J%KeoKAn4d<tR!E84?G4Z}QKj0)`wkf>nDJySU3LbWf&<A!9GlT*5yU_4Ll3yR} z8aeaWS~8(Y`Tif6CZM`h{<&N&!VpFH!JD-ulwnYjNjfi=-7KyyZO$h@l6Azw!v{|$ zX1d^E(OQq#iJ3^9tVpd#Ld$h#LE5EMDf;Pcw}#1D88YL`;yaV6cQ^*%YV<6Ire+U@ zll4xsZshbKH?1aO_o)LxyuM4i@N6_bW?IOtA)X2`bNz4H$K006bZ`WVZ@MqLSNqL- z&if7L2Wt7XAn5faSn3fm26MJL3U70>q<Ut;#pa1)5RqETw2RM<g5#6yIUuvpKyRA+ zR#sdE^lEE;a$08GQPxTDDxWG7>t6=Xi!^?%Uu99pvp(bP(e^NBE&b$HQVh2KRs|EP zq5zi&3#UR8nwYN5z+AcJHQ%^+QkncE!BJZzp*PmRBdGaJu+d_c8@Bu$fQk1P$$9qi zG|lA__j%W(>1!B-y!NY8!~04XDK3pPyvxS(GE*B%tnPT7n?(BdoW&k)U~FGo&B|^| zB}%YYw+a)qo3snOSyJ6b57R52_GO>tgN|bDF71@p&~q9A%uJAa{#ApF02UJlSdR)h zb>VST;{DG?1%GqxZ+7@3wq0PrQiZC0k*t!{?#j=yYmP{f7)Pw?6Hpg0oRL-HR&6)g zo`uXpr7)d@McT&NXI<|mIeDLkl?B)uisl0ll&}sp>A`e*dz4M)RUzZBL}R}%>}rs1 zMYvx0BG&m7GjC!_)H-J(lGk(y9%BI@23f)vCn##}MgW)*0VJ&i3Gd7=hP-^}>e)}X zpnWPn2qC%K+o*v(V_li_|G@HcBtHFu8CDRMxdd4^im$j|?5ZF#sv*2>`SC}jZ?4Tw z;01&?#BwpKmu(g#4<qbkkG>QnN)68R!Ka&SU(~Zd-$x3J=E)VIzBJJWM8TS^p366H z&8|(d=3_J*U<DyrSFof-N$$Jn*G~9(Ux;4R-l;<@j-9v4(C*5K=k=DhJril4m7)bZ z34}8Nk6_UZQZTJG1)ep-MM{s95_WD;4s59zuuf+b+y5eY(_wveq+H0VeNt}tA|4FS zaO*0tukDCAMd7_)g;R^F?JxRLGrcXJ%sF_Jph-V>YwOEkTU*8&txOTE9FLQA<TO~_ z+mNY|OtDQHHROQLZ((Yz=9I<Pju?nFfU~=8>HbxthAIeVF~b5t`gsJ!{efCyi4shb zrzn#%Lk@D4R7St?p-|`*vX9I3=2wdh6Ml()zTx|SNN<8hUfg51onf-3a7P@vR&bY7 zzstFGwc6rIkMC!uZb6%3J}4!Xs05Q9B{_uCGpB=zCA*FXSR6s?EIyy<BmjSUbV0i$ zNpUlzD~WA(i=<8Af+V;4i_a_|=Q${ENp^{CS7xAiwz9@V)(<tD_D2Q>aZg4~prKj_ zD=~6X)9Srh+&?J-HTYS+J+tsODT<NhU<RqTU%K2*yxhvct^GVLwcm~(u3ZB20%*xO zaHtlMaOF&~LL}TP@^UG=JD1g+CXq2WmTCL^Go^<3Bj6qW_9(`UVm2T5BWs@DV~9S8 z^<q{?2#i%v*Kkuk0;+z^^wWJt-Fa4ogONjfTFdNWRx8-W-5b)OFuK=@{p;!_aG0Z6 zI}$47nPLx%U3}QO1>1TYvKD0EOFPrb2k^x(nZc`;@<(nfx}MC0k>aq>oeNMdy+>hK z*nX0-ofZrv)}P*K!B0fb_P)l~Jy_6q6^@13b+sDZdU-HFetJaG{rgO(f)x507P1P< zG0TkQA{`_PN`7ValCG_M3pM=&LzsnpKC(8z5-Zv-VW|1Abg_t(u<|DE7x1!0T^Nqt z+*#P=YEYI-#p#v{|5$L?MyYpzlQ=>o?BfAU!}%H7dkNNmrB+`m2K(Q6t06!k*bvZR zoRcRyFESJ_&oi%K+P)JeUEAt2;z(rz;+f~Fmj&(?`)b`?-i4p8w^lf~IHO_l6@#Zo zn5tvgC2yFO{O*aj&x@HG-8y&Kbw?|64HX^suik{6Bn7cuKVZrW%<`L|W_^H>zn^jC z8l7xuwz<#?{9LYB=@o~+a0Tm@>Pl+YC|C$|LkS7dyEx<d(|qVzu~??KzGu6Bw}(S> z8?i)fREVwjmD};8yhYc<#R!u{Q>mhSjf%`L0DB^e6gja^*1~ZZK1yJOq@w0aYQ@;2 zNq$|eK3q<wa|PAdY{UE7ja}3PbieBPXWj7|PAmasK`giaR$bzkb`BMrkKzum)JZsC zi<;?AMG4~iz%j|#t+5=acI8{IqJ<w|ZM?Ni<E?CCwzvSfBzp!jIx_`8ip4|2D(DBD z&t1&(!r!=r1Ti^VO{6YDovzNNOBN&r7Mvt4W3S6K`(T+u3t=0_q}UnQzoJY%UsB?t zEubMvEe_rFsl3{4FxngD)w(h{N4mn=n#hxuT?*|!svfwOOYkJQP+fqoq{yJM%#8ry zSzTYOx<fHEU!lZKoOGw@<==3~^Z~T-!4<rgocx4F`ZTw4+2lcvek#{IeGZ${l*wA} z|Mzf_`wHyV<K_D=b5%}Q?;J%Yz=y=K-(k2Mhd){MYYxg*&Cdg(ey-nNmM0f~yQ8vQ z{7`n7>IU#{fTp6CdZ0c%Xyy<ufM*}^)P&=i?q{Ra{$wsRT<MGHQVJ$8g=0xBTrCG* z)E{b61}6g(`&gMm)gzCx2G~SSej*ps43C@toMXz*is*9>#q6nmgry`Zr?F(6wNT}# zCMPA_#z$A(wq|?FvVrSW3hL|CFpvtBfk(J*04s<Zsg4irN#AAQ@!q5ovo&T%`Po0P z3HB;1gLt1>71CVYXdluHgD0N+(^s8mqEkKh{!L1nhoc6sgCJ}*L3<Lz6cNqnovl4d zdZC2&54qrW|H13~V{v~H<lUZJ|I%BQyZ8X{-1Ts$nKvN@WtnyG`^Eb3<aABMdkK~; z*!=c?)Nd=l2%2`TH_`Ed?3BxKD_v3VhaKiGu#D${fD0LYMtK+YfCrlwM1y}SdiBJe zGg8ysd#~&Jpg7I`qIbIZiRJpgGC9G8o6i&e_VUv*8cQE0y`_84n(lb&#>7^ZPbBUi zZV#_cY~OeOB6c=)V;(*J^vmt8=*DWJchx^NcNqgD-jCz1KXpT%g)jFRH+$+@Msx7; zG9JEPE<v0hdp^qHc_#JCoo8!5AH7{n`uxMQ-aMjABN+T{G<WG@o%xp@hXX^;W5YDz zQORkO*G217hHrNdEcCy7)KBYB9!ohHe(mEeKywIr_aPa5U^@%VqSHFgo!xqCP1Q10 zzVyOpTT>pJ6<`td`DH4ANt2H@8Moe|#p&<EJ;bga?%fZQetYPbuUQgX3qjmTTzAsj zV-rG^yM;WP&1IU?L{*$<))L0lc9#8ZbHOX6Q)d>I!M3`2p0a&uD$Z~6bxRp&7UeH+ z)Lp$ob_}MX(B{G`!;bmAQ{H>#f^GPLlkA4!ZX|&$&dOI<@31ew{kpuC<;G15u+b}9 z*$R7VpF8VvpM`8{y87$$e>>NQg~)oZIV2L{1KGM!60kt(SO59OxO3fbnbhqbBRl<H zQnYd1PeQz>6|J$7!v4~evS+(ibN<ZMfHgFxD1Wz-jCs24d2MxF)9fL_DnsPJHV_Xc zjiRC<Go$^``z5>K!}+->z4x(x9J<?#mni*PH7{+nFIZ~KdZ2NejqOOpm7Oj$Now6B zuQn#<>fthhL-#~JNp9Ln{GTcd00P*hscxnS`D(7Uu32flVLQ*EotLx|<vJ6!HsU^o zJ0n|LII87eWC1tI*8HY)2gB#-v_Ikdw@^~$O+d_iRGIwWbvD(dMa!4DA@MO&XD7Ex zE^1S~Ofa$Ckv#A-o1F)Xvtv~k^DlrV=7zYk;k22>m@y&evPStlyxy0l!v}9}R%^^? zl)@d;+<~oDxrz&!(vtppWhTs${zt%@-WI10xyOlz<}2ONRHv?X-p3{R`iIz(g24~1 zC7h~r<S*KXvsc~-1ugTHKm`0z5?bm*K{_K3i4pRSWh;B@%sOAF>thDjpYYmQeXj8< z0KA$fJkUPL|MKT{?%bdE)0Y3*I9wO&MRZq5I<7pNg0<WBdljb*HQs3~X=~!EL1QN2 z?fK_TjKyelGi@Wk{QRg;xAYM6yy9H|QyNNe9>e_k_sApRN&>zH=cwEHgVP6F$4Xf; z)q<{Zop38-&E+m>&aY;NwyeuYC(RbS*KxYhGsNXr=WeX5=0Bb2=kx>4AEmv15D%Af zFt8p}-Bfv!I}wbEQNF-k|GFR&Pvi8%cmmqZ*+NV{VB=KGU8U+-9i-CPB1T1p>1jG! z)(?#O5AeJB8q~-MKk@d+5`$uH%Jn8cp(Z@cYKCvbp}1HwZ|~*%83`6oEJ+~Gl{Jv+ zr*<No)gV;}f@%L)Wx0HKI#}`^(wLZKPw4w5zP)HpXz?j<U(O2ptF<6$Wij~9)gP7T z13UK>&H57qMuJCeOwLLbv{}@%f|dH1q;O{UPj9!|yCyn|XuzA!dV{7){B`GfK3kNp zLNwN-RpeJ`IvsySqjM>y(>ecg+5jmGFr*`Jz~PW#T_vDyb6w+SVI0a>{B00P6B4PM z(*5xN%>-xXqGZU2mlff~wsI?(H)juF>I-}Ty|LB2tbbVUX>WYE|Hg3CAlQcM*;ZHa z4-S(GAB8JX1o193*UB$b>6jwxpRG^n@sUPc3<RlF$ZxWWaaU6P!!%Y+i;_HZVl4i< zuY6x+n{vId-ar<2)@#&R5FxW4znqpYK4G7Rn8&L$%uSmwYjLs%f^U7WhpC48^(S%# zpgwwMUG+~dxHRuiJle7I(oayk)i$a>!^P=0=+Hvn{c5}tL;wOJ(-jj5q9z~S>4rq- zyR;CHkCdiC&-u&>U(n-9R-poz)-<NB8PUH@Jhf0YejRj+ndb5<qj*;sCKSjsRfy4E z!L`irI8esw7NKRe`PGRbT{<89fp)WlnP1MiowIb;4NA|xWMh&t$iMEi!Of9a;fJ6e zrN2%UDcBVYmzd*^xHig)Ixf%P1Y!UZS~$VFL3ZoSLb&cS7HU}v(m5Gh%|JIRmkAZy zOKo1eW4aJk5JLAAAG3#QuC(QcQb9<~BDRlG@*8Ut0gm2Z%w>hrGo=cJbbOxy;i0gq zB*u7eg0hR|8h5_6WxeQjm$O~FC}-m_0lDMz`RrjEC4DzM#aQ6YtjBNZFs3}QU#{kc zHCuF?Fl*E<olA$Hl$+EC4s=u<0c9=}#PxuXd#<w~*De=vz?fT_>IU5>lytc{@KeBY zQV_<7-M0%^J5%&VHCc$LbG#<UQE556!uBGcdpzR=KvJf(aU^V2+In?cXeX}T3Qk+M z{{AHrS7J<21l^JBySkepxKFY0UxnT2vN5)t(=FOpq__V&nM~W&#k;n>v5O6f==u*> z<uwW9KHv)0-GR#i*}_E?;t$?TTrs*Uza#oOC`(^)oFyI*Ek1fQlvJ+rGD3A(aj=T_ zD;>4QSFI&@h1(?i^SiaeiBZcCeN)iu{+?$!e)8+o3f=jl(^bmvyvJP@Pot|fU#RO@ z_0cXTbaUs&dDjQfQr2>P1Irvd(g1>8eNqeu{tBd`Xs>#KPI8L^;0Nb>b1RLnGe+Ic zDS>s8{$GxEO0|KM?s*qNzEd1aPD^Y*-+m>mA%x?y@`5>`RtbuE4vamwM?tox325~6 zufX35njKVZS$$v(>=s)~ZhrA}ZK?@@SZzOhw)bTDgivy`PM%5WTj9aA{@?jdQT^;@ z!2y!dOq@ljpMnx*f5z=oN`hSpVsxRG25Mc@m{uaTVp?zaBOg6=>$S>M5%aBXOPy)0 zH!G)~mXqTjQc{`{kxST1+D8H6hqu<nX1c|7T#ISLYS1HhBWLF4L*IUjPNol#slY6I znB0YJ35?5#Y)=x!Wy4eY=MSOVzu-YLpffF|+rLJ&CYTCaou9Rsz#oH^3#*zR6AX`N z9&iF0Rk2Q=5UG4$zV+6)lwhDl(;*UWMRE8qL;hVL=(o@;w~&-CdCU&3l1fIy+Cr<9 zuL*es?1V9n4fmGa#1^-BHwo31lw&b(G9q<iW5{K!$j5W=nDBkeA&xk#)v_?04%y+q zp+%wX&r}$+aGoO$8}5SD8bHUTgu6nuztpLx*Adr=e$mLR%O0f7E})<umM7Hpv;KR0 ztcOUduw0Ar&<<D)C2EDuB1SrD@Y$(*7%Q}Zmzl;0s|W-SseRDiZ@#Q%uX5ggP@|#* zc$~%qr;#S$9CahQ-h?wdA{uGScHXOzL&D2tG$*by1Yf^<B=W^%F+QnI_i+4_2G%z5 zZss3&cmx*bCYC6T$vZI&6KVXmgR!0xUZLnms}T7vBOUp2NnzVI^5|J7V*@TpD)wbA z9sWhW`uTU7wl8Go?<{E^1_hn0p6i6@5d{t0)<36D(D=va`An4~p=V}{TJcbcW8T(z z#8#5E;eZ!8(M`pPpk71MP8k@qr)fYap|Rkb3<1M2_x}LJTiYNRyvOsugqZI%txzyr zzE9`~7{tY)v}syKx6#6uYb+Bpx|aEYObrtRJt{%je?foOh%2*Hx11oIwc+VsdadS_ zMOQfz&^LJuknJImgh&ZT1ATeMYQ%w*W^vyyBdV2<2XH3kIU`viDuPUN%y3pOl2R6t z6i^y?7)c<R)Yq}~3s`5U9T6-Si03ymophMeO9}nWU_C7dw+kie4ixEELU`_5rZulf z(i>u)=J6H7mjh1tOj|1_JWP=-RSNP@z0iw33&j@mEbbhc?Ew{W8#AafuK~T6K9z%) zg*SbkY$h=v8l4_Gd=%9*K5ag0g&yNa4>qeEDnV6X$0MLHU&C!YRGB>B?hR7Vo3t;5 zs&AXR?YV2W*eSHq9CwXX8jQw?fqL@gT0Mlyr1w`hXe#o<l#TLhN_TU^R`Kx@wG&{e zAUY>oI=YY$GGweSF{?uyP)i|b%^S%F<*r;~Zl9>jT^>hVpzD<`xwp)jNWHCLy!DW> z(c&T~MnWYcK|K_(<`IG5>n(suM?+{H)~~*8U;YhbM6??#bb)jd{iu9mwOpn)r&>83 z^iAQ!n(egn)YV-Uo)KSF-B4R!n6ds}Ye`+plFVOYJ(IELZi9L4Xl5XaC!dMJwXH#3 zbpGWcU?BAlU8_r(G~A*Utr2wm!Sap-%@(^qp{x!~GWly4P)u2v!HrXIyK&hf)_MfA z<FMHpY>M=G-w6J*>)*Fy?AQ4*4aI#%ICy-Irm^U&bWdtB$%0x}FEk2Qvdt`?w4R+@ z5Y(gTg(KQpMrB2fb&uXD)hrW1ewhOK6pZQnnE`jcbOe#6OU=FKTiXl2!h37WGde>) z4y<PTwq(9v@fghMyxwfPB=BU=;Lz2NgE#YRuEMK9oke5Su7TuPLA4J}I!08*<C79= zuKbQ|#ONW7G-F!6(C^_kbIv^w?~d6m%yI1`bngO>7FmS&^P874BP(5?(nTs=q;svb zyi9`aB<;7yPIUZzHJd4|6t71|=?FC=S;+XV501Mt^XsvL4RmDHKSU2=t+qV4tOS;C zp<Ncfkw7J+%o$^-V4LNQUZSj_j+93HVr?JokHu*nFhMVcj1Mre+9{XXG*PHv5LqnC zHiL8|+#T5K^^R~nO-wSa#lzPuCcKEPP^dzwyCnWfcoJBxY8Dd|5Mty?opW#FVy#^! z0!#>UHO9t=wy*x)Se~FMca11b2=>C|hvmH`^Ozjx$#``!f&LZq-V++hbyPkrouUZ# z3<~`*$;Bap?k|@09~9wrG?pv%@)@mp^cy{>_~mHX#8zNhriP%?V?<nmXxZO0=rqw+ zm!=ozJ!QYgJKPZab(U$C{F4uGgksP`ioSqI(`$pKwv?$xuxcV-Lle5K6Fk%eHdG`3 zoi}>k%h_@*m~8e*`bS`d<!RNZV@3rpuyj+3F?@+(era&XfDL@D#aP~iP}xVl@^v$y zuI$=`sps4P2!iGI#%T?%1eq{JD7CuK67b=HL@ZqN7Tztrvgc=G9Ec+IQxO%~en z@bP1amG-Vp=joGguEzJ4cr<KUGk6}ms~ZUtZ}_qS9Wt9ai7<72Nt%aX$PdwYu;*g6 z2gQs9{GR3K=H=i#)8#SIK9+>vkxo_85pxm2iz8SME<;gSyC&ntXk#lXScOgEYG&ZR z5$E|X<2iWRt)p~tI`9k^|Mwn(MLb6CnwZUYV3f(=f2Fl@qTttez$)J3mGa)#(yB%= z;ESUJ`b~F17l_;uN-=BUBpc$D@3_fWoM0@OM3tz}p>ATphC%ZGd<ee=7$>zMBZE~7 z_>b;N88~;ew2GX0&jZC7kgya`rWB;@ba`WF=$UlHi2P@#-3h~8qa?PWc8$hn`U=#| zSigZVkVt?U7q7mPaO*Ty)+LR3)ovuqeT;rPrFJq}g3U+)$iH`ApG;pTv2ff|19h-Z zS%N&P|78hX2!4vk=pKPOi5b7Uj5yv8YR+W&dwS`<ZtFUpb;6iiOAH86r%WhJx0Egb z)3831Ggz?s-MG66g`|R75?z^Al}*4u!(TOGxl!d4_<<%<M(F-4xS!LEF+aGLiceda zh}WlS(%GoKZn`btv%9wdCZ0NxVP6bd*xX5R^fw-uA*YI_JDsLY12eC~CJy>r^f3I& zGXura9sY}Ro3WoG{}xet94bm_ru)XAyN8jDipR0w>K>>r#chRd+_JiVqmV^21?(s^ zG=41h)j-HEk*-GsKmPkcV}>aMbnn;d$=4UwLwv=+LkY@3<`;!a>jEIj1~qkq8G^h& zjo~Y0)m5T`SGo4L(=^v|y?I^N-Ux*<GLpzJ5gJ!}3ieq}L!_CN$=@#n(rd7mT7!gs zZR5}c$A90&Dvm;jS_lT6F#VJP1L9fN&aa>)4SU$*nMv@h@J%!Zh#?a+?cIJoZs+x( z$@%AAs?X4|e=Ps+h7YT{8)`%JFj|%j9$+(l_Ai99qXAam;V!AFP)Kte{+Y<$VkbB5 zL?4al9z44PzA?pfd(`^@4@F+h*r2I)bMqpplJ#@cz%4H0ME>~RbOo&+`9oU@s{i@~ zrH~c#qF<A<?>dkH$MLc)TS1>ssv}KWdTlb>?5+D2IS2UJv~uZIRs=n=u@ffT^u0!u zcWgADv7iM^I`r}j?#yV9nobVeRfV6|BlF#pjGku|YKSiD!B+^GM+q%Yu2Ks$Cp@mT zI+R~t@w=3u?KJc!jEwg0N0Gs=R$|B_VB&tLCY1odCTlu<FBMVK%C|G)1;Zf#_;T9m zOU_ku!|Ni%lb}YZH!THmHGSaxCGq9y-;jBKhl{z{a;2j-@PKcTwk>;ZRvTdcJ@9c~ zGBY=8YMZoJBq*IUMD*jnQxd#%B#grjaCWAXT!-{Y&dq+3w;xn6;O&^w6~h!`>L3?G zCo~e0%!oeM*_C8;{lqbpweU>y{D9QBc<`_CuCGN=AjvID!B_YK*D8S0fV&C0L(uXE z)O_8?O;4Uvg{$tXkJK@jB?WJiP)gI;CFsu+G-*blI9hrrq)k)w<Ni-$;u?Sri<}1v z5kEZ%Auew~9!^inwGy_wZwa(3ij@rM*&C(701PGhUu!AmTpfx{JPP>X>_?j;X_9SC zd8$%01Axl;^80LA57H(V&vqWtSs&L*!PH}CUAgFUB^`smB`54n%izXWT})pUr{Hw; zE2x8knBt`=$K~;e?sH)=H;lE?j161~@*CiuErN0@t>!LVmtF?2@4UVKyc{A`ME7y| zJ7)cmV_@y17POoOASa90U5Yxs#WM9H<rU-<L|22~(&|W_M^Tiw!57tO>P?r`c<2`b zbP*xue?hIclL)e4te`cB3r@4%jSRYTf#)Vj<A|tT1J@;9aQY3i*b1}(4hg)0=Wme* zK5Xh|EBnjj>GH*#5}ue1kat5P_a_qfbfjes>4pOLhNCj(Gs&cBQdtci@!_{$d!YS1 z1l#k++`?AQ7X+C&eOX@mFOw535vo<>J9M25$&&a}ai!-v@+6a@RqSt3a>l_Z6cZ(3 zm7{oOszi8txhEck+1oR2es2?V@;j5wt<Bf6o;6$MF<i~>Y4~>Gh58$3Yr0)p7O%y) zho5*pvE3Sr%l#PM2&gsU&e7{G54-p@BJZ9lro;2OBLxz*PcRp3t5!iwffLq&f`<A5 z9MU=5U-8daZ}wg!S&MgFw|#Rn=J7fCHyt_L)9WJ?F@3jRX_<UyrsZFb<oS#kZ0E;^ zy?uIRyyPjjSC0h;{20IwnL7=@#+%PSc>dNf_R;*~KbwkgTd#i^D|?xTKz|{vFfs1D zNJ;8R+#P<LYi?nm21vxbLcaFw(Je{)6Y%K%eLe}>jV0mB2Ef>o$v*IZ_rGbp8{_^c z9$e8(sR<w39=Qpkbwr>mgH)$wlj@4b1mg|-6{O$Njq!cmL90@Qj^Se*#wC6Ak9xl> zpD5cs&09GQmqt%0!)k@O<y9nh`K<Si7Jet)758-)rm=^2q2=(>{1o<aslAx9qOm)* zmw98?94>bxw)38;N&I24dE<IJI0rAe-STpZl)<)Bt-XoKM42SBL=VMNV;^z5Zy-L7 zNr$Pbm<~gzN;h4+(QSzIDT_OEJlbqI&8`33F5gz#b_);>-rOdMvVH7%d7-qG?OW}^ zzqSt`&{;qxy9Q$?OtLuk&!%`P<yRJx*f~0UH~N!mh!rp+<t{S3=~+661xs%nOAxT( zX-t}U(^MmNNg+YuZB1yj<XgQRvzzC$-0qruQ`2jI691Gr^Hy>z^GI{MNbV10NYhCr zt)NXL;L7;hE!Ee{nKmkyYi=zI5qM3&PV=JVZI22K*03x1r{X_@?^IrGh?*)3>Wj)5 zh&%eVQPb)kx42m?sX-btJ7N&2j<FW8_O`pH>bWoZ4IcY7JRIH;tMPndJXT_P^LAwU z^26GM&7!;2QHvI^+sT#(8=@>DwHElAH%}Zah#ES!LMS#RZyw{)#6Z!+R0Uaj;%{M@ z>eRL15oEv-^WB@_+Yf#YDv-<u^|iT*%J-I3JU+jsEDcw#<k2ra)rb*Y9<E4PV7^<! zc16CKmWXls$a`hS;p5F#wgv_KcdjBy!4S2O3BL(l&0@b|=beuawYe%u9zgAriT33{ zx62}ucNc{3sJT8#hap@7d!26GKC+PEUvxP$Gr0Cf^G40}jXgg$cgrGLL3Ec7{^`5- z=z2I;E0ufJVLFhVyF4%?sxms!Pt1umQ)lx+b#@mxb<%A_d&i+5WL}bQJMFyQlFP#~ zOe5yqFZ04Dvzb6PDo4kun@s_87F0;dfAJoXn_A5eho_wa*yh^9z$ywrUOFHO@5obp zFTq}x8Kt!JEuJ9G6CJLBPI<*`0T-di`XNte9gyd%+!AID@<!XR%qetkAfsOKO}35O z)*OeseFnFZCA?ul#kA3NFVEP6%?b}vBu3T?xkiGOo47e2HnQYOshzwQQ&t%&oVQ2* zJRLRiT;@pal0d!}GI#AR5_Z|8iM}fwG2A&2F?iUnfEFg%EY-3)(9?Mu;U<#aon2K* z#qO+_J|PU6!&9YEIx*H2uSCdqINOR?bu~ArC{l^4FfP9L$6V)!LqW0{O|02<Bw%7- zEMMO$ZFiTX$>Re6q~U}tl}xmk&?UXHBUe74%ysOG^6^D}NUh_M5Ny`7h5isLb_=iT zEL;FpR9$5FLAh2$R>N<|yv8?PbA!S*jzleKA4q_$c4w_w*dYz^`DO8XVHV8rm~ash zQ`4a*BS(JnAyJas-tHLt%tJ9O@tne(F>*|aUP=(Z-;||)lEHm1G*JR+t8A_(8k>J% zel7lv+O~CDRdEugU0j=~svjQMh}yQ!uZS$bC=H(ntymk@MKPUQTV=Pu=O^@QK1X|F zuWhOC5&CQ5d&4PZjh769;G1SH{tlLx)CF@HU7j?y>)<q2xH0F&U8o+TcFf#VM&xdx zi{@Z02avihvBBMx1^uKG?T*K~cBRj{<Jf69xny-4`B14UDb^$tO=LftoEG!hefbfu znC+#b5FSpeF^QCdI@yqS=;=O`FB^FtU+5pLxHX)U_*8n!eYE3w>K2GMYtP>;nZ*;* zcq6&9e?rajpznI2vG|0yxt`ZHUnJaHH7oP{?~u(CPq|`qEFzuf1D*Butr{g=f)P=e zV%D1HVcVqfGVi5P5=UivyXc-b$)FfWN%9{-@7A+lx^loCwHqn^8ig3Ql=A*E9D+t< zn`?!{0RbB<d{{0s?R-_UvKr;m7NJ>=7wL9zU;hV6`eE0grmP)j=Q&rmxR3W)oP<x* z?)an4<3HWckJ8G-HcO9=>>uQ%YSF}AF*g3=Vigo+zsHxSRchz)ySyU&7v>!@+gwAX zAgnN*trG=Jn_qhA(x#~?6H>^&=fLi^MU(xcWQLJ{wYrIkIX{`LdK(>bEB?4X0XrUi z>61jO-d`{)3X_4DQ+2-K{w;80bgF78mh$<erbzB3;F9YakdIlBe&t;xNoPN*AllWE zPPOIATa_tHpog&nlmJpo+S$+q2=UWZcv5RZP7rEPc2O%csB#&jIz8-%1LdUAcb5QU ziC}#ZSm#ZJo?EwgR39^>c8um6Ue#4j%wlZh4de>!#@)oirAifd0ZoaU!irBOpI#i^ z%ZooG@Fa3U>;w{)4-F_U*d+@=WzWuesl^~iXNF;MLSwOAdW+wlYnjx);t1LBWlKd3 z%X9ZT{`NO_2hlUH?(W`Bbbb_NFyv;h)G;5McF&0BZmNcvuaQ6Bsj*fJ(_O@M@vba; zO-hI*Ci)9RHWg-0<7vnztDM*U%}>l-Jn5%KUOqmlzT>lyW4Yax{cqtGnsUjo>&rAI z&1I=scbVq{^f!_$UkD|L$M^cC<#7@n1pda#tVX`Cn9QH+W!jBUO@JUn_`ffE<`!b5 ze4GWx-w6Ys!rN~O<<)&i+!kHhF**Odb^<bx^pfs9bh-Lnat(V9s%FO2*0N}!b5&D6 z-iLUVjh)K+v;GNx;KkMda2&tQV#GEUdjhp2%U^(Q$qTg45HS$%=kHT;(me2Zr9b(x zBB+QGIzn6N%0GOa_R%W;;;IY;B^rVj$Zu57k@!V1D$tWw-W(TQMlnx)nxUJ51Z{s= z8iB+IWS43Mih+pVIMJm?6({x?5{09l_CA;9`VlooWxkS9Yh+#skeBNNT4z^^f-lh9 zl``^8fl!glX>4`p92D!M)3`v}5Qt<malTHJ@lpJ+R@fgXUd)_A9JHv(5S<4K@Aroc ztd`D5z#{@Bo6?1nIf9eFp0clpdQ7$&Q=DB`V0fCPh!Gjp92OcW)@m+1rJ%Bm6Wv6g zKg*OL+WKg!4m|;8ue43>4b%L+swHuy-2=`S8ysexfn#iox8o4YxNkgM0%rdBuBqvo z&}k^s9*7F3Q_=qH?@@biN~NBo{9HYNNNj}m!h@Z1NFL>r*h0E!s>%1WQ%LtBfuQC{ zh!nmsYBzLx`(#E*ml3(HmCjv3YGe@olp>O&AH`MBJSpj+A^iwZ|B`&5jSkzjIh?Q< zMt*m!D`fV<;X3jZm5<$3WJ%}UFm}dM{y+(!;y%vU;jZvUiAwUK$w6#SS>mgLHxJVh z71Egbk-<Spkzb)35VCXVDlC$Tug8ZKx+=b5YqkLt+?Lg)*OF4nd~bY&Qh>lc7IPjm z#zL4+q{#wgfU_7?tAq|x$r?^=`(6w&@0&#YOBd`j*G~nRLn5R?>)U!Z#ed)g?xDr! zM&5SG+d<M0z5Se<jKe{ev+veqE^xCeZ-^!2&%lR|Aw>1ixjnq1Xk3KoTO4x0pLgmG z;^YbLlk;8AwbjZx3$gsDF12>CJm2e0&Eid_mheE1WrjlVbmJkx-W?5K0o?fH+t%|a z@yVk(MTON3+`}25u#pdP*c$)OM@;M<=4s2F_(7@FRpG5+faN}i{C&|rpjgJnw=HHG z1dFs!?~Est7H~*>n|OPut_n=T{VqmO27gEpC8rDU+=I8GMDY<V!-T)yyzB)$&-6?H zYU`rOv+}`2haJiBcF8$^G~(asL%Lxb<QKG?wn7K$H19q8q}&tY=vyUqH$>K<H%4*D z4?XZQafe4!BO~2%)4#mmb*;9yce`vU^Wpxe?8Lg}Ge>1%Thn{r6eBIlgPP$dC;1wR zFHKoa%XG6v-E$Nl(5(h`KP(kZz*PeVR?k%MKC_lnhzL*oXM14{DEi4evzsBF94hdy zUqx~4>kh}V;?Qy*`F$1bWpBy$vJ6foB5~k~XmT;zGMLwWRYzc`mao%Lf7gu6YFo7~ zXtoWw#4Kwg^;qg2b{TEEP&?@iL>>=WIPGJ5V-kFu`4}{8`eD=)J`*PTZUcqw7<GYe z^mE4;kGzBH_v>nqkr{=)JR2tD$cu)kiee{(H&@NmN*oXbWw#KqAO0%MtMh91X7lET zzx&z$!C0r{YyvtLxJq6Vr!NhH;(KsN2=@`uM3Ka*K-m3}2p0Q|zIg&bMG*VpImTZZ z{<kcBMQQzlLaipT#5yh~8y97(zWTnEbfH)upqDapuaD%}1H^?_0<%LF_Fs9ARy%^i zc9kYX6KmC|lEabHNQjKeN7Q;vq}RKQGZqmubik{%=C{LfA|LogFO_`%rzrp12l=&M zWUT|yRO?#QZ>C@8*}cZwSBEIR0N`K1h?ZT(_<T$b?+ubn-fs}^O&1aK1`Y$bbCeYO z4^)4VFV+T%E7J5LKhlbEuhkX=d7bp0%7y6fX<_?;Yz$BZAKO=KR5Ca<vh6}cEYjCU z#NR%k!+If=Pocg<<dri{tWgF6;-;f&KQ)~Z`L;uUg{i$_elo}8ln)eX??(#2%6g`4 zkso!H!2*^vLA<Jc%$X}2KBiC*CtHTqv`PrBR7Y+DnLNU&1r!6BQ2vGcX5RDt3^|Wb zFr9+8I@gNrpw%%ZN7x`&rUuC$K#>*VL~&EV8>3rujlNvjJfKxy9aUpU<8S|9>&8bv zhys_nc=<<Hxm<<=tThn!=oGHCGrb3+`_8|V1|=gJK{Bi20%-UxwCK?$QcXo|9F45F zhx})H4U!dGzyB<VqTCq3evKJYoF*c2zA(|{zN56`Ef9aZ4?^qSXM@sry}Y!ARi<sU zNREQCPyOz_N2Xqb2x>qA_(&nV+;X{(vq|bu#sA95O26Y<XxvcS;$lBztDhHz@h{63 zmtZnRM<aY?QoLj@=q^fm1sf`*myh|(m{cJ6I7B)o`ZrJm{&Hr@0(Ha6s{Vl!YQAD# zqi0Lf1sSgw7hlF+;l6(NfkqxR9O@(HLFQYk)x7VDwv|u=e&$~Qrn+3#)>8}Hiw}Dp zW2G9c-M*fvna{J?r!SPw+hB^_Y9pE7D5&-m_LvH9qiBF8)n6SdnxBi;Ocx8eTiSBZ zmaD^?bu-oDZ1OyB(bEfxOpv0r)zT*_#@*9v0%6l%U(YhKk^8v0LmYJ70*S-BuJxBh zQpBn0f`jPv=Hk*4yrw_Ma03<`1Uz@F>~}H%4&(odbY~ZMWSkIa!{f$moFUbr!HgI% znw)y{U;fMd&p&gEK1Wbu0dOko+N$t!GqPt@uajRo7CiF9M`#0#&v@eUC1IKz?tQNj zfMGy$a5eh#r{~6;9@?vBELc#@hSgtl1sCvWPGol#0G{)Z36<A!;b2p^s_jsFk=cDA zEB0??*u<1-u#IKy9W_Uv+^0Sw8l|~!O-oaoYTTZX&K-QjjL0l|b9j|{^p<SJDhj3q zbFBGcZXZ2axvzCI2P-wK=UFR&_b+>)1vgw5SISL!Wx-7J5&P}UdaJ*N{sAM?OxwT- zQv}37#bB!@WiJVq6O4kps{UBI{>d_dvwZ0t-c3QI4)@OoA+Z6F^=Hn_hLS=#C-K7n zp~YM6#rM_9ZXM=yah7j3<#X-+BR9h=bgsTRg01TKAUA<U<cG*+b@x`}46fSV`M<u} z-Ub|CB7zgRfmCS}V7L%2f{UKI8$zh_g@NT5T%>Ga8&j5m2)fo12QIj(jDMRWV<DPc zZ&S1SpT95b&)U*~?9yKX9ru2OTn36I?~F|RZaKeJ4?W<gn}|;R4y)jQiYZTy&Uc4{ zFOq$J@N|=I7>9J@h5Im8ypOFAHg<2V1)`Upg=X24fj79mtSlaMpbMV=cpNkFcw>Hq zw^_;P8!#QLte&vdtVBVclm?5NvBk!_UkIq{i&eCA9utku5g<A~D8?k63OaU=ko3kf zIrX}?XF^G<%bf!jTT|NjT%@cJPni7TtyK^dn=<Jmn1OvuN0)tm1Iwm7cEBM!GrXQj z-an^VF5K{2tCmaVZZ!4HbN;W_25`bEmihdOy)MeFHrayotdh<QVwl-!?Uwq7+ONeP z1HX7P(U#-MuPnDM&+4#?${33?{2gk{0(9~k{&pdCzWVydH$KT4VgH0^X+)_jnm$e% zPqPU=FJtSP!*U`wQ|56kZe3hv6?TYvxWwQ{ekuNN8PgjHG#np4?>=2+TYcc4-Gycr zV*rb>=(>x_H?!nUeEWscA{4(X=$Uy$ZTEM?zK;1}J@ZFCL@wn{__rCvL&UxcK_gw< z<BmAdZr}0Eiz;U19pEp$YKKW<_FUW^L_$3KM)Oq@4+gU;@7Z%)-(R=gd-DptQmG(0 z;bUlcQA*9<;I@w#TYt*>s+OKnn?)Vd8?->+oNOTc@#k+?69gQcas6;0rp$hlmuqkV zDC!@{Aw8f#u48(=%BN@Ns=Q)LmSC!kTzPgArakj-keMa@U#IrlE@Gzm!_}s8AlLKN zTV~CwOW%l!E9dD0PfyZ+9d+|T0HVo?BTNJ8M2URMbWV3C!6qNWM$F>_c3a{A+n4UE zx~`hZ2c=kG*2z-Tf0Bi-SC|k_gkC)HwCA^xUIB8f+WR}!IBY*ewxW@P1p>mZ2l7dm z`YMeM_1NvYny;todsY_gK5z+}*k9}yT(eRi)fekciYtwd#gp8iH4db|%J2Ges<qDn zq^Rg$@oeLfk!9EWO$9o%(E)77hyOladn&zC))*@;T~u`89uLyq2Z@&=L;sHN{b*SF z@gqEbz)Yk_P+H2n^HH5u@qeCY&)-mQiRRx*7h1(V?7pLT!z9-J_jgT0(Fgd<zZ1U@ zMD%KmI6&f7SNOZdy#wMykEcodB2}s%r#y{;d~)tRWaawdJW<``V+>=pE9%Qql&=)| zyoF{AnfuDg&#&+QOZX;YrlwgSqZxwYqu`wOS9_AUb43(bRGQ}+MMytBYsS_Anyv4< zzsM<*u*qE=W~MSbH_u0%90{|&e(0f{qfyYUUiEnW?NbqP14^#uxfSx-V437ul&^P} z)w?<QpXV-h1RnK{p1=R}o_7M_qhmfrJH~$;uO6|P;uiU#UhH-}f)vjGBKf~HZniVF z2-V;NvF`5_!~yN@`zOz$jPnp}&e2@ouaY|6&t`=Lf8yas0c6~z%`?8%=sy4PWm!9X z@;8^)e?EW48a*%W>G({4YD>6&`*qmc?=E@w{yzO$rSA6U-!)Z1&J@ANXR6Ymz8bI7 zU8NH%O=I~JPaKTdxd*4Tzt5~&=s@DmPw9-+)N$YrWbt*Tl4T97XA<olc_gAs>#X9| zC*tY=rF4fr(7gRYSs1kp?q6s${Jqp@ujOD&`!A)wJP4AtK=raS(%LBe;wF7t?_J{g zsdL}wJI1sjZPL@}cFx(G=7){VvvETDTenOn^89SIe>+K988D6ymUMc97W4G}wgxkd z)xLE3SqyIN=lOjd<Sn?!seZ^OfZ|IZG9<8n*z_i*vfN8o$*bfzyN%&%1lT<o3%PIi zVKbzqCF^WM%OkH3pPE3e>*JYC#KlQn5Zz?${*x8UEA3;>vGVN`-KWi`V%!ZJDu*-Y z$MqmMos$B<Pla*h-Tkf@F>5|{>5@)6?e84wgBY$pQTZq9VcnA%xe>i?Hj6g8vo-Dc z<bXTo)Oh?mfxErSf5{)B!H;6b9=AY5xB9SN&5^@K@t>#xLKXq;ni~y%och(|Q6EDO z6_c{ziaa$Qn|K@~z{EJugj*qxj|)J-RT^_U9!T#*&k7%mbIA3!N=A+dotF*hza?_h zEyGP%dbMvWB|1!PRqX+_<dcKVk9gmh|50?8QBA*X0LMpez!;-JYNWKIB&9}+FiINf z2I&$I*kGeaNva?zC8>a*bW5v%prgA{;V-&p&zrs9**U-8?(5vw=gUI8DGsS;!Tb>q zqf<8gCpc~I=JV|55<~g{Wa=->S%(Bh{@X|`OjkC<HvG;9@sCj54VzLFLt3D}htVg6 zVr$4mrud^;GRPw9{pXQ;KR+81Y;+#_EJ$k{falZh657l>CaRu3duyT@DmF!%-zD`V z2aJe$az>r;ADvQl1z9GxNcCHN+c$0Ftkz+g>*=nG8n+CU6gftDl~{TXfuFMunX$UF zwmc2>+<(jcJ|5Iugvv8zy^M8u*P^sg)~S`xz}}u|L14=d63YKb-ao=YP#6(g>}v~Z zI}D=ae@@D54jH_c6hF~1;(TtB5n(v)Ecgmf!93bbQV9`YG}V(&LBC*hIFgW4(hmta z%MP;|anZ^tqay}x{6;gv7zE1ZRgyYuxB^4f4yU%0wko5DH%zI=ZY5tn>lb<kN!2s_ z=2?2#9Pic;N0O3)ZX*r>2}eg-e*+No!U3ot1xiKP4W@w^>_}xzCD&R6h1x&*%(8$A zv%&dESO1(5>bKgWhc!d_53@2Jhm=3@N|@kc9P1Ew4hqSZ9x)qkPUlc@1jj~TARcHX zA^)H}=0F3rx0M-|r6}WvCCl@si7)|{>^vG#>dOCknX&e}%uEL_V5mWDi}M!GBD<=% zCZWvYNNvDioDo1+gC?*f8xFF~k&#yv@-21d$|k3B%k6C9j+K$LZsAd~3oNUonhYB~ zTvvMiW%5Z;gK(HDzu+m3-x-PGJXtKG`niWF6wWoKIMWs{_(FT*re*(D({naRkWqpv zj;FQ^c$bo4Hc|Br;b9Kynf9Ho4>{D>XoQ!p+9;A7>KHFf)8JrW@!voa=X_`xmQpKp zS>p3jaK6Il6<bb*g2>H{Tc4Xol=@AE>e-uX%wuwvYrXXj7l$gb#E~)7X*_H3tklW^ zhB3&?nCXGWb7<IFUu-@56A~bG1sbvRmj3*1|7R-jTisR)Da(M=Sb(}&neE?N^?6xb zLE|;$pZXM|!6Z>WYA=k^Deq7W$d#KUTip45^8IP|ZOP3zra$K*%X5DRI9-=U;Ok|G z!I~4RX#<HGtRP*BCxWF#0i)POZ}W{s?%@ujf0(9^_`2$sj#RVz3jfN$v1l^x(KArV z;P8s<y)9k>0fYhClL#BQ=htGmPE`4Q9Ln{zkpng(N;hO8QIc7b`i6Is3m8p276)z( z2v?aOy*FAQRq);+-ruo*Cf8o0U4Mpq<763uKkqqD?A~3z3p!^4>PF;YSKv=1_ndyR zKt)$4>X5S>>qoFpte<OimDFq3m~Lm+NW1UwD%-iFH+&t$$pvIs)K~h~3^3zuM^p*~ zzVnDJbz>{evRQS%-3|xFHl`-syOhcp8AOiTu^j*FDp4gtDc<>A2vq*gk=>sW`6+6P zulU{W{SPKOqDHYYG=k<C|M@LVMGL)A`eS$ZF=<qrH+NeZUHa|@i~MYwgL?o6t(R;z ziqj#jjZk@}u&4hhYF@g{;khF1{-i{1Lz(2yBOz7@cX8C`@IM&Y1o||$i0sd8jqMG6 zoRA=eep32~fxG`S_H1dMEDjpoQMBv9+%td0P}Stq{F3%asGon?G^kyu4Ubj#-k)7K z{`I8f$nTdY^~#$2c(7O?`jIc0)G-YBZi4n?<&gLLC8ept_8N%1n*=)6sHLJ~a}u{B zR709MaaYeiAWcR72ao3!@H-S7bUS+8+L}^foZdG@CXu=b`fQj>ATH4s#@yGW4d>KI zbOij_5C>8z$gYE|J-W9VDn_Nn;mk#ru4_EVYn6Xl)Rc?P+zekkXB86w2^RnD8t!zC z-yt+o(Ev7h)*ZV(-^r#X;dBD#L3>qJ{`x;-?b_nYZ#R^cBC#EG*|w}!{MNFQ$PWT= zFZ%tN9h1s5FO6S%4Nv4JF2}$9_Ix`b{5QTmC_FHFgH_iN@Mg9tjgrS<XGg_STSYap zuXTlM3!fxmND`Gt;6KcHBk#7TB#h3Fy(qTXb$$3a^wT5zpGvoN8|7&KtQ^Gt?mp=` zc}jPKr+Iocc;~}eX6DVN*wgFD#~&_U(*51N|Mb6wHy?h!$^3ih^YqWk$%o$`>HeLj zKE2tz^YMB*^WSCN)4zw0KmPeaN4T1J`tS11$G<0;gqwq>gqxF(f8(iHBDS8AEj}I5 z5*i^P(8X!7km|+JVxKl%GErU8<w3zGaQh!?aqJ3DX-Qbt;lz412tpJj0d(_8k+-l3 z+qaoV7N9aDbQdu2BO<Vf2jFJto&+U`)Sx!rxyS}SCcvrHh>_<2l2Saa;1#pfTh#r6 z7)~pNO#mGpnn39YaD;)k)a}8eXxqgYxu1|bS71M)R;msNZSr56v9_y8vcFQ<I1PRa zLsJHj<lrF}u=q`W6Q3H){BH;nM3;jHn1d)<;Y`>*>nB+3S6xOTzB)Yvbg@dBK23DU zLM3}9PgyFgFoW&kXjTB#G@R~9i$}g*%H(f4D>k}P0J)3;c`1MyOTu0$Oh_HwK@%m$ z?>LYv2w)Eb69>Xg3Ms9^X+7a=-n<Y(6SzbHg$h99VRYQp=mFvM%CDHWH7WH9REqIQ zBW0rVyXigEEO&NkQv*oI)rsUMRxl#v$7sg;+u}hMz<5tU_$hb;Pj`gPL}4(e7r`|O zG&<^uFN7IA3ozH7xGKv?mOfL0JLHZP<XHd-8Buh_W&Dd{qlm<@Tl<F%&~FF$euHM3 zk5W#<AnPQCwN+Un*1i-KBHQpN<}&1YK+0P-luQIk5}r0QJ4tjbXIh9^dM$h5)aSMr zeWFV$kw2wZ%qn%nyaI{bqskk4%kj5~F(?k$$19wq$ru47B%FID(poDRvE{jpdAmr_ zNmk0J@KZ|#8OW^B!HEKf9uWyld5evAP0p{p%Y-<C!q;?2v}v1|GhFG>4A$s*Ilqyz z#K^INViuXd>a-0|F12_TsSOMcmT8U4sAY(2UnqDP>A4xqcLY$FU6a`{NpJ!shn|8z z2*;OF73YT;{y>6ZO#q@?xFQoy1;Q}HFgd5Rg1gzj%aP4qC759wK@;jUC|5d?`ZImW z(~cBMIC(41&Hsw|EKn~;Cu*cnKWXRr35oPt9EEl%Kpx8Zs1G}h15r9=*q?%}6d)<q z$q%K33*RDJ-g&>=esYzZwU*4$PQv(^iR+OCfuZl3u2=z0382#5rIRvwc~XwtZLtBI zKbG#JC6>Y`nrr~TQgcSeb0}n54)+lWj?a3|lfv;t01(?tL4pJ*m@^1Qq%TlW#|AzQ zf6b(%#7r$n`xZxA9YA+g3ZbS?`(y3c7yfcYnDHL~jKfh98O~P5bWt1Tq&dg}j)n#a z&<Cg-HQnymeepgbQSd6wY7OdHhFnF0X8|-<#J+Sd-Ci$*ceAi6%;m-_lu-kcv`hCM zNo5Zww|4~f<7t`bQy<=9_un-YW#B65eKxvC!3;-5or2F!OSL+gC<Me;`jJyO>T4YM zs+4Z06mrybkKRJdqR2CEKFrjDa9iq(?jIhUGefDSUXvusXkEinUt7b~%t6%cJ|IZ+ zOQCl_)ByeGIrwbFt^ynSxIDH;(k75^fQoT=1u>s|Fat4nS4&N*X3+}%VUo6mr~M1i zJB86cLjsXFiX=GA_kgrhJY8&G`p2$2WCJ#d2%3Uk84(T0Ut(xl4*)nNb4x*8ZldGm zM4Cd&d{byY0IFy6AUeayb-aGtJ1_6eS{+?RV-4g3QQA^RV22G6qAVgthUd3fuTt0- zY#{yT`7|)(1&o$gF>@LZ3E3$N(vYP4Mq64-H--aO8dPU((0+G}Yk#Xc*J^j`He(Ey zO|XNu3JEm8QG@~r)cK-xm;Z4Q_F4>i8UM~p63hUucwqcxCdpFis+`{dX@Fd)rFI{3 z&5_1ks`gI+<N#UCG3U4}Wa=nn;`oHVb*?R`uKD}hOqwB1);+p^aGID?GVAy4N9u3p zD{=80Z>@M4<<|LTo1Yy!QU&T|(eBZi(B#}ir0`P1N=9xE#X&w0<J>s9<^LSOau8M} zrZ};V+B%UwosK^_Q5a=0SzYlHcso&Ue(MM_08oU&sipypnfH;h%^mmNcN#j$|A5iL zP65(C>Fh<a`yDac&<2*id)r6`tcFB)Dcu|O_rc>3@D^>10`u&k^y4qkv(N3PWOP!` z48f#Mw?+t@>v4^jqTo~<1#*TW2L}GD{$>L}w~5cnXDwTL!W_aUKEcj~MN;?UfG!a^ zii!+;?SApiAHhSAsb0Ef9C#8|9sQnn6$(jYW*i*zp#GV7fu}8m^}Ma2A3RXS+XR?Q zL_R8r>w{C7EK}fM;E`V)#{ia~)V|2({Ps2dBjk&OdD<!{MtiZH?iS0cFx}Y@?^-IP zJr3L$N4IQKA!%-7R@UbN_T&Whos_2ZV9}|Hf<LtbbI+M0w^NC*c6KjuRlcUxvGX64 zE==1>#bzjqUgik-KxKmx3s1BV2GcIp*$4qDndzDqX%Bj724EG}y>z=UZgLIDS7ihi z)LfzPlAEZlg0CaUi$p}WOd(qPA%!ku>{&vidmZAm@hm0r=RWJ!DfBt#SXP$Y*wQO^ zC|3oPGRPYET^-Vw%tj~W)yoE%g3?NY2X0Cs&~_G2VS4@wjWiv`{SF!pb!>>Kmf5)n zg=McKmD)6%IvhZ5AJ8JOOSb{A(7jcBIr-qyA{@&1V5E<BsJD{nud3mTwHMQ>7wK}U z1f@wJdq|q`-r@h^Ap5<7xMulr69-3kU1gSx>OUZ_0Q4#HcBjis@!JIQ@Q=!G+r))+ z7);f3!pgp>Q^x=(rhU*OzKuM^J*wLy51Vy`ctI+RKtUMxi#`hh&cK>X;Q5HB(M+Lx zJqZb&yK|&&J#HuyX*TWR&a;K5J3R#xLF8vX3DW6zJz~5%@|j~I$_RMca^k_{l+5OS z0#%0w=j)mwvB9=2@%|^0e`~(#6N%gafGb;a(B;S7T9FBSRe8$zRz0*FDDt}u`I{t- z)w<j97t>}r=c;MR{9P)8Q}BDQJKHX%rEie}1|cn$xXq1uGJWclre0d{9#NmhX1$@r zn8gu4GnQG?lTw-jC>Ix$l(n~X6#!vT^dG@dkDgL}#nDy$N4qQ4z~p_Wc~x}G&x8Hf z*fCDB(PyHG{=uf7>f10^Juj-&|3bMfS4J)&$Lg<S=)purwBr_`M|Uqv&ZOj%_*cq% zUtjS)h_xoC2>`GnNg6tk-%3BfaHN|F0KJQQ@EfbJbiofBcBd~xey(dFG|{NTX+G#N z@_v6_T*Z?42h0x#*gI11Q2R<MT5z&8QB%}>JQ|cCVX@BXaH_+{_%hu#eX9~oK^u_K zph!2-OH&4*ooS+eS4#crv?FbWSvqp_&Ii|{8@m1(;QQ0yM^~jN{G7x4AAJ5k{Vlgk zVVTU18x2&xin}ifcyM+=U1wAl#8v^MYC96MXb{UkYeE8n_Dq#hjW$tRG*Z_#ZKWB0 ziN9o`*XT~W%QP~atbqhh!TNlAC<<rje7M{yC4BX6z^yX`iaA<<+zaY3BV>+H-Dm-| zJ-+dDT(DXg5<(i3@Pb%nW#wFypHn9pS_UvXf|~GDUmfW%rPTZCU>{n#AF!csZXf)( zt%09Bj!NRDPssqVV|7PRADk|yiK2lD67uec*EVx!@x*kLPZbm037)oIa+MOfk%wz} zZv(EF*-1h!oXWh)-A1zuP4p5k%}(h|SOX|#NI2uDhnuLZRQLV`9Nk`Gkx=ce`ZC%N zr&5C_0q}bU04l4$Dnj)GtkFK{C2_wUfaWzPYP}~GPukUBr(q5Wud5~)&YQIxPrrn2 z`nrk$X8@1!p!qn6tr4x*#7EO1dEBJ8Y?<H5DFKXw9#g^qn^QF90B|o9JcXl~!h;8! zAnqTxWJoTn-hMoT?h{S)RwQsPhC~BL;i%p@ckt0#__l}EpvE0`$H56*5)n>m+K?uy z5FD^{hI+quw3hVuq@j!|-_J@R<~2{tty6Fk4qyqRAq}9)IwdPtBhOLpw4R}GoT2c7 zQ?0hQz0R=2y=pmyLr!2|u2XW1I&h_76v;~$o$Kz(ck`6)DxM&a_=EQP^!gW$!WUi> z1E=ac?O^b1G$eh{yjzzn#Qc&=bFGQrY6kENN&7W`HWLQkxdU#6)0Fo9%Yjqj;559= zAp>82(JLrFD<ye|rz)OtZUI2Aya{DbzBH_Sj5u5VSuB6241gv5PpX7<c3nG-UCw`V zadtx&$E%$oU_G~~pDSX~=(;rLHk{0OXSf7J=b-46&-b}JTy(WwKeQJdALKE2C*U9c z?;p#?l6QgUn{qMMpZ6{5t>vdUzBby6=uohfm_0OBmwVEEBhtQi`4T~LPA<D(^Yz%i zo0rgI```341~?5%jgo8T_cfnMoY$ZB23vXb@k*gg{?~K2$wK0|bcMZg5?kukfARYc zBhKNvXsqkD-|KhQrD#nNrLiw>+o3;t7%h#Y&8GVjH;#TkmRt=xSqVtiOXrboZ8@j- z^YxCMLd51|;(fNvJuUpeQ07N!!pf>b)x<t{5BFL<PO)T0aAWE4yK2l;Hm$NHxaA~l zJxjMGoZL}V<($DhK!cJa1j#=Jiq?G{c5cPb6`HFko*UX>P4gnMo8FxP(NcN@(esUT zZ%8WPtM0{CL<Q)a^QGZhRzH;K#F4@hMtVapJ9Pk2s!O^>?}+lLK0d7cZ0vUBa(YQ; zZ#+5Zu6rPVGJq7C_$=&8Uv<%d-P&!gkV_{a_83!>o#r4;Z(Y7LSM<4&%EdykF-JI= z2e(sPhwJmOh0f|*)@>ry9B+JW>PiC9B$Zmrb9#Y8bK6Uw^aY=bV&?B5V#ah{4;PMz z*~9m;7;O0Vlej`od9%3*##51oErIJ^p7O5+7=Kz$2nT!17pq^Brs#KwQ~{b<Mibc{ ze;>o$_Nk}RejfBiQTKtn^O{HDV{QcYJ-Px-Zxu3c5x$!DL2RnT|9hb;?ZX$>I&r}d z*F>1ZN{Xs^NUr!k@f-`tRiwgNnsS*83D&h-#xXA8&Y8V+jS3`&52on0g-er)RvGr) zOG2;cOSyga;{~6O;FGI6$kJspoQw2RmY&BAodJ=`N$^c}5(TP?2@ZdlyKc}wr`s=m zz&_hW=7vW)Tp?|JJIpSxoUYaKDK?q<iUwGo_@4O+gsO*YCRG>v@magvdTcYCRQ+Iz zzMA88fWU3eK+e_cmjn-?BTXvdIk;;s^M==bPU4StUv!lBop4YKhwQiKqawwgoc`*i zFe>?9LDWIm360w?cMsR(U-*akdGd7%w~h{vf2|a29Ie|B8`MtP)nxl{)AtGspoXEq z{xyXcQlUwmz?TCRw(i`4ONt&Zqq7y=id+`y!%JpvrIeg+c*_%_FRi;ute$r9x~1zi zoqZ^NyuDP--c}+~Ex$-HW5=DSuw@d*$hkHL2Mxw=NZjWgNhQ6j*f}ViuxC57RU&=c z8B5BSE=-}gER|8C=f;f-qE>69zZXqjuCNXVE=M!-Qm6RwMLVU4#1jAFMWAFCMk!j= z1IW}m;)6*Jk_ZZ;%^A^n1jkpr{_QFHj3D%Z)PWxGmz@*%QH2YKp@^>LcJ90JL1dbX zfQ!zQ4lKNWiwA|(5}2F);14S0IOw1-Rw>KqXh%wKdyal|U1xfnix4rSD&gG+B=WYA z#P?f`t2|@KWR3SoU~M*IN4fBuQT1|R;lx?8M%pTJ*m4_cEx#Q<=+5cRtQ(Y~@GoAG zbsg;S>?W^M{W8;WffuC4pKhrTkNHj9^^a8_R2wE~dd(()7*`l6*e#Rx4c$=6B!MYi zWo14o>1X|DHKI|(0ErxhgtrNJD0+o;j#5Fnr>{sQ1Ii#z$r((~97hUV<LO3_RhCV5 zKm5lDXMB~pF3(#PtXPsx6SYO5ybvl3pr)cYxbQ-{?SjW`lAbYe1wami4LDpTzg_Lt zmd=dNyXS5p<{#2*SI&VGx+8x-IiouJ`TCUFTPF}~!HFe9_Ose#JOxw*K<=+j&LeE{ zJX2MO^8lWtI+v9mwSbcAhL5NbL-S$ci52@DLNWy;G`_IcBE(*~$}QHu!YSD*AGd=5 z2PO94I1rO<Z{pqMzKp<JglM24Ml6Cf_1XgSigW3unceoN$0R9({cgVo(1}V%x{?<c zJ%ad_!fu#g3>fsJ&;s>Q)h9IZez>*czg%YMr(SXECrDeVNIIi-IJ+(1ZKmq`+9;t@ zlY|L)JuLO7&zgb>K%;+3CP;3QvKrSENPxR3rS+8s3n23TQ=e1#Kms4y3pLqO0Nyp0 z0y~7{q|%l7MSl9mKBKNBB)g}psX9b?&lANH?&ihxH=gzhEQM#S_uCM7(BYR2asTJ} z1nEm&u--x$jhecrVAxuEfgFxAyU<|LnKFy!WxhaZr=zkkFGg}Nfz2V(-jIA!I~<J? znZ0KyWBv}ZJx=CMz}+X_n|7ql_i$(NPf^%DqjPHO^N2TJQT``&+h{c2Iu=HD8`=l5 zIjrK9dXlE_B_8Z1ZXu_lNTIa;3rE^BQ135d9ednI?VzxsE*UhEX*{{XIYO|W66%zi z^yLFM`I0bAD(LQcio1jdAOJTwZJGVP)cL3!p<Bs?A8Wm5H#@ML|4%HvgM)ymfl<SF zS27Rf9oph61=-^f<?N<e0j)qjL5H@)+bwF9d;EEq9k=0=q7e1p16-k$Kix#%=XwY@ zgF>N61O5!vDT5meuwGI=kV%TBqb93Enc-xJ8!iOK&vfVsj6H~dW)spH8W<_K4O_~6 zT2IFDU&n}8ZWgs%@a#NXZe}tn=5h3UCcejcP_KWy$$FEd%zIYmiRp-*$5-VUm%Hfv z_hq`VMGyD^WCc-or0Lk-A+$7_FS$emiwolKWb-o42wXg;9~XYdMNmPHatg0ygavHP z(<kH1J<kimN;kM$Z4y;eOiHp}o>krsAM-cp$qlk1rM3qoHh(&UK%){{?fJZ6!X(d3 z)2>iO_r#_?$Ae>hrHG5~PH>$o+VB_*Cjede^H+T46SVWKzSC{1Pg3>aHF>*FzMk5K zw?6Za)?nCE7*gUUyT#tO;c_i}dGFa-raJY*_1jV--)m&^!hP-f)D{y){CFQqCd{-% z%k$fPTZ5E^iX5yj{x^AlS}c;yl?!<fJTRSQI;ODI@TW?C??DTz<$rF%IT1+%uv<T4 zqpieqOUZK;`!L2rx+N@yAlH^pDWSwR+O%R?)_SF4Zch2}VGZF`?72y@3%b1a303RK z>eD5T`)DE3VhZSsH6sNb^PHef9VL~%93OgC_SBC#c;+FJYO<vc)HR8qBPugEootOZ zyrAjtMNe{XRxCi2x+C5nPnoL!CLPf9H15??b)b9Ay)Oos_wQ@$>tsxxsAcsQRulrg z;AmJ4%43%!KdU~aw=iI)h7U&8geSL$OL_w;qXs}#r%LWKK>t(9FeDM>tYzxvAc<@( zT;icG0{SGpHycg*c3MSM(qz4Vk4*(}xh8M*3LI1bL;z5sj)`6cFO@o#Bk<x+tkRpr zh+L|Co*rm1x$Z**H9dU^PaNr8BzjtmwyLI{^8DTs!Mf89pCzSEUSKB4wv3%Pd%1E! z8O4x2P?O{XdRGOImCF^By~Osw(upTKxTjKl0>)H~Infh16_rWM&Z<JCG}Ot7-<f>_ zYf4i=<hFW?_+sH;lTFszUM}UrGLdAJ$~95nexMbAa>S7u@QUFZX`cDbaFL>RIFhs1 zBthQ_b6*drxK9Zk%!;^Ti(MptQIja_tZUEFmD9x79V}dIl@cD2qG{74uBT-hko3`s z`hyp5^gv$YF2<Ct2!JOi(SvMJC$}zDKhwt`G|C<!o1c;vsB(6Vk&VO^LL&+iT?)xT ztyJX$T$>1Ts2IS0Ceh)BO@&zL+{MNcu=l)7f$mLW+oBpS*cZ`OlxE2o=C+!`IBb8v zLL?G%+=Ur}C;G}le*O{8o*Yj$K{%VhOpys5y_Duwz%R`sX*i7V9EAn8_5r-mA30Db zjHBEiDUR!o>n@W-q7yhPbm}`4#qz2TfYQPV6aW$;^BTSjG?7N&O5yCO_p;+fUzB2A z6u(H$Z7`cOc&+|kskbk-DY;g<nIV-ACP2pBPiCZ`sZxrzmhDW3gBVqG%$zYX3cTOU zL@Uh41G7s5qSEN88Drrx4|nMT_b_zS{0)Xij%x-vHyG6pGXF)O+bL!)@KZ_<MtOlE zMp*XARpQgDBor|%H<<E(zzdAfOR+7IMOulY_7k)h??0PVKIj%-ip21{vaIh@LvPjN z7OOK8+Mg<580&kC@j#Rw_UQuW+2F|I-0YKpg6}ic`=bSoP1+{A3=jimLtzT;b+Q?6 z%pOf&EV4G_YOD$-l3s!N?40Nsg=NVGK1RcW*?@tCz}m4)*HMf)jxtbDy4BPOHpCbx zTOUeFYKjHAEn*JYczYPDH_H+c3SeVBjEZP`_~N}f9Cf!$eE>3rM+`G4T2t9d5!jo- zCUIw657N{-V|tqMcTy|+G|#G*8>s^J(ZFaI=AfD+ZlUhSJW+EV%ZPP+JsRIIxLL8z zOX&~2ML$nrLckMGY`mF^lm6HT0TEy`Q{Y%hZ3R8h6MZiY)@jODS=q(iaq-L^4!UKA zU0rw&i?Nu7OVO)9e-@JqcGOwofpzDgMm&v8FZzkFY_xi|w=xbek#dSHT<yppA>~Zq zqi~sTYEy2B4Io>$29N;QQ%)zQamgnE!0b6<cE{`qNS;XW9v4Wn(TcDd4(Xujn*u=+ zTS*+HaeM(}Z5L!JS4odc6LoNR8S1c^R{ebYbun@IPwk|3%MAC6#GBSYU2G#Qt|_7F zn0FJiHW7>#dC;#Yi_CT~tLvSysKTd?WQbGBP&S2IL+~f}`!{-PjZG;cT_wUgSoNu` zxd<*xr=UW~pO~NT8+d${+DX$-B7kmtSx>ltQZizMY&E5eFKUcL&K47ct=;VeIv|@L z&*Yirrltn6mTbLuU2QI0$_oovkQ70i;*<Oe$h0Dqj2zMR7o{SMHW`4g3?Yd&r`)lL z4KOKLn`UO6r8dkKwmTIVh<g<j$9x!1=`xz+2+BtZvr@Ny%j~ghfa<<(qJo(vtoA3F z%@Czk(C;D)W)fk&h!JGxnG|Tq5H#+L0FJ}%(E4C&f`K-UXi0i<qk#E9ym4-TAxB^; zAg^&bha#pFQfJd12~|={>?@4YmxQKfj=|`DQXBN5cF9aO4?&|&js5^2is060Dk_rO zOhjGfPe3L(9QB*HoRGR#hfb7_)PdetnP@BJ$<;^i<9I(3PkA`>9V>b(Y~pp`=Txjx z1Q7@BNGyCn5rMZ%V;q@;EBVXa;n1HCYx?pVDz!&5_Ej!fHEY^Gt_h~dTPHE&hZGsx zE#GF=Rj5=P?v__($M|)`13~@#9GY-?fL1RmlZx%vU(jn1P;%khyf@dEYfSS-vdy37 z$9jhKV5;f@tZ4$1&p6PXSS7~`1xA{XZ$FZfq+)wf*?yWNfkP{%Bzoaq!81T6QM%qR z@IXzmwg_w6((Qj>r}~JE_PLVqnJl2Np?H8uGR61YQT)4(8hSzu^K*U%@4Xh=*NUU@ zYigk%(b%rmo*95T`mP^_=br%C8JXG@C7t=?@pE%_vPV{d6rU~D(QwFd`K0gSs|lKF zR=-Ct8J-1#fTt_9jm}AH0$<FzU0nPp4WsK~S|pwZV62g(PP>$Zfh2)n8>ya{r@|B( zjw*i?C`WA>s+qnot#8yi+Ap`ze`}aoIm-TgxjLlfN`IH*TQ+7s2qRRb>7)K5v~(5_ z_+46ZfW6TkgT>T5A=>g}`<0aTg=A`Rm`4>!#abXZU-GDaQSi*S@Q5_i1YqbWCa@BN z>^0Nr+sbU&&MaDuz-Nrqh#ot?6Orh+R&g(sy!Yvo%Nv3mS~l*1ITF*-=8m0lC8ECl zIMejMtzXjD3MKOzuYehQ*;D7GnS363o~sqtz*t90(F(cxqx>({mW00^ufM=gTb-a* zfSE!)=h4K^u06&!pL$OB(ig?NG=Y{vKaL|b{iM>OjVRcBxT;;LOuO!S)mqK=;0sj` zmq<JV1z5<ID1%+8V<RXc;`n-`ebaZD6^npcAT;sq9lgkhotSjlHs-Phlo^m7WJ|4b zjG08f-baB2oL`OQX4rdT5B`(+Uhc@Qst8?9H+M2K?<0p~cRj?DZBpZSw5i79no=7R zTe=M+uP7tcfwX1q(K9?2-`qNWVGpj{y0bV336PVOq_t6}m$6sl9#$#7$lN&+7u?LI zsXE&BN-eK*;T^hiwq<i7)Ufnn9-u~R1I=_#Xa5;=$N1B(q7vqLD~9PiM#3h$wS|$@ zA6xU!WBFBpo)0iX-}905v6m0#ksmo+<M?O_dtP}E<0zRLL0$R!)4(n{*-;X!)XuXA zYyr#30ObKG$phsMRJ;^r>{Yc0B^9lzrltb=N$Hj#J+x{2$D|Fm>KB9k)!q-cqk8BL zL#wJ^4UqEPvLxB`;ASp3b~b!?r0MQ$^)K{LWZX>&W7Re)^NjlGUxpukR5dg+7TBbY z>*I7I;I4k5PxAr84(QfMAR_<c&sv!#!V$1?RL0a3NPNOss$;@B^0C4z$u3yqWS~|6 zD#nVU4WGy;C|7W;P6{?P17^g|(33;}C_3T?WW^pn(WtkQy$)uzLSc5AFp`fXta_hG zN-I2h&z5Q(!Wq1L?v2GCXVd;n$qcj|(uWv9(GS_AN-d~Fiw{V*?u-{;#sOag@wGKA znf2-ZL9HtY<KNY^)<yW{$^x{6Fem~#@k$k%jr`TRMc$9CO%hYk^7uXbVCr;{voZ$r z0|MBFPj$8bj0>ll1+ZD#hW^;yt=bFvf@c-9{zyWeo(PPvc_hZI(z7KD7%=Cy^`%$< zV@R)o_BR!zom{?;2iqrD?-5wl3k*Oc&l^WLoI_6{r6~{E=m7~YKsjz)5!fU%1^n~w z!1P}F@~tFTw%i|e29|74Aj?=B<w%U^uJ8!@VHt9AFm*yPz&__*tX053lmFIG`?GUn z=+tEWo!jb0+|+O%wNj5a0Gc<yQ(j-KZFcrL>rnM2<&l2c70dmotuJrg%5O^*_VVe? z%ddg)B+@V_<zqZ$m?Om_1;?rr5beLpV5}+bu1c7!>tBfJ$bx`eH6UB<7H{kynK#sO z;`aO7p$?XUKs8Y3>4dS^#(7t1`03Z*i+?s9BUMiEVfduSr(_y4s@o0J<9JAsJXWFh zT@oB*r62U@#3vOWIZ7bJ{ydKWT*&L|p(b{cLWw(lRve@1;ke%4r4aI|D!G`^h%-V& z{L@r3MOy+TSKRLJW1haJe<9TB!j8NHNe~{*G~qLtcFNgy`k!B!tE!&ARF}(jr{_EU z3G40ri;vgF(NtpnXpumnPepehuTP3(Id%pek$0?_;wk0)kG}_^c1Gyr%TH=d22i^% z<03CY)&>4go(8|X$~)LLQtx|uJQ^yKZ)DpO)pAV2zx#mOy4LDs{Zn1|ogW`!38WD5 zh*QJxBnmd8`iSPW@ROUqZ*R33Oe6M;Dp5NP#hTssxbn@Ec2;WNzFv$J)6JK1>2G{A zFy*DdJsul7NlpOG)GSN~ZdhfeOVD>H2DiQYa6kW~sOQPAed{{l{pWE(G+Sdd$IuSv zweL=>YNHK{38Z#6pnw~5R&Im6AMN~AsdUwWCn+C~^`E`0^K_c%nP&*wN<%=^W)=|B zqJMnNAbyK6tYv6MQ>(H>)-Qw4laeLKr`1{kXJEyZn_!6OL2s*tTF91#o$*nd88u(6 z?A#Y2$IyZGqz0$Ojl`tHuha4iE2ruJ8Yp5?qwVa9->1!9)>vgVw{=Q(YBkt6;nQO9 zvf8>hng^lGy<J{N?__DGd@|Fo=U+0@vaL+In?S|iJ*ICc7LDKg=CkPc`Sa}^Y|e(- z!+VRFDF=j2mvp`AQiPzN^9$?OmHEy^dyia$-XRqUyM4oIC+G`0wed7EW8>|nn*0J} z=NeG$la<S~)J3$}lv9a!_3Jm$?AsjCp)62!daE0L<CceVUQUH6POJ?oTi6_NrP1iz zO1&05qoE1`J--yz7y8?$a--lPheKOMeL?=>YJu){LfflU7oWKVDxtu)8`VB!N}jc1 zixD|R_ID(5zbNgX2i+tN(RtjJ+opESL#zYCVwmJUGrWvJoTi`hnQ+c0{r`UExp!^B zq=9#9v77ozPEPVH)odGvW=$LQ$sm7{8DRP2UW;1Z(jOfIS-RG$)p*spv}Fid(IbT` zdVzqm>}89+oHq(2YX>tcp7xkg^Ox-MT`Dw_jOSVIpew(Z+);FAP#X6wHily|5FDSM zl5s11z9qBGrh>mgjI&HflNl=?b_W@$ts5TYKZeis>%($4H&|4^-MARFES-s74JExk zT*S#EaU2qZmv<qpsmu?KbIgMBAgZ6%HtZ$^Ls6!6Rc69R@;`b#e-(SZ3x=8p!?Nl9 zK287WTJ|*-n=-y}y7=Ti7JKjaZ-dm!&kubb8g>77&`Pj3JQ?`G;Cj?n22@$OLQJ{s z-nh*5#aO%X{$Rs!Y~wO4vE(cVi`33ghL6A7jm?0~)M;2|02DT%`WH#1Z8gVW*h6>& zJJ(B9syd^OzRcjBr5c({V5Mu(I#nj8XF;Zv#&JXs2-8GjUM!Q9Pv4*zqG6PBqq7+R zYF#nAwUN^Q<TFv78$2%=dapxtGrec{nfBqjr@22rvL#5RIhTx)O<>_9y~HEjBB{u~ zS*BpE4JMjP9*s-WkuJMN;%yC-u+|x;wJXY<Am#!b!Iq(z(CR7&nCT#XpaI*gyj!w< zrRW?K!k}fn5VfxOESQezZvFj(-5<sk<}8TgN^z2C11Zu{IjtI6Rlnu0bQ4Y)kuXxa zmD1r799yxgNu4?HzeJ`zt7oncyf`0v-<N6ZOAXLEEC|;Ul&iaz@1KQ85srm3bcC8I z9t)>%tesMbEjBYhq|$kCHk-%^4TN}_mveW+FbW}V%IVf-nxe|1@^1slpqn~OlNS#@ zwd{%E9d!*xtud;lS(VXv7uzeqFk??(*5wxCok;OSSddvt{JA(bVus?d=xb)x6$$-_ z%;?}h^z(nAE*$gf6f1Mm5`Z3rjlJ0yMI3Lo#jXpx>CM8awD&?eH&b!4lpS$`N~w1x zfNU<%QJAt`=pCJ+b3p>{Xthv<n1{;!UV)nSw6;<^zp`TL<&|Gv%SgC;U^?Bk8rYEl zi3R~~U5$?1i>;-tY1o9ZNgNo?$!0QVm4SThz3#Wv-uE^q7tQP@7$j0w^u!+Wvwtig zc8^4GolcmS6wVmc#<TaIuF{)o?fnv&H1!H$=R95|Ba(42a8N}J$Nnk#-S5qLUjGtd zOuj$~VS13!VL7`UgLnJNna$#htoA3bN4MCnTcu#6f)~)|8sZ|7kNV!gTnkNA7P4q} z;QTz#??XkeGz3L{8gxOe1?7U8;{fW$0Ns+2&seFYTDwHd#p~%<u?nrQ$+jvNMYqs; z8O_H{WLz=n)uaRct9Qob2W|}~n=1e0etK2Tlc|T2$FI@7@6qI1Tby+K>&!gTJ5GDR zrjyXt!F(ke${V~I;H2-7_rlSG^B=h<z;o%%hoN#iH|ei-1lswWr96Jlb1YB|cZT#^ zDZeFVsM}cadA)^CDzoT9Sc*8PR@v8NN)S$@&jj)~V_!idG?&l`lQNO6zt}dAvoVvi z&=G-p;%;cFEuQoZ=UBPI+`1GoafO4(P&(owhgo4x&YueQnKM(_d?j@u2BT#TR{{4` zSu{BkbN$CMs`NExOTGYBa9AHx*}ZX#W}!PmZ7I@Jh?6qQm|cE>&mELf2O^nt-VrZP zdJ~*;;Jv8PjHm=?%`zO5taCc?sA07|4;fEHCH9oWv!5v%xQUW0HfZcd%~)6-`Cn@m zAx`2)RMeY0%==K{OEbe`=JUrNH?vqOBV3iTvk0XaDP-|t^t%V{GMU?Q(g6KaR7}#g zQwck*vf24?|1oder8hqhpNTHv=98yWd-;c<1c$Ga@sh!Dv~*gA(_7=iAa9;d-Fs9( zm2<lw`&8Q%+bm#t(OHciMdq5pBfoBT7iKToO~@<Jk+bzah)bLxcbia}MM5r9Ljpe+ zZznzTbJa}9fx?Gdl4f5&^%+0?UTXE;gu~97Orcm}dvE({!KP&p9OLQ2b9?DHKRrcD zc>v289l)i>HP5uWbqafw!^)!<br0O`$F+1yt|ZRc0KaDMr8*ey*R)Rc6HdAN!A|L* zZs~G}ZOR2!KK^jM8S*$2zKhCY=~~vvh$J`_^L(vgmNH|63FbHc1n9I1Q{$rrn9n9Z z296xA8%WuSQ5q0qt$Br6mB@k|8G_K^Jmb-?Soj|j{VPmN1zkC}sU~cwd7M&&_hR>5 zt|ri$**#}1EvRC60aSWDOZj7s_Flk*v>sKi@FTKY48HeRHCO003KrE|``0T>j+_QW ze6ys6hEs=tQj_sK5d*RUdbb0t<;h18T8<$-w%Q$>gMSU_JNguaCm2In$zxfE&B=j7 zT1T%@swD{b-9<_#HYY09r<HbM^_+sBbPE;EKzojlE2agLC>{{0x%l9|J(j_XduKLn z_w$fu?vO&RfpW+ovlE%2q9aF&34z?yl#YcQJ39@VB*Xe?D-xl}NqW?fj-oH?M4E<V z97@#+A+tiZ5N+Ta3FVZw)1G;WLn0Ukxn=@Lqf75YRH1l1M_;ZS6+L|gb>2S@@bugk z*4<d;!>of|NSp}{0HW7VPZyw4H#;Ta3jtdMlqCYp6mevVuFqte9>rrV?W3KU*HCzi z38_venIg#1VDaZ}GL=CT9MC6zL*`0OEq0}O6}fbEG<0ZaoaUGS3+Pu8M%c#vc<g1i zylSZ2SmeA(U&5>&DIT}QwWJJz_)HoFqDQQ8sFqU5UOh|awaZsW5|ATKLNTczI)z8& zA)<f942pPi`t`=-3n38%GmLSf@#A%S@Zj1Bty4ch??qfqcp+0Okkj*GIT9=X8YbsI zq*S6Qi#IZ;Vw|kxlw-ol*B~B^CET^b)ZV*gE%IFD94z@448oD9L?hyuMl$N@G{;ab zY?Oj$i<>40v5q-Tg|*m3Iyv)A^T`KSqre!)^<}H^f01O0Xq2h|iuBgEj}Ou(xTqCD z0HelDhXhtmO&nqn5g##NcFkvv)K@A^P-;W;KLBaeQ`IDsN|lnyDj10BEiole1mAl_ z{|luIrV_l%o2EB=-_eaN6nWEO3+^JT>CE2hbY`k5Ea}txW`Pqvq%;`Kcr#gXcNF|7 z&RNF*?Qp(D2=E>s-eg0tWndPb!3W6{IMMng17f)XE(V|?T28(QG9`ggp@rOWEp!rm z#kw6)B+?s0(W~2#Jfu;+{9wz<3s@?53(cveED*2BH{tQOz<6-9Eq);tYRNy7eR*wQ zH8@}^jUwF^3KaGHvyx_VJmYeOPy}n<Y9qrQt*9NMq~q>~f;=1}?B%ceIGF|%1S}hF z9yPKJB6eM(6P)#~4V&ZQTJLS8Xwl5FF=Y1ME-w_cqy%sWXew}8<G8-4Z8Fd&B3{1E zSt_mmigu{-oiT(UoNX3WLUt2uyaF|Cmj5of^paJ&X)4Dd&`NsBU=+Tc?D<~Kwcrcb zAtgcC6_F5;pyW%LS6hR+dka_c2omoOaAb|HPf?7kX3Lvc*c3*Xzvk7pRc>-8!SgpH z1Lf233IPbsE0->$L-}11&`+{>G?~}+k9@0<ycE&l_KIgy-_+s~7*r6-uBE7Y#AbAI z0cWklf?F3F4~jx4<56+}sq!~uikIV!<f111-|jAX7u^G>GXqNOUO1V*?3NM^XEHC_ z=f1Y5P`pGa+%TGDQ18BGl-ksM0wRAep=AIg<-yYC#8wnmWVWb#$!>muWbAj_7~I$N zaWJwr`#Zq3qVaVQ;ZFr{emnEZWb~#m5dhPyF+nN85X2(HmDA$T*`j)sLHCs*A+n9e zT+d-wU$Cc$#_t??K@q1|n{GkA!laXZ$oWu>3B+<dH(WFkms@~Q&yk2PA6c*eNAc`Y z6l+T;76U>+;}U$+Unmcn@Dw?t9ktGp35rpu#m*tw4pf<}*8ON)w>z6aWBm&ujph>I z^k@dzU$-gKw1CP9Wr4%2T~fI;3WlCn&{@spZj{AJmINQE4$f)LCgtG`h9~>zhd;-3 z|Fqz9^oVP}3@Fa#1)Vq;VG%mO_;WP%9)%o{V8&5+&7f3hnKz@L2PXLpRZBKo!z)~c zLa&7I4%DdliML&SX57>}Nn>j20_K+tOngaJZ-H?$4c{M*bFIQ4ulxz82G|}|bo4S_ z*$!<#xoMtA@v3latCx>wFG0Qpu^mRLl)GxXdiY#OC-fQ&5|1N|1JG*-mM*_O{RQfc zeh`h-^vC&5QK?&*B9z&+8m6eEW;AD*tfoL;e!V&&_#4d6lHZH}0-`FKMDu(x!iK(O zOxr~Tt)fT`*qf88o5O^@erKiqN0y^nmrmN0$)w9I$8edRUI2fo*pH#Qn2bp2e{T1E zD0%}p(d2_|fI$2QC@>Ev$&^a4iVw017bN6nNF~Gv(~{BYg=oV0;_#Pk8|H~WEF%JA zXqu@27w&PIEDD7t2(9W?b&V-g5$*D%klSlU2|&%tu`_dBAVH_$w(8p8g89VjCd4NP zgTO(Q%FT>CdO!(}kQ+@<jX(ibq$rGioz+MA1nV`w@arokMZGw=^#n6^ZaBJ~R8m=A zP(zh9u8}?ST*a5E2X6dN<6M}=ySvZD=u%7NasYn%tuV=(>wSrhkff3TN^gPGMn#gv zvdK9>0tBXD=VW;iCN6R(plfu%k8^BtYr$fbK@h2F#%WuyS{UdgDrFli^3lNvkoMVW z^^GZ58xB=U<I2E^{f2D*SH%umQICwMTn4+AI<y9$N0f6>YWLzO`Ms(rlhqZrxSohj z(u;JNq6UcyFGmO-_Q*%zQ6@=BXbtL}{%rGK>XzgIg32WI+0O|vR%w^Z2h*c{w1f5} zgA!?4f*9gUh$qBR@4Uzgy64S7<36}gk*otEH48wArUn@tT<(FIjM~xxzNJdw)g3Qy z+~lS#7JWy&>SDN@;w6*30EwWG4}*f>)8t}V8^Q0*J4UuseAgtboK)tMHW~;m!tuP> zeTqNv+?K6B<wtm@_qD7`j3vNibEIDj$uYaK=+7j@pH0T>CoDxEmP)rZB5@?*dH&&o zWlXlFw$*b7)KIy&xc@pyEK0q!^ya%v1$dDCH7lmKl*2rKWAQH<NoCM>!P?@&q1+j~ zRRDX3{xJV_n4<@q=zrwPu^|i{+3M`{v20}oS^Z{DwYwBOi07M>LU=0Aore7n$HiNB zZl_84(fkgv)VsSu&hR-;sf6?{{=Cb^&`~5%LucY}6WaROV^~RB|GiY`SG2~L70a*u zN7TC<t)Poe_)SZAY%$f^%s%KZnX{<7$5~^552ryBoHG6-vSKUhAlwLz0f4C}#Cr#? z2fwUp_dY+Pk-tjP)tipGV%iu2=Z%UrA(R(#LTKKR(dJJ(lCW%23ZC9KP7^|?<Gg~e z5aJSnQku<&sq`Z69)MYO+er^6B?7)*Wzk^Fzl%MrkbdEXXmofRyCI?$L&hSYq4}2P zdM?;_k<ox(@c|aj&IAB4X<v64bWNfNP{Cxa*vMkK$KlWx6vv2~@PO>DW$w=JMlHdt z^*&l*fNHDlYGhOK{XrFkwgLO#%XRIqCKN9x!i^ZCDt0I`2Nh#Z9-VgYE9%h~KfXG= zq6*CG-_;CP?W!I$Q2H=;HM)t6DxIt!e!Lqvpm3$ZTOalE`F{;36u*`r4tg|XRK8Zi z=sKPdjn%;T4h;s!+P3=L*9T1LUl_)3BDC}*%`4=LsFWLB{)GF>J#3>@<dg{Q>MX*c zth(4+XoKG>lSltY)9&y)?16yXq^`#|rLK8p=m3*)Z^9ke(d(Uv?++z-KmP%Wmc8hH z+y=bq`<TS~Wz)3$D$9(gi%rq%h2%zmFqf~9lZ2egkk8E{*|xCo??|7U&c`af4NdH+ zns3L>N9(#BRXo%RMnj4?hf;6GPZA5x`fxe2*7G-0I~4H36saq88eK%i`!9><-CRA# z#x;sk3&*p{f9-uQ)N)^=@R2=Ym-83e*U3|d=X2dIf4_dy5=BfYUVWe9U|K}{ZEikP z$<-9$%+xB6S<xK~rp#38CMCdsj(#gzss0;nKwEnegMWfN8p=WjQ>IhLuHPruNPM^c zCi)v1p%lVDsvNsz`(dk`&v-Y~=TYp=lYd{o&RXFR=a9cU#sBs!&C~$^-fMCSR{$wM zoSgX4L^ehO01*HbAWpre(moW3QPgg<scZlP<u@qNYkoD9$|mD57>_6)$%G+NIQ3g9 z#&U$sYVF2aDkt*cF5@NoGF1>Rx#0bkvDWJ8m+B~LE`zq3*>b%cQTy?>*YnlLa)ajv z?X{oltXjQS$J^_^zHuB#;ky5}eyP=Seta?u(eUkEz{dFV`|lc8-$z{RuTH#s^W$S2 z84b5#N7EYdbR*_4+0nc)g5$sc!mzVtYob8L=lf)5>&|p3B9;3=SKHovjai+;r>^#c zuT3r!FCM&qd-Sa%_~84e_wP=A^rC2ZjJi9{Hb!&A9!+(3UhK@2-+yV;)74M4c-!j7 zRL`I9hs!;w1fDn2{S&9Ov&!Zlard--Q>^jlzQldd_;YkYHe~eS<5L`c!R=B28H*l1 zo>B;lPoTa#ibp|oKx=4*hk9#?EbiE~q+4O5yciP5)eo$I0TT%&dj-~+QtWNbda8K; zu5+5~lxI2d8dAYVy3()FjZ9_Ay>gs7#LG2HkAcc1#qjRlW)4zE#Ep_P*=jw{iiKQ* zQaS*Zkk5y{t}Jj$5UDD3%T^RB^lXf*D)Jkq+9~m!yLNvb@%^<&QRI1Nb#W{u^=@g< zFa4V5u|<1*uhQ=B@0R0qZtdk;KlI*Hr+0;F7Vw6QdsP>w0K99;WA|UzlolCy*VeqS z@vf`uB8>0XwM}`~)prcn*41|RFZ(of{);+j{J=tUSi{){)27y`XhOG6YX0$Uoi-Bl zYy0d>Bhfw+<wf!|KS_E0*^3PC<Idfxy5p|Hw+F}XPlv@$x-Y+oy#aE9&P-`Iqm|<$ z*C|yTs-%6rPx?T&>jS#IB@a&rD8tA5)XhNfAx35o-?QOc;ge@0Tx!i{j1pMKc)+d~ z=4G!q2QZ*&OH=$}Qnp;I{}p=#j-+1hceiA9F7@f)j25fk<*XjvJ>;B`LZ8M*{9Ez% zkYzs+RIRE<!_RJRsL3$9!#ljjpzUKW_dZ6NqpUd^3zPG)WfGO2D-#sLfKJ!^hTq?} zlL&?Je53_@ak5Vj)8u|g2dBJIH}VW=(=@h)$*<<h0E53{JsRbzr9&K&03NP@s%=@a z=Z}Zj?={YRqp!ESK6oELu~qH;#sAMy$4=v)<L=+be@^P7kjZ?+B;x+b=<PSeqEpps zhc+L7!&?mtE$*M1o-n-9;Yx9mebvx~;eS_^smlq1acJXzlP`l{i8Ir>gJE;p9G7>; zS9k7k_F>+feC&5xjt4OHq5l0naXfOdn}=(vWzkneA-}!&C&b3_!09-St=_WWm1A;0 zI~;XkPzoqwQA?S597Rt5ZA^Hyf7R*;1xs`4>Ni&*xmojO%`NNJ($mC>2cQMO&QJog z0u&T`A0TF@Cu%b~I5#Na0beL%(y&l5>vi%l({jA1KsGbzXki_h_%_G`)Doj%0r3bj za)HIcyGBX(6(?VDPJa<pT)rRZ6>LXV4%9lZ-vN;-^aB@nhc%^#{qq@La_wAIYI_Hy zl6sQr2rQuuY|gXunc}_~CjBoJK<d9g_{a?clQX0!F#|_MI`WjLbl2JNr7w?6;gztA zB`gQRFSsQnM5D~5X26%qUi$J~W5ZVq*h0)=8uOUQOlC4`5GGsxOPA0D4VRvlCNEiY zOxMgNHn*wGZgTUR-V7%=$0^QolJlJAOeZ?msm^wulZKLtr#$CbyndnVU!jbqJ~4y; zfqwe)p8yT0KnF_Df*SOo2u-L$7s}9vI`p9sjc7jwU{H$wbDtRf%*!5hpbuH7qaKnF zNIkltk%n|aCMBtZQhHJYu@pg|>?na^S|ys!^ro1C04R4F0iN>oK!nVwP$3hZq6);Q z_=^ZqmwHr*Fg2-2eNR)NI#o74^{NlSDpix3o~nA4t10`cQB~Gdm4WB1*Bh!@L-R6R zYNV}pdux^4ni06>(;^|dD@E+;5xy>jt`3=8UI&}kDy{Xfh(!!x7pvFAI`*;OK`UAz zOWDfm#jb$0tY$Ymmk(IL0%sJ!89|H0(VDijs3omxPrKUGvi7yEjcsdZ3tQU%%C@$+ zy=`e%2uRNQ_P2BC#Wu<T+~OK{EaVUXagWQ~<~sMe(2cHir%T=HTKBrx&8~L0%iZpJ z_q*T?uXx8x-twCFyy#7@de_U|_PY1I@Qts0=S$!E+V{Tr&98p<%isR`_rCxRuz&|l z-~t=?zz9yTf)~u-20Qq{5RR~fCrsfATlm5l&aj3z%;64u_`@I$v4}@Z;u4$q#3)X& zidW2H@oYm20{BOZud>`3e+9+@@Pdu65{`cC_$#&m$B&0Bn|TnKDn1TaIcj|5CaXps z1NlHZoJ{4@03sFLa7UH592!8rgUev{%s*rt<}#c4%xF%tn%B(cHoN)%&2WyhoaapE zI@|fqc+Rt)_sr)$`}xm+4z!?KXpTV}nk(=)h?Wn{XspNs%8ib+Pu$^-M?ZQX<4}mD zAuZ`n|HL2gFfu~M?CDbHgwpc(N0JwEX;Zs8CX{})tc%i*RnPj?xX!g-zATV`m}AMh z4mM1F;f+iS``93%^gG_cX@w*g+0brDp`%T0iugm+4Jk*gtIh3(#N#33sCBo;jge=B zgWTxONIQhQ<ax|v+v$#XL*CI3V9Wd75`j0q_e~IG^IG5h7WO;HED?7HoZ96e_(BS8 zZ-D^(;J043ImQtWY!?I!(lE9Fw*7F3-#XU*Ab6q+@@)Zpxz!&3r?#<4;SB*KVj#i@ z2Rz(i>y$&g<l7L4#RbxG0g!{&4qvp*XZ`49!^0myKS(?{F7%=6n$p+CbV8Eu^jTB- z>h6HYxfe2yc`Uo*RrfU3sjiT(Up?$rU$i+2y>o(y+U#IQ`>mNQ_jE5800QAP+3S9o zqVL_eDBt*^1CNkL$NKLA5jWo*(+^&c+_+;_yh9@IV}CG29yMS5Vcgwp<F>jV|9D5s zGj9-s>)aux*L>e0{rKXxdf5^Avc?4<jD)0K^`D8mD98Set{(*P26=`+2*3uD!(-{V zcMRcKEswQ7`u4iyJd}a2kWde#_yvJ|@-?G}U6foL<uFJ8+jXgL?Gq%?oew%ef>021 z3wisV!Tvz#4o#+8MEC~Dw2ZgCeE2KI{LcnierI{-hjbO8aQ<f*<e+8P)&+t?X5u#w z{r42F$7>U~8b;S|4#9o|@ekjiTnWe-;xKIk0R{p=T;ULI{eWunpnFCU5Ak4l?yzh! z7#mQhTy`)J2AB|A5Q41%1teE-sz!QC;chTkYe-0ht#Nd`CUXKXehD#cq~?R0v33Fh z4`i2IFenfgI21DYXh{Zzt3hc72W9@STvN6XL+}Fzv24&sg_to9@vvm@KwO|85PuM3 z8y9p<hZKD{5Y&){v|)MUFbHkn5O{Zb2?&O^7J#7tK@RvQ0DT|~iS`cUU=Eh%6PvbV zlm>&oH#oUK1_F=-SReq@5DtO}8{!5JBUf?`;fmW=g9zaV-0*>&QE?_$di!^FJwa); zW)28w5Fa=WRwx_d<`3c^0BMkl4Do&;h;57@5S$<Y<M0nIC>gP~g>7eK3)mA9XAa+B zY|>B=x<CxBxOQ(C8`NhI{{RmpD0lA0iwHpmv_K4XI2yHPi4O6HB=Kl#S8J{2g3~Af z$Ttw$CyQf9b4s`nmPdcmk!Zwaei#LVo3?H5FlE7D5HWZf=2vmGXAtGEbt(aa%O-Bd z#%mc_5c5EBKKE=`*M+PB4hvZji6(~AL21SRm{DsdapN!!Om+j(NDVXR8qWp~3O5PP zkZ9uIh$69RerJmZfe4&H3<mjcD>!(Nc8#MEc>H(}-avrk;fxuDbq0Y50wIdjSP%%A z8cazLA?J|Hr*jgRl}(3}g%*wjkqZKW1!Uj{rJxHIw|4J%8!R{wGe-&n@C?Z~5Tj5K z|8Q=>$Q*uW5SB-VbE!|$_J?ku3%a0piMN8RF@=VSZ9!lN1Ob-^NO0c}dII4Gcz^|^ zSP<>NYY8Ws2_bp0VU)t41Wz~+voH`@APpZFdg~Y+u((g(U~zm&5L32x|L|_|=o*bT zngU^h1+kbBv1t;Sd1yI}iuVoSNQ{{On27`Na9W8PsL77p@n}x?SfwbH$Crkg=5EkA z8}0^yig*yj6`2O{XcXCe6SrL0DG+8!5Iq@=^B|ZoDR{Fnncil3{23kLCjdJr5EZ&s zGnjY9DI43Ca2DZigNb<G5DxK>hAk+O!NGg^DFCfEBF6`dWOkkcLwOHD3{z%o)fl0; zF=h=X5On~A0uc{jDFA~RjDM$bJ!x<0C>*xwV_QH9{~$O7@oP(#p4*WK?RcS-^L%m` z4{HaWdN_3i0iZqF8$D`lEjoY9SP-^`mIN`K0&t?tmVU$0q4f8g1>p}Zmy^^%mXJ1> z5+RW&T9wi9g#ZeJ;Ye@X@DTq02&ldBl61-t5-A7>!3~Sbh0YhL#X)JnHV%sh3B$*t z<<NCy+8yR_oD}hBl!u!#_79p09k>X5B6*Wtd445_ss+)LZr64TIvi;#5IN_L|8Z$# z<_&4k1_)S_4>6zuunj%89X>XDdpQs?)`I<3tNwuq3dapgcWJyRqrmZKz$RlkcMuW? zuFU~&;6Q(i&<6rA2$J}&0$~St&;~h(5MZzcX~3HTac;kg92MCRNlK&zfv(5FWL=;T z-tc(ONe+%kmefJ12w||x0jao25C$+187mMQ%dv?_5CG7zAA7CI@r~lzo1-QW8mFVx zL7NG|hP){WwqUOD;IIb&`W(d&n+w5o*y<brR|;HE5f{J^tf(9;NP{Oz5Y|8s2C)bR zI)VWCs@!o40Z;$}0Rj(z5P;Kb2tiy@s~qD<jB;q1-4T!OpsNY72Bs+xKfr!^kPwmh ztn;^p%+ZPQ5R9_G0|=1`%Rq2F>m6>I5Ck9)Loft~NF7-_5Pndg0#FZQ`nA=8wgiC< z(9pOqYn^XOsCgG-RcdyddUf(}ZdQ5_Yyb(skfzHvsMJvps(=lCKoA;m0D?On-4Le* z(G5P9WE6`WbgK&w@edwK5D5#UlAsBLBdr1u4(6b|m>3+jHfA!mg0(vk)qoJp___&^ zT=X`R)X@#)APkfLAOHy<yACn976GT9VVf5Lm$jyE>gyaUxRUKqbEUAR0+A2J&=1E) zX6+!iT`;@^;SA%55OfQ@EUOw|$Gu!T5N2R|oNK?%u?)<h4FWI>)ti=hpmXN%4B^YK z0%5hsv5FA!Ww<C1zQD8uv4H5y9m_@yzjqLhiwXj8sbbk{8%hlb_zreSn2Qz<L|6w7 z(6Iyol?&hy;_$c3VGRQCtduIZph^%RjEF+q8fN>1#hC<du&6%fZr%&Q0+72`*{i}~ zdb-+lARvm`_J{W1xCY@4OE#-9CS&aoi3kx4&R}_}>l%<+5Hf5KQ!D_r%dFz@a5dZy zsd#Q5SPs+wOAusm15tbfK)J*Uj1c9j5L&jody&Trkpw45jpBK+B&U#={2PF3wR12K zR@e=*st+2uhXTQ;L28o*5w)|iWQIJwtRMgv%nt&9rv<?bxjGJ5Py_^ls!-5_$ANXI z#t`RlZUNW|0wIW_D-d!p5VCv_Ly!iBU<tF}3=2FEUMv_T*$-<658nW}1mOnCHKB#M z5Xq=zFbK=Yv231*yaG@F14*#`dd)#P5V<Q4^H8PmAY|~6Y4p}|_@{R|jKrSN&R^FK zP$>Y-P`wl^t?9{Y0niW}NDxWaYGOPZOxJ2FDFEP*51X41r9cVM*q`}l5LK%XwL1%U z=*I*9Q2_-Z4Z&K%af;4$p`E-o5C7o8AAAum_zuKnm+hP!fyc=La03dU5y=I5U!0E; zIc@K^T>Y?Va=98w7|jD=(rnD4jEZ^nb`WWJsRywQGPa?rNQAGj#0en|%!q_x3TbQr zqypi)evr`!k!1ehley>+HeCk-k&LNU7+O}04DG<HCYpasbJXEu8Qg{okqit0*|yfC zNyd`~J=Heo4&6AwYAMz**N(RLZ4eyJ3Hy6&Z5qm4X~0-xX~<;G2#dZ8&+!0ziFTa8 zi`EN)z9EN*{R$XssS%k*bK?hwkOs&8ykwXM9TQg&3!ng#JrF2&z#5sMRNcmvhH~it z$j_wlZHp`r)_@P{0LU0C5Xlvp;`VLNoe-|5&I>^fR|&DLQJ4sb4hV?CtymC^fN2!> zZCPrEY_QRbt$jTS4*yzud|{~Y_JKae4p%D>e0_zj&E0-Sf^57GeZ131TO1kgsP`-Y zr9cb;2+PCB$_!y_sRoxU7~)G>8n6rtAXyNJILQP-45bjo31@5&?b`)03G2|$bL!DN ztr^>9w%tH*-v*T(j>@h`4AsnV%Y|~GMqFJ01O`c@_G}Qd-3{$vvkGBk*6J5=7sX`2 znHQ-L%}Jhx*Mha`3ehm$A59w-Xm3~m0un0#Pra*L$Z5@H(lXq<3bAxuiFH-~tQzkt z5ccqU?eGtx?bQ)201{5Xh{p|B=*3we5WzrZ@7$_5z8Q*Vo50);0nXt0HxGzV&D5%J zif3dqt#gL_5bOF5qBd>fAP&;nd5i8AU0rD5wvGy%+lNgNVJ!fkP@cx|yaeaPZh+(e zQ0WM9>?erap3SDAo_pQx4HoCP%)k#aMvRshi52jX2O;eRv36bzyaR!%7Iz2zyj+V7 z8W&sXmqvHpK&PCr=LG4)NhWUZ(2y;c1-$7G6St_q*TA{ZnFC>q8ESF?ILczNb_$t> z!(8D4ftL-DjN`E62h4x+&~vLm57ds`x?!2OcgikY0DS#y;EfQ7_n4sn{MkEf5UlKh zS$5%32<*Hz1_MzFs|Kc5$fm6vk*Rwcv6hwoEDt^Dr6~KjuWWKtrVDaF3DYKOpj^;U zHVMakeq9&N0wD_2@C}K*m<H#nbU7FlplGJf=9!jiGq09#P7p(GxkkHaXzRNN5yeD0 zo?Iz(-XQJgEdc4T5aqCdoF?&<@o-sf5Y!&`>g~n?F$@CW3Ol<HqK3B2n87`E5Hbc2 z^ZVzeF@cT0T=#InDjS1JF94Hna_^9-r-_<mR*PT!^aFwM0x)G4S!hSE_>LwITiE&q z5t~yc^sUKtUH%Zbn-I0Y`mXF7b~>Bbn|N*~;)O>LsE`c<(di2ROOSBx`;cL%md4!u z*?8;N4sF*B`ChP#7UL=#fL}Hb5nbuwD*$#t3hY2;6Dk_*{0{)}OTa(@<jTnt(Cu44 zf(-@4n>Wv$yLsaTyc>u~K)ZJ4%nh8_aALV~4jaykXOU#db_B5$XqW_3D*+Z6_H)Nj zfINgIef|U*ROnEmMU9TL_-`O0IWQaQy4Z5yynadv{$prnAUOdZjSh9^P#-&oT)&=0 zn^x^wwr$-`<Vo@!Mu&6-kRkYS9?_}|KMl;*3Eke31nD^}H;$*gkZv76h8!7k<9L<h zb+c-Cpi+5N|78Z+t>?g38@qM$8TRLbhVa6U%L%fdMS_(7z{OMTQ(R%my?y_F40p6o zj64U%^I6$=P1+3^BApn~WW;x7dk#77^EtPHHv|M|C@2>-aEkx&Yz$oe`lJ6aA{|Fp z)LjAJXwi4SlK0xiQU%!asU(D!W3NC14`iz`<4W4gA*j?!PXKWSa;26A2?FPzk4!?Y zB%KfhF+||{@oX~<fl?|qdF;|Hta30D;1hKSYG=ZqKx=4@f%p)Bp^CifimG?M87K)s z1|pFlCG-deM}kQFEJ+ckq*A*N8#3skD+j7ZfON|FrksdAbLdL$dUQ@FDd#bVBzOd{ z>IXOo8YiAM8`6-L`vhQ(pd^s&s!Bnj{LCsTpAw4yME$}#6E9k<!fPOmK2mc_qR1pD zB>|eThM;g7+D}kXN9`@jex$SXr*`PV^d}ON1nrY^5aVV;hxVDuoQUSZDpgW{4G}%n z=E_Yof)pBvz@PkS=u?7XA*&>FhEwaCaZVIKIxx?q@tti<dXF|`fhBjnka%0?qzftR zQUKM2OV1+Y9D?p$ca#P4&2<S9XB>|jdq>QMz^m^esTQNQT;Jd=wjmIJ@~|I|JhDm- zKN^w)k%yR@hcSxwbqkqJ1%O6?a?(*oVU<_@NjOOZF3HJuRC~C`2!j%qq>7N^XQ0BO z*~Ti62l56sa^yMBW0sd*Z?1mk9jKnxKyt_bNdXKv$s}jrjB040KBCL1Obc>ouYk3K zlb|dH`Y0^3n1&m|ux#8c9=d&!MV6fwvXrOFOyW&CqBew@IJ$V!m7r22HMyLd<Mxdw zt4(t6xOklIhsCaR;zEEobNZ*8iEVA`P%iKJDPhQ0rxHjG9l|3o(!Y9K0Bi;#k};Ei zLQZ$qe|OARkuskYs9EkdNvd(+A?d8Q!L5nI-i4av2LTcx#cSZVPZpt2-EFuhZ5$eR zC#9{doi9-ERO+3$${~lGkIeDcop&<lzBj+u4M1#@%*u)D$|Mdq2w-soL5gxz*Orhl zq#4Z+!1$cujr>(`N(>Q15|VI0g7}aBIdT(#H^PCDWE>+i>p)FB+Cd}%WJ3V-fS^bk zW<eU7iXf&4&^SQWkAw|EDgJO0DhM(S<YcZ@Yw^#tmJ^Yx_^KuUprAvD1iu;5aAi0t z$AqN83<0ns921fpXsjkU_7&<M?a)ash+!Ag38f?x`p5GK;-R^~>>;nJitntLmR1RG zFJb9NVKju5$q9f*h{)XE{=vjoMaFd2klG$4`5Q7igd6^d;y@n84Htc{C}VOG@;p}^ zptwkmlcb?KR?!f$j6-yVv;zRJHWeANavi5QM>|I7z6F{@fJp#>*bssgs!e1fsR~3< z!eYPs2@jQ3LX7~1(U4vOrF=vG5nx-^=8bmD1C4Ck&@pjR#b>gmISrXu=mz4fbvC4c z<?<x>$~jMhAZ~U8!9pWwF(LXnCs5f`OF6=kNuTuOoYR3vM4Cs>rA235;1Ed&JBF5d zlw&R=LF4#(a*h;z3@i<E(*2O4E8*Z|k(~(&H!3+0W|{18i(%-2(!&+9<U;`LB#JM{ zBD?NQMSI3{i#c@igDhCW8}67_(mZBNa>n#4rppZr9Rd$?_=gfzVu+JqaZ{WoBz;ch zUW78|$xjiZA)KIQHHX5JHvXg}@t`2o4kN_fAt^#%1uKYPYR#q&WiFmNMMJ(M&$BSH zU}gFs_@tDRh`7TnWWYlIL%>0#XbvP5+u)7n^17ZaAwwOgx#mw;6k1wpEizVt!bxJb zS+!h=M8q_SR0%?j<PcU=#+X$@rs0aT#p54%Wi8w$0#N6Kr5y((*hL~^oNlm#9mWs< zW=#^WhP2CP?)q0>gFB_UK*VJ6Sd2$VD-w&;F<_O=*0H*xL}lh?9IJAOAI4!R(7CE1 zg+Po+o&nK%{&l;+Y0gg10$0(=gSfUeOCx$?lb~c5xU8Lsc^h}nflz}cki$o(##c{* z@It`<1zuxDHx3rQQ@JPhnOq_=-jCu@C>Ze&N*Yp+NFJ*lxB)7NMKu@1{i8D3MGLXQ zBAS7y14k}1%5p;gLb~~EMpqKaiE2m^k`xUDvV!0QJ1c32hKPe4#Cx!gjlzo3d`i1o z^Ur#FO0W2^s2m+>Q#^~(JaAa*t+9cVT0!g)k{lQdk=o0a(oCh0L=%!kfe4hvyfk6` zL=M@~$v0@L0KE8UVqs3y(+cO4bAWN21#^->zKdh3EjmP)LR#YZ7?gFCBNZuo(h-N! z*8k<jD!D=RB0(Yms3ZZuK}kbHoF;2iuZ6#b42n|Bm~5*YG{pr{A)JuCXks@+!Ms9K zL(W-k5Ooz-Xv$4e^;~RG;ly$Rz=Mgkq*-usTP@t4FUcs!5N}MbB<|}Kxe1-)uc#Vf z1UW@CxUuQ~MjJ&qmBGj<=>!{NUNbXNQFmB~1P-aBb|74HroL&17Sx<)bU|6^ucsuS z;b1zr5yHy-GQ+_qW&Af08g#mF_S-XSoJt&tFKv<LuIaMdH=kMsKe&~(Mbf%#i!r&) z9mCYK0FfZIV@FGL%ALw29WAy}&~W0S6pOUuK|=uphc~VCv^vBU>DZ~!*Sg*VYunjV zng{d9?vsePuDk*WMC=%3j&~$&N(6GIH$L)@-12wszv|CG9xVWo+n3LB=Fh!W^p0zJ z%4FzBMp}97J(C1Bn(h$q`3_H|3lM}Znj?@9=j98oDY@o8A!e1!l3uX*3bHgp>_F0N z^?5e`=B`!T(B`Se;+?EFw8D{&JI=Itb+M&<C<V&j%vWr|d1NlG%SB|-$#<8B$djy) zIgyf~jc~}g;G+l5SKDD>0U*K+I$C3oG|LtJyu7K@h@wrEQmKa7gC5qfhpkF0-b25~ z0Dvw~f{WM>Zj(Mox{`MYi?0&^aG(oSE2Uj~5@OgB0pJ9wD2JAEhjw_YY120X<csd> z5kV6GLZF;{lMJiqf~+A2pZl*PVkG|(fH4pNTHp$#P&N`&4;xCsOlpQ}Xb2XHC$%fU z$H1fWAc%Fr14>XK*di6E!3N%duDZ$=s+b7*nU}-B6Ob4@7hFOF;ToVYi+uo%og%*f zqVS5U(kvP@ib1<6Vp&4pi>kW#C}pWJlW9ZnNgul~!PFU!f9R?Le67119v;#oV3EFb zi6j9#6P#Ko^ZCOvEUckH1V4}i4k9t17&toY4W??0bfK$K`j8IsoEs5`f5Susp^d;< z7vw0706_^?q@9nM2x3aJB1nQ-aSX3>2&n+Q#<@g>B1Op)C%Gw~Z%M21T8>IQ!mt3c zwOAsQh=-Cm!|5Qm<p8Kid5FG~9M`K7hngd5u^M&ALf$yWS0swYAf~Y3ktZy^kT8oP z&_V=Bl5)U}p&%1fE3K$$nb&hiwtzgMQHoPY2i_SwwosHe0}6{ENO}nh2n;>{95l6( zqPKy71{XrHwdkjbGC0uN5cr~zcA!GX5HjK$#69}AcSs2w<b>R)6oqlIfmj8p0S1tv zLyLkFooGo+JU^n4!|5{@W(o>|`iE{PhbT##2eS#)Xsn4W$f0ny@@bgcNt4Kk2&C|p zxBCjK`4gUd$hnxx|B8_F`-^wvH=p<vlvpXY{0Vkqy0%ajWznACy2kWi2u#pHB+-fU zs7q3*ooIL=h<P2sX~(J*3O_)rvH6J&M3DFC3Z^s*X4nR2YYByGK%YR3cJLU48A`?s z5q3Z?-=MI_phC%Pi9Xwq#grsGd<<y}4w96TbXz3G%1h^?7T0J9e<(`-dSWW;dxv!~ zE7pk+c-TgEc$=lvJ#Z<OpmfLFxERPppoVyWtFWV^1gFke4w;*guzU_VON^yzOVV_= zOEHvGp`hG2#8Gr66a)$-d^TyLC)1IVYC{cF@CABgHlP?8x3D4Jh#kgB!QN;qcu)!j z6*EGiO)H_#K}nTY07FYUizXyP(sT%~cn8UBnQ`C_3P={pOU>Uf9l=R6PZFJil7}p6 zyA>rALebDC%*#noPT(XT)e)k1@P>K#wubDDir^Yfs7?cQ46nEnYJ4*3ET^a=5~YaC zQZq{VY_IewiF#p=#!@)e@<uouh|Zy{Rgnu`+MaEs$b{%eXxPdBWSP;lz(|vDrLJJN zw|P+Z5X}YhB+if=Hkk--5SR^PAE9DICMCDOD!%}^xS*H_y5T0|7zS-PBYm79VxR_5 zTnnmjN)SuNvgwTvQ;*~1yEbK@EtOKH2_FMHCZcGr-SVdmEl~|^KumZvL?}?82n2$m z22u@?#?Z2OIwg|q34Sc4C==D%3XpH0N_l7rod8nc@Gb*tyyqy^WQ-8rK!z?d&4W;j z(<}!+9k)-~3#-rtVzAU=6|Hvws5APE!3?otu`aS$%YxvDy?_Q@*p1Jl%Bob2InWV$ zoS|ZgQ#Jb)i$I4}5IAq>260e|YaQ0GkcUnCzX}DEHYF4P5}^p8_`w#;$8t3gig}(s z*$8uOITJCu%t%je>y&V?iu7CyjS$(wN*gP~z-QVide{Wd$qa4~rRdo-maR%fY>2C> zPvtsJw_}-j9SBcdtJ#rQKYUr{>4Sk-n=nkDLKDTnlBjQWi$r@)N=U9yHP>MgM2B#e z2rUXAM2nQ114P)(mj$Oc-HEpS9as?nBLs?y*d5+#2h=cI#w;R&(362MD;P@*+JFiV zf}Fi=2yO5LbhtO5<S;-HoC^Jgoh?ATG#iKbfmslMG<b%WSu=-P4z=oAx7ayJ`352Z zfdz016{^!$l*(foj#|u?L^H>tXpR`Nl_)(6WvLqf0a(0fb6cuWsCyd-9n_(6LNdT1 zh@b(I59@{iinBE%&9>tNiwHDL<2g-Q8WQX(3gQe71Eksb1}BlN8C6c85QoossjsN4 z^97MJe9X=vhkFrO$$^^8D_bgc!^vovusD+86^eu6Sne6hc!D(q+K^f4&;ANdOk|Uw zpg+eU#Xs?m6XV^L@wq!i7$}L{X|<mZF@jkl2yf`oy$Unrz`s!;35IB%BuK7#HP?js zBgh#pu)PWaKGT6H(uy#*XL6m>6bg0<6L*2l!=piWa7_V%2|l2NmPkpKk-0GB$W)jY zg!q>ykw3?xn`U)KHW`{U@Q*rTLjJYO$$Jw2T6oOi^|A7`&fYLQtu+drnTKz9lYZTZ zwtL0U8p}C4NCTGRjd=)FbcoEzU=8I234FYus24*0js57yf%ul73kL!5DL_#md2kjz zc1K@P6ZI4akQurv=?N0KpO-zNPvIgLDHO->gn>AQ)|A_@#1XrA5GFF$ifYQ^^@&zC zwZ9FJF9Xb~G%TNh2TtlctKd*6g3?*85-&EHX#*r3RxTjzhc8o&V<a745I{B+kt0Sw zTpU)($j0>mC|d#NLiM?R08Im9uXzfs3Kf_V){=xsj%o~NgE}V#8wh^RQB|S6)gh>u zP1@Nj<d;nk{wh6!00KR<t)K9Q;n)!WXLJ^XaAdZ;({goY9jhHkJ{s^zXJ2BISLIC$ z6#(uCWPK|*e@T^@$>RSahlO;ADL$yTS%!b`m#RC@R~+RN<B2Fvu775ktYS#ikZDde z<I%e&BX|-$kQA;t2+<>o?~%J&0+H)WP0Q6dtjt$MRSjChm2Sx7ls=0G9zAwFr@!=L zy13}Lfe~#>-|H%ewz^UlB~5mt!g(Bs34yJU1`(wt2(sX!ZLk{(#tC6*Yc5q9)#!o> za0p=#sIEYm2h%Qwz~=)w%jlUQ9xOnnB9U&0B50U~cA%=)Bx|7{5_5p&wh$b%p1aYN zYLl?E?DA_GlDTzAV9EAopNXdbS2^Tjb75{MAY$n0dV0|w5ofrWw!(O2*;rS5$>o6{ zVL+iOqcn<c-VCN9$8V;VGy?%F2%3B@RRNfWotl>Ag1yzIB*v^(*i($to}_P}i^G@( zf{?krsEmE-1czAOC0yg{8VaW<;O!}lp;;GBHdi(%=Qj}@B{DhQNSdk4Yy_EbwvmcC z2<o|G7|N-M!btAHA?X6iuD?lYQ%i20I1<%pvx2Mb-)XAmkP5;OD63dg`9s9*9SYuE zW4-7Y_!g7_-%zD+@UB+p=n(+xX$U0{h8iXb;#&@N5F%%J?oAyP0Xj~Q1<PVXkFV(o zc0JN6`8vKX$hn{`0dNEV4{14%`0dS_hCV!K@3abbsPC~EO?|tPEMF<j%8eE$l?nMV za{vvqV2H%FIZ&8~mNK6;*J6-(k*c89oqp!YQ5`;q9N!I#9(4v<+6}CObhKEdy*7{s zgIltjN)oY^>(e1Yy-OcooyYm%5@t|P0rY<m2dGJfufCEGk13u|%oTY@{tn@+0TN38 z6^o(^{^Ey9o)$uPs+-}O0g#Zq@N*)!yx*b1qP@;;Y|**?5UjOo5JJ3<iHLR(SH?6B zj7ZXKW_5=0u(W*$cb?H3_6bgS8)7f^Wbv`$`}8NVcWM&=C5WP3h7e)%Wyq=FB2_Nh zK--v7CjnqsctBYHS1IvwiDGI7?kfS(PszM!z6kMBijw)1ZphDtpC>)W;xd_yx6=hE zKG4{d?GHKX;&a=1n1lp`-?q@!xN)$Y=!Y^F(Se}AdRq72S&nC=oT0xIi&y$wY*kR1 zIiR1Tns8@bXDH*ikX%>`7U7Q4t)P-fJlqpiXC#PaC}Bm9KH%xnxuA_Lp@jFW!MVu? z=n8pecL>MLHWA?!qhETB!|edY9bs#rY?3*ycPi#vipui|Aeo0lj9_?XQ3I0=Q3Z0e z==XA=00p=KlJC7C696)M$^(goy%&9^_XfJzcbVT_5^2Dgr+c{Zik2`d`639H1@;@p z$i@S!o_V_e+z4?@)U_lph&LhpEhO8`s35c7tSGtkBD)NM8Gf|zg~IXK(WmCmK#pjV zg&6AP6a*xsO0>C{{%1;(by2XKr3OW5xkMZYPB;?qh`-*qptyYgxsx#dwh{26e1s5U zRH}H61_*iR1k4L3Po98;3KueL=<p%Ke*(JogJ|(0MuqO&W$ftjBgl{<N0KaQ@?^)2 z2Nh<khq2tjgXPL4G#3*k&YUGBT0FSX98hxtDk?1Z@7=q3^K>$8>hvkpr~)=7{73U$ zMW9%bCZq~cCBlc@!b*)Qv)sF(L=&zo>-OV8rTyeBP0Mj6Shr&Zw0*nLtJk-J2NN!g zv+cqEeniPNr0FnTJfL7DyHje|aNmS!6P6O^aHd0ZiUn*Fut0Odaq`?{zWmm*>)3ud zGF*L9=t9p6Tg&e48|6%z|7i0*xzcg!rD}gOZ|?m0VT9chy5y@coWg$MjFRQs9lG0b z3#m1nXO4DJ$L-n?1MmJl{Dwr=hHM*8q4N0p_jg7A)U!19;Kvq!1sZsuP8*H(*+Ro4 zBpiJR7PeVq$T`%Ggc)ks+d<xxgPuI%a5a^G8=8pVXy4FA&u*)gcp{83y4RLD^N6<) zI|^Yqj5<|)C!<O2EhJuqnE@pLg+nDZPjNsx`J_iYK{+LV-Lbgaa#U)$<!eh>xKKO) z^GGScm|Ui`R+13?BN2uP6|j(85t=!tlZ-92Af0&%23bSHl%^-3fqvu_pWa}n5IWy< zRSre&9EDVqfgUNqIF;Vm&_PG0sZgbXktisrGyYiKJf4PnDo7jg`6a5Yx~h;oLg|*! zHuqU~5K<$)Iw@N}nks-F47IZvY@Yu5DzZ=|CMT@PI(v~%cP->ho6lN1rB{){I_k9$ zDV5keNl=i4LcDf+u3!i`rcRDzqMNK@3o2ITyY)g@X0`T?)QSLaGQ@1WL+Lv(Tx6jl zKs(+L#4N#d{zcnpG)eQ&u?<`NTtELPdKHqJUK|u|r3msSEf<@NldTEG^JT^VCsVm> zLI5-DGR>};J1J}@2S*cnNho?=e%jVtvoQj&I`o_^D>NOqNIU(sVL1z+XhLKNtf<gX zyL>R5`DqR1MpE~5)7NF2-4w_Ry@`oKVxRqSG^b=Y^V@kUT{qr&V;U2m81k`@JNfF} zFrI^Ni6?T^-5IdqjXSQ;egC)tLRSPmZtqXH8BOtvmrE!Qy)hGYx96n~U8w+eCRA<K zraybA>nF~7O*JZyQ%>Qr>;81SX_<51JE8CXtin1PP5SWets}sdM(3V9^e4x)lsib7 z8@;o*DKn<<*hA+|I9}7#wD;u?+`0M5YO~Kj@l>Baf9&8>yFysOe?R{J`8QXi079|j zj!np?zu(X=HSYV%028Rd1>$5<?jVOm^1?voxFZ^h>lN}QsKE_#kVFwgUk3*R3zr<j zR?iC|3RAej)~T>8o{<OLS}4OA(y)dg$%jPD(LEdTu!laZAv+Yq!XFZ`h@~?Y2!Cjf zSsl%YPJAL1qbS8GQn89wydoB}sKqUEv5Q{(A{fIc#xasHPqQi`8q=u8HL|gdZhRvg z<0!{D(y@+qydxg-sK+j<ZjXNa;~c@^F+dWskYm(>zznI#MSf8e5dcOx`pC#hQZkA> zvBf+jS;;b{!W5lM$Okmxu1$KeAE`h<LSRQqGD@jbXkd#bSD8isFD&CyvTWlrc6duE zqOus_Na8NHh#uVhGML6ZW&+m|Lu4|una+GBG@~iaX;QPA*1RS*v#HH(a<iM>{3bZV zDb8_{vz+EUCpy!q&ULc0o$h=mJmV?PdD63<_Pi%P^Qq5$^0S}*{3k#ID$s!vw4eq( zC_)pe(1kLzp$>g0L?b#VU`n*2*i@xOGulmEYP6%(6re{#ip)s}PNXJ1DN0kS(v`9l zS@38nOk*n3nbNeTHg!uy;4#RX^7M`H@CTB5DpWa2BpmP<;!u<NMR)XrPfC3%8vT)$ zihK*CP`zpu^TQgeVzsMY{VG^-vdplOwT5eYNE6GdR<m;d?;W7A2t2&D*13i-SMLxY zMd_;70rq1v{^*|9&brsZLhmNqAP+>s5xV>MgJ*dqEMy-?Avr|0vJ=dic+!H20Dxp0 ztU{_~LtC@fjN={EdO#|7nh<Y@2O(n>Eo=?v2h}n}bs)=NY;$X}HEC`kC3A=!Fd|sp z5?5=(6#zF7n-DQ=W*o{HKtdovlg9q*wZ*;e#c0bAD1hQ0rJAaCGh$urk~dE)VGIaR z>ydbDW-eTP2vQzf-uZ$mE%2ZkL$;Bh@y;z?{xz-ODj|)O(U&ma;t4ro8QuazMIr<a ziK)mTr&n-_E&OG$N#5~TU19hmeQiue7W|b5#!>+P_fSZWO5EWU%Lo&{otaTa(vOYU ziKDino_tyC6q?9Y#~w)&<)-tHrF>%?R^i;kM7N*^J0!<GE(>yy!{H}uq%t-_*k(8z ztYH<eA^xaH_rQW4s=RkwR6a9`95O1Jki#e(JuXD@k&u_7**6zPGoCQiiUM$UD#D8g z=>CC_K#xf-?tsj9_Mr@hFuBf-{@g-Jk;owd6*)ecaZ|-Klz6nG(aeAomNxi~Gd^0N z_j#*=h;k4<Mdl)^#7=KZ{gzWZS=J0`ghjR?5qKy@Ij&V1ok5}+(9O-(O(Bapf@AEb zjA_P0d6ATSQM8Dxt{n(jO0+uo*-trBIa|g5?Xo@Mn0|}{HyU0@neYL*urOv=Es7Sn z)0bet)mo8`nMr)>9d3(+BOZOF-qH|;5de2g!{637{&adCgzr0?@4$^a(wdMW|Dzk7 zj+}p0U1r_I#6^+n22kZ;aA=;e;U-a3^~{0Mh2&!&0{EqP?gMDlF(lp!Gy*8VApoE< z+~m`woB;*^fYb;895G%9D<F~<dSyK03M`y|7XpgqiVn^`=O$6!bcGBU-~tbEh5%mS z3IRQ6C}CmhnqXt~x&ja(nkxqwC`FDQU!9x;fNt3ta*Y#nCfGLV`2ag!u7)VVa*Uir z-OEzap{J%8&=NpoV(r9beCZLJymR9J-2xA9tfnqmA|k07g7cOCaZI+%JX0v=5pJ{y zjDt*Yv}QbIHr|J+3&}U?2g7MR&UmYF^zXxLp8Gs<6veqv2Qk(G)PzVFv|4;C@M$Cb z;iJ1DxuE)LYXU~D{vZooP)OXFKl?C3h8*o}`se_kd)6-`4G9S@NQz%Xa)m_YA8zAI z?V6+{Q{O3BfQUD2hvY?(*PMn&#L7Ix!#tFn7%flbs0Fe0pHut^L;wSWOd1po65llo zIY34@d;>hR*5bTTJir5E=ukyOodkY_7YM*Q7=z+~12qJj0DwXrgkM9*9}V#ddME%E ztd2!U#G3F#`y5akF@rMjf<hes8D9{`*{NT{MFP7}TUsn%_6fiZD#Rp=0z<r24fVz8 z2>{zP#64V)%ESt8P(~S5Ljf&BG86@Y^vVi;L@WqE=p_V2xYZeX*Fr#n60m^)aG^yw z+Xl@GA5scKoCY_zUEVQ7k3gQ$1V_`M5j;qQ0}22V*1{vI%*%b=95Tc+7|+x&gu;l) zN^As8*vdP^gD_--ln4dg-A`sfhF9Fc0~Enfv;$@I!v{))GO$Q9T!RZr1n8)tcT67? z>4P)eTSM>zLk!?2ZjMD*14A%L*vx}nR0Z}WL>&Zy4IKo{4ct43$3GB7b>ssu%mbs` zhx7T68~6b?zymZggrczjpF`BbK-3)OH5@J!MK?4N?)2Ic@>Z<9Pe+hmlR+WWtb};9 ziNActhtP&DDaK5+BmQ{dMf8~);DP1r5H&IcJJ4AS(L@-2qRtIS7am=Iv|jaHge8RH zWt9p?kOTe2OikcMru@!>U68`4gm=tPxpjmBBt)=qLP=i4Oc05`<r-HZk+BsXF0@NV zNDxTKRUI^hR1T2GbWZRc8k2pbIxGb(Dr5&0Lh6KsHf%$U7+E>2hv6***F@tT2!K9x z#58oy+GRvLV8<*xM7}f{L@*%I7~*nyUPGu>#<hcEK!X67VGfSc5b7Wbl@vtOW%B?b zWPpY|2$=w!gPM&014np@3JPY2twGq8i%cp6)l^5a=|nrM$;L&GIbg*P5?x0q#%6G4 zc~nI?+FlP~lpqK|aDqfuRtHaL+Jaz3#0fw?#$^ze<35sC9tgl2a;9Psm?|s;%aA2T z2omHxVB>fNSL|7Zv1CI8pGKs^koB9t^;NFOVGVHtN+^yh-qlS2n0d@&d14TE78nH< zkT?ihY=VTuZ9{jcoa3O5;OGKnVnmYRmqMTdKXikT;pTh#kfa5IgT4q20uDJiipc5T zOnO9uedwdzhy$_%>qSUK*rQ?Sl=pboQnX1C3}rcdLo9X#QmD=w3cyE_iN$qH54nMG zio$OR05!1x7e=U3H>lE;9Hp5}MMn(id_6-yp5#Yhhl=q~r6ft8(Zuz51Xy^(UTA|t zSOeKjgo0eC49Vwk7J?sKN~H8dH_QV%AOkC0qSEzFu4v0X)MY~a0_Uvcim8Jq2;716 zgIl@|hA@J#glS3ukZ3ew^PJd?0GivN5Hb8sLU5}4JYGW-Q!EOhfVyHqd;~^fm@6Ra zN36m`IMGkAszOjhbS9+HY$CM{g=FfF8wg2g=x4{d=-@qs%qgI^y~w;lp5|!7iNQiN zG$L2j>R!<qJeW{M<ijSkp>-5dNo}c^N*_~=RX2zk0&UQ6CIl@ANoPc9N4Ua1gx&>x z&{Qb@h0=@ze*MEbc&0*_!ZKtBU}6`BWCOzJrxk(YjU1@}(1N!@*j7af{rqF(kO==J zkO3})uQsS~QD-esU~e@;LU@Kj3<r8<gi$=0gERzVAmduKNscxKmgb;qNh|gk;+4IK zK{iF<2u>Sz!+qcebdo0akinP;D@nl4?UZ6d^k_m9!#@B8&_?D(eA;7J8=36tis`1+ zrq7xvMmU<rL+YZ>X6;1?VIyLtMv%$86dU{?!YIa}D0<>oOk5ZKV>z^JxOT*vbWV~e zt-=UdJ4mFIT9!FHt4QdOLwtjV8Dj|b#UNn~m0CpR;0k(3twRiw$|lcd3{hBQW!;wl zEv67e%RWR!$b+p&i8DgPUdEO$Fh!-UhDD|i>Qn?5^cgjfgJMb?P6WnYsL7yp9N8pL zzSs{*oDuBg%VlN<NdQIPd~CHS?REJ==sH9U!4SEk5K%0^P--8U5Nrbpg~wC}J%oae zgy`jZjxMlj${>|bK7@G0?q`@o2O2A+a8*p;29&}AyGEAW{HsX-?F3=Mo6JGY_2)z6 zB%d&b%drSORD;J#qk9ezM<#@FJ)4y=EK=AKQNTloHYP(<Yk$xyMS04qwFwjEgSyqm z<0jRiZm?MOo(vTM$*^jsDhmt|1(Q&xLO7;xrq5=aZ~q{vE^sQ?HU&*k>pwdG1UukH z<Qa$Ni0xXj1OJjNB~X@jGS%yP59_HHa&ZGkK&oI+1*@3hKX`*sl&{{H<#|#Hl!_ap zh^|vLL@-E%H<V+x<wQ5=h8YW$ayapIj17F=&t$|Jt_gtE*rsfFVL4>wLh!@HJka#; zXIJL&$sjC4bV`3B2cJ*`>ZY*h&IPB*L#i4Z_u`KN25td!vPeV=ytM<4HpG=+14*ie z&5rEbjKelifB`Csa|u8MD+D8Of)6vr10{qj)I#(gZ&XOKXe|W`vx>aP?Aa_x&XmRi zXfZ0I#52QY__*?qYTq+M9pijW$-GG;&;qI5m#peU;pB*`3I${gVcBK>gFRfP&qiZO zT=U?lAW$sodlZhKO^vOjX+j7Hue}gBt6<smL$Fu`r-_(Jn8RxZ9KC@Kx160lV}zXL zY8{u)H7+6KQqW%j#XsMn4udP9CbR$)1NP1tc*5aez|MB+9Wr0^MJ%-R4v=Ng#{w(> zVi9mo2p&S7XZ7gc_|?qvZkDh-1UK*jB0%VlvC0v9#~U+5Eg<5)%`o2b@yzxEMsgM| z4hL2{N6XfO8Da?T4$TbT$2UMIKWj!_G8?84Mas;yv0X7z2<CM7^x2?}R{Mt3R14oV zPdYG)wYjH56U?UUUTty2Vdn&8Dh*v<bWScrBdEeWa}Wqnz(c10#Y}iHbfk=s3A7n{ z14W+o)2v5Hxuqx+0w**!Q{)a=^hg5>KstPbZaSLE@`eDr+-%=r`MBFcSWWK%#TC0o z_(;UGwT&GvBq%o#pQMElV~9Hhb753VG_<i=^xjJ7rnb^_h1rUFh7d=pPI3DNN8!%X zO!e)lahpUi9w&q-_=aa3kQ4R;EK-MeTLg7?Ge<)VQGkHzX~t$Kvwm<yUtddnJA@xd zL^*ixA@`dAKm#vS96>BxRhhPTze79{a$qWuO2SA*AjdsyU_-F*(6Amtn3h6t0!dCP zL%23mjL)5DMqWi6hTEDUDn@Ue>wZR$MD&;d>qhh%h`K2M1TqNpV{n90EFd)J35MiC z#WIGXP^M)x+dxLeSuyx_ATLaW=!itjMbHOf>Q*h(VN`VO7^HFXWDEbA$CD^WMKCL4 zLd00$bEr7#?X9)&J_JWr%KgR0suIXuYa^0Ccn-@#N@wm*UY7&vhMj+gqOfiH@J62{ z0eLW$XT!*sWOOxJMR^0tY!ZbQuSJmo%k6Cj9v}i8KYFC5l9Vv`R8?6}Ikk?V!;OnX z;Yiv-Si?Pl-L2ORZ$X4m7{!oFh@qV&L*T<@FHO_(W_D#ql7MC?Bgb1i#n#G+L`)S? zz;jqgT%%PxVcoV{2ykfZ4$yu&eAw$;2*3$11Tvfd^tBufgQBh)qinq|`e2lUIFvHg zp+)b_g#V)OMvMr$D^-KPMVdr*c+!R!ib9|LDwRwuT%1cNS8_T}4Xr;&mtV%Oc*a)b zN+>HwGDNmriI&UJn-^g$ws3@WNaY)zybDILt7u9>JUr1sMoB3XXOzn*({Q!nhr*O& z%y>-aF2tdZk72`jS5eqMs5}p~#&W*OPlQ94C9O69sxH<Ho-8=0jDz4X##<G9PT&r{ z+2=*n!$-0Mz&|i-9XJPxy_48SP;aZVAQe}X3@0pQ|8OtdA0R?_L#Z$XMX<fLTu_6T zYh;Z|z?a316m{7MmgPpEnLLkR`Ns#k+2V))ip?8d7}|;9UWz?Jt!q>}O^kW#wX%u% zXl+L$Mp|L=Jbat1v5b84e1ND9g-+%RiX1%TVI~9~l+1d_MI}>>=obc@iG#`k>O}av zv+oAKYv;iim*x<7NL(hX6AUI~udB3$QoOUZ>WhC2;Eix9o|Fht5d8H=>ZLVAYmv_o zUYU;+`_(CZf~LQdIR3M2KIBeHTdNL0yn82rU_pZi5hhf)Frhnl0=l(hhtS+YhXl)E z6v&WcM~@#th7>uHWJ!}JQKnS6l4Z-2{amhWm$04ycHRWc`?oV@PoF;-awC`|K*53Y z=D`HIlxb6^PZ16@T2PRHhX$nzU?gDwBUG;h%~kw5mTXzGXVIor>-FMVw?2spC?Iz( z!FFNau5FvwEmEuR#2vg!aNIZnN)Z-LIFqlzZa60v{MMLqWy_Z_XI4us9KmK_1Iv@A znY6-r2;p&q8Fp`JpsigyE!>VVK|TV=nHC_2U~a;O6Dp?sFJa)*uwy4zzMOew(Ur|1 zZhn~>LYRe-PdC{Xd3Nn01(wSQ(@b50?}Q^fP0;UhdEF*|mp`9=eUIxuK2OUVA-8hl z;vvX8`_3v#Fn2^7kU)gE8>}D&7o?~ncZfTvAL$bMrycCvLFyg+{xS%{2uUo_#1ol{ zC%}UA8!ICLXjy196w#u9Aa3ISsg1@ReR61=({wDUt#9zdF-Xkf2`8S&K;+TMC!s6} zIEHvyD-eRz5r7^6vLUX*D8Kr~or<ai(@ZG^IMTO{+7ZvF>hMtR!h*UXXwEb7%+tg> zMbha@w~mD9Pd$N}CptnAHLb~l#&M?~3PmjFw!;Jv>pX*q<C8RZ;#oA&PeJ`oQ-xYY z3&Vx*3biB~)$>$UJjDx?y|64zDAn|IF{rRoGvoEuUxA%&#Jt9NF<6dHmGIa^9W2S$ zOPd>Z*=ecGvptXoo%Y&}E=;!C9bJ8K)P=VF*4%T^&8#1(x{2tZI@84~D*+5FD6D7G zC9u?74GL_sa@O-zps@V^I_(`!7%7FAHS=xQ;fI;J$XFR?TsEu=g(@h3BCyC7;uBBn z2N5pJyU<OJ9!j+!m?r($<(FZ0R<w$3waTGpL-lc-+9*h(fO-#%nZSOgEQm3D-)U#E zCXvFBVWFXpT05Ha(hnwbCgv(MszZIwupk#WkLaSMmAWyNWkq>1T5C1PkE+a$TW*MN zb}%wKzrBbWEQ&Db8+cBxyY9K^OYb1jRJQrNc?oaaakpZzu%9y3QmR6j#L;m>J1Nie z&N~?|h?4jKUb)-TA6G7Ph3+i(syI`RU3Rj}@p!Gy1^CiXOn0*V%nLo9i<9%3HvM$e zXP*vtUB`Je`RAek|LN$N@y!e8R~@=no^it#>K$*Rx9ocG$#oUloXihj{q-Fim;IA; zE(jBZGD`e?%7l90!Tb5|pDA(u7ZW)o!62m|Ohw2SK(DweZ6PtoIJ(js1x_$|!(dnS zD9Dg&P3Z;-06}#gVyLoZkS!{4lUVpgLKPB@ADyAz3SHu+o57GQjGM<h>_-v|(vXKj zD+l$s)<eZ1WO!3yPx^%TlNn{KALa5$sWvhhxVbNhRXmqNkTOCQ-b(;0YRL7h*c7Qm zuqEcuVi?hws22)ghdnHpYSLJi9FC-o1gT>j@pvXD=FuQ+<D+tLH;@PV?vI5u6H=C! zN1TDtkbL2eiKRrbmE7PZfsM2zid1yROK$Qqj2IpnIT=bGsYsNibWO9+Q#4bql0b+g zBr9QQmM>8QIDU-fEise0FKH5&z3kEWkmyTcuB9^t2@D&9I80^6WG}VyQZSbp&9v}R zn$;x9g#<!HYi{!?qd~<wM8rsLj+30_H0L?dnND@Clb!91qbl7QPkA0IAOHY61JQ}l literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_sphere_gmm01.gif b/images/demo_Riemannian_sphere_gmm01.gif new file mode 100644 index 0000000000000000000000000000000000000000..2976a61a328dac18e8006561c749dc0efe675680 GIT binary patch literal 343123 zcmWhzby(BSAOCDDXa>?bdLSs$QjP`%9G&7&`U?n>BIq`{JEWX62#QJ>;6{VQ=*E$f ziVBJf?&t4$-uK-7bNAfcyYBtEm$9jl`eip9*c$v3xCGDu1~>y73mbwJ!H!_(KyYw# za`N-=@$(7_2nY!B3;tgOghhnKkmog!%2uL^*Tj^}#gxs(mCU6iWu%P5rA+Qin?y*P zMxqS=LzzU#Tn&*i3pp<<fBtHO947jLX{3@xsH(E6x^kZS%^VHYZ4I?{jhGe9m}SlQ zO)bqUI;O5@9klKhBR$syealP(Jp*GyV`C!|Q)AO>re+pq78X`**UhhE{t0Hw(#+h_ z0%L`-vbDCgwRW<zwzIRbcd&DCbj3OOEIK6)IXgPvaLjXc-f(qsz3G>ab$*3)#ojh{ zy^X!)>F(j<|J>Kx*VkvsF8~+tpZ}eJ{5yfcfp?aJv~+|1je>%M?}mhhghd24MFcJ0 z^Uu8(aW5(|Dk?HJD)M>M{h0@Z@`uq6@i=@eAvQK<DIqpKA>~bC+2f>yq~x5zl%$lD zBw|X&PHJXBdTM%RdS+HeR(4i)PHJCnc6x4hZf?#%UQT{~Rz*QxK|w)DVL@SGVOwG0 z+@stlMTL1qg+;}M#l??GN;2|F9u1Tfm6m2?mKNug7MGQkmOU<e{P=M{5$jJ(NFWxM z63d8BO2*3l1IuGF$`gmni*w7%9+wk|<xk4XYX&MJ?p2gmR8>?})wEU@6ju`mtE)F^ z9#+&;)zsG1J*}&6$j)eZ+Su@Pr17d<qpNFU!;5DP&z?1PKW}V({<5>_S<{Qs$1fV| zUp#y9vgzfkm#<#6%r>{aZF$+;+T7aK($@Z{q`kGhy_53#<-0fSZ{BolziX&{_vT%P zmQF|8U<awY^IhlrrdHBJ9I3vK{GQxJ?&|L9?&<378QkejBKI~t@AD7rD=O{l?(17v z?eFa$NY5L{&mS0@80;S$%E%lV7#bcL9;vArZEYPL866uL8z;RVAEQiACMM%ECMTw* zOCL{<eVCq{nwgrJbMjxDr!IT>Qq62P*SEG}<F{*ScOvfXy14G`9Ul1y{`&dr&+k8{ zr>AFzCTD-n{+|B*dv^Bs?_b&(jrNx&N@KDxw6WIL#TY7HP@n?=03iAc0(Jk_%l&J> z|J?+jrvbFMb8BL;WCRk8w5g@U=qAwXM--~F$HG&DbzGVgv&0P3dDNud)n1YqNEg=5 zpHly}VVZN%xoAmU$<w?@)nm6|=bKc2iH_Uv)JHkn6e2qO$7xc?&UoeZdskI<n`I{u z7wjb5X4yopJj8Y<3tek%n1AIxS%2e0YvW>D;QCPM;*Up}3H%Bhy`;8_FgAWLy!xc= z(11(;)f{=B+`+OYOaDHm6u#W-O<-s1Y?}QNH%8R`b0DB`<ULV!<#Au8)6vdM{mnMl zk;qoR#R|8Z4lKoCUl!}`(MHpXBLb;aaXiM+OBZj&Sk<3(8@IhV-kW>%-^bA#2g_`{ za#6G<Qn(iEd$UXosi{-@V0`1_wd#GfzkfPQ_nb}AmqKWBv;%G;u21FD{N3TN_Cx|) z%%K?1qF6|bjoPUejN{VqUd8eJ4oBYPS2uua-}w4!ED2RzyOu21y1ka7(1%)2Ri5!) zPgCEjtw@F1lI)>;Hb7;j?&qIKm>#2ygLe@_D;f6U7Z0x=zm0<A!#A(<-SS<+b~X#J z@iJS5?)g4jkG!kvqza??I7dTHdtR@Xgv|JSDvj8x^GXrH1?oaCG>f9x3H9SJcF{oW z29)nLwF}ObX>94r9f77ozmB&RM{Xn;%?G4DI3x#f1@;v{zp@yKB;L=n+bwG9qsi_y zG|%|%HF`>IQKU~IBtMmrVCVOndbm@{4Qf4`2DLj>{~P1W%1?IZn08-J5vPhi+JFk= z7FD`FWHfcn-hk!1yK=<_GBFtbt#!{EXM9}@-RMl->p0nZ`la)9=63<yZEkYxc^|jm zA(>vp&oY85>X23E=hAI9oi>PLJ)GM;vquSfx!kByq#X^e6!7L$%x;J?BfwcS7ZfXT z*;E4TDE=^&S3&~63r&Cd6hzOjy}J$*JZfNn@Kdt!Xu?eG;Aj$KEPp&@WAA@FZT_X2 z471AI{;vz0Apc`dHL^+f9@o3^^H*q;bv;<aM6p3H8+{QT>UOgBK_oMq_F_<Ex|W>~ z@gHQJiEqd*_(W<9g9kA@JGpy}Bgz9avRNG1L_U{wC))rf0nzVMdY0LwOMh$o1`A)- z-I*_YP5l@C?7#dyeY_A<Wb)(lyPppfJovG`WX7?h;Okc&8w@#N`K*h-OZ`W03TD4| z?kkD^D3h!!U`qceme<{8y-UhJ3S-W30kTdwzx4bo^IKJEb}++^PK6OivCTeMyEqnY zB*4cj!k3M#ryu`}qc<ah-3kg8qesFKsYJ*Z&bF=9b&+X$-KRR@YLPDK^n%`ne^PbX zRHppTaZz!#$*l|>ul>&@G8u8GXOcg7RPaB;+0akH)tF+bcROqQq-kjB&bRmky6d%l zQga?8sK(bMOzN#dbSwz|w_D`ga5;AyuXu;q&P6U#@0BTve&e{=?Y0xZPCXNJ$xn=K z=w;cmI;jBe2aeSg6k)fcrtl@-xyyF~fcE+?h`z?%HvHqVt*7vuDHe0PI1ryflI*?e z^ex+J>KfM$UXu{?HHVl=ta9j86s=?rXxK?vs=rjZbuZn?zg?Iy`UuZlyPEeYrk7vt zlQB;N{{DkWQRW=tD+Kc-1~g2S5cm-*fml7)@QQ7w+H}O%>3h-KaJ6d9Jlf*-P|g$P z8g=py8A`6KI~UICE>HzyrHmVMBV$&67lOow5w_fcpZK?SXyE&vxciIur=+7^7#IfO zAo6}Onx+5~VI~{mPfwoD+yHm1f-RFH5mIVH<LTe7<*+Wnx%*8gviXOt8rico^w%p8 z<%}Lj^##|CW3H>d`ChGO#aXXd-x#%`T&+G`Cyr0H&fq_;HEFz|c3;veN8`AT#4nkT zHk@9nRMh%qU|Sh-)wrPVzZxADw@TOg#ztS2xZ71cLN}AIi=J)Un5I2-`7|V%8Ts9S z8e8xB(@C79yz`uFZJv9YJsI^T)Ft4c-j0Xq`qSj|vCMl+LfWs2tVH9lKJ4|&QGUud z>e{M|>)^=ID=wnI!kUZyS+Lq~C8j-RTI%Ev{<G9{rqBxQT3<l@{eAw-%gG-Xzgd48 znD9reVeNZ+zc!bSPx8`M_NUjQp`U$={#)9VZF^In`Yg2N!}90Ig11A*0TFLCU0*&> z)A=O-<=*TE*Y6MPJH~A<MpZfAIGkzg_+(B{3+8cI`~CBMI%5+KZbk*OIe5Y>ng~3@ zRG8)o8Ij%;D{Z#Q=zP+}JK7Yl=11K&gFinzd!G1f0ncGgq+?YNf?GtbaTcHSo;P}t zEJMA;-xkq#J`A1iF}%*--`<Dz{F)IYxGws>a6nB*F*Rs^O-%ez|D^{nvr6B&qnI8I znRDOGd6Bv<?R9U+<=NfBI<2kq_Z^4KKHtrIU$UX{^fhf5Yw@aZ(`-v^FM`2U;6>Tl zA^<u01>kgWk7<J2x&r(lJhw9O9BvyT$4`mpZmwX<#F<`qqQqQit`;rb(Gw}6l>Ak$ zy(GVDa{tX#qK-<vwa~7Wbma8&&&~CY=DwEwky9<z$MvBsdya1xW)nJF8f{CrU6}q% zc3lW-!u#*qr8t2Y(aK<cT&&iYUkmsB0lL<agMj;g7OAXl?fvGT?-u`A+O}wWGduD* z?CqcB!}PXypUl79wJsJG>1*vQt@ro-^XDVL)=q+391;Xhsr1*|yLd(q<26rL5gF}0 z(iUHno!?OxJHtDFjsyk$__Ky&dp%%m@h!XfbOS}Z{<=rW^&l<$bkoHT_nwc4i(EY2 zQXhLg8a^6)=jrJuG><x+ayna~Ky->?&9ByrH}>gxNjsQ_8dG#<NA<=XJN9jFrcxS@ zpWYVQyV3T0w%_8%%i^<r@9X~#JNl!Q=l+gv#{D5BS4b4k*>*$*mW~5BxT;11;n?0$ z;nz>P1pXc-UVpbH1mJr$|9;KPc();a{nwE53W&M3c}eZzH`vtj<~_EvxonH?5Ori` z`PGhH`?23MZ~q=QWkm1ax%y{eaplL$v5wE-V}Dlu{QXIKc*gkK#iuj)?+MqZKa?vE z!^btR_$mJU2@-4qGcW!9JvY|*qiyVL;UNw}WqVIM>A(KqYdGz6`}+IevtxgM+@zU? zxZoeBWSsuKUb0oz_UHT0$4wn~oI#TXAhlx&hyxB5fuk?PF}CBF=^r+?flxTGi~^q1 z0nZ(QKNkTGthoGn3MYJmNAeQH)Cm#}gil!@W*oq9_)y6{SlR2Lf<xd?!9!yILsgVq zB^*~1ZY@lGpmP%Q8KS|f9;?rb=R+%_3uCXg$C?#JYj0b8E4at^^P&Ey5K48xg>AxW zH84IK?7Ho*JQt;=9#6`SnQQ~gK={nt<L47V?1^CMOmL8T!d-`i5Z(m7M6d+HZr@m0 z0EzSCO(bkT$jc#|F9g6CKqVZYLxR<4#1N)_0EPwRP$AGjAdfeO%{ctGaeP^=v}b!v zjC!&fRD-<`92fzvZ%=L*NUk}F$8A5T(MMN0q_jrd*XE7OGXhy-AS{7^ED@|pVY;jy zs6PvsdI5?gaN!AIU@i_$q7%a<*(avTMWl+<B<a-z{XR@u`BzuL{bA_ns3(^tBht6M zacZ0K>~qPVPtt=E!Kw;4u>pL|IfFa5(|6i4PUkWtA_xzplEjb*76rgrf&LPL2^N@i zkvA}#7XTvw7zF@P;U37WDH8yU1g5-!HxxP!$6!W87F}Q*yeSK$0I<}h(Nsg^XVX6N z=4f)HYoKs5pEA^G^SBnT<e<Xj!@1<Z#AKs6ybwL1XdV0zVITrLygZ+4v6FFwD=xbh zyhVjuV*v*oT!F+IiKe$eC$ahf%2*f{1CtHR4koe$6X9YCS=X?zo0R<QTBf%ccmNs% zrvTQ0Fl$@^91U{9z&xlBI4PUeG(_=Hp}JlUC?X|hAiZuo=gMI6-P#1>+y~kYiru-o zg4=~<mlOH2K=hgSU;tgM0<<3sSX1H7rtn}YTo=e!@&Z(-|JH{;Af<xQ@EIyBl#<T^ zKtrgo01C*Wjj0t0_rew2#1@1AF#Q5p2ofIC1fB9OWW@Mfm`_TcFI8N77!@8bPm7Cv z{3upSCO3y6S1$?tqA;5EM8fkN*uUwTDV0ft1mf7lZN7f2W1>7God=_U-vD$0REQG^ zu7qKNApj2&9NZM%I}5-R=%O%iMI^vL`Db15o5-vLb!Y?$z7NpBGJzK)IuP22naJ`Y z6IP359q@)l9YWz~;E{cldQpYOn+mOk3Z0>f#mhox3Y7*<l}3@3CPkH3-&C3{R9gJ5 z#PC;HX;j%bRoU%U{w*j?8+?3?{!u;Z(GFjR`0eP=N3n}Mk54D{jsUdFLN%JVsNxX- zBZ0dE0dq8yBL=RN$;5&IJkfA4#oyi=(83jKDP##a!JtHc7>x>vqQWAGta67TFA&A1 z{mfM)Sg-<=`LMu)3iteXh1&u1e3iGhOKXS3R#7!m1@Qs9F`xLVKev|&oFwe<fZsP? zpKiMLeBtTd&&ToVH63V>7yz3h!5QuW%=K_K*+3`)P{PnlXaJFcS%oN|5`c0zGD$=N zEkHJ92IwGyK_tKd89cNAcmc3kpTdQt!aDxv=er8aPjY|Mr+?n4IzT<GcX;&O;aWO} ziD4bC8E!mv%bM=~bH=w#4BHkhoHbB@uA2e^VIVXLz1$&d8HFJcL-+Dt9F#;?O<_pI zz`ab1<0uSeL@*r!l1OBzK4g_W3^AwBSJFuEh|ADNO)qYe;vy7YCMrM=hO&#`&%Z@B z|3M_5M+<i@Ja`eA5XRf`)Zx+opwX(hrKeMMb3u!mq{+|MExv`Z+Ul)WO<G;{9(Wc% zpz+l(ph3!qDMD0;0vcoiK&_E<BL8K}DnKy+bh6!lXrQg{9-yKCwZK6l82r%+&}&WM zWol59!;~q{HeCRBzAjB^?ru$Tb1i@J!F=;B{LvltH<iwB0(tS`-5|D1$Qg#E<tWx` zG1~E3tGDz07f&C!+<#l>^LE>q4;4|tKuj!^{b!8X0**kz-W^y|R?i<oc6-){12Ftw z6f-dkjLfEM%9?wdCHd&x!ob}l8kJ39@by>O;HXdDjYUn&i@AOVV1tuR?g+3<F326n z<bh@rMVLGoz_qn?{{8d*`pZ_?cEadWfBkS0B%Cy^77TMq)9)v-xdbn?lFpSReSSmu zxy4p|tuy&`y>opAkeZWW{XoK{>*gQ80AL0o;3rIp!Y4RU!S0_$&r#~6zJyZsrR>Ez zvY<<+m}3r^r$_HJax?Mf#pxE2L%<#TZwe5Ad(WcOW2Mz=<I>yI2EOJ+zMR^v`HrkD zn8UR1{V@EVyGx&^Rs;eESdn_n1>s)+kaAexU9J8QzrOGG57%3JHA={?r@bqMAqll% z&R$_LE@5%|VOY4g8|_o*&4Pcy6EaNcF_(kyBcGVngr(;XCc5|)MGYn{4d%`a6bcTN zrG^zr-<>`2=avpAhIg**^{+gtvTqN$a`nTNtE9GuQd04UcMYX)<N~xcLO=lY19H$j z75)VcI(M%dR8s-@G_06dF)lYUW;QbIHv%rGm~9y8^X?oT4s@pXxA_#p^g0t7IJzA* z3TYbMA0FK~9fc|+-Lfxy#T+0}@OpKzzsW3K*(Xp-Bap&OS(2m7x!nEod!W~E7=(qb zqd}0Sa6PZFK2&z*b|%L`CTD3Jd*hH^!T8G4I32a|%#(3M%}}!3*cUT^u4zJUdE&zI zs6yk!1?@>iTE_$=bM)J32tYsK#2j=o-2JDdkZCE9-fx_7cCy%Hf`25Ca|gn(+#^H+ z%Vx5E!IoT&p3-mZ|IwDcq&g)XJ*wnCc}aUl?FK-Hp7Ac7QIMaxB{cSx+533dUvea_ zNMK6Of9jQ7NNQo5%Fhsy8%f#f&5{QpSK$G%EP*Bmcg&anX?PlhVFbIe?2zF0?RVkC zM7S3@Nhrx)D5$t}mdc!DVf=2}Yz9i4@n*^LN?T}1o2gkIy^uDVV=~6o7<l3m6E-sD zgv#!H>z{Do4<mwGsgM+n4{!x28uw0zXKu+8a7NRe<D1=?nN`L?b5H!EBk3F|saHSE z#?jK2yGxj$hitua;N7NoBj=ZQrJg7gp;PT~!w2tH&Xy<5gFDPW9?r~;3{0~402N6e zam)T6&X0kRU`HgNw!FZ20dPWslWM7m(S@4m8M)}mS3<Mg^0T}yv#-z6l;`V&no1av z`8O4^R(=$`B{e8t2GRi7$U-(02fc!P2SqSp0y{W`CN$nH!I9ugfu+mUPaM#Uh1wy| zCP>eX`NYO2CWowFsIXNe7=&eUIwbx%Bk}deIiZ3bg`R-{Xf1IvPWwYNBh(PH0n3DH zVm9iB$K`zhF)ZwT?Mh$!(#QBbZPL~U|NO{+iDWrI=ny*br$GzNH2h~_hgLFk$UFun zGN}PsFArw6w2}g%M>k8h*~?~Bqi4Q0Ouk(n<``ZT`kSOLpE*haeb|Gv1SV}p#eol@ z!HC)uV-Pcm-uZAXSsr*42xCNpqIVfeuI{bLjnPxauk(ym48}P|&okZ2#!wkpsCzEF zfFF*&V`VeDov2M=b3gzQM23td7TNi_Lhm@Ba8lWLv{xXIe-~1XI4}*LyKbEIKmk5G z`Y)$4VkvtUQDa9gqh;xHP$GB=37%lZl?J5lc77IL*>^z!rC8YMh4fcvgnkT!84c>z zS={iOIe*q57s&j+wm}8QxRyxepYH)TEij~y(qV_y{D+fhD4;fTi8*kgMkuTQ8h~KP zN<wvLzu(r&_|CpEvA49-dto-3XLsrH?i=l5F$HE>^qw`A5saa$!Z3M|HlcwqT=FyP zCgwMXtnjjF{$2P!k%@$U)<|R}WilyY3WXHlFEI38Npo-t$ft>}Q~@reuqH-g_QNc} zDRi|M#<vR4j8j%p6SMQ-A@-2<brZ8P?wyi7;7nnP0AL@mFfk-}pVG6_1Ys+M$(;xL z9Hz+P=&LbIK7jWnBEyTO5`E{)Ylo~I)DyLv5c_+8Q(!F^3IBp+>Q<<OQW$)mGx^Vh z0<cU)q*O)>ycNfoc-WT6@@c<`c{mW(OG`O+`Z%Uy59ku1=9x?uRDvU#sTKjbCj%sA z{vZJ*J_x2q0NrLM^Qr=K8LmK#1P8`_S)m{(y`TXvx<~Uye>0@;>xJ2-i!f$xQCnXI zJXlDZUn{dJSNggb*t>4iG=~ucj!gUDaWxhP651*(niNITDJk*~`Y50QCZlSSAoav@ z$Eu31L?<p8<2wb0u_CdVDo+V8lkKzaw(I*2FFi)e42$g!oLc>tJL3fGKfAmMT~x(n z+Jj=~#O74!T2q8%*h@<wS#;HCic&B{8HI4S%o6Ts)tV`8!{c-xMIxUlkaC5EEtHc` zxP-KG3Z*DPEV1AYJn0&ZRCy`0fUO>sc{{{+LOlO5fXRn~)@qVKAWz?8hY3;Lt&u84 zs1Kwnu@bhh+w{w;Q8&gz3DSdA6&~k7UGwEdtoo$ne1YEDTVC2wM`&ZfIJZh!tCxYk z=~fYm7I@G<XeU7og+j9`5eoHkSXqfuX~NA8mG~XS+a!RiAqdRC$A}^4baObTYJgr6 zjnk1QC^4MO5$aZw*@^%z%Sh*b8i=v&a6=Coe_5Pfm=#0Jl+Q%zvw>lm$rXT&H|#PO zn26^S_RYMV4EPRICQ0$vjU!{3Q32_anLs%nF!@>$FUdb%m#^d*SdM@(9?~%{GVUCd zIuYi?Xla1PwtKSV7D^mQDJ;*elfBp*a<xYNr7XVTO?iSy)X8f91?%gEDz>)v9xb-b zhi@(#us2^$g=;Cgfq0>QQyVY9qr~+WJbdg(K)Z8JM(LS)x1JT05$Tas8t*pvC=lZ) zRf6=;B+~gO^WwnV`Tkw!z^Y7Q+^X*jE7Wh%{ey+`hXeH|*uFYb7z&aVsJ!f_CkcEg z%nlBObyt7R^R9^a53w|ig7ex8?`*j6lx|nfU7n+-GU+fY5VK?$A^H<^grT1IOU%S7 zBgRv0Bo8mAhNttqflUNZ={vWH170GzFP=jFm1C?B3|T@=ox3q92EjfFKscLBX*}2! zb}|6-a}&h@5Or*che?oUp*fpkEe>$-u9~}b=dfq*;s!l2DctN*oDeOa0}aved$PI* zNaZy1<Txd{)fB;jem<*0$E{0V1bQk?p66v%ZV)#E(Q53<7t~}-t>9T*I<q&C{{D|& zpUUq4_$nPX?^V+gws@ysJA66(Q%Cs6hj5*U)dXps@F(B1xe6&@G=ZI)lNFm{7^Twv zVx);4LHUqAYX(R|=a`(NeZfX?Al#)2*iidNrcT$?so&R8!z{APbP!Zb`kKaN5}-vw zT)j=Ik$c9BK4*<VU(BZf*wd#BAPibwgMxD#ma}KUjWAbJ;q1&<n!z<Hhyx20r`#i4 z4p#4ec!~tTiDsx!1-d!LIn-fXEtiQy?t5k;6F;-zJ&AXZ7~^$8ja)d`>&!`RMm*n! zzZ6r{HcJj96Q+h6;S}(B!tLt~sO92e=EOcT#>|vwEgL{TPLDYZh<PO$XD&AY4W0_4 zv#xDqPQKf9;TDDtDVQdcvZgCU;sQ)fu7TbtFvtcp)!smF@meQ>*oO5%HxQLTFNdxY zP9a9P2@>-7v~s%|tiu&W=KHbTf5j=BExLUu?|H0;oX6#B4x(&2A5euLViSjRA`Xlt zb>D^s#%s_sF-DXFGMT-dBRwf#G5TZ~A`-_cs1JqG6buoZM6l{yL$nxW)s6s;vnu%y z&_Y9%H!*O5M@>Lf<}85wW%ds;I%loE&cWNn%(X2_&r*noaG_Jwp{u+RI{;Jz1G|hs zLth~9U;-xVPskVpM<rV5YJQw9YKl`_91xg5k6roY#>D8418IQbU?e1uqks`hyrKbe z!3y#kqYKx-0DP3L0xU}EXErM7#J`%EZU-lmOv$2+zXHl|;HXq?04$gYf?Nh<9m)xc zl?UQ}Rv<D8StCU3N<a4P>StAm6ArPE`BaVrdm|Zg6u?Z;K5?eEUc?x(yZ~x(pyW|B zz{tGrjkKnhMNY-YnK0&NoR!c}41f;11SdRT8zyVJ^Tsi3=G9}Uy!UJAr*<J!M-x<! zQ}_#JR_;S4p9nKB3LAg>Nbio>Mn3&fQ|gVTSj07Awahb_7%PQtZWAQ2!Aw->l#|F1 z<6s8n&y4e6UKcvJOAwapg2^iq=>pXIE_q``qISp(jx1ohZ}kKV!ESCt3<>0mOLlWu z=XJT%tC;>IiI3FB(BT~~<$#$4!|*~K>hS^^SR8BRDlcK4p3VT7a2tq$zP2PI3tuoz zk<jNp3_v-s){L=n)5R}+^e!ki7s?#n;)_Cn@M=nNmwWE0atilxA5QS-XgNS22#`1~ zh}pj-7JA?T3HGMpl5gkUg3&eQf-byCO`rhmkQ2v2P9WZm`F16^aB3&HJJpo}X4Kh( zXoie4Nw`>XC^>M-ph%L|g58`cm1vpMh&PfOYrKiu*g|cwZC!ot+yXI4rtE5ra64Y$ z2WC@NU(@HR{lY}JD3%TtC}RHD43Y<3bNJa+;Pv25{*YKp9UF4@X<xPT<Ibyw9!fL! zeWae<cT{0<pd^M_QfC@mk83*k1T1+3VuWy^uC6!cJEHifUStJ&v>2hEAr}jp7+ULU zZsV-}rFqR()tqOHPo1UP=7)bAwRogGZts&_<Q=}+bWtJ~w#}(%!H&}t-QbL#jJ3iV z$rREIaI_PPI_GNnL@PO~JEcw%z#}XjlRJ^v>i`MOnNZ8UsIv`Hh#)ZBWPI}U*0#Qy zN3k6Gb$RqWUbty>ye{O%`HR}YMYCG@`@x}}CiE|hgh|$sJ0b%=^!#0zN-yerS&grI z1q7W_*y*vT<->j`DACv4*0;BtXnA(jco_HT9_W!Ru@NYH?)(Yao&2&}C*=93zFj?g zjfqW*qq(S#&$nvAMs-6%?M1MF>+MxZ(DgU(AF>P)*rKYW{<NeE3j4zlS3eo7oaA%H znwOEDY%m3$j68n!O?dTm=fXTkwvxxUsykX>8)OVG3ArgdE5kNQVtwHEBUH6N`g5oV z&ks==o58?hvY&fn9(7Xtq@SmA{^8>#2R<Ua+rh}fh~;!cKxFTQ?BCjq=UfPn$G>`| z9~i#A8BI;OscIno{>S*2GpWAt?>4?#r<Px)pU>PpD!+0zAl+Mi8FOKn*7p97QpYdN zW?6<(I+tV+7U24qrm@<*fgQQd%It*%yOZRHhj2R%riXJKtVihOn7qStWOfNMhcfw` z0r}t@**8Xt<0_damdtCT%U4O}HzV)viNvT2Ok6^Pk8~-6WD(9T(FV@x3Oqj%4@<?* zq@Z&@)UjefN&|AX6L6MO()k{}tC}iD>s=R)x-LSxFKFQ|*>ox>cPklmE8BFdEWM?f zu9E9ak}0n_#W=gvE4wuX^`_tAg=#?(ek8s^yriEVcWndf30?yWw;e)1`p{(*Vqm|k zt(x0os;u*)qUTyqkC}USV_>&xQFjK3Q|q06%H(@12}3JRLk$}=*BnTgiWi#03modB zqtNsrU9sh8Cv2(htsdi}-kT*UVUs;>5`DLn`)&^#*iY(S-zVD~k*$?`y<_`)a{GJ* zFMFLzFnWW8=?TJth7KG05|zE^SQ34M93vHUJpyjKkg!PC7anWelK4W=pf9qy|9(%u zdFsWji0<n>eZMODa1BOyi2=M^??bIp)<V1(J$PdqpAco}u-`2ag4WGN(@Ht;%2e1x z5_&YbKjYMd%Ny7Hp+8%BFvno<NinCTo=NukfdXZd!d%n;-syw4QxLM?cmvk|C&^et z$I1b;yB;?VZ@7n(q(Gyav@_j@ZXV&eo5{7gLv@uy_02<18+4CfB|gYa&KD$|Y4$cL z^)`urc&Ys1mBEK*n`^I92kX&>1^epk7(6l}r(}3AKE&iss)-|KztcMtMiO2rB4ObJ zsan}gju|dug1RV3K6WO*`_F73YWRz|PCxVetMAMPhs}lruZ--Q*`%0_o(_Nh&`CG< zE+3IRRKZX?$2oIk{5*DKE~?>~0V%)-B;r6&(<Lk~jl5kNEDPzS*_W6|HuvVnNU<wa z-9JeP(;D8I>Uc<>fK>1QN*vv79^LC1-Jcpg*cknMH2MWHcE~yQRbuS(Y3_@=DiAd8 zlKb@^He)|y$4;2_kEfV^n+^U^?u$H!=cWfsE96KGi~xq<w>{U&js_iadz0mi*Gq^} z)cC59QTh($s;C6FOghvdo_U(WvPoe*rm#WB5nSW!lH(jI<L3;=Ic+W3<-yWKd?ntJ zD|4K$YMj5tlFJ*!H!?2NYbofD7df*Ofli1@PKc>Yh#O8w*iJ}#Oh|=JNG^*n#e!)^ zV>C_*NRsk#>e}l5hnf2w(!*f?xdzu<isG?cm5t>6hy<F7$E0fLq*~mhdfw#as!5HO zNzL9#t?5ba&B@Cx34w)#>lK#BG|)d^kkIN92s9L-f<(6Q%<^E7M4PvA;FW)H%;}g^ zAi;do#-h{;1x#bOY%NO(Rw~ohr36`&t*!aAO)uEqe_A%e)-lf3sb$)+ciL%W+Iia6 z=GYch2*z^FSPD&BY}%M}+1;MDIp1M*RUVTVWk|H4NHxf@&k@LeLW(Mr{-In}b$Xkr z&4FCAL6Wm~Rc3<?XG3gfLp^50LTAI{W<y#M42d9=4JbDTjn?Y2W40(ennex_F29?S zR5&NQJat{t_TNq%dkJy=b8-|y;xs{?I7drvaY#8Mq@EGvDRb#(V1<*pOlVA&<b1Zu ze2(FKE_6Qc*de21F0I2MDQ`~BdoJE%&Q9LeGL#^rG9wG6cy?TS2p#o4m{^lAa95)9 zJ2naMSg;f2dO%62&0DCeTBvVXc-p(rFul;Yx$x|G;W>1%iOab@wDe&U{0a{5b@eiR zDqg<|ue~vwurV0V>>$DGKscB$WtqkvPg^(6CyWqCaSllxb6r()Y5wy)wo4hd^I12R z`VSn^^IW<c=aTZ~6S<b&`_IWlOn0)(U`CuhM@CkLt?15-bWZhC3@+c~0FfIyW>-no zdCS)K7HUeD7yVOaEhTSkgWR1LX_8t~{J2HCTxTS4@oLK=FfvtU?l9KqNM>0|TqY!y zx(;c(^q4R8g}NMUu6&ML$}e>pid*?wHD6>n?FL;gQ^~ouX%0TN@5nVtwz;7fC8cE2 zGecfJjZS&6ov<Lu^%qJ7xTzp1Dp-|DXGDeAQK6nxSQr)lfNE)36@UY`^xE@f;>9^v zs8IvL>aH6dQ-lMX*kxzyXxouSM|s|*ovM|t-j#i>`Oot6iU1vd>neZWs=&;u;MS^; zonsb@V=v3cArH4lRrBALmqt~lZ*4k0KARu!wJP1GQXyCQBhU;{QkT(H4@hwOA8Qw3 z>k8cKm!#IAGar>Km}t?s=7-zyGU(R(l2`T3^;YAYg}3pqwOy}CI<Wt+>44gH%1@vB z>rC!-`QX3Wo#!%;=awxWV-&Vw9KT_bzhU~oU2tpVi_lu3q&t_<+Buz%x3uj%H_hez zP3VsM9?Lnc8yMff3f-sJDaUU*7~KwxPLQX_@JSBov8?bXE^7Y8;%!~ch1{-i+o6qC zzvj7iN4urn*x;|;@QUB^&fmKFW2L8MWoUE5!fs6xwrLT4YguBmG<L>e|5`;{wTwf* zU*2Y@r`LQ3JiQXGHz1?#iEm|D(a2w9dp3nowc~)zbP8>d^X3c8H}-Aked67fFxzpS z+wo!B3Gv?X58P==5uOKJw+g2>{Qf$RYJVIv|A_ItIl=YGTIv%l7q4reO5Pus^Z!&W zUse#mQ<%T=sM=@6$GB=LLD$5Y-Q+U0<5RneE3R=7`}vb4)cxFp74zyPkF6D-^zAqu zx`gyyCE{*<>+aKMyEXCKio|X2R_}r;m*J5miNCg`$6Lp7YZGxdJ0&b&9w2Al$)fzd z*VTJ(s`nK8_TJ6xb!`1d2TNJ_li)@LF~x&!%wQdwZ?lcAt68qN1-QnU`*!s@r2Eh3 zsW=LSxhK!~#h3XiZSU9h?NYc8#-;qnf9y}D?<Q{fnzXv-KyNkmd4A{xOKf=uz?P+| zt$vJ51WbLPX&dM<Ul<+Q1zqwlwb|WUH~PF`7eE)_Qw_Cu8n62}ZNCcjT^I5#|GeID z=2dC2yB+E_^m#5O-m~t)!8g?}-*vv!xcZw0xE!WAeh~WarOtGKjvaB@lxna!l}0M@ zT_(#7Z@~@$8maayA-oog>Y42-!|U{T-Rul7+gy*4cYA*jF!*fFW7Oe;=Z4n<?|LKu zBb^v!L{L5VR}QtW=ZwE{8V4clznK1A9guf<!Mc=Ib|+)S(WB*ymDEm>4My4z;6g#G zLX1Ju-^89P2j(#_61|`w?H{z<-ea9ZaC=^l-bce+zDRjz_%E3Rc(cKSp4xp?@QS%4 z9h}AZou;Jr_2T>8c+W39vvW=HuHVl#GM;^DW_3C>x*>UF^?MT^;4mtx_6^MwVlNsP zc|w3ueWIW%QXlbAt=Ha~uh0bD4yq5&XRPQySj{bUulwP5QN&;Q%2!36V@v5{E4AZG z@Z*WkM^kp&MxT9W!u&Hw9J*E3EXwZuUYU~S_6bU#5m4CC{`5r|Ym62-x}_HO8kl9Y z`Ubf;6}?F%J~*T=I6T<;Jm2?iFh8`fWB(uT;XC(tYo1UwM7Sc)&%5xS!6L^B7w^RV z2viLZnvM5Q8Sz}`41M+N`}p*r)yfAOodsbaUOBDwHqQzEV#?f&o`(t{Oj1{QGjF>F z96fAYq?z2blcn8$zqxe&`qrL@XYOWLm{<73-!LnYpLeByWvkr__KL}||CM*M$m)9N zgwBE8!|?31@Z?g*$j8AL?f;0=LFMwFawlcvd56Q?eF$oix5v=7{4j3xVceY)?Wnun zAHC?kR<5jk#&sSQET80TehYyAQW6Qx=lSzO`u+>!aHZ=(h2h&KM)O5pt9%7tN~*rx zSqViZnoJ!88Q!mUnro=|d0+PvdeiL0U~H55v;JD?V&a{B8ELlxDR+;R-&s{|UY{dt zU6221)#~D(mjyASKTk*CXZctDoRbckbiMCzWxnX~&ymLPQn(LFm{Ru1DyMn|RtOF~ zNsyKMO?&_8EOZo|?gFc>@#^04u<u#-e*Dd+<_9C~^FTqAsnnf@(Wor8v+SRzd;Nd+ zXa63I{iTQm=U)8IC32A9`DZF2s5m2drp<qL?D#R4gH_+1&Jc8kE$Yy_botBK>FmwG z5r!^!BJU+nN^Q_>c!n^V0FhZk3}z>q7pd26Ll})v*2)$;iIPkMa!#$8OW%4o3UX!0 zO%UrX$>9P|&k3#DTg;;+UK9IfIq@tMqV6&fdiw}9QE@kaD5(2L#-=v7+N#m_*mtVd zq*&^p$fkCz$t`s4olj2nqr!{MFKzF=+~AgX((@z}JcgFj`7Sw?%t@?qNDxvWpot22 z22DuKmr}_7FU$;xp`xDr99!ueE>a8ry#GsSn^JC^bHV?&^6pf<{i}e3-zxi)e~*^` zcs(<Lb7i?PS6U*Tbj7ixpdn`CYrUyL+6yd~Ii4-%`Q4~D)Xed-c%c(__veDj)2XLx zPbc{9{5=&sH0uc86t>a4zVGEzA9q<O)ww-rXJO>2n)uywAZ}icSWpo5mZpMg46_2d zkHE-D!j4|~xxIefkI%PVG(jlxL^M(Kfy3gJ?pg{cR*r<E(^Z)QN&?xq+IoVxW%}8J zN432;GGv!|azbYZXD7q-TKdZ@cb~LL2yM#$s*Kpx4wbO<vth`0n0w@LBih5P;G;7w zXhg;SM)+nGI}QX^EyTwk6XysShJAVgWvA<7+Pul_(vPEm|N8d^t+y-I#)crfN-hmh z7gHEyluNL5GlhaiA2#W;T_~jz%OPkdwaT#1qK`NuFs{=Q^>y`cWS=&wGE_xYxF&hz zJC)mhEciv1<S{vOd}CR}#lUNckL3z;xW%M;LZoM@{CYhul2JpxW!mY!eCwlS>tYQx z46!)5gAcN<*TY~ZXxM+yGJbc&O_sy7*l4z{#uM*UnPr#GKYj1n?`y_Fp@5(Q87km% z_`actQ8@cE+1M_#y|s!XL-MOr^+VD(F6vDP|9w9~>fqsAj1ZE{dgZ74Tg4AF`M0Nc zy(9D%6X{W(Tenj*N$P?@edbOwZ-=8LCel&Sc#)c^>GL8{Mng`!5e#bg6sB#RqmRi9 z74W<Uqw(EyJ>RRUW_sQ@nN>gka1d8=P6)o0`66C2O#k*>qZttM(y6|{aP*%uH7at( zh>e#M$sdrSAsvFO%oeLzdj5H+W&PdJg*2h4E0@h>-(xJ&j>!>;IvP7w#Sb)g9V+-0 z>aTgK$cEpJ`$uK{FRx?gndp36!Ggfg=}X0NuNkCS#FZBDf|M;j_3tB^G%c^++uzw# z<S+`-cT#2lqAIulGB;C1JnDTW<ff%1ww`d?PKB2`Z^~{%*Dd?EBj+Ao`Ahq?_x=j4 za#G|y$;pE&{$8)PU#3t`09THSrJudKto0YdwCXLc6w!dIcFV#c<%$k4CCVS<KZ>|K z$IcVax0W`#{4MHb_r3&CyHnmKRzDtk^xXBwkc9(t?ej*hUajX&rPCPuD}TRcuo-EI zapWW#h;3zrL>7LW9;#5N?@881*X1>Czar%u7+(?F$$R(%3{_#TCBXGk3BFX`%cb-% zRCfaXI;#J2<bW_O!kC>oysPJ+A&A4r*$_GV>`9tWypHeSFNz-b3to!ms_2-FlUh^# z<*cM%)?!jhb*5%c-;(rV#rAAe%4S=n!>}LL%vuL}VNPb@Z&RqefAn-|2@Z%f##<QX zttmY3#+t|<2VtQYnPIp1cvYH7!ZE3;w&yE0?m=Z%+P^O$*E|DP<J;FlW8E(rh4p7? zOJqn`8@5b1a^yTvm)4l98x4K=s`S&a#5rT*EBD0YY%8W1t>%6T%k3JZ{BSc3>5`E8 zdzdaxzPpI^O)~PhlmZ@nint^$JC5DGEkc`%W9aS`;}`6)+}!0$>-^cpn|{$X!9c={ z^O4R-Xil&hJKNK~%ROR6lWfHsF`BdYCW{x8lYVH53I8S~XehJiLUPJ;V1;EeT!D}2 zhm)@Ow+-cPf5JaM&G-_}rIjf&pq8FAoJ1tCCR#K%c>24R{k4R5@6h7a1P)L?g~7b7 zrr$4w$keGke`IpB8e6RYbx6EUQ6(sT^g#q_?RrMxWUpfDi*$2ojxR)dRTFMD<D<&$ zm#V!-fnnM!PxA6d^;#EOIQ;o0dHJ+Gk;)gOVi4Jx8b9pDUrn^Oo)@>|KT2%>h>Q(l zN#azlxNJ433zy74-(3^3X8+^$Q8BgBUGis5Pybd3Vx}cP^fz&N@9ylIjN=QMX{bca zQ#|AK2tD4vfeD(2poc`|-TH=?t|m)l85f^juE$q3ZN<{+U&m0NvodNaEo48*X2*-< zO3N=Qwv+E?^J!NT7d`&=J-W+M#}qVm;Zx?9qN_Qk=5}vhZ<QrC(Y_Ve{mq`UF0pER zyCe@0gIUt^o?qiowd+Y`!Y}jPRO_ER_=-FQTti;YCGM5RviAV=qP4n+eE&P=Xgot> z<_D~I+q)5d2$+gQ()pj-j1H^=IVb3rFsp;-=$~{{`s!9foR6n{$}C3hWL=T9Q>jeT z-8gKR8kxmTuS?|@&x93N@yCl+qdsxxM*3ErEIhFSzm<(K{F!~;F6j0Rxpl$dqDhtb z7>;-Z)ChHpy;LW(M(qZ@-XU)(0Ra)^bfY&!=^^4M`kZCxI8*xasYL46&}AQk>rVIB z+!R29?-22ta(Q((?`0JFt1Q&T@7#L(q40~8`Uj^`e_j4c8o;)a^>Tje_0pCqOT2H4 zS@C5P7tI_?lmD78TnlRNo`VD>2AyonX7QE;pDZQ$)X#~vSx+t-hNiPW2{e$q#jgGt z!ZU?r6lf=(d*P~{%99=>)UUyj1@ubNkJFoam$Roj&<$Cq->s?DWxhjCXRiEHp_nA0 z>6aKYl#uCh9<|0A(WEGmU!EJ~<RdfwxduGu*NWFWGy}U@FFEY_H<b_YbxQnv{pwlh z=+r#77(&;%V5eLNQgfffayAW?ROicouyPW1lz0!7z)`G@MOieke;l-k5!YJhr@ieG zxDb(W6U=gTfXohIXE0E>wVFC`BBmvrbj`c`TM_0LKW&Y4j%adQ=vSe!&bQU{dkwd^ zE`VZAnyGFV%@Zz2xtZ=PuclL;-xhM^HM}}Zg5~D8u>>U23B5DpERPap@<M!<`LI9s z(ssHzKO3p%BcoQ@>tiu;bw#JC^Y~!>o+`H?#5r8^Sv$CmGRWZcke=^(>s#%QLnETW z;vJkK;1Vp#XzdpH{B7GY-ouAHQB--bI5QH&iWR3UNNnf|17IlwFzBkVREVCmi|bG? zKChCjg%jS9q<etF^I`N9NpxBRbXtD;m$BV417Invo>VhY!bDG;o=Rm92B~&+F?6ZM z5|sz^H6>z{F<sm?x?Gqp@mS$Y?R0wwuDlI2kie-kF9pYg*5!St%bMlrSeY#=zl^RL zSs37$3bM7o40EqVzZxb_%k%!M67|3L@k$du;44f?dnnG$0cp#ajwmqA8{6C#xYqkP z`tt1i>18dU8Oc@76s{#CeOJ0i$w&Dm<_Y2;7nY?HD{fOR>8d9|De8A4NQdZ&+hF;J zbzu*LC6V_0u~<zK-Ni!!B$6N<1>TBY3p?f&r3cr^5HcC2oA}n6?s1IP36AdIMUL<y zC142?eZ><h53?KlR<}3?%$<wp&jff-c+P#@>&TB5$mM4FQro!k$$QMaeMvACK**(( zzk1zq#He&LpRswGxo6cFRA6FAOTUquJHDOA;(zY+ms`Pzh&m{1dF0$*lwIfzdlC17 z^h<)NDuUgYT)L<KaZkhyt=w4{sZx=8G9g|3Br$<NuyoXltcgBf30c*JPAfM?Za|Nz z9M4ios+9qQJiB<7@M+OtzF4v_#cBP_>G>Im4@Ks6A&4>Si9qziTF!~kgGD5|#@O?u zp=N?px?8J)mJDEt6Qr~sS=J1{Z4NpYtII3F@NIC^yb}NDg)sV8K_QXl3zmxyI(C#L z?qG@I^AzE)uW%h5KRS&OaLEWDB8)o(o(wwQsQdW4G<QOxp!3Z3&+zgev+OhWTcW~i z8X&&Z<vB@o8NiK|P^9S@##c*rBAHeH85mgRAM1^{BqE5A9;Ulg3+64+6-%TlA9hK* ztPJ{e0lr<*5_tY40wR+vHLxLKg6G|KlI0}}<jxA8;>~_kN(bT*W(3|`UFk#Jv>OC5 zC#kGsy!qW4;Um28AzrJ|UI=3;NL~7@t7n%jA=yrMDYxt&^wWvV<V2IBPR|uF<bHoK z{{@k9Bno4ru*5_a^F@Aiz2Gf4XeO}LHv-|GKL+%NpSTgOKQyyY*>St-V}1K~#i`+z zx~=ER!E%Z`Sj?qM$bpPNfdnc1>*kf-qbS2?RLKD_Mhe8fgy+MR$u`IEO_9Y@yHGZI zynbE$fi!n%1u(Ox-k=It`ZH)P56#+y6vyfb^Wvo<x|jqB{1{yeof<O@3Grs~xkS*v zzX&lwFy986^QcHlj*$5z2O~q^DkL!x@yQyG+&pGzJ!BiXxID-C$RS-p32}iavMhp5 zvVp+aK>k{V7r@}z>G7PzD(`!P*92M4`-`^fKE|~&+~W0)nezD7Bpy?}`(1sTJL(#C zEp;^WCe!qj_~ZVC&DGrlQP$q&D_yznD>v>%N^87!pvjaVBM5vFWQi!Bk_m6gY$-{C zr_VE_ROOcRGdx18O9K(Z*$z_H0`muwh1&_d5}=}NT~sqxI@5(ol^|uJC#BFOjiG^f z62bhbcxfzQFjP;_0MC(07L6bXn&}EgluO9!NuTQSW|Acpx`Mz2eu;UW0o_K&*{9ky z92*Nv19&84?<{jPvT;_hvL??w3HsMn5&h32@KFyylG|mxy!c^PQSLD8vmQg2s2<x; zw?%`S@|GejnZy4@gPL6u>xJd1%&eSf6ccj~^9D29u=pEFp7zY5>1pCK4u-_Pq7u^| z&-f~n0v2eO1;tKvk%D-xc9f;3p10l}lP5tUgdpQrDdi59!C(bV^gp%4@bHpR5qQZ; zy}NI~e7s}{<bQnox&c>-QVP#DZOb6sUF?GYv`9!Z$BMfX#MQf&#b|m`h2T3*65=7% zkclF3j4n?q`5z+7Pp=z1;}mwxFIb3X-2k{w$q_!YPklZ`J|Umu#S10w+pvBS?7=@F zJj!dAX0Pv(mGk3r@x3BCizvh)5<#{*LmLfzW4?=vfs67CjmJ3rH>CWp&SB~yfYnHh zeTH~9E?ULRaciq$5kDuk%7pE(L0fowbmn;ca1hsXH{ixfn{|msb%`K0U%ioEYQ+wE z5X9Oc;ux&<aEx-ZKEFYivYEa#4$pInmvbSY1XtKk$<kOo86sGw{pqGDab4$vOd=S` z8_1*>DCI&JOe-18+VZv&^L8p1d$%U6T*GOzE)doA^o&*{M%5Kg1TB2lMIzRpp5b{U zKs<929rd~#E{>#Fzv#vSfhAqRxdH*fo6$jF$y$P}ncT!`EQ>=0qLR#=i)MI-=I{e? zzl(FJWU=ebZsq#mD;a-B?wUIWcOvWkOZaZf0JA0qH=^uMRLK!6`XItkus~*d=EQpY z_w;Q&PYH8F(&qKQl7he_5%i;JkX^E|v`M<_DO2lRDQuVAhAu}Yo~gD=!z4yl86@o< z7?AHGO(e+F?n(QBnG5u!LI^owdeScyl&(`5|Lc-;2VYY>gou4-o^8yza0o8&G*m5P zdWq-k0ZAbUeS;2Z_rM{rN9GI!-hF<qO8Xus8YmLl6={fPDcob93;6F1*$O&*vrdk` zSod3pL64P;`XULDieouJ^PbMylB=4~%Oc@<NMjSerKEAOmqv6$Wn>^3vh~|YQJZmA zNNOQoDvf3O`RySQY2$473AUsnR1K6UQKZOr?Y}|Mr{|V*RlJm#A_@Nj?T~3VS3`^} z3XfV6=ELY3ODQS6EthV_D!;vT{(_Rt#qZWPRqWJWt-lQ198qxCQ;;-T6RY*4OMj+c zzMa}pl*vU9G5FfWPv+3_62Xy$Pe8)^x`Om%kq|rsudV=djc}#3P&<edOBQk%WYq<; zTj|{_HRP9*<BOnvvD%@JB|B3u@sep)xXuxSl+>6dbJ3^6Mg>30reK;8A<0Ma#7D~p zn7fka`LDiTW;w1{0&N8E+`0Aji^tI1^It*|8hZm-3sQx%yb6vo5d?|aY8j%Si6>Ul zAY3x4OPW`g`DTT<VDR1lRBUqeeDA77#Iz~?r(&=4eZB1G+c%Ap97LdKNj$*iX~%+C zB8a}0e6Elz%-JQRuo+?0z>}$~vj_;H34Hr)>{_}U5+LDWP=+s==ObBZ1(fCP>y)@@ zbw`)4FwOaHYZEYryOoJ_9y44wbuDU5dLKVr8RJWvpKSecr&P%AzCpQme>L{ypCIet zmZSHUMOE`t9<3@=XcNdvLh>c;uH;L9lms~#+#23}OYCS{E3iw(EJiMha6Vs8IYp00 z3nV!8KLB|^hQIK3hc}pqIheO%d2==7J}y{S-m}gqXpZgx0^qL=f=>zpAQ(Xqzkqt( z!B62qAnZX+{=pvvaTM6@5>tT~ynqx)0Ts9a5!k>ZFu@h5!V*O4DWL^RY=KL7SOf9O zLx-ao0m0l94;xXyh-=@8pZaR}gB__uM#14=vM)&0<A%vlVz!@3^_Bgyw2pf%Wd>{5 zCLD@BqA8aqX$~OC9lMi$LLgW{7f?6KwSzn8tt<$`ECls<cXugJ_a~4-C#0sgi#fQ5 zdw7?5S6ki;tGDQmE&xYD1G2m1G5=mCoNW%M!6eWciuOTOX5R6w0U5kN8@zxKq=6Io zfD<r*5geiHy?_@e!3YRJ5@=&t?5Cz)6DwKO^JSGp3s0zv;cJyTs(-v{DDsN4z+3fE ztdn#lTQd9A5OUr4zVT3G{%WraqmQSP|285i+w{o2;Ja$V+#d6JXTmHTCna#g=p_Ov z2!k+GwRfwgcQ<`2KD}yQb<;cj(@VX$XFa$x^9*M$<aPoJW&+hi_2uC^=EcEH)F&Cl z3rm>6DvVy}#eL}6vJG?rCzOF${_Z18!4dqmB^ZH1n*bPS-qG2F#H(e0wUYLxiB^4h zoQ?WL?+wULercfgio5#u#Q%tK#5kg9sQlV`Z5N5xgs5QEA57m5*xJ0<j<RPCd683M zCm@1JRCD8|CQza=7d*lz2m{?J^S7twcz<`*yW)3u_thW&@N2#DZ?)AkcPY&6My|oN z_CXvNzDbmU8IPjef8IP$0wj>xPe>|#ox&;b!YQOID2zfr6KNcbjv<tR6uf~Aa6yu} z!4#N42~_WxSz%N$5I}4Zn1vt~EK?9dQRsxBlO{`+ASqHL2#_8;cGRdbBL)l>Dky;Y z_fOwGlP6K8RJoF6OP4QU#*{geW=)$napu%H)8D;+^k`6E!2(8%88mL};L!s}kcmhj zHfg933PP(`2x<|y<^N09FJQoeDKplLnKNh6rb)wwEgLs)-^!6Yhb|qvb@1ZFgGWza zK79Q60UX#*Awq=<AySNJ5u?V9AV+Q_iE<`MnKEJW6e!FdDqLEX`m_cTC28xtC{x45 z(;rW-Nx>#H`?aUpw{hn#wVQWu-@k$H&Yk;pC*!0{%{GM!RV!4cG%;Gkh*6v~X118& zL@D3AeBb9uOBRQ%n>ckq$>PQ9+Im^<Gefq#sPUpc_xr}VbLUSIE_Q@agN{1vk^>Ju z457k^H-y;3iyTUbaE>$FVj~T-%F1x8u)y+aD}u5x$f_x*VyKCSB9f@0i*~qSqmDib z=^uae@n@$SasSLw#~pd>(Z`+inXw3=h%yQ(rI-rBDX5l^iXnwayb7x<v=YcG4#z4Z zL$uCPYpu52f=ezr=$d1|0rT36FTVyOY!E*(5k!zi5>spuI~jp2&&VpnOcPBq`{WHN zHlad|O~{Z&(Q-&>#flub5G9jKO0lgr+-%b=xJ^0jlsDRJGey+pT5(R3H5OTekF&Pm zq>Oy(0dF2i5-~3kP<WYUJz;nOwYW|+p>MiHAS<K~Mif!3kU^L&q!7Xa8$=Molu*J8 zJMPG<4m{E@;}0*C=wc5kau^}PFyeRv2_dLZ%R&sZ+z<?}z7R-@dkZ=!At)Mh2qGj@ zv<RacX#e17D3C<z$;KZUZrI_6A&%IllKv@!0u_opss<#RdMc`^pp-HzE4k__ta!~b zE3Gff6LYRI>(X}HzWfrbO+Th>qzomjVB-?U9Mi<MOo*j!vdS9qQ<K>KL?enf;&5kH zUS{#66HhjAg_Yqn?Tr*pMJ>gY-9{CA)UZDt8#qyCF=dumVnM}|M%Fm>j55whV;=AF zkw%_4^i$+LVWtsAn6r1Y8rViOVcc=dB*R2cJsCm7F=d@)R&!_r^W=>=_|Ri7ywb=a z2P*!E1CRZVh%g5;<PakSF^o843oOdGFy(kT^w3@q_1%|W6aNjEMS?l<2;mt^lGyp@ zq5qFw`j~3`$Bm0KreWiyIxd1qC;1H-A%m!_vgEI@)Uqrty=)7vxL!8XE;P4Yljgqy z8*C6l25CeMBSi58DSV<3ifBY9<WL1I+@TTF$rEKRa~aH#LJ*nwgeE{y33t>Z6Nk&h z)n?O)OvvUop4!yeP?$or`G!=jh(#@80i88;!VP8s!*;-v4?}>W4t(H+;if?gQ9UO) zwK1aNjDy5K83$N^!VCl{6PY|YhCX+4R^~WI7(57K5P#9be*QoPBRIkcTzJD4ssIHr z@L>;ca6=m2-~}TH!3Iiz5E96cAv0(xOJVWd7PJ7o5tWE|DWZtLT2wF?Ew3ljbN}Qc zAsNXXSr2<f(HO^+<h>?2$q7`6(iF%?B`aMCEGSc1m)r#=m%Yp`W=hjuXr_n1%o1AC zDugD~AcQAS;ShgNgd#o>2P5R+4OIBVA1;xJq$zDuu6V-`tdNXVNP|(RAcfGlRzef< z28CiXn+j7%Hs`dW7PN>(DH@}PGu)6n-KmG12;m9C2_qM?7-uPBQz?AL1~!*EVr{O* zL?&vYiBE*0BqZZNDlTSOZz9ZKW*Is@;H3~_sMZ+5AO$p3076pGgInYfhkB{O1~wSM z6KWR*J@T$YUD*mCLnI>MnFvJ^IppzPbTAq1;~tXq=}&<gRG;ACVi=RbCI7kS6iqhi zNuCthy+&!WQj%p$s8r?q#so9G&<~dP!(aZ~v@AprVi9$4Lm+~MEJqac4@PJMCK!>4 zKP~Z3nV1C`$WV?)cmW!wu+%@hwl;8{?K!9@1rfn%PZ!q07NuZ>B>He2GwiK9rvQZ? zI$?`w7%mp(H0*E2rnXOI(^vl#=s@R+8P!5Cp$@DfA~MIUEDDBZc&LLPxWykTC}9LP zhyn=2a0fTY0WNP~1B8_D0=BHLEG(UuOMjOy;SKLZ|C-2(Fj9kpdE_Gv5XnB87gX_% zm%I(L$3KQa0TB%4s597JlDr3%6M?KMA`|8L&?gqEt`C(g3lsccCjUQeb=5Djyjimr zLmx&ER5Fn9gdLu+hfgRXGX!m-Crr_aH>iRb)(XWZl31zX1ZS`+WX=#zd^Whn!WOou zMJI^G26lc&8t|}>ERcZ=VVE-(&N=Ki3yZk2f%a?o6i#gT`A;LBwuw%B;?Wv7MJmz< zw$7R@ZE04&R)XOSraJ-}+`tC8yl)SB_`(_7z@?SS>$%XqS0H6dqJ<RFrYqV(B4?mH z6*S-s|LAFX0Uc;T*Q6)^U<VA=%L1dg_s;NT5>uP{Nl;FyN~D}BRoUmR_lYUM^Lu41 z@%L3fG^<VuR%nAE(+N^^f^l*M*40W8i88FC9iA{mB`lR>ZU2H+Z6!uAb5blS7sAaJ zvCsr21hGeHw4<`TC`2i6(TiN<g2gdh&aZ)u*lhcHg}=d+l9znixjHd|4U{5vsGOMC zIy8S??2DQR)R#c0ZVq=C6LH_77CEp*Ef{KUA6r^4d*Lh2g!ETLt_uVnWOutC*|RD9 zJZOneoZ>t+Gz$`KNu(rosgUlZ_&}MJN?SThRkdo%R!JtU>cxHrHgGKm;VeAusli5T z9AxHdoTZfl6lZXUJUU^`<=iGyvjJNQvz_!5ub8pMZbY)n&<<wL;}o)J1S@nQ3>fzK z+J$Y7(!suMV1x6UqV>(U!Hq;Fr#6a{Irrr-x2!C>TmN+Mu0w$5Fs4m|so!eeBb)yS z)0kSt;MJ|O!ds->JP$<#A|OY^D;{~t`_w1*z(EIw0s|RnFDZ_Oh{v5ezL7;Wed;@9 z`~JJiGR+T7YPug--9&0THHPL>Y{YFWtaD&_q7<j#gx@;x2_zSN*DM??*q4I}R=m&_ zx$p!gF0syK?@bn%(1a~|p^IW$JNZd>PT0X8{%sG|+h|YwuTX0lDAs&243#_Q=w5fc zWNUtO(fj-O-S@L-2;k4%3cf;QkcNk*5blr$reI`%yE-5S=mGL3?*SoDVkpL9GViF4 z1ip&k^EfH=CT;XcuH>o;^)_v|RBrXS%6>#GTK_ah<`{$aCI^B(XbYSG3`ju|bWdzR z;rD<J#At(SjLhs*$T>(Q+u(+=cn%ZfpbVs8750V~WT6vk0U2_E7GS7Utguvi><YE8 zRK%|fkq@y{2sq5ow3rN7EW@B`&VevTw%~7;Vrg_*31;pOF505+Qs(afPv8b_@Men6 z60QgEECGjt0-WF<z$*d~F%f+vNZg<UR6qqZ?<hL2d%g#J#K$18!h9@Eztktw+-K9W zYV`(;FH$h}5Ud4_MlvKw6H0*#)Zh@3;FvJuH4Fg^YD^PAjQ945g}ABghKR71gB4(? z#bf~#3gHYWfjj0Q8P1^*Vqq7kt+U3775}KQ8n^Hou`wIJ&kL2V#LBO<(hjwp%ra1| zfvBv?*brLiZgld34&-nS-y;7m#NYalUjDBj2yf2(@TL+k0hNaW>c9aNaUcoOCeEu6 zib~NWaR-uQNut6M>uY?bWGg-p(^lpau_}ICiRDl*i)3&1XpT=-(G!%w4#a>8K1>lv z;T42n6u7_(QsIL><%GNmoKT?%ZDAH70TdFU48UM->Y*M)!xna-*leK{+@?8(ZN-?f zDV_2un^GIOu^X=~48L&<k4T_aiySG(wa&4j-sG!7=iS(mK<W=3>Ci&-PqF~c9swzk z0&uz-qNXUq&USzX{4qv!;UDawApiaHFI%F}x}oug!bp;W2Pp9&L1siKjUuIr6Fc!D zF_HvXX(Q{WBeUp=T9EcavQLad5iS7^qQDA70s2}Y5LDq2pn(&(AQeEU$a>=!kxo=z zf%#?u6i&enz(DHep&n$x6IwwRbO9D_vK8K@$KGc7pmI5xvpJ!13%xJ=yip9nkqiq8 z4O`1AVJjUUs<v!PTh1i!(6SEK^51#~x_&2k4DR3p#v&3aFGWBF*nuDLVPOFCKK;@s z*a71T^QhiSsUB?uBQoUf>wGTF^gI#e;HLxyjOExw)K*YgP%+9N0|s-B_eh~_I$<}Y z;SuZrT)4m$KH)WzL$t!CZ2yGqg;-1&E&&wWfD?Xl9?GE{Isq11tk`H_oR)GaowG-M zv`4RzIkr*!tdcsDY{}Hl49}1&&+RL*2=>OZ?!J>i%H-bgPafxS|L`#2^bju9Qy={W zU=9iK2u2VwZU*duAN~wK*)$P-f*xQ1^N7MfF{$GOlrb~WG114APAP9vDI*!w(;T!f zIA?$MCleH*)Lc*`{e;Op;ZHu{6dnN*&f%IEp%seG$hc`#l+PBH&lFDK6w2TWq%J6J z!xpq}`K*vBhmA*>lNMk#R%LZoX;oH#bUC$gNU4(S&hAJ73jMCrpjgYb+>hPbEtW*5 z9o<np$1E-7ksk99J^$e>c;svVA3{vAD<kky0k^;q+w@x>kVf|5AEtmvib8wpv=SHd zDn<{#rb>@a&%ZKq^<rjF0YlWdND>Gk3<4n&3Lzvbv@)FNh*qr=W+4$)p&X#&Ym$R( z7}jj6vBzW~5fUK{l5uagVH!jO7d({<Z}KML##LXnR;jQSO!j0^wwy?IWoPwPgOo_a zX;Z2*Np)_u-VWW?@S*bO4X4x{3j`j)L@oVoO9O5X3l2<+=cX7AMp%FX7(pPxl}G$x zYN@trt@diMHfyzZYq_>-z4mLt7QFs}4ID9Jwg)kn<a^e&0}J#6;Z-t6Fn(AsO$_X2 z5JM0YA(!Cb2>;k1SX8l3axRH1#W=R%5q^jjU*iW$p&FG>7;qC3zM?nh0Uk=BMr}d) zVxet{GjoM;IZIY$&8cKzHDyn>#Te^GQI~X8*JMW*bZr$#S4<1LkXOBCX4lTi+D?jI z>q*s-XO(qX$CEs@)I9x2TKTYA=Q3%tl?G^FkvhN`{0wZRcY3L}dad_sqxMI9;(9Pf zA<q^FfFQm;CekFbT`Q8m;1*C}<}Mr*fBN972*Juc;WI)(3e><6E<q7A0S4u2iA*b0 zR^c2z3l%<r8kvI?ZZlNP;0qL`H)UZKO2HOzA#S`bZn7|BF}NvLR&`CcbZ;~lP&b4{ zc!XW-bpKPfWq%Ypy)b5L*H-~b99JuMaTXo9(+&FqJmoO&Mo@T%xBvVvJ-^gimDfFy zCk7ag1>QkTvv-NftI%?x0Ul8yFR&>b67(+712+*t6EyWgu|f6XLHQt272!={4iOZA z5!4_FsK5>~Arb;sX#m9(MhLKYj}npr5<)dp@fb#{pn>NB8>XRvVc`{oH0dsQN1YOM z6`6ENIE1GSgg^L^C3%u3x%o&~bz}8bvrt#TkA?SXW|K6vgq3oflsj!EbnK2ws}$dy zRcL!STJP~_g}4CiO!17E1v&r-&MUl_xR)a-NYtV6Fa`#W;?6iuZJVmTLaEZWfJ5FD zegD0LWn9Jt+1K^@LJ;(T5zb%<sz47|kP#vQ`oeinBuKSJh!n_RL_tV4HuM~lAt-~= zJAzUcGVBv@!GKR}7KGHE;)b7l?4MU`R#&%?Ta1z^x%mt_p%dDY8~KE5wK-+ClZ$k; zTp0Zbs;-zc%1SvMZ8%xCYFX{CS>y3pq17k3bRdqm@C=C`H^NLifDNG5mv7>FX}YFu z`ljvkA8J5OHSb6mvSX0><CM8EN$+GLv%e-Y6z8^n9#jzi;0>Mt5I$owfW|Qz0TVEx z?U*SO5Ty&EKqZGm7YUevZQ&DOffZokuwn=m^!e*p0drjl3tQDGY4vm)S)uVdumANL zuSb}%T=#WxHKL`nn|f8rZdbLSOr!54X9eSw$x>NETBJvME!onfi#L{oxR7WW@ml&H zJ0W^;I<!T5w5?XAb)wL?w@7>%Z9RsQI*Bnw&M}SpsQpx$RnL`9(5nRD4kRHA!i5U* zpmI`?Q5#j~P{DqSK??q06DG*$jPKgSrjUg+t~Xg^13FeYn1uJ5uSa;hr>&qDT7*gW za{=2auW)vU?Cj1@?bvQu(QUDLH=-VUtKLzhd00!G%XhpKl&Y1wKJO1PLXkY8@gDCU z?9;Rn{9$||nB&uuHbyBD(~9kD<njvy`!tofxCGhvi@k~urUk96zzRM=68|CroI4Yt zE@O$9s1)o#4W8f$SV6?T1~$p2>$*=zw=jd7Qe_$0k-huJfjr11xuM6K$DYz-2iude z5?GbA+(<dyo@MT8s~zhb-zvnF@w+YmNV@hVc@1fKljlt7fggA|!OdK1gTx-<v@jQP zDKaUjFOhuobWcl;OZ+scHJm^OwQixM5EkJw$f_KZ#s+5rGp^<}CM6YG+%+?yVR^0l zrW?nxusK`TWVKt!F+J0_8+9Q$bx{^p0~^W1j<8!e9Mezz5K6JF$XJi{-5@)%_YTX~ z%(C?xAN!C!6OQ2wrfH{uB+mTTd*mMa;S9`m^WF=n$5*J!w{0sN1pl{qUh8$wLv7Uh z;EMWyF(kog_GC{yhYCF56EGp5GPKb%OgNq!7{hK=m$RHuHiQ{V)AL$5<$d1a9n<^z zWR2Xstq^7rr?A0IpfFm7&k-HfaUEZsS+5k!CF}3b^B&_8d5K3%DS|~5PkA~(4x$&> zUxKtbzT>agC!C>dHSPwuCw$?&DwLTZUdnCJx3(3O1VwSrb@n4U^RbTRG8*9%%-{&D z;0aOz6Gq4s1SQvM(!|0~-Jdda{o1a(JJaX=>7hRArGDz49^S>9bu*b&_kD%aTR8q* z+?;5C5lYJ7yP<S;EXy(u5&lZ`kN@Q5kM_F{s|(?>^+lAY0sn>}<2`=w`95p=;qL)I z@CASH3BT|S|L_q%@fCmZ3!fkOat78524FyYYQW8vD%n8}3lvBbrOLw1!d+~eGRfow z_adTTPTeeLxRWMn8YdGD!3ZYd4}>5lGoclPX$;uF5tPFhy{?6>5ukV6gSA`xh`*qT z|M;bT7nFbbnSc3v;rXAx`K5pQslWN99#yfw__ZJViJUoINGZ>I{7!Tx!}^7rOqtS< zI+P{mSY4J<nM%ooxL7&Nyu|P7(ap2~6XpI|RU`-if(MTsHD<_w!9s+Jcl_}6dk8V2 z#EBFuTD*ucqsEOB_j&vXGNj0nBukn+i87^1lK1+Zq5r@F1`HWAYV6<v1W1q~NR}*V z;=~D*p;Mqt!Ga}=mMu)bI0XZ>j8rpJ&73)tCJmddZo0aW19lD_I%4b8!GlMST0VZ- zx*b#qk=#X$7&W>pNm3?FnfiVrBgD%lN0&%BqT=e4kx-^cl`3T_a%5DKQCYU!DzoNT zoIA&&MXQ!*(Y8vP&V@R)>eZ}K>v|0v_O98qYumn!J2&pwx?21GZQ9mo(4LFO(tJ5N zWyz8sJ0}I*ll1A*J6YF+y>H&Tbr&s?TPS=Xw{F#<HH)6?9I$e{y4lJm>(w(=rIvvT z#_1QPTeA4aGDUzx1r?M}NEA^-5I_uc0}V68!2bdZ9qe$=Kl-eMVTKxR$YF;beh6ZS z`}k9#H65rBQw%fM#6u4{@#GUwLJ<|<QU39_#Z&m%XVrXJ!RH=(bCgAgS!u1s2U~)) zH3%W$A>v(KjYu+OUVCAuNhhRqVv2R9WRi*)V<@qQE7CDnnR1tD){1eUfks+zrTx}g zZ@KWsn{KxC!e^g;_Nix}wBh+0orcO;%bT<q#~GVyCdZs}k3~lvb=F<V*LHU`(%pA* zAu<Sge(<4|9_N{*-g;np1)qHL(PxHz_&LR&7XQ^)6chwDu>=waD%it7HPCPniWHdf z&pje8%WSjGJ`1ge6~2>DOfbwq!woII=>O|a1P*0XfJtewR8u<gNR^N9u@PigWEE*- zsY#B?haiR6`(%`x=4B<8S$blfbfomP$scIIQHv~)LB`ypm}SPOqNCLkoS~}`nx}4m zZp?AV9(Oz_#&%k~T4@vyM;xQaW#%xNrbt=}rIlWK9bcJf%3Y_36f#JtZjowUdhZU| zo_npPF<*UBL8Tvm{$+twjROY7tFH+H5iCIu!k~f*4Um#-v|^7<cG+f=^bZ&mAOwSo zHud0Q5Z%f+W4K2p#h-p(M1`)8TCv-%97B$U9$HAY#nvEqC;}dobnV;MUNlojiYL%* zY050Kc+#9?4x`cv=n;oDnw+WGLjN+JyS%3H$GrgaIxw=&PCM+b-<}(xB$teOF2W_6 zvT<yNuAIv-$1L#7)n$h>r*$#n-OfG#oMg~K6TK>{@gaRxRk1FeAFW&1YAb*OPVGb! zJte51KsOYGP(mWG6ZYBm-;aO(Cz1FMFfgUKqMO7GM&1evjqawDrRZlzQ%ToVe#8~8 zgk?x#ftTTu#FkMBLK0Gd!W$$J7wFl=F8#t%z$$e)=u8StlyMlF+*G=X?JhN{yG<{4 z@iE!Ou68`^p$~tk!`A_dPqq=+$aZHk(Y#4z$a$3Uo@2SnS*kjn$j;5Ev?=F#if2Eg zm#I#bD(o3;dr4E;eZsdNrvKOqYEqjTuX=U0tPSfR5uyMV>ZiXv>T!?Jst`S@)wTd` zYbQM^Ah>FT6#tY<M|>-T1F`Zq_jF}~Wiir`G8n2s@PP_>P=gUZ5s2s6WlDW9;iW1i zFcmJWVUHS~o8T0u8PZTTtE<frJElV*>T;L7wB4U{ql?wWMwY)r*`kC;yp}a*Vb77G zrLLnLer1tU-U-k2$WtmXj)j6n)1Iqf^}REqQH|v@U#@m#pg8W}eGiI|3Mjw~Jo0g# z^sFa_($;|p#egO^*uek`Nw-6aD=Aqp*SQ+#w@6Bml5;5BCEX$jK?LFrHb8?A?BKk8 z>E%jUI%O)O=p2`QZvQi{gp&*{MyNgA&`-Ve;V@nb)0oP1ro(6{?L4L@-jEDYz~js@ z8x^`_7B5ngk{K0gX0ztqC3?~m70}RvhxAZTRYuDS_qrF(S&46rY|NFe()UIr1R)4n zYfw8SR0Dfh$ewI%Yg_p@jQ<6aMK6L;6J#V%1TK=1_Hks7AQ{0)PVilYTMK#k&<8{? zVhm6C!yh7{h%9b2OC9Y5DnS}j&zZu75PM||dzZS5(Pm>dm0e9|N7K}*cD1JkB2IUs z(?ba-iHh=!qgu9{mlf5S)4^2au9!vdY|&@fG*49PuuX1u^JuT4imaHH#_`?id|$mQ z9E*T8VbLH4@&BVh8szEL@QT-d{QIK_07%!J@T4brC5llJS*{!%)UU6CVBjc-TnirV zErjUVB`y((OK3u}rL62_FPB-(s)=}Qir8mS16tpR)|Nutp)OgA;S6gSrn>A?5N~*! z*wQID6ANBvSf-{YHuJKWN-7pN1-<WB(`Re}+83`!Rqc_njL&VF8mH@3s-+WH!aA!8 zI*<<Vj(5pSc9uTy8KG-st3_j7ZvpFu$Qv1yfse$>x)v(9!NKbeXvv_cdR7QRKxu@K zyVB$+r^*Dku$7(l%$wpgCqt!_!Yp;^hW`xc4Z9X(wZT(sKr1KVm>8%iPBBp@#oMD| zDVmz<&i~GMM%?Nd7suJ_%2uq}J^DO%oIj3QkcAA#_N~)F@#{bn*4pG)%lbq5P-|RK zG?SX#q^<xpAdM2Klr4jyZ}t7M1SvQc3*rHTH5LS#<D%G6a*C7%_9&c>$4ceY*)tQ1 zB}ylZLl5(*c7ZOpxdF{fKNS%+J0-CakttM2J=&<xv?9M=9OFx8+KZ+_4|0{;&G&q| zjNj8Lj(`j<bRG!1ax_SHO`+sjOMK!i`G<K`FcWO;y2`!AvbYo}>|sykRe%kwkSbVM zwFu%8inv41p1o#iSBax1gtKEF!@>n`+s>q$ZJr~nni`JwPd{v}P0xMqT^jv|znqPT zRsZvI2%ButwvD%CHk;cO&#cA2%_8)`!$s;nRcPwzw5NC6y-|x#x~4v-!sEyTvvM~f zDxjaTD315MgXAAyI1vj}M1vjplUwZlmfZ+SF8S`Qk$-*Q-y(SOWXFpScMwDyj6jAz zM060J^3F6PhaJmW7KL%n`I>^-;Nsl*cc+nXY;Z$#9MNUy!^SvzQT7rIcsLG<rx zTlLRn9n$nh>ThwD@1`PdRGUWCHrb=&_%t`Gr0x$J0hDl5{|alXrlW+m5OKYWf5{cP zbxioVaVs10*W=3D;zdqhzXkRygC*Qq3@ZmEjKK(b5QHK)A9GoR30Hy%r7#PbVE;J@ z7)3Y7FrK4rsi%6~)_Oqa8niTYD<wod^is6PVYlajfo58`mwO-<Ozb9GCB`U?=4iSF zX{baqRg@_&<~(3WT!>?1$CX^r=S|<_T;k+o*4K9EQ#IRHWOH|9y%2umr-b!XUMipv zEFc4d)B_wBBZfCnN>Nbz@qQxLWe@~;^;aZ@V=8y>2UHLSabN_8usDT47gB;nlAsBa zFo3Nf2T70zrJyAX$bbz<XAtO9tJiv`b1}hWLpp>*8hBbCsECWGT0S&xz_5F~#~Qxp zJBspCjOIjWqILCVGdD9$GZ=PGRVq@2Jw>xFpoUf8Lu%#JM(A{1WL1O_BL4z3pjH>M zgd*Y(xu}b~$cw$`i@ykr!6=NwNQ}X_4;S(eTHtrrQUlt86NKawOJIdpxL5B-Y>=cC z_l0bQRWD>n1~y;?Y*+}2Ko^gL7jT#*nLr9p@B&A01d32O@wkVOF=xp^Qh#`76hn!u zVS%$DZWcy6F~xz57*oeUki%e*x95mW=X8?TdsCMv$b?(V6f=<~X`P5~oI-<#RVw|4 zDgdWrsMv#N^n<K;YUwj%*|h`Pg%I!L2K7^nF)5QXNs~2si?~>R4bU}Em@NVX1PIb` z2Xqump+J0vQ1S;jf;BjmbboqKFM_ZKd!Pn+pa}oR2x~SaRT77O@&5-SAPQWd1f_rq zS`udsh;{bpho1q6h~_(WLWurIT8M~R1bGZ~X_t42mw9QI2PuL#C2o;;L=bj5rlCZa zcw$X-8Jf6>y;Vgpm?_g#P1YoKq;e|xr78i(T&d`TTLm@dlzk|<aKNH95F$V7kc2mh znrHK5@8E<e5(71%E&o)7zLsUdCSMG6lqJ_L$Yy_+G%pcVm4a}U-Jwxe;um{h0y$s< zfItRnaDXtAZKvmlq;oR*NGHAVmf_}0h&X#8h+%c9T6!s-<4K<737(3$kVLd@BUVg3 zRUC*ZZ;`Q>&jf?Ol`}FHiZ)1@oMv{P<|;~qAK_DKp7~WMng41z5qHGWYDM4=$C#QA znm=mg1`QBp*pglZw0?-xez%F6T{wUACuYhfFHF*3;UQd-HCdA*23+u!b|40CU?!yS zG7k8F(-|79M}dRLI&j%%<d#|kxnbrhq(Yin<C%0nT00v9n1NX`CleYfvofF~RPs5W z7iphbq;E7<9v=CTL?cQ5*<5PJndannP7sX<BAN|igcJaA_RydZ3a4aKA?6?g=fwgu zAca(zq15Ppi`PJnXI~4&n<?j%nDiu$BW)#Ab1@?fWIzSJ5C&ypIi`1dp2d3C`Fd~( zJ4LsFwl}1BxeRr=45Rv~rHYpxxR5~<GEWC}#sqJf$p3;VM4!-frPL%nHK=J^nkxMX zrb#2FX@qbE8dhl9aNO0J^ka*0s;tlQWLO|q*wRn3d1VJQF4f34-h-68sUH3&hL{8w zg#d@qmX#%BV2;rjqVNPmFb1u_C48uJs%KJp)|UL(j~-@PKH7nRW~$~Hs{87%FO`sj zhNOO}o~!DRyi-hu2~^6oTP#Ma(uAcmMm^1!Y+|&7S2dDa^#$Z&E4Y$<LkM>(>3tLc z2B*2KCo3)g;0zsbUb)61Qz$nv(q30+n+tTUkK~1dDrST_FMa?QijWCua0i*N2#^zc z)>b*zu?e9t38DZUG+LuPccb#^dOOOa7M6(T=KrtdIjUXjwOw1P{aUIZC{yWKu)=h( z2x|)pyRa*`TbDzhE(T*)DX|lKW0rZD(TA};sIdduibA%1+*c5DSEuaI4|j*MiQ6Gh zRs{L<cPkQ`+%lWgig?2Ir#)g-^G8YWau#V}W<3*8jt~Y(Km~E&2}Roo)mC#0h&;1! z3A2zUQd+4z=WUp3we}j2p1QT7`nA35yT1#(Ui+^KIXk+ys*@;n5UH>#7@y5ld^O{V z_ep~^rfE3%Z+Uxm(noOMqc_sknbZZifjbZmLYfp%1}3Yx=_?ZavkVk~Ycz489XBIc zmUxQCcsL6rI?I#~#Uyaye|sPWq96ut@c##xU>E*kZK-rQBK5ActB*N4OBUFpAqb>3 zrD3}pycw*)8w|E%i*6kzM1To(P?xZV37=OdpSmThTUSNe0b|iqw}_KX&Zk^os=b;? zl4}>NZ>LTTLPvGV4axGR>Py5X@nlGlPck8ek}Hk0`CfRlNCBFgx~a3A+qq78W=+xw zVn794TncY^w5!XyI5!z*sclj_wYEE2;RcYkN1pu}s-zmn8_W#9TgSb7#~hr&qDrJ7 z$U_V%OeYu`%WHMH6{~Q|n9z%STZCygIKz0WgJ*YDn%TE(XFeaBPFE9)EI<LTR>YrN z5*5<EQHFlcNI>m%c;sWbBZrhpx&OKTHllCAGf?sgVNeF2P_+H>X48RSWE{Kp=vme| zuMw81Lx-;xoVBYpo*hi8$Dqf|0L{@X&C^WH)ojhu9K5_Mw&dx@Nou^Sb0{byJg|Dm z^ae2X8NIferFN?a{E3;{!#yLJ!%p+PWm+|8%6(?lk`#an=&P(X3D5y8(8TBw{_qb- z%r?3<NJTK4^ZRkCtT#7XUkU}H6~wuoYi4bcFN>fE(t!vwmkGNpkCFnlXlbJlTrv@y zo#TeJ7F@wI6|gYHwR*e^*X+C3jMF&1!KP|%NoqSGBgj<8yopJr6=}}syvX>OX^#xa zyvl>r=VRp3Rc>cpp}8QViT@BCzyoSk&;#w&Uk%Wp>=6}$3Xbctg9nXwMVlXIn;Z&% zfJ)I7ZN<L%xzL8XbYUf>B*p?m(!V^rc9tllK_^bfqq&s3K`NfiJjWbd%{6VuIStv3 zz0-Cnyn5Nwe=Ne2*q$a_$c9XOk;Zkvr8BqsGfcg!?|j3erixKr&s2S;X-d8<@J_AZ z&teUyPeu<sV5e@QEleCxsa(G{dyRprluUVl^HSGyA#-^hdI!dUrpI7u*>hA|ffaax zk2sevt<3yN$2ncokqzGA4b3!tm)pFT-K?qx3mk;GXhS`GEx2`)md=)@Z>7zpO+7|W z-D8|t&zNl0MTih0aQ_3fXxl{0KXV{g{It-8x7K>)eq4sLaXnZ(OCD&3sH4Q(3CzoK zMrZJv#%`IZ71qZ2y4~FEwUYg{;oS@?-VEaH;?}&!=DAwhy>x)mkW4z5zxSS<{b)v= z$SpkI$rp;bii2g>X}yZW(3M6e8DzssWcn=I6hPaETi}U{+fImH=_kL`nn32#p?{UL z#oe0^<*iR5N+2ycqlZEXX2zHyI)Gif^m@Ah>79tZ%qd>SFJ8?o&gXsJ=g{oud=BV( zp2yj2r08wDCb-^8R13jJ&JBCc&}*O16Ft{N<fwAJI+&TTvft4atku;kM2OWAveiSZ zzF>{&sXmPRQ2!waUZGPao4*|{mFwja?RfcH(Ul~ISo{`n5r9>q7e|XqmDAU4{xC2U z=PFHM+&Py;I@5Se=*$r4(@yPu?hMpE=r2C1h5ohNjA7o{L+YvMYFn5)u1qY5JaJ2D z(yM$jY(3YTW2`dC87rWr=CRdv&#=8U5(06`qU!$+@TQ)=S8k{9>yxKEjW!ZrM(Iec z3}%DFvl;E{QG(&YZeW!XGaT;bK^1{<PRv%Tow9eqiS5jf4cXf+&DGB5&cO25uJVFT z&DEag;r+Yb{%3y-VrV<Ur=yP(<LD@i!jPWG%!7Q611ffVT=_*7X7?UXU2xD<D?#W+ zuXxpS6#w7@?hnaY<;q$ibnvXO{*!i<@bI<D@t3(tDcAaiBy}AZZ8%DxcS=cXInUv) zXYAo0uA^^>yUjlGiG9;9{_-o{@`F$Kg>U$VANVZ}-d)S>MtYtaMzE21XoMM&?|JSj z{JcP3^x$z#{8r>Oyn|Q;)%;DM+NVw{*-o=v+gq=91fL=b?b~DD)<zlOnj2>OyY`0K z_U1@!<?0EgKntbEF!p%tQY+XXjzfi=-5GYCevjvoo%n*^^38Dg)o=aR@A82z-o0C% zA6&ddbVK7liG|tdhq;19ZIPD}Ig&6+LY|*vr}P#paNoq~IUHR~KJ``ui(2!;I{*;& z{{QVGSkT}>gb5WcWZ2N*Lx>S2PNe8i-@h*uSg?RGqs9#$J%9u$vSdjUCn=#onbHzV zmMmLjexV7*W*IYP&g@K+hRshmLFEjcGlxzcq<Hi!<-^C%(?Np@Awsl>5u-+pBuUcL zwbNHmolFUul8IEQv!zU}Mb*}At5&h(%B5ASZY^83a_!~2SJ$q;y#x;iRv6eY#EBIv zK6Y$aW5|$~O{QF#*=5X`FE``d*>f{zp+%1-UE1_%)Tlpu*4#StGG>*RHJ%(9@?zY$ z4G-?M%eOAzeTC<(WtZ06Sa97gN40isDd?m;O%MCEQ`bzHvNpQPXc5&yQJ*&Dv;Pzi z9;8K!4h<TVP0yWYa+aZQljawhTC!ll(sIhml$>Z{2_%pR0*D@X*nx%_Vqigq4qEx= zo{B28@InkT)NsRn?)gU@5k%N11{!MEfrpWbK*A)HoLI>}{<6?wrY~%|2`8O+`UxnZ z<S6Q>q?Xddsi*viYO1Qb(@K&|yy}FyR>Yt}j3-|C<SgfyLj^A6=(;Pfy}<MfINx?5 z%&^09Q?s$hB%@6>*IZlev(!wZrcONbG;Pji;%sfQ*kn6qHrpIiQ#UjR`wci<gyYMW z;vhY4F1VD_@;T_DlWscey3%B;?YLWH)bIuwuPGtXtAh?Y)RUt<H-3U|r~moNun`RW z^4rh9{{nP^KqQJdP{A5zkO2l3MBu?5e>imZS!kn`)*uhlpg;wVJUX!ll2kk?z!zPD zX~r#Tx)G=Ndg8H1AAbyzDL?q=1Ce>BvI?uLnDj~$>qz+|j7>zLB9u>@Geyg|y1WZ7 zF!d6SQ8Ujp?9jyujZ8K`{mg7NXF${QW038n=FU3#<V@q&FebE6iWNh%Fhv<{)X}_% zv#U!>moqriQass|(@sB?BvkLd3$I92%|mL{R_7S%)mYz4Bfgx>sL#G!_1m>208<(; zSYZ>qfk9*;l#s${(^h+JwhOw59u-8uRt6eC5{aZ0zjZO(DX`FjT>o>ypbtl$d|KBH zqSQO;Jf@ryM3FlbA*3p+wqvqMe!n`)6IP^r!j4%Ceyc4mk)x%qn!|Kh<}xD|Y~q#^ zvzSnoHOp8tIzujPWZrxCop;?sHn~qfRi16-$PO)RvE5>3)X_(Yn^dk!TVc*Qo=N!` z=<77eZfJb3TBOt><26rJR-0zeJ*la-`s(|1<<CDT0vwP)VSymF!Hq<?f!VeNP=Eup zkcaBffQ@v72HQ%}idwWc7{Np)<uVt2a*{5?v7tSQb5|XdqKBv4K@f*{f(@+D2|;)V zUt7rzSUOP(MO@+)dw7BpE@29_9PD7rDcxL77b%B1Y)pUgjsL{b6g$Keigp-78D?@9 zJktD5ic_TG$e<XS;WhCxwXxW3keDb%m1$<sv)S~hXT9rT4=vl{9(F*L74adW5QRWm z(p0r7S3xam?UPTfY=x^_Z2>0z;adH?W|Ck9L2P7G0fbC3Ap%BHl9N2hKZ?)+j>JG) zcPoOoTC@_D^z9{ptDptrbA}9Rut$np+6SK^h(eHo40)hJCkk;D%VEwF*>Ob}a&QDO za3K|3fW;?rh_HnD5OsKYl%rbrIy50scD6AdY*03*D~9GyRpjRHtnp27ezSMM%Oc7u z(?vGL?q$FTBVd9<vq;^HQk6<0rq)QE>U;$|nHZX=zW*afQ<d+0NMThT+as%~_3?dw zjNcZtM#%pd@@q@T-~JqwEF3UPAC%;1N7d$`Wpn^r3S=POOaiV@_DzBmtdZa>m?Kmg z4ptmw)w_liFG)-(3}lc5B9z1xu4K*=fe1q|(C~sh{2>Xc*aRuE#6yMskeOoQ3z>@8 zi*-sfiIO=U6PrjUkA<w8V<ju^z`0E;>W)tutER=Y+PvPhj*K-c&gssWGq<Smp7^Ye z8^PBdqaBS%<<Y|(3+gmI?r2thgda^NsGs>o)PDFY0)lohwqrer0>FTzM?L#l4S8q_ z8i9c(O~lCp>Fq@<d5Mf@WTU}dFs3`2X}gTlO8<EEA#!jS0v7-gLq-gZNuEFjDW1f+ zKZs!uVSqyvlmLfWWMUT0c}oxJVi$%rGZ(BY6Ev5n)h>GVnoryv$;#`DDuz?N>$OH% zxk=8?G!bL8acgdlI1IS9PG&TtYb}t2*S72|Q)~>2U%7*oIL@(rggp;In}*nfB9v-_ z!&=q`Nk54qvZ6aE)<ru2h0cOj#3P2t+me;71?~W~EK*5ITT7#sy0mJAI~+}MJ0zz> zWe|bzgeLBluSR&H4o;ARbTV-XQH<dUq9}z7U-48PCNmbNLtPN7%3U*MHFoG6lx4I? zUeuTuy<}x?nay10vBH-%=A;al(@C+H#s76t?~Gnvs646aT}qAG(_S0D*Utl!N<61Z z)zTiESP3iiYJhy~)+BpKuqpDgWYerRLQG;zXSyIBqJu_QAOmfM1PGmUV2e{KqZ!=? zwm5>Rx>Sj{!~w~JLL!nM2r<Vw-V0xzu!9i*VT3<iNqeZUl2b)DI_pk(nL>ORnT!Zt zYQjm2%m8zk+dJm;o>|-5KJygS+!?kCsy4_ol$z2M=eYKQ&cmszUAv^E0ON4LKMUIT zh-S1wn@?#3HRv7}D<292(!!4J+SfWcEDrOJ1s!n0KQ^jqh>zGG7kS5tHCZ=Nn^d(f zUa6{YB-`1(8rH0wHLan7>rvrrN&lsg<s^g<icMg`EYnd7bf9d#WJ{IVeSz3jvHD$U zhL<wq<yf7p*iCI~gWF5jb`{mSX4j~!i_%25U>3z+J5%|L@NSO0(Zbg!>C=0l0xZ7k zSZF-1M~_ka_d*3e!3!7CYX(114<>!AMpA$qmyWoF{PB0d2VU@lCw$=ze|W?vzVIFT z$1pHi+7g{;Bqsf&i%0p|kGEQ;8?>#gKiHHaNyT0()QToNkq0CAdY61oi@|nCx@2QF zb=u{w#9T%(bb481ML&)2#3{w4YeV?MC%*8R&U9~5<JxJ(Q=d-8W-ij#i}rOH80EZf zW@Fck0PcGB`b-_`bdR5K9RC$S7tCPvsSnXTNho6(>R5;Fhmc(p5U?tnpoAlf1rz|o zgcSdO01Q9@JiNZ+5PxWb4uAp3JFOHciH(aOQi`#c!XVmOr4CXG@(8^-q6(E8n(WX7 zQkaUKk&d%yJt(U#(^<A$*ty#CF0E=4>GLvcl9OsHFK#-%;>$rD+(F|zzV@P`JXsC- zYP0%MCv=-L{wj{*z!@~kt34yIpxKJQ@(%D=Ftj_Y_3^j%s}&n*sJMHy`$;7IxjSSD z5p{650!+h6@{n|p8y2`YkeEDAYB63xHOzA<bSWI4;5^&9Eye+%(31+PsGNMsjwb1Z zK1)QNIW`njCWg@qEC1WBo{JdR2|6W`wxM$(@(L>(RKAh%!EfS0Q5?nM3&kEZGpB35 z_}U`NkUEz6BI~=lxss><YC<Q>9-jffD14)$0jPk|w+1^b2xA}ibDzetFo*&rND~%> z>oCnK1HMy3X<QovA}zWx5fst5%7c;1^EerkEmu>er}+^e`8?1w5+uQ;Tsp+#nhri& zM7CfKDXWVrgC0pFBG;+JmZ7FM$(Y;GM9<I@Z^A)REJ%aY!KUk--xITv0k^1g#pE%< z{F24tfE44XMLn}8HVVJ7>!$=ens_0s!a@%$T)RYbzb*`<FDy6>YepLIu#Dn|X`IQm zF)<N=Ls28O2mf@57h|b&0XbLWJaSwdSJJ>i?7&9A9P7ZRw8)frl*f6j$DO-JGs(y0 zxv$(1x=f4>+`%T1!8V0dzHK{5vMkF|>^2}&#pjEY`64%}n@D$}nH9W9Ce*We`@Veg zp79Gb@Sr24LA$ieLblt&_o*;l*&6zzI|Lz?%u)dgIEHAXNy*F*fAElFcs$dRJiIA2 z2oe|9qM%g+$_&~d^|-A%5R#iZxudk4pjt|%<e6iNGAWy~Na+h9>N(zk9jvUF-1A4w zfDJyulYu-lvn)>IJWEuRqK1UJhdifOgtJ(5r!lfki*&bnswa8F%dpd@?0}>0kRy-` z$$<(?lmFx+lr&61BDf60A4RgLjo?2toJ{#Nz$OrpjtI4G$s0O^k-xda*gB=rw7{A| z3X?lId#M~LWJj=gO`Cg4WHX&doJvV7BAC%fpyN%h60bf1&Z6T)ZPKPsG^;W@P7*EA zQ$(|{WXRGG!saBx=S+;<#IFkNjpuO`AhOQu)ESN3$nN=+@L>e-{6&2$tflEUV%)-j zYbeOVu*nj`MVf&!WC41J&-tv<itrE+!4{lsK+fcw7$K$51jh;-xehA1@)5lx>A(*Z zDtv-X2Zg<40wStvHX`z_3(ZOx%uwCiB5JEa5CuN=LP$_NNKhQh6J;-NOAY4y6G3@V z82?2S!w{qCR2}ItqvWu~uJgLD!zYd$Kfnr7Qvp2&<F{cvQe*rhMsuhomAm>Ykh)V4 zN^_*hv{G7S2oKSN#{)G6)JB!ym7WAmJQPili?wou7o$v)P|+8!;H#$0q1Qtr>#8zl zaunRO(->upJngEXo579gjMPXzv0N_`)dp@LS8h00bWPWE6~%HL*KPA1MP&_c<;q5N zONlHD{hCzO(LS6Zop{q!DC`tKizD+RG$JL{wHr)Yal5yRzhqobF;o!D+6ac5)mpt+ zgLoSlxJkOX0TtWKofM_d44nU@F&?q8cR5ELOH<ZlM`qO?czo7M=@L1mR;$_tcK>>r zee6v?3CKM0#P%A|aaC8MEn1^BTH<S0vP?+eQH@2l9p{Y5dzG`etVl_*)L6(!uft2A z(Mw(|Kfg3sJ#a9!i!k%#!iIgQLdvj2YER568xdfKen1<Ht=oeDDNOpb8Cal@;MLAl zsgadH!qJg+Ay%7G*>qGntx(XHbyL}#%_^J97W}zuWsGR+$3WRiZ#BA43|gTz&Z7-o z(H&iMEl#v-+SB+9<H_9UliJ&39+<hlb$b-;+rEs%MX=kaffY0>97(b*RmD2h_d~|D zJtX!V!wy3h3eW_LwcA=fzyvI<P#d+pc_1(CPoE4{3Vbz`Ejg#iu|c35LjPP6#$`$@ z!J*{vSJFwr>|(*cz(+gX*=UotuH+1(^IS6nUDD--Zs_0s-CqD!SJOq*5RKQhWYnmg zKIn{HBqSpx^sgM%(X9o$PT9*qBcH!K*z_q?h1Cg$O;xpxD7MWXySsq~L6!~(f_-Qf z=XG8WVFx!<pg8nfFC7=mi>+20)6Of_r8v_<7?tr|5+`X~wIGFBh=VYYSt$b|d%W2! zqukfE-1*(g*6>-85z)^zNC55z{`Frk{$el=V=e|@<6JLzby|mPQF1G{C`OEltkH_B zD~yz2+~rj6)Q;|;LJS^Kk~}n%Tr9LrTlHMV`{RMJfl?TVn=^d47XQXr519jzdc*0} z$&mG%{`9yBG+A+MmjV65T0_$x%NKoFQ0jo$Oo0V9STZkwg@eht+N9HGqTD;h&?%l* zfb`JO090^Nx=>6y;oDy^4rXB<=Ktklb6wX%&0;eiCj&lURy?OQzE^f?;5f$7ti{fG zqhL3>w}K5x!ZNh7HCrS-M)|=oi2@rSu&m^T0SbUdx@}}yeVe%9h->Uy73orzV6Dpo z)^DW1nIgwl!oW{PlJRAs%xOn=oVQd+f?IF|DiDQPm@dejR#@f@S$<Sn?#EW#);`_b zP6S%@B1>Q<W|A&xF-BUmTxL&1<F(AhMzsz5I-+&5y4ejAy#J8n2>#b>)@FMnzbZVH zZzfgXJ=?;>n!|k9WeftheaSMM0ejE~Muz7q^^j7y7D>j&24b<l{Z+vgR_^6w&+B0y zrW^z#--9;a0W*bEcmpmNgHm9HR!$gttW9Q{#4MX-+^FS$>{crlGf(VXaUI2U9b=<4 zX~RBjFb>_aRB7g8$W=t()>UA0n^B6i&6}o0?%SCXwBtMWNIecuU_{vRB+Nxi)s<Y& zgTp@txhM*7hUS%OY4nGGKmyFfxVx#|Z4?(U%{+f5O_KY(GZn;w9%WK?N9~DdQkVr- z2n93{g;p?yWQvO)n!PK7UuZ(2OWf=F{Z=dvX;M5_!v7v@#2#<*_Tr;mS^{Ri6=l)i zOkl}&<Lcv$%C>B++d6EH4hp^wei~RH-DB}YA0uVEQ%y;kIPDRxI}T&&h3mg}hHc68 zkZy=%80gp?$m&Yo=TgeUklW;;EIAz0z#mq}1U>6gMvGba10k4#f-wbKSc_Tcp)ZNV zA?mJ+J`}CAWoz>2DDu5<>cJf}#a|Zh@*Z*`KX2l*22o^e6&($EO_`T|Z`fsE>C{)7 zp~du-V1VUm3;xJoL_g6M=Y=h5fzz5nu0Qr%q|6e57_bL?h-wF)Ne?jtPs_|~^p;9q zDPVo698s5l251jgS>f(LWi4*)>4aC1gA%ZUG5=75Sa`~)Y~P28<!HjaDc(ID7Y!co z@gwI!qAg}3|MX8ca#CdM<#cA&EkfminK{$f6};Lx{@1PLQT_f}uoco#B~Ms6$v}p` z(+-f9)SpAvzYZV;Dt+^5w8^=d0gqiV>vb{g#pJ<7B^~yW^hw!)9z^cQrGsuqQjjh+ zFoG_C10xuN(2?k9&8`*Xxmbo`O0RSpwBIWZ*N{d4m_TR0a^us%ausq=&-YLlbskJ_ z^(Kv{W!=c0+PJFebhk(=$5g%I+P>QFPyySp4ehk!U|9)sa*jX5EVu$O5Or4Y4rqd6 zH+D7jkY=#zj=)B4xo5p`kq8Rh%*)|n_4Ctg9Hajn6*yX463<0LkAo<%fhTwYHGt^2 zo<}8=T<e~68?R+K>1bRA%Mqn_c12fxpZcli_a9fUGfv$!Zf_Tb^6HavgSYAWwr`!* z6doPBhwsZSA5SdI_4g3oE<9=`ZPj2|%(s1zxP5JrC$Tv9Gzzct)XHs@iolNp&;X6K zrJ4D2M8~OMgiKf=;y$iTnFTwbf?%KmE`WnvaPgUiP)M=az{pvBT$790Q@(C`r`L2X zR#&QT{d~82K@BHn)_P}#jjngyn3nIVwNbhx`%J|YuI*Gn17h&(-Si7*#Y!kYGU{?J z-Y_KLgmVzbB=!d1`-p269LUwWQ85e8?Jxhm;b@<&J|9r;C6Yn7wOf*eH+cLeX-&!Z z8B%D4UYmp@c!ek1q0YZ9NO51EV|RcUCU79ZV+IW_OPG+E!iCJ5L2Tx1B1MYSE>g3m zQKL3();fL!*>R*cZYEE1>!xxg%a$%*!i*_%CQX<qPm;_Da^psf7b^mF7Lj2?q6rTo zC8$&&Fkro&_S&^em#$n^uUfTLs}`+TUSqXtg=*|rQ)W$-N=u5Ar?#Ftb<!la5#2_N z7%f7icaWdHeDvtSgQpH1I&%)ok>h4D8#ZauoH=90OqnuZE`Ry5Ws8<9Sg=f)0%f!l zCry?hDH0?I5FRyV#DKw~Lz92{_Tm4|t$R1`-oAeW4=#K-@#4mh<G%M#od^*uV9cm- zg9nfxMUWs_(xkK#D50ld$&zLBmduwcmzf;-apT2{<s2?tXFeXleE9SoGzd|lPGY#Q z@rfdhWTFXNowT)<f~k=41R$ThVhSn}jui_lUTvk7Em-A3l~lX*;#7!DEu|Dv2sy-z ziYq=8kwif`;}cID>6Ft=DAkmsjyv+0<BcZOnA42b`1DgyF0!~{L(80aOo;?FCE|xv zahR1YTG7(gS7MQM7Fuet<<?tqWg>|rb>Wp)A$<Aq7hr+SR~TZ7x#t*Ul1)|_W|?i) z8EB!AX4(=<6roycH_#x1Y$E@t@Q!WBK^m!~lTun~Z_4>W0Shd|Ktl~XP-k6sOK>;Z zcj0NVS!Q2=f!<_hobgy1?Y#%z9P-U)UtfL<Qivdmd;*3TlL+z2C78%{pj!%-Ldq=9 zn#E-+v7mBcELqlaC5Ke$^5KY40`sImO)i<_GA%{~V~j**G-Qw@{g_gZ^U_-{P4T|F z6Hgdvgwc@@C8^?)O^VA@luu1rRh8LtrKML~c6nA>&4xK9nPsAx7k~Qs_2yuN8HSj9 zZZvkMWawQ62A`aH_FbT+VP|L$JJ2wLY$|k6%0Ks5+Oy9;0}ZJ@|18nLb2E4fYIWCX zx7}#ofhV4-=Czt0tdal4+87(|C3fo^^W}Qqu7eOFh#;X*@dO%pc#=sb2O_vE#S@!F zR#;zUiLJKVb}Q9W;1)d0iRA{2?u$XmxKX|$b#$Y>-GDO_IFnOedF78oUhj{K56SLD zME(o#xhyWpB*9M}jPO)ca;R0qUx5X2#1pS2=7DmZN!MMAsL7_Aa1wUd9EsIg@|}6= zsj_C9dG_bir45?eYCX6{Lu|86v2)PdbKkwsL%*YfbI?h*Lk~bOtzBuRhKB0YDOaZ6 zdb5&TYkYLnAy|E4=U28OfBfMIYVgD*;({Q!h=~+*t6P`uhBsPdYeRhN+qXyrrKJo` zA%!!Xx-#-Po-F@vB=N#rOe|+YaD*d;;W(iQYZ5tnZSGw|Dw2_a0<gk0q)AR%O1Opr zE~rR_b*+2dmSk5Jv(V0VaKT+&?83W^?do@fDU4wfLp-fLCNjvgjPjP}CznB?G^a_8 zp?E+uMX^8xGoZ(#yywO@!tpoC>4l~^6&+CZKvaV&71Y9$g;bS?YVpHbtmwBjH*_sN z`Fj)pcvXl(EJ6{OxI`u};kE+BErDq{3t3PhE!aUYTUo&hw>|`}9zIEjMJb$%DngBk zc(7fH3rUSW;y4nPkcGP3r7m&VlACy>mL8d*PhjMtW&~_tClXh<QWr!aV#Re?+EOQH zrxr1_B`*J(z?fZj2gN7?=3^nVqGGUkJmjTpWnTnT7zKqIneE^;F<^lTC}0ik#WA1y z^qz9SU^EzX>QkXA!l1U(9rpQ=Jc1nL{Iq7jTj6h!fN4{H9*KxWFrqGQOBMo`rNB~f z(r%udmRIy9!EJe~f;~iKK{A*k76B|>7U9<iX%xbn_>v_kR3R^W%0d<LbaF6xVUJJ} zLShy(bT?E|4wuQpfut@ftE*BjuCx`0g{7JkLSkC5`4+ioB6qq|)0(3A7s147oOCjt z7GIUTm2IJU><nWQ#;BSg%nVW2qW~E2xzE1>mQq8r2Mxw20~+8FeWNlc`=SQORh`Fb zSeyTqLlJ4Kh~}?8df1g8EQ-;L(xpHK%A|tUvPrEvFmDjtTa_qy%7W?e7#a-NF=14s z8Qm18IjtN}ed=3Y@-(M7IVw_LX-p)MP9ZuBoHL)PuxJwTVMde~n3Nb7Gi8iFWd$ej z<TN}wF-BH+q6`;T#k`gQiaT~K0uZQ&C^U*d2KK<mZ31iG`w~Yv<Y3g%1e(Y6F}9CV zdtYR)*3d&*7NYcFBxiedQP4I*5~5X>CrV2<)WU8n8a^p0DOf?+l54g}lBsRkh1=Zf z)`csfoKAOYx!wY`x4-Ra3WW+eqRwl$#NF5DjB7*WGF7>zGYE5|y1M6HMZ*q@omT&; z+bp-hZJXE~>o+?Fn6y@rcqA)XTgjWw<%tKqfjZ4QS;K=H$djHO=!ReM>*hD-22*v6 z!5s&h9fKaUed2j6s|rj=_Hga8^3kjw@ROhY@D8+Q!emDi^wCW+aHP}H#kDdd%2AdQ zL@EWblaL}}hSau${8HTFj9L<tU~Y0Tj`29gk-}EPI@YpYHLX`z<DJTQ#gTg<j_-A9 zAmyub{yHu)iIUu-IF*@A0pgK|h@~aV&Pz#z@)F%PWp8e`P2m)$T8n2gw{lTseOl+3 zqgTdwCTdd@U__hY>~8xirwRY0^K{Oq#{i#73xEt{f#t^@1SfLPnl&`9dd2@cj7C_( z9L;2f9}Uv6WK}G+n1v#ym7xuBIMW{voGM2*;#S&r)TDmbj~=J$pq{YSte&;XSB=7y zuh7Q!ieZq7OY99cHQ7*w>JJlEC984;c3JHtSD%c{i(NZS*_L8j=QOg$U~P+E<_x*Z zO(@mmwPv#EK=yd{?ymzDd}(~nVezO(Qms$G<C$8Y<EI{3(F&2mizuN9t{=U8HsOp$ zAX^*`QVK!b6tMV27^Dz}V#H!^8TSxWq7*p69fV1rRuPFqUQ?UasO0oA;jK@8@>jP! z^eU7!tVbX7ms2k0xa7vEIX9!E`dBDH4zh9&Qe+WH6`EFxE?Ame^osvwlT6sXOC!k2 z-R^eV+fgU4Wz4H@xr(NpWR{+LYc@|cva!Bk-~Jo@F~>TRPign&qn`Cm;Hvri-&~vf zf(y-A&muhG3s0cKBaMn#n8ForXoDzB0Eb-60&87`hk(dyaa!cP)QVIdP$bUCW!^3E z2ye+)P>mkxS>Od?U<SHc%duFC?Fdc)Tg~y<u>IIl(cX{|S;3r=R83VhJsVaT(N=wl z(OHa?oeA-2Od)WVo1m3pB;S^05x9k0W~7REIFIx-LClz0Jk5X%(31$Tnf7tt6mm~L z8I2u%ioG!nzJZ7P1X7=&-(*qN$k@uQw4dF1mZB+Kqj}VY*-if|Jc}#*K@`}44Zr~$ za+p;Rpr!$ixOAMyQ69)4j>ypnEr|pK<_NESp6F>{BRZl6av)LlT20(YFzG}{j9~0h z#O%@D=_niSIalkvpwLYh64eg1U5s5&*_yCPUxX9L{2&mv70T?%dHqTBxf6D<#>~71 z8g&4>c^wrB<IfBYJ-~or(LlXf2SK4-p0$s@r3%%cpMk00`r%65jZGmun4)bI8z#sm z{T+pb#VnwLD-^>MJb^NVfh(lKl}He`c-V;eP&1WChyh|CF5paEo*~*uibded+1lv= z)guyQL59NyZeWddo~p@Qj<ufa^#loSA}1OJvf17zg5v)(i6U17T@h6ibphY)Y*Q26 z#m4v!(*@6WJ)L88S@I}PpP&~m3QEkh*O?{C)?q;#4dYH$igGwZ2dDtqA(ow~Puk@h zpS7K26;j+;k%CDS8fs(SE!u=JoZm?ZwQvb5u!1Sf0w9Qi6`%nyxZ?os;on%0AG#E6 z<)c2z66W<Ij?7ESrQWL*WL+9$tfAbCHRJ~ZQ?T(E=#*fwC6h&7B<dJhvkg&4N*B>N zSt%Ty@ZDfW^^RZgpg0K+c*$ba(V{vTAv=kYx#5)=Y27i#K=$$EX-bN6$N~7(+0xt@ z`E}vGNu%2xSfDAAL=~E$Ias36#iETC!&TVCJe>b2T!Jld<+C8?Eu?}dh=MK50+N;G zw>+Lp-D8V9#6%npEbSvd!izs9;v(MKKqjQ<k!N|*TIrcy=egV@Qep@~WJDU%L*QKP z6{cZkWD8z}RZWveGUg1@;F#DTNov;)zT$jb=3228o@}NUt&?b|mlC!H&A^7bu~{&p z=7kQ2KKO$^1i=*^Rt@k#9*Ig_8D;q?R8lG>pdC`zT%)e&W>m&sgfW^|J(?*viyCmj z8~g$waDf<z0&*fJRV-dgIo<)HNOj6*b~50028nlm=PsRRtC?p7PHC-;=RsDWtL;*b z^`&3-OAS@TP~Z?@rr;+so9<QBRgq#Te#!qS1|M9wjetIqSruqXYFT)llb3Z7Oo9ez zlp7gEXbs%tY!pJfVd$au2Kb22b973*Db^m9=x6*9+x1&*K2(dk-`L<CgqaCPVUuZr zR4K$l9OQv0guyL50UV&g80bO(x?>)8NZ;^bGo7W0M4oIVAi9VeA%29rI4Mmq<craz zT^=NQuAE&G>*=-7jp;~Vc8;(~BzBtMu}NNiLJ6(jCz55wRY9BYwP{FJ8#g&oUbNzU z1O~T#7lN|nEWVW&LEoPi3SR91qS(xAK!KqmYQ84NKXd~H1SJfV9Z}*L)O6vb@>``Y zC9MP;eGFVSMkS{j$Y_1)N11{rz(W5Re8L`(!7WfhFpxnQ48tsFm?)i;#!07<uF}Wt z>OPX(Nkrg{DQlKqDS1k1v65bu;w+XXB<FP?Up}M=_KW8z)tDZ|kf~sE;b)TZ-q7{u zH60yTiB*~)0>^X=TE&UeZJC{DX1k7?m`NXKQcpa=*Ba@hzM8Fac!IxTq4~IGQ95Hn z5tyq?R@^0+89pWdIM{<VQCLx!qtOm2$l(zjK`H1092|j<KFh_CB|Po|E|?`t)uX3P zo~~Nn<q65JxolkG+OQ(4t97mg+HB||t3t-uUbd%u*3t;x++dRF?Je7s{2aFmo$vka z(_T{4>c!HX6_%+aV`weA)*}C(f)VtTS)fiR&Qz$`D(^lh#~Ek}K;4nOEmo-<<@wQO z!mjATK4pW!C}?2<CP;!O7>J`a+ybG(D=_D?h(ap3!Y?Fl1c_o*bjyfr90noa<gKN4 zwk3Bq4qX1DK-%o*2Jq)L;s871LRt=w+=yH1OVDbfv`(wQkm(MYsp_EVvytLQaux8s zsa#}2cFid`eT<!A=I_Fao|+fS+#<X#VVV&tzAo>D{sR)s+fcS`Q6dx;nBN!r*?Lq~ z-3}Uq9ooY-Q6^jhC1pax^__6m&2i2G96n1dY?xJ9MYzZoFyKNK;{q(;f-!ipbut9x z+2cJfAPt?^1EN}wpdSC{5^x*4@gtIM%&Fe#cBzo4Zs-s#3YIBT@Eq>tp2CbJ&}DGM z{N7_~lUUisfYPaDVl5DUTe~h#Tz!UT<|5YFq%S%_*~ajN7Gq%vCEK1IZ2A$OMOJ#u zErJ2@8FKHYc9UF;ffBqyD!7e>nXf5`g@nw)S7?X?Wic$QK_)0hCTxQ=z(X<1!zl>E zA~XW8G(stSf-%5?FBpR_G=oP##6n0O<+@S>GH^*??&ihp8;f&Y8gKzGq^+^1P1G?- zyk4|UWFE_wwJOCA{qfI9(;y$w47zCzimTM>?zzHZ?>h3<mY2JF?So2>@h%Dr&_h2+ z;U=G^axjMoKyUvRw(Y>4%78)EG+OGVs&Y17lrlF$Bmheoi~$^kK`0<d-_@u%ip8{8 zTrEg(F4O`nz(O)eLp{_36>x#!odPe!!#Bi(H^>4gw22(V!6`sOJ;=j6<byoOLn-uu zCZIwzOLI1GgEffhLr_CAJnJlh&^H5Xivi?Ljq_Qf_07_n%%!tRRN^p!P&+>`1hcLl zAMLUs44PJz>)`Vd2`9K7a@0;HWfrKM+-YWlTkv+qL7T=HAwdh*E6&`Lg+eq>Dn~0k zZ=;&eYA_=gI#%2=RKk+sWvMcL=m!yxG$RCy7^ndmd;(lhOiOoC>|lt7u>vk610^KG zG{i$ZJi-4n1cMk@gD+^Y7aPMeM1(kqLvJ&;H#9;V@WLt7!#vajJa|GOJhLzOLN=&` zHc*2&P(;v%wNCi2j(}%cTOc`*1A5O|=PIP>%EVjSaYTaYL<;7yd7@zg5x3a0n)0VL z{ijIwGb7|KoxWno49`k_o1Tgr%fw_m<>D?f;XJVb1>gY;SN0SthZ|4;3;<LzhA3x4 z>f3tZY^LZBH>KS+?5?CCT_}QT?}6ZY!Y4RdOH&9}UP2Uy(kr||JS0Oh#6vH;!V`$X zAAAB9H-+P#EHD`NG<&f%aD#F)cRZ}Y8Wi(9%)?Kwfp%|qHlV}4^lFpJ%Z|*Yc(V66 zsCWOGtND7LIXRbZTmRBJH}IF%H(i^{1mB(o>z;l>TPaRk2M6d_JyN-P49GMxmu>By zxa$gk?K{=vdu>VwWb#92_!RmB^ZvsWbbyBk><x=@iKk4fyowK_a=_uwz@Z^4t77;% zf+M^|jhinjI13;=0T+luEQqWvXk|Qbf;U8iFSK?rz(E%{!Yy>m1)<Uo8N)FcH?toD zL}Y_8WP>(jgOtZZD=-2)H1$020w|OMEM$W(v|2Z?o=yE~2|-SjviF*^yLy|0Ij}jJ zw>c!1ZnGK{cgpo#Z*`F6H|nTP((d)rvZ>Q5QJ_0fm1$dd%?W~L(JU&u@KW+jS~CB= zZVIC`G^JPi_6-&gI0u~x)D1J%se}imo`?KoO{v3&VSIE&g>(~1f+i5iB_zl<LfTop zf+uvW9jHO8Mi47R11BKEH?)Boh=Ldd!!3x2Q_$l)jtjZq>Ow60xp+0TTSK)kcRZj% zw#x%kzfCk}LpF>9IIv#-YA$chtjZy4yQ}@$r}^lfedsN#kH|S(dya9%-o8sPo*yj> zqN$RtY196v#dLzTQ5nMX;ME>_!z<|2IrtHB2WUp9*3lCMGy{fbyt{!9e|bD8r%&3c zovMWT^`1Pyr99o~3P{HvBlxB!%skCM+=R?RD*OQ$yaLAN0=C%nHzdO)d_(^d9DNcL z!!680R1~TG8U#Z;{pj3~>_r4ee0?^613JWm^m_s(=(Ie*!y3SXw5#_@q%p7tq?xBR z+mnC!tM>tqE<lEZ0?WBvs|(&6#d0azziX?8a3oe~us&Bzl=bsq1B4$xeDoBob8t>V zIda^%VZ$a(nlls4m?={R445xpwsg#r1<RBvP)Is)vIJ$3AV7HRs4)Wu3l$Xj{JXag zXHK0vdG_@A6KK$!{fHJddK76=rAwJMJ&Nxivkoj^$e?k9M~@&ukRVyo#0g0#BC%k} zqNU@Pj9@NSoEY&Tn}!SJB&1UZPhLKI1^O9Os1PDXj2acrqzQ2+PmBLakt*fbR4G%F zO|`0Q<%pVFvu4$@^~#noVUNxM;vy!`uwA`a19Sa)SnOlNj@3T44EHi-yLs<!_S;!- zYtE=y`)!Sywr<+8jZ23vp14`?%GIk^s*^8Y+02>i_MKZdaN@z0H-FxIxN+;*w|CE; zTzvWS>6;^GAOC&*`T6hn-`_rR#-UHX_Y6F69Q4o=kHPW2d$61EBwUW03M<scnhZ6} z(3#<abLO|-dg~3h+iaUHw%C9fX2lhI0fx0+cG*Q2U2Mt4mK<}erIuKHj0Kfeglq*B zR49AwvBnnjq?1k%%cPM^215jqLIxS6uf6oZ<Dfd|n1il{9E$%)A~VjgXswMp+5)7I zMuNhmCQw2`r5<>=fd&~^V1a@%Y;p?FKm{F?&_WFz^qzk*nF@v(XxM>=t++x7EV0O{ z;;ghXx~L4d$b?8th7y|NuDtNzOQ0(Q6O1s!5>w2R#u_Vy*2#*j%#>I}xy6-NVwnY) zT6USm7G2JvgceZ#FeVpWVstIVXiqdTH{C{LCd3bi+fYLco5`@7Y^=!!9dyKrM;KY^ znP;1AKG`lCb<lB;Jo3U(P(1|M%a_1@_XF_1fB_y@KY!y}FJFD%Q*goY9EK3Q2r0Di zLTj|akXsHv46&JOb2IV8Xhn|g#noi2(MB6}<nhN?h7|v@NFyV2OxDGkbW#&28=11o zEBhK~OD??xb0IMwis;NUFUm+wkID+EB$MW>vj;q7h>3zJ`oZVWuDwP|sIbKzo9ulO z-J$~+8oes3Ac`o$E3m>Ei!8LZ*hnq5IyLjHG#(1IE>iEpOAkJN{tJ;s7HL%yNe;Vt z$yjNX%+?@L`PCH8QX!*^UjPx~2~ob8W)*mhfyLQgmT3_-X-{0{w%j`IE!z)?qXzfl zy1npX48!A&9O#@W1s-|ifoBbP)k$ZZaKZ!U-sqcGn0f=}3((-~wa>o#?xPRqUV0%O z|3Qkm=^cG;bGP005J#-G#M(v{*|ivFtTC7T^SA$nM_Oq45oR%yS!8HMipVwTNtuwu z&IYrHp8bp<dgu}zzC<*K91Uq_vIs^r!jUa#;Ugk>Q=FR6l_CJaPCLj`Oghj5d+<Xa zWs~6yX;?!W)=(e+um=!Cz=9Y!3Q|CD8{Fh(sVSHx3u)QNrrI)*Gr&bIbEyjj2Uifo zrD_m~TO8vYr->#-ZdSFbT#$z3BQA*I38oQ+8q|ObTf`$7ocM+tjS&Yfv|$;#7}>O7 zSDV~012=%g7H~e4JKS*#eZ8wtgtWnpabzPK&ned|;!z!WXyRS*lBB)b13piFGGW~t z(Dq1K%6{n!l&MT*^A<!tS4PM}7)s>DHe~-u_65g%x(OuwY$Kcby~cht(uMx^$3OqI zEPw+fV3H1qGX*ZNfe*}5L4;O8Fd1!35>eXHI@l2qf<z=yYeEU>w33#*Bqkyd!8`sD z!yCR6p7E5YP;y8Q7Ki`_KdeCz-4-{KkVJ%LvD*@v=$0q??Qc>P+(GbQ#lBogi>+!z z7a_N#Fj7u{LgLIV{y>Ijuu%=cu!9<oVGCsJB95KVMjN;g3@)I;7|@E1GicLCKmKt< z9n%f_a7P?O&hlaulUO&<@f~uNOC0Bbhjj*l3P>&wVbD|MCq+3*Q(o1S)tl;8!)KmX zlFxiV#h8ZHcT4xZ?_<53Uy6V!BVqp%6G!~(9{`CYz{yNbNlQXt&KAf(2O<JX)7;WQ zD5wxIH3TBstOz&p_CXN3X(T2&$r8%Rk{#RtCNk*&IBYUc&wduPG)$B^rsBgH?6U_# zgxgpCNw*_v0WEl2OI!E`7l(vuRHPzY;T{?o#Ywb_UW656CPx`lWV97Nss$IgpoCy_ z;WVNEMvjaj4qiy397%9QHQw+pXaU0*o)Ci_jByNOloybJyp}b<VVn*LCqugH)-268 z)bE7jJLPg@xy%)hX;?=SrZ7glpjsaFNHvty!|H;wN<FTw@_YCCsw*i5RP_~y8n*<I zh|p?NwXU_TZ-uK|kLjai-s=CZkBJ<U5ctf(Fv5X=2`tbC>!rdn#Au17$Obv6CfI^A zoN#i2oGRNA6~;ibrs!;FncQS2=Oj_JU{nlffLhi1b8Z2JtrD5Ix4y+ip>|=YLsJ#e z!W4$0Uu2A9#3;ZbCD%u`K!qMY@e5e|;T6Nk5issh3S;>95ndRB8j4X26&>RiNeD(q zpCOE4=+s&y;)W^CU<zws3&Y6SkXVCiA?JM+eCSZm^3-uIZ&>FPyx5L9)Db+X3aEOf z?9QyQN1ydDcs`<huqPEX;qg`2!eqs;hR;f(_=Rk(EUKSd@kh)Z)uO~Mt1F5Lm{+|z zDH94jGmNDvkb+2%utfjEF=8{g%^rL3u_6>_N><W?%jRiM6mWwMpImQy%QI1Om@?b6 z!WAq7v~B~<8>jeo(1f~SA$A#DLs8`yDlP8JjeFd1B`3z?X0&CVneLu*qzhn-VGM6b z1up)4jYpKj7cm`%>JGt$cl==tfUtrUUf~S&?gn<x_=6fmaYk-@E7S88E5*`bjd75# zJPhJ>dE$lCcx+=`r$EMl*^v(WfFstWr1jRhj%xxbY}cMlP%C{6p;!i6*cm4F?2LVE z`6WBV_k(L(q5VG-PaDMrG+;BI)YqNGxDXIDNVqMCSRGS@Q%pm*79cB5BG;)UD}(_B zzOdwbUmo*i`$zv17-bc#Tp1;;4d__}-sOTLG>Qoq^Fh9SMTaMjFoX%Nnin%U%3YjD zLTZ`+XyF+h<pLMWeTE(Wa130y;?L#a#5B$e3}m=;3}S#o7oKqlH9UhhBszvU$Pfy8 zsKF885KiuXO5bi+qZ@}HK0DC=)$@cJ9qVB=JD_t8>okHD#xMsvpqk)YZx27XP5=k6 zJN)JU3{b0ft=Gz~d@5#^F07}_itTu#TBar0l&yYdM8xz*uAmK>-0Vo0>DsVO+oGvT z1TQZLuV@Uf+!l+2y6J;}ENUjJoKlDeGOGicz#se}^Lo$+eWIRppogl0Z9s1cM2{>; z?{4x&Zz}(ywh$`J24}Zi&kuYH;$&~)hRYNpArnvmqmXO&c;rU*2l#M-3VJRzb|E%M zE*_*I8Kz+vjDZ<|Arg)u6x4tn{@@dy;pUj3Hgrx6QXvd{0XaJ4kjn1?*})OS;2A>U z5YQn!z9Z=%<dYCgJ;I@=#sM8ztsCNDsp>%!V4)fIFCEAMe5?up2~ZVRk=C@w!NM-W zzz0Gm@s)rrkus*N*e91LFs(ie#Fp)ThRNAH!vg^b1XD}|S&Rf<OmV6t@C2)x6k^=6 z$%$MrP0$U<B5TMVF9>W9CSU-c=%Jl>@CVDW2NUHTIzR<X>rr?B^oq!}$|8xDaJIb6 z;12%_;ihQezOA=l54ax3W-{Ru_TUJPKoexf&2-O4{Kxm21xIkC7vSIs&>$F^;YC(N z4U;b!l7Zx`VHiZp4#c1e^gxhkhZ(Fv6wn|Qp5ZrwZqshDLNY|>T;UxS?HTY3=^{+3 znun@1F&xN29oT^#n!yvTBRjMqD4FNhYArqr@IF`(DphfN9PAaL$0`{RJYvaW(gy<9 zZUS-6?cVMeVT9R)v6yxw+Fa%s@oMjsk*^pinydsGqj3c<=<uvj@w_P;g>1+uOC>A| zon%4;*a3#j(J(PDQI0_!*>ML_tDjga%aU*&391R7@ZeN$;Tnp!QpL9h1I@C{i}e2r z6~I6g#6aXIBO!l;A#)^uY$Shn!55sNj=sPYl#NAjAr7AoyKKQ2I%X0=M-2Yp8ET^$ zbfaUO0g|+#kPh)B6DcOS;Tdj$3~u2Gf}yC8&MMQx|J(x;%Of3v5*>`8c;EpZG{G14 zPaVu5l$tUCqtZPG&=pZhs}_&}DP}9VGVRn(7j-JV(hGKu?E;mJHG*;Op3Uy0?HHG- zEtS#5{7S|ItHvs5+~ndeH|QGmvhgH~8v%0$kc<U7z#1&?Fh{h>5~ULsQwC0}F@fN1 z{*7+rvGfYcGNULTS5Gsk5HPlAXC~?}LUTz%Aqheu3<8l9X5r%A49;R<HOK$ZHEYBc zjzJB?z%+cJ7+^$2fPoFSK^n?48xBDX=)wAiQ<nxQy>91r<SRosZIQSE9d6+hiorV` zM0_k!?7AmDHjy3PAy3ia804WIwt*LLAshHl9sch<4|Nsev#Q=Bm9P?)c;^<oQUV3Z zT6z)Lereg5tw4z}+VIY}@M;A43Yz||+h~liBy<`NZ<{VO24#>h{j%LIt3&ss0~$d@ zNfcK-D^b{h0`|lzYM^aa>j;q$i3X}3JH?5h2ykqa%>2R%V=qd26jnMR6I|g9j)3Nj z3k(;MM`~g2Y6KUYAvmAm4Pc>4S0qKut2e(P8rq>99DxdgAq?z*50C$0c0{BZ%=AnV z5q*S88`6Ot%pnrT2R)=mK08SrYT*kqL0-r~C`;`dtOFEgVHtuFs-6;2GuA1&=U`E( zt0b&GZ4p1?D+2fPD=pO*M<(u?jRU(iE#1sWY;QqtMpT)xRKKm7zN9WOs2b5k@i^j} z++^LlqTO0zRzFk@ZZ%hz_MLJF3OcXKg4HV^)3shJMhPxi{bpHpYs@y&S<Q?`Uqvwt zh!ni=6>cvflXNwS31xD@6^daJMoJ8*6gJS6Hq=!dgdrZ*p#<RI{Q7f{^3_ZYsX3j~ ze9R#h&R`hG!Ikg@VN?lW+5;TaVT~5e5uV{W287k#AsgZ$9_s%=9vT4_z=2TBVH~={ z>NNH}6%|1gknGCt>>jX|O16DCtnGU70y9<aMhq<vR4qXeRQaxExlJyi@l*@XF15+r z^3t(fRkGL(h2G6WJ75ahiD|DFo^&V(p!V|~b6CS7ps>Jh=&>?u>oNmpAIa=5I+KgU z)}lP2xQ;Yt)OKy*s@a0U5khL^SVUxAXBd{D(3Xl5yx|yz1CTl<UkNF`_*IcA#vEQj z3>M87$blOkhGDj|lcopONH?VD;TgVE8_;1s2uvumVLZzL7p%cz14MP*Q$RSjb-|84 zeXWtsN33SI5KY!&!V*QsazHomAxX@4@$OcF_uBdnngIWA#v&*hkvA?f2rnBe1~XJ@ zC@WU2CY^Y|9{K@$yO@S@=p9sG2!Y5kg|$+u_9J48plHi{X%sWNb~D!(_99La+;`35 zSAG?eTRr1jO-2o!;TKdykkd7G3RoM&A>}@o61G7XjN#|7#dZj{Tek8(YZznLArDf4 z9#Y{C(g9-V^c2C)J-{IyZXu-hAQjjF97OnfOxGNOlK#G-cuqkWm;shcv4ve2h8Oj5 zKM5;iS9VF3c5x|0BF#UirH9#yt$-1TTecVx)UK9E#g16pZ1zC~f{D4rnpW_MmDfT$ z2pg%mFOgs?yfK|rfFAn6oxGTx!zNMEVKMcoF^B)iMMp1F)|j@w?649pGn*B0wup<e z(4yGv_VPFkS(9yRWJcUdrsl^smcbe3;0)|FUpu!PjHeWi;e1+BcMdU;s9`y_vcejX z4CFNxJUQtM?ENr!UlQg{(cu~3K&BfOdq&AV(!uJ0QYhKsT*xyMbYUDG7GrZ6K6lwb zSehqacfzzXea1?d^>brv7c6-g?wHvuN38DXDnX6dW^%^G;&O?<ZGxonuqu?BU@+an zNkd^ZdIM7hI)E_Oxt-_QClW;$;#oztqD84T9@BUU)q>z=6t@;?3V()uBTiZ=4u0bo zX4O^<$54M1dPZQRZXJ3ytN}GdVGNdm8jSxl8^j?Rtm6`pK^wq9ISo<1ddKLD!5NmL zfgMDq;oun{F{KrRml4Js09GhbQ9z)oJ#QKvzLWnt_jt-d7f6@?Q1_LIngDI>wk7vG zei@imTT*NHE05U%eHa)Bv_MJB7^7K1SFFW!#sr^nAea~-$eIPcnX#JYBN|W0<YWo{ z(%o(l$=>=Hl$M>phQGT8Dp~<W`OSOJ_(jF{YMt=Q{)R5NmT($QRaix$q;;UfNL$HB zk7MDnZv<r&x-~Acp=Cp@iXj`qAQ+y(3yQ%PAZ;1g>ll^_5_q8(!ed*~^n9!#9Qpta z(0~~vW|8iT)zksM-fwy?QIvVRDFy#TJ?>*b#sSE2;gyFPr%^Y`VHrA>DiTaV9E5t- zaGJ}zyvq?aV2t`eE|Fm@_}3;TtSEUyIz(_c?7AxunL(^%ei&tnMMvaHs{<$mWu-0m zio6*?FaRs8Q}8b6AWV{1vA$U&)`and_EoL88+o7xXuv}$U=aSKzcW2h=z1p-MH70J z1snw{^m?`6arCa%9-j!zYLtTD*!BJy;yzQjD2|}VXnx_W_j(VqBU=|1x-~w$f6Xf! z#6S&p&N!~+Bq7NYr9mD_ff>qUzQExYsNflbVGo|cVkpe0$OB(knx(TR9hyO=8Syz( zvCD(<9jd_-se=@nVTGA{>%{+jUs`vDmwLKsX?CGHssYzOJuI13)~c_1fBNS@JymA7 zn#KCAFcc@ovP4UShE$yRXsR*s(0VW9drpcLov`K%=#A4qUMK9~AJPESMco~Th*FTy zYPqa3ll6QFJ1_kCSrL2I!3d9IrWR&FAsLd7?YGxW#>4Hle~kedz9AT7IvAE=7_fym z5coHkLmW=69ui>|r~$t+gdBSA9g5)(*ui(QQWCdaJ9qN7xd$ECK@F&Z9@dB*o^q&j zJ9Xh+6VbiYmWq~_;bHM3?pxSjOn1yZwyS9It3;N%({Anf9nLS6egw2EH#MtGY^(K7 zc&i!4Vl1!>hnf&VXD9!3;&-gQF;v|!9#-uHPbwV?tQX`{KT*D*SJ!3-cEAWt{fItd zP4L;E?opw>q@Q2i3h8*_z^K+IL+5E>4?bZQR8!Y?y)`xP*I7sC@Aep&!5D_2IL5T; zYo|ldFB^Q}b2ri!vH={jAsD2T3sNB!KssXF&%j{uKn%tl;*TDtlO6y;4c-A9-hKeR zoE*M0-8~l|<jFJTj2%05=E$W}m@b{UhY%x5j7YAc#f#*|Y22tWoX3wKHG&&SvYW}1 zC{J=*$xWL}Yc5|}n@O!EHD@?;HrvUpXU}CommM2QbeK`2z>+Ej)~na9r@C@UoodTg zEn2i<X>En7YghkMrb>w|MT(TCvz|Js)s#t6qqmF}Au2S;k6k}}^x&yehYp=NbL6-g z%%*UfGl<QUSquiumoHl)Yr!(5G88CIGB-hjq)3n+JZ{j4!Gc8xE&ufGTg|$)>({Vj z%brcUw(Z-vZ|nOvr2`8XGidDK(IZHaB1@KJb^@jH6f9Y^M1I^D%wjWU5T8j?c(9!B zbN<rdi${+hK6eKdLbQm{+qaT3Y0}gQt*5eM!Gd-5CdwGCT47a7RZ~f&%YjcdmDEuT z9!1nKKtZ_7Pd@F`Ois?!G?O^lR1;4;@+2e6F5{R}j4yD&p++#>Sd-F8Bbh`JI2_ez z<Bb?yWDfs2;5-wI7;4xN3_=qXDN#cXnWK(D>~I55J*UVb4wLGrgJhCM8kyroH+EU$ zj4{3_CQB^EB-2dRXn502IyK{yPeDC6RD%sB)znkFL{(reRb7?UR$hGt)>viPw-#G& z!6g@6cj2WMUw;Ai9btwYhS*|dRQH%<lv##ZX32FH1Q0yzK!XgWb<hMqxwY!*tFXo@ z>puGUqt6l@zyJdc!tnrvahxsD1ap^F2AvktQP<dY+HKdJ8{h#J9(m?9svdjp!Iz1A z^woD3eqres%O6raBgG-N%rZ+XwG3#>o(Lw`%Yt+|2;or70QF{1JY9&BhG;qiQ#R;` z^CbT#y!aBzE%Z#HhC1Ac*$tTCfD?|F7;Cg8IT0bG4m#GPL!>!K8rjf9CqI-9I_y;A zA&Bs3@f|hnaI6r?SZ4Xq#ujDVWyL^)Bk_x5nrSAQG}V+Lo6hjGZ=7=0dz76{L8T{E zR$T>PEP)D2s99*K)d`~S#Wh!5cjfh{c!3E<X&RPd$CzWAZlOgM&Rw?LW}=cR+6*wT zAVLxM_%rL_h$pUiY`fXRg9t3d5ZrLT7J)=^nH6hnbkluN-F4YH%f?{P$^n>P<Ka=> zdFid!-h1(7BDQ__m7<?1u{dJHEmZvBin{F%C>4RZ#Jh`vz(_sJgF)%LuZ8~RWE1~P zGr81FHQB@i4?K^I@{ApTsN>>`F^&Y%#TcVs<Ca<~nNUPI>kLuKCyQJqJMU~F4K$;8 z!Hq!(iC@aH#IuapNPRatU&VwrF$RulB}R)0($bWsf3;~}`GVSm>NGW`R4q?e!<wJA z!j(YjM=XUh)Y#fmHn|`IZFW)HUi$KvNxdy@ipf-C>UOtI=}j|B=v%31064+bz#jcj z&El5G#3tHCAN`<53?L`D8c+^c$r+aBp2N8<D9bu!2;FwLGrH29Zaj5R-FeVsmutOF zTl1k0?eb#^RDdNFZ!kh0YB7seXr*0Mv5GEiaUfmDYbnYjN`x@Tubp6MY1IFipaiu6 zj%=`_8}1;65-jlzbYvqNDPf@bEatO|ks}-=BZrl2_P&b94}PzFC6cU!j(4PD67*n) zD#}p~T1<%@^NVFd3TVI@A&?^;vDg9~IJ9n*DT3OVpoSjVG^f2OLPFUfgOWFlrQ8XG zd*V~OutLJFoe+g!JImO}<{q;Zf>ALv&kX(2HqyC)4VF5C+;m7c$z-8ZQ}`j@JOhLt z?4Slk6hRE=ks2pD^q~&j%{x>e0vJfHSCzY56SUZz%}K|Lo&#eTwF9?jMawVbDGwjm z=m+&I;*E`n&wRXv7E;i$j<Y~TEKJeItp#!xy%@$U@+7Z$DMfk9Q>6d%o)^6gWhhON zM3XjJ;u3D8NgKiNh4$c)3|=6kMA;A}n0&?&b7Uh7eTV}qD`KTpwo;gIJyMb!!jA9V zVho~qhdAO<4_-vW90tk8mE=cEvVMsq6`NQCCHBk+N;8scYLlCu7NMwZvx9cBS~&Zp zwOF*GgkBlc*HlP0Ma>1Cj(QXg>q$DpXeWm{tlJj;nYT|hA&3MuC_+gi0vgx@A4-I% zaEB|a-LOLhDu~?Ve1*kf5z9GPK-P3V$1KE@w2UW3<LXv=mv>?dJ~CB{eeOd?J9_1_ zTMJ$-it&dxq@pT#GAg~KhRx<-&_dJ%m{eoJ5@(vklhr8LlTQC}ifD+V8s?DEM>?Xw z1y>9m&-g<yo&g9^up=88VTUvJ;0jf~FH2Vnv4}@3;wn`M9S|19ghvsEVX#Ac$v8zP z50Xlq5wn=cZ1BYt=s;$oq-fBbAWa@=Aq;A;D3?WwQmS^K&1UUSpEajw$&${r%!h@h zeJ2cM2&qW9jWBSF+uZsY8QOXZh)c*V4|Xd!70`np!6mMo=Ukh6{G%BiNUjWMV8tE) z!EzeSTt}ZHT`y91q}F|w8N;Jp^KjQLu46>DVmecr-p8h50ShXkyy^5-MO~tJ!V%yg z)H@-MoAqi2EM7qk2`#lkj(p_w_6xzOvcyFoL$S*~1P}jtfWjNxa7Z?QrsI%|1HyLT zM#ByP%ws>}4Z(oJA)fIuiMTSZ!c5tcSVoUOh=Lw!xJAp*p}l%YX-Vo}WswSdz+#W% zd_I<#t)UrBq}hbX)`U~@v?(>JX?9PX{gY><92Rtv7R!x@%ObR#HhFegQeUoAVsf}c z$k@%y0kv&%)XZjzzN4XZ4!Ou(V`p3VCUSh<L2&>rEI~u}qaghpc0xx+(q%Vwj&4+> zvn2^h#8JF8EpMRE8=!XS0vB&^g}G933#lAWzEbnWC%BM@SNI|*jKnX7^t)f9u_PPX zh=UX)kqvI3qZ{P-<o06hjc-)RtRBf2IoN><HHiOWMHim?9~j0CHN4|u3wa33J|;5v z1rXas(l$As!3F%?@*VfnD_>7Bjc(9bAsn+d&kUR6kHnj?wRS9;)P(QJ>N}hKu9v^T z32>{B6Hq3cathP3PJ}D`Y-!8OUQh?|*5VU~b9)SAdRSXDd*(BtnL!L-Kv8x4;~pcA zzR2y|ij(iT&wmb<b2SH@EJP;eV8jkd6`fsb>7h}6@a`LXUTI5X+IDpu`qr{ii&qRo z4R+^3F^ci7c|pBS!0-%e;0nR8cS6BP%%F8!Cu9+{5;O5Vsqj6M05K<l4!c%vyub_M zV1ec^4y5#M98nP{_6%_F4AiC(=1_nX_6Gmdh7N+44(#v;sQ^swBTMp=Glka>?{Igb zU<VdPOZW3Kyc7*AlS+X%Oq<7fB7s<+_drx7dP&1Hl0{jSm3rH>dQH}PBLpA>M=0a9 z7PjX?sI^k6MNh1CPro;D!M7>IcV<p-TWK~bpm77r$9x?y4$mijdMIahMhDiHax15O zF2_ZMMje<Ueu-8_&=MGoW_~P{e%Qiu+tMxWmmgizX#f&DRdEYqKn1Cg3$>sNPH}2< zk`&Jn2Cl##!LU3CsDRSLbq#1$;_wVq@C@{D2#1gk5hEku;7RJRYw%DG$>0s%kPS+b z4ez#N8&MJCzz!?JF&d!`*^nZ2WhMWD7Y-?c25|5WF6c2NV={83GOJ{bIOBqKB?=|@ z4uTb8zZhU!b#CmSF-W*E3FIZqR1(c(5<mupP^B~&Qe;#pC&$oltH*jG^m<xxiL&>F zE0ib+_fiZOL%R2H-|=Pl1UG8PPZrmP8E1S!Fe;&ODuE*c<dBDZc#;og5C3om6i^z$ zfqg-6IW5N=(3J&Uq%75yh&E?BjhIF`*IkjQE%Grt-!c~P*EN0wAoNEdP>~Dqg*>X) z3&9WyVGstB@C?K7YOvN+{{oBj#tqfr3TQ9}V(<*%u!}-75*~<R9ik3<#Z|oE4IF}C zK%+4kK_lb9O5^Y`kasdD#t#2eNe|#=c{hVICc}<6!w#-c25#UBHB)$RS0(QdKOWN% z=&&U0KyLDI3f?ex(#UScq+`hlCi$q3jb${CC56>wdZ#Cl1F3o*#AG2fJmUmq3R!Se zc5s>S9*wXlV>pqkRgu1jk@`e&WX6#KwQ(Oghazbj%V3fy8J$aHXJycm76ph{G?RmN zEZ>KdVI)R1=N&wWQa;H#>A@cBH<UnEltOo2>E$kg1Yd^qbVpS$#{djJu?$(MFRXbX zT-lXTRXw%_K`YS>8;Fh*h7P;fKx2hs7WgvT!wc82fe6+Sd1;qAk`Cj5B_#rwEGU3= zwK5JdKu2OFv$P}W5DfoZKo7z21T6>-CaNSy_>J!qV(8Eizo<Rea1G6{Bp8Mf!<0b9 zmQ19Xk3|C$lT>d}NKF9QngU6X9%MCF^DcdYkf0?f1vh)@6i12TPGjhB!D&NiNSymr zaT|#@ZU~3R=QqvS0mA^D(ix|-q8k6;1ik?Sdv*iFk)7LDlQ8F<h&V=ySbjeFh;B4# z?AI-GlxdnKe@aOU!c!peLW=e|ke2Fd_tiAi1W8B(O=MzrDAr6Cqf8os4jj{t+OrMG za1GvoN(hz_;gAtPYHfh^42J+DLvooTbC~SdRs|@ST<{FPzy@LP2Q)^Rd#MiGc%vnQ zGcH4Jyd(@F6JY-(Vly~qSj0A}rRhwe$B*|`dPY`-NLGqin1xhPn*eg9w_|W&Q+r(s zkzcwtW@tl&k%q-NW;}$Zmf?{gDH<}MD;+=za4M$+>ngQk4?%FJdAg^TlSP?RlQ$Vs zIVn0ecSen7sF4OcK1Y=7d6Yw!l(7J*?gB4QS)WoPCs@Z+O|>SF)v5gTsSy*iGQx{6 z5)un`Y!8ZJFjfiY5DzYs4uWNu5RrL1Loy#zC4;3iBX(jCrUoej2+xoQb=3xQSC~k` zGTML!;S)ef!ZA2%4(_-;ryvf$D3905V4_KE$pj-qbDF3*dj7~XP3okm2c>sXNKQ6R z>Dq-T^o9Rd_O6SvWx#2MfiaxGr;%ss908>nn{j;1`LCwY2?JZOl>0>gU=KZjTzE<Y zdK!p<Mw1@(QGg1b<Yzjl!x!dper@DZFcn_wd1;J_lpq_jBTGE<`E*8wR4A*JjkKvP z+jVC0ss1IZh;>*vt7|U<BB!toMA()cNVF7zGa(jBBGao4agKQv3~wNqY7h=JQ<yuV z4g!dd%(f#ns4@z{GSwh?^}wpXh+_$1p&p2r%J^=Gl~|?ewnqcEs=1osihAP;fU#+i ze8MNLw>2eHLgz#lep^}(iF@%>hF%tN_FATNV{tYKP@m!ixb=~2`mZq10faEQm0QA$ z^AG>@AOeuHxq6yW+R1%3DY_E-o#QvCrc0iwn;wUna51Hxl^DApJAaV+E|OZZ^Hr%z zH6hQVsnkRhF6(vuHN2rzvvqk)=;IMLS|t~F4#}_$*w9HXQzaGQ5Sa(PBRXO<TD`M` zwDxllx|)q}Fh3@S5by8?d?yC#sH-SrnYx+|Fm?`Ln-1WR4&uNK51~veqn61i63K+W ziUoSzy1z>bt^sLTuo<NUY`|MMaOPx`Rc2*~(oVj)WvRP+6HF-;Y@B44!JdK{aEJsR zoP5g%0~Fu}mutefJR1_#0V}**F6>;OONcVOEHtc>-eIw*TP>@bvGCD;i|VoNsg(bK z6i&BGsVB=kyqkdk`BVXlq);5i`8Xr>+is>r4mVm2CYGwnP!91x4e1cZ8X7-vMPfKQ z#~;HoD)tO0wyO!j4n6n`ocIoG)js8@N-xG$<zNl(pax`62F{=jrkW0^kP7PHfg)kQ zMcPcC+JH*hk4&0x`3b;tVz;uXg`MSDS87MN`N{68C<_;_dO$;`jE1R<uNZ7*m*L8x z;u&*ThqNpQx17sD?HUrL!YTk9oXcDd3(VUY!yq-ofyy2BG@dB6T{@hxjL>sFTvP8? zNAcGcL>ICmOT<$#ssDG)Nz6!0{76nLpt0Bz3rf7^lZ@_`m&}L`dHK%kOK$)0psL#t z51-UB3o*tfO3znP*z9OOa}0x-$;S2U5Igt=dtib`TeR&n#uq4zXuzUE@CRY=40}*v zWT4NLG@2RRO!G!>_Eteeh7<pLF9CdoNr5Nkdaj$yX;?a1?aEGG3QuYyuf2Ce8L275 zhnzay!H)~DUqHe`ZNj_U%Sl~14*Rg7+d0G>)uqd5IA@+MH3*3CT`}czl*rYL`qf}9 z#3L)I^J&dUJQOMWCa(C30s58T9L~j?K3(FqD5lr%z-!xZ3O(B)Ewf5zEYB)q*or;J zMoXd;ftijSOBNBn&iD@HpbGJT21>x9QLv)#zy-lT4&A_DVA6ysp}+qU#J^11G*l?k zuSu?%1wylFz*u3MQs&9K&D-uo$__WL6ilY7oUa=EDLdV-A{oNV4Smhs+|T_R!O_CT zG2Ov@EXfj5;YYfIdPa_@bKu>>>Pb78rXNU&-jQ0w^m)W|vb#zQ-#y{G`bFObTAHIu zs!F(w7_l<y>y9wi#eiK6g3YW2{^tn3#tc3Y2tn8f{z}Z)jJ{xZ24M+ZpafhX4#j|u zqVNo25DX}G#X;l98Xd`!?9q>ufd9+lBu(2f?s~76(kh*$>2xS8B+3h?<G{^Y_3Gm` z?N2`RLqq<-fztt40CGt#)Vo0sFwo0Zq|{K})YA1u6D!p_*^~cP-A2qD-dp`GU2Wc& z7$8GT#ALnRXWibIs<QbtYeH5%WU{U16L%SNOmtr7B6^uEgXev{4L$2Jz(h-PmEem_ z&n7nLH)!CRmzTC0ZN(tIDh3VRLxg`o1`(L)XiKE|d!*4+Zyo)u7^2N9{-l@uO_?m? zsh-m3G<#yhP7e&zrX1X0cDTfi>&5qm9n9+?+yu1}>_a{5Q^e#jxzx+i)STm;#Z0l{ z3GF}GQq!*0ifSJ>CA*J0%_LjqsD{Ks@!qh;4CC&VlXUKIF3#(o-?N$!Hmb$Riw)aQ z4&LCid@iH)yzh@~*oYTPd8s6S@C@%j4RQaM!4M44palP;pbXEDnQ^ycBfhQsSZk?C zO&A}L09@)#8BPN-<K+~4tbTBA(N2s2!Fa)CeSz{4cdv+B0H{D$zh)Sx>n|UYAlv~? zU^p}{>?nNmz>)Kx8|60HIZ#b=;kk(6F)db&9@l~hh{`P-OI|>HULY$Vk=pHtWabTm z=J(|$Ro~61IiPVpG|Hszb8gpNzcUPR*zq3rV_)_z!{<nA&uNd?Xx#P$#4+qJ30EnD z0&UKKX$jHB1kk_?=@#N32ybi)$yDXm74MH1zY_qljM+eD%M30%mQdj^h7B14gV?Lr zE{eKxUBsBnmaST}XvK=v3e`xGrc9PXNy^j8PAxTMlGKR*k<3Mi3Jvm;lMf#~dhpbt zLubw$Ida?_Wy2;-nloq2m?={R%+xPmwrtUo1<Mq!P@p(*(qsveB0+%gxIse(3>YGM z*!#Cn?p(Tc?cT+kSMOfFef|F3tM4DZ7$R7}m~mrA4<JE`ELqY7tP?0)r(nsFMa!0| zQ^7=i+H`5sqi*C34N9jDo}PSi`WaLR(W04+8cC9rNmI*}y*;5UWzrN$RIOTpj76)~ za$6ZM>Y~^SB1DJPhbc^WkRZWk1D$<$MlC!w^4832L!aK7Hg4^?b%P&YetdA@?AsrA zUqAkE<NW_0ha3S16wn+44<yGx0n<rG9S7B6ry2?W<Drljc;LY%o@}a#kR1j;d@w{2 zA7t=A6Hi1jMFkTyhn-K}_~RLM!a;`|b}Uhb9dRsqMjCjGVFw&=#;H#~aOj&aKKI<S z2Ayu2X-^yT%p*@c@V;ZFyX^`(2)l%=duY0eCbG!6T$bzTBanzgML1J{Q>izXV3LU@ zn{d*JC!c^4iYTLyQi>_3ppuFztFY3_GOxfAi!8Hv*g-8ASP&rwd-%}@Fikh*v{O$z z9jvg!W~gBY9vUkGiO43aj4RAE<LnF1$_P!gG}tK3G}KgEtu;Sf8)OhfX0z=!-FEB5 zH%~|b&LlRCLoPYy%!F<iiKGJt%!U*~NV_fno9XUK@v5X|%Jj}<&%Gqq6;jCl^4m{8 z00AVBKot-CkU<e6oRGq8{yj%S2{}{;#C#7%_+Eum9B>>6)u}N*a>98=jbJPh;~jM3 zk)|92+XeZ^b?1AJ8*9V~Mh#b<5yu*Cq@<F(E3pK3%Y(YbPFpc2s>n=@(o{1RHrqTY zCEw=6Z6-!)y6Lr@da8rZp^C~i(59Y>%FshI+p4Rt!Wyfrvm%{gQW0jj^i#FhX1ndc zLNyGr8g4k%F;yi4tJTXg+pM$CXsvZLT#q_!j-Xa!O%K;#i)}VW9=|O&WR+zWC1;6) z7CGfMqBc5gv(@%G?7ZDhOL505?>uz>(OYt4`9iL5-g)1Zz1{&8PRBrm8+5Qi4kg?; zo@vS{2cCGC*^uCZmnV_;-WN8J#d`}J2c2=u8PL9GiV<UyXV}rE8g$@ECLVUO0SBFs z;S*B6_uzY38*+T%A{aX+K?lkyt*LTmXR_Q9mki>iV}vduJljQ?oU;*+1Z`--fz#1C z@sgM*jcLKkQ%`;Zl&Ss64M|zb)d=O8s$7L@iu#&ZmLN7r(V%RUQUN{wktw&;(1ths zi(m*7H&U4jRd-{RWiYduSk3AwX0R1$2#1<EL@jZPgN<xxQ!L!*rX|VhP37E#x#MVV zS{lJfwIni~(24FC-7-i3!PN}^|5a&!>p9nYTIV|Y)F*bb!(;7i2fY*R&Up@E2fu<> z4s2}0c*jUyAoDe%gYi*ewiA$l5`>NiISCy#Vn;mWaSCy$1AXWShsfC14Q^Z#9oise zH_Y>lTm0c2!61V<-pD_h&1{V}>k>k~WI$j@gdzzv(?*sPG?5U;O%Y@X(j;L)ra4Vd zQ47jYh*BC53JPn50z(P6pp~voVNqaP;iJfAHW9pIhB!oLI@PH|QN^H#bxYN%@+L%B z6>%znL*f}mldGZ_j#p27P2;9mC&^vWH<b&{aJU#P<<z1%V9bRs#5hLKY0FEb;|?3! z$iMZND~{=E4;}01E_lWN>s_>?*B%#^yFTu&cYl0`gx*1+cx)pX@_>gpj3J>w_RgmT zE0Ky=`bbEU<3EwS&wqy0Ab89p7wqVU9iv*G_B`VdZ3spxUuKPG1cM5qu!9}K0mmuz z&wn+;r7m*@rk#;Vq6_4RN03v@l0dK&agx&nVG<LWEUhNa)F3pa>A??%a8Ow@lnE2% zHAX>(h2x}DInSw1%2sx5?Brpo;0eTex~iUj`^*uO$j@Cl(N_U=92E=7n=Cf#awEwc zNE-Ukhf36QWDMO!)A%iLZM0l4TOI4vCDN&evOgx}PaYxZ$P_ISsQP*-#MBYfYG{l? zvS@@n<Z+H~Y^X#3&n*~p8CFz0?x%X$7)K_xn+<ZbFRJhvM;pX|1~GucWg+cGHg2JY zJv>7_Wv!(xwX~fsc}ZsnbZao<N=!B#^R9UHgff{qEWqj^Y8;$e)eL)05^im=-b`WG z#OXq_u|S42v}}r1>=(?kAO<qf><{Hh8F~^CwD?To;B@6r(<<&Yevo2qX0lo=t^}d4 zg>4sQySa<hcA~ho=;(Gk5P_`Gw;hG!>V`|)BH<^GUzVgw#oOEwmAOHb3}kgP84quq z;zEZ^Bs+jAJ@FRRsIo)pf2=1y^3@1^B5RQm&@hP?tn6j(Vb3MAyg##A={sm8@Br7! zRs<*Ttr_9}NSfyQz@kC;iWIDqUv2VZJ#Da0R0Gt8N0``ce)yY^an#sIOewTsYQ?w4 z^<8w>mczi<hjyE>-iCM;zkw#7`n;8n3wO9)`53jS9kLZ!Yh>3dG|3G8qLXh+o!n;U zj8o32M#aU^{e2Xq?-MD=j*DC`>(O3g7OG1_<UD=lP8~93$Hvfcj$~}39`N`EFydS= zbPP2e38HiKAX#3M`sb3FEXO#qVV@=i0}dt-MKF{gif5qXzFSot%m8d9M?0ft0wG8) zCtaPLRpinb$+TQSLf4Tvm=t*ZG@UFstfu|ynNrJes;#-|Y<jqxuNJYaUwAfq-~+|E zhWd*C1!E5$WY$zY05;xe?Aa_3TULLo6|$AMV`c+1C&4PjA_i(KWEFW?mJ`lGHAf51 zLDaU^qG%a)i}KR-c4lrA`A6rNZgqqC%SDB^P?=X|#*e6{?3n4sWDyB?{5u}F*eQn; zS?~ZQ9DC$7yzH`(jeYaNdfh+=FzgTv8z^BCRJcXQKhC;1GCIH}Ut=@0;S9bPc;yah zxut_SOa>d%uAW9(sMTH*JUwks7@nrkMTpp<EB5G(O?nGo*a0Nm!yiwNdiX2rk9#1& z>O8=DJhd+D%y|8tI2OCIPgC~Oo;}D^l(yTCjO5r#tM1K_s3+sLC_AHX<GXOXGT;*b zye%U<l47@ZODQo+JQMLF=$bbWnYT)UkO+B)OxhT4;DuADhk6hOZ-9k?*}#H3I6I3Z zJbS<)K?imyhj=(8c2I*qpa<5212|9zaUdl`Ll=;XnUcGuW*`Myum+S<xm}{PUgDVm zTp;4xG~+voo0A~Dsvw$ZrVO$$!3w$$vYNxfCT+@!>jS4))4oaJKJOF1Hnc4AD}uO@ z0UDs2^y93p+ncV76<IO1d=i|}=qJPJF(`_n)Upl9nVi;wJ8LTrCG)?BdXBrJsEPuU zy;CE<1CMgyC<RoHb0e<eGOp0WqvcvDbEv=%F~!DH#Z`>1G=se0$puWfkP#IBhG@VA z6x_UY=sZa(uRMAea_9zgsHq-&hG*CVQGkPtdxmZ}w?i`-bP$L9F&Rb!4{_^;Ne}}y z2!&=42;W<XCX^1BQ=lf3!kKF@2(rSw(gaZ3xkV@hz`_Gl>mX_hLk?rLtgsAk!ag*F ztPWU$eeef26v%Xf!wz7JIjloqTY@0+EF0^Lr~sTC1H{4+M6<I$Lu9)v(!WKNJK1t5 z&e1l!gR)B0Ej7xLHcFk4Lk~G(KsvIcA`wM*d$$Q}sZ+E`=V~6GdN|FKGa8JCSttZ} zkOx{623W{E33(WZu^#Km57<$+OR|w<I0uLc2XiQfKnR46L$@W75^;F{21nRIbYKRU zX*Ar^hGO7?t`Y-lFov5kumg(-mxH;D5T>9BiF16D2fIR0vyI2uLZ5>gFGMvkR5iq^ zibKIiMcK#4nzatdg2@`l$ZQ*ZfI|^b0T_q@8n`;gc#MVYtjo}X(A>lK3!G$|NPkid zi!4Ois0|`JsA_wbXkiXWjKpoDMC%|Ra2p6K`@59PvU3?ckutBCjKF$<o}pT)n^ev} z5|MgC#Rl;Z&C|Dd*o92^mwK3o3qgiizy)U*m}=M%Kyo|>0ncwZg>AT`aDXodaT56X z!6>nYaZm&Afdfx42Td#&lA{K2(FR`-gJ(zuFL(xDK!}1MAh_)RCAoyF<(Mm)BbvOt ztG%R?zFL}_Xg;3UAfWT0YMQ<=L`+v(%pm9iv}jB$fK16mQBR@Fdnf{f#7sIwKhA^< zykS3w{5oUHvBBx5)Mz$B6sXoj#A#a=En-C2Vko+!&F8R9y_2#7+)Yf(MBfaq;B-ll zA<lV0JesV@<wTh1N*D_Cqw0~f2$?R3@yU271x+ZV5gfs7h=*9XD^%zRheCx;n1xvw z%JNCi_j1ovf*(Y)26Iq@TX=_Gh>@0|5?lHoYY+u1=mJrohMU2eZ?ul!dpVfXw3%~I zyNXbC<jcNdz6<q<pGXZq`4bKm!w$QO#O#U?9nrLSAqp`6gMYY(6tz`Pq17PhfWyel zUn_#nWXQd7$XTJ4rij1O<Wbf9QT%JWgCf!*bwrP-yNnQ{>A216$W15B5=<mHa#Km* z#4j$h(kneGQcTX9GzV5(MJ{cm&(ocPLkDvxxQF4%d^^)`5Qb7fgh9}Ryfg((7z9r+ z1q#s^P?{J%T^FuIk7uw0KmdesSjn>b4r>69Ea|FXc!o0)paX5f1QkBGk~wpvLS&MY zmzdB-P`f*6zMj|<!x^kotw*9G!z{?h5L=<Lc-2{>05|vtd$`q~1q{m62PD|l7p+4e zh$nffQTHRwV>3;{p~%!^Stwf8Lp&BCy*ZA=9BiBa)-YPqZp#jgdQx%AL|Q7hAf!^) z>9RZ{&MehZd{Nhz%9poA5L09ja=6=ZU=W9+B=W3=2kEI0c|1>w9s3xiky(<h%7$R@ zglAA4+Y^Uoh+H;024+Zz?r=-BDj;xt!f|Y}1=Cc#B-xxh*`>J?r(s!WI<*Z|3S+g$ z>T5MKRH0u5f)Rx*3P^*V1=`*13&Fqw3gA^3wL{1V)?u?Ju=B&GHH~HC6_))mAj8NY z6;jyTTI85bYJrYPWKwR?&21&yDAmMoWyzKtnYCrx*-<V62@tx4TbndR_MIN-u`}$! zo^)W!BXP>9@(=rvDmqGBDFI-Q1K|BJ25Qj%22mITG=KwZIEDeEGH=}61M{Vi#Wc_r z*<w0A2`$|U#gktNEDa^Bn58~#I-ynt8zgX)oLvhR=m0;URo;c+yts#d00ZD<0fa=q z#!wZdZIxFUR^&BS<qbq;o7#Z7KdW6wtbNvwd_?Sxj*-O8lDx$4MV+%n+i(?EAtBdt zmB6?4BltxT<cwd?BUjk@M1}1{1+)g;YX)$5f?x=SC*X$vDTtJV;0R{915(fm&Q#+N zUA<JtleLpVct@T1;Ar~7FicfeE8%Zap%mVM8gL;NU|~sk;TXnbx|m@-u;I)++923r z8tq}t_~AYjjj`J?L97Gk{jnovyF@hqvS($)Xhl*d)?TpX-T?AmlnmeB1XnJjk5C#C z!#m&k1><9WTNdm^!&5hr5v7EUlGU*WW?ac;0MIdjgE#0ZGJs=os9ZaiG)k>hJ*Hqx zZJ;&5%e+j-WLihQ>PwsGIS+n5L>^2Ka@|!sOzUH;CYW8b=z&O{WELicOU~p>p5aXB z<iyBfP$u5I8RgHqQTW>@KrF2uHR7~`oL4p|MNFvJ^rEh<&1<pNVHm(|;ok1$&2j5x zUluMbc1d|5=3+KiWTt6HV!=B@UoeZ8XLcPRTpe%_2XWwrW^kEQ_=J>EU^@_nBy>`@ z{5|ThR$%z0OVx<FRFh3DnodpsCM+x#QR_K9ndjA|Cc|1}*lpwx<Hs79ff!%`73hFr zAn1aQ;Tg7u4p0FXBNZN~n^1OW%itTPg-E9r;);$(XUhpfHbmS=V*T4ck6tp6jwk^v zX>2`dZB1!$ky0&7TXq>&otEh?u4yn9<MFbyW%kAVB`!3U5^HvaBd`Kr$OdQV1~T}b zNjQXCD28lk-~e)Jg(#P0cnFe?>Z$hJnEMFhz-kDEun1en(yfVoUD<h-CO?rrF)WmP zj@^BJWN}h!wr1g7h-=>Uhw&!w@;2}DM(^}i@AYPH^81H$u<KDN6~=Ik8FlDZ`D=R$ z>>w86WgEoBiH#$c-XgpIIU;pzY57R!ki^f~-mulyUGB|Z4lYj=S7C-g(=JZq4DAh9 zk(=IP{%sdw7ODS@qi!e$Z59P>ZiZ_VgFFxeUw8(~bzpGz5@v`5Hy{N(7Vfw#=by>c zyEH!F(CP@Apied3Q8VPQJ~et&HGKZiqe~$aeyr|p>keoJT5azv*YYiAZ@JbX5fA~k zcqde`Z_4lruE_5jD^`hwTGZ$<XA>yajGV=$9A=5T>Rqxg3M0ubBQr8UUB2w^a3hb> z>~KXlcDavX-eMNy@J2@v58q<*<!NX}<Chr+QBVVR7>7Ry2L8#0Pml!JHo4v8?EzW_ zV*rL@xCJl3#$G7@AkeYa&W%D%L+(Ew@|>$6zl3Mh9aTONYr-5lh|H$yD?=0ti$-D0 z7g7Nc7>Dqd>)qWo!*Hkhma+A#F{TAOW7Vgz8{$Fyv8o;LEXvv~B8k}Yhy+(~J_lPg zvTP_7bl>c#PE6cSbQhQmz0U@1M@MEz&uL#YF5_~q5s&8Ddxkf#12y;rb7+SB?1pgI z&+dRUa4s-y5QAG_2Qn~9s3zwgr^{MsP+MQ_<m<}|itcy>VVD(^s~O>|$Zp083n}OB zrR#uZuhnPA<nJ@TQPE8LR=>V(NUw|NW7~H5b90L}Vq!T&Nmy(GANM=IwvSHI$fk&1 z8p+$VMBbwR;_-N+h&_*ar}uV=$@A^Jnb!AxSLR4J<1>a&PV9zZkc3yz2D7@7TS_Z$ zdyi0P*eCdfV!#&Ro?wn=ppUOB2pw|fHgdI#=TcMMc}%r?7WQmn`7-PpM~3;cfYnJ^ z_IKz9@UwZK6^tn;T3_3&V7vCw1maUBdR1O!!(PqS%!K?Ccj_(oXkCuZv6iTA@IRm8 zD<kwPKJ=GPs**yk!z25$2V;H*kOw>|Bl*Plj30C{4{jKTZrD%$36Hs-aRKTUW*7!D zxPxqP1vL<bW9Wr25fgEY!jSdjku{o<ZEklq-NZlSUkCOM)f%iQ_I-vm7P|ap2M7`G z{^{HQXYe4xgbEijZ0PVI#E23nM!feA3<Vf4V$j&ZqeqY;NR~8lViL-flvuK8*|Oye zOfX=|lrdxG49+xc*tqHGM$Vi$bm|b*W7H2)KZ6P(TEwVPBT1PuY3gLv6IM^8N^v#i z6%|;pty;w@8>^NrTe;S<)un6Ku3o)>(FHc_E?&IH_AWcN>@Tyxf|)fd?CdaNXV$1$ zYivy$<j9b@QRdd|GUm*g!Exps?lb7npvRFeU78%~)Tqs|ZteOt?AWqr)2{7WHEz_V zON;LPxpQaD!ZBBtY`ifw#*3*nv*xVX;lhIh_f_mS*qc9OBsnX_jPBjKbbG;d%a*PG zty;8bnH?JztXHmFNoDn9RTF+mP#ZB?gs9LUN%3J69z+R6#~gCV;nPlO;B<yfG|2?h z7h7nNMHX13GzAn;IMKusOCV815Iyj40}V33z=8-c&_fVKG0He2jWyb6kscJV0D}x2 zeH7A2OPJ(Dhbm#%(o0{+M3YT9>BLh{3I;{TP<R-{M^Z{L<rGv>;b&DR^^vkwS6_uS zmRYgTQVUw=<>D4xafvrfU3uNL7oLADGaX@uC3aYH$~9(OWR+PqoN(ZT<5@VnIXX_G zkLH$|ZIxPjscn<u_9&#BlJ?u8iy|tVp@c%_7;=j>Lrr3ZHN)pJ&Fo^zG0mj^^29r$ zQ1MJIcF}29U2>JDi<@bw$6kByq2iS(^3j)7C-`ZS$$tF#2Vj7H45&webx?_*f()|Z zAWmk`RK|oAT6m#`9D4X+6G)6$;tnXvzyb>$6mgF~1=;v7zyS*kkwuzxuw#!N^#DW> zMT9tHkyEV1l1nkoRMUfJJn55^LJ@_Bm3n09$Cg}5;$>A=VKt_FW}ZowS?jgwCY*BC zX=h$|`lTnIuKwvvpn^VTs-dH52Arb4h34rvnv#Pl)KOpRv~HX#9U5?=8hx3e+?c8j zs>`w3s;h(jrOhWtz(GbZw}g>O7=HvKS9sx#N1j{6y2<8x?X{vTv-3Uwi`9Ko@yAGi z*A9~Hwgr9*u1{_>SgyGef&r6DT4>R(yCyXe?}$M3utN<r#DFgaTl{m+z^%LfI*k?` zbMQt!F5K`)B@u~|N}5-!<i$4Kq_IvM1NChkAYYkf$xlT^Rmx$mOlB!Aiv@F8GS}kf zn{U|+9?p8{%yZ9vCKf2FUl+agWl4|5H2j)MJwN@oQC&6skM;%*`&<`iYS;qxr?Lsg z8OIpLGsG~7cW~ho&-euz;P9Qg0qbtV;$C{zgREG%=RNTeTz&2{t!gboaf~AnQK%G@ z1xZeF<D%TT(zUM5ZKy+@15xNkSGv=&fC6*)hdp2?#32$9Ar|TX2JJYaFop$5cOBy0 zN|0nRCS@!Q#f#GMsPwVrC8c>?LYd06LOo`^2Td_!)AnfQy}8^he8bS$&h}J3==>}> z=>wZ&9#fhAbpvVO$RE?3R=+_;?SA+Jq-p$!8UBr`R6{$}sZf=ipAj%H&FITB)bIya zyrCFxRE!&gMV?)lr&#JyPn!Pb!Dh{;KK8+n;r7D_MEoaP+CrhX5R@Qsy%0i`L)Yah zq`3^$@LeDhQ4vH(I@7U01r#8~>WV1MX$njq|6qp*RKS85%%BDy0RoUna*~Ke@pm!_ z-h-^T6XP9di+aFPQkGIe#6`tRU=mZytY^mTp^<ytgNt1M+891Kl5a4tqT~6{=NR?v zk$rxQ6e1mUKdGgoq7`+GMbkk@))<m$5Vcy?7}>r?Qs!%5ljI}^D4ppngBrttgB5P! z3%vL$FX9mvDNA`CV{Nd5VF_F-p%txZ=?5zPsU=eQuq|%o5?m~FA-Q}R!(gt9m??SJ zhme^}9Wqk|9cV^0sW~uzkhQF4Ju6z%s@Ao#wXI~eCOu%#A{cb@o8i<Qkv3G$Bms|# zPFg1x+nGErB4sH}q383y6h@Ynsf^fD6I#^5JvhmQjWxv?L3t*}J-vz<byVn}h_*hX zx$k`u-OWTdDx0Sb@_wgv)czJJQq7d=YXM9tVk*i13_bm&7{16xG5YdGoQVe*mCdQ% zcA7!I0q%pP7@U0ycQT_YE~!g(Tu>79)X6=la_JH#yNc;KWCj5UJRsc+PUqEu6vVCW zeJ_05D%RHlF$f~qQC)cePLYW7BzmP7Uzdcjze4FJK=IgMj}p%<RV%Ug%*q(``B*ec z_B@m|u0S!%mpJmNPY6W}V}yps$mnsjTT5EfUW-~ms<y=(ov4aU1FGNf(UF9@?byiH zS+nU0j&2OhT!K8T<gO(>s7%%>KRBik4z;M%MXI(MmqHbWt0&wQp5-WHAq;U2t07tf ziOh@M6^S4QFY?!X)2wEPSknm|&`5sw>oC0kk`oI^N|JzwM?An9IJ+OSl2VyROT?ax zDqxbH7#r)@G_5HulU<`_-T1~l@wUT0`x9s%X`HU{(S3}%+GjkKS{JLfqn-lwZ&0i? z_H_+_D8+4bR?6eP7{eHTxyv$emY`)+c9eN5R(jIJL1isV$%8wzCZ_vj09hB8y40?? zq8cG!YWYG|<<NM^tIQhAfXqLz$eP0~ZX^Cf3vcET4Q}uehVd6-P{h#h`dSk`Z!EA= za_2h>TZlq9#d(E}o|wo)#+NZVvi_uOKz(&t@r@5K)4BAYmUBl!nK)6h&0364V@TGL zT56`wIHVNWzuMk7fQwP7tals7z8r)98N*Nm7iwV)@ED^FfXL1=bm40vqi4BD{;6}J z3nrrS2P!3m@-3N~!WBl2yAYZxg{*B=8)g-mqC0O5RMbP&v2NTniZ9s19(IekAtSX@ z_rgLFA}2y|B`(2p@aWCwjv+W?fz~%72rZRNJa~F#k}%8~?PxUul#O-MFr@*rSr32K zjtf2MLOJcw-hjMm8}Io1KA!Q|j=VTwd(7trsN+}d$r#$;hBbP83}3wA7N1}nFm_># zPrQL0haiJBTmg)?@Vw_o=AbI!1Jvg-Ia-;}kMm}^Zvjc!TiJaoRJ&`rU{(l2SrBj4 zb6BseugHf$6g&9CpH{Em=pTOn(9uTfns$fvH)0a=9o(5D_qk7LC<%rq-t|6}lm$GW zrdaeD&5VV;MP(Hiogf}xINZaT4~RKlXdTDtHIzd=6sUa)r(7Q9L5*vPTBm@TAI;X* z7>cHm7)qU-jtPb_Si>TmfgCskGaL{z+{!bALKyH0FcgC;h(Rcb0U#8^FO1SI48tzG zNs;A(E%eRL2_GvFACu(=@)^~C6hf9XAC*;EgOCfBQJcDi*Hsx)h=dteX<Y|+LRgWX z8BUW$07D086E}I2e%;kL=@tB03_AT)<Q$k5C6C=L*kL`z$=DO3CEDKsAU_FUTM%Hv z0SjhLTH?u(K`|hpIN;F#Xj+L$;BYWfX@v@^g_@)oQU+=u)#T46W+DiZR7s6sBsoUV zpxkb?lrMCFC`^JHG{XT6LolcTE{4KP4TCTogD6;mC<Mb029zxX!Yk}Tg&83dmPPOZ zowK--bUE2kF<Y}KT@`MZ6~R!JZQ-?H)iHtLGQ|K4c$G7h;TfKz5Lpv8%~hPKUHkFQ z`$-Y-)Zv~L*iY1-9un44@Ee!ZlVTwnV^z=p{onO4+M1-%00LBTE!=Q5q5=wrt9%&H zWEw+RqS5$9<!v0LeBx|uT;)NEXq2KUmQ=~9qUhz;O8vz%d_pO(!!5jlFBs4pErT!& zgUjWGF;K%XV3;lc2*WLqffZOmF>H@6pvAE;S95`oP#K?-S<Ai!h*Bw)HCAD?IY<_w zOSN$!wpE>olo!@@TQdm+jG!Y~z7AZm2*UWte&x<Mz1y8l(Y&P-pY>VYT?zgf);x8I zp@oqk4qQRT3@r>^LViz%F&u9_q$NRIBnk~G;*sQC;>BgnCW@LyavVp(hUT3bs)-z{ z+1PR57%L8jGXMf0sDUVm13}fIO}&M2$ptg)ff}&G8>qo8*upI6f{|@dED&3<DJ9`Z zmn<C}vqj~Abj!Cuo0avFR7prycH<3c+gFmAnT=&xR;R$!*SYlw+A+~cxSNr@rMxvs zPRwP;*k8#1h)fr4iQXxeD+!$Spu#?BPcp7W%_O3vF=7Hb;v-7rL^7sHS>(~QPpWms zN5xoWTIOX=6gdP^L@kPE@K11zq-}v_Xu9BDJOd!4!ZRR4%k4!d0mGieUN6|fF#LfS z{A4KHf-o4%QJMv@0o9TT6)Z_(2|Z;}8HF_p1#(88Hp);{ZOB%Bj@6k6ih!jE1OdNT zr;-MYHBABSXy*=qM8m9I97+tlnN!>i&y(0=77;}q;OJedr@u+UKSG#$5+uQ$kzgKT z;T2}iY*<0<XXAy<e^N%LePDs^MxJ(}MqcKNZD8dMC};3dH;~+Cz8WQ^oXRmr%dwnl z+6gfK7(*I3!6zKU5ZXd8jKLF#!ZB=5T4a!JHrEoy=x@$waMqG7QQ`CPlC*gjRb>tq zv<uaJ<5rzWimXTnaNUybYK>S#8t4cM$iNKTK$Nl@TkeiZxE+?Bi+F0x+~MJ$y;GPT z)_(jOUuuQ_5u%zj+M|(&eKO>oG~8zKmSQ%b1KL)_k(PrJC`h6jAXR2-JPm@<k4K8) zC~{_Jl4MCD$4SN->9wL@{KbZOC~+}^8svc}Z~>jbMJ@<oFBDm1>84L9;WIYj@damf zH5<rG*^Ww1HumVNYUQkcVR>;C4^aRe01>aQY>Ze0Ev(@-sh_dFW3mDmg<Q;ljVG7? z9*BAB;~-G09|B@~o~gFV%zXY+TtphU;^)fE5q}2F<B67?-YL>-qG<)vfg)(uZtWpy z=DkK}js4HQicO;KSiq{D&Oqu7`T`Z)!ZT2TD-^@85zD9YR4O%Nv5hJ;&Zv_e-Qoy{ zQFtkWI91bq?9**y<~Zkg&5M}r5WaK(G<6-zPVPfklRCgGU3t^`9jp7<nLM78U+L@} z;^Y0rlVLqY(C+2X4k95M?ZJ7E0S?soH0=WNXMYMxodW1)Y(^%2B%fj+*H)(Q%2-Ge zYM~k`37RCV`75mSn4>;wT@*tx<bfD)!5A#VFAxhUVbJdZUy`vBsYVx5o+`Hg0Pa+- zstb*av~43dcG-}G$h?@ym^D)eSi|c01Lfu~L%>xG+*jt>6@Ss0TfW^qhHgD_Oi*}> zJK>*}P^(^ki7R2NK%(jOV9$CS?LS!-_{c7t#%W^OE=A_<)J~wM?Wv3zXz-@+q=@2a z399k7nyV>qj-jO4Qis6$SojD-F9ZV|pg}MIgD?OCF6b1*{@%n=>~kI4&|NI*`UfJ| zQql>oE?J@auCErp9hcQmw#Dyx(EwPgfLNkg{)!(NmoffY6BInD?Z9D`PR!@#nU>ZY zUG}U#GDY51>s|(;1Pi3H?9*9rE8!95eZmp#$|<Hv+{A5Ky6!H7W+Es54)2PoaPUGh z@rFkG07nSw>)4_XtK^t&+3*dgt)$t4Hgv)ilmRUC!ms(>njp&&51-H#&cz;1#wMK} zOc~)aNUORk=D0)_cTV<^2$7nObe`Ehm@zUZvobGpSy{vxpr3aB2!GM+cg7nW6Bs+y zo!!BcVKqh3S*spL7zO*W>jrWGZZHD&MWxLVra^7gDzfhKZb*Ha3Hz=jZ!IN%3TS-b zpysRB#4x{h^5`|Mz&>v%^@1;K0vBYe8W@8uY_IRJ2{Ynt-d5~yjxTj(tW@S`F7v1_ z@v^#XL58?*Fe}pyq}SsX!7&>IGq*Ha=`TX~gUiCKu-1TnF%gyjBCC;Pfi=e+Hrrbs zZZqEHWj*CFJ}Fw77UG)HXPhMB(lYHj*Y3~sC!JR0p>$eEK5{;j#yw{yC2L};y|CDB za=$V!K|k-K9v*pc!yj-#CaD4T;%0KOXiteM_{K6u(=wE8v~lWam3eGbEvJvNi>!Jf zn0e*=_7EG~FHAQ!xv4`o#jH(lE;U;zPX`#z(%TgQ^#bGHzV+b)_uU@*C47=In;fn8 z$VsHRQD%AY2mef}Br-f-b^q|Q`)swwb#-pwcDo{t@%oP@A8M*B?{g?>D~2+jNE%)I zLNPqS80<kY&?k}6brR<7U0dw&71dGgwW>0mE(i86`RFhI1M@c`Hn**aGv$IgIyOvO zlReac|F&ZQLkx#VjI!SBHSgISc4>m;+fa`w^zbEPG0QkVmIfK3bhjxwBOc4S_G>4U zB$`wN#<RLsZM$0SYiWw*X*kF&sMU(bI7p^QW^!;RFQO)DhdD0}hf-YJLMRl&5EBb- zss&H=6y6ee5;x(rWcRW$j#L`w6mQp+P1`xaL`!fX)j0wD3Ue15sX*|97_&D_-$OsR znMTk+4d8$@vme{l>>K;EerGcs`!~s`=NB2ZnPzKJm&IwLHl%5=q_s9;GTvu>o(R)+ zZI{+<^ERL7^FD|5ZzHdXqtsM?GH(%bS`(LX?ZWQ=xrHs@=1%bqQUcv|FXfKYD0e$s zkXI$;fOO)<Y8SpQc@4AHi9in|sg$!f+0o7ntnoB=c{O9U0dIDcWS9McDf5{5A4<!$ z679<vxKYk$YM=8{Gh&0gc0^9KBtD=bAMbDX(f-tPpHF)W>-n?8Fj<#%ao6y1BR9b+ zcdyN@DM{>$8e8#A#dIOgwNPWy0r?8C&=qD(c!%srhdR8-3zMVB$({jYr+Q;sL^G%{ zu}bND`&X>vcj&6q&feRX+GSzkC4jSMnolqV!)L*L>SQ%FoX5Gi&Uv3GyMJ2sB996^ zD@vy{D7C+qv|G)L^|M$DI^@al44d`Ys(5n$EBD<1!z?tq5ms1QEaR{xnX|<5rE9kd znXltqV{$6z;TC!OVqbZ0TUT{}F7&&<>#s$;LuA+V4N$fKC#yWlTh1yxlt@WX<GNBn zyuSr_IQ#mU2pfe7duq4lg4+opNA)9u{JGlJgpV+xqL^oFo>r$kZ>&80tSgNLde{8( zzS_~u(|paN^|y!5qW8iw?12z`!B9GS5ijE_2b~i0tx-+m-$o@0JsTCPuQpzBRTZ|V zANIC=aR;zNKScS}PcB^Xz<qI3y1gOp2uYP%>6a%wt(!d^-<_5)1);Hh1XE8b5F0rI zvJp!6o4YB)<)_Dkush4PruqHf6DWxPgPh?LzP;|V%M&Whr{b$UesQNb+TOgPkH;<) z!zYZvEyA@Yu);8WDjG2(K*Va*3RS^^rVy4YMT(Rshn_k`)RZZcq(+SxF<Mlp&>%k_ z{qWJFr%oL@b5P2W<Ax<0HfhepG-IYrO)y}-eA%)^OO`BHrc8kX#Yxd6OOO-^0;I=| z8Z%(95YfZlKYjbKX4SftYgeyd!G;w(mTXzGUGM$d(t!mG88mM2=m8{15hP2R6df9L z3YIKdcILbZrp!z;G1H`R$<mF=IVb7V!81}1ACQ9zAzHME(M3s;GHHs~>7heX3QHk0 zXmDUG*Rg2TvSlmR>|D8Y<=(abyH_t@zlQ}EKKxj5<I9jEXSSSqvu4hqM|VbzIyGz8 zuWQr3U7I!S+`x0|HlBQW^5D#a3#WcPIQ8Skg_A#@etrA!@#ojSpMU@O_5lp=zxCP+ z$GmRbJJ7uF!sE_C?69j&y6Bv1hM8rUyAV0!I6P*!;D8y1nQwLhrWaj&*+YzH{%~Xu zFVqM{m)UBmah6?X8HgZ*5K2g)h8~h=qR%kWXc0s@3MnL!@F?k|lvZjfF_>hs38$QP z^696bhAOIwql!=p2p(>rL58R(DC3`d&T7-mH{py^POZ`!ge|vbs6j5e?7~a0z54Pg zFu@2b?65NuTZ|>g9*a!>vXS_(>?6!H>#Q@-LW`(0Pfk;)M^jcqrIpuUtC6<bP{mCb z-hBHl#1Dn*@R;N<%y791Cxos#>mc-wJ72#8Pr+f&bB{d&15EZl_`>ne*=LzmR=@$> zo6lHchh-2v2Y>C=8VM(?(83I9mDR%!f$>m{Hij{Amt$UuVvIv>dBYbq)F|c^TWXob z7Dvc<<&}eY^iiSGM$<$Si!RFO$Rw2%i6kdcnnNYVUZV1hnXJSz%PqMi%84(NQmO|s zX^4RZ7AWv!%{gI?S>~C^N=qBISdbyl9ptL(uDqNW3W}hx@C&e<zPPET!eT<yB{mpy z?4*(&t?aVQIJ>C-k<T*Kw6soBLj}~;T5~Nn*-lMW)m?gP6*yRf>yXx3ZFMeJU8(by z+wB;{)^B40e-GOJ<YN|EW%+A%aQ&<eJVCz|)Rr4yxs7nwT*V!ixpF&%^|xEdfCCOP zd^xd1QQ)|x7%EZ`Lyckfl}!;ex=<sPSr8)VQ`CTTDB+5<#^_;>K9aaeljwLdN;h0e ztZ9zRxXI(5vf!&rFOd?nsi&e+K?HSPrdj;)$%iwocSKO3t+#mQ^R6X|3VLXwwE%1j zLYF?&X{e)?10_fCFd3^&Y7m;qnrA{I8n2lKHDe1^+01q}RHaQfZFAMD;3l`Z*@_vs z%GIvC<sH5M^$l_ga$L3Q6D?`2a9J#L;e6sltrMcBga=}fc6!wvZ(R;^nj=?o%mu4n z9Agt=U<WD45RBXG0vEdw1}=(`ha~Lb7B#AoE5hIlEV{xJvk=um4A#4Z4M}SbLlW^q zGLqvZ?<5y%NyeUMr7P{ECqM}q_OiDW9ykRmQmKJG_;Ho;4U&+B+{#t#5rjL%U<NnX zK@aNEC!ht5FIcGGpaxTunIJ|n{9Dxjs3t&3O$uwAxfDedxInO_#(}IERRqzdwzaX% zM6QBctYnoO4tCIPAFNIe_ht=k)zE||Y}N~rnM`FKGd?q14>8Fjxyey(I}q9xxG3bD zU2=~9LvZs=Ft~t*DA-~cC(2DPb}=Jc^d=WJnnfz8a0oS&;uWnFn<;+OJBUbxA{c4d zX3hu_Kd8}3%3EH>s06*iOb=v2iJudWf`p}<YzJn70Sr3ug?_NfkRA2t_|meLmFcVo zk941(<X6eR3@T}b+9aYn=}D;pkTRpBRHZxvnpBeJAz)L@17B&j8p#qjyJ1^zY<bJL zX;3+J>*a(%2+X|=6Pn`zTzgPhxW#Rit6j~Hd>n^W8WK~Qd()xiuqmAiU1)Q2la)7Z z5sXy8K@`S7XF6Avo7&W(HvDo8E<O>@T7YUtV9Y1N_{p#$9SISG@Q7uMSJ0GT430AY zp-J?vq!XSrRAeK|BUAR6vZ!=`6yf{mX;Evwe-wfOD`R9yd2mwr$!~ss$pTB2W~ioh zl6i~rA1Lck(@1?JGdM+H*EZ$TpSqG%XG_~{aueO7CKW`mGM6qn_*AGy6+6KcCJ7-o z*7MW{aQIo~dC_a$tkOrkR)w52x#3;Qed}({5SOjo+Bu~Tkr~1$XK$j5n^e)L7PJ_Z zEoR}xFWwWM3(@C36;=@<nK7V{)x+^jQn4sOt+E@ttn@Uy1)tdQdQBjinD+P-m9d}$ z=`d|-VI1SIq{SK(P#+9t0GHVM>@M*Glx=r%zm{t9rHN7$qaITdQQ9;!8R^Xb)=;Uy zuXXBEWDBZL`6^54((-~z9Y!vj>eTvPGlU`3234zypkpOVh3Iwjw8(3pYgM(ZXD#!$ z(yCT%;unZ-_1vp~(>8SKf~fo|FfCj&kkx#u!3;rcCnf^Ce-5vBkwqSq-srqIVs?(3 z1zCx|B&IR(F)AYXBR&Kv<2m_*)vb2*t6?2$S<jl*wU%{S*dYQDtWU>t3DeL1RLM&U zIk&onDQ|rX+(!-9GL9|8W}eJ7g^lKGp6Zd6n;RS3+=hZi^^M!S4CXLrNL;@BrBu0v z<}|MvKwfpXyR8+V$E6v*^0g*)?v^<Ya??0o29cl#P1L>8g5a-F^r930;^-j#j!6GR zL}QCbnG0uF!yB&bVLqH$I{t*jB0KR!LwhESVqv5Eu=UANo^qA5TGcb-$3GM~QW}(W zE<Qu4(1^BDV(0dyFjZ7zew#ccL+Ub^fp)ZYO6{IfdAS9FAZ(ng<yFzrZ5Xt!xOZ9Z z=SYWFyn>Kfy`%2Gm1l-mh2gu=PB^d{bKYcsZ=LNOA^P@k&u#6qesAfjwi#8OGvc<P z5shep6qdn_ez1@-QAUkC9AXl?aFdd!VajS6dYDDp#ycLrkAqglqh-X4TON8<r^OGg zWx;FPXLFzdDp2-AS|*vs$)6(`fRh<60Uv%qX{U1O4Ya4IuB`3<=b}nCY~wNpt-e$a z(JH$h+%9*sGgZl@dAwyeR^i^9-o}-k`q6}Y<<N?6y8CcB{4S1{FSz%q&!Szzu!TAg zO{!RgiqX8&r;s$^&&8jSc#$G#hTG_%I_$D6PqXUBj)cPFHZR5cNCi5e8$eI=BoMXI zLLGFiEpm)!AgNFM1n2s~XfTQA^e3kJ2e<-==q@AooNQ~7PU$$s_w4EE2riat1G<XO zg5E}{#Eov6!}+3v%*;&sz^kgPFL2H-`&>wcim<)t?1s)Pz8++Ucqm-f>WA*G-;^r- zkZKofK^TI848%Yb5R5izMDPZW@a_pU9PH7^Xt5X%jf@BX!<2_HnCB&)C*$U*emKkH zBFbb!uGDCN9{ynh2{Fe00UvtcPTs<iHV_GbEv0hK^$3M9^vCC9D(GlxfJmuQkS-HO zgQrY`>0%IqW^mh5Wy_E%`7(&9#;pgp&fN0m>mK9@8$>+1Z@pG1?YfGE+K$d>5j?^U z3cKar#1A^2YOQ$C{LU}$^zN>9As2eV7{&k%+F%TZ!TtE9;1UfD8O;6`4$>Az5}pj8 zkVK%EL=GhnV>HdfI>rF&$a?rNkD8)PVqmnOz$ywcA5SYS_+XKCrsgCm*mCZ+LeQl~ zaQ1#H$*M*Z{eUA7AtSWrGp0?Il<W6`&s2!2_@*oW`BZWFW`+5j>J_;T2xU<S!=wAG zY6)>s7yV=Vj1X`Rgb9hI-oQ=@siD5?s|xLo-~3JQcw<If!56$hi{#)JV8PJjj~jPq z4Sk2<6pzv(?*AgsVgzs<6{^#yC-c0-5mAhfR;&Z?AOiJqEJ5lYxS<2ohmmL?^#W2L zi$>=rk;rxn*?>;jL`k41<$zeQYe3N<U@%lfCEIB56sK+@b8r<|vH7&?Ch_LnqR-5v z2_?yn-Pr5;v?}cYWWCl*Cf%!s;OowMg@=mK7<F<d{VWTAqc?t17jWSio&XKRzz%>R z77VQxNCgd-av|6-@%%}6js%U;XyPblvL>(pX*OnQKn(M=5~8vPv?}UMSik`xFxAMi zI>kpH{(&B1Abs3I$7E~u<|j}HauN-4x1J{18fEAzgUO6*FL|%ptPL<_5F^!Q%M3Hz zt_!<dQ6xvwF}usGeo<H?vsg6Km|*C<!s;bqazM2OK%?+F@`f?#Zkw(U3z;!BoiVy_ zp>_VC7-+LbVxbmZ>EH^+M-;9pAx+ZU5Mq|(|0vFl>d-1P?(#MZ0ZR-_K(0)nQv?EW z5Uuk^#V4d%3kG5UE*>ceRPRq}%O@nU*m{mG8>3<zCAij8QXI>GI&mT)qNl9w_kiy; zgm3s}iR!59mX4!1Kr$q8(m$iGa)L$w>;}~O#7ZSqa!%W0Ko_Jz|I^;CslM)u&o*Qk zx(WSK(_Qe&?{Wbcun|OWQz=bUjK)YsIb$On3nVOUDlLW%n<t?Z3TZTJ#6pG-lVYO0 za%CtW4a5>iRrO8M;uuU1^#Jl`z*D7~R0QV|A??!ktTZn>kuO1Um97ojUc-vSbWBrG z6|Zjj^po7QYb5au-2im@@H9OrbNi5R`=)g~B*#H<Xov7D-%8Uo@eVazh3^PWon|9l zZGjd}gcSx4Fnfe|cJniyEF+MFMbD9Ho+ML?)3T70MzivcMy3h4QjaRC0XtwAQgu}s zwk)ud9;5;T*K)@=a8?JhAc^e%P>ieu?Ggq305h5_OI^?})i79{E~rYeSdF#I@bfs* zRLsVVO&v5l;451vlTLBgany`6sjuFsX&CQq?#7QoH)LEd)KCMguhi9w?%)z^A<^j1 zU`k<AoU)7_rtz3WUk$2XJ#0op>>UO6OO`;?{!l7lKoF_3Vb#_w(jp7)Bm;ZKE*{YX z-?CN>Qe)2(J*Tv$iVkZa63Vo6%KnmUnrko#)2QyVWfL<b`LjP`Q5Hq0O#}2KZFVv< zlTKYSLFSA>zt7Af7eet&LaDIs05ynu(nK;;uVjg@e1Qz8fC~Nq7P@G`(ohW{HANN6 zVW6@_(Gk-!&9d;&V`|j@dNl8|wr2)bi~_!3Vb`{Ky&^4i!SqPVq<HM+!V?6AY{(2n zV-<rA8D&ZZNE3NgWc!kV;!{4slvq#Yxo+@SkyZH?msxpfO`&g3&8lWA*Q(~U7qNwZ z^LJah6=<h$LU^fzc1c47)oAlhH4jy<)KwSw>Jr{y51v5`#2^?*LBR|wpH5Ur8m?g& zf&Zd%VusU=IE?bH5@5BUXav@?Ms?IwEIK=Y8JO33Z8$4%?E+DcVvFD?ELJ>mt2||o z4x=<ZtLFATmLs4oA`@tV%$Joc@|9vk_ylh11dY0obqB`{LwxWDbtQE5CV=6~7O4+C zG<QJ>bP3b=jHk8#K?B&%z6C<@O>}eePXV<;PZxE~mC%T<opRw1$Uq5{AP>ag6SydM z5-eU13q^+{cNq&`DMM?0H%5(<V;1Ub_b`6?&|ob}DrNwX()NZ$`H=ph2-rd`84(D6 z&3bDKd*d?p5aZ|SQX#2Se2Yu>Fy%eXx5`E_f}CskP|<zg7k*u~6?v(P9XE{MSX%S9 znX~o#05mlF6kJKSbZ2Ey2^Dn#Om!#77G41t#NZZ0;RV#-4`QK<Od%GKNDXFzm3{=V z6eb+4mhmiA;`B8ge|OVBEW|)HY>^@<K#LyH<P1t~lnt6I(t;6&G{<1;JKfTi@yFOK zkz*Bd$*!jVJ#%?v83G1dNk_1ZitF<RFX%9nRasv)bDH%BpH-Q`ZgK_GnPHmV0C;9Y zC_?=-T&*yH6&PKb(Od_too2xmia`n-feZ5B7-Sa}yeJi(U=p}M4ViMEa5r}s4__V6 zBwn;CH711_iiHzURJEs6S&W7`%Aot<tkF8H)q1Vjx~<*%t>HSZ`vD*RA=lD!=HdcL z<#x6pv2KHSdk@3N_-7@8PRVSq=nCi|>$MS@_*YK@SRF`5AV_^_V@537ih<$yhWWa# z`G9Yw+@!-AoI$k1I2gycZ^R?DyMc^{g@()+L16o}b5@OIJGRMcwQ*ZKT-uGn4?9MC zbjff3-vqU2ce-6d#5ay=H=+yv67>^c0S=x(4MZWqbVnDszz%L93{r!4m~u3DGkBb= zBY;yR_<(9M3`RGVQ`^x1IWANOHjjdU2Y7%6`iMvE0U!85uJwDr`MbZ*`k=MKAMODN zxRar&w=L-wqMh_0J!zKr)?=Lwqg${qH`@2)vuu9(r)|)RtIprPj1`SJbJi4$p*31> z=%r&i#ml1>8|00>RcNUhr^}DHvH58Ac)7V57mR@w>R=w`K^n@z6+R&ryoeP{!4}5g z36i{?9{c{lQALF(pz2vT*@!A94~3BvEBje!u%~1KTC`Y(pvxM-$(;0Fb!RB{eSGZy zdf_snpOh}YHxrRKFHPx`kZb8G5~xttRGy213KIuC++02~#6^6}R+^<96n|A5rfqSi zxwXthGsc5^#&x>5g=3`eD!`&E7H~lpIDr!2!5iWs9+H6)ynz*10Togm6<lG0Q=wB% zRH`G*BAje9#M@FOMr#A`%I|Q!F%KS#_l1u)D#m(E{DI7oJuRpKEqN_2e65GAx03wg zueVqBIP8;*xR!4ZWF_2Jd(Xo498AMBBmcbWhMAZLod=l}nHjU|ysjk0c#IdljZgcH z;n*f`+KzL&($6KEeX@boX%>9J6PREWyg(d2;S*-z8#tjHY(e1(q7}Mm7CgcK6d2<0 zp8PXteg6sp*CQEuc0JQH<~TV`c)^y-J!@>2f+<K%DrDfkLmAmc`C+$H1&H(?Ps+pu zvh^_5*fw^s6H?CE^C5#Lm!<66q1fq8cF$!)HprdB!Oh<U-I&+Cag!O*x%ISBeBMh) z>svg4YdX@$ubL4!fh*m^F<rTFJQrG_7ovd)py3(3U=k3F6?9=6lED@nC?OIq)_+IB zChcCQoXWRW<a@p3+1sm8ev`i(Iy-<33R>pN{2#u+^l%Ke8qtS$9>{i1h%FK5{|9_W zqIfpZl$cnTIc1etDcsXHUCG_s+&9oc+_RDS2kTdIm)YxCo9pvb>+QY&Tf^^i=$JIg zUR-tB!$AZ?eVW@|;TtX?8Aibp-hc~&A;DA~8<N5L3&#F#ch(t(!aBav)ClsXQmZRD z%P&t4Z8RQ*U93BR8){hc*S1w{%;w*M=5k(1h3#lwxyS$_O&T_A+!&N2XAYf(b?V^J zqlb?~KYj)kLWF1$qm7LuWzwXnQzuU(Ns=N}DrHJjEK#{c)hcGJnXzcms%0ye&Ye1S z>DslcS1({hi4Hr8H0jY}Oq()Y29=rAsmzu!YlgL%v#ngaQu|8Hn%J>pwV6GOHmx>p zY}>kZ+W?n9XumD4+_`k?+Pz!%tzK?vt*KQ@b}ZPzT?;$Q+RQ3dsZgOh|8=VLC@`f( zg#z8>GncMhws0kr2JPFJF~45Ln#Bs0H%_x=xn#*Q<;jyJMS{#ENm8TTj210IRA>-I zi4gVRX}FNioH=p~x*;eq&6zW1%#^tf=8N_%TeM`!f@R7SC{Uc3Z?XhQks?5P@Yq2^ z1`HM=XxRI=Z=XMZ`TP6-4`6@-4oF~u1|EoDf(kD9pFaQ4qeBNQzz_osHSE9x5J41y z#1c!GM;;X7O@YOC+-dg(7+_pih8feHArL{%xsi}UbTov=LlIF#kwqD8#7HBIc=VA- zBb9WLN~N^)l1nntWK%6T@wAgqy7Us%P(w`?S(lGB7S&=?A*PjK|67HHW?*Ff#pYUj z?S)sIa_05sTWI;!rdetV29}v!AtvTjU^)g_my{7D6fju+q#0+he8UMR@fZUOF29@> zODn9f;teIO!Dh;mD3MYUNk(dt32wRp`5SON@=;ulbtJbOLe4=a-E`Jrm)&+-d>5X0 z<eBG06G*5RM0-2b5Z`<q;PKBr`SHhKwbovXZMNDLc+WqYP@uwuGhCSAh8!-@1c)Mv zS7H|2ZK0itE4Jt&j04Gd&~nM$sN+OE7IKkByX}@LNFtT$2}&!0+T@cn-DFF|R95*@ zmWgs{Xi{H-8E92fA?BwuVTtwCo?_*BR#|S=$<~}M%f+&t|97ICvdJWW6*5;@Ri)Ts zgFbdl#z`S66qcA}W=k!{B$LcH!hE5KF0<4^Q);UTV+tyvhN=>&wVj&ksv7kMTp`23 zYTR+NF2`JRx3VFSuDh1e>lfU4hefa<p66i^$pZ0S4KvKAf(YvTqmO>uF3x!4j&JMW zJ0gfMp$s(KutN_To|~={A+no=7AM9#FTF3uSkOT=Dl~^f#razizyc4PTagEss_>Fb zHtg_CQc66rl|U7}CB{NK<yd1p4{8-wSA`rHSSHiVX3TJPV}15-QqQK%H&YWbpv^F* zJoAJWDs*L*0kxS=wy*+eGV!GHL>o^m0?RC!w&IdE|B#r%zu0uGRHs4}ZU(lI-voz8 zejtw87Q!}L83Z~nqRy`5<tx06XjpthR(p8BEcwu<2#9-}2~UW^6#C~L{MZ5oSipi9 zj0;1X>kzusH6ko%L3HpU-F2!{FBsvAMhMYY>*`RPi149DJ{sF@Y8R5*At`sd%Np-! z@-Up_BzQg<o}#uSG>sweDLo4m$U;`K!B}Htf#Kd?_@ccyYR`>-v6&i07Ctfs>SyO; zN*E<WG+?mLO1iMcFt$O7Z$#q|WO&9N_K=F!WC|6mz(z7?F$)38#%reXL?>>e8zBj) zRc1RI+SInTTFr=pa$}K-P;@u&Y_L4$@sJ05|FEpV!H@!oh?WX}3Cv(Js9Wg}LAYQr zgUj)t2OF|s=g5=8(7g*qD*9m%QJ1<R+NdF}gUAw@n337l&UQyal9F`SB$%`Ui&2Ug z@OVPV;T6w#8GFjc$|$C+<m^m?kzO0=_(nMjlpEM%3qS#*rheiqkAUjf&mQx~VHD+y zgCwLOL9vQ>%)%Cqpo0Bekw2KY#1^Nxq$W#28v@!UYy)eAZ-675;Utlp5M<6OS!qFD z!LmER+90veqaMGx=LR&;r7_u2LSZU(sZ7m}gMc6*7|39T<>DN%)&)8q_OP1PoDS+{ zw7MJdt6$%&NJcX9L?RhXiV0H^Y|^Pt|0qH1cRSglX1bWAiB6^{hHA<(?0JkZb?l7$ zROp@#+NOb853zOJlS21-7(MRsq3ENGL;+cuiely!xH!iuyzz~Vy5bLFNJT7Au|HIl z!WPNk1TtoE&Xk(UHmJ&tD0`#8m^Sc~$bp~)CkVG(<&<tHvKvo>H6B_z!Ipkg7PDgD zEGHzjsno6R3A^Qq4jhvP%4FubZs<9zwu^_Pn^$#CcdzH<%SL1MChRVPkszh@BT+<H z?%tZtn5<K-be-5;FOye#hVh<)H6vlsC_Og*ld)-0tU(#vSUdI!vWMvy`5F`03^ygB zdR^bq3TX>q$U;)Ph=n_K0SsGY|0=b!pas)tp-I|s5^SMlRc=iQ5meUnx45ccb?8>N zyJ=8ZKTQu3k~P$#&W8mQ$b>Jg3*{(p>mT-@kGN*Y%w~f3b0lilG*eW%^V;iP*<>3- z9P$u}loen<qMcgnJH`9%&Pl!Von5KaMWbCzz{f+L@+|x@edf%tHiNLC58W5<O&GEb zoh*idmNDaX7{H8*SUf%(jas}yN;BDSr&A*gVNhZks^yw&zxGMn28nDKS>SGYJ1gb1 z?QL<B+XaJs+*ua+mdk1ueMErN#7TMB#8yzZTnIxMUPyCV-m-YV<F2iS`I_l<jy4s7 zBX2UWiB5bXec_z2B&h_y|1WXa!)~IJJ5vn6#f#`t2>j=K9@tL`E!klajc+=7Z;gbZ zaAe14VK4!0!$FI*UMX#*oD72!<roGlB1SbV?vH<^h{lMg@rfmEQl+1)Edp8X>fIKH zrV(`8bAtOKAnMe(xfT{J(UTtbxCcJEWI+d{TkM?coIu@D$K=GNOdtS(Lmhf1G)V;Q z(aDQNVvbJgRA**x_KQb@;C4&j%+}eAo80R3bWI@kPIy*Ko<?!^Fa|!T!Ok1Ogq~iT z@Pwy)BX-|t>L;TcEhat={Ew5q4AN`?scn2C77ypN#A8B9RLBAnoQQ^!PVLE+9&puU z3r<YYmgC;mipOwE|M`!Byi@PU(&c<h50ZI6R9&io0?l~x&KI|z*vo$Qw6DGGZ;$)j z>%R8+>DCmYI@KF2vxXirdJao;qAkeFywn~dLK1Q#slSfuY+eL!I-*u1;ZDwT)^G2A z=T1BePfHVZ_rS>*Zv$h6!u8&_``-`$`1|Gk^#<SFo##-2pTFP+@9_HWY70vv4Z|P| z5NCLu789A23S?jfIZz4S&^3@Jd8;BMl~;AI5-T(%YbJMcwKiNB<SW3UH!lZN%@sH^ z5CbsO0YP97_%JQI2ZJ#vgEL5bulG3Jk_#^sLsTVn-(_^qMqWPjL+C{iPp3_1rXxy3 zeP|_0<CF>7|F?ZBflf|BXY3>;;KvyhgI9Z2b_2G59AjZ?H)!9ZU~VUOj75L`v{3s* zCIFXzeFSNig%o=AMZ}{ExbO<!APX6l3$Ktgu}}-NfJOS%8up_Ok6;O}Aa0yATLx5P zxRnth*FYnO91%1l9q41X)+@0zdgD=KORye6Fmp<_OM}o4_dqQ+sEWnrAoj2Wl!Ht( zfFaE0gE+)4$ftDEMubLKBgv6%O7u-t7fu}EZMI`yRJ1$%Q-xO8U*cCW#KTt+HAWeh zc3~)nX3|gc2X`rRh6t60k9B`L6L62FVU^W?TH;}wVGFQu4wT>x(O_aT5r~Hu6Q(c= zY9I!q|DXz=FbfL9h>`b6EX5lyWqAw)Ydgk)MJQa<;Y!8DQ=Pas#S(L;CpalcA1Xi( z__2x`S!~^c2s#*iG&FS1q%J_1i@G>w&KFiVLRM54U$cXKsRD&l<W^R6MeJl}{v|wK z)Na!Fh1Do;*NBbnr;XjHC-7H)YnU@_h<`qFVSlxM92Q7Mb2JJ^3ER*MCYCf(B8Y>? zKdm7OXrKhpzzedlai|7L2&56YrCX=;KqYrm9ym9|l|em~TrbC5$#Q}gNdbD`dK?Lu z*41-ACqvyue4P_s$EQ{0)m2_K5SLg)zKCY-^)H3s8^o9!9uY-SByI}>S5AVH?WAr! z|1ow&Q+_^qeqfk)S8)|W=@m)oPueJ(vPqPSwv=u7hWdAYQb|$kQ!%&zcqR1>IB|fT zmRhY)3yQ!Btq={;a1Ebe3Z9@fCNWz98A`m-8vvtQlbCs_)HWuEQ^N&%EH`AywQJ3V zOBFdEl#`Ld7MSlzUEKl(QKf7&)NIBlB6%ZCJp^V<*L>==UT4-#?*(7Ph<%c<na8+w zbGD3MCz?8mS7g_PUig#orkYIYZ?Kt-v&o?erJ?p0jt#{;%cGkR<!<T&VC=ICob?%s zWPrA?3$`!|`_&38;R<0e1W_OivOo#Epb~m82&Ql(BN31XG%y-bHrsiSB?q23|Mhu5 zmL2c1LlB9V6X{$isDftjm+;A@!qhF?AR$0Ei-&1^ptGNhX*!Onl5B%*4e>g`2w#`E z5m2;N3c8?hC2=(oh+qeyL18f$V|HhknyRUOu4xz_8k-%8l!#gwO8F;D324l-n<q*% z>$52C0}R3-4e>ynRAURT&<CYp8k)iireF(VAO^vZ1i~;1lEMh35Cun|1aLqKmq02Y zVL%_JKm{ps#zAtM7niy6q~jS&T7X;}B$1#fRH#RaD$oIk<DOkAt-sWYuc!hPVj=cP zbk4Re`Wb{^#(bw!gw_^T(btj{VG#l2L~j-ncDgV&S#B$KZlXDwJNc)2|Am@BV?KZu zXogB}AF8M(^P&D$7)-e{_#`OgxOeGe6qTBe?gMy~APmv)3Wc{(M_>g?APT3EHLu_b zUhoI@(<!{b3$8#0R1geQpa%UY5+4yZ@&$?7*_PcYYpO(Rwf3a1RF|U{krK&kA>=Gg z@DHgttwozc-C_!18jHe5i$zzaNOz{->Yt8TZA27xZVHT*IgIl~PRGc7aHU^X_@G?0 zg<N=9`Kn<f%C81Xu#JkSZwt5m*0wq$S^WBxQOS37_^_H0F~A@V$uJC@@rSq&2Y>Jk zVxR`O06?rj3bP;zM=%DWfDNmVNhbRQXkY}XkSd;3TQ%lV7y(lT|4Fk<db6JAN;+#d zqL(+M*Fos{9z~UctH%vnYP7Z6IIUPXFf>)<;$6qWt+yDpOV^n8vZneXecGnA-A1QI zQcmGklUW0==4KPVqeWy}nu>z2<~OK>3TSOOw?i4X;p?d1TetlBP*7>2c{@=L`xAwf zho>MZ?o<n{aSLR?1%D6*u3(QY;Tp(kVw{i+vmgtf@CjC61+efn9(R4Dw4L1fmYdh4 zayd7s%N-)<a#eau%ql`100p#byC1wQ_s|btpo2?0eCt7yTt*_^@vU5yrcTF;SDS?X zlCHxjU(2g~oP>-F+I3>fr`9V^W~;r^xUZ8nCK&p?ZY#d9|Cz*(ikmz$j*o`E=E$(> zLzPF<D4pS1F3Jisp<;e$z?%RI_Gk(-!8O9b3!HEcrO*i|@d~X_osKA9qXZm?aCyW5 z5t{d%ap`%t7JA@utjc99LG?ko6uTX84ADZgAk4_vGMJRZ0?9-!#OG|$6t(?1ykDg{ zy=bn}$3*H1lSIP2?#eLm+QSZNXZ32Y<QI)YjCMfTy-3`|vrNluSiX^JK9kCum0D5i zXbZZ43>o#Q5fhIy@d}D^S~dC#oe&7GkP^ah3Y4(MDD{sWmnzqXTiW?5ZmGx5SGu~w zBI9XXcyp|u__Mwy0zlB7jm*y4(k*3B!pX$6l>D^g|8<hqR4>>>uI$B4NVFr=r>>Z( znWId~4C;N%_`}Y48PM3uuIy*9Y`0`m%M(4z2FsduOQM7_#T!PcDC&2a(LS;84UljO z@!*FlreZX~Kbumjvj7NUaJjM237v8Z(a^4>LMjt@oe5Mn6~QAphDxLhT%BiYD>u&N ziL8Shinx?|d^rdn+|E&rAPzzgxyu5UGs*X9i(MAHE-Yrm%Zn?Cwg3Dt7$K+gRi_1Q z&|y2T2`zRJN<3gBhkdoZ5WTi+OVN347zT@XxU8ES&3_$DG#|Ygjlv4JfDMTh4V$83 z5r=^F2n(M;1-EbrRNxAqfJm|soz&TgVYAb|{{b)zL=oK?YkU07;z_}x$Fm#+bLT8V z?5UAbE!zunAAS(evbap<LXwGTrlTXZX$sactS_Ccgq3NT2HFwd*1R-XMQbg+(>o;) zTAHTGSA0g-b*;9s%-3b2*R;IdZs^yNs>^|0#l(Yf7G(>)Fbk9r53JyafasNzq&2Yc z2TuS9AS<c>EWkKDW1Wl5*~zOiB`cL^+9yZUF7kOGD5X^TQ^(@EGzVQw<_AzM+caq5 z7mne(w-5T@5B6{a#)Pd|U5nw>t=|!Z!VBD*Ohlagi^z+v0gajDwA`KfuDtWyQKChv zJl)jY(0`<_P-#8|<}>m3-Rsxgx4GRP|C7<V$wz=4sB`GB=k3ezlMKA@4V3hUj_rLS zRmN~&1%Mz5BrDA#!H6{Wh@c(d4jj}FJk&UwvpUO(<y?BmGIKynA26`a8LsDhe&Mq{ zApU@~x6QP=4PLwrwZ1L9Uk$@xHQfFDrrQ?KZYJYiyP&3g&``3cVfWT>&Eo=Q-S39o z<%7{jT;$xn6@pgLr9SFUiD3$xzH>b^>svG*mT<ouF~h(#1lZX0sEi`z5*(`u!VoEI z+zD(P$Eu>1Y`M*`qGQ0?=BCRloA{6;NP;o9tWB+gXE0rU&g}<6Wv{5a*;-Y*&D-9J z=qRbCU?tYwRNS!>FdUJY1I<<@|M9i?#nx>NemcJ6^Yr9`x_^O{-K*ZOkXq^mpX35R z<dg-6uPzypp||EuNOz@<wSWw=APwh`3x!9IpQ$xmQwr0-38p{_+DD|Iq#I(>YLbX~ zI<|qFC&8!t$AOH&CfIAQEdu61;oYwD{n0I@5YIJ$Io>tmM+dbh?$s3}L<NyeEZ*W} zRdsPX$1%B?Grq&l?P=88jMn>%T=?nN{qI4Zexq*iV{g%;uC`#m@EqOmR;(x$MI|}$ zKJhSW-@w>_D2V#S@tTARrvM4UkO?Qz#wD)_wuPMxY>)@(oh~n22~NS&u4~Df!9*nk z7TEzpn>dTS^O^5dRCWXO|9Lsuy4ysLbS=zP^^(uyy2*_`nPmOq1$uP_lb})fuBLp- z_#S>)sD))~wp||?|NhWHj_`{?_NpGm0iV$&inmX0#d}*NznlxTfa}SSsqgKTp9vdX zv)<((^0O6r9!Gf$tfU!8E6(153(5GnhSY*=?Rwd3(4_*arwxjX`I?{kfqqQmGUzB= z=pxdsB?1sywru%Q5X`|cWy~x*b0$q1HWA%SbR%cZMLKlqY{a8S4<A1v{R|pZ2oa)1 zj2cO5v@(+>O`T+VqFIv^sZu#hnc`^*)z6=;gtm%R)TpgmNpme_%2e0Wr@N%~>IKZI z)nQq+W(Bs@Yu007|HU3#RyJ%|v}wySW82p4TexxM&ZS%Tty;8X^N!^k_Um7*SFKW| zDs`8xrnwL=wPg#KCra^R)iPRCC{WC(dgdhMNmwOH=Q?>JB~vEMOqp1=WW;C@qCzA^ z`r+eI51x$~FV2xeabm=W4bLo0Smq#@f&;Z=!GdMV6e!W1OmBh&Ns%BxdhobGV+ITs zDmq~Kr*GeR^y$^FXW!oad-(C?&!=DC{{8#@{w?Xif`tqkYS@7XAc82ux+R*JE;=Zl zn*xh0vJi+MgAh{44B;M%hz*M5um~fKIQj@AkxDWNC6!u|M3U5EGOZ?>ZqjKdo-zwc zsLCd*r7>F)|7!{=T@2fWD!~K;?8ssI8p|xa(z5GGD5I>aNwvsQax5ePD-syOdXefW zAA4Nt6<Fe-L>O;aVa1lpTCou*o@g|s6K^OvMVOgNJ53YST54&L*9wVkHa=>*Ew?#z z^Uyco(h!cggbpg`i-ER?(7ETNqi%`oumggJ9cq{%2Jl2+fu4WxQ*~8VTXpqSSl_$n zA7>~~fdv?5py37{dMNO~1Qm3GK?fn6kiz4NW2hkwC7Q@X5JT+9BalcG)FePtT!}@P zOdHK6oM!CFC(MQ-Do3P}s>MgApfaq>BDKu&O1`MXOG<q6Wyann>E$cSzqYK3%c%}q zjNM!u|4SwrWGFMr+#7%LDNa&QDTNF*k~!0pnf6SLC6!zYbkL9rwG9v4G@@g--YD8I zxP~A-Zc^o#!<4~IIrX%MP-&0>JQgV6<DYwCHTr0zlU91ZS+(fzzW@jP6+vN#ZSc9~ zBphhcWD{D}p$&b5Hqj94n3lwlOgt$iKez4HTNp_TSI#$w$}tvNl0vF6c7YU<uq^=w z%-^$?DV*PB^i}*W#PK2=OTo9=axgE2gbHC>UI9jy$XLmds99!l(@o9By~!0S(13%9 zb70()&lUXy6gHAWvh6n9>d0ti4_p3?4VZ^BqqvzV-C{ZB9Msf_CUo``R8eE_PXrNA z|6Tfe?6cS2zFE}~;nrMt?KKDkkys+Z>8vhR>#ZvU!)pwgb+*F~$>!+n+0;&{H5FNW z$;EHMNJcpsSKZEqx1!{&F*{;R1DE2rsQ@l;U5Q+h9%necG)^sxi;@P@aySesse+Od zOqVM6B``5XOiXzNF5>YBG^y!fuRsMEs89-4lx|!+nZ+NZa0@SpK^ZZjiN|8sh}Hy3 zHX<?Ep>nf3-uUiij(QaFBxStiEazsLYM#!r!?W)EEIb`J2GO>6Ml_}od$amNe_#-U zs1b;Kz*<83qEjpgX^m19f}e040+IQRZFeG~R{jKqlKrWuMQ;mWj0Q-zH=*Kg|Fp>4 zj`)T!r~Hjb@#>0^C<w5}iN%9Xf>Pq*GD^pVQY?{+*D#7iq{0{`g_vv1E~Ft1WX!^0 zv6zJ^Qb7ech$0E8*dfJ8@rf`{!3e@A;_Fnink3S05VN7p$)30}-uT81jdIjNAY~ln zB<FaS%GC0jcbzYCCwl&&KoiWUMtH_kp7`nB_i&}F8|=VW<uhN^u7<S;O^8y*dEbTn z2uKdm4@89gNXbfcNdBdWTa1hwX~b0{a+T|VMxo@67>G&51nFJyYUK#QatsTqGJ~jO zDN9ufIg<wFm4p!z3Ne{ER(#_Wk+B6U9L9=XrXmTVu!9&xVG2^1Vn&?l|HLeA*$P>h zhELB#A`(+_lG@RxiHBO5qI~x|n0eERG#h8~$_a&>p;J4dnt>R_(~Wn|Q?7HRD|*=I zMmW|02fYG95$GtaJ7UdPmEu}K4Vt0(J?ldm*@)RXQYaFU#6;O@+lm0lv5L-3P8ro` zjyh^d9<A_4?usCnHd#`xL{61^5oJqVOQn~tl9gW(SeFWh!h<z1w6&;HG@>EHSg@iM zy@W*|xWI)^uwpX=EJbHzA&W<x1120pO`rS}O+ihQi6={$ZZ5JYmjRE8!W*kN$Jrd^ zp><Pg-A;GD<DU+Ip*(e^Z++oePw?ecY6b$9KLeY`W4W)783Lr({}yXMv)Kl1Bsme= zs_GI(&P0G0t&xpz<XHt;GGUh-tw={YFx1BMq*v<Kl3qK?zEtUP7L4iSxI{3^U9Ksi z-CHbxA&qVHlufZ1io|#sx}7Ywxux(7B_JVPn81WZM?|7)u&Q0H8p?^f<6Z9<1-zJj zvv`%#BBr3DUgn(-3FKR=sKod^RGG)VYi9HH?$M7kJS}|r+~<M%xuC#4D4^~8Lf5|b z$HWS<Y}0C}Aq%lT{z14CmyO#aHycSFSLU;z6>VZ5SlY=2%%riU*NH>O=_}1vOOuPG z!GOfB-NphLmv}@xP~kbtM68%gO{ykJp|M$H;&qx>$#tC!|C=RN)0&9-E_k;o-tlTV zoW`@1S--5_F0vO?-jQC=hE}vTXItB_(#JpOp#oE}AO<rKkR1JLKJ;1bpM#|k9|!!$ z0xNbmx@#<<7i^+KJ6MrPeo><}TR;nMG=Y_*G{PWQIg*ArFq;N-!yVq27H6r1G%eVv zX^9linTZ$CXocr`Y@_8e^%HN9!XF;74N_==6pEPYiX@RDCz~XzQqG<3SoT%m_>sJk zS~iz$ro8lp**ec->zQL<4}7S3+e>FU_xeE!3it;G0HX8M&R0h~<B@%ZE$E+{W#HW~ zmXK&0iT?DxqD8_DTyxu@0XI77f;+HX?h29#11I7m|Dp8Zdk-bvku=j%<5n>jR~IXA zu`px^Lz0Up9h^emTvEhB3{MD#7bp>pMvy`cRG`8iGJy$S&n`Al)~ZKpj?E}aG3S1i zS<h>R-g2fd+B@4p7{Mc+W$**rP3L{@-P3J*)Bvye)Th<ctv-N8sC~#Wtk>hM*!oH9 zY=tUON!FHVwEwT);94rc4LHe4?rp}F29k&Eu5iC=<zIXUHCWPrq}m4F)M3)C-fH1F zWN^;aIV{SXcBm85_ykvY0yR(rBlrZG@B<|fg(t9sOJF(H5IxcpHq&b?Y%;cEL$*g5 z9-bqs^GYw-6EjcwlpCl48mP7oa3`hnJr-=i|9zMhYv_RdA~#;?0scZaz{;~cA}n`P zh=W2X`VqAI84<EGJ8j9n2+OQ+X*;)@q*~~xO0%>FiV95vv8#}&_scu>6Cw4>!cU?t z7lW~ynkA50prlZfI@!3N$RSi{Jj{p_owx~$`U5Xuf>EG}Ptb!W$O9wrJVl5=tSSUT zp}>@}xnjGr;1Mfuay{gMy)UDVbMh-7C^Mfa6%iPRxN<>F<h@xrgQ&ZwUD>a5J3bv` zH)OF8=L<Aw5xaUL!s<JuY>_DcNy0|!zMg1841+?s>l@OlLMt>9O>-r`L#eNLxGY?_ zfC)p&8ABN>Lv>LXQ~-vB>4jPNiCAbu|2Nbj8sUu2;22@psdI<~BI3M1_=HFZnc0C2 zY9hqkK|KuIriY*+MO;Mlx)d)nClO316C4%zI)hByM1a&be*iuju%~e=w>rZ?J6g9r zYd1fOA7**Jiio~Jqn1J|y9SHJZJDU;6QF;)#efsIfm4^z0;!Oq!Vgo%D@4X)Y{~Sa zAgu5TWi+A6DL<1;7>}Zb$q26ei;SSS#%$C^TJwZC>4bB5gj1LXC6feCkcCE2gqIT; zX`&{YyQX5pIq}Le4x~qBYsB<|wtUo%X&aSNQGqn`hk#5=ft(d*kU?AlkaGK#A~>HW z$ia2ff&l9?3puQaOst9sJ84m{|00CNlwcc`Ks$=^HzD)Ba^W$NghCBVj7lrNDts{) zbEPko9GBe8_X|S_qA8oaNt}Gbya_H=&^T`ZiqUyPION98=mb}IgD2<$N|1(Gz=Tea z1YT=0)<~k!qspqJvO~NwEXy)03a3gbt1Sw;NF+0!5ta8+0SXX=e^g8BtS^1&L^-3n z;wvAzTu7}GC;@x7cvMBe9KsQyChJ2aZP^y>>&O^cOppw?yGfvDEJ;lA8}pMOmE=tS zd`TCp3KOcS!w}64OP421ilQ*QZJ>l)Qq9KuKi4dUPLKsh046JVglIs7M&OfPYn!VA zHmbaxC)$lD3a`}@o~^v1|E~PG*h{OO;emauHW3H{^H{;_%+b06z8UzQH=@Du8AYs9 zw_?d6KHJMw45YEa2!^7*S3C(6`B3)+APIA%k7Ufo1V709D3hejA)(3B0>=LwQ-GOC znk3LKF;E^MO-fo&RuBeZcm!`Coz;|>af!p5=!}XX12XsoDHsJ)$b?3CCT&TgMaVAF z+p2an(RWPIc?2i(^2!$tGcTINv6KP-kj`ePP95!3dGd!@$pu@%75%ES{sK?IVjqWW zK8OS~C8bF8yvVd^utcjWBvd<(q%h9XD7)dPNh?Vj<HaD^Pnx_;GIhz!Bq7hFsS_F! zS;{RH+C>B<&B|bf|4(?KQ;3IB_yo}*omqptJf(@8_=7OGf@DZJ*jWwPfzs?6(F&xp zD*LKqOT-o3vVkC{vw}qD`J$e2D+<Vh`SMhOrK?%lf=|qq8mIxj;-_>Y7Qw<xftVD% zR2B@ukn#*0c}tW;iB+--iHw9f_k7PrawPeb7z@M3`lO`ri^BZ8w3<4<OcO?vQc0SP zNr|J`ff-OVwK)2lF$7iF96<$J*oIYrQ=f3d#{<`Htch<7jYa5CCSwhhz$!w4tasg= zDnrrYG*05_vq*JOoLMiw$_^gj4r&VzQ$dy88(6l5r*5N%7%-I|jmsMh7CVBD2Wbwx z<iW1F5QzLb|FJPqu|pYZ>DX(zzV@6&DpkS(DyB%nMuE#4f}=5(B|i^)Sumy9)H>F` z!^~v`)17U`o7|fPYSYg_1zn;9Y^a4@6-sWD8&YTmB3ra+K+0)oiQR0nXri5U<Sq+z zN8;St;V2HS^f|EQqOfeQ=z#$hP=N-Z2BJaBww+!zniWqN)u{_bQ|+f5bPzq;y7Ba; zgOUhmS<*prEZa~|Bjin&6WNi?Q?_&5kgQL<QJ^)gT+8i6Urad7<y>VoQ_y8b(Y-0k zMGBq#95*S2XyAloNKK#!omoh#)&$p1D1}U514ZxzTU&*5eTlZQDkv3ECQ?+Z9M0bn z-r?oB|0}8)XM+yei^L)j%YMDR4)8}DrCuD?o^FGJr#Z+S(5E?4NFq&D@YPFJB`_d_ zzOZYo1S{NE{MgFkNciNw&8o0Sx-bm8PaYA?^3&fBBdK3hMr5s7z@xYr3r*3qKXsAZ zySWTjI0s6Y1;yi5S=a<J-~v&&38jKxJlq2+-~uUd1YUpyP7nsRfhHtco2i_Q+c~`p z#K0-qz~dyVM!ZKbJ16$4J?{XT4!D6?(Ff_xVNqVAe_#i2d&@YIOCfgH?=9lJ<jadq zsEJ&x!L_%+TpL8=AH`i<#Uvp4b-TxeO#HmbF239^HZ3qFV`W}uWCm0D!!4d2T{C1; z|I@XM%lL^`;Dl|sM$LGIPcQ;NXahB91=tN&*dzltxP>rq1dYK2S!j)rsVYWb*9kP4 zj%Y{kI??coN7f@=dqo~+!^cY9j-s0$5l{zC9c6_!8c_X*>y<j<Gq=COGlo>v!XjSr zbyaQZoh3$3>WeJ3K@oWFANQ>&lGO<&ykaa)Ap0cAVdmm4CQxVQPiC&^W}ay?e%1k& zOv$9Nq+sI%ewdFF22h{`2SzGaPy;=11v1zJRtVP^>4Z#31vQ9*BM5_3;9#eeQjr;% zdN!1rGei^4Kzj9O7JWT0b72^bVS+Y6e;pco2<3&IYoyuXr;!0&`Qe28&a7*Y|Ey8I zBQ-2omdJ?|+<L<U$kM8`S<giBllFZHT+LNmY~A_wEYfso4l~fXLrIz5q++#cm9#?J zLQ|cN=AQ29-J;f@7HWtog*5brQYam3J%S_ngH-4QsJ@BOI3_><1aEi*PB;ffScBZW zE<m}KdiGsnyUJ|>tMS@7u53}~aE`F0RB3ZBPIjlYrEBhvm04j27LZ%G9FV;xMICHN zuA|r=#MoH|%n<2=K!^j6pp8Bl35>*+S`Aq$9a$@lUn_pxUiDSU)tg||?9Ddj{dMM> z#_7y;X3~}=Q-fBM<gjUGQ~K?((J2L3NCs)3g;}U#Q2+#1ATrV@aT8As|3x4LX(-xD z5L7|6s@Hfj;2bt68tX`w<V9TJ*YjS1mbRiR6&830-Ro{5HyZ2R&N#9`?=<iA0qj*} z)xRZd^W6wNV1qKaga`bH`d;iqVo&x}+{o^4U8QUYU1>>ES&{@T1E0c}hVTcEAO>gf zH!p1uBf~XcQwyhG$21o;5eDcw2VaK63gu$~Dk4po1xN^ubNt{KM^tykof2j4-<a3u z-bzTN<SzS4eeIMWXlt@$CtZl%A|Lfvv1_TLx`kbG|I#{FM$%SAC|UkX6TO2wumKY= zffD!vLBIprSnQD2$o`SyDpkTUe_WK+bAluAEnf4J6scmKb7+tD|7R`GVm569uW+4Q zZJ~~}i1~yCJ_SIxm<et!xv7Z&S~N}I1*GJKLxyqK5aE)cxpoxmM%6$SJx=6gVIJqA zE*jglvORV(gYuATQZIP>XlU>bw}Z?lb3>4ZEk!3!Z}^FFRrC;Ap94IwffCsG5y*jE z?}I+z1CkH~Lg;c}?={_Y5f?FOxslKLtZe#)y9L5u&8~JYmUd{jc?oCs12sc}({=>D z=4<{5Y&eq-4>H$WTG#m&Uh9NMNQO*^ghr5ROmMPADEZ&qu6Kpkn<GwowRC$`P9A^Z z<W(nr3~v~qhkgKMgKv9!a%k*b`0ku&iVn}f7HqHEkc8?T|2l|+IB<hC=mK2dcoQ&# zK%jL+00}{mER)Y~B;;jcA9FIlk;kmxWGCG%u3Vb$FrDvw&qrgPM>Wt|W0eJZh{=p= zHicQBgmO@-IN4*UUV7Bfgf)O;PMC&1U<4lugFJY^MJAMC<9Zu!6xOR(9T)q2T`wPZ z>r&|exVi^|cYEoNj~zZ(xU50r^RJ2)Pa~$-SC_~;00Vb$hex0UG9UsQPy!P;f;iZN zBgla?2n0b8gtB97MBB)TVl>7TGDtFZfM_K!7QuoAX(6noaA7T54sGR%C~+diiWYTY z%&2iA$Bq~+f(&WVVMCG%5z;cKGL}Grs9wT+X{yvL|5=c{kt$_sW~rW}ev<MO)DzK8 znvQBJC2duvOPMs;fJ22$CPjq^4I1Rf4<D|4^nk@vXDl5$bI!_1>&6WmHf-6XNpoiI z88ddv;02=>%$F^GwPeYHWeQ;^hMgd8vSbO8B1M7#;jyCzjTtdmu;@_d-@SdFKZ6b} zdNk?Mrca|zt$H=<)~;W}c75+3I~XEVuz)dxMvWajdH@Mh1j*tih@BXQLKq8{z*_un z`SN8i7`$cd(v6#@E%!=Sk|hJ9#T_wel-8(WBu5FLByR-a@sl-cp+bljEn>u|5r6)Y zBt3OhCj)julz~J6)suoc?bKjQ54P0GN(Uvx|4>N}L6l2|5jiB1haZNd3y331gdv6u zr8FTyEj{?)PN<mT4JDumv!H@QA$Z_`M@eE6C!-uO#35>g@rMz1Fe1nxglxr?S77NO zRvl%Pg_c@ty#-fXblqj$UeZAam|%nz2E}oTG4>c_Jxo^FWtj!>k3O-{S*M+M;+dzO zdxkcfH64h6nQk=P@LO=g5!Zxqh#5v^bI$qI7j@O)WtSOq#nl#DZX`nq7^lc_$0^A` z0){*8Y_Z-GLXbg-Abs?)6@7@@m*0Mk?Dt<Lk|0IkfCnO&;DQal*kVi(sz?wmwIsBx zEec^sqK48^E7FD^n)nck%qAP5OUBAH{}U^n3S&x6KK+!Vj=eUbNiv*>;e{wqkP%80 zO1$xhB3L!K6(3)PMb=pZrzHoLYqhl{mu6U3#+QBl71&^89+sG5jXefL50beF0}CRE zz)nA%@maFTC!?Hl%Cqr7feN_EFhg&K3OC#miXPYKa?L##sdRf;hh28taVG~Ps!(Es z4Q8xy#~qMBveYW72+_3Diue(0R(%Mf2(7l>`X7J+`dT2c!JgaGP7D$YQ!6b>IM7Nd zp;Y%m*<M?%-g{GoH;O1FyCRF=!Wgbjvrw`PDmejlwkKsH)rc&YTp<k?N`yg1et-PY zNqznL3viTVQE8>Y2PdrXTny*+|8SUqF-NhPi7kflnvzi_gU2jTpb2OGs2sfT!xLY; zXaAT%fuJ$S>>F^17MHWmQ!p18bUy=KsnBO==hk+kFfoE9La5<%9C0L)2qc`iGfxgV z7y*Z<ul9jRA$=_JH6!`;Cw3+QYQk4%1IkZq#J0A93t54q(6TJ_tZeZuf*$glg-(Ky z1rCmIFd<e?gmDT=oTC(;C`Gy+XSSmF>L`p@gEyG)h*2a#3~ca3{uE&q(1i|4Qkv2n z%rb|9Aq-&&qf1>_*E+pGEMjAtLULxOs5E74W0RSI?l40EGjPUuTHGQRyO<h(%*Gx! z=zySPz#HcU$7VN^o^o~u|EcI;k5bpU6s9u8okUbZ3PyOr3(9bZP|cwZcMwD%0-=gW z9AN}eQN$fCaWy}D4L|zn-`D_HHpih&LBx8IDP*ESxh)VS6+DrNG?X_9_H7~$;Sk=Q zWudyIs9WFCV7NF~igQrn6y6x2P=N9_Q<!i^k*mrhQ~?MvP+<~Pp;aNWf<w{aVTV;R z9qLj?#4b7PVGz>-?8wB#iaiktjk#T$X0SUE#NZur@*+Fi=}zML!yf&3$HxS<o0;{X zX2e+|qo!BAEc8q|)6q-N=vYVYaBmc<7(o}vCx^56P!4ezgAztygmtI_40nJ-4s2ir zObDVrh}hq)`qKzq|5;Li0~D5x5J*c@cq^2!Y#_8QbRh_$l9eQRpouC7%LNK<mbA2` zPf*b*TI3{0q{zf|+(3!|8buTTYZoslVTn=XzzUv-1b&$5%+UQyhh*U)!A^%IYhKfc z+En5azd1W6plO_t!JV5hqk;~A<9F}eD_{G1r+D_m87|8W^9bdeG^%k?$Y~?>9@R5A z4pfeo8X9-jVu)hCzzceK=vf3whd5M%3tmuy5!|s3CU^l3Hef^{<YS-vOp-sjs-%Ea zib(=$a+98<rMDymRJ&C$xHoMjaVhB2zx@=b-WuvAiAoAn^nw!Q0H#oc(g{+CK@Do4 zLMZ^aD_%)r{}ss~g(N=V2t^3Oe$D)9lb|`4DNXZ-R}!L@h*+0~tyPH=bL*LEH%^U} z^GzzCKqRv0*8?Ls!Kj&yACyPf=IsDDKyb`H73)u)K?kzgn<Ejs2NyO}f)bUB!y53w z2Z+{T4v83rA-o`mNf-fqk9dR_)_{pi_<<0$vXx0u+AG_xl%)rBP$vo3+m--TSu+JL zvxMv9Co^lw7rfv>l)GFFcCxu^Q;;W6af&IZ!W#i3;r}-A2O)$)3|uG$Qlz?{szL%A z_#?z6@<#}(u=ig8i{^WM7}5E1r@m?R5)#3rU)jACuHsaa#&BmDj}4d(>r^nMD_v>i zIT!|J|HNk+_qhZ%I?A!vi(}C2%f0Qa<qUCvhbpeH3hCSd#bdcc`u0EuE?9yI3T+1% z)^Hz0=omlz^N;`jM>ZfkE^Wga@=ITG<RlwJ%2AdwwX0n>XshJN88nubw|pZ{Y(foQ z822bX@reKi<r1XeC>KPbh)ZZf5+^;Wcs-$?k=k!Qpwn}}-V5J>$@gGyQC$)7%NK!$ zNih5UW`Cgwght<>22_LrZYThTf9zvUmfkqW-3i8jh>?uB+06|OtItG%+Kt>C^*|f8 zy;Bp74QF_R9+_Z*BS@iqau_Qe`rtG;lz<CxIK>^>fhtJE0auYAgd|H^Yyj1kK$tX8 z{{c0rHr+NGLJIUPwqqe>uUmVjUC%a4zV)`O*Rnwd?1?8b0gEua&<KC{1h6_G2}hXw z5C6l2B=A$!N=%~<j2P)6)~l6$i?z>Y`SX<m4VSd4wa`iAW?LCfyTv$$oRl#qW;y@_ zdl<Omq945$<@pZVV1{`$C^-)hD^7kgiiwRCwa+43P=j`FJ8yWy2r6oX5tPpjJ)E^0 z6v2l*{9zG+z=I<CV1{C@VjXT+gC<xz(%4dxwopCc)N#A)As4yXZ$mOD$8LU=#4^cT zAOG3W-t7f3j)WyN_xnZ>ivQtgK)8yneyT6tOyHYW9bUhPPL%8rSy_p|4IIH?{}Xi} zT*SmqnViYR{FfAM-Z`a{UXk7ga$w2;mNNiKZomL<6iVxz9PA}WsJ)Ruk=h*5kz8bo z8>9gwP*e$&fGQ{fB)CBx;DH<50YwRc7&y%x@Btn$!V@F`Amkt<%!508K^!0gu3R6l zgbhj^o7CNwkPS<>6%N`dkU?<W`HA6*1eH*sUD~PL+A$6R4Tv!C!Xuo+Cp1DZA;nZR zLMGf;A9TVSa)O+#K_o;%eXy5Ta79?~8R?W2pe>+%HK62W80_p<#lRH>W?p0j7-rlC zJ7{1Ba$+au$;S~wrp3S+McAPvR?1ONU;xypO^WuI+IGZ+8&rZ9h(R*U{}?5l0UPi^ zA3VVeSb+&pfg=dQ9pHf=<be^8fe?7XC-{LJ7~Laq0`;|vAJl=pnbb**jZu^h_W?`Q zt)1Fo-5J7^wte9kPRKxzV}yv~25}Hi7!U!a%TIKIFhBwbH3EUO*>~+9e{_NztU^1G z0wQ=#eKZpR@|z(_QzFh+mdFJo8k{3;ftW-fe_dV$vdIlpMit!^HEg0MdgMpGhCb*6 zrY#SINtkdf1`1x-8$njfY0sq?)Q7=^4!VUcmVgO_K^&Z!3FLqf2mut_fgcnjA7oA+ z1Ogw7)EXp%)UZJuSiup5!6zs}u3+Q;wAuD?<AK1VH*TRzts~qB|5ZAQ<yiLCSF+<K ztsS~h9UFFnjGTfnv`apIm%Qx<B6NZ+o<iUWUNfy%dmW?!DjvWsq~kT@pdHZzMx?|< zq9n#uB}!4pu)u&}Lg;~HWm;xxgwYO&oTi--%}`kM^b=z>*2>l1hFOY1otj%{iX4!^ z^F6`{i~=Og!4bSq4j@w?^g$iyL4Ev7lN3TE+yO5@!aA&j5rhI6hyf|&5B6cguA~&Q z1(~v09r%UcZha+LVy79JWw)W_JIWtWn9FsgOMz?yCCGv&@CuK_o4hpwCSU@7*u*Mq zLn8=Y;q}2F79d~-rhEa>S!qdO*2R4h+QAtb<xQmJ!By=z|K<)%Q4H*kW=z^;YLP!s zXoXtng<@!iYUqY?Xoq^}hk|H`W~e-|g9-!+3&g;tq0xjDK}uTKN&-|s#gQCc$I!&w zYQDj}5W_k^K_vtNBK(0A&>R)~LD%R(Z)T0t9KjI~=?Y<#3%vm&bV4TR$9}k{748TY zW+m125?AIHcNU9Tis_iT2pXcLJKD%rdV(ov0v%+62vyezb&4r~LR5hld+wtqtilzT zC#>{=AQ~i;=x3iLq8pf1psCJjJ|tpF<iatgf<_TtRZ(VK+-HdBrDAHPYU-wbsDyS= zJpIEkP{4_%XlFi;W4I_P{u5~m6m_^<hj|!V%-|V>|3M|J12KF-8SLKs>;W4r0ThHq zln4Un2*DwUfe~~<A;kfBtb-G-L4i;yAo_=M22j-f%G9Ba7IvkUStpr#YqNoA8opx* zHBKqarWHJaC`c7iG{PrPLNdrgClH%SVL~Jzf+p|+6G+1~B!L=CDI?&}lNh4E#aDmQ z7h0`OBNFH~0aWEBN5d_FW6~ApWkwIk(>(x>r)uoRg2rqNLIdCiimIq*wkT*WmU1Wu zb36*m*`6!HD$&TQS~v|C{9YHx!X5O16i|T}6zd>yMKO+n5g5S}NWy*QPa$MNA{ZSQ zq=6zl4kqY_*g&1N7Ra?`p_dv^xN_^al4)~w|Dl$prCMfd+lhkQ-2##R&wyltEO3G> zOzXV$M}Ek{8LY!9*ufKoK`4}g6PN)afR3O>(*gPrHC2;#0H~!5C<`W>!#=8lt_ho5 zASTX$I*|;=TJFY<<Q%vRZj>sg>66K(;LczHY5Ghna@fmOmRqm|B#aw0jKCwX!5@%; z5}<()>_HloLC+Q8AkcvuAVOEj$9zOWBdmcuw8JW_f*bUKCsf}e^p90uB~~WeP!tf> zZY!8_?K*~ExQ6YGz~f5&PbzGe5r}~@1&A!j!XwP*NmU;<=8q<<LEVM|kXXScc)=1- zK?v9Z))b-+3GOr%j9K|7!4*;D71|?8|BN?1ti>>fTv;MUS_USnfF@S%<yx?1`oo<3 zgXX@B$eJo*rD|w;6YbTWOIFJ2)R7&ju3PNEXej|kVF4uk0TtMR7({^;7y%$SP4FHm z=nz67Fv9sV;XIT<B1i)BR;g4~QYQ40)naRx!ejSp?G#gS6?3oJq~%sNPB#X{lzM_6 z6oM(JEq}<u8*T&j{fBHhZzphqcx^);tbr$7!X&(a4Mf2R?C%{6!k!)Azm=5&G9)7^ zEMg`m<G$4sr3qvJ7z8_LWOe{EfLz92@Fas|2Jgc^xWVRnu;+fJN{Z&AtYYb!=F7p{ z3S)^O7^)#8!aS(L7C^!qgn^I_|83Elm>?ucZvt;2$N?09K_El|Cctk!%)=v4!W={n zHpW}qoewEMXZLAw_kN=lOS2Vc@wrsp_nwVTJPsWOMYXbL89xFxtbrQmM<;}sbgd8| z-hm=a!V`298T>&p`mf@}SHM-%e+u$|66oR{=mICG<35~ZFfyc3z+~EkBvW!id!#=2 z!#`}nU~Te>4o8Kls$)G?s}j`hp{}L`k->yY(W%1C<-n4{0UZ#b987@};6Wb%?^ZMd z?cOkYDFP_0!5VCXG!Um5)Iqg2f+A$XAsE3^zQHH_4+=Rkw&Ip_X6;N&b5nCCG(XoY zn9CMFaVZ3X8~i~qrI1u<|H4Uuf-JmiDey-CHNyJ5D<;%WAP#~c{EHyG!5##HA^hy< z(6eAJBtrsd0Vgh_s^Vfc?xJZPWbzIl$ce@&^kH{m1~>E<3>FL&7VDj=rzzHAjqvD( zvWAT^3S&xTDWJjJ!5WZ(Dy#!+zJVV&&6!yNy4t}Yy$T;J0vB+>8yErd+0d<2pCHtO zJ7fVQIBiuN0u|)JnN5Ow;^Q_xakhFNG-I(-U$Jt3rzr%&8^i(KRTqu~3sI;W8YsaL zSV1XVf(g}OCSao^ycs1x!YS~99B={_tb;rZp5Yyyo?*qm;K86$$>9Ew0wQW&V^cOk zWJGq;#57UE0d}M9|G+?7QKjw!LL+vAlitVu17nxu>Y)+zfbR4(7E5AuM!O(ts;~l{ zg&P>cQ$7MT91<Jc!5<u}9R#8A!HUxyQx3qvFxn5TjMP+8pYcAzDzJefnAwu50U$U< zwPIy6PcPMdr&2rjk~6s)f~O!H0UR7b7tBH?l+f7}h$%>d5V%4rB*7jKb$}R~c*_=R z$wDF!12N=7K1hQ+)O6wL+rEVrUGL`~3mkW72jnd(Un?A<9mhWxxCIJ!2UzULP^g0= zItR|iKTLrr$_!+8S_q$PWnVTN@x>^k=4NxWz)2Jx;K3WPK{6okDrgkD$<HA1fszP< zBy@t3%!eQj|3a0n&>liUJG8?W(1BE!!hSd>08#ChIu6@Fu@)=2a#yc&6FUJBMJBjH z7`(yRk^w4+r*)gnl#;?H(Ciba0eLC0)Z%GRD*_-00UE%85Nv{e*oRhVMN13pz#<|5 z-!;PIxt{NJ5*4ze`g2@W;KVj^W=w8JCVIek+-%T84>&r7d*<tTGNnIOOKzA8!m6gI zuA#0)!OX$=tidU;53VKxBMswF^1&Ye%i+yORuCQ|`1F**FFdRRC2)cqJdP$T!V*8H zahs5VbOLlkffNJ+oLYA;4STY0C9w#7;}CnWWI`vHSr=G=7>GjB=U>&P&=Cv5cY{|~ zd;7dL|H2_8K{ArTAqavXWX&M@rMtryexrqcrw#-5w*%UHqaxZN`&Xov)1-DlI`IR> z3jE%SUIza|!HXgZI!_QF3Pp>s3N}0oKKx`w{KOxO#s5$s<)+b10VfPnAH;#4bwx|3 zdX)|Wtti4D$UzwFK_f&$O_u{suYwswf+l!^N&U~%KE*a(>wqxx6TpEeC_z&F{M8D5 zDWJj`RDl$n!QxQ$adYwGkislnf*5Zz&TsWm?8=lrg}39WtP3QssDT~aS;-sZoFnAf z*K@q@w;&tv0rRs0GiGBFzJVinX5hWv0}q4qef|5D-_yenY^Lg!-17iLkRnKsELqaT z|4Bk93#T-kf(1(!En2oz{IccC7cd*kbSz^Aq?t1#)09lZ2BjO7E9J<U^YZ1LHEY_n zQ}xJ9B0p;c;o<YsPtZP2e58@oN6@7)Ppsr1#0YAmPM%J+Tek&LBTt$bHOk~QQzlJg z$96Jn)>EgjpBzyUW5>v!PiQ^WwR;zD-nwQ#{V|dX&<nYCN$E9gSS_hcY0ow$t0`<) zNs}ozYBaeKR7Q(9b4G-S5TQbYMh7+R=O-UMtM%Z)QwMe(I<sNUX(?x=N|Y!~jvN`% zW0{Q`GiI!)B};NF4yP=Hk}zQtgGh=L2?C@Cj~z8=%!mO)1&a<r-u=6`4}E&||LfVe zcmE!KeEIX~*SCKke}4V@`S164?;m<#=zs+lV2EJ`8gAHuhaP|ss33z7Qph=nAWDv+ ziZCi}xZpzajii!x%gv43TzW~4JK|X56i((*1q)8@7{rf0@DPL#Nw`P?5F^6)Ll8#P zFk%uh!ti7eMP&VDRMh_)wvB#)VG5WTQktPt9FzuiC}{))q*OqpyQCeuyVIe&JH#QR zL69y5q(wwU1VnlG{qN`Ad#%0S&kNR?;l*)$&g(q!y2VLiqDjh(YJ5owbecj%Le#2# z9Anju2c26~I-T{z@mj+C+x4Q~1!7Yl-eV7e3+KC}V8kfZ?dt|7eaRa~Z|783m5a_e zB)z}K>DW94Ef6W6HS{}aS+puD5~p@wiEB&7%90eXhm#aZQnaZE$80mZ9d+!LRvmR7 zwthM4BIbwovHBl<FME4s>baJ-@brH&^KZj0o0kQ83JapOL`6a%(Ju15+AoATqHYh^ z^gq0Nfl{PY=9(UmIxr)F^M5e>951uux|<~E0X$C<vuWmx67j$M9IuX`<c#J!h8Clg z;QXLU6%M1%DUQWSR<w7p3}i`yoc3EH4Wj#@G`ga4?@~2xJH?809##uJe|Vdxgj!RB z;avFcw42cO@IbPZ`u&?thk|t|_GWDb2rJ0uzD;owa#r_IoY(?a9u1HBt+kpqO_^VN zGujE9bF<;OAzGdKHT_yLN8KTE^XNSh<bv7U)10rZYk^FLuTJ<+7m1O@1>vMj9$siz zQO#7JUEP{C=ar)jvF*$qjSKO%^wmX$NZ!L1&b6#$ofkCvne^N7iWg><u_7183W@m` zoh^hCiakzLA;UwLPJ7uXELrOI{+5+SC$Zq|d)yt8mKkA?^ZE+Z%$>6h=dvY>EdKt( zojvX-lIWX+z2YW$6oYp&{vqcRlv1Cvuh;@dSez|Q-c#5?c>qbg-DdSi3y$r~73t2} z3bMkvdh?r!q%>!8HIpIv&Ak*sFuiqRhIT=Kfy@Y^miUpGE3t=V%b6U;Tv4l^+vmFF z61g(FNxusgZ<nL6)DET(#e;uU$iW_H_esxxk5qODqK?)cU{uM-#sd_Qk;|+cbiGg> zooebISBCF6-BhB>%{FfvCTH;k4)F>;b?`Qt-K2~7O|LPlL}!vse^U7J4ribR@)jzL zzWg`}iy_uoBiXdY6-Hp7z2rfdPv@2?J*8=pikWVooJ)CfH@uHI9t-NvXE&j0_Y?HZ z{N@%7@x*ZdUe>?u`Xo|Ist*H`Q?B^u$vMh};6LKfRKb(YLIZLXPq;W=6Zf|&-j=7z z*XC|l?Ppm=k&2XWAe^*yqGvJTVgm(AKQo7DGQFc|MdXnspGo3F!HQqwtSFPABs8Jg z;HKdsmIOSAvz;m}=PokO_+X88tWW7BJR#3A3B<#3ol#YhqtFp5VjyXOj$w!?gN{L0 zw6W;W`z|}y?w21Qf?Ti163xkNyyaLw=tun2snq>4qxnaayJel8Dk-Y?wHtlZeO?bo z*z9?B)c{=xu~8%W)mg+nm+b_SV5%~yxqYqgKe4*Y6ku2-QHX$Ho}NXbJfp*K7#D{C zg5ijh<7DFIBex2V2KFbnDioqWqzTK7gVf0VK=hIu<6;A3%J*R$Q^en+xFY3f9@>1? zSZ9w@=IX!wZ*^B{W<)kS>7B*(Od;*x(e4qxKI-HU1)7WXD30u;*E##K)^wCG7I-!C zBbhPViFWhry$wWgeF#myOC8O$xh;dIDf*6>%Go=l-XJBd8=a3pia1fS;4e0Ak}LX| zEBfP7S=u9)sGLVS@+cfMyI1@7;Qb=TEp(OMfdXiux6F&LQkP;{Rn4Z4DvYeiqrG2! zfGL8uhA7wK9Wl3-PEi&{fG>=1O`!q}5}{{*X1^EOx3~g*g*b@(qfsVJW@1Ki!%K*y zmI1F(5X$S)3k|COaGykpPvJ>BD(2whZybG(I$vSaeboiFSr?FG<YUu72Sz8A=4m;q z#>B?vWknmZq(4&0_ET%mu6P&(Gyf?#_1-*6j56H<-Kz)FsMKmZ*SA6Bpq&h%#4W<2 zl7@k(&?U{>&Gr~|moPG()a*E=uFgW*lE;i%guXs>Ql!|4IYlh}6Lx9yx~sc~a`0Cu z!^g=DaE0MQ)H8<Jr*$;%>Wc3~lN?n&rVrQ~WnP}n*r?(nfFOd2{L~rk<9M!>JLK*O zo^T2^g)0<TpuC`<#`ao!B}RV#P%3_4a`O);D|{eqfV@8KwS#i!aCN~!(#(<w%Ddi# z?WGw4TUwEnwdP<wM1ega5R>YmSYO<%>UghT;!(ydDTE&CH2lZ6X(y%c?32aaRxwe$ zNRd-pX~SdR4(46$6}Hl~pdCpJVgIlVz1>bAwLDYkUO>l+x)3wPL@Kax^+JR7y<cXT zEA~s>-4j#|o?>|I!65kWeU5EkzAj%sTYF(7hgP~D|E&S!M%R?Bz*R7rnvGiLDU`{z zgnqu&{CkP`XwJ>I27|1#+Ho1r1yb_$hLTb()kmyUWiOwzU3j0)Ry_5*jQqjogl}zm zfsre`cW$(zW#^u5y!Mz1(ZxP1obf*H$h6XL?Rk8h{TaborMVY;eH%^n58!^`w#ohs zuXvlzz*|dbJUl8fjD~Q1+-g~RC#Rtu%~#D3XMg!N=*K9xC}q@`yD?>+cOUgUJy>~f z>dw8GqVgxg7P5!Ex1QrL*5{G;Vr#v3AAaVGRMb^bILco5RaN8osH8HrGIeMrD~Q}| z$^$O@gl(+#;-uo)-;>;3Ha8m_^w4UwPNog26CU4ON=Df$^{ex$sdziR;$Y3AjceZg zfuqAgV(ndTIjsl7BoD1VMBIz4W8GnAOXUZ?m;)(9O!H{eM?0!m?7Bx}q^ts^DAD^$ zG=->K-6{X3@U0U97q$E?)BqZGil-ju_Z2`0L=Phdu(c;<l;E8^y26n?)&;SpP5u^Q zmbVH8qSxHC=B*~i>@@9g!h4EpXKLH*k+&A(zu9x`gF8dc1xEI*?ASubFRr^HV>Ax_ z_0lL}L469r$2)(}Txl*bE1flm7_QZNjlYdmtK&6eon+&i@&Crlkiwc2$K0N!{9@2a zq&0^bO)nzVjI^6TeF{*52DLrPRf^Z?`qot>Nl0&MkzCPkXqMy1SJ#oua`1HkQM`_# zVW;x8YE(<2jDaEU3B_+kf^8EE2FaBD`}`Rzs~o<ay4?Eh>-760WWnQRtD;(xL+n{J zvIN>EZTte_wGQ)92jx4L77LRV=`coUI01?*V6F~JEP38|Fb7v>d)(;cw=`M4vDqVv zHbKN&@}o^e%b-y9#|a&2b)?E}BaOKZ%?1^YM}?p`1CrYYKk)pwj?Blxiq|O^d$%I@ z?g)iM@`wn~5K$ju<JQr_%N8fySgL3~;#)$$?vWJ83bD0W*O*fBF)E2&q7m6xI39~Q zBNTFM7wT!u=Rde16Mf^^m*0Vu^vY`VX_%p_?j32u4!B(bY!OD9?TW(JULQB}=OmX! zhOwC8mf>9BW)bJ;3Ax;NOcR)jsi{lT5ss-^=9cmF50s`oWdH1n{(Zm~Xxk?ouj_10 z+o(0#5Xxq^iji~$$SoVuW@}0hC~6iBAH+s9TU&FmKY1{{rRLh`v4`q5BTpre%NEoO zZy_y?`}}vZ%@X|#Ae6W5QJ^3X<67GLF~|!uq7Fd#x+~FpicVjn$fKbpeCl_lRbX&K zalF>6#9L6)ZT-S}tTdK1oag{Q4bP*JO8M!i7{!{4mHb-zrM{-T4^cswUcrF=TJV2$ zar~;mfmlP_oN+@GW8vlN6od9hS38sbhW(=IjRk-lOlShHW(}4ZN7D4d2F%ERXi%ys zPz^Vk@}*F6m|N@CX%qA0OaX{fEOj$P<MKP3zEe%G6*#O=SoMdEX%X^B0~)$cLClUg za2~h$d}@)>(mgY8bLaYJqK9i3%q&WZM(*R1hm1!{EW;p+aw(}P%6=X}z!ux0nSc=* z++EkvsdHKF9>UXC(a8PPW}kVfwu^CBeEbXP6b^reM(~9FJHQAl#1=eFATPwi$^jLt z(0=(xsDEg!a4zHkFN(MqIt2(L<lgJ?f++>IslHR`Io-N)l{ZQN%iXSt5BE<V^w%Al zJ0hI!tkb=!e`opg-Iee3jWDNHm4iVSp;x#@BVRN_)=>!`n#}GUtN*Ot!!*Z0!9T5a zf4YxUUYDTT-44sgjTM!IUe8jzPpZ^{%C4aiA8}#DSSU7Cak@->;g0Yl&L*L+$Wy$B zv5qFG+sQ{j1;mcxB65=z)!J5PV_<(WU~MMPiQlr}vQ_l6E0))JuFVon?tq3f9@zAp z+<f-@--8n!O+E2D+w(4sP{%ahn4`eKZ^h9f$&LMs!#jNZSkynclz3`=Had%+3QngR zY{tE0z1l{Zf`Uo2&VxvoQ7z`1!OR7t6x2g9A|;iCZG_<?S(X;aZk_r~0pZW+XYw&f zieI8?yK)sUv8&|G{!&%8b2MrZukb4Lp6YWC;|3l024WHGZ#TfDdfT%d2VX}+iV4(~ zt^PZ-!cP>A`qW#Tir#6bQ#_4*bT%jM6BlSh28(dLgr3sp)q~UD^M(DSx3Wv&@M^yZ za{e>#d`0I%^4JBE;X=0Hg1q5M{n+)!Z|C#tzQ+y5j`!HYlnzGFWxSe!QB-GTtg6y! zrz~h;R9CT6LxSViSM7lpE0k7WT%K-!*YUS0fa^cm-{W#OK+R&I06Q`kPr(>1`s6x1 z*-LRSrt$ih{1XJyY_c~MCuS69f9n9Ttn*KMLDwxQK#SP#QR;8L7S0b|yh;6+ftnIJ zmD2IkW>@xRPBBzCKD4q}1si?3>*vRTyBUFB76M5gJIBQu*6NHLT7gYlAf-*@MPZkv z_U;Yt%rnlb^9aPmZC%ac7u$7f7N^`vzto>CXeWewF;vc8H?EGGc_==z4YKG7B_O!q zs1GlMk@~DN+t+`zTvz4k#omk0$Y-8)4io8qT?>AWX?tcK{$Vv{cUy)~^U2Kw*0T)* z2Z2{Pi&1sL%Xq*jS*e_!Yo+{-`$)oJZIk=m42qRRA*F>NKic4jT%PZQJoz&{f2+*( zh=zR1MCwKi&=ep=Gvf^mZAQ>!c)Snk2KcjEf}!I{xfyZ?r}JEwXHI#y`bLENVu1X@ z?<+T5-hj+vdj1EW#M?Z+n2{AToUaG`JdN@hEq#!cs=k!^kRk1nQQG6IG?S&YXAJ4j z8PcjyDoZ&1ly?FT_uW$TROJjP-V6U7Og0(FbYN?boycTS78T!`E;K9hOxX!8%0eEa zpOi{vKe?d`k`wjaOfXTf9fyb$6Ok7Jh*T`>5{s}~e9=FzI5MBa>lxugf5z95d`JI* zYs`b~bSKJrr<h0SR}6R(V>~1qZz7c%b!hO9h?ba-sfu1Or^H`m;knqbVAklU(=XMI zl)u_EFEk}&IVI<Lln@^X<cqlMJfHB_3&Cq=*>xTE3qQpOOIbM#;-_c|H9;6|f9`4% zd4nOV<>OL|FLICTdX=j-KgjSA#2_+fN<Taq+*7nKZ3dq0mBoL@*D+Ro=Dhf~!IFz3 z=8_<fIQXK?KMHNfwVerG*Ez~5rPFz5GM&jhYJC@<Rkn*m7878_W-!B<#JR;fTgDQ7 zU;9suh^y@2eKYlKJmL^baS9+4jgrO|i@4_;%pH^hT$3ZT&KxxSQy5?WTr!K1)N5OJ zP!p?q$kejJnG)Pg(vv9Ag$Stee%?|eJ%pgBhzXfLj=5iHsd;Mo*1d6`QRxWZyiNeO zuOoH0Vz-@a4HoK1I;wOX!;xJb&kVZxxRq9MWzOwMQfhvmAcNjr(7ANSt0auX3%!c0 z#8=5kJ!%7lB|P<!NzX$Q{h=UmeoFK^m+CG`W9XR_ePQ8*u*}PqnxfRNTCGLAe~O-L zBG(nk1Aig320D2!U+_!zsXIao*U69Zb^8f@S*4IK*?Ao+q1tpxZHEr7$>lM|N&XZS zcTI-8sU5tk_|APK|N8W}%eMR?Qkhv#M}k`Genj6YZzb~{6)>idiF9eEemp_>PDiws zmRVvTy=onq6_D6{uN$)V6>&7y{!^pl-J#9`!`PRLOxoP};nv1SvdP;WE-2NehEm=Z zp2#<)(Co0qd!9}{W67n<vL4J++e|8+y~&J>&K_BB$9xMDE~Q`j5U#SAV+&G)rW?MN z>ah^1wkw$i*O-WZ*rw2!Kr7J9kDAUXn>tK)54`DW>_};Qd?}tVb@}u%e`DT1AcZgP zw)w=m1DtQlkEN=r!LW6`steir5O!F<_*P7U!u`+m3;qui(*$Jqhi%4*1RsR@TKF!Z zyIiblP<Fn0b(x!Kj(<f)CwJnON&Xv&vr)gv=QM9(bOxg|WpcC6V>5{@a184!<^g%1 ze$lB=%8_zF!F)HSrCNu}xCy;fnaZsrettz#(!Dx&SJ~-T-mZ!7V7uO|h1cAb9lATG z=|6FkX-zQg-9q{vkUsfEwq#U-&ymFdCBE=7Z{g2c3VeCTnRWNd{ps$bbJiUmW;@_* z(5ik%QtOKrL1&p7+iF#Ye9MBr5(D(TF-xD_ZF_kGH*YK*OuMZ<N`EZJI_j*sWwN$p zbO{yt)lGWZG}pD=@;up2R_{AYPlns>ZvN4ik4LImJ3eY`k=tyO_?94n=P5~hF(0cb z^9@)6HbOe)SpJQ$_Z0bg9#qU8^xyq)SDJhE{L4h1jPkuTPpb62rFZZB=AWDH6MKJr z_aHzji+CJ|tCs%u><Zry&j4qUzIrSd9S6x5ntoR+*tVEK8(4E4ILrIES`zR$BynEg z*?GqOXZAOL_U2FA__TEQRV!bx<MXxr>3f4ob&noiZGU|O&J1$CvSvLUyPw*2!4k?+ z4e5#g?f3hwYucnVbI|>uu(ul$Z_hR^&N^6sWU--Fq0B1vcqVb^60^oI#ymR$HItjA z(y*y`hyG4Be}BVs1`JvukU`2VW+cU=*=D4ViY%S~R+&bSd{b#kj#jp)Q6KgH!k{3c z4<XkwQo?2`lad4+Q^q2_-tqfeeoug5lik{AOVvW1S${N(dTaGklg&)!ld;yCl{S|) z-M^1j6eG%n%mxxgLI&el9{2%795m$*^VK~zyN#%$$A>Ua8Z9fRxJSm=?}U6G)+w@% zq2-LGTdQyGohg6xT6hgZAwP}3={rB%QDl{rp_8rG(fHy@V>qrrXuhL~cd9@k=4esp zc|~mLLw)T%k)vmG?TbzJpC$udzx}q}AH(*rr~CZp-b~fA_dRd^{NDZc_0MlDbrMSN zU#B(SC63q8SXx*5htV4}s~U+Nq3<ly_N_j=c(w}Gb!3^adf-5xFS4vq?YXxR!Rpq& zp}-LARS-s_1_g&clN?^L6z&C?y7cddE<PNhFqqYum>{G+()Pqg+`C%*%;K-YQ?Yej ze>r0LQu_h_cIwlKv@s;hdd6dNkrO2aim~r#L-TO<AVcaHDRxs$=)KZ)%T%$mbvmKS zb|Xi+^vD85&eQ$f*MVAGN%@UF4+@k88dY|kZuQZBj*Yu2v3>qf60W3&99x_E?2e7b z22syF*=0#9PPaR#C@-z7^!k1FGvQu|N?G3{%--)8uPmq@?BJpbIu?WCM^2J0Q%knc zd7d9nrwd+;dkse2pkidg&#G1NK6rmmhN;P`adERjKuY@XdAyQ<t*iPO&APTCLs+W& zR0Cc<J<HH~tMY88>RZp{>7R7}lQi?kfqq{jzGMP$o1HAu+oe33j_^NLxyH;Z7L8Q5 z?b%zWAJ~5#LJ#eHSK_l6`0B`6qw=BfQz1>Qb3(E@r`7=N?xT{CuV+WPnw}RG(pQHw zm2VYqIG#+aJgi8#`}eY+f{JEU$v#8v`*kk&igeh%&i0BGYGgT3%T@Nm^FcXB6Rllw z&GJGx^N&HEqKTyI%Oa>#5&R#RU(<Fc)T#5!j(=+Dge$zbI?0gt*@sw(qqEP6V=ods zJ3(?m=|V0Yujl^3(vIgTn1**2eEPHAExM<NW-T#{tqHA8Nq31Ka?ZpTe)0I+`lAq$ zeUuY>n^fk`L`rGQbL~Tcwx0>!6DvgY-#~B9%99>D|NXW2a34uH%{5=B_F1}kk!eU> z`m68Fh245TWtWk32rXNTP-w@)y^AkQOSM=3nAV(`);@0LIWdync|+>#J)jW#eZGYA zrHC^Bc#M`_Jqqzo=a%1p3-J<>=?2rhWI7{A@-y9*t8G)w$GZxzEoOh$5Bh6b3>0RD z2#ep3U9vU$Cqr{}k)fbCSLak&WIm?*foX<+FYJ!U<G3l$rq70zkWqE``_1icAzZ)o z1wA9AZTOwAldJ8#5jY)F#&+v3DW-!XrH>{vGuI<dv)Ap@fF<AC7@sc@+4}{oe<PF= zy<@^({(SNgr(DbR!!Zi3mqAUMQK9)RhBRM*Sb|34?k(dV$(jDS_aaXc4C~k3yr*+} zhkw5g<<|%+urDC{3~iMfR1FkbAx4SJ42>Ut4{XVO0c<}WARZ)_45!ih6m2b=O96%+ zeVEm?BJg*63xGTEmON#u6LzO#Z1V1NGK-jcZLcfaR2#*`U2FsoU1ejy?a`HBjfhT$ z`9!X)AZy{>tg-vG4w1rS3uExiNe0qKnFD`vIFibW_~r@96aLX<R%n>-<#Rv7^LQ~{ zwdrU9N8y9(#0sH}n{5pq*CB77H962yTalaw)8)-QfsLgsPUlk=vfXuu%mAD2xIZ+O zvE*kDbI5-_&>Ytxfh;iR&y8l$M9L}9zNC$j{#BtJr%v~5n_Os7354CGnj2JBd!LsO zH?Y5=Iu<ry-r-jA-M&KI$Y7?m^H+j{epN%{qPi>P5BpvzE)MFbJH0GnQt_bV?#5Jb zgh5G#j%KyR4Rt!)^pGDuml5`MK#DK@cG#5}?H5D#a9#TRUmo2_UyR>!543fPr5D~E ziE*pc%I7FIg?7VS&wORoDQNk{7H4(17lUppKGch)sC9{mxt<#6m;QGAH2pZaBRDP5 zKVARx1ijVduWi~q{(#rto-R$!`u^^Um0t6DC#I6WqaUSCvxjx8YSNIy6oh;Q=;U9} zZZ7}siOCZPfV+mEs2mz|e<svws7}^L|LU~lej<2(3=jUvQ?pL%Xv`-2^v98&;mfZT z58sQK;OEnye7#+8oAN@X%L7ezq9hdfcziSZ;5RFwK6jSui%wP8&&*O;?h9zD+H}p2 z78TQaueOyj2-ErSbp>ovQ@s{Xo0q8^;_Bo5xnd&=UA3hApMpA{R+{!?-N|UH)woSG zc5Xj(PnrKdBwXKYYP=s7dMTCpLdm$4xU0c=m)qW2#9^NI@!5M^?QzOj%*KsAgMMHe zBN7tb%`1T9=d>E-%zGU2fL=VtYO=Ys3|8-__p1^#V>&kp)n(rG?u45bSTVRiML(A) zk!NkbUX-#Yg)p@GJZ<?@Z90y$_Zj2zihjSv6yLG>d^|_1wNYYE?jp1Ik>%`|fusLt z-5o=$LvgLuLbFk%lEeEKUw7LFZyp79@{j7yyXXIs)_D3%$^{)>Na9Y`%Lem$N|PDH z+?lj<A^hhP@ZOA0>KqaDBC2SD6jO2aPIOnO%w<SSu&lO=V(4+vpH2FqFZK&>HUz%; zPD{wJ%H1kyV&Y2~3l6hPzqU#JtS0Y>5<12?Um{DVtx=MZ(dl;jf<5%(Tjmz+6%XHt zu~zwRif>3Jx;|04d+YE1!H(o7sy7FbS2dYL#+E-~e=MXxWVRpY5x*^w`q`MX=DH}` z`i9U8X52GfY*{ADt+;7sPyJ@^fy8lTn3QL<`rmJ_UVC@hr#n_#2W*jgqBq(vhkJE_ z>lG{I8MN=|s7b!7k%xYgR|Dy;xtRZl)AMq<QI~3|%Z;#ypWuG}>k|2?qpR_E4=XMO zd%IkJJuds|+hjU*dgPFGoR(20jkyXlnEKp4)YJVV<CSO&=K{^6#CRy?#yuT_xFgT^ zKUx&>FE&H<H(QZ!&#L}?UwtOEbqsdhyoz2aOl}|R`$qUY<Dx`%`|97>?~I>Uy$D?) zqGjlfmxankW>g;X*1k{EJlTf=Dl%SH^0>~41){wDC>L<Myl(q1HGb@1zdm+;KmDTL zfW!??HpFX%$#}(=8C-5*I^T=@On}JZ-I?FHlRkRxY9${eVm;p~98vaM#wuvZ%2S>% z6zk2o)QY3e#I&{qGD8hnhq=49X(nfgWU-KSGvpArl@Ys+z+%`_6@d}!TWjlJ8FUB- zjW4Tb02ZRFt#?l$0~ZkyN^W=+>R}k_Hf&=w<TvEOZ#oo++YTHDy_y6$Dq$e&E~bA8 z$XgMbH%`Lh&my(m9I~yEvjF%*689Mqm+KJsZHy5p@;Wr+dtH>dyb$uzJHpF5nrtz| zxGj{iJt)w|?WFZOmk|l)e#HTh=A#hVZFm2HqX_h|I>}1z-;pQUWG}EJJUqnfBrkI_ z!&6_l74t+(w?{Y+M=xf^EtkhF??%6Y#PG}pDv|o%O>z6KOe6r1b{v}^)BO9+;*aUM z|5zgru<&OtBx8%QbH8J4GfgCHaHiHqb2cy63=_dVi4fbkx^_;}8}T37y_@-LWixI} z-0{cYNgD|9@*xi2RjxF(ek7q8k~yT3xr~yxH&_NT!;}gU`2bi9MGH|D#Fy#kLE}L5 z)-x(`j*`*vrIdT;DO_zSj*Ah2P(zezOdd2$me-Icom+$e?kB{PyyW6BN;B|DGt5d; z|Bw{p>F^t$e2PKj<48y8#m0wCX*#0v_S~Pk1&F7on9KVrN@aK$Whh2H*nmcFs$92} zaE_k@QL83B1*eFtgWRUbws2vo#mLy<wD|MPN1JIs8@%$c=@_Z!HXW(P+%Lr|X!7?H zB>Cffq_T^pvXSSBc&Yebr-5o6CgUZ<nia%yc+z|`itt~^zf;ItkgV>d9KFpnGye2+ z2C+=Z5PaEHR_=aA;C@z~PfEpkZpD7qhmqXTtW@Kc)V}cazFq!|J0w~J$ow%vfZwVM z#@gePzt_PsaF#Z&!}S?O=8hqiMUiMmMcvNITkOcX_c&#ApZo9mYrr_q{yb=*BlWkB zb3FsC4rh*;Hrato&WEO)eW~lcB<=wl_pi3dZv@0R0cwT=i2@`UQUOGn=}zH!=N(xB zorO73h2YAlI;nt+{Zu79X*Ql>b18qzCzy7*=w3F<7o%8dHRLxeMF|?BT~CsslAAdk zD}ZykU6GgNlN)SQva|Q%SBK6WZO|hZa4atKkPtuLko5Mf$jY~LwL$f%Ev>ZOt#6oX z4SWSPnF2{-N&1G0?<^P3@ZS3Iqqq-}Q!f>8Te^rwyIiLUFQ#2&yAC6u5Z|y!`Q?1e z(IOk;iuB5Sx#iMR`QmSQ!~uc4UmKo<gF4ic8cl&z2+VgdVRx2gh0rmwW}GThAPsR+ z6AYwyiu{m(I7Jsn(HGdORb)t44`i3h`64xoDn>hzr&y%oLB%qb;xG}Be}R~{t2vpf zKAqCbEv~*KAT2N4`i!f$jBC}JREIiCe-t1!uRECzYCdJ>{1}b2EvwzMtGzZnaUr$) z0=1XXwHJ)_#4`0DlX|dUJv65t9+PjpRFC*mk78<|l4+nZX`u6Kp#M@&)^*juywbq> zrvc5>$RX3nWzxvw*LdB2E6~*_w9+U%*6@R|>9$Ohs7aH!U(<iBe_c(oD^2(QG+~*V zuQOAMCe080npJX|)w-HBR+_c`G;3Ei-I8h1GifpKYcb4eG45(HU1@pxr^Sq^)uQSa zgGsBEU#m?{t6f*C!%C~uSlDx>HaD3zk1-49>)wZ)Hs7u`|CP2tvSd%D_F$RzP?Pp> zzxK$S_UNwmSbKq2f7%n7I+A5NQcXH=EA5#%9obzSxhoy{e>(6?orN-;#U`Dlex2nx zot0gk)hnH~g6`=|U5zqb%_d!~F%5M&U39-{x>ve-{&W$Ty8C3h2TbmD5BhZv=X8&D zb&s!fPyXqiVtVsI=FP0hn|Z%Ci#czWyWXs>y!rU&%{o)hrcBS4Nzaa7&t6W?L08XP zCKLd$pMyv(0RRvJ04Q*mn4K7aUI9e^Bjw%@D765Wp<_XR1d3BFSEZrwT@3vlyVc=_ zqM-z|LNv4L?X5czOTeXSW^wUY2Il!_u4+^1M2@8Uy{%(RKlTP7d0dSn3L(vxP7!!A z+FUVHrd?#W)v>byuK2&CT*HPzdxU9+gar+nwa8tx{71^4N7Ibu&=F0<U!uh_Hx56( zp(S3JlWD8p=#Qip)M~$heNr4JXn013=fgE6i_AV5?`Yb6kGEx{==52C+MOYoLFa8= zPfDgJXbRQrYW=#>PT6xWrqj$h=#7rVq-J;f_s_#Ag3l(qJ7y3x%-T3%mQK%o0B>Ce z;5)s77G;2|%zHfwp1c2%^21|*IOu2t>3{3(U!oxB9^2yES3Up!9Fp>_<5<M-KoFFt zd_9<4d~ZDj^?+|9l*Z1}ER5c&ydVs2>OB>JCI-;BA7S)`ay-%H9MJ-$P@QOAC%(_I zco70NB1Q`PIbL>?uFss=f9i9hB9GN`V&WHs8L)=<{#MHWNLkN-pBu(B_hLKU)N6k` z!z`SiCq*e8MjcOFgH6qHXf-M&R-qd(Fkx-C-ObbO&9Y3CdpEZNBgso7#uLNTYzly4 z07v0&FuSMk?KFTb2Jx6x5CPSgRnv$E9(`qubE*}JV2&+zASIp=Ujkb#voy7IyHf0P zMt$F+2IQ$`%PYGrGJ#UNBReKI;9)GN%WR32hq6m@OeOT`j%q48oCuiZ5<4EuI}gea z*fc}u805h@XN_P=-Sx`i^6vTXiNf;+(fcpfgC96FP{H06YctCNWcTJ|0fMR=jMiBZ zjG4lTK_pgZbx7s}we#3y*U1>_^+?D7J4qFhhvZWdx+Ewcm5BafBef~Z@$Z)P3Xk;< z)oF=}pC{OM+~(sVuJBUikjqb$CLJAY5GXTkHc*r|WX5(Rj_ZQ3Sg~(<g!F;ECv%4H z>BZcBU_;2c02JUMf6|g6EWW3A*~2W-CF^76I!gpHo8)O*p5s*({&w|7=aZo_=uGj@ zOZ220GT<T};!CCH?G$Q!EVpub5P+KXgrKov-VjpT*Fl1_HhW}o|9(%?z8U(p>Bu2f z_o7&a)~`l~*k$fBt66>raIn7Cx((@Yz_j;~IBS0&xUniB-*=16zju)BuS{1})5lI< z3!Rb6)hz3$6Ko8IdF%SJ-yH&q7kMB|a%|1tdj7y&UrTx1S!{}`PvxJ@Y$g5rHu37> z&cs#YcH-sD0U}aKwvx&WW{Bi*5NeiE9tDtLKsZt`lpu4MgmCZXd_vB_KtiihOd^5~ zAUijLa~8_KPAgZ!2tixV6#5xkF+@a>q%?}h3H%@|qBt>|=qm8V^+}-)`_I1FZd5Qo zCnIGPvC*bnwD$ndZAw5@aWf#BPbtLG^(h}0d%l(@D(&t-EJE(H^5#ILc&iAzQ*2R* zmUkr>gr(lmhHz9<;=tWSBnl3nVg19Eay)pV2b?PGyOJs)LT>SPAb^u%NrhoKGC3)< zn2EAcwdj{nvPH2DJ#8?LXjXJAOk`VL4@N1~>6QZQO$ky@6&P<0>w3*9-nT*FTvyRR zmze^a^}bpV$~`4qs8qyyUq#C8Ll#)Il<ARYpIxJCYQcD^sl&*Glkaf61E2ib=u`|4 ziDpqz(`U}eQc)6^i5+(!6K_#{-{(D(Lo7v00w-JnBpz56IrO{xR)mLPgxehW>N0sh z&yjHH*$3sFIzq0+fXu-LTi2poMdALWPpw-4x@BHLSxr;#-R(khNi0MWg(FhbV~3sC zs91Nl6Kgj_O5Db2eJjEVBZ>i-D3;hnWu`FvgbX+ypqRu()1N&;v?hka0j^*WT`^6w zWWQ?M^}2O>A-U$UB4pJJjMiYMrZEHVz~zJLr3zpYdzGd&*5DwUU+hElk#G&7P{6~C zp<(qMIfAOSgORQ{3kAhMEuzr?7SxZ~$NI_<X-orT{s5M^#dUFVFa`iz78FrLq`)xx z1}S@v^<(=t!_vi2EQ!NCvOWNQm1t3u%r|UoG`8Yh&=^~KP~*a{G#h>C)jq6Q>y{yt z{P}i#$JCpVum|){mgxy4a{*+YO)}K4dj`s2<aJg<f**glwehUny`@;~OU->xsoYSn zu6XN9s<7`ujA3&{VA$xVzZY$9fq!*45{-4DnV0MwndO#9p|n5Z)=xQ}V>BzqJ|59= zbxTv&`9rA8%JtgOM`5=jB)Xpx)4VKLL#dFUqje)T-HWNWtzvHZJWQVVF1{6L6YD7T zoN4W>;J%lugr95$Gg(KD_^DO0{=QkL*-JEu_m2pEd0<LQr03`+LObYUMxZX;a-8(1 z|0T6KDA84sYZMtUTWtk2FI`QXFCApgP@BV6IyeN{oAT2XkU?1X_lSyK3a`W@9-&?y zeFCw3Jtj<1B6~VMUbL9^@1C0a@`u#gzWf`7$XA#fl*FnS{Bv|j$O%^D8PH!^(3ha! zbumZuAp)yCmaEr)G0(J*^9F#BAac3|f`K-~kYEq+9WAu+E7WH=QqrMvmZqL+*A;0x zo}95`t;_9O3N-f|{baB+|61FVejWlP=Bs;JZJi4fM_yfj){f&P+?TX(`mC&Ae)Y8V z{GRxBdt~F&UxZ|fvo;AMG*{O>v%mMo<Z-yn<%Yz_%>iDm@6juzBtD3?cM_A|<NYo_ zPw1FZV6}cE=Ui^_T|Mj=eLVRiz3Xxtb4|+DT0gz-1XE^8YA{2CBeInxc8S@;Oh8FX z(tAP3yT7IEnWmvZ7!K-8l|$@&y?dJ_9S}{g@*yqI@PT3<+M-<Av^D^BZ!hReH)(+Y z`~zv&*ft_?_;6`j>roSnB@1*!i5@`1jXX$ap_HJdzxAG-?)uaw+E7jnc2vc4CDcol z3Jt-_v;Tc6J%9s=1KQDA)xAd~st$a?wNV4X_XNXSItNH~ea0RQBP}1QsRQ^ZEocC` zjCc5JM<2BQ#S?Vc&0)4v0C&6F998oyk{YxbZZ|>%oO=b>fGPd+a2pgk(2FAqD$)0m zL1Y4ypsOv?0+a-_cz0bw<)q|2ryw7D#g{A@`FKp?5*Zgv-t4U-T|ufYuuhA=A-ZPG zL;?jSi2-~o_y;e_LK#&u2LjNbBb*PhIS4o=zJ-5vhe|YW{Z&2|PHMxn?DeuL5&6>$ z^#u=CCXhZg1ACGNY8*p}H%Ljo2db0=F;Izi-3T7;1@ERqNqb?9^)E@1piwSfzAj)< zLsUsv$QQ8pE(F+u0D1)XXP>>a7M(4JAOQgI5KC%j1_h?vy)iEbtVxW#T|%ea3-wU} zQ{m38$o%whGJPL1NmK*|rHi)#P=2PaAs#k{a}p>Y>d3!dkPu0fK_by}0QTj|I`Y!X zDTWv_=LXq<MEx;<JZ^)8AB#D;-pQnoE|iQeHjFOyjxNuPu56F4UW~3ii>{}SX_Sm{ zHz#XuciMM}>1>bbUX1BEi@7G{KFQbt!`MOZ*x}6B(e~K!#n{QS*eUwB50Y`ShH>-W zasQEWdz?im#AP^cJPZ;BiQh7e-|>#$Go-wJir-(1uk<GO5xY^d9)Dt(aO$0KmYHzu z<$kef6gTDf*V|C@Mk2`QKT?KfCBi!r$(N$n<`Yp2NmQ!r7`!BP1r5?C32vDLU=kQB zuq8YwhVvxFJ8r`dlKHZd1v-+2mXd`T*uxSdZ;c4X;-D20DUw%NDbgJ&vi~DxEJLci zR4Vl}nPL?01D{m2j#Q1MRIT$=ZCmGN6j=i*O+h}*AS=zdBh7Rv?df@%8AG~-RJx^6 zx|L75O;);HM>>%Y(&0RPWu7RP^gmMe;-_u)${_0V_8nm@)lLhjV6DNyOQ+yJ4ar(i znb94Y;|5N#=b4ENS;<masYY4pK3SPrS=k*~xl393OLQznq`(yU>m`O+Gy>XSQesO_ z(vgj4ry#!GB0!@)0YK$`w)+MJsFz{_o87+8Fo?-+J<o9$xk;*nXa|7hb@G98x>*cr zvfhBaiDDv(ete01+$b;FHD{Us#?n&WIz#^El~lgs62&@>X$P0JZkB&T1Oea?N4AI^ zEMm)u>I0hWQz8|Bf6bCab+kmo@*GumOmW5F!1&u~X9~sGi?BhXPDW@tB%Q!zPVPpi zV;6W|q6O{u*W}dj6by>AlKKEu;DsW8Zw3L55mVv?$ESG4?_`D|g&;X(5d@%wXGy40 zZQ&6hIq=C81-k(Co*Aka0QPN*q$=}1yA%_Pye4IbgYFdHVSf$zPJV3knuPND!>@%$ zi`09sSr)OsUh)*~xN79Kg?_DJM=dK*w0~Smxh(e}y2SW<DY0wOArA3Et?bDLnIixk znjut2%M61GN#tH1)R%gBCHG%t!mm@yp>SFsZIm2ig_diPpn1iUhO+EzT9@StJY!{{ zbY-z|WvOpvd3I%GXJz$rW$i^}J!4g)bXBu)Rn1~{E1X(3v#NW!s^_ALz*yb4oElf} zdjYvctW!ks(!KrQx`iyX|9~<+k;0NamxPGCmbQkLGNA{R5K~e^=~_yXRI?sU>ElU$ z&C3jw2?uJF<Mrf2fZ^tHEoE=*9BuN6F=a@-{rPg;zl%CR9j!_KKT@`*XZERwch!sa z7LwbeIHv5cdHMe(<(vk_u7*3mYM684sbWmK5>siE8z<$6D#cB^v{8ih28xJk+r>sU z6W7*uX2{iOX6yAD5T;2+=KqhBS2!^)P4r(fRjXpf{xs{V*L6fRbe=a9p(#=@IZP(x zcVfse*_nWL+Tk$FzoNdfwGqdUVub-sX7Es>dVNV$1BT3A236|P3K9g9xRN=Tpqk9; z#neNuBH&Ggco1bfatscdZUs;j9Ymymr!pe5$VT>C!M(6;d^<QN^Q9lkx+|b4yH>I{ z{$E68u|4%;nWiqa2CrkX8k2@bT>B%x`f8U>=9RDpldf(P>am6Y4=Mi#%7&F~OkE@# zfDL0z*FBS@Vf(oEWetWZ4ZevUp4t!?1X%Ekf?UbOzkmE@iWilzSnJMfeB}0KPTd*) zMR-L9wPoK!;`&&OJ)#`mGsh7H_q#nu)^lS2mh?*$NXPk}3iYI4B^*K^>3uu%hk#=4 zrIPKXG3~uxFs0A!W$f-{UhQSQ>_s#8aWLPI7-<O9hK3$DaCbMneF+oPXpm5O1+071 z<^+R!U(u2EB$$EhCHmO}DV9$?!DMe2z%UXbXqGa{w;qgrS#Ny<8Uz3%$|(JutR5fw zc3=4Y7)X+JLm(gOmTaHVezS>ris3=}l1Nh+mI%f(=yW;g!aU?AJLF+H<mEr)ojc^) zJ><VS6xhu^FxdQxJil3HIE)<%j5KJ+*bFa4*2P{9Ckn+C(T${<j->mKWaf@!caP+* zj^tmC;F(7YWk)6D28(60HU?QnTN{jA^2;tqiTLdscbeRxW3B#U?YU!}-DBO=F*E6e zH{+R6-3=)+W4-?4!@1+5-Q(k{<CCWJvC$3j-3`Ix4H(q$``q-N3K&Um#F9paL=&=R zuwn4fg^1|?>nF4TM&Jt(>HqZ;XGDaE|NMlhHwuXOpPzub;{SjBL}T$t3g4qj(~-uK zu?!}O;s5-EW;UD3-s(tG*~5G~NdmK4bNO_U%K!WX|6n%Yq*in8LINS<(zW^DOMVSs zuz`o#|9#0<PcAfxW@YsyT(s0a;h@9RudU3Je0qx`A$xk!iWz8s+>~#ayQ%njD4tWn z%0D<X3=Uw(SpJWnP<STlKrb@?uKZDzRvdBIa~hX*lu^@%y1kWl_b(qET`Rw3QQib> zx;rJm3@TRYhqTyE^p`u5y46o~b^iLYnDXx<A~$4irZ(=zm2+G-V>CJK6xka3hY$1y z1AH*8N2=@ZpR=FtTu&C8Exr#H;Pu_+ni~co@8@plf`z9@K0%nY%RYtD7}&793JXx~ zgKZEEXJ7wo5=Go{6pdi;fZK6V1FV*)zPl%hsMlel^EO4+^gXnF`u(1Z1rf0&IAVzK z*$-1y;l?7;yYl1SMcS-1p#X`5fi1VWl-AbkL@XFOl&DHCHLrX~L|B(0k~B|<eJl+E zNTAL9ySW0czfJUIy($=ecv0+XVmYEOb+Z1*ZEeaB7w?<-%d@B!Xp_QHfxJ`$Y29?= zdx{wezS81oO4Zo&q-TLFjD!m9>MXf5U!#MADpvC=fh33wd?DMuZKv`}Z9Jt&k_T&& zT`AdNu5Tr^#-xf(oSqi^OH=x?6m7o8(u<pq&HqZLV8@=)WK;}-6Dwn(ZYDf_apI$n zdWUIQwK-pFBWo34@@-$cX={d#I=?y5eT$}h2m4BxR{O#P+~=-7mZKpW*MTB}n4BnM zED|}wTy#~B2i<OOeIJ58!SxPvWjHjB__*Q{N8vAMY_B=nu(|;pIfdi-o#@hl#q?L} zyk{Yrm>y%Le3RtD%v<B3gAo0CGNTov7zDQgqe9yM)~8U&43^iQESRl$<CG@TZ|*Mv zk~v<)FnU7kiW3{UZ54=}m?k3i&_2YRfUeMhi~y+KYmGS0vF(8uTYl0;*eA`i&yf;{ z^Ub(~8n4An=W)VL?#s#Z9P;{`(klfC!WT*z&x&!xo-qW3WIO#GB_PC`3dpr-dUJ8q z-BjyE{O0%MDV6|v`{y{B@vZLxz?UHXJxlpD%a2Y$=f4MZPwJ+Bl;-qwVHdtl;)rN2 zn=}9w7iuizo3<HYXW|vxy)Wzbb)DZ=J}2m${dyQ3aQT4@f8s46{ZXtg5NwJ4Hpok? zN{<I1+7L40sp#7vJkiOY*MFT9?i2Y=h5TF@{zL8!fSCyZ1r*C@M+EW}Dgqcu)*;p^ z3Lmxi-SfZXK7eBqCrImDXz)WaSBq0Y5>L3o#WV`3APV=-eoeWvh=dWLrsSqzp+q1+ z0ZEL(1?dGr)X9tJ-xs#W(_eR>Sg<gPxOMWFf#UQ*IEGOGhtRHwc}8Ev`nx<;%F;59 zPDJS@R~scM6wRqZkbkgP5c3=w3S_Sraq+@ZZi9k2DX<^_UmwZ{4W(gZU&BVDK=(9= z0FT4rV$tb{AbJ8tYHW#+raU);<p7dvMDfPWLP(;dc{+i7M-?}XYnWJ1C20UFi-Jd= zz(bM1dcg-MdfcusjPh+R(F5VEBw>Uur%H3F<dAK$bGi-@1?Jst0HvyC6_k7IpvK@A zndHMNl7BY7`*gGX>V4qF&)4%wJXlAX$s|dU*Er^K`MWBBopcF+cv7x-y*?3x|6T~F z?5PPHjK=!X6rul?t0+WIM`bt5b5p>Og1*zlvd1ODar_$A0yEhkPD;f+ZB<o#KjeFb z7s+l_Km*ifjoduUggvcvGM1C^Pq%{RIx3W33rwZm{#B`NTW$c;#uXhXmm5-4>ExD4 zH)Q{+w$ZFIUKlm#bttHDsVSh_R9om={#EOL-beQ%lM>_KTW3b7GTR?m=w&>ukNoc? zpXn|}GQA<O<^%K1WHl*cI=~vEV0DLSY0_Ybyu2A|GXWUC&pws5mJGq_`7O^Imo?YM z-L!k5Zo+icP|(^wQR9^6y|Q+3+D70ubQbFi-vIyqKYn6N+3@!7j;T1|z%BIJL8l^O zvZdDR;b!<DToJKea^y8MMs+{=cQ*rNozfmQLTWq+0UUGsPscp{i70*pWI6|m?1F!N z_#JZ5qQV09=O*TS*M9ZanB|y6GiYz4m$5fQ?T`%kmJVu#rKbdm1Vdof5lHmMVHV(c z9ZXi-&+-o%CZW3;TfD(hJ#nlG5rGCxEe`T5g<vlU5ZE8dcdVzw(NQsG4C>8;3<V;| zNvo8mKMK-_r3RE}Tp_%_+lP3;Ks2O#<8t#Q`W3c5EJikwo+;}AS$Mr#=D1}FuzAIi z4T7amia_OO&nAK65cGjiq&k2@g#$P$z$H?KOCIHqQ7pV=4po41P)2#3upAR!2$Pr% zkQ4;pI6+06AqM&Y^v^73nysMB%$r|LK@Z?WIQja{Iae@&n}ZUjA<97w*eF)tYz!A` z?#0^ewbVyw9zOlqiwvX(CCKGMPk9Q-LVB8+SHFDxrn}IEXZ1{z?|$BF*2fWjz1u=Z zX>A<QMVXxl0(>2ljv9N(Z-s-nSBY>w?VN09lfPvTC!Al7bACGaijXPZKww-f;<N9P zFojNpKdWL#zKrzdSY>*89C#yrX^l9%MU&IA>D_yhB*k{3<F6Xth1A(sW)i>_A^b*N z5zAR^gbd&J%?@H5b>ej_VpIp=b7snVj2oI9V?V+3e%}2d=_}<idEM-0PG)%aMZm!I zn}7Rr+SKDJ2D%>b?P~K6UrC)`b=iNXO_hVzJ4z{wPr9z<`trvCIIf*qCm{3>RR+d~ zm$COKz03U5Iraqu!3?bBK*9<n4vJf{lRfkfrn#1(t1GHG7Dy9R`ZEQ#`E`gAx)AkQ zc!0mv^`uB4m|DM_n42}oS)b;T%*s%Kd44@ya+Rp7UNjgR3gB*3u{0I3Kv!0@%G&Sr zamLsv{?LzuJ*>_Vca;pdx6=UELIv(^o5}La_Cl3V=Fs&7zpGXEH$OCDP0{UO>~E2v zmqD^}=$9@nd8Bf$6hktRZ?>8b{qFk7oo&!0qA7m3_!?`I>b-O}#KLsz!PfO)Hx%?K znpEhq=^IaziWgSIBE|!4q6c)UjoR=$G|H6#z8Zv8qCw^;k46kd$vTYxckoadl-&m8 zmk0-r!OR6<Vxkws1<)8Q+yVd!v82|=klh8lb`Q#-^w10*sOQx4hl}=3_282Xaw%Sl zXJ$A^Ch4;&oHYuvIA>ueVR{P;n4|rfBr)zcUVaJ>Q6#`}F#(SVumu;y)Aj%M^sY%Z zmH>^Lg7THY1{a{O2q6H@ZHxEi4cBmz0;tFpAL;=<<WLl)jE80rpxFbV^wZ#tomYT1 zgp<zo^`h+`UT7KKJ@uIMSt4=(<EgtI=05er_SjDq0CWL=+j6#{-;{Cd5m||W?isM; zDgRf;F!^;-ViD3JG|B}<YIzI;u3d^tc+R?Y7D_dH3f3NOAH5E5lSCy;pvb_0#X2-^ z9juQ*y*i5^-td=*gmFs1u2m2526(6}>a`gO-Nvhb8KLJ9l<p|VqdhQXnY+U==@A}2 zFon=ZfgLcxPKm}p`TXfKW4ei;8{#ingPZ^}xEpWe-aJgW9sB_R5{{v!E|m3CCPz@9 zgrN0xRx1ya5?O91MIgmpnFa2*#t^f^hJGi1E^~^j59i*s*0rL1g+T>lP?_PBFLBrR zew2ZF5O*{rPduy)3VVjRZV)BS*7tKF_$^r_X%$5A>BKq?QhJs}Z_xSFVBvWL$cK9P z2!RZbi=F)KNSs8nw~$1V1iNEPDJqr1BY}F22}~+>%5t%97Z0Qpi98sBHXFR8HxG^0 zhIWagB3&Fb&jabqArGcfX~D007M|pJ!6n<$D%Yd!3E)Cos&9(vw&qboyYZ>El<lQ3 zp5G8X0I)=pMwr2Eais3`6bU$r-Q(nZ^nU}2z*KVKI&6Q}8!&Ur!ouTrVN3jEdG!H} z^>Oc2Gvlwy^7eLN6A{;6OFmZw>~JYR6Kj812CIGt4bX;$tlN#yr3K-j>J`?}^$|W8 z)N=s%_8Tk>1`JS+UkAaPv=9UwRt5ndVaavMT<nyMW9SVVZD}NUP}#+H%+nDEi!trz zF^lCezU;z$AloN1S&u+!jslOMDXcMJed%uY$FS>kx_zSC^|j3XPH;)0Pd{Dp{R{v1 z5k+YW_Wo^PO|@bT`1Q*hJn^Mld_-Xu4i<xgW#FNBEHu=N@(n-84+jlGf&K6hP5vm7 z?_i1t=56|ZQ2^{w8NBkC6k!x@t{u+!-N3h{fHx^UYb1iPASn*xW{wBh;r%{bWfg{~ zrj+6#H?1gj>mjdz2%JO!uFW}jxgs|k`3rC<ln%I_F}-T7C|9d2ldilF5BP-*_>c%b zHUL)|g0tR%DQtWK2+(3YnEkq&j{pt=+(_8Ls#wxk=&MmU@ZcE4X#jbF(?E^Fs5?n% zRh6xAvAWuZIL30o<#jC>h{4;*?q|{!IC<Pq%|s{AvF9cDy4~T=E7pdy@}o>qq&8T1 z7KW?|Lowrm82*1aI`e3#{x^<aW-;~|>sT9%eP6RTW8e2|A%tw%Nu?TQjIob3`@U1g znrvUjC|g2^k|Y&Up^{4ZIlpu6U-!Rz?mhSO`8?12dA+n)*Z12$?ze+OC=eaWX<8Y} zGzC;jfwofC?I`~&I{vj#{`Ir+w|1;-v_HqOb^<ugC(tll>s2x|EaK*;{qP#?dqDuy zW1rq<1EMeobv)I)6+6dZ9t6cl<ll+__XaXZPeM>A_(V}|C;)Zb06StDzW|VYlxa)7 zdrZD*_R@Ws>NBB1&E5(kjqmykX}B{y>BVsq{s!sn!260J^L9{g*q>eli@a6MBB|hB zl;*=&0g^IbULs>%!bipgUXrtRMHX*+(V5G4gn6*4qj7|}(T*_;)f!3$iBs4<0TJ2c zG*<xX?+uNjq$mKer!QgA`OqiFU?&XJ#~W<n4HDa+=l%d)sA4L<g(w$rbxH3*j|RW9 zXd0Hi{vjCg`Fpz5#~g18<fdug;;*t<)ACu~q*(@wg+IBAmzd5P`7d5Eq5_Aix`$r1 z4!u0RG^E(v`)xOOgV};Ur#HL*_Ka*U$?SSaAMEx@%3(U}`((=PIfg@7#u6N3$v$Hi zin%r-tr5V5;Ua?O*uJ6Qw2d<cC#X~a8o3WfqreW{kfbAq3PvD&>6T*(r1Pd*b6s`+ zC5|We66oi9^qLWmQtuS+Gv3+<Yd3)#ss^|J#D6Xt)0P{mG-7(ySSCL)C_gczu#@{b zgjPQ{WZKqir3>HI83rj=d_Eo&y%8lHT(blHPk$%nZeP(5DRt}U1_2j1@%Tna6~p9m z3c)*-Ji=Unf@i~_1WDGmCuzTw=q>i?odAd#3Qqat^7S#eEW$0y$-Uqr6-8GgdfIXa znR5pz0<8qvUv4vn!=a_{%r@NE-t=JB$Fc2Ch>8<)UXh{fkCXL#W7)hz3R*PzU%3nE zQ+uUT%^6d<Cr#36H7Bj(pZccnYKHlo+#prKrih_q384x5CH)^6V)p~Jt~1r5AO;wS zz7msT71#p9(gH-pq*fy*9+3n&E|ro#P9bbj(004&m&|}EoUoKSwe_d$tSC~U`%GqZ z?Ayttxz+H`!P{LPQ=Phf$+8b0mQB0MF%E_%yd%Q!Eq>RazPI5p01k23XK>^rmqP(_ zEx1=zRkj^t*$5cefV9=SkC_(E`4ygfo6yrhy)9iNx(acoFjSH=>rYS0-c9$~XCSIQ zXaYV%3PDUicJJ}fjkmTTR&Fh>mD0Yo4O+ckeAhfIf=tQ*XY7|!2Q(j`cB}6<Am-4F zltoKs9&gZm5ZN2yMTSaC2gY!f26+dF-@m3?cvT{YF~_bZ%c3~@Cu61E*u}NUFGamN zCzHZ-i^4Y+@zyJZ*ExjD#f;lSe?q4Svd_xaasy@Ij^&6C{psntO}wL5rc8YK5AIyD zgFJL)ti?ddBhXN7xE6)J&uk(nurNrA<D~TA(oU%<4qCY}eEaF(@HK?KAcyJa9PI6t zw9J)>^0kTAE5_x|ey`E;UqAS-eE9PgRa$WHY**QSbbswBVdyl*m!tPJfAy7z+}_`d zmfPh^%{5;M`!IAC_Tt=DtGXE;+D$f-Gp#a)M_JeS?N{t$)&zZ+nv^!cS!<vNYp|>} zdh8Hy<PfjOI1*9BYyX-TTb!<Y2le}gAf4}ec^88W{5K5n1n7O|@;3|GYKs&5W!F(T z^~agLs?9I{n}pbs^UDX{yt7<16yo@i#)Q$U2Mcc*=x-V6ZvhH$nvfZD1w#KC?YGct z1l#+<A*w-f2)bm6SNYZP^<Z16%LN6XzzBvQ@5nb0fVgtMkG3xSHldGaDbTV{IF+H? zo2i{8%j9qF`0F>k_FD<-9}U>H_^=yh6(23LhWHOA9ZvN*s8ZK=ALpSg!hn%g(7|hZ zW$*a8{F^w2C7uD0NU+~zFdiP_`VV1uZEP`!3A;9Aowa45&vED9?%gaVM;Umh0!NR{ zCuHKT<@#=`!b(yxLh9wcKIiv*)xk`!gN1%0eD&adSre~Vcf=4&7uR0Y4St%R9*fID zfP}ZZZ8q)$pFrzOn+jhZh9TZ(aV`IOw*ea;zJuVXK<t>-@XilNDQD4l?9sp7@te#O zw1+Mf4_9st=UA_@c@4)u`0_#F6I12>hQii;GJ^dL;+_5hBAi42&KIH4FP|%(Q`7J8 zKSI>bzUE1^3|{sTc<jad*7Ntjr+X}G#W;qW8!sA91)mL6Z1IY0Bt6(?wLM^e^Ns5= z7x%f1v}<2jvk<N82%H|A>jC1s4qWaZA{O_Rr{l1HU{qlb=Hv}A-Op&5d7k+FoyMEb zuh_ome*Jd;tc`==3JOOARvvBIa9pWG5ZK1y!fzeQYveN#j~_0*%Cww#e2wiWRSf&1 z)4c7r8`GKh&)1tZfRZAZ_>rIP6DK>6mwl9<eH0$fgH?oMvkzF_Y-s;8j}8CHIgF4S z3JEgbaqIPxK7ERp|8x?{ltKo7{mJx6AO3@XQTWj}f7@TY9Y>XkOr__3y%+wiBmaJW z=sR-sD=260+4ndBWxoe+9z44>bzzM$4O3rX*Z%G_eLu~5>&=&a&NoM)itv#)h>x}$ zg_RsTibrB^H~8kiJZt@4^m_V^COjSfK=a6o*FG4a!=QwKXt1zRk=<JZBCC)-0cpQ! zl*TRZMJuweHL(@aivwere3~8Tt&7$CnU*XH<vn|YxtRegKn3zL1Ia8o?yh&+VQq&j zK`mgn&61n6tCLJF7qkeDq0Bo0>1?9(cH32z_yo3HbF+x7(M<oR6~?8`pWS-{i|_22 zSv**C5T&c5wJyB(asr&G1Zl^sc7%>VK7BK0Kz=-3;9R%3(jm68N8)HrDq702mN~B% zGP2z=t_{Ifnv}c$2wq0MxmhBci=G_3arYvsk)xzZsK_kc1=qx@!`xL8}+nu_5j z)4342mrCNs4a}{eh+U=NC4vX!@Zg;%N?4bHvDc*1>+j7YUY}>>o;vS8uQ6U?9JGy= zeD}DgLXsy?ix@TOuR_n5(4+~WQ(}A6^~La$Dyj2|l+3&+J#*WU#umkp-7!5qf7PV> z+VFo-&+ki(1f(@LP-EyZn74v552`(;WR%2^0!c~+jFPzo#C-21v%!51nXiW8_xw7| zlOI^h=)d|cBQyRwFo|MHjpHKm@Nv6ShM>`h`~AsPqAF@%y7_534`|UUHd-G&RGRZ@ zo<CLOW@oZce(blq^B;0mn=&ULDH?IwsVwIHMVYFdZ-i=Dm|?<U;Y{o{+UMVQJN7!r z?4S$SYI3^>uq$$NABRKPs*NvshTEqMd$4rZs!V}p08wKY;=bGurz+7T@m|-A2E)`v znQwc_)&Icx1tv=489dbj0yLJ99y0g#lXMczqRKK;{Gms*P)(Ew?A$f0#>bDl-_Lc& zRKFPe;8%B1eL!ln2O)Bw9_3;6OuTO+IyPi^b-b|4YQ#YOrsk~Di`J0KgqgNEQC4x^ zE7hvAz(_`CApkJqZ55pB?LTq0jq^!Q-xKi^eJ);85)u~3o6nub_zWL*Et_3mLnE9` zD}!f(wX1i+_i7{itfSlO-%f3(^QUmXbg#0?50TYPtKXOaN^TvVt#ctHDWpfsU!&tR zGzjVLA~aRMPVDviBT~i@01I5AI&bR|^PyGm)X=|0!^g|-IL~9>*9Y>JvzM$@Pw`$L zeVw)Y#<tH|jgh)GWBQRCUgmAR{c_*{in%%|PH$4}<@<B)%kzcTCu-K`&(s55Lcilh zlw>SQ{T8yrpDDSw^tg#ELw3ijy=pEW{=jeD7QR2Mmi<Kymk1eQZ&zVq21Z5b`D&$s z2>Kg8!xdYenHJlUVsFZ3dtKcXsPUZqTYfe3!)`5C7s|l<4IjUO1qcT**@^(n-uyuq z!Nr<_5WEggE0ChKhV#!(-RW<vpEmHyd4K<U7dBa83^qd2Nzg6@^6>(M58Tg0>OukX zn1MDCo+FKp1Xc_TC=`7F9+@OHhPox(CCKj12J{-5G0M|t_&7x(iv;p&RV2%wpU4mm z1lZ?i&Xhsll|(M+nmrd>7#3S-CNl7GwA*zJ6>By+GbOGW?epkJo781L))q18<QA-` zmQ{EC#mzdd3CEXx6$uC>@stpg@wf+>j~AGn;T<r~`T$RXIu_s%HbU5Fk1hCAY49(e z?4(dv5HiLRQSq(GPiQNdZ@$jpJ7q#y-!Fwe6=g6d1vh6RkW2>AjVg~wU$1Q|H?>YI zH#J@Wx}yp>PjA$h(WfHXlu07;gXx!-MN5ncpB&VTIK(&&Gzq$J5r24qLH7t;Ln7K{ z+G$|`oLg(J-;obv+|p<d%t`cpfH_Fw!=H#r#YD==zqgtYxP6Z-$V7`^OsvBYwQO(k zPs=!)ivnt+tu}!*oXC*$dxNP}5(eym*w&T3Ui0y!xJ47Dr-lA~T!{ag>#aYAl3ZC1 z2jb{A5=HTn0P#8*#o>rDl&i7+NQ2?(&9mO>lE!BaHKqkyDy7z5ZZ(}BATEAS6E_Oc zxEJ%Z(|~r9SJ|e@W_-K{kR!f9yu#-C@e8?gCDBhx8EU$lH*4?UfEAkuYRV%6exmX$ zdb6iLcyfn20#xHJ=I_D~;%<GcY0llD%&H=t(}_}qh%oPum&H4ieR+D#6YY!)6lf$f zZ+cFk?=zMdkxH&w6xGSKkLE}=g^L<pP1vf$EWUiKKg`{B{@S9@(%8(`zriBRF=$|A za&|)qO<~41gy?OhSbM=Za{!#=@_wrNAenpk{saeT%i3P_`=ft#9$dUC8PmSbg9-(t z!QYIli*^^)Qic?a?r7!EI-E04e~{bRqSlQAlMrD=Pju_%*?_icFrY*)NW;PJKj!V6 z@8>gi2pTWZru{c@DJ(%XYC0XW*bjSKuXs^l2G8P%VkhnsiD<Zyk^xVYD@1(bRD?a= z>>Xkd7~urxrr^(#LS9KP3>EI>@Z>$1hFg;Fo`4YR-@8R!>SdA+THu{d-%-p*VG}$H zi{~8AsK&iy3H}bIpb208Po8*r%~3`lN<EM8$*v)j`*Wn?7V^o+TKel?`3dRWx$EHj z1~VCm`MP2euhozsZYq>2e>^~69c@6p^|5Efoa4<HlcE$|>V><aLn{YR@h?iufRqT+ zb)TsQ#Vb|G-nMa5dZfGcu5%`pmJ7{iEM@J1xiQ_X5dLZ=LB1O4L^X<t5U7}M_|KU9 z-0CcSvt;WMz2y0r&C4a*V`909Y2(548s*yrB@~u192h~QC`~?N+7UesvM1bZt!p-^ z7($#uP2O_dh`-dEK;E<dAlVk#CTKiO7Q8?!Z?z_gFFh?>DPaI^Z-W(uBhxP2LZj=q zX>xwp)aatc!s}WVKQ;OWCl+|)7=1KMMDOI7wg>P{!<=he@>)p|{yAB4vG&-onVg3o zIBVR-HHtR5$YlCAoutQNy@^b@9s(lrTaTo~MVGfKmbUM$H5j?KAo3LATsU*KA7;KJ z*DEYFU;Mg>oglBPTfIY^9RqwJ4njFG20YX%nwlMLWk#IE<X-Q@=;f)Y=cvCZv!A*~ z<XM&l)mpx~tE7*`)d;h5x3?RyVHAUxLSg4~+r#xIo`_K032mqR`+=zhN#`6ETQvjD z^l?}7fYDSxN)nn)goQI*z6)>ktYngBg39eXP89S+t^ed&NEg1z=>8~=Ezz+FVz3DL z=8C#=VZ!_N>8-Aq8usTKMq58JPVi1C(%oi6KT2xe1bd0nfPx$BPs_QoYKc7%PWHD7 z0ZAm?8X`1}d=dK(FEzwk_g`-n7Xit8z?k0QO}ZR)A!Q;d`V*!L&XKrH@T&sb_T3+! zV#^^jC!!!ueNdaGWH+<a6AJrBO2#8jSnzJ8Ot1!{M_&yH=O5qA5=vUa8w9u#S+_7h zG@<(gm`qYf-=*xmKA9AZq`+=HVWm2ov)J(x_RP+7dQpmj7L{g0VHN=6>W&F#6%Ri$ zgs>{CZNNs)S$`+$!Dm(GXLxF|>rjdrP1A?kZAN9QCV%4`YnS4$aUWy%A^fQY+Y~|H zF*6F(847{{=M}8qM$gn(HWis)@uw=8GVJ26K_ZQ$0D1(9!D1fC*eTaAe?;0Brid;a z62%T(fgKx?mJLWT14g9%d%Ou?fDFkI?XaC`alj-y;=n$d<9{#^I(nm%sBzAka`c)( zVjxXoYdkHG*yC!NF=uRQm}$C|Z#VrQ4R=8v+2-eAk{)5$ST$-__c$yS@?kpJaSc}Q zNEP!-k2xU+xIT%igGr;CNOSsA#eJvI%}<DSW9J;ixOHKYN)@*~U?x(7*iW?au~99S z)G#{0r-?v&l^Ny)qe=BndSl$=n9X#aEM9?mEMk&fjjqCBq!?n2nnjKuJ4d%sa>Rd` zQ%U9vPw=kvdDtmDg~@Gz5V&{YS<{$95yWQ$?B$*8)ICV776@%=AW4~4fG;F_PvGGe zeQWtfGZ-%q%Zm=BnQl`AO>72S2#`ubVJt)rz!oU|fdO?#3X7C7B=`RU%}}Iek|S*9 z7R)mcbFpOHYt6hX{z<Z?#iP*dXECJfp_aF%be>0a)!CCq`k#<s=BO3Zd2+I2Jb3cm zf1gN92odh~45*FZ^eIS?It?~e0O1C#VErDj6f07nE{s&hxh?m!U)N?U26iK#GfXyn zp|5&4_=1)W>8*KBic+x;!aP?ur2wyzM}0W_E5pro*uW6t99Y<bcyN2FHXW@UZA4m* zo}L5g9p>5e$ypG+ZIUBw*n*xsx0+r0WA$mK^gLhop_{d)BdN}!j5eQizy-7XJ<X;o zCvpR8fl3ZE8h&O50nF^vl_5R=#AYAre9Zs;QAOa5)(bb4_fCf2dBBLecHLFbVAu4y z7!tV0_&4)tjP^Oa9lwLDAOR?@TWC7#&Vx8%Rw&4gKP=&sAV+ehZt9sjkPv@Nm^6YF zxJ$S1Hk?Z3K9T=!YkXq0BRH3aayTk_zR=n~;7)pDF5kfN?B`j&XQPP$B$RXMakG+= z+sea|u7?%<_jdt)A2Tqr2cineQ+|Z_D@S{%%PUs@yuz;ssm(#0c%Xk#9#c<Z_Z)q- zi#I8PT6k;ey&{b2!0fB&?O7WC9D~DQ)5!7}cS<UBv;w<FHuli7^@NFJ!a^osA>PX= zumw~(%#U@6!~xTDt<o;SXUq&a8p95pdf2RC7e9}f>=XRr!H#5zH7Z%(j&$i7DZUEq zhJj9zk}W^A{0<WG&L_=oEj|mOzOP$OX>wd7IRkdiu_yM<U1=JO=lFa{^=eC+_{P&) zR-;Wd4$UZt#a#dRLgx9vw1JfhXIDl_8H9*+oFKOmHePful4}3Bkfi4DWM=?AMX+8j ziOo$ckkN31g?{eU2qAfEtNU@e_@4}YCNUWgCHWnLWpzlo0(~xIbw4RJ?;*AJ{)#&b za(<3#5BKJA>ULTMZiMmG9}&xh_~i^^n2Dy`zAJ3h&D!zv^f9P2(i3~vhhReiOHlCl zV@Q{(IWCQy{YqaVeQNIXoA*9fy!ToWH#AZtG^J$>3znMe^1r10h)Xl4$)P}d#DRp8 zX^7_3iW1U#6-=;2LL_idX-%+c;4|C7dajOSzZGa7-E!*OAc3R|lea!iw{xE1wl06_ z;j2}-L?G4wrcX#9k=1NtYtur!>BTW1ydWddmC+ea46Hg6oH}i8rwaPO32TZyhn}Eo zv!b!kt36N=&sV-dmkH%=zX#x#=bs;nh%sBku7Gg^{;<)ueySDJN+~&yisc{6{<UaQ z^2e*vvRrgaSK|lQQ910I)cW`1k(5A`em!j7lXTNzNw`n7smZzo-~OQ3)-QfOJP_g| z^yc<W(n>VxTY*`UKdg+^>#aZR8fAmoi@l{YE#j>P>)YAnB3B~PmfPrMPASvLv`Hf> znbQl#XG}CQgYw)-&YZJPL)uN<_ek_!?ye{OjO9?4xZ*6<c$#=)WswWEb(?hVu!9|{ zs~3II##?JoD*0#MBkR2RaMXMt!1a4I`SsJ`_92p1{W87rvZ_8w_{c}X2h7}@AGxze zf;FT;fODmFzy1t4;IPH5XVu(}a9@b?#zh|t@m6NW1e_w!Ts*l`IUS|ky|Mb!$Itl{ z+hzN%kRQFTt|;9wurQZ`*hn#~x|$DA^151U?Yki-I%{$j!!EtUusb7)I&V6yFAIgi zl)rG9-XUH3BK72uHxcHW+VmuyLpWvM3{diH-sI+|5iV+`9F?ULBAS|fARd~@egM%! zQw_VWJL}lW*bS3GThDP#x!W*DII|MHOhmlir9@mgO~JjxB$Gs8Gt^x069c(>by`wh z=C_1VuaTBcA85rs@X|KEiTOo7BFxiih*Wf$00B&nK4kRm9Bq7PkprjH(}<Y$v7Kqn zJ2J_xzCaTlKsu{65nh#~dEmj}q_kX0UWjVJp9u&ByhZ1;YJJft4Zc8G|IoQXH2na7 z_&LbF9JXlTMS#^rf78p$c`5`a@oh_4OX*r{Kqfy~<nIfV%ldN*KksNmAj5=Grl~PA z7)2gZAKGgxa=S$pwLjXCYT#8rKXl<X%mxY|*sdnd5gb;a7I5f&miKt23Ek0Dhb#v7 zKTxVLXApgVudC7HI3ndvXd-1}!ld}L9BN+)snvrB!<gDMi87=Ox;h()C%XhIRI(o# zS~Pv-k_D5rQdYaPf4CXc=|Qp!uHk;FUYEl(2{lD9Tlw|$^Yaa2*b3J=k77#;SF%|y zv?TEFHB$ODST3D6u#$L&`}aE}SSdj|S`8b>%!=Hk%U8^kC$3V!P#>w#v@7C*^&e8= zH5Ujr+ih;P<8A@(-=;)tm3hI!q(0e1hQCM(PwZ1(5EbZjwYaWQI~*ON#Y1Wa<No$a zZjBKpbOPEqNKO=WyUyg>Swek5<Vh`sm(6Cx6{?YLV9D*!V9j?E5(gaTL!z++v{2~+ zN11-Isx+%7pc!Up4O`VEou1w~m!+?N&kE$TP5Aiff(w9C-bh0I$6o54>^hPBrVQ#q znL%cClq{I16}@@&z?&4|Cwne3#qPW8J<hPt%LL%taWttrCj_-03g8ldrsn^B2QjPa z8Rj9m!BbJ^ET2Z?=stYuM`CcsK?0-1d$ma~1_ClRK8FRyB%>CSy$-rBvHU31zT> zfJE!NmE#;xr45K1PRlkhSr5R;z{Dfdl5KsH!;2Q<N0L97RsUVxe7^rV*?Za3l;rjC zM@gJB;%Dr#u3&W-DXO$F)`m0!rdM^@J>-<ORvH|NV{)}Cl9$PF_(!Ci5M5W!=)J=# zUYBCSVMllPqtAz&;v?RDPmPTAB1u$D4X}Nl|IlMY=05kG`IA36L7%~bL=2=rzGn5N zlh*=RBZ+n~QHscv%iqUyTE&~CVvd|siZ0~dSWkvcjyIpTEri|#;m#xJfsG^thUB)L z9{e@ewaLk2h3K~p@zIP2UU3oIf5p168U(X<Xp+j_49t8{PE)EtQLYc1eYybd`bNqi z*2;Dp?C7nZdkjiE6C#VHIqAZjaRPp@X-^azG^3*M{bcgdZ?>37!36~(uI{Z!a0br( zK{dJP-HL;EvW8uf9X#oxM?e!hS+4h`a>30@qzadSzD_gOh+g8oyReeWC(#{g0)K++ zRnspzUOc_kNT((#^cV!#j6jPFVSEsvkv*ftjs-&p_-Q6P9z!p!#GUZ_-HRQ#^V*(0 z=kKayQN?=NhBGC(D26cdHT~JK+C7s!I8;|RrN7Usa}9yyn@((W@f?9{^Hu+Ki~92M z&UreRJ^<yA3xs3%@d0ccGgR_Mt~mP@-L}93(Z?D5^1-4_=Fhtw^J`*dAV5KLUYmQ5 z3R0E_=MH$&X+Dv5SG&{)J=zV5Sb6OKM1w;<_`C1JT8n!s*LJ^4JJsV)SiT$ncq@1w z+#{hIeQ;I+1vNV5yY52)KKmD)KUNrVjSs0dk%!A?_L)REy6zZh)ejWEM)K!{o-S|2 zQ~U^wUS6|Xeyevw)bT;+uS0tyhIW-QRl8PaBJ(-zLDJR+%S=mp9EbDdoSZ}b;o-I9 zG;ymWrE5zDP~3AZkG>ezweh?ICGT`a1<+iAdJI0V*0DXTT)M^puQYqWQd0e*-Ym^S zF?^0w8n`c=SVH`{aSeFnDVjIFQ!0Onc0=KuW?STy55){@i2y+imBi@P=!Pxh-dZ(& zTW~;jWzeF-aRyX36ebl8)mKQY>r&G_CF*H&mXDSkm}TEYP^ZtU?sQuE0*f#Vj^(e* zTr{`xa}j%UKC`(P4F3&3rwq9y7@h|^0T%!WDF_}YHqk!V%*4b(@_uAg+WAvpCIBJd z&63Y7+gGOQpw_qITb9N1zRxO~{cjUOy_Jy>M}GcGYYW4`=HwT1EBHpBlchd^0sES6 z9}Re1L-X+XDaX9T=m8W^P5$d~X7Ns#n1oD|uF>>mV1>iddy-~mm-*Lcam6lXd9pT# zAgoqg#gbWDMJC2+@3}`$h&;hEBGkmO-s(=`_HG>0`H}!R>YDT*M%3zNw-9<l?vR_n zB7QL9%iLzHM{JE|c+H4YE&n%3uKF*o=~MSFmAch9;8=u=C9}~?@`I#4Ed{a^IL`-R z0Xl&Fw?=YB56E-OTuze5Z`ZJA#o>+g@!Q;KAJAm*eE-weQ+BGS#zE1mez%C6Hi?NZ zJ)+w=KC$?T0dgvKdH?7`;X+^$OC<w{GBbc=ak~j`0Dz7$Hub%P#h$u&hpF*zLQX6| zFuX2ZiPAlhDmSs6q=4=GFtIiz$4pWjO8OTRUZv%7y^8WW#_;Eo>Cp@f`<JKg2_}~7 zwq3r3A}g*7jJ4!4PP`f;k8KDwG?%XnEW3d<j2YEXSXtv`wNCr>Gp-CY&N?yxbj$rQ zQ8d&jU*~yW;XO-rw+R&ixT3hv8G`ImuBJ;4>|t|4jD%_b@fLX9Y|8ISQ&{JZVdk|s zQ6bAdLW!|z3~Zf;M@Ezg<{N)~d<(6qCZHLO9r!5ocj@#3!)0!42FH&+`w32hwHxbQ z?q=s@XpNS|N)1<~z=SMSoe?mi1NxfA&+l<&f1|_jp6|~o6F$^_nFAMFCfS?>Xz&eM z%ie*O@w{dFsF;MxLQOq4dyaHyPBHo%%=QxYp=~KG%1)G5+MZxCoWp{wPrU{x*|ga- z<RE5eb%zJ|uxAmvgw?Of<(r1A%u!=0=r&Pi&`5!T1ICxnR=TceTtgF~0O%&7V%11W zglf)EG>C6vE>%9EM!(7|M<ka2Eu}k<TpWwA$9=0APCG)^d7@LGt8WdVP0b^pzeerw z!DKdJ2KbD_)Je^hUq^;zv_5$)UN_#3ZBz7VL+F8acE&2VNKl<p+Pn_Le%WL;5YD>e zAXZ&RP;3Hl7YNlT4_6yGuLEV)enw?rJ3C56H2(>zQ(7`V<0;X}^0j)D`hV1W%%{#) z^4#GlAGw#v0u8c?upcw@#>-@+0X~*vD-Z1UT-G25B%4r!%9}`T2|Zu}67U?)kBLvR zo~MWMLkh2Tlz*<Fw$>BIyxy;s#^_Hy+eSXfd~%D+WIG5hUv^;ei&ps-xAM#;{+;o> z=7gdLmVEIuHRcWcF{HAOnO~j(c_ur=dNWRIkF%Kxyx-PDe3#A1>ef}(J4;?}^7+wK zMMCVQu`+cz*3L_n9%)eVcx6_{{8L|^XhE|(D-Fy+`B#u11s>bosu6rI*wc>j@ysq^ zx`4T;Zr3N<mgGA%or&uaxzYjmJ-7L+B&pd+GRIclJ86ywOTGAOXI$tDz`}36*mOtl zvr<;Id-WV+9OcU6Z16yShJJmm;F61zSgUv<A6hq4eqsxn`}mEgI?+ga+#@V0&9=%n zOEJe>Zm~Npyo!xC7(S+wQk_0j!qd}yQ9k|}<ki7&E8nc9;?3sjbzOfWfiFv>>Zs;d ziCb~QIg<nj-LY5o8+oX?=@;y`c?{7OZ~Mb3X3~SB%r>xEuC|S$1TSi-7nvQ|HDbIA zY$W?`&?D=Ae7QR^;C_&MkMH!Urt-~sX55d?d#G-4*m-CT>scpz*si+ec63=zB_BaG zeqz_8@Plp#boMS^DgnFjobf(i9alpQM6!VnIAPlo2fW8uQ6dk#wvw1Lf-Xg6_4j{G zTXCM2>PUTBy7{fM2qoG5IGw@a9e+4lT60;sVpWt8_|5`6F0aO(Fl?nseR`<){W6Z3 z!_d0!D(AVR=`%-Rx*z%qDz@xhnuTd<<$98chu4hnzu*2#^uXY(mTJlK!2pf+7yJ*1 z-=^1f$l+6uX7g_NRYZFh>p%1t;Z$K#X1~ZF#$I<hd2XhX4#j8{=*JUsNR>adBl9HI zco0QM_b$4?>qHAsl#EmP&`ZQk^{(TkGtYYe>*>tc7bQ{(gZE7)M8ZAaJrcVmY$ld_ zo2y-7?*#*+0=7iyK6ct}KB3|eBm9@lSzy5DRYm*h6zlI1IxDa~qQqT+CHpRl@}~L- zML|2=ufJ|i+Y0M><Wv47wkzTFomXZj5w{V7dHD554TqTTdgSU~iWT64U1O<nvV<BP zqn;YaD05?Zl~BD?+dfgL1`g37`8tgO<1(A`%;g(YHt?@xg(J?Yhi;2C(4ZF8HiV)J z2=#tB@W%AODC?s?pWi=hm`M!QU(k7VB3iu7*M6>s!33dG4=SD`r_PX1>Af>e_)Fqg z?&LVseKeBpXzMzC5$WyRRxR`y`M7D*Jws3Ps>#60q!jZFxc0^Q9*DWlAQMN3=9u1> z=%24Xj~+a%g9mzjZ3s6B9Y91C8Gfa2xp8}E>3S3RpNO~Gjv@7%rX|l-5D0M`#!gQu z;(v%Jo&(RSQ*&+OeT9D&okeu*8a-yHJg3Du6PB5^VV9izKjnVLuD>`+8gW0`jl1z0 zQUyRaM8|Cpg&^z5O5FbI!~4eHj7^^7lJ$J(Mp%uESZIJWsTRPzMbJ8av9#X?W2FQW z{MckDN%9GXMVK+<S;)9=Lutl9X2(DQ{zO=p4z*Em1qlv0K>b6|Ue1@43K9D0Fd3{U z4k#*d;?!32si3_SiY(|2GBG~JKIY4}2h-#9glG|vQrxzSiBh>Kro_I^V1)%7S1w{l zc%89DRUtja1U_@8Syptrma`gB&^|LiD(GYu49(tlD{XK+FqSkPC%7)~aL@|s5J!BB zLUY&!ZtzcKqaL_%bO${aNe5(L``Z>2PLed@=>Q6Tg$pDyUa>M`Zcn)<6ii#=Hln~u z91U=>C13ejTOKS2imhfA?OVXYYoxhpoUkEEBcq)}?BiJh8l7Apy}}-L7nvehL{-`_ zP(G8Ddb>2rKT#sl18Ye_f-CBDIAuRtDr+^C^4er>wQAq|^=F^2t2MgxBbs}sHM1~L z#SgXi=x65sMlAl+pFuRxkF&W@dIKLq3g4I{I7ym+3A1rduKR3}pmDAllszieRxvtH z<JY8=njD%x1pxUhyzWb1J)S(hU9k>LBM3c?w~(Q8ZdCAC5MVJ7iCMTHv1U?~)(rQ< zZc(xNv<$&9m8xY-Q{uhIO|TyAmE8Nb&zDUoS5V!r<a)$%zP~-m_tVQY)ca>)!2#xy zf$1BV%C>BY@X&Yyu$IA$*2`!teD*>xHN|O@dd=#ID@_EzD8#R%_&--df)v&SqLqwH z{L$L_G|6~38M9LC$ywOmB1h27JZ@1l!r#R!z`tbdYgwIzP5OUArv#;H1QEb2>ayfw zF3%b#tB5+;1(zEBE(lg1yRt&Z>y-G3o0d%i0WsLdzofo{$+c=j)8w(WWc(Xsqek~x zc-u?E$^YU5J3WU0mj#y?--g&JfjD}M>r|;$V8GQok|qH8$___6V}Si}-PxdrU5%x$ z-PoUes`7X0<)>Fkw_gnSy~507r9zn0mGC!vgf!Lgf2!%l0u97sl9W$UB9Mk!H6R`E z7$)9Ln}*amOf};HUv(zL@;AmfOT^s?j0=`LFkdoG5RW%WiNAwQCIoEkulO&bSa-#- zR#c(;?4d0@N^>QS6`p$t!mWTY4YZ*iOSA3>NSAAeTypw`TtR;(3KH3);~OzhMuIf! z@Y+R&{<&K^JQE5gA2CfJ5^*O**qo?ObFFBykJ)etO>}iV_wReg4Gv>VDKUn>ehhQ~ z-`O%?BnT7Yj%Nj_#*|#qO_?0`QbmHa<#IHuK-zVn+8VsJZi}{+jJBqs`lf*{%}{T~ zP;UZsZjLUYfd{bKE%4oWv*!EPsUeO7tTRHpv{+V@6nH)E>aZ1ei32n^fJQiRf4<@< zs!y}rWmXBGm3e{f;^5ZXJGL7W_ZW?%bU`S=L@8HLdHxz^`<#|GNIQN^nq;V%|L)bO z5KvWmr3IuyNz|l(wCz9&EQV*#-*`xso;yvHY${YIw`kXmX&Omr#s_k8&~(%!+lV`D zJaRyM<8`l;)b(AHEddiFQF~2xfYS6HyiV~2-}EKO4=(j)zT1r#(26qD2sBKc&$=<1 zu6iP=jsxlDgH*_d=gZ*9oojtwb%{8`1FVcr6J8x@s9QEhE*#UC80ANu$yh<dEn~^T z1Vtk$oo&`pp0?42U4O!R6FIptdf_=;Fpa~wotRv}Wi-E&5lQFgv|<p#^919Rm-*ZD zNv``VK9GIxi!<2R<YA@qF}*g;P$z#(!4IU_z4B<BAJD~j3WsJSg0v$*+H+zDZqhnr zyfO)YK2%0G6fc}WRZ0Mz-#Bdz(0K3yVMI-OPqMhb!yoEDQ%Y1ho20cFmS%dPk}NJ= z5#hG+6<nu`AlSBCeJRQXE68{fx7Wh~Rz(`7u6}MAPuC#fHT(=4EI_&&2GP#jeQ_Wi zt2ucxot|*D&XH^m+E^Q-pyM~T6&$P=3PQuEcVUcrf?%%T4{gGGJF|+PhIdAHUi}y0 zZBLS1iK-q(vSsghV2|_Oa~nObm^AzjhH2I9D$@?KO4FKoU#W*{kjAtyiVAAsGgM#W zmFy~|+%I&PV*`a>!y%0tRDKv<lRT!gA#1+t`84y($?QI6q&>JP>~F8})&V<1z{N|> z4%j&btjEN>NGekQ)Tn1d1n}@G`23}~?I||CC`I{`Ef^-(F~*s|ek+p~+*<zfbESse z*m-}Dw%M3iMv@$IY`9lwfSXYpZgDObZ5~H4J8C_qGM^tY)DsL6q|mF747DkEt^9YG zCWWQPUtyA+qOvO3jSx1mNzhBbDg<FO)Z5-{?@9-P{W927g&?g<4l6RZ$9Xi<87t4N z3ZRY4QC}xhBcHMvy}Mbgawe~IGEm!)(+tF$9;F)3D9_~JkDc+)O1_H6Cv(TI&UWHS zo0OAT%8q^~jb<mJLfhQCXR?y#ZejJn3rvU4#bQ<x>ZY)?sV5QzYZWuf2_O+pLP^hI zYqbCXoYG@8sjAxt(xGEY@XH$UTQM>C6Qyd041B<HtyU9AM=(Ymz#zG#)tU@YGt~2S ztytM>A}QgjDebDyTUZUdhQY4tAizb)SmSF3KL48O_7=biCU8R{+j33jrm$__KGFG1 zrFA@d^x{=e+4*&<yq}@^V2G9(URupiyJ$?`MI6IBPT~hI(PQ4FVU<=uf~3)bDMP)D zM9GA)^T_X5mlzYvYofJb*gBBuCDSqvV>3>OW#)G!NJvVAiLx;561nPvvXQ)Ihq0B@ zD{q1w`JM7!W6#lc&v3SNYuT+|nKs;D?F^810$w<LT7@e%S|Qh;JSvqjsw$|a<8+GG z3~bRYGZ39HP}AHtVmGos*SRBc*d(J$m5Ft0A9quwZ73&$*^GEHx=TBs8}IWo`hw4l z&L(y8hFlK!2WQK-FN42U`b3YVc8rNgjbTpc+*E@#G{5FZ;H61pZHHc3pKVxFd$8mm zuC*Yoh#xvmAZ^lE4s=JnX}>Nm*0I#k^?IZB_NZtbR%`0I{eN*O9v817jos-n5p?fn z)h>tQql`7r;LDITcX03Q%hJj9{vf=%E?#VFRHrI&B_6GP9CPJUq$q4m#VS~1?~|C1 zyjx@6b@%W0O0KJGeia_WqgJSa(LYAh9%#vF=&U92>yD{5jn3|#5$56?RZj^^hYub1 z_OVjg>Q}+zY(|JuQ&!JpYp8YSk2p_N@DqNBbi3DiPa~5dma<>RoTNm4Fi300H8UBc z9Rt!HJRYDLs!UMN=Ref;1Btz7W!7pLrtY`MjKiK^Ic^!daoU};Y$!UDbbdRO91`&K znt>FT0&kI_I=nI={Q->qmmy6tSJk*u=-{rbao{jl5@ss@7AnuxDEzXK+(xWP%p<H7 zno(NPXKIxYjaR50Q`rmQm}QBrz22~FD86ry>C!L92Nob#z}jV)SNFGr2?Y&(Sl*ir zyUL;QW6ok~fFE86jOU;DR=0coy02QJ3$5#VzkNc#iJF$loI>;6QxQY7yK&o1Kdy_H zVAa^c7t?)fYp*K+qEczzb#13HTbEc;`dFPa=nWUR8#>i)r*;XGa6>F+^g^7d_n#*E zP-H$`e+Itb!>5E=9sj1Ys|kMH0{3Vev$0ki8|9ecY(GN9>m;`gy)a2bpU)V}`1^-r zcBY+t9sA}{PNAWS(b(C|f`BodCTxXZk{FA{J07EvPKaAxO8{p=&zPZT5mjqjLhyrs zU11Bk@+fnleL@j3$w?TLg-C>$zhI+vH0x652ZrZ-+&=v2<1rFL#yYT|<SiP_azUeC z?>89GcYJD4?DOW&#jleRQ6V2684em#`W6(Tx<ig`d_BFN<4)x)8`A-BVsnP-1VyFF zFjZc#YNek2cG)?(LI=A_4FMYBouFsHF9*W23^Y{B^zmI^Le$i^1sRd2@Cp9~v09?y zvWt2VMhch%@!d+mHjU~~wDzST%{IgFve&9XfLhy_wp5~cjGjyFb^FS=leC^)+2pl9 z>7RajZj`I>InOwv@_+YT1O558uK*d=iQP{}V`4z(BfR?}84yH}64^r|ZmDG)@1jur zFzEGSb88`+5TLmS5Lk-Y%FOa4ts5MR6|Owa-<il1e8hn<%?4J?+ZcB8&&TYpbWAsd zm1)&}m=ID=$qjOBw5>KN&@KqR*y@NV|6ZGNx>ME)3<E2N1)-~rcq<K+X7f79yt<iP zCTSP6QkO(&a?DYIz(ew$LGj+QJo@b@fsv@%RMasV31Y7?bdi_RPMx&zOuxq}X$B}8 z>fib>(K1!I>!;z#1gM9^?XFkfLfVTCIt~sdw>8Xq^w*eYuXF2{#UBi00CH2oQ6Vm^ z-Xm%1`hTS>$#|w@zd9b^dQN#+&2Ni)+NuG-p+!$a=8y*P<xxHF>eIi}U!tSx%k6hP zCbHg2v_9^P-_m-YAHBKyv?~Vat8ZQ|a*#&fvkLw!l%va;I-2Fq6x<shYzY;JoO4Ti zh|dsZP|I_!n;qx%Nk|)bZ_xQby1nHzNdYZyK&2O#^p&$@7brhu6MvYbHm%#xR6V6f zH9Gv%9AUx4SS{N@>y#)|<Dh7G5e|aNf(=Tx#G&bUWAx%27-NtH^pVT2OXa~zuQh0; zl*9--1POA}Wj2qa8Reb&Ovts$=nEv~Pv~=WIBJ~)St+JPq;{%KK99_mr3>7Y{xaB5 z6567d*SACLqB7wZ>ST;x+IGmDq8TKz7IRodr#BK)cteMGNS$Qg-On=6S86-O*XPJg zY)t2F!f1ZES|7_I)l_y-m<wHtufm%T+2nIdu2^JscAkys<(0YmGDehAYabgM8_c53 zHPoB)-|DM}nM+u=u*<l#pK8MZ_b!&0`bu09%qYIjJV1a$oqosp{CwS{bc_N41l$Z; z6|(`HjgO?&mP8~+JQQ{OOTpJwpLlZ{yWhV6aCLF4myh}{u6?xH%(>dK<*!g@Y<IR! z+PvlGZ@Ft*W3r2@7d>t*{bSg-jJegt{UU8CXS*!;nFylhg?<R9I+MNo{VwtbrdB-` ztu{GI-ri}bt#>j=sr5WpsL3CR+GH*NxBT3#A(HDR%hg5^MN9ej-As(x+FoV!0E(_k zEvg~G#2uZWZrmIMSp7OdH`O-0oNHr$tYU|81V4C~wV<W57q2ACARI=Yz$yW&oKiyD zZ%e0&H|!}%3zROLdi9B?h|4sVMHex`aZ0mNa;vV~4xT5?a0td8NGRm}))@oFY?IX( za-$nxu&1^fGfxKV<ge^5)-5_p4%;hF^4m9OFBRoh?%P8|7{r$MLa%deoX{k$3cv$y zLI%4olCIrvzI1n`j=!;r7>>+ahhE~zjxHjoi3AnSdaLX6@uVWA_-K7|SGC@52Qu$y zr=EzqT*&uh0RDVp11!#uHBuDJnAMoU1vU9F(R3g0(q-wJ_2*wd&Ab+tJNZ-CNu;4E zP+Ty_3b#%t3g~VMdhXK$M#@BG3SL-JnZ$8WRM=2wOS&9%S-8E1r<VZMO{OP$0=S9R ziH|Z4{ikW1$(*B7COP5~rDPLdkZ7p)f#B%NO#)`J<Vs>>#*R{oA23(vjREt|DUC{1 z*=H#OD5UixKGe5(eZci&)b(Gr=4$81YOv#G!2V@28y|-;G*!<k((fY5ywKd{dA>z8 zqp53>!MYDZcoQY)-|xzu>E^FqV<s+d=$jfvQ{g*{T%lTgvJy9DBKv6X`%Xrtg<h(X zbu0r!882c07}rJTNA>cPTGq)9onc-H6FN~G*+Kg?E^m%M7=Ada!Oma7RU?w6<mfWv zUE2j`k(^gUb5-x8*~T2N`70VnDO7z9thcwf<jCd|GgffayycUIVU!t8W?Pc-PvFF# z)^N`Ul^F;h?n7s4#+4L;0?Wqe$eKpJHafZ>qxUON4R4dIM2sR)J(>6Y9F@W3fUZGP zMK&WXsQK<;zBZP1_t?3MtLCU7qw%0MM2d4h+WX+<0R`$W^{ru(Z0_fKGA6H32i4YV zZ(R;C(P%l)O?GN-3zz3|-+|zKI-hmLm$gQgMY^1cQ_Ptzn%i4Pm#iEWSYNHR*6q!C z6-66E!s!|<LND^vl@S7z5g?%CXGTfUmGc9&6Vs@L)dhYFt>lR2K*I&o&cX2h*Q+)h zL$NP6>w0BiH1^iv@rUO9lTyfUAtt_-=Z}M%eBkEqx^w4cL%f}_{(??Uz6+<7UpwA~ z?ZrR70?*Y^%<Oi5+GKLqqoC!g1ZBX#S>cga%j@F)XXxC{#%KDbFASRFWNiHIr@vHl zs(qk2EPD`Q8W8;^exIJ>5SL>7OICNIA=6k&tEpf@nN2MdB$TBL(?oOTW#G(&-@~DR ziY&)9t3K-DBL!g-W}w)i{<izRk2O{<*F=idLzKrRugM<6k=G}^AU=J!-u!7s$IAGD zp0(5!U6h*#z3?H1te7y(78(^IL&w%>evF4lWPrL*{IA03=7?n6y9dMZ2J%Y)zlO`I zG>H-xc(+ijq_B`=98*$!tK>ssRR1;8peDwvXL5_*u`PT#*5jhTS<_CBWQ6+xHO(E9 z?e_f?3n-RBOJ$lZ5>Dc*C5vg(-d0HC@q*3qW9Oh2{?4ZFp9gcB7f#nezLconO~=d@ z{oN5&Yh9IosUR;s-q-8)Okh}`MNtRZ{q*L982_8&*k~PJrQ%eyoy}y)9UjlE%C<-@ zuRa5T7HrUH=pO}5IX2{D(XeN}AJN-H-j=VMEEg|~zg9|8&B$O1QCujt+`rxa@{mQ; z2UpX)PdbCfFz1(45dzq{-}%B+p8f3GmjGND)B+OOsDXGTYmPuwX*TY8AJ>$C`T4$( zlK=9^#Y_60KO$h!zBU7d<(Nwy(^~n9@vcw-&ezw~$Oqw<&RsgKx2bl(ayjPuRK4Ys z*hmu3uVRT*)8YknJZ`A{$7SpIT9f~0XtU|PFTBnC2LXtIW9Nj1+Rn9-&W6%ACxwVV zY$UEa+>_yVKI!WL8e&HJ?Pkb(NSR-dR}zSERX}YaYA<OX%<Z~a8}*(%mnfGN_2%AW zdD$&{kFC}Rx)(j_$<tjg#T#@760G^Q)<;}aSed6@UYtmGT&xvd--pU2=;Y^DAAZT; zd*W?SLmWso5?qa6KVLG%1WVc4AGvE0=P{*C2%K)99uHc129Vg)W~BF%Kb?G4NVATt zQFyNuQ0--z=1>>n1ilng%fIfkx``DO^%0#2=dYpTIkx<J>O@p#0|7)I_J1RS{dBEN zh5}NS{2SH$Y;WlvJ>49ZA0R!Gg+<5=vM?|EJIMG4@{pzX#7%y`M`LVa*Fx!cLQ8<E zrXwb44ZDecMf42a8w^@F$_Je1BfLvz72)$^@7Xd?C-IveIN8J{hzLYXGv|+@2eTLq zeYFxEU;V-WK=)<R$kHE7+1q`2F%a>Z{b=97-|<S!l8i~cN)x2EVH{OO4g|n_LT4fb zW=FX~eb`!k*ivdjkSWT!NkYPJ**p_Z4QiZNlvDiXwT3r=Y&*0rL)0>ZBa&ig;9vZ2 zvVvy<ab=$Qn~Y|#DMt@fs6tX~#z)HQ3Wnyxf2u^sdGwT}oq<~|k;`|KCxVV=<bZS5 zN5ET}UD&kBdmfI>xTlnIO#14vhC*-Vz@ES7IiDgO2YBrQYbBx&So{%u9mwQQO!eEU zD6<frceY&j|ENq0x{JP{jS8q$vm-}22YpVMzycU7vg$Luvs%C6+3BHq_pv?tgEDIg z6=)QN0p1K@-d9JSG8j_NT?Qj$+t7EcP?a@9Ric({H08i#WkHzWcj6-zSpmV^^ET!x zn<6d?B7zN8Q%O^NNON{m2lmA$_pOpx4Qg%`8HhLgG6Vw>DJ1DY6?4FWX{_-}Oq6C+ zr<?^<;&+XngSen(?dct+CKh{%Gq(TfatiPoCu@HwYitmh#F(8%G&??&%bBdGLSN8q zmG>w0{H7{G@l!P_Xz^%SV_&7pBvT3|T6a&_ke)FOC;mBA`R#k8Mwfc#m}1@5PrDkv zDkBZLjbxyz*7X|NIO(`7Nw%C`j{O_D5XC6+k=-9{9wmY{FqUzRCKBh*#EeRvA}lt( z$iBqXxaZoGsN)1qah$3QMFGuZuU&kW$)iw_PjqGFnif&$Lxc0JEGd1e)3e46A39{n z&(Le{qjx1|7O13u^D>2RwV1~Ti;|G5(e*sl$TdU#L|gVkJDHIYdx8XWSWfhMeS_0; z;{^w%EB@Gr_xTo-(Wq|f>GH13i>qwIsuv8Ys*KOkdyxqei;Gzk4maN#K50apGd21= ziTRIBF@8>)RChjI5q-odLt6-n?>J}Nz2)^xe`UcmGS!G7EvH50;DL&a-GZ$BW_E73 z^iAAV68rRrdb6s{m_dJ}!6ve>+OBGGV?Ed6poz~cM)640(s<Lll?9`0Dock^YWCH= zA)#ySd*=1fDmLI4VHQ6cHx-Gt*jcP-OXM%Hl?ina)OdSk1`NbiYZbsSIh=OwqE?1A z7YylP@u+innw@P88`qMY_$Xa8lS6HgjU+eua3B38_+P%c>8;1o9{^J#S*8;(ET+FG zKYlT_)-m`8-Men-Q!X_ZEqV47I#*Wz`z>Lbk86bUxIJ*u!YM!G+G?CZq~~XEzD6Bw zmEo@S*@(`Yk1gBU6MpX)Cu@@K)aomDlOPkYaq0U~7mmwhUCE+`KCxlR^Bc)ltDDHf ze%quo@ZX}`&8EwZo0l2=r@!}@)l=PWP`s-ZiHC+hza|?GlYGjPyq<iN`-}2T+*dgM zA>)lQq3@DIRx{dex=BC4b&Eu{(5pl?pg9Wtewq7Uyy~0+lXqXfLzMQe^_BBomd@Y= z!f;T122A#2X<h79*73mNNf}(PX=FiQWHTmn6uG(7<zA@s=%RL05`$N+_TZw-;AeEh zm&L(lhkXan)AA&5Vqqw+#=$VBxOca7??!}d#ueVtwJ;}6=nh(#+XN>P{$p8#?q}4E z5B(W25!N*k#iH-})35xGp|cKastdsQ-59Wqx^zfvFj7Fe1RUKsx{+>?k`PcBwUGnq zkWN8IN{OQz0Z|c90V%OSQL#Qg{<{C(=eg(Jd(L^!`}-Aq*#NLC{K|$w%a{l3uGaT= z8o+ROJC)Ns@$Fm&=LiYYZrt3agh;-=T7;UV9p-Cc*tM~+b$TsN<(O$`n#XfY0H?}6 z2PyKU9#6H!w-hyOx9h`aPMI&oUF~9qizG^aVn#Y+_kQHSZ>E;_h?kNhXqrjI+Uiv` z95sTm#FscP));|rH%67?{(+zw-ulK%%$jHbop4n12wyXv*>DoG`BK8eT>=PmOB%~H zHb;pt_?|wx<5{F^hG%@i2{c4W=y$50*)*C~;v;lMZt-=i;4MmUc>GpZfJ$%b{PyJx zMT~y2IK5Q>QOITak%Y=4ajr*~<+efvxMGt+!`h###JxzZ?p5jaupXAjUBd)N`8c0_ z@q;N~Rt1R<M>qg%W|;@kF3Jx^<5e4-bz}AXbKubCp>Wm1^oz%ptV<FKkrG^-zE8OD zCHTye8cuA1Sy{1Ue^C~5i3;I)R&~wnJ-nq78$6YYE>2AHvr1y)h-*k8>5ZU-2O6(e z!w~=>?T=WM$j3g`lV^=7m>$vVTfP{@1yl)1PMBqfFJUG+B;znXcl^~F7F@IKRs7uZ zza5YqeigTAU!#@3<*ll={1S0iO2J@MF<w}VPoacQS5ZA)53(vgH&593dC_r8dhX-x z4CSm`)d~v_!sSO7udo6`rrCN>MMxEmAC~4pOaN^`LfObgS}s7l_+3b0$~2y%6;CSB zPJJFzJ?zbxZi71q63<kXT*Y5Y3)j3$Gx#?x(88m5@_df>Oq{J$WmPikWkL1zQ%%)y z8H3)UXHhyCI^haw16?I?*KOy*dc^r{ZtLJ1&G5xn1?wQldZJp6`b*3RG_*w9vZh2l ztWVNsO=6Qv!fW}md6YkHq%of7{2W4E<w$vkS}VFSR%A^aEEbpPp*naafiD(saFl2; zSG?+bt!qs@$X!)9I_}Kev6Z#2zGA!PDtm*)c4<;_Ni#ICw#G`3Q+UDwqt5fN5?X-X zCw@tK$f;JCkwksi+jez?;XhU9hHVRh@6I|k?K*glen$zUs(w)TL#cr~1HMsbQx>Ef zDrG$S$$NQv(9Slf6b*#=b7V^W2peG?)58NC{H%ol9X4gLSD_VKN8JuFB|`lTWi^Q4 zKYDAw=_6l~8%LNXyw44h@s)xJrWf-2c!ZBi`>q&tXFBxPt`4;QNi&w$SGfQTuB+tP zn?W{v%`Ricit`~@X}n!()rFy7(~M&jZZ~vaqsgN-JlTepX+pXEzDN1epGGrnPL(*$ zAj=MB^|34a@UvY9Omu?r(&g@gvd4OZcb=gCYiVt@fI3)g7g}g{R<8N4zA{Ro8ht9? zk=8#BvEvNV$_%&e3l;DA=A<9!j4{6}t_I}j7KxAilC~U}x({tl*)Vu-NBLzmkwTR* z={s3nV=-JTq1!i=sD?RO8-1i6c{6c*9yzB29eL%Q4cQ#?7E6OvjTGfbj*WI{@Jvs0 zb?8u!z1?ux<t>VKl2{YQq*rxKJVHDlfiw#)>IshO;m4WcyIJGq!-qL|c}czNlCX7Q z2;k{Cwor+G+PvM;w*3Uc`_PD+Ieg{z6_@^`b;-g(absu9*QJ1;&NtQ9X3c&rru@AB zQ{g3R%;DK@P*~gkimx>pl8`O5-&An$;8omGclj&3zEn*HVa$r258HC0%iLYBp>bOF zILBvKJ(e_HuixcV4dwuVBg}uKIl4u0<dOo!trU@BVE;HBve}uYzmoMhbGM@UY1qs> zbR^Bnp$rfGtA2P|Chir#b>+3|$UnW$T;$HOdx6;J-LVqt&o-|mcU5bTn|Um;TfAdn zCLMbhkN0wD{?Z#8czSK86+(GyCP+i^9!h-nd|FgO`VA&-quoHGLzHXJfq^+(i!<4s zD;2`)o|rH1sv<`FwJUamQGUS8IklH%SN<14^0lP>e-{q|>MHniFqap?Asm|S7xJq4 zcB<LV+_a=S_-~qTA3S~)ckt}?E%~*24?1|aOOr;}!G_a{Lc*civ%db>vhC6JH)q<y zH>v(!c$CQ6q9@pcQYLwF{Ll>hrz!E`@OFQ=+OqP%<cYA+J>P!X_34qzz0yR3fky6i zOlr)$@@q_3M5Dx$nQUI`h~d%4$Gl=_?qEhv+%VVR7Bg^e&Rb(Mb=oz_sjWTt2CVAc zetqwan&IC+7<$J{9hY^pkrzo<4t0aLeq%k}C{Wm|S@_Xh`df$wkHA^Ha)$ofCxXR* z2NDni07-FzO!Y_#{ROqSVluss5_r*3((q7l#J(%w6_hkvEe#AHp-w8MwKD~hPW^Fb z2>FJ&5{cOF+JuYT^?q-IUZvZx07cBT`u`HC-Cm4XDnL%P2(&<jYPgS2=xUwO2tN=E z5SA1q6BGckg`hF=v*qL_mL4d0-)#dgpd->%c7z$p_xSVsADs%>ElcxB#Wow$>ZGG# zC7ah*_*!cZLy1rF`!ps%-GX_UJ4j}W5s(KXWxg?W87sGFKzcVw9nOw?AEd{e78?#< z561rakAd=ne0_QdecqgVG3f*-Wp!9jJ2_c*>RLdo7uocI2QC59Q{32!rwJ9#){rXh z5P$_zZZV}MA_Vve<VoCo#b))1vEYug%Ca_P14fa#)t2UlM~WDtq<gp`&y3Z{bGy$Z z1;o**a^<GqjI{a))j0j1!$0!)w-|ix#n7q2CbYd26|d>N_Wrr(3@qB3guu5_*3&ir zgYUQvta{8TEu)e$uTsY-%t{XR;xpy)qeo{%jim~fGU3fOB#g9;O@TJs<0xhhcIw1M zKRL|mcKSU(BdY`?AD34}<Qs&=B}N_*Gj+ziI{1Z#Q#QJrBf6tRWk5!e&hkd@$lFNd z%^HMumNOC%1laNxt;+QDT#Ju?rReIoK_2O8U+=dAOOX0&q%7&<6yLU<-+ru;z2%+A ztL<a>S<$PR!>Jd$=SGkhN9IO|GEH6V{`#hmBe{#5MXcX8B+*-*En1b{w8a(ES)6$2 zN*APyFws@~eiyqtBYHQ8`Y|=96c9be()Q@{?4^)Vc&D*?j|?|GdktH;v2#0_B}<an zQO{?^a>=^69zOpF4r~aXv>AJqxG&kz`?J?^FeUO9Hqd!nhH5_;rU}$j{b3S5e`PJ1 zPVyKhH?Pe9O3p;aBkn5=VXYl+tUxNSIS`c<)fEI@Ds{D6A)Z&0cmcoH;FOqX{-Lo( z6CJ>SxJkA1QZCdH7oTOAXQUINY4$~1ULMmpf9uOXPH8|=XkKYFZs)F4zu?YH1R$2R zDq3G9cU(g^?4R36XEXj?`%Cj<2@|cVSM2_>6adQroLZeNYW_hrMcQ*Kj~MoNyuQAa z5b-rD_A~pZm{sNBS2Y<|CxHZO$&;Rxx#c(Nn%Bjj>Azl%+Sc%TVFDA5z-b@8k)awu zwmqo2FUL?5ru8jGRa_fme$f_p>-B@!zx^NlO;wlUSk1QjPEYiLsE<3;r&W`~IH|A` zTs7PpD#?M*bqJ@9mMwy<bm)%<lNtb^`AZ6;&z^YC_`h$JDKKjE(X%SV^#(dGK$2ew z!M|9X#0so10Q*(Ccll`n`{9PmRwh$|3MmBbAk$lACHyfwUmyHntGnYKIQ1RCNu=iQ znH%pgKsswHd^KPOCdg`?V9OEK^kdr|%D8eVI|Jt#<6H({nBp9yi*O&LPJ=Jyi8gR3 z{|=F{S`SMXU@ImG`7oltShBAIRn)mI$wAk|4QW@E^i%S4G@Sw*bWD#GQs=yVG>i?6 z;B3>l7wOm@6@9t%&L<=Dg4jqgxMaTNqw68tDoFQAov&~}f6Onh1aeh}MwKH=p&bQ_ z@$i!j)3ON0MN%i;r45Xz<$dLGhk?6V?xBO|8;g;v?TdQSKcXb-7I%$-XpW18BJ`#{ z9q8T-Va&id*aBdky&d3F`Kt}?9`$H>5`+%9oxI{EkM19w@^0uhPhS0?AHi%COoOz5 z?Hc>uKTTCe?vIqbf^v1$X379E3{$eOGjplCx*zGMz*%Zb;h$bifZ8LHhlDPkRgxf# zc3eD>9V^^j@zUbx$0>>Ea#m(GStLHA^MVCoC}lp<K0S-vJ>DE039w6Rg0lBSbXiNL zJma}SDQ0M0CM3*GD_g9=tz!l);yJ}y+eA8_%%R;s<;@<7oiibAnyAmgr&!gO6g97C z$>CQ?(H7-)r#odC)$=-ev<bkQZgd{WW#X`(v|viz#@<|`&DIC9vt!^`L&8tkfC11o zm;GNj9H;e_^aL5%!+;Jl32DD*Y|qA#K`nZnqo34cn#4MYBZ^4eH^}#C0q@PsJtA{F zAc7q>bnnYGvm8JSTQ$7uO#ZbqG5UO?Q94+;%~Z?l88T)m^6_KHu5`pwh68S!H$C*w zLwY$y$W6$@-va*o@Y^VUu(RmNhNGTi5vd2Mi#DI)*Y3rGTvd(m6Y#)-6Ybg+ZN$p{ z0j+JEiz}fgJjV3ExpF--q9s3F82;9f%}d8DJ*LBcCz_h*_Rjr8Sl8Qz3Ok9E<4*?e z3X3?AO(7^pg@QtKZWFtyZ0)i(O52J|m5^;S!18@!2jea&OGKQw3Nr6sXg)E@4#*X9 zP)w%NC(v9pg!onn>Q1`N=O>_{E@^{w!?N6FT83$)+XuDg|6={E)W@aF-MO6LTQZgq z!2XiSt)`=bhi8=A`erFDedwA^a{@by5ZQcrGLGzgFGocptgRsY&X&%V2MEIy(o>K8 zvE3am{B+E;*SR@5f*9ML@l#EVf9xO4MPAqf*rA<TcH3A1jAaby#$S;S>vHit8MXKZ zAw{d)j4)7qO<8m^dpq##uJ6|h-P(v8mrrD!)t~PRPu5;y7+rJos<mlLR8_hT8uXTN zL_e=&xsL;$^%AL?nP{08SVkM|IZMOhV%i6Q+m7~0Vn2$#U)%z{ZMCXYY2x2|pZ`sk z;(M3vO^9a-qqfpefIFup#UmBjr_bxXga`{W2&>r4!~B;47AU^768UNx;SF_6rF3__ zks`o#&)l+a$8g9WVZ?;n=o5OI>v!(F$IQGO$S9*PV{Me_87hD|r^b!kh?z>_(zigk zul{~eT9seqrd+ww5`p&P`|8LY7Mv{Ei!uudalRDX=pMXrNn=4cY{|~mvX`d%+QYvO zk~}j5L$rCXSh0NK39Cn+$0zw>v{9sy6nw8X+PS+Uy1<EqE@Vf)`$ew-k!c}Z!UQ3G z5LK5KAC8a0NSoKErrHO?XD{BF70qRplWcnuyY(UO*+gBn*LgQPVq5beE`CMg`&$iU zt|$GKK$C^ne^PP0=&;8H9Hm^Rg~i=Y8jOMQL7z%Llf>T4K8m|^(m|)H6Et|l@Sm(q z_u?6I6cw#Oh|#$n1tBZd;b8<sI(UprNj&F{QIalwX9+*{GHL`<_rY0`+TB9O78~*W zT4BfMcm73%T}WXl-@JS;&BqxAOxm*CtQFp;AUdkp>J|}>Bf_CNzTEQOj25>MkYMDN zV*D060;2XuFb;8y<p>q5n*h--mH05&zc2CE_F0dG8TL0(+|QZ)qg;`>w^Xf>>!kP& z8QHg!Ha4~(gd_IeS3del2ly~gzptTtCp8MrtiI_B0DiYRqfu5Vwkmgcl0fd-l&~Ku zcTe@I#+=4%BU7zZ;P!N7FF>OsI`R>G-3=K+;|sGEk1mQ*pO9Uazw;=HIi>JS!pTj} zM~*eg=i>G6ob*5040_?DDXo&laLZ9)@{)RfZybe#%^PEK+DTM|JKrOKmSh#8%(bXw zf$2uDBqZu)Bwn)tdn-XP;)uIv65I`=fs4f93Fqhx4TXB}3>J4h>dSu2eRGj;=;J#z zmBV?Sp+2L7c&hLx`oLFjFjc#bj?)PUW5Gm@Z`I;ox~?O&vX3mlczb3mzYMD3T>5q| z#$2uLnhdjJZo6VI3FS>HHnD%{7xpaY8iB6$h+zzkp2<z{|H<K)pQ_x8tB_&H-$Znf zgt=uE+k7=I_Bm(6UAM*9zb5Mj*rbdo=h4%o2$Y<EsK9A2>s|O6yQYug<w9{1LHv?Y zA+TxoCy8#g%IViPR+?8V?G(f`*5;BG=;SMV%?4~eD0m>o{>{s+*A8TWMW-ngNTBT` z79ocK(5qs{Qw+Y{qO~k6%CIdg;8q8!toIk`d~B1HJ%k*4K<n@D{l)M?_aYa)<m*We z6?veA1+C37_w6DuK>jAYJ$C}*XlV@|pdHcN_Aw2#x?|!JIwb|uIsKseLpLr$XhQHb zO9hI)96;>jqD;4V0^IYjMBTjq3bd!nkhTQB!-3x?pb7alQ?=U16k4NVzq{5rJD>8I zeKSo6o%#X8uTf;24Ri4hqB4QuKGr6KB^j}0bJTYhQY7Sc=au4C320ReLaPN+MDe%v zgQ-K=f09Bwg{3R1X<@dCU)U<IaiOR@ji+VkfBj;8QUfYH;xJ+^>O2y;Nd#S}14Lt( z%^jG_p0R<c=g%CFaAP{96!Wxze6&~Bmp$j$YG(FXr%-h3UUcd8phOExtxP(0itVLb z)LR008|!xQIml%svfa##sRdn^Zdc@18`LYhYqOWLmy5pgY*viwskvl=<mo}(RsY7& zM5;uz2l2Ec+yPpbD&!O{N~Q3oLs}8zasA?M{v$h$jPpU-%xwG1_aL!AtTA!CD9^w_ zVAn>pzZ#56Z}gCr8AUPl?=n9LQ@+l8)<j<)-jfeIroa%122M>OQA)ZDvg`;XvsXI! zaTPqYr23Q=c9NWP@mMKi<|ZAKUMRAqg}GjWO{SYvX<Z7gzyWI<sP>b`(hAI>P%kEg zufr>ED&D59=3c(*>*kR=e8TT#Sr+fkucPLaw39!J1VYpOMw^|P9KaY%izZ9kGc_(U z>TY=m!$eQeS~~cqg{GPI!3q@Ua6{IrW=i>s7ufis90L}*xfgA6>6it+Xg7OQLj?g~ zlj8ck_Mr>H(6tmCCBkErYj5&kgd)jsIxhb{);DCC2_eq?@5opj_;4|vf&0Ot5hBze z^L1i~rh?I9$G9gmY5S*V;IRSgsiQ}DNKRQbHVzly73)i?OQ8u6tx~w5xz6$y=2WbD z?bcyS5L(AkA1NCyFim3HSF5$U5aBUi>iX*X-p>mBuPAB@Jw~;*;NReTj)*7GH>sS+ zy-+}OsVCTk%bXgRiQzgXNm@H9Kh1MZKX33xoulW(bq<8DG=`*5lw$Wy5TU))?Y>Dw z&=FUR$Svb=XSx)a>pWVp`IXP>58FmqvY~2ix21LIIvc-*&eEn&>(Rx@TIPF;@vb<; zHyha^nJ5wA0O$+Pb=$bx(;ycS97#7EO9w63QjS;eICoYvgbq^c%73u|MfV4#svAc` zj427oCoG(8q_evc$1rPvL7&X<3>Ss0hF?i@26K}U)ruV@L(jW)Inj8gQ2MikP*<AZ z&7L$Dp4hS)@r(xde>G43{OK7Xo1M#1VH+&gB--*Lc=Zu&{UR;Anx-TKG2ahn(XwMc z^oCIsO{S{8tF;D?v%GrO-DzWZjFzT2fP8D9#Av-%o^nkDy^FefkM~8>Zsyia1~28u z6P}NGERdBHBniThi4zY6fOEM}b_gOi0vo>~#p<BD_mkz5yURd^21g?Q7WRf$V((rV zxOG}!4k33<j3iM{#Dxc~S2_LT7_AR<F5P6v4?zxAA^a?4&owXURfBNZA>>wZ`XEb+ z?U|ny(M9TbtnkrHsPTwLy|@GKv<NKxn;u;owu`!zxgtS8I!I@9%7&`HDJpel=Mnhk z6-fLGcKDTPX7rYfI{4TOeQvHB$h_=VDEaiqNE4PKi9C<Q5Wpg}XBDz8Cd9zV&gfP2 zhJGv@-R!xQmf96+*Pe@XZvb$x;uf&<Ja{BG+*OjGoK$$O&*AB8`#;VrQ8~XkH$9=~ z4TW@eVWswYh}USOl8kT`aGN<!Hg6q#%gq0dtD$FBkUBK@Bc0xnJ$TiR$B@j_<hdyP zL-9O^F;pM0`B*@2QO;a(*)P(yCj>cNMOU|ObzvU-*&gJ9W3)Rux1qWFEuGC<(bO<4 zMZv2Bq+FWmmY!Zcc?wW!rKWr}=4bAI1cOE^bYEX;4^f^Gq_1@l+i9KV3FWTDX6+s! z?x7GB*yMl@1SW{|QA?FXdvuCww4p6X3sK{+1J5v1u1XJ$xdeWzjnG%;gt(v@0xnt` z(>)E-A8()NB)LjLl1pWr8v!8ksI_CFw0*C1DMi)sa#>5qsvYDR4#RVl0e1eqDf6c& zg7RXwaq^zjl{TCXN84Rh*lSSB;9df9nv85f(Up?nH*{8o{}yA-2B<BDH-8D5*)#hr zuRb0CQ&#ca#Hj?t+Y-ga<#*z>4I2uzHLAJvJ*2?BkKmdXM+NGP?tu$qMOEGFkKiVB zo>&2TSxCoC^uj~ECSgEjr<X!j^gmI}0JGdHE;oN>U4}UeFNGi>Njf)d+c}T#Hp(y* zZz~PlTGk2b1+_TD*TMJuPjg&KD!yTThPSrb=CkOx`$m%*Ll|v5kajh&7y$4jZNr&q za<pjxEMj^QQPBNb7JB){r-Ci}-XD^0n0z_#(*cZ2PcMc#&b$;!w@)FMT#Z%f)EQE~ zZb7%2aHF$|uju$3HB8sP2i^#Q=^WA2ViBvTnGUL@e`^KtM*I}aJUx=RU>^Lk4mvi+ zr5|AFhZRTGiz?dhX|>5ZN$p2{mFy(ZeN*JNq6YZ3&p?%lLliYIh;v?x&i^qF>So#o zpKG>qrw#+F!BBAR`+DwRvd!>A92y>f#1@Ylt7XJY3eh)`%@%|#8`k4P3*%m@l1p&A zF2c(ZKYH7m6WwMl_wt50m}hGhpHVYYX*w1veFh^EX#D{>(k7d&^XdXW#_>e52{%F4 zcSskSe%V0Ka)4&=YeGC~d9T(a19e!%=#}V|ZG3vrHrid34!-Lt!?f33+I~joPK5}i z#e@65vs-?bc<(AOG%jLP>jY3gc<K)jI<HJ4OLSgH(RFNYAMxsLEPrIa#P6)?MKo>x zU=R9AI}Q(l4bL==-+w4&1Vl(w$WU65OJ^J*>ue`1bhh;Ze{H~zNuO>;RAk|7?uRf^ zv(JQ5*^<k?d~~eib7j61Mxz$s2W-wDWMA;T8lrbs`qy;T`NJ`1Ohi}}+?EXPeq&Pz z{4S}bVpe_Ecqz$VQFh@Q==2g^k-%U@W*Ef5jc3F)&t5Zz#&VRur(@poeFL(16@1DD zH;)3OPJeP7AJDbahL!hbyk(&lXO-KqB3L5w<OMnYi2SlEa(Z<0-Z@e}1Yws(!-O8t zH~1{_foAzHf5M<Hvn!bO3H1DyoHms+VyBnSBR~qd54h26^dpxSm2Omlc-&C$8Mw@* z?YGL3BhPSyz%0n3s2(Ae1%QF%GmRFQn<1kCFa-dMB6)(TNnGYD@}VAl8Qh8i>YYpP zbR`8uIozjob~JOvZ60{NTHZCuy*6YjIl4GEp#ZENc&V^bN=+J7ETGuA%nQXv1=8MY zEAOpxy8N`Bi%GqbOs$i=<uP^hVuE>vg1>~GcnOctFqcS|SSU#sh?8&}8znI&4Dd&p z&rOrx&1Y$reD2kHe&jwT-W?6|WIocb<NmVZ5H4ZiF;}8^W3Rk}4RG%O%Ky-BcD~HK z*PHFV3I`rq0eKqj_Hc@*5k10ThssSF$fR&DxW8HwNthJqlqvt(Ze*EXQGb<|Y+rvK zb7lqR%OA7cJlY!1@jW<W07SDKZSH&@D|K(Q$QcAcZ5naGRJ_uU|6I}*?hF#b#Z_~= z?4>b#Tw&T;UwI-H)e3-hX(99=7bHO*pP_>-+zdO?0k2@j%M7@d>+V`we`{gS*zhDU zJD?z&%nDp<FhGmL!RtxR*BLqysPZ{45+>>hCI}UQ;;C7G5y#VosdG)TlR>wFE~Q3# zKmii~e3!lDrVV?-SFP~Pw8d0BCI33MjKH>{uskNHZ*1gKkjcf}X}T`?b@Wl@XO@!( zpY4saXR<ghcGUB8l@1FsFXo?+5mFwtEI1!tH2uJ5LB_d!3|g1;`gi$>wY81Jc%j#W zTTBZlVS!`aXZjpOi-PMsCEs%Nxn$WBu81CH)$}LOF&buo-~E<y^2?_%InE|G9laEd zJuk^v$9QF_Kp)SNETY%o=MDwMpBtp;_sMK3qrb&iU6|ivxNSU~bgt^1H~ez7)yu`~ zu^H5#4YD=}rnM+N$1c^3QhRM9jHF;Dnj63+qH*6<m7h!5%2APrB0Z9_WH!XoxB#*C z?9IWGXH6BQ$fYRHQulPdPID0+?^)stD%66yw~=l^*j^XmZO-k{T6;W1tV<YL;37dl z1@x@dNUG6LL?!C~i>}Fq$gI}8OKtCF$5_&!81<dM{S4^k4yb3hmiZ=;sSI%KvIAWn zVytIonzFL{roe&D-OE>peHeg~@rU60n+3o3L=_m8GBrVi8px{qPYff*g{-LFClT!H zTe!pIg6{{e1rJp8cTd5k0f4nuV3wxp0XCrDqr#?teg|#kTZmD9aregi&gG67?gSwb z<i-7c#S(77bc!152lTk>zLop+T_@~yj_|3!iB!u<O=*vhVIUQ2m){A-J>5LUsGEio z{@tpEPebGHgi!7jTy!Im7f`4P0Ty$+j(%dF7B^hH=Vm8rZ;|a)4E0l$UpvlzRO>aE z%6a=hN9c$uK^vgA4`p@>Q5R-WcAJ((n5>Yvl$d|ZjyW_ZxoyM=awQ)N#{);&XR1II z(to3l2@0d2b+xfTE1t!FF)2_E4aa>a`7}%sN*zbopI6~omt|7?D00j@!sO7N?J=Q2 z(aw@SJt5PGY6HfeqVkZ>LRc@t&ESLFXBxADvTnn=r4S(2@7Vg<;#-5B(LPn{8WDXM z7BNK86_PXr+0kR#&_p2ufaNy`n&jpx5~Y=pv#IyHXRunpBQt|%Sx1e3(_HS+Z`I~m zx6(!PE5olekp;t<xm@Ken;QM4bF6>8(}k+$o>$vwfTmSl%jOwTZ>=(cYRf<Th@SE( zw5T_3{9NdhDtV6;h;4%N!?h?^7)%6xtW)$)ZmOr&F_*10UjTleHRsy)>t3wbq`t(T z$Y9o*$X4Rkq?a9~;)=twu2Pr;xsEy5<&v4aJ-2s9#z>cai0D_Uqn;GX6QUs^jVFdt zCmJplV4e&e-w-7PuTJUP8fp953s~ld=w9#BV#!!d(iZvJqq*rPXlYnAgzH%-XRyi2 zTJ$xWd^cX-s?XX%q85#o6{T)Cj&(4C$r3DR;`JDd1^pZKR4^!2-Z{tHOK@XI)p7yU z^1RGJspZm6Bp!I)w0*s5#{Vo=-fh|~0<I(cbpkXeRX1^jLMeN44y<k881z@X4SMs+ zdYEn1TTcxA|Muju#t7<{EGI+x(r3M#hv_P1MhtGfqdgOmn-@A@C58gehVK4=0Zs{E zr<`TKuTQcOJp}K!q=11-r7*~@IO}7#I<n3s#RE%*=-*^Gj%_SHdFqv7#eHt+;ISJY z@vMuQavTnBc-D?$n?TX!9`kZMDxXUyDy4hr&1NETpOr{&!{Yq&H9LmYe<9b9Ho+GP zY1r4Z3GY$O6<F47jF_Jqjt<O~HQZvjT%v<gIbUXZumN9I_<<J?z@J>r{PYjMNLVex zNWuD+#yTOu)o3dR)+OBR7aG`SjBu6lU?@3teW(UWztjZfPs5E`rl6?NO<Le64~JQq z5_2EYLip3WTD)Bi##gq^LV{b8bcKyY9C4O<N4W&II!0q@s9q?313iYyQ`1Oo)#15D zq7oU=e$Go(72>J7^mZdKS71Q(qEpO?0ce4I;ib*e4^5HmAv1iC6=V^0)a7}xl>LQW zaH;0p8<h<}O*Y+UIaFVSsH{}Tq)9Q%s+;StiDCqsVIJHi<T@+%yaVJ<;n-KR7j{rp zk)WptoyBzJgfc;I>H*VR&#_9zDdOgdan{sbjsSIc6VJx|E=?1pj`IAD>4p(=$L0(l zCFJn()V9>nn4nG&De2dk-sVUj!KM7i*5xb0uf&Z$mp-d#+2eZYDG{pUEY)F>s+)rz zFV#7KslYYog5WN0x|hD&@c6fmFr3{^uz6=&!xN=Z{@B4r0XQNO9ox2em#fAkda%Tp z6;FoDZ#wATyrx%rzm?}M1{)6zvTX(=_YV7zO`>tdX_bLnA7|ke2K{|GsPlo#UTC1f zA}PDrFc9bm3tE05`&wg*Ddw~+d+A?i>lNXwE~JUnuLRmF3LXr_xa2fEdn*<cOt>Ys z_iSKvUFHVHJ<ETGM5f53s@e<9&&Qg%{4~pDJCvhGaNbjbKF!p9sC>%<&PMlhaG~_4 zMtFbhe#!RmyS|3&@l8-R$|6EvvIcw{WMT~a5s^Bz<!>)1W6h<cR^ayf$KH%~$E>q3 z`p`lsT4robtRz=<F@E#*!I_zjg)_l$Zbq=tu#a1sRaF1VrM+hlBaFSypqFKKn9>sr zcUm=WXEiB$cJMY%!*eatKU~c7nStj`!QXolGD<Y9n}>*tJWq4M!syboVyZV#Dnk&a zWzX|pF+ua-ymXSRZJ#Xb&r98(Y>G?1Rh*X14SN#G!0V|%Zqj%^UGm$LFZ@G#<$JBb zQg;6>CA|=sgd1G87(Rs%d9&ICuppp1Dxv;F`umJI_Sl@wL8861K`!?G@{ng~dFBzR zpYq_2DthV{dn&4E-ze1}gi0@jGk)nF_3sO{?_~$WA6(8X%sS=Qonla&%D=PJ#GbD0 zI0}cDYF^ex%B~QuosE(;N3?SiG-;fP0nkzFMAC=YbZrRxtKqvp-cxD9vooOyGE<{# zhE<04RA!shsVY^fy*fsVFtZDEFW2CFa|0h#OW8JxN>s<$JK&Jt9gXMeUpe}BJQal= zMC}=Z(z7v|C2eCbOe*>Q_vVottiVKWZsw6ROTNZmL#Sv!gO=eF_P>Z!vE0ilk6xfg zthcLv3ALuqWSQO7s1MNw$_V{c&6y}H3E3P}SG`pVms(XTG?qVi{$&xcKvmiu(u7g2 zigzs0;4k@H>CJ6iHWVP>-c?~#3|F&<vFXCtgOWe~LPP@zkpN(bde~r$it}iqmgBLB zt16oljXT35KZR-QZd7E-ROU!vWisep$_NjQIO-!1Cdo2I9*9^9Ezy*Ha0Wi?CqO|> z6&ye_j`UOEXmk_ojdrrT>g45vD*&lHAC}+`M@NZK8Tv6Pgk@FyEgSp;MY9n#-y3)` z8|BQ<&1&iA{#GkHAYALbnA&746pAFk0MX;LKPARSMm^=*YA}}0e6g0bk>X4;1W-Yx zRwXkjlq)9CO-~b8mo><}$+tq%q*PKIonekfwVGWmu7BZMA3#AoUdFIRt*UkwVOj$# zL*LR(CFqX28Rqt;5%Nvtmj?6CjTG2?Il@@bM;VzixIz`f<&dPyo1kn{ht&++@XSy` z7l+mYMBEj4L^tzQ9nvll7-%eo0tF>Q-}Ug75w5CL7dA2HfNY+|4O<G>971Ve7h&cE zeh@K}5<w}(L$Z2lQ&-cbBFq<X<}+X6;|lrt1a!s}ZzBX0s7`uIPp<|kbko*hlgkoq z;se|yuHaxo+c3kalJ(Z+4}BH@T$nAKcxBb}d^wT<;vR!UL*2PLI7S)<ypPrQg8|5H z+~MXRHULWNv`AG;{Gqi#X64KXzd!pcM~&;5%s<4dC4!fI(i<_YQE|?xDNZx7G@H$2 z)Aptpe!P4s7aT*g_?B{Ql6n90LaLrFsEVzi^%`<0LJg~U*gT=(%nO$nqLO=>7Tbgq zr_P}<B^uO^5wYZVE96<zmEpezNo7=OAW2rE@Hi;#W-+u4a#zJ|K#{_vwFpy;PP}r; z`R@p3z6nzaKseTwlpI^J9o~IppWc^1_zW0wmEO<aT+S?3+p99fv=dCdiF<=9G!Q8L zb^YDd#rlX$#F8e}H}Z_EwVW5>xSYUQ1~(?94mM>-JR@8srA%z5SR<`>L(65~zwA*l zt3PFecGgPlC<<wq<`AR<;$*T&D>(^sek-=eC}QAu+pH@6_v$zUW5#!WLs^>?z*JYK ziLk_qNFDAa8ul&1sBr+5I9w%eg;1=)s_9@sbkk`$bF-bpS^~Y*W)%eC-WOR%Bbj7t zqA=65C3FV0Qu1FysiCnibu&{1e3#V-on?0?h>+7nn`KyLwV9%6pM)tVT*WQ@Ton*s z%~sdD8{e4~SeAV#XFT_@ve=%u{|qi^v*7<59xt<2%fPfCgiu%~h;vow4PR{Q)AXYr zz~^3+=z^ooY;uYf3*3@5xnQ56fW&DMmf}#v46Qwc#aFN;Jcqw7VSLx>l!cwDWJlax zUC&ufBm7%GDwe_6<9CdSyNl3&?fO}}mB!PI;~ny!$!nWClk(Ivm6>!`P_WOI$tKZ+ zy0xVzeaRz#&hHl5Ei|}Pz{b8N7QZ2eJ)5SlL%kW=EdP){#v>;W^LNSFO!WIblC?;i zRqb*ZVo59^p!_IU$HkHH(!<Ty3-7J#f{0%$*3c==3)Z@+i%ELCDp!n%bMx?j@M)Wk zqCfZ=(O<4`j>2pfM0K4?2B^~(fuQyRa{;Jy{t#EfqDZ3UA8IBp0;HxJzUvH?d=3|H zXH;D$9Ij*w7OYJ$n7>&AJq4HWvjnCgs!kiCoCC2WC2#zLTS4?ioquGil?el9XP8+t zRp?5g{qjgvqUm6<-^>dxksR*xK*{_3$Mib$^jc~{=RggmZF&{9F7T1gX2RP!$Bf9- zknvhvL|6Sav1;QR(yNHF&3yKQ5VYfwluUH*Bq+vW;a%|ChVPC-@}@lB<>T_|pKqz{ zjg5WMy<vRq;|cuI>YQdD6~I7|t>?X+@BM7NVIvH=8@n-Y<N^@Jt_=(&<>$>hHCJlz zrIr^LFB5Jr?i~Bc|DA`YwdszeobS^Ur!K5?_sOdQrWLPMW*kcUNpy#bV>x4$|B3a| zx~9A6(6<dk1H6%c`DiA+_L$xS@OYnsDfc}xdEC!h*FTeP(Da_fvUy?BW1OayaCXFh zaK{C>j`_Xp7NJalwNQ2-m_uCeljjcBJIgG;ff}RI1Al@S$*}ji#m^M!1{ZA;S#`0j zqE7G`vxL2J$vAS+I5Q`*@YldT?=;}N;M$r6O>6n6<_AfL;ZwijO~_sH4iW}5tNVXl zrHz&G&p0OdIW8;H062a3U)BA)Q>D^BwsJP@AEVyD_;s>mY@VoJ;w+_-8>dTrJs~Y@ z&NvFbJ@hW@9cr0FXBc)8jQEOP5E$LyEvbi0OGCLsx~WZ;{<aA9RNX?u*IW`W3xELi zXg`}Z>}=mbP5#Bs1;Qt+dH%MLo;z_LXXwX|;f$P$Np&9$-pdKu%Bm_Yns8cr|Ej@$ z;~amutyuh&AD6=tkR*Q@cf2rY@24#ECU=-6o5m&wsA(P`pD#Ktd`?7syBK%-lac$U zfLqv9dViBM=he1%Lej1RtK!A4Er|^fDgjW+i*2A_lh@TeJK(lJ7T4Z`7x%NUKA$E8 zct}Hg#ubG3*LcIoDN<7n52oPLaE<=LnjqUQA2_GRB^UEv{d-QMhCNgduLD)~ImHle z(x?B-`5RuqS7?BrE=2Q>iX5V*6&x4tnGZ4DrBaNhT03Q~GQY=VhtR;UHDCjB;JaDH z4IB%fnIG{CttIk>sPGFONzTC~Wx#^G1$~#J{L^=2R?~I}>w+ymH?s3)WN5!l@A(jY z-=mxIH!x@OzL03Eu#F*Y5|qj=J0H7zZB}1H!j8%8OQ%SyWJ4fokC51a46#87cN0bo zKPsJlLGx54K9*7%WDm=5E4=NRjzWX3{Lj<=T>qp(#c~^QFC~mEim~_&TzcmQ(6ptO zQ<mWlv3X0_8Cf22vA=v<pp5Zm-JJjRm6LCBWS6@)7#Zy9DK`oYrRnR7Z61m%(I%We zhadI8Rh7QU<-FkM@8sSlWSx4N-$6-!IjPz6lrAV`7j^ci6e#Q;YjN08GLO_tr<ndF z*jHBaDm{>RTZw!4rT@+M_E(|1OSOAS*&&sAbw>`xo7H{+KRE6Y7`Z-9c>SbJhj52P z2y+q%4vzB!)lo`I#DO1$enVvOx9>YzS~onOci(6U!53<O@)Y&VIZY#!yQJCGw`xAf zIWs&?YJGnzt+d*;GC1wR)jPz5hwn$Lf^!KXdQS+y3tkuJlwogf)jqOiRCdpyh-dX` zHvif}tr4`MIv4pjTbKeH76++A3w@FJJ^V@i+s5DB1h`jT)QumF^zVza^Y&i|INu0; zvUoFVqB40Yb}|(qYIvN}o5<t#3&_VI%>KmZeKM#d01rRyAHAU15e47xOVIiW>@5!! zVXv|ivzK`E*}WT7j`K(&8DMBCDlO&*?UeQ3on{;}=~I-Q{N7<maq&$WdFj%LUj+bF z+*7sIbNT`5hu@W`aq|kl7X)APxR-XA$2mUL8s7?v-y7wxZgQUX&v=rr#1tj`DL6Y? z-%CR=yL}?sM*@EN7w!@E7u8jt-q<}?5t`rz`v36%{`cNbTxD<YgZcLyGHt>lts80> zPs1c=+7yBwO=T3&&J+t398U+Sp+`k@hFV-QGz(Rso|6=Q>I_uS_6~|INeW@^&@{eT znCLXb1@jCQeR>Zzn{RYV-ME0i7Vvw+f7zWD(EI1j+j~j;d5i5skNMI9y<r|2Ga6Nb z*CtEqC58#zVm&dZw&1snV??ldy`5^5V=(l{Q%jQiyIIP`Xql~%R73zX1WP@9&iOi^ zrg**|EuekIe{wlQYCcK%3e~FRiHv`0SPs8buXje_ix3NmatKyQ>jBLd$XT}IE#)t7 zhG^eVEiwVScsZIEM~=(xtbjzkkHh8g2ODn(EuMO7xZHo8$SW+m69{fx`>^-4_9ag* z`@2+iu0kollFh$~R#k32Z+~t^)>fu9{ItDE)7Qi83-eF4VKT{u0St7Xpyir4YWwOG zPBpewtxqv9N+?zC$s0@FVSNs*c~!eglb`GgdU*JJzFy+Wb6w6<b+n?(9XLm%4ugXF zD$b29Ai6f!z?QJ&8ppTKZiM-M^jiD48NQT3t4EuVd0DXUS-_gNPX&E8U%pY1Zw=8s zgf9N1I&72K0Ccr?->T73YUl%t9eDEHDkLlPu2ltFEWQbe5iC8p!FC2E>1%s2D&*;! zDH!<c{QA`Brz;;2<EDLS`{i<#jV<+iEE|yUtU5Dbt>u1*IFV!^w@AaSCBz6Tb2&br z;igNrk8R(!8$tp_pjqO3?K+P2)=u9Csvw$*NI}<iB_8l;N8X(LVElwpK@6yo$Y^dP z+{>uSn4#fX==?Hrzd&QaP!+r;I|c5P&A!&d5#g$k;9d!unFseju$bVQq-FnHA7s+m z*eyL9^M9zds?Q?`d>0(Mm=2L2APxI>#9lMqhJs;Z7dtbXkWG<0Xq|DsvHL_QRqNuk zP~ahK=0p~D!Id|(6{MFWyzE#u@f^o{3YaIu9=%po#!*bq1nRyLH;r9hJh{Mm;+mAp z5K-Q2Ut6K1=QCAWF#mL`HS(d-AE)hd2KS%~T6`)N=^J;b7<tD5(~HnK;GnHw((z%C zJWB+XjOZkTpzq=<fDH-6B!){zwZ2wyTsPPIf{fXR-Bk9q7kSKi0Wi9d4A+8=-|GK# z(cm&kn!1@3t@}3KPVl*P?R+3n7+Q%7V|3j3tMzw-KmLTT%NJb9)l6P4AG`FgTX!a2 z>|V4PWHIYx|820bRyun`Oq~}e+pbm=mGqT)#$VYaje~Dr`mBKiH2PQBe9{j^(u?mm zM9-;H11y$xFl`x+?h9~6aC_hbAIx|;>8)-*bFmIP_8b?-i(ZRMQ^0o_p@p<i2&V&W zmNh~3hv9F6T#Ks_Ycgr3qty^jycQo+mJq<YrA03~CL|b|TxKH3y2J_s=wC2uFW~&( zxiWBG=7b7D0r(jJf%E#gyD3?4tI#`7k*i13Kq2FD!}gl-3@-VAjj8t9$sCkUI<HYj zol(Y9UWwMoj{4am8PAz=qt1r;G8NH|pi}qiOF$(`bK0n@X{pxmu7pdv0+n70)ChoE zREq+P?B#N=XS(mdeCRgXPY+3;A4hsTYjK(FX<ILo2JBaXe6%EReOr1g!M*B|v+mRo zpJ^|7Yt&WBo`S2sF^mU(yXt)a<<e%6mw?60-p>7}RXR87;%ua?3F&k-yX*E{A6}9@ z2V5j^Vb`a+g@5eM{>Ib1q9oA?m`6O?Nb9+<Heoi{_icZ%)}+$>v6>x{Q49zHszxId z`NX2n9+?jf{@Q~x0ytn33x$1RYBInI{P*k6>9-GWpFVkVb_URhZ6?4t{5BKeB2Alk zdZmNSBv4;$EBQve+g1vfPt#TkT0Hqx8Y=Y^oq{PmU8WIhXxdJf>{(@|#f*u)%T#z_ zDC94)*Ho(~23_3F!9pFDyzP!}Y9kFrns@R{MU3#&x-5O~@~s(R1q6Ga=|o!IIB=wp z*F6D>G*I&2%M(*aB+%Xnb=WOSb7|f!zu;UrT*19ryj1Mf5HgZ`=QrY@>b78vc4=2T z5fvMvq*jLw*PqdXdyv{`nCrb)I4kc&9=>n9SF<TvLnnTVpNd|+?hQ6m?eI`XYvQb5 zkoH3IB8_CFmsOTkgc+MK4Q~kYkX)JlyDpzDW@^{}q0&XSoDOJ=Lq+6ma;gJ|-n2-i zSDw+wMo%8PdhH<NX)T&y{l+Z4V3iNS9VFxQ-Hv?`i!3+p>zDT)y-mM$aF_pNC$X77 zh@?yXSkr)3Z(#6)%-~lKhke=$W8D+p4UE&mkN)C$K0hISUwcQ(v>`Y{Wh)$48B5># z=jcAae&#MM_v)Wve{LPGLmJ-L_2cUQ^44$^rXc)NQEtpn=N2|u1`6+`QSrt(w9n>< zfY(Ord7Kme_giH=eq)hF_s>YGtf-T4IfOAcjG4+_*G#x;$=D>E#mZfYGy@XPK7M~$ zk$z#fKmZG7vO=t>OqQp@b|VZjSK4uCDh3b+luk+gT(M3%)nd68tN}i%D+*Ry4EWvK zfYp8bRS%%C?j+i}Xnba7`-JdHpfCM-FKDj9Q(vl+OFS9!R5#)J@2_=@3k@}p3$A+S zuNp4vV$3b-%1=X4Of0W&p24@Z#TomWn|vE`FwJ8IUuI8MoUUA^rLf##`}t=7lI7|4 zhflTXIyKK}gLEm-JnU85Ta-UdoKHT;F5K4B0;pK3o*?tQbhzd=u`3PCL-tkB^erI& zRQrlsE=f5q*F-B{i9`#dx=l}?ptMFJ5e@fJnTOpO!-YUb$D_20&;;--%}`e`G8rJR zYSUj{OuWF$K)|uhw={@>5_{5`U#Dw06a_0`y^|RTpq3MY9hS+<#j_b<fuL$#E-n;s zQkAAUQJpP94`c;VVfnwEk~ECRa&9G0wR~h9*LKBZ5=`p^=T||6Ft1#aZk>+cv|*x5 z6(leMO81{^3NSa!N|wh`(d13Z8|R_Z6?QSgF~*6RdFWI5I!Pf*BjWk_-`+WI>8FHQ zM>XA|d<9P#qdr5^fDzuqqa;NrHZclE0qWxnTN)5RK%`fxcUPT|@3dLb0gF%*3qg8P zb-}=6ne~jM1<Y9_0e}z##4q8}fYH@Mwkq_FHPA9Nea1`!PhhxG^@cl=8DP&8%4~0K z)FzHjey=*LHhtCzVFVX!88Fp!?o86(rvR#m1YSez_!SRa0*!q{wb*q=i3d{>`ifP6 zIaV9uSdhZ!m0a3viKXf~W^$aP)QK~+goLOXiz?`9Z1KVccE}(E0O%R}_H{@60p=Yj z4YXKHKV`<|se&88C_chQvz(Oj(Sr*rjujEJq)X2nWjmK)Iy1i`rhzw6S^%Cu<R>Ym z9SM}6#;{0=b*c&#fGvhAaxD}4)NB<hLJqZ0vCKwC-8ucytv)*MXn_P9!H2E)y{MNR z29RD|%&+tqlx7{Dg6DAXgefEOk<`?)xM9IbzqVkeXPG(V$%ml3mM6Dd($mjBdasvA z>EvHDO!J!*bkcheQO5fEz2ndR;TWk%V&~GQTR#Uj86HMYnz(Lmd>aHv0WmLU-~0%$ zrB)7k7*|r`nz3_ykIzrbV}JJABM{pnh|{`5J6CAKFh)z|08Qki=inaW1oRapl0@g& z5!VVwxE9E%%93y5;h0Wd#^ZC!D>RYphEf3A(>+<-fb!xfao6@try3~a>FI>5s%&-? zeV*3Q=_F<gLP|4b;bZ+Z#n~>KS2VXHa{1RZF1sVY(R5eB>DP??LPz1Fx!vrQ1RD8+ zj^atvJ-IT6;4GES(wFqE$nw>*si5r6@_kdZYFEYrN22V#pBq)n&;+J@Y6X5SK~;6G zTZ`P{tys2s-@e~lOBK&Yb;L4gHSBqSn^Rpof+N=Y%KfAqk?a2d{*o5n45O18TI+<{ z{7vulm*tnicg2(m+VnMDNmJh|sYlW@>2=|rA%yxgmt57kt(Awjxp=uc2t+sskU~&w zqlN%iPJ6qOK^U41P12<wrvnVfni<f9u)AgGXv49F3xa7^s$!R>gKb?P2?PQ-G6|gT z%VMi<q{`r#L5E2Flg$syNGMa3VXw~L!}rk!2XCqR#<ZI>K;4yrH&Ei3FeaBcS0958 z<(lFKC<ybeQS|3CkZ^gg{cGWsogFB*s`WhhwfK@V3K!l>6deAP*s3`HJ6qQ??IKCB z4gv&|Ce&bZIWg*Z7Vp&&?HLP3fI`JjC2k-`X3S}`dVFX@o1j3JCV2rAdbd?=_8~07 zc#aDAJe7u>qmW3K=wCGsbuO@<e9;GZfuaLd5t%Jw3>At|=*HyoH!Xy@As?{H1%DB< zL^NOd&RXI`rN`EudQV>WTWRAX?C%hw72NA1=+KYd4rwdh9~2a##eV$hTA?53%#ugY z#mGPswjO9Ph7}uV)-7dU%7*~!sLO!y`Q_5i7cN=~pEUYdMmO#VIQ@eiTl}VZlGu@6 zC3)um9d+9%?KY}f`LZa0x@p|1{TbRPbzvK%y>``|@fPRQQjYZ3MBd6Di@Aub0z~nq zQU#gD9UJ!<OK-ACZJow2xEQO~hzKP4WRg_r5~T!0!OaQ#C0gJfg&Hc$#;_HbpK@bx zf|dwGLlbFNY{SzgZ`}?-et5}vW)}roIQiq80Jr##{X2jdZ)p|01cZAX!2-xMzDJQQ zSOf`0_rVttyqT0v@+o<TC?TZ`{zN2_!Fw_Z(8R>MC>qxUsaG%KY94_R%Af@RZ0M^F z^?*yhv@0}zaS5~~djU`j+EzQ-KoWh!<ZTIM&>f^zpP~t(+zG={11OmF897z!fTwpq zyaaWwjYk?`VY?yJ_fZVBo79CAYME0SLAbr27@~MIHjkV_uZ09&!tde2eJqeEyNIUK z8+Z1VyxVOV(X<<pf$_Vv`6B*QiD`6b+A<E>FciFuhFGBj25tIh!il-jTzQL#xinQE zA)T*CweTlR3zl9V0BWn~0TQhFi00p<J=7wGDp$3RoJhBo^`+@X11bJtar^=&B4zS= zHU$ij0W~-S8PV`<(RilB%rX&LRf9WJ$I$>8x!4Q-wacnnLNpPO_o@&TD7xH5Vj~uT z-9mg71E~+fOG$YWeR<-qz=y>?gQB5X3F#SbvBG_cS!Y%7wMX%3qUT4CZfuEy1}HFb z(-R*O;GUpNCCg@nvqz@|1t$bSw`c+Zgb!`h7yt<R(?o63u=g=Ly5*WwXa5tW#fa0B z0Gg3SM5P;DryH`4jA%xI^_z&ggcJaa42j99Uo5IyEUI@y;vJ9`GIXo(;&|2Ky8kIU z4}YruKaL-F+xObr#l^MvrnvUrqe$1@TvA!pbqCk%+LB~bNeBt`y;dQWRVfsbtVF3O zb$@>Uz&W4C=W*Vj$LDcg<JneT`iAx5Der!HB73`6!8NM&XIKT11OU0^-{INxr~^3| zKtO;|^fT3v6hWx&67tLj?4lez{eaF901G3KK?5*1bZN8(E65Dyfkc!GvMN7i9V5W- z1em{Y$wf4LTnMgWdu6{VqCyu=^Evic-pDGaMYP?Bz(>d8X;NiZxtS~}bL;tHtfU)s zgYs%b_HJ~nKGF{jv3LuAni;;i9?M<>yGXbQFudD;rJx4LCwq_{1mE5<zWIm97Buqa zQu%vz&T0Z{ECUv+4o@J!FPC%Z%yE4~bAOrS+5uRb@DUei@F%b|EL)mDMJ@LC4ecJT zo!uIVcZtC61(4LmLwcR#1GW*{>mj?)vjkY8UMhGXCEGO7j{rMRKx8dNMXKj>u&|zB z1#+>-i|X*%QRE*uz_h*?u-lMpQxC7;`-M#hO~KBeFDvzCyNPFO-fbk^D!Z@F-jC$$ zV6b<fIr`BY@!93+3gtwR=0>2Lyis=XVN(a8={Q!F%gpA?OW}M20R4>SCORSuAI6&k z3p1^mZe!CnM1F7Ma(RH1+J$HIz~ZanH!N?m@4;N@V2|o!>;yk&d}2Hqx&;T^0a!FL zwR5ZiPe^+ZQXQ1dmlu*G6H#{cVLA0p%X2o;^GM>;&6ekp$+LEMAL;p(lvRbkOI3(S z<(p&8ZG%-zBKX5o=PT|~-=uc5Aq%oOtC6%YmjdsHNZ)Gc)2DZ8%HUu06WXnz&P(Jw z1|(W@Mp)A=ztb&e0?I&UY(qM6)Cc9y##_dJmybu5@hi0pu-`@YwazJ~bF-7)MmD}X z-6}MS&{aU@Az6Vp(O`|%w`J7ACBy+MZIStt9C57<RKs?g08wj$4l5!9lJi*(LExOk zz$Uh{^gDqSZESt~7Y&f(hRB?2WuAB1dz*7OmD-adx<D-L((}lOO<fqaW8*hfWeh16 zRur9+QwYQ#dc}3Z0MgQ>D{E0C7X%IMQ$S#AQfC9R#8v{Z9eM(}r^25IwRZu@?SjHC zUWnL5_!1HkeaL~|oi+t|+{;agW5@|_w$t-n9$Q_fwsgP$EEl_z(<It8Z<qL$mOf82 zcmYTCj3QH_qTX4ZCc=RC4`Km4D-I7&W7K2dK#D0m7ZE$Xi?Cwc=P=_?4};N@(n0{w za(0o^e;z)|ET6YWo&WLZ15>FByxhAZlo9o+uwOr`eLn5-1B5Dj%#=XXYpeM8Z>Yd7 zB)3OBzAb`j2w6n{26&K|K3fSI89;|Qrap>tZM;6uQytaiDT<OZdfc{kPBEtlsquh{ zjI4Wes%jUOU>Z?=0S;mV*o&@=7~Qc&!p<V~&ixwf&f@*O6u@@Gk5cX)RYa*|Wh*Kn zk-y@1eB;42QS4K2Ri9ks9@I_U3$zF8>Vl*8u4qK_zV;om7+?q%3~{?Y{@91y{L^8= z0esy;UKR*1TZ^n<MSVDRE(i~?{xj$`A?eqLJm-MA`wV%qtRt>3UGM=i#4o0A?df@B zs%<rdW56Q?PJX}?emdOlCWY!f-H&`X?la^$@C|!aKySFdI|}}m#Fq*8>_?8uRqH&3 zof;o~HIViTTaK!EsJDRhGk$E*^!UZoA^yyGh%G9~2VMvp$#8*>!qT|n6J;y;ei6s@ zmm7T?%0hZ4T9qGjp~l+9P|v#&33pI`QghkU2X!+i*4ii72g)ku+s=xPx&5K?E?+#s zaS5dHgkP#eAFcz8BaIJA-baf!122&6<!^gheU0PxvB>13G)zGB?uD1HmPdKo-QpCH z$GPd>eyCQZ$tazyZokRzxsx+{jdzKt=iA7S3&``^z2ChaUn8gL8}x~$hjSK8iTssp ziAGib8RuXwzYM+2YJ4;zvD}w(F#T$3ij!rQO&q1ci6YuQ<yr2<J}QzngEKzOtg_6q zYs_-jyd;V|uT>g5eK&9G4{8{Tbmn|DWya1W^@=^<HNWfZT?A^h!l1%sN_t@0MCJ9b zDYnqO*MjX6x9xf1hp*&}k(}0VPA;;w%OWp`qc}}ar$l)N=f;w;-VcevNsFkz#=Mv1 z-ryRzoV?~_P`#>CW28mLo&IZf4UsjAl9e|EzNS9sV0qWHC>i|s-5F2z7^r~5VmM*` zx}Qs-M<6@<^1N=q3!$m#hy9@uuMyW6^M2~A{ra*GcNYr2@I)?V>;CQRX_~o?hr6}0 z-lwo#U@lI*fAo-Sh~$puxo#ZV9G=x?56x#R4xTadP(h-;@K}hA2A5JpPkSFMvevlR zxQT!G_6RBE$TJlhdhp1reY+gI%+^u-j!$DrGT=E48Fg^sy{T2aaoBTSmOhKjcF%7M z>QiicoG*~?Q9IYiKm|`6L(?P5XLZE8Z-{;rGn-$lVMqTA0HYS=Sl)AKEDC8%sXarO ziCt<4dFSx+asT4o(??|$zAFN*b6uvd8IIzd-;tjFeBZyU-iyi>b~x?-A~>%Nf$bad z6>qP)^NA0|UU_DoarfiPDfUO|NbeWOb1zWsoWRAMsoce56|n;}5bwvi>f1LdjAHLJ zeXY&hS(9^{2M@eua-x6}sEtzt0s+f<-Bn@Ofy9;^$JU3jy(pS0(tStr{9{x%u%P`O z$@K#H{rPM0fdL~ggxLbJf{{A&`~9l;lK8+{e!^xFm+vi;w_GN(cl}>18X^^A`ii=O zXuFSb60BXZS$>zdMWnWo%Ucj0Z*=+>fU(ZezUj^hj68nDS+EUCe|7`9rQhB0`zLEu z8*E2^EXKU7>hYKC$H-qh=<eMG_nocG*0tmtbG)vLS1wQSTN_*!h`g*4SdL`<`k3<u z_W$XT2B7cM^`T1!NXzF_qVZq#s$?EN|H^QDop~8mkpC(&Y8Q<9k8u#*ninAO6w$}b zM2L^E-a&JFz`3XCh(Q8%wLfh&Z!PKh+hhq8+Urw;zr?%uJh@Knz?IkZR@Akb1x~Y7 z%?o||8HoBNm|k4+*MFRq49Fy7<lQq=)cY^*Pi%ts_Tpb4V?O-kNcTcae+B65j~&06 ziT~Ko4>^O({Bm^h27{GXjeS?29aICc0@x<JyFT`h3!vsL)i(dUK=u;%k?s538XO7S zX!Jki<Gjtb5ENV9TA}i~(OQt^2Y3{bvv?OVW14<of~0YCHmds}B{o7IZAvlcks6=l z^A9;$IKrVE!}rjM_cm*t-;elvH@@6H{25o@##W5xsCG#{`0}fc0lnh#=Na>}?)R84 zw|2G;PoM~2mEZfL^8L1Fa)a6hF69ytGcE};#MW2iseS;b9iDYlzbs#E7ho|(10L-# zwt8r_mkPBT@~)#~Ysn(L7k2Cj$X#Ish{7ZHh1^zc3S}LuAjt{!mIYnWuZ|l#F^VK@ z?oyGrw~FklOfLO{h<L2K)LLFr1rbM!wCx(zBc^Z7%y_unS2R()a1O0_9UjqLi!G|L z&*VGhHay2pe3vC|(yJrly|a)P#<Jd_gfeX{V?$MK+j;Ne2dSKru-mLCqUEJVvy@Ip zUKz&<h?9z?Vv)SP6_9wX%N>tz!$Z3@IT=en*Fv6Gjr4e7Z1M=qbQW@s&#!@?zM!kC z>`R{pDe{iVm@ePLgth0_lt7aTZ)Hw(h@9Ece#NWccEe#$gnwLVAnVrWe;2C!Lt=ZQ z6*g})3)XIt@thUhS-cF7AAkQc;k(uP0G)#L#6;D1G<VFuD01?#&ESa(o^r1KxcMF1 zNL`t?QQHqT!pi;xVO$M<;|Aku+2yBS7V(^=Xjs*)9DqfY3zsd6wjl3pjdl#pKJhu# zUTeTz<zTy`Q?SH4`Y2alq*3Nwu*28#_p5fd<ga0Ig|!TbqUFh*X3TvDEro9so(Q|Q z@wH!io<)}i7hVgoRP*%h!1QTuHk2uwAAO(b$v@RtuS9iw#<U&k?QnOomQ-;Su)z+5 zT2FD2?(?0Z)KCQ733ezVUk)!;U(SA$*UpA>E9M%G`;3mI)qr+_r*E8iZbABM##(`U zk}cg@uV|*&J$leMuiwSfmnJ25bCGtpIF^03F34(F$G5;nJYs}B>Xoiv{G~`rv1cI* znpgXnX(e<@-=L}3+2tCvBm|mGt?6(QL#UkzoVUEIoO#PpRw+RIVtq&pgy9JYsj|)I zbgt^wTOG?`0eN~qX$6+S2A>Mf3G_{j{5|eg8BNmERq-Gzw%(CO-V9c<%jY)goXpHB zEXS5}fBU&|JyYT$%3pF>)*7fzDERM7Z1xD!rhn=lv!u26xZoztWPD@@83wDCxt^uU z5m06FdlFNgp?NL(fn<qAp&NF2xY#N&d#9raD*dU)t$!I(eAj|ALU|dT{dM*pcfy^| z4?L&e8d#?OzE;bx<nUs(Tk><ig_RJ?HMeG==oEC(pC@yocERai-;e*H{zc2jMO9*+ z8c8<0ghKip>peV4w3;{RjaY+)t7`42dSLgw%)juiHa?G}WsCAtEwE?r$$>oK&(fV1 zdAH{a<SR~`&X7NONmICh3piD(DnVS$g)g~#IoZmUof@rMPb(ahq}3wi8s5hYM{l~9 zn_jRk+oRS;aVBRmdv%b1(K(k9!%G1o12j(?7}H%S$1=1NL_CGAb3c#cT$bZ0dYl+8 zs8;C+zF2COt}WwBQ_A_J8^~r<f(zHi%y4?WDvu!4ro3sNFx>$F2mH2NGcrTn0!DP+ zj`O&T;(F(gFi)qAV&L`5pcxtS);;Q3%-9?>y~pYyJ_ubpMag+QtasWH%vXHe)#Kwz z{|_Bu-fFhszk@4y+wO{G56%z@@hEM*p&{TS<Nx=d(aPLwTIMpsRz@>`%??w?YfH)I zWkIt6Js=0ZTo}g5Ov0<#C8{;~cp;_DswoBXlx(rX=$?WzRSKo0VuI|!)hZ5&yT`}C z3nf@!=HG)|+)aJBY@<}JNq1qC29q6MBp}G689FK4A8n;JHjBf@TF^cnvGOO-RW0cp zfP|7XrV+(oi5;xi7!-1<hvWQBaaYa`2m;{)qi4r?WJC(QTo^Xy@e=hl>TDQ8D2SYX z<WkEg3<0Xa#FK6A==h-FsY2L)WSSYeF)`3PT0{O!XRZAq$Vn9#EhtjvyTQ%xLBNQR z)0dWN<z3&HzQZ6L=s3rQIaa3^$U^D2nC#s^OC@2FPNv1MG60^pZ41#2UFD&@0F+9O zO7s)i;>%C+vn969ARM&!#A=R)Ei&+i_e@;{#`LW{LIRPd3E^}=9~*F?$;N(V_GHAf z6*h%JTxYE(5?nxGnx4>m8{q;1ntEm}AP-O;#USA<qJ_3Zgub{0gb3yE1&iv>JsHI6 zW{ZwyoHm-zXZ>L)-bFDz_AR(Y$4Z}NdG^7OpVO<-MmntcjNrU99VX!tMrrtR1+PCd zv_Ws5iiweFb<e&-!69mBTbF5;W8^lFXfX|@le1Nz1#^(OlHm6R2U=VR@HP=Td~^0o z--iN=QeOYvT!o}NFAG<th37{{WMWv{m&Lr}BV2b@FuJ<wN&LWmgOpAS3lQc)770rU zP*Wy-$U~R?mlp#W1qgYj^x7C{K2|=1k~dyl)^crs-*saBRI=yxhfl&ZuXWzZl1>;D zeVQg>+rwN@m3c$r_cd(wG?7+c<7vS>oVs?EydXIod+oo9CCjFy^jVB=xJ;v&rM7-N zTikGM&#IU$Zb&zbth0^g8d4WEQKoYjWj*y@Q&T{j(Vcn@B7QGRF`Z_zo!eH#tmJkG z^~#0Z=d~`fe^jj2d9<+~-BHv`KwTWQFGyJqbQ(ows8ktm46n#uzp|F)EjX8JEZXt1 z@`+BCalEzO_*K$>ca@av5Ndkxd)55Hd#9J?i^#6S8GWg`qI!OXzVPtV4`Y>O=5E(n zImigV%K6yLucGMDHh3l}P0K>$VZoeB^20dR4&64BI3U88r>u5Zp>c1^h!djo>EDxz z{|2&|-pEc59@`7IVL!v}8(i#uN7s8K`?&IDgq~qFmaObBr7aYetL+s;t*|dw%UtSN zbpBo2CHFX?l-+V3n2Xh{Z;wALF$l`(=2r9?&x&)Ikxe~pI0J!2nX?$Ks95*<DbFCB z<iPyjzXw=KD%iUI^%asc&Mf*oqw}Z@l3~uI*>E+7{KFY<gh|?oX-GL94vb9zNnoKJ z1ChSkzNO6*7futG<=0}h()UjozJtaULRjl~UMXp}pP=&U8M6Q$^m;SkacJDcQ|b17 zk@1M$<m@*21g`5gcYQ?<2FfmD78{3WtKA0D_5F<n3e!|x%%AgJxUtn3<5miLeQ5NO zseZ9<<{H(Jsc*}1{($z@wdv=Vt!xmH!%xUu!GD0?<ON9R+~x?b`$PyO;XU!9oX6Lz z&O<9#&+54(mnmrKi5z}W<8OK>VK#At-LA6kCn{?c9N%)gDDD0F$=8%>&67h!Hg~!~ zec??f8a3Zg%k^ztIOAp#9_mBLnm6J%sMETMd@Na{N1Mrrh`NhOIY#_)xGzy+2pWR- zsru?H=|bdFb2qbSx08ItgUhcT<usT`8K#?-`@Lf@Wz4?c=lHr_tv*IMg#^nAA#`X^ z_qHtScQQWuT^{qj^Ve_1{vJSo%%Gzmq51kD%T#xI;|`LB1&H!V=^ArvZRJ#^Nd?u9 zDCkRs`c6W{(yCS2+1Pna)MkaIkftYc*`c<=01}2WMg-4EesSe&GlkJ_85?qNogs3o zt{{Aj_$W1MLm-P<R>rsa;p&4SrzDQyoI99uh)j9!H-eVe0Zi<cu^+?Co1Jx*CkwYX zU~&7Nvqja(S<C9VEGHN7OW!G{Z`I}~v`TLp%!}TM{w<=JqUygn5}w<tgRqL5q&W8! ze^jT=+T@+lSI?b0agV*_>fFG?X59!2>u>Q$w{>~{>f<H~z1GR9=Io5VLI&((FRE_1 zSd_NQo8_MXb98u`zAa`BDT+yg1fZ$c?_f8<>?ubj;XMOzyPi)8Im`siXl``Nc6D`3 zHN{8hiA9}}+dNcCp;$Dy>%*-Ej<g3i_B4pbw78YF6Gql~owoVOMNvzXCSF?(+fts> zRO8-08r_0o&zFnoBNMw93vAPYJ8`$it{2<o#kae;G`vV?ygfv3{tYX+X8!D)PCr5K zx%<P*Vyxx$w8qNuu6|)>^??Y}(yDrd*8xO?FC$!E%%|Aml$gE!Dre!GY&stT*@7Y9 z?K{u4d+85Y6xkc2@_p31f=yvsZV$)|8Zn;x>BGYOaNXlJ(;)~jY3$(F$LAalwVTUu zUasL+$V+dwPE=|&EPkF--GCrJ$m-!)-;^B~ZjBXsesk#-^R?!4Pb|EGktJydvT26s zo<qEyIN5)YS0T*Wvz}Lf^n7cf{IiDe>1xV~G1oMb#==5GwL$ue&Ce^1uYO~t73dG~ zIi>?}!mi`?g67UH#fO$_xJUct4wBs^?JnIh>^J#4Xxgr2|FRO%wQ%oOn)7c+2PTKQ z6HWbENjo(M0feA(Sh$@H)uY+G|9i!;hkm~O*5Yg@fiPJ!2{+#?m~owmDW6P;5`Lu) z^(De&j?umP8CgdSAF$RwS(U~`woqsXA$*eWliHVhs(}W=tp}2g*9-@Uc!1p&Gae%L zEN8p@kd0OPRi}*QG`*U5Sd6V`Ye}bpi+K>txFkq44K5UoF`_uV73y7cvzw8bQE#~W z*#P0Ui_k9T#nV-cjJqcm%zTZF_<kTh<T{(=sa{g7_1-0=BVg&HlQFc+ggSHFBh!EL zh|SLX>`?}Mp0i~2>B$Lq>yqZ@d&ipvRaoS{mPBzig&8XtwB8?-L%9}?;!2|?-90@! zQ`+5-84*d8IH5eR9;l8GHR%9?VVSZjR0ze`m$+cwL$vvzGx)!^W>|UMecU2^$Sa%R zi{WtjqPsBjmzh&f#|B1OAaKh?uh_d7p^s9C%FN^JN-~`q7Y-d_nWAGSRi2Nyh$Es$ zy4)JP-zDH$o2loBbK^?XlY>S~+OB(O$8#SgA85jO7Hynz#wX*GR7wqNZzr@OT&frX zgoq%{9#GHxpm{I*WU{exvY*PU$L8C1Ca~uUc_2E7$MAHhPbDoOm|LA~;=1Q)vqLBM z-M7P<h*q*$kJc^o1uDx*<8QVT_d2Ac|IRf)=l82w-IJis)g*iy`D7c_i>{qR&AHux zSinBz^h2w0&iDP`u4pduI3Q~huX@v<B~YR*6nHsW`%823vc<dfHsAj93;TrAgf5bd z3z)~S(or0tjYOCNFxB4f0^kI@{b}G>Kf*4O*9WsiGoPNR^9mpGMN-e|S8mTx{}vz~ z(J3vH)W@ss)G2djMa=k&?1YN%8LCRwtB^&G!l$D*s2*stCjE>m!x2xQodGg%!Wk#t z_Wk0yjve4s(tzc6)%Zm&IGVp-{d<eQU2wJ>N=8!U0Z4lD!cf8R5DQVC?tj|8-hxd& z5>TRjgvErzj{jza?y85a-_97Y%%0P7((>Prx$8?fambIz4G{}Me2_;%1qt9|irEPu zz$6@EhNR%CkFi2zqe)$72GoZE^;3t%tY^ed!np5eaI-g&h5T2jOK%fy`Pk4fN4W?3 zFrRgZ%@Q?@keMVzRX-p*jB=q1$nr}dx8~eFGiVY$Gi5Y0%|zXxob1Mco+U0v(_RAq z7);m+!`L}o_Iie{)gAaw0KT`?D+T(NlOjJx4d@|Xpu=5gF#BDQY8xbGm)dHW5!yq& zAHoPhW^#AJ;*sz~`f61a#hIR|bo}(WjD&KsB@r65I}>dRKiqc&!2taey&f?w-){to zRMe#-7IqAJTz-<6M;U>W)WCI$34KvMi}UGqnl}N)Ay>?8Umr<;06o-WDKCDK>PDlg zv}UH*KuiuOni84ubm!@k2P)d|D8eWG%OQrU#|AL!Sv=@M8{{~A6KZ<bbc2*NDw~l^ z4uKJk(Qx4%n4MK-9C0AB6`t%v);X^EXoDpzg~rSco}42`5<eEugP7lhKPOmK3#(|% z;4<RyAcg1Pgihh>EEz$Qh@f%^#Dq_y2RayI$Ne#bV47KOl^L{~5i$A3U~DaVj&j?C z5+?9GnKLu%L{)WnIC}8v_!RZDDJ<NDq?!Z^=HH0q_e>851Ct;isX5dqgVtRm+8qFr z!*gzB#M3vVGcr?%ndi~qvvmB0Bv>Mn7E60$<>}#;=M5k?YyIa|)Kz^6(2#ITJ0C@b zvAL*+g`?^7lcI>2gT}Vsk)WTZqusC=0G>eH3PVDjY+!-JOcOjbXdQOmWu1=L?0+qk zKo5WP?^f$uXfTl)AO!W?eTm<t`Y|}48x=3CM?kvXGPzQt+p40uk4!VFmfKY`To4(t zw9IqOYbOq(2`-t5rZFEduRcn_X9cpdy<%RlG?Q)K^bvGU>fB07qL>_OnpSu1jcMx5 zZ5HnloM0vH8TF-%;5OKjUT9E^3;Y5i^RiPW!G9;Rl;Yhcbspi^ultHDlu7V8^F>aC z@BHo;xeA{P)n{QqXm)0T4ds+i#v)7Bdj|e0{%#)j%poimK*n-Agy^opM07KK^vMB2 znZlPh5^dn;cd1E}fl27&xqzpa?<Iv0&}VmJ9`EGgGp926wo7+)*f{o+5rBRK-~z)F zGcTA1a%sVSoZyQkz$Uk*xv$6lv5MytjAiOd&>mioe^|8~jn4clkr_I<62r&{Xgl6Q zxD4ke)S8gp?2(?7d3Y2rltn01{~~wg`pxTz^#y2-PlgBT)A3w6{f-V@myKM?@Has) zb>e^P8l?kEDhuitM#=2_w8V1fhoOYT^{``d!g(ZI{2m<FMiupjONH&my#A305D%dV zni`pAzYucP`yX9D@YHdy8|U~RAcIEtBIW{3!l@x>yurE;fH-><dG3Vh_pz#N?yW)K zGHee4`?>Z5%>CT`)49Z+_zOarNzIv23>aP=J_UoHIhg<?Wn>|K1~M)FB68&=X~9qL zUGf_%6!>)igxLo4d=P<O{R4v8e55{_p&#FUPK2x9YLS-w<y@kAW+V-sR0j9$`R;pf zJ4QD%5uaJ|-%hDySm3W;AGc!56x$<SH4?8`=KEw2vf*({+wR)XSoG4~jmUz7#P}Vs zwkbFifD1c?h&U76V<zJ>HvWdf<MpFXAv5*#zHRNKoZJ0v{L4Lk{a0SwUb(g5<~(92 zOSr{uAxa}78c9o_!;-@@ZPcN`>ltH@+r&csro|oFbR9<7Gfa|TQTUH5Rm)ksj$W#- zrnw>$)Td+7@CyLk))^MZ_+I+?sMHxQN&*+T!LP!Jc(v5dI0Fl%t1ZF@mT+ap;1HPe z?1M?aC<gU@6|dQ7Dl@SyBf1SH`t2;E>;dQX?%RLC7Z6JVS3a)9P9A7a_X!}}s7KTJ zFU!5)^vulQ1K9b4y%+LZ{=c9pNT`lY!i?Ufj+4xE{Y$fNv~vuz=DZgSwm35`Bn`jJ zpxnzehzC0(VetSh_HAzjc(Mgeq_92(K=jDM?$`y)g*)Nx*KxT3BgSKW@1y?J^~qaz z1i0Vp6fQl<(<)OBF8AHHU`f);uY6c(cwTPea8G`+TH*|wO5{Fvy56o#GiGyNVYb<= z$?Yzij#o>4AF#a%omg+b`XpZk%uo(E6~EA-BMQ4GVVoST&6@Ls)2}=IHP31DbyQ_n zHm@2<X<{!(pV_cF%7SjnU-XUK#Qo!|d%^{rH_|&NXE&?3K3QvBq#E;EJ94(3VrM|{ z@W##gmSymdN538De~TZ<@xCX4G3alUGM9J35Bjpc0%-aNftEvALsW;f#P-2NsShLe z0{2c2CbGV|v>Ks$=JUS8%lg=_|4fb!zI_%|Y3LMinXAdWW)jsVOoXtm=IDPo^2*mv z&?Y_C29DwpCO{_(!=DuebJANT@^WR0bp)Sr$z`Fw(BEt>;xJsvTIb1OJDhb-(fEn+ zcU^^^m$+oG*&}n+WRoW8em1?qCB}{=+)?X!1lUO@`50Xl_a;{wBIs{w&S`itB*@8M zNZ@r|8B^5lvy{D>?66PZ8inGNvqt&OrS`txyw+`PL@4O^C1vCC679V2oo^oMV{51) zDd8@6gJs{TTOWST#l3csQJ}I$-1oKs5XE_F&-Z_d>W<Y9(DY`KzB`^@?(rxzSZ%Rb z)E7&bt;t|*hnwoJ(!6<$_M*v7#@oR~VeS{+Ukh_uXW8XArwTHashzU(4d<9SE$UfU z9Y2)UP$44dq~o|F`@%QAATUF;0RNFw_j8&|e#L5AvAd3{=aAE*eFua;?rrn;JiR7k zw--j+OBiX7$+d^-LmTDc(!e?;No9n;Pmeqz4EJ1BvMuzIdazI}!v)N1p2{;!j?hZ* zV-g0y&Qf9Z>6!A?<tbb*<}2@WYF|y_y((MR(r&G(_NE9KI-C9^Fl@9UD9~`bKWNrT z#P?E{n^4fBuG9s&eM|H!{P5jjDvP>P&vK)mkM2?%2hlk0ukOVYKU%<!!yo&#SRDcS zo>PUXneS|lgJe#X;RgLXhv2qF(x}miN25BQN_;OTNAN3ZvjzoS9G<d~N#@HRmV3`` z`Ys}8zoi-wa=13^T=OO+S=Hc%G*H_tl`THdRuuiJGw6iz-iYYtO%KeKVyDKl(v~;k zQGGYK40CFRoD3h1+q(tU8h=L_qNTfLwn=iSa=FV{HZxi;o6V<_KYd?q+50hn<w_)T z^yH^9CCTK!25x~NHwGti?3D}N47}Es2yd4Ws=?cJ2<S@Gw9v4+DRbMEYub%0rb!2X z@TudV!6+TDo84ZHo1!$|IB``y&kTP@K*qc>*F66I7ArtP6%V{pH8!q4Cb}S+CtSXs z`ZUBkM0z@a(rnLiI<jSL`1W6Jd1!{#D#!K9gZXpmYl3V861j<**S58{og~tvMP`x= zt||;uocF{caDzfhD++;v(J1%PA<L5{LtJmytKC+cBq}|=M6bBZNb?$~08*Cctgo#^ z2oy<Rp1h0@FRl!elkYh>wJJW41O}voZycH^xdh}EWOdYV#yDU^BV@P@TF%)pwVt~b zl+>lGG}Ydmv}iA|N)L`eHX?Dc8Rdp%ek+(}Wm6P8R(CwtFq{O_M~(!%bg)t6`^J@A zl2Evbe5&9im8pH)_%J{B<k_$kmp5BfDx0mR>PLl_XTBBYS;p7b$Yt7UC1hlpC9nM| zt{vJ9{#Ncc{=}#drE$TyMQ@k(l&`-n``nYEk_U6c$5z{yc?o>lvD$1W_<1z({~!*k z#p7Y&-jjB^Ee-n8b%RfWWcH41u^WgLiSduemTegf_T7r(^zyw(2$<_74X)9;N3(NC zXP->M^~Ab8%XjO#Z56QUirYL{U%9Wn_Aw0NyE!y)21&=UTF*wNJb!1x%rknA^2&by zE8oLnP=e5Ah9e1Ftva<L_TknW$)?|YcTab<jog>laXKh&?S{7~$3$pFVBYRghpobb z9e$*gaKzJ}3SK}$&6|=T+WjB-2`;pYy+yeR7GQDLR~~nT*!c>1Ubl6t_y>MHHQ(5V zJds3FCfvl?UH_S5G);s9K+RB~vXT^GbO`faic5z+kSf0IXyBEa9}4_b@6cgmi&OHS zc+1<rSeT8!<ZH9kaj~O%AUc$2nUw@E1Y5t;xSGbeevPn+w_;w}c5LOH_xjlP(L|m1 znJ*uOQWjM~iAa_59koA^l$QN5Uy*As%eP0Zbk&v2^@@?tu^24ItYP<#>#frY@(2=J zB4TW1UWq|w4kCRVN3E&T_=4X84MTrflO^O<rH(JYVHRw9EcCpv9-PQkhVM9+LPl7< zxr6e?z2VztkBTrd!lO%8MJH;fb_If;>YTXWxqa>9q>zxJwSe7neuRZ&3Z?_)?-RzO z%S9=?BR;5JU|-RYanZwqC|T%v;CF{>`@*47jM6oW6VpwaUj?3*{+!BVX$!3%K2WPq z{+`FCc#2iT)wxkZDfMuSZ<A^+zL4dsRh3NpI;EhIS?ZZNI)%Z<3rjp6g$4bbJ`OK$ zOh0+DplJJUBfr1MCF(EhE&EGhX1A@2I)_>eZV!mZRR#&I(U=PoLFYqGpGP?S>k5kN z&E*J{>|5kB-)=lv7+oLUnNU~t6L!6^N?dOEzqk0Odc8yJ$A0q&wrgD093N$;<Da4a z=38G#mg1`YS3kY;SpQPOvkiGGpLbk!-9cA49{1-$B)*hGuQO!YPv$$B3w4a@Z>wh* z(`rOt<F6Szp|1KiOEul;)PF+$ClNXPhtbD&i22;S|AZp1F`f5J`!TAuV8YE@V5}Rp z4bTL8NaB}-ZH?d6eDC+T?Q1G%_|CF!59(eL&|sAk7CM@^TLTtbn+r5vT^9Gw-k}rY zV|RE~9u*XD`n;h((ft<4>EIf^7jY#m@^$OSMvPb<L9LOW8Itsg-oh#)mu=nrV&E4c z7`rSILFT#%AQTDuV(H6PX5R)sC14HQ@-vNh&IPYEaQOC!^rdlV{dX9DT}bWbN$Uk- zK~Ys8Rw|X?h-<vXH4x4I^R<t??n*pYMCFi>@_(0hhPZDovX4;3HZJiNG_+g_e4jn^ z!MJ7npEiEPaV5=L0?UG*r9FE5y9MKm+lT#1K8wQ$Ol3)es$hpDXYVd$OPiF3`AuKz z`S7P;tmGkQ2>y+(hlh?n?A${q{iCyE2a<)x<ROzB9R%JWNs_2fe(FQMBwNj)IP$h( zvf=sUAK}wn9a;YY?B52!%Hh|jc#0)vxZ97-aBcvT#Dpjvvi%AH7y1mHN^(@^1M^Ry z1-h*tbzMtxeUiDlw3`l=n!0IxjE%0&k9V;6Azq_fJ|v3G6jXrtR}L#!fb}t1Ca25< zc4``LWU$wKXh>hq<g>~w9~w=xUN|~Ej~r&+b<=~8U++;HEG&N7f-x;c8pUrk`B)`G z130JW+gXdO3Gd(b7Xbyn$`3i)7>>fK=Kho+l>Y}U!jPo#kiUABSzE3);uytE$ElM^ z=WEs7MiM8>v2v6F7HW=ET}v=xL)J?7p!)p)SxI{==S=q5aHm3-WBfE!Fc<V*2&~Q( zw3F;GMTM1PhV6uc+#UE)rx9Z;_S#2J6q1-^X&y+!=yiP?j__N95;U?F?c+yVkb%`y z<E2_xF<7||935DheogWLf^r+k(Tg663m;TJsxa_5t94*4m^6&d9n?Vw=iP-FRITRs z*ER0X+N6=EMu$WIbN^%Nc3QPH05U2jtJBCDyKuXI7>^?<7scTQ7aQ$tuu(2ZkYKi` zJSdMD=%~kGA!IE&*l?GmoH(R;u<CN5!5vfQy^@{K2G-6cX*vuk%#w|a2MwDCBo_w6 z8RnY(>;NIehwD>E^1CxHd~gJonzsX5xfK0M@~P56X>}52l%($icHU`_{(*ZE&L{X@ zHq;ob1*}T87g~mcugo<B)iP1)rj4&=MHNy$sbmbPL2zSOi&&P?7-jOmv^D3~zAoX# zcXd{61uXQ2r|XyIDxh`ITrx3o(9CVwZC4tL;ZP$>7{PE2SK)Y0V2PzFC=nKBC~b8< zwCS87H1@LG`AB)tPbh!<D=bMqUp!l(yovX2p*6>6XLYZOx0}*dBvMsJGIE{L-iJiL zXgc7xIJ+8RyZHIin*0?3>=Tye@<sXk4Q1)N;eD@~sKqz^4Y612<vl%fygPWP{+x=@ z#gZ-zf8Fv_tMv?#Y-%ZXZ+7W??RtJCHb;b;)crYUIy2`5c5TVMNnthkU32&>R(iwy z{O=K3EX4`~OZ<k7Ok}QGIi?3>HP&!!P^52J14HTrX<!cIf{$>+-YT}T^ww9n$`?}R zW@!!ps=?2kS4pM$3X%Ju@}Hy3X5@9YViZR)Zf-DoVgpf7U&S_}-h&bm1FHf=)peZe zq<h~0!&w!7Q-n(2CaGgA1Zg1630$|BV(l?rb@x`IB1ByXtX7FTfdtEonO9x7EfVuA zsWuX~1X87ebzMN(>eiagpc;|L#_sE{+ak|%4OKq@%hHCh$I6c>8M#Z+ti0WK3t$Hr zt!tq!!wSXu8%=UUx-B;}2{_{=kTQOw;+tYmBTBP!Q26qQlrmZ0V^Fu}Hg1)KQ)UAg zQ9Uo1Tf4x}o!1}rwn3`<IG?3KgJMO^Ig;uesdO6DKd$tM>t(0itvjGCJv8}Iw<0hM zmY*0bNr_UK!>LT-247#zh%KqQys7I4)-v5z4bD+XGuNam4MZvfOYo<P7D|cRd8M<J z@3!>B!15O4dpjg&yL7d*A%!IC2mTw+q_-!gw_hz4t)YhpYq6?nL&`Qo-7BQ9Y_J+( zP!F)h;cwLf)T@ejJGF(H44WT;!1}gg1DA&-0aGC#R@FArlyuA7>+R&{w=@8<I3ZnK z+fI$}NfKf%%V#c|OA@>kwI~<+B$yp5K7ds(V}M3vazOwgTDj-WN~r1xFeL26RF)+c zs`n@W`zp~6G{IaFV(RW%YirF!h7h(vQ~izV#E$BEri$2*Zqg~$S)3QeOd`!<`tqb; zTPyh|No|4TzDT;fKN#J-QQ{V@iXf{@fRq;$0EpUN=)L?jbM1+c8XiS&fKlVWp_Bxc zN0_S)gXs9ypWSMgwAoaZ$qM0j?!0I{c-N}3gfniz?LQu@C2Syc?)-W2`7LQifi|SZ zv1!eK4Wxi&(crJIK|i_Fq5oMA$sK<+%hj8MUaKVdJ(c|zB$eh?>$yyKG!ELN?s9PZ zpWKjg8dw#taJ(eCP>f3XS7m&x(sr9Q;TEeFludpZje$rWLByMx>U+O$Ym|Q->b<?6 zVo~qEp+^9zq0N=rK!X`y+>}AmXq*%Pl~`io3Hz#!-TUuEwA!$Gg&bw112po4RSCcM z!^u(xU`Q*2fa*5MG>VYCg?O&URtJG$9F3bRI}Rjk4yV(H2lXhMdeykhz<UbV4Q_d; z41y{FB>V||rfCXN;{b!frW%BF>&|u+EJ@h{jCl(B2_m>JX#gC95>elPAvH}JSiaI+ zM4r-@4HE9WivR;k7GU{VDJ4@)Zg;5i6${i%0*@Y>X7jf8fnux37uC*a<!aL5VEe+0 zJ?r`~SxKnO(jL-C3);7-fgVa5+4bVsW^_kCV`JV`M+|ACo@3P-kv*Frl@^biNRR}Z zii_=egqsPJf6wK*Jv;ps#=Q-XidLx}RK|d1F%V2DML>Q;^Qk6qV5aqPK+>0bOwcnE z)z0bN)I*SQ=cp=4>h@tRYIHLZ^>pQ)L1ohpr7IL$X-lNmee0t=F%E6p`Soj7o%*Xd z4tC{%z*tp3knlE((cGr<Z1bhneb-=ZRG6mepLoycbekYEoau4Pl9`JrR&|>+S-7Qh z_C7o(PGyxOLrLesvS_QbX!j2)J0wJCpYwuun%Z01xO1@M*L@^?M7Bud6*WfpwAZ*4 z6~GL3tf%s<wqidhV%JP=i^WTR*cr_1!V$YVv72}q9}f2x;cjJn=X+Q%L!MwJnr1Fr zP8#XPDH;#(fJ_z2K?)8(1X72O0k5H8Ks+tcGdD3TQ};^mZG8+`89ik5wY3z)+MYeA zyB)1mOj6a>wVbzBSpDg?-D&O9?VkxN5_k}Qr|D7S_MxU;>B>`$mIv4-9LP5+xDPAH zz&RbeZ^B8q*>-oacCjN15x|sK_N%g6YsAW&;lJU{aZqwvS#b$>e6TgF=;*q3$sbYV zf=M`aQ0BY_+jlL%r#p_hXZ`CuuFcFdNf%H~$L#~@&(^jBZ|Px%)FCYmAR<o^#4A{< zRBlLhL8r{WCq|w^S7K5wUm2E_rwIP)juVY{fgIdTf(RK~qWD;Vo`W1Cx$nK3+QpID zkaM_W9>ZsxCf;1BUS6@BbjfG^0@Ff131TJ(k+{-h?f28I&AM2S>K*nlZF-0CTS*q# zVND;fZW}Z{ha)F8Q(uP{e170cOiE%7hq6OciwB%J)Nbm9d#@{1OPcdtp)lF**I1KZ z77xn1B&D=w$nzauSA$xcTUPm|G{%L0`AJeGJbWFvqrSfNBXooxY^ojn#h`ld78rV2 z&oY#G-@0eOdG(=N?gO0mfHnTG1^j6{p{-(NP}_9y^^>SKAWLlwPO~{dVIk4!L9Ywu z&>548E7!lT#DtK+L}4*#JQ$h-A1Luo^?t3|xTeN?B?ZU8DfzVE5JR%2q~p<j=$%lP zN|75*#%T}ggH5GI6He+Sd(8~g%Z&63S_*6@<7i!-_j|0jiI17VUsg76vJWYs$?BE( zgi&Q6T#G-IeBt8-oR|@iNXjrbz9MfSbub|Don^}2(38;RVw38MRfHz}8q4_*&3C)T zPz``^XySJ$07I!0hk1Eq-~wW>Q|Z5qhvzjWuUrgwc!)dtVNL78q0MlB8E%#_!yPm( zxLLC{s5A$9)|bY_SeX1t!42QWEnL8PX!e3l<!nfp*}a$N_N;@u3D<jY{YGy16jv<s zk@YSSHw=WodBpMiaQ6Ow$<M#Mzep<B@rjOaWO=goDyZ(tFtsjKX7@pF-Ct+KgK*P7 z)_g3FQ-?p3|8X=L+uzes_WAp)_1}c*NuV5L7iW(1X@0?eICN!LlN)D{nN%OujXQea zjy3^^N7nRy9N`2fqI=i;Z`aim8&NGAPg_i0rfJg+b+MHFtu!1m_$?S(^hd*V@*0>} zElPr;<UA0j&j!hkJU@@izXC0D1T{iudkTWAuS%L_@EH^a+ZJIiZcLZtgxCY!fCHJL zEI8=J8ggSLk&7V@G$IOn=V)kYfC`h^uY(gMjNuzdv2Y~dnaA0VNhA@NtVFaa;=R5> zY4oZ4VN;EseWfZkczEg;ySIg(2E5xE<8jB~UM1>vz-O#rVt&94FqYa*bm29#MF^rC zQs~_76j!*@h!1R8fOJaxo9QTt>YaM<uF>mJ#rdc=_vRmeftv34^}>VR779C-e;_v# zK}oecsCyAN1$Z4=+S)%_<q4sbi`zOrH31Nb&P@&W(iXPs+Ge0?1dtWT>y+`R>Qd^j zugh02v7=iTN^~|}r(L^vFOJlV7zYzwB@QwA)KVjC5xFYINt2?e#mYf4p0Aanc9TY> zL{_#Yhq%o+_8z_S80RMT`V2rt?UJ^(PLhHR5F$XZfwD$TG4mX);4{xRFd%v86OJaW zPI3Xd7Vp?<zA+L;HBmLWZsQ8KJi^QTH{EYplqIw`2#^wI?9085z@{i5Fw3eU%1)z! z4<H*h7p)3Fh*&@<YkNSF9KC5s$yP3`Q#*0L`HmvW(PPTetVN~lkKZ>QqFVf322VgJ z3sB;~-4Q5oic!ASMs~1m<#k^3YkQGfSxZyIs7UYM|H=R_xmd+N_k45adA7YhZvZYl z@0@;ttVky17NsajNLa^7?E3u~=@Y*xY?E~5;q^P;0ebqIxB*VRg`V&~Iw$|~tPB>q zQ&@KSy$9RsI8|RHug*|@;-Q|7hFJm~IsbCAYqhnRwft<9N@SdrNFegfa;8*Of*^p_ zDX8}0atmTu8*e<9C)EO`#qLhG3aaH1c2Hi5*Q4*%8^vtjY|}G_M>$CP_M=*)@P_6w z5g@!A9V4y!ZoO_^`eGnSF_cxV{IM~OL#LmZ!5imd_Q}y*_xY!S7}9s{SMH+Ef?utF zTPQ+HvM}oM$r&w&wUr7E&7Uc;mNfJF!=3rBMXQ0m8#eLR_xY7tTr&9VRurfu4$BnG z3yKpIui+?RG-?Lq{*JG0R<{o~BE|l*F{e}<`Tlry>Seet1qSDpI*mx71_n?HV4^<S z8{pDUUSqSo&Xt}m51)!8B1XG;+0IN-Uoc0**+^U`%B8ERF!Ybt55M~V7}&yLH_1m8 zvVu-dC};=}szEJ^3D%$%AEMmD&1`82>K!knqEGDH<^kQw^&6Eo(?_HLE+Su5=;<hS zF|!w+3g4<=qDsG!)F2oxr|o*)x^Ixb$l9zwdk7%MhvJG~Ga#)m$GAQ8vXbkhZ|Kl7 zbfVALCC1kxBrrZgGNX>MIJ#RJnb)e#Lg*bm*Aq?VYd~9)2=&zys8s`bKVN3~8(a>O z1DL841p;X(YVs!{Je>u=;>~qh+wJUg@CW{+#w=izZ;+V5W2KSpIb6qkbC;sP6Z{`V zSvrQdePSM>OaCm+DmAsmq!l7GtH?H#ypm2#$@{qmTgQ5SGl;2D=w8-IhPlM|=BG-A zX8&=^g(d;mdA^2MGB4Znk|C&a90v(wUHU>=t5OPwIRybLTBMh0uW7ugyD1KPCUwJt zrr@B#?$rho7>!>!B6L=+1%pauJ;wP_wU&a?!HH~#wJoOZC`_@n6pl9?G0H+rb-0x@ z+9}_YP)_e%Sd;CprgE$Bh#hi%t&sF^QqpnN1%hMG@ka!#Yu6!328GfBcE`tCQ~j<D zkCZ8xA#8unP;s#uJktN!_CJ2JP$#x({`47VyLiWF)uxia-`<!Ve6Aat{HAFEs>X@g zx>83s(HFsTMNFh7IIg6TWzl9f-9_Y;<t+%wFtI|V`lsya$yRAU-df%u!~fhl)eIn6 zrO#TLktaQ#omN#2lX>J*kmGh0&H52*mIQPP2Y<!=@!@0dm-QTQQpg;SX7zg1`RcC3 za1m>|+^spilVqy`jpqRt<_&dpc~m{ugNaeWp;2U}m_t2m;k`Bd`sr7fSKEAU%%0?( z_IWCj!H+`?DGSVwLk^#Xu(P^R^x1)UMTo7<N}!eMZ+p_}7qlt+w%PCY(;H52q|R)* zskE`r4~7i$`<sHr>WOyGe&lGd-;fTK3ce<P{<V~s!43}Brv(V{%gDWgpWib&)7w*e zr(H-=$^RYGjntFHXIe0*GKki^UqFgx8@u_9XBzj@-<}9+LDY0m>A6m;#;Gz0Xeny( zC||$JX^Y3J>lsS)Ax=M#c>9yzE&6)B=Y8Sy5^CMkXVlR$^!SZYE}rRhx&5FjjBbL* zy_~tz!#D;T%G}aT_$1&`iVjV6Fh6{t8>vG@U#TE3fJO`0e{dA?MU;bXqy+2K&Dv*C z?-CtZ*uOzPnQGklw(BBW+^zz7q_{s7D&AqUQ#pJuO1D$w41440=#nwP`&o_t9K@9n z_l}%vMWk&DzN2e&X$O{leI1^6l!^1w+kBjWaay?N{dQI7p`BXM#aA~?f1-QNe44w^ zSN)lZQG4cdqzy1yP{){RX=zIYh}Uh^Q>`yOHnfxbdUV0auo>GGA>UJ|j;Qr@+q;Yy ze=Eu+QbJ}p1-W5|n#-bZo0Pr%;*Y-|e1l#Vx;j?7gp;%@7$>K#bZ~BJg#Zk%93R<* zvlBKCwK_O1FVs!$T<H0L`4LUD`XhZWi6k=1pt>Enn!uBDs|?F<xrlK^2%MNdU_+ne zaZ%zDUc+h6?q<F`3OFzrt!0j_T4|l?7K~VttT&|^CrR@*%z<%ys4Ob25)Be;s#XZx z4LDohsr|qZEUUVd92A@c)up}_F)xl}vhZf(*If-C4`w5Jd(L2N2Hc%ck{2zQYu*ox zdO9Sct{%Ax^n4k<y*<2CQd4qnDf+k7cyb28J9vjZ`EXI{iuTB6<>xBM<ZJmtp_|47 zY<XBJ;<?p`<$me8nSfsNSYfQpsRJ}tKGNJLUkV`15}O)r7G-Y!vH0=e+lyHnUK9wf zL|^6&-4fJ$>03PW%t30XYjnjr&=jp^A$fTbzH|QOC6tPQqv1ulHLdAvJ^C`z12HTw zQlrS=#TeQMLsYIwE^iA(NKc*|?FsqMkCH}3OT7BW6r}#?RTD7W_``Vl`5&6&_R>1W zjIx_)t$K%^_RNrS2V_*6m>~B!@MQ`DXZ}QH5m1MKk$NfjiaJ8yOFx%l?zZq&Z+v~t z?d-5lVN2ggij>Z#C@w5{im*yqd_f0(l}=&&6u`Z;XhWQY1UV4ipJvhLLQ2_~MgMDM zd2WB2Mw(}<c>_|FY7H7>8<Zk#O7C86#p0CRIDv|EblXeBD}o8zF690b89HSkUyWC6 zcU)Uu6K`em&*4kAdck0B!64_S%?xxWqq%sv6;W%99b@tYN*)Dp!UK?@1kSTVe@b^D zXD~8tcjf<a?bFqyzSW<bc48;9%jC2Fw#b`39s5&Pnp4JkNxA@uEzn8BvfghjdKV@$ ziXIqbyj!2_?;X4TjUc_dq)-_r_5RrxNW7HClr(ZZH*{|o8OX=1)6iMi<xH36&)?D8 zRFG;}LJZ=0RR_jNsHRz~C9Ybo{C4)5rdniR>+LXUrzj~u*I%2aOTU*wZo8^14Rdm1 zrhRggIM}2rq5Os{S2P3O@JZioZhxk4pW|`$AJ5=F9@3}Ar%#OulH#@0ZyJ(hjHIWH z%*z!{olhc?&+Z^_(ap+cPh8(fAf35D+*&yC`yXLifx?&Cn$>G<8=a*rCJ-NqocbTR zj#=@R2`c{MlH{QmHd4I7X4w7QgtcJB=WD#Ipw*t|QvV=Qq&#unK;b4XpaK==l357g z?_u|nY2VOxrkzzJZqsjAz*OMsG^UV8Un1%?mrP@2^JOLv#1k>tIMIk2*HG%}C{=7z zy0ZC2G4NATsPy=RRP`QOXouMn$hC^MaUk+-O)IOnW74Ie+=^zZoKGOUyvPn-^?;D< zL3KS%DZX<?*v(K5)r`Tmr${TNCJAx>C0etHYp0rP2`|Ocsx=0xpz|6CO4Ab{Pk1)b zCT2W*0U`ZFwtuD@c5!m;=82;bQl;&1jTINt(q1UgC2|ZyWpJ(%IlTh-6$jWIh!BJ{ zvO6AA5ybne0CPp!fNC>+^j-S*CxcR%eE>ZGm?BrdNh4Wf)3Q0|mhQ@dI2iY3E-)VQ z;Upzcz&UleQ~+Cj4G#lgUmFnDui<$TcZq2QI%%Z!Keq0}tBEfB7yS^@AuuUa0TX)F z(2IfzHS{W7C5RwR>C)7M8k&Y8T?oC1O0iHiAkstyM8qBtg%?G^ij|vn*6*Hs*IDN; zm|0Wze)hA!ALExRms%aPr!?yJQ27~S!sh~zB6Sqhh=?Q=ba1|>ZhnIJRl^V>B>j+- z7A5~t!$N<aTD*jv1900!5hoJ1<ha<v5=;cLPk@NiHOC=KV%Bwxe|{z()+4vfHBYaj z?lRDpOnxbe6wnO6({`DGDU(Sv5DPTlJbw!SiazEdlHC+!OH^$rD73uDM+)d9fa3>_ zT;bq=01Uvx-Eh#E7sLwde$`oRF8y*KUUcsdyzviQhRn#Ex)6Rpb*q;W`(Q=1GTrHS zkcQzhL4eB>k=NY2d<B^XpX!m$%fme2VMZ7zxnbm7w8%11L|uT;NR<XJ5O;6_xCf)E z9S8TI)JQZ@QhCprf1jE-Z4OEW-FCWUy6~7h6>H8EZlxTZ=Z-wEq-Hkm6I~usjgdd+ zVNuHPD$sR(9Y81t068XlIe@rEAub1q{$rr5NxriT;+`cUk`C`8$12vz3?0O5bT|mv zy&?!cZ*<2hQ;|?8pgimV3J4u}1QCnX79dK+!o9T81Qk&6pnRtXXU{{1&>#a<!a#js zU~(IKUX6js5vV~=9!U7Fx#8iS1c!7%_1{Hj4##;EDb$f|u*W@)YT97uf=#4#WVOIW zo%G&8kQ5{iBm`^9%EzA|K8`WC|6LpLWdd2w6%uA*-tk0sR)|IdytP5jK~ZyLKF{$d z(OrRQ-*D$x&3Bj;+rza^+?O79QjuN6C3sqAFt&_6-{L_k79{P_9qG|CZ=L&2e78<B zZb$TH5|xYX)e7quiI^#_kQ`msL*R62{5}DS$QluxU%;3TClpXnB}5#W3KHmn0+jz` zf@1YBz(^d%mM#v?3)i$>XqEs*DOG#E3!EyzqWMRe*SAUgCbE23c6r}%1JcX}G2+v- zokhU<)($c&FJ==%Wbz*nv0HCMD2T;13W#H-pwc8gmas(9ZZSHD9QMW5)zMnrACtA+ zmM}$JTq{NRIH{R~604j;i^%744U=~4CQ@ye$HdLoW4_5w-Y1>NRB_#ye$XTRkcjC; zW{X06BDp3n0R~onw@^8e$C345;&4mGe*yxpf+R(Hw5&z)#ub#90^VB~FdsHKK*xwP zF^X~N>veKdbbbPkhzXN?$Iw|m{rQNv2x_EPW;yO|QAmk~PQ`m-$yD&{rs~o*F@hK% zWgsHF9Prv3G`JVu#FVTCgvoUvk{)P`A?*n#Z8vpz5N^LK*ekZ2quJtUq=c|zpeKmC z-;s8&(|tYx_zbEzWEd=>N~<y@Ksts@!Y%Np5`|9o@={5gymfWbLJo0T6c|l=38vXL zO-cD%wAQO&ew7n<^2=~6H&=<}$d4SXub6bcKGtnPlwx>HA&Rs<>i+OT{~l5Qki6o) zW-${w<^coONXo|ygA}TyL!Gsev5qtqA4J0QDhLUd1wUH~Y|_eHPnfT2D7=f-akNvo z&l7eLv3<b_9t;qZqi5dujFMpzp>(agT%-qG_6C5HrelBc(C#<vB_O4TJN=sM4j_c7 zgHA_Y{Pb}|iSnJYuod$63My`0U4n!!8jjIB2){kKIRR0Lj0N%1@8XJy46deFn)JF` zuxw7ioNlr;6&=HcKH!+4%#p_pXs>u{&xY%5EBQx>eWTx#{9b##(f>!p^^(|(9i*7= zFkxqbi)o~bIZT3zOYW3JC+P;g^e(LYFrICMcQeo#^e{bhPxGsX;@9}^Srz3W<;U{z zZ;{O-?IW0Fp0M074qylosns>YBq$S1wM>0jiKF>~GR#9KslpRPy!a2}8qeIDPiodC z<c*}R9<9SJGw`ZQS9OPL(ghD*(W0bC|CEMeGls!E&qRZxaIZgAorzRbZ5NKZF#a+4 zWB>9Cg8XBX0NEyukTNM!+%^$90S5wP%PG<eKq5Xcv?5J3H6yj43?;JUFhM~!GK9%Y zc7kH^r4QPj--|w>+A|<x-gN{?CgujGghZF7F-89!ADo+S7H@FU+YnHy6WuXk;;#@( z{{~>>e43iDvbK<q0L63VJwh9uB~cIm>`huXZ2z!y$Ias0k?*}S^T%sHbnIrH?fZUA ztiC~jf+^?Xte4QQ7@}mVX{0g4W^bxQF8N?)_4&zRA>pg0BoS_a+%u{)kN(D&sd}Ds za2F|1OQmiN{CP`4`IKdNcnRtX2?Ye`KUU}Y|KSg51o6v4L4R}?OEn^n$p;1Kh(?0a zl%Xffaec=VV%fBn0Mk0Dz~{cCZ9tT~M8CilTA<4=^74Q4Ur-}wk!n>!_svjMJ%#%Z z(#%y&P}pUl)G-v(t^68ij;`)8Uip*q{)Llgk7(9gv^6utuwQkj#9Va$eM#B+V+Sr} zJ{Bka@tFORRg~Lz#C>t3m4OC`0cuptE5;D2UUZWe^@)gq2<*B-a7L4GARVqizIh6B zW%$7nX$5V`7pPOPKmE~DaxzAs0PYsI1Wy$QG++DLk}OGqS4$t<F0<jh=?*TT030E6 zl5i;lZO#)FreE&uP`j~@#5q@}X+D40Io})GzFH_ZbW!2iIrS_6`1NaIk|JCrL;4z! zBR~{c;7J=TVU325MLo}e_&yIrQAJi>i!Lt>zwN4q*|?Cz9hjmIcs{eKZvxegC$1CR zOvzoPG8$$DkNdGsbg=|;99#edxbXS_=m*ARZKLE)%2W^35up;}EM%(Ec4AhgtuOeM zrj9OVCBWymuUO+SrB9qc*$0c#QonITOIn2!sV<N@Y`%GcV6sgk>`Fs<jK6ef{b$S; zACno7tF#J#H<}}EkytMmv?P7jZt=B;X$y%ewnD{y=ZP%qBO-{y^Wh|NLxcq6v=~HX zpP(M@&@9#*DRfp7N;5reC*Dj!#SjqyG02zZQZr&hp^Cp)aurQWeZ0v1t@T=8AVFec zT{ly7DnRZXNvcyojBUYk3w3g-69we+l>sO!%tSSmM*#{Xb&@AqT@|eJ#2p*2t<Sfa zorVhV-b6bS&490KZSLf^)y8Um-SnMDI*#`$^iW}KImPeJNgJp9`h(JIovE|TlQzvQ z;Yk5x)GY@!n{!o$^!$9crZAxvy;A@!r|7fWMg4A~)K<OqL@gyBASMr})?4NjNgoQM zZGu#XaucP$Lffq>KvUq~9E+Ss`;#io>eS!fBrt|yf6Yj1ZG}f1FOp|V6mwjafr~oY zxf!kJo88YFMfyELFl>M`04Ps$69q~JLc71J_3-8@j{pRf-nYSysz&KEC0L{Wum8<o z@~iE;ruL}xHYq-*KFDF;sY{-PTlI|?KtDCEcu;ShAJ3LWz(8DD!TMZq)xfQhrSJqp zlT~XhNwd=c6d_r-*Vy@;oFG7wW_PSnfb62KTVU;?EQ6b$F^AgDArv@KpC=4*zb<9l zq_Hj8wv<UKd)Em<oPyIGJ{}PR{f7)<n~PLDiqZ?U0SjVZkj7<CjdoefvwMplVwDr= zC~9WZ{J8#kMhtql<}dAu(@|UFM-<9ci*nS;gA6LOC8aGJ*)_u7z16a!%xz8Ivt08f zfNArm8CnO|B&Y_8bep<VF~uC`ir%hVy)u7ucHZtn=uxLQq?o^}-^vQqkv2W*Zl^gv z8FuLkS`EL;cmc^Rh_$>vCzIIGWvw%}Qv6WDJAw{Z^xOZriIhHSy{jUfU=GSh{Q3qe z7iiW`%5#|T9Y!@Qhvi;(^<P|zN^5yHN9z5xVqpW|nzprFg(R)=NX}svT_yL!LGZ|P z>q<92fF%G(0VSu<dy_k~t0K;958I3?HI429YL_z<9j$TDF^7hCqcT9#yLk(znS#8S zDRr;$xswj(?p~6Ky{6!}Z)2XM4g7cv*OI?}y>YBE?&ptBH*{s=J~^B@h-{207PF+! zf0g#OQ%mC*Ih$TgP1^%B$Gyb&R`MQiWNQ^Vf;T?d^`MoWe;wv`$J{>z%E1o$&z#gX zy%6mvi;sIT-VjU$#bJ)rnF)=(4-(&4T!=227Jo>!d8@I+M3kg<EFt7{#G!AbfR;GR z2-ertog)f65U?$~LIz5@RFi6yqpEM^=<>M9av6Sqvf6!0<)ZMBI+gFrT53-JOraFN zmLI-y`=f-+O{oWLB5uAs^|0}#Jvp;-?wqdd5B#$HzH?`Otv`hRbk&@#doP=4lw%`X zlRi35#D39Ew)-uujhg;S#r{c}`223fWF{!hPblfo99u;;`fX4c)*Pm+E|8UUO^`4` zgoT(;bB85Ah1%IqQh<fqH6G9ddESEIo`u4WqgqP+b-SpW26*WWt)sj*u2Roz@Sh`@ zQAV!SE}oB>-_)XW<^%#=gTL)EAdh2G0&Hc!60?;E0>Y<fELx7&XQe^w!5;z?t7ZAJ zz8%8-<HpQ@I7Op@3Ni-p9}rXuQ$Ek5XN8I?7MM#fQbb6dM`}=u|A`mYvM3OR&)$|c zhoRcfRw7cMeUiYLhC9AZD{4@I-GG5Ls8S>v1k;wsJLgQfue*qxEuWNq$3^H!l0<D2 z@5ogvvQF!tG)Q#GAb#W`53JZ6fEgcEl&6-lXe073?1;}i-sSKP$zwLW$3K~M!6!31 zi3%S^&Bw<2jW1p%P9L>IH#F($R2E|M{4@6lSPVIBTr$NsOtyS&zUdPhadf|(?eANg zH_wNXgq$>J6Xw=zB^j&TZ4s>&Z4D1MR-%*uS{k;-CChYvNhEdc?Ow!IXSV639i^Et zl$8z>HQN}?*77;To`OAUr>5Zz_GKFKcagc%Hq$Fq9W!;b%SA61lLR!7#1U`sw{RNv z^zjfK^04OlQDtFsNs)KHpWCL|GCYmuytk7*K=~WcIxC;Y77ugn?z{~uv1Ho54mQs= zc@Zp}!>RrI@#gJkEWJj>czdIZT$x9l=q9b}#VAxmj@69@xdL{6aDS5CNwEaW`wH#H zP~Ce`zdppB<`wUA{~~{G;yiK7Zc;YPyQ`EwXRTIoFp6T!J_F(A=)0c#3GjDJP6I%& z)uofWY!*sdFL2&yAR`Yv#rs6>Jz1<k^GY~+pqS<*D*EQmonL^$t-#U@V21|*WV-g| zjy91V2Fb;Xq`mqomqEy<6zcJ2bM)Eu*xg^>86$8x6@N&0JhnXPelN1}8q7VFVyW<z zA%E&~yL$%F(gwAB=*mK4$^qu(h>)t{v{yHj(OOexXM~nZV5d~i{tj~rC~9EcfGXAY zzdvNUYQ_4=?7yCasYvvkGX*Fvu+WS%=;M@}YQv!pcUqzS>{A=X2AL-B^ewpj(-K<R zZDH4p4CEZ*HUTFei7l6!Osa+7!Qf+5&+APMU$S3<tJrsY%W4|q#Uxg)>l=TRSoCFA zv92pM>*XH!x^x~CdUjADJ?$rWb2aTnQi;;7s2KhK+U%}K#vcAEzw;d$twuGnZ%ijz zDvt$Zm|k-;fNJuLS`=FPHofpQ6sYwXi6d@tX}8?2pzMD?9?XIoMNV5l9g)LGiI{q~ zkaq{=aa6V<Kq=Foo>x-)P<(6HpoFS9F%EEKM(9g3x}oNFd{>+Z+}-^{@>-wO{^B%s z6Q#4UaZW4#c>B-IBB%6G@BZ<!RQ3x5E?`3QK5k|kB9~wgsSM)hFQw+?Ule$d{IUXN z)NPkE-0eG|p>u1+d)z(qFMt15cB-JZ2xktSPCUHtauVk7%epHtsvxk!h*%R>EGA?c zjIsUjPfLxIATVGFcb^VaqhC;;W}BI%er&{B!2lN1rFw_AQCjYN+01!T!YpgG8aiGa z@ha>s?}HT(cNYoe*TeN>=R#0{U~cbd?u6d-->-Z1)`X`mO8Zz&if^!=-d<4A!=fAl z+PlrL-Q(fQ{69S3&+!&i*wZy()7z62&Ppd*n^j4)F6l6dtnZre)w(Ft8;v_THA3d! zYKTi757dyN$!;eAvd4edZad+B<<DS#7rZo;I_<pq^TVs@4D?GFh5zL^diLm({$pXc zh6S<6V=XHok8<)fxt+N&dO><sYBU+e<Keo}<wTD}b6Ls4sI>i;z>Gvsq2DejJAPK{ zM&hdUyz}Se?*f=ZJcx|yQ%|#{6P{jyccYVmfE}Z@Cy{Ed&@-MXqHFkobpBO?O?T1P z6J++S;;olc*y4nmVq8*y=@EkVzp>D1H@Af?uy95^oQRp@Swoj%JT?)9<V4fxMB^na zi>tu_&!(ziq=z-S1%TQX1W`31KE_{5+b*Y>p|up*GRIKs5;Pv(Wn-8Ewq`PzP+4Wd z==Bqf28Bgz$aNi!&F{M|xF3j~5$pHB(Ipg=3cda)yTz|cumG)_SXnJSjITE43>Udx z7y-=Ky|RK;^1^q%9m`|wK64OMJhi)QH8Grn;A7hpZf6JOksqnxNf&iD9=t0WvFq`! z+9$Y*QD3oAoZv*tf7X`h))ceZ9l@(l@Ju-HkCErsns;_7Q@@LzWnr|goJC^>8q;IT zzN(Quab9BC_pMJKSU%=kkJ{Uc;t<KBAy7Kkq@mP6!xBHEgG}@We-0;PkaLD~qTM?s z*-<F|HY43E1hW%qO(AOy=NDOn<B5TD+AeC?JcR|^Wv@7BVcx)TwlzNmdj{&7?bqbS zG$I+%jqu&^^oADymR`G;3b2z5oNDxW{kmQHmblwcz<`sM=#4BR3Y`Z~4oyh7C3u$2 zf^CWCu8JG{7m=|^-WX30pFz$joV~=|a~!@a#Kurm9C;GdF)77uS{RoS#46@-zo2G+ z2!xde80=eyK6NL~ipU1I_yL$8!nTwua8h?k2IXU>RtHOqjXyg}II-#ZtI>iV2+E|m z>d|xcwRfGQ$U=0^G0P-tT;w;rkbQc){%c9RUxq6?mGo0A;(`}quVl$Lgy<k-*Td}q z-6g9mF!e&?dAY@duq{u3n|nYY&S;oDw3d9(yY#9pfe=MFt?Z9vMMkO-f@hr1iK~as zFm3BC%qif-GK~Rj^3$F&oCVHURrbg5nd^nZ?Ud-j7_IF(q=F6diLGh54Kk62%<P0~ z5p-LkY~GV$-W=*AAi7S4Sn%vQk8pEJsoTf3CyZh*U&uAm(P&Dlgt;;nl;h!#@v;jH zh|f-@Zl~W6tV-w^?)N6Wl|ryw#dBGaV$bl>MubgkL?W;3XSr=umW3F;C>51$*|qnf zD)MX;KX(=O<wu%hT7|ZHgT<m^OhC?ivZyx$cG*?*TNIiDHqfJ_w385NjOuuW*zfMP zbzX$(61=^)zyBKks1G>K<#?$RlyvdDF}6P4=pdL+5onU}#)qg?mMMnDGAyhX3&nbx z=ePV50uW;=q8m{)7nVhmOhl8WTD}l5?L^q&PRL;wHPd!%)E$lF87o`w^8koA-Ras) zJNeAw<j->cX)Eq6Q#?VufE%;j6$}3>)g=B5uh8t$@dRh+0(w;9b{L}G=$%VuOO<-F zO_-<nHsgFf0n2(j4XHbA7uWIO$>(iUWwqvTbYjgKKOAnR;Tv23!LyFf9CRrM9<*wo z)4t295?Ru0Dlb`Ub-dc)7e08M5W9f0c7qS{bAl5h8Ffu<MJE8RXqVkp)2(DBLFj{M z^~0@3eep(_3Ixfp%3yLN?x2E!`IWmrD}0Zg_sT>pqa}N`5F*OEY>XOo+vVJ5pg|xq zp?KHsrLO4mjD4lJk}%_>q_$(;c-kD(y1wdPXfiaOVdi=XiiP^Nw*yf+FseY>rYH~~ z`c3_sTC~pQGr?s8MM!w%s&BJlQLTA&8{u)_eQR0$41{b`HIcr9ygho|YF)8=DO?7Y z_ROMVfS$XjMfd8c><qj^<DSI`6Mqig6d~nFp;oC;^I%JHgBNhWT~6FEx@KW7$iV9O zg+@v(;_Tj^*mWn~Ii=Hur2DcstE|x?f_$JxLN>*xyZlZcjC!5d-Y5H?|MNO%aCWnS zgjlc?KF*+U>~U`Ee|W$cPXVB&E}8qad$qakDfVpU`vGW|U!sQMzMHWU?@rv#!N-*L zmsjH4xRqBwH*b|5jCKK`3b|&5{VTo%r^ag*qygC0Aaq!;Cl}xKW8jvMAek(fE_Bs; zYsm8^Y~|5V(DA_E<ren_4#Kn>Ep>7${qQHpI&U$X56$k}kXr9G`P{850RK{jZ~Jiz zMyk`&?$zZE=rZG0Q*O;*2W_MMSl{t4-yesi#5SpMZ&Op}?+q?!LnAnd=<9)B`StvR zwWXC7-`W(TJ-K>IwwyS){4|%!bZI8s($nsB9B-G*A3cEc_aS=1^zD392-fB!iXG1U z(xS19q#Y%pCr10okND8_yAjs(?dQG@OP;TaaSc!I42)}!xe|h4Fzfjy%-V%3UZ8Gg zk6vM>?euttJw9t+yIvvJ-v0L6bzDepZCmTmEEb{FfvfYu2X)k%76#_Mz@a`I-)CsI zAuWrNg3^S5gEYb6lu^p>_S5-OR?#VX*t{ERJNdM(G5LrIca-GKG{PYB?)g6vXbpm5 z#~mXT!nOF2g|SI1SM?<g_8Xx=qgm0v?5T(Q39eo}S=NLV!MplhV~fMRHbr$tq{&wu zZC=%FdRzB@<aAQDuI*(i%4^=MFTtl<fR=GJ=EIfzpljpjamHQaGt&?K(17e%<*D$h zl!YrNQAT&F@e-x?SNmr^1yAZ1-J@b>-*mKD)(zd7yvFrUw(NpU*2$n2rz~A{u6d6h z5a|7zKW9+of}3J9-k!f6UuDFcF>a|^&z*hOZ`;3p!?dgF!z29N>PUe6kTEQHHT$7H zU9_b`^mp}~qgLF`hfIA94zw=Cr!OQiYo|^+(f`AKd_jtW>bq<2zswwMoz1AmS5C*8 z;W%)yIb(sTBzsUy7%&2W`@#V2)ST1HhrVGq`wR(N;qg!W6-}ez{;MhL`}eGVxM!ky zFYUvlt5x``-bS**lKL)!N{8_Fr-zg8KQ-OF;Jkqs{W+KPeQKkh+yAUz`0^dYjT@6q z4_LCYPW|09YGLbTuIK8QvGzQ4i)%XkM4tqy)_P$i@C2ZY>yu{8n9RQWFCet6f{SKd z-Oni6k+DLO&kddpUVL$&YZ&0h>2*E5^K!o3?v|Fo3AEBo7My)Y>{0l)#ZQ+Bn3pL! z%t4AgekPJ|z$3D^;DP}uzU|4vzx*A1yYyhpA@D%TljX}i8g|@>8gH^5+jQU4F6CL- zhZ9iy&g~&*(~hP2F2Z_c?}5Q9X@6fQ{C)`4j?-dZyZIacojWfi^5y{Da`-y^rj_N? z@T8aF()|s*y=42H*(GzGNX~ri0_Ju@$pxdX=jN9yPa9;0p@98Sf~6O6O)_u1Y6yqc z=X#Z%6&A>7xlZr@=)ACTT*7RE;`ZpT&m(KnGX2UF3brcH*7OzwkU1P-?C~GqEAI!Z zg6fYI+?j{=_&cwS_VJ%4i)EClpG$vl9eUYv%i`DHVf(~q&cgGyC#Hk0ztnPl0iE^h z_5pX_5KVfy+GK`*sPWhx)2X+$Go|ogQtTYw`eT3aUxjXwr+Un~6J~hE^ope`XUQ78 zv1>{<dKL3*p!wW~ce1N$b#Di?=Jn1cCynuW_7jXlGP;=e@mchBzTqKfsf&3BH^n>b z$L}mI2usBet;u}<liYi$M{Vn+Hz)#Ky2-q;I(hDs6;wx{CfRW5-SWp;c{#gRhgF`w z!n?@a?sp;#4OJR#Jy(k40W+A>RiDIO<6Pth>Kx-&KE8f$*Y3~@gJ^700$(mTEH~6| zzN*3vIpS+iKLk4cUS7oYQ@~$QqI*wl8NbFi&+|-Y7wEq}=@e|_H(XPDjgz^((66%A zj=DAK2;S8AV#<7C;{0t&Wak+==bP^EXQ>2yWZQd_6JH%#Ej>3fvU?&uR0d8}t*blY z+v*2&NrDy!zr{L(*TP@C{*E_wemwu@wSe5i@;#5HFRncyS?0W&-H_eT+RE7J{m+dC zqCy{PVZX@|A!H^m?)=XL2fTaYtETxT1?7P*WE@SD@C5!nedm$fUUe;jZH&X?p)23? zXEzUY3EG(AZS~ZVBF8Hp{<b=Vudc<d9lC@$Vfo_wTz^^Rp_6#om%r3>UFOeSns@Et zWo_wdza`f`)Ytwr`0y`O;OezS!P|egK?m?q|CHKn2&?DojU>N8xh31fF7sz(FYh6& z_N_R4{Lysn157*fG6JLmJHk+II*}@+Eh5rLgxoV{VU?U3y=RxL@}=}otSrvHv0;;} zvZ|xIXx1tcEixI9EfV9xo~}Xv^0xuvRSJ9O_Op&1n`XKDn#-WOY)6#@o#mk2QHWt_ zAs>Lj1OcOqKG#pYefIdhS0`P2j@5sMM`Z$YXB>>X)<$Z{Z}(LDctyCB;rt+nwha`D zG96JhFz{gD!L)qwUtdl=**ZE=sN^i}=T^_lb36x$>hAkQxeaiTFDDH@Thz$ZUAxfx zv}aV_9`zmQeABkXL<@8>v>yi^of^&*RXMz0Q&_T}WH!VKvUN+F(Yi85d$wi&2+TYo zYKkNCa;_zT@3wayZYO>H@A1_Z@5eFLPZ7g5yB8~Tf9Iyq*LORep_`|H`&fjuufv}x zP`t;C#%Lgmnsxr2MW7jQ_)-)#-}Akb<~wm5XaQOfqAl4aLgx*x1FQm$n2O~(@i!Q8 zsR<(yc)x*IIg&3ADCK5wP6NmoB9Er`nWi}V<#K(CizSxPypZc$zdEO}K9=JhUaxgu z&o}IHntZ(gaF6f{tUm+vs@NJlk9%Y!;HW7q|ICG;$r4kj2S>HEMvvdx|0KCv{%zt> z`lKQLV4Ulu2a?^M{_2uez3hd`qM-*mr!U*(Hr_ctF0wD5W!Nqwi$tW&c@(>P`o&*Y zFta>8uf79}L3vrjhhYIDrV41tbUIuX`NUWY$4p~>Tnnz3kB|TE6LL&;ZTd(3$U$GL zFN$kkY3j1H#b>O7YxN?4V0JBYMya(cxGw(3Ax}q4lx=2UIo0jdDH+1uEsn{=LOShG ztKb7W<KwhMyr(z+e^D8xj;MounLHD@Z-VS+p9TWPO6@Qp{;y9gy~uvy;ERmfRGeS2 zU&7C~1t!GBr_{d#0*2?=nVaP~VAjtNPJs;KSxeLqb5T2#ds87m@w4&q)`n6OQ>5X$ z#ITN@g?<Ib&F{a$JFy>(BD(Jx_~}?a^h}Aoaa&%0<HnoPloS2$Z~Q(1luN1N(_%(` zpA_c`N~A`O)E#o)eNf0Nbt|(rc>f0m@c&V10Du5YA-n%yDvj338BRyy)%95Pfa{Jj z2AcnODs8e@)xEL<;8jfh|ERRs_0*?P0S3TXobuEEO{GnF9Lr+v0it*__;i?vV^7%s zP-$2@Vfz~$PkW9(icw;Uy>CvhG9%0f&^g-Pk)7=?@7=um`Zfa<(>YUo>^W0x9sQxt zJ0Nph(?>_dp|AVxz49D`AY(8+1c=8U<yH4x`|nY!yP@)gPZw|UoPgpD7y4J&<KEc! zuQtBLhGcQ@{aN=1dbi$86l)xLF!=MM2tme$AtKB8DgrczjGO)aMcE(#9y_-WzwG<@ zW$oZ@3c%wgLpNUz7$T4GQi07cqJu{c4DqS7J)?l2!2e05d4o)x=kcXXBTPBP91hGZ zWkcePK$fDMhdc{@ajh;#qqICQPh*V6&eb`GY+%VhNIc5g+waZJ)qB^9Wo!1UDxS9v zY+Z3htFpOS_V4&pQFn+-(*?mpNyke3m%n?I;U~Whmj{)GzN?6_)qh+WaicBRFFZ}H z<(Q*7aR!aK-nLqk`u)GvS_WKwjgukXzFL*ljRH{l2J34LY?CnW`jU^vt4&H6BNw<k zy`O1Wo29<q+L&eX7@jV`9%=8mvA%w(qiBcXU0uEqCN7vDz9Nw3oy28cl{q-o3{&L* z@4LpQDw`dXpRPyP^uF?;UWKne{%~;EZ9TmGl6Z<a`gNAj$KK`KOCNgH&ggR>2!I=! zHgJOd4u3xo8dCq<mokd_^Zos&+rXEqk-qY`l~>Yw)n`aGn<8H)m8&}Fl2)}4m-V|6 zqL<Wr1y23>#1&7aydPHFd-uwK2P|<NE*HTw*WbOLow0Yp$wPb0D6f61UG9fwXSagj zn9ZcHwC060Qis5na!^Fv)w-X_?|a5C;bgpJE%zmMM~q(d>hj<VaAVS<_^lH|Xjx^= z_V}&+`dro2OCP*_o<!cXmh;$*nbsBE$uKa#kFNSOcJkEzO~e%?oAH+eR(XrBcTTgZ z$j59p^|h0ibo>jIsKbf3i7kEMM>dk@xrF@H(kN;iVl8~Gii_JSvvC&=dmv>qs&%{O z?1>M37e7LqYzj2ZW{7PPy(j)dj|l-%;cQT|zU0RJt<`^7hY2a9x;@JR+KN{PXRoVx zQ{j!r6hB;bKkf42_vZNCo!>F|U;^__-ubqRP0rz4Ofmb{RqAO2)f>V-$OtjiSlqQL zrIiFuGUu*53ml7bK6^v{b(*gsCGSNC!|0NIqczRkhw7w!KM;VZW(@m=f`^Xh(uD;! znGfg3bd9F#L`-{_ir(BaDBI%0JEiep;cOJiy5t@|c&h_Wo>dTG)e~A48DXhu0)EN$ z;uhU?Q1VH68#kJy@qBfH6z9+vTLtMSM)iBpP`h0w42idEa(m6xfP38RT@W@yH+dpI zc)sv7e6qp(Mm8HUfz7onxvdr0UI?EhSScD~?e>fpi47}KYxFoy2|5B8kYP{>h*(3p zIY0pApRhH@<S`29n-UW;v<3Gqg_U-u)+uN;+Gp(luYmm`h%EZqK9>+HKkhJ5TxvWW zsPm}or+qWE`ss8?|L4jfXfPSixF4@i1l|NtfkpZhT#qPF<IrS+TIoe4br+-PDuU7+ zMr?3w*|wsTLDknCMHqNoMjr_XEY4=TkLcDS9b0MrIT|i$?)*jNwS8X$X6Wi)>wgZm zP*y7J&Z<w>zJ?+&^3s3+__YM+RJHc1)K?`4C?@2#Wm^Vh!DSc%0_1UFnluA4n2v?a zDB5S|?rHc*7kNrml2Vyd1PBz^1CT1H3Ou;@Sr2$nZUM~O&R>zsM+hcmYa!=Qx%vF= z-heTkIS?o;x(4X7h9&-KvjkNiUrL1GB}LNa^IZf1({h$R9LI?GKtQ*QW}B4H<^_M? z<s}tF^y_r71y|%1co_n_{tc%Cam&J3F(63E-d7mQBR1^<tm3GG`N#mtPr#T|79WS( z>3mbYp?Ud4UkN-tVp#qTjfD=QdPgk^?)$(WNOkZFdAyjLZ7Ek?A{DbUxfDFSkO_zf zsvI(UBMdQ0$4hD>V>U?uZOvMMbMKW>0d}AG>~Yq!$4seKLE#UHHi#3?Ui~wt^}`GI zT8n^y$IKhy-`}pL-K5nCx)23S5Ao6D{p{w2Nz>L;rOfxryqC?fck<tpSvJ*su*KV> zvAIgQUJg29JR72Nu=X2Ez*Fk^q7NKoqSLr@QS+b2C?ehLY=;&3T|XyiPTl`QrBQx? z6US;D-tNQ!x5$zc!tK+?R^k{iU?OJw#*4Q)U$S5U20fL9#c%Zoe(v0l`d?Jqs>$=8 z4-y~r)clxUHT(VZAw%RE2jRG8zU$Wv%jsIZ#QinveZOYe=dLxXIR0nn_iL{F!L??? z0=%I|*`v%c3%eIQxXWuF(bSnclwV}<;NBpS(^|9+)aOw5*T#<_YWjesDd_s8U!JxR zE`u9^`x#0lo!R8?s?uVm{aF&Z{cl1xF7m@Jg{vSS3H^-gj$FZ*Kb`z8xO)`CFcZcA z#bk(tB?+W%(vPp2(PTS=L6aABkyEYLsb3F8;xy`?Kb3=$piV4%LN&;7fs*8hqpZmg zY#z&K6zj^e8YQ6tj`;vg2WbKDUM3=wCcbeH`)B;-<95ie<b=&XohkOlXG&U<#2;+Z z^yKkICo>cmI63;;e^$d;7BY*JulyEsOb9JqdSWxnkZ6g`SIywJJR!}>{a3y`NS6I@ zh@CRve>1OqLWw+^<Ddsw<EyZ{9uN_<j-#?)CbD0wYKtE1O~;j}roZ}jB5UZqtniTl zK^0FD*mv)=*ql+i)B_%zqhSsvk~1c3&SdZVL&X5x{XoD_VPNgjdx!jOdGc_SL(nn~ zLKT!*AZF`!lB7z?Q_NI{bM~e#35U?Eb$G)mi6sp(&$(l2L9-}FJ#)O#lMH1=QjWDz zEq2i8uECT5kn}+gSG|}fZnVX^b5l?_db4k5!1mm?sj9OgYAu2t^h1Y?dk;K;q3%$U zFR^tPHPq)<Sa$@tET-k)*9so$A`o{1M3fLQ*(#U-7kFqCdeBQ`la1=;p_*n;cYnm1 zo<ii383i*4)(qleCo+?POy}!ol*8IB$kW^~NEe*H`Y5s*RThPMOB7wqJ~c`fUCKsy zW+RkZ5WZ#cYB$fkUp@253v}VdL0tK(0e)YzL7~L6u(U{67m~$23xElbVdTTrs6qy+ zhKDjUWCZizab==kT;Rc6R1P;~k&J0}K~EWG?O%;z@uCV`5-J#QI{<K<K>{3<KkE>r z4taJ)?<5128<h<rfZQE2c$ATR9tk7^akE|`lbf(=ZrCU5Gm2g@$|@P_HW?pO5PSox zT^ZJ79qF)`fuO?$vHT22B4Z-+fgzahk__2S3+E(!;fe5Fso>4z#m$sP3OdFpE0~{= zHiOI$VBULz%wuH3NYKg_(3S|#1^^8N;ANC1sErDA;X6?gnUW|Dh&pfzUcweW%}d+J z3aht{q4vgGc<08D5sk`-N7iA;S-(6LPyhvV8s%Y@qxkvvH8Zhhrx-D1@KCn!lTOU@ zP1I*EmeDx8%mv*_f!S^%K1-l;0TvLDF#RMoKY#_NvIJc{1)~ekZL;Vs$TBv<nFx2> z*+!isf@(7e+9~+$Ui5n|Je`9mMgqqf$!VK8N?wS;tTS<)@h(2OziDBfZ3*@?&^!SA z9>V^oUGVp2W<HxuUyF?nfN$_b-p_~xvysoEM7jgeA%=_!6|}hvqM41bWx!os!k!=j zd7mO96_n9U{x=m3??M*MoV@}EvMFd<Q`iy7ETR8mA6meoH(?jJ&~H4Eb`F|vc25#d z5AqP<ApfRiL!uF$HaV*X=Vz@E(d-z%vh%U*^B+%L=(mo$a-2_&0JW<Z;3LR9az)@` zUI_72H5c`Sj2UELCf8DvT2W1#s30CJkOB*1qo4eTuFXnLfdS$>lB^n#HPw=;^c3~? z6x5lBhGoYVvQc#)x|xEm<e_ReV=Y>;<`|6Q-l9U=aO(inApj^1KnZri-xy%G48SN( zB@l(kOGotdB~^uFc!kDA@ZgRJ7(j`Hsa3C1OUF^D$qG?6fO@DVGzb8`ytG9tp(Y|Y zvxX|#ge}?nSWv)<0JK&p^P)=)Wxa@L)KCnf`NmvxR5dxVG#Ee~3rPGjb1n>tI+26% zu0&02BO1u)1R~TQ0PGS=5KD;r%1DhLQ1NKQ(6NlZzVi{}e78-QZzsbo0Df;VSKdzQ zX9!mDC(G_vT3i4;dK|^x%xWYGC2g0T+o7PH%TX3+ptZA6d>d6uX{hACGbWAt>!@z9 z6>vcxP(g-vCjM1BwLun*V8bKW$dlgrwZ7=@NeQMB>4m%k4uFO%#d#X>U8()$6mZf2 zv~UHF0>GV8Fo_6Sm*;-ui5PFg4t9F|1TKGcfgNPDK(X+pzLwDFOakfRpB8rQK^S-O z+#pvdIw_%%Z|u#$Z95S`Gc|%F7?l}Iebxp^Og36YvBQ|-G-fjcJ&8<@PKNU-x|k>D zno5x^Q6h_6p+_$0CL&|Zka3ZC<ybcA!FFn1MV@VP+NfIcZ4>1E=E$eP=cLM@_M3>8 z+wioR7$5)!-GaC8C?lc)lp{qrqpW_Cn;b(-oaCZ{JJIJk=u1Rc5D0gYsDJfL!q*6# z9zR=b%(&WuK1@cNlhLz8p}oCqx+*wj*l@WVn!Sk%*o0SsjFP7}=#q`&szUrm!^^~W z!B#|w3%sS0@9+pmuzR|rL{_;%{OD+UVht;$hFaOivM+z|Bz5j*>Z7%M1^aG-7qa|P z<ZESQJ`ql2NAvrgbE6P|3*t&M^ze+HAho|_0(y9}Kaq^MlLZUqg&GYcG>xH3HY<E* zPC;DZj$izocZrKgT>qV&m(OW3D-%A?6WQRvtzA%Bx$wIZHvl5zZ4y{=A-ORMW#(J6 zxRa9KID@{-Kue~SvcZ&}?9T8gcn;Y6h$xh4-*utC?Wa1UI=6RbqIbfu{NAae!slIw zyazp5$WyAZ85E>@*@>`CxOo8L!jBUrlE{il1eFBZ0Dw<8^e~_1b%9AC0NAf2cLvl6 zD9pW?RT6M53<)r9dhPuKyYpP^kvCXkUurrI-{=&nW(#){g=&c?$QGi5-S#wPh!;Mj z=j&O^2P{p%MzT<xUuOj8=D$f)3m2YB#=Iilmie#Y;wEb9W?mz?W_)|JX66c%TCx1I z;Z062GqET}hFjv-2dnN&??k3VL5(>D(us)WcZmJo$V8W<6dqT4KjiHW1?9#s3^0nN z$KeK>ReU|O#33$k{InD0nr^=Mb;)#J6UJg$XX0kt_s~?`<iaO;U`WT<z*?K@exdqy zR5T|Gm6w%6<V&DvzM04e3Y!DaZ&0^r4vm-pjE+|~hG~LN`Kih3H&&%s>1v?65O7oV zB2+WFJe-@?Sx_{Ca925T5t)06h&%<L?E(b(D&+YnbTr7%>8?7$9<~lZfWKfTx$U_& ze8h+C^nCKjRwlI{9?@B<Aq>=_S+g=o=+bC-^-xfLek)l>kajOjRW!~}^p{cUE240- z%dKUp#<x$e&=be%l1E|mIXH8U{(L&}MG?sqyysP3u|ph%V*CC{r2n-+ZoET0Q-1JC zeEtHW2;z!r=tNgj>XHNCejvgCggq^XI|V?LKuDNNdw6zA2?G`#2EIhkIBJ&)o<>*m z2D3OQ2g&9=eM2bf7{UH#>rCuvMoWmdC_f;!j41qwH%l~~Yh=th%e3nzWA6>l*-Veo zsz-zFHW+!8FE|t#o(6@=xMrr{QfY*`Jv@P(^tKc2%@&S!L7e7=1@RZFLAVn8nNk$u zSZl(mP2?pud>FOhfW7V~i4yOH&oL4w*^O6c^!Q3=>C{3EufdoDXYh*nKBt>M`ZO0A z0l-^KL~}atjYPeiKGdZ&1P=Ry={rMs%V)PA{aJ)ii|&SVVO^2D<_Lfszuy!LV<2)m zMLvRw;Rt{}lbtd%p|Cj+&EwLD(DPgrq%HAUB!L%pe|%T1X?9{Y19LK^7Q&3)`*OMl ze9=Lk?IE(lIU_L$)JJdhqNxzge-X0OK-ks((GGlx!6|>7VqFF)zTm?@Sk>^SBU<1T zd?I{CWRwH73xHx|>T)SPKopc70QX=EoZmziydeDGiQd^&DmaT&@TrL)V&3ydU&L(2 z#4E@!I^DE}@O!qA(HFzXihd&UjfXfL^|EK?$++aSnF*MFXf^FJNT^y4pg)owM(A8Z zoPHbU-zm~gJms|G0(Al4bRsO~M}h*ciob#HqVOWHiOO|>Uz!mq+iY7922N^254oV( zc0Tw1&NhS5(L~t3{H)i(=!wmH#g$_a`m#u1{99ol%Y`G)r)7QtkS=Ht8_wp|?Lh+u zQ9OsPn0vnP2YDznH0$Z_*AQlL6Y<{eHF%insYwPVdIoiaDBQtCpLGP){=Ga+e{VdS zKCpnW@Iq9Xf|4!p6O^+Zms*^W)l*J*Z6pv05SYBd3bN4svQ$l5*wa1)f8qWJd-huZ zk_8G~1E-z*7oi%U$j0c}3Gvh`gq0iNC6aZ(%!LUNM3`6j-S2SC)=$6B;Y+NTa}?Bp zoe!y@{_mREs536egM6=&yYaje-preQ89BFJ1I7+0&MJc`orun{estj{Yr1F(n)PTC z$&L~^c?exZJ`vgpGj%@oc_uY(SGLlXvGmK0yUs4hy;{Crf3j=rBxJZ<>ny&KE9A~a zo#H1pb6~F0r$i4RYlvHy8LPopmjPab>R~YP9C#T33O>#FSe)%K{h>XJtYM(4-$$j+ zAZmc=XzyC8?|bL`kFsaMydBGAyPpQLD6{^wiR~%4>sKX#pY5*?pA-PfqJE3J{<{A9 zSSJyDz{9q@{%xC;Pl~{IQT}KI*Al6}r)~!gp8S=+^Jo6Z-@}i$#S8x|90~5);rtb( z3cV5qu66$PU-*lp3SFo8uRIKTaPl9)RVd{8KfA2If`xxx9{6{S{11-Z`TQvezzP9c zzSqM9C@elv=HG{tkK1-xw#*gNIy_qL`o{X4tmzr3)c;UvmKAPq?Mk(5$J(vfo+Fu3 zk$s~T?yFA!n@X#N2#m@kUVGzM?|9KHQ~Kb#NBhA%>5FY_HO6Jnp);^uo*%rs_dIrq zz`t`>10tdmUQT#OjP)Jccy+hR>(i@qRU<U2BpOi5XiE_9$N{g6-c6M~kR{{O?d4bj z#F;PVY%14YkI;^6UGyByjaR9)zUccctgr@5jwzTW+)FRm!5fI&_x*9=)zCq_^+f6X zhuTIJ>DO=n7nL@Y3^6O*c6kFNY^=Za|DEvh`QM<RuP*L3H=Sc2JMPg=`So$*<!!GA zt=N&R@=1fZ*7qjA^PVp4AjsUSXrC35m0Xx54$vIXkpFwdo;7s%55Ch}Xm7sye&Aiz zgxNq`g+?C=Uk_T~oh`dmFuUEzx}tX=Skeb;D7-u`OG?>F_S8zDg7t{KOOeCafM(s| zSQ>di+TK!iT&^}l#}2w`A4QWFVBFt>#I_gK?`eYSI^cJabZL%?vx@hfKJ3%!INbT> zGfCwlp~q?8Yd_0dI`=;)7P|%aWsu#T$y~Bjx$S`5v9bDZu*cO##RAIMT=`w-K+>L6 z6gMuKI69M2|0UPfdbiSbkGIl=&Nw~n6tq|29I|94W2z_2!~Nu4{cebw<H5%o_+|4P zH<!Zem#@ZL<FB>G9=qW)@Kw`&!r%uDDWWr9evEu{vU}F&<ZW4yWcOoQ5$}8@2xM!| zgMxq;=bn(H-*D5-SG9WiH~fLIeK9WdR~+;DwdUf8!zrTH+X|+-p`$vE3x5c`4wgxQ ztS9+Ok{5jSP2QDf9Do})dR&s}E?!)mj=<X}CmlCP`?hWrR1xxu<_z0?X6um~TnRSg z)BGrLZ+fV5Ww4=HPDY_ahN4c$6Pntw5O=;Kv~&E@)r9;KEAlYG#2j%td9^j?l63dc z(yc_Pjwj8AI0s3eSd75}5vEJso!d_+6F^GuJ+HBD6nq0Qex0JJ;Ci9NWWh&C%8pnO z?C3^${G4zv#6s!IM5$|4)WfRBJ@`=1r|_!KjKZv<h!D)jnEU!4pPvLCeEbvp+>w7- ztvi!4iedrp2E5|~A0;gPaK1_GTY&(jgu$5ytcvF?W!(;rs<v5LYYPNrtli*$mJu2L zqR)~hN(*a}zg-FmDhLI5mXdc4Jrc&-z51aT227ltNWB$y<Oq<|sBT*x7}o<>72@Rc zd|Z|ZqtaDxOS8cp=G&8y(SVC*6oqImkeyv`e)0=sBw@P<3wigdXYYX-bT>dIU5ur} zkFiKEx0bOj<zuPOR;1}s%hEkXywBdpONPi6$=VLP%`3GnloJpK8@aDUup_zD`)T+= z8WQc-WhD+Fid$+52_G$I2Wxiagsg}thz}3jI4EQQ;Aoa45~b<slvMG&ULuc%RcL<5 z-;kjo4Qs15(}Uzy^yN?Xvq0a$v~$ffe(!>{C$-Q)tcSYGR@GbMI`9~FZ4f4EKU0b& zz{58~DYz0Wnie1^7BQ?K=SKp`HSf-IMw`NvuaCL!AE7;4hidSxUv(gjFv2<dGsyU! z@A}>1K9Bn%9JRKLjwKnxoyLd%z|Xm6#76AC2AE3ca4!A2dFhb|<-;|`jtMo*l-B<I zH$h7|F@5sFTnIw~l+W|`FFdJXX{Gedh~1HKH<RffvQMmC!ePIq#d+G;EjXT)Vwa)Y z&9X*iO1bQrE8@VqFb9izU5c86(_1J(<`ZnTYAPC-09UO;CLNfBMxxSPwGlZiRC5Rm zAaqK}(%S=Ko-r&PR|lsH>zYk%R3w8kq1IB)_EHWK@8)F~ZfE80)hQ<G2~grkW9~JT zUe~lgdRIYR8>L_bu@{yW_6ye4q)(*bwirq#N0}Zy-^IM%er_tHh*d9;$d{%qR1}2P zy~bX()dA)39Tg)1hAA>z{;iso9<eb0c#zXo!^nu^8;u-&fPow2Wq#)eXBC{5m#YS> zLVTDH?&dDsc>D;eChz-1)2H#|E8Zy5NBhN)^vaF#0=GT~=Foq_H{=Hy8RX+s|MF?Y z#)-RE7}5(UhmK_#<4ZI-l6}r`WO^^$)*<0>3Q5ONuxZ?a6{|Lq>rR14^=vP@hJC5{ z_FcjZr9LM;xWt_})|l7B_|G6r`}xp<X9pkm2Fh2CpljjWD_c<UW2C(PP>n%kg_UU6 zR_;^j#v23_)?C@2E^d+K@O$d=8yEV`-oTaiQ%YB~#LcC9IW{9&@XtYjgQ8u@9j%#Y zq06c}<$e7zkgGj^r;p3bl@qQSO?bT%IwjDF@m2dtdS{twsLuD%7SqH`vRIZfiV7${ zse32ogwmx+dG1kx;zP2#%>%IrwfVrpD~{F?w^{ExOUF#)eZ{NA9L4qM${04+?H}^q zT&mjzu?d2@gNR$+3qJgD;&5E+9sXE}$M#IIPt$mT4)ox&Y9-rQ<XdYM=08F#>&LEp zj|rlk;sR^%BrEk-;A`*cVDWx_l`mPqjkVv~dT7n_N)x8ktvU^NnWGJON|gWW3KXBE z!40N6UeE4V9C>7I=uLJ<J5`SmitQ(SI{JgIIN`>-SUT3*#V5`<XX3o4rZwJ?kL*N- zh)Bhs8?TW13}$~AcrAK9S4CMU3TPchdQxb+_*whn2A_7ZiC=od3)lpU7c0&`FBk^m z5qZ(1yys36j7)5S*Nf42DB~ZK@ggNo)8o6aLk=*Nx%E)Cq4e*&=aUt28y5{<DpjtL zRsxSg?{qGUEy1iUnbEOXM$i8{@(?wD8g(RpC0hLN{_KjA%k0MVmm8-4js8y5#{9Ky zOhrDG*XjIKz{zZWw7{RTc?EX61*GGO_u--;zmDBHtsuo#{Sr;oOq?nk4Mn<M3@4Xi zd1yf?fC0O+dwFxJ?2LkF)r9<oL7M6FwD}3j81<PP>Cuya3SC<nYVzvfUi+Pl(jnTI zK{6J5<GdWe1+H&gIPf*-c8bFF?bK&iUwz9`NdEcc2@Q2`EOGDpMf__c)}F@wG4GGQ z{zJ&Qd;59!X_lU7@8G8Ona{CjejQP?@AAHTK%?8liZde4{g!ncyxpjPnY(mgl_Bt4 zyCQ>jTeBajh7>$XGg$N+_%hKaIBLdXmYsbD7hg98Bn<$vfD!U$zv?ZaQObvO%;H+b zBwBjG0_g=XR6CifEQt5L(wHittM<e1?-hB1D&LETRb0{%d+Sb;(Q+TC+r8Pt!{m%8 zCDR7=cNLAcpx_=J<RnqQT0>9J-~6rMxv$UR_v=`;{h1z;u;bhNtA7vd?9DhYGL!Xi zE5nm`F^`pbvMMWxmF?-h&+w~-8w=*Nm~~|nrUU@-6^*s&w=ccfdtj83SXJ#!GmxrA zY9rI>ota)1S;u*3KMK|6+R&tcm<J8+v<+*M&-@QB=vtn6h?fxqz#oDKTvA8(hi69e zGW<d1NL`pK4aV=RrSmceAPg^7;bg;If?lQ<zP&~}bKjo|&k0qZZMY{lbIaaZxEkXu zN#52_@!($dp6Cyf%z6eCIt^Tp7`^4T38zi8zpGI5*u0hTCfC`+=F4yBNmY}RVDsM3 z2bL?c!Uk<J0|g$>?54M7PzN!9H!M-IlDYrDvMS8W54Mj7*^%d0sx-0_8JQ0|ZCD;= zedfraqiHdcnKs^tL^3>6a8fC*;_(tc;OYNi>&>H~{KNnMdls`;@3HU3K9(3FOK8TH zJ!!KgYxc5cl4WKLGxo7m$WF)>>MfNt#uAB;M3yL(ib9k&e)Ii&{`sBn`TjrW%sKaY z-PgJ9*Y&&}52`bR!*m)}o+=u(XB_fo`EK_Y5TwTL+m`uNos3BJG-RCZ()z+mU1M>j zR~FEvZ&j@r6kV~)ECSDpBlcYjXN_*KFw(idq(14S>E@Tys_isKZtoR!pKZ${1c{w* z<MIToA2i!@lt>(*4`=ECw52(Pq-`I+am!&OX)e_hNb_ssas^@XZHB=(dVB-@a*@Mu zGm;|}Ibq0kBmzcc!3BEl!-o(TNT?9(vmQ+cD|`NKO)dlGv!mjv9+gzWc-qCbQ4)b3 zEY4+*yX{%T=YUP!KTSrG0CEDyq|^ns38HZtGTLfd_7Y+;0d;{iHnpvhJ!?hV<pNl# zBv-CC>1n>=D*DbT-Z;c%i8Mc(RHX((k;8~jcM+VRGC)8^E<JPsjGs2sIf&xAAw&d< z{&6L3cM36?HMW}IG<DZ$E<@Lo1l8J2Imxp0L%{*VW55u`*)J_e2XP*!ICdE^hC=8# zBVrf`=RCTZYf60>A__~tu$l%r>%9Mz%ag^$kq{l;h2=sJRStUT;;{5CY}HAmE{B{| zM2i5(VJKuI0ZC&ZG@sI=aCAeKJ%C37sPSC~)TO0Ki2zNH8LpzqMtTt_<zvjNFTI~` zSS@D9FaT5WI7BEOk>21$8&7lRsA4Lg5m#Z|{&e~f$90r;_|XacsG5&B!Vn<qpb-Dv z!bs;`rx_xogAuAe*VO@l{fx6N1M6!;g^VLYv7@Sv$jI?0!zU5i94Qkj?Fegf6^^6< z^v|WIEKfCn>GU_YX}YU4KW_n#NI`ZfL-})B*zRNo<5<ty2uJ-w1L+<puDA%Kig@Z7 zd|HGvG72^BF>op$nzx2av-74JEJ4rhwyU7iovctH;^-I@oimULV9<vh(n4AGu`|=| zT+Yfn(-&owCOPUVajwH;<S7E`yp5>peQX7G)cn7+NPrxJrSFITLtN}~uwihW7e~h8 z>A=g$NN_ff%hg%(q&)zTT<JDI8eev&bg*kVV=T~$5y9yDKc=Fgw6ms8jx4SyZ#w6{ zt7MSMFDLUwl!}DtK}_W3O4te4wDS!od3VrUEvV#Cx5qSkJnEj$5F(L}?xyTkTUO<1 z^JLut^>*snnF!7=PtcY|O55C>6B!>9#@b%K3SrRWTad@_X{9nqK*povRE5)vTzW$u zPd+j@h;B{hx;v#*$_ep^%ts8lUD}vjc0gPNkhy$w5lmOMm0|!96$sMZ8|bgV6btek zohj?f1;p*xn>eDHl+nrSo|l~Irl$08&WjoCjEoRRit#NZi!7)-9VtAU8U?2M>bd)^ zmJ&J;fklh{%BM_j&R*?072Ci$mh`%8u0#<xG1J9~Q)d7Y=h&yjN6`HXXs3e^;o>hd zm<x2ms4A0TZj~NMa)~9;O|Q~7PSGQ<Z?*!e9}{o5TA-|D5I#0%ZOAlCRN4jHI4uGZ zvNWmv-@>#bI?sxJJAgCXK$2F|!eb|(hn6Ia)4Hcd3=7M{@M#wrX;Uo+otdeA1p02_ z@z97@kJjw3zd%EiT%vc+1v8M*Lx^a@Wg(|!315VtAtG=|dOH#^Q7Yqav*6MVcViwC zw?a*3Jr5&|g*AA5v`i0FM()Qfr7c{g2b1Umbu(+>zPybxfQyv66JzC(0}uf-A<2cH zkh&^Ufe}q{1XL_`)WQ)R1uVwR428=qY7V$m+rVhdcSb!0+it2ZA}f!qP+m(kOD5Ou z!JEVuk578<o^z!`lcqVEF@GCmjI*zDxxa(8Vh453v1Gw-6rp=4txVa8V@uS<Llbr1 z(Ft!qmcFdwo2&T`l_#<oW5WpBedF(qjEOiNJ$~L+g`3zK;L%!eo)rMh)c&>_rJJ6n z;SpSk6$h7Kx;N5D03wDt6TwkEbp?KX`C;GlJWYHyhYQekO(8TOPC9Z1a<58n&bWOz zUynxyC*6U2-roP+!Z?1_DPZr6A8E3%1xdou{k>s_3{x$4%c2dD7uy`e_C78<zFT&* z2w<^utdTL^$iSJDlYkd3Xti$0h0&uc3F^bHI(=4}$~IdGSzVlf(;qFoo_gsS#)6rS zryQ&dIamZEE~P}d(sR-fK_q&JGv`6j?*uI>>xa0*KhNpbME*cc%~N&1BJ>etx6xpL z5ORt2abNoNaGB@%B*eKO*m2x3fa5LmrXK;H2a;fyx>g!yf+KPSI}zy}dmrw9O>=)a z=~4EnSk!HtYa#jkO0m;9fJ6@y_lgC8LMuib{&hX`-tE*dJY_zIam>#Nb&^wN22tt% z0{6$2k$H}&lA8hTtXUfF>rCBs#YYPz%I?W~;ZOu%bnX1qkKhKw3-4MlU{lWC6#SUS zeB;ka<>0+CoF~T<8PkZby?kE-M=zAiB7+x$!>upKe!7rP2mr97n->J823>xYUzDv{ zWjg!+B)|x$sV8-)t+T!*|JL`-?sM(0=gGVd<Xfn2L4Cgz5t|=&_&!&<xNqk82W44$ z7%Q|E@ns_68*Aru&A<llw<h9x1Pu($7@7<>^U)QhN1@J>mS{&Cpr1z(ZPut@t&3uB zGH3aPED(TeA|t$v5q|pZo6|^tCf#&lE}oo50%3|I_$fe359HDzA!1h%<N90sJ&mr3 ziHslC=S$ZEVsOYv5`D52aeNmR4*<&ENJTwp(71ZgYJeu6XGYPfe`eo_Y`48~SMZ68 zLGJr#2IssPT>A`-2VRmudaQV=KaL&^(y<0~cNuqg<sFL(mC}IdbmmG7X|>p??}JR> zVP@pvATeNLg`rNrNT7#Q9uwD(IicO8`7gZvJW^d|$yPNiV?1zaVJ>P0VamJ3dKvD0 zuO%=58PG<HDl$xG?$Ak-EM;VE`KLlYGk<1)&X2dcb(cydFO(cW(z?#)i2qdnZ--Rr z;<cNGJ@&K8>*q~7zi8Hc?vJA7a#YQMD1hl2S#iu$V9UK_%<}8c{nDrj0+PHWg^VU4 zHcJ_z#~7oR0>148Y1;*UmOdq(vwPEgJ<2eZv=pn4{F>Qys`^o2ofE=qH^#s0dBKxg zfuk-FGv5QnzJyhNtbV`CS;C4KPgCWB_in6?@@;!8Q9p#klo!0qj>gc=&`ob6y-@Lc zrtZpISIj>mqJm)h1Q`2=SK7xN1M;bj&iJ6;OI@7xtRTAIhO3H9{9+I4QX8ZkPIe}x z6)(Q<CnG&qz2tH{?j`>@7<D|xbv14mL1H4kH)fLbzn?quhwhDxTYpd5H3|k0>B{4c z=l-fFoZCC#^G(Lb6YzS`xpBUnF>${5_02JZ{Y8I58e@HA->^0f&`u=APk#O9b(xj= zw0=G*+du^gSPy)AAcDLA{wA@~{2RDJ2&W%!|9f+^CRZSeshX6y{-x^WdKlpnu$p$P z!s%ByqDl-&Vj|pjw~gOVcD_u~n_LqRO&Zotitbu#<3hzO1K{>HZ&_E^LRahy>kWDG zG5E`Ylvhrt&HbiJAxkKNhYmyGXuf9fmeSKg^)nq|pSF~r73l^}HV1!K87no8+geHI zgg3)h-wqehM@o$%778y(Aqg_$SF86<S_B;zH4c=#q0jUByT(kL@00ukp+7WV-wlb& zw>a9Wew@?=6rC8lE9F%f0<>KjcvXC;Y3qE|oz7-OU_UZc?BIp9U7eMoeAO>XNC4+a z+Gv{|_)_d+0L*t`l-4(v4MSe{8wvg9^D;U;+ni@|sYv(h{DZjfU)Mc4Jfc7M_ZHC6 zXAh;4h}uey<362%#ABg%tg}n>BNt!uiN3lj(R*=}wXbz?&*b;^=PQRra#~may9n>4 z$cCT0acJ`HQTKb(yq<Ww2*{A`Qo7%>c(i&KHigf4)y0qy&^PA1&bcns2Q*(v8|=P+ zlCA&J^e7m9Rt@v)V6NxtNXi5KNrfz(rzk~Z(k+V#qhZ!N`%??92TSO(?k}7fK#abi z*k)m$t;wu-^jucfWkKbur`(IB3<3XQWrG!_&~v?gtL1!8x_nX)pW))K-5QM>CU6u` z&9s;|F0S<BrJnhGU$r99YuNG7O6|du$17tj>h$+a-#x{g-qrOm^anPaaP;|V2ZMoK zmnsudzUm}i_Lq_Rt(zrwZUz`Z)nmGg;wShFR)sAF4_0??^6D=*u&rc$cek<(M+~DY zwKq%qY7e0nFWpdxa=5I1cf#&)i__%**wuVvcK)&#@E7yUdNx79R%h9;kN4ncslCUc zO&eIop(o<e&vg30ek<J6=ZD&l|CQYRU>F^L;+Sa#t;$-e6|{6bXzx~_b;eV|=(gco z8`!aqC*TUN#4TV0!O1`$)*V*PRaY=rs{HO~vcGPkkgYMB^#lK4%uq<ja&#$JQ|ax{ z6?a)hK3LYUl~iI(W;(R8(O_%pj*T|)m!X&KAg_j#(Qu{Ej?F{RUwhIg)AZ8i^gZ0T z&cLUxG;JP;_l&MHH89p>xV8hySs1f8^d|AosFeO#%=Z@tFF;<jb{8w(F;+0N+1~dJ zNyn}w*(1s5LzZ%U>ml_})o07;g-{-?!J>C|!oV8lDXwPahS6I4$lldt>*_h50rrr~ za})SSAGip)yE!Z2j#RSAmiAdB<^k!g>ey5Eyt%b_xsAG$&eU#o<krHKZ~tPiTr7>A z2k<p~nF14kO#iGWYpVlXjTaqaoTI*(?d|_kJhrIABJ;8SZL6{%USCgaDq^8Rs|J76 z+9>=9Shymt7wytU7460%4mR}iMYW~Ko*XeV!?7_XNNyz)`G61#TciW8$qbd}^>e)@ zR;?te+bz!z**L;zAaV|fJAVq!vH+D58iX3uq7n6gRRyv8HntjRxB(%4Kk*0SgK~A= z2+wZ3m|lX-fgqngwfsohDY&(E!X{b=@a7F6=i61g4jTD_;+9_qv=TOvS^$gR^skkW ztvQdeV17zqvx3$x3OHvtk$Eh^S6*?px9UJ1c5rt<OZt-~gLXW>ywF?3Vm9;mSE%^I zaV~ZJ`@_dNbg5M)ionLM#lA|lAkYLSb3d7RdX^twc*#=H(s{OD#dty#XiMe3e9PhQ zqx}3wtO4CUfUGTCBie9x-~a?a6cAOAc&SziACuQZ*Q^n0V5REx&Wy&YTny^-9yIv- zDpSmk8^{3wk*Otym-xZrwZHY7pHuOE+ti=|CW?4r6LD^a$jkAWOGDI;cl;6n@~JS1 z2F#F*AdUCp_K2m$>wAB8-irV7rSAY_-m|5Gz?&i-;*SU(o8JXkSs^v2>_L64N_p;M z&C0+yn(Vs5&gnD^(L7IiZb9%DZD0gB)jYU;77ha<Kr5Z<Yfh4q-y4RStu(ze?CZ@= zHJ)D(lcZywpC#>&hBDuUXobk1aS!|6e95Y5A57=bd$5zr4E6VX?Ed1R;34->I6}*M z*pga1S@d9|k#7L?lI?Qs<k!1?Q)CpzW7WKAC@WP<L&M$WUsNIKuL3cmH^XTOdbdpa zbCBO${bb1{u}%<Sncs`HAwb330ga#l4Np^_&Q1asS-FUuP3lh(>fRXCaK+3oyTn-! z4EU);SK-wGf@H2YMwdoRCnc~&+ZhV#jZI$21CfPw&sMZ-0+CvHh-9OPwVt6o?`fNR zA}u!G;$fxbc3#(8!cIx+$@-wfXYgVV$^D07Anw~xSC;6Z=Q6g#(|#&>f*%bL2e9`u z!#P*3`%W@`soKrHi^4@Mx&IJK`J379<U)}y&Q&9M`5fSIX~1mIG4kwRS5NO0p*Nfm zS(e0UyRPjg_lYgJ6AeDsKD?EZ?OZ=Dzr|qS`h@FN+Y2W0$M6=Gef5^Ay8gXNr&;W4 z0>3P%BDNol?CUz~mCl-+?&bL<9V?d1EW}uEGMuqB!ZBtsezhic*Iq-#-7Kv0Asd<W znM%PL#^81NE#wL8gBJn4UyJ*$RB2|epy^$MYWM?BAf~+|H*s8QCI`Nh6>Z%;`fpIp zX_?QXjhgO<U>&H9%r3b!GIGbP)5+<IoyU^G(Fw*NK8x7r(IqTVx`9v!vJlGPib$IE z{-Lh$x6_{Z8)Eh1h+0VHNlz#s!rmBEY%2?Qdgth~++*NK3+Ayo0hL0<LxFh!a~fsQ z{bJWLJ`fWMFyGGYCK=j0rQ7L^m`iQ~1VLFrZoePKlJ#AeI^}%1=@#898g89BM)ExK zCH?OnAP8zMVOzyDD}^J21BYsLc;`Edm4<9AbzdKdE)gnIDo$uVkVY}|o~lkRIBgIH zS>pQ`ulPYp+ju%<xPL=;IL+I2&E_pJ-R&7$xM3+~`h`~h8J6pyL86VDTvSf`J@!b@ znZwht^sx_b&nVqO9nf$(?t3Tt_e;{TKN^hEtRR%1(7ZBAbBN#DW2tEE%n_4`{oE2B zf0B4H*uI=oA<1LsX>tAflZ4^ir#qyLpYlm=1{(7+d;(I7!aPS!M=$cB&whX14W9^z zPmSaTN-Y#_b{+mI=hSzGWxn?O!^I$U{-Vp>1u22Z-8=cY-{iluhuBN8w()0IKC-+2 zzCQLyCohjTtYP}+1d{yZK?K}u$anSQlb^?9b$C>+ighX5=Bxju+$&rBN0HK9mQ-q! z)x685rArez(l2qM-nRP>5$xWqdD5sk$G4*~V=ip<=D|QZ*JNq7h{U@{Y>=ZEaTlUq zE1^p08_HhllX&r=<=mN3_T^3SEh`GXf5r%e*NaejB`fXTvq=(fG}gpz9rjbA(S6Fa zB`{v{%q?LY!F&@(!6}IdLkZ(U=F0wT8?u9Nyt`++dGs)Q140&WAZp=6G%6P`pym5v zw)o=QaWqV|4JDOI(I`B-a9KjVS*qZwocWHY%q4ftZD`Iv^9SKj%_8&J?7XT`s-`pa z!YM2<hAl5Ec|3AaK+saVpFLa5)`&63lB58XoKmTUS`1X>f<hVPbV;_DMuNHUfUFV} zDuscokzmRsYSkkJ%`u7O|77xaBy&fhnh8{4IPAoIwrW`4%rI3I^$u?=al4&8HEga& z^ITASCuah|l6vbNK~<GtuN~29uJ81{T))YT+zIfwJ$zh~wNDXQq2M;4+RkjfLMXoT zU6r!Xdu0plXHea}>$9e(w2I7CQ7Kpg6(0oEzC=}lDisf3jebcru#*G2UN`m5sX16! z<(pew654WGITKNdFJhC3mbuxUYQhrAr{7twlTi(TU6R$Bgd*gcoLVLO!YEaB-b*!z zs^Sk7*E(_RL#<<fxwbEKqztZX#x@EvSM8Tnv11?UCGg?{oGPIj4lrfB*D>9dsYvrv zqHsW5*(KzCCh2B;*@D)R>jCi_HbrGsw;+f9D%e5^w(R$*rl)!%*@ucOxr}>pC<_$_ z+aJmSib2XLOG?CTn78`)q5q&Z=@4bCg}FJrK6QUd$^@$CO?5wQ3!JKhs+|%9pwf7X zZa>?W?Wx+8E{21sI>7wAhL5bmLe!mwZ>eysZDKf>x@XyP@BBOk3XJ<-Y%J3F3sJ=r zO)UG4T(eXwW$Wz)L=P$x3!xe-C<95!VaIe8?mop0_MM=Qm$<JBR-0=r%>X5G;P0Dw zC8&}^$~iMj6~c%3r`H6>pa-1UhlB%<UQ-!_u*_U)RB=#Z_sy)BfMjEEwgswTPOFly zk!(b%jr-7C&Intb<ct$=S!aG6@O(Z?5p#a8+DxRMzMlM2=GkQnT>^DSN7|M|5mV~x z9iZ6Y%`;u5Gr!IpRq0bhrKl#D$Lj8Ts`i^3HM2FDDn#dASwkwvFqg6y6d<D7ZF)Uk z&{AdlhGpwb4KKB8=YxO6zIhsJu3^>>W<j(!u4x8QQ+@{(bDw#Z=!rV*FAfldoy~QJ zsG54z%4xM&nRA?}wPw)U!b)oGUt)$=N-31(C#W8q$JPXI9r2O_Y#^#(MCB#bVwc9S zJgEJJzLI=sBNWi^>{B0NuS0;cjK;9`6{A92ABL?MmZD0#)qMJurt_-BnmXXnr#N3% z8UjuJ@j2)+RNsuPuLNNQR9BR6^mxI|>Y-t=)RJtr!f}cs<9)a;TQUY(=-U)=+5Ag? zRc$j>uZVh8Mfutf3R!3WgXT%7Dg!D#WZquhC%MsRgEhbSnIa1Sa=Q>fyg7cLL`Br? za95vtVTy`zLkd)r75|=PPV4<m!J?>gC?7IkfNmJ9lDko5T&+x$`s8#S8tfMZSTfB^ z7Q9fPHZ06`<@h!8+B9|Gq^4(2v+N9+kI_FereVnpOFB<YsSXPmqe#zFL>QJ5<C?^w z=6JW8Dp+==b8oqsrMz>v(*ue$KzK1mkz_!|p)7ETk67EA8eFa5tVAS1EJ5>tr<8?3 z;$hIjY$Zjn*+QJ-k77|cimq3!ufYCg8yxkSOL(t)t&~ZtG^hP=W~(iUD@8z+o1sEk zP*lS{1w60GZiIJ>ioO(WeFr5-w^0PM0M*K`l5M?`;!vDtpJD@5U9Uv}WiB_Qu?!_+ zQOgRN?ElQ_PAe!AcfW9_f805s?2t7wRjo4T(#zw@<^gF^-D}c}7Wq|CvF0@!VQRM) zdkh-3p-as*`>=W`m?v@W4vG4^k+xf+<y{Anvb=@q{y(%^nIWRgGvbd$NTwNeUJx#= z1O@P`-(56;!rQf<1Hl8*jXjO$I%+!Vh?3nD(1fN8TJBFnWal9=F%V1fUS;gYCO7q2 z#y9A>rt5YS8b6e`s^JP7VaXjt>28SF(7Iwbh4t&=4?#^}V?q&6QIDWvl=dOg5gxBx z)_F5;UoFw*mw#t`4KBiDua-2~v_Yi0dzYXr36uWu9~TwG*|J0HI6UMY2G083%RxZP zk8gO`nRl?q*|${15^ikz>R66zOLbA??{eHo5aM4vah&+$Ek(?Xjia$-Hz3>s)ZX~! zjm8L2;)MQbKb0Y<v<WS@M_csOZ5wH#SOHC{pQ0>I5hGZ<P%xL*<S2Tm(C^J-@y=H9 zlp75Yjoq3*F10ENRBd~6MeG6mmq=U2@@GMs_!4mjN|3?dkpj)J-Mu)Q6m=!Gaz9am z6O3B9AoYA>%q2?cnJzTaJ*-EvxvEjM_7!G@ELm%=()CtLY+qUB+4m&qol0&FbNe7s zyw@U&{c4%W!dQ-*^*`B>VnL{waiV-B{wee#eD-F-CDmu?AB|7HGtTEI#NH~OP|{Wm z@Ob;(^vgkFf(|gQ4T!TXroO7frRDVQVEUKeorNk#u$5d3K@vq#iK?KdM|9q@$b?(f ze0S#GF;=*#@jJjaUN3m@pxK|hvUd*5LCK=G!)K;d06-UjhohV+LICTK3474}WN%cn zTuhjvO*kxXzDZx&qo(l)cdR};+A2*=oVslC{GcNIqT<SbHn}mjDO(m(-^!yX>r~>u zK_6)qh_(q;N(s8#S~;k$C57YEI1x*4bETDBcd7jn4}(&x8&oTS_fa`NHeWX%eHf6U z#Xc3nRv<;6JJK%!blTu3<gS#%<X#Eyjq(d$)jXlHfF7_-QGC;jktUj5ZL{(31h``1 zHFwnf&1JmJ@$P<BU+Zgo0u&kFBn*iXdQc?+>fg`NVb|~O#79b=G?(dusG6`BFA>F> zVaj?CU=<<<_K!o!;9rWkc(2A$wyws#jeN(jMw-#>*yy8pyr3>n`^`P4KeL-59oT6} zqv&D!rGM(%e&0O#kocnxqU1{9<Anf97RqZ7asN`xUx+NW4U1!oa}d`i5S6enB~5dA zOLL|1wwalVz{RrVvgl}m062_rzi$8e;d)ws$whf4RXAouC1D}7rvIH?ENh{+yt<dC zn>b^~E!n^i5bl5bO^jDGce`#x(l}sg82h;N>_bc!Nz%~x+_rLkqpfG;L{7f~epP-g zRV0imjOwjuqF^oW7aofhuXU0h@0FRSNSZ9#Ox=5S%}DAeQR=qx?ay7q!iLUqs-+|M zORs-8USNK+2`+rZa$_t)9&fIK#~qP_pj@F5LJw?F(lbdqFAlBCY!FRNEfxD8d=m|G zv(Q!8z!7&FN-`ardnK82T};25j^n`_<?*jB9kApu9(miEZ(Gi2-H~2{h^!DIVFc;P zUaU|*YdVfo+U2?fgiXTVB<y?4>Uc8GMG-waR3jv%PVU+pw%>Y=*ASx){?-D<*IDPn zI-fsaVc_?^K<4)N#qj1b^FJ-%ql1ly6&Srj-4qO*EmyQL(Jy&R&{7&3Y;{I2IM-6r zKEjS<?(#ujzI#*fMEEM=-ZRO+z1J<-8VNHUy)s$7ATVF8{kuY<*NZ_>@NXXZ>?=K% zPzN*WQ)6RTkhfmuZRLOOGzUB4p^XMHZbIg@2mg&WS&m)5$KpG%FRA;ykI2u9B5qI= zn+_`mu`5$duQvR(t5v7oG0~(!B<7)UL=lx9g}4E{z4M``R0Gl<;sd$0gt>&7>u?<G z5?lMue$+<w3y6&8K2&ZVBD+ES_|SA!EUdOZHGb=Y-ON8HLPWIoM`y(VoXrU_oQr2> z|M4R<75@0+)%}&~=8hI{16YC^Oh@X~&v$Pue`p>2Q1C~Z6d^-u!!A*<8<clVI<8>S zBMZ2+NpD`ft|dN@=<qWt%|!Ghkutp(#Xk6G?%{6(&tDQH3eU`4qGDpNY;UUEv^?Ep z+Z_-JBP%f=gqi!bHsh5<>R%;z8wkjy32;_)|KF;#>@eLi2%+9d#w6aGy>jryilt+T zdi)l=QpiF-MD}Z`jh(`Apw{N9i~Ca%vQjlL1GELJHQoeTwJbC4?oXX|yY7@~dei2b zlS}#7=aXM-gX^ucm25kP7??gQ9*l^j>yQB13=p0cHYtkm>7!#*Pj?q7jihQzz?cv5 zCscqE<K=E%LXc&R{gJEOGVU>xwRZRO1$jPAH5_%wBH12N*R0n)&nkp`58%GGc#bor zPfFvv;h+1VCHmEct9pm}<5D)WxeS$@N(G16&FG2w)XXhW!6OY!Vj5MU{><b5QKh{a zNq0S8CEI&Z(U+ZkM>lYyTFiXlNErdmF?YAxr|H|VY!tf=)D@X$E{wSzExG);IFQ4A z?FakfS19$W&vYNA_m^uOY{vl8xPa``=^<Y7y&z8-=JLw^aG)$FqNtF)cHVQd%8CI8 z@)VyOT&*PjjzaaQR{f7EO(~0qvASx(D-Y;Y*L8{J)oO7rvF@}wnYr~9TH|2@58(0> ze7pyg;3-FWW2bcb;y>qE9TtKNtUW%4a*Wo~J8T=%@?X4NVU<%16kA{|^wLsrMCoO} z?z2fx3n5Zb0Rm911#0RaavKR^Qc&_VTViRm%d}f?%ggDX{Weq{#YL9I&BJTt)tnOD zbbtA0zWytP@H;cm4E5T)It~P&5LsyZ-nSNW40RTEP0tPO=$NK(bG6RN&i3TlSkvRz zRgdZ)7Co4z**7>mMJavep}*4FnnLC<v$h*l*D2-YVQyoc55oFvC%$EjI9_eJFyN z>aR7`D3w-%P{6IVrZz)!qx7S&*Q$G8fj)0|`=oH-O0eqDgGQMhna-XJ7b^|Em^(+s zw#2GMq<Ra34i3|B`Gg|U3YWg5n`O6>P^0^DYFf7ImzMiq<4>EMp6seUCfZ?vI#nB7 zFYEX_i1uDT>%rX)2jN@Is}37}t92qTP2*0KEtCa)d}cSb-Em*%-(`6#Y{t8Sue7WN zEo+7J+FY}`%QPV`;Z4{wO(-ggnYK&N7RY_%be5w^6R_=JKl{T2I2ActT~#e)_+?v* zWA0$8BpRD8WHY8|K?#`K_q_H#9MZWQud&a*UPXBOpG}DMbP#``J@==Y$`m+pNPsAQ zkC8JyaqQf`9rPDP{xCx~E?GSXf`4wRR(pEY&;hFbWc3-PN2&c*x{>MjDtcVks|N;L z^3}0Nb65ouXgrC>Rzxv>qBQ)k6($1*mlxb>Y&L}pc*CTCr*URKT9~N^VwNxeuB3-M zv!i%7XXK271SQuag8uY97YG)v1%8Yv1_ERWC5nZ0jH*IS-=dnV{A2xHA_lQ(A$ML^ z$fOdfsD61_tXJH+m2V`myArNUT2`{+P_a{8hgL1weHm-aoI}+--+mVu=B<3w5?xE_ zoCc5BDWzcKPuiHnDONz%hI}Hpe?wee!q!%|Ss=*<jw`v7rY}yFPvk@?*Sc=&*wS*c zy*>BDC+Qlq^|{iQp(1aciRM^ezSj?6%BS1;FE`r>q@OIZ*n6vFw&deez)_{;87UuG zg$SHafGh9e4zoy;3Kz2cz+k;PJV4;(`9%YlSWNycPNSj-FV?%?d`b@~Thd(n66gcz z-S9A9dmr7+;$w-j=QBwSeUdBfPIluym_*kUtf8%-GshM#gn92F?4!vrWb+&Y$YM%S zVk){5Hki#yl?BUmToe?T8?Su{g#m{7ZRMGzeTqLNP85%AEACAxnUL;s(tzd#(l>`z zPa9)Gb95Cfbw4ZYKmC}hh3n-7Q1DsZ5F$`|=kPlWT%J`kY(7Pl>`Jga{5p8t?tGpK z|FVS~l$fePtX0;F{o=74pO+NUA$?W^rzD6OqvI4XJfG~H)!x3KTS75QklaSFigEfY zQOiM7&f<X(+6qg}4$JDtw%tRRMx2s#-3>9-x@BtyR>%0K4*Q8lJ??6~_MZfC*x^eA z(owxyU?=E_VjVX7D6Us6hm=PeKLMuA_hJN$;J>y8m`6<Dwv|ejjX6`uL5K*DDE-`s zvt7!b?6?-`Dw-=x;o?oTD!ATdx!Z~$zbHSXpc=M*Wtk@rF}}?ohg%L4>aADA5${c8 zq<q!8zn|8P|C$u)7=RU}!gV$8WqcHdD}1(RD(yfp>_?wZojAqN*HmCdc3CLYw)5vX zL4X8fE}Whk<FMu#^l?}J1Rv>lnX7$rKoFOwhwnMj7Kq^WC86AeJ2|m>ANem7rN}}( zNAzR9*<^H~x!c{#Q`?9rYZQz>PpO=-P2`WNw9v&Z^T#m?jXNC&55X}@#VB)uIA^#- zLmN}wd(>?0>Soy{FNaXRp4SJ(+k6k5yOaRocEiDP=i3#7yW}xZ5q&ieO^`+_yYiO- zvLyCwyOAXiFyi(^7`NH{f$<A79uZCc0yJ5&)E`los3(DqG?V8g)4JiImfqZlEcUyU zh7)n{bCLb^mu&nD#xll5nUA>erM<l8Q7OVSEKM^3!sA@T79}5C6Vz7HjQN$qGftq1 zX>Rc^&sEEIG<e0rmcXzURhg5np_iY}rFs<(wfszAAH8tek7TnYIj<>u%JG1<og{6X zC6sQDuTIHb_m|#vrXLAA!9BOe<3ANzL7(|Zi_H0HXXbP<FZXXMUgX-K1eI<%b#Gop zb9rRJL+&Rv{1NWx0Xe6UF7-)I#Rz5wR)vq8kypBECGZaA;bIQ-Cnz~QH+-5I9G%Hg z3|TY2XJ(hjw%i8MO|T65`lHzP+=WnWFhxdOqW#qYr4|3UKXc(baQ$w|PkxJfmpSF? z{I<TbZ;2HzYsB6T{C5QXEy>{Tvcw@$zjpa%wp{vK8M({D$I7>^-uwGrr{ePH#q#fE zKmUFt%EeFQmT%uQ`1k2}Mf}U#<vT5L|GxOhU73Ae{^P%U|JEZbt}Fz?5f6VRe%aZ) zvMf-sJ7BQ4nOBkUUc2JgXx!fSD!If@$0~lmytlX0UXi$dvEt7HU5VFq{K~i7iofp- z_J2)OB<=huuhI9~|D!CCu=~7XZ%6yzk+q8Cf8Q$h|NY$Ghu{IO2msv%@NEDXJVXQ! z3G{}@jGOu|L6n)M{THDJB1~BVfcgg1s10V?W>>Q8YKX`F|5!*600kI9<^OLMlC*1h zRUaKxwEKUuklx+N$DL^O9PYR|^1m#keAws>!|2cR!*}YRSLlVeLhSA~Ow`yEsGkkl zfFWqDMRsL&|24jBve!VZaDYdrc@N#=U(5LKe^^M3vAZWLPxHG!fnpzawk|v*eIM)} z7rD?|ANdZ-!n)pG?qdjPoDQnm^rXdz*_Zz>3+Z6!V(A?i7gE?H<%ff$9`L+g4G_<E zul&Rhm_PZ7FS)Zm*JU6_z(&M<qjV<=nM4q<)TRCc*ikQ&d*45f*VtD$J$kV7W#&%k zo3Td^<C?j9=Jp+(@d@^bw=eb`SUrh<VCbb0)o*)=fB$SirUH*7_w4=qw}8YZ!TH6P zl6Sa@-Xy_)KdGc{OW0tkUx_4a%G#%T`9!JDf%5ci;*1Z2k7}rJg}bPJF+;ofx&lnN zANMW`(8IsWHkf9-%W0e)^2;&X!`0-N^Go>WS#sO@=O5O+wUT#iu*)CTe(U_r;M0S3 z0oUAIf@^ZT<J|&s{ilQKiq6%|))ZSerpabTbfU;mK8Fof8R^6S#X<^Mt%|n;daL<0 zxrsHo#_FGHa|P8YmDd-GKULgVL_>g!gKFybyn2LNHA1zGA&vFsZJ!$pt@pv+rp7_z zFHIdTb{b9fUyX@PJ<x|uZFdF#G`95A{U#vffQ{ZeV~2Rw?@YQJ4o3)dsekFj+<g#q z?+rCHv~^MIHyO^aNA}97>9lu&t{QCs_qL})zdhRh(Dbe6e_2RK&)e{f*TZ@BP}Q(+ zFrnIqtr=gf*N#K$oGLd4!~>gkdKz`ZHV5|~lt9pGL4^n4Se|DQ52Eu`H%Fw}>4X8n z+OY4VhS5z8Fy{Fi(LImN@Xp+-fb;f*wQ9EB<e0+W?>%wG(z5+psoc>q>jPIlzVM7& z*M?`9fd~m(P4_#m<`Irj!(#WB^j`DaaS*(UB8Kg}e4Z*+aVz5I{`$S<$4+g7a@h$A zT)oLPo-<Z*-T&@23m9hoToKh_c@5lCY5Mh{H16xKkCpTbs&I|n4k%Ph+^=($LzQhD z7p)>N>*4n<JZ!vUK29FdWWK`~0IQpzRH1#K(d8|(*1yl2od|<+q2m0M=ZQ^a&^cj| z1;d@Ex4RF&)cE9*5WBMZ=<hFsSDGa3mA{y@*`ylYhlCFMlXnTKHFCecLfgRt$jy$y z-3vmp+s?cJtM*HS9j6|M7_zv!$mezx+6);}7qN2|OItsXjrWQ01lTi&w7VbL=ZZII zI1_nTVjcvE>J{;BI?HYFvHep^i^5K{N2iv4-?)|I**Knb)qQh@%%hh>rvgt@3ZD9) zu3Pw4XmZZy%`;_Y{=)Ml$9G;oT?YZ!?lI229277nT5kPEzxds~S`t!+L)*ynY6bZT zPShDvJSP;&CzswN;YxLXA3x&$r3#C*9Xe%2_BJUH>s4|dI;%4oA6JOtc5X9$HEVlH zx3KEA=zSaeYZ1`WlcEn+2gyr+b!b{mLbz8$Pm|vV=Oy#J?(MqX_-wt=tLMSh1JU;% zW6Prwc%500BhycPKaYgLUnssV+#z%8jX<X}>hx+jBu+IUPfGOF&WOwQR{{>+z^n#9 zXLd#)?m0AuUA^(E;jv2(qRZZA)YnYUs>L~xlUFoV-#gRx0db>S4qm^H7wyfekPi(X zg<s7t5j1wjP2e2S`Z%JLx--N0u4AC_i;{*~=R@Iohdx31xS;MzN^W;+tpyp{J4W}R z*P@)Bq~9WVs(@Vm+jYHFY7UX{rNsz3WWyFXmiYNZ`Id@><YeygeGBjgw@AH%48!qy z$;t19f{nH<w~j}@o@yDpdtpE=2b!RGdJ$V`bjXoE(wAEfZW7xR@!l~Bz)s&Aj3xS> zRkK$-|I$E>3?cJ1dqbKgdnK>6RT?+@@HEW~8vkf#W;gq*YPbzLO?S|(7{1F_U-l!W z@8s?@pGRlPPF{*|!p?{GFU6YFD(G9arM85g74?YPAM339uk6-{*NwS`twWs;__RVO zU*;mGr#shs*CS*9%)MT`)YT?(Av)K7VewFG$jfXnqrt=AvoEewLia6!+4y>^<hsII zV{7d5k;NaPR*$~K-cI;<qrltv$KCDG+eseVuX?rO9s~S%TkDc)m@o@KxLye1dbWhH z_m_AEkRf11ipx|rFW+ux*v{uA{ww102XSO>lVuuq2*S%Xgb(}lV_Ebe3Hwmo1`^Vi z3F8!pERdY>{nuOB$6bKlkQEHtmTJB#-YNZ~J^!Ny)pN)d(GEfYmNQ-PJ8Ag+S^Tw$ z0-lgs`GFIw1G;~)R2clkh^td{k^n&&<ILKBwt4DK>CaHW@Mzo^Y4P@{^cx?|9$vqj z63|?6tayd^{W6Dzv~9%=02~&QYHm(UjcUuP-5(ktb2-LZI-Cr<^58|~-rWWZ$Ir)a zJebn$)U)Pp`J5;2{i0wxrqOg^)n)GYR9DY`t<j^ar;pHH_FT9KL5-JsUm^7t?F}`_ zPllpLc3*b1?$jq!Lu?QJemQb&=s)C=FLy)3gW~rWx^kObBjl#%DWX4pZ+Tp}R57>k z$?I!Z=-h><$8(E}bw$g3QxLjw<IOWIGK;Gf4D}dT!ff7q%)?&gz?|kXdTwMC9t7Wj zN`|JVTBB-0%d=ptcViQ}FR6H@iuj)u#Qx>o2480wg#ZCmj$TfBBhOT`nU&Y$q+WD8 zXhjeGxj6~)@pk-n^%=_QQ3K=2>#f^$s{dA%(|-wjCFCY6#bcnyAwUl*MM9c}JUC%) z!`k2~hFQs-e`6~;Id%zB@Mt~a<1^8oHZEEMW$j|_!^M^paXDn4Z)5=u<mK2dyRTm$ zPA%oFj&IsQ@x4vhEb;9q0es5SznOz1yfdh{JalCbi?`|ifTsQ$OWxb&`sM5O%=_|) zegAet?!Qys+J9ba5AJk6H@z@f`DgLZ-p}9f6Nwx!)soa>t$`ywTj>f3G%)$s_&J`< z0=a*mNA?i<m6RRM7kc^-k$+C$@&4|U3aQTpM`rRHvZPqadp};R{NXB2`TKDx>0BJ) zOVx8;na|IY3&)S_MH7%QgycVGkpJSyvb{+#3>nx+<|B#6dXr%oiil4Vs!LP{01gC- z^V@*XuH-a%3W<!w_97PID1W%9XdSB33?^X-OxU1m;Y<K*ioOk%U4zskfpX#)Q3iEg znT)DR0miB4<x_NL5~)~|1gwb?jv`n^9z)V(t!cVCD1Hiw8<RqfKytMs<CjtoHy|}p zm_JBrTm<#xs_&s8jB63dAb=^(s8j+9xtRuAM!FZ#6L260K;#RcVDcznoU^jQ(CtdG z4gyVapx3@Pc%%p%y_Y6vK~>xZ<558IjG*gBBo&K_bVXfcq^4j|v`Q2$0-fhg2S7TM z5_=m3WUx@#ZAfS@7t9Am$Dz`3;AvDUlt_u&K<45=pAE8*PI{rZ&S67vlmv#aVi-#q z$jFQr4JaT24S?t@JeUmt7DP-KHX#H=qA}<OLy!b!TjP?$If-^wl8iX!X;)UYZ>oM# z>J=MImNN=qp%!+*5`s0d_sRt(Vm$)<$^o``g8|N<!0;6g@Z>ud{E7#6Y(T@+%mYP8 zs1I^Ym4+c+`7xuVvkRsWGUPDmB7nOX0JLWj;RNtQ5!e+7&h4{!x+~Gp3A70s_=E&X zHVW!lJOGmy3K0NUXkdejhy=upz-4h0MVl0B*97MVs<NBY9}*b5n!9I{El%XN&;uh` z2o6^OzRBeRpqb3V_gEgk6?Aze`pr<mau?zVnz=WFN(3@FQpmGvVB`!c58&Pc1RT&n zQ$(I!5EvJcZf=;1s7iBTf_Hy1IY^h}dsj6CuK~`e$S#zx8>a3f|Ft-7IEC9(4UE5! zcq7ituS91Mn9xY{YeuYpe^P}v=qkp9R>4CmQB-e6>I~h+4GeHiL(DMLcN3#F5&-7{ ziBFs-Ra`!-P&=C;v{?WwkvRM+^!{wZM=VeI_zmcB?lQGZ0B@PiL{ox6Ydm;y357=k z12$ZMH#}qm39Ul!&17T}xS{ggU9KRtGGoRNYyxs3Baj)DsJJDhB`F;ypI?YhRx|<w zBMN43$zE?mZK5&$OkO^2VBsDgjEFG3kLW}LbsKQNI}-|F7Gcqb#$f(9Y5|pL1QZ@_ ztf}>e%igNs;9wvU^dfKMNfwtch`1Sn3UP)4-t-WgBAOu>PGEe&f!7QvvM3;KBXJv< z^yMe`U5%^z=;baX;>)k9DV>Uz`!(&usJu3C5)Xc?tTuN83%ubj434WF;Z@0DUm#|8 zD}EY*Mf)6tlyjCJ7NpFgop+ISSY)UwsBL6z^0@+F!s7tMMJ)IW54y0>bCo5bSd^YI zm|lrgy;ZuYO8Jfimg>nAbuf5|q+JOwc~u1?UM_LFgg72o%w1oK;etYtuMMkFIszeT zAcs;0x3#vgWj+Z4+n5Q(-iQ*lLhVmw@ZN&GBA6$D%C1CNpt%Fmxo>)diA+RxU^Pgr zp)&K`>_GZb>JvBcAQ}k4f>C(#x?w5|f{tW1y-@>?VnNLea4@5}cr%;2i%!O8!ibeO zY{6Fm(2c#G!40%jwwu~=mvDF=&ewpYCirHndMIe|D?gu!R^q9t-Crtb9li|^&?0Ey z7pt)BR*Cupz7C*+Y{(tu4yIyJO5$xPxH^E4Ws3)GBPxdj$-^HJUaN@xz@!Tih+;a| ziO#m`202i9I4-^z9oa0HDGHIq7{;S#NN5W^;kXFIuZX;1@4}AC_GJ8jFdyzR)z%UY zuB;NR{Rwpg0161)#T)r>x9jG^1^(L|@G1_pr5ScS?_mids*P_30ID=V^|@?{QD!BU zrzC<3*k<pM>eIOaR~*Wpz*Ru5fKf7Q)WOrN4ww%Tib?+(k#~;J4BL!?Zr%=_>rCJ5 z<cBa}I+i7b%ceX)J)W<&@`2xWe!wR)q&j$VA4IhT-_W*u;5StcgLK@9=&8V8h3D0K ze@U%6%-8MBU5CADE>ZL;@OrLPQT9gmoDs+v&weqJ5fenewA!s10#|ur=F^5usJs(0 z&ZW5YP^qX5zR4_&;6B>~`fs#x$s@u>x<lGgkI|3dn~(W>;n%RdetOK0b0shCH^Jl? z@Xcy}OKt-mz<;>!jyHERI;YG#$3TrQ@Kbv=Psi8S=+0SGp2nj@?pl*#^d)p59FmEm z#NM<;(OAgLrMpjukq3g{bUSeP9s^+gmmGJqza}j<@bWA-@Wzg<{5RM2=i{;0sG`b_ z5Vt%I!YXPOF`0Si{hw^231|V-0Q(!QekXgrj0}}96Ee}jj(5)A3_dMhpqboL=6xU8 z+dr+|nwY_9Lu$AnOxCYl0LWwj*C6VQhhOqaR&QRxHyU37j{(r@5>J9RxSZSIJegO{ zaO}WHM2Q<BE-o&nTeM*<d#>vicU80Vc6Ql(fj|7IMd7H$N$%Sl+*dWgIy_IaL`CbF zN6)*4-evZbJ98giLrdCU`|5B#+p`BI-<s?3baAMrG3)_KCp*!*6t<jKfdjQs8SH|l zVOF6J7H%EVWWDszmWdD?y%OeKJ@l}B#8XVYl%1{qG~F3If=2j?^+AapTb|&oCdcT= z6mWawZVz@WwPs1*H`z~^w3r%JalB@n)dMG9kFkBOn*d6gf{;(m^S1O`rMaA?OVwd& zHggC*fz(&y3en({Mko}5_%L)uh8vwrcy`0+iNxr$H#U`lSiY~U!q_K6-+tw{7=!Rz zefl@r75?PDAr*KvWKZDvT399OJkP&4aA(bzo36dcbf^q4dd0o@!Xz8qEv=~!8=wrM zROX*fts+yH>Gq~YNFPRmGeYrEMF<Na*3u+68h?%h1u~evoQKvn7Pztt=X~2{@&LES zUvP1B;Mg$$Eb<M{sl<aEB-Pq{`8T@`Ne}L|()pCLp#SB0c-0L5GTOlt><oT>TDnjz zj14E!tM?gn^fH%k1WFqZa%4oY-svt(_>(T=$&DIRFSD65t(Ko|J}Xjf0{RfRRwW)G z<+-yz->}ema`ApiOT^=+XXhs$4UHba93I7#^G*^n!12u3`Oz|Hdpc~Bs<TTyj^#>@ zK>l^-8hCPLzy?zsS8y@@&EW}@>(R>Bjs=qu)kq(%T90e94&28#(S$JWGViGdcckRQ zo}W!G;PH=_!XDowuV8#0JGBn+Z?>j9T0&x$k2`=wiFbbz23mJJmkxmW92_JI`CtgC zZ(9JXY6h4v?<TP9W0mHjP(I$$mnRDjLB9a|ze!fC2G3-454SzMFEWc<o_RHPVCK{Q z?7UO!%4!&xX$GQO=LIpJ(2M0;4)1xE%e2v>dvkLOHZ0#?X=gtn6M)6P#@s>npcx%J zgauWw@Fz3zKV&|dY)+##TP@JQ!z=G$7#`Xugg3Ju+MC${@+~>M;^P-8l*Op>VMdd{ z@wIH63Fs<af~-o_wxLC0d$@ei5`>#hZC{{yT;5?>XY9UME#E>DnQzDXpcBZ}uA=%j zKEx`!VW}0~*zS;o`6=6#+4Bw0y#b3HLiMfy+V64UJ?LEUzSdKnMbzuFC1X6<ZIUGy znFu*Yu9mM4p`lI4UWAW#d_>OIgFaILmXE_}WO^*XBHse|^zY87#C<aN7oJZ7TJP=4 z%bm;TaGNVXoi>m@k9jEb0vA9-v)21L&%K?NUutDg(@DEUxj^Mr_;TvU)+VKk!dV;D z)<)I?iQh_`OQAm9#&5VMMmT5T(^2`2!?%Bc?Mu)1DoXb9H*Y;}?0&i+Q*utW=`(Hz z-kX#c1csY!xqTDV8AC5RgL*bUcE-_J-aldz!KZv1gk)iO@=#a>Xr;|OGF;%+y0CB0 zy1Jfwt~I^3e4Xt_j>RS~8IZYG{}Xq+ETR*OhCEBn#WbE>D&qt0Zg4ka-_Mn<6$@aR z(ZBe8{{HI`>^rjktLG~={6_ALq&=ykHXC|}2e`&SHVV{n@8=~fyh>1-Ekwz8B96cA zO#UOJbAzX38M^$%G<*K(fmcsj!K=qGEfM>F_rCwGzz`C?01!eY!3B;Ml`a}DsCR<t z2SWi2LB%#7t}8f$VkuZ>aw~5aFa;`T&@W1*DIH3H0qg}}sE9vri`Ni3k1-thz*0G! zxCfU!x$0bPl`U&ka`KZ)onx7LII2>ZOg)ZtDl5T%A)IU|=?vL989Y-}2NWI1XbbA2 z3mt@v<Hi*Rtuo;XP<)WGt?A)Ug$}pwX0b|q`Q)riT{nFPvt{J?{(B*!a?5tYI9nuB z$L)sqBhi1QG0TKwhn0I|hEVV9tQlsXWo&f)-%#%EJ96_%8_M6vKZxW<ICpKZ4nW&Y ztjj%rMSU186G#}~BI{79?CeizY-~Lpw=oJuFn<}nXbsHFS)3jI%yPIW_2_X|d<`oX zYB8vy)}~#aALD|!_D=N;N8i|0ad+r#*VRh#+eD-s4bQG?ReYa&)kY21<kG3zEHY|X z;Edg{`^{@v@l-14Aq`|lDDMbTQPn?i89Z9qE3l=SKfp|TZ9&*%cqONGX;Ffnk-UH{ z73OWXRjr_H_1^Ms%2KBs@(i)0I4EU^x?kJUb<pV(&aekq(8h<AcEhc;Uj)t94`ePu z$$65P-caz!rEcvb!0tmnGS*&F7q^rzjM}fy7tiWAepD{?q?*Wm7{Rf%OUd5;M$i1z z2rUG%)8L#pdD3#!+H#`aHZ|mh6=0mFBQO0)y_QM5kl1KL@!E34!s68V0V_r2PFKI& z0Pa!Rv%6}dPWI6MuF=A(el&!fi9cN#lqvYU;bcn4OI5~)=7!qokkLH58^GCMXZbkC zhF8!;?$h<9Km^n+@#p(jMEgYF>H09Pw|7OI!qqa|Q^l-jRD&Tw;$(XE=W7k8&afx# z&T!=q)xX@RKBi=LUW##+xG#uf0UVdX;^joHrA+PLHzg(+q5PY^H_SEkO)8SB-!I>Y zdpdBd`i$i3!vk#njMl61Q`(>9j%x+)2T<HaxhE_mKg4&(JV@I*S2J{1?NbMr?hQ4M z9MO=eimQIc4L>j34K-t08FPm=LkuVD*wmMAz1onf-5b^J%SH`hHy5T=JIk*8J&~@e zB0d?FNPS)ZIO^f+`s?t|f8JjO=he>j9Xl%X@oT*3L_I@IKs~&@!IWdFlJZLMR@E<Q z8q1%$>KJYQbNZA@RVV7N*Oe22J-_}xvd;UF>M#D|Z`Z}W*Sfg&=zXuf_YB=-W?Um% z**i({(Z24zxL4?!Nyc@J5E&r}*%_6YkP1<hN}^r9zTaQJ|H65n_ZhGAdOjX~eKQt8 zFDA5nz71F3gU{YPdnALvR#1D+mg1`O1?T^?)(X_U4y~=62wc5codY=%doEeR5e9$v z{oNtFR^(_#SgB|OW8qGsV)Luu_~h<+Q>9>Tp`$+&QRXY~I)xaOSJ<^<g*W)Q_ODpp z$L$m64S(>h@w+F@Bq6Fbp=Mbpp8LSJm?C%f_=v)v?vG$U6^P&3(!9);PycIeGT853 zi8*6GBI1gZgrOZ$ou*Qp6Q|6Z`75nr?Z*UCR`0M1(Fs1Bz@|NBuv7yFTEQSdA`%ab zkm;u~+?AxV8Ce_w!dH-ZHG4g7BNH}gb|!rxzWi#NP);&-VF-1FJu-{V(x~akP_;iT z>6+xM@%|U%ibt3srV33h_k}MHMu;dEPGxXzascx%8xOPhn)<(>lC<R%M-vSCPSRtM z?8F8FLLt4uLFCM2=%I=@Vc@fVDQUwv4+PNpy|l2r#htojgF)1d{mF_mm7W&ja@-P_ zEdlT*MVa--7F2n&s=LC|S*~!+&d9XNF%0Q=-tv~8?ljR|YNy(9elTa`MyVG2AjeM3 z&bIy;W>GesZAGqkR$rO;#U13pFAy5$V_Ql}*FnnF<Zwd*Ie1ZK)0Im$LP>QK&h<M= zu9cG-cWujq<gWK}{c=_5R)IUMj8v(~Rb{mVZD3icJy=PuJjf>NptN4|pVDB4Ew<m9 ztA#4XoUL<gh8-XKo?Cc)Dm`dLZm=Mp1SsUx%ZGY6Q+H;PyKD@<>Xu#lqmz?dC}M0h z3Lf^%abMk9qbhRrALBZVau85J9>zI7I^dBy2f)y)?lSv*O5BHw#6Dina0t;(IPa0X zVW2V~k^0r^k!TI9s(e%U2C3e|{G6;Iy02yQgl7vixi_Hc-W~%PUzly$9a;n_CmlT+ zgcyMgxkX6Z4%XX{fIoU@H>fq92jjo=?{)`*u}Mm`d)zZ01{U*<IrxoxzFE>nS0A+v z;Bq~-)c#$|B%OvC=BX%Q*&MTh7q!-L4V3ZCDwkS0;A^jTPARQ*rry6Mw;kXK{23}d z=dT>7AahqIEJ4}gCqw$>(dox<1>x%f>W^%x{;<+@J*GqYWv=P*l7RNR-4aa~N<t-v zcO&mWRwk~!kIUIt;c^)j2_kvi5A1uNf=p@_$y(eO$&NyBX-1s{0fEh>ckv!~0WG_P zQ_^#lNqfhx=JN_)c`m=ZnWTu~M@Wnx4Keym)K0;+WJ(1pCu^7v+9k)^MZFhM<E7m# zk&TO3;Ok`<Vhmn=-Er0m7g5WMQGTDhfd&0?`XZi`z_T0vO`9;Uwcjs2#Vwfy#1Vw3 zKkXMyo2RCSmy&nA?{fC-V6hKYeCF{!k7Uz5mG*k0v=T=xIgZ-_ZErySTH7Jc(5e#; z3@b>_X7&cJdWh&fI`JRoL8j~{2I0+(N`<ETm!GNvL4UV$p!}*2{@rSHxht#*>763B zsTX<1r|QdWddjxOxtQ61%3g(u^n?Z}*;7yMBdTnRtE84mSz#pBa$cv8KtsVT>6a4f zc|%x+g3EkR?w5rq)lPhv!{t4Z3tXn%6Klpgyv@h#ww*-ItU9PhN!)A3ZH3KTSn_Vu z_`={_TUiTR!nUGxzD6kPrVM>)n&8W;xXj@)(BJAjdviy~Cvbgl)7F~8rVHIun`n^E zZ;iTswVZ#tdgXGPW0K{|Y8m;W_J6{621I!ELocd4G!zH0sp{oQ#LZ)8%FHgY-zFCp zzu%4Fw~<O7ynefN(CT4fLCZR^S%8-O^jM|SBTc6FxD+6&yi>~2tNJq8#xeU(INs<} z^UT}za+m1qju$0X2+tI}9Qeno1&<Ja=Ix(yN;2jEVgT5;7{$GO;rZ+B>mPHl#^rAc z?y$-*e?5#cZo*ee&pJPOwsmJv>w@v)cQAwan+AKzov$sv!gP@j<`uQBkH5QmM;@Uy z&k?NjDT4w1QFZcD<wS|7ahcnLwl`h7>e5t6i<h|ECQ<>41Mypp@g=gmoJHMhmNHh! zn-DU+xvc*64Lo`B5GM-#pjSvYxL#cqrUw8gIvR6eytLb0ZD^^uqp-B!UHO1TW!zyS zU+I4>5(727&ws!_yTZ|`IZSy3S0HjhxNp`)+-|#jNWQI|bZvUOR5yalO$1gdncZ>s zejEBhq_=MS{rY^C<<p9uK(LoK-?zVeK}PEZym_-H-^-w*g&|Eq9M8U<^Mi6xn*K2T zmXe0d*=)|)q$63`M<_|TBT44MszR)ej#D@9v<4rpiWsQyO3n95b*xt&9xV{WS;m>d ztSWL}F2dPT>2{p#WLR;a5F2~oB3+@IRa8XUm)m1t-d_1O5Cm<rYG0&xpo3VsJa`^4 zF!FP-?1#7*M|#0bXW52OZnnkExQ2&9^rJ7}UKv(Jn@!0e)S*ybqZ7HR)@focQXbIL zvRc3KyITJbBUr*(IWYBd;LTK=#HYXlyZaaz3g)Fd7%qc91V<cGcz7~KQFog%9XISW zl0H4JysY=A1Q2r8y_c|icVD%oPeZ-8oNSW?C1<&(pF_d2V-Pt@;=cOn<0c1#VoWw4 z%BLHAYi490&2fPMN(Q!Xr(lc?YW~Qb`ldXtCHUV?OA9xJmQ_>6IIfKT=o*UdfPyhm zh#F!>(3%wOz6}E|G8oyXX4hI)*m&JN>%acd;@Ru{kh^D>p-vLInec;305WFf;n+=_ z)SoWwnMWl|%UTVFqaSyV45DsH$M=GSyF_Xz>pmfRQ0W8I6rOI0#_yr?dI{CZ$gF&_ z+1-#*+W<BVnHou=3y-JU1r~JhigLHqCy$u7``X{!=t@?xzO9fR8o-?^LqCUle5;kQ zq#-kPlwMI@u&=F~61bgq0K=VYK8PGNG9=Pt{W`zZIuvqX=BFKmAdXq*t{KwPcyWgD zOZ}ghQ1`sy0U?zcUE>u=jx~=5AFeq%<~_N!J06}};5yHBft40qI6%rv&qp<z>G#oC zIS~eM?p%Yu-wcIh&EL4j_Xfodq-!31L$szm8yR|dwruh*MKyhAnJ!#V#zan&<NWUU zx0t)^+7!R-15yyT+<aQ#HcdMc>tV|Gf?2aLbGvK=Qlmbe%+lmm6myw*ko5)X25`|e zY{ZGKmDzf)%@5z~Z8;U?$Vzf{9DE{FGF<|5VMU~d0qKhlvc80=Kp+iJp<IY_2~FsA zBf$1GH4vXMlTTICEqAA8PT$UF!dy3KTgww=lZrR7V>CdM<EpEwKU~`ap=IcPYuQyu zt;i2d3EW5pU}Ug^Cm_j%q>%kPIKx;J#+U9CaNj!cz7F5bnM>zrXC~=9FK>L%;U&Dt zp#_wbXUmoSxNpD2s74{OL%0{07)wjj`CjgTmwPxiUDI&x#NTN@m6X6`Zo3lqOHH$u z2W&Z)8<3Jw8tHD%gV8_Pb*`DHpUWv(fkNI$`blhCiRmLpyL1jtZbK+AId;^KACbK@ zs3DpjAUgK~GHjFS9<B+Au%b&mb8d~u{$qex?B&EV?5el1$@E)cJ03R8S8bT-`#yex zMnc@2hp*n*PTzqQ`g}b?=~sOk?>RJi3?Mlp+n&>UpRY%F7o$^xH$21rDOXI~KEZBT z7$VG<7&sTJ^Qz`w)fh-9kf+}(_fp&*dn~FBeYXbs^@rGB8qre3cw(m>cgeFl$vIe* ze*NQO-iN!PCEnrr9OoywoK<xG+!k)$&|?3Xr4`<&+!@G8s-s`Zv6X<u#L+L+l^-DB zZgDwhrHtRJEw1$LC}G{{N_fIl7*%a}k}nGj2j?EKQfH@9LQi^xA4^v3<p^k6Q2WKl zKjqEFS~=~NTc8j#-lPYYvPxUw8FXH!!W8SKb`cc)GMhq5N^x6G`AAaVKf}3jQ@TcF zx@*HX{b7d9frv3T&#zGy5ykWyWTkGdOIeRix|*cM!4B@Y6u_2xC5b1I#B&xa#CGF5 zV#-JgM!ZMK+|t8J&^bbCZ$9%%sp`&g-G)A_q9~70y?^*7th;r_w7sPo4qBvFyT8iz zV~n0m-%wO->0EM*0WKUoD(L`;g;f1Qs+CSk2Q=XGMZPF5;M{|$WZSxcK;aTE|G7(9 z%1z0hLQu1t*FMm$rj8)I<~eyD&qtF)j=J=$2`_U9^zt7=2s<uc)P%n~%N$db0cKMC zbyAMA(hdsvi7?6m4m5F@bM;rJ{4vBe5tuviR{o^utSnzok?%g6{@OG2z>UH9HA3}N zr9GRZ8z<*m&qGBWU|QS0z{tGTlvsV&4L&Qs`eREkQ4YBmy+h6-l&lf&xe%jgm)~1) z`Tj@?1~|ijRDi^Beq%XjB%_8ulk+R%qi}ojwxHfO_;Y)hMugW%85qA?g^?Jqu0HO7 z)##*?(txp4m7pIfKzP)!eJ&L0w02e8ZxJv=K&xGEf}>WKQPIpWAmHGmrg+S!1lMpn z20+iV$UsDDoJwYFZD9!*S{`TcH{iOifcbS7qnjfRrR4RxB4wZ0jH425U%sT?1Gzi^ zKv#l}MrKbVxoveky)=!P7Od93+9xkYFxCrnZjb${!nN`y?!E)=&s{FJ4X8Vd>xfR8 z*EZ(`FpZ+}PID`(#wz_Y!A$1%?I)3C>?R8U8#r(`e2tZpm3+<6ga?@9r~~vb_T+d2 zVZipgIY~O}E?iF|z?UmMFeGf<(LK55Z5h+gCQ-mv4p#s6dd4RWg6rUgq%_wEng<pe zZ~b&I?r8!fUH>>E)qmw?BH#DhcT;sJCYCT)Y>G1zaaSefj!G0wjPQ2m{w<bg*}>Y| z5kbA!Mx5sI*``@BIghAtt?L)I8uGcNT2x^DJE}HWvh<6L==;`L`%tpua`^Bn68WmX z!uq|KS*7yc2(4*MNOP9kI|lP2MfqvUzSoZrUM4Ogq7#pi^Jo6SpGR!6DKlk;fmK1T zPrhV;*dx<U8B$YF?Ifsl6X%TzL`($=KGdTe#CnFp;>P=qF5&80Pli{2vReG85+uFc zdOzPJ@|H@O?ECE9Ht^Wx7jLVdrk<VuW-Z|I8yc-n-|EP4J|J?Kq;P$<s+XA%f6<j# zVsAwBJ}w$p_2VvAdSQscYj&JeH|HA`xRMT8<dTGWJ&ila`If-0PjUhFCMo4aEv2*5 z0p@GI&m0%Ifu*f4qT;+k*1bc8`iK3lV+L>20z!9MBEj$sr^3_3)|Uo~cU+gFNd<-2 zZ$}^k*ifx>hpxe4M>?|Mz36qVeY~YK$<DgDLkMuB{{?`*J?hdHYS9kC$>1^NBN^XS zQjV#l8LM`vF}gII--Ff1N~GLtEK}A0E@~WG{Z_3NfEs|hXJGbwWYE<)x(xT!nZ&SL z|Akova>QA9X4v#{r<&ldx4^rPc|y~RRr_tz+Tnh()=nX*n*38XJUbk}A0CLphP*P* z^zAOjZF1`;It6`#Kd^B9FXIF!Ib<1niVQ1|y5s36eMThR-}Y_5ABO&)N!_$D-?Xr> zM%>Nb$=3=FLu8obF#VdXDuDHJf5j+R&a^N`-E1n8Rs63aVw8xaLta}>Blws9@Qt}h zSX|K3o;ZC=gR#anb?Ei?{nXq&(devSWd59NYhE=}eeKtr$tl4>9l9gkFzZK21e8wR zx!s{(qX|C_2>JrCUu2dE?6?C6+pEFt?8iiZ?VqW!(=f@?H<xz{m2%GI9=dpsVeU*n zul4glhU6diW_ZypFiDSI%k>2C2LCmdCpikGJgHuO&v(nRBq!l5tp7lt1op9_Pktgz zJQgjeyOg_LUDkeajP^0Wnyr#F{Ke{s=6`nt(~Do9?tCr&K!qltuUu%<-jyS6kQLs4 zBK?C2&*cN8_eZbVAKdLwvgOkqT!G%rqNFmULvi@2sN;+#ar)BnFDciV%z2TAO<?*o zwmj)#m9~#uN3s+3&%Vot2?JzmK`UneFXL1I*K?!YgOhe53UTfwqo5&d_Vs@OKkj~s zFb;aX`?r1W&Hdp=C*awyFPSj>g~qce0i2sGisWF7*Vm}nD~~E`B4*MqKimKJu23J% zXO#5tpU~Vs`*Y^&gKpD<77<iU71&RMol}X~*hUZ1g_T|FBfemUGx+-yG>$RzdVOJz z@M4c9G4-@g=qJdeFrX8F2vsvrovbE=9TY%kyeDty(`Er^Tk2%ZaHaiqy_4@zL5;_q zbHj2fn<hcp<sZN#l?Piwi$`>FFqO)0(7l^r#d>?1OC9m=%(e!v3Xiy!nu{seh4G1d z)RUT_O;6@D_LH0At@6~4EjQ7#MOJAWB3S)$vFz!OTR-*PideE9qVq7e9B_hnnnQ<2 z9(UCWfO7Q4862>XG|vkc<}?!f`}x${L$5Xyr`Xa?J%u-F+h0!Kay#T-#P&>S97kwe z@CaCB#N5u+b}kL6^6uV)%;(0<Y2?)VC_1Pj?+-kJU005A%2vitgjQx67K@@v&K<Cj zSlAn=gd+T9RO>U(z^N}q(THY_UP+;$0wfA%noSZstdoRE7ZFNyRIS_%J1V1?0R;jZ zTKnw{xVj-&O<*}~(q7^x4>lADmvFbXm82t$Rn2~eob`q)puK?BxkbWjw0kP{5N6E- zw~vN24GNQreugNQ0D!Pj36ouo^@mkjUjrs>%CN=2Hosakz`CjlK;OS9!zm4(AU;A# z3gv{G{o1IYh73LPfHb6r79dV9AjRHTxD!t@)1yk2Al*V-fHMkpi1<yYh{V*iFsj58 zJcb{Ka{Pl%<%k)Ysx|eA%}N7RmI~{6epTEq-qMySw5F-c)r{tRU^!E%Y7LDP^#gQd z)Eba)mDQ=2<sWA?LTbmgTAoHtu@NhXDbmruYMMRlME2-e1X`Wh;xU)J?zI${H$;$s z`(WG61MXgD%yo&9F6B(4kb-Esp115_n>Nw7`~~+)=dXx_8)OOe#$@+C--ADu&7OaG z0ncNpiljco*^zQ<r#uEpP@A{mfQM5E?NtI)bVt?enZyb#ZHhg4O?}jdd09$xhIEH; z;cuH2U8S`iD{eOU@+s`}S``*{n5Z-vFy4S{gI{7ZI}#zwx5^+^`VqKJ2?TadB)Qnl z`HXr`ht+LS0}uRD2y?F5-yRht;;7Se9~*a>c5irh&!1$z2{G#+{LwUaIOA(Wi?1ji zx4h@+X({kCHAlI%9cv}Nriw2j9R9uJ{QaYgYK^(SJYGsfN+rJY56lgBTR%nb%R=;P zQd&M|uMoa8oiRD_LVF3`EWryc&RjJ+fz*b;saIJk_6Z&M{qc@c_wKj9wYPe8ti)1i zJix1p5#iMDM<Q!gwIOyHgyMH<$v`ma*3l8I7BP{IN)2?k4+xVSOq*psu}7SyN*nE# z2#CgE-teM(rqh_N=9$({uMTa1Doi;$XOQxn?^}Qh(I%6GhFr8=Otm#%23V;G23Ki3 zl$_LyCuQJXTE(Ow|8Ckdj+?tZLFzT7uH6Cc9^3xx`Jp0dw&nyB4%vGh^fo}p#K^AV zD>XJax<j?zZvuUk9-l2(*L<KTfx0C;@4p(M6$`L%e0;U6S7aKd8g@|X)WP{K2a#rG z4yZ@(kk9{q3CS^Er}TSemuOC7Lha>&DDv1o^c*{<s2Hsl6(TQ-fU5Qu9^VbisiEaf zqh&K-=<r&HP8JgA^c|ZZPjbpFk-5h;1e>=Nm{N<j!KZCU3^MdPoWs7L?;L(>ICCGQ zmQ1M{linrR1|Izt5PZ(%487QF4)y$OLo|P+`#!*QND^)}dvgXa&nw(Yd2d}By?8Tl zyVd;NeKzRUVQoq<&Hh{BhHeg4vHi+LW4;|O7lig2ZWFKiJ%u45U-0J4FNj}U@6)`N z-Vpz&FvCKI%S62;?Wj>gBYj*2pHXW5Yope`3h_cPNhchU!hCaaN0G@9dgZY<vte`1 zmS0lEb!Jm18FY2Mf13C0FjPpCw!f#@F5{1TwSBer@@=p_X-HNm=b$(kFG0_-)z$s# z!T{Pp&1iKs@nqOtwZYSk=sMS4D3D^hRzojIw>uQid#n$~-=Q-k!_`0P<DgCTNV)FH zeZe~i4@3LGy>M^I<y8T=7DV!#?Wwzqw~{DcRR_y?2bdcfhmjhoaXaSng4z3NwgRP! z1Oy)V8n(A1h1ofYVIT6ujn+!^>1zpw(=YZKHY11PXjscW-DFT+@<o7yW|o`E?JtJ% zUk)PetgEQa)aO?-yr5(uoZ^vy=lVhR5jc$(C#qX*!8}$OUQH^~?Z>c*=bxE!#Om{m zKT{!(_%=NG9|RbB45{sBsL<z!6Km(N1zPu--_rG6?UXE;sBKmH*MA;Xr<L9{I;y5) zu}jPgXXS_S2_(ELpH51~X)TysB(66)Bm-<bXHYcsn|RcQ&#lRSmNQjF)s1=CjM&zV z(goN9uT_6Hiad`TWXQWSZ_4Vb#;U_YW#Pd_+UwGCLK%4OP@6QS8|I$<$Qd)(T1ZsI z)bCK?vVC#=<Uw!s0$1CsuXB2BAFfXzb=^fd;&^p`C_jcY!&OCAbNkFHj!&)|s68`? zT>6oPF%N)cEFeBG<_krhPYx;4OrQA!^8Q@OaUn*2B0+D7VAv}|HHKm|4Qo5P4i{}z z#lK07;RG7V`&Jiu+1z?6Yr2+7t|OD(xqga^_rtYdUUy5n4HQG_A8?csSbTuw$Zxb0 z6p%KoLmq|=`uabuE6-f;dt##S>TlNR2I+&4(a6rqzu04hnqEzyl0DhBh&kiwkBovz zqEp(EzD<kA0XpoqvW0$}upV2ekAGc!Don@R^;VaWvS9Y8Pm9oMS+EAd#d2k}u;gQ3 zh0Mm9k#X6(8pmjwozVn90s)8JU04eq1+nv7dCx;WB0<%Cz<OO@<fg#B7IS+TN%G9T zfA-^FU-TxSB{zw+cV9W=x+8H!yDMuu@ncZPcpu!UKsN!1(NyUO;x_xKMfAleyywEL zQTBH=&!w-e!22W!%NYYXe<eAA!>L>}!pZsETN*nzm5wd{C*;C`*IU1o6NijZN9 zsb0AeMdF}EFv+%3&>(uSzJWsk!auvxDfqdBV_7Vv&lMEC^6&Y7A=~aN?qFmg53vWG zMOPdYxmEjn0163AF`()%C0$97%KZDU^NHq+4Q!5swfyt$K?E#%L>>Ul`KTr!O*>{v zQzE%eR1(OO0Z0<S8r57z8lOQ(FkHT2SX5-?Y4Z4W)XEEjUl~uVWclQ^J_hu?<ki|p z*RU8z{k1V=qznKhaQySIP@riZ3|0ui%z&6(MKvN1z#vye&e1fzOA~tic5(ZI0$Z<< z(^Fc#`0ci2Sv~^y0?nN)iHE*cQS`^L!~q!!Hi6TGMc}X>G=T+n&*MNZ8qzWl9oZ+0 z7|iWkxrKft(&1i@9gZI%cEug*<RHt_lilI2VJ1|=kO65#9(H7af6gJ~-~a$aOIkur zG}y9EkJ?pjAH#|C4Eo!=2|R-(t7p9e8wiOgPc8S&P6#3!4Coe@tMU)shUXcMlwnx| zq<{f}Ij31YpQIiO3tKTk$pc;iN}ss-tLW<IF@S@go-034|Jv{(PF3Z_qnFPK1_Yyo zfkqP5aFUHj&6%(`fx-&x8Z|YLt)oQL#RMB94*zDIpv3GaTc|<*8ww`Gxt0RGDz@Bj z0`qk(ct|?__~q4P810WYOF@lbMdLJoUlAL_J~x5}$N?%rvZ|IV_TVFq%f%5*S@<}d z8dLgtfOVJw=jb!`Xyh_CMAQ@@n-vC|4HB|usWRI+$V3+L6Sv)D@HvAw1e(3!<{SHq z3P4vf7D;jM5YSP0bxD@`A&_NdQi5f28ix=Z%%CPU13C~a4~1alH+VRN)9jl9K0_ex zq==P=O$<!&V6$qSO?@Q_<x_a0wT5T;@c||ZKr2BBPW!-Gtd+D%fKDIjzDevlL4=`| zFvNSJgC^T+R!yAFu~kHfKqV52BNp$9?n5b4RSa8iCE-#miYjKr>4@zwdpwR%s{RTe z>^2`jD`W=xuj)_;Cc6QIfNCpulur<GOO+mup!FL}$6yz%`_X?}2ao=+*%Td=T84~r zOpiKL-58QKZW>UaOG$P>OcMy%j9bA7bQna`*)lB7XYf43{`8%2{2JtPNMNcdblsGo zyFtX6QJpjWv{m7N1U2fMJP{=sN*M^j1RI(_i9Rf9XE3giGt7r&nzZbg?5H9}i&cCh z*hkbR-%yL1)in>jQ$xYR`uyP2N4z;Patd88N&vD3zx~#P9*)~kqTm%mtI=k|RAA9A zMOa?XL&eLw5|329sI;%zGjgjO`GTM_Rx3JC+)BVj^lO-~h`lP~U4gk><>wJZo}LP> zYO1L_Rnm!tEhHF8ROGa8uIki2GN;+D4z4uw0U-m~d|V{S6qTf_jz8E09hOdFfJtu+ zHGNY$i(uA8Fh`b!NY&n?WIo$ld#1v3hQ_C_@M<oC(-lH)^P}j1grbj#@TN7*N<67G z7@t&IAoqqK5o}brdBPPcE=Ig<|0-q7QDm*m<*kr4%HMex6$V<VCgX7-1C1cvFkzs< zrz%NGg@zwAVN$trI1i%++pKAJ2Sv>vVU<}3il)1sUL<!)NpE-7SuGj72^*_%RKGYB zR|&C@*{8@>QeC#6Uq4Rs=&ZPhfSwvtz*i1D>?wVu`}l94a&b|#YZn+MqmUyuXo!VG z%Vo;{Nyd*v;Fv27>~h`IO=)&;ie(Ib_jY&<b)@~+f&AcPZ9cxdsy~d#lkFGA$E67A zrC5jKXgI?5+JGKtBC(;k8rCXTVald@77^OnwkbQHZOPmc&DQdAv@7=bz*}*7siBs- zI>I3CkKecqPGJ-=7=jsWkUD{{<TN_~W)#=YLU?D}Ke`{FNRPcU`6g^!qa4nv{my~K zU_ovB+YQs>hdS^)_BH3+v$@VIF8K^9TMoX`{6wtGFfoHtM#_x-q;n+>nB;Aic<k30 zWvq812906}GP}ud6kGtKLH!OM85zjoLe9#pRI^C}E{1pQRc!3;yDP$T*+GLI)q#X2 z0$L1e)<v!101ne}-j=l0tYIZG`jd5IE~xN`11k;mKaBeLv@>ce_LQK{R&)P{h1FC( zsRbYV&r2JzFRh>dmMs|mdC(sfW9_aER8q}Uw8By~W1BSb+uFbIP~peJ`_n0A9sLrl zzHj`&I&VJ^N$PFYwJWiq?Y~Zq2HiGmqD~c2d)xEF`k&R1S@?)oz~P%~$DzSWMB@nR zw^;23$fxW(2SgNHiczCq#5VV}CaVyE##J4-ez9xDEk9Dkz7LfD=-N-jKJSe!9l?R2 zqU<zJfvsGUj!)LaAY)tjw{qpislQ@0Gi-AcR*j;!{nn+K@EDLW`{-sufD_VDzoW(P zo*o%qqp+J6qjcX?Zi(LHks9YJ$dcGsA`mJm3QwKN`ERv)eF3hxA5y2wz8illMypUF zLas^!(9Pjk|5;4D+|kl6)=)DEl~Bm(9;kgu&AQUWle>G@P3v2*%rZPHnP5BcTJA&U zs||$m+KmlGVu{|H%J}4*ycJ8LPEv^?DV|VFMK!1bgN@@Cb9lb)Kwid&8?-bvHJs`h z(03=A65s0a@-Lg~8+?^C<mFwo)KIL9G^vj}*bayo+BLC3ndJRXOpEj|r%ctfyC&mL z27=s&Qybp;fD?5CGFP>LVzkMh^f{w1l#6F@GP;)9d@u2%CN{i!(>nT1oHzAGgHs0- z(@)_e*5NisUz_X_-W??lEJ}}I@CnL=YS7r7H9-u~^pCCWVS80xS|)US?6|+(snlZ_ zkEv45Xh@9Ka7ZBrs=KqM%==_^clSAfYW!mmRIZ7q6WYbpymA^QgWBq1AxD)5^?y*_ zaU3MQYu$PBg-_|Z69&E0jyb&7-ZpwG?Xe-z$|2rFwdWlK5AWqQ>=9bedO1cLi$f14 zpz-VX7%2{^1m!p-VuBI1W$cj2u+j-_Hxl0vhSSJZbYI>y$$*v_sw=GK8qP`S<?zxj z%Ptk0a}5nm%hw)|`deL#?Hzy?)nD&v{Ub)yQK6aEMIG+tJR3$04AMkz4r1=LE65t3 zb1-;Aj#W6LNTd%;)JYmcXAS>Ihsu99R5gxKe_wL^wz<N94s&w|(yOnc2+;duD+qIP zu;I=Zq0#p)UbR1bfa_#OGQ+kolt#oO6=R)%Tom}@69e!5?o7x%@n?R{XTA>v?ky^P zEID5#VNBGQ*c`=h87|xBGGAyW^%>%V=Th{k6~$a()H4G_qsh2&dP|HFu||_KyqD89 zg0SgAC66#%z-qK=lHD~E1~1LrhW1UEevW7VQ_b*?mwyb-XilO6`gotAPy9}5uex=c zO*L(&YWT(E+IlAZ=vOwUCO1U{mQ$TJCX8jMzr=)NHBBhSCa%{wj}H(mwkgIMHA#1F zaDU60$t08=f96!|n#<XXtJ=HxRaQ@|jw_ziROQYq{9=t-$hs2L1VO7i06EkX%ELQr zBvfrg8pRK_;+3GrTeZ&Q<HU|qBjIZ&GhyY?zuuZw8;1=HCk|+quAQmue@Q;B8@_iU zh+<;$N{ow*jTeADF!P~&G6k>}3HZiB>Pf9L`+n-@?P}BOd>l!fnPo3lw-Q1nFX*Lz zHvK{I7Lz=$3>6PMGgTX+E5T`&#|cXB+fHS3*-p~hFFfdeXPv;3H<lmt{&r1wKIvKA z0Rx8CD9stD1l5AR+={z!bMCi0)V-ncotZK%jT5U<Gw@GmIdp^OglbQYAT-q7tTQI= zee~A5yb(e68nmg<ky2_@rfJVcbZ^hPr%O)rbxi(s9zEQa7ao*bBWV^;ZEo^xWbf98 zU1wupfa7D@K9~oI)H9d~nm7{pJL~*DYk+z1$gl5<<*vco;&n-!ZB*urICS>)1%u&3 zR<za+5n*^%*S?N90L>I(|NR<igokp4+D~!*dtFj@90$D9-{`M5F`pmlJ~`X{vN1eW zP~Gd2AuuvJt8KaNX+u1eL}2dsRYr0eR<8O<#IL9IxG6Y=W?VWU+4D0G-hOPxKfPxb zG7@UeX$;!c-JGaI4B~HeeIR_&k?E3h^kZne`{XP0%9oo6mY~sjc=J!&6^c1OM2dKo z1a`{($URMyWJ!I#hlcw|iz};q=7G}7hgjdo^|(lQM7xD+4<DW<?ueQ$A)yc_V?YR$ zC+e{Nxwcl_;G1aZ7QqezI?MnZl}AX){XjWQNc(>*q>KZThIG<npFWGH8H(nqr03S| za)I`1flMoho5rW#&fd=rcP=|}Hr+r)$yXOp=U9Vq3wz<h2h4h)h`S^1w>_J~o^|H$ zM|-A^7f7Pakad04x>e`f<_RZ#@10s1&cB&2X-j>bn&OyLph5PRa(r@00@|A;MG;b# z8}U3H{3t3j#lPTt;c?nPQA?!jSm7N%*b$M+Hl6J^R2)p28=OptuJ0!6CR*G~eA<+M zO^@#;54rG!<GxhuvD=A51JJ{dReP4gV%|=a2NM@3#q)i+&z?)1S2OFEeA$;Kexx*f zVTkjpq^!x?`Nm41HTQZMbMNBs?_X>T_ManUfR;n{>JK^K8k4>EHKJh>aptvbKCknV zDm|2l+E9a?^YekMUjkc`1A_N_!a7s&Lb2E3qQW{|5>fB7xRHSwQw>7e)H>DJZ~I9Q zzz~=m7o*X~uMMmd53;r5p$@Kgedp~yvz80~kA-AD(nU*P#O372eQ^-?z5GXr%*(T? zWe#%VTgD6*V!pEGS<|6~1+RD;Kwh|BuDRsW){L`Y<HfJ$!1<r!Pm|++W;^_Jm#!H) zg3g>Bs3td8O;+|A(8YX$RBea8s4(4UUDgjrUx$77qIX#F{K~t3!#4An$3{^<7vKwj zY1K_J4^*5?4w{;A+X!<#GZ&nFslGN)hmZ|w1F)2*$rOjV#pvezk;1z=zsCzbfsKA4 zP$*us%jT}5r#~y?>$)p21hDFT22t@ZFMMfJopj_Aeyi;lxRA|?;@^)S>XFDWFnXOL z`KsnPe&x4bKP<X7w19S8?_S3nfCXfv;si|DhukDb3Ptv#Hi=QM?^d}{A<<UB*^zgC z-ai4S)aeD1Ro&MgUjD=P_|WZ3UgrFw?cR|Wue6=k4Pd>mA`w19^~EV1$V5x|>z@|i zmL@M)#ZcmZI&8EY==>g{yJHV~7xPA`;o-c~DIE`^e%7z1+EZ(?lf_Kwf|U0o?+@P- znh?i6T+Y46at$aKCwB|IfAE<Ov4H|dxL0KWbC~NVwRRD0i-jTiE{XEvQ4B@fhVZbB zQ`QjAnz)(M6D62;FsTa)z%Y53ev&V!%ArA@-Oa>t>)HywEZ@IoiCG5Qhpzip!nn!D zxP`d^r>^FqAMr;YER{dxP$9<MGXwm8eV6}xdvYS9nFhYe<{%57f}Ot)epPQVPnqOU zzest_v9Q)kfhr${o*BlzSF{9JkaJ?S{<t5@_bEtZvaE*ei68h|_c;K`yG<$Y5&ekF z`~ynpvM50;8Ahx*1ybGUGWGq2f}cqC&DjTbL3H)`J^Wcn&e*yijO@fm6oE!Ue*tlQ zRP$4yjDxL|!8A?Dgl28NyIOhvKjc3gQq(bf_(Xs)b6O!AJgPufK=jioe3UarP_o?8 zbEJmW8ZR&p0a^o)%E%D-i8Xj0pPjUd<2cwHu|FzZ4FD0n5Yc?|k#+Mxrjh_OE8byb zxn_fD0a@nzUmz1e;--b5v)xSH)vpfNQpnNqJdEp7zFdG<&m?&CF;Qt51}utJW?gP7 z|GfcrrWPI`7N+oGO-MU{D2(7-2qFkWkDgq7=PuM@)%(9XM~R6m011N2!=-y4Xh(0j zuPO;*uoQ_i;5qj&f_tq!Ww#lfk|)HM(DB5hJw#%V6F{8i0^~C&;NAK4EO+t3G_k?! zryXDxN3PqbyRPy2B!%HBO%)U1d6nD?Q1PT(zN<GNDSii+B!wvCe-Nz54FIb%b<0wU z(oza^$l{j(z(`{)n7fYx?jJ3hmC)Uhu7}MG0p(D=ixaGj=mD&kZMs5>5b$Z1=*ZI# zGmX-^B(+ABJ3!c&L-N6DqOA*Dc%;Hf1fW8(=)Z6>-)V>1OQI7edPk4=rbL2wNY(~p z20gmw$-Mqd1aCNEz;sb7;c#vG30?KF0)SBb^MMH9Wrnmb<^;+LhlXB}pHbqDp|8lR zf8}fO0G7_6f62i7WGPSzOZ9HIsIzyX;p~j%V`&XyifZB}Ts-zHn0*$r%+2n3t4TC% zZ8%B5cMd6SB!XRgAOEW$FsPM~6ae7DDWxwZH;JK1A@mrYAb(fAwQC5;HN(D}C$>pJ zQuLuhoMra@(cQ%SZey<AEd*xbi6Zd^PH}`J?RvsPi}nE6zH?c3t0?5hbJ2*7XUecd zgl)iHN1gv?+)`3N;9OQcceA`NFJy&!k?$T4d=sly94LD)Rl8k>TPx<66R>|R^J(ZR z_TM*S)u%J5=YQ0mmGxtWsVOiK-uUAjz-`%6lDey+2c2W7hR%+8pnj%?d6~qJ*na{* z;vZGtwD)t8M~U~YukVz+!Msg|Ld3NRDPOAl7*r=@wct-he3;2guJ5e^(obv+cwHTp z1I~d>dSI#UB~i2F8SqNdfMz-j&|MEIK`w;oSe!#1iD1S_53Nu+bjIAOcfez*FkhH! zuE74J&P?|!hK5^6^_LZ4j8U74HTw_qmk~{ebBftmeo}NWw!#%EG!%JwFWlWvh22G@ zJ5ueCE$6cY!=FUpk81`~9V7w6c5NVj>EL|;T-<B7?^YAlKucGm9%$$&pHgGQHQoRx zavLt{yFQ_9e_P<vZSO|Q<yLprXG6byhH^T*Wo(}Z%gyO$n>RcXU(a15D~x1*tYb?0 znXPI*98ni^)ke#|L5afec?ku@W(u!8gTm`NdGz8b8ZXwZ{tG3HjUrAPc~;vwe8H`m zI6QH@x3qV02YX&?mI`|bUMX&x>boowAV^DU+&;l|=)ct~M~v%3)=lu2(+BDg4esaF z4Qd`aDVx|mP^mbxvt?3Z#tgj2?(&2UY3ChfVgv^>jZV^J4mmqex+KsRhwAF@$1=lT z%@_Um^7lJkJxiyH@?uVxMi+SdNs|SX?pRv5muInMnu*jLkqbET`^Oa3wrJX$yLSb9 z=ps$RQR0Z&rMa;Xq_j?VivP)AoC1f#?z61anb5NYtrN&Fd*X`8)8_5IMq~y5P0@Z~ zsJhqQ=SGNMA^B!`oe2K-mNN9--jl<)gIX&UI0SI;@4pL2<CD;be}z-Vc!A-F?&BEb zbiat%%54MO^3n%(R&894-9K*p9OV;O;Q0ODXHI3jgaA@JC=CQ6u9phD+YfR^Z?odw zFFy&=m}@;Xx7aY(leJLX0J;NETw{>+Mh@R<U6+km#+ImG1f%pR7!)yOmK6u$pGL%i zKWf3APs8ms-vuBKlaO1fnc|35!9U6jHW{o$qvf)y`=5ZYtewe|AUU=Nwi;YL37UKc z(?M9=N2`uhNM|5#%4hzLUZ`(Xmo=w!(W!acJ`tHX1_pUaiTS38ujj23nieY{j^{1; zsN+=$?)C`|2-q)i(vfVDjye(4lt|IWq!@lmEJ!#s?j@pMSUiZy1RLW%f}JBG@=q@a zQw|5L>;a%qPWk;-HF)3qUUuwg&8MtSFm8^3PdSd5w^87}s}_2L-&8C5P{P!DZ;E&u z|4$eOc{hw<QqE8syI-WT({G>kDogUkq-f}q_SjQ$hx*I5>Q~xbKGQUU=}*j*k`Vy; z1kih-#a<|Xq(l!b3l9<+wC_~9mc9-2aATwn^$Xu>2J4!^JGzGk1fr8%Qn2H_%UDFq zumcJGWl?2ldi#s($#hE_w2H8R@uYlKaHYxgMo-^`G3PKPnBQ`*0I5Eu^*zYe=D*I& zLbAC8A!#{|oT8MC#0hZAVf<h$PU$TkPj&L?r_a)rIhF+^8c|MDBam1K*Q3<fN0QN} zxb;tgtWAu*EBeo8HF+&MSmSV<a@ajYYVhdweX~APiF)Dkh=%vn8yMxA4EtZk*jUdg z(CewpM$0{9Bqkmw=HTEwjn_DmoJ2!2^ftA5AcYF(Ct`Z<_;SggYTvQ>5I61Qc=|cN zTw|X9EM=#xSCJ{&wSux1gz@8}ncJYPNGCV@+<Q8IxOz|N)H?~h+`jGi_f25JRh=CY zn8<{*_8IBlj!_G`s38)TP<txLh0!@SLasHqUZ2W$cSnM)$-9c-Wy9}mfp=WeyzCDB z;W+#k@m3~iK5i7Hu?Z$+Uoo;1!HNI^nmax_zxXHuIisLoHaLG5y;aBDst2v34t)|i z^2I@WlO`6n((&)^Pwv$Mhw{VXtBiej(oPUBK)MV12_g3E%9c(_eZ7VbBNP7h$+fx= zbTdUsBM~UUN++CHv6eyRZ1+?BcBWmz+fV$m{d1)=U{R*cN5{wgWD$0spH>>2TUbPF z3d@hrDnJ7CGo=W~4FOEe63`#Qj}V7U1FWK`S+FJ^Gy`I55*}6d9?AI(^2LK)0TK`2 zbGYfEUkR!%XkcXcz9QH)aUcE#x$&ycf-0caSA&6J8x#P_C4C))tqSQy{>_Rpuo%@4 zp`=G>OO?bwt%(Dx$=32gJlbu~A;Y}x98xsg8%pbih&nJU8$BQQPNLtDzh4-=2TF+? z;^{XGHyrROH|U^>?9<Bie`aQe;JV}{!7&j@w>&PzX)s6_9U=rQ={uF*1>-XJi=I6n ztaO7^oXXnf<H!68I8`{@sv|0jra!xZ?7ySYrZe~KIo=)l(2e*Si<re0+m;``xiK4X z3N*NdTpL|N;(O-uz;6+2h0oSnuthu9#HQLnFRcJwezN_5h?$j*$2cgXn=b6IGkpgA zR!~fn&6Ltd|4I(oI~x2H=gG4wIHrL?<$>5VGIEBWr@w(1>s_@CjvYgjm&MMuzp{?$ zR;ud-gj9GSk7r5W9?zP{&VsWif19lKBk<5_u>t%n3i5b0fw3nLB$3jmXNZP(Eel#E zBRkp^_xT|eN)&!QF~rM{7$d!tx*yA{`z|a+GQw7b9r{F|Cr{gzi)i8M9gbNEtwxlf z@-gn1$8&i8?@wvv+6yBArM(DRvWObTFE24*Bz?Jt*Hm@djvsP|H9f}7UZ|XNF#{96 z)JHk%idb@h4P+2o9_WG^T@*}AGm23R3PuOPJ9r(F$Oi-hX!Y!W`VMD<`b1iyE()yt zR48ZkXBxbA-kG0_$Q40H+>`G*>KJnDg8s?-_R+^Lh~BE!jzg56bJj;MdRmLDavuu% zk0XGG%j@#jafgk2w+%Q%`Nl+s?}5_}XR7a<!#$GBAJ{=c@`HB2p>qACgVY2umxUxI z_8|itN0U>{R^BqRhZbF^S{>=GZl?F1f<{J6ug%Dl2h+8jc6Q50Uk9C&VGx-{5rS0s zOhTkl!@_K8bR6RDGIzt|*G_eGOv{D`f4fP1;J_EqmP16Q5rm}u8bMKunO2e*r3J^b zVNseYB|&fY6`%f9(;OH)$g{Xc$og*djqjia$wJxn!&(OQMuD9E>O#nJx_@j|<1{gC z`LvfFIstJ;-2>Ah@Eryz!q(jp%Odml%dK|23Lqg<-Ikty=e))Q{|xXBMDgozpv96? zM?MbW8My1NALh=W+k5A-qMT|A!T0W;LwE(DeS)y^3=7@dCAje0Ksf-E+;=EfbaTA2 zqJ2izk-FE$6bV`|`FuhU&mC~!)ngt?zZ2(i_8C($|ELhzHg_m0?U}*IGJ-udXUx6% z37z!}Y}L6Sh!>BaTQ?em^4*Y^ZOWVjhkkgZry7N2yTxRS;YET3{*wgE=0KFw)yp@) zjguh<ii@jS0^A3j{;$R_M&@(2R*-1B4>fNT^gg88zg*2m*KLtMB1HK6&+||Y?FQP& zX9@HhBJ0la%IoBsGZbD-oPF^Hv-ll+JIPsrdX)G<ERtMt<eCllDii=}jQcZ3cAoZs z6xLfgwG4n9SfQ@DbLZ>Q5ovb3{rqBWsp{G2i$B5EEo=T&xunJQeQYN<m%R3P7eme- zcg=`C(DDHRehA28rE_PFZ~3141bXCiUq$3@PNJ*by#+CizFI;EyfObO*B~~lHxWHe zs{W)Qa<Lsm;Vu<Dhrc5?d@!Z2#H}ekxb}l_Qv~wx6O(7*V8a=OwUh6@0V=gQfH4k$ zzM?LK7lH;N4U~mpPCBaTXfc!1f84AbIF4)L=Z1G1g&^0&cF{|%XGDXXltqCkFp?XS z=dZ<Q4e-;znAcdrC?|Mc02Ek8^}2pj=|GB=C;srrEu8@8?nKW=hEm&a^YquF4_`7! z%X_V!nop$`PNPTKhZjwzQ5cw|_@AYK#v1|9qR5B)JgfYRiQrS!(x^1Frsp|v47^<V z!B5Tm#kX04m?pssn4OJlkw3~s*f+TEwTMG_d4jkz*6{wZd2@Mu82|t|jlxP9@+vRL z_3@fq==Ap}^wE1_|AHEXKzm)~x9_VC=#oE<%nUw!T^eG<Lj~icfL@N>>D~rG{BVw4 zkH>Quv5)%~OK`B`Z>rZ&@9xN}Td$Yru3*MdGXfY1T#zo_v|m(g^st&p(7hv`+3V(f ztdzOB4NxNLtjk4{8)<o=wkBWaJumE$EBo71<IxyoYQTROWGr>l8C}{5{#XEQy*{sL z@SlJ2yy3P$9<_86Y<PP0=nX8t?SkO1fX@9{<*Gy9UMxR4fXCS+aRL$WadGo!=P*i= zh6vLp3u8%iYyr2&or7OajVicNaEk94kf!wK+%8tY_Ghtm@)<-ja>?o2@cdB23$z}* z*b)ujPK+;^s76YQ?sc5KRs`nw$m2g@@b67ed5AYhTr1w;qD=Ak=8$_`h4|3NP(jaN z$*E#!VUnB(_&HvD_@aOx(J=$;{qe%~?)Y`_+P`E`i=Y$1r^~p5*e?seF3(s;f4#cZ zuQspQBAPz83+B1X02G9<Tp##~CG?A&>bjVl(;9f(65XMeo5)B(Bw$C4m+gHWWM9dX zog!b_%RMBwIDQf?H~UYJZJGG@>;BVTzO^lWn?Q*}^_v{aT<M-R>AqJG7`}g4WYLSW z<$tR|^N^4~rws&RpQ{U%XitgYm#3Q)gKLIRCtK0|eXp4BR*vI^@UJ9R<tU9eibnJ1 zQSTQ(zB_-w_+BWj7uI=g@V87w(XBPX{(8<o$A9so|71$s8`I~_QyJHLmO6TNCavvB zUb!jzjPft;Bkf>%z&+m8!*c8S1E+!=Bd^J9;Y9ntpBxcH;;1q!1tVBKv*dL<MIFDC z5;^<Z?NJQB4gLN2(>yQVazMzpoakbr5HgZnhJ$l#pPtuY4>Djgpn2|OhGaVYp~7sA zA_kRitMZiIr&~3aui@KyaUZT<{rHBC_hc8NiI1EqI^*TAkt#nyE5>rvRM?asI`W^w zaR_KNA`M)XTIotRyzOzlN-43VhT&A5T57JiHEWlvM9Wbra`d93@kijB5Zg{ec`F^5 zg?%x_N-+nce)tDhlXm0kP=<7PcUluQxKQj8Bp?^rSZ*4xWbcb1B9B{AfIkec2qCiR zRUgg(1Jm}c{2HIjdqvwPiR#Wkgw%%z2TNJbA|xUt9}{=~?3b{iBwfr2U`9GBask>K zz%T}i9p;1Ee|%XJ7iWV(7thiN($(-HlG9|heHOR|6)k6)J04n9eK`qIH6YR$_x!Yg zm}-C|t=6_6wlAa_ie7`q0ZVu;{0-JKJHm~NBU51KI+X0hZ?RT(X2K<5-Ugr<q}cL@ zdb$!;6lubEJ%y3rYnJ~ygcDF)Dc+Z1-OZ2OgB3zBhmw#KCI%QWgrRvPVL(BXX`(dK zL=y%S!Wj!WG)O}pLaC2KryvEc3-OHy4lMA867%oLIUFUTphv$Y!6R6dpl3mZj~v@G z#1NHarra5YS#GOiJ6}k6k~LI0xHB6+#`3y>Q91w(6-nbuN+qYTH<DI)3I^^on8!vG zE2S_gC<^^FyQ?<>Uv&%-VypJiTON;HvZdY{(;Bajv6|+19d*XMXwuzJgPkTPsM^0T z(;$3uA*RD05*HOKQeYTZ2qe%+KK<S*cJjkRMM%syxdhT7z(7<;F6&DOn}PBdmpD4q zp5Pp`qV+iLZa8dIxb2E92U*lqVXZNpM>PT2(W*yLbdt@Qj|*NuFKXKwes*>AR7{JZ zHa<fkTpPHDA=1fISp1}P_IA0Z+&?X)xKa`L?PEOu)coRSoa7^R%lSnmT}Xijv$isD zcpw)(5f;xwxLi{(DF>4!wtH+@YUV1qxg_n>lop?lSM9B86SMMYI7xb9q%P`mh~}5B zJEf6KLk7Syp=1$Q=yhbE#<{g?mN6%?e#S`KS)3)rnoGHhyMRPZd=Nn1=LSOlET#3p zG&d(@Giv4<9L|Mn<*Fta?TU_ux38ziMMFr%L|tj|7V=R$VkG`7J=|bb@98{qjsF=l zXT9UpM7M+WLt>juv7rHvEP%Z|EqlGjdmS_mZcF^G&h=W@2dpk4ec7$s%}YM2c}g6` z!3z-1Wb`V;mkcV>PG=mowX0Wt2(u?C`EJ;rP>9E7k@$g<mF1sL!+V}B;p~4$rALUd znU*9~^(I%wX8>7YQOFhvi<(mgCb`s$vmAw`7H&*V-)U39+l%Fh$A|4nF%@Zi2a0xi zXgR$@VbBT2Q6NYAW=^A#j4sy(*h_hJ7pz54LKK1_r(60`_Y<lUd<F|2ZnHEG@OBvK zo5H+qdQ5=^ek5FVh*weAI6gbb4^@l4AF`8w^f5D3_`W}02Pfm$YUOll(KXqioSO#2 z$NWd3+qW08BwPkh^KZIIIy1)dl7xWUA@D&YyXAkVdh5Ta-soR@!!S%xdu9M>>F$ye z7)rX4MnFVT2}y+y&CJl<NH<8QDBU0+DIp*rASx&*ipt@f@9R0w^ZWz*m;G9M-|JrQ zbzPK+B5ZrLgWpdKVLVa>>d0!i%0+Y<mF0o|VX&p{Ke`lXjw1$4)#STgQ`MB*<%_M` z9#=R;w9%!p=ae8<ty*w8LQdd^x*g#b^%U1r&2$O}CO#9yn?Q{+d%N|Bd&uDwwYFU& z%k>*X)3TN6yaV?w$Md+CNQa_UVg<?%7OJ})H8YeQ<reWMc^(x+0ASDZNfXW}`t3Ge z((%ff&oZjFF^Y@&-;1mSm5;WZCHl_HQwA5wm3nz2`ekfo85TzLx;$tck=zJ>wqe@i z_|iPe=@JtOT{tIq#LYsc3Uao+G3<xf<h6|%{_=w%2JKTby)ic-Pc~kQ%_po;7oS<l z>DRTNc1=$Gkzn`mnBwp78i}%zWJ^|slW;huMa_P=c}vLSEwcSaqO$IDxE6=t^b!<+ z_ec7jK<ML>V>y%Az?Y^tcDb(9)db0UQTH2wHrx2i+fwxTGEgpsW+?B;6P91uqiSbk z%^i)$nDR~sm1k>f`cB`IhHdEi&Z;uocmo3AmV*?_tVzKhLgAz}tMx0|`sIRe%pYGp zDgCZ_<2j{1_lw{~!tIk3(Gbz;#$(S+eWEafUSKOD;oN1>^dX5D97_?9Jjkp}AEUfb z9Omn0r{ZS*x=v##j(Y7t!DEuvV95QhElT*YQok^HsW$6DN%EufgS=h2Z|w<F*0ISg znHo+i!<^GK1R~ZrDGv%ZEtjzow`Hv!Wj696GcDM#d||Kt?h7=c?)LAwO->2&Cg$yG zHAxjzO%ofh@(%`;U1gZug@cwJ+sSOZd{*Ym7B;gLUf?JtzD10^82)Q$ios#_!xVDH zlVMU>5-aYcJ!H!?;HJ_Z%#g#(V>gtSRj2R--`WJ#A$D|C%~YveD340msc*gtj1o+F z?U=;z&ZN0Ai%U>QCWoE=nHGDPmfRIBB^ybhW)f;3pIO6+q5$~hY9?VUBjzZ`kzsBW zSEID&=KJ{P+X_76d~qZpFwi>@mj{0bGcf#yOP8!pSMhIu%~w7bqB&9Ug%zhnS9}Xt zfrxsJb9@ue;i^y@tKiv5GMMbS6JpCsY-zlhPF*d5J$3!nzVZeKKc7pIc2{BdPS)jZ zlFBS|Qb}%cq`vv?mKRHtk9gCu=YZ~iOb$cizr7rTrwJZB>QVWkM9A)y=zKYMP2+Ao zl-xr9v!eLwK$Ye%>BoHB$vGWwo(^^Lg`IMr6~GypbY6AWl(kHLf{3tRp>a{k;M!<^ z`sOav3z`>n+^KyRgf^|0DsLwB(&H_MS0ra+I=OX7`AOJnB0%lF`xL*8H`A5#*sx9> zE=M1>rm#6hKlh`F*-XE_p)z3MSy(GUpkC_C%(DDuw`Jdt<J&q-Rj*%dGRif_aj+XR zyuNNp+z%to1iN12^8Z;6wP<_WQC%+I=w|a|J6rsap5JCuPaZxS)oTh7*YNQ0N>7IY zXI$`%7YkYlydcpz2rIUwXL~c*tS$QC?aN&Sk$(rWJFi7Bd3{@4dUO&%OejWzx|b_c zk#K4G*BDp{XLs);RnbrRBkNrYHl#VKh%YeU07jBj^oAtn@sBI7igNTA5l@1$3Yv{8 z!Crs>aK#lNet&~E&BJgfVU%+UTQS$jGg2F`XWm7yztmo0VnNp7t}?}<pP->)oiy?t zB<B^%@TL%<e#|GH2Ph(^9WGx%?4$B+STHMmp-jtU09JorB8mf5o+91YL>t;KyrtqP z=I}7wOYZ3`LMT(MZuFYd$Ypv$5;zO*h~Uy70#cIU@Hxs-bGZKw%%@63J)4@o6m}nw zw;~CoW`pfShs-rcB#Jpp?4d<@Bk`IjstAnXmW;{`4%snuek8BpTxhFW2*q3wrkI^b zje+=^Vh{i*hJmiCeh6<Vw{mp%2!Zq`B9RqZ&2a^dZH&nrBA}Y!n!JAc7Ce9opD*u? z9trb5sSy%lI13`EP$$n2I|d()Bft|RP$X(2sMIlSx^$Er(St8+s5=2qFb=-8{dmJ6 zH`VW8@GNYcmBO4`uM{T3nT}8;A)KQPYkuBx<v@^(=`nf3>CsT@6BuV11LT*UmxBN* zoU4)*wb$o1aNxPO7djsctI{yvUX*=wT{4b1q0@-VllVD!s<4B$RI{%{xB;<=+pC2H zv^QSqfzHOB&$APSZ;eO;UKIZj({eeQw8TZ!fuwo`WX2i)H+UBil_7xQaiWsfhp}(7 z@EYum-Bw%wVpyu-eGE!vc<h??aE1Of$_~fc-6A3pb_islPkk7KVeFE*m5sh9>PEpP zYKNf4gr{sRrVg)I!kZG48j%4frWB_L))jAz5u9=vZ22JMcTL!Bgqx*CN&DLxbHWXG z<O+vSp?yM+p{A%NSki!jWyO<5rze>0jPz{qN2`g1Q7Tq66EVj;9+BD9C0dn3lf7*r zl!Jz*Q$Mr6e)FCqFyIp{pSyB6h*hV+Lj4<W5)2uPZtyV`Gh8@Iz`PN8P6D@<z$j3? z3<|iPWWmEF4S4)acEi!zB7aR8{?VxH`C{-T2I^Ul<<&)R_2;6RIN&IY=IZB>DtS!a z$|=jTKypZ9D_$t&Dk5gqpxXs<jYgB|LiajIQ{AF5M!_qaw8*!`5?7-%#)Z;c{U{vZ zpIIsB4+5)PAa_}_eHTIWuh5SYumHo5a!fAjG=V<{{rU8E{jR#q4NS;<E&>aY7Z1JE zDhvOX>4h(&X3N49XIONp&;QivOa~XvVwl)qB;5Dsf&@NcxNyqwJZiWDNF(z-ETbAP z#1J4RPBp*h^2$-pE(|ngML?vzgybZB!ycLUTS)es%wzJ!PD_=MfT~ql^brT*EHe~q zrke^TcVHxQNp0|$r7Uz1vh;0P@^|}ZG_BCnE)D8A(iC>m0MQ5HDgVKXr2u1P)lw4G z6A~hgD`n+0A;?n6{(YU0F|5Zf={GDY;}r8$?jF|w=94#FKsnt?n&5pBKmh<WovYsP zGnP=(mH6kz8kwm!m7V+1bZUnLxxqiKf)Qcx?iDAwb0`byo^d0~of>qRSnMS`17zrq z&U{ROm-<zDWtl{2p)bv>11TQ@vs8ti>PAaJ>tSnj@g|~{MbKq$jYkMfI=oJ-zy4-a zg^DkX{weIem2yF)lxCOzY6UpN^Pd4<m}M$jJsULZQ`@&l%<zdlKY%_~j=w;v(8T2l zG*wbXCQy5uv-X!#%ti1wLFBiXB}7r0`yuejRzW({fN_b)91F&}RB#-f9^67bcjZ>g zEvc0v6gX$8EWx8WXZc#3CqR=S?N|9}M@cQ|y{bXpNH18DO0|WK&gBtWKF<Q<P$yR| z6DEiHxe5-3fdxygv2irXW0_mO8ttg>iEmq&=`<m*umC{pV<!I2Tp6GD3!e;ntc1CB zZQI78fq|%HXl(6U6<68Iz_R@oREn|%NVoPd6g~H-;gI=47UhiZ?43k&$zp0rnykf| zF#X+rDWH77O9B3Foq&kHXiRIadO)&Pz-h@7nnb~r6k&&4epH)4ai+$no)7Yo3vXq} zIj?K2@`ow**=Z-grW6E8{cR28%m#CINwc(rW?H%^QeHfX(E0lbEkd}eEaFr&_wN&( zi&W`v5uJN(|Eu!9HMEX$0tFi+O8XVPAY)6d_KgK_(TEgaWM01Wx<oc)hl}(n2&=gp zG^c~o!$M2bNX6+<md=CzIzb_t)%ivbdbD4=rfUq#qu8Fwhzy`rVX}Q|;7*S#9XT*s z)Ndq+k<OMGml0i-LD_@PDX{l49ZJ#I*GdNlzXWvViB0@6t`l4Ii|!D56-88OH{aag zSzJn5Ks+DY06GQw)lBqI2i0ed{_M|z2yaCd*BQr;J(~w%Z_V|?LPbdm!F6y@hxu3L zC<fb>`YF<kyHvm-#M@@@t+|l5SMM#43CL8c>}7(Pz>tvlmGaO#kcPTP(nv5o7yOy? z94=;opPC%J{?)JRf9&XdN)9B%fmSck#4QP^Q|)-OEP>Nlp~D<;tdQ1RP8Y+?%rO+* zYAC<&sNK{QUkcCIasTiic8WF7qA#%D<5gcgsL=zFOcqqFA%+t{rcbD%7AG(NjJ}Qs z%XV=;Mo<eADC;To)}LYSI<(*FV{_E#g1BPRxBGJ*_{rM(w5DMP*;b5^V2Dr8P7gZS zq4Q5&|3-@IyHgo{u~u?M)S%9c<=h1EJ5f5z0f8WTX=cn71B#y7m_lbtBR-ON;|*FY z^Zxh{(;PXfzlT$AJ~fi$3ll2znPj!)Y@qH?gW6T8ObE??ff$<vjGE7^l@ad+r(laf z|1ED0R?jy~O$)l8mqN>#-F}Tx5Vf&+Yv}to$oHbrJ(d2?-bzsD%$0NqdoN1NHR_Kz z88f3o$}@rMT<i~KR53&=0X&VNd;EDRT-)hB?JW1Iwus(K$(nI{o40Y>3GXf5irr>G za0;RomIb{9;ogu&J`}qsESZQtGhwxdf~0-QJV6z8H-AR?b6}7swqa`6_Lt~tO`p<E zZA*Vce~{4)sKz<zBEQj_p85?;@e<(G!$+|>pn$>+J1Nj?aH2Uk7*RDsET$4oQ=hAX z3uqh=s=7bkB|^qFnNb@XVAnd>-MjH9;p#R?58AZOd_Zs6U+=w;9<!WF?okM8>NX>M zqnitjA*EROuV&`>7)`~A8gqN|&vq3@v_<r22jjhw_)__;-f}<)Cd-2t{fdqv9y57+ z;9E3SbQ4W{`393RB;YWQO4&G073F!fi@-K2S)qq_X3EM|o(MG_=M5XnqrgOr;`P>Q zILi2bF53gi^eOa00ov4t<Gs+UR%Qr0CBPNB%cH-AYT6waK-oua?a{b-@}bN!9v}6t zOH%T()qQxHhpuBDNA!O{81<<2)_rB#b>9H9i{5w&9|EFVaWm-r`kjxJoxy+XtWPpO z>a9E|LWL*R)6IRX{PHou$m}cQ)ueTiNpoD}F{e|(Uv&NWdlVZzs((N2)tY=nYr>;z zOwJf})8RAZ{>XK(!gE`H@Q5gn1{{Js-UL5nO>UgL@0s~Tq!0O8F{aPF`L;#IAXM_; z_>eqtIBoryt^u7zeh~f-%~Cupi`*9$H^4G4@@<opwfe?f%mH4I^+M3C@H0dNH7|^k zFngTz=bff6bKv<G5!BZliLXm3+cY9hs<mG!NdWL{<4Y!}FNpe2<>aMeXapnb7Mi4E za<_CrpD^vDOY25rTTc^pJX-hV+cZbfXY^UffuO?{!f1iy@@vNw`ljr+Rm$Vv8>b>h z$N2Bx(A$S(kG=@if1ld9%EbJa8@(B5B#&0jIsgn)6K;=by+N&no^cqgO-(><eJf2h zN#$~l++RNbsdy0h1-)c-zUzI?96v)nHwqqpr)ct}VM4XmGd)bY5Jc^66Or)U)EL+V zb6CC{jP^q|ehRVeeJo^ss&ue?`ZnQ~!NUaCdvE68O=oC_Z|m6?wN#jGu`!Or>q2$D zckg59bKeF2^Jh=bb8f!0nA3j#9DPIN(uD%JC4P4EHTs|ZS>2mI8~yL!Q@l*R9|}xw z+nfH1q5Sk@x}!+Z&Q$2!0&I&F{)Hx*dQgadfdH!CgCF|-e13z9a=Xx&yZ}TqH(4$v zN&>fD?X*2UcnSqA8m|CW3&XffK?E6ky%`!d7)i#ZUj|p!!Q!Yz(CZeWlLO&Eqb|Lr zQ3-~ip9|V(f!AI)W$w)?Bd?fvJhPk={loc>21VFtN-nE~1EVsn4B-dw77k6yWFCSq zv0kG?tg6=kqQuMHm+>Z{{N%YO9P=%x8=(r5KLj<aXzm$LS*66N(E%3J@kFdPHhtkx zDsG#V6NjM)Z{jMWHhU@{`N6~kORrCAyfnSR=k)Vst3zH~1PYzp>wzf7#K1<S5w43j zKc!u_ZcG^pxm5YOzp?i7@m7D*X0P=V;eM`qB1uajF$wb-3@o)w_)n$l6nEZLopo~T z_^_IvHP5}P&FjnjL&T2^F|(b3=jwI>m19gTm<6Elc_QUq-t!b<5-(*U=vjgy0H#;T z16w8&H_zGAy;P6_e-ip54y>!W_Jyrol%`)1D8;}yes8u6!8A=-&cvsl;t{N>HR%yw znocyBd>5KtVo9G0_3z$o6&xmfgB+;=jTrZF&O9e{50z?Ot@<)=YDx`r%Yu)Na8EjK zMRbJyN#_TC`SEMY=it|o&$R5{?+9>w!b(Sc@e!#$eYxOkpm?cvBo9NNzgN{CyGw9I z{4l`)=?iL~jqY$jQCgDIlGRh9h+Oh!0U|H*F!{gKex}Ac(MLVwqMUAcZiNML+3W52 zChQrWz`-j5*jG)P+C4otGqrYa=5HPa3>Pac{`2wUV^1mh#;XizYb$#BWKoCx7X0X= z`J<k5{{i`EA<cIE1R<B%oA-igmma6oK=S=RWCYlK|57t9rW~G1r5_ym+xw*_*+k2| z2r_94KKcP`msrMwc%!!weS(^=A_XEE9pfdI=y+|&a(~>u2=4qgasQU|FQ;@9Qa^6s zV7=cV<9=q4b6RAAXRNa8QqaS~kk5f^KZiaCxs=5HkTNYzyBq9Uk>~&0wW>5T*sZ3v z{kL0P%Tlm=L(h-j?v0b*1wEQ4r7t~N-+p<^0{qy%<JtK^*y3iF03{q?`$YnE0sufz z<vK-lMT8^<;8y?<oJq5>s6P^p;kOxU{C`Dg%A~XsZtG)BrK3r#sstvj=Cbj$|DOo0 z%ZL$Bl>C20Xv&dD=Km`~n`o_mTd5?b@;@RpIW32ciMHD17nCp(q9Vlqh|p{&+w0dl zygp16=yd!a5!%tlWXFs5ufrf@U&f0X9in5XsO+XXPt}K`Vf@*3%3DN}Fmd<Isb4;- z)rqQch3<U-0D&R_L!sobPehIPClf!v^TRHYQf8AT(<|@I^+n466-w@WxYPzCZ|!|4 z?He^yfH74BrHR7pgg9jAWXlw{w+3~txMhOue?~075Q)9`^TBTg(n7WV1=V_S`BRMc z$4kbr<8!5ISONAokrzuSeCN)pI+WQ^`7uxxrtZ#C-LC%Zn}fM=@I>3_n#vFtZ;8vb zTaGju9M5u4k-xa{-c8gkyTFaV!udmjfbec{kV4|Y2S+&XmVG=lLuSKMbb?3O4{;7C zLm&tcP%%MEmWRm^hm|WYu$hJh+y3LNu$v+$DaW=@ByR{K`e9*rZI|{-Xvv#`4EX>< zWsn0Z6j2#Re!H^p3AC#^+4Z%V^ZS7N(!rT&h0Oe*6fqu9rkJGT#A7;EEeuima;@dq zhq$Oxbq%?i8cWh-lYOkk$W=2~nM!PUN9ZX-6al-<xo{Kc%1(b52HP6}(6!vw84|?w z_Bz-c;yzV!*n{l**kX3h0SX4^=Hx=+@kX#kiLFnCeuJ(xsri^eYD&dHI!aabb*^PH zCz+JtW0m@sl5Q%@3nx%f;148B=`(kJ+Re!WaYK$la!8`8P6=PK(C92enT=XX!jKr! z)D?xT09gCTnf3yO)a4l#hybAqf!Tm~evcL%nuot;Co{dZHq{cSod5_7zVb~?puuB~ z@Pob#CjXbt=KHj1l9TcbsaaiXreMO<+a<Jvnh+pLtriZ~YyFnkZ`M(t6537w<cVrz zL+cBJL3XWOEHC7W71H*AY5@!52Uu&BN#AqKc0anMpB$1=yk8P_O3JmnX}zeNO#UC0 zX?r<D@A%?iUF;;U_`tQAB{2xI@H<5Qr0?^7A(?5XvO=Q+<qp8B-@R7ock%U8ZBydx z26s-yA6FWouNX3z>m!gXJTj4l|Ld8rC=h?ODXc*XzbCXJGS|uAc5oy4-|wT2H~%ib zj3&L*J~{_T0R3;Qv&WKv=->(vR=B0+Mf!+W-)-~$a@N1{VqCHa$7SwwZFXKk;OsH$ z&p~Fu`J>X+c#%i={ct$%ED_7@P8i||^<1l|?DM{_(cj|O$RF|!GQ4`jK?1)QMUIYY zqApX<{q(%^igbXOwyFq1T@}u>*`GwsJ@y3BMV?^sQ#smnj`b)l|I^IJS8jVlL1z&- zS1WUpa8@!v@#Q^IHb*|xwT0kkb}r^d8vlNmi!=<6DH?iGdV?rT5n>s!3>c0yIW@w5 zN3N1W#Ut4m)C`>M9l!3%jP`?-L|Lcg#K1VX<7LdYN1vpuh`(X{<G>#-TdF*v3I643 zCjINq*+#;f+){u|1&W-w{zeGiRMRBk2MW}!iijN<TCyQswqz#~k*nT>y8!5fP4*g5 z`RA1qFF6KB;3jQ}V^{z$4Vp|@&?l2346+(dg+9~)E{bC7NW%Ed=%>RaiGZJiI7|_6 zH65u-1ek;oUxQxW@B<4)CRHjbWD(I(`f$LkPel!ip1WShDxs=((GWYD<>Oo^MgFbC zqQ1Qeqm*R(s{qF$kO0rFZ!$#oJ_Av5KW!Ut-gtcSwG?i;ud$Ro8dISRSVS_mR>5u` zIDiDuAVQMuxe)W1BJ7(%q%O9EG=vvuPKJiNVDH0!MJNlCgoz~6u<^*Dv|e2o4bH5N zMD`Qyrrg~~kL^0*Lw>au!)V;yMOMBLO)40=CeI%%fM`K(w~qD}&g`-L5T%o!VvUfP z(`TI@v{(J|%QS>it*A%}cbBFa+Q{wH5U5_OydVd*cmHT>FoV-M*Mi+w12k;q&_2ua zZnI6|qGGtip%yc{NiI7{W~eVc#UJ}58#!9x_hKvZ6QTnVBn_+zjqm?H>(mY+ZfE`T z=hzD+Zq?v_UR%wDvz)YA>lpEGV+t4Yc&PLKcZ^i8-QSwfo5qW;kvE<bhx6;g25ciV z-=vTbsfdurG=6MW@3vp5P%es{VYbNbLyq&9S~J-FhunP;v{z4iV!hPGqE=tm>#4GN zF+u|g8x~0vi=PBY8P+;SWFDQWtP|GGX``+ay*0|M!DgUp|JW?KM*zZjD}2G8G=URW zPH5a3lBE;;*BQHW&>uSyK^a`2!$Z|90N$j<W<Zu6#zKBCr&2~;b=daSKGLe&37^ek z6B3RrG%NX#5@trG(th-qk$C!PaD6q3-UbX~lX`C(Brpx_6SnY@Hf0%V9N`*6AB-n+ zK+XoAZ@Pu*S%WP#+3mqZPm0KV%<vv`Y*I91&}$zXhyNCg1%oTS>6sDWQVc1AY_B*A z35D0C<dUv>*<W26z8|rish9FD&>MOeanSV+Ar{%*wvj9m*kf8=f};mSzbG;etshYc zJUT2B+f+;+yE^w!lua1XB_nw&2DjOk6NNsau4{Vvh@eF0m!v|i4~>o_B4=_n{k!_6 zQ;&9REWI~*?qBwTSHTbLS^SsC_@`_)VSOFy!YL_KLu;H@w{Y|mpbx?R>ANy#ms%+L z@iu?XTjjA#C@l5y+G;A^lCsnI_Z-!G??Lxvy+>D%lE)%h``z=WKbnrqySx}N>*a25 z!N1c^R($QfE&zLq9eNZak#4&y6oBZQ4E2wC#&o>Gjk6A7GN-x6+hN%kVHeJ56XGvj z0Y#{=2eIBxXS?tyw-;2R6F4hoJ(fQ+6cf53o+&=x^4#R+!M&!w0Jg6k3zqjh*P-*L z;a+*H+uR*S#*c&Xx;--iQuU7|RK7aiEc0M5>!WBrrD~T7<%P9E+YDtr7+i!?=<8kv zAm$A+b4}U86mj@#6>vn6)gFtI{HGhKq=m?`OZL@&S1N|Wp*Nn(Y>?&LHnV)U4KS)@ zxG&s<kqr>r-}z?$)8*vre~y$qK;FlAH3*ZF(tR=7wmaa!`7<b+qb2C8=+Dk@<NinI zU{@GwFALnr3g5~?ZQerF1q4Hkf)|#oNc$hb9J~?zmgpOSkW=k8Rghnq?5h1gg<_c> zMKJb035Xa(XY>i)G%T0Y-bme7I}<#JHZQL9UcM0#vgC7v7v!!4J(AIkE~qsPaL*a^ zz7z1E-0^dTd98*SDqL_WT|a9ct7d9x(WiEuC;ELSQX*XZ9xX(C_LfGplKTQ^2tHON zbqso7RY4nG5*xz91JVS7d&}Wu+oX_f(!?tZFp&<QDuYjxL7Cxj+wCDVol%r1U)306 z{qs=W3|GBdrpxNC?4Z!kMyd@+EO!&tV>s{?0OVv$6?kvo_Xp=W!8b#oL<jhA&yKb7 z{^QEv>j^ZeSTyN2&Z8)Pf)16Gje2td8Xb5$F9%z>gmANi5i8b_6=u@QAa03Wl2ymp znf>PpRqYC)!2-Q;AGrt(bH+K~ez-~gwDin0Z;K8kb9m%93Yx6M6X(P$qVTLuA?(?p zohJD7<2}~9QRh)Y-(aGWvjUezI-lWaZ_YT9Xl=j1$5GHI+`h3emmNU!c>0GK8Id`! z299&tAE)`h^=$Dgs5xHH=PEhPXA6}cm<AO~xHi_+bv#^h22oY143QDV(orw7K{rW| zDawL9nG`=rpqE9HLXx&rr2pN2))Hw7&V}+^#47n)KY`x+5DW71q)GCj<Z{xW<2Z@& zkTI9gOL$1hB522<sc9G^<p;SzqAZJp&<162oKhMV@pQC!Iam48FQrR%1d&yxcAJ^= zNC!t}`{0L7{P@76F`ObEl$Qld4?*8#@NrJA+&Flxk(2rbzK~5o81cuh_#F-Vtq1zC zR0IWUY0^=<lcG#bU9(x5Qf7*XtzGR~(rnk&4fG6CL(C%pd#l;IKFbzh!78rkS1!MI zE<;l;(kK^sh029_;|+1qt5wNRtXpUx2+GoGnh{!^<z+ibj{B%C8r_F1QND(*3lQZ1 zUXbbz2*V{oiqj$CR)Uu4x-$Nx4uu|C;JOyLWeIM&qI|uIS>|%d*a{mCbJpmK-<yMb z=6PN8o(L-|TXiSyAn?bEwnCWe8IQn~J=JmNb1E#Ap}l3e1VkMw@y#^|KKBfU^1YGj zO|H$4=PfB5&jq%Mf#hOxEX-6JwlRL~(8|NeB^Xp$`2<)UeMHSi>Qfg%Q+H!z-huJr zl;=FkICTq1zcwb;pmp9Lw92f>JjZ9$O3f8Vo$U|u7gvoJb2yayiK6_Hs|a%CW>@?u z3=*#t<g;d;aL=lm%io%l)D13Xk6U^Y0=Yd_P24^E^mk4L0wviulpz)-t~B99*%bRZ z$m+N);ZbY?LM)+q6*LY8@792EztOQZpy?54$)EP73YYd9%y!Kw`4LBN6d17zm{^on z)PN~>!JCLwOn+>N#=~}e;U;OsxJ*{Vuc|#Oa2N@gy{kRyZlFl1VmqxxG*unDl@Gds zmdNrMx@y1+zhfTEzkmP!a3N`bJ!y)P{K_rGQOL2VL{oMJp_KBLGSTcH@sp~?Z}gh{ zZF#m*Pa_VJLiwX7=t?NIi;vyFpSfUQV>1v2gETb@U!p{HuGNEeWLFMVv^A)GtE}p* z<hqP%Ub<R_NmsE6?2Zp%H0-}cZICjpM!xgOg@j&YnbXW2kglVWttxXQu#lssAZen2 z#tMA0Rp5Iq>S22UDTW1uD7UrtN0;r71yEA*<)p>M4DWDoYy)1(Ux+6n`<IzRcRKX6 z1lljOmmNc~MOyZ|kv>Ry6|Xmv>5;rzLgtdr6&sFrYalmjKmQGit%05bXg2|rivY-1 z+dy92wbIoApQ}W>blrVurQ&X&%GhP-isdbROl?SF=vz;JNEQE`QoSfLyyb~__p|>x zn#^uEhT$?<Vxz0Gf|GQLkxjKc?k&_!?a+SM`eZMAI7a`f6nuBtwc;*t@~(l0u{`d8 zG`JRI3&7=P7m=JAKB9d*8w83GK$@q|W9Xl3lhhEUKcS=c7E<pdug=3bln^uvS+uK; z<iU@Z&CdnEQpQ)L+r4CSy<6^J=oXB&slS*E@T!H0_B5kxI!fqKZ?fyybb>S8P_vSn zIDd$Ne=8BSvUp_5%NS9Q@8W5(pbEi&airc#ohQ)GTIkT9ji(p2U0j*->Ux~zCf{<4 zZGcV?G+)Os=z{B?+S%)RiN*Sfjb2s6HRv%^?^gQ^XSbDc_2dmlkTgN|4m8;ph^)Lb z&P02d%ATD&^^u}F17iyJ#>*ZmfC2LDpS4?juP&S6-oq@qs7P=;(hy8l7>957r`VvF zUyg^)4!c|TJCOH3jO$HcD5rmyYgp5bZmRnYPyAxpgTPkE2bCtZQ%w(30=m+VyPc-Y zy@M<3-n-%0ZuM62)$#ZAW|0F)9;oO(u{5UfX{PDvmtxT;Q#lILh?Ma$n_-5j@j``e z`<LKrxpw;C2^p=l^}`U`iIKGl@L_svJc*1vC+sfwlUFAH!EXpZJb3aW-RVBQFL+{N z_ii4?WgC@uZ!E(MBpmZ>w%_dK6w?&Q)B?`i%rS9H6FbZ?*p8=6jkEln%Zu-SPCmlr zApk10@7l~<bjL@nC(ZM`{{HEnaCZd!N^F#5jz}NSU;AMH$!Bt$<hBA%Pub9(Lqa?p z>X?6rhXPm9np<YwgIf>)Z@85QSc9?rBW4O<!Jjb}@;SJ}95fv6D6|A=f;)#SxfCq9 z-d^(9Si;%QG1-o@ex7?)1ba{3A@sD}EVmeUT(EOk?9uniqw!ib*$d7k{FUkoUo_R@ zc{2-vP`H;;(mpwwtuUz7{H@y8%arrHDpae}TWG57O;wkaWp3ruf#;W9jK{MR&p=Ag zablu1pl=C|UBWfOi5-@@>X%+_tUdg^<Uz3<X*kV9F;B5E&OqKFR$GPFhE400_e{)> zFeK-@X2IqXs8f8u(aSK4LVjL#5fa;|2yZDe#e>vo<e#hbKm}q-NM~E#`P~bsjgIg5 zs0;p(8zKA|PIx(+KJ^Y#JWX1>^k5oJA`Fs*Zovz;kgvALUoAcAog3C$ep0Z`p1-_* zxo*n5F?TyRl{eY9Yv!Frgvyc`z8(z0V{uQwSq|dAC4*&y1j2oaOdokw$^XvVpXq9W ztoy5+2dUO%J2&}fq$it;o?%8e-oeGj7s-La+u)69v4@^puz#Y&b8y5a+@f&L>eZgj z<{mb3&)jayB>~=|x8`L#?fZ9b<I^ywO$$$acUg6Dx=iwF7v9Re4DIcLE!ucTEc`q9 zKmAr=!Usg3hK?QH0evOLwjX^@f%dgK9!$z@pt5<zmcNK3+Ip)nM~q$Sq5wKQx9+h> z0$Y3b`bQNFd!?aARfSvk6W5%Cm*y4LnLp1>98U+-_kMJ5c_y@2nV*(%0Mg(ddHI>Y zlIr>LQ3{o1xlo(vd&Yc?8D$4l>T*FSAuBkz#A>oTYCYG?cEsVhd3(LLEfidSHkYTr zR#^B2=;JBT2Wx~8CoEsTDSkb(`+ELrkL1x2;>)3@?VQi;<?;I74+0Z@Pm6t$N8Ex6 z&?}CowXs+nNLwL`i-w*RCC0Bw|85kPwwCT#VgH>L3;q4ftlZq*uWY5j$1kVW%eB{V zy*bcum$-j?_o{F%$8O)vc8m1Om$FA+PYMx=SKl{@&s3Doej0zJ8ifCT^(DS&=|1x` zit^;W$D*V4jIms<Jbm8i?~wOD4uVFkN|&1^1<Zb=J41<dkYu;z`qat^r|-pb7a$O% zfDnYiKnF;9?r)d#ZlMhykD2%knX47Lw@udD-=OzBy6><sbP4%S)Mn;;>elz9s|!`7 zU+G_k0Q+CWV!u+Tz5=XYEfddvHS9q{x9(GZ(pUO4l7M-xFhQ`IDC4WjWlT@ceb_p2 zHyGI&q4AkiEag9wCZ|EQS8=D8Cscobtu(h|$0}DLG*(<Pj`inu!6H6&ccu*Z7ab?T ztxxY!pLZWz^{yck_o_E9Zd3hAdx3a>rQLu0uORu~@%w*=2DFgVW9Zz!T!XLAlg=&@ zw_g8UYGU~gY~R`H3kNO^uvM@(19B9M^F+$AGfV)mJ63&Av7>RFrhcY?X)d7$oTt*U zmZVeKqKq9LBt=l?VLlUQ=^R9nraprN&<GTjsKy8U@%g_ZG{tBJGdK1BuJ)f?AXqhq z8EAq`$y48I8RuD+r7A!q^z@~*`0l1#G*Ox;(R>=9hTDT-Dx#>p>qpPoYeZ7q%uLrh zbsWxRa<93d3)|Jt5W4rOZd_b<I#HhJ;`rC;{gHUC0*wvLd55J0Iw7l}gL8JZwk!9a z%#ygGn~IQMfAn$J#EmXL&KayC?1OH?qZNg#3zYJh1h+wj6JmezhmgoEXR$bS!6|M{ zAe)MqWS;_%Xs@|Op=%gDHTnF0^!dH3e}t<Ek0>J227ehhe11`pE4QFiD&o3dxNt1J z(tfAOS(yphsweCx!`ZulzWb%`op(4Y*Gc&}hhIA*1x5R<OeorhXc_A@=7b{=60@SU z9;Ga|KBU}Xyd$7D^48A7TNH4*kCtBHKhk-D`ObcDYYWXVQ;bj5c_e%570Gv5>5|gK z?$icVeEDbg_(pc2R#7r;5+XXX>c*wo{$7Gb@{6jc7Z6E9EbPIx-}+V2))fzt1G^VD z#5;GKJ9|i?7F%W&F|KmWraF|(mWw#-#5p5T+_!;F_loWxJ7mCGp^a0;fDMy})PlB& zhxnTaax}MrBE)laI^uJNxt-LfG7Z}}-Fo)bWGA0-f@A%`3+kUW#;gKVNa0D!j^l6a zqOYlab;YY>;n)*o@_?C5$`%RijQ^pyZ7v4+<oH1nEgL`8RuX=$Sm1%NM-qDs0C zbG^C~mWYdl0Of-0o$~#62Mh1N4Y+gDT=^JV(Ym*tFX?LJ9ZT3pOSNMRoP$>}IS)wf zo%0@#1UY9t7)g0B_T+C6$EY}#B5cuKysk0lZoE(F#xqEwbu?2=<du%FNO#qa2uBPh z=M$|O-sy~Y9yJyD<dP!Q^iC^P2Bp8F<sWr9lzfa;BZ7kfLw1dCDc^pb=1T&L)AuUG zTgO^<yhO7MJC#;}RuWprbWz0IJx<R_L)utq<gJ%_S4l>=)Q^3FbA#-|Me{oa`&oFs zn$a=)i6IxQ#N3Rf{Hn!Ihns;AN<i>*_FHG|F!QqPfwWLdcO%io<8s2gXP{j+=Ytwp z!@D)yn_m~dd>@^TzW@3rfV=^>m9wvoyzJY~ul9-&n152*-o9UT+L>FD?_-*zqE<(8 zQ8H~7<)n7WbYDZFE~8+^?^SaS#PU}EQt=}W)HC}x`Nlnj^_i=%oAD@JWM_)I-gv+O zBg-iPCS1prWK&pjFQ@Ov%Q6KVU$WdAjaFD#0}$q^bf`>maGG?I@&<RuLp#JdwWIVn zN+HGAP&ZLU8Zl?Um(Vh%ad1sKiPto%b<C)hM%ONT%!o#4+25xftF<o>=6O-O3N^cf zlnX9Ntd08s-N=?x91-;M%Eur3q}C;Pd2z6)y-U^L)yU3HzE7I+u3GslStx=`c8oDA zTOl<@ocV!+CMxODdHz=Ug_8mE0nu&1P>r*FK10`mN|z88)hat2teFF@fLUpYVKp3d za@sg;u9szDO;)UNdPL8oHPWiR&0hv@-8|RC%FoZ`E?*6C0}a*F3CR(8n}0Z%h*s0H zq(phJAGT7IdFy%p4i`j^>D8#2raY=nPR%q;WD>6)rz?qz5iQ;{=7h>r9M?aUwb>J( zA*lKH0Ro4ST2u=rC{9jt?lSUxW7?(0QssE>sT_olMl^N8IjKk}oCC0r#69R93lry0 zXb5(u&;P}rFU|qgZ|X8JPA3M+fg^(uE7WsJnkp;}zi|&jUsiiK|4#VSXN5pXOByfr zHdiNYwpF1TdJ&u7x^~Miow*M@chgMzUG&}TXH5p2Zjwa{tWS;dTrfQ-X=y#s7$J_n zj-GlMx0)Ku$fXT$i^S0*7c~ovZ=_ea#J@GRy3)CQt8~<q)H2(f8R|P>B9~dxa%V%+ z2nKyu8lT2zKw-s3A={jDk|@H1HnKZfHG8p-sdGTrYR(h4BMKI|05}zJ?UQ2J5fX5n zi&flYFyAMgxcT!U_BNb^x@Tb52neIr;Nu$ZH#+5YUfHW8mv15f-@R#2&U+`Rc}e{Q z(TA<J#5cy89r`^I^B4Dx&KXUg=Mr=OtA~eOxg&{hSoHnzB;3lGn7%A(Nsb-bXtmmt zOw<!j{qgeSsZG^OvGL@NQ=N%>mB#Ds(Y#%go{tFMzu$dN9CjN$ji4-0p8X00@I|Um z1dczY7M^*Kt)Dk;_wEzt>a~FQj`*sC*wv-L<tBOF<>F)GjBe^HWcCE9bfZag*K~z~ z--AS~6T2<75L#M@2Zj}i;rq4NNEmm2ix2^<UZQevbV>`K`)qy`Q_=hk;(r#SWh;Q5 z?5PlXvHbm$kw-SQZSZbs(q=NP(v$S}M3!SOw4L4UYcw+E(sSk7xYNVk2*vxHlRg5C zCK1}B1VIZvy9!%axjNlLF(37Z6-+Agy4E`EFC6#e%=7p1)B7kp*h8#Ugd9{L^r9#= zz_8(YIYovE9^ke1_EzU6%*M?->HGhy->$oM-&h`JSw)Qn{r5-d>aRh3tCsT@^0aH{ zpH7Q>LbFS)?pAdXF%8hz970T)cEy(^*Qykazoqx7@3wvgdyGOt>X1U7#fDt`w}m!Q zv17A)w_@G*wRJR|Wzt$6^&6+6_bj|pkMoDbN#jcT?tKa0ab0HOz9J?KYah64d3Sf# zb$TFgK<JU)aF=&q6qzxl@gc#*EJ{cUo#4OMSFrIj*NE0F%!Jv#ylCL{)uV~NtewaI zJ^nkPB_=bSx^rjl_MiTUal8j<pnJB(I4gagQ_SF^v+o1#6^YXs+CGd(S)I-5y~7DA zOV$WVy7m2QJ*?bOH*aK#0nbEc+U3-ILBE~|zi1R<{&3()uP&XasBG$jNDqe_e`jS$ z!FaX9x5teV9X~WtPjBsYo>UxN9ep;|D{Be-d1K>%G&LZljPs)-lTmabM<MZF%}n&H zHEm&u9Oo>>QClGLZ0Gd-)v~UmD1_n6Yi)h0)|l3ISa*-aF)k7x!*uIVWb=Utua8H4 zk~qghQrC#O&|W@BXZWRD^Y>eM96jNfzWJSAg$Wd3LEe!j^S6|u+qWYqmGdkjj`BLm z|5UM(PVnmlZ$(u(%N7x_WgY>P1R7&cE)|tZVMp_Xh!n1=(liEiU72!z8&0uei~XFx zH^Cxh%DcKxlVi@ZIX5?_wzN5?v$wRWmuCupw@4+sXy9&g9z=m)Ja#)f9H|#3vkbDO zIF#kv*Y#i$Zz_n)MJipzrYIVGQ-D?Dj&zWmofyn|ctf8w4M>F2gw+K0D^A|v39O<& zLq;OVRLR8T?i1*L_uy9Hb7_R01G40xZra15e>wwsj*WFX{9zDvl`fUPodd>0Dt}Jo z_|^wnKitN?i+?AJ-tewQw$e(FSL6gTX|>)gyAXxr2NQsf7FhyjL6znhpbdnvBZu}0 z?N|2U?xp>aU9T8*k#Y-3dx3G^2jrtpO7eM0baV-8vh-Y+<O*)e>zCbzQ3QSkb|F*s zvZC9D&s0Y95bi1j-*hR66(=ti8N^;;I6ho@fNKv_OU*+BqVmHX2^bG54+xT_F?QE# zq;p5&Rv+Oi96!>cC6HZ}uJMvxQ}BhRPWM<iQhWk0dj0Xc&n)~l%R~X`zmR2-td&C& zW<(Me&`Kpdg{Y7loy%dikQCo`=XtA|k#MN7^Gl4PA8tQTA`y;Y@=cS~mE4w-F7sjs zwupXI-2hy|TJ6j6Y9%36R7yp_h2e9;EX$ALk-vdz%$RZ9MgM=2)pa$Q3B0UX$QDMU z@q7o-(bCbX*#SPmVRN7HoUn23_}k_7ZBL{4;hYRJY=hkjNYB+QyE+ZEQVk~KJUReL zQv{f>vgbl3PfufiZ^fv1P!&Rmf6Pts67c7k{v<WRU%XDR3ZVkQTIN;F)D^$nPyh7E z%PV0ILZ9RmK}OeAUOj&u-twWl&7^0=m38ZBCdx;svZp6M44&dch=|hWYi5Za5{5MK zwykTU>|;ae^voS&hx3rUtmU7rUK6rg^o*G72Gq+BG)((nKPE5I9h}VZBIhKbC9mO* zio6|~cf0bU!$e`&!lEiCU#o&wmq%?XAM6_*8nxFFD)XjT4z5q1h(jY#@u#4tlXm%a zL?Q6T)KFCvAMv*#>E0$-DA0PA&v;;Eu)wJVxTKdAHI<#z$GGa0uRMP^+1KSE_bM=B zdi73+4n33X=&(ZPo~izx4H9-6DHx5g+L{+WpBI6e2yfu5l##j52o_#ig87D5Je=|s zK;=hW0`Qlfia{cyMn^*aRRW!n(7b-iH*`l7o|;+up2u@SQPWG~Bn$EKi$FX>n^7me z{pJM%TN=)IU{oLj^6m&{%Lt^?byO)+#`DqGn$Y|iWLh!IHUFMc4hUT<gqqR@q;4av z06=I1CkzF|rx&fZ7VXZ>%D2qQ`WCGd7@^eqB5Fv=)K21>PEP26AEOqP4Iv_aFrcaB z=I}zoN;u<K+D&2ri6fzXX8NtzROhp7I6=GOf(l!2kl1N3T*5Q%AeXL^Vj|Q$h?61; z;g_)z4OUnpX&VrbdYe-OwOur`p1mRd*$kk&TOFpg6Q$y(hP)eTay1vuffX;>ut|09 zRqENI$hPRfgIaN}acwJHsoBMu$%XkBGi99<pHGX`4*{QxSnq_qM@4}9AY=O>GBRj2 zALJ5(EBwm8iA0SJOdy0AxV7F<yoMKvr^;|dDThc^dh<)oTj^J7np77p=FBdZjztrc zEvm+%8w>DF=kJ6*TZwzFZ093KeWfl{kaB;Exc$2Q*Kl348fBuZNGw5`Ew3*aIVmBG z!Vv{48{BBM{3rUHCd#tBNbDG&CS-xB(2V;Cq~*-2Q`f)+*l_DEH0;*g)!oco-%GPB zMftdDip8P00+q@GEBn7z6{6Ny>{@>I27%XN!*gwC9e2gwHXCe1SPtUvG37+N(cC?~ z^P6!z`I!2(-(WsYZwsmMiNG7Vnn%Y>cE{G{?^u@7Y6R&Dj*iQQk-9-PCjyG-X7rsn z*l3E!DFLjMse%*l#mqLvIPhdGoblX?*BEO(q^YKfCD+}uPTOo=>*yNWGWZg)ut^nM zreL90zqR`BWsw*)$EPSn{M?$<0`?%oE?ZQVF%Qu<H+8mBoU?^-{k-{CIhr)NpZ;K# zx}gd^gOG=;|MFH#-rY{t?s!=HI=u7VpTDeXzjJ!0_;OE|uZ#%;oLhvx`SoZ#L~$#j z5o&E=f4w$oy|N?BvL=*CAW<anx9`|&81sgXUkysC=SfNtL3o~;5}s@EsQXk~OGs=5 z5isQj6&De-lMzRL5#Rb=dUA;syTs5^rauWwdbp0Wc!y)Si@d)^{F(J#v$$3A{CdZ; z_G{knh%w4EBNL@fPHLlaH}ZDz?`1;ce0is>_zXg9X6JGi`j6LI?3Lq-1Y2vGsShL; zWfzm>V;Su6x~5%m-F?=I8*ti3N;1^jGh_|rD+ty;)jJi!G=Z^ED!bJyv9~W_Ok;Qr zqon6T3yDtqDRi><V!DLBk>1bQ3HC1@n^vRVF?lnM>etE{T8k22?%_7zwhd+*(|Bt| zYly~{#ge0~@<G(y1515EwDZBGro9-8$yM9=#{_%m-6~w1KLH*?SS+CtYgO*))Gsr1 zR`$#8=a((IO=xv^K9pujatix0y<d3&lU1JffRI&+wwK#4m#W^{_hY!+h+~WDQBCc3 z@D?|5-ciPHl)<gd3lUK<_$Wn}sLklwk)ygzc<kMS`cM~K!(QtH3o%c(Y+Q8QD;Hw@ zy}NPu;Ut5lVx^<}y?fAAs#EYmXf|E&#J#gQ;#J)DHAUnBd@ld6;((OqjE&{U=!Yfo z^sYbvYW){VTAEH|?tAi0Ce%pDvVjJ=Q$A;;PtdiQqeMjp*>-K37$uOp@WmYQy>b+; zILgO;uFdrPTea6{M|eTI2Dxi-)xu)ItLT20Zn)ngnxCUHhpwixU~P@Qr7w`8B)>A= z5=WtnWQK?^9L<bzSIIfJp4)4x{<*s->`~SS0|H_6f7tF6j;L}}^`{}ey5X7i<0O?o z<{$LEY*T+6->5Mb)mK$F!MkTjrfd>78d#^*GGh#*IS8A9iY_?{$9Toe>_9i8s|xqX z-oxt(ksJOl_)WL#Gp#NBlNGHuXpXFE7`S`#u+e?vs@rOwrOat>wz4SSc$=M|`BBUv z(l&U=AQ*wdlrK3U&zK%p%*LwrGal6t-JvA*w$qu8JJu$3DDQk+&UnZ=^j4jJ<KaY3 z?WK-D<T(G?!(0zHehurZbwy<CT_nZLbi0#RE2Lq_r0=#{M-Bf@#A#jlgg@nIy5|k4 z5Gy<?6RoUFl}Utd%=FHXs|o6IzmQ&_!o=Xu!tl;(IQ9$Ju+TTb>+UTzTzdoFrmLh{ zp#9}rgH89Y0h{q3-Rm?J(=yKe=C71Xxtg%S@r9-N_tGEMrgua#-TrxfzZZ+QOa7jJ zaqf7_|0|jQt>qor4zHLmes>#ioB!V3zNKq&{D92ti%8mil3+Prv6lDaQZCbCnrBtz zRV)LM$lDG?7hY$&&k;UgIOoSzonAyaokDqElaCUTGCcpkKQ`mKiz-M%R-+!S^%wi5 z56WC-%UMmrrCnYW9$iV@AvhW!o!(PPzkoluLy*hz<c~qvmjC!K6e;kXZ_%%hd2U*x zN?GCj&fXv$0laN^TJ`$7_tcZ;a@Q*g>){Gfh!J^@fHw$5NJK1ylEKGtFH+!?`Wu5g z_%++0%?0WIN`7QO$()TtEWHMJFtv<OCW17sseXnmKM>Av#K6L=rCq9HzE_Pz$1Yuz z0WqD=5pmD)ogJ6?J(u~Dh~Aq&;$Priy?`fDJ!>u4Bhgq9kX~u{@Uf0&)B86~hPQ5M z_!Li2eRt{mO5RnS6rT)5LPj3GZnulFkLc+EENA9P-X^@=!G}lbntmIRb&`0<EE_U9 zv%j}qt(0PJnR-Qwx?}MWSvrA-`t9VUtBBP@ZC~Kt*?N)1BKoNQSXNvnj9qrl1;!=) zd;Rkja`_)J))%Jqw8_uY`d~5n^>|rhGvqtpXcqG%gKAeAZD4mFnJK&{25vj`j5Ye$ z2p0A^hME(=v10-7B@rtrmImkp|34zMxe}#_bva%S&B2niIN%j1$kANP1o*<|iDuEt z1=sXM;Kamtwn!x!6tYrlG~xhK;co0J_#z$yP>YDy3>n5(MPgK(x^m=Jhihe8B2E^# zfwi{t#B){YEUUHx{+|ge{^laMzI{U3({D~MI>GP6vy&b5W6f0Ksr4&IP77BtW!ZL9 zl9Id}8UQCm*%V%>nn!smX|pO`u6m2|t%9VM7+F6bm8uFgJS<j~HsImg2G6{$-v7Q@ z;8@}JHB?z{hmr89cxeqLn-oc^)kkm9Mv&|2IB|HFPi9d)M4x?tebg^hL{NHKQ1=;? zQKX4Kx@dJ+j4|KCOv%mNt#7zTgoA!MIkvR>`w_esGz}%kJ~NXfkEGZnRgOeasv3#F z<<!jWkUyYdRwTayvh1x_KN>y*jcDc^QGWAy<9%7RRVNA>V!&Byb;VFuxV{zb!k*)d zR;BbjWddrj3sI^gM6(bodF80VNF!~nHO1e8yUFB|bgi7;?8V$Dzbj{DCtJ0ZE>4u* zMtFybL0q53X3$~r%7WUdt<-x5@Il++U5dr#=k^ptE8AfdhwAn=vBpDNY8VyXJ)1;1 z{;X)K2NqSaH}y&G7TFFrKTN;Ap|%U6lp27uW6HI_ha}UdM_P{3YRpdnHFK0Z1(Zk) zOUb9UpWctWoK+-YejBFJEGwC>R)=+P@+{MfVrG8ly>z7d{*cqoDFtyZ6nvz0W@oaS z>-e$Yd&qCY=Tv*fbpL^ej&Z`5M6`1@^!yAdkyOkw9_nyn3AX-pc8l%)D^yLj+D-Jx zM;zszmLvX2;gf}+8x->es=>glTN~9m?;JfUWns47(msU&d)1{)lJ^)mtDx+YqKZ>f zg%fRE`$>omNqj*1E*~}QJih>TUPY~5RqRj<bF&srZKoRlzZkmjc&fiY4&a|Va9v#Y zn%BDSwc;A#+N--rR(6Q8SIACM-C?h;Ju2ChJrbq9Tw4?pD)lo<Qb{UF`T76z*Li&Y zIOjcH&s*>>lv93ucHZ`&aCF(OlTaWv(fi?CNP&Qs5~)uzY9cvgo&!)9ey4DW600A5 zJVo?seb5<?w=cCxYt8eO-OHuoj`{w>ZuV4)$)F_FT(L)Pf=ip)IeFXRBOVwZ1|-c* z+f}B=5GA;VnXpt&nq;Ky%_^(YS4L7UmDap|;hU?0pedNvr0h{XU*?;>4W)m!RY`!q zvn}_%zEJ4q|K{_QI+t7hFY3skx5e4T`SmWn|G5W#uSmEViW=ygoe87-wB|iOp9m?x zPdQZeZak#`05L@)uv}S#KDa#8iy4@2#>ySTn<Ibc=9F{L6rfpH;`XaTqq=^@A7(lR zvak-Llj53>5n5$-!e1h}Xks;+$N0o76jq{7Wa!o4enN;tin(`M2QB0O1dXbJqYHiN ztz}lu&Z=jBOVRD6AHmnAsN-PXfCM(&r!R>BE!3sErg{$a4OP9KL-xw2VnbeWsDT}G zq$BYvUmN&$6m!u7Y541dvZwEgYhp5ZZ4LP^-v&RoZBN#l!ksULap=~MdYPWoQCEcV zC%$08ZL+a$Q|u-=8HH*oB+z_CY6EM}Wn`op-1D7j16vUsvo#Z-pvvM!98Mk{fo|Bu zDvPrBTqm0c8@ygXtlSxTMV1rZ=syqn7@2mwIOwWaFm`~zLYbyx>(O2`h~(@N&%;wF z^wYiM*Odzy4+<hg!z6}v6*^52cc*dx`cE%Wj}$ClKNA^^ck$vgX-i&wGOCHGBj5#A zk&wC!6AB!YCg<jBCr0wO-J--U$<2Uh;Jat#%%mb4Z%vkS@+}wSmM&>hhVd1GxbjsP zSo=h^`Y}TA=vQ}c+P@%%Y3lbu6&}%?-;P6N-!7cH13lT5R&S@;-O8bEPvShDND@sS z$0VY)hp&w#VV|J~(9~~GKjO5D2wg(Gcp0WqPLcHL=FrvNXZZ{su8RZ*La>=iW?<C; zp%V1)WB;5q*GwF|gLYQTu=80ft44%!)!bN_-0b!`N0E>Pll=)pO(yUvSn}{G;=E_l z^>%S!vDA}_cyO4nP}QG>loJPSi3q(JoG27{M%}rk%37=BbA9X4N_kXrYsXNZ1U-Ea za6fraJx<voea<{$BxR9>ZS>^umRK=i7`4bSHD%r7={!E+UIJT3t(s6T-TLM%9T?mU zzZIV04T!Y9y&{34qj<Gl`r)5KVT(IFz%Ox2zDn3I+8Z>-^Mfr)$1;W3S29nVllb^s z!IGKSbg#7)`w)$%`|myu$4*yz+;KaTU-+q5RDZ4J5J+{K1shBeOrb6aeMNv4Z6`xY z)K+`r#E;oA2jcRjYu+xIeEFuWa@F_L$<k3=g~MoC_d*`tD^1#I{Ong+oo2s$>H~lA z0bwc8I&-h|o{%7PY)qW8AurFsjQ!)TK@QRzC#JXpF4?jC{^X+E>Zx9(?7!>>y)v$x z+Eg4oVEgia39&6znadgK2RO8sxvBb=e?{*e13sDgU8527A)vSqwrfkqWanfgdb!v# z*T<tj_BeRNPlf}dLDU_X*t^L<pJV5QyI|<`WS6=z7IW0p$t-8VU=XW`O$~AOzL9y* z?e7Hc3#0ad(b&PN0Wp{WOLnFZM2mD8JtT{$2Pwa11^KGHvw`33Z7OTsxm2<tUGz%! zsYuBu<NClaPJtC7f1>rmzgl(FPB993zVoU5XU-HQgMgr!b>aY#lY}js%Ro*ybd?|p zyiE~VY|+N2-AU+w+g#^`m{){Lze*$MAJ26=33({?qsp*wPuOZI4b=Up{;bE~Fu6z` zpQKcJMNj_+zdJE4#4m7G>Lx6@eBqQ*iFuT5HOEJu`}gI5T=yP7RQ0GKCt$cg9dh&Y z0Oqh9!cogd6Puz13`L}N$dG*)3$Y!&Ww6hV!Ls;65uhPai4-V)@fQBUHh;tqo2cb9 z!%i8I=gN&<p{VVSgKd@3jiL3!ytqui-br-pHiufmaz@CK%x=YD!iKQw{&R_{9}_Og zZaj}8Oxr`rG!8AG9z^roF1y9UWu}qP#--HF78S;uX^d`jk^Z+LlJ~HTJps<S^!u(% zns$!r2N$@DVf97^Wgi}@nimN2WT}^>iu8GmrEUjvVQLhC)@}Z)LKn8!0y}z+Qxdnu z<VN^k#Rj0Lxuz+hs>n}^Qq<nTFzdNtK(x?LY*ol~c=3kHSgwP*h@;lLN-<c41r{|Y zp_j<cP#b=fnb!tbv)F;T#Qt#KQ>igkZlS<Pj$%AJV6?boG|EJbA88#}{?|)Jv!0qE zOr>bBa%Y*wUI}N+q5FvOVD*vBM#F3@vws$V@qOe?d7P#?^UHlc#x_Q?nE!u9P<Qk5 z6uk+r<&@}Cya`LT30m_G6S=pLMbo#(WhPS7+JvOFZkx7(T6t#_^r;|!4^yHLsW17Y zc4CO+u<`7jzow@O4hDpx0l@Zbj`rYs$XQC;#G)y*30vNhWJO^Kkfxx1#!x@s5=yvO zMsI0v4x7W7dRod1pGf*<T)MP&a;?PlX97y)VC7geST+!BWPXIJQ4EP}rPh8iIkr>? zMSqZD)CV!Ls?u^^)%KUwDICygB}tA_4CR=*=z-YV)GNQ=h4!7Js4xkN;!4pB#2i*m zZa{qSuwN&f%vT21NyNMj&-pnaOqb-{wLV{Zs!W`dhx48}^;WvC%dlU_$r2>hqFBQ8 zXt2fWEme;sh&=lo=;L#*<eDCk<;-AdQ=Un_xnPuU>Pu44AB>(#R=hUx;#RT$0u}Nv z?*Y^lGl{f8VN`}Ir}$p6Cc!{AxGIOPGs#%m0ITP}JI-c{tCJN*nOd{hW4DfIVUp%8 zruOiFZYonl3-a|o2Aw0XpDVB4d6Zqb?AmpXpvBZ0W@^zGdb~^xR*u0A=IiHoTONr9 zJL~7gnc7<n1zMG+ch#A6rnVO4xB05R9K`pTFvH4R?}uq+$Y{0cAis5@R})Uc`H(t~ z#ZZNke*Hc@V@gd2(TJbL$Mgn|Ra#jh-cYt^q`o^r>Tk^Fl1=sojBRHq00|{T3dzd< zNE{SVd3C{tYSF3y3CqBjzMoU%jP$_ztRug#%^VM8h(g(#2Vk`=uzEA-IFZd~LDAe> z)^VxQO@Ii5iRu?()Moj_`-e`vw;nFJ(Y9p$={MK_29Y0RegYAP^`ToIYs|!$gpGNF zO+SGzW#_~dx0FhCZ-IR+s`O~`0?BqCmcgPntJia7uR94p$)6N+qZ++53zQj(R6_WI ziqdMhrA??7+KJ%5uXFXGA0)*{FlZhz5gtv`KA?onnVG>}N!rpVorfOOKpB#4HdNR; zQ<X(=IqA>mn16R+rbp<3J0ErQl+<5evc-hc#EOcdpV}6~gUvpcdhGJE0VN_sGqy%U zav-+g+^5^7mFB`8>H}};tp%Q$s<Y_mRPfurNe=@kL7n+Qo?@6F4`@*&>Ph-Lew8}Z z;cr0%^?~zJ12i3~00yGn>sRBp>9)_%CHm{T2Y!0xC%~yl-w|UBQ#4^rJ=%1V)r-{e zj5F0@yK$+M&WzJzcFU>$jmFTg;Z{l(d{)I{nP4KefVYX)J7+EMX^0#Z{U$pGKx_;g z@O=z%;WpkL&d$j`{L6dNB5|LTIGry&!!j#CIA(kD%+?={UF<pa05H8fI@OS7p^`f~ zPn#?*R8qw<Ra+UQ@hN<zb&~FEt!o3iON`^~*vI8VeTodMxdjDA8MYq99FWv_i|fRh z*VDi#bqFJsnWRPe1fm?1V`_O)jJ8U25=jV2Iv;f4TFj<f(13C@NSx>(;Bil<*jG1! zjY$L(cqz34)K8Zo$Ea0$NB$vtKv$jOVG?Y>%{=w5rf!9ycMEcCOYF(PQ%6?|F>Z_6 z-AyrushUM%%#(^M*mvo~!AC>pzAEH<#V)3MIXy4yEzik~n?s|p+<;1d&s-nxMkZVf zSk<e1;Ficzn&dhKUDmk^y?QFt!!a_}o;rBwOEk4kb4q>;PO=GR$ZfxfKqabtoTYX$ zlwcuh^&d;aD4Ng;2|4hY<~og2Azpm}2`l8|TMUgr2HF-R28CQjKqRT8Di9M>-!Gj= zs_wC-?6Fl7NjgH1SSS<iTcEMP_OXB%#WD2)2P!xRc>4MYRFHV!fV!`HEe7KAWK#3U zi%ew`tQg|a6o$V$?#TS9mmDo1>qNg(FCS1cVk;i>6VxdOZvCkGegb*{B?*!&CwV+6 zqo5&#g!SwGk_Kup(?!c4=Fr~V+~T=3zK=rxsMPIzg`%0%OSV)itp){LJ~`_w)##&{ zvu%&F3@MccpQ4;_8Cy+1Ow@*HkbskXFs?ukMDE=N|IosiOe@P?XqT_0jnUHGr3M90 z@-cVz;=L~o9@LUyhFSvHv6;lSpvb_OTIb4C`^Y7mY?WQM>jD|sl=P%}{n$}XH+n#j zTB>d|AW;tb^^PHH3o_hepv#3{G}oxA5A2Z9251PX9;9W<#y5iHSr?6bnH~zNN8bw) zi}}hyy1gy4m;u58$vJI6&4?*ALDxCxSFjz>++*m}_y3KgqoGWLVg}l1z#INv%ZN=d zVv0fs<lPwtTOi5s7R4n^Nn)|$7F|(7(GyJ6+$wpWv|U-OiY#z5ED66h#ZI9wylD>a z$%LOUK1`M>Q}DZ8Ntx&mILI+K|CDEtxctwGBIixfB8o_Bm<sXaTD{p25{p2e48ffO zhR=8V37{7@D6F&=eVc}DoF9(t%TgmLvgJd-!n}0hV(>r3p({%-J`I!A64<5f-;9U~ z$K#k<E9|I#vdR)$1qKmUZ#h25z}&G*b{QS%q9b<;WTBKvV<x(jJwYx-17Oi=wvJLg zgp276Vc!*C8nuE2Gr?Mk{R%D=+Kv(-Fopv{R+ofa0|UBibSWqV+se?^gJ_r2g%j9> z?iihJ22`S5aRKCX2-at@)lw;1nQX;GhGsYkqk_T$429wWg#)^{RTnz-uwM=e4vOjU zNN4KJ)l_MDg;w7XD=VeIh7Fz%J9M^oZ#f)p`TA=?EwfhAHN>b1-XQx6k&;{jG-oPI z1NF6*<S@9uNPKTKvu_O&F&c^D^~M@}%C~@u1n`g+O5YuMTw3H~2@G^NUC|a~rJNM$ zYBhx#RO#I<9j5a|vXSvj^#ln1R=;>^Ip#S-b%Jr61(LB`=!ISslbLWsGmja8uxOG* zy{!6?N9NcnyU5Ty@)?n@-)l2nSHbvJ4bAZZ`J>gGXprO@fSsb0M^cyyc&?Tj=L-Wm zm+$@kM>k+GpaYWxC`23i+RdJ#SbYonhkYa^s)zUQq#x>NB~Y&N_2{<_l+P832i})* z+(xYtC6>0-H{{dL4)_>sRYbbqaZP+JXCd~JuY{85()Z#|^g_y8Q@$p}47O0wN`>)i zEMJOQ%;~|b+W&o|YK8orAZ`<7uDzAST%s;8=d}~_+;4_EL%WA+JJSaXB2UJiwtgA@ zKn@tX6xC1ApFZZxC@Nt)^fq7XV2d}>jV7WsZ!vTmj~xj+{kfn<L$=BmSe&;Xv&gP| z3|6zHE3#VsBJ<SrejICMiYqQwpqb7cq9jEH*Vuh|7*1!KeI~hGJ1|B)6>N{ED;D3U z-RpMJ53F>?FQzikeI)KZQ6K@bxFt_gf#}X2lCgmUU$h|xYjh|V#OM45l)vXj2KlNh zNnM?(lgdW9(4E)m+E(TSfGL>@Nh*A)qrHJn`|h#Fk!C?XlRES#A>H6SHU37r>DFM@ zEukndP1+*SRA(@1@8_IpVn}o!KR`R7r&b}DxDYW*RUxg%N^DvUVzZ`N`%-OhH7h_l zobu?hts`|e!K$76;^vUq2Lnnlrg|JirJNmAaQApG9eUW0*&|CrJJ6C~mT0f+9@tfJ z)E#)CF$I=f0EuFcQ(Nn_6W^7xA$)TK@`?<tNJz&`ZN^HSUK~RrgnV8$xSPPt?s&v} zrzdVj5bGs_zRT0yAiDKc2epR`v|hI;5n@n(g<wR{P$5g}-QQ1VhzCMcqDevvL{TG< zXgTG0AjGqQ4!#aK?jB+w|Jf}os)qHs<#b*!glN$4-Qc+(74YzpM{IBNhqfSNnQGao z6BJf5I8-fLCovdVw|=1i9DDQLOC!@(z#?Ac<WA3=G4vSdujwqExSX8{%*U~sm4)XY z^>;dq-c%Z7mp)M<c3(Ksh8|pOGyxHl;6#<P0MNHDXO>yy_=FvZFZ8u<^X{igJ-yH4 zeH`es1*>y^D{eUbB)!6SZo-A?azW_jQS#wpP2jf`zYhP*4RxQ1Y_KP1n;0Q<xn9ag zCk9V#I0MqU;9qd)rXl-$;qmY9A!08Zo&hS5rHNPeQP+q2(k@xJclbTc7VGf;{OS(z z;+T=;km=C?nB5Y9{M9&F6*Xm+W=|OAlvEzL#Ww(7TJV2<hJIOrJEBv~qb%xGyHkUR z>U^8$_2j_uV5Qg9=9hP%cE6mgOLdNu6YE(aKpZez!F<W*tOLx9{sTum6#-n2&L6SF zIfr?31fgAYm!_#oIl4D}>lu5g<lN?d``@dH_wQGJ1Ec(Hwm9ld`5d{t|7lID=2;mi z*@`$@Oebc=zF%Gwy4Y){nyqeiSy80Hr9r;X<7Zrzh(~(FTB<Cfr>4*~WNaOuM|0(_ zM4z^|!n=nb{`Sp^%q^+I*s6gnBqKU;_Y{C&&04~%ZTkz4nmS*n;{)1B1LGR$)3uE? zCX}aQK8-Zlf`GwS$!cNQ<n#{zB|UJKXMGSSOXmiSB6QxOr&dz7e9T8sqYP!rZO1^# zq9?JDxgDQv#W|;^8aGYt%|U4Eu36_OYlj6L$3Vhs3#FlZi@p$>u9e0W*%MAUa+v;V zSq6eesD6YuN$q?T%-xVqOHGlQW70VQ#X!GapB!V6WVC-PJQeGEg`ak|tpm>6xY=++ zzwtdQi~qzfGmv$N^@diOfhD(f8?-)F=etH*CFjPx2AQIL6S;pBn3N&q(`*w<OqX67 z9Nw=f@^ZYwQREq>#3_2#JbtwL9QLzc5i`X#S;0NbUM}Zy>?U_fT(aan#j0XE$9oOk ziHhsb-R3O1YU)+q-w1h_ZXb}kK+Y%$fL$@mbZngFEQ@u~Fq5cAg)Wr@u(@m1qS8;* z@Y(tX)nQx*?P~K*x3^Jv^{nEC3Utdzj&=>%u9~g|CWd@6qD}*j_YuZx(H%)ZdDF%J zMlK}g^oydhyBiM7B?04YB7zpC>r>U^^1tDj4tZAV=A$p(Xc3wep8s#CK4AX*o;Z;U za06HiKRSY29*WQ|+<&~;^T()Rl@Q({^J@{1|J{^lgN=NUul>x{@3yZE$_&kEc}N=S zI-6-OFRYYK_emw4$xOQcGT6>q^rcHeVD&loMn}=S>>#*^i<T<|6SR5vgMjVIZ-4XB z+*zv**??iq>86^1v`S9hLV>!^6V$*F^AxEa7N1YKtoRSsh?0#4r%W$YbhvL?-5`S7 zb@rmf3$(pn`ZRB-%c|vdb5o4UDo;S?XY>WZ(-y>z+tbzj%EiHx7j|or$?iiJD;|!A zb;)-3gFI0HQTVGf2g=xmBeLC#*~r;lat=h}0$gr58L&(>!cIb$#%?)v5;#6Dj^n?V zJb!a8=GNq%7m~ThyN%qHIL(qdmmf#fH(TcL=mqPZDM?atZ%fe#_Y%CabVyd;>PzzJ zWK)orVZd+z&x<Wa-ow$MAesiRKQGhgf;m(!IyW=alZ=)V<gz!2;ytQaok|0rcFJE7 zbB|9}y%S{dv`niYAQ8+L-U_)@IKvm6KoKL?pEp^wyOA(^np;7gF5v!(ud;q!EjWl% z*BPA|5HcLPrcxIY9#}BtGOicvGg<3Rz}TY$Jb=JNr-_$TfR}Lz*!UoXvp0Qit7haz z6hUGmA>y9v7@ufGs`zWw7h|3kF8V%KOnhvg=lAP%zp;`;&8HZg^9%pg89-Cd;XYj~ zbM5GrqnYakwM(V*-eHv~g~tm!FI4g$$1#QMQOPHkR)mYzy!a25bTY+XuPE$Poi~=D zrycO6DFS^%`k_5KjbZ*pYJ`lCshufBDWt;NDNdl?E35Nh0<q#bqFDZIE`V4CEsQf0 zn(C@n^jKFjuf(-?!7-BK8-yP9t+#>w;x<EUmolZwdO-d8<sHtnGdWN|ZW@-SGo9`H zu`X_LDfxpWPb@GhOf6k{c&@40(D~aUWyA#&@4~^U87Klg@hKoYd1fT>*y3~Ro|pkG zI@{Sbv1cOYd44QgFg2WM_@0DxE@s2+HqPMeywY7mhDADvrmBs!%Cj(D<t2jk@j`m* z>3lLm`sPV}>d&l;jvS)S#$&nOu9lJMAJiOP**pCVJ}hYJbMBi9G;@0)zSO9-DmG4J z%JT~I9!DN!OL?ZCz_JB3qgHn3+Tpr?ES4sV2kj#v#9#!^lS^vOI@chJ{_zAOz!%&h z$3gpQbVc~Bokk?)Z|GM1BaW=f>CSo%+NV}B6P=3gDuY!y1x~&83F<evxR}`$DD2+I zD+)ySL5RkdBP5{@-9LrgEsWbZ&)Kr2b^-^<(G+-5w_M#dg0phwx<~3prB|yW9_afZ z<Eu9=(s-1&?7k^$>q~yJ|9$Dy%vkP!@tpr%%n-{LQYmXy$Pk|;UZ~@f3@!>95WUmN zsr@kLv1~MsYxyyU>$ptc=fpjHsGyW;fRMPr;n{Vq<RAC>uaA14_V7zp*Fj{-)7?|| zn(zEw{1yp?qofb@s&49s2D{c7Bwj<vSYn*(if=Vu-CC6<ZU8(k>P)fnX9SyVUXgZN zH(=sqEb{K@!Ym5c+i%N=rTs#wPkQfHun$mn#?hM9ZHUX=8A7*5`IKz!QdAdlBGscx zfcPV^d6<gM9o`z%xlf$>d*<TX*s_F@qph4JZ&AHLZRc}gmS<&oig}(zug4cg-If@6 z5&T07AW!m@=zk7+4olYWuE+=ZtT&XkEvGyXcUh%A)G9lONhb_>hYO-)%%Fhp4Hu(E z#hkQ5C7X_4Q3d*r5wGto2TJ5|BrcMvhn(u&<0sgmLA&lXhR<Ki#A#Vvd^H6JDt=6a zuVY~vXj1(pWTNyx<M+z|4OMK81ghKMK_Nc8r{e~W72lL_+@<pbmXj4D)6+94zCRFS z97ECcbfzW5x1D9G^`v6fryP2+n`Rf+YB5l9w&uP2kBO=8*BZf<FZ(RdOt3arCM$mB zejNI6LAN9RLX2CD)|IaPmr-rr;RF6ZTu@H+@E)<1$%Sg<^aqohp~AGy?CzBw5%gxL z)an+T`>5$hzJ!fQl>hy%)`+!5a0?(*uM;*W@xfdM@RrYCmJmN_yqQOK$P&Ng4gTzg z6Ud5i84ziODDDUXT5-ZhtioX!2_}itP5vNKzr<f3Ab{Y0Zj^*`Y!NXT^S0<0T<POY z@Wm|h3a>r2!}!}<$ha~t&iGmvB?KAje8wB_HPOP3H*Uk*!jGG*&epcRsAbW*!7s{f ziyFTU%q7p|4%tO+;LTV5^c_zK?k9w76GB!$Wvdb!$>GhF9qb`|*=NG*>}{Qaae(M1 zGKDW(`YK>Cww0YBo(>E_8r+m&{}5HaKBMnLW9uhl5nmB&p8VCc+G;HFfQUp_@IIrV zU?7wb9i`<3J%bbLB?*dq3EH!26>z#nBoTWOU*;0GQNM6Vm9Pj~=!s=sEJ%2US6~J! z{oYHWwO^1$dU6=<mEgIYr*~HlmSLZ{x?YXoYh(W&-1vZ<=4oQ=XPZji3?p<U-YQc& z8a3s9%zxkrNdWq^b$k$cNpV^@L92UzCz?A<l=UBOMPM1xjVt<QPeDzLszsR5;^$Eo z7UseO6i(m`hNQ7}I^zS}Wto)^tB#rldJC{GCKO}~7<YFAv5!UAKvDYuzYv|LjL5y^ ziIQ2K()=n^yF7(h6V$@Nr#wX@5xTqb2(4w|kO3i2AF3N}@)>q|D@CXlC2v((uXRd7 z*%X80+q;GEj~v^3Mm8G#CYd$xVFD%7J9V@d%A?!fu*Y*;NA^7#GLK0zb7pJx@qYr! zwGVgN4jNa6jC|tuQ5{+h?t4|py(z-`B`5Qf@;LHS6CV>^JWtrVvCSuZS15t%$@K;F zRcD4Ej+YuAm1(NXaQ@)3djlC@YE<Z>zfFV4laNpx@@F4R0mnU9F0}6{?7S@03et-n z5K0cHv7q-@klG_5&)xcQ-d=GlOT5vQQcD#mE1WosWDj`OZQ3Q^<t1cI&AKCu-bFNJ z4*ag%COipOeYOKHvEsRG6TOrx)$)}v8*UhQ%J9;p*8Ac4hXlm82t%lYV>|?4ZR{Y{ z+PBiuN?}gTGAATY8bR%lUt2);0Yi&Oxl8Lu*Ft08@@TC0Cvp^Fb7`z~#r4qT1Ay}e zE%O=f@+-eX7~NCM-UIjp9gzR}a_X13C2`;NmL=u9_>B5@4m{zTOL`?wiKqN<y>)`( zB>oAS;4PH6p_k}Uer1RkrI%~!p+lZp(BK@>b(<a9deJ{v%~+Qy&K?&Vk0dM+v|b1( zPvyTKpK91k4{ertzawPjRGGK9J^znDY$8h^`Wt#r5YQEAi4+ZK$8=warf55kK7rTT z)I1*Wpqr9mCZzlmB(u>UE#4N%8?4>JdxXf_H!%?61gE{FZ-EXdHvtKZm#|ec|FtTV z5s9xJKmtqr#1_Hud-|tv0<4qx<2b=ckeDQRmE7szvO3777#;qI{?8<n(0Y&8CsZX% z_Jgl%Q)9S8o42uXmG$$ekMHyL*gkGqtH0DgYQ=w^Z(PY;2{%j+byRpt{1)>!aAHF7 z`PuAMeutTVS`mbM>qyy|n6A$m0F8r6gf3J__Xz_B{TP6VQ1tXVA*7s+1+~c#xKJ|9 z>z}`b8lL-35<GT-lg=+*fp8>=ANZ$f(S_d8cqQp@6E8u3oS+&VIljd69w+^pgh4M0 zCgLu-w6u9MMF7<Vl^}u*v(?B4J)CFrpQh^qL-K#SF0b3+%ikMY$r61cuCI4zXE$eO z1&qq&T)Ttp`h47u`9JU4!Do(}zSkyl7o<W7TR^$=;jbU=6G<m@WItoc`dtutpIJE^ zI9B~Tp{uD<<|qDuB>it$%8>{?_w-COkI}s($Ns9%7ISvE<0tk36qYU^Ko{k#L%Owj zSmF3{vAkQr(N7^z9eu2|La@0_BsBsjQmL<vkXe~B%}&>13%!@oPz_O18L6kuTENF* z2z@#sO_i5TM=sRpnmqb(x#UY|^)tdS;Y6BfUil9Kh9T1R%w@CSVz8|KSK;$G@AF?j zmi-e^uH3*o-v4JS3`{J6a^z)NDl_I*Wk3Mu7G2sv*!>3$tR^b+#K(t!>aC43g%IJ{ z0+z3tymsDiq!M<dPem&&i{EmLGpZ2W!=eraDtPY!z6sU*bA6OO1;;?j4;Q+=sa9L* zPr^c)J$X#Ijh%dO!E&z4X2j{r^H{^?qP|>&%(Kn2Z}Q?B!fi$%#p8qw*waB<*@G`_ zk>*2qe8w<BP@}1`16uSCK7$n$0CV4PM$8jbqD(VF<gWOA;Y7<AELl<<B0ny3SqK7Q zmf0NxS=yVX167}GO!*hE2;XHPMY_NYjeil~?J9>mS4iDLF-1r}!pDU&1=`~t<lXFW z(4ht$=TP>9+GEyT3|4s?$f^B4@MQ=0tbzFcm&P}{QwJa~rgC_>tqiZ2>x_#k10Clc zHDApcbrjhxHiqno9CLbFENK0s<d8DLT?#n-Mf)BuW3(b=C4$k4SYxuVjPpp$YY5{l z8c?6st6Yus^%>b^{!a+UpSeUulaO&B0ir_S{1QS4v_dv@Oyx>buyjm@J$HQ0nb%eH zSua7U)(jwe{Mxk<9rariN<We1o`&A2{1xFhaN&Xag`Snl=VVFO+PzM=Yi!ePJvnL) zM?0QJ#>$j*!}X3C-ih<UQ`j%;b9AX6h1Ir%G!_94_{SS7y`*)tMm~>Xz3C0V2`dzq z>kGn{RgFg~*^+fmV$0lv05TKML-wzTS9`=#blLHaGM4TBRhQCG&v(s&mbY`=2JzYV z@|)NdIPm-}xxsE|(cyl2!3pug+Y1Cex2mCymRAm;{Z&_PB;DrCNWhWvUB9;JLbi5e zFXG6g|6KHba?4aIl3#|=o?SMQ6a`X8Fzx!kP4dJZ>KiMj({;b&M_=LBKHn{&bYcao z#gDmfV+HCxPY#s}A}a)+0q}id$2ACPuvE91z0wNidMUmrpj>e|E1$x&-zW_gT)!25 z*KbL)==QGy9HX@W4P?8t=E=9#oq_XQp*3Di|0I6fchFwM@SMXw{)@BG+}Eo)JzL?K zPQj&TZ(TO5rLc4duIIeQ+aL4ksi*Oy1ty8~4=zz|e+ciG<7++y6_?JHCAasq=yQ1; z-<dl6B;MI2!9(b>fXpdAS`KP<z55qT=Jf+a6SygFF8R;*`n@Qv@}K!*QPoWsKPr~O z+eCUBw(*HZg_BpRs&vN+dLxIg@IKIPq#9h7w>GMFzKvH1YudxxuO^$m;!OJOLWAh3 zSzZ&PyPI4%v7qmn<&$-H;8xubUS#TRArN(N+)LWMS6ASMn2xb`c_nq`e%cn^<R<QU zd930|?hqP$tB>ys5NYJ@et;E}@p3n(!*_^$x#dD?4Iagxx(BMt?`yTK*lPRAO035> z2gnJ`*EZ}ckEiTCDp|0m981G7=K7fu;l}eZQb4$IMyb2%Sk9yMU3{tc%M*~cHkla} zPNR)l?ZX3sRn4%}<c*=%^H<OByD##O9B`9A&*L2<BXv;9yQkkZgWoh)a>WrVni-QN zjTN+to6-jvNDCB*)^}|2!S0#slUTlmrSusrV!RJFOoV|!fVh+nD&P*RLN8qw`jQCi z#_}8C;>;FaoHbHk-_G+I&}M&V`Xd+?(W@+#)Qoz>>tSr2wpi7)GCDw+4>kVn@+5N3 zVd1&=3-`Yt7v5ZHxpli)4*`m{WnMP?@(2Gf;u_&*t^T8bwOQAd&?aCHA0+`9+Ikn2 z$hoyFJ<bIFTk^JccsIgilSE_?^So>2+~rt<Lu1}dB6ni?^d&CkQkWpw7OC>JJ-P11 zVS&)aAd31;LlLO<6J4fU=Zp0&pS>gTN5~J)x@b7}qAE|))g9wbh|l!@H&VsI2WJ<w zZLZhq7-=RwNkbWRxpbbAR?eL)dw(Xgh0*c&FJnHzlVdT`*M|^<^)bX=<mSEM)prEc zjfeBd==>a2nf|!0>igOH`l}_;EFv#f9Z^Z+`PsL0cKxXUCS2)j86&0rSC^iL<QDcR znsk2E^!DtHanrS7`<bx{l<DT&^!vW_-!q$!K!&{|Rr4(}?=KtAgUTiL{yPL!-t0T7 zVT1Kj)xF4}a0!FX_bhR8@H0u7#<<oJQ~wDSjM4jVSanaF@oO+q*{dPB)&f6!m}omg zD&gjmT4UPsV}KZ7A|eQ7MNx4PFaU+mE+YT}&<D`g{%3rh*x&}8!+G&F!0v~Dw&i^# zWltyeo{IaBeap}Yv^ALKfRmwS0<)&D4u@l>6O41fwws=w4vBVRCJXnR8i(2fU*3z+ zJfoKM5b;HTo3_^P#jPK;zR+4SoPm*->Ew*4&`EagNm5zJYIwTP-cV_Cl~o#4{!BgI z-C3ZT{9NRUlkr`3XNn`&S$M3{-JED3LvlYYgOyFz=X$GUBxrA0m}o05LjnWl>{^xJ zM<>x;SJ@bVfepzO>dR-Ec7*(nXW1fZG?GzXy~~^u@R#3S*Z|whha*fF9|K0tlFLt1 zxDB+PIS<4MxI`t1#TI*KPOlWJ-nZh+_Xm(4yifJvpl;+!KPc@Y*N>mJl-G+Q0%0w} zyO=YJ-Lc4Acu$wOZM}T;*&M!@{3*?m374A@&bO;2$;wKD?x!Ro7i>K;99>{!)JkFs zGbXT(CGqam-6;Y1bP<wA>VR5j`E_(e2+&nYV%_HZ%taJAhm-RZ<12~al;8&UN!46B zsD69)+Qc-MG(*nuHn~Ky`b<hf4g>F*SVERbOVgNhNe5a}kxc-aE3@$UT(UeMsoKFy z=zkZ8y7A0bw))1Aru@2{5A`Y_=cLJ-$($F3a@8HZV{?ZMCkK!zQ|5)Ba92P0I%CoM zYPPFCIY?$O1;dkET~5iyA7LA&QjX`Y5tqf9P8Qt%<rw<={U`fs*h|YJS!D~Cg!ENp zk6@D=kIHAF3Y`^q%M@n?8k!XRSG<)#wi%SJbA_%>?90@etg3HuIoXetcpUREVx3Wa zYD!|c_w8%_-Ao^Sba84~G7ysOQM;Y!U8Kh0JboS#q=^TzW{1q{0p4~6>4hI_r~w!~ zz>ESE`W}l1mU;@F%YTH>DpW>~QeG3mwux{4?R=O%8h!W5kzDK_%aitE;W$Mzc0qlQ z5Ls@)=M%V{$L}>&k~JF@O=6LeTy242{%+Tv9u^eHXBGN5+2QjWDU<Qg&P5ZRwW<4& z|C#trAVBk>6w3e|fv4+k)iQwn@j@5#>I5VGISJ{`)cI|L%(xn$n6FQ4X)M-JknbB- zk<SKX@!&I8n=AvyrF|d54@kScBc;dZcZmfVu6fiXfWx^+wm4o3BvTHC({DL-i~?(0 zB$?Z#PXskP0gA3ZL|tVdRgDSr5+mErYnJzJVIO-BPq4aVZ@%Tl8C)^vL3yjbz56`2 z8v=ypMyrP2R)~d9Pr`*)3^Ovf@i>iaE(!3%{Aw$CZf*y1V=^)}2&|A>|8)0BAuDd| z6ZYav_Rp>qBs+#5_+vTxdN_*p_fXC>A<UAWKh_q~D@BEVWsUR7CL+K0K<)mJU0k5~ ztgosnxMa(xQcL+FhG;rZUN=)lEtaLcl0+%|ZV8pwt5nw*iE6(${?V5}{WZl4^nTAV zJqM$q;i1WmR!4Z?_v)Dg<Vmi(Ii`#e;oPm2RBruK<Lar%W8l8DXWYC(uQ-5WmwL6- zI8n^%df{yrA1*2~6|2fnPf9$k6ak^Z0SN8NXsGm`Z7u<WK1SUXHjJdmFx@NW(Bd@5 zF$`1D{PuTEY`r+VQX!a8XD(BicRB1XLRLp1tx<c5g3MfkDvh2RZ8X>HY<IeIF4-~> zX^GSN?nQ~)>u~CdJgkOY_PdklXyMi_kjSlnj*@$lC&sB&nB586HD5=WEv{ox4-r~# zW>~?DZ>8KIIr7?NRyF#b2@!j~Tu8>|&E0{k+&!e*qYeU94-*X|;+O(USPtz)TzOIb zK&e3G3v)d6ctJ=#g`htHkN={f<b#S-DP`5Bu@c2pxo;$NlUbbB)pDwh$`BDtdxL5* z4W3F%@+qn;m?&Dqb35JUec27yP|CPteMxKT2-n!BJH*gpTmBv6PFG)^S5V?#A^Suu zKsPy?v%3GU;>pyoC+FL(vu_7ekR}FH#UCoGv4~189V0s2evc^$-Gh=m1Jq{q>xDtY z9zIuu6Y|i#V06Xch2YqDrOHFA<K~rTioV6P;XY<f$6b=>uhqPisNHy#KawJ{sgAq< zVorq)^Gw{mFDHvjYsO0$D7|$|4>lh4fP3YA%IfOmRz7tB)oz`{I(-8Od~OYKw%HZh z!rH`qAZ-gSR&fsT`fY=R1uDzqo$!eGIEKJa+N%0dIo)w@fT)z1YAWeykZZ08F;2c` zX~EJjrKXMzXPl|~+)gMLQs4HURTk<})78C_n{c71`cHZf?k~rT(h0cG-0yTVILJA4 zFh;o!hsKTSzbbkX%~DU=z)BAztvh3pT1g_nS*y|0|LRy*a#6q!qtP?%t;dr9U7TeJ z>5vy*V-hRrJ81cl9&eS&ng@Sj0{{hGy`3o9i{q6qp}58FaN(epyk6UFSiF$$?Xad% zc#yKE`frcpO2?i18lBV>A6XU#DLuyY2X0HgLH;jav(2ZuYtdHek>A^p{G^y1`p9~Y zTQxOUxj)MK_ZExK&)d<^$$?`2r}pr+2;lA5RMnZ@YJQUoXXBJwyFQnPy5c(nQ?k(c zPe!OBkpweSXGo-OvdZLUhAF^M9nuBnaj^+y`iw{Z&rXpg`#yDCLu><&FB!{y+WS?k z;%3I~`PU`0uL0nsd7oEQ?)zWZKTg(U8Wk1xXz&t5q>LPob4?*m;^H_jwn!Xm)>@5L zzlHw}I$NucO+wGt|7LXBu{59b>dU*EC?7-C#|JgcaLsy3!-1WoZDs<9*VnTfo%xBS z?~7N}!$7dS-|l9tyBSE<rD-a2+W?(V;l|+9I2=JaJ=<ozXiWIkiF#I%l+SnPvRtQF zAOBZLzguOK_`aM=`(C<gB&pvr{_L#7%~$%=jo{eSugzML7wMMmc3tUFjpV#6Z9;~R z>`hTW+49zf<3l1rcu5eF`P0_(x?@hR-fa^7qRyZR-|w@P=EkT0qSS_QAJc4(f&zip zYu@B{dLzOX3aqbU%@L}<^FFyvGm9^XnzxM4+<JRXM8mS8$PnI7*o-=)A?Q(ei;&Ap zwCXbgEoX%PzKk;ZpmMHI)~(i_8$~cJ5-S6dHCF85IY!(SlGZ6m9N2Ut8EK#5%mvb! z&qEs11G)Ou=Y8GBFCpDn)~PGVj&-DlC;tIbJ?;a+lXb#R$fwSfD|Ho{<gX!CrJXo( z;j)Ip&b;L1Saj+)c~PiX7b{XoTdbhX@^6Zm%;06YwaZ^{E_1eYlMWj1s09?KE0Ywe z0!3Zw_EQ%WIKz-1_)fCUi^gb#*(5X6rZqGoY-b~o$e&hxB(A7!!SjR0$U3HBsw3Jg zTx1&5bWDD2&G8Zw2{19qD_1X$C>j(e>eL5*9~MM_ae@MezVL4We7m^9&VZ-=`W`#_ zIk;qQQu0Baa#70V|N2vG*?#=f$={vqBRk>|do%#ZTHeOYrXuI!kW0iA1dcA>&v!A< z!k9tM9P*chg?@?fMC51|%gb-sX9(sZ=a)seDx`M&nTt`#tYl<kLE5hz<R&h5`Vul{ z>e$MliTt#g2<o&Oz<CzSk;!T9m(TffP^x%GfsZbQn)Bq+z+>uM3-jYLMXhcTLI!I| zUZbS`dgX~Ou}}ri`>3d$A1dK61V1`O)--D_HHwgeEYqW_L;c~)=bgPQ@9*Ziw_WKy z$#D91g{Xn=PeJBFfSo|$^!EaPi;<Qz%;JMXp~zW~%{KpjD}Qt)j}TV6i-U#J;BdiW zR!JOWEY#7K)7;$50tQ6c=Y&^E#cYcRfbql%SH5+W++DRc;u+6TnYf|I8&2}XHNy|Z znUIaF=D|E?95S*#-nfVM3Y~KE743yymb_P<&U}_O*A=}r0ppV>c@&kJl8@-Oj7~-t z$1o5%8C`m(0Nad#4`HLGHxk%VWWNGp#l=%Ep`rPOn%hD$ec;_b{*MlF`}MJ|J!#w( zihiC@@;3M!R&RJn{dGr?aetBbYEjOrr-bY&c#dz+hGYszdGLKk?!0}(TrL^v`hY5b z|D?tCI_7mB-<v)0%Dc#>GkMdn!_x8+<Z5|2&v^MO#VjsVmT?e8URa{jt`t*|g8OD5 zUT<giQGjOdCqh3{RAa=Rqar}2x;0kEQ%xVc2F9OZ&J70E)Upr}>5Lg6u4&M|lEj~K z{<uipPo26V-`rOFnde!-WGtuKx<CRWW-SdV+@4CUwSE1ASOisQ-YH8_x`WWjys9YS z$RHoM%88B(7r&y-qXoELBUi(bVfRXE@6tem`FBo=PZy$$HdW0Yh+)&u^t4jtr}Ht> z-0Gm~FQ=`NXeR@-Zvf#5QTEn9bgH&N!1;bR?qwzbxSIpP&VFYH#)LUfIdR!Rn7Nq6 zy1OatLRbffr)O}K{$bTpgf)D}6xLs~u3upP3aLD9>#~2P*_-q@wYaL|x>MJ=tTDQd zChE^+<g9{(e=tf!Tq4putBEU%7hd-gmW8~R7rBww#gx;mu86a+$KKP#M5OYyF{&Bb zPX|*mIBOG<^_wbey0aO%f_Y(8puGU84nU+@p}&YW_caRfDabDE6PC8O_XPxkqBvv6 zq>=}YMbl#7UV<IwG1~zdVFfjjKjJQNWZFcXQ|3P60VG{CWgYGFjiK>8{lZh?bvlWL zCMEHR?s9lVxm-=2h(@UpzOGKm!Zh-Z2uQ8)jM$nV>V6t>XqU(hGEOSh7Ts}0ze4^D zMEwdjD=IzYC@FQcY<0ZYq0908;`Awyld!-^JIo(CN8qkBIQIl(hvQNoXQVn;ibD)j zAqm!&DjAibgeF~{qqgj{4UCgyB*=qk0mVnj;6U-Tq|h)J@C@8heW?UTZ+hhxy0C!c zcu0G(-)^}gKE_6NM`$&?2<ZtBKACuiK29Cfsy}^F;bD)q9h_-YAm}dFqMm#slW~0M zgMehRhiN<iF97Nay2{li6jX8#fjWI5Dvg<^6O4t5l|w^NRgYgGH(WDba~NB6#j)kO zx6_I{H3LdPyti`BQ5xEb-wd*OvL`n%Wfw~I1ERu8JLdfV`~9hQE;Xz11C2Me_5`zZ z>&jsrw}wT0aC^y!mWF`r$v>DD9zbbd!)_iatQn|h7nmK4`sJHwu<-~^ht>x>naay^ z{kFEQhz<IEpQA|eXL}$cn)6aQR2IphgFPO9(o54E7kvML-VcqU?-vB1-RCsVuyDyc zW04x(%}xw?JWq+>ba!`7#dK~I>R!BdT8~x=viQn>eDo~s-%Tb=`yM)3tLhGB18FIE z6W*4ss8PHbjQR`@{IcTUsL$kk(dvu~=BvPXl$`uY<NvA=aFJ5IU*Wy$$eF#;8khr7 zPzQVTan;2%==<S%#sc2{aURgp?B7SPW*~jzkmnyNBbFoY`&vp>pgt&~UTF>?0}oOE z6CZva*i>p6^#%_7X{bHpKGb+dq7y~I<fsT#_&qB}1tdIFo9+|A*)=L_W4;;L)>%os z(2m0CJ6^t)nun~5vEIX9`YjUdc}a--F7jzm)D*YSA5Z>6TTZ_}CIGAV%i4WRj`ejd z4%hM%87gLBSk4SBPS0|YdBXztezj}gF7W%Imn}ogZbjzR@D%l5zpOpZr$JTX2~`k6 zHK+_3|9S!u9|p%ijrJaTS&y7eeX4)zseL4E<soHl+)koCd1OmKc67MoqpwX}+;fzG zWA%do@3O9per~%P-{EG7kO+?mul2SO?jw|G&GXChQRqA9G+mdnd4rGccouoc`NtO; z1aQ9VQ1=$%@+NXvwsQ4cK#4Fla1lw;vXLdxQwjnON{s7w7N;r_x;NyfkMRK3Td4h4 zPsRicSv(Xq)KjgSLti6${#+@Cy*|bhJaqVG+AxZOm+DzDZyr|hq})8S#MWd=8iXbw zClg+z%_H#!Be6LeFEbzPq8%x3kydb_kol{C=QF1W)(IEgp2^+}`@1o9(9^9amNc#< zeh)V*=QQ)=3ew=Jb`m&~j~mTLI)1m68yJIIKS^#lH~P>&BT4Ie(|NMem8uW%+P^yx z`{l@cO(CTVMQ7z!S$Vvrd5HKKB1$4AUflRdbkwqV%ot9v5KA(A(K&V~@Vu?rw=(Rw zUIHrC`D}Dfgn$_lhZ(voy<(+!x&n;fMjRlWoHf+NhjsaKx_F;5e|B*AZiA1PLj$H> z{?sxD%As~k9M_jPQ`WExmc|(_qTKf@yIrTkvZmM%r<4NDg%202{T?Lkyv=!vw0t7h z{w=e|=zqkVrZ3jV9R8K3sIKcvyej<oG{)lL=)w#@>nr_?8mQ+Hi4l-kLm?*~B;g-j z>bGK+=R`zYlaFBL8Jza2XhHj<jEOH(o(hvqA-cBSwsa><8;4&j2PfNG#iYgSGlwr^ z%8z0Dsn%+dXRx?afBBC-+}I%3ZeCWRQf+#W<TxQ&I;|2d{>=OEe=Q;JTCx}HFsciw z>+%)lIH~`B|HukV{@)2l)C6%tt)x%Dn)>}?-{Wdhd6Urxv)3GDR#lo(U+*<s4wzFl zIeL1SUn!gYKK<-83AFDba5_}lesY#bFZi9u`SHuf?4StTZuQFy(y1O-{4PMIV@zRw zOp<Ch8mnA6VgKKY|8ZujWEn10rcjzp%3lUQ?P?rKN?L!d*8@B}@6+4Jxi!PK>Ex?8 zlh%{psbn?r1*K+g{Bk+<Ys81&=2adbJw*TApB0$<+9wTJ&+bbJd@a8UwAuhu7mqm$ z56TM#Y;)MQj(Sp+BJGu~^a#e&q!4y-&nKNRxyapPXDY1E<cJ<7kLdUfw}lYB<dxpc ztElGRvpMf<SKfOoi}$?ntU2QT!8FLBWcuDGcN|LThvApDL6K#2n9(5So7YrF*z~fe z+#OSHREx%@R0weIdp=U&8uHvH8)7*|cFP*Tf;T-+I_2>AzrrxT2vq8<MCcX;Y{MM3 zVK#l-EFdDaORzQY5qAX6`h;o751d};)bbE|CHcB{Y6#oBU5sBy!{N$xVVB9x?&b(N z(akiS5C6?{$MbzXxTRmQ``5y=mO{;wP_98<kQ7kHS%thqUT=BuwbXPcw;y4bX4>?j z+WAE2Ky05S$hQpnGrY(Zmu_$egZbuGt#j#?I!7%(a!m2injXyw06JWt3A=h0zchdZ z?FEh2qiANintn60V^zmkW#XkWY2(#n&Q0D;)lN^>``tBsHfQc%IMZ^jj|N(JHTB_i zIadiNaBi!vgE`CCpN(a`aR_@`xDORY0Nu&Uoi-c>*$vMl&i!}o{ymoDLYv70u;NW; zFWtLgO-hcNf_LAv7=N1yUVsDmB)RLk`*(v@pOcd~dkU(ivQ87=PZbZ^g)As?rU3L~ z8>EjnNlLNy$ED-uTzAUoLZrynvFA#bPmS!I6tY5{ZqYQWqgoMDL#YY=iwobX%<ssb zuC(Y8AT}1l{hn1{CVU{>29iN<%VO*89$or`34tGW8qw;4`kjW}Tnlp9`!)o|p84Ok ztL4iJuEw8CuD?lM*@rj(e82Ox+%Lgk_&@iAU?k1$8d#;ZA8yDCn5nx%QA6V5e6;_? z-yFx@QGh@cRSNMkFf6c8!8s*l@U5(6_xA@WVX9|;9VQ`uvTlKfui|x5)L+fi0^+C- z5`n->-K1*}B7d3?zPiFJm4E=&at#CZ-#dEWl|LH-@_guiuS4z8-G_gIN}$5t{)&~^ z7QwwWo%%O!{sfFhpC4W5E>1DGJ8qa9B*>hUxUx}E`ycTo7%2(<+ws2Fy#G&df6Z>` zJ<?g3HDyHyyb(;_S}0hKVy1JD#&3LtlMEhqnnU{rnfNy=<yeV*RK1udP|lRu{T3kI z9O#~W6qAQ6Om0!TV9o=?ax7&KYF*lS2@~e4C<|n;eTDwU2Hy>4y-}dnvd}mZ$Tr$c zv`m6sfK9x2W~doxy=WXWNLoBN<q51D1lg3|veQ#)-i4O;?k=(|RC@v8Xxo;RfeR-7 z8{hV(@4n}8>;r2UkM`w#1TU%G(aP#P<{AHccEZi<s#?AMrUyPRLkoIuJURZtmPS&p z(WvtsyrCjbQhbazcX_$7IaK%^h<L|WgFJZ*lVCK;U0(mVOVgqmYoMv4*uT;i!Osxz zcp&!?M!SKKnK+kZYjJ8qL)J)e^6+{@<X5x}ecz@cNt6>f{oSh2rJ`No-GXW+MElqi zudNcg*cJDGW6Bvt@H+g@x$mb>k6hJci4XTzMX4|(c6PBI*V4IZwxRzv!<wBv1}&0I z4(@7<%-pleP$_;d3<U89f38C#Hi<iT1EEX?)4RC8gPE=f-fX#U@$I$hlfBAJCyajm z8^S`IZ-Jh9G!us`+VMdmuCDwpzZ@ZAbrIN})W5IjP#RK^0hxpTpQ8J4g!=yjIR3eF zxMAF#k=@-HXYU<4?y|?3nRRAXNRl+ZcW0fwg^V+^5;9A&LzIw+WF<*bNh;;%_fNb( z@Av2ZdOx1{Qw5@td0;#+{_zT@%-9$goi|S-*5>pv@y!AOvNGlE*hih6hr{`K)5zF0 z47>8qOB#?eAjT6sa#Pm$aVaG(dgc>F>ws6~oAjX1Y*_q}hTiLv{=X!=DvSB&z@ND= zQHcwjAJOEcAwC%eUw6|}BZ*w)tm_&O_yh~pkJm0HrkB7fD*fv00SMRy5!m1#Gk^B8 zx5xV!2EWpM$KRNd!qc42`H{%5*&?&+9vX8u2SWeBzcwasb4yoY&OA5Id?3AJb-o#c z*$K{+0wybU5!*w`RMaC+j*76S&TMkW14^-N+w=!|$kJ6@uG<ECf_FhWtSemSa)x;R z0I#1);x$Wesmu9mBSmm9hI(o8xN0R)c6Li#wJ{~+wu2c0$=8q1nSY-fZilsr2<HK| zjj-%`%<I+AoPTEDFoJ=%ZI<`>D$e-Hdb*!GxOEiHqP_zKLJrtd^Ss2bFA_|`BVHQ1 z#zJaVnz7FL{k(h53P9K@%A(G)gY9?E!SNu;#&6C=0iDeF!yQc4q-kBX>X7Ev#q3th z^yiuiYd}6M@)+Wm)yc&`jl<*--X6q$7;k8JTm-wPjm|{4^j)~@WgN6u4TP}@7V}rg z2ztSGGEcXoGejoV-V}XvRi+3mc|u+I8Sgt7ui0L(OjFh?!{~vGGR{_Pdtr)Aq-48H zO8PbUHL>L5k|^fKn%Ib|`RTBnVV&QQayV##SMhu72`CNjOkNUioV+)ZPveA@kvfNm z?vTVF9(dN?Txu5VVX-+D*SBy!4=j3gn>S4N)o6fqMEF<<+wHIcU&*3;&|Qd11zpiz zz%HpSqXN8a_pV`X^B*sNeJoda*(Yv?3R%bN<hD9+r|cSU?yJU>frqj)!x49nl|$n& z!KZwIE@x|tO=;#1KUeSD1iB5$dsbo_H6#F%gx%97teJ!=@x1W2*SGfTU{=z>$p9f{ z1dL(Z8*$auWrF#k$#Uo+Iw}?ek-6cCpb$!b^P=Nbo`c-uf-Swdwt1M2>-fLf7cc&j z>s_2JKOZ<H6Be^zzsi5L2VG=uTeRrTp_(FRo0xp|snO%Gnx8i13xVYBKW`f?+v*$@ zsK*b)T7KS;l>aneef>?nkx<%En|%Q2m5mpQ(BW{YBz)qX!|oOjD+`s>{%y7O7Vh48 zLmRBqz#9i(S{`M?nojPeqm6rG@jjks&v%0Hd!zAqffZIS>3hOxqwe^{Y5dv1*JsrG zpUi0vo(t7yoaZXPpN9+^(UfV)Oy8bf!Cf7-j0{&}F1lBxe6Zt^v$2<L%ekOMN_bT~ zcDqkxV>j*EcyAQ@jkAoU!zM}cxj3cjZjZaad$uvE7N2;k?4_Pm#brg+m+OI+Wmi74 zO~O}j0Q_EtzHDp?Fv4+x3tbT-f|8EvUFr*+)QB5=iFdA{^HhdqDCF?Na~R{9Sp+t0 zji=dH;twMq)((+J7L7*+AJG?0rf%QSPpIx<U3?Pq%}x9yWYo-9F<bIr-TPFG&@81` zBPH$Oee>7&Tyz=qzFnRoyX2!cZINwXSY%4`iJ#oG*q!qWKG#Y0!U)O(sjbO*$%$@n zLcYp6r<zBU+mjn!bB)D>ynSZ|?tN-edx3}nYoT7+U}1u{4gNmPIrq16*#MR24}@|5 zXX%UJWwaVOeSgeM;qLeK2R{W-;(7G@*v>@_@M^2PiOCV+{>dvwyDpVj6_GegDA0)w zj-J-|%m3ufyv`*oqp6fdbgV({;mg~px-*xE!lz>`S`9b%!Y)j2Ie!>?RnG-92K~KU z5VLXuJW2g;ZcTJM>c~X5*YIzAK625$*x}AZ%<WgTlMU{dI<8C280X1B+CxCyG!uqi zk`RKy!pXl${f{Nd`<j>-h>lUN*u_??+cH{KAj+mJ*d`jb2_%`plIn%l$}f#WqH_Kq z4{dW(GK7IJ8JC4e-Jm3>N_OFz#=9|{L-Q&L@gincwiiOTOx$4Yl!1O1Z%tFx#$^Lg zBBEwZww8tZgUH*_se3eOfG(7^++-Jm0>%RD2L7xb`PJb@N<Y^y-@@+4D{JL?3dY?@ z`t=7^kXi714eoX-qZ8c}gHdL7Hs4p)D+PM*E6Wc~DaS1*-1Ki{W(dVCi!lLV=wRo( zGpm9!i|i2+EGGbxB!jh-W8~)IU*d$a*Wj<S<!-O4*kIz!za_#FadFGZ*1zwt!HPZs zipA49!VutHGEa=H;>x3BF%jK0qQSawKQ7n+3D4-vD5}YRC||Gn@Ko6)ZMJBE(_tfV z02y>$fGu#DEsTO~WLCGXRmV`1m3hm5vLwyIlC)1TH1=Rp@G7-SNHw!$O&o{5J#_8? zgX2=}kaN-_qox@DJ1>Hu9w5NrF!62x6rn~U=s|~N?{0KSr?k*eP!?4NNqn*w4*;gl zSu>vo<#nM3BONiF&{Z<y8Z6PaTOvQOFTPU^+ANBjerz9zaV#IAs5O>KCov!Kd_OW0 z#X^QD^8KEJl5G}GGISnEIWQ<jPr`8tp1T5;7}jWNnJ*=wT7dnt1+Ssbsp>k(3RS_5 zY{^DtfkuB!zCUB3wjkdPe)#Ok3baWM40l!0SzRHq-GRT?VQgedGZ|uWn+cj<Vd`5# z?0bpN1WqbH<dctrC{YSkqCk?HU~w|b<N)1g_vu;CXgpOvjjEw2IAksx*VfR+WN3Yi zGAlN%vO=~0a<y{rW)7lsWf0}6B1W=*%$V**KdIauo4PWUr^1`qt~9Yy{Nt`NV*r2p zbxIKhUcdq~*}|pYFG_+JCOMfueE?6=3O0M&r<OZY&@aGM`W5*q=~?QLNR3qOvnnQk zUpV(81iW_+)f3x^p;j=Pqyx+N5h5V*U9c(vYVUn4L_o|Bz^4A_zCQ&qP%g&+#x>N? z3&=#)E-Wt?I;F>BJN9@wMKq$)OwxPe7@E$rEt=y<+N-fzkT;qRkd+ca09an;NY9eH zG18Uo!X}$v7+a)i%vC0P2tlbq9)It~^8~@C_qEGKcrCigc>M3g#l$Y{!>kyn)qJ_| z0MsmwER)`l^$ugxK`u-**DF1~MxpY1mI2lraED~EodA@Yd27HtIIt}C_&1Q^vR1k( z3uuB4zH+CvX&`3q3ESuK?C#2)y=2(EQ{<L3L6X%B2VCSxUD3-zTTK0aZBx~UQ!h8% z(qA?=Rve1_a!%ULw!L4^9X1(vwTb=WrqM}9b2Qv8z)h(mEWcEFU<hO(RL&z&oK!;5 zifk>u8Zm|c3)gqkxxxD?2HML+PM-jAqLMj{f}uh#FXC~gv{SQ>4#97<W5RwtJ@L%c zTzXR56p^$$9YZ$E)IQrEg?EVHKJ)k9`JfrrfU1&gX6&gXj^9a)zL`=VwP~~A_PM%y z{Q~?gnvH6+Kf~hBDYH5_$A<tNpMtD^n$}^D$B3>VKIIh0lc&z*azS5;J|PU*p*S94 z&Hg6KC2KRh+VG_ZYL9=z2EOBhJcX1mLMQw)Ph^S<98o~1Inebe@lt<v43ZWTR3ipU zia*2!JF=E)qvNQt^3pM2efv0aTjGexZjo^G*XK+!EUxo`BLrULJae^bh*Lqpv<l;@ zDr?R+5UOX3EawfIk+OOv5Hg<6=i7fk?T?2##{7kaL)kAf<3lFLPM&!blq?{JNV@zd z$^AWC%GKn79<()9N2%{L|9GrU5ni5C?3IvAmmc(CPIr91i#ENm@bNqc4=8#$;esPH z8u>;IoFoMZpV4ztZplmCs!0=8H^o3r{pXnisefGH4aFt^qqb`I&Ur@$ehl_*6}EJ$ zWyQ#ZS;&N=Uk+VsROL0<BllRmdYxFHd+(@5Byddjpvj<eQCH9^0ndwYx+!}%+<H$t zJ-oshq570buzN5?E{z%>gQ%Ym6Ej5TnZ1jS&7~1vIrSjt_9|0aox!Yn4B_6U80U%* z>6%6|W6YaS!3qqt=E*I0D(%)7o?@|fj#EE)s~wdRURxSbn`I~+>x6)>rPf*&lHa<V zTbhz_$ypNK)+wvu*?!DZwXlS7@8O(!9qR5?J*G<gI}>{9{GL8T;EL?N#%#ajnED-F zEjglUFyp%9-FR)2#z}JFZsJvr<=Wlmf3}7kT^+T|H!Ob}p*upc5G=<(SPxR#|DzCB zo;LavLv~looC>xk7pAdL)%{CTjx1MRMrTQvz4?>5!Yb*K_uzyKCzCi-EM<O|_L0lD zt<TlH1sbSY<es$o?Mw~Q*u7<<KFYVfX#qbwAynw~yVu~yXSXA0vb-2pVZnS~H@(ej z!SoW(i0@Qd6>A=clRb7`*0(l0&O7`SON3$NO?jPXdPvr7lzKUt$;@<sshF_<j~y7Y zli)VciSIf>H&vnLQ4q}oLI+AOqU_D!<|AgOuzC24)(9j-7kY<)XHF&;aI|y9NtUW5 zJ;LB{zZ1Kd6Jq5pk~?g-hOj^S;h8AsPxa}I0|uVv=YM?OWOlByn6YO|1-K6*oE{fF zj!VbzB{!7&7yN^rG<Uyy#CUG6SyUEQ6+cO48%t~znz%Lm;0h;PY~i%-I<nqsS-Njv zl23iKlb^~$eH2`B5;Yx<RJmaQz23<eH_{ZJ(WzgVC!1ma;}=+Y5}zKPb@kjle<RDR zJwsqAkZ)au>1;uK+_t&7e&v*3>2fV=?WiZBCl~edAw}do$t%?Bq2~<)n<1%fv@;qG z7ntz%=-EzQS*_1_$7DQ@=1Y2wT}z&*y+3!Km`Zf;udp--%yxv5kZCuL5nVXE)}xdO z)n<;Q5XZ%6=-5)_yqnJSd!tR|#qj4~s;u-UYhm(;>0?J_h48OW(j*MKYjCdKY55E5 z{~Q?~G^&`JX<SF5!R~`*(%$)Hasz|se5I;CPL#B(%VCXd$Hv-&$A^<;dwdOHf|&t` z=TcMg&Tg^%YxGgXmk{pHk=)~dlX8+nCNGAt*S{$33<R271OgZ%n}KnJ8YU}10|R2x zA&o$VQq%{9O*wstM{0zyj=yJI{%74mWEcJMeBswm2CzmeyQw98(f@eXW#2EWwKIhu ze&@%PI0WCP_qf@;Y@PJq<Ej2NtDECgMz=Z-FuvVqe&Gw}z8ChYY7S#r_HI9_c-R9z z@@kH$y?gr(e1Q5mIm+V6<*%hR7ehYdYWYn8C>rJlZZ?1lN>B5u)Wj(BPlxfxXUV@d zwF!PqS3lA&Ej7(jAK}zlCXr-onG8>XyPl;{ayKsZF`-+|>uD`U8T7=euO&09pUyZs zg>E8{qqg6EK6evVO~#-2SX1~VCxlzRblYR&+wj-1Qf9pLpJ2h8<?pW~TZS+o=ey1( z=DIZ3qg+nvA8IW+F{I`$b8h7R=l^#14lOQ=7NQsubd;DXdvam+t~$BNq-OkSQ*-UT zy;7=v!$gG9->ml|CpMSYOSQe@Fwf#maV<h&ai+*Pu5b42{neA%j#5Yoe8!a7@L{8r zvkh-eU2sNPj?7cvB%1)aqeS;73;Vm0KjWXcI0_={M4XK}w9F7TUxW11wEWWSG;DTT z$r^b_3Y8VVVC<(#s=}t@84X-e@bv@s(#_+NpR~a4ehl#Sq|Apu5UO0w_ZM<8YLj@7 zhR^cbDag6q@z|e&XQ3Tq!onwbdYEzN9~YDB5^pN4H5EEktPNFI1P}2K4=;^bPQcSU zuHX0WPyJ`RG}!Z46f0A7Wr;Unzv{<{$6p@dlLya2J4KTn&Lv&{A)+cJ!0G#|w1!pv zKONU(yx{pZ!x62z_a@9uE$W@f08|j;)3s>i@A%G4Zt*>4zDM{Hkp^LLjDmdsSg*E= z)4K_g*FIiodxtkiUctpI?yoyE2ietL?Ez67w@>WEpX>0KgrJ^@%Z7IR_h;`G-07d0 z)KQ5hKFy#zH{JQaxhG0@U7kig(fTNB!#?n{W$!mE;lE(#9oajPMV`;kQ{P?s7fPf8 zm@rJAE8q`eNRqLA@htkB+Y-vz60}r68SU(!LDYkM05XUfRs(8Wut2PK)e4%f7cz-~ zu2m9_%LkJpn~+{>fZPPsfR`=u<cfN3fLJh`yy9ka`Lxy~bfsFz;z%M3lM6`a(kU62 zAeR&Ez!sb&R=}~|iGy1Rk`bin;qfr?Ggy<XG~xYJL@{X2lKFr(1Msqi<ulud)7ma2 zkKYr1KbF_$$@W^|vUb>-0n34W^kVPJiqSIbR9*b1S@nqm9syy^i*tbgyQ7|qip8I1 znb&zlPFQ0)X@!s4HX`lZh(R-Oyz!#$Zm%cjJ(jDc$t!M!e%Lft=BVfJ8R5T8Y%+Go zCR>1I;V2iyH<Ayx^p#~f9n-}HzA(Ei#0vn9XZUg`D-cOj$uq+U8|h4AhxAGiOgLl^ z`&9JarC3wq2@q!1%nwA(lL>6|LwH>IxQdLNL#^LF53&6~j)(<OI1OhvkEagO%=`*6 zh+eZU+9vR;m01IE#KM5`T7Jo(?$Ot-x@Wx#s`3DLGji~~n;$d$xj0SivmpVR$nep& z_WV?J74b>c%W#Nyal>aYAsK(MgB-dH!eo;8ICD_I2c1DaQQ(LwfxIpO3S+y$l5050 z@21{5MTKB(A%<$>l}7AqhnH=LL15$n2ly*MK$hsLQ)ui4Uc51W-Pl-^Ie|5ir^tEJ z*tC)M9?Qt`Q56fTVL}OVEJH>X3hgzWUW$=F{N5_7YC3omwRG3UJ!j;H#l2Z%E(iid zr{VdmFN(j`18l4F?%eitD)6}YXEsl%r|+*ZxxjA&K@Dd+A^+Cw64&~@px!+&q2zkt z>$eXAbRg0$>w@q+!VRC>#+AU}*#Kfb7lhZU7~aYP)Wc^CFIA%lUt6jz_Ofsjy5CHh zJ)o-$iTmF096n*sFpNWc=X<i@d5yq8JWfLwd2;gzwypwT;`57T8nC2$ZLjSX-zYDP z9TOoDy6STs>kk7$h=z3*lNsjpnDzW`->gCd+c^hALmo(`RO!ZiPj>4&%Ht1<tmIS= z>(|lUa}VV>b*Mau{^X*ZbpDaCbeKCzBG^p*CI}b<*WR$ZO8}aPoa!UJV1#Id7FiLf z0R}8}5HpvnwV;MfT8=txi0+s|=|AC_Q4}v+uNR&$QXTppISX)1nPB5M95NXzk|L39 zayte1^O4}N{rP~CYWM~E<Jvibz9z)QhgjFO^Kj(7LZ}se(d@S|7jVECMrRSpcdy{O zvb$lCxN!Rkd{cWFnW3G13ieO&tmO9Qk)#*T_aXw}Hjh<`l4o_y%*g8HtXC*g%pS^= zCu6b}GZ+%7+6iOrG|up=4P?JZ7X|VrA$WBVU^n>++Cq(6)9~a2phReJ28;A@ruJ*s zfVdNuU9%xUu9Af+*0cIJML-s}&H^xd{ERO2*<zq5MjM-*Ca^hVy+gc{vVL0!==?14 ze(I$+we>Xi2e(d+%Ja<V@0GL$V-2|F;_~+UjQ^~%EV|34AbhXyFAYk?lyzZ_VNITu z;9ZK&$Cs&^QKGci49rztQ+KxTX4$eyjT=A#;rRaW7{K$9(lOgo&dm~dejKv=NZW=Q zfp+J;G1cHwf){XH<^Y_I%pe4wx+VxuHwEE5*-tCng__UxLbfWwqj^Rc>!w|a=s8~^ zn=O<ij}tG?hBAe|8PgZPVIXD6?yfm^87nW(?8KB7ZD?f>oOW*gBF<q?bV;50$E{N= zQzgy1S~(T#ms5{oNcc{VT9(9SwZ622T&b`#*PNvLj3vsj;&f)2=DF%FmU13z%KI9z zN-gU=hF+*iS=3kpr0haytW1U{S7kn6YR1o|IzVe`U<aVcap~p$_!L{r+zmc07%mP) z?n^YR<r5fVLL_rA?4H!5Q;vO!vpFcAP3$0HR|aXuNK2)DgCv?mH3LR{6%#)%8hT#K z`l%9ek>mPNO~0&MMyJA4N_K6^(M+uEDsO^@=#LsAR}^8slUM7n7ln9k%uey%es+yU zZIHl+muX8g8Z~2P)@`)Y8_O@OdixgTPJWuB!AWOWGV_L<r)>;<ad9cmBx3uAF&eX> z&gqJ&6Fc}pE!yYgOFb6WI>A#3!S)z^EV5d<8P4opX0^*8R;_+7aSU5c-WD7YxSFV8 zwA+TIT44?0r;t1bpK5>_Nl`%r5DU-6T;O565t?leb#&_F@=UvM^;5<~4jQ;7H>YiF zF%@05Ur8xsO1Ttr^}R(5x8(-(jLisgKS<QjyCO-Bc_S2qIiApUM+9jaQwn$OFrHT! z_D3d>Xa#@6N2(I0oDX2YJ-Cmfwo9S`q$U0OAqxjD6@+kl-$Lt6!rVbK_}j_#2P8w7 z&qz4}YnUh_!IJ+e04la|O=E`>*9(CKyKo%7D2LBrAF28G&Fq^HygIc++J)0D=oY<< zZ>8b|1A;uq3SkeOE$TF6l3nCZ+9l0a4;wmGeVCP^J6jtBerhI0({4Y1DRK3*d^mHY zA~Sw>O57q6>L8r;u(rDL%2__ss}J0>#pc#ddMqUv{8NeJTCVhk$k0)*A8km7(xUT! z8wuv%GO7(%iyRa0W<AO}+c0mBN!E6Ho%0GwykOEC?%6;VcXx+B8`aQf<*L6HbW}81 zBGHktxF=~}-^uqq*<3N68Ej@{X#X>Q+8d`(he|7OnkL<)558mzczm0df&|(pxd@4e zHY`62rKTrbO$>~(y?97<0Qpl6d)A=eG~pR8pQeAH^7-Z=3;Z9-l=JzGtYY`J3HwgE znceGF)1d?&duCF}uRD(o)PB4cYk{_;jT<M3M0e?67uH2?deR9`l_4*zfr6Zc!iU3y z=Wrv*T4s_xL0J~Gfh>YiF&C6=Y1ie=#JkI0u8{KT!EZv#!xqy80RLj{DaBs{jh~EZ zz3ya|0Em!{k&S*-WuTTx@mBAGZXR^d-kIyS)iDAaZ7K}>*-g-=PtppGw#gXh5G(VZ zU4~5lqv8*2fJ9>k6fs1T_`}CIn{`7PNO_AJjUF+Z49}`)bbtBr*=to<%O|E+o3t=@ z&6cuekP^NoUta%cUA^z{H9Jz~i|y*2FtLK&=c~MijK#|Nbl<jNAG3V9xbs8-$4JJK z8Tmw0X6D&ew&!PFHJ=f*s=U1mgM4nLLK%R*Kr!JMnT#@T*YL1z5WLe?Agc#9ypbzd z3Bm^(&QyXP>5#H6k+AYc2Ar{s2&2=e*q?vru2>~d)LA+u#(xJO#XW`UUdA5kkp6WI zOR-u9i=@5tHA{A}TW-s*@f7**fKz9evs>D%`u(#$hC4|R<E74WMA9L}6)Y0==+G6{ zpiQCs^9!>`h=vQNV4JXEQ^H4%Y*w%3>0CZE$KWo^1DeJp%nev_kl<dqg&HLDU_)M8 z^HT*7VZD9?*WliJ64RrU+j>we@}w1Hrd2r~wGq3p=g`Fg0o@Yd(H&&GKh7Rv!CmD8 z^G-Fel8e7q2Oh`kq<9K`J1^sL?$TU2(Bmp><VwU)z%9mub7gW>Z-u^=bz}RD)gfEH z>4cgk0&h8y!pxDGW;<7K_0`hNbunO%MIUl<TF0ZoeU&Uy+V$#e<s#+>h1-h5tvP>{ zv{xR^`O5pTY04g(NWW{Yx;SIrxo3M-QHtY<-sH+8>FA&BisTi$wKo2BGqhk~yy>@h z7u-u2*eSCbJD*K~QPd!%cSYUl=>TTNY|cnwaL7&CIVhOpWY#(EXmQ}cP>{AJ;5czw zH+EE{oVZQmaS&wJ6$Xxd!R2$eVS}eECBqt)9Y8~T4d9mm;bt-Ird3>%=}D^`lp!Vc z{12RA!{W}iaFC_*pLK+Mqn$Ou_-He)x8}{CGS8(60qGylSX>f~jYKY9^9hLaG5hu| zixPh%j}F^}rXS=jzJw6LRLiBrpqWY{*}@t=Xg&7y%%P7K8e-diM=5piBQ(~oMG&V+ zdqH^rY)0&*J`SK%!PQCi02SwoGxrAxbS@u}i`;G$84BfqZh6F20PN9=(}WF(Oa>IC z%Dm8DCHivEeabb?s>0)()8+Bv8v?LClBZiWFRP=O*SQmqW2e@0*Hv#7o#`5`)L;`X zf%s|0itHO(ExojAUp<CL0^qR$w>Si8-bxd+Eo>FGN6J2Y+P<;k!A%Os9E*XoWXPLX zi59pO$4IpgDCcG$ADM0-d;Z}{0jnxpl;aLT8xIifzIOOPuuL}We=mPg%7ZKR*W+>v zbKdt*hyt3afGc9ixCd>QD=S(L72JJt!0BB$EDcKlM4$S#7ACk5Z~kU11}|B_A>cr% zw05@tq+ahFT*%F!BX5n&3cxjffsRHt4Q;t%=`9=CeH-Wlzt|}$Yv=4ZE{GGDD!~Q~ z-S@M;;UC6zVas7m5IHeDL&0+)3>#|5VsL{h+lYSmXCDg<z3@g${*h65_6e_lB9=a2 z3URrdkveN~h4;*@!W#`UY>x%9_$?)>jJ*r7CX%D6w!=ADTk*db-s`66{sOm$eIloP zN)|oC|K9cI8my|8`S|yZR<%?`&hw&&Qc*ho!RT10x4=a-!~h!W=;zi)nCFj@6v%Mv z0uj)i1j(8OLBd$cdr0&_-%n_4nY1IVYuIf(vl<?o+HPZ1LOOJp@@hr<y&tTBf9&N5 zAUcTsCm(QEuq;bze64o)$bZqPQPXaniQZ^Ve%N5<!)ur4x^Yu6#V9h+I>L{*xc;+w zxS%eRkYXYZ_2)uMvL=ZK5ge-|-l=Gi?78Z8KNC98gC*x`I=D#sEyiW=4+yaZL5Ds! zeIx#`evh^U0_J_wMQ*oqkTMN9KwGZ0#v?{_{fhquYrQvjZ`~zSme&7G?|YxDsOoNc zFF$(h=?Xd68Y6SpP;6MrJB-7`Pa1vSmG?qoF!q-ddz(TfU;U*^8`WHc;4${`z=|`< z;MOsot!qQ&BQjR*a#q0SVpX1(T#z{Wrz`p|RTBN3vlawn`w%Grk6yoUClX<s8dwsm zZ(Fy2?J0qbFCVo%3jg^0iBM3`ru6N23*v}ZjcUBC?~;OXC8<UB?XAKFr^FP;U?NG( z`=8`_F%#qFWS=mWRrGR`7-q~bAzyRwKdyNO^W*0GdSa!osJi)wtO^~!r^V;&iTR3F zy;P1tNQvJV0m=$c`|wFTFRE!M0T53Ly|R^EdDNu4z)QRm$#f6YloAU6ydY0Qh8@1_ z^K<&XCHYoH1e7?n*S^IY?IYkM5#3|FGRkh2HY}KRmr(^f;7UA53&mRbfeM4IH#bEz zAuYNj1>toxv|oA%`W^#N|dp)53GEp=QsZ{=F}Rxfmu`If&2~?OD%|q9IND1f_>~ z=BS8=eMgtfl`o?a`)8KTD7!srpTYg_%ezc-qmth=eooVl{how3d0+0ekK=o|dno#i zO(!v+H@Q|Qfh$3YJ3W}#j=cpI(b$hi-TxvY(@bDOQGw$LVOINQfv)YtyrJb)op$`6 zp6X-zzD$sS4-h^oAovt1(9kd2O+{}facA@iD}#6(z>s$oX)Y2k_aMff)7V*AmM$jB zt`zh3QcHD%%_SN2{jaMb<jj^~60U_qctr~3t)v*vd0Hl*K-TzXu$HN6(^C3n>ES$A zRX`*((m$Li(X3GA6`B%GroU2omSDG4#P)Ew1Rbl-+xO)Pa~GBQ0z^fnP?1r6yp+Bp ze*ZpkZ5paF8?84oO$Or$yRROq0P<r=!)|5HVS~exVnM2?X|+`M@4Y{oi4kPAa+ucD z`)jpL6fj`CkK=ezS8Z5p7TEAs11n+j?LchDyXoHFLDvY#)a|VgYfBG^>L-SCpg(^Y zYbjoSl$t5+T2BzUbLK;=uIgJo*J;8w%alwpVO$(g--|J#H8ucz<UNObblH@zJOX`) zFc4na)R80m^S*JyvA=C{!HLC0!Ah-{|BK{>G(W}oUo8p>?eWGmr^V;@<UYqQd)(Ik za8J&V%OBa+z4yMhLG4ts(&|3rat5MP!uZ%+4*u}r$$Y!$8-IgR(gVQcbWrM%%p*30 zZF3c~g1`Yq7n7(nu@|{WZJvEoSDFcfSI`<XbP5$UcjXLAueij^6Wt(|WZL!IzUv&3 z))~+Dr5_M6kzb_7ccl3%?lr9ai(43F?=MNd!5s7EYRM1YXG>MX9sT4uou*p2VqE4E zc$UrLUk&#i#A2^z<%H(N51SUxOsvk`b!1`ZslR¨_6ql^5~T{-W2nzR4F-nZc@} zhD>e1VWAB*SYXvbFzrjR0G%NUO4fk+Tlw~)R%O*W5i6Jk%1QGM<GBrzT#uIgP{&s` z_ekl+`|v@bS+7e1KWb&9>Rs=1Jl!(p=L$xaymc*m`%OXDZF2o$uz%J5(W3iD?_JY7 zpP)8F`@+VZvGxa+x{c-UNn$&fiF*=;$ImeDv?!&n{nd4GF0r)6bQDJ?O(g+nk&DUi zNK<u89)e-j(@7czBq?ud4#ndIE@ZGo5K0EmxbMC$8S+Ae#`JXr?d5mKv#5<k{+-kM zj!Ov%;LQzc-%rzdH-GUi>v8lcG<Q4Nx?*Kre<KyEQD2J=>d;x#V~>bU4t};@WYbxE zYA1{PK2gHinv8c@w<8W-GLcUDn-oRN=ZN%W#%K;sw!|82C+yG)@>d4yGD0Q`+rH*Z z>%ds?<o^3Nbb~Nz6Yrlzv};+M7Le~!w?q_m_FlHPamcAZS+~4*By(@8iJNr)sdEzx zd-BJ77eWhptGE2`bY+qJ-quJw_zvyTHtB5YR_k7AH92^bQ+m-}yuE`h^up5v_r~On z!Hw0%k4P^&G=8k|RP@^bckV%S=cC(a+=R%zotm-#bRjw~;b@UK-b$J+p+B9NB#hJy ziuj@VFg{U&qe4_qtZQ%lzE!A%60+lSrP(zFRlCJ=$fV}oVf!o_8yG%7Z&|RGd@8s= zsiM(n!z@Z5=E<+1jvL>`eicoR-f;VK@ht2)%hOB+FpX>QaQI_WzGT@n<Yml`*^GCE zlD@=0mTM?dhgSivZmqg9mcKGhR=bZszt5pJL9qAJ=|byQ4kwSgQ={V_Whu^JCr+;P z+s6c*IvjX<lP9b0R;lY-x9-0`;#YhVmO^jbX6U5qbKUqRyZCSOzGnQL`ojku-GpAf zV(v>HMor|%2KS3eRa}E)-9hH{e~2m$e#<`I1`4MPjtexHCaeMQZc|C6Pw0Pk{(2M3 zm??DD7|UQ)6u_Ip+8jLJUpZ1BH`>dq{ylySp%Ok7TxpL?FQMPkoXv4)vbRd9iU9k^ zWjZMU?SWh1CIsO=y*K_xu<lpqK40O29}&hALO`HC$bW6DO}I00rT^w<oe+1c@b&R_ ztJ}}r-McQmn{~K))}!y?#a~`N^*k5P0|B56NkpTY*U;M|WmRjvOgF=e*^l|hlX45y zChpw1;<w+m(Ne=&IxDZBoo55oK(3?pY^A8W=jVC#rXQ^5B|1w5%5SdY&H#EiA=0MJ z`M&Fbz!mAGSuJA)pj+9tDk)nq8(4zcmahkm_h^CE8_dSGU(j0tsN|TV3_x+WNiP{Y zd%5qPZktQJytaHwuZ+drFlhZp0x;+L>Hh1$LWI#}pi@p1Sb8{VSS%Z%+}930L{f)H z@*~ZuEm`CBJhk(I5BN_7u~F+Zg;HC4RzI25xY`B1zgy~DU(369;0nns^y&B3)IC=> znp!y4E8X$7DZjj0GEW-HSP7Y{f&I5X4@G^T%pFNHa1rHbK=$tRDnijXsuKMc&>rAW z>n9j-h>t|YaB6Kx`)j5gFl(8H5f5c}9z?xiX#AMH{H0#_<8(m5AIJhXl}F{bQcDk1 zM0ucB(<`H%b0JAt@v-6{Vt~VA$aLnl0V}%-%7o)md5CVVy!|t$nYuF*=W;F$r&<qe z&Xq9g;vS14!g);_Rk1e8l2__3S}y__Jb--EGz=z>FT}>H$Q*d#;{0TxY>85`)8i$R zMI#(C%-z-Gtm6qdxMX}2Hc8zzs{#`QVx^FK(4S$C&jiuiAG<Eq!(_~g%V(wpJYz3a z)VCIzP8W90J1UdAwwf@l<a3{1amWN832yX}HxPqErma7kM@)BQryCkvR31=@1^3k^ z;pNT4g&PAStBJv=I;JSLWMrj8wSZq77ql8vFZGj^S+&q|FL9xy5PEizJ|g;n_GWv& zhDXJhx#DrHN^Ub*p;x*hMZHxnh67tdUggwjlFXMg^5FZXVX8953V39!*7qc;{@bc6 z^=_2urCS;ZHsuO07DePs>LHr4E^?wiWO|e`TK+Zs5>zWoR4gp`Q!aEdf2vR@zBVyh z@SmI?$n<lR|9|R3@>WfX3={yLk1i+RzddB;DMyEkhdg1`T1ur*XkcP8m>Q?@ajA^G zaq>_Mh(L_>C+dR!TREjQ-h1@#MG3Fgc|77WQWmq(nQ9sm?pIsnK;c(?{xwd8=a>7Y zw6<*CO<$#|>sIyS;SXo93^_=kB}B_h?scksWOl*Z?RIo4<!z&XE*O{sCLb-mLMHT! zm$WFO5$m2l*W6WJe3!CgeEcyO&Dtk6Cxz2&`5Z523Oxw~610FCroO<hDe@$Hi~vBf z0BS}GHmX?PGJ_DF$bLj81|r+thcHI62v03*41y?T0$*cR0di#_6e-?V`({Auc;7~_ zic#~y7;EqIS?WwWN<gU2B<XzTU%nBEGd}DuRMj3xNQ<-uK7(~-8u2wY#kDU8?1bY7 z-ewNRYmIvv77ibscn_jpGuj@-rFAN%IDfIR5D`AV`~i}}<P=vIn10D$E&^y*u*g#S zPK5Tx?9WfQiT2$I>2HEaF55sop)o5`bOqp0COvAm$_3&tRtKWkb`>!y>@JU_60D<y zU0j><yG9b#v*glwT^gb056oSsvI`d1jkHz`A=jqlah16eUExOdC0TKb5w?bfePiaM zVez(!zAgUqw`UF}9Si47#o^@|-+$490P+R&6F+Nw2<evC3e-472j#;bi#ZP=u+Q~z z->~%2*<x%MGb(se=PaOh2Tn^<(hy<kKBzHtKzNM8ra4mfU-&MMn5P}GaVP@$c##2k z*dq;(3VDI;01Jg*Is?!Cs%7%NWjMppV`Tnn1vLw4B5YyO`c_l+f1K~Vf76YQYRHj- zzP3$)=mB$4mP+wd-+1ITy;plf#phLcPhNOf`R^hr_)Q<<5MaiA3?9t4>dbN>5x4<~ zyO`ex?D~1InU%f4d^@BOv_={Ai?)JTaR8qHCOg!dRydqHV{|@J^skh(k#D*Wy0YkG zcIaA`6iNg<Qy$7a%3vtn_#r}hvTDZQ=kLK^4~1Hc+|J~y%*ng94G*~c^1}YQ+DZLk z|Fkj};r&7BgGGjW1wX=s)fTS<`%EgoYce+;fxG)25#-^PacwBFowZBKn8akczRPkX z{;-Xmlf=}NyCn%T5}={l$#JhWQGjRIfS{`#n@Z<0s|{vOR9z2cAi)6uDd*z4R)vO9 z-x4^ML^!+pRW5V~o{hfv401huGI89p?CUEg(Np7{Vo;N+z~?VMaaGyC`N-Z&v%yml z<;!%!=Y-Qf&Q`iAD~Z8B<;-+H7>@_!wOBz0u{(WS%Kh}1MWTnmM|R#K7OG(D5X>Q? z8Qo5e6Mj7yIymxFm(iSdrDhdnM<I%IMzYTj#*;VXAlV>-0{dTyF+rjGI1r{#_Qd*_ zh6_qUCF}j!iPz6$rjI?&1~b+F=Eo6l9k-(;T^2ySYR1_~)c1N*g_Bpri;rHZ8HbxC zwR=h6slgwOy|%Ip<xoIeqgf7+!Fm9~yyS7&GuBm(`)|`bS>WYFer#R#vSlUQ&i`{6 z9;}T$7BMPDWKU>+Wxd)NgZ9f95JF>Xw)r6_YDlcaOezZd{+mf$5yKr{&0_|-AOF<o zjfW0A*wc+I5~tQqfyM^^+?N=ixaC+U3pJYj<@or{_kvsMV}b(hcIuZDcTH){FS4YX zl<t{!S&wse&`tYi0bq|rk+r|VpCb2$g&KGkF+?Ys;8TX7tmC`f*C8T6=rjunP_7mp z5d}=4ulrQOztHt+B?2kpE34XUnv0-suU+C!^)|&zoa}lV@I(9va6UelzLx0LcfY2f zdkR(IATJZq2+O_V^}b|W@q=)eQnaW;-cKpF`Dgsm9~nKF7C47;*PYSl;NR~q=;|+Y z{_&rAbd#bh$13A|)zv+y<w|kUb#cmt0CCywUy&zM8qP16&dvVI{nDqu+n@R95kP3_ z_}Yb$Z`ykomyO-YrSYUw=qFY=VOn}WIV&-+l3vb5is&L1p^fDd08t5we<nHoI5rpT zLi3#NE4g!v?-T8xBUIsA8d+&QWD|u*CBKdGO>Gh(mRmjo=d(}D)lJG}T5nZb=iRz{ z$sq*SuDAy*FD?eS*2JNZp3w(TAk7Dt7fXpvJU8xj?#<Ea6bD#8&zo5}Iu%G^FAPkI z#vu$ikB@{r`IKY-zHN@mxsQPjF2gDb+!z}nCmLGXa}7sB9#Wz;?|&bwh;R)N&%qf) zrv7k!v7y@39k$c$XT$mg{PVY0lWEvy^oyV6oXT0Bk;(T?hc~jOhpGiCvb{_B#b%i& zJ878zKA|;ju?N>m4MPD|mpX@`U!~KRImJU_K5q}p7sADL3BQ$BMP(I;?M-bd$>)A= zpd1Y0-PM{LA5NuV*ejR0cL=C<8d`COV;10vO6=d6yr;Q3DsaYSuL(mA4T$`#z7yjd z*eFO(Wt}Lu7kEY-#wnniQ68*Dih~aF5aQO+SB-Te2*Rfa4T0cM0OQLBRpGR@>|9;H z|FZmZg6$6}ung}w|5C-CtMOX_&qwewP(A)|>EhwRYTE|u4&;R;qk?VZ3_ZI1<fMsY z84=$Zc4~}?&Zokbs80hc%${SoYN#ApRE~q*R|1BponBD}jc1375-LOS(`Ls9iUlsP z3!lO7?e3lPejQk@*6GD^h3?~kgggl@6S<UKqCo7Ol5?vjnleP?>J-?%mOgLBcXH-g zuJNSP6}51<1>)G7@=uyZRljkX$33ki`RnaO<!WHZsG-&p4Y+a);Xb#+SBHS!Bx4RB zZ+Uq#RF`Xl<DeQHOF5EV;pjdZ=G<g**I;1X6z)BM`$jnTZwf~Vfp234rCp|1Q>FA3 zxpzR<?^Y>Q_1O@Bv1oziG*?d_ddp2eyS&^C5o}f(nNp&#DdgCT%6*k%q{_+1^$MtN z6oLg-Sr((Rg;z!&N%gbqa0?^ipqW16knF^eI*hr|Edwj@^0m7RaaA{Y$)Hs+DJ#hj z#)E@37<qeq%kqhL*=+#8F-V1r^+Clz=#eJO2$D0Wm#u_=#Bg(iX`Ce#bk;KWx+kBL zq0lUWM;F8cH{vmOP;U70Ts@#SdR4aGUQ}58vB40b$4<WByJ5I`xgLacuEJg$dAZ@6 z9RIg7*;QBTo^QdA`k$8=OA7=Cwq~+F<pGKkzW)pU9=N)#OxK^l8K`&}+%$g|vC3x6 z(NPrp1rFW?e=&!KYPrj){a_W}hFCk$(5t;gJ4~)E3_KXaQTUZ>AA`gwa)8T@NnT-X zL(&?P$9+u`MCEP2R1yV|HAzoa_L9BrB~#a;0GMmf+sXYg$}(90Np8Yhl1+ribgrv6 z4X>DBN93Q^M{4%lBUUH!Yk%E(8lN+BDzjf&x!<g+!9)tTC(&lELa*|-!UGTfD)$%7 zgz&$Q(B-(Vq|1b2QssQ;tn2AX>y6OK>buHb@D?V#j)GgC(Uih*R2uTN1L*xK;ODW7 zjN#5dx};Hz;tF2o{zpJTXeeEfaF(a2lP8y6AH`AD?pl~IjKSv&VqcRr;bJICN=8L^ z(Q3e#Cs97*U<?rgsroKg#N%jx1-FOVWb&ZT5768*oMa@g^2?m{HZyzl;6(YCvot=X zrwZnXe&>6wm@K|YHmrUSow8FSwOQE}-S5^@4wdca=cJnhjrfcNx1iO#nns9}UN$JN z`P3^3S0g?rEDVI<+Mt9@F^?A@B!q_4HS{mTuLBezYfnmQ*0sq2UN7wJe0Dyl>E5{k zFG`~?-QGCS9uxFp+>T$|Dc9!}Zu6W5+AuFdwL(GO0voU!pYP@OXnHRK+qZKRjw?Nb zUmtY_Q9P;q`V)10=WX$W!}?d~t}5jLG7m7)%VtYTqCxaXl!7=wfX9Af-HAKi^c`lc zpsJ}nTLiAWpPVC1jZXk~V=^}z4GAyj)=o#Ih4WjNiOn8kF=f2u6^=?Kl3W&{|4i{Z z_{VQA+89b)T@%Tg#KL_RkCP@Gn1^TIa}a(_AE(c2(&gVY%bk$r!Q<vAgB6_$ejPkf zbzHwA`z~L>p4j~u(Bd!7^bN&(37>rRpQe%iM+#SxCG62Yp*T>y5(-39+51iZNmDF- z@Bopvh47vHz}4EyWmaPfyuUZ4b5%2Bjce`)2ioxXjWn10J+8f@<q@P`Gy;cixveu8 z@<<QM^QKR9b(y;a;7Y;p>8-5WHQL1(dDXNi@K4DvpSX3&dOx;RK^OlsjT0S{R`&0< z+<Lx}qFMMadg{y04X?rQ^SpT>BUkIv@*?{(^smyf_!F|u_-a2}wnRDkaPj>b{KFij z_>QZz3I$ytymAsYfpga|f?4(=k}N{A+NA>5IOYJfcAxbxNsg4TL{vPo<~3IZ`?hi! zkGUu3vY}8nLGaj9T$kx~j!1Fa@x!+(l=P>(9hc1y@lL$V+`7#q)qFr^J|1gOG960O zN-%urVu-ZW{hn`pYEs^L|K=a(UwPcJ8{e)%e+hHD(0PuoWtQ&IpMbN1=%a@WsSL|% zP1Rg8y!$kpxC4{rTYt6|SjWiH>eGEIExJ~O?5#KDX(JiAGJVh{S#HdWk?O0_us*K) z4m=SB?5AnG@t5Gnp8WY2Y@=dLB5+C`Y2l_@;r@!ZtRQzM3JQnlPA%6i?_Zra^(~8i zn09*9F-n)t7FAev4LA8qZdUO5rns4Cryo`z^W(43n_d@KV`h<9@xJux9{P2*h=8ux zGGQTc3RUdiXSu@TtZkE0)PN*+Xud1>`ra~13|quuXmkJ5x2eFl`D@bmTQRCMUXmf_ zjRLeah|igZcNcQ?$4b-t<qO%&3IxT2g%)(B>~9@aHE(L2)#Z2E(N25f64N7C<l^Wg zHQMvW$cd#n{QAAu=MoM4BBR!?mGJ4*pVwtac(I@N_P<hY)^z6c8#=+e1GDNI2crH} zU$wlxYDVcz_6Hh=HUqJRa$6AbnH_;ODncj+hAw;id;T`kbF};}s!>W9MCCJB;koe( zWsT)0WA{YPm{fi{%UQskS(PGaYK&}2pPnaS0#q?9t*<R=Z?>k5(oBwL6#B2-v0Z3g zpr<{>QPT_C9NVS#^W_*rcIv_|Liu%w)w+Tiv)V6?hn6najr3ny<EJofWWk`WS^2{K zjuIpwy{w6L#qX!Ni9f&z=(@iZGQ3MX<#*KFxpt3ZfQdH7lGb{;o$T>Qkj#Jk<Uf`f zdra7RZ}YoHqWlZ|&V9VNJN#a>J=r^8VY?sx>*0$(Z^l@$BwE?~rF#eA`apBa*4O)O zhkRgiFRnFa?dV~=ZL)pV!_&_A)jq5fH_5~cNJG4Z@hN}GJ25kG&wn}taPXz|i{i_d zk9R-AeXQaod3qCGI_5EdZv?h0_UBLD$FvhTW*LZHz{9Ov64Pq7iQ!ts2uiP@q&+zs zPjIuXM5C}FnJp;GoT|nR9-tRW!os$hdgPVIRb?DL$K|Jl5-*xG=7XX*I}l#xC)2c5 z;#F#ZdhjnJGZ2@0FFUmhT>JT`sE8*q&4k}iw!7bPq5pccG3=&&#Oj!Gm6NE%%Uaix z&vv+~;7`u23QXti$^_^i`e6jUtsOI?g44bwn^M99>^@f{0mompt4iR%(3~I*D`+>N z&9521P8~U9a-OB}97EBa#@~O}%nD&S^gy<%D?B2G@Q@YQAZB6UHeWkd5N*gG)))GU zXtLFCHM}oF#mfv|uI|53pmpcLY2(yi6-qP7<zrwmzT5w;eCq%8_}#TQr55llo#6@C zxxr9jdeEx=9I>&eN~y^PKWuGrrQbhW<Zk=W=eqR<E%5rqPjU_oY_8)|QaB6cTLcd| zL<=ER^$kZa;ncaSE?<tQ+_M1b!UOJOGs6GYaoZAgtZ&Ctpo)F>IIeT|Q{nOR9RnTw zv1KAoAhcy4|6#lS_>B}Z5&m8ZcamXvNaa?S(c7<EHx1kHaFl$8>$45f{)J=+%{9jV zOitJt1#doahxM_k&K735(niIpN0+w-Jn$ryz`ArL3H_$7{^*o;sejd<yPqx_ZGSDT zV9CQ^_d%FLkbr5}vH|e7JwkdUjFKJC@&FjYp;AuB`t(p$Se7k`n!)g?GL~hoVvU>Y z_sSu#mxZPPQl?Ns!XaO|RMi*E{5X9QDAmiv`PNYyUB1nBjru0@QJve_j9>X$oH$`? zLjonch6#|4fTvI~H~#&g2lt=%+<H}=iqUFA_QeT9xd?B&!oJsu-tG8uj=pxVHT3Cc zkQV*QtMKax>cth>^BR2v&B%GeePjY?VX^*uqsPOD_rJ}9DDuEPG47f5*Xd%6%L4Ht zn<(I^YFM+Sty`sO22BfYr~Lhk7(feyfhZuB-V~ZX0FeQoEgz(x54+q@>_-vO34h4l zKt$S%YA~|QDhAE$D~ysvGFNbZFYuNHde^|pdqK89+c<7QHXq}SkZt2|NLFZH1|#@h z9F`5MR)8iEKrcs(pt6UjCfNm$UrX`jEUpqFUgR9icTEIMS|tOqENh9;to#D0=jWru zkJ9Q;v#*oFs<bmSGC&x?^lO(k1pUk3+j$yR@#P2^)~L6hBsOqLz}#;UNOr-uR-7{U zU-PY#3{7jQjM$5L{jAt!o0dg@Q@eyobXWk0%6~o>WNhe{zmgdRbYtUqug9t%<FX)X zg4hix&h%tZ&7SG?!b22;&ne?8o6IS`ne)U4<91{CcNFnd_3F8BR|P)Jxgh}uZLp={ zBloEJvqJo&0#_*`-U1Di4as${u(l{?ViYXiCr$HPO+{MzuLDQzS=_!rMx0rmlcALA z05Y*IfX(v4;~V^i*~l|ylQ}GoFoF!kBT<r+y!XS`5PRjr%Zqa;lAj?N2$MQ845)hr z(usRq0d|kN6&FW}4zbOM6a{6lnRrWk5>H?X984<Gz`Y5hH<iIJWN*tFjp2PnE|Ksh z{!@OB1BX<f;Ts0C$7M&gwUZTrO}jejuwIm<LjQ8hykcD38Gc|q!%e~!!e=2tnuT5~ zcULor6xZSSsquMk5;yuf?HVf^S4!wY+eO1guJyLevoU{iUt#u#R<cMe%j?+ye}oY6 z+mwZpjCMzXuXx}UoeZ&!%#QmaEL~soOE^Uj9XVNR2`^6H{7n2E4vY|pVE_Ok^q26c zUn&3&VZd-(^9mcE7ddlKG-MG3m<4`)nIQFz!*ukdL#GiNU#)u9=+Q*V36c`=ZW;ZV z&L|mYX%9HCYN!s3w+I5{X=i@5)%dx4=iKmjZl|k)m$x6JXWl#g508#~O_+Pb@BQ$S zRvWp(nFGd8eDk5Fu_lhl-!gfD4Xs@p7RR6PC#jn)T)*g^u~K8fVpKdkp!^kz_<v=o zhL|C$41xX8W}KfQfCQQ_Y(OUs;qkP8i+9~dV2u$qgNZ#6wsL%1x3nwdTSDhBLd7@_ z2rXkdt@ZlZY%l{-l_nWmDucX7i6;V`LCN6_{k#KIcuZY+^10Sb%;R#@A2zSHZfp~l zwN)4pu-Ce%LQ))0vTZ+jeY*uUrKI}%q+t`E<`B}yW%uaRaqo+vc!hJ_tlbnzT6Pq$ z@(I9Xc#|yQ;Vu2+8*=B7`P)5N)tJsk%tUkQ|0p`|zohy;j2{#b6%9Ae5OMFBnHDH2 zt`b+y!j&U6ca8=iBDlhlxx<+&(;TT;xy3!wGDoRd*}S!^Y}~hx&mVApIIq|Dd!6$c z*Zac#_2cK$P=@LQvPZ}}()7a_54b`W!8;&CW#Qo7j)ST;#w;Z+wp|JmjMkwr4P(v4 z?`%_r<qrF}`J1+x-!^-J7Tf}yCRWE7H85@!@NPjzR?I;b%oXH)5&|vYzZTCT2?&TF zm~z?M&H`00(e17tK{Z%G-wx!+fuK1t_2)DBsIy1KhIDf#rGet8g5%<}+o=?G>U^M0 z|8PU3liuOB3~`#i+I0991o;JXJrOQ!%u8J0`9oy{mO@Sg?oX!z>LlVcz(8x0$bok) z01>@_;}>r${0tq)@q3%^sDzPI<<WDtV%$HHu>>{xu#s)Yye}&29YS<$?N_aNE7Hl} zQAX`%?KoJLcj`c;b4MWOV{1|9R9H8*XD*Wqbxp-w*xYNc6G+brhlJE&Krv4SNOqMe z)k0QLqRn)~4_yiL`yQxuRr~Tql(r(lUK)Lzy5NgZ1Osm)i*@OYkcMO@{_-R~AwKsi z<J4B3ZI&80b+0duz;L%HH9=(P4mBh)1#CW$%AX^u5k3$y219{4<ol(6We?Syo@1V2 z`$f4(5!9cZV0p+8kgpDtu;{I*N@AdRKO#kW5=VDo&sYe&U$K@y*qoueD_jff_DW}U zSTDA7uK#de2~bXck-n*YBYtq_!QPLi<j@PKcfy~8d45)_$Tru=*tdFif&t=(nnST- zye&w4C?&GRUuq$b&-Y?UiC#u&ut%Bghwc3J7L=KWy&6wt87>447@S*3D79hXCi795 zJ414HkucSAf9Wy*Bbb(5-f#ECfZE8$qzrL>w*&>rT87nrogT}pdVtS=-$FMU;@-NQ zmmTS0MLFQjnL5|rf2~yquk}acvCePSt*NFLI{bZBA5z)KYm@BJMFeo(%HrLL=Rt)A z#?YI_;&oPr$K|8VoJtE&6`^1SH-0is6hl+=e`{SH=5@fV*@+toC-6{7N47+35uLpo z*!+fqHE>=`M~dC$V0+g4bObuxaY#Osl&Zi%i!^x*DzD>)T_e$wOqOL)_%74E>48|S zir8zv-7II!rgSJ~St}ZpS^cXL`E`i6C|pNW2>;wC;o6e^d;3<P;(aY9rRltk=6gBI z<<@_zCcM>bXCIS#yzt9A{vQe@9dG|*UL_Y*&qKwzv|V02FBF7}AMo?Mo;v=p)+l#= zZ(Pb$xuDB+YB1ZBbyhHd_Xu+h&%S%>%dAmnMzPlP?U0Lj6c><97|<SAr=Mx56)i(t zR&|uWk%XlR=M$jHEtF?x`Zhn?AO@ta$iq+X9BfKAksKk0;C241#(k+FBYJfkaER0E zKD>ET1uxZ|Pk9f2BKlbse{?6su~hzMS=TBwy&C*ZXu|@{;7IIyJlR?EekaA~ahcBd zT%d|;UcRiplyrgG?x|fFt9$W}o^)BG<tUhFa*2O{%c$P!C{`SYb3cX<Z(zxbQaCPm zO+Mdq|FaAy9%iErK@|UPh~zBsdfLn}or{WA$DR&Ix_xi6##)GdULR6r$-_yXD%HX? z>bd2)&=ZGT{Rxu5!*#KsC~TUtB;%Gl>={yhK5FKxQSRBORAORsPU0dOxu-877)*?R znvmv-_0msDb#=#_MP7LzDPOC;i}yRQ7ZPi^75c?0x$(!*yFWs?b9i&H7c<DPv+?LN z%62kBv5gDIBYiE@*1h`PNF1Ua4|c9JRJrsXa>Sta5ZsASqBMkZ{3<an!x2`wz-yzx zyWcPM8^^cz)v3<$LJM1e%k4-2<VXZkfCKQ~W<x_~`NKpbg=h*BSoG)D@KKV$?R7}t zI{&j-I5YtZdv0h>^@YD92`3Qd^n44IL)Kd;4LPLLkp##F98ECXkD=P?;hH4Gw2;Xk zU6Y#*JtDQqrpB<`L7o}|L@deq%w^jkN7qzbD%>}Ark@Lq2>46B(m+YoZ83rO`*Zha zxb2I%6A*<W((|r}XNt}TmF=)wk-R{QXCUY3b8ag@hria5uMKNe0`Ny-!5&1l2Uw_$ z1@u9m*!yp1DXz#AG4!e<+;0c|>kXXFA?8M5*w%=|Ard!*nHYu4TtEn0GX;N<VmHuh zWY*Qzg!4kD&`7O`KI~r%sr*Ms-8)Ik7#ocENdQRJyp`@c?<5<L;#uhf&d~;RoP9QV zuIxxTRJ(e@0?&hdlKM03$l%8~WdREKKdj4*elbFgxC1K|LDUtHR|4yXpW+~<w|Hg^ z^4v#68ZGG-8<u#S_8SBK>PY_Vb-w1lY!@>BAPM|HC#Y%zBO&a5v|jugLA-yRKVY4I zW*zci2Yw*UWI&Op(t}9L07ldUA!tmX=q3t|okG4-xMiGE`V(2aBmwe3gF#L;JmLrt zPNgsjJcki;lINX|K0{1)9dLR!h{)y!jJvXQJ5oBJ88fkYXi(N)bLqqlZvePrX@hu7 zK#1;0{lF?%E&6M@AQHY_5tz%ge<pO2>0GRz1@Gs%E0)K-;cE2Uax>P<b<?dzue>di z|2hIfL_zy?_$^cT+alqwbod9?4I=S~?<%CN0pcJ^&|L@;Nfvy?7MPrc<0~1Z!5V4x zg&E=!e4!yoB=bhS_|iNpe%DB(s4%HQfR}+OvC=viRY#iJY!70@Vr`U|#q}PDgN8c4 zpImwH-Sihl7ejUZd*gK<*NWf8BMg9mivt2S?noZrBgQO=aTwr&yn0MLd?;U6o_Mo8 zA>8nny%`5#vVnWaF%C(U`t(Nhv!OvGim!f$AFgNc0DH9GQ4Aq!ebv`6C<;D<;;Y<& z$Frf=Sprjia7a2f>m7sdH+fl)DU_~o?0%GJT*cp*qC}zwsG|twO1(BHe_cOUU;|SW z;CIpOw1M$yNR;Aj%tg%+SF_-}sr-^6=Y~*<wE4amk3v58uJbS?^N=|_n1CM1fpmho zjfbvS2Pw^r#R_cXnc5)c3nld9;<B(8E4U<H)j55xLA9=92C!lk^0yECSq5&A@XkI- zWj(`9KloJ3?L`FCwyOMcD29iik@j4|C#4W>;)vkEPJRs*m8zSaFNDi0<l7LnqC*M` zLg2pa#Qvhl-HO{qCoM&8RlC+V6r2;7%Z2PZ8FT!={V6jB2wf9|(IR37CNzB$()TXx z{H`;0B;a2%#tdn9;%$C!q1R&%{~mWQ0pGHvvxu{`$w&Bs-@Y{vqUa~r)9sG@^Py*3 zNbryyo>daG#Sz{~YGLsKM|shsI&gRZoU~Evx5M`d!I#Vua8WOO-yklxgoINnqIR28 z3=+RdRc!3A_hMLt+<TJoIU>)}YDW?8Eetf4r~tK6fS7z>7_5Cyvc%|E4VakqXEW2q z65;%&MDAl4ieCu*QJvd2tYJ<davotd+UUA3=A<fp%n)&+-WBs2ztjP%jBPp}<*Aou z?8t@k_T}$(JZx6L&XA$uWd5!`#CMp)6bimcf{*rLpRMy*13cacI3=X{Wv*eu5W=hN z5a2EpS)!SDOoBYl5~4p6NBSD+Rb)wq+^oMRz+-dCH%D1mgUe3g(3;$6U0m}vNjq5T z8mOyLs01RPm#8b;+M4IwT`eOm#J$_4?Gk(HyNtrhk)ebu0QQJJ`wI4EX5y}kji-Mg zLIqB7{@W;J^wTC$$O@c;YyR2OgFwZ{!#sU&A6z{I+6u!%XQ9D;hiVLWIf0l0?(`$z zuFhmA<5+4%h0h@3#uB0cO3YRA$bkS>rbGkbNAnY!;l7Wdv6yngAUDzQ?+`Y-SQ1{L zE}H)U{xzwgHneaYk@-6J1f@sQsw6eCHOnc3{jh}i0wK#^YQ-n?$iO?=PiKaD<-B9S z)hH$PmHTtQ#3IQ3l8xe>P~g{m86wKlgHNK^K&-8W-%IxfvQi=+1V7|K2k*dxcX(H4 z`CrY#eWS!T0U)k}2qa<=t#zqy4RMob3yq;mF%sF#p`u}(EwY5fEkcR%(2ZlAsh|gh z`*quP1ax||I)_?R-6FYX*%?%Ga7VHADut&?-7C`D3m8N^u9u#09|hJ+&*MO2>6i&D zC=m_}E=oKExkiQggXgL***Bag!Wg8Ueg2XXHMQs8I7k1^d@;wlM9EiBP9`Uef#TuC zP0&P^;Qbw*ejRAy5BTo|xV|YBw#Q8SJ~%xw7qM&jTa9>4G^AtI{YHG}qf7}!fypCE z^H)Da{o5msjK@0n)&hlRQY$9Ec!k~^KODUHH5H~nqT-U|0}BVA(9m|=6fZBVQf!lW za}2iusqg=sMF1G-KNW4h2%iJn-jOK#Q<%AG`ERci<J%;pA63=;OrZ6l>qjw-OsF*i z9)RNemD($Z)*^ER4mMGOK@>*(R&Qw3vDVc{#%}Xre<aIbf(rKC^a^=$1q}{ld8fGh zeq@F83|sY2CQBzzF1MK2)j&2}y#rg%%Lo4bnzAy9@MJ5WnL;e=N>BXqmu=x5E$TD< z3gPeP8t#~0==Tpo_fg?9|9VZK7d&Z=;znIfkx|CQLx?J3<yB}xUmyH2>G=#BTHGgi zPKS5GPqO;2zzbPOC5jCWZGJT{&XbPDJ7M$7Bq9}#iKjC)*Crsoud=3snYxJ?t`)}S zlUcrxxr^q&okgWT<jYmXBRAx|P0u7spWNY3DP1V$j`Gy%E=!+8NO&RsoIrF1SJ|z3 zPrsR3ZyG&-_j6Bl%S^SlzJ+&RMyDcnmwSJXJgswmrg;4BFzi>DVx{m@u$A47jc2gz z@jep#UL-hyK6r@5Fl>VMBOtd~0-pxQ%L|*6#uF~>ic9ki35p*>@F=7a=f&bCj<`B@ zz_I+QuR^mioah$<In9t|#H;zD^SeQwGM-%FP8u*2sWcQWZS`+yn{kHcF~XE`^upC$ z<t{}bj9`Bf?w#_$;-Hx9wT(tHS6e8^YidtwDbYul^2BI`Q#G)vs`w;P$k_4QS(Mwm zG9)}o3O?Af1@?un?(kgS5xkCt&h(um3jofU&8095GffcQW;jtPkVah6kTsIvTMy2T zI{5Y3eKw+Q^W&Qwfu}d-5<XmYU-{x8uu&0*Z)rS@xSZUQ{PKm)5~At-Yd6mt`pFs} zrz}h?=Z@N_kZ)=)1Ki|^I8|VBKZ#&hFlw@3@)RV5QWqN3ys44h-&*79JnD*H^XoY~ z?StQtTSd$?<wI}=?<+qfQ6%*z;jJ(0fJlBn6rYHuAon;z+Db#RK;XqXzwVK5!8Zlo zlLa|)g4<*X`=+<&Bal-kb2_hhh+d8o_K--+*%SVS{wICu=0^$SA^a3Q9JxUR3Ws_B zD>9GxQVrQ?eHW3mF>}m$`b5Msd}CxuW~RTm%hv%RZZXPJm3gY8ihB;^<#<00uXSMD zUX_!fT>h==v57sLc(v$SS+0NJ&r*r{?`5ReU9~u=npRX*#je6}oa*1te*I@g*aDAt zp!F<);XWedhbH^7_(_E$+YbaAP>?Fe3ol3lu}l0LWcOD1v2!m83;z)^W8Xe_l4$>G zPe_u8;2RQH68~pyj{W@e1snon{lMcNiFf)4Z&Sb8XGz+Hp=u$|)?pGJ=2JaqVV#{D zlL6)t2;r`-<wT-R&^*|39HD^)i5wm!>m#jT?uM$y-{leoU!H`@^8mU$eOM~^yXaw6 zPsGs$B#YJFw1^G5w}&p?4{WT^0v;v_{e_VVEvTa~Ep<+2g+4IZ1;W0tKTxs=1xkr+ z1tP$MbMu?S7C&P|PY@NV>urB*+eqsz_Ax&~v0e}AFn0yPXAjp)sjmH36_MG#uE55S zQRcW9@VpJYcutn{S<#|9PS*1x;cl&KkOohKMi)GAjILzEC5^nVVC~Z_b87nLF8Z$f zO|K5~o5$PgDW&&9xmdj9YC7-Tc@TLyRH_Ty)~@9gX`Lkrw(PxFR<dpecmXW{qROZr z)gxOF!YQth0k~Yb`}A2ij#6uR_0TH32Dmd28?yjLdcfUh4}m?W%%u;6wb4QlbT+fP zt@P^L)f3-OFSUlwbTRlwXqT7XoAV~DCkB)`Tp3d;iHgt7V0RzHCT9$Ev~XoK-ZNUA zHE#UmM<{{ao4;`KiImBld_Pog@{kp`JlyLel``2nrg9jmG-afp+QxW%5oX|kR|r8+ z>!j<l7Ygi}<+u8f!Thg)J}OE@%Dj@X`G0@06kllN(W|DDSyhxnkTW09&N1hwvN18J zg>wI3#8ZR^_yiy&ulayMNKeINHS66&{UAuaofYFv(pKDW?irH`8p6FRwFW?2BJtGL zp>!>cUlyW7E6Rwl-MFf?Tms2gN4nWIGjAZ$pviI2Jx00}<!(Lcs^-o!-`FAY#y^+{ zcw&Mv0sKz?m;wv_O;)3rM#!kU){4+gxvOA+Lq9MHVdPkfdU6P-{;sFUo0MRj9nx4T zbrV!~HtC_4>?RNSvO59<ATO{hCghNzTx50G=r+_A(qvHnZGnc$S}cg&%%X`)5oWA_ z*`af}rre}T3YR9sGz}`tQ5dF!-a68~>Abc6nc>@WRLt-T?VFs$q1?+uFs0I<a$Y5b zXa29P8>b@bl~kf?bF9n5YjsB?;<`3(qV58W^d?H@%N~v9hm{Q<TOUrVeZKpwvtxj& zv|xBP{B3RW^X};RdU-z{srY~L_!Qb+eDf<MN_fGKIV*Un`Fop&b$k{gJN<{@tWfkq z@a<WkK0zS`kj||mW|c98KB=JnO19>~xwd%{P^^M{N!bz*1jI~`?~Y#i5=Xdwy>uI( zuV3h*{79D2s`FKPLo3`{HG21`BEuj(43&ReZSO@u;-!VIN0Ff;MWin5cP42_XjCd{ z0cV+IYT$ai1lq>S_atdcKClRSR8%P9K_$<+YqVj-`MDayeyWSD)cv}mwT}vV^N_4i zgSs)DFHt9!#l8E65mwt{^6yPxL$I$p$AClec9iq(>{Gg2KgJ93;1ccxlch!RV8fQQ zQ(Q}|FK~RqKS^Z~P7f^1Q14^-Bnb*e&y~{>_yfv?Bmu$&A?j8o$}NoHhZk1%f6=6P zu9|6BjLQnD<`T3{py^HeW**d;D!^w*JW@(Rg1w*cG6Lq-a>G&VfW9i%Egkm3v*-?4 zt9xgi<ZbSC5wXChnrtIVhJ++i-@>QHV|%PztVT@Ii#6)G#6`Z)3DE-*D${CW8Nz19 z2n-0I$$OvUb>JZMMFSX^sEv;WEwsiuGMB0b2Dc<ny#`_%ojB}uQc)-9GGQoBLSbI< z5Y&T<d_1NwCA9RpZ7%l4iC5s<prNNMRj0WC>GuS`_G5@bP&S4X#*1^pBTC&<q*h@g z`kTZf=h#(>GmhNqJ@QauZ=hD(9Q0o*8lJfDTJ+V9<<n|3A%f*EnLbNjp?1$b_!Sxf zi3;G7gxm_$Jou<q*t@BuXmPk3X=e?7@oWndH12E^;BPO(5sI-G@K767dw?0^zdSZc zxuOc~{D{^6ufK%!CFSUWiaC#a9~XHlTfP^=TT)ph9cqFpflw4J#5bl+QW|Rw6`2WY z`Uti7Tt_g7zTO49wbL3<-hW>i7$U-L`z_=~f?3+@EN-l+#l5xl5rsGAH-#xFGC!H4 zMlRo(P|(-2tH7wvf)1}CGX89o$(C!cIJ!sCiG_;en7$rFlnB(Kl+47v9gF9AFVJc- zV?r*N^8!xS@-W7-gzl5aS}}&S<EDWYQdd48*j((?=45$X`(YZoAlMj9{=Y+8Df<f( zbzrRsLqr(jRphM`Rr3RR@2L(@BSnA=<a0GpOF!N5%b7<v(YR$>;ZKT6%^z$QT(jrU z`CUfkNeXW1d-vBV`5Xyc4%8GlVGvK)ZU?L0m3tJ0a$exN!CbU5Jh_p68Ehf2!Lg!g z$vnF6k(zVV6N7&DgYX#lRqdJrlSE1`ln}#s&W{t68w2}CQ*-qZzYeJrNyn*SVcuX} z;iC*MlX9)gsEz=_2RCHnVFWu@+_v>)-bz6~t~8V>;!+rtx+u}Z&+oyZUaDR2rm`Q% zb44+dWx2e6yJ?xeUJbwYf)B{g88UsuxOjhg43VeBmwCfU(<}xpC^Y<9rquYr+PsX| zH=7M{dy7cZ*>@N8H*k=ifkBQA?D7~EzLrGyEQXxdTSf>}XKP0gn30-i8utat&w3cN zodauThv`Wm>)q_MgSV#phR;<KH}mekw*5H|n&D1F0=C=E8eW06Qy7?bn*r;^J`1AO zH5LEx;gMJMi71~4LVx81>#hlSLco8D*Ltb+o*HvGPK|LT=C$PCT>B@qct%muh7bw0 zY|P!sXX-5a-fDALYAx8&bX-0w#voX`$EL|}+!#vyBrmgRY`uVtf=6fixA^EZ8Gq^U z>k^H8uH8C<wru|>{kqHWgwg3iezATBVUris$EYn+1?OC{l1Sg(?9&Il<|fy@o_?5X zoOkupZ;`q(Hfe{*D=hh2LR}^Cm?5-nN`Fl@u1W)LohC*g$M3Nn_x-rXo(l8K2c?nW zvx4;nV|vl^xBe}igX|`n{<PZd1+8zcGk8pO)=>4cOY*uAP_uzZuyH;h_<{3U?{898 z$ksR68CEwf^IPuel6WoC%e{BwuHGxkjHS?+c}d`({;11eJHa+4mr4k^cVe1T=AmV= ze-Y2-JD{h}MoGXoTuWsaX3ulKC+q(w9}nzU$qLj{cG>4^o=-{wk>;l#ygF$YE>Znz zrSz+LdD9*H1dY?7hS>vU9n%1R*W7ho9jlxp7hp$o_l-+9-BGg#UEw=)TCqxT8}!0{ zidb;U<!vr4$FvKax>y+BB}U5`9eU$?sL=c3`?~%2=J*=0n7PXC)jH`VFWzBk7`GR+ zgwka@pC$MDkrb};6@UH&Oc73n<!-m#Ns){4V3;Gpm>fN79k&TK>tdr)E>^CQ(?dz9 zpoTC$_`{IwwCn3yt$)&#w#gJ0NQzG_m#m+baFR6sfKoVck1F^sN->wEJ-dG5%)Us` zz&)?y?G&J8HMkvEC|TW?>)nvztk9izpuf7)OTVS+AW~ISC<+WNV=Rw=H|8P-8q;;7 zZkOi24UI<Pnr(1m2A1w1`Uzn+tktxug??W3?h^NbcqqF|I~`+XQ9w#=r05u(wl!K6 zE(#0D65tXDewt@V7*NQ)pVG&zNHJH<uMzRfq8}<)2;<UIf!%NSRbM}LtOVAL8>H%* z+Z7rTW3rMi!oH^r#%nO*Dv&g?_Aj)6!}^I+d8Ns!22@UY+%o#WKZmPIGM8Y=^3xd| zEV;|*9h;z!sKcTW5G{6E5C>$8O(CsAqw4s}y!ZvTs$x_+>h@Jcx1_=eM-SFbV;wcl zGx<Fivb_8mXT!3rei`luv!Ail)3!&K%{x8&G*bpq8`6w_b_!1GjLad_Gv#5I0^}&9 z?9lmR^g45Pw1@`d<nuZ6bB75<ZCRH&2e&Tm$tKrP{2J8ckVvE&qvImuojNSuR6wyl zC8h3RDPObcF8luSiAJ_e^tgaVs6fFl>&xkylu{e23dgF!n3ido>BY&OfZk_ilqN%U z38`ncn}XO1FnNZTblN2ZkKLcX(=s@#biNozZel{3eIhiiSE9%iOX}9O{?#40VTlcZ zX@0c?BH?SIdIeJVJNP7b5jB*h32I&aXR=%%7*GsgFzb7+mJCn;r7(QiOC;=B)FDZ& zCZR~+o-{+}mlb`M7TF{l4JIElkP>j#Nl&fTw$;L<VW!E`3HFbFCh1)&zDM8Bc50Cc z@8(;dbfD|xo$|g@8q1KLJZJ?(;ZM4Uts3t9CiEq+(gKWmyzA%<g&Cuw5MzX8DT-N| zKsO_E8#{8xW77okc&v1w(Xh0f(vq+Qx}z`8NfqLe@ctvi{N>5jDH=l*<H;{MMN3~1 zw?f4A>nlgMr&jp#FTT)}*MQZoocN6vR_x)61p)4rDa!3V+xfNM8mFlos(SCZVadt8 zrm~ephcD83msOO2!|R}8ec7L}ot#Cpk?qW%rp`VHO)9+jaQ>8G<xIcGKRxOHYzs~t zLa21RV$jSz7!%(%#SQ79;Cr70&z6iykC>*x1|dA}>DGKaPWfX~m^8=zl&5Wnhf69J zVV1~(_y)7ixE{2UjKRh&)QaPi&qxj_cmf#B>FIF+^kyk4oeE_I(yA~=KJyxX*o3Yv z6_raRn0F-z9%peMD>M%U1Ny<p54|-%!eoIywHG_NTK=FUfP58phPs`mtzvPkh9b3T zCFVInsT+9fFW1$Qm)a-z36*7!$V$eX?%IEt%R5VF<ouhWjuV}H5($H*@>@4ll?Eg7 zzp0;bpR4ODDP3XG8TL8++-DO~kGW5kA}uenW&_w#cL+^o9Ozk{H0ehf#5H@bL1{48 z(V@H>kLw;4ALlifVJ_1oR|8;}?`F5{)#ct>qyg?z^02^Cqx2A~xF}foO<V2ZWy1<# zz4`;n$8UNcNDXnCFtK2U+){3oB4fKzI1a<4AL2N#Sa$_0;@P9UpW6P#F#f19sEV+! zEs!U8_cXFg?(Y|<tm^X<0(fxRpRU`^h+$D_SNA!nZW8ot3ss>DvTzYvx{@9SI3#Sl zH1}nk`Me~{S8$_Ip>&-%xRCX;W$ae{l*U)xHH~Hef6dk}I@Ju{lWS0&LkZYK-lq^? zX8aY$qZr|NO2(ju=PlzD<kLNwW4Q<lAHPMb*z<oXLEpj{-|elb`&{hk33{DUnCGqc z!HNntj6eC{I{oR#3XCWE#)noM1;h4iZ2KPU%#$(Kp-h|5V0r|@BcU!WU<caAb-*)L zW(F@Qi6rsFBd7jLWD1ASW64l$GM&iQ=qR*wr<tACgca<N%HEWa%5dzgwH16jP1Egs zJ36#poC-{bjiGXlYfdxVJ}s5fSUs^(<#8KMRGpNaj?+fn=2X>{PhbmRR{o<v`^P`R zfR0yVWSfdA%v6zi^oR4Cn0w}qw!u?&F7pD9WhD#DjUDdu-Eds$e<N#tWvM)CshA@j zf#jJ<<q1*Y+2!!j{>~C8h_hf)42OOUM!$?qjU%U>>1!%z>h6hxF*{yBPWb#ACu;Qg z(PtrM{N^x^-jPcE*Zz-$azVC|R`-vB{ON$i{H%!Cd%xcrTCWv(yE+b@hk1(_i#P-8 z=csjB)Gpc2c4w8`&Kh7=^cT+26XZL<WFtu!yXX1$6Y|H%E8layK5|Z&cdYzKRqaAZ z>U~+cTJ3Y~FJlksma7A2e<TiSaJcs}dbtXSqG^{H#pZpG<Ik3?(}$<<L!|%@iI8IE zSbRk|CEiWUE%GKu^KN$qJ!k8@eTQ-~b<2CQwU3lD&{lmRq$_)AYou=N<=-hvAtQ{~ z!%&%aGEq#nIi0zoRNL#9W}Ko%6FF{Yp&7vVkPFi1&i?G>r}S2aiYRY(P*Rm+9P@|i zV4sAC!`!o1)Er=17hpE1+@L^4vFGw6FhDIlPgD2w>j;iZIw*+j+~U?0PXp%nBVYew zJj#-VMPYUQ5$gf#5U+K5q{?t{2Q(6y76qi0rVtGYsk^*%n{_VZ$c{fMJP9qSVeBfI zyN1!h&<pI2L${vrg}W_+@aM~||F!WMPJe)XcnkQbj&rn?#7@_w&bO&CHdpcl`Lx{9 z3)MewybgTwv^)K+B2$r(C7I;60s_pJPL|3sbnA7F3SZFbZlLJAHT>(;mEd*nH#>&- z8RuyGYniR6070ovKPd?XI{2PoO1~wzG+(&0$_}ul-e|STdCV9y889}9s5{x08i7p{ zT0I<NLN0y>W5?-!h?J*)xC6K8fhe9(*74uJ=vf&DkVpne@=x(81h*j!s=K^Md&~dK z&wottl7wVw8Q6R66HaDh`=?lqT#o90F8BY&hK7zjRPeC9G^C^&W^Kf<mH*G_lLkYh zJ$(gAe*ZbGW%#|WBwAmA(Wb#wiT?6Vk?HAFek|-sqd&})toZiA8#9XB970&`D;OWX z86aD<ugI$*<;XQ0mPW`I$(EGD^NtlT|IKRu9Z8QU^!IkZcy1OF#7Pg^NmcGj^-4(b zWyeIXYv{IcM_?b_WFO@XPdn|fejx#Re!Gc;N^x+uKcaidipa~Ie8jdnQZ7$@cs8sr zeB)(+O!n!X8wI8BYgHe1Yy_Kyt6YR3Y=tk19J~_N`%rKCMQ1UqZS^H(Kk%iTh~7nK zsqr_F>KDE&az$FokwPy}_kFjG87WJCnY+&^+l8OE+bo9PPB1Dv{1)gf=xq0{YpbDa z#=b*_F<(#L{buz~=83eVy0jC8seao~y##2|I@JNT7r74!P{}c{#DLz>!a2|aMAeDt zR5KKx7O)o>42_fXy?;To5jA8NBu-~<Q{B7#CL+~)7_UUFWPj}t#iNS#YS1*JUJLNs zSjJpVo<>Ae7ZPofl7U8OYkj&e=*TNO8WR5}O_8N0&Z20w#kI$sdrs#6o^m2>=U8_; zALUQM_7`#WBS&(IV4q%w#o8+0H4@albg*Xq;#F@~5YJ3qm=67FE>B2H3WiO!A@NKZ z4j+RyCG<g0lhZE%JQt8sh6!AHFlabZ;Y-DspRPDN!{-NQtb*V13H(0kZ|tPI+g!Pf z6VETX=$=-7EyV@Z{L}B<(=yauCXl&@&|pf8gWt;t7$3^(*rRm6=?3jUy9cH}=m~<R zjBNCLo6_JJD*K*XWkh4&DWsriX5nu&KZd!@5nb(i27SA+rHF7N?=eU67eVDB5(=uN z1@zH=S@QfU@-ACi`uwCT^J1DWmd6m4ax4-Ofq)9gR3Ws2o;~90N5UB?3H`Fm4azVD zO_+q+yv%NJxN0g93UjJ96~Y`W@%G^yiU6IkA%;Bu6kJhnVX#F|)&v3S@?FXiD9J*D z$RK@Tpde2=1voy&1z6tH3z~20<|e1-Xi92H9<Ncdxhd}&x&Q-ah6)WNB1~a(Pi<U) zYV-VMKEEb+M9g7S#e5^@T%VC3w@FNq2M|1GB=SB?siQ0UjVHI`tzw^`sivrj0)esz zN#9Q^e#5{edm>(Rc{K9(6&Z5kOQN3APp_&3UoU40i)2fm3w>6+VfLcw^T<=gT)Ov& z=T>V@AY~dlYZvB8?}&do{^6mkx{FhNv7YOP{ap&A!X&WJW}aiN@b8WgGiO64=cskT zi(sd>Gg)S?<75yPe88V{u=gh7_MfBZQg{f^HKxO{QU>-iCUXN{OS~F0$oE(z8o=<o zy7REu**UP7MeQVJmC(N6m!au1)y{7rlkQTI+*&r2nXEWsn5(a<SDoeeLMJAZ^oEd< zrZjM+D$D5Vuf;<BwFF_P>Wk8tEU8bcU#*Uf<X?~qMd!c({mI_W<@`_(3LSQV;*JK| z6W)7i^nsLRiiRcAWPpjpdESz+P_DihX?ZF^9_F-VZBOv!!NxBO!HAa;ys$oTPn~>W zydy9R2F&C^z_o9<Auh;bRHCZGC!K08xb9@1<B`I2PiOmG!+Ds6px&YkzB->PhbH9I zL3Bg=9t7KIk-{P5v`3jeZ|eH9X}1h34KLivUPX$WG5fkuWi7>q4Ne%OnZ4$d=#P}Q zI=<W28m^;XR=aF<rrh<-%~3XgldV5)>!X$2yvxKb&p^nkOF*UH+aj(S8-&GFNF@tX zrzd*8Oh++L)yXP+Vb1D$&(FL{wcWm1xSkG8&f*iV^d||~EpX1&9P^>uwqA(wSqbU5 zAbLC^rv06j_~O>Ag<u3&-r-LK#`SKeUtNWL&*YYtqx*#y#U4}mU#-FMAV(>~JG++I z=La?TZ;-sNqlXoC`(9`3Z98(q^%r!WZgnY`g*4kYhsS0zY~MlQ^YAxi1*s(Z@e7at z6dy24v5ufj$G%7|#~mu5asLqI84*xV5S$2mc3JbbXgT3VXZxUlAp`$wwDKi4*#sRU zH8`YSwD;Bi)(JS-a?!(<D8H+_$BIF>+VTPSeweD`ANmmX&MG7_9=tqS5PUgetKiyv zE=GK!^87OLo4wi@fJ#@{5RLH*g_{Ww^WWVz6fTHwTWNmy00d<AUik@Cdi<O3oXiGy z4RaP(TFDy5(S$N)*R1NCyH94}{k%6<E0G;J8O(?zaWIfvIt$8K1prN5k4h_Q-OZ>V zg&+VcHR;4t%@V|=vIG_6q8qY$Z7`-8j!m^_VRncm=3)O$j{=??U*PrCD%*os5DNNM zPA1)8%H3+YX;<JPm|O5c0^PWvzcWk4Mw8IQ{EZTpj`d;6TZKJ;xa`ai>}%SaEJ!?= zc1a)j*N*&1zYrvUC-=h=91YL65Kh#S%LS27zUAGj`x|xRdW!`ZNMMdc^c}_=Y!US& zH^vP{S=fGi#ajwDk76D$Mk;KB46ALTkmjZhdo2m4+ATGsT}2Y*!;wMW%c0GfV-Nbn z6`cL}9g9UDMHxnUk5toNocm@VrduuDvY%?`p7;3NG%W&7dAU{?B+cMV1Y_$Z{^Pia z{U;xkJ+2FDbP8-qu?fOdbN7A13k&l!;PcQF)ENy`;b*#Aij3ZclLx@;4VEt6->~IK zHA;^lbfMo-jhk%d%R?4v0JC0HSjgh%t&iitt{?HMHe}^qnQU4bq7?zqYa6r3sTN;L zUb%<yHvRN?dJ9`oYfrNgd0(@w8KQf^t8ll#-_ojXnvrWXKuS~YMHd_JR(WpI9lRQ7 z41J2kz5C;cOT}-FouzQjD!NP$$O@7biYh>oPIn3k0aZIR80u7FF1Dt|&%u2Fb=e8W zaQSfimJ{ZK3@`aKj+Sf4d&a_s!@|WyD~Us}R_f*_iZX?Pqu<x8@O-`NmceOZVS&35 z!>pU=8}d8zO2AUbgYGgrml4tDHc20xZ<-23sQS?jNxKKB$H@H>2_et`yl+~NsQ-}} z$6MOBVZ+)D5KTkH4EsQZwY*PM3punVp44rXv-+{oMgCkP$J33bQzH-Ppvr`6MH%>l zGjLGAkc;{A98*!?(0zaM=lhvG((KV|k3@Zb@d9#J5NHQ%5kY6{{;+v<>$2pS%-eMx zGiCtdGi^06ywGDK&gi_t?i2z4FbA$WQ!^#Kd3`GFsc6Zi(5|uz=?kdzpgMWcnaC-< zrkwO+vrAopiN)d-)lc;rz$FIEqsKnp5f*-!D-Q3!eVN&ov!(J5!>{^J;tSQ|^rbHt ztDF?+0HxN`@pmw4#1`9h9TH9M{=GZ?QOxZe5yAl%HkK~SyryRLs(T=_QYC=nsC9X+ zD)LvEv}7Rta>0wDEgj>Z%N!}~cB^~a4K*vKQK1=yes2pHPec0e>MkLm?lP{Lk2!QH zCtpFmUbJ*8(@Dqt5L!|y)eR3Bc|N_)x4_EL_<}1oG8<Yf3gFne|MH6L<3AU}HHl)1 z@csi}l~2@HKRRD7$+qTd!wRI!r<yP;F<oFo{VhLWe?h^L&6Pw#OnaLgK5CsJyIQ0y zP2qYceBycDexd@Irp<lUJ!eJMlm6CqRaMd_&n@ZwO^X$l-PM~9eoF3ke@gz4uD#g# zb?Wnx2Qa!+`bI{FfdbNxJ%DNNmy&t@=D^^gDc#6c9y(puFV#wvkgQ71UHoF&*rT&N z<BGPU8y97rvFg14^LxWt=B?xJ7hWV*X^QaukzN7V%0SnnoZp>kJU`}^6r@owU{!(r zC1U2(rzq~YjOv%aB$*Xk4~2Lvz#o-22Frw9USt=i9&Vo5L}p%_ujH9)cejiRUGd+# z=*jF<waU;=$I(dv3h;`^@1Celm-A|$Lk1H@jwbv~JLOn~eDwH@4VLCAn5e(~aM`u` zHvE|`(>W6H{#EpHKFj4e%ryzzR{+8uHw)ZbUg|uNBF`uKpK-d9Y~PJjd%i!~9=vn? zZ<TXeH0kXD79aEDlfH!$OsM;D$0PBB)*=ePdbnouFXmVP;|ahTtmc1gC%*h;&{F0e zV@6xk%V~MDXxKne$kUj6JBNbY0v!|O4n<nT+=av#rf60`*Y?eIXgFlR#Q5<u$-so& zZu%VQdGP!3c(WIUn3YJ@LKJxB_{~LCoR3`Av`v6Za@K7^HEUlNuN;`|R|ckz;S<;K zJl?}4#Pbo`7R!s|9$Dc!EVw(>@%m7iJ^83Z-&v~#_KqU!x6jfS#*pe7i;#s^`!~}b zc^K}%?<Ol3dQ))ilW=M4h^|47F<g?FAf+E`jwJL;M-C!&@#1DSZ<$1%2;PV=Jk0Ob zSyP#fBKCirSNT~ti(!)`2cnY%6wBUyWpI^kzq4-jcl7Fu75f%|KNdhN4W6>UEfkM} zU}?BD{1095^=(OfFzDwL{z(mjzyMzndqv!vOOh=P#L+MT1Lhd-#wIp$9vuAdZ2TK8 zI!pW@96VEF3Fr;!t$Qb97i-p+7>*)q0TwEe{rZJ6S_{KdFNz`ZS-Fc~4Y3=aTIXE1 zCl0HiHZgDsmZmEO->QCIAX%){$)nr=*X$V;WMm)yv8n&HP>Z&~?vC0`0s^s)M|vy4 zWkc74`z<=`4?m!5t_xl`uw0jzbzo6lX1?t@zgsLX@X5*nUJ~+IhQThsw}`)Ycg6uS zp?hVpgND;NFs4c&Znc!o89bxuH*ZO4qD?E=#txGFo$NNlQFHHSp!(ZeJCsw?L$?{{ zpTwP4t^}8V9z{_QSHo<1cF1NsDWe*gTQKn@0i*+`Qk+onHGJM?i#>V8$utYU6He>L zjha`B{GFQn{3u;@A1+xAengOB>b@XEy55tKt6g$3)N?R0cO7{{X9Q;%Zcz|hIGrsn z{g#Yj-*G8(nikwAK5NM~iPwqF{Lhilw1s#ohA&=KC>>%Z4kPdj%q<nj?jrcBkFdoR zG_ZB6dk*WRRPG6#u&~15$t=RQho<?0c&xP8e?`^_9_LQ;?BIsblZbz8%mqM7J7MBM z2XRQrYm0NoJ$UuN{@Dc~@vz=iXaLuQ<21&Buo#`q_{B)k?*d6)8PFqhg56vlwzBTE zpF7)>udn3y2_$F!xVDJ%>XjwB(KM}}ZR;ry@9?!1<bwQ6P1AU}XufF810s|EUBA{d z3dMnYK;)IRr&gpbYCTQTK>X{lh|@mW9{lR^*EOBcLPDW(t?1fr>~Qi(P+Ax`;N_h< zf>?n)Z~i&NUi%RXV+-9noK7&mmNCgghTC<FmRFlY0Q)rSsQAs>xxjg39O?u#c{Y33 z3D{{+$5TSrO{>1M+#xGAk!4qF@WUwgGwaqz3Z>I?Ym8WB*YBz<7xk+}44pfu2UF$K zy`h%R1Q?61({Vareg~Ru`|Xt2frL<G&O9xtSvgs_CfDtGIAD?YCCh$Oxpw=V;i3bj zfaAH8tKBsqy=t!J*sr-yMU4;rX%Y_zT`U^M^P+2l>T@HjbE5*>zTg;2GT?}$h5kA* ze5}Wt-kasmY6O$4Z=ZfgaM`jV3tH$@bnAsOVbA2V-r$QTDfL6wSs$&Uw+Nic2R#x2 zIGUWwthQWfAa1SA3<4D1c~!PmADY_gPz)0+o7=aI%L#GFA1*}8J)9oWF&I2b14$Zl z=^LYNtqaUI$sJ1+30=1JENw8You4;cD{kinRPZieYvcsD%Iolh2c!>#y^^9bNyqh3 zb-qFvYw(n)??~<NDeN#OA$=Pe8l`2+oP2J>5#w$>%PdVlKi%{PH+&(g(AJTWbRjjb z^<DL&mu?BETJ}wDpI1YDG+OEJqsJF+J@(9B^=9TP%?PXvMu2T`+w~^uPfC?1KfLTi zR86mEzINa2q;6UJDaIG4-Y$n*=!|zcAVzk?j#jT#Drw&GzU{Rs;TY*d28M5Qa5S?o z_UqFgH|JAiG@PgL>$RBV+Aw0RW*ly4<@Av?LGD7QSN}X~FwD`on_mAg|C61Qh9kx= z0x|kurhL%xz{&IveFXFV(scS41=n(#+$`$JxzCF@ywnwy#REax3YIzm{$M2vicR`5 z${MKR0+!_Sd&jpk-PCT6+<F{=Cw7ShN_y+`yt08QEzvbCz!7(4>g^*TL*+w_BQC;o z;i$3CHtjRVSe#v{d-nU|t;LYMe?QY0B2P4Y_8P|a<h1C`&VS??uC{JJ&E4Z8hSC~_ z9$n~H{xDi)%6AR>xz@2Sx9cCF+BJClHjZv<hr%)EX=Wh4$0N_}?U%N&Lnwyuc_YE+ zYRiQD4>XybfzVXHf@cJSmahXdv6gR#$3jEDH%r|X+5=K_dk2v2{mT31+A=A|qUg;H zbL|D_)t=GWzpejv1hqk@zg6<)ye%(Tef#~x+t-AZ_5(vL;w)auaX~T`^Jt!Sa%0rt z(@j1{vQ4!j;?D4U_Y@A?&BsA=CaK7Fh<4+v?8#@e=fx0LHm17!PF=Mx&z&fHdh}hr zasxSwpA0S;22N*xK#oCC@h+C!-~z4;>Rv(JYY8tZr)jOGqZ+rY5^mYDoDcr;hkuYO zb=UrJ68uklUfJ*0@rN~QI!&}v(gFX$3Z<$2oc5v&1R;N6zO-IY+N}V{*Vpgaudmzh zF^T(reR|-^<M@9_F9<`?F8JY34FSC8^yk<bj@Y&@PCKUOpJtR6>H=I6>=d0LiZ&aB zVwj7rJ9y+<YRRM=P6$UobDiBYkGrej;Qr12fLwsIg&muzO-=t0u9Zz6aa6eUkD@u= z<j64m;iTfq&Lh`mLi<qES7+r1mM_Bhl9vYE<Hs`!U_TwSo-CFLpubzSKR-bPb9wAO zqvqQtaOM2BMz|uT*;YF{MQi5pulO0b-2m&Dwn=UE>#{Unl2?&zimoX4ncvhy;n0oD z)Bj5mV{l2;_3K71&Zw$5Yz-WV8<Tn;t4_Hk*q<)14@N)a-8AQsGrS**f#34ru`q`3 zLxUW;+P2MU&*K~sTv(nf{YmW2b5DofN2YMd&FWkr*xid~=XHGeAVj346|qdb9Iq<i zuY{~(jWnx`(F#lRC4v}(4WH<-1c!s8+om^$H63x%z<~5Vm2`@(0v?nb#EE87RAdIV zTiP{EQ;;w&lfO7QIJf@!PP=h%b3*E_cbgkN)_0ok=3I`Ml-4FR5?=8<)Vg)b(dPs8 z-v0C&elhQiX@{+2E^YweuUk3s*XS03cIv9_N#%SBCBfm!sL9081Cs~#pK2C#VY+VW zq;&j11lW5f{d8M^ZGR9&f5$#j%)##4T;Jyx6%KNBAd{tmq>Ik>t)V)Mf#i1sTEWX& z$U$Y9exZcb5cArP@-s(AbJcNmYL<JZe6)kV?RDjy=6RU1eQknOftB}XWz9H|m^Yc@ zD%b1kygH5VaFNYowbHp$PaW)AAi@y7i)r>cwi@x9XD8OO^k}!=90soqx!OKBFKF)| zs^i$z{o(_iOZm9NcH9SCq-Xwx)#hF3&jC#qMJ)5U>=7Y10Shg7iq873o2*5_s{w7K zK$@vWUgCoj#q#EEkl?h=8-q<xiQ2k)kZDu!R#W`WF7D|2Ul+Oi9@B5%PPU#f%@?Kf zM162Ra>eIV93Z^+qw)@fR5Q(KFN?bP>e0VoKOYutZO#5unU3CG-HFP!QA67g20<r0 z=p3hUquRhDT@HDdn@-<w7ai2>y{rqjIJ!a~>bU$>53IF7)sgu_zKy3RT(0(MD@ltN z{MY9u$Q~%_?6WKB+zh*T5Od<$<Hb)5Nyow=;R9=1EQ0#x`MWSYvk_~eL#rHp=uv0v z2zM$E2iN>yC;ydBPSpPWriri=Vu2~{7u@;0I5b`&-^NW8K7Kr7ct!`sZS^kNpL&HX zQlk|naY^UmjD2c}Z6hxa!kpdmy#arMNORpZJ(#CCJru;>e7G=ZtWrJ%cQk|q<eTjq zJ)NOl|8@3H&l`2~xSEx-$?nmMIdRh#UrTcXn6!<=3qNh1oljlTyCNJoZq-W&Xz}PX zN#yU$i{3H%#iuoU#zBF5r9?dMAM>%a!pr&>W&^%~4(y9EBSHUMHJ|<T%A%y*hG$wW zm5@%Oi*Vfd#=TEBGY-<hr`jqLw`d+*eJ35Sy?G9Pq))q38r*A?PWZbnN}89bn|x&S zjF)*n`-eIfK-5{2`l+dKuHgI@(j98KaIUR;dW9+-@Z`-D%aFIGbcBgb#^nTzQ6KSf zS%e@8`wEnNM`+!`ea-nm<c1#I?zygeOZ?`2)i$=4mpp`CT@zK+pUFj(#2bo{RU6&x z0yQCX&S#s;O;QCKZJd>Ca>b4OhJuC2oiNb8ss|4sONkfg0kLlhkPWW!mxD-FC}f^{ zEkZLP1xiNhxYPyr*+&IV+|rd^Rc4(@q3Q{9@lt<Hi0jZn`K?V4P%ks0f5Gxka7bRM zw`_<8bq6Z}jd$euM=CpF-&<3<t(5TNj%NpaEFeEVK+Iyk)B0MTTnX7Z4v?sR8=lUW z<nAPNl3s+qTxH+gf?rhB5H#Izrq?z5O{pQ!*YEj_jt^<HgZ+jy0R-hDqMK0JsAb~4 z(#U=ch=jG!9MyyQf%YyKA8;}txSi&w!_c{E)OLDUOn0S;NwpPa@Kg%h*|P;f`vaH( z@b3)yXTs44z>EPVA34Rs3j;L7@mXw&o+=?PH`=*Xm7ea!r@E!_ba;Z=^N^wRzBA*r zN$~{}=P5&wqyEE;UX8Z`x?c%OMKPO{ATfYNoSAw3Qop{yGu@8ym{zH`t#;Q|-tqu_ z?=TNg12p3aBX@{<fOC{W)CptM9mG8QICwte9v?(6#d;CB%o@}Hn>S%F={mt_QUD+T zh~deU^6PuP#3f(fuXj*lq|yq#!|l@_=-%ytD#A&>ybPRDc$*756(baEoA>**!(8r_ zr<_^pCO66l=xX{jL7N5ZPkyXy6Ras{IbmZ$PkPUUTQ4PU<s@ABg_rSFVe;InD&WSN zrQOIq<C9x%n~%x(esQmY29)k;&<z|A<kJFvI!Y*yZ>=af-+8WQg)GuGl;Y<?p$7g3 z>T?fDe4F_0v<lV@70Az3>6ROodDB9M-=DEaa}g&9(os!Sf~GA>xd)zSj_5IRtQI!K z$tq7i&!E~|+wZYA=PlK$<C#ehYTv!RTVJhzHb7s=haQrWL2Pcp6ndEdR+0=8k0><r zf|f1qntyyq2+xH0i2`j8H_xz7D;cUEMwQd}m3nq6Q(Ou)dUxK}iX?Tj5oIdDOez%^ zV2{9yxt2tezmzRa`JL&c%U)=LyVWw&iv{@ZoMs3%-YanXm@Ap|6@A|~SEa3Pd{~%l zE`5#|@$l*sPVINC`w$7YAt9vHd2c2X8J4Ttu(30jx{Aua(zgGYrh!IS=U_BSzAcT4 z`>{J2nes{^43_uP-i&JbIJ~cC8(g@TI@A=eC*_I5_fan&?7fzIqc5L9?NAqc+n_sa zM-ZV(JXEE@fKd@bh}J*@-)ROWCP8lRer-pnV!d;?Zw5|kP7~xXCJzK}TDAuj;p1*# zQl(r7NV?>YzJQF)60bGz*BWhEh{QVrUH|u9OVv<{$SVeP(0smYRA~6RA}<MFnQ)w8 zOw-_E3Ug`Ste=hgj853DpdmsK{6h4=ruiJ4cbepCKNf{Xj-L9`+9nb)Z}LjG7|Xa* zX)T;;F3N@dwxz>!^uO8A`KQI)kooFP<gSgM9c-B|ca+NDS8_HG)imYmroS05!|>+Y zWQPpwN)D-T7*NIO9OFO3T;eYsA(+P?^4Ti^2R{8m*%hXhM)i(?w}dD*M<E96c9L2^ zWz{*G)1zaPOHG0YEon+`ip~t@&+^I=#DVxeR-x;Kd<h$$1+ojm^(5nFb9F)P$>C~h z^{`VeBNxXPjPS|b%9ap;i9LBBnjQPp_XAorV|@gzt(hm^LK;419F=})7Hy_zNY}L5 zfM{oONz}o3txcm<g2MOEWzIpK;vf^+><Hx=V~WM+lm-*SR7m(1VPz5rpNU~YfCQol zbQwpP{2xPS8Q0X?$KkWy*nqRqy^Zb;DYp@hbflzG5(-F5>PC(pA*~LiK}0}AMFm6{ zrGTi|fT&=CVm#_!9^T&P^?g3y`xn>ch^&MI2<PU5SAuNeK)|R?B&wo^@TSxJW1|{r ziLuGQ?S}r^71cAzQ66i)0JOh0*{`PZU)hcd%U)Hv0wbh%E?8t?cWc6>sISnQLq%WM znot>A;qw|NTMo1%Rzs=n@qyzC|6aF5$E57bZSHpsa4U4h>ar1v>mAm5A;<0GI;Dfo zB#Mm^9ZQTnSv4YnK`+YEe#mo^kfX;t^CD2M!qnK^@Jy$lBKWgT;mLfi9b0EDN_1`C ziNH#g;mC`3$0ekBwU12fTpYPukIjOV5QSGpat!XViu|oL#4e$&q|S}x=;}}<ctlMg zl!T+iP;pH)cXKYjK3vY7BSE1f-t$nSBqf!rHw+i^u}yieCWL@Chjyu|Hu`9H=a6wh zJ~G0l{OWZP;BU?6(tH~FY9D~qy-uY_=$WzRW4aW){dZ%W6j7>aSC3H?%4KDLtG*D0 z`aXMFHQ2nw`QeGU%qa5<x__liJ)^XKdWy`ki>o}bHD<1*$<tW^b0a^JaE<g_<F$C7 zLm#QQQ65Yr=JK3(y1}hb&q~i}JNF;I7c>S%bT^C)`<yM#C?xNbDHIBtcK3ceR8>pG zy;Q3$TZY}c7)s~6zjBbZQ9!a`*Oo)L)EeO>Yv_~JB-RW6Vb6W3hgu(%v3YNl{5z|V z_CZ&TP(8C9>;{R59h=+>E&2S%{9}r0?7m99o9$g|X{ebn=4Di33xjZ;y<_Se$Q;M- zm*}w=m_|D>*ZR-fr-;kTrwr;GMhj{Oulg7I=<T+2w3Is<H8}HVzUlTipp>Ofd;Zuf z$Nb7Se2A0{Dm9$ZFW{(|(_^#`NPagaE~2U5Lz7ujiSGR5Tsxg=m{iU-L1zn(4L{Br z3>uh}I_xv9mZ!;cqokI#YE(U2jhB+n7kN@H2^V`tN9v%%3Zu#wM6M3mXoZhrPKf`w zaGhx-yu>N+t|4ziN!J(RJ8nW~1qujblh*6DdR_$h(D^D8D{FoxpXC#xiCUtgrKN$7 z8-Upzc{k;Bn3kmTm<Mb?Kx=spODQB5vyeFxUkS>1GLDWUWmV>!ee7wv)M4@yc0c9i zw`|IvcWUp$0}m-IMfTS|+frp;Wyz)QuD-q$xQ!81oYr0OP9T4HW`5BoZZtoBDO04| z&_>M<-+t-~5|DhbY;|i<<T9}0yE(A)co}+KaVqz?z~3l;vNPe)j?K}+aS-skl7l7O zP13KE0A}ssK>^tefv>nN*?)o3*4#tl<m~{mHR1J^J<ZU|R_7miA~S0GbCZ_mm$!X5 zyGnj)<Q>YRwL9>pA3;IP>jyW09<`V+<du60O!;TIuO}CCp1&<3+*%zg0R+wgU}WF| z!2KOc`hAZjLQqt5q@ukY)J!_#B#$x&Ce?S)6z+PHeT?QZ&COOx3pch3jBs!fovpT+ zQ0-$OV_R`3rM2ljOD$|@bQgFNLpG&^hX5xF!mJ%Lb9;$c&ZI&TkGM>P<$Ox$c4YhA z7v!l|(Z{NgB_xF?1VjbNe_T!Fvcl3wGP(tsZ&N}DVsPfAOdwLjqhezKcn-op#1+#( zifB3h=791~@68r{E@_%~8Pj%E$XWb{eoAL>9+m#*TJ%MBgGCNG);X=0>_j9-^bp9` zfC7>!Q>*E?fZ$eTNR+M?IkaxYCa(A!!1W$j5v-0~f?sxbEPd<T)>!n3&Y8o$*mRA4 z-C#7)AZ<f-kEuSaqr_9yUn;WP$@AKo6wPJ{WzLKIqwozg`K+l8p`?!`oHTPaL@eI5 zb&m9d?rMHu_vSFJH>rmuPIKp@Wop3;^_q#~4u!)Z7^4&2F)h|fjzq?|<QvfDAL}&$ z95QtlM2t!8(~5{0_n3CsvJV3F=WpCn_vyjSSTgWJO?J1C`OdwhTQ*A9*JN*8iUU-l z2Jh=Z%M~&U<Pt}nBS~s8f%x@38s?NAaaMTzvmT!VpJw@IX_~9)JNS(^c1xFtHSe)j zgdtnKGU)w?W4IfXbsc`_<MH?8fE5||+IINjLl6Ym$aVPIYrRVfT&^wO+Bf?(1@+zo zRbeUUg&VT%uxI!u9P4+<J;VVWHK&+JUMVR^ePw{aH0_l8--2awzxr95_J&N6Y)Ig} z)m@RpfucGP5hm;OFDGKts&Mlcp?_`UHP_O(?frVwr4y~bBX8sN-VhUJSihKGUY>xh zmUiCL)k!V(aCRm7<wU$Km@>HZnjm;+`n}h3qa3+H>HDhO5;fe5h^#z{N&@sRsb`J2 z=z6vE{2o(rh+mErnCYGUE`D$LX=W3y=?C)oQ%5pkQdLb0?^06oDjjBGtSZW2iJTK6 zG>r-ikMfle`BqlO9QRI|ggp%;`No6=J|Hd=s>ij>9v8YQsbR0qUxL%F+U6Z2kR=uv ziS!^W<sh*^mlQMi8khM<;eyak{Qirva$cXr-|LY6oiO0yl}fs-T6fm8dU~|LU70Xv znToz;*9tbA)+9=bydJMMnX6$CXr;QSz;|5kRUx7Nf%n>RwWdbG;Hq>q75#NZ;v*Ax zjP=Q@OW1N$svJTXW|31X6_T^8<brw|&`Ja}6=^4qojTUgW_Mqge|~<AugPNjM8p^# z=v?X&aPN*r7!b1%Dok4PqyvA9oIP(f;b`dE^dlcVrNg1vWPU@mppJ@wvx}grN2zn| zSDCP2yJW4^Teg}SR_>#ve+CK0nD2V@rIQ+EYOO3GEe(->L`)GAs}Z^I>ywZ@)y;bV zVYaltyMnL3zckmKH107DsEgm2*ABkJ@e%<xGTq4vjYzj0ue`?-_+8JCH{?3tF%Y0z zh67%7!j1*VF>|~k;^cn!<5X78PbXLglbw_~q~vv6z!mL)NbNOY-+WDW&0<KX)jN%) zVS9#})BHiZD@F*Fg4}zbVlI`?1{9i%qV`yEA45I?L{S}<fPLVnk9z}q5McsU{D;+@ zt%dz><4VVi;zKJG2DZ%fHSGdb>DB~VW|u+|+R!$_%2WYcr+COlp$AymB?KW~vgGtI zM{f&5J~bjkip$m9h_=n%*VL>Rg?GZg(}eB*IhVfusz%ETIj&;xL&KmWz>RcDOQ<Hi zSLf>y#n=N=A8)R63Vc|ER+8wWd%{7ZqCTs=eKg^eQK?GL-Rhox65UYgWs;kbqU?XJ zL>eOVqo*!3)>FSnU&!53qG=Zw^rr5E3>T{>@)-EDD&xuz$o~uud}NyI8m~EC8PXG9 z7Uz5!*{M`X^L9&7wwHak(8T-VTT*Rb^XSOgD#n?ZV@~a9!z?kCMz_Q}YCHiKONf*# zODuaevf8M+T_@^dFH!6L%rMfevU>dYSFFtEKm_@mAI?G>7A$fnSZK_W8V=m4_WEyB z_BTZO>9K3%pD3m3xW_uAM*|At1``U_+C3t)#sj_|4h`EPwW^BuXwG|$UNr}g2nezC zYuVFQha(ptgmD28`$ndWNp&bmusi@)2}p%dR}9*A_v<OUj?n05(Lx4|gIYn@>Z{|9 zv)IXa`gDcOd$su5ZO>9{n*VZEjAEPzQARdC_vVi5Z&GPM0Frz%F70cgNzc+h1}Cs2 z&+9@wwrsg_S*9yT8#_j`%lt7AAJ5mGXxzPj{hpPsynmjeI$xY*Q=@%f-yilpVLD5s zohZnqits2B|J<MU_6JM4_&Pt-d}>$fuWe-Vsr2Abopw{u$vKOtkDi(^2W=X{lqfCv zq)a|uuIT%hq{zJQ9I4p8DXk`p<AXi-wpF(IE|o8b_0PJQDrS!w7AW(L<JJyN3i=s@ zksWDwloqqc#HCaM6{ZJ;q39;;nh=kOlO5f~Y6J?6t+@n!C_Z!T^uFZ)p{CkzCRdwk zeF_vhnKKEF(E5BbJ1|J`c#CH$FqP0(9#q|s|F9wI<3-}hm=_>`oR*?m=W1Nd9oV<i zP((VHaKpYOWlh!hLKv~8JXN@C#;5;X_kq)HhY}Hz7yeZnNkAI|jrTt)5Dr>BcCxlu zHS>TbRLCSyxJpp&@}S@7SaMsl#xG&b0mkX=5^XUByo>4G_LR<33KAJ}()%P7^J%); zWTgo2wl|zu*mRq6N(?_#GT-O*xhttTUgtc-%V^$}+yA47$iM4NbqkH~?SA*<-dI<e zC*5qc;KO#olqBC{pNpJJB7Nd~cajA<M|SzQvIxD6`Hm!Tnv1i9$Y;6R{~aLejAn_E zJ9d7WRT%Ul>N_!OrTk{vA<zNeyF`U~h4F$Iw~I$1E3&yBeHY8*(sAXRqo}_fh|syL zdE<;D%A`6)Y`{@_{q?DP0eR{0`jo*i|IM(2X@*}8!Cy3mFJQ+tj^&@LFSx+3#QR>L zE3Fir=9NtqHKB^D>1tU7iVm${toQQqhzR>xzGb6e>O9{BS4fXk@~Q8yrN;F(xKPud zMbBrI5<RPfp~NxpAGwM|*V}^Phgr*8k>j=j2M*;(0tHOv2wNiOE{73v^GVwNKclkg zD-hceNGP*BoQur#Y0s$PqT_cn?bq04;=?_&^aguFk-zdDe}-?(4pKDi&2i29l)CRv z2=x*QFYBF`J}OFp5VA?&tr5%`AQDh3Y`&Mhy7}7yVO#2N9$93Zh><3}BKl8Ek}p-G z5!Bfgf`GpJ$Nwl%3U+;_;ok*g4M_=ed5L}L+bbd1n3;&hn`s|!ZZ^Vg1D37Yb!Vjk zJ)yY>i`)GvbKbT`?e7y?k-m0{`Ikafi`SPo{&qe-@uYm(Rf9j0m>${tj*Psnuu;Ni z*EIhOyZFeTxq}Y0rHUV>2wUF7SN)OIUnN*WY*(2_a;RMW(H9dGVXajHJ#guJ>JQ*| z6hgK1%mA^(iN{adRq&ntqD5|Otv)JxgIJ<|C@e2-F71#clb?B1Da9iF)99ou7w!l^ zH~t8e`g08`>aRW_>cP)p#|{J-zCKXyu26MmAaU*6HQ)WN@Y0QdJ7*7?)r@JHN14?P z_UFCO9*Z0dl2oCJ(pcE9j@R}>G!$M44F-t@H463q6K-u3vZM;pA^ROk_U~O2Cv7Kh z9DRO5ew8NP^|OYWT1ZU)a8=`9bk4GLn@5jER*ciST(apKk;h(Jqp~|JY!4GN(!i^< zQAUW}zKz!<P3Z^HrXEzNY>ZJ0LVP6Y_?)Wq`fpY^yg{uC`88%Qj?Rod_UF6wOEz}5 z;8o4VtAQeP*6yoG3O~+LXs}7GsW(ozMl7VUl(+V-wHdE+)IMC0i-ksiTgEzMnma91 z*Dz=N&iDj2Z5@TCA=VtVGojp(ZTslQ5~ufXL*#%FSz9KiXN6Ca2#3>9v+1^ax4j`_ z7$ysj303vl!j9$OP<^T!q1=XjfC`lB)++#*r<#)2@1U6H%T6Kr)w26QvUQ=47IcK| zGHPoe6*_IecrfB@p7whOE*yTR5isY+6&Q3ZwwyDqwYSX|Rc&b9ONpr-)1s<bz()2s z=1lA55Glxz9a!P*SgydIP#B}wRH<ZBumdBmQ!K2tgFZ^(NABc=BCEX7xhqvH-vMxU zoCZ!)SQ&p7yNdSpznyC^OZzvgy<?HF<H#7&3$iX01&%ERu;Ei9N);&k&<*kU)iL<} zgjQICvrO?F<0SKQ)q+!HN={9cHwYsRHSjstOZi|_>t(?7)6VA2iiIY}8LVNcY?qt; zROt8FrAp;ag=4PyjpgqNs?KeL6;btezU4JXs~n5P>GKIN5h#$AxatAQrIWJrY+-?L zX=)s}XJLp=M^hvt_Fi8nfUO@AE)J1KFpFKF_h5nEJ$i7lk!W_Q1+c6?1{d7xN*;%; zj#vp=fbMXhPjj!W<IKnfL$In#Vg+#iiTPY0(&Rw(sK_CdtTYKlpzqF{S(mm4h>HwI zU?k^-FYwY@+50)`vHwA*mdUX5PE%y8;<NF#Fy%VVSENY6zg3=MUw5CAa&h<~TcM6V zChAn@qb%ger{%@)hf{|RQAK>b=8u3Lp5%f&ej7#Lnq7pHm3mK&H%fQ-!TsV}|M((% z(NC<p6%R?L<)96CIxxT(0N^x-mo;8g&#H~UJappJC+QKqaYK#lX5d?T(pgotEcoSp zpnM&a;Wm6`FwygD(${88^6&T0UYs<4^S=kK7LW#QZY6Kb-`Ol;4dZ04OU8OV80y0K z!lF|H9E*s3+jZ!~ha9=1vXf%6fbdC@%TrMUGR>3Vt|`8ISr0iv9XKYcDQHH7-=WCN zZrv;VH?9)7U@P}RY(KD0|0s{r(H(=yj{sQ$W?R6;iwLT!gs2-3^Nn!{y7hjBIi>4z zb=2R$uVzgaRqhYdJOJ_#H=A`QQtzvC6%t+=RGm(GYqmA=-`9F&tK=VDy&Cxpy}4#n z5rbqUgY7YlLZ8=3-C;>>g3yM#W?%VrM6KDe!vM#e)Y&Q8tjIpp=U5|gw8%fo%4a=y zK5EZWEP+!4w&Lf3VRpjTX?dBt{bmF+8myyuo+Y3&%eAr^IbbyZ_{H(68&9kdqGeLy z7v?@4c{La%{UKEs-uFVIOu%$Q^2Uvy!{7eR?O)k7{cnHOmO>Bl<$@z*hKzHL36cc7 zvXp;cm6;h0;a^UMt0a%I4OiAFkIL>j__>-U>ayMCB%Z{MkKe)_ZP)W6(`StOYgpkV ztT*~u6nB6_1Xk&0QfwSBuP-Vr2>kRqhc68uNCUeJ<YR#EHNAC`&w=CgJ-}OxiTt*% zweLHt^ER2^#N0I%qDiDxnmbvn`nllgFPUPjV{4+fuDv<&U6Q?`)YfbM7GH{cLL4W$ z<ntD+g-kY|F`qw_ahApjNy^hVC@NwP&I)KNEMPy3Cv>iMYwCNYu3|BIM!<Rx$q2^$ zIcQWbExK-q!$2)kbH=@<_gt;3lLVXHQ8<wr1y}Q83H0S%A?m;jTcyz#1<2~zvqd`S z(W*Rva!b?hTVW^Pg(>qs(_1QG(e1&`@vh~z)hlzwsa9;#{e8-&p{=K}+vk-+Mln{A zB}%8dDqDlfF}5mW!j&p0=jTfuRXBz0obY=@dR(=AW{6)ZCGgq%EwMtnwG~#v5sO`O z%wE^Zotky5sH{}j^WEp^{~}RMxrnrt;3|!%j<91Lf<cX0;wXxf&;h1J7i5Kwju<=8 z2q=D$5hCgSg`S!4G|Eob^JOg%T*i~<9v<!YYj+5*8`)>NnH<ybC|}6s-jqbI(K-bf znvj3$Arp5`9Y>3yNfPhs?v}WOIknUmQt@iWWtx>CN@m{An6DLQ{St@{is%B{4zu1` zf*xbbpUSLmW{FRE<2C`{_d+T8dP0ALljQ!&aKR+MMp*kkPwXi+EE7&bmz^!9#B6xo zT`W>*G<UJxccDdF0Pd0T0z0*qq;%q(f}*PT<G=8yVjq(eiE!8B|6ZC@m|U9@e8z<< zkw-y0Ya0H1@*N>-T|RmDOfg)6K<s8*E84p}Q6_dHT6bJC+vI!gfKb^Lik)ytT!PBw zi)3oTkM43P69Hc>v;<a$@2Mq^!dxVQpksomj$gbqhM@g?WLL$DY@^EU7pk}4ifeu} z_H>{2k5d0Fh0EWKl@AW`kEsr301e|qtJ3I~rf=vcuSHyI*i;){k`%H_rt!JPj0uN8 zs^#=)1YPR5+z$?%lst-keHTmpVt;k%e^obCtl74nDs%a9NMB{8_mO5<U5}svC}Zv@ zC4druPhbk;diu{|pn<6gfn$einA(XPAGIF?7@5ylJ=E8nCeh|WiJPB9vE+q9x@l4L zaoy+BJ3-|Mce!3pul)l1Y^__bOx|yqN|L#ZQgb8^_o1!JSFf<?OlN$xNw#EjY_9`% zoI5wAmpwi3h83V!@v)2d%S55ZS+Ciep5xsu+MhFlTc3X=HT^^3nWQm{h=hsmG0v&u z84ADd?XHJLgv$<(ClvwSE<%fSS^G9#LIA!tgKx#X2@7XP>xnmHlB`Y_M%dr_#eJ22 z&u{sPN9<rW{y~I%D2;!6p5GgNh?A=fWxY1M5~5fh0IJBA71``Ga+Or=V&1iyV#*vl zHJk&j-rfMCM5?TF@18g%rk9iYGeN~GO_Y{!w`8^|ZKL5KD*F>&u)P*A6dKvoPBY=~ zrYG#=E+*+7ea3lS>s45i8=BWpFzD{`tucB=DUN63QI;s=&tKqRQu?PO=cnQtUasAv zxva?6nrsRijZS#aK+n2lie+rvQPgTgQ{Cefj;6j+yu1FGcfepV&=$=`2EXdLQ$Skm z*{yvjMXOiT2z)P*n@UaiULyS|E8O~og~Ng1(y+=AxF(t)<ORY41gvY0{fKxNYgzf< zSdoX8`;*5%`E4_WZ(P0ou<NP5|HJFTJHso|;U@d9fH}wIvSoze@<a&6Q6-azv$rF% zH4ul*$@sRdEaDJ1+XO!LU#y$<5$6rY+OHg9S;^U3@_Jqdgs9=H#EjS|^DFxL^BVA0 zsPKyYdBf-)W!8a&=sy&V`vEY4EdbPk%n@MSm4?^_h1<p_Cai@O1|`B6WbGX=GR8$J z&Qf?)F(4bS{^-!hy&^Lz<1Nj2ILU(_>fCIVF^<T#V%t)Nl(Im~N0N}G7y9fj1rgMX zu^qu&;GpvvXtw}_X8=5kh(5_R4Gd4Ju}-?%s7A0!(LJeH^Vrcy*&a>}8he+5h_x?y zsBqzGTG!qV@JJM(V-9Q~1VmXvboNYqv~8H+g?T_JV2?fuGZ>MyB*LCNfGuQ7?Bq(! zjDx|i9qZb1h2Ge_Y_e1zw^Ry_2+fOt?1BH^WFd^R>1Z{I*P(S(b_T%5rC{19=wVwz z4iV``MEGr?J(E$#0^q@0a61kvlZb|GTei?5@BWD6RY|BNAAzl^@#EF6QLVh%;++@4 zDlc$O4?L}c+T9YY^I(6dF|T<Tut#vcKtj2G0|a}a--n<=yE>5lD=>2eU<Wl<*a)1k zwi>Pozq3bu6k~pUX!C*`;lBvp-8TBz61U!$C8p{Zt_NDG1WQQ-TY4o|bI=U{-<vh* z49fA-TgVF_@^2&h<QD1}fb!fz<uFlmzlv_;=!y2(oohT%i?@HMrw^y+y+SLxwS{`U z4qe~KgXyAnV*<J-OWYz1u4IS(VB!Fdq^ppj5=WAz12ZQ&N*E=!k6YY@ODx$6U&tnF z>&I(}$MdUZS+Udv5h;(evj|Pn9W_bfo7J_RaYZP;{1{{#K*(4@<xCdk6OiXQxULvX zTQ4#_2KD(Q=Hv+K=0i{o9!fAg(x)$sO(}NUEeFxmsF&Z0v3PHZN0RV`ygiy8nZYNR z6yP3FKYd4VD_QUlQ@}R@dddju$bo2YIZ#(%YiQuHk?_kbN9+7>-EV3~=c{hHkkxre z`9(eLA;q`yS>YREDpsUBxpuX7=aT1>JAYMgZdMZ^d~KXU_q(V<5b3W159;M>SV0Ar z*9Mi>^4|@ryXLFfZxn%cisPOTJ%jXGa|~UP($+W9zmR_{C2>VX(}5cbFJta+gTB}z z3nbOc)tUd(k^B+>cUFM*Vqm&42m^+~)(<mbwG+59#653`qe$`HtC|^Q>8l<1s@$yb zljk-%&WWj#GAZavN_k!i>SPQ$aF+`Y-qYg{RboNZTE3m>HIQkO@(mF$0IAM46b>Dc zGCFnwr;9l3re2TNY`qHVj0o8Gr@CUA;`uZh8wIz#kf@j@H64iRQw<v^VA<=_uw9J6 z<oR;*L;Asoc4oNkmh&ojoyil*{owD(pxqxAQY4z|r#mRA=lDHP>=D`Y0JJO#od%-) zw%`}G&}|%aGNWa@H61*2!Fr(uQ|l6B+Ir^l5&iMv?~jf&zB@u;HdyY&JB$culiL!e zyKj#PGOnfO62orgrx}1%W-xe`DL8!%{7+F{C8$_Q&uj_Z@%NBK*@R`tRq#X>_<FG? z^Z+<Afy$c4$KEkb+|@zT)yf@APo;vWY5>#8!MWF+Hsg!H;*+{udwv*#tH-=<On04G zwYUXSl=G-se$)ylh5472%)P&C3oHFIBDg^@_nU&k-va8r&;ws#E^P{DSot-qcK*N% z=fugnKPz+&aK*N5npBD_O@+IygoT3CfEZLn3@Ve0SM0~9ZP#RgsDoU1Ja8qIgDYJ@ z=58HM(8+rFH4fv@^QJRW{0dhm%L_qDAHER(vaaEuqPIEI(2yHtVFl{U^9#0?$aP&E zjT8JkBH$%d54#N2)PXAPecgglVj3%`nb!EAf>;i-roBL|hkt>__3rt5AjN>5RUb&Y zBU%=<8?2W>LAX*7AuFg>m2<H%e5G5+!#c<yB0P<Qj^y$+fP{DkstN5ifiw$nI8ybD z#y9PlOKr`+Zg%!(O2cKVjMyfGOMRO9&5<}k?Q$ePP!AJ@$%9bS5!n48g>Dh=WI8x* zfY9{?NpBnYVh10$XGZT$wg0L(GYP&3x^0m{5{C}dZ8Kn(QQw{*?M4ucuG$0;6(7Ub zpmX#<4BT!D)y3uG#PA6>wruC*#*egEuV!i*#4j&%&*81~4e|mi>JTo8mm$E|fR*WM zjkuXS<rb)f@lE}|>U(yR-4Vf7BJ_JZRC5Gs0n5BG>0`eLPhK7hHO)f>a`bn7C4Atm z%tpN(U;GcLBdS>v|IL6$hfo<r1dWME*6DD@U`oHCeR-JDUcRYbq!cvQc@KE|Ow8d; zc%8BRCoB+`+<IrH3Cn7@zZSZGoGCm4ql%Tz*x$)>l$XD8MxF@WKO1GLV>4<nZaNPe ziW~ptIo41OR`?d5Gr28n<I+gyHq4v|$W0Fz*PLxfodhRr9q<^(6Qv`VBPvefv6kqx zuGiN=oI^Zrbv))*Zo^eG^md@tf`Zr$&@vB<3q@833g#B^7R=>;g2>+{U<Wlomtj~b z-EI?8s!oL45T&Fai5ct9$|O!U_zmA2j(qKAS#vz)EzHd0xfr;cf4hS=?KZ5rla7jI zppFbpymLc2{0_e+J?w2QPbjz*`a~>qqVm)-gsg+($<K+L<q1p({$>i826!J<H3U|G zJO6XI9RlwNgmoKc&Uk~aiw)K`LGRPaHy0A`Db&?$llEbU8&)}BM9<eNidQ2Cs^CaF z5Q#6Fss1x{#;mTs-7(*kX+1h<wcukh9}n9egBeLtjU`3r9;&)JNI2C;%tKT^gsIK2 zqpKk5BXCP1oHh>|Ge{iRc5&9>T-U!~J>@c!?X_YmyyOjLeQ!SlSvsN~YOPy+%NOq# zG>XNejxZ5nOq7c#k`5wc!P}9&dc*1c{M$2Zm%1~%RP|aMFs3F|*fp#4uu_U;t_z*> z|MawmYVcP_z?1?}zAmY*1HJZcVY~wtd~LFfD$${;cx}{d!B)}M<HFBG<k_1~&@K-i zY$VPETb?AMj?CY6;-XvvV7LbES6|BoekZMFuE24!r>k!O)2l)%YT5y8iW<8(;07mM zjYfu{M{(%fSO0X_m*!s8UKX@j7mOr^!IJviFZ4OCIPBkgv`7Q9ld3$$jQCmYDHi%k ze(|*=vcr{8{h;~MA1@A{<N_edbqj9G?R4M6t8XEL0#KM~(zj<cqZ>=PvGM59;uk(+ z(AX&iJ^((-B+mo*m#?h;Nt}Ey_@Wnv-*vkBtSU{OA7FMGI?pRm9$IV^w!VEXwsFyg zooFWh5G<)$Jze}{>#w>{*@Js?NU2Qt(Gi3#CFH~wGK{kt0gBiBY>8Zc{%DLV_EM~2 zSo{U=NX=z(p_wZj!b6atH5BmT-p<5JG3(cY5yUVDS(q-<qT`Cb`FvmZzC_19!<Uk) z1k=^}ZWrvr8&$Su{HaKR*d8#&MR3&9m4eI+yq548xyM^E;==Pm{GdSVlWQ}}wdAnl zt9^Y49$X^q{mYs_1^0DHY$KFRfjComI%^w`|4HbM@jsD=e!m%&wxPjLcI6ERVp*-@ z!yqAb(y&kJ_VZEF*U#FYY0<k}L|E!OEfrMc3M_C1LEroNT_2Saa0=Ezp5P+m4yWr^ zBiAo3>C4WZJL{FJwqBBBWn!HQr#^%?Mp3K-o?v0iIiE=9$-Bh?<s}c@;{y%09K7VK zZYxMVa2+2agY<crZEl^On$<>8cpQ2g9s7Qny^6h*Qum1#v4wPHz`c9F@W;ZhMI)?F zq$n(MHF=}kFSm5h=4+k3r4}XiJ=e;n2+XzwFOdS^y5{5<Wc8}xg8J8}+Y<LK@bA$; zEoEV9^^(`b+C?}J%@tV27nl~&Rpu>BeG5wEOt~=-GC7V5x#7M7?9vm1TJdI$&0QbO zg_rFfs33t8AX0Ic13Ne^rKuu*jEGc=b{ROw$$mJh{cUu{|9>S1>#&VSm|DIm4Xtl( zfJ3fNZMYW?3M9(@ig(iynA8W0KL4031r-ho9wmk;&#e3Y4|<3Tvp)nqM8S=71RrU` z%vWG^2Hb%IQv{(0S60sFA*>R^tvm83Z-yKEc{BUp2b|eE`88zoE;5?qA{bbF3;%XZ z00iJrx>XE!BohUx(e0maq_JV6*4e*~7Sc3*fRKEX9I|kZ6QF@-!zpDf3b3=H+nYNg zt|Q>ejg9157VJy>y#D0DyMtV6j)0=iQv1P-UBKium6}~3A}HG(P7Ou^L5CcR!bjKn zbY)C;y$JFS8rh&6txAKX*K+Xyi--u?{NLTrRoYNxD9<7G(w$uX8H%~k<wlxOw2EG& z*SzlNSQww2V@1r$>pLiYH)-6`=g~qj>WKv&9`Fa;7;Xu1z2E78(m`5eN=z;e&<TNV z5XnLofJv!<^5N&dV%Mk2{=j0sys~s96N<#Q1K?P3y%4|ur5;rikhNrxUGBcHTkab# z_^Z-qP5+=KyV-MYKVwF8k?&i<qnYY&N7$wpHgLIcJ^5m_x*8Q7Kq)P}zhUv$8f8MD z!jXvLe})+;pcJBSXKiGuH$6rY@|(-auA4+jcsVJTWxW9uCRFxs+e*hT#ZI36y!#~Y z{K;7m!o*mIHzLG?!&zpZ)4fP+q9<PvM!Bxn^^DTAFPZ)I>r~#2D-9r&sWv?hH7x0^ zp<U6SKj7^j)|x(kN!vs?T*r)Ls?o1Eot(ud*A8YDWNI~N^zsSW7~oV(Ovr`$g!te- zE7Fqc{j854u@{P7n$xdjaXAiL0>V`H?s7t^9akcVK!@{1d)aoR?K}ySlZ}6vc<6AN z4EoTiU#mzhQ6QY!DjqOfU<M>J_0Y0G^MU!~PMan}Wgm6H0!2;$`FvjwWzC0VeUXe3 zie#)g{{8x`^3w3z1~g9Rw;HTa8~Na*?ufYBog)1)9*Iw?2?%JyrR=J87a6pBt>%k0 z6N3xL952r091ROPh5M^tkXiWBK-19B>Y-ipSuVUOj}`6p-6kg>eEi&7VC$WyU&h0f zuybhw_9husftgUCKxBg_9_sa@Kq?sw%Hgy1qOyq$TC7634=m!0x@=1GG3B1Eat(Rg z<UqLcbaqq0jo)!nAuOX8WE^Sft^+CKPbIG?RUamg(}spJTy8=(zHN<3RgP)y<1SBU z6BNvGBPrkh9)G}E8~5Wb0?Ee8E>4d&-#>x-EGX+RkAL<&?|bsU#K-?_>n{5<-mehF zOU|;U)DvO|C^-(3fGKCp{xB>blG$+dXz;o_tu!R{$DyEpm+o7j*RoRh^8W9&wLJ-+ z!0UcCvi}1{zLGK4ldJR4EqD&y&<+0`|Es${Bfd_EykPV${la|=+`TIwdyruSK9OEe zFkZHUHRzPok2q%vHLvu1*5w?AuO`9r^BogL&UQ1DVcHv1!3lj(atH7QM;~pk2jhY6 zHT?0;av}G|g3I_jn9>c%87}jt-gb+oj|%MO#v8e>5_B|8hlYMTA@=v0AkJ53ZkQZ2 zo^Rghm-}soTF$$jynT=;|BT18PZC~iRIpbR<_Q3dEYVRFa`A}AMYZGu=5J$7{sjoc zBfpk<@|fX6@e7~Z^`S!S79Xg0rXYoAC|`sn?_Q8Z)2+{3ycVfoc({H{z66Ev0Pi@g zTo1(81@wHB=|1Q+T+!Y;U#q>wf7rj5DiFuiK38);roN!sKWOvrjZf?GVRhJcB(xe2 zVU`2Qa}c{WA;|$1vdjjM9X(-c5$aa|Y-!5!^Qd%c1H==mD;XWag()Q~s*f}6@tN~k z#AT+b5hYU<5^yuEY8t~(IRjW-Ie4#3$+?u7`S{1R`v(jHE06ftfIqwus^JivjYbpx zW_yJmor(^_E^B{xYs=am4>rZDh>OrDN0s`Se4EO4Awn(ZcrHY>6(`ZLQKyEt?rnJd zz5SVRCRM;%Nr&T!>j7YWJ0&O!%I=;vI3Tk_^J_9}GweXsW*NQ%i9H%rU#FpWN0l+A z*%X(j@@+Ib@(iXqr($jNM~d~5i-I#$Vw0*Dhu72kQq!^8<=kn?3DeS3RF9Ac#KT2^ z5nebT?uzOIM$g)M_L)4KMCgu7)xFKl(yL(!m||%`y#Ywy#(Py&^PMtWTm@eW)^9L% zq9XJ=Hu1u{+DL4lj^&yGSHV{0@t}L<n2rHqbvZ`+7=HcULuH9k_F+=Fqr>$#%7+|? zKvROL?9y9B_L<GDhRmFLzVW^a#S<yYUX%7v!+sqI5FJFQl2G}iJ{~^G$5@2Rg#d6( z@dp-8cgd2%fqc#@9|^mi9LW&b^$|C4$@UNh@iwT@EqEMy;JrbOYGqhHafS9A`E~Hf zBTSFXpCh7<kwNSb784^|rYJvlkjouUPz#g*o~v-G{qB0`LIM7_BPFb&$HP`idLMrW z7ON&O!|xs&r3?n0{dH;!X+Rfr&)$2S?L0P|9@aZl^^4gjLgl;Y(xK<yzmydNznd_{ zt938ZcGe-G6t|!v497A|9zB`7DID)`Oir_?sA&B8@y6GL>qlM3YgK(Q4sm_2S@Q}) zKSmD3Wc!6UhWUi;dyN#&-4TxK2|y?@k2xIU`2SiYR)%b9R6c!>ohsUx`-s5icho_s zO3$B9&nXo44A{*U!*yz^?3H8&nFuM%F>D5Au3m4fEWouUx=A!sjGezG^fP-N>MnFS zqkQAG8oU)SIa{1TbCNWGn*2APaO1^AeL0K*{dEWg>(0&m?b%{uyiE1N`DXQ|gTUe6 z_DC9K|3AHN$$xfu5TOk4<HCKk9nc>2!VlqM*oY3Hz8zGIJfw^s;>&oHdF+vb<cTyh z^7q<x`>WmIBeKoc`&Ca0M&t0$Db{et24b#GzTqUwf5Y@T*Y)K>0g<tiq{)li6B^7( z4zDAfDi%?9XfW`4Fx-|?)!+TbO5ay6;d~v``bvzi##a1!r*_Fv50}6bVU2uo2aCCb zmYK@C-KyAgrdtQEM|~|FvbnAi66(zO;m96Ic&;(i6Nn&8j+eU;uh!FyE61d{g8tv? z4+=O}HkAgi=hV^WoYMWrC`hBOz4iA)rVlU&`__By43?>aOaLy+fu}}Z6$LZ5U}1?E zzwx0kp#gjRb@s8Sj?rHYXSU$w83iFqUw%ZSW<DHb3UEoQmNp^sud|khinW40tSv1% zv2TmMeF)o){fh>y|1ypDHuj@?zD{H<y+v7Yb|cg0vt9&d%C)zpcGmS>Yuq6gGJK#L zn2NFh=m)9cN<E3<COI$}dQIoXDnk{cP&Vc^;JRRVmPv?nW6LZ<zQUN##MwcrqPt%C zkbOYk3IKdRzF%sXx;BIgGl7YS-)vG<-q*xxKQ5ZXRIY*Uub`C0K2dq^MRv8*u6C#f zbutA%qK|ft5Okm$6<Dz}lg*iYJt4kyy|OGXEDP*jWOayi6rba&9;<`U7&6igR;JJ8 zfvpZNaDSYSh9~R#7_FaN0})9!-3o3_vu}e3jg*Bel`%7m^`PLq-qA79YbyAQlD*mr z0;isi$9%A~az`)PacLT(AA_v^#^dQQK!m$rq}}{}{pimwEANK8(Vew#0aR>|2AfyX z#c5@kP=PIo9Jd4oX8tF2mnB|W`^Q>&izUj|R^P;AtXXT%=4Yu5?;guWm#N_Om-69~ z#;kT-w{-a<>G;|a0kLMK-!R}*Z>>bLO>)tJvm^OGk0YcR2P~!84aX&9hgiE^7SGbE zD!deGI<>}cw6%3yQY2u~2~;j`g4<rMXU<#ZG_$19gd%noVEgqrUM6^ywL$gBhPo!B zlKKr&9PQ4mcVzYEMVr9H8P}U2Qwo82DfPRt8dupATRVbaWh_s*oAg1#ewSd?Sjo#` zPc(4pEFNzwxK=V={_BkH4_A$xjbgHR_Q_v)_rF~`^Vh!D9KF9O&yxui5pPb<#yk%% z6YXG0brm<5pQTw(6zuF-GZk8`FVtZ9Y6z2Ow`_7oN_MA&Si}`r+%l?VM1*^%wKsA$ zIi#ei!r09#Gj=*ZV>bV)u<-{qnH(KV;Zp7Wb&LUglC{jMw`$Ca(VpX*I@AHNAfnzT zm#i>uOC~rzt31#^=VJw+T$zQ`OvuM&elZF5pJ&FW^o?`o?dGKKdR=f}!1)TS?_?33 z+BB{{1#DS#iv}U|iaEN@^|}lvE4qE|>9EtcNJnlO%C}~iJIz1p=k({sZR7Im9k7WB zDYQj;RcyR++fv!ThRd;LGDg=A-l@Cp7INk@;a=A`WP5h_TRH=s$N+#m+6YvX(bvGq z&)DG&c0*wQ-Cb1Bz&quOsJa|>ab^P(pHhc+e_VH*N;~r`wtyVYKwor`Dn_?}=+t@S z{+LYhc1MrrHf!$aksZdmh6ans_=`Irqk7k9>|TchHRAgIhwh9E-r62}NQ`AfQuu+B z1KnQ3F1i-?r4c|Xm$9(SO;otabEEzbK3he#D4s1Vc4rF~n~qerim?nv{WN~d*EKxI zIk}Q2oinRz;ck8NP8I`o5P->Uxt-<6-_x^Tv#*niT&2vYAFWF~^3nfmUV6S<Jb>GC z^1-7_&`$>LTKjuQeMfQ4>{1F5dm#eb!WLb(+LwtJD{h@UKJ&kiOI&eU4&dRr#|L&0 zZIpaCb>pn)c2*$6o!u)U8RF=9@zJiXrrY^GBn`-t8Jef2@}<>JiMlgBJ9dZIiT-bP zUy!CiNSW$tx3NnxTW(A4_{BqM9_)t8@;TgG+ApX=4aDnzo*wIWM1>#MntKVnCvxZc z&w<XhT-7>BWj=<fI66~<lbtr_Rs2bbi*-w7ph79x+A2`V07#3Ow?ED`JHzGZnc>tf z<7`986=7$#zZ;7v+2Y2M^xCV}WgTwE=b#@H%lI_i%-4Ika1zM#3x^x8R7nJ|m^Ytr z36RdS9Zjs|+U(_+o5r$c=wp%=F-Ij{>%+{K5n+2k&t8;vG221i=c>%p={}7Y+33{0 ztH(fv5fPU3tnv?{CchUr9@gFs2(^|!K5awB;=G$myiC2AJz8^4;2x4MAn#-{ioG&@ zY9sH02pW^&d;hy%1K4-11%0{~mD=um!wHoLvZI0AK=IsQ02$3dJw5Ap!@{5T!q44l zHfsp=>eKW4{D)Wnt8E_fOL{%suwwtl|FGp(|D1W$hRos3vxnE2hq>{G2fzD&eB-y$ za<~zT21x&dBSHWG(4YZwz%GOj3ZQoZ2wIxn%N@-^3#s|>dK>TLf%5hZ^vg{nNKyS` z&v}<GOqLR@3Z(7&nx`sM+&cZH`dVhHb%LiGu9Zmv76$R}pHKC--9Jys;*+r-XkWNM zuTb-!9_V<`wqKWa*8WQ8!!A>cz!%e3x*lH=Kmd?=O!t%i@CTj#GlLhOU5$A?eb(V> z&x;$$-`>BNxq9i<Z6*x+xg(${b1X|p{jkQ?77Yo*$^|43=}~zIynN{FwSMnexQtv4 zjyV9yLhu2^-a6)o$KC#d?iO1H)Ws5u4=?#e5~$Ch7@W8>XJ{0{S1fi=y#7bTB4Bjj z9zQ|u%ZFvW-j=4tFJN_sB(N)Y@bLev*Sio+_oZ(J|NOX>a?+Svm-PFOq<5R&i5R`i zpW6tPm83EfydhO?)0h*<|3rBqb%Oe9KIs-FoD?il(2F>}aTiJfaOCC{t832zCU6B3 z^OS|^YzHGrM%K?yiakQV3TZ1&=BOez#iguNBn?Ev;qVAf8MJYOOZzU8Eq&U8<}I0E z<aw>81hJ`Cf2w7ry6%{Kc{xKHy}b;f7Nf1D<jvP6n==CR#DcAG3=}ib^KFW#Ae4Xc zHHD|y0R;@CEA4~?NV-*44w99*bRFA)mk`WGM2GK8f`l}6pkuzE5>A?KrX&at(5+S! ztXnisE3sRse1u&F6T&YXyLmBGMjymQ3p7K!U=O+TP3XiCWq@bb$8iV7x$Y3&6@a3@ zvvMqoap{~fIqD)B{zO2;g~6!fbD0mPg}GL0UI06oHk!Z=Y-IoANA*H-lOOfKy}=%^ zgt~r@$f!rD4$X=}Ni@9vf6gS15?{UqrI9~E!tEH!gFcE20|!cP5`_@&sf?$CJ+>bL z{e-Ka36oG@vsG8%CM-kx>zs0NQRE>AZhp;r|AB<BGpLks&VCbRCl^==B5Gl34^Jc% zWPok}v3uraLF#XnPlmKbU5X+#o=@?+JB(s`nK~?L4U>A2u4%jsJ)0D5bMy=H3I7Uo zml)Zo&+AnOv<v@a$$p%@n4HG&O*m=iWGld2uRIu?QeoK<V<m{eeAK{M!{(WMj4hrZ zV5BV&2a&G2$~~xlo&M@$|0Cx=p9bHR{P}$C#xfzUQBI+ol4<748G>dM4ZOb^WOR;= zz5D1FRnuO^>`TSBo|~VapD4BXDeb?z2fv4HWl_y)_Qq@`q_W}Ps%XfSoG>f65)|06 z0Ksu+O!x0|LTKz$Bk(^=^YN`a_tJ7<7aqGepIWNtr;g`wY^k7Pnb4~O>7AjhS-$;L zkbM!*8OuwLCd!ypNDx%y%%bc8ouWWoqjLRsN5SyEZ!&HM%XmD_-W?_ph~F&$v-e6b z@yHIJet<H<s$}I{j{r_0Gxr1TF2sshQkp^&08hrBJ~TV?SAZ!lr?sAeq6YN>L=%>Q z3sF6r9Bj|SiwumEBoDuqf#|42VA_iTo=-b6b0SMz_cSmxy0yGvyYGFj?E7S4D*NrE z5#Mo?`3g%A-ZVjubS36Uv)h?yrjp4ju?<d96I;{Cc5LK>j?y%a{Lfxv>1!2q^e8o9 zYDR5&vHEJZA`r4UlS64dL-1~)ROWLO!I12{og-un8TR_7BOJO}BftAqz-XW}gK2;l zG&#^s78tK>u~ybcsB*e5#}hrm6*aC9!Bo9<tnbJ>F=XHF{Y>U6cGr)--w=w_0Y<n; zMIPmQ?frbTK8e8&r_%Rnuz=OmP*q_fHZJ#Mg8+bjuH^r6+j?EmI-}vWA9~XZOw?Pi zK~j}~J_c9^WuE(C&7(k=z1chQZ7|h#MxMQU6LbYj_eYPV^0{XcHQKOcEgH(1_p+9! z8x9Dwe-mgB{1Qv{Kd*E2*JFDHt&lSKXy-)^Xb*5Jnw$gP2?yAN8jgvr$je~|1^e!| zstI$^B5L#kHLqsLAHAq2$AhkpENg^Nv5XuQ;B6fk3gun|&|_Y|uRhF5pdf9rn_dfj zhCr`XJpwPy&zG3xsMg%+kgQH!GX-mR^~PJj8_*AmsDsQO-_Jw7cTq+d$Tdmh_PZAC zaro<gZ?qH|Q7kRW*{=Cq^7uK92s%1S^&!R8h+OkVfh@Afvib)*c;VCZB&d>?B`$dJ zpYKwWmnn}$VGXj(*_y%LV1sQ{+pqNwYB}GF?8?=A4b^t50v`^b{G)aE;)jrDPdLkm z2Rjj)M`-RuXzV9i_vVWNOZyokR^_FBX#U$Ak<3?qx8nOwKI~!sukPSorSBv}5?dl^ zm?rz@*QBLVet=XFM>FKmZ8!FIHlDVS>1WurxFdC_dZmcPHX3(==$bh{VO8JMK<cRo z`;>`~oiSR!_2bGX%4horlkYuuhYt9oGev?P<-xDr6ROpx32WeAzD$^ajYeq&|Mp>V zD_ZF5LItR}IgQ~v(_V+|-wW_ik$uF3drhNTBZl{8%eRP5w()f`gh1AE^8IvYUWr80 zTuH6Seg0Kls%P;#*nXG$glpTB?i<J1?cTM*7vGZ}*4$c+a))mgB)El#f=%1@0ft@! ze{dJ=kM?{$YbP+km7jgKNl=&sC_3Hzi@H&DkSiLSy1-iU=UD9eNa)aa*678hOz|g| zy?B}B7_wWy4G)q9CFr-FY1Rq8aZ!UisQxpWmFj{$#0>dwZB!@F<=M%3d(i<mneO?G z&fi3;EZ=o(+zNZW<}!Nsa)<x_{I{Pt4^&2qG`3-&S}_kP7j6;Q5Q%8vfGxEI9q>8s z7$biB)b9*&PqaUOrf+JJR3O%ZJ|&as<8z~)D32PE=<6vnpu0|fNLpL6cp2dTr}muW z3AFw}JNw@yVx%lSW8jx=#JNA&(!faQF$DBT(8A@ZPDgfm?DR7?t7csC+uyX|e~Ed$ ztJ|E@!>{pQRW4~~zvxp!_uMHyK3;eIwq6fUb>WF;5bJo?Lk%{11p%ZjTd2fpqZj_P z24<SXpViopc81Iy+%FaK?aM?ewdXTuqGJ3P!8_5G+3A&yNqzM)hmJ8!|8_;DS?&*U z`@_*7e%Kf{3i{#Mu8D^q=gL*{YPTz@AsM$1-Htwd|C8tNmg*~T3Jd>=4z&7DJu{tC z+VHFSt-bKJ<-sbjLmA9!f)4a%Xs`_ADol4MC)R^A)NH^;crv!})QLx@mL9UcAdkP9 zaCwpdRviL=D1*`SLS=2IVJ<0rx^W}M0kJ;<jwc=BWjj`R*dwW@3Yx7Q4M6^0#1E!2 zae}E5i_?iwiv4NJu+_+^Oc01Y<Q#TFigdc&BjvvXpaxIKx8}6J3V!5j%6v}T&0JrD zGf`Te-jp57y;PC^HUj~Hbu<~;glEg+Sz(zGu*)8Q;}aT#>{(&4lM3|BYG0#Ar(V9b zzGHmcrw#PprGwGLlp|jFPY(&voJ?(c*franR@>a<mW1y%QG+yVQnPJrc%E9BDV@zk z;-f^bfR7&qU26lSjs0FtoJP20`l#Tmlk;h;{O%v@0&)DDn73VPC|5}>k`6Z9QQq<Z zUjwe~DukV0x8X(0wRNyc(M>=oIO1esl4ufsJGsmxALWuSq>EBmEd=o?n!mu^HV}Em zjglCG+76m=2OHfBTpmTraG^Om#d6!acPIu~1albGnVR68i)0HM6~Y@?f35LmN~dAl zdl>J`cRVm|zRVO-w6T%%mL83RFwGvOtNjGoO+`XK3*fr2H*O|Jw!#IJIYN-4?A-@O z8DXFYBKeh}_lsX)G)#b_2;Ms{TD}(l-UOepw}JM*%7as2OCRV^3*KZ`{5*O3*W*k( z%z@(YXbg#UEhp)?QMm9)XH}#4)^Jcs5ljrP;NKQ-p05%z0nbiUG_s?v7&@M(<KvM` zkyRu~74)z>6CYE<$OjWw@NO8O*bdB-s1@4IDON5zysrqdTrHMo@A;<ufqTfwOw*W6 z5Zw$-=<tBMq%C>IJ|3)w>*h$1PFJ*-;bLo$3zga4H8>a4@HPAp1}N+R2d|Z7VF0g) zO!#Q>7n9?)$|a-k+|tgtMNB&X8Um4Ux^=KnqH!IDC6uiXLakuwyYb+vh+Fouz1y2K z*GYD5%^6-T7#GukrlPLz1BWFV1X-xx*Un3C*C6n<@hj(L_SIx|fF@6Js_fD`kg16| zxsJAU7@pRU7_T>PEesT$m^$n8z+HdDXK|paDI0V+R5jdo4(Sr+`xvaD*F$w{zT2sJ z*q#6Jq+X;EWt4h>aQS>P7i8>fxE6s|HOU`KPW(SbXW|dV|Htv!1AAfDeOqg>?scD) zT}w-Dk~{ZZA(f<Jmu=U%j&kI_awQ~5l3hnga;1_ANv=wLRXY9r{(*VSV?HzQ`OLgu z@8|RMwIDO4vZPV;(WB&&_l8Z+L7x@1rFzhB!(x61?Kg#w{}Ii7@H`d<D&lLu${SnS z^Rv3&riQPo0-RC-O%XPm#~7B>BXzFkG-juHmTnbY23KW>jiTX0NrrW?ha{^jXY<Z_ zMrSIcmG8tz?Uf*j@1pge=ZK`((dr$$cI(tvBD1<nf#lrPgwmnL?0@jmxcPb^4qrn_ zlVVlP9o1rJ%8jAMT$`6S{y@X->mQ{@Uf6R-N8&ZWK~>(}WrmI5BSjIT@#vAxOQZWT z_Lo=DOEtB5=<r|lHk=CX&+5=7w9U^*fhv#etFDt*(9oi5Ji!;iDbb7E1{9&C{Yr_` z_Xx${07#YHNCQtffgW!dH^0(C@IcF%ptBmY!@bbaP4%xOZxA?qyh~+p(#_L|;_ROl z>;&|Kgj_hOc|UFDdbG>}ng-*jw?7wb4NH~3Z7`3ui2dQ$2#<V4W!jW@KS)FCFi-aE zmfzX)MAzZkY7#4;OKs4qHuw@BM4^*siO>2-CoG^7lhO$Rb-sRin-5d^FrpIm<xEaP z7|-gl`ybHuK$^WRIxVnH#XJA(4Zathsc?+FO`+|=NZkcS@k+hD5}{e-aSb#IozYlh zoG5Iw$>;D``0(a+Ugx57ruFZ`+xb$wJj`<SyX#s#%aAtc^jRu|1S)E~NY(4GSAx8M zSB!#VCLcxdr<`mUy5&}UJ7Kd8CEdyQ<t~ELiP3>w0s|f1_aQp>Z*27N2Hb=#)hMV| zjE=V8c1t@OjuWpD7^ZcBRywiI??t55;nHK_9PiOH)wP@DZbyoydx{>KwAGh%Htda| z?_}JEE~%u&^nGYXuVwVvn00n~cao9!fyy?E=KDZf&70Bt01~J+MJq@)w;P_ERPu#X z@#vp9*4<Og3$n+mSwKL&LGJ|>)h)CkkR|x>nh{%e)Tu*5kvq>DVIa;q<egu?ZzolD zBAxGF!rte>us>%AtspUt8=cMS=-ILQ-)49IATfC&ITP!yJV~L#vE-TEkQK}L(oVwT z7wEJR&TR8}<d-xLcphZxVZ0ampc&d=>+XM14|y?c9Xs^8HyWXcxe<pB+u~}r41*OO zDw{t{dUac=x1Mcs=VfH6hH*2mvwu?8G4Jgx5s=nVS9_Rb;P1u6y}X8%Jw^067W$P3 z+CIrmIkEVVOub<2BOXp$qSHgamOe-oF*<WNBW4&!8UyPL2maxn*cv9k8a-`#HT8GX zLv^mAF{V2$Q~L_~qOdVk0jyIguu)?1n_VUOEmJ)dP1EPmt-EAx=)YK>bjUnTW30yI zRS{?XwsCBy1@iva$9(`W1`x+k0b^L5u@$?Cw?4y=l(DampV)d2^hfO9j{|^HDVxd4 zD@Y3+dZZ(rIIvPV(#=?DLaSNu2OZ7V!G=0q>s9zt==0+Y8g(<?4*k4z^m<DZA7(%+ z6BaT)RX+~n15NLb;AA;XD+Wv}YNG3t)aqM^GQNGC(!*e#0q`E^={Bl{&B~^~OjBgF z+dV4mF3qW2IXi^w<c^t#knG92r^6f3qb05~d?%Mf-93$-z@622E<6-FFw?rl2Wp%M z(U^d8V0inv-~)4^n$yZvb70O~z0d^A8K!%Jn-nu+*!yrwsuCTAUg@sJ9zF}l1ne>i z64u98P4|6Y#?+dNlo@NYM}a8k0uoOSDuwmU<f?JYGp~itRy*`Y%XC=MoSE}9;Q+eM z7hTOiuZfyLOpTrzt9MavA2z`p<i}jQGgvZYV&s33J`D=B7>~2Osj+SU2wY`*BUFDV zMQ*K>FqZqzdnhrh;#A4dp=NY9a&BXME`mEZ7KnbmSBA+$zgd=jgCS`tWTCbBfvRZC z$;gT+uOUGn^!Z<Pn=hYsd7-yfp!Uhu;lY$&GuDH)<Y(2!f*$CBGUuDmAPysJdmuqe zdN8jAeYx=_|J1|U#OFvPK!`@KMxj4sDxa`NFKeP#0^b1WH^por)jo8D%RKhPvTE5I zp@8R#e=3Slz~90~i*eRSG}?r4p+FryTyycbaNY?^h}opk%7-{1kgrY=S}Nk{pQ!qh zOyQ;LQ?ljgNc(v{oj2h2eNp!+1f;_^1rOH3pz~)TRjY4azsC!_1Cpn2<h|K2e{S^( zUF>_+MXr~tj+yxx*gX4|r|RI`4*j^I`-Q!Kc9YHMrTM3FDDK~1P4mdtu-u_CyS_-7 z`QPAW$kgkVzptUW@al4ObRW7-3mq~AZ*&j~iCwk12@gAn4!pD+Q$8L029}APsCe+^ z)2m@U&8vbO+VR6Z#F4=xy!YDAgdcG*hS{tbK{ELq&_llEHycm9B|LK!Snu~PvTwY; z>y5s=IlNIue49D1P>#O+?>z#uNg%D>`1JbifsM+O^H9=Qg+02hx$Q9Wsem`1>+f4h zS=||ga~Br8->7-Q0$wmKt?@aJ%<!fuZn*t}4xy&fj6GRLSw*P!(U^rVItM;^9n{kH zTYh`s^VY;CRPO9&Ka7_%TJ6?`0BFN|?;!dHcslUnXUhxkV_S;y-&7YxXZx?ClY7w` zN+%#XobPdh$74z)t!GE=sx8;+dc)BY@^`XWPf)pi@dC@(C$E)cKW`kwloP*uEy2}4 zV}jp)g;s4upF-DYZ4_hSS;Wu3Y13i$6U%Qpn}64LuUCZ5U;TQw(m*tb{-Bwcv<8cv zJ(_1qVn@6Gs)S*J^2f_Vm27N0za8>wdf2*j?%${y|MTBm*sF`nwQtwuK>vlw3q{`g z4y*bK1#JeFD~|=fd1bF<==g~@mizX|RL27h^KdVsDpooZJw11@|Ac~}r67NA|N97Z z$BIYq-GwdIyDXJ@lb)9p^@nHQe2d-FTCUPsEn$DUS@BCx=X?04)s>5zs{+4v|Dm7t z7JXBFZ@Dr4H##TD<PR!qck4fawK^4`{j(eZ=)=JNn0Je02DD5+0LBA|(L7-%6?Wfa zix|i!@z9sC0#tM4H(+}v#_2ExDhcw~aZv_rWc6O-8&p>u%4H8=@XzwYoT?5U_`CI@ zF`%Aqu%CyXZF72j)yz@1<u+R&`6l%Jmfh)Xy8&HUgR`B~+(i)v`rMmvDoBfT+3Mq) zq3g#!`}JWxWm=}5SBn7>$R8mC)@viJK!=}FLY|;J<0#TMw0op=f?jH(?KUqCs8&OB zKbe<!-PxF``+3&1qyRfZ@7#-^CD}OXt&)Kz!&D#LP0kYE`=m27IvRf2zyug8GYu!* zh34v)s=xE+liQ(O=9Bm94Ht!j#<3$ckGPx9K-Avfy+1iQf#PcJ(Y*md3?)gIgW>GA zFmi33mA)Cls7n7QO25}3<7SPEt-?+6^G_u)H;`$F{Y5w!ovy$W5D3#d<YEfzr~gsR zR{z`EbLz&g@koN{)T$Q~JODIAnaf{>3f+=>nX***5Qab{f16KaVs`=m49yIRbksdY z9%NCyg*gM!rMcm$7Hs_tIM6^Y%~IesGhgduFypccW(CG#2C&|@(Ri~j8~DzH8Dls5 zg`7=cLuskrguUim0V((q+E>UaB)5JxgHJ|WEvmxI=zYAaJ-oUKB0A>HyuxUO^t0CA zAXSmJMu>>v-$I)a*(SS?{v$v?v{9*0KVP+JetLyvf51i>fp_gw4^eO}e;+}P5KnJY z34(99s`5tU4R)oaTD4gmAMhb4SspWQXtuJfHsDu>OCggxBuY+I*?d$3n=$sy$gdst zcoNLTs8&LNE8RbwRUMtARhuAPeMUj^j?DU8t8EXWf7H#q&;sxSf3Itp5D`n}CB@yY zL254KSA`v4J>pdy!Z4f<{aG?Y0!~)nT!9LjqDgPvrDC3!tyxGVTiuBl0jO`4sB?+Z z^W44aV^y<A1`f_O@W1tN)u!Si$P5+$eEn!+yM{80I+z`Nu}Fa$FrHWGopMCyGXPrS zU(4}LOvm1!czcpVK;4pCy(KrV-6*g>85v`3`~9ay-^Jgj6hzOQpdKk-?%RwkcM2g8 zcZ8Iv(L=|=WRrQVeF>vVPd|m5685p9W3nJ1C=v+%NC@oNR6g1LNPsr(q$4gg{{f@4 zE_Q=)spp#4{ZM7XK(+rrfvfCF-|wxD&KPzH+xHHgsK540xl<7^`7E`(vcLnxpO=o5 zFtvRKwh5RHQh}ke<L}LhPDVWd`Wtu?&{&z3%gEf3e6>8DF3jLLXNVk7X>HEP4Bj)A zm|18gSQZO^OpW7bm5)m4_Zhw(6?xMv>DbHHw*3GOG)5Fph;b#?QYaqU>-MM8=X7Xo z;R>5yOP$8qBz8E*ntXndED~s;)_OAKZ7lAAluL!=%g<IeJI7Z0+*-*ZH_vM~+9>i~ z$<P0WC&WxY-Y-N0;IUYhda6&yR^H7t)XA7}Z`f~yD4G4j*4O{MxUgi$efnbSWhluz zalc3N5swCBJ*-6yB=MreU_M(M6^(;)s)@RhA<n_hb0HM=?vfGjFHiYXdeZeR>@*9` z`z2Fay5z~Y3p(-c)VLAhGJUF$vm{1W5I6YXMbl~i6ffQzU1@&;PAD|*ZLmn01^qF* z)7O_tg8T>JKx**`ZPCFaGl^W=2bd<KcS5;~XWcdUHG_*#>q-d;_Z%;+-gfQPm$Cd5 z@qj(MQuG#waa5i;7$2*YdBluqDh}>hb#v9OF{di!1PjoTHm=J*$T%ChJ*rf7^8kNJ z&b-*VA#Hr~+%}Htv06V-`*KJZ*uHwpx=UmPRGFyuZnWbo4EW3;YTq=bs(ZCN(spJV z9n&IR|K1Zfm8)$+-Fwg9JcONJti2*1G-!ABwo#wOjx!(pG4F?GrK?0;%?ni^{!YuL zn<=xcvY1y361w-hDn-nXnr=FzLx8ii+EZjb*OgV1ryEBFJ<lzS?zvsSc{+eZ09&g_ zKfmzV@&%1BRDi3rl1fM3&&d59YzZvm1^Y~zPMeOX?Z5JdLh10+3KqMEb3P?LPuX_{ zOIl3}*bT`6-H&XNzEsZu*r^9h8#Yq{b60}aSB18^U{$3-y%zbBKFGb_-n~^%R4;D^ z13COQrDbG#fx(mia#;J{a85_qLaUK?H0EuO<-N#Hc=mzDAG;EJUU!0Ca0M*A@bR#T zYq{;4xfH;I=3S1*{QFpIl3vg_Xc4EwSPQ7K6vor^T|0jKqL{zr->2Ci-`oliYb*}= zLheR-_M${Pc?{M_6R92@UAL>S0VfaV9l68q=ey3PyoeFsn;wO#bW5XhIqPK4V30f> zc{}YHrK-_qPK_VWHi4%%b>#JBMa3zAG1sNeu^;_g8#4RZs(jU!J#JV#p<CLNg(*DJ zV)#kVLDEw(u0}FJx3*7#_4eBNuW!@bjE@SWz=ViiZHzxPqt|C|iinf_oy&Ky+qu-_ z|8!UWnhwv7WY|UO+>I>#r_s{@YSQv`_cPNAo=B`3$_a1Z^g)IU=_qdmJNL591w`zT z&Trql$7zkluRl5)M4egv-qzk-ppwnYsvU&`*p?42sP&I^-XEL^5UdSSl`N7G=v?%@ zc2;g-^d5~`i8%*NyfdqC-8U%c08**qT-TA-6wUHIKk>T7vwpEI3P++Cb`4~sPvdP3 z_u1sV4{9npxXWx|#Ro;Y_>({7kDu1R7L#%P%r#!_DL&)rv?5o6NHEpl&{rZ<v1A~T z0Kc{JDzbc!za`ApRhkEJ*j&$N7%6G&m?x0zHM{I!f6kP2mLJ&uI{*A_M$7H54G#=| z)D99AT$`PL2mJmXGLo2Ec}Ac*_*EbhfGFG@6+KtWTgZ>ERAzb+hCUUFg*^NRu4;m$ zN|saJH_wi#C0-eOa9`tr0^cF(tYBb<*-P42o<eg{B<TFdPa!Y<8a@%ouo15K`7w@G zI)0B>E<R-OWM1dgj^C=T6~OeDi923)09ZsZD)&CTk}cjQx0Yi1j5j_T+_W4<Av<@a zc5;Lt9yxl&KCJeG(tpsZq{DHs?2jLm#NX~+qH5hb53H2@SE|B1m!G&f@;xv6$Ci`y z5yx1tPzPcB#6`#X$Pf)?58+`2=)&%mynzGBo|Qd{D)~LijKzwz@ay!118lThc>{e3 zK)=5ya~!U&r%>DgV5*P@Haps-(iM^+d0R-<wi)MBM(=(#6N~TJY&P)L<IqP`E(Pfo zm@pkipli<cKc&Sjr|yYWK`z5}`Mvb}AaFLaju!#X!uEq#3K*Ei4w7`*OZc5h+UqZ} z$}|zG4bEp2p}0)9R4*CKYyANx?I4==hLP|Q%ZH4%-nsT(lVGMPg*1BFeB(CqvZ=Ny z=z(k?tP)b|zCko6;uOu9@J=DC9&EIksAEsc{8(<`<N?**e8=3>w}BnBZV=ej?4cL( zZv?Zk*ranh;~fjtp(tMdIP2Jdsx-ubnHOw}6_%7pdc$LLv0#{}4{RGU{OLcdsss{H zG_du~%0$Du@m;U+ZO#oaYco>pX(aQ|OH$yHg++;WZv@6VrRa9#U^W2B*f^BlU6vM3 zQ`(ky+<?XP4?5`ZVb);ZsM5QWT-l#A?eOg98HMMj)NfkI5`%`0N*9)uJY+N3NSz+Z zE!Kf}j_FQG@D`GZVl})P*ps-fQ^*pl>_!I#Amq2M$_e-WO~_@#9>MT^Z2t^J*ZbHt z!_!CdZdQRlJC&W25wv&ixLKT`<ZQ%?*L}0Z>P#%S9L&5a(W1RnbPg<5p$Ic*g74TA z8(7LnKi2XIW_tPSj7O1ZYX{9%Y^z|yZ3QF8QNzisw8l-Q_i3H)QEGu^*CI2!14c8) zfV`MNdB#Y!Mog!o>m&NMA<ej~2b|n}+h!j^CI^7AMV)Ee57|Xh+9myprUq<+<*%>O z)&${z*s=3omKPPfhBo2N@gt+sj~Noy+Yq4L?a4EWeXEB3_DG*Z0Vge{eLIrb*reuN zs&zgRcKqeAW-Mm!`3AhPz0%4QcBj9r^Lj^G_<aFtC-;wl7!^j}J+Lvt&5&^L<m7~J zR))QTQ!Lp0y;&zyN+()|JoDQn$41JChk|;M&u075CV6}-aekfV$Ky@CnLR$QdcSTm zJw{rp1J#npRLr<)!l&>5N3zu8j9WDrKX$u=*s+Gss{g)+%|R0H_H*gLkm7o>N)2*N zBuBzR(1~)mkAN&d!B+!SL`?=NOh(G{&@K{clPi{Kx5p$F;NA)LKQyd=;hDbSOkeag z?qi0Z1y;cqh6`~4CV7<3kb-7;yo+3Z)w+xgOqUfs*@0*ScMPPH6tV`D%xroqJS%3T zs-KnE?foSf@OM1EpCmA~4tISCIuV$H!`NZ?b0jB~bAJm&9nq>@DanT2j#H(O_mLS$ zLI_+wxks<Lcg%0g*+zCaJJ|)R;PSK75nJXsw=(4TU?8o3tZAn8V@J#S>Cz}Dr_iH< zM4LPrj|rC+G<niBWDY}A!nm_D<=un4#;_e@qbjBltqqfNUmm`ttDRwV%$~hK>@Aag z5G6t|YM<&$?)|efHf#4JpwyAw?RJVE4vmDx^0VxGU2qqteb?MOM22n7IBw}#dlS0r zAYGT#5RJ1<X~})oZKc^%xG0Ct(N)jhgo%EHQOE1k*7h~1&mOGRn$;axUxaG}!S=Kw z@4iRCEy;Ig!TI8UB?eBX^Tuk(lMan~TX%FKu_t5+2G7sDW_1+ICcKAt`W!-$oCY7m z*My(C>(Bm0Pgr$k+$N%IavyXl!eYWb?n^LVV#Z(E+%2zUHan9mMcwKGP^QMVINjT2 zwr>BeYgmZPbfLQXUi9U^c0b{}zdlcu?;!DKyzlZP-%azrr*w?g@QU93itaQW|97r! z<)E0xtLTuPuNecIqZw1bsr?FU_nYaK>b7Ca*s7w!^TqQF|4~K*UK9;V>%T&<n@{Ve zFv87LL=fpC)h@xz?omO~nfew&Hd0^w=f*LTaB*pyZ-hZs#fu)_616%h<Gt<asZsi| z=L@WBcia?ZkEsQ|I(^aQ*N*q{Ut0~|;YM|z(USHZ^2mg7@fb#={I#gIDhn51Pvqvc z0kZU?qleYCG{y^gy>g_AKv~?9l0OUC%){sL(!%fIhrf33B}x!$rTbm`%6B>X>+Glq zNjDGbtCqfI4eK$8j~{gUl>M97C*Ex!UWUIX;N)`p<B$lHwaEWO<n&`ho8k={pUTsd zW&0JHT9QthyZu|B5XIu1v_Bv!ort!Rgv~kJc3{NRULg7ABscEAk?zN4W`3b7L^Cld z2M<EvmrL5m$EJcZ{cNA`6n<OGws4^V4AdJ|fCr2ymZSX!PMlcW)Bd!K4e`7xs@>vh zUc)p#^;6+jkn#hL39W%%^2^#y<nV`nhrgVzqn@HC1{Q8&K&s7e*#x09m^-`M2MIy4 zD~l?WsuPw~JyV0Kn-nhL)I_BhMz344pu-Aviwx?!a&*uwQV`oCi2tOgQCG%#R(tJ$ z)o5U8%Q9*w!bwiJ#`V=ZN|2Uz(?VY)Q*JTku-{7AE|MdoQuw>mxdjGPK1+Y#QJ#Ev zIc7mTEj_P_f5Jb%6<ObYwdq^*qS%Uafc}%un{#)3VX+rObi0tmeQ?^p!lMo$=P!jp zH<phacwe2|!~I*%BLFW;ST2)L;DSR#9tg1$B&_de;3}8)V)If!;Hi+gg8f<Lezex| z2J59-XtbXzn%kdke49>LG?w!Q$$Ed=gry7z@?ZL(Gxs5z7<7K(L%=@oxHaM^Z*pSS zhw@Jm+5*pi#6Q1T%TxGCYu{ZX)w3ks^SXY8_0~A|hmH7Xe1YP)Zf~j3Ld3X|#Z^{$ zZO6+i7e_in>hV%9Y^KjJ-*p^*1hv)7mu47elQaePs0YeV$OZhYsZd)gBR<=y=}8NJ z$~hXg1$jn~2^09lDrpU??phBpW|aMlcmQlX+Mi|ZLyoTove_YpJOSLUkoGL=*C>Aa zCywU^6Qm=q%-iuiUCK@s!RlT}A{G5OAb5cs#ds0EFDX1OlJ!xm>1wqEdm9Qrgh_X( zx4#259+`3MOgs5Am~>8gIzixF_T<(WFCzra@bqW+O|EZ=Ax8ZeA>CVJ%FM*!2w->F z%@0<-3Xct$KEiXtB-1=a&Yrew`SedV2z1=~yn|LvjtYK`ML@7lV!PSRuX$NLK~d~} z*<&xc14ShrKp9HC)>U1@{r6S9D8ws|TTeTX5|2+gI}F=@>^t+(->09)VD3Ye^?Ucw zQ^$9qYEE>E?X>^;GJ@99!a$55bkLXKli%yN#xI>JGYtBk?S1#j?B&+k<Kul?tEO)n zw=U?0%ewmf3_RfnKi;$I@Pf8EP`S$5-q=H;_U3CmFushp8?Zw>%lmN_C3DE{DRqg} zHU^b7<HbJoQ@FPOdF)xYa;B-7zIX9i7p0Fp3V(Ua-lX9#M=NL}{9z0tj1lHUck*YH z9pv5VI~hb^?7J#dVf&q*clMW0F(xAbV}{ka&z1io{QG(EhnS<+qW#x+bp75G4)u-K zc=n;gqGq2ff0uB7Ray-_+4+JMZywqo-6r7AsC|9qa<{-u){DHa&8k#0>%7x=^OAC` z9>%!_4LU2#*f`j$(Ipc-GkfO2gIScdi$0TfXgiI<7x|sBGyI9?_%_W6#$$ly**`H? zqcdCXpQCpny8c(fDrtdE-x#;Hus;I#{E56i5_Fw5o}lp0l>(nn0bk3$?|QDK9a&4Y zew$_>HvNkiE|zrihU-Sjos37ULlfJQF%d@@k<1$W3kEx24Xfm?sznWi*|u~(J&>pR z>tpyTE2%S7b6{Ki=S!VPdA+DHz4O|RPU(lV)2#Vf?m*YIyUTJRukxOI`@(qDk|ECF zbQ=!_im`h^9B~|$rU#=tP4Z62?Pg2t2FCDcCDYSyFainRc80f-pZXt%L7bBzy4^f@ z!O!DjX*y_#Gr;RD!SGw8>7e%&$`IA<cwhFZvwK73la47hq<Tb-p$q#{$Xv(i%wg<t z1tjY=$s_)i{)_@lbS=59n{Uro)8exSbH-VB@wPI=$o<~Q@XRcqvG@~uHj2-NJ;f06 zHSd0L+z;hHSdI(XVyZAz`57tzZz!7XR{8Dl<((bFy)sw=;K3W!#<+hMsbk0+*3DyJ zoa*nv*g3cNSdI}w<<SCQvCCYhso@qjITc9emsUhfNci`6<dTG=p)zN!|LtzPZ!aXL z^$2Z9Nq)rx-m0KUFd7-s?B3v1rZ3vzrdpt2cE(h-(OIz!K#01GJQ9>oOAwl?vOIj_ zIy)l%+P*w$=~}8M;9rar>Ca2GN(L4|mAw3tDnFNgZ+zEW=#F!quo(dld!_~F5~79T z5Cv@SrShp!<tFl;34Bx8$JD4659C@V+O9QrsJIYLfGZpI#F{5>`SrMYJia#Oqb|G} z=^H1$<=b<13B3K~off-wk@8an<*Ci$yCST8X=_&p7!cArH1Vh1J9hlqrd{jgVq4hd zmP(AU9q#PLK&Er-P*(db$5TG4Ivi>D_Jytw+EB@3XUJFKQR~rHiS<s#51t7FB}qdg zI3{7`(XnjO4YnlwC{O=U#EEuMvD4rD-N`zO->^)DbXYP>4FKp~A@|-xnHaE>htKJe zh8brSQBfBs0>(oUDD+*OvooFIj%jdT=swoy+P>lv)pTdrOY7EE{SfVkJKzQ4h~{aO z9tY~0N!lA`uJ21XwQk$#jh9CF#Cf_HEg$34gcP3f1Y^?)fXILL*OCPI#&xRA6?n0y zzjutwodR@O64m;UOfrX5;-q~a54}!B9B5=;y77!FAE6NWUD38AIFE(TS53tNaDliy zImD2fNMO#<eT={NVxo&bLX&gM=X<}2MmvBSrlIuKcr4KUT1$mwzu1r#=E>P6bkK1n zo@Du38wH9$acQb#4*Y$*3tQz5*H(j?&K(l2mMIpBYyc%6&v)))jBBA}jpQ`?peUq9 zT|61#R2GaoqEeS|I^BGfQaWx@$FAPyv`8q%=sgKOzfekkA{ob2JSLt;!n)?K4)67K z%d{2c;NBqtKdnv~y>Xf6cGT~hJ9-!G5btaAY{5T0?x{os`gbcRbdTTwlrD@8L`xsL z`J4>1NELPuU$U82UODCg2Tef$v&x--_7el}0hB?*MVFVy1FF)*6fVjNWu893V<9WR zaQl`8H^_?&z5%va%s!yZUl`Wji8B!w%*uVNaYOax{AyR{++$KdTBeO-VGpr6@NL{R z$9&o%ZcHYkR_BUb!XSsK(Gh*y-sF}408&0_HrHAvsy}~xqi`Iz`e>pmST=6dlkfG; z^zn1!y0g6tqx!wI2L*Tkqe2AL>WWw>;)o1i<6)GI{`&7jx8L4=3KXqeo7($*2jApy zK+_&;E5%VOaLZCvXv_$V*WDjmq!RAO9eFL{0x56{mp^$Q>$8=TDzK=;i&zJtX>2xZ z18*tzi!1IRRMmH{PU|H&c`?4avVmlM7@;7ls-KUZ=zgz6?HN+2T}0`yK@y#lK3b8v zNY)})9Qu1uDma$)`PsWOvHk<94w#&T{-BI6yA0#ZDO8w#kmR_(XYuq4oiL99$>Hrl z^DYi6c+k?$t4R)MIhUtb1_$u3g5=KxW}0gaNW4r=Q+D~$;|dGP@ZAbD?~T23BvVjq zc>CCz6ArW5yRLZ+$MQB-5dqGxs@E@8@r!cxW$vUC-YmPjw7T={72t_lS|w=rxStXo z_*7oFPA;q=g%eOcNP`EUUnw^T3)wzSJ<d_Gt>^L@PAYi|Al^Kyt*<-^O2b?^LVb6M z(j+^FSI{eFT@L(`=iUnz?^PJk3=crEG6m8z30L&pjSd@bb8?UWu`a#_Lg_38N^}F( zBqb%8_o$knvr@d44Fj3_=@8jhR7Mft&mV<VQ5c2S%K!DC9;E3jC@QYYe~8Z{{#urq zrt-=@BnU)G1ervL<QoiPMhguU%~j6N)QWW2IC57nHK$BF7ebRq)6}#~WIik-g4JSK zNFZ}RkdA4$Z`35<Z$klD3D?JLr~I_j>j+?wH(6O@Pk|PGgxRq_uq?X(0fzC)exh73 zFqq71WC4e#<=ws2-EeBQb`>Q4pAoo+hroF3{7&Xa_vtgk%A~J$cC(EyJ@)lBchM3W zmEDZQ&KlWoY`Tm?tbi763foPz7LF1w&4KYrm}U?x$#H1XZorYfj{LZ6MeEQ?vebug zYy15%#n>2|T3isrAZ}RcV0!!!=^?)}#R@J#{a|34aK-LPYFW@iyvaL^tNBDM;t-ri z0cAyX5(YnHCw1UUrX4SlJ02phWmq(FBgsN;1;?sanls=wbAZJYo^ogjLbAolV@LG3 zS}HhqMBOj#C?8@m?F8oEW1IM^>dhlcoISs1HlTayLN>wGnDmU6;J4t)qRDR2+m%*Y ziAxj$qWVnpX}V0;($EqCD&EC@qLs=)O_F9ShhumtC$6(RHEN6%oFUS+i|~?&f|?iV zwK~}(#EiA24B$U3*MNl@5RJl4Pk*|mT*CJLQ{_D4oIf$2fI2yj6Q1usJuy4mej0B% z0@h&|^f(WPc+jQBcNr5S(xI!fZqlQKD+V!NZas?sivM1mRp%DuRtv5a>og9e&i<5; zt;R<*<k^vVjYYr}_<cP^2@TZmzaP?11Gc~U&mxlh+Zv*A<}5y892ocm8JKVwIS%SS zQb3iUgg!6;V*Vb5c-t%7qU=HWIZCX(pVW>V2oM&%EH70P7<b!(SHlC8Vc-K6TBHwd z*0)<tnoNncH5A&QBQpZ}IfyJ%22txg%4$JD?5Ny;1b8Vu$ZibV-^P&LvdHnrD@aWF z4=ag~tdB<rN{vcX7!3wwZKZN~V_-bOF1cB&<*||rz?G6x62BIJlkiDSGaT;@!=D)t zHorWe3B6ewYDb3WI1L+*&1N2fam8fKo=MCCNW$sHP5R&)qlBt@^OCzWCv|=+e{^lM zgTHsZA%IbP9f%zoDq*}aOm}fu=H_F?=#znSHnV}%ClB2}amI?JOOnV_YHOHRk+gG9 z`go0Jc|JKAIr?nR4{nh5rxsJfPUSkBIhh6<DgAhDRKtse4DMYPcG`(OusZpadP%XX zjhXf!I$&j9qt>t|W>{_(jdE__h>I98q`J`zW07~lkqOpnZ`$H=)cAnASi0<pKPxQw z9X|z4mriK!aV_wac}--LBsrrL?8qX9374p4oHe_J0EzJ!hW5yIX4qDM@Jr(nJthd) zw<>0)Xt&X28%RdoQ&>>Hq6OrO4d3aDG>Kl0bi6#kP7&%SJz=}Wg^L#^KmaDhLKPYt zQ=$xlQ2o>YCZ$CdNi~u9LN4;8w76trneIx1vv|t(_}KfuPXbj311c%0`c71Hrx!3Q z46xVly?&Ic|H@aioM~)H9ehR)2CX>ryv2Hu3D#XP*S(`flWiEvK4j$=oXT2mqq%4^ z2nea7sg8ry#>rZ3wD3_&Gb&vlPt%BY7H;RN1AzJ(4Oh$2(9iv}4%SK@taVG*gf5DO z)1_8Ybau!(y<pL;3W+2#FN3yke13UvG}ei(I>=FBFUVzr%}3}$gcPOz6ysW(kxV<o z7!J~$BOzi*Oq$g-rz<9;NU=Fu>2v}mMYJFE1O?FvUDop;iC|@cTCkCfrK8Crq0Lgq z2_z#!5@C`hf*}W-Kwm%rmdVAxAgLL9QOk-aDlMxb1|I#Hg_Ex!z<c~aTctPQ>XFp+ z%P^~+Qi}9<Dz(L>rEE|@ZiaQw>g|KH6?j@(8C3i4(ey1*1?p1UF2o}~*&%gO2w`>0 z?y>*U*c*H*W^Bks!^*|YKK%~DsUcl@7$mxqV%%CK;5?^VCM4VSMyiDr@nBXpVIXoe zptqe&S|@7&mU2vzL~n}L;`0Oh5>J$+8k>Vzv5<p8sL^)S_{zr#WGs}XEi+i?NiRwj ztE!ujm*5y=(u8Km_b;E3|FJ)k^s`W~mIs}@F9U^IDo+pKZ4VO{XasYJs7nx$Kq97c zg`orTe@L3)mLOZMo{yA_h|DRJyv)AAb0uY)MU#!$BMGb|V=^mGWZ7B6A;7G&y}jeN zd&hiGSCb5u>ju;EddtZAR~-tbnJXj7Wl)z=ipK*s89Us1kw@r~l?U`1Iibjk!Q}Z% zPpKL?_NVL}{8cQ%Dt4o+#b3@=1l$es2o5LXiU0TbN^hlLm|P`%YN!XwVQ@)f5UjQp z?5I58Xgy$5=}lyVF#Vvs9kPl<;D75C+Jh<TBJ_(d83^7hCs39WyIj3W(BT)4bb84$ zP;e0nQc~co=QI#S!k8DiA0Utwhv=rMT<IjPd@9+vmQ=nnCHK+OXgBw)YU)`wM@538 zF!-KfSSTMdplL^zE4pH6JfPQ0k~ZI?D`j#GnDjy@M5dRcCj!Z|;3(^tsQ*b3dXenX zL(?8vHu89F(n7Nkv9v!iDu1-Xdu8tQ+Tgse?Zqm}r*=vNfnxXPU1(`W=!(;xK7Tfm zCb3*5H#pV;4e0tJ8*kx3h7KP#1Rd8<@Z3tKFerx%!<bv5w)zTp)>FlNZlp#lyeA!A z6&*U~cU7%yOa)37q3q-2!H#Vz`;V%f#nh;crI`;+BVoX3kgL-9N@I;C!Q|-e6Tx@M z(u2W5sa(xoj!QjPTVok9eK-b1*M?TergFm055^eJ>ZW4OT_h_KXd5C@+DZFIurx#o zIlxm1@f=L=+Og<S)73o`ursS5ks=Fl<;(|)OPwE;zSLbjZX9l@6Kw;`kqvuk;yw`5 zf=Xi%A93{CzC@CmIbB<Ziz%|uK{Vgvg#Z+iIMvdeN&m|aIs8-1w&-;U!s>6omCzlE zW<v?;l2u4=Q$=>bES9{~KX&X1%vK}#Z2~_l3pQVwR>!sR-FMNJ4lYbSIToFEBhH@e zBkdD&U0!6ed4c&_6?#-QQ!$#R8ax~_sCKKBqZ$L=Ev0EB(T!4vO_V72QFN(>6oONV z;x1Vtnycr;5xB=u(cq&J3G{=Hi2YpLR*F*NA}Pu8QPP^!qU%P{l2{detTAdLKC>iz zO)tihxWE2Bm#nhXD3TzHA0I2EYQcxkpq}DWC!Ck^vvRc?EXkQEO3BB1%BTLFIr+Yg zzInis@P{N$NNtm&8@7<7Eg(Q9*uaB>sRT)dlZ#SN-|nc!J3ab6n^T7mr@nZ6X-n}? z&yebCbj2IAvCT7yu5=o6>6!9iOY)M3?8a;!{?^ctWp)->MjBX1)>iT^lhb5kGaTaa zxA3XQ7VW9}wPdG{$0VBMWUN51N6y9Ftk8WTC5KWi$Wd<NJn*FxDRj+vnq)j#qljzQ z;HudR&VyP?yJeri%WDY?Xs>~Xc<dMZ1Zydh27x&>1{e`l?gk!W?gQ4%Y#GaC$wurw zr-ZnXx9#HAl%Cc$k|)(|8(2?$t7V~<C6%dq(Xr%}%$lDZ`C9OMWx8=VU8fQ*?`%nI z*cbnjbi(ORt5V<ul8AYQP61bOe{S9ljMWI$Nv8qU^E=s8m7zkXwJZ6Hhsl%RlYLg} zX%q|P)D$RBH=d#}DYfML=9mvMvjA^P`Dg=+A=|N0#2b5KR=)mfow3YYe`IZqU401K zAW1dy{0Oc{EqSU;nVq3Bxa5#nC^tqUc3OvohZ27^X*T4W--B{Q=;}bf25R6uu7U76 zh~F}uKcjBKd`hanTrv@YQ9K3#1HWS7LXPdH;X@ncsb^2LZx~t{iR?jS;yHSYAy+P0 zJ#w-%G$%<naOBZjMs76KaC)_lrBV2Rj)<ksACiufr4DmIJDR3g36h~e2rUjo51Ob4 zN9rw2w)RGPd5i53yfgvo6LYHZ+vllD>2;6=p6;qrWc%R`LQ62)L4QcOB2|M9`==E~ zcCt{ci1Qf-(lpB*8lL$R29GXIJ3PGQFo<wz(N=#Smy$g5q7^9@PMX)vBaTy4i@+M) zWFaQ^+Z{R4h7_$}fy<S=mrHq7UUI3KsYxr=bwtna{d2u3;Ei$1s!=X6bIbbbXoAxt zY}zM2hMP^}ZJ$5tfYZRgFDL`b*&w8_ncje&)1sL<U8;94)`&7tcOI;@OO`JJo5n+o zYb}l9Ee&_M3X+Zo3I<HvL{iUw((C48+>~UZ&#p0`BCelbR#6uF*1eMumv{_%CMoMz z$)PZwlwL1;?~c2{`9X{NZupo#rXD`V<vuSU)`&YkgvZD2uam>?`iC$5kz$<nk^|km zbq?Hbcqh0!m~8jCL)F4r$(*a$G9XQX<aGzAUL>nQqa^;2<Q<i!l~^}skvCpEjT*7e zCKX7=ifgryWEKN9N)ea~QT7IWndQY!R2`odJ!U~}Jf(|OVQjGYehdJNWY!guLJdXe z1`7-7Ez71Y``gPD>^MkzmZaN4K8U94M_Z0L?`aj6!YgFx23yBZJWe<j<nfoFdt*@? z#TY@Ar|zX@;ECWumDGvv%5Rivoiu7^%Ll2-RYDHeb^mt8UihIsDta7l<-tDZrIcEY zunM3G|Cvrx9vC`jDwdI!q3qM9oJun59v~1vSzEqS28k=>TD@hn9Suq1{KB#T1? zht6pA8${}dL?s`-y1t_NLi%_RU9~7m!{HIX9$yr1-hbUZ%qs=VD^Srst8}BY2VJ|o zDP4LZjhjngBPaT1D8w)^#dLuz0ay@V9F=|!BmtzKkU~hM7dZuF)sIRj{Ct@1eCj`( zPC$CWl|irDl<S+&kgTy|Md?S+oTtU_U47<b{}B(>d@EI4Xc8ZOm+(P*=8fg;d-r-Y zK3Y#$i7lTeul>{qS%5$K%IcfTy_mOMg*oYim1XQy@nDHHh1Pm-uX&1MFIaVDuxE<G z_Mgz`)Df@bXs1$cJkNL#z8Sj~EaT*?%mz!q2X(gnDC?=CJD8}F0y6%)_rkBB%7oT; zN`4!uL?thy=z@u2w-0$F0>M(k+>)5eF=Nu;@h3%MKqk=*%;&#M8G|PuCB7=se|&1J zpknY|e!fGeLL<NqS|3#ReG)(8qJMFyc;Kr|cL#Z)zeG^3U!8Ief&@k^oNH3mA=c#W z18HlN@(*6*h2JuhBv+^afZB_+{RL|5Lb#t79ttC?wt!TeXmZ0<oB|rYm!n=pZec(} z|6aLl?2JVXsJ9t-Kj%ghi)C9ueeVYv&vA8=r;1;+DF}Xj@kkvz$}@F{89cy~er|2U zWoZUU2}D$AhYu()K~e;ca7@bMssSCenfR4KVS4M=8;xVSvqAc-(v6xEt@A-{aRPz5 zF^p7K<WRBekupJPi~Vd-vOftRC5zPR)L?Ti{6kq680Q9BWr!nrIaFeX7|pxiPT!Kq zPcn?gje&@K7G<V%-u2wkedR|9uQ(`t5az04ALVXS<2Es?;mBiO+;bX!wUKtysS5W( z4R_SHy={2x*^#~HME{n9Hv?u`U-u?fnqCzCapEP>=OhTYZ5$oM2@$()(A;qM6D4fo zmtSWnzr~x-xt@?s_ipb-_lM@^e_hR5Jl>o1Tgyz$qk4hXzw#Yi+3ery!+WBxD}?P% zX%w@`O*eNICfVFoT+O8BW98@?N<Fcbae<Pw<A}rsW-W{)hw+TLcJM$o3eeXe#|pIv zQC7s9rQAGY1j<Yk>XTTbS90Wk&|x@mf4H-vW65$$q>);tkbbe2YTbT}@h3e~t03mR z@QvEYw5CR2L`}>+wB1U4GV*7wu+j8LSb6Z6Do@d=7xQ+7ev}&ZR#8=#_SX9i%}gm) zs6MkqDq^qK`LK*4H&=?wt4PoWPDa;XKZ)LCNQbI{HS{EcYCq|-q8roh%xT0mRf25b znHX9e?H2ZW;_s~LC73C_GPgH_nxTP^qT=wlrj#n$S!{R(;b$#@mo8L7oyZ`kQ=c#= zHNwqJJ~>&!fC4mBkTkzJkV8g*{BwVq2Bh+zn=`R0GVewYF<tbxY735a1K6uXKTo2X zs|*wn<@2tpyLOW?HB?}*OtmgKzq({47Ch*=Dt$MG6H+)~@t;Q96MSGEF0_TG-%EwR zhI$xxYU?zPJIn)6<DzOqshOo3u-j28rq+6NMr^Fs1$d&n__T&sR&|44MtFag?jFcO zh}PFh&7mbVLjY4{saAXj;x)KN85ZbJZ3gGMEF4_I6Bv?_KqX&hebLE43OsMX+yuI` z3^&V!L6g64ch|5<M61Dk>j{q=Wo8LqY730GFCdwY2S*3jjtx4|5jueXkUJkJJLI`< z97{t$Z$k%J?%<?=k?3)G^?p#|i_)4zq^cLMEwH-U;*0xot^H995;6TMX7t3@PwR7a zgj><C%NtGrYkAkK019N$GyTui1~GMHx*ATCuQlpM>glmg+!cAh^&nbX5g3`GhFA`! zwJA2x^Z!nL*dZKc!<ZKE$iVwdcRq`IG=u@uKEo|=J=-k&yCdeH$X>2uy3DU#%UtVy zFW(`n;PqOJ6_ET6rnOj9x9DQ}C0NK{HYTm0HvC!Q@t1Rpsrl!>+VD!dFi5M{Lv@Tw z?pS?_ok<Z|F#Ouu;}NQubpQ1mB3E%jM8J>d{40pcj~3Nub?(<^gu<kzV5vh_u)%?X zfLK=>&B6}11nM8l4wC_rt|*FfB!IP9wzLS|RB%O@XaDd1A<W7d$$Vxh&8Ro467S6N zQb4@+SEX%{5ZSN+Y5gje-Ws1s$7CwZnUwATEQ+=*3Z+mLu<o5)k-N71YM0`8BT&t9 znQKtp<P_W`(Lr+8r1%PKxw{9ut#w8bwv37^JjXww&ASij7Bu-!Q*z${BT~DF-DLFl z+kL_nMcHd0XrfPILo@H_yih%pM+8tbJIojU^C+4!%Quw)J?~oTVU&yG#pGS2fy#mY z`?TmVCms$>2;^kWY8hv(=sYcQ>b7lsKtf#hfB<9ze(UJlO0L`V=wX8NO9_7ePK%)v z3jlB6GfTM=CXX(=3hC|7101!rKk&l}4ZdWT4|ntTm#|^?fBSk?NWZjub?&LyMQgA8 zSCtPxd7^UyH2p;|Y>I6$>lG6nU*Z))aihvDqAAz3TbL*nTH2yL{t8ACN1FX2_zDw` zyU=rmbjg$L+trCx9e~+_Vj5`OL}$f|b#i;*aeO3zjIvCo>$_DQ0$LP=i;4t)W&+F+ z%IZbuVk<mCfzP3UWBIC^p{h}k@oXFnxa(#`z^doESC7O=c$QN9YbROQ4x-7g>lEIx z;{FmOFi&g=K+<0DPLE*ek}Z^fk`hlO@^F=^)Cb@Q_Mz_?*qyD%R`>ODv$EL-g_h`c zC^DaEW@lRJ@(jQ2_vz5-S?mQcZ~(<^_w@^|d+WUV=uah#)DnQ1Nf=Zcn}Rn5;!-PM z5J{H+s57h~tC&fV=_5W$nzh7~kMQUQl928T=~&Tf6^eQo`+&RQ?Ju@?U`I;PR;<=K z=O!~q_6Yg}GwR``+supV!h4fU{dc*dxz~Ncr=NH4klCAA%&U<kWX{DF|No}oz{+hs z-Iw^<&`3!eqpxLNVE;O?^RkwSMJn@N!Dv}5^9;bg@mg{Ur;rbG;$J4SB+djFezCm3 zOM)GQ)``3drr;0$U>OmX;1^(4IH50T+URE4Z4ZcAWV^NDwdySAMp5@^Z_M<5&7$=( zl?CnYk{v#1(;uJm-A4LvY#CWwfS)J*)iu87e66drlzJ7YZ0<{HJI$l|URBT?{hCsH z^&w~?K}|RBT|hAQp&rv3Yz2{kB!l;h%E9kn1o7R*xTmTx#}vL~c2)w8%s-xkoVsEV zO&2QN9+uKy5^miK<)T?cOHo2QLa>Z1R_<@5Ir8{D%e<kyGI}!-=Y;_$T64}Ush^o| zslhIt$EEwmQhFa?OpIKpPx{@1mEt&r+?P*<@A-sjf923d>TxW&fTR^m^!IpUB@s_a zYqn~xl3i*Lz^*#+(4HN__BtmuT2&XcvcYO|PdjvtBJw*q%L}q7a56dd*28V4=8EDz z3EokoBrx42-sZj6w2u|!^<1J?gn_gM?BUsVM^cGoA7%=luO(R|4L3d|^5qnl=k(5R zL?@Pq(Q^NnX|BFEI_23lL*G3+Htg^ScHEHJ3x_7xP=YftKl9X1#c>7lTXB1aBd1*L zbCs~5y&2#|6=gR?u=Z89gW5<0DOHs~CtyB_sWwHJ2pm+x2MC>Wf{rRwJdA6pLN}1p zlGjeK$**kHh=R9T)y_#>zG<Xiy8dCoU;j)`L^Jlez&54(wNdSVstX5j8Wld5?~i=c ztH5|ZxvvNwb3U1k3*oa!i*?2PK&QTyUqv-*##z#~TNk1C__$$*Fj+gT!{WvI0QVhb zu9_|QSPv}@C_pz=!AIAAQ(8ezw!2r#ur^i9=VoGS=U&MGe@<z?s~wnW8p6_Ab^C|D z4_mEwoSHy1gA~K}<DTE#9f5bW4-#9eS~vq`4RY#d+yoOl{AoA3220r|-`z+>kOlYr zSXeCYG~nMgSBs0b!(F=KknaB*R}HylQI8G$9v8+8M)Bpq&bVnVBDlucH}Fnm0Y;Fy z2UiI}6NHk`{{U3^BK$>vqHdL7pFh7u6`IV%nktl9u(4z$&@TWqa9?^sxG>!KuUoBJ z+>P3rlao)p^Bf+owP-JIJpn5|j6AhIo<{t>jSIZBpizC2u-V#6!xE#cM#eeIPOIIm zLJu8Gb*ucjPN`p?U>%O6CDGFmIA<sFBVh6OFYt1cB9mePeUTy`s`fj0(cvr-s6B-< zr#)jkEx+&=nCRzUu@G4Guccm5hAs*GTNKRhN0?WkC6)vV0D%U7p*^iC?%)JU?=uQs zUES+&3~#sk=PCAV&bUmjsgt00r_v7@Rv$5NL9H77W3x@*F)q7SP8iuP;^f0SR;fX= zL9;q`TdY1s#^Kv-aT?sxCogM*P)MBckx8t+2BP@sfHL=^Lp!!I2Uof%rnFp0sB}t< z8S>FMXRPexbOOt!KAWfP|B_Xj!SXxMO0abTZsa?#Y60??#6@di5fa8Q1p!p@*Dea< zs{HLnu{{*&6H5F_>9>_J?5|8m!nW@xG%(N84{p~&e8H_a%iW1nuTxZi?d*eQf|Y18 z7eALDR4tfAD;}H_7PyHO;{SLO$8!z^xN&*--{W-h^!8R;O?01_UScWifPVKqF%489 zhPGXMv2Uam+NUh@XIk**VFi|xmBt2yPt{|8`G<)t2`(oi3l{lhs-$kU;|xFJ3@33G z5KVEl*F>@`Pex^ru6iR~T5iopz^Owd*RgiUKoyrP)S;=6s```&&2kj}5HvMhJ9Vw0 z(1F2s(x2DQRtVm71?V@mWnfdCM13DG(#H5pEnsr_{3H9h*GeV3!w0@;;&kiKA`1IB zbHQ1xAP|gtv_|L|6b^icGk4r9cfplg>D%5CXs%OB!*4`?KHQQbe*<C!^4CFt$=Wn& zjUBRf0Zvy$vA;t$E89n^z!C4{lbC{Sti8F{o2$v1arfxdYRSdQO+$_L8|DyE?dl?3 zF7_YZ6fs1M*l-ND7=l&9oa}Ku1Az!_{$B&UV^{$hSN_38_+;g~Pm9Vmqu4>bt6?2R zOhFjFZ1p4mAAmKuKk;J&Y?a{9!D|=e|CIDQ_#s}O%n!EI+=<_q1w}-*Ep!6>;MiZI z8|L)arYxcR6Px~8h6Np1{U!e`&4Ys!Q>W#((fXg%s$nPF6yY@4Un!M|#E`hdyn&Bq z5rK=S>Y~iagf|v2%4s||==_5JdAG*_q1*!p#<<Z(p}8H0bjS)%+;DS9;~6(o^bVlJ zJdAEu*P)S>$et0K4xnUD{y@RK+tY@pa%7Fjh8J2lJY2nG9#NbX_wdzpCs#Ysqgv8e zvHo1F%NlF$bi)QW&~2LWKZef2t*JH+!)If_1`M{*={81pr?`#oMx>-mkdzX28#Q`# z2uO*P3Wx~iMz?e+3W$mrAD|*8AAiAl&$+JiyUu&w=echjQ5Q}D6C*)=MP`1f){`WT z{tf0D66Z@2+#*!pHCQrv5`CcHqs(XpHl$~%XqG_lIojD93Y?pf>f1DTr3sPigV-t` zlLHmy+DpWJ4Qv%}faRg+UlZHxi`K6vu#<D(cw4`F(-tl<#(vu#$W8kfYWJnF4sc>K zo9&(~(d^n7hKMTE{%~{G_mXbEFRh`Jv@3BumAOkw+oN+q7^l}#(5lQx%^|dq1_XKk zpFHL41<=|nyC;Jxu3Gh4X?Hx(GBygn0at=m97?gry6RYy9@pEbT`MIMyTS0E!6>F? zyMir^Dy;o~--|8mO5&On6B~TioRxA}^>6x#yIYj|0xVAWlYHamKTe>gK?m!LPHshS ze8(=}^kX^HETuTX1h!H-98A7oZsv$;f}D?ir3`+D^$!mx+z#V>&jwc5j2mKUizvH~ z{dDLrS1ep##<gA$A(pxG@*`Hh?Frih2Im9pphgVD<Se{ilPx_+f?`Dsy}!HlyEfud zhB-DAsefvV?5l#kh#!^)v$^oIyX0csRGY0rz4zy0Rp<ZoZ@`Ap9RIx8RKk$Dvzj=D z^c${(G4=3}x_7%D5{B$=a1a%D5aRFNaUM$qcMOL=+dDLC)H1Q)i(qG$KdIsKs9*fN zs|G2K-jda5AM{->^nep}R47`L{(so|7b8EJz_*mrXc(4xF>hocF_MpI;8vg=&dY4e zNY<q+2ua5WKBgx@$Oxm1>rcC}DBf^6;)Rm~htdaY;I1_B?xeT9c|UyJzzvs;8`j%n zG=dqv`%2zIKh$AAb7Uwc;=YZ_TG+x~+qmMUL(nA<J%o&gW)(Z+i{t!9Ii|gF@+j-z z15S^ApI>Os6Fc`I8j*T}YpB;mYkpEal5u?#9jZ8)WQ!G3v3|kweTC<+*I~Nqtj*_@ zjOP1F!LG7>@riJ(h)!g(Aiwyr`lj)zXv&yBv(naUstZ=WX)rod{NwVig9l|t50u=> zLSaW%dxe~-c<3Hoe-F+1&7193BmzP(7+f0t^tnVLPMl}XFYAH&MQw{M0srF*<rz9j z**X^K_pv4dv^53o3ygdJjB}swcujmc8L2)tk!pf0`fUB!>{7KadFbd{WrGlwcE1c8 zNvK^sj4D$m{SK?6qm2*ass!L+bok*0=N=x})5C>6vgiNoA-*Ne(l|q(&fs1?D`Bcm zD)Pb-FaG`py6r6Y0a-`~iE!vD_smUm(9~FxQtca!PF3bFmFl|OL5uw;c7h=#%c&~; zJU@+iKk^s;Vf55D{5sBADwnS37^iapFN#c6N^wP@TeV!@@SOeV_(!EdHXZTqt4EVG zY<ZWG&4BKFtlHiX?H!A|Ap1)cBK?8xro4K&-%12Sh>?6zx8@i8n$l61f0tDM(L0po z=9^UAN@gx?ERI*acNJ?DKCk?)Nz9Dd)tegETo^@llEH=sNmt~F!)x(uqokty+Da{> z(7}!FQNW>>gnY>7s4ts}BcytL^SZB6x~Qp9UQx%s;|H0v-tSh@jO{je*B$Qqewd}Z zCn0;u_4rrgr%>^qC>Eruu~jfd(rHi9T^YOm3rjS)3McxJYOfm8f7!75){EcN=(+{P z2889LKc#aV*Pu@?ZrnAU<tYnF+(jb_>71h^Hhmv12*_YC4*7I2UWO<v_d@13<-O*B zynBS;0y5IvrTdve(!HdyXW<cVFPLn*Z`x$|ogUEr%@vcJfK^TS)HUiIhc%hKq~<<W z>3$*j=XPNt6^wgi8}`u=<gJ%NFRTy-dJOv~1a-#I@SF`;DVjs%B*yYK^W6sLH#DM| z#L+tD@X8Tu)U0{HEhB~X-pjWYO8Tw{CRAf0>pc!@dB?7pwcXRjc2}bDSHw+DYwcgh zei?oVj`kAi3>Ps~6v<F;7kQ<*m9n&k#`0s0gMN+=`j~|F$g5)A9w^!5l<CrMCCBP6 zkT;Ko>amgE%H^9@&hNlX&?m#ZN(QVQ%_2B}hyMeBhc2@Mo0v?u9tDc*UPOx$MPzDn zenF+H3is^4xFMT$Y(GYXgEDsgPi$>6mha(v#kTNI#<X7FJMyd^WBf7;0_zhOrx>`{ zWEbqp^lM*4bJmFX9an566Xw&!LUtm{&gLlt6YFSJ7L?kaHVSZh?*z}|c#PIxFoJQp z#@$vAYU;4~3m8O$M|^lRaTJ+*kHcl^@570s%x7N$ZHXUFo9t*um|wSPbAHw&_Tv+A z9sE#H)g>rXDR)u}n<{`+z+Mn%`6G?Ru`%oPpxLkfUXb*i_bS!>wt4CkCN7macN`4+ z48Idf2zy{{$`irT!iEi#sHec;2`avGFJ?+R^YBp#m-B0;{3HAyg+GljZTs$tCH{TI z^kzZr+H1lyTh|2QM|WlD*6SP7bT2imw<q=}KfDZ{D_;63axsU|Q)2VcLbQqDOz{St zW`Pkap8By!yu?OlO`dsYbAX%9_MVQ4Vy`{L(P$O({O6_fd%ub@B!FWJ-lg~Ocbe^; zpN`b#&J3^15Q|c)3KAMW-1re|a2|W`cmDg|zdFy*HUCBxuytImSlZJk09b%T24a!8 z;E!m)jm=#qdFO-oU`CFBf)I5Fed;vRN9p1i8vJ_333CKcLr4%5aICtZV^ZTN9t~Us zsDuvliE2G-(JGZl)BI{j7GDr8?Jb?(t-n^iMR|#D0DwbI@U<giHugr3Xtb}eic zk+mw{t0mNg!Ne|1ED726>D?FIW+{{EJ^3eU@bWTZ4<AW+^z%t}*{$`ArDjosBfbNl zl)h=OneayyMrJjTEILX>pDj#anM>40;dh@JpHe(`Kx45J0Gv90-};Fz=VXfqYFE3y z6Xef_l`9k9u?wi-TELN<-qQsAq*kUqLsfOcU5H+GfcsK=|2S@$^OJ_1_k<5u8PdNA z@y{k`n$sbsDn9CBKN}<M^3iKN=-|P;c6b{11{r{s3i~oe6&<^tKhlt{IA2`g#106m zs@nx_-B+I_ypriQGfDF{MVw--)?CE5AqPdw&m&@a&TDWO2?M(!P0!C9&fpPtPdg<< z9Dpzo32uT%4&x=O2{YMjokxf)03D44ctPmQ^UWgLGZ{>)L^1cB56y4#;F?9tsZ6uX zWj;LPE&ODhAoMH=_RgGE%_GM0{z_lp*-b*|7wBXK^J#xew~T_hLP^g;vqBfK`#1?e z#X!A*@0<vP+1wa{9K>s#h{&Dv4b++7hAbFvl!EB@5BT!}`$R$SVxQqAMNUX{2+%QF z;KBq~wJXgHzGW^YE~d^$FnH_y4!<qfJ(2h!MDqAG;b7L(?#g%gcHl+iKN$TQN7MBU z?Sy(uS`GAzOzn*f0`+1aki-6;Ur4x_U0_%VYKtm<F;M~-HE0~UImP^<&;pQNT;|jo zJ_)RySs8fl_fMp;ACI3ha%g4^C>Y{%n-nk+P%BkO6x;o?;5F+PYs|=62HA}UyCq4^ zQX7r*X1cw7S5Q4qaKBvrfmln#b%p&2fhw*K@A<34TI4neUk_iPDC}SEE4p6}fol@T zg+||PQbS9_ErSDk?dSpfyjzC+0kE<uE^}u3qypw#15sDhNtO%uorykjZ7#B5OI3y^ z)V^En+Yp~x>o1yc&9b~Gz{%zR37;lkf9xp^38){#KYs@&%`#n)k@Q%V)kR$9(m9Rz zudh$0Y!L_+U+#N<AQ7Z>IBXfQmZ<sPcf#0@OUah~OdW@Ye~7ndUOc&X^HE-J(Sr0k zhzb3wj0tJ&@DUPXN-Kesn6PGFJ;SPE>y94d3xn)?bDw~<z<sN%z_)#Fpejp==gpX4 zV?T>pBLg1Y>}@Jme=mjpAG$py`;!P(8Aw%D>J>IQdRZ!bwd7+GgyHs`v*8x=rKv<X zN_h2;nt<TD4&mUGvPJM)fh+LT%j(I{#85_E`s777KcCn4B$-Jj#mx?KS$RaGIlj#O ze6*ya8B+3=Hf5&C1&$&N^Ek9t9qTtryRB@Q$Eh-;06a7_azJ!DQbu;@dF+4U)LkPZ zTHWdG6fX06;-n#M|NdZnV!;~0NgKmQv9{sJ!hFlx;qS~;P`><=i|byKM)HZ7nmD+P z0nxHUbI17J>8;sVfMk|$Uv#M36z=+iekR*BbhZaOPVmCYr7d`~fQvz=Bfs`m?s-cq ze5fyQh(;BclVg}vQeb%i*wXARXKbYFhn0hhAULj+wZJol^OC@SPcj7aaAj*e*s;>b zc1c`6{Uruw&4J#D;(V2vYcJDo9Zz1sZ|wLy!^ud0zMo3HO0a#|p4R;k{t3P9G#bRx zC12yyp+pg<n&aYVSmfaGwN61OyY5E$<s;*pz{ZsIKU11_SDJ+FD)0Mg?{qCQhBmPy zCC21z<=l4;b&<*3Uz~*)(`wbzp>F;^p!L(u1&zh~`jb*OgJx17#WyPVZ;|$#G})@z zFZ_oyBU=9K9;l+Z<zUU^xR~_Lq&FeL>I`?j#3Q6tGAf^jnYW~?S383?ay0g>g)%A3 zSywjMU1wgZYh6lLdramK?*QHXvXQR4)2YN?5`bRCc1-#=^ZBot_f&@V-~W<Yw;3Ab zIjV~Y4}Rlu?xqxhBgGK#Jh1(}9m>J#XeYMRqtG$*$_W&Cs(YAKHNp?);q+l?Kzkou zNb>b+PCffRR$Ys6tp5q`OA}{H3u9rIcUI<NB`NxnbG&Q801?g7tSr?P;+-PAfM>x# zG4RVB7FsO>MR3&M6`qnML%aQ(h`IWbJR;7#a;@+|XI$uyu5d55$`?ByxQibBb<}>f zc;k*raAJ6;i8C)TcX%)LeuR#RlT4$N1Tp(ca^Gk_v>&NI6M<fJrf%3BboHojYC!5T zt-WL^FN<X!s|2tMKC@#HH>+TOvc@Ca*nb{FW3c<oq{Nymm!9EFr8B=8vu8bUxi25e zpB1}HfNJ;vy@$2~aCcWi)!5xBJGIZPb@)!Umm@s<HHn$`h*g$|b=Y>DNzR=dzaO*? zr*9ZvN!W3mYA-i+9|aIJv&=xX+!bJSj`nzUphu`I9ZYIulX;2nu}hbFjAvWS5iFh~ zUC^*&u-ML=<Xa<IfnrHxSt9avw_3~ewlysg>6*jpE2e2!j-wuCBW#mjJWb{GJk_*$ zX4bh!w@lzgc!-G_$8E%7Ws<u-`3v67UeAmPKet|Y=VXhcl`CR&uiA06De>S#HKLSw zTL`KKJ1ES+-7EuW6vVdhs@yb&(*d0##?VLju_s6svE0U3vVYEKHeb&;T)LjPmBYgx zG4p*P?jeLpK>tU!h{qKBx5$rW(5bIza;W>-Ql$dx39WSRqUDG?t8uER+?%U2t9hHp zT{0zR?JgiGs#Q`)ia0lp<y-K~Xq-cz=Ya(UIdZA^6SQ#Z3+{D^3$$_AcRIcyA8nq~ znKBCj3cqd-G420+`l~;>cjbbT>g%xw?9ZP^To|@F;`w1XtUGR>m3=<O1OxlpZ(-Pf zv;I}V0zrsO&3UO^2C;us+|!0o?Sa6$EE*#Gl~>3e4X2=!*(u^$4t5}Xqgmx_PMpS+ zZ1N`gyEB|1t=-OE$O#B;TLf!zl6nsV7|*Xp*2g=1{;3Z+<05w_lea4dn31^woAaM~ z{!HV}-!!Fqk(#}y5vT6`yMlHwd?2HvPD~TX4dxE<l>8@cT$&!zj}_H?qr-$b=6%w| zT{DN;F-C!L5s?fBeM~3>Bhng=m~Uij+k@tNpSbvhG#rz(2awiMLd^}jGpxX?{W#XB zK)nJ)iT#zGGP^xfkKdi<kXiSgTZrwAlrsXF=tIS8!~8nshC2KhGAn-xE0D|zti~g_ zG-A0nF_3-A*J19GK&0gZ?xfVSqy}NOS$r4>(irH#Lz78XQO$be3DXi$P!TT%fMPnV zSecpT9XC9}f0ZOJ-OD|<j5^!PT~eU%U><FR(})?qqF<(2=AWv+lcE4hg)lhR(-Z!7 zh2xM{2kvpd?N6-)`SADi?;nbCsbCBDOx>H6WeWMHLE6oxC}*i-xdzox0M7(A0y&>> zM;j3;0FT=(6RyqBo_diWJVzUiC6Eqtq{C=v?Vk;ZMt<XKu@Q2;f_nCP;37<4ty4gM zaKbYG;Yf_;3Tp68v}$95?q~`VGBZpibHI=5n>Sp~40EDls%RGIFuwRr%gC<5CZZvJ zo<%8YS@Z@utJcR-@CV`#pDw+S-%K@KKPs{#C{o1na##VoVj4I5!db|siAfZKwg-(* zU}0cILzhukSD=f{2qSSSTR~tLhGsj;pLry8Jwc$XIpy1tz!|fcWMt;V%%zoqqWJnE zCXmY>rAYtm$>yB)ewO|95hCOr;_RrAzP+bHr?Rx_aaf#$D044&M=y#CDa&bw(27*a zXFz$BBZ0`s;(M3Xw+ieD2y7;E!jT9hs_>Gsu8twLZZ>XN8-Yaf&DR@1P4sXoY3ZXE zcMdW~Z)(anrjqLrM-YJ{r<nf|1n}A%hssPN-dvNB#lk%aXPNnR%lM_<x!FL|!UF}( za733;ZXe8*8dFqCq@N>77ru&m!OVi<E;#p9Ko!sA#t&&{1um8+-91$G?jVyKS!g8Y z;*A_}0wH7>rRxZdz0d8hX`_CKIEC`->EPQbkhW6epwnuk8sp!lD-NakjNj9EGvmWm zSHb4Pi4NohI&SRERbUao20DK`viJ<_n7=^>G2T$iCutj+qA~3a-zel)WJ$~9Nz0B# zSnv{!S%F<~y$*Go6Rc|G-nFZP{7J=UI-m~jG-g-j9EE~QeVZf=ASZO&3fQZkID!_} z%F=3e5`K#C#R^@r6H2I6E9XnPW@e9O3o*cmb?!B)gw(xHl-yM*x`NR_3e~-77I--W z_e#<~k`@3_YOnZkZbvqSWHnuAZ3-W6idbuUGgBdp0GO0H541TykLIz2)`k;q?5PHK z8SDEq*X8RVCX{^^o1~+-W5ao=NNU;*4WvYt{n>u#OLLR}Ypx(vE!@5|PzTYqX`e{o zI&XTSPxGvGW0p<9{V{}{r60rQoyv;$m}w+qNu9=D!)XOuac|Z2c;*7>==RH6MtVNY z3ftj*&Nr^uH}PO^9Rjrg8US0slh)ARMo%5}a(_+Lh^_Ou_$E~Wsda&D){e6e!{}}E zAivC?n+cK_C>4Hs3js29VEu6^kt}R3sVbu5u*1x3tio*8;Z+%figRUYbzlj>w@ph^ z&{4dGt-QJe8CSXqU&Pf5Ecjwf;}z;GvZ8O|7#v?fr_v>jIy5TuIu(z*+b=gce>`fR zmA$>GT&r*2RMvR=z(3FX&FL@5J0CR>IWBjE<}lIAC`d>y-q4bje4Wc)=o0<<70lh} zF=Hlze>)MuvZ=GgxsD<F<$_L^y(?qj39WueuI&}tF3*?!3+(G|j3;pKBTm}}nO z>ufYeIaEkqT;f}w(|nzTxOcx8a4@<u?yMvXKnTDGZ>|O9O4CgAH6h<04j${fHmp(Y z)=+*aNVj9+ot+f#lm*nQ**g}Gl$jC`wjWu<LE4WOLIe^JxJ#FOjWTlv`1S+SJE4G* zH^c$WEbGW(R>*;JWVQrg#U0E&t!2@8iC2x?5!WelI)ONbf$8@`wcfn#df!`uy*^Ba z%!QiofTwP4i1aqZlReI_R7DmCb1nD0@UHx!tUf)EkDlrsXaT~^NbB}qAB#)i_a4zR zDac0_s1tN8Nq;sZeDe&QahJEUtdkYz!pbdCgcHXzd(|?_??YYbFi9U4wS&mv3vGwa zr0)Y|fSo*-ij&bz#FqL4QCY3rCWSlaVpe*dDBa3qi_V;4<KMh+gG=RB20OsIaq?tX zj`3XUcK7t_uKIo_7JZ2S%;2WhD?nzO+td*p3``?5MAX!?r5E~B6CqsC<4iz#A4#c# zAOQ*fK}Jv}Mm7U^nJcPFe-mOyM?Lugjc{U#@IDbYLyBj}!Iu$N-ynxnN#&uj9xqXt z1?i>Bh@^O8az^tN{%cpIDiX+Jfkm~mDYf5Q25_LKdhO1~g1~tMz_B6zAD#20?z>@k zTuk}+M7KEHwD&e-b})B=@0DTnE?Li6UotVOMBnGSK4$n<TMrlV5*#dYWmf!fh6#&M zh4{D{M|$CAP2^R?+xA2r9x(I#04pi8<<po)-FXvkwly&g<Hc=e-xpq)mBzg1zrY+c zp>Zt(<gSrp>!0-G&+3h(U4A8Z=y3-VNE!N$&e~kdzH|A;q(y46`DrO(MPv2wN2CX^ zy2M}0g$l?AZ1xXtrbKa$wN!E6*Q=}IDiF8X8;;!1zPQT2!ogg;cindnY)WIo)Uu2L z{mfxPWe3)Jvl7CdSvY&WxZem)$$@27=Z_HQ*QjgD!+e`Tl^Q$~k(<w_lQ_Q7k2$xN z*+FRVp)$ub-7t|2a9-!nKZ@3Ja&I2vw-xC+9HF0i#2$YOlkTJ!wA7E=R0{*4rt2Om z&$X1#qXoDxi!$+dGwwQlL@jxAbo^ot^oDdv&ieu|M?9?M1^rf(&_ENmX@dLXCrTIt zqt>gQRamoebQ*2>JgkUc!wU7U(-}_eEga1YG2}e^gi?d&0+KjBdBY*POUa=L4L{w> zKk)1PevkvL$cH?O++RA=#vUJZ$Gq{`J(wBWe)3ThV(8DTqtEa)YgC#ekAyWMLI<I! zL4G9uh~?xvrDTPPVPaOm?1N{PRECWEFlj1-J<t#z8i&nHjvQrmV)+=g_tmtbV>-(C zNvBRXbRY3xKs`aLJq_g(Zao$mby_jj$IJ1aoZO4fb)`4n@ZDN=I)eQ_J62E!<OjWX z%Q8mn>2v<Pmu$@ZQvuRp<OgLS{y0xR$^NWFasU_O>>asRyH^A%@c6nUrq&*A#mci* z8(!Xf%pSE67dx=e9!u38biF$H9HVEc+8$9LJRLaHY$T>N&5wDJ%449BxBv9>@*1N= zQKzp$(Z+Ba;G6`OFcX|1bk0NN{H@=cAAi)GL>1t7%F8e}`#@(Tqb<MQ^BegT(ZJ^5 z@Eg%?DtjLasM1tKY3T~l2)Zlzwx)`yJ<Q4*Y%#+?kFv}~9kWzLGH31~<iU5ZCL*Yj z>*r+33*x+mE)QwmL7e)H*pj|xdxgJZd+q8tAJz2zr7yN`0M3VdoIh&eeH$FUpY?Af zzf5MlYie{0eAV}JnXg7cNa()u&6L9GI|$ZEK2>IX*KBDehTEFtW$eJrv@etI&E&Cn z{VH6d7|>=Et`66$vHN`lIMhQNuV``lJRHzF-S%?qujIzrPf_3rX3A&3C(j`S&V?EF zCKB5OX>cMhVPbqU3^dzj+#WvrIfNUVSOjB*(Wx)_*Qd@7*ozy_LE25T0SNG84J9Kw zl>ra^s+jJ+QI$_;O!@=_)-o8Hl)*xNuUP^ch^oLi#)S0n1?IW!4##IDRC2#Y^%`sL z*Q3=RaZh-~yus_6g?)DPthnlSz!7ROWsS%-K}1&vQWBPre;cTt5tTMas6XRYus}(y zGwE}w{ztM(jC$mFnar(*I7@GkDEI~_6GVeo(RGh;1%&c7==nR1$(`PaOAjQvxjzd& z`*UPgnse{EtKHVf(`%H&$O29_``@gfokFvizZJjVT;3Pf^ySLE+WZ==w7Tjaw=Oi4 zJfRde0RCXmgpdXmw8l5Ivj9({?n2qfxu+a_p)AD!b5*SfYnu#InpGr$RUFgE1iH(n z;`AYGBVeiDXYONckwxT*ekZnhLisrt2r&g5bKqQOYBevg@G3e%r@eb40jy%`D1xq? zEqIbjW<`5G%*6=i4M<1V8B*4X(Q@T8{sc0n3@#Fg6kvEV$E4+?$@;a>a#<9?cELWP zK<v925c(GSIynd^SMjsA<V&*w)O}nBHYRgqp|3`vH_=PvlQK!2Q3nS@E##$s{ort} zh?aQ;=U_ty`V^4DhEbJ<kv7RSY=z+Q4qnm-5WI-(oo`}X=VK`5e6VWNOp|BLdevNr z9xsEOhz8bm@9RXfpLL9VQlNezl*LcTUo&#`T_uMa|71u(7h{xNSZ=|{P8u*dQC)q1 zq@pzNfcgI8?K&D!KKnUn5UO*WhIUbK9{1REV&N!%5I8+*%jC@~1%z!+3Q~EVpQp2^ zTGUwyeHg^n3VjW!9mVQh#CXQa1Z!7H|Jf}kmwyPa4b+9u@8#nCrqomDDk}Av0$I(t zv{CYBV}3uiF%hAV_FS~E@h>PKa2aPhOeXoy)<@C>rK&I*52vtY(5_*@=lU<gF@c)% z%}rjURpSYA*8C7(F5hFM?guuu8SE{f_aa6a2%g8`C_wEavcI<vdY|p#h&A9%B0m;o zBlctEXV$<#&zh>4EHIal%H6!w$Rv{j<_XiK;Km>%CXn4ER)x3TxQiwa873AqakQAH znT6f1Um&TQEgk0ui{9%Ifm;-!aqb_77u^X~Q{x+6h02X~{2q$p=Bc5n$ok0zY3pX5 z@jQ(Dq<b(7$SRM){5$O4u?4^q!FIXbM_UCgPZMI$KkJhg6t%w4Qe-RyRoUhTR6`V1 z(yc&frxX)wczLCb2GlS&j=Qw>C6BKLW|kDNvrMHEW;NU+z8}4z#9iSPnU@#)>I3+$ z*{M~k?+(>^<gH8hk$HcqH|QVx1}kMZwr17Fv-bNopm!SUYA=kGVD1y!R<;UcUI|Nw z0BCzTLCsHVT<3v*j=?n528}Ss0;pJwwiC?P72|yNlKJ40x)`*9hqv{`n>_rxW({}a zQnQHTB3Dsp0L8`Nw?vAd{AgJEzoDY$V2!QSMkPR-ha}%2AOzeaKD@^i4*xY$BVg3) z*f<SZ5jhdxMQH^m+^zu^hO$;B*I9yGaSsQ8$d|PN#^9LRO%+G8P4d#kat%gAs`Jnz z!$9c>dfW5n|Ag)DiILs~pkSZNe3qzz0pIWB)oJiQ>^W$2Q8JUGkOX$p1vPgwYUT~+ zWWQ1F)Eb2Xj{^(<Z6@3bGb}|u4gFqjl%#4*dkqRhgW1PYcpOBW&NaI}t#f#xj_s8I zp;P1Z3SQ$-Pd?wAK`+dkjW~4|WEu_nH^8dQIpW3H$0pJD%|!f*@6l{j{B_gz29CiX zyK3D}X=j+C1}^OmNEXPG-I-xde*rW_jKk;@^Uo1IBfIOey_qP-;0gX$4(Y9vrn30} z6PR_YSb{H=%)BZJL<b_-P#pRIb*NdsnN}9ifgb<OW~JST2r`;PqdCmA>?lGR#oLK7 zjy@8%qzX?}3`R)!6c`4&(vUra=moS#Iwvcso7X>~dj~@S@NC&MYYZm`0tG{vY6xxz zv9E&N`1*Ns2TwY0!0JqYui_!cwsl~_mZ0`5#AfD>Oiz(GFx^PoK@Z2Dft<7HU#=A9 zw80=9w~4*>ojK*rXyZaE?!UOkH2-Lf{7Wz0h0X@S#6g_s3mhBku>&r5Y$oaEg75*f z-Vh*-QPeMIO8SS4?4T*7>^^MQ=8R}k{c<Gs)jYGf4c-HfS*$36o#P~On;n~X%@5~C z*mg`;A7lrPTGmAhp`_%1)cCb+N#=;}Q{+-da~T;pfIg>nZTM?p$)C~FgaaX~@nMZm z`csy~K3a5ABuy(z&@e%|a08B`PWwPk&gnES92jGI2c<z;bF;ZKA^J=o0N@{pbcJJE z>@V8hOsoGHS>1;hfQk!DBGP%y$Q+aM1D{%%M_vdvQaMGSzUoMVtLE@6A(>Yu4t=M4 zk=w0;GAO<LZXxdJ(4=o7P=km?<fXwSjXU@K%@<?}k8LeDfX0O>lRSnpQ4wd!t1e)8 z{$M5u2E85hi^~D~!sWpilsklc>cNbJRCbtsF%y|F%b_|%DbKiOb#&_S^d3a^F`gqj zaZr5QyNuj%31hq<8XGr`aII`Cx!L7kM6?_zYi_)FuWwXWVN8fNb4V9956_H#gk%_V z1h}oY204Cpev%nfe|x{;!c2*fa?6Izt0|~AYkkS`SO%NPNu5&2IP)RinDe)JmRo*; z<S))t<l`6bp6QmHFCYb}O8)%RZ*}haF=Y-XeXfAaum7THSW~o}S+K<O2vvA9uv@EZ zE&u=)%4TvX6MYrL8gZV?9u`@_MW~zAr&LLfV_E2mDD}Lt15?a7f3~{$e%Te~yRub2 z97@tD!dqa#;&FWCLOT!PPluA|nUN?hxvvm**}{#hVH2`*ug(<7qGUfRjN4wEEtfp- zPD!OX_hFjNHMQ%=q*Ya+%(N)u`l+D(3vStB(Cb>EG^JQ|_B9L9KU=Io7qAh_HO0fs zMtM*6E_46wPV~)aVph=KVhfz12qr6oC6v{?LhP8YRtmfpdeMu{FXgmP_@o2_Kc5r+ zAP?Y*i?$MS`d_|@H_;4tN)L`GY+;x+6AlY*DVDn^rrvrL{V0?-&}8Y})l6H>M<?%- zWS`KO3}K_KK-2k)-GG?cZqLCc86wMad`lbx4BkfwP6BJ}Q52q3;7eUV-Sd1pMX=Z# z1gxOp`xWEDYIFQ729@WZlYh9fqn5~@I?>m<9}wta1CgpY%=)7eLp#Gl7VhowQYYmW z4b-8^-|HF`243yF#HbNS4!R@|ny-O<O-uC<k2LwoIqEA_v@{|H5j?5kyWAo3fZken z=s<I3W+$o%?2@&Q;VUzeYLOI_D=kow_u$m&9gy<Xa`}o+!H8RrnqHN{UN6EOiq3LF z<b@r0BP8CT%4*fBA6p>T*s-?vE*pt5mK(pD4d&wX#x%krewS6>hyW%Z@(CPbE?}Xm zCMqZOl9StP2}ZCvT@)YtcYJdy4WD+}?{Y^V0?ZF6Q&c|9k@87Khx}7&&mf~*!3v|I zDLXK<FjQq9)-r$n{yCO+dN?RMyuM#`&Z4!`vMyEJfDJ-=Gk=@Bq5Jw5yeOffjBG$@ z)*8h#tMqBx!VEraaZmJBX?-=IjH(r&%lw3Syoo&1=AsIFH<ZmN$lzin8dvKEL^ZnM z8-}X8!*2TGjGEySO6{XHfZ!CJJGGPR;)uJ@OOz0X&O<Q^k&R?(;|?a%){hEx!lbm} zrPzCOdhwE*s=3l#X)AYg(992Gq|-N^b?@d2UA|+iLe*LY^G#+^Xs2Ry9&@@<F7IVL zUW5K5fN_8laIBnP<ya=?nx+h8lGp&ZN<(cT!If@B>J0w7QR*ESj#tQhrYPO!Y(wX+ zwCRJUh^*5EKz88hLrMn`p3FNZ1XFEq+;pd2CK?tA3}hp3vx#t?bELkJrVsg4(OgqM z)ZSGa<2QH--G5`iZ>5t)C$BX#C^J=;7?g1kliFN!C^_|)ww8%ny*}jnXiGcA><RiF zv|_(0mu9@m4U>0znl`FXvWN4OQTF;N<rP*ScfAXy4x^E7=io=nTt`!RV6QC)Q0EN& z!UjBEYFT1$++v44QiDFDGrhNXP&V@@XNJuzl~B-u1!$+zm9wW-!Sc<6t<6;zbeJ@Q z@3tR@)Mw9~)bJsm!orlJGik~M3cxkqtd+`^>8r!ivD1|^3TMpX?-$8>nJW~?82WhJ zroOZ&=*{(Tq9=POyE6d|vBd0+6k6kO+MdRlg;QyEV>vrO5g0%<^ii6@x9T80k?iVN zbc<`6^C<hJ)P`KwhvYq#dLxl^l3tTPwc;qZyjHnxS8S$N_HKh&8r|Y%SIr&B@aAu; zbiDSg{HO{+gPo^fc8)&Qj!#z=ws^y%_D0mLvcdg8Uo+Bj+049PuWewSI^6=6PY^P4 zr?#4<IM=3P<*Dx-`fE904ciT(4j9fV*xEg)+$4S((Mw*KBz?0;quy3qxNdzsN41&n z%7IQ4_Z4iA43}#Maz{1B*${VIhH1Sby{b^Z%M4wZB;{y|9BCBRa#BREl&pnZGOuh+ zU^l}+Z|#iT>7>SQw<xz6d?+^DinJ}5p>dt#{oGAeNGbWsk(v3Y9P$FX8k)Ng5%dk? z-K#<@i)(nk$<DjX)=Opc>JkY%kyZb}UbUkt`9h0-n`}B|S3ESyoqN1$&UEB9ttY}Z z-(Z*MK^-yUY)qvk&)a>RWkC|CYs$!sosui6kGhzw#q8~`IMksQ`}rlH3L4Nr59&%X zj4ogd(3GSCs1u1dxU((O>_AC7tmxa8DSM@$+hB_X2+pp!h0L#cEFd1+UaJ4MGVYCv z%;(Wwcj!r=T3`yw2?3go8b7-=l4sJhTE>+gQ~7T5W=l`yMlL2+D&(JYY}?hM!<?1c zY5@71oKcnB=IY#)`S#J_X#25WKkX^r8JynaKR@LbXDzq3Q^#AXJS~`1qf^!r?Ft90 z<K&<NkyU74jub>uSL}Trl&rgkNjTnmLH|+0+_;qctn2J`=Wxe2KDpXgU^SKYX$gwn zp41CGE`K3_m^DUzW<te6GN3Zc`r9B&0M_ds)uGBx(yC6&8R{-_>l;U|^;e>812z4{ zq}PJ55P31JT=jDGb+TM*ad@t)G(N~5%66anwczfx+gUuvB2e;M$1{siB~@6F;fksD zj1rBanaHlJozg?i{zc^}I5Ib?T}kku?!>~i_33YQluffR)RmH?^%@VteDM$!xo+XX zoA(*ib$zUtGNW;(`KB;zMN|XY=S00xEw`~<6(nI7KEMUkx*W2nn5nB%!`Yxy(E5Zt z%UrF7_WKPlsWyu_kjEvghOlfx-QC+YLQ(Kb&=;CFTixK9FY(K}D$VYoEYI8OgGXj* zGfWl?z5EXbW=8tFM5nLx{16EyjJFD7a;jef`rAmZrNog!osOPz&bAYi`{~rV;ED*R z=hCh#KM^bVJegl`Hjn<Qxz%f_oGNb#{~nfm@7NPM?+HaZQ4caD5>lm2??Hd#pj8r3 z+>j+@V=C8stVjr2=0vTvcB=mi29`Xz1wgiwm9bS$7K@#%m1_y&)bc6nWp*4~wW||C zdR04AHbb|4s6ZC)_|iS@AZ(qz_mb>ADm?2&L0DhSx=!&vOWB)qzb`gUpQ-Gm+G2!r zxe>tL;{7!$PjXrHea5eKsJ|#QX-}>~Z){<9LSDeF-+^BZ%_J*8mhPokm@!EPz&q;X z(Up(#GdHATbJ-2Lo_9bOs=P>sbqDRLNoz0950*?VBC}mLzgRmv#guG6D%roCYpszf z?DcwEl})UN(^K{#x%@mq#J5PGTJ%`Cnv9o810<zZ?#Ymr>J(BCW)!8JK4oRfAqApF z%DSdOEDBDo`0kqzdXxPY{?3!`5P)Z|l3iNi<(a06sGLLAsG=?|>ac8nj`i6s_IWa^ zy*Amo+cB^AeRDk-b}d0C1pw>5V0&_fe41TcJ^>=_T_%M9V`!9CZ*a<}<4FN&y-)mO z-vgybYm|;cl^*Z2UQkDCOoGHYk0t8nivXHRU8AhKS`$VfZ+tx|^K?&5t0y(EQxB^O z)yD^}EH+o=VpDo2{1&k%=4>667J)s*;3ZqB4l@7FyE?(?!)Sfs4iE;-WMRh~*eVKH z;!o2Kptu_QF<`I3K>Bf}m19?7V6etg^Y|n)DbdAV<`I(Cd&})hz?Z)#RgkX#7NMx0 zL7zBw&WUi3OfDoo($LS8R?M3zqn^*3qpnJHa^fjQIO=0n&1Y-Df7QW=BNM=zQddGL zH27c|Nl~X|+5dY??v<?go9RxF{-IA_Rl^mHzHt&Bc8x;vw!Wun?-p2xzPbm!$_X2Y zGh8C|S8PhA*sZr;e69aYsL{JkBN2Poh5ARnF9)rHlm>r}{-|r%Q#z;^yU8ZLLs(>p zDBCe>f=N;WASHB)94+0e$SEb^^%5;49YGKky0h*1-eq`$Lu}DCj;?X3&Q8xh&1%-Y zB`5~J%F}wi>G)sH_*3H|fgSdHp;qgk`d4~`UtXXDD;7w9uGI;DqCmycxclncR-K^- z=rfdH@SSEI8R{T;rtc6naxx=+3beP-w{ir6p2!3{3sF6qca@js>;hQGGp&08^RyX( zzSW_R#+#~FV4trlEFD}gkr=(k7BS8V>mPdv?<^d<`Cy4;>-43X;=L}u8&&0yMNPXy zAyt>{fW+*^FzfX)%_l&inUm`tMNt;Uz)a65>gbX2C@{-^8tEJPLf-{o*I+*eO}{FJ zab?uaAALZI`HYzKE=fl%(}NzFw>|^~0s{Z7XGO`jG>YlIT3DA1&*BUgq`pmxsImxr ztPFj9d}YFL$-d4W$`7H)J5Vv}MVgoeKX<Ckh^Em=f5IV6mCnT+QT)f1yNCGhX}S$f zFy_9@S1t#r{sZCvoNk}1E75j=>MT=5eZrPpXFYCwZ~fIDcV#noBjlBKx$u5WwsyeP z&6Eqjq7|2^pZ%Z_{!q!Y)Ew~4-!vm>sAy^cSIDBhy3qGO0#NT<`C0DFk8)Jy*Hq7y zv{4CYa@ec0$973?g+0y~dMWt;34YJR6g0Uub>4ULv4~vgc#=E1B5W_6W*3)o#9u=( zQH(pJxqiz*^tGX(|1e8mdM(peB=layWzSgJl$*<=N1|iom>;kw?dzv+T*!9)v2_#w z?)ZZB?KdN(L&8gI$ZK5BYwmW9u-JxbC!8K}^?wkx%fywT1f^<G)r(3YzR>k<XrUTa z5>O(hej~dYJ&o)M3?I9=3I*SUoQf=xsbxQMW&&tn4Qh6_>X)3}r=IuE2GUSmi^91d zq?+r$e?Fw%dHI9aEymj64YS%IWmNaw{LGe0IoMyC%-AohxoMJ}l-7}u>jrIa{v{;^ z{nY9X?6Ib}LhfD*thxPPx&BX6Ww5VZ$mB%6lpPp@NU5$;G5J~<ySzEPUv9usQF1Q* zqdIhezYgi6>Q*hh6dlHWW}n+;KGCy7fd}SeFBos|r(xtQsC#C}JMVj1-stKs?YR7x zi58Swn7aCe+~5Ne=#6`frG7a2^_O=mLY@a$;pDpvQ6X`e-lX6V6fL?73D{r(NIDSE z27?LDbt8pS)B;@lp>Du|hpYZ!bCmc<_9Um`g`R@S`*}cbMdJ$GLmSu}zL_Hv^KK|s zbAEPmtU#nM`;D6eB#9=`TPN~JN50QqW+?xZs6npIr%lC*PN2J92Z=YL<Usl6T;JD; z00E$my5OdqX$eax3nn3j1>ggugXL3~?--(uIW={lZ_%al?$9J8I8cS88aTY7d@wj# zt{!5g8B3*li&H!=`7$dcN#4(}QmQXL=d@$8#CdslP$#L!YK6yV_jvF#%EP|M3>Mlj z`mNiffWPb#M6*Pe;nAQ_xOLR`b+RjHzUd}><FnzzWR1W}2`Q|MXFROjgVB)_e9Gr1 z+nFQZ!Fa_z`X|ROmew*-*wmOdSOKbhKlBnZoEb00UlDEZvWfJ!R9HJ5n`2@>TPkGz z(32<cf@p;wC-vQ^Nu3pD*#Cv0$gujfE$8=lF9?hZr#0j0u+*1?i3%s)@R`%y8!q!v zjR+uC#J}3+T#gAjhV|#ynRv+0OUNXk`TY$4d37>#a>#<zAYm2mZ+DGzzo3Ey@R*4b zV7ffjnfxH`qCAyVGei_u$O<yTBt&Y<kTQL4Cs=lF&@CtJ_?<Z-Pi)pHsE!YWesAKb zali|thzw?k2~``@u0pD#5CWo}g5@S^+Kqn2tcyBt3C8HCS3Hh@U7Al*G?L<P+@Uhe zZrkiL9Ke*8^p3!R?3Toy7nC-aj1=>4se>$z`Q<@;c4itNC5JmTLf_5pbL2pkFYbTr zY7-)yY8tfe<JZ{TN&Ad4Vkg}8-?n=OId{1LR}sjD$E37>kRkYC%xQ&8r=4U8w`yAL zTSXXqGy~y)mj&DaUWJ)24cR@!?`=mIVh5lEX5p~ZO%ov{sj=7nkSh<H3|W#6D=3R% zMlw%1L)vCl*DD*RdLdIEXCmYnZT1U5hZ&;I@Yv7#`h_P7m2-2Jdj2BD@xx9*N-`fT z5wgb)JROGIKPQm`BArnc$-<(g5~G|gzwF>DnUVHf!uFjMgjWs+-3QQD>1Wrp!=wra zR-LRbtQWK|5~KcDo&f)e<OB3CmyQwGqX#vEgXT>%jb9rys`ttKeK(VR?oExJsq?&I zm1b8wL=W(tXPI0z@KUccM7TiqjA6bHM-7vA^h*uv@<JXA0#1)#8J-2tXaRVHQwj&y zlU>AVQ6}`jYk=eG?1)mg{K1xYIhmQ?Vr6EiEUe0hy~2|H5L!>O6~)Cu3SN=bQKEG> zjS@wCJWaFWL~^%bVa*k=2)6@N>xbiu!4kgw|8e$XA{Xw6uj4JW-dz&9P;8X&NmmSr z-AA|swR|Ct!e9Nnc&*`7><!hq?~1-!dBFsB0I~W?vp+?&J74_Q-pJ|6`KLclr|LmM zUa~zV$w`Vfas+4_3IOHlKR6f=^MnD>m&&X<k(_`ZroOVjt0HAk!3H3Ce<_XOSVlr< z8@f~$nK|_q*xMAzhi=fAv;Db^d(zJcW9&r^qZ#Pi6#kYhc!U|!>DwOW;$?2*FXi;> zH@B%=Kl=^4NNtkf4L`0#EZ|EAABHzFb*)jku|W`7<tXtgI?*7jB44iE&?<~-DEdV? zLl@7D0p`w;rHQx8Q&ow__d3yls!Y-8Su?386+(oIrbr{v)Pmf>vJBn1!kD4PxC7Np zja_EmY7Rf0La?<w@f=%SE(&PMrZ!pq?6WnV$BfsH9*T7Jmec;j-h4P>+%-V?`kAC3 zCDZTjpGcE+BBQ<4o&DxEm?cSdD5-!dbr(WTT(S>5dWK1?Hj|#hQICL7md-Zb=e3=L z5Ia|VqVaF6w{#lqH>#|cr5mR&b+uLBhM78E5q~aZ-{7UX&}ec91K6UsWm(50@wTQk z8+s;kPHn}wJ-)HhILE2}T>p8j1x-LdwVnsmYSNy7{GL;c4XMp9pYdjr=qAJCdk6Ta zn|Y>oSk4QGV~E%{db_m(Ew)<4^95d<Kv_W~dRdQETTB#~26TvL;703*D^M}S`=0uJ z))&$>pBIQ2wLu8G1bL^r;+c*jNgpp0bg;}*2cz5B_(8NbFFGS9K%QNKDjVdO+AET( zNN~6C<cwxILN>baFnGth_hyDgQc?K{WPxcktInuAJXD#20%$qT&HbW*u7)vxH&|^x zd^>k>jrwAVMQC<zu$!#^*|@)tk^2V*$h3#r1s^P|#6hajBJeaBfAPy(&4Q05s1c$L zTeG^jUe-=#P7r=UOp_`;`aLI5^Q}kq*gkrm8Gp&KUMqvj{}`CLV{VaZnVbBn1b2C- z<#-%OSA9%|nFuhyoulahj|tFl<rBnSRF-;szvy{t$|-@(41?`&=c?+UyFHIgv%cA7 zOeInyL8Pth;uRy#^g2VA--y`T!L9a}{c9C->e+7v2XA{UQ+Yjl?s^UCDCEITr8H(z zk0xsYI|1vruB<p2b2Pt7iV0Y*Nc{Zvss9jUHs39Kiu5dIoe3|Yt&%3`$`TVirpj9r z2@#&$L|vsC>WNKc8nlDBv#3Tm4)u*ZCtW$;spTLotjxv21O}^5dLGTM>ULb}bDd0o zi$)7~j)oUF(Wcxz;!7mK?RT5^;%K*)gG-h__G0BL^=Z4l8~5;^FpYr|?a#j+hvse^ zoB~!xjQ=f#{<!i3W38=i?7Dhd%5V$maCJa1a5#P9^d`(V0StgUS2WrQVr`@_5dj8u zYEM2NFAlxw^d8~n^c!7w+d}EfA9phlpi?0~m0{f=HEUEjqgdev)3D;c-p)Sj9P@Bt z&p0+x&u>uo!_Twv_9ap}xc7CNX868n<ZQSQo)z@HoO8}jAslj6>{9k?kwTR;@l}i~ z1i0OAy6+6$@b}?JL8=>MjT0u}*Y?2tIrQ|?3j|F3k)eRV-K;pXCGK*n%h?lgqJ=1K zm}@N1BKhK0eEe7RYwRyHJ99A5;U6y=lJrm~dK0CXB<(Suc?0Av-hO=Hv{ZY;reU<o zhZK*r#HJ&D+O!2?dR)X>M$p*;EcYWNc=itGPZ02rv6n3}te9{b8aHq@bVw$zgiGZE zyVE{&kZXH9owr|%uMJ@eWuR<HgEC8<Y+7iFR4`H8n<yE{XY91LMw&Arts6#q+U$&) z$`4d054w~<9JO6-oSZ+2j+@wdhUrw#l?X4>UVKuXGWI|L`WAbqAw3|H!KHO8kD+HP zFLSDSzl97lv?1UV6OHv*x5w**4wRheu-Ov_dC$T4YA%90`A2xF`{rT-JuQ)Hn*@;f zau!PUjReg=Qu_ToxB<bP5z(-7qY9;HD=}Uw8Tl9lRP`UrOd9Hik+BIxN&hU#1TkQb zS7vYa;I_52%=7)(Oe?f0M6rCP1#RrlYYcEjetTsc>8+FLo$d*-P4<T78bWQbrch?K zA<G*9-Yk_yYLVB?z1<B$jH)+hQny9mUwE%?B26RLrphy$>(bmvCftw;la4|!Pa~;~ zwD^DmlN>AFjuB&RmV6K()!u(R1d8h=3qi@E0t~T15aAO;OavtIjf^g?kmMnDR$E9x z(PF!GVuh6Z>d+T>vo+`z0nG);^R=MX$2}gbe_LZR>GC-|HJdtYYgC@PU&B%|+?z1} z0kh4%cFt6PtjLVI^3yVkTmv_FO#o(1(6r;&A&7hAU_LTcezC*^vUy_)as<$!0t|kC z@~^a60^L+qpU55AuhzdTW=BTRJpSG^KgB~4L-YskIElv+#Ya=r?I=dYV6ix&OgT~a zAGb-)D*|HCWblm@{d&}1>1hoC^VS!Sc!qGl{3IN(XMPPz5(O^6aMqEA;&a*mg}i+N z;A;Y2Sdm0I&8b#ECcJ(cgc^M6Y4kpF@DNco0#q1&qW_MaG!C6KtQ9(RuH!!<p&pYg zF2XETi$%;*WXlP{V+4^w2KNeC<Ru|MCl!nw#TtQuc7hZ=MO`0^OCZY7PS(jdv+t8r zN7+H9y25#<pNJcG<bCM#K5i3%uunt94>BKCTtDZsWsqm~rIu>0e9L5K_~9(X@$uWe z_KC+ssZ&EIL&1nK2=QLSn#Mj)H1|mGgm|qoe?S_Yd2G0D4~eg3<uN1k<dEQDAU-F_ z9{|uIY9tgZf@@@m>-P(5%=@06Cqk&#V9>Qh7V&n1O!vDBx<u3pSzuJsaTqcU!ZT^2 z(-#{oj?C@b(=RHo+ghzl=nmGwtz*Y)mbQ&<<OEv?j1Y$3=1m$^dm25t1W9n)zIU2G zZ=W@B9D=M|d!<h1i`p{T891}T1gFv!_oo=v48FbREwxff_WXz%#+4^cJgH=~{=A4r z_O;HEZ)W{;|Ni55)<!yJDf~8I!N&yIMsYy?6d+wYwFou>OZ9{q)r`IE;SI7{*nx$n zN;SQ;OucF2ip_4~&f#OLm#IwU9b%hp2!6S<@@*+BRT_BQkpJ);4L?}<JpjW4E|7!} zW*B)g4Tiu@7;VI`TgddK;hA#(S2_?rCvsu{p}it?WQ?JUV6v$Msoj>{Ia;>8vq*?F z5f2-Z!lw+kP=p$ZG6^RjMmdv}st7QDZRMaUhir{NYjA>@!P5yt{nnVZnp(5nuvF;H zaY&eb(50rEZ1$r~p@XLqWsRxTQ%}yB8r^W+S$S3xR7d0DSwtOfrkn|zG^t`^_ux4J zZuX-f$3>N?Ls5-pd_<w%8~peh_f1gcyW*zi7MyZ_WgJn`qhGR{z<=UQGh-6(0LvB= zO}dE*&79ND?utiY@Y!@op<J|3_53Kc?`B)9tY{<W_@kbWXKaEp&<gA=E}x*L7eROo z<3%qY?^C<&drv*A<cse-*)=P*YEQ(`m<dKx%!H2o)1#>z9pi?dutzu~A(=c@%-|1` zCq1neJ|R5|kY!JZbc2jwx24KRw#jgo|0z1}xTM}Tj2}=C5fpIYjNzW()~o<=n>#Z# z!%?}@(#j?v8qVA+Gu+!;rIr=$nYk*<hC3@OD>ECve0~2tf1S_gJkNce=f1D&d#Oz1 zzpr1{!o{f<^<K7(Q)yz~T|FVz-{Z{saLtUa8ZULOB{`Kb@1aN+E)-FEn43&*u<fhs zDxCOOxJwaSeo)v)Jn`-xAfS2#(zdT}=Q)_ty*4lEO9vJ7#bO4iV+sSJ1s2YM)_msK z$02X=cxo3W>+gp?n{I#Z<kd{Cnsi~{6-YXgHL{PU_kR*2tL69e#d}4ghBP9b^DYNW zu<2He?ooCBtYKrJ%4e%*)5h)Q9v_5>{-?F}fp+LF?`9AO@kwX0);VRjAJ6k%_di&6 zmkaGxtQ@CLGm#z5BHY#VWXp<_n7+ST6{!jmmQ6?JgkKHp=V0DH&M^VKM)%EouKN!N z{u!&axa5#&O2?2BF)0ARp}xJV(8otBVA=S#I1OgE@&@&Ii8@}Mv#HhtT!DNDV@va? z60qF`1>SjcSTBgC_1ACbJU8dslnk)m1GbQTZ$vs$+1Tm%j>`KO>Y2a3+E?cK&LOht z!)fKxXE1BQJuf<V?=vEWlQrN61dBR^36$y{d0m7X2eI_YA?TK4{gb00{u>bajiBOX zDiyoYU`1-~E$SaB=vLmO?pb5ucKe>Z+R<2=yhM*P++D>4EGZ$7TS2?~`INcRE<;;D zb4CmFeHFBauD#qtUSsRbv#(E(C(Q-BV(ndn>8Xmfla&$A>7S<b8WMq)M1v2V--@k@ zptef>#aLCFHMMvLWy`e_6sl8dOwyh}C|YvTs_%m(7H|ERbkO|$TjbI)<&0q^7E0bx zueN1Xf^)JMyrW+WmgAq^Gox3l0akG?LoHK57(vY@kmEy^rj||Id9Ws3KsB;Qy{|{J zjrQ*D*Q6I<9e$6kK%Dk^kKyyLkk?rRmC}-QZ>4*mi<&;(%Wf5Z&*|(IS5n|~nJ-#! zBb`6Op1Uefs9YDmwPBg!dZXd}hQ^7P`}$s)(D^?+yFtvY$_9)2@L%$RIu%c>I=X!k zNBUg_`)jN*H9|6fGqEsVOFzc~3Bk;C86ygNtc69uft?6FQf@3FDNWr*gn9`q&+k^{ zjo-Dh)+(|n@{QA0`|jZ6tuxl6B^Zb0ccYu~pZ72AN1jZBx~e2b3SPf4ov-#ZGP1<8 z)b!`so%@2zid7T%J7=CH*gKfV8|f-h`?ivDBDKx++&`de65gFYC}x@e<BIe1*XH!@ za8MIG!8Q<)Luj#>;GgRk1J)NC8x1dpfwDRVubvLfDd`6~LGqG<zedo1ior^4+45R6 z;$}A?n~jZRVS}obcCGm^hMAR+a|Rm_;0Nb{HTf2MBYO<y!5Yz@L9O}P9W<<YoWeRw zcbToTSyY~{Xx$;2=F9uY`aY#RrMR~?s43L-c`mH-yTz-|F5HBO;FHeD14+02MJ<hs z&w8Y9tWdXCj_s%OhYwNq&REF%iMyAa6&$yk8NqBm&PjKeXLVYHUC)VSNz8O#?nUps zi%!G!QTJ^0s2dRFhS;10u%r?TyWXv8KvQWeh`Xjp?aSBhqq(TibY^-Sp0l;PdbDPH zw4Fgf3QJKUPJ5ZATa@Z_J@pjG)!jYDl{erXDmb&zLFja|Uq74h-`)K>Kf;PMoo#a5 zSID2~{emCpPUq<R4saqcf~W7i0Ig=6Ay*%`b*FlQo(UeXoZw>==?C)rvR+#F1dbtQ z_@ep?IRV2O6{js<@X<C@`7Y^iU?vWr-1y#exdE(1XFJzYhhB7#Tu?j~%Puk)>bjPo zzRV`!TGiLUn(~p_V?Ej(V8_ay@;P?J6KF$~V$k|<IMvYFT{88FRqgHR9VfM<&tDT_ zM#Ovf(xDobRj2Ij_>8ZneN~@VXF(Snv|?NBZh^uDfBg3@Y{ss~s>s42!=Z?!)6K_> zhoI_>EyGToD|;^Eeq?u!W{}j~ep`WdDGdh$?`n;U?0cm*z%pExLL}8y$AmL@k-w-y z9iypVq8SW<l^JnCs=qm7Jvumxn;X&cx*GzO^kV!ack}pJp2tT8g<C=9_^dg&;nTy5 zX}bv$L9awj_?*Pk2P3Zf8y{$Lm{+s(@jheCEsEka-ddt=NFI~rZc@}T?uK-m^&Jlq zo4EemDqkp;{wkZ_5VS$Lu=fk1iX+oOUD{=RZ{}})1x<@}XfbI!d+XWKyI6g0x2lc( zjqrUHVRaToMjB0Q<H+5UlYmYWxZ-NZlY0-em$P&Li<>@kP69C-+rDo;4);76uoG;D z=+}Op_#CZQE7T9O=fu4o{2lpZ0Dd}zcJ`?y!_0D9jSuFi0s;_G1GQiVF)j}AZ888= zN;O8~ixXi3JgFq;O@xns(;!7w;0U0$b}C>b8}CLd(1QTES^|&C+kysCZmI^(l=}rl zidybR{kI897k2NowzB%9ZdvPA<xp$`!X296sdKCS`~BlZ-e|ZEg}j(Dbe7fuP9FUH z^=X|nsS|pQYA*HlGyk|mL5&~-2^fYzL4OQ~9+Ubal6Sh}lVLi|#|BY@mUrv*UM&w5 zs9Gq(L=Au^#p36ZeXxu3tXjO$ee?Q=K*j^aZa%1{o(AA`D5Pb5(9g~kP{CXef>LC- zhRAUP7{ot|tA#&HI`>NvxUegzuWnvyv0E9z7e-~NAenn3*i*vrs5Q!gIFzL;XCkZX z>~%Hj;?o)lC&BU%oZEQ;UXF(|^|;h+&tK3RhwifCC0i$C*Yb^kpkC2{vmizz%ilii zcD9ebEve`4lu8%Z;m;Uu&>%EpKsLPG!2meHA-4@l-OsoqXAHJd?%4mTS_=p%>F0TR zCEBzLT-2{d$D^o9rQ4W4>JR$vVuwt7t8eV!ORsnpmBz6Gf%(00>CVC;K#%<Haahg2 zY?QT%9oJ2Os+Xr*l0e5(otkW|3J<B7#%H+h2c=86+7-BKzK#~aNjZ2ougE((yjRZi zdDin-@>pNK5>{hZU@(OClS4DR5FhMyy^K!}$i%VT6D>!tL^qSCD0AelG0v-@*#IF~ zRrx8iP!EGh-%XL`p$kV3KF`iSGT<Sb$l)5j1hyxPlJec(yQ-^y=rabCT!!obc*b=x z?T^6xo4v@EA>6XjRM0qgKO1JwO`kt`ORBkCt(=f;sP^C%Vew4b#jjW!doIeaJj1C+ zEj!zObBTj-Y&s$!WoJu{?1l)H?o>#6cqXdI+I2NUq`Xg0TF&_WLlLoL9~m1T+0Hv- zyWrC~NyDVZo4Er6P`hVVwWdUmmbyKST2@nt50fn+;`fc_B#b}Y9XLhQc-eGD|MEAz z`j@Y(Q3=elYEd(#BnQ(J9q*n695B0(kntPBFP3U3;SZ<>%C3zr;SxOkfo+5JClr}( zI?^y@TOi8;e)EJ}aCu3fi|_tl97%W2;C_l5<CbOqkrN=5g205yf|Ed4bAR5x;{0-~ z&)G!#KB-A4uVD3zA?&$CTw7&u+z^x!cKpGW+2*JYM|J%#ppAbQ@g<kB7e^a^iX6t^ z*-u-D#1Tk4_syGHeyW+wPSEFb#GXt%Fob;wpt46LRh`hyZU-Mqkk%;WFj2W7B!QhH zRm0mGep<X}u?@YKD(DnZU33hp2DALTusa9q7w>RRs%{bi;@LvxnJz7Xk^Ztbw*|HK z`z5=+q9OeOj&@{JQusVU%1lJ^$!T<+?~pDbq|C-Q@M%LhxlHC$?^7v();d-?lJu;@ zV{78todB1E)+gx1)O^W?p)g&tUpW^`T(n$Usns2wPHrcF`?)h<;GHb&72<SFUl2hY zCNo69HghfcgSZPF`Nf-u&~cYg1W?=%Ukww-^0YouJc9$$H!4&6f>mS_9l*&J!`a&) zAkMju@Q<<s_0D8T6mF!dD6RB3WrKl@>Omtl5Y*A8Od)+1iYo@L$q!k`4x0>W&FhIA zomFv{W8FHsp@;G&2YA0k2}!kf^sgbUf~#wald_*8O-i5WE^FRu(FmwNS9<EQVTjc+ z$MQ_fQ7fM?&AjRn@DLYuns~^?mQYvT%ry_pjJ@b&hv5#hs;5X8&O57TbhH~yP{q){ zVg=x}vu6A<MaW!&!~$8J>4<Rw@&EbQxVc~Qr@ooB+V{aFEzp??D`3+0&MzSS5X)li z`TgUKv5%wB+T_7>$pl<W-WI4-&ePyzWAVws)F9$5ZT47`k=HY+n_u)#7}VKyjdX?Y zR0PWGq~zE=l$@w)gb+$yG4#*U=ooDY08Sq2k^P3^z6vcB2(CEx7pgJ}fB<vnENU)a zOzyoTP#oqWgq)g{Qof6q!_!sFSi<L!<>KJ491)f<)3$TB`JeqlyN?0U3|o})3bv5z z0Jy%evMVPiEh#T@%_DwS==z`_@>}W1i0~h=R}*da-)VLn<$o;>Ir_2r!>{~{Z_Zfe zsi(wve=k%63tVYq`F8^8B5{f{xX3@6bitMbbl2sK?>+f`$jsZ^Ha*rqFUK?PJ+@q| zDB(pc7E)7&83X}ka%6!=YNt&nz!Wh7A0<F)5@tE>PJt`fgvLyJxn=k4NZw!y$Va+3 zYiut{x$_}9Z2P{Wudq52)Gx<#sYsVdmO?vjm)zyzsI8)HzFYyDL4Xa17!7)hb2|Gz zso#+gcOO2HQ<qK>LC3-Ms0nEDu5?i5nmOlDVo9XGfhp>}b2(IQ(mHvyE5qde`!cBT zdrPFn0vEY_8eLGH3+8gItpX!F(Bwo=WDTUBhP8$Oniu@8z1d%awUB#CVn%f>$tck? z3N-ZDDoN(+AYjQr?{L+nXV?mt`wb7rvi8I|$yw$R{uAWqhPxXasHCT-Cb<547XNZL zuNj@(F@<BO^AQ2FxX(3#kJM7ot4gbn1<<eN^}I20^F%+|j(>OIX9RHVL9p-?YrGhb zG39!?H%pL%bB#_1jRvjsiMURD49ry*6fS_bS3~~0@~+WoLQE$ttMpG=Ga}T)0&xmv zrRLz5dKo+)>ofK(8nn@tO?sj4SP2W_Ykqu;3avL@gvuOpeb94W^7)}V84_pyhQ6f= zj!D?&Q3txvR_Ub2+j=$fQhU<@x8;|97v@!{gv?YO!oh+=!#DEwrw<}`>zK?!B<5l> zZ#22rU5|Sz&@7!SFfEZL`rWriIOPa7P^x`fM)J*ka_E)cm(^K0?&LP<DBhA-2&!Ma zx&(Q$<3wE-{9`Y@INxxj@RI(w!kqZFZ_{*on%w)U9mP-IoE~1g<|AS2iaT_gC-B33 z64;LIT9%|Bck&2F@7dBD!+)^cFB2sUU?OV#k5VpiQP9paac+wpuyeVk0HfE*E7mV* zLUsLsSiN2C)XQf*&vAFw>@EuFCG#o>Sf>ui6R9gQH3KovM@^u{%q@gr`JxPptV%ah zMCU%Y@g#o9$d2I@{BxsQ8L^K%9K2|<q|aXs)o==vIz{}Tt9N((dvqACe9hwC`sxSk zcP(t=)lnsYk%wTT%da=N_dLRca{jVe?uo6gU>MC`XareoAOe`#wYZiN)p}l=+w&=E zZ$$0Ypadq?_J?ba_=pw(izGY~b<6JKh3u4Iw<w5zOc6HTolEz*tNvyDR8d07LRyJ# z{Q_zRHxS|Xe3#Np(pjxn-5s8!<gedTd_vm3PFNMTUW>ehBk0?S7B>!p)CtH3!Nlc} zp9Fy<tqG|RKifAVRK1OK+~T`(rx!S3U;|gd?9n}&?uaO5xr2ps0b%y82%7S<xYr?q z-aQrg3N`jBNta--Xm4)+5x02yuSkFz*dA;9JI%jRt@IuDG3i5<6mtPt&Ja)PuGzl~ z|E@z|1Yr6AskVi`ja<1mOvFE&+$E}feaJumMltOt%Rr>wkSbxhN%Rv5ge0!GixT*? zAmhdclP?`Qao|IXDDmEO*PYU_OGI(`uNhV-g3>T1uGA#yvz|wK3xW7U(MnQ5D=SS5 z_zM*m9~xsu;t<+`;)}g!Cv{CGMmwBrnG0A-|7yypj>$o}O$Gw$BvD9}FI?zsx+Yie zC)3xBg%Xw`KZ)&)K+1fPpU!ypa6lgsdFkHA5EF~yzH7_ApLS%4M>a|3L)@<FYySpD zN%K*S*%>Gy!sfpqV)3$K?9y+oYTWGcJ?f<qg~*o#+DpMqp?xr*F<hjL_t=QbI5B}M zZ5-!t95}ZbM(T5F{*EDHrq8sHFg-FjDC4xt*d>>vD7#G*`ZgwDPz8l8W+A>Y6=&vA z#S3Cv^D<qL-dj7RvA`~fXMKnyTHKX!F;MBq+2!GT@6=Y(mrqQqi#vO9`jA<On=kE- zsGM1_no>kAsk_p|_4L;LYnqmkZFDulv-;O}8RDkoCr}zRd4A7d{41kc2Cgm}x5%n> zB!)c61eiUD)^gV#C&c1JiW{*3eD}?n*~oF-aoUv=7WBKpMs0YB>}0s>g4j0z)yI?R zN{=n9GH57~<B1?$zUy6x2iaSY0lopYS3OwYsz=o;Q_sS16F^UlT(Laju5a$%n^u2X z7aC=Q1Dmw!rvD8`yMeWc{kW8kwtv^GpqYdsePzTH2~njq_T96iw+y-n1u<WHDeaR= z{z%%fe$+&760}!tylq875sK`T{o`zsx@BCuMgHNiV>mgjGlwRebnE@3BtS(&!e3Wm z-yd=<-()KoFaC4)C#$&A&WJy2N-(-QMQS@?^m@(clYu#<ZRyRX-o!Bd?=Yz;U5~2d z^Eru7ZSe4Ki1GO-D<UmJLfn)Xr;RK<P0Aq1yDINyC)k0V!s#|A)1hi=5=8LN`S<%) zk-e~kz6hi*ukC0`Qyzk5CloAf>Es&PYcx}-Lpw;<8kf~NC^5ss@-hsjb>&=Hh&~*m zm{rtKeenJDu=#Au+J0~JlKcBjM>n<we$k2b&1av1`qgF2*+aAiTMg3)jhKqdV>?Zj zm2dzX6D}|5dZ@=zQjjq9`SyiL0pmrxD@~7JHp<Zk%5+0=p!42;3x2B(ISfj6NP4yx zn9w6mAc0N)T3RPNo^sY`L(m@m1#1ej8DCWig0`-fmeOhEe_j0t*(JGcZHOQK*xfXR zVh~D{C6^EKUJ>(#vM;1b1qWd2-$bu;#W=r>q4maCBvy?4lhB)uslU*76!Jq)DlVmq z>{wBEaOr9CZ`<ca;A6IW<RIb+H!wOboG4m;*p0o9NId0JBjkc2X%m&KGE|hLib=_P z86-0`aE?(=t5&Ibcsc4X`mj3f_<uBG9|I}WS5(Xi+y|l7^$|U0iA?<t)x(ZnYod=b z`7Xx3tNV|1*tPuLy^<s45cvU+LLW%Jy6Rp>iQMeOw^vVfd6kZXIgVE=d@7VfO12z7 zwH+<-2r&lJEwc}YC|xhUQ{UHreVpKV40;q3LL6~bX1xCahfSEr5R^_6Up?OHAs%{e z2OTcgJ=|PBHvLE^L2Lq(>u5yi$b0zeOoUL+@$}`@Z%H-359yrP!unXQ@`InZQ6(lQ z$VDf)M32Ls0@CKxlUy6jX=Z;5NWsWcJ`JQ0{rubN%wZ@YR(&(%qeT2wx@Vh5yyTJ* zamET25WHt5DAa_MWJIXf^O$jJ+?1SA>j8@kl>9a(k6`RHGYL~Wh-RA+x1ar_hkbrX zl_&73GE7)mk^zBDDRcK%c}O=8a8b58JAnXex97oPCG$T|h8F~Ge$&uXCDm>>($9zM z7B5J3bW7Xl#~^#L^$T*DAPG*lgn#!Lo}YvRAe%ieHP3_rAkirh=K-3YC!KJA>*)2v zv2OX90VZKiODnTNtp672)45i&qd4}R+i-Qgt#`8+i{91wo(_(=5ZFDG&h{k{iuf%f zBjTmwq^8-e7K+H2vFXT?UJx264Bx*SE1kWf_}^n5+mL(JQ@PTvmS)`O7_A#U8&m^Q z7+H{?@r#?pV`rF(7#UfBDe|mDkxms(!OOK!y*zeAIl8e8SMr=Yx8&+7?!Aik6<!L8 z)mK$#KmW{jv8L-(w_Exc*d>Zzz25p`;@ihJy}ve}MXJ-x5bJUvU=P4lpzn5`+n^D= zZj%~fngnonUc@(p5YlNmavo=*(ljy!)8-y-U3B$gl@QtIv;=Q2E}lOj@Zf}0IKEVO zsEu;8%v(!zNzsu6wUAr%lcQ4+vibT8ICvjZQKcKx2$JnuK)<9a22!z?N@OQW<kmWa zS<=g=1M6Q6-=qsPTE|(B{b=wz*Z5ub_ScuiM+MLAm^BpC2Mf*JI@BYhm{wC_eW5JL z$^=PQyl?lor|Ku%Ze|-MOpAbTaq&G7f;&MNVXkPPq|M$fyzyBgGZx1^g`-mxyc(2- z8W?x;ZL|fX+)CH9paCNtQ3W!m!(Z-u`~9}sPoqtEs}^YxcVjRxEp|&S`#)z=p^!o; zOPJk_nc>NeQDw5b;qwdxn<{ZvPILmVIF6S&|3N$wU);@-J7E%X=1i9H@4DSTR<MaT zLauXh(tCY6yYt)OUwN+DhUCm}KX^$B{zEzc9C7Hd@-jxm1ND=j))M(khb&d>TxwMj zK{PNkpKs_1yb~xyd$j(kO^+%*l46Blyu&%z|7+wp+4;<&>_b6HU;(mT;eza*68Yk8 z%#{V1dc1t`f(*SxWS)0&>9(B7&bHh<RdyMq$mo_{G;N5=bB=1iZJY1BAV*k@e%Kz9 zmb<Fw6M*`;TYCz0cyM6$EUr@K;;#>u|IJAsm$-8&;<pi4Tl1^qz+slnUcDk*8Is)t z;?Gsq-ytqSU!EgwX^FHj^OFm5V<$-O9yb*>OklFC9JKZe5!~{ZFN6yCjEOY5vpu3e zb>8TfF78f$Fpp;bJtH6xRDDmb56`(njqCTuo==kQ>aMSV)O$3ZU)kIA_F`FMS5xn3 zP~Bh{^j;S|Rz~{iSaO}^=gAhyhFK^WFTqAb|MotL@Jp2`Uer3&`O8o1tZw3MVYAW? z&cXR^;4DXH?cfX#g-Jb+ooBjdUoJaGdsuxBJ8+o9zSd=3vXqaP%U(dvF39vTWm~$> z_H*U>N_Kb4+5U@F%M0SgujC7*Zb=5ncYqYCyS$hWhUw?U+H)+=#y@o>td2jMcI#=J z^)GA{HXiRMzcwc<E4=9yb;b$fzCJT4%p#bWt3;e4?nk$r=P{<FM{hLNOUQRq>wLr9 z*HNVru{xT8Z*(Ox2wQTUKO*R|I(mio4Mo2!^!Ua72#}t@JA9{b2XGBLYz2$ipurb% z%O#4Apyzee2QSi*FMh~u;lv^qo?dMq8Pza;KX-72d*OVm<@!Fdzd-ExD<g-_QEVYM zRO!PCu^^c9`tp9V!HzuOJ~{rVd1CnWUL?VhP=EJ7|7M-AD+(Hw`_`k3OAl8p+pfL- zkgPONaI`b$HEw*Xrl151P`dhMi(B!i{oV4;770hnNvNfuR%%hj%dX4a@-6stu{Y)W z82X(I@mXpL=Q1ZRg>#5~>rc~CA=L1L<mL3=8hKy6v5y*SCAgsnB2LNf7bi+vqfBrb z$5tN;=7`|{m^smzQNV_Y(`;c3TPn^x0w;mrc)KqFs~;jUbRD0XiUWoDohR-32cka! ze4?}19!@+QA2w6XQ{mjCl+tG5<qhc+wCG%i7EwQa2JjT%BVU_3PS+o@cs^Emw+@`A zVL6nlZoCumaw1Vu#pzAWse#(4j|19rIVU$~*8Qp)LY)&{fBv9djpQE+W!@q9d~hgh z?Sb52nM0XheK`*VKfrD4JnB=c&*suRN8GxL0Ln@5h_#rN8L%4Y@IBuzO9c`K%(I$@ zA3f_3nVO|uT*^*8<{@A*>?{h*zz#mTBqN?du>!E<+Spd!$uV<~&$E2Zh2^82GE&;- z-OXJ?Z9&*ksoO<uXP&hfPDAsrP`kGajKqH;P&~$0zFRK&VRc!Wnm<4o&~^~cJ?t#D z|5+YG=Eur&R|!3ir_GArj9<WYWc-9qmfz;I6C_-S;<Q&XFzJNw(LD6QC&HW|+!fgJ z;Eug;4JTa=j1~eyg>yDN(Evc66Gf;?`9>I%3MMd3${YxAB&g)MEk!C&USSBt@S>VZ zxpU7LKINc;fb&*%v`VF!q$I@3l!C>5rYedA0rgf{r3D)lUjx)ul`OpONIo&D>dQK4 zG^1tcN0a%T^IXm!>o=~ycwRuvy!fvxQl~gN>!5K=!_&hY-^<GBbq#tD*TctNNJ?B` zxdc5<IH+O}M12HJ@(u*ng!wm}{5LBpdhqN-B|{Yh8>{`RP$<wHoVaodKj|T0u{Gc7 z)FKz7bb~^k*l3{GND0o-WK%iev=g|#<J6-kHZ%8_{>EofLd--k>ZAAaZ|)>Tzua~7 z<Np(`Zn|)pi#E*gnjX8fJ}fY7eBI0PR{Rl{>QvKqHGGnqUHLZ$V}BPS&mirDfT-u4 z#vcshu&2L29NyDgi}o;kdtncQTUs^Q4<-|%oKas6l~V4KeC)0EeNqlkDYGqAAtp;0 zgwrlGxev<w$*MX(6u<{AcfEu@wXnLdDZo6i%vK^IfC-c`@XpMAg0=yUT(JtBOHPlf zt?A38n1eSA3EXI;0^oUg(779Sr`qMXh%`qFa1x+s(L@6T$pHuDV)FVK!X0Fjbgz|W zSNqG#j{1@EE<NZ-bI_3fk>hcWW?#<}k><CyGsnkjrb6oK%(BWvcT8fM3!RVQM2-em z0Oi-vQ*_V`GYf)>ftk&%fO1nH%3o<ICihx)S#Yvy`Ae%GD$&|Dj=;ntiVcvo|AQ1J z5k`lCGcXZs0p@=dk0X8kZT`bx#97fu{KSY&>r0_*FA_rO!Tj_Zlbk)3AqH5=y!{F9 z(c~yWNHY^wCLMU3Z={yok6+1@H49PCWtL(j2_)SI?2<UgW#_R%X6g9r7km~IW~Qyi zFKyL64D3M+0@nsrvNb=4_a(pju1FL8k$;S3LtGJm{mbZdY0aGkhD@wSn~G}s?ZjXQ zu<*3+vn`1Bb_SCvXuEsu;j_CA;zVmORxOl{6yB#RLp$BQ`5Q2%p6NT&>D>zpYEk$} zSmkA1c%t0iy!6jldmPaRaZRbRts<C1@{_S<p2sKOU9Q!Ux;UWSvzuDo*Dd*w^0dy^ z(jc<QLjG&Dwca=@xhAq#!|;2u>kyi24lohzYYB!vIS=l8R=d8L9`W-UqHPHGrKrhg z!@o==8xlBvo!pl*Yf9<0!GdYe)Q5tYEyP_-z32r4Ibgyg{jWkF3p@!X8nQWOA3SEB z7g;_!GYOJ}1ww%i>M4LJ_y{lP>xPxLk`GGwiwx$`XhZ*b^q{UDJ*`sqBJc*hMP}<$ zyp;2(O)(tP!_L-C1)C0#6F@T*b#3A`!qSda(ImpMJ5GFKIKikkQzM)yAR6gxL7FN# zm_qp?c6K|?bTKMz=`!ua+U$vjwSd%<T)f<ue2&5xOEPh)@uI(vUx|)K@o}D84qpA% z-h+aeizfp0AJe$<B2%zN(7e^~dzTOuO=k{j8KI)>V<VA>mTBTQQacaQLilm*_~9~{ zPS-ib?=~!lbasY7{{Amh4}bUt?lnm*JU0Y!Px*UDH-m;SEGkS1pI>wjdyr(B5S0>1 zAMw~LfY|#FmvEA^D7NJ6Z!ppW3t$qH7&RmMFE^lv|59sxU)da0wIZ{eQ~a-?hfKt? z@=wVBD1y1XGczX4vN?^oJ#CiSK|8EzRb`LRXhA-~cf^GJ;B3WpKU@R?D=@KI35A<W zTY#^jh4nc$vMiF~uL%<oe^lrngs_k?CV4dSa~xCamUHsAIgVNkQBowuXg0w7y!<)s zmSof<+&|ApaZ&sWY``1$6nR?9g2F>t4c;Bjjbs>N7n+i`lq9n^Q}iDO(1$Kx{&<)I zim#Tj-D43#X1rqP5T|N}?LV2Qn9qpysDJ=!Qd^$NcEeG?nMYCcUr0r4q-&`yhoLb1 z)IfD&p|&V(b2bw*+Gjcq;^T}L6OT8TocTc?Qqz7l_bPolzD)pOJb+I-#V=E+-_WV8 zHe1Gv7igb#j>ED`vUeJBWH|taQuVKV99|gLIG26G_;#MJyZ|sJM}FtObpvhiMHu_e zO`itSQUzw8F=QpUDhA}j_cm3b(t<bg4P0Mv)=hokD<18nZ;xo9f%;MnkycrKjaFCP zaj(1@u6;c2`k<*#8IkyESr*iQ7>TZ=HlJjH97Y0e$|zNAHTa@We_+!!2Hp2tnXi8B z+m0;LxYGT`xb>TZhXhf6Z(ow(w;sjw)dZQ3)I<H%uuMKl>Gt`Gfjkj`Pbc;Ja*pe8 zo1O*tq?~!DYNBA+Iq=}gfQE^Z{|$lSCud#f$3jKwAiy>8((=@V*oZC1AwU2LNHqav z4YAQSupU_>)Q&sO`?)~R#~`X%#BY^E2>*t~ZUVRd@}oG*fR`(yG{h&NS+E_{h>6#a zU|u3Ygspw~?3}uKh(d(&M~zEGsZo?O53qPIX_rs5ZP5oyw)c|*uB=4g+WM)ZRvMoS zIW5y0QO*eST3^P54aUrUiIi0j?iT+xcz-hi`rB$~|G=GXj-Uf>k1h8R`E*76xPADA z6GN|6y-`=6MWM!z^byLl(myoW>h7a@QmulwIr$rlGErkLJ_YF6lgBlsr=`|iJT}tB zmni#4<pDAActruJ*A(O(08zt(ewp_e0mP=9Mf9ebjAn~V-Apejz4I%+;~Ty>P`I&* zTBl$5&c)2|m?;GTm6(^!gh%J3r&$rc;z!Q&FwwjiY=$ei`I1ZqB#w9r!V&}t3SMi| z34dn-rW!vLlGr;TAPWT!xt@aHUGd$rI29DwG8p3G4>-fta)V(DSIA(%@W<{G!w!f9 zw_P=csI}I2)hZ7y5kO|SNLI2%Cjqe^fN(1xG0!`bK{#{Ul^gaH5djhMU_t}tVT>P$ zHPmiPEVL>!z?+4KxNzwKY@*3ATn0NZ7gf{Crckx|z8(AGZVVAPpbiDR%g~!{C`Jo9 zxas7V0TdB^R(L_M`c4qE4;3mMFO1in{fPo3Qeb|Z?Oqh+ymbHI6);G9rwk<f<uECX zd-2*JDp49U0|m~`Uj0{ffmwpB^hba)5&Kt<dd*nAo<LM=z!&00+xZa5S!gLBRJws+ z;LYDgCe}x4jL)CR)I0M4CsaRi$ZOK~pLBS+8krU^N6(3>A42`OhMvnu@yHQ{TNx0t z=}u`}Y+DQ!EFoI%3=BGBGcH5$#sm2%X%_mUYdmB@FrX@4#w9W)4|NPIF^%y~IVAr4 z{3&V)L2#7{mXdf2OB+5NU@0x(Dk0kNjGl-S8RNx%9pd^k51rzxk8L2%HVM~k<gD>E z#)0&ebi`ez#s25guW)cD6vBfCeG*At!$+T+q?PAiJqL2%X;(#EC_SMDjtS32ee6v* zmFf8ytZhiO=8`gV=sFoHC`J{!sNXnQD(k|+soi)nJ1|8K8tI8T3yVh|#bQ<uqu%ER z-*~2yc*sq560S{C-K>)SdDwVK4K=luuK1G{4+bh1MTVCZo0~*l^F-5{gukFf@1Na! zFAx%ma;P%evo?<$PDfPg?RjS+>W_nO@&b!o)hO0!MwMucTfmG*$n2`=%UslEc?KAN z1M&6B9}Yvfn}OeoQ_U&FEnFU-Mg6<$lH`G!87$y=ps?|Ng-1|V;^HAC5F#rDXfnEg zJ`;iW2PppjCe}$gPBP6IU>3Xq7ggqQH3|mobS6eUWFPZ4N-}zuC!29iKM#56h*)qW zyk;JfMiPE!Y4DmM8l0nOzi^x`B{oYDPV-0TKSwT+SS1u_BM_!HLX(rmETPk$uBP^Z z6~CyXAeFm0V5lfUsW8hBc^E}gFMyD#Do0TN3Q&q3C{Qh0B7t`SBydYu0=IHm>8szm z(UBy56{Q4J|H+uA`3Vs6`SpNGfFBMf8z!8~D77%d{5U+yM-+q{dzW}ETMv6_TP;u- zcmF$bk)iRL?_Mj5rH>?rcO$>zkd;i)7xVCF2K-6W^+=|u<)m*zMh)ewH_bBqk}K`% zRPo+;G$}trrdhm_Ppx2@ZgmFlq&6|q#WBY%C@~>b=iw4td=&PMu~8@baTWUhknB=b zM7F!i;r1)RrxU<muN1kU-de@Ube|Z5o5?npcK^mIv=}@bj^g@}4}nCVP>Pt`vOFB3 zDn#RjGn;mf?4TS?8!TVLi4GF;x&fg;O5$R=ugma_)j+HJ!>ENI8X<ar_6Mq7HCnsH zKP8DO^3F5B6Lxl{<mYt6IhM1CByVThxhw~D932081a&JOb>f{|#V;kn3KJ?`VWLDu z?3%*s)r(;Xx3g+*_k(4mj84cc+*x4dNl!~Rm8Jcdpr3XY>OvuBm>PG>YaN~<zHaZ@ zAVvL2!kaj_?*?KF7rujcsaV{`i^p2QN-Bb*>yO?OIhI8D+DX{zOQ=9K$Yh8=`Ies= zL)D9F&0LA=h$_To6kHR$Z0+49*9?(}Y=gBKUu^a&_C{SCfYJ!gsJkYW-Hq2JGh5V1 zg%Y>rniJlxUd)iK`Bkf0wd{7a0G%%@vAW!DO}u+y=<s){=nG2Gu)A0hAl!lznMNVU z__2=x(RLoxGyY}?34U4zeom(795(*W$&0IHR$d>)$tF?Z`Meg}TR1P245vE7G~tT# zCG6Kq1QkV7!+;m6gk6;FfgtlH0iEG<LDu(#@nFKn5k24>3>36uMfv2REu`9ZJtqQl zs8oOG;&r>Io!3}TDUSf%3kGFe1NK*65Da_WA92E4j5Q>D+*zoY0rMrn({PaMD6uCz zL?jCF5+}OC!cGlzEtggRjBxci$FFh{o8FHQQIC?6sQM++z={pF7Tr*X?%sCBT$29g z;fJ_j1Dia6N>WC2Q=a!^Q5J}qZ4u_*9<^)sWHve7pR<LzkT!n>?*nz2=G?CCyK`~s z;X+2V6QNA%`@Tbd$1cmMUtbh?%;^1aUi4%gqKqMYUh?{7xw4Bt`dFK){eLPL@EUbm zk8o{5R7*a-`O*4dWmc>#z-vuUK%FT>2M7U{kvb081b`t%*X*9D5=F55<SM!mU*#UE zp>_g%P?Kt?7-wxPh%dY))AT|%A*IJ9ZYWm+m4fh$n=8G#Vs~Gr#isv;e<hYf?R}CC z|C^8OXDV8|U~S539;eq>Qv(cFpJ>~4#Q({2U02P~$d|JARMTUKA0B!;7Q9i0es2T= z*1dM<SA;Vf2hQ_O`k+eVcQeIOK9`~(_;bsdnEkHW3bNXXA>tHt=bK9D2&Hj&_*I$a z(iJU5EqTS|Xz~@2nXDoSZb{$e1%$Qo%!=RcN||X8#H7i)Yo4dcx^&6-<!{biBzoNr z=|F$G_ZZ>guLVk&(Lx>d<ip4qSP}YNi@>?xlL>dxkL4++Qcy3aMjPcMs;SR*u+3L| z<dbEn@a<7leAfvevJ?+e{4`wZ{hQ=8Wyko_PC;gLAHn|l8TM+Ud6e|R`m0dHhLFRL znPvP-mj>Fqzu2p^{(c(a9;K!{I^P^U`Mpzxl!}@FDg0Ka-c{p^NpPSn^h;L`l`5cz za+wl(j-3QyCk0Ag$o>%z#zF5RN~Tt<RW9XSnKAJ;$w09Wx`C-fTfeIh`>5iguKrDW zB}gBR`WQ73d9aCx<X=EMX%afx)EvY^4)SZ%1POx-tB-BdI6;XaJv-6V{t~0o)_rqR z7o_iwp=OIl59rCq9z|u`eI|z%Jk_c*sfv1=^hOSS`9%BWM@7y=2(TmAj^<`rKQEg6 z=%F&rzS8h(3WuK-ekgud^6H$Cp`v?~oZnLoGsHWjjSEsj9oAtJ(>xIAK8kyLR9NV3 z@a{_>dN&Zh{30eFGLKsMa~UzGB<k{J+D=;WQ+B<#cmGd~H<ad#6xjo5iKzeT&;bpT zC{gNzn`n(;RLo;kaSlrH(*nfB1>zzgo1-M_q3k?yfH;nNqJW`*ZN(mzm~v6l?&6~D zui5Wj3x5vR^tdembvn18TH8?CIec5@+)L}jEf+vDr3V%H{>WY)G<<%>S`uN0lk!Kw zV_hU(q{DsEh3;260_n)BJZKj4t-8`v;mL<7U9)wm7s>ewJNh?GpM<#m8r2g1S_t2A zz3cs&8ud)&-y9@ETk0V?%m<}00ct@$-{qV<md7mZ=VQrN)LCe4?d(F2_fOF`&XHB; z&dzox_pIEU(6Gx`$THh;pj^q>5WaP+odWgzAvDvp;U6q?mICeOVXyRKy8+lkhO{La zv512Q%yS!2U!4&W6-%TH>T08c(|`X)HsKMn3o^zF8N#4vX5jbP(FeLd%_WVa%xphn z@!(UvVwXR^gJqlonsinipVu5(+;n~SbZqYK#o$b$H%Z~V@cyCZgQ_|MBj8Dep~aW5 z@Gg^sPnZ8H!4E7uy+Zbmi>^^1-Ax;#6G+wXxII%dJ1Kq$`$olQ&X946*hS}~K`L56 z@%q*~lJd7>_mo4vpX+}={<;mBnHd=oy=gdCjQ*7CDv0=e8V;OutnwcWvZ>?27OK}S zj{(4<tjqJIhep4|s|E*A7x;~Fq|BLWm0gPVhw1QkNs(>1;bNH9ssh1AjL^-42BjZ5 zb3pB9{oAD|iC^JJyH{`R-ylv43%NMMFSE=(Yp&+JbZpR;X+++7xaU{iL#;1|6^!x1 z6X0iIFQ;%Bu8{RkPt+!OQgE&cZFyS^C=ugR*bt;5eYbT_OMsl(pv)@yNdaDMI4z3_ z2da_4Yo#Iq-Z;fv;Kzo#NzgpON=QF=YNlpK9B@L|tA`nq-ch^&{~v9Jq&2<|BpEyb zVLYEoICw+H+h`+yn(ZRwRRQO{XbyNn?`BPFYj^+yL%s^zH3#Ja##0pJjI^+`j8SH) zvWcN4(+_eHKNDl1-p#WRe*WP|<U6XHpqzBQX_MP>Tqe}Wf2L)EN4<hgbJ+gMD@Z{! zljyD-Tpvphs7Bp8ytSSHF2U9}2N+ob-q0%`=L_=%m3RwGy&HyE92f7Q6XHH`+RgRg znE_W%Prs?7f;-?f$U1ME)!X+oeCSTin+GSw?g?!)6qrN}=95FsQjVw@meyCtLb3m) zfG9;Le)l9j;4snGyXv8G^|;<0|D_srchtR_dkK}vI?C+78};}}0E-3|fmxf5I33xb zBre<)iI)O`7H?hND$%x9kgf$W6(#Pa@}|#g!c5{E4KjFX(9B--Y+%DdIgTW!CJy+^ za`o6YoxwOa#l6)zMLJq*s+=@}O&*N+DnnyCn)9LF7}RlH=7EI4kVeFtNY2e&UVUVK zO)fsN;Nc<|c=F=HuSOm}-Cz81X-IQLu4j`QqC{8ZWgGq=&~*A93kBkv=9pj1?0hg~ zlgXRnr#B=jBYsEmWc<$~0eD+*>vILaxlzkFotKNrx{O1xVP&LQ1TVwRY?w#0IV#A^ zg<lB9JLzp=s`_`}b_k|d2p;~}K=?z1xscH5bShoO^~rOiuXS!E=NmAV2$NDEL5{j) zXyd|ucAPsOeTIBk&HJ=Wk}D9@oz3H#8di^LA16L_XBX3}k6<qDOEtoZezW$?s=<H& zsX(3|Pmu`_U`i*B!jiQ-17Wrv=ny@n3CbT*$(Wu1Ur#ewAd4sR=*N4%DphmX0&7N| ztInAyJ2?LnlXPZ$69c)iulk#oW@A_ci<nPdH(70{nI8$IelNs)xostr>E-i4x8g&O zt6glpnUg`0dP_kPl-JwWpdF*Hj&v1ep4bOv*m|5(w6T0~!jg@{!AiRg84WV9!7Qh@ z$%gEmAVoEsIPTx@l2J|LYTM!Wz)PhACMw*SxY8^o?*xPLZJfLRaBx-M1wx)55XLeq z`SLmU@W-uzha<JkofmHWd60Hw70XByRzWlkZ75&*vQ+8)n}v-rxc_dCs5D+L+1Ms> z2=-yw%~sY$ep0H0%%Ml%2FOD#aCZ5;no=MnO2HyB-VAOAG2)LTH8r91ic(LQ?2+e! zMf8MTq05yn%?og0i$yG-WL)=+)c%wz1NH>l$MMD<zoJYXHd!!KQm~X(jfd;-EaXq2 zEVpNOMHH!niC+Z9Xan)s2g=J=B>v3NM9(QZ;~R0wo}4d60)Rv<+>}rwpaA#ZyMyVZ zav-sX)=`9dmJR2GB|vKcP-g6EhCEepnew~2pVc;Y2A0UMNRLlX>&i$KUbsoEU7@*X z(=B8(@wBro`Nh$$G~tp$*S{@!drm+?pNRxgJA|Y=BmEE_FggzdA*twb@u?x%PidwS zzET_?<7_O@xQ1m1Vt~G~Vak5VT43ulPR-BJ)=Cd!h$*Kdj+DD$UYN4iDslR*Y42T+ zP%Y9BK&L6}qtp~NE^HY`2+RDWc5)!jTonD(ABN9Lbf_XVB$yhEaAubk&Q_ehTpebk ze*0|t=Y#Rohm;#?m(Y3V)R&KXeq5kVNgBqbgyNQKZ_yHhZS&-JQlnD%Cu?{Tgds_e z=+nR0Pv)K|PnkM($LcaSdZfTb?wO)0%@<S^6I8w={U#)qcM7xUSY<wiyTEW%vd(c0 zwG^_y1!nFS>ZveNUQL)telr7Yon!~L@g&PvhNte?b!c12zeS;rjRd&FD{?Nhe%&?L zC{1OUSz>mGHulvoWz;fU4xJ}4+(_1Lri5h!bQ=-yUoPVqELBlA-%}X#g)E8^tkorC zuXjZ{x_btfftYN&)ZP)tI8=90#%-E!`RICrAvY@Lu=)?S+TE?QIl?t{S3K2m=hU-H z?+QMl8JRf)HU~qpYu$ZgGR^<^1=S%6M2V%nySiWhlpQKjxK$Je7+ncGi!-n>YUjlZ zVU*a`@iwDlFIc0#9)kL%aL1a`PL`GjK3fwu=$Vu*THvntYf06@i&~lZl_O;&sPg8+ z-UYVL4DRZrCDGY0rGwO~b4}wTsVC0o%W?}IrU~ENZ`TMlHo@DD5)Ood#o21(xQ7An znNMJh>k@${`=V5@3iXV~OW<L*=9VZM_6zP8!m8;v>*-jG*FeZ}oV}Mv@J-1#E0JL+ zEkymDHg8nDVh2vxV}pG>G(9ptMooCS`lzii(5lyIE(x(BM^fVtaH&Y4OkvGQw|07B zzRSj(qnmp@N_sjHr#I%z-bc<lt`~8C>f6pC>nrA{%Elm^oWW3d5v6tJQZ7zEpGw^b zcnAO7yNBF!>bm>$y0ClGj}$a*{P%5I#!t+SIof)KJvU#Eo6W_s3l3Tyx#_$BuhzW} zOOV~)oo1VkmpcUjl5d<5n4kXG)}cPFgy!Vk`EFj)zaYsyh%iz?slAUfq_FvTzyOHp z&OvU385~4GW&3QJ+_+{}XUe?MeU?8xjhux_MdQ~paKFQ0IVbPw8~bG8zRSbxJb#;9 zY<(8wBjKx8lWD-Ak2!pVYR(kpmEE5*T|j~o2>$r}oALtE9?V{GddBUO`Mofp$^La( z6pYw~N7R$7bnaPr{6a%~#6;CCcAO_`2C-TA$*2W8Xivd(v5QirvM!BuF2PZNZ}T9e z0FjFTu5|s4{?jx_JHOFFi2Pn1Ey#RqmVYpz$<Nj?ewq0nuv(vNC$6jBnyXV;^H4D` z)>rwkv(nS_=!&`(A(yRD8TS<bbUeb333+Vk@bIS4l9UfBUUog*$7-bjUV1(OyEUJD zbggvjv34F+O6rE)Q`84cZ}x%s0?ErErI|;*bl8=bFX<OPt2xD4qSKH}ob9jbcXZf+ z&lyMBZy}(XBHI+4D9{za8anyzXQGs*Y}L1pCP>uyK6GZ{BUuyt*Js)4Rxh_JV_Wh7 zL$3Av9F<!AF>hGXNSF82PW(w+oCQzF#ReS0hiq=gZ(yN*HfCfK!Ev{&&wNM#R^W0h zc-$Mis>hY6leqS4-$NOgl*GgG_t}-Rr8_lBas2jFQ`kgMZfJ|V#DW2b@~E<7KRXT$ zP&z)>;m|e(w0odZID2>`2^R)W*5tmj<#vDUkkynOt?t&cg(Wv*Gv&B{qR8tTweQGx z#m!+xC5jk<#(UuM)8FHrCn!$?q%i^MkC@5Mb~;BpAcoFy-rJChA;|u}<^Cc`G5TC9 zO_=+dW}O9BFF+gM)qe4RsNhWu9YGT;U@QTq97%~Yzh7xHr;wS7wK06{tPl|bR!!&b z8pM-k!HE_-+?D_shL$#zQLB}mX8USS+=iewzEecT$|@PlV7GE?@>%!lz?Vwrl0;5! z3#xC&CCXkuiW943-18lRbYK!blc=x%JWANky*cqnx9`BvY-uk#Czqmb_sUS=kBsIr zOyP)bLV63!L~kOtmIc#r&6bvLMshY(;yUj8l~{6|4;1{?&FJWf^VB}JPGHbU0J9G} zCQ+470L*V%+-R*2B8<pELroGkn&dXrjIV38N6XZGZi39|_f^)R<frP$>zd@TJ@M&@ zzV+=SFML`koL>eHBxhdqfvLyQ*6j^*Kup}kwJO0OxWAC3CoT8=?zd^FoX5RYlWHB^ zDT0J>i)C)tZ`=$GP820~1rn4NCs9QR@v7aLY-dsCX%*kmb=)4#;45$7+E2TQ&&|ct z5d3_Dq*np0ztQ{u;wuAc)1n<<w3ZZdXd+k8E}JW_fIw>0>+O2;E{?IcWFI9kSa*^~ zaNh*seBAm+mg0GuM|}ZXP3lI{es2Vx&8=#t!&2i8gbX8qT4T*&!9RPs-3t=fnT$T{ zV2`<YLQ`S<h7GQ?_)&FNbT`BY*ZwsznKl!jr<D}wz+EdLJn%}nF@u)XY<=Vf<1M$K zU5O(lJy-0xoG@;^&&ZT~6>FxR)xlE8zr$hnC!kth3JL>E^%b5fhqAMOJ{Z2ZT%{9b zPqrO1{G$vn;e`jLpN+EMFmH*hOn9?z-JgW`0DvC~3Z=#yPU!fYAI|IB_hr3WF3G-d zCQ;^Tc2Y*Fa{=bUoXB-`bn;#SD8VkCf4?%Q=XanTvCU~_;o%+4p-PmLcDhsGFzlrd z?7FRJmM82@bfQyi!@~tltGaZ{rJ)4aVC1sB%02rRO*ed6WDx>@4=TZz87JQ)V9(<O znn3JK;!gpZ5@n+tTY8L0&3qZ0)TL89j|wfRJ?WYw&~TH(e8QUF`|DCiku0~|p+)Jx z8kb9Ym$hJr%O5%`!<eC3leL5F4i(MgFm+q?{$D0K|J{jW?$E0k-FkTLu?wvVzeXRW z?78oibPV#0A^FS?`HZvu^xap;cVQ@So^vYFBg!TrkPq>MA<oz~|4MASBI`6r8ecHr z-dryIH{7`Cz#WxOTrv?Yk>86mFOZq9mvO1RIx{ofjD+K0xn!6F@~QgvlX?a(>0@)# zncR@l!J~BU`zDO%(_D+!BLD2$zhon&<5BvC1u(yR@6ZXmA&kygh%NveW<ospkW)O) z5ek&WmaX=qTdhmAx7lQr*&Ht%>Z3lXoW~x$Z}Or9sfBedBXEabvg)*8v)k8VA*Doj zJ%Gt_A5GmeYzKIP)kQLk6}XM=u$OHe!}!^_*&UOUwe2jD>@gy&|9ek-<ZL|G{`v>C zs^r<#ksF3xv+{}F0SDpeLttfQf;S58u?;o<59*QLWf9oQnHBzb=16jvaEoMT0pCSV zTq}W8_UdcC^@S&!-$wjQx%5T(%Z6N0l2F-$`a7YtxOtU0?9_KR8@7qAdrnb$wMtU} zj5JM)BatHG5&e(h|KgfpZr;Dp)8c1bjwQ||B9l(d#~V2B^5)`mETDeXf~RK3H7-oP z7_o`p&g>0`HT2x;#}~30>JoOaSwq+)s>H?+R_4yV<iKUiaYZBDCoC0M6FF>{Wn36{ z%T<Hug4T~z{Vr)IuEDJ)z<z|`OPhDdG}kUh7`OG#q4|qghF5#oO;l4UvL`I7J${yz z551+9@~I6H$m5*PhpZ)<_c5B|Xa85xefU%L|8W36ce?i)*<HH0*Sz*Ml2u*TbzL)i zlbx)rB&qJS2_XqxBO%GE(7N{`vqF^iHIgJrDvfV`e*eKakN4wo&iTC0`~7@9%Oo^D z;Js<YR-Ry~8uD-6Pez4*6|Fj|4@~G+`7tbh>tucMXkfo1f@Pnh->?xS<Q0ytkLrD+ zZ2y>C3hXeOc)-wIy|uDiPdD4q{54{*wkf#_r=A^>{Y+ST(r%KSk;71lg89r+FZYz1 z#<ve<yOi|Xotc`~V-3j|BA#T+0$j+5Cjw?Jq4nO8AsA?MsYXiDktK%>;L1N}baWA2 zaqiHeN3WmB&9uA^f4HNh_)tNoJuZM3fh7gbz}3$-K6b1Zjocun&o;p$3RXTSjj+g0 z)XeW~C@QPR_M4(uNK|+cTimOoZi4Mw!8YB3L<krJe5OwYTece}aXxId0-Y5hV5aGM znPkW04DYg%A?oE^NY{K7E~$1><)0J6=i@k8Jv(Dy`kJu@)w#!^QPdvhkjWu^Jw7e| zYbmDL_utX%VXUITz+3H&P(q>NLD;Z28eu;hT;IgT(I9)48MZELj|5oMeQEz;=)Y>% zVy#|C(ro-pajI%|w4G+b*L;VRVaKWhz~&um;)WVN@OK&gq<Xe%!;$mFhfgVFqni%9 zYa^PS5coIa;UEC7u76S<@inj+1P3&&Sf^TKVR6^zinnh&Mq47{1dZ!W!w$U%2L<m_ zas{v}pP`v?9M&=S4j(R?V9Gku4pGVW3P^)Fj=(I^7?uKtDHrCRy|e>=r~1!Us3AH; zm*0ZAzU<Xu;XfqH&c?j#KA!2+5MA7w@SG_=U!$l|eE{)1Ap4Tp#qBuMhl+CM_nn?Z zj-#Qvt+D@$jnJzjUTjy&d$L0Fi+lbs_)$}#5Hu?MKHGB3(tyfN7C^(Zm%M`6Ap-Db z4%3td<Eh6ovFE)NU)|f%23Cq@%*!$$0v2#r^5bn_KjLka{-b*zNnn~Y45<0Bdj40| z3772NQ+#^Qft7ldZ}q6gjl(a{gvZp+rP15SF+AaA(Y}_7&%D!<NE_=w6S-u$3qAt> zAb^$@%=YH8eb75SM5xIY)F&ZG@_1CZEPL-Quunx>V^5Ck6V<^h`Tbv&HZff{%H9A* zJ}+H9z_m)o3T&8TtA{)fyEC&N9YCDMzuZ#Pkij|u%TF4yGgm?zOp3M2dcKaiR8a_o zctx{SXQRyQzPF-v9dIsZ9qufE9czbqEwdyZig^vQ9}r<7RH&pvwl4wZlfd?;viWi3 zlJXhda?w_>PR?RjA*2}Mq#}WPH<^UWSbP4&P2sV!oZ7C29wQj%RvEqhLnhiSLl2<^ zn{6a;nl?IHfyb@#uk5}(vt8H@{R9W}Z@gs{=?(dJJeByC#S;tU!tJv&eW`2>u9+L+ z=qeHBmCcSag@vGFL+`%j)!?iyq+Xr1vuoH_XZN}7&I`BuJtNggjqo}bsO-<K&9yuC z5hXS`$@40%h}s6*FP@09e+sPS%Rb*pFiHTk=sT*#6WgK`z+oj#u!ELA9dTjqOMrzd zBD{iOAp(}KINWe#DYWka%f<3=m*l(ENZ!U;!N}JR)f1U1DT-ebnZqH^=c-uZKdbeA zdPq_?{1J5zzf6dfVB%4Yeh(ye{-OW{15*(37dFvHaW%%xhcu0J3vaIs*9~@$DCC5_ zSpIo0?QWC*R_2MVW5jJ(pg81UJ;Q|x3vXQa;;>^l(Dy-tqgS_}hq47^%vz*w8HJ_& zq~|>qF-}H|ns|PrXzi9LpU`<@IX^_FiOO@b$}hL`&x-D(&%1PgL7TOZC1t06?9;q4 zl>5|?MNldD^pZ(^FW<kSZI-UPb}7f35PFT{cM#zP(4wf&pltYm$?Su(%tL_sY#ZA> z4ed^?c@gwGw|gt^M#;T2OsN2}G{GcN3X>J|pFYGG0i8FXwBy^3tl5z7HV746#Fok5 zr&gw^KBVM2x=Q)4kM$@`@{NDF%})^en(8Xd>V_M85q74Q6T72iB1Jyk4~qM~!p#0X z2Hv@VyRMSk>N>J5j$P?E@_TXOHLu<hwNsubfC4lchU$1mtJng&4N6cslTtvboW*g& ziyacSWSnr~V!!P<#S6g7bS=~MF{T=r4R&Nsj=NSLHjU)XPa!Ey=sW~FWNK%L(eHNB z=aui;KJEY3Kt6CH`Jo(;8Vm)eqK0%aJjDL<lTEI*Nrc}bd9INZ3c-nATB=#!Sf<OX zj9xtvLq6YO`mpk^&yk2RT%2pw-k2#VZ7=&r(Ss-%V7jYF4H7J|mwLWXKSm)oY4R{& zd~=1z%sNK7Yz11q5|`vqu48^BiOla1qU|x7PHJVkUjDlJ@^-QiF*{5o-y)5;3rvgN zey9#`2>Y7Z+HOGVaY<2MjLM<H2cSg}GwKN{!vIW+lT#>11BlRpsZhPz#o|~!GnQZK zuH#od$;E>tJ2PN&gRJ-@8~0FG{*hs=rWA-fYTKAEeaWSvbU?-do;gibfq*#+jsd^m z7$60@Hz1MRTkD<?Fao2w2bg8Kicfq^fQX_yXc91+zY9;;f$6`l*x4lw$O7@zKV@XU zM0AH!QrO0asj--&?}AbmFBBg~f5lD5XJZ+!cDCb`k+xYO4Ol=ldatDIZmVH@MKI+@ z&c3HE^P*Zevw3WE2&)7IbPYs~>Qq%t+2`qJLUFc6Q;2d$V^QT8s%gmf;;S>KLE_V= zf6jO-*;30wN-o7j&nVj3R185bs<VIY0(@=Eb#I3JVpboRV3Yer&6{^iN+<LVO}gzC z^9^)LPujd3&z4p`9}HVzMcL=*p^j1ty&U2+Cy6B@jZN)!Bg$9qPE}|&@k|^HU!_6A z>M_lWC3V^_h9y)OJ8vZ?cKaRAW4sqxlU3&L%O=}*LSiC)mW~PoqK4tBjPd_gPZ>Q9 zu!>Qm7`i-v=0VCCE4wr(b_!l)69QfJ{tv{>Qu^0BrstF|FyX|pf~v5C>b;{a4vKVz zDT*|yDw!gUIuF;MY>2dvxV}uz)hu;fn77@!)#6?da8#80ZvVgSpB;V9S>e@fB!!b3 zuKc<<8H!eWm(j~I?=w#h&XL84X-_U9xjVtM3MG|jx~q;YRYMe52>gEYa^ImN#?<LM zaTyklJ`gdYx{zO$guTp>&71c_T%&p&ko8H0#@Dg=5?USieC&0*T#^cHjST&!^4pR; z3>cN0dQk#2NM0LQr38NR>JuB1Xm>ouHm6)U_jvNQ{|I14SqxUy-2nUOo^laWF({I= z9cL*Pnu1V3j}oO+sw62<H6r(^U81ChbklYH(>RbvaGJEF6SgT->XQF`^ZDH<UZhEL zvut#zRk06tRe35|LetVM)7Eqj)38p~ynD6GxoRTFe`Nd3j3G(;V2Zekt5KDMag<?Q z2#eteqCtBl&CgF`Rik*r`vE-H;H@J}?<4QS6jS1d<pkX)Vf2*!RT<&7LKU^0khA4r z4b4zhjZ=mrt=%OCT#4um>%~#z_sEiBe2L1DZ*H0_gFM^dej9naxpl*0l*(|Z^o}>F zZH`kZLAV;c6CU9puH3W|n^I#gAfzI)G%O<*Pp5kLQRl;WT74RM{zwJMs<0iJ4*>Qy zxlzUu6oZnEi@W>0prGJ~+93__N29~CMpNAH*$x4T0Z%{j!%Jp5tj^#h#Qxlpqym6? zjs@RU1;JJ!Z9Fy|h*?xK*ciTal8k;TVC~yB59!a=ZIZeq4l&mHiin6Jsnw+I#KmcL zoV*uavp$Z9H$<VU|9(Apuud(J8Y!8asTy%dRe@3oEq}7ZsO>qf?x<pOPAOJTC2)M0 zU{K=J)|BJq<rt{&jpSB1JEeA})bBDuw&_affQy)Y&idV@3k3qHk}K=12Y}Ws+Y-K! zBAqG82|*p|Zm_A@3aR@YDQR7Pj`$5)>-d)?!T$)|bz)`g&su$%dAg00Go9l_TkpKI zp|3KVqZxX;>s;$H#BV7C6b|CZ#)PsON%T=^OhvJJ^T(?I=W@jwm}XJ<LxX6J0fMhy zJs7DP%}l%Q?2|J}sxegM<*lrzxNXnm)5x*+|I<xi`rj=|VC>fX#UiR{m0%v$_Fgs> zQcL6I6-&>Ho+8FLc#ufd!%{WZ2Zm{{BP`yA541h&aCS-Ytg<LE@u{83#hgW&<3U#K zGt+inJ*Bh%#S1BIbA%)@1kkYChf2(gkKTCdgZy<Frr)Gz&2Ri2bujnls`0x*t~Q^0 z)X7R6I%b_$apR5Oclpwy;vHtEUv9s#Oo%BM(?f#?CGe#>snXce1eQwFywpPf^;*Hj zddx=ztFIUtXtZH_^^GRg<`MN&F{}9ehM``_3uVu7vRXc|5WMZ*dT?{>ox$0Nj=w!( z?-hf&atXpJQI>=rL-1_TwhkKjN|!oJpLsjC?#lo44H6T!VFijyW6eKBk^hsN_iSD# zZINtZqHA-sJZg7^i7NZ<Jqq2s$P+H1LDfQWE?(Jmk^4pbJsDLw<=Ib)7QVI7mVCp3 zN6z?6_s?ynb>3Tv4aeQrMrGeFj9quJ@zwj7#M<Ss6!8?U1Q2)#Kmc58dJl&`YnC?y zU#J~?uBv&*h}mm+_2*Z!#6JcYPVdIm0#M7ucVpx|65~}{wvQ_R-tB}qf0VNa8C3^B zWyE%v%3yim@)k2{8jCt}LHQ0%K$7lT&p8xaccPLY@{2GZxGsqg%QJnqiWquHe3#pF z=>EAqnf8N4&{x~4l`|vfO_O#&>+|6LDO>c#>&YE}U>x8Isnv<nWWrhggBeC93xB!S z+glsZzSV&%Qtyk#YhPP5Go%08vPB(xe@E`<wY%43=55Z}P$Hj%kRxz;pA;CVXmN;) zy6bvYDp;nY0;c&)PZ)mXyJTY&S)D-7NgsWBope7cv%vCsCGnB!J>K!6=!?aH`nnc= z=v%id7i7ZUpZHMoWpw|#M80+t7(lu3{sl+I0e3}S0b9?;E(W#1RA4LC^v<?Gx9`KB zvQ%u}_c<@-?m79{*#+}rt@c)(*J5#<8eafYYwyUh#PCp;@oe?cmQeR_Mr(r$c~fq> z<o!22Ddx7h<-9@er3=w&6D}UFr*CcqC9$Ex6}!g9jW*08&)nZu|7u2=wI<{PQUnks z8(2)qb6`D|q{8+b-6MN6>js-VB0cnH)0cAhvO~Ui=A);D%hV9sn>&yE?-jkfpI@Sm zfM@`v>O~KAfL)r7l~Tc0A|`xeBB@D)@+JStmIz9a7F-C;lnk7OBVnuLibW*Mwe-B{ zi;G?^6Q@ks_7_=Fi%%{tL-&FJu~`W4`||E|wjr8_aHLfxvTn+pckr1T8+;qVwF`3O z*uA!O!PdGqyHmGDD1*Xu8awMac;k2hl9G$6;T!9~?RS*Z0RGOTPYw$tSIU<s?pED) z><@05+Lbien#j6S<V__8wH4%hSJ4-GSVwg2WF4)}1LZOdo84z>wKJgyw=k)e{rD!5 zQ1AfM(N@&O>(iqP&UdT!MOfW-6)*el_rA=1=QE&sJ?P8#V#QhV>U5>hAekaceV8r& zD`9rfC!lV?-zQ&zJmY_FR`?AFFmd4*%uqu`FhDGSPi!uF5rnk5oFeM09yMMt{BlUM z=4^JA!)lgB`rwWHr++!paXljPkppFT_a_moihKW8J}+Qo_XAuR@+Am?jv63};)C@c z22g+nh#5O+!29XUMXw^S#Mid-6CvhSVLsij_QI)O<DA?h82h}$Of12g+k%FIO)>Qp zFeabpYe3TI&eWihGIPX#iw+M(K!a5;mi&VC{>KU`8;8DRS4c0&IMuo|4V{P5gVj`R zUCxhJy|AW)lPl$JSwf^-h{Bj);c=pENrbqm5S210&xS6=@eU<MxFTkvdaX_=jI7zb z#q_Bz>@RRCdi{G9?zCk`>A2)Ti1_-8<IpXCvuGm3n4uxSDucx~j)EP@{1CMLPSk;F z3S$NuGQ=*jBVX~5eeCT~eaPjl?mfHqzm*@OY{oRRyyp*fE-URSQWFWsQHJaM^o~$x zA(U)VcR@%%Cm^y+6ASS7fqn?+ftDc~sV^pb)aGW&c8VQ#cH20TYFzxeTZ$ttXR?N~ z4UTj_T}?NgVVlm}Pvq+a@Wmp*f<#flFODD)!HdG!w!ZU9cvEBPYOXMsI-Vsre)-rx zbstXF>FaFgb*=?KOE$ck6*;iK2nIlz5-waBA62L$AUXkv3AkcW!s*!AbnKY)>nC<~ z<90{iNB9U5j4vMNiaBQ5Tm~}T_4udiO6DXkf3>kMEMgd|GBrfru2mhjG1!^n1B*FZ zD>c2NS3;czN}Pei&d`QGf+cE)vmOZW?z8JfTyki~0a)S0I-H?_IDmhZmA-uObN~L7 zD9Zp4ESrb~h;pH11CW)t%i#Id(yDk_%}VFV?Qj;$D`@BB@%JcOqom5%UhNNWDIzWS zY-UT-k0Wseh7Osu`LWQsqEV@pex-_$_}!}bZOBjptm1dj$ed7Ux}AYu#ih)FiS8jS zFwG}4ih?=P^S-$=Y2d&z^Rhe#RLDiN6GZ|vK3yqJSbIMeC?R{?-zV+JQCCh{JZw=H zzs|1WoMt0#PVK#Q?YW##t&gbkFj(J_XA&;rC<1>Lp0B~8i~pZ6X6RIbm4~Cle-9ZO z1_{BMKdrBL5o-xaEbmcG#>EkXN$!)<fG)jHorcejL#-)}G!UPgTWEW6+S~b8UC^!K z`lRx*?~N|wN()U@m;*1I6Quk3ZaUkOC`xRd9p-4T05Or8r7HeHvx=`3+`qHtFwyD0 zW1mW9GtdN(@oTy=>v{ZN+h={`$LTw5(pYLB0(R2NXYtCoT#=msGt{Pw4j~gTbfhB} z#0QS2<oRb5CKI%52NW@bgR8}#rD2iY(>n0Ra);Mi{FbW@0P3LF;Y=ro!oODNV2~7| zwQPRjvmjITE=VSUE|CV(mu6r$b%ZLR#%<>sQ81;8A5X;FFpsjK|CObNlK)l28NA^d zfQTW1SqIjYUg=%ipEB%AeFa_SiYx;L-<5CeZK;w|1-7I|6WDv^Yl84$3ip-f+s2ID zW_c*sx#eNU)GXz2hWxe*-7pO_qs34rMg)MkzyDcb^ZEFS(ejo<>_q9a0r1)QESQW# zM|;j~`5`BqIHk!(``=pULuJ5fhaLt1go0G?Y8w8F>|Qz~I)+i(kTE@(Q6+LTF#0mA zK}R>%xbaEM(d%B+#sK!j9eE*TJYR{*lO|XhI`+#G_-TXoI0EU~nyOeEU1<~aImKl< z!Q}_TW_}p-$q;uXe(==M1bZ6;3U|;%O##62z=<{wci4r4i$IVn5Y9yn0D+?yAfq2w z!8C@=F}G#tR8_NA_(U6~(U~Y=thfB%85nA4iGD!sgbrW$6;^D6Bo29a0-#~<w$GS= zHCjpP+Xx00&sTd*$Hr<($$Tw&<L6!FFe@qasZ$KYfB}#gYUM!tiju)cvJe(slho1K z89_l?2|3abt=s@*sgs-BF=-H_EtZ-pWjib})?+6({i2~Jzc~Av^QwMZ`Bfd5-%4fs zh4Qw5K^es$Ba<WFP)Eo+x4LNs#{J}_AxT&rhBU$o4drX8GO@3DN-lJXZo2Yo(C5Vt zxZe%t#b;iu&W3sXxYxyjDT=%%M}#G`mrj3_K=$j~$a)xBVRkJ!mEH{|3UP@d6W5PR zO4Y@~_E@>RTY*a7PV8*tjaLpROeVT&Ml#GNB|Z(rmbZDwDhrA6%QyHcs$gI{JNb!n zC)Si94ggp*2p}t|Y0%Ley6CD^pPi3UC3$|fB<OUK)E}Gbj*-J<hVTb(<&F;SHdD1$ zSr7ehSC+XpKA#J5q@lWrLgH^AESlIlEh2*T;^9Z>t`NJ<oWn_M7~4xoSjO&+goF7_ zJL20jDbotfLFDCj<LIH7YOsdLP614$Zgy#;?Wn1A5^P7V=3($WG@dRA<trk<im%CW zp->ND)hjP+95`ZvmJ!W0UHIjV3c;GJe$AIN-(NC(yQvQQ2ChKDSddFJ)L$Urj!nm- z=gvIM^JI>LvBHT|w$N>Fk1z5@S7ldUclE`-33VR3{+k|l*pRbr^$1HWP)(LsQ?=gb zZiq?Y?U1RKG5gM7aYnWm|8hf0RwcbjKQEc*IHWi{taKF`cIsZf6>pK!ZTi8e6zDGF zLddTm-Lzef>y*Q_-oaKfuiu5Kj*K*b_N1ka25Pyi!rp(EJ7nw|{nhH|h18Ki!;RG( z#VWo^4^Pdb!l}pv*pa)ld78wXYFJ}lLlu2KD@dCu1y`RTzReLHJid*>s29kU(&aeL zrXd6PeYdCBEUC>6kL6CMk5G|(2(Uv+OBd14-aPo1xnBU;kEd6{w1flbBHg}vVKKJ` zn<K4U?BaX8vEKytH{1R#cyW$Mq>hx=FrsTnO3NV5_8bpeL>K4qq@b;GRbX`pu~?W? zlT9!xjM1=`^IG#fn9P<53`!2;RUK!SF6Wc=HZR^W1U8uaW9gvfHHZf-{LOT&^3RI{ zuQiQ+-T)g{vq$zoW&#&sAxqzSYQ{n~CT-u0RwSjvrzpk;AE}knn*{?k(>!bf{RjjQ z)sFZl-{$_xExq@UtL9hlEk9;&DkV)e;r^r-aj?Cy75p#XaDUGJp5NE%f06(7hi4NL z&Jk}ae(}FU9>)oLu<~4pH=I|$_kF7zje{u&A#-=7D#Q<+Tw1Le0O=18YA){p%^>Gx zE5#xnI-92wz}%yAlCw}OU5$BfASzYg9KW3jdtqWH|Hsfd0xG|x_arzcNY^X=r$y`b z>w^tUlqpc#MzdiO;S*feg`ATOtzL&uA2$2zz3yq3%<f}`O7Dyw2@jqO+1FO}-;1#5 zlNT&g!^oIvdYC)kWEfO@{w@Z=Fy0BaAd)a1wuk@jry?6hf4%%$MxQ$vO$n$;0zOO- z_I(aASiF$qEKU%1A&L-~Wchnb$t>`RCaDyntn(%!JmoZ-m7F2`%|w69$>mae2lY-z z)L@R;>HXdwcY{yZzI+E#tN`ul?g~sKCs#8_YLMvzbop^Q1`k$kO~#B{9h&CBR*Dr* z{$326=r~yIz|E;(b(cYC&B;R_wt*f8t_|tf{a+eapM37m2(T0B<}#J^<@*K+G9bxt z_kSrVJ=|vK*W2=^V8jYD2n|a!hJo6xdWu4<_KCbVR;6YYl3CKakvcv?09w=Y?rLvx z*1|*b2}LV=WlBM@MPkW*EeO}C$}D-sqZC~%ur7$FnOGW0&k>Czk3{P<spYv9*Z@S` zVJ5af&JbwF;z?wctA}}+G8W~rzFkKql^2JOy}Nh%4_E?&W57fhMkxSCJ{(ul>4S&{ zwO<jG>$CQ#t2NCwld_OT8;*GiVl;D%LG*yihr-I;(Rb0H#U<wmR?>WeU&KPTsPfhJ zCb0Ndu@5=W_lxBs+a5^|IU+)O#zq0k73{;@(2G;zqkMJIU$U=5B!p;Z&vzVoe!u$E ziJX6bK@&gERpkgF!p5;pVYcU#h`_oiV?dv#22>eWO=aK&nOR7%HJ5>g6xK4ul!pyi zveRpgLZF_U)|WpJ^+?ShX<@2JWQ$6ndC43r&y}M3u-YOrk7;D)s6BR-A=w?(Q;$&A zBQAg)#Q>eZWB7xNH5Ek5vUnW`xFc@AqWGmEc4|c9vdAvr%;r}xSP0=30=u*Rk}lN3 z^1-oo=W_I^K+RZGu3}e|QN4bV`-+JCp4?)b$$D&i?du<_PAW(xmP?)4x&U&nIJV32 zYL4XG;<ki_;@qM%$74~dHcL6Z7`Jbe)yff|>yiyv395MK9Pw8j*zF$+&f36^Hf@hT zdVS`ZzwXN;_L&~&IXW_GI2e4FwaJ45UgBUt^|316DYG1c_1mrt&2HC+t9nv8GgeYG z9B$WV*Oj1hhYvknY9FySi&p+D_I7q=vm<{M3V5)fqfH(;&I%&5Xk@OJ-_^ex+I@;m z%1!W0^0MH-nRTA$e2!-7#`W8%msz3`ifJ@GsSFr5OV$e;#g?hSgIlnd%CaALZp-M* zFn&Cu8th@W>>f2!j!x8(9ozfUZA>q0p->|qAc|W4mx90_%j35l?ia7Th<)GrYHk~z zV=kzlzrho`WO4S#M>tK)M;!D*$T=tk3ixf|vatf~r?&qpPx%VYB0DRmD`Vgs;;CIJ zx$aGB8_3t{r<0g(blVBmyYMU*YlQw9b>X9>RMNNsG{m?G=c*Cba**|dvTR!*2`An| z7pWrPalnM<>Z`;jZ!}N8HK#&l3R$>JS;{a6rgR?)98mT=D|?W^nb@;*Mclmg9rsb6 zw^j9iwQENUSdXRaY9i0qBXJxeNmMIon1?V_bi*Gyi8PPGe-@S(n>O4!jDLk0tix~{ z)*@t!Q5h%_L`5xA@p(t}8Wzoay<Z$SX@wA3cVq5JLjwDWSkl_JD)sHZQO9AWUguC? z!Wn~xvwYs}k5z8^meuc1UHa`bk4S>=5y1)BqDi}F30VeBbE3y+;|%E%4q6m?mW&H1 z@bTGy1wnBF8`auW2+^*CfYc5Zs`|gLyH1bWGa`%^o|kX#8oIlpXWYc&--ojL=o7w@ zcGWh2z3y#CkUa<i!*V?ueVIDhXG}KB7p96b$0rAr<FVF=0WM4>A16WyhhU{N4^I47 zoO4(X<J(Ofymq}Ad*Uw&d=&y*qb{2LHC@mS(Y*D{AUp*2(aNf!vuFl{J?28KJ`1Rf zveD}2dPtaG807~R?Q{DM<Ur6bHQ4)l=CH($rDM;AD)n8uw$Ho~X|SnUCRKhE_5{Qo z-786>ZhiwNdpzD+Ad{GWNfI~(faVPZpYvHee_5*Qh*zjML~fh|KWrbdD_xuwFg2wA zIGG_;cVdw4`B^)`Z&)L-{NO=Z*m+4a#59})Q%T^7R0_Y@lfh*hAgn~P$HFl_q2kaN zN3rk54@+0O838it=kT$f)?}Ze-_-CJl*b{f?u|nXo#x9<$5&>fg@E`5w^RbhO4uWT zd3TE&rvmU%9+B$Cd*=?=19b6x0-v!ZiL-Q*vGQ2Hv4R^iopo^YGe@>SN1k9~iy%|~ zuu$CHxq7n<YjkW8lK=?tv9k?~qzczlGt<PX?eNu5_|K6{>GQdXqCOOc`E(PviwesD zk?=HF!f<Z>q2r%pCOgjwfL*?75E?3_9jw$ej~W;jGU(((l(w)?hxIWj3ec%e3_0F> ziL^q>vE2p{h?NR6N)Pztx&}Jl`XpqxPjV(<*)BO6+ppC7his+w)t!6sd^*yjiU(_} zSYpNaS5G--h9~9$MZBXDZp;vFITz+UwtsVSR}8jHTf2fg(ne%z0|Jy|`w`Lb3IBIN zbEpIB4xP%Q4ndS-W?(5F_a;*#zRM#I`J=Tv?2=7l=uh^R17yzt5&k3It@He#p42%~ zJ@#jhjya6@z^wunvNqhi3Z2_NE%HO=I&cV9Ojs}L(2>p08In2z;X>XvGSGMzJx2l^ zndYJ{CRNXoer$Wdw6#-B2UMq8`0Px%wJz<Zop7_cXH~wncV1NaaIvSp(VL>@@)95L zTX%G%zwG{aik+Nd-=Sw+ghBIkez6cC+MBd!iLKX$HQ!j(UZGbDb#7G7$Rp1kY%^jb zO@Z;~7&_~e@a^5pK&?$rgx(DfN<lh=f2@WencEJ<5xY?_>1$m#GGYA$wNiiL_)VXT z@VMPas+fg|1)2N+4Mg~GzGn(0Gc;4bl>YjoNjF6}aMJNZqHtX9wXWy(T$fk2RAJol zW+XV6wMvt_ZnDKw+nzdiI=de!P4oBi6HgSAV!_N2;O0{<OhxIC_>>^$_7AO{?<ARM zj4hZv>CM)fJr(am)VO(j;sXOK=N#OQ5B%k=b>}hb&EK$}a!u{4SYk+rRs4<mW9gat zn+aL{p#B7DBPpZ1rWW6B9lM#XN^Jj2eSiRgn~!Kpw2G6J5c@3nU+D%Bjvr1W)Ej1< z8Urh0r(r<ap3W;%(D0`(kWPZnD$7#Popi9-b3LH0h9c1JRxaZ3FyrQRh0*2EQ?HWQ zm|MW};ylA!XM+)tKhhT8AK6xS7<EqWX;=rV-Q^-EJDF$CK7Vt4u~+BWH~+<7<<-VH z&y+m^5pfYP+V-=W>MifLSqEaWM3zE4VX1Ubg7z>|rh)?n#Q6_Ddx_tBdhzjAB3QDm z9c83TUtIICMLJF-;ytVoTKhz*0J7uopBRL?DM_py8zuYfrpRF~7(EIAM;Ib}&N)fz zuKWd&TO4FNR<uVDSHu=Zs{nhSD1$|x{*LSlbyjYFSn895TT{6}b<oc^SL5=@ca_e_ zJqGjFwIr`o!SQfvA#&%K?MPf$YJ8W;YF)|3J==w97f9sOkPSo>BNz$)@`$>I;&2cY z>U+)vA$E;WLqz5i5e;17w_ldvP-i|7WiLQ@+}Jh;Pv8?$9uo~#?ER;L)$dQh9l6`^ z9_~`B_R~zwe>$Nf>EvodQk`EU?m!dvcg!l9FWtt(W}bt|Ox}#WD)H$k&ba`lzB;bR zSzB6~Pr)K7!O+;?g{4-Z%Nhq2TdvoPA-(2M_*!YD+{Mx&bR`X09?WXzpc=SBEx<Q| z{)Emb;l2y9RPcTJx=Pe80CogbP9*+7K%P6HZec}rTiSjMwx#Cc>aO8D5HUpEJxFjJ zf}$e3)N~gC;EB*BuHq~MtB9A_ov47!7rzCD7eSek9JoKwqxG1nr{`E`18?Ct`b0|a z4MkNE-&fIW1N4O5zV4*rq7>P^jYOG@Pq#NfTF&v<T5-9!wc-2RZRD*THBv%O`-#Ub zq6mxlokSCkF8l#pAB_4kypmTZ4`!QRFKvsuK<vPAl*N&u=FvIgxA`@VScTubGLIsK zf|40Hskvy;(@*eA-5JhBy@(>hB7^^KIbE0Mt2^QAu+gX%ZWUHvSaw6A!3JB4MV|d6 zkr9l1cIbW0<8<TB!6L9oG7;%gLhy6b6Sh|UoKPWdy<r+x8t%5Izb-iKiLxvLE~kt^ zfPWQk7<k9o4G+&D>R{4cFy~J@Lt1FnNmvFaEfo0T@emm%;S`YBJG#*;UWa=2h1EFt z82hA7k#}J{Nk-WaQOQAdb41dh&Yijje5}a7p&zY-+dmp7H6xd*N_5&XatW7hHCL>) zG8>o;3-Fyxnumo2*klXe3B})556Rp-@aXYrYq&-}y1M~h*AF)__>UZOoSdzDDU9W( zmW~GRDb^Np<RCf{ol3`FiZN{!*^Bu!XzPU2qJ5i}h}BKqi6A#+)k9CgMk?V`5W1Gr zzXV)%c=^(ZaxhJFif&<3y7g~PVVoF;0^3Cj;%GKPDF8g2hE`v_6;JfF=RiwsYRlQJ z`3|VYCr~e<@WeSOCHrFs;tp~I$RGjb3Juj5VH@eX?@a@$^^s}xdiX7x+@qXapzFzB z3igUF;X-Vr<(M*bxzIk}3_b5_*o~uzZUarx^mdX!oFpY5MgF=eSfe*PN;jiIrS?gr zrqJLiM580L+q67*X3WBJ|A9(@>*oc^<jVIT0GgJw=ehmBmWuG1;_p?0-csxLodWIJ z>G$w@O^*;{Bery++3)qh+e-dRp#ERH@zQH@MS_gZ)O5rE=|P(Qg$j*Tu7QmNNfI$H z{>|9e*GZ|uURfuZGrdsI+650V);ArWRUQ{&1j7-zt@sbFm+KMa4lH(5U6_v`3Bq%W zuHT)~260dUV!|Bm7ycIs&U*Ae8}@y!!(@)_?3eGk3AUr%jzW~`^+!)#hJ+p+clx*t zW9|)UmD;ZZMpxd%mwgWvZrxr*F?RhcfUSVx5m<xzC;L%luqeUKQ)e;5Mks@}@HdfF z6BaP^-ONTp`2Gzf=aKf2Nu7dEsHu%!kF`JuJm?K7=p+Zp;3B(eQBGwbWGZfIGx&S| zg#&Ro)!YEJdBUzJEkUWq7ybk3r+Mj6UxQn*zK<-Bb+VOV82Y)qaBR4R2eav$LlmJl z?bD-hTOrhn(DFirQp=Z7&)1{hUAJ!`Sb5mDtBW;bEI1<QlCEDyX?Q*jwSG+#o?Km3 zXQm^4uwsk_?2AdX)7m0wNYp(br)qYE3-{1h$8Q}MZS(z<C4_em_0&{ZTASBeMuiGc zX~FRxnKJKU7paBY*r|Lh%|V&DZ<f-L?CGxD5{yLU3Pnk!1D!f`YRB5^zvwW0f9tBm zYpy!q#(D@Yqv?tPKQm-pcO#f_5w@urNla4&F8<@Y-zEo8W$+3POr2|Zg63QF=<Fo{ ziXlLqp&=VN$ltdguV!Dk>xNL&@onG^n7cT2{OnqD954<Ixq0Xmy}@bk^gCHnObh?G zDu0e_vNf@f-O-AFQ7e50>+tfKp7U4%z=7XYJ$e5EHe8Uf(^xK|!537hHO$9|eUTup zEl2>P&`?;Jz4~S8w-b8_vu0x?>0j2&E<-1*437K>CO2Q+)bfCuhMT2A9jV?rUhJ7! zuJN;NMf7=WX>RInh8DIQYsf|D6jJ5Ou$j^4Za(o9v?Izz^Y-he%bFxe^d?K4ynygk z$+($U3#s{c9V@%U>QZ)i)*|&5r0~4w{O&{~nLGFLRyT^VU$7Z2D^rV@m$cQ^l3j6J z?njo>ew#|T^|lqC4!00=ecEzrdcDaM&&1t|tXV3Zm#u>|a>fEQTa2HbukM|}FDs4H zMfqzCZYtflsZxS*vXk0fPFwJL0xiY<IY4M4BN9%&u$@L-P^<Ipo6Vb3IoaZ_Ty;qK zFAZZDdFaxwi@$yeVm~Olgd`h<=85HE{}oWv(KwGt-`{DzhVutlrqvqE+J}sk6K>n) z-3VM^%V~Yz=FMOXD)ch@#$`MC%H6Yv<Vb?T(UOj+vcTV0{LNx^xm!f`o!V<`UOuF` z*o-ytGf=BTtOsL$oV1IzRdD#-B-%D6PJ(qa3c@Q`1&amIJy12$0crC*%GkNv-kM7y zqXVI}_neivdLd0Kdmfmmm=mFAfL-fy&2N4ig#0|bJYAt5)pjUN$iBUD&bkm>tj|pk z6-QKDWwaXjt)julZ!04h=3#I9I&4dKRR));k*;|ADR;}6*Qs<>tLAyUD2G?#(ks0M zJs=MNi2yZ7Om=v_!e0r${EjE5%z%~V>bc3s?oDUijA9PYm+Pe8*6?lbHQ7Gd)Tfmn zUJr7#*iDKX#qNGPXHg%Gn@YQR<<Dw>{~qNK(&@^YjLy`=Q-Te7`$m=3^}bdq_x%W0 zL9oDcl>~cP4r2f!v2+D-QkYG8-{(^bA1~pkbn_!8O8dV)KopNl;<?aCbJ2kOq0qYy z`{?9n)cnObCt)2AnwBL`{w=QWi$(wK^NeyipgbJC1fWb_))f6|Kc3b$@=b5Lp9jNO z==^%%NVt>pT|yx~1P%gbL8;rmTip5~o^?MxfIO0|IAtZZ$p}#e_p)uX-rc%teMzU% zk`ED6yobM6ePh6V8u=PPlcaI^=EJ-Ic6EsOk1LQ!Z_U=K`d-93_o0*yxaHA^={@)E zX8m8Wkr!Z90uim(86RGaJ+K@H{TDh?jw`~J;f)G=>qqy@d#c{SKI||@k!EBW&1pkJ zXDufTs(0d5b}N$!34mRxR^dX$J=e`!<$YNDK$R)K@pR6CC9X6LbW^U*_mjobxO)v> zYWpSlid%Q(ENdl}g4HYA%^No)tOJ`L8pI)Tsqj!SW2@bnJh^GB`yY9VWb^z1NZ+y3 zul8C#H>!JPZLBbDH8r?jp|488<VA*pk;)cMB4)qNzp7X7|I1jASGe%Yyy}m3)t^xL c&_mYgZ$SqHe=xX}K;<7N$DnUl!C=7Re@6+r1^@s6 literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_sphere_infHorLQR01.gif b/images/demo_Riemannian_sphere_infHorLQR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..64306155c52f21d1db7f9c7c5507464b3d90d2c3 GIT binary patch literal 652118 zcmX6^c{tSH_kYhm_KC7DW8XDNb{bojkdR#s64@FhYcw+$YmA+2gY4AUcMZx;LPFF; z*;+^`DxdlFeSYV8-Fu(s-sic0ob#M}U-z7IP0cT8YIzXATHs#*24DhU5E#KFjD#au zkSr_;j;w4bc2+hHb}kMM4o-GXE)Fhk6!$3sF@9bFK?Or0r3=C;W}^Bx&_)5`XmJVS z0O<>NWo6`K&B7J*92LyNl@yeew5^rAs#JU$FsCu94oT{2>grBOTBNr+TDm%<H#%`| zb>iOXdF$(^Y@gRR!s=rU4UCKojg1}{o7kCLFfqMw$MmB4MQb1HOIDXIM>W~n*#1vq zZ0+pq?QQMt|MdxDSM0AiTyb#3XFEAKIXgK!N4mH;ySR7+x=>tQJzU*f+}vH=ueo3I z#CduVJ+J3^d3$-^@VoAF{f6%i-+%D)^$YY53=AO!CEmJ~hsW0h2j2?5gTHh4&fSQx zh^UCDsM4r=<a^Ok(f6b8-;X8|?h}dsKp>I+p`a^{6c?A69#<I`_aZ(%EuI`tPI&Yn zk(`)Vl9ZH?l#-N^nv<GZo0^uImR?$xUXe~oqx??_Gblw_8R;1r1({hHS^toom7SZN zn^&EipP8SZo1fpBUyxVuFe&9>K|x_bQE_2$NmzJEaY?Dq&C+QqwS-D-rk0hK{gaBa zii+}zM-`7MA5~TrmsQo&RJGMqS60_l)zn2q){ztIYU=8`rt0hJ>z_2#Pu4Z$<u%kb zG&VForer<I%6iiHnD&^~G}+R8g1wp6+}zgEl9=4u)Y8_{*4EnAURT%A*3r?^*VWP0 z)lcv4>h6Bg-P7IEmzCSs)AzLR>A=&0f!U$Kk>R0%p=aR{&xW22KN}uNN*T$`8!0Lo zc|P(#nVK1y9vvGQ8yg)P9~v8fF*7kXF)=kUSzR+ZH8s`SH#IReH97ra>cz_!FJ~{? z&d$uvy_}n$o}Hhan}0R8F#me-<@}PO(sFD2%D~X-#MJ8Y+qIgy4@;|Cp4YcGwm!9Y ze4U)y9T@tiq4neY&!bD1e;@w-^XKp1qd&(w`p2Q+$NwGw7oYIo{Hy;yeg5z8_kVx? z{`dF4{|D3Chk4BWADB#WCY!a1y`7PPjftuX1_A;AK>P>_Q~ft8{cFJg+yp=}fs7L; z%F3t%u}B^Tw^3TzPy$NQqR6bN{CNuhS-+LhrgamNu}YVhMrQF?mYiLknlrceL=NUs zzopjMDyy7xx4PX5>|`(I>qQT<*PWGpS$M&#L`dTSb)?#+!lKxst?pI5)461)oLg^u zV{k*sA{W~mmRfx0>f9&V8{c%`*T;)5cD#Gqvs-lGIo%QR?kNEz#J=+S^!uS01lxsh z{-MEP79l=;q_c<jc&4Oed#}KE@8@yn?yJZxomrozUe0nTj%@N-D0P=rmy<}SzQ4P_ z{dTISWA`0BmQBpMxAWWjXqMu&>E5pItB1eETd{rJ@k6{aHe9{kKh|bpPokKndi}je z-?!%Kuf6E+`}1pWy<=B&nOYEWNQzoL?H2Iu_$p{qEEt%U#5plRi((|G!r>dj(5Y~= z6U)92?$&jaEk@iiny&;|66Z@!ESbj*_z5QN4RJxO)Ls3OokJfY(M4NpDdZ%XcWJsm zx7O3KaCxaH*yRE1^M@bus6imruJ^%07Wr;jJ*Uh*X1crQOW(J-YF3#&YI5`_*b44j znd=mzbpv1J!C=w3+P8j1<D4Mb05*!|S>t+dMHRXB+8dEyy5@`q-M#NgaWCf$-;agz z{57fZ%KWc#pge=KcDt%5bZ5JI|CE%W7L)P)ihE5}-A-LY`_4|i-({vB=)`*O_cWbd znvqFWd`|uVSIJ?eC&zhXg~6tCiTHB(d6cV7%RTP;V&t=A#v)XF0XKYC5cOy1E*f3` zxpHO!D^{~rRsXg7Gj~Dx*~$&0_xKxHj<<rp?}t9=^U{;O<vjec=S}~Q&_r?iixa6U z)Egge)XAQbx=~vJ16(C(CHdcK1V&Rco0`${P1VTFIJsuok%yNjM)D$Ot%hL_w#KB- znGxWsH;@%g&~xFRSrpE-EB=@<<~y#fnPXIyJ+)*y$UGb;9)!%<J0?}p$E~ama;zYs zp6X%6>-M<t8%1aCO5_K(2*C1#r@2n$pHUH1g-j@^a_5)*)Qn7Leh;j`rz}5sE6!^J z(ZNp?cf8FL{BpQXF@0Q8vo{F2`zqh(@zF+6*wwpPIM@x)soRF0>z<K=0U)Gg+TgFX zj1pf14uMU1u<EK|!!NGQ{BOy_%UV16Fp1Q47P<cN_er76u9)(bQ)Vj1KjzQ>rxIil z`S|$fO4zR6M%)#~m{#cR&8;#)Ge8L**wUy`87A@F2!sYJlJ=+T1IeXh?SH=%qrsqK zzY9Gqi(@t^I*tdtqjWep={A$L@=L~SfYpT-RVL}$q6&bYWt)LpGnPJGfEvcms2Hzy zx_3}cXmn-Nn5dqOg*)*{T+5ijoYE9uKe<I0{k@m4SxZ1N83$>f-S-mBEX%pshDGMG zFJY8y+1qC5v7RDqCX>q|$iqkFCkK=Refb?jW2j9R@7AXp{#^)&!FC9u40N%n6~ddH z{3oQ8%`Z+?i2iaKV86YYlxsV`ZMj};e0+jP1kYEpcglS`^adxWK7gXn>0XWZ$;^0E zA)~Q9^vQWT@g94noM{0q1`UsiK4GbF?RqVL{0-G=_769~V`DDMv&3?j3((W1<5z$0 z=k<e9?ve%MJOx{{Nh{OWlDFHuInNf1-`fafj81wRe$QW=tWxh7n+l5jUdUjt)*LaP zzWwlf(YprV1SKO~0{p#r@1E>~G?N$jr8_0R*!lE-)iPg1h)$HCku_Mz&L!f0R>{G$ zP3%oI8`1_(88W)Ym>Dq>BNI~2zbb1i|L}73jgSfv<t+mZmzNnaC(FeTe9bSr%w}h{ zRtoBEn|LV9CH}U9_G7u_*2m^b6fz)KjyjtJ)_Hd5s~Tfv1w?A{e3`^St@(pG`*_w@ zRn`Y}4sAPEs+a8>gRazFJyvk6Rd8q!ZENt-Q*^0Ve%02T(-0)>=ej-)5)226asQ~j z`peG%EKGkwIQGXKM-m1F+i9`KpFH?30)yP4O_T>pUOb9R&-6o^llzpe3l%PnhdQ*R z9tU{KD=y7?s?#b?1zy)mS$<U)+VUv=i~ps1rx(oOpR|U?KtETZ<u^auTj~QFK<ayJ zmER6JM_1p1`DrT~s=vCX-3cKDLhf4@zq(&deZ5;+NZ7i;*Ueac9M+iP{*9d1J@s5A zyvOzJ_o}e&kAb^koBnUVy1efDdg}DO5uJB?I~q^FRqn>jrM&yEKd&1ZbL$?PF7EJl z*Z|l86L;LR%JsKg?5pKtvWDe3Soq-(nzJd<)N+lx@bH<ObyKqA<Qi|!;d4w{Q>u^U zy5O76VV14O@n?GNIR6}uJnw3vBv^is5IPz)vu@7JbMxB%s;PlZYtD|BTmxK>#+{~{ zb2}zKsze=4;5b|IM=WogK6^Cj%NYzlNh8Sq3TKYv|2vadSxA6<=$sClZYus&w5k8S z;6-%*_tI~|zIy9R)A9PP<ve;@7i3*t5@K2_WI47i?0(PYPODXEG;Ui<{+>Z%u@6oA zKAh_~8Wc!tsmo&Pj`<ML#qJA0_!$J}iH8d<kMB0z3H;=|{`+;u!a?JG<$$ZZ%Ztxt z)SII?0<L}fz0{lA)*9yS@9Y@$danIvQ`S`Ajj*UUZ#gwOM??aG^9omn^*g%frh;79 zs0&~my<*d9H}cJ&w};am{dYdU7e32?^wOsa;MRL2p}!2|rOrXV={>T}-}k6=&1VsF zyHI{A=)`E}u*USaw5Y%9Xs)hNQ|sH5^NbI2%u8M4j%oXuJ%2x9(z_;ori0=9xT(J~ zZPQ6B8w8_>S6I`atlxbAM3b;#cBy;TK!wPvdAx0t-aTL1|D(?Jc;`$<#6QK|75=oi zX~5M(Zi)(SC_Mfwl7NM7<&oNZj=$j3quyL3{Oo?Cx9!)_m9x|f^yhU=P9FTpTS|TV z)JuS|$kVg-e#x&q@Axa_iT0aIHejA?#(w^b-VG}Zcw$a(pUM@zED3-b-{gTrud0CH zGrx*|=>Y)_O(C22fJHH_5xq-)*TTdujd;2Jpr7tqUJ4@d@G}obFU9O%WDvnrw=V<f zF{=Uu!dC?}K)VKjz%(LCn0iq0Rfh?2Vi0yK!a)#R^bQvT;HQfIHSGVI6>*6frv2a6 z?2G%$;+Tk!f6gC0*N`}mg&70UzrzR?j*)O0z`_7b(GYelAdUxFVUP`o`*(i2)#OFC zEJXJ6hO<(MjR=3qP5^-gHSd8SsPKvBL?tsoY7eyGL*m20c1^?4NPn$E;^yXceS{*G zKh97y&e$o=@0*87!hK}T{UKSfJO<3<i_gvjOMAf^_8?reI2W@!^VQKO_qfLC00@A) z0njiM0KvtG|BP(o1ELdR7Q={(3DHnGdC|uYf=amM6va+p6`~{rv`5djMf>uTKv;y6 zO=2`6vDP#(h>1*y-14}?5BP`1B>uW{ke5^*a^E%ozSUuz?csfCJa`lb=3?A)UQDXv zzl{Q--OT_#27Aa16hwo$%s^JL2m%eflMwgW6e2`}8SO=54q-Sf_<=O!dOqwVjigQk zxlo`)ey|$=SE5HEW}pNc<Psi)U_hqA{~a}sVm1$yX(SLGK8{6%U_l5fFua&JAO}~) z0}w3u8Xe|FC5bOWaRA(k;4UR|U;o#Qhv5{{XG!qR<cwcQHvGxsj$nI!312#eSN?XS z1|SBoTw<`cg{RC>VK_WO0U2{ulam6#qo`023LHgEkHUgM082X+hR4HOnC%?J)J$6x zAcjYHq2bZAe{0YX8Y}?I!AAvJ(OGH)))iBPHvqp6KqB}N=f+?sXPmqk>@}vqNi4z# zfJb8?AUbS<2J^up_)vf|3gL!_+wPI2H*V$mQji6CJRv^j;TiPT_fcK<BpEF7Hi)}e zSnXC`axG!215~pI!cn2^{7@f$AZrE^lo*GrW!H-UsiFWQ3}+Y~u}*-30HhHL;6$^X zqyxiL7zhheM*%u$mc;}_(jvm{pIJIV2t2De3Q)6Q0RfO=LbMbi6$Bvk1b}xMfDo3I z6CbUJXMHmQ3$jUZBScpK5D*?ppu;(tlmZ!YR8UpkRsn^T;&q`Txbd)LPoQ*PtMrF+ z>CcGL!-7(Qy!e3E5zqPZWo+(AQozz^fNlu-T2RW`O=VxEa*k645TycLpvQQ?9L?fJ zg&FK2rde28Zf4@TSU*++ZG6yyJ*XWTCWHcFu_=5E){_jNnvr(@6rc{Uyy-ynBqcU= zu?kUvdQ_1rmF0N>i|B%rCqE+TkPJbAB_gAxu&ka)xQ|WBm2se$4yIK@+)xNUn}m<G zUNz*rZRe^Yqfm>Q{LoDbvFn~JHXpSIsi5ThMP|4oi)jqtBn7rffMM}S1RbE@a^n#x zPxdM&U=M}00V^i8GIk~_O`xKg27+Sz2jyAV@j%o}Rxkwy*(>jlU{zg$7%zh#Vv4P( zkcd&Z3q2;FD&vwMaCrxSqTyaB;2Is?d&J^mQO|~f1yLehLi298G_1zPeQ~a)Ao2tK z?iG!k8Ic5s)HT$N=Fc3loV3aQj)AFRI7?})u9#x91*n3N79B>q#$c_-!viCbZ!oNn zDA3QQtoP;IKaap_Xpg53LHB8_PY4`*7(m^Ir2@x3vJJQpSZh#-eskdO4r{?)CFdU& z$#K9A&svW~h%s_I#(`{Vr6-oHhKAJMi{{t#@f`OW?rtuLZMbRC==3XzxzsSc8EVX= zfaX|Rifh7H=s@FGj2HvpM1hT6WA<cY8fyzUv0!nVnCc~jDi%_()1pxmZFCVlRTIsJ zZ55-`vhIP5d$K?Cft{j=xUp8Dt(K@!;CfFEE44a+w*op7edaJtmd$fRt4gV-BOk)6 zmDivh6`I9IjdSfJyLL{yfMq)<#GZJU*J02ZcNPjcD~0?n&o|?bUt1p8GaPA7AZH47 zu_s35M0K4=Bty_$5t=}`Yj;I`G&RbnpuT&$%Psynp}Z%Os?(j+UgD{M=jQ7j)aiZZ z+B+Q8J9-h{4dPX~82KRO?y(klR;O>?weM9_gw~&4<Y@lq1M<$fC`o3hyML$qwkA~3 z>FPRLKWVdXO)*>m*}wCt|DJ5ar>GeDLce>3Po3|GPZmZJ>iZlV?N3lZ5H~vX9vxmp z2PP?13D-r!JKTM|s(xO-;55K{Z-BpO;Ko269|FWRlPvam06lpdtve|7cR=p*fKo@N zgwmkm>p}6}L3!OFRktDa-a(b3p);Qc&$<oj^>)fP3@H>18Kw^Exjj4oc}UmtnK}D2 z%*vp|3f&w&a3a+!AhhIn;q&Rs-sIQMul{}R<PeV29lq{191`kd!Ta=z?)5c|`!0Wn z$6h`ScTMtl8#&GE7oIv2+B+g0I(+Z%h-_{LKYS!k7;|jn-7n<Z!hGFNyzuni>z@5W z-@S>RXx?k5sz+}KKaB|R%$gkgqC=718cSmz_tWjK5biJ2^>jsyHYj<LQlG{PPdq*0 zRjK<_GIylxf{(hxgxTU~Xv0L~%6PA(m%Z?0;yu4urHOIfiK=_!XmT`vO*Brh|K81X zjocWNZdb&{q+1^OE!+5%lGl)~*LuK&QdR$~+vMr?#Nh@{5<A!R?#WwjV?Pt4-ZqRX zW5GE^03V^|iHv*p1c7s=Ewks=y#hdt@#4usi#Yn$tI0^X$jcwRt)HdG9+-^%QhLdr z-_3pOyA{@z>GtC221(c|md|EJBzh)5@m6-xtjg+3ri0t<%w9F7`<#08oM!PH+%)PW z3LFp$u(;QXY<VC6mH~7_(hl5}UU=mKm~*B@S-#vaF%~84{@@U*OrICu^2f=uT^paJ z9fF!PJp1APD*59|qp|i6Mp^N!uSZGJHPJ$Q6+$(DIPS5}7ZSRY{Mi&dpYvL(ifE=e zFOxsxR}*`Fb?(bW()%cqIL6&!ypZ9z5N)}nofyLhuzhuUojMg}^dR=G$Uwv&uCD~s zeWe#@8L}Fc<%Kh{H9rAlld#1HuHK80(j(IZme)F1g?gf;FsyH?V<^ZfQ`e}#L-HHb z6*f##X)^2jSfnQs7Db4*JNCE}zCueO1C23lQPFppnu!^jKBDTZ0|nhOhl$&=WN+I1 zO|$Yx=&X%Za{5-{pq|gnHmheik>>u+EIfKdBr#Hs9J|-`R_R?*WJQRa`yI2DTK7kb zVbQL%;w9Onu<#BF|C<TDgsdn~J>{KcUBZ@WqRgk&5Aw^`!uXgJu04ROx^a@j8j^xZ zh{C2|FtAIs9Cmzq+i{&39)1nYPK#&_AhRW*^OT)A0_bpcdgQPC@<fX$PCA$mfMINE ze<2al+a79^a(z5$8jtWnKk=-APE+cgMWfho5IY>?<Q`O&3e3pE>`>qbr($zhAs<Kn z-A$XfI8$z0gZuI$r7YOeFmQEbt}+uvG<J=;MrU)gfnSRRXlNF14D9M6)NTfRzYSyq zz!U_xYJb(fLLq`^A2<ukeN?vAO+i*z$crwJEgB|HNQ>QLJ#vcSq(GghkN{pl702NT zAV$LhB?3%Ce@aY-tcc_A0T6GyU<0VU?C~4=1eg(}_T|cllDDZC)F*QWP^yp;fPvm! zd}N1#i7^}%83mVYVm?<xoftd*lLU4eNR0t+#c;}r8tkpC;a3<K8V4SQ2%vE2W5EPG zA{qmqt6jfl4hp~{0#KRK`U~AQEFlz_eiug+3K7L9R>UF#@L88ccZ6m*VzG!=+J|47 zoTY{9Mtg`5CYoh|(K3fe;%5-rv}khzN6-wSMV}<z$^H;P;PD6o7UH4xFbtg)4HTXP z*c57DAq;ptt&k71AAmyiCK3@?wo*DgdL~P1k9A!OekHknoDL5tAk+3(LT2hXZT@j8 z#C=?@-3$kQ=9{$G4j+!={vM)M031R?L}3xxewm+rI8vzlr9GfvJR;%JCddZajn8Ve z0J#B(5cHG&evaThgo^@1f(wD8<(LWqiZqUpJw$02Y?}TvU?$ZHy&sH*T?tK(qW`>4 zE3YB2;Q^#GkTQ=!YMn0>$L<6XK7z0;oeVeufVW&Y2;hQJAK%#!0N)V-n=|o<aXP15 zn&Y?6yOB$br!nvV415s_!BM}lGguYE(`)E%pc!xlCBc(6-z`FVL~8<q(LmB=R&W6E z4t_abbKM1sqhi-cAiicR78Ge1fP=ou5&5y1X~0PbEsVK1mfIKv)-B_~(LqT(T$)%D z@wmqzqb+*P2X3xhASBTi-R1%0>Nz3Vk@RxcqBBeF*aqi2CzFVe;hDEl3^x8e&(_iG za0buoYB9IFMa{DGlNu_DOGp}8@i|AmwxGT0sI-JsguhB>SL$an8gvhPd&xBUA~qg@ z4&D1WsbFstsC2sv4G4MRzNY@cYx$c}%eXQ{ush<)w%3>nEOYf?YXEl$BW_d&myrqx zT|d)_SH)%-g0cg2hHeN`0E&&46E%(q@lT*{jbGRN6u$p)s#K#C4T|Mbux~(rdq0Ta zcQGq2{Ix5lAAY!hjKKWk@lrG_gv%IX0OPw(GeC&NVGLP#+^B;v?ec*WdEhOh1m)@5 zxSaWLop{hor<q5R>eH$(4g2^t<DqG)-70{}G!mVHYv(s&V@2XKPSZFw0kh=)fZ7TZ z!8>e~S5%z7a^;m!W}hV~^xn+jaG=H$r5L`%ObEQwt63-UHa&*}jK{HRcOw1c{pi%Q zP;f(ojfAZek_xl!-|=l|?kAW%fn4w)GAls(HD^-tt2(^^m|R(z4Ig5Wo+GAX0j7YE z*hfvgic$oUU5q^zEg~%NJzd64@WZP_UWVs$OSNy7nGh9rD!W@NzZWYa^lrvED}~R# zY{CLt*W&>P;`J0&iVb?y4}p81s^=7LktwRWuc(#th@#5k(~0s*Id|e4sQi)$W@AeA zI!4tjYWKOuwP<CxCwjaNPVcXA8!j@y+*O^YpWbI|-!e=PBWrpl$yRl)fgITgWD8Cl z4loX3fQ=n5NR>U~Ie+2{JMWkma7w^L5~L)wq*=qBmu+U%;s59NnM*GLb5+1paN?x2 zBQ*d_k*}OzszPxLKcCQaS=3|_^e}?SR_9K~B2!yjCh|KIhb5mo^IC)KmCm>c#@eiM zF3zpW+(~6g(b+FQSwDo)OIpu)D1^=se^%dauT1>xi!ehX8R@b(7|U6w1!!`x5U(TF zq#RCJ1Ha;A`}b;-vIt$eTol+YCI4`mRe>KkLIW0Nx7oC;An0GxU0_X8y>X`84??!8 z#oC=8X{P!S2aB;~N4zeFe2h~__3-4&(=T_$!UWqpqjsMn&fnX6<*L7K&Q0~DNT~xK zvMgzMG>BWk<^@PaCFzk6@0jB)B9uhqO!MT;b%8M;;fKbu(^#T=#uKmTq|$h8ZpB0t z7M@fSr&K-wu+qWIn<R5OjDb&TbgR10f(H~;XkgcH78JYYkhB^o;anqwD^JrzLj_CF zq^@ztZVdpcS@iR91j!FW+$!M)NoGF?0OyRM?7nF(G!7u<ECL{I3dFPs%qjQGP+A*= z^sxeQfy}UPw-TNm#08(SLDFH1Xd`tD{=pW{+xJ_ty{e-WvWe$_xIQsaOuURcTN5r1 zrvR*p20YbhPL}_$tX6cE=)d2u-B1lq4qZh`1W$mZ%nVqh-DZg(%7FYH0-kfvQy?Qh zj#~ko5^TN=4mx}$y9QLgJLRWmHTq0e*x-rI{)_w(;~T0uW9O5Ub|I<+8TRWly8PJF zk@HM1B5%Mz+UGtmQPzp8n$NYYZ|BYxZ5sP%zv{9MZJ#UNjq}m{xWpCt6Otvj0vxGh zi6&NeoC^LDnEW;hHwOvC|9X7D4rmDXiWC*mNrxr3f_(q`Ucz|@9RGDJgMMxyA}B=e z_C2=G*RwN(82lg=U@CS$UGL4994y-q<ogv*eUUxDy47Jr{%R3E+gf|(m=An26RW3@ zRAtPE1(FBRF+1WQqcf6IT*8D5KARVC2|4?d?O3>&8DY;UvO22&M<%4QmOV7F5;aPN z{qO=V)h91Jw4N`$eoh8LQGiq$hd7FbE3o+D?CnZ0jjD$)0flb~QvdXF`qWjX{uS+o zw03){5`|ct+vPkR+TQS@6~u8Jz3i)<4y!JH3s=WNRCR|$eitNYJk@etURY@FcpeyZ z_g}p8=R(I*SP(v5$8C*M1H1mM^wHxs#TqEi@s*&R6*pZo52)3RT%uf+YO|NT{Hts9 zfy!;4@<LV*KeH6$RKMJv%-wcty-YzK&$`0Gjq=NCOUf(vp18hSK^i|j>2WKlS@Bu{ zW!!AN@A3W9EpGv*4&5z1_Pgg1xIco=q<0Q>iI4!%zUg0f%hC&kF(U>%>=E~~v5U9a zUaub6KI&UExwwB_cm2nYi~lIp8IBNkE73w;9HcOvV-52lW-H<Re<!YG<}iD&%S7FJ zru|(2(hySFXBIL3y3ZzP^x{?dmamwrj~#+k`4Da)hKQ~20@*#OAJrWFr+Auf2X#+= zR7?+_#>cc2R;May-zpg2=$a|{p1PuYrE8kFaJ%Hh10Rgojj4F+J1Kz3=8r(=rND)j zQjS$$!7xF+=|@Da5PYogr~KB+Mj5~L79tnAjOXwr*U&><f0x(G3rB|=_qVohUj4QF zny26e-1hnQHNH2CBNsxObH4cZ+29-|$m&lF^q^vgRD?FYy*6xe{brR5ZeN^uQlHp& z{{uv{<3d>XE2}1V(>JTdqS)U0gP_RQZ{Ge2)$m+S`4@lw0Z}&tqo7v<nf_ivBV~Gb zJ4*TVxKB2~Je}aW|GngLe)49GZ$y(66IkZS_Zu@J`7_TbtvBOW_lLi5wegJl+lEj7 zeE1q##hFQnlVtZm8UWydrp8!X*_DVF5GSMxo!_=M)MN9j>2OYe$ldb=A1)rxm+Dvn z53k3YZPiA$>Xj&j`M7@?`5D>Q5p(y_E%&9<=S4FTAN;f)abq#h*W#w&z87xxGT`sj z>&kwulg0qf^_ldpjLDEeKK(JpC*A$FCPX&jkj1kxCt$)DQN-UnAK!TNq@Fmt>!*ba zn0U*%nH4DaGVHfW)>Dmbf9}ZEPdeYxn~@`@Y>sBrWj~LnMes2G3+<d^_HG!^Bif!! z-HE&NXLI%sP(MK6IJWt_LQaVJA={oeDWYZ;c7wpK)|7JAEIC#f(fYz(o8#fs4&Z`c zSX5~Pnf;ynoJLkXoU%J&TQ%mEJMK-HsbGHk#|n+RRQFnP6(gR$x}$EE^;Fg<7XV0_ zomq#mYUXpQAWM4sAANZpWGa#lF6tPMI(y7^HeCpN^hci)I)IXT0`et=7Mw!45g_;a z)`Mll!bvhVB%!#T&Mcj7A#hJiyY0Gq2Z^{vOlLz9B{g9c>!RCUgE9fAR3g!UnshQG z$-j$Wha~Q@iB#UiU?7-}<%!C;hl5>|zThMTDSj;F$+00D^Gi48bgST6IG>9GW^0)y z>#y=^k)k8;pan^Y_+z+L-mNludUId(C6Z`@D}sGjIo(PVxC~bL`*`DFhwkSmY?8bd zKbq4hME#mU03WMVWB5DyOs-bq*r5^s8x<HDh^48(g-)|7KH<PaUt&s-L(g<0h6cxq zk|?ynV1k8BlB=$|4;U=(OS;}`AUruRtWA2@)5TEKL@PD+#isWwLg}vg19t|4ehja> z^reo)$txAH;XvGpNU#klWk&ubg^1fDO483Owq!yM38!l6CSMkxlq7J?5KGK+qW%K0 zi~`MOo(1PRWfmge5y0(4R9b$vvjq{FA%2;OXUgvpdH3WI0Dp|(s67jaFz^(GH-obR zm>Q@c08Y0jP=rSdDZQr{vaP@Q5O~ZC3&<<K2PMbNO5mD!!<NQkp0p<7LL-Xr6|o)> z?ii=S7J-DgQCU(tDqpvX#MS31!hQr3(IhQuK`cPvi92IS{OM_$5GyJX&Cd%*f_RZc z`}b%Bn)pa5r&gFZD&*pqWx(5pB#tH)#;L>#@b9yZ)${^lPKxh?N0lD2urlK10n({O z4X=p@Tu88dIBC*;*!x4@+X}7jp{}AHb-&N*^I-m?LxL(@H2Kf)!jB87WuP-GXTeC2 zCKYPx3+~g7yR!(>rl-vaAegoUSnuBHpJ4e<HF2VQLh=;0t4+i^C?PO`Xo8Km&;&zn z$B%nKoR`?ZP9S5acuRhgZ2{aF9dCFz(a@0Q#~*L9n0Av6vvrCyE(4SaP;*@6m_0!p z3pEReH9HZ5&@lVN*mEahgGZsZ`QW~C5SAKefKEd#!Z7G~35B$?6sQ?0H@YH`i$B4R z0HaVU?9lPb`MPrTywWpJdrhdm04aDY?g|Q`vrMwY#!2Ptc~d!zoroYRL7Dm}7!c)7 zj5T+Hev#9&X18{#Ik`OwwRf6<Q2%)W6iWcn=S?yE2&+SAB_2>8g<|O`T=_P({Lsgp z(zg6CX2Mq1d1_qxWx#Tqe1!tj{H+^p9OpL^XH9<zGb33##T)s`z2!%6D6#r8Y`=s{ z_)%ew46vtC`+r9S$$YRJfi&4LaJ_ZFJ7Bo8LZ?Tle~qVc<IL1{7l9WKP4cpOef`Q- ztku$oQyQAEjArt=rKGw#l>K-d)=NQ*N}OpPvnCKzXGnen#T!zm%y0(J>#{ix!BrCR zY%?Tf)Y%#5xPc?!DV5;p#G~+1$X{8s?>50Pu~>2jC5R%+hl9QIQ*|11&jPV%I+mY5 zK8+aLf`c?;Ss8?Q9W&B-It-$XP(c&KJFS(e@iKI<zuD8iL)On*NO>wG&8C9cXU_Q| zgE(eGGV(PU2v!lIgH_P-2ul2-Ie5nDlmj$wY%%t-4Opdy{OB3K5H)V{%taMB7F&SR zg&J#J22=Wys7iO%Et}V*!Ys8AXEXs3fJG_a367lrX5x%(z#1qr4bR3ZH`L4y7z0V= z0<X_qCT(mXwQ(841Bq<de~%8}-1c+tJ5^HoV0o%*_w#wnkCr!zw0wm%->-M|>hx24 z03j#XmFRv4la&;IjoGpM2WK+U2#^3eRnI1giwdh`oD!&kY8Xjlsj)hVkeJ_4{W7GN z_w-5EI%B5=9yU(P_b_`W*zJ%-=`++U{t`2(qNJ_mffJ5F-dLtNwlbIkwWx{9+qP!i zf|$`?&X{Ms>||Bvcd-XJ-Dl#BXX5G;1sXmlDs7QXYT}HX6cadzc1{;pl2~ArIE%5T z$ulP<P9#d9*wf`x<+7pnH1fC|&)b(2QG8rAg`KmBY&;sL16U0A6*;I))Z+mqc7i)S z-ed-<3@iiukfP_@B4$ui8wp4^=d*&8d?!Nh5!3?<wbG1D^T_5o_uL35`GC(nXF$re z$!J-P9m6D@>+(=i9*!{wE9H~KN?g0!=6hBx`vR3_ei-yhD*LHg9nnDc6wNyqSLCfb zp1(2`1Rh*^1WDxwglbkM&T$9d8~S})1%?+;{{~`u#gjIagkRmwyTtE+0Kkdk<mb&G z&yx?9k|bU5+>dIxA761O7|lE<Kst_3t-(l~zQcmRL;ex;8p2yZ6H;^+DCPhh0ZxQ3 zA1Oa4jR7tk<1c`Ta3{KNvI5n2SuE&ma)r_jjoH>mCyn`w%;ngND7wn;MP>kW9yN9h zh#L_HMC5SMD<F%*XJ>72O8-c%Jd2<l*Qu`LUQL1>K9>s}9|L8Zo+4@DS<Gs(Em4KZ zYE(y>$$>6(hYC1jS)6T>&@&VP&LmZN7JIr!=wqXm_4i7EC;G9ge5bwTD|_p};jSJn z(w~8~Pwjq&{R5Tp67`x2WM7#UPo}h9>{%-0@gh-QGgcGn4q+u1y=T*=ZHZQz@@N6o zdJx?i@Y4ctvviIH!yQZ^>Cm=Jj|sfL2?jRr`uG9qMMw%9^8O`Ejz}^dUG=|A(!oPi zXrqe;U@Ht&2N!!5U2$uQLn$#<b#bkxhI|$ktH<w9hvRW(uqvar^)%VIH94o_iRTm3 zbdc|m6@VrVqFs}H>TtVzcx9+FNtF<L7T566DK5MM$}lJC^Fy$U<ng)qbLJ%KA&{{_ zx*2{7J+q}ri1pyy&fp|yqS+8s7z6W3RWoZW#Pq>cDhSVmp+dbzk^0ldy`r&aXz(>B zuSPheRU4u~jb-WtJxnu;yRrz@7!8C2v6?fvc;)0W4uXLutD6lg90k!#j9p6_5cEoy zIy^7-^L;d@r#O5|VtU|3YZvho@g;kssF2}@Hw4*HveWu-V(zWvv9^1(waRWlX$Gv! zAaPN(1sPx^>?u~%#<NeR|EXVPyXX96F()Q~=%@?uFZ#o=q|@Qx!Vo|RnS$~KnOz~E z8DM!jp5t1!VxXEBGFYDHhGhm(;)w8Xw;#f1GL}hFTZuqrY|=ee?!$}lJ<l{>(rFv} zfBELWk^nDKAW`^C&N%5bgLju*fO)~}eF0d7M%1k2s#{ky-zIWJfKP=1mPFziXQF<h z8<S!N2pxh!uU{0Bf*Ay^w8LP84e2!P+p?mtz#>U0e@tqTq|ARw;@UOALx}bw*~6P4 zc?gy}lofkUI!z$D+H<=e`op`E6fUg~7KobMBw8-uC4vF@L$J`y`)gVD(u+Y#HV5)s zK{1ct++UcS65bVo_7f%b>F&G!?8MVE7s3*EkKjL9YHumF4{<ot^whFdho48uq;r@P zR?)&QJI6S_)!N6ghBdPIjXWN_tn!^28aw)Aznk`bk<yDSrechfZ64dVVvJ5ER&|}e zVXCrYaps~WjpKc2Qq9oq>LmN?!nW@}hMI(8Ta0TKL;3A~eiA&q%~gN?!_B;WDD&Xe zPea|EG|jkB(9oKt!NG4#Y`DsUgf}q;2TF935<23_t-Fr9K2GoK`*M2T@l3g%Z}am5 z_5UI0F{-X`{4BoD@A<mL)JRQB@}h42SyLUgIQte;yYrl>XEls?1Fmt%--*;<JFD2E zQuw8LMjVzl(Oi2?t<LnZmVfJ$Tffb-B59}9B7a2kG*L~=pxTsus#p~D+Mn`{v$~i6 zG!|O{7EpDkdIL7KfL)}i8Mk(pTA{n1*4cZ$-!(FpZ)GLi%iavy{qL(d=hk$bj_>CI zzpNwa=>u{Fv0SJ7QGNBS#_^o#@x0^lE1%<qu;bSW$BTK#OV!77%<gQju3Q~1W;nC6 z*=`a8iK*4mS&G%`e@l?Wf~9vmKlMlUa}v8!KAm_Iy`1{r>h5t)Y*)-p5@l)k>ud1n z`J-&+`y8%Y#OZ-|Y~X3;n}Qd2j{xvh!tSG%-Q{ZL?+)gl5$4|~%#Hf$6$BCnMsO?n z?x6?cSou`lIvI2VnOoMjp$0!d06=gh+SWHogH%D5kROQ|Qlr@?d8BZAWh{KkuB|f- zwbE?XO4@g=x3}$BZRBlAP=T|?EVEJ;8NvdpQi<uJ+5wAHk1J$$eq{&z@t()Uj{D4& z_Y*!p{}tH!y>1Tt^iz4I^Y-R!qyMiU{hY{O`(IM<2Ifyme^hXE^d5sb5YJT&EpozK zgiBHHEqOXuSv}Nj`TSw~j)e`?sFYtX**<Aj%Bt)q#pS@yq0!CU?a+oS(jT+8xBvCa zAB{am|K^m@r^7S*AI9^}-un7i>&H`8!Pc4mc(%}qe-j%kM|WOOjYkSE^o5+G)Tmbt zl0mW016Wm62ZUT5H2?ei``7odHz$HaK&+Z*B1|wGXTT<fCvv>@_(ctU6P!0^&4^bQ zym_Ix>R%=Aqt}8_YPg&$Y<rD+Aecp5rR#m=?n8-GygPvaCM<<ZrfKbTN~Y`mK9r;w zuxd$Vm<UElWtuB=No83nL;x^xDRDU8HO)g@Xx@}sSy;)j)JZb)k#vp=_a)Fbk3^>~ z1jJEs9&R4pbHF26e0Nzun4M49u_EpM!OfX81WaM8l!aGtwhY3->RS$0PWDZUxsZ&m z%uyM!&DM`Q0p~AvNs^9R_P8;3<6X4;vQ4Fk$&CU7XhsRAwv)7HfD9RHz&)MV=Bj^u z_*;=Sz^bFv^jt7Xsd-GHN2z5>JL<Dige{K0?UhTEa{H2Bk8;Oq<R9hE_sKdc9r0Rp zde>5w(AVw{-6=sGn^kYV_8cs;sq}5x(hQK;#LHxU&k$`|j-#jiPVTv!9q;h+2eKRa zmRdO_T;j8JIY~nIPzW6+W9U<{c#5uSu<yZ~m8>h!Bs0NO?)j@ad1gZQ?9{n8_s&jh zebQ}V*RDZ<XT&L}A2TLdc(qw`#Xhw;t9t5>IVoekgO~Q_qub`4{N2wjnB6*VoA-!q z99;A)JifbhGokq4g>z3MiQU}n#IS((qTU5Mn2Vh};G8^OS<As@QgZWpC^CoZiM!Gp z*49S)#N)m+U9FEQxhtQFJP+<nYZgcSr?pj<qOZMOSs0_eQ(ND!{i*T(^pWN!ZVozg zy?zGF?mUK3<gkApxlv%i9{lWt89GDIwoV@e`(9=a66Lkqi;E9i_0Dj%I(zeJpQS6l z$%H=@xGWv&5cJ!Gf9p<0|Iya1-}-;QRi8e8eDLP<)89<kr)!u{`#lb*WIq<BR6M{D zpa}t=a3Y_<U~sq@p?AN3_8~pe4X<|F)Qx*}CS9=%_VXKXunr+A(_&5T)CsfNC6-<r z@Y3*%5NG$28xokMk=1*}Iq%dAiR{x7^i#{6pOM&31u%S-=&Ol!%_V0~>>@{X#`hm0 zPL>*9lGPk2@#b{s{~m9^?k)up7^h&>Dc=Y_auq`C`4=?l1022>V*&oABuy%jGlc3T zyk9e-yWEr>^H&lLF;CDzHB-n^kI+2wqnaxj8Iiq`B7_X62|tO$U(E~5<J$pKN8N({ zIawp4sW9cVca~2f8J@Rx@|jhof}f{wpc##wnNGBfZ}0VXQ`uB(WmM$#|CPqX%1?T5 zx8x7&%BW`5PI{}h6g&+{80oYTdMtb<tf#`D;T`~ee`+_}Ld%M0nCIb(&)3g7O-j@} zZqXo~nF%Vm=Ogek9Il2Top7~*3eGU#>iaFFe^(^MPRY*@x#!b>R~6@vlgMZBh9}H% z&qStYE}YB!R?Pb016ZU}gGD0Mo;S6G@d(@bh<d^ENwUR5v+MO7bPq?_XVR8lk-YBx zYGO~b<*kE{n(n6>vGDowur+k`9Q?o*8lXiBGWo2_p|D7YUeBMcJmU({9=EuJWBHX? zFR2OQImrJq3WWC;G||})5X!z{Tm_>>f=uqlWL;m;KS^XwK$4KNQVm+Ky<&CaB<Te7 zN?hya<y|LVyvY(pVJgmcag=J@(nUBqekQlb)*)W4QR&7lmVcIr<&#<j&Siv89r*Gf zht7)bXX8!=TW2JH?7eE=r*TD*!;+o-+0NA${4dnLW;Gl&$V#%meAB|2-AG;;68}YA z`Ka2_HR-K*`+=fOr^Gyp69yMtpubQX=E>si6MBnAj@wuyX1o7Ot*D(mBZa5M(m)=C zF)k18(<L<u`ksu2CcQg;Yp&s$1bJF>)2hC~6mfxrr17*sw_NQ-?R;!tfOkq|-GVyK zX{yeltNTLBP8MeXK+<adWY!`2x{E2Je<s=Pp69kqW_oIzkyJX3MLYEzXJA0Z)nDCX zdqMW3a!aQ$ez@RJ-D_Q$cngbFuX?V}1C@WHn^S(UeU$%It-l#Q2s1<D8c?0*mP3+x zPBpl|jmp|)6=i>R%f4r^TWoLd!;nubx?c>+Z-|%-QcOd+sf`jdz{*X@kku7^q{~cz zh?K!gI?DxJkKsFQ-$EnatnQK=EAGPrBFvr3?8^4lHnvgEGXo@+3GaooDpl+38vUj= z*2M;#K)#MPQ!g_Y5Q9P_je#*n)z3%CTx5)uM7A~SwYK8m-0wjVpDqz*%Swv&Bt>T* zuAKZ;wmjXa-rjVa5O}BO&D&|FdMAtf)`kUNMyQ&xp18BaeT(i?myeGskI37Wr`aEI z4B03Y+@4Kt+Kl}cIH0-ZI&p>Pp2{;V%|V{Wd+}#`-*evAd?u;#Ey=ETjkk0}=h;3Y zX27&nt<!)r)W+WN)TMz+kE;cxuRj$(a$fu>8Ct!sPCiQ!&sx0_dcOAJh^_8P{@YZD zC`si<8JFJ5TYc@>49>*LvwhnafBl@xn*O5ySA50zY2?f<>W2fyleIG6U-DP}OlZ#^ z!Z|*O!2VBcKaqGZM(Cr}^dISsTGn$lTEeJEN~}<)ZKWdcQ1aP+S_)799{IfP8qfJ} zq_Z(92Oc9Qn|nW&?NDnjJZ~Fg<~_WfQ+o8eAoyrPF(4pCrf2$wx4Os-Jt0zX5EYDy z45=*+teyLB%lfGv+OISOzdNujKMWC%4MG~s+i~9g@xA-j<b|)@I$1hDr3N<K2W(l> zbQAT8xK^T?P-NV{LZJsmf~WucmL;ar_t#Y21@+09r*l8=63sSm<Wo-6TN&GERMR`% z-;J|f9a`_!#hw%I>VYr}qHs<A%O%l{_o5J023id_e?0JI`)&I-(d3&VA^~8@RH8UG z(;#Ve(b?7{`gNeeyUIS1+LdQjEY^_^lKkXy{bww^3XrfFEd7<^(MKw0a%m8rS1OK< zu)O-`RL;#DH*UErnmGbm#Y_R(bKb&N3xV<|rn9Z#k~0>RDU2_cz>|a-#3Z877XvCk zCs-g?TtKB*K%dHQi2f2U)WuRNp*w)t6DU78fjyqv|M&{2eXTNjb^w`c+K98kTp}A= zMjaGBEk?4~fR$g(bLvY-tvMDE24Hc3W4PO{lc+}0l3$>xmfow)Rk15cZ{w}XwvXo| zVcdHs#3XS-q9_-zg8SFTvboAK!DR`RjWvN;&$%}7&OT4EY(u>y*H#$A;DG0Q1mCsQ z+;DeuQ+f6Sz4W1)*Aa3KnZfU104d8vLL;=o(qK*tO8fwOl^9ZRS^U+By4;O|rE!BC zt4ZFIYrNaRubM$j92zDjnmx#i0m~xYU)^+_{a6B3cNa`6QxW}OurKj-`)XU@n}stZ z-fZy9szC~o5o-0&p@7;O&x-aF9MWWe_6QzTY>qf^_X>ROV?eC!iq&X;bkTO&I?$*D z>9N~+?Zn1%{+QV2%TgV<koJ4AlcGY+NmS;)zi-DG3!rPZf@oPOknFSaFRNDtz+l5F z4{<kXhZ`To1Ed{A4IN^<9UQz3RIY#N^ZaxI#}`?4yFdu-EVU%>CB``^=4Xyxena8l zJSPK+iZJ_`B<MKL;OM{Z?Vg6yU%GK@Bpv=-n$yWDMqnd)&Tsnzx4x6yW9J-brOuMD zUisQ7@T>@i>9}xgpm)j;tIbfc_7>nBMEiO>MtY04-f)y41xSDc7GxY_K01&;DzAA$ zR2cItB)Ed(!U@}u%a6{;h%H@yNJmcI<)3_qt)LJuz#Eelis#RT!dN;<BP*sJ8`;@+ ztHTyX&eILDm1Od~*Zz2yShqX){CFgndr9}k27ks&`DIC48OJu5yZm*KBs)ZOj|k<w zu3TQF(p(i7R2d*T7@#5-t1cI)zD3-SaY&Yi1ihJi4|*MKAWs+V64(qjbb0h~(Zt*S z$MJhP<y3i)Nwt6gLRz5k?<!1bP@N?EU_s8E;Kh^b#g;7@`S#J+mu2gIURv}exweA9 zz}b7VOrOi;C1RlE+aG1c@a~_cB(6Bf3znB%AytyJ<?=$e17r*(!fW$GYyD%SZ`Hkr z{znuCz~|w`yLx=CzfTxGzapBvWn%Cy+zN$W5ULh&ur-@Zu!(0UqXNx{wSl=0-p+=} z)F~U-X>^W#xO|l>U~ccxf;L><d%4v6>W!wc>Y#&bdZAS!(Kp1E`7pL3Wg>=pB7?Im zg97E-eh<rXhd1(7<?`R|G^&suf8BY!R`-N-vvK-{Kk4I@w2vzKt2<`~&$}>gpPEe| zZJDUQD^_23Tc~s=T~}xv_T*5wM*(1q^fFb2kLaS#!INs<M!yO+eFgHl7=qSm&f``x z2foamD$lALv(D23A1_<Hp&m<!CJyR992DC#Q1SbCrM)Wezq-K<g(vC_L+Sw%nx6;3 ziUn_FoCFoodm!`&Lm+UgdClO}z|Eo<bnC*lsDce7FgwYx8eQjmlV8FgsnDp&+t7ri zcg0HP`lq6*rt4<9z~WY!4kvD}*?xQYq-*n1+S(NsX~8RH(P@6QKNVlWe6!)N#VKWe z;|f8ub&aZ@hhmf$$&HKTz-Q!}&pAKE=`#fO2b|kUSZk5?yS_y(*IO05Rv$G~YkEao zen&asd9@!$?ROk*pilj5D0a(zZ#~_WNk`BTTAuN{i_2bBUa}9JqsS6A$tBf03z>q< zk9sj4Mk=^r39zKxpagR8mERZt+h6h|4D&C1UL1b>d0J)Z_s)`q?}FzSbfTf2IBB>) z5SIMr&KCo8lE@?Jb)D4*m0CW7&x%(#%1f)r?LX=MIM}^n<oj92wV$tBLZ1AJIekdJ zby#8&O$X29Z=#kTo)Go8iOI1m$hu^~KiRjmq5g&W<x>sktdFXrk#%GI##?cxJh{IE zkUANM=C65?%3oAylA43y^R&myDg`?-0~>=pcoJH3wWCkIHd1bEc6)zmdv$;D0(l(g zj>>QsyJle$l|PE0&`<mB7A2nMcunJYx7Qr-q<GRinqnwje#^^trzg#{cVCKj%#;e$ zqr^wlk)6v<y_F5tzqyqhH1~1vWB^I7VPi+aH*Z7Xvpyb@(8QnKB#AW?C_E!j-6WV2 z{8>dQu6+Z&WuPJl{+9;GRb7Qo1iDI87Y~1AnHBO_Ei8?Bc<$$FRLFBUgY<I;BdKwf z>*8Bh^yNR^?=HW;eqEu=U;N9%Hi4qRoNYbjc?mw|?<WM?O2K^t5nqM_nB;gn_*1va z<Kf4U(_jH3lJYxMmCa_AUDeZX_65(=pm*d2Si!qNh9Y|gUw=xhXulpMi>U61%MkNe zcD}?>F;{uhuJZ2x3^w^CzfV7>s(F6N`iPcma{H^LYNd-Gw_xKbkDv_|<vCmC`{T7I z|5*ffaQF(ikc5><ygfnS7eV}U`vM8Ur}<h9#99qBXs6j)KX;#z=-u%1!%5V9@vGWC z|1cl%MjW}G-<nnvUO;PW#{IZ)_L_vmI#8yO&|>lZwI;$zs<fITwa8BQWo5TRRoznD zbK#<~>df-;;)ombKSky9RObrH<fw&m0n#)D%wp9y<<c{TZ<?hn&t16)mUcVmU}t#c z);Y(p1N-m$Shf&I`j<goLlJy{@bxD73VG2>A{TsG&q{ik?&e=Ou=+kM!rFmODY0k& zErJ>(u|H|WZO$Kw8=fe;)z~$T`YUJW{M9OqtLE9JF7L-n)u-maKDljm=CTh{Uf>~E zI*AmZ0?r=~QWk1;ymi;1THV2s<kz9@5Z2~!anK;^+vDlxXKOnSqIX4J8!SI;h7UFF zU3e{OR4<x|PCs+&yY1-8gI4o{N<|OLbvLZE(mu|yL;1kS`R@>VYfFo*@usr+$Ayqh zktT0J`5=!)(9)C5{ZDNfss?__jw&R$HYq^$U`U&0$oJ!>U7Nq1q4Zx30-}?^)k*jj z7T|dIw4z#IN+4<HtSlOQt7oJBcc|-#a*=4YTUf{{#h1knRr}$<>?zv+hfv6U2N|1= zyVZvuKHG~6tN)P>tu&OOEQj#$)>=<^WsZN}j<^wJ<bK)z+dz<fpmwLPER!U8FF5eE zs{JQbKcT}bJet|2UD-xmes}H~oYq{F7?i-TO5o3Y9sWN6S3s!0>TfTr$a*jzpDfDa z>B=h1N2V8b0<Lq5h>|tV2516(ai@ykd5p{nKKw%=a5v>$UYNyS5sx>$KH-tZ*>0KD zdh2f#XLeMs^#OC`g6eiIXt}PAb&?abepmHs`}dS*!jy-4l!N+|S2=?3avD3V11G{E zaI7JSg4xoh#i}M*zG<^&bXoD10Z|&7bL5AkFlmTMYCOe=KldS<cwpnXTOh8o&joh3 zTAyoKP<6Kr0J?e(I-13AI_dPWskasGYfwA-J!2`>u5JQ{=~+(!Cx}9AXZn)k|FUd1 zxu=Udy%TsQkb1obIKC6Osh@f-2eer4Y8_B|9r*Kta^-2NVYk`({<0<A7Plthtz9QK zXY{FtNbgg;d9BF#iGOpmqXn~ny!q|<c9-*j3GF6^_Y<%qC`Q#2E-nB0pN*wrJ&&@F zueBDta(x49BxqnIusbb_wWjB?ygzxqi~7AMz0xoJz3cnYM|oCnHL5STBZz`Nx56US z!L2rE)>>&>2XAmYt45bBck!VKV%o3U8@8H<h->^w%K3ELxyY}@qRu^A)JMs41!Ef6 znZ)>ltvu&tySBgcp(kmb*(ab4bt%iL&d2g1Si;pu!ljS#E>Cr9KfQn}|9vGeJ?CeF zCTK$EGd+MeJ?8&+Yk##a2Xq)u!X_v}C6q129=wDWWFFu8*n=?gM!W;%>D~r%-xeaq zvy!oM^9FRh-LpmAA3s{uM<zh>-e=#?Qm$n3q^53rr{1ePgED3d_02<ikaz7DJA$eb z!y(Wz8ZWt3^Y>~${k?xa=qJ7V$G`l~KmFJL`z!tDcYeNW^;P>jKtO`zh#<j5i-<8g zWa;3+M2QeZlz6C6p+Off0@C=0BgZ~_K!UtOha|~3C*j0_1ILXUHZRY_EHh?|7%*VI zaM8(S%N8v@wPX>B1<RBvQlvn6@}!B9Bu|eF3F4!N4jMFMz<|+W|3!!kvi`x#H<oN! zvuDw!RlAmLTeolF!kss7Y`=bS@#fXLmv3LS@cw<;5Ml)j7&2sBwc!IukReE(DpAtp z2^6G8rx3*=R7>ZcJGp%Ma#M_$F=b-LeA#m4%9ABY-nkQUPoF*=HEP6ovEm`$5+gor zxCl`(MPQ26i9}Ffb4ZdTQIambQg!Rsv0KlSsnT{$-@%6$Kc0Mf^W?Xu-=3Yl_34zL z$9Fz(prb^V6rIU6e9^;)z<s00qCs-osH2Z)8ws|PRBEjym{KcaCYx>oji=5!6DkX$ zFguE=rkqM5s;PXi3M(17>S_aA!t%?-7h#N1#u;g>(Z;g?|Lf!e!VE)9u^t+GEV9We zy9~3<vcT{s3r8dEG}KaisWsPLgKak2I{Kr)-FPeHH{gUj$e=oMVMG*BB8j9qN!E;x zy7sbD?>zE4=>)tw@yt_CJ?HH6JN4jX?>+eD6G+W7&1}dK{`^BEKmiE^B%|E2L~sw; z7F3DBm0W^QrkW_sX{Vkr)R04?kWvc7r;w0}DigDUVTBbw*ua(+Z_HKKT<zM`*I#GM zamT_AON<5^dho%qBZj2RGAWKEDoG4`+G3|BOFJz!)!1;OH3ng$L$)hx!>vHw2I=h( z;1Kao(cvoLL=j6YSq{4A-U~EN^)i`r&wuOuMBsr5|1S6wfb;b8Pk!~yPP+Km94Hb? zG+~63NW>h@KZpPnup$B@1*B3-FAaB7PCMOp!ka`LRmq?<!z@*%B!kM;9&ES@u@+cR zkwtfa4O-}-i7q<Ee%$$In!#o*Rxurv6*39QoHa5tX_fp;rzXKLP1`8D^_I#w!X+1^ z+c-Km(saFCS0Z<ZGiXsu7-@x)G$D?z5=yY+u5W((Ef3*;4K8?;!x0~)@PP;aSCcx$ z1H9oup_>FcM<|iE5`z|5w4sgJ_3h(HMXr>#OBFQf<OjF?G}KXnDm7+QlcG7q5rM#2 zXRT)aAcS%Lapx|hi7(#x<9+Q1uyI28VAd9V|2!7zWt%M$TB9`M%rmXIHVsO!#ZIZp zl4PUJHgnPK(o1&3<gXw{L@9-lV$zJn%{TRx^SnG4FFf)85l0GA0FZ!+>mR}J)F(i3 z$8T_=#3Ud%i8LkT5NUG6K={)i&^bzU1HwpwJYuPFnG7YIdI=jMv@)E4hE%26P*G^N zlvRo7W;sI)ih8#K;E4r!J@nxZf!G$noP$=+yP*wiFufx{W@?mKiq)hwt?gMWG){UF zw^lQ@@r}!TXv+;oK30+SfhmJxA_&HeV~FJ3Z4!Y3oF)P%xPbYufB_WX9r2h)J?gQJ zi8I)q%mcXf2x>ZMiiIK+5sO7E=YpQo|Ck0j=BO}!&_Es$$p}lrpa!wzgb|`iX;#QW zCA|=aN0EXIYnB8g9APRt$k~Zfv;i5M16M(`<t=eJw0_`Ymo~V-ta_A~Br-;7ld0PE zuC|%1anDKLi&FT+S2on04Q*OVpZeIBh%$DLIccgxF{U7jSU{qUf2+<L_s741{cnJy z*yB6l8Bci%5OJUIV<!%VPX#ipf!RruB}AbJG^wdRj$~9MBjPdAQR)vQ!=&mq2?tM| z0W~UYSqn2XJ5#EvDXba-5K3gjtfc4yO87@U@R3WEu9T%R!pA?v@JnL(Xqb*+qA{O% zz3gdkN!My->(0=vDUFYOT}+$W|9IoJw`sGC%rTS%FVPA{#KIEz>t}l4Xr4V0EOGRl z=U2fRPj?QGtam(|JrM`6^9+)Zl&DxPBxpH-yf1@|n#kyOQ%T#LE_JF)2`48?QBZ+_ zg|UO#sZ1%uj?xgMt~?P8dbWZK?BO50Z0Tj^QWm>xmb0Dp>}Nq6TG5V{w52ueX-}IE zz|cXaEpS>*i%Fy+MGFfrV^T9Eghgl)Ra|DP=D8##Mx_RasTsWBnjlDtPAGyCny~6s z>7*yau@jH(9BWvy3)aK&v5xjcV8YPT9fwt75|@ydCZZ$P=5VgA9P1!nL1@WKT{2Ts zN?8hP!ZO&6@`bcJ<%dGl|Ek7{v;`#9L|9OpU<EIj!3}osWg%Rbd?4)~!MFekj3~_M z35jY>v`n;ks)gHj?Q75c7P!dg+uwe%O95JHaTVp%=TvSImdFGnh@l;<>hDhKTqjz$ zo87OTg2+TBMUjt;WFddmkAH;Rco-&LN?f8$l&ES1ol}r9B9w!84Os|Jw}(uX5U?op zWT-@i(V+AfRZ6j)%?1oht~9S22#)Zb@!V3tbb|$iS%GVxM$DVa7K%}%78R@Lz1-^d z#AGYUG^vR`bhQmkFpisZAojpX6vGgTfJP+v<~OX0XO8$37y<KmU3nIn)vb0lkx}t# zS)U@wMwVxgQ~f_D|Jw;Xfa(r+CIJmb2!eihgHOcPYfy(E)MEpRZ$m|hsZ5f&Q)W(0 zenZI<!w#jCwQIr*M}#v1_bdb~ILADAm}gw}O5G~m<v-ZL0_XktFwz6k5STSJLL)PK z%iP*%yw|!cYSBtv^x_vKm9F8ot9^=^PkgBJKw%pq7LvHcuX+5qIi6Z^cBH4O-#KfM zqk`lmH~Gm=E^=AJ)8p;bHFzVpo(IOF)3E^c1CKqQMX^_d?2@DhBXyv?hNQ12W66D8 zXOoL=dv-JXb}FNiJIBUqRvYMnT`b#ft#93E{lLNndgfXUCkx-zn=SURc4(g}dRwar zA8)x>n`&B9|2M*|w57%LaJ^aQ5|KEhD2j3Me#P-Sc;c#eaXrsjqnz=LFZn7~;dsfD zeB~_PqplhEWbs_$5|oHVKt<7si|_4W$S!DI+to3kR}$JHLEW@B`5<dkbSC=MiJD1C zJ2x*@L?n7;RwBCrHdHpHTsQvla|M_<w6@+zOjZ!`O|_+b80{g}TB1wLt+x}kd?A@T zi(CBSrXE)y5Wf!JIw4h1Fp$(5$EU|Z9?w@#{^XFi|NZfwfBe&*@vRnelVR>VM(-0C zAs0G9ysG2aAjUcBs^=sEzF4oJ5+rqu4zOBhWtNV=PGx4^ED59{cYd$HR)7R901;{l z`G_X7|4=Z9k_HzpY^G!&i8kyhn&_C&uD1MbYi{C-z{fSj$I-;a_2dqHz-WvZZkr0C zO{RlAK!LePp%O@K<2o+><j>U{Pyetm|6Bp`Twx2d@C)^?<XlaFY)z~_&VT|Cjz~dX zNTHniiBO&+%eIW!Ah2{=FF|1MuVhbUK8dhI$%PQ>zi7szf&c_<05KqI1UFz8f@gSE zFlbbe-5!y6l;<C|fdqJ@Sda*6fPllK?^$k8imp#IeyRrvE;df*`zDRjhzkiZ4LbOy zJ-(v=Kj9L3%<wwSthy@Xij4B=4-ECM3x#nQiLn^F5E!vA<@}G<Qth42N?`cpJ3b*7 z{}f?8`pG?VF4-96AVSC47)riGV$5Q%lRhQCL}R})WJ6>|5EpAisAAl@q6N+^-6pXf z?a?eMaU6;$m}o!;II)<V=n0IZ->Ai>x+dVjMyNCi2<addi7>c~uwDAYeUh;J^5r`E z<>F$&6g-XdF2Tp(uL_e4<&Y8oywLuPF(p-!7+2vKOA_)-t_&{^{+>}!I8WHbsS++B zJsd_p=1SQn5}`gO;l7b%N(Q3riyUbW+X_o|O36c(B9(^Vquvpgs?G-3!OrgSS0r&O zfhDE>0ScH;!+aoWAVanUlHZhRdqCqRz<?&4$?Z<Dx4bV)wuEhz3T|SI{ASEe|JWlV zDFGTd!4RN<^GuDaT5gZ#&*Z>x7+Z2BAu}?IkqaFY3}e#&w99~?QS>h1kT?Mvrfes# zF##2j0l8_}{v#s9XrV@izVdJ-PRPt81lw9h+nf@HkOGx%hbnbvq-Ny;wBV$Q&nt-& z`Ce)aHUPuKP6qt3ENx2PJWMS`5z!Kj?Se`!zr{+f<b2F!ZF*y=n(E<}a9;$_^Ay1p z3iA>UW}T?;ju!J5gYg)*P%`PWK39?pff40o^48FhGoe8g#^BR9kFBs{I!v!V+AE<T zC1mu9=!!0)_Rw`~&o<LB5O+^1hu~FgXe)k`4o<K*K{U@Q(FHNAN2JF&|2@%(kV2={ z@+U^I6t%C>3NF$lE&N*1xG?P^{{}qNlNt@r)DlmR-jn3AP#7Q6K9Mv@BQpz8A@VMh z)x_!<4<;63VXCIA*Lc!lvJpWwCXza6q3m$zj?%9jL@6x_9Wx3ybMwvIQFpK+5lJu@ zv@%5L6vFl_1Tql@e#9)HvuZ$0?b?#W;xcSbY(|IhsJ7%gg9AtPZagv4JKT>HN<k4$ zK|R;Wth~xSdl5d1v>0DONkKJKUGfX{6EiPwojL&(3Xl{&a$yM6J>10fv`k~}YA7Xz z_3#iW%M?Opf;Q3gu-35ySqY?i6GeLF17Lt1@PQudv{`WpA9zVD{|f_pgeh4%G5UyP zMXPT*K?C4;@H)jtQy7w5RB_V2WKrK`5gHYL`X)ReXB8Bo6;MH7+6kUEl~Ya9K0nnM zU!h<9^<M!tU<I~cMO8kT^hue~8OQ1qP=OORffYWI*Ltn3*hE%=(!CZm=!7mDDUjO8 zaYA0__LxphRR!vJlfZsc3M$K4Sr(U8ivpgf`E&qCp7Rr>^Ux5D6cI8;$0o(d#V!*L zFNe$0WXvKRRmTV~U{X~Pasd^BG>=&A@j6u{_tjGe_G<qX7PMAtv9@aqHW?9CtX6>< zL7@{yLG$3~Rbdqlf09uEqz>)ylBA6ej1K8~HDoDt%{I{6|3btA3$ZFTR8~mP5$3dI z4cB-8BN#qFIqR(-$u32$Clmp-igs|(z;!NzkVfxP;qsDb`4Se{^_(EJ@E&JM@go+> zN-^)XN#m0~3ASrr0T%pqYiYN3W#M*fH+Nyz75-I8!%z%kEuN;d8e>895(rBvR#s83 zRw*e=iH?NE(b{GcZ(GPzNcPQI<!?obLqmWB#sS?9H++fbrQD$foQEHgg-@I4?2<`} zL@ZECV^G5t#ZXamzsT<1#<)KBXmu<K1LhL`)6+l!6jb+Ku`o#oHg^?xfnnix9r%G2 zSQZx8YwPo1DNo4~R$!n348%z@4<_cuYfHKGbG%e^{}>d^Q0GCTmk%kVDJ%4P7fZmZ z5)rv#19X6whEsfX_*Y&k3pOCbPP8$YMf%cGa@kS`1@(IdPLm9E54w|WDx%UT@)cuo zUkFbc4G$D(t`JaHNTZfWQIaKHcXqe7Um3W8CHR5Wc#YXujnBAt1J-x*FV>(Gk3eA* z1k(^)!PJyCJhD_v@1<?sRzWF(HNjDZcNM=T6!!v=Z{aMYtWvVX;6rzqExNLj-vTf+ zfdWW?1*r8ZpvDKvt_F+Ph+T9i+%o&*l8K9|F0H8ujj-YJZcRcLY1?m|2KeuwVSvf7 z)};3SkThU(*MVubjg6TWklBH0!I+s@f*Dv~|Ce+!VNwj0j1&e~7AEx-YLOH&&yUqM z7TI=$Kc^crLSz3RSEntJBZPWmhuebn>7L>PA(`q(U<2foSuwdRBGD1^S&05&9DD}` zkA*QDqk6QpeGAec#Xv%!WZ<YI#atQuI2SzQhWtRciXSzOq|2VH85D|Ps$$`ekBk&z zjWJR3NF!62hq;-R8JS)BrC~azW!j}#8h3TKcPsdJ={RAjR1u27ng^(xBd0w|Pa6kW zLA}vHYy&|M`RJrqLO>}4)3n=4)+w^r5E1cMSAdpsxSzdxFK}21ei(f>?51oGp^uny z-%{YV4+y&tB%WBf@-jSW8KX1$7TI&G|4<<zU_pQ`*rb6urB!-snR%uS`>+xFu$%d& zahg8w?=ne_q*b*TP~i-P+Et0#CwXq1nfF#(b4*QQN&>6)vJIo$d84q`Ri+O3Bnt~D z`Kw_&lm8(TV0Hyw>mSWJa@$vmx)rw=?FS8Y#gZx_Wm(2Rw>_>H7dbAdSD_VJ!4+EV zmr)urg*kSM`GFHVyJ^7|xVyW%Tf4K{jo~<smvoL{jq+S!6NZ5m0!T_fc&N2BoH2-2 zRquo)@OkUYgk-Z1OM8?M3o2unDv{_-NlF)9`>QWGw#j077MI?P<sYL@MQ;{EdRtK2 zPN<>@qU$nI)rF#CObP!+f9xb+{}Pj%VPO+mK^D#%jKg>(1vY}QTf4n`#%a99ZQRDS zn~iUpcdNE)jdA~|nHE}s6CgHWUG8krR&7adOE;U#78F<U8=_RgZuvXS+L_Ic;zHr9 zSQGIBWFRZMTEWHKEO_Z3o?zZyi|nw~Pfhvye4A(KH}1-X?uu||8P#aXGYXd*Q~g>I zh`|*An=(`K#cfxO58D>D`^IS;7Z|<K9sSWCea2r}(GgvyAy|Q-IVFGh6kLHCSz)AA zttKTltKg_WMHndiV<I5s*~GMC)p;qE&dP67W~$m|<~b{>4h#;wpA%fc0Rt71(~}z) zYDU>+`HiPu)H*L0xMPD{{|_!`S@8(nM+vJ~)JC`PIF1UnxJsb`6+nS?TYS*7w$NkT zuqhqVBb~c(!4}ZH-5Z_Kxf`){e7phn$6NBTy&V;xA(3Li+fNl5p=>mZdae?bdB5zC zJGMcnJgQx0))Q+GRY|pXhbu_n19)NA#~i_5iik4t!SC%XacUsb&NGnsE#=o+;(Wdi z72y<)jHcZ=YPmc7H{17UfT7`#b~*CGonOiLy0x~YWqQWledrlo7jQurx|`^g9@1~z zurHn730BkZ&*l?pmqCHnjJ%yLJ8cCekWY`kRnvnQ$|w~?lk{6A&Q#lg;<U3Il{^Xr zAM04Ze3xQ-E>tk%|C6Q+e%Q8YO3kZ>`mP4qsR&z2%%M~MY=Aas?R<*sT04GC&(Vq( zzg-#(VH3b%fM4O>#eLjyca4KS-o1P2(;XLhK^Gjj^x1vrZCv!%z0%`-rp24yHC;Yg z0TiIY5IBJrNE+*BGM@t8)V+RIN%#T9-VX2k^~lr$lg<xs4-jG4WPxC{NlMr8IpYyL zX>4KdKe->3WzBQy2D1i!3!hLkytl};Mx(vB_t&nky>$0nb*-5e451XDffZOm(5=>t zf8NlSIi>-^mOxvy1mZe~FrmVQxOC}a^+-;hL2?4I;-%|gMu!?RF0{ok<iUX?3DP== z@}#VlEMd8X|Me=StC=)i$y~(>lr&C;pn*b#>eMMxL`jV*YV^~mPMtJ4eOf81R7#X2 zLAnabk=8|A7bQXj7SW+Xg$9`g1nAG7K7ID=xdZnO9XfI9!nx~)4VyD(%J>xn<_nj> zTefI9oFxkuEK?dwf%2q@5+zBJ3<=^xhYcDsV6<34;)Ah&@bZ~HjXJgJ)vQ~)ehoXe z?Af$y+rEvvHokxCWPDh`0)`A4G;H(;G6YFwB~6|@fg+{xVk}t>YbiXK%NH<W#+2cE zMz0$;ck9NPOXrSTw|&&21!Q(mp+jL2CF<H$D^^KVDM^i*NhVJ@#gtN`9EB87LY)E> zP|$E9{|Yp$u(HZ3HPsZ;D=)#qQc518L=r9_AvB^$33=3zE?uO7Nh%o;(gi3Cab#kR zHJ0?Dhb_63;VT!`#0o0Vv|@-fqkyuCP(dX~)F?_Z)zp9i{#OZAR$;XjeqMbA)>vnu zrPf;O#Wk0Ccfpa@UVN1?24G-hSD1B*E#{aMkxf>aWkC3_nGBt+u)+sE<kL@Xh8~J& zqKYocXrrdVGtU_p01AU}#r5Dra?3UMgcQ+DF<oMZVW%A!rgryTcx;S!W?ksTwFg^a zq7@%m^nrDsmik>K34c^p65xOZ8i-(m3!;)FD6BxUiH|s0cwvtmy0lV`)*57^NDghw z{|hEvwD`*|yXcY%D^_5_%eWrRGRw9oW(%)~B!QUYN*iYQ<0}-hB1<fcK(h+64GzU* zlS(ZWr6vMqLS=tfUX^86T!K{=e1m|g)|haiXBS>+g2yIcf)Qq&7Kzb0#bb9;mIM+* z0HGOYGJLke1$U5EsG~aX%yZ8^GwRMix@-Vi3ziz^19HnT=bWd~QCHnz*_DcFs;ZJ# z-g$Gu8tbg@$v0nEx#H&tR*>-L-+#dh+lhfi6-&yo$W~Y(G>r5+p-eVOOKpcamNbw^ zC2H&LMqLnsk-N6=LdYAtAS4Vkzc5oviW_Yk?~Q<)loCs_YzPy+GsQ&VOo{+Z|M$Q` zF?pbqP$sM}!&CM8a8{0JIq_I!U5qhX>%GNs9A|#KX2^jNW|*8Pd+MBIdA{sJ4}E&J zLI@#@L)y>UZ_j=AJNL6&Z@&dMoDDko0K^bWa|&H_izOB{soS9n-qmNqq4n15wdbD2 zfY>Uwv2kTrXY&<+0K~R~9jHl2ksIAA1dC#9LKd!o1uI4ux|qDgbAKy|h%#p)hm0!~ zYam1_#HB7>jPMPQxW(k=(1k0cVHeD>Md4@!LK7K;AOb1Khjzpxy}e=;dQ(I(U@^A} z0cAl2JJ7+H@{}q4rz*WNTg14Mh_4(%cNN2!nAQ`#juEdfWpLBT;$*Uu|1l<Ic9IOs zEQ6Vt{V7mN_(!2~=Dj@XagTgN4W#HWsTCNle3%Nt5!UydPld`lq~gM<yaOKbw8~Zb zV-NqnW|sNf%09X>Td&e4m9-J5ZJ%fz+~TIBBtmNywrE8wa50l0W@tlxOUb+jr;xxA z?uH!M#V-hv242_@h2t8REihpRT#zsgjUdDvtS|><h){*RtmeB&gv(scOGlo2NsoHu z3SDd>7qUPFg&vrs)gk35rd*1Yq&T}OLQG3u=@MDK)VsF0MJ{FP7@G6~vNo9tP9>WY zV>|_!CO8j{ndy@ZSOBOCKmuodtf*}Ifk%sK^fmDKM>Re`0^l6&|9r?%P7;{bzNbY^ zYT4Ni7_7z@NoMU;`@5vYz_vxPk*#dJLR%<-H6TqCsC5i1iUS`wlU3+~6RpriEM-Z{ zYIz87xrCQBIikW@up$jEDy9mFsS94b0TYBkTrDEkh${r*go(RqHA6DExc1Om-SnnR zO1G0%%%VcBK<5$(R#a2IE@85ZrxkC9A1>)GKD<+l@Aer+yZ|(yraEKt(zrZ3t*m9x zlOqfuYCY_gW}~D{4Mt0g+SUBy2t*U)aA<J8Oday1>{BGv7}?TCT1`Ayqhuvz)jx}c z4OhD2>Dj3AQ(y_`DMLM_QB#S|RoY^lw5VX{?8Tv4p2Q?M|5V83tcgNh+`<lP4J$Rj zDlT03Vh(9|!!6Fc3tm_Oaq3E;Tiw-Nc@5-;Km?sDaN$Z?m@}!V3knli=R|}>v9M9G z(qR*uyWPDfOpo1IKZiHjzKlVjBjdtlPu3VVZZ-)=7((=PATye6APJ{Ut&3lb+Kv|D z0wHCApDvX&^_>)@w#7opw2)iwKr*JQnk0JCV@a>kYPg(S#O<_V+)t`axdT$5a}|_I zRaz)-v@jwC`-WXv{H-9_jMsgsS<GE{OBahHrki;Y3^m}OT)zmH3V-nkE8t=lZnm$x z{EWG4!pkIcRY_ex$0J(gViUHQ2`h%^R|BiFiKBoW|2!L96)Vy+!d*;@V}Hj_x(H9Q zY9gZ;05i4Z!EcQzYaX5$>RE`A-~zPB9*p}qk9pi0wYxco^(a-o^QG^Qli`%pKy_P| z4rYEswjcg{n;!K5_YbtH)h5RV<^32?ZObJPu?i+PRl4HQ`eH>apmDkhO^cQv;$fL> zbml*&*%;0YMxWCqu3GSd8IR}!FJ{3Dd<Xm%fe6HV@g3e90{VtI>>=k+QdeqC2;HxU zg)A;e;0OK{uy1RfI~UxrOk)XmVOi{ZJiQiuhFa9ZOOu-X!eN3MMvZlHHD!<xggwcz z1rXgp5Hh;!?&aDvEe?7`J9-BS0ICIkvVr-M|2A8uB{Ia+VdNHqOuv}2YNo&CAGMbZ zK;q`dlRi}&+uF83a5D%fNTmr*mL-jUO(@LT-R`@0dEY*x5F@)_k-haUu5|t4nYg$` zd;|aQTCgZwfbVm>1+BS<8`^UhUzQ?hAt7>KNQr+<P_bHPX$Dt`idaId#O#Srl&d_{ zX8LETHC$OZsai21X5O7D13l@b7&Ns0hdYeE$D#vYkG&>A2t*p}94n{TQ<sjYMs@X4 zaYqch-TJd>${r<WlF9TWJ19dLR8oE(Zdpd>g(gIcSSUgoIH9~$L8MEo=Kb&j4|uu) z&I*Ia*Z%ys|1Ofj1TK&YxZr;QR|~-~{|9q$3<$S>{pWw;5^tH~ZrtQK6Q>BSKnri@ zBN@ke2DVP?^d#>jdQ@Z;SHu-1cTc>ddXN=77*=Y=(_v_YSv99ncv50<G(9~x1VA@@ zJ?MkCfpkjeS~B2tJpcrTv?)zPbyWv_%VsKI&}@3a29u;UaFKn%Wo<e|Hrn=m0Mczj zg?3klN)2Lud*f)V01l$S3E(hy90Y$nlsRX1Z-~c#1h-ZW=zzPh3`~Fmp}=Rs0EogM zh{BKxZ%_+{cYh7ofDE{BZxt`w1aT}eA>g10mcV`&w1FI0Aq&EBo~K|SHx*SPPqvd- zCFdn7_-QP7VXjv{FerP<vqsEQ|AUor1el?FegXp#RcoX5gFhpDz4$Z5cYK3X9Kxn4 z%+Va4;yz3`Dp(hVTW22F*EPWfADV<K*cN47NM+2m6mG*LoG5PjVnM7R4W&>DY{&|< z@P6(VBJd`MjEIN(M?$QS3cT<O0oQ<aR%g6W3s)e3yl@P*Kq0pS36<~&Zx9H!pbX3q z4Ez|6#Ds8<_lSk2jx3>7J5dVKU{0Cnb{aP@1=A#z7J9!zdRRenVsVO%m5LU&iY^B- zB9m%zGAA^MCoZFN)AJc0AOq~cgTUyMKiN@qKmja3K18SkMu>#W2OUdTGL58Lku-%_ zlRxTlg(sIu*Cs$wwryS*|9;}9c1qHAKjIP-A`OPHhO96PurO6*Rw8$2IpC#tc-Vi! z;7q-+fA=Vt!N3Xu7!07WB1~`vYJdsqcm@8bR+GRAzhDe_sfhdscxNVo6!|%5$O#!~ zP8nnqHPL|{*l}<3iB558qBx4CheaqD9}`w#tT$?`xF)A|Jjer!wU<yVGX$Mw1GorL z5@l;Y$(z6^j4VKmPltrGm5jFae2wHtQ0Ny#hBeo>HB{+!)dn^J)JeR8TvYOf%~e#W zRDOK*BYRVB(jW>MiI!qERU?8e3-MiW`DSv-fA^>i&a{B`=$-+W3QSN0GK2}Y&<n}H z41&lEy|7-P&<N~x{{@-A3&v2Nj_G*!r9&dJT^^!U;J^u%fD0A`PCrs$o#%N@5`s}g zk|Jl4rHFc8LSd>XY92FLFy|((Xfo5`7?5#$E`x)d;TbIO0WiRm_|Tg@>Vrsk0YoVr zMrnk{$YWIZeAh8G%(h!m`D|0UKmAiHg-{<^$x~&Aoe9KF#*$@o(^vVTL6fNqh9C;k zz#;1BLvDE@3MX%ixS)6_41s_N3QC_2sE@qB3NGLRn9vK76L9+&aK6w6n7|CmkPLly z1(C1|^ZBL>3Yj`Yk?J_1rBEcSz#}~JotrsnMqx0nGm=!oA6Ifkxs#H;GbWLRCSz1a zvFBkQmRYk&|BJSXn>900yy&C13S+%iJ-}%xIzUoKuzbytQpmPag%N!&6@^9iq^|;< zSXdUrl|@^)AN`S~%r#U-L4Iq;cHS8+8L|>+Nr}*)3sU872~lQlwRd~hsDG-DhbRZB zFgbr}fBUG9w~(g-c#n8VpW)&Qgb)bI5MRO23%F32tk979x}a{xriEi8JERh`APwq= zjw_)zo9B_7*>MR5MW7f@qH20sgn|`wF(-<mtEs9n2b+lTs<#JgILQJbprhb}t266j zKq{m+W{knwG{#x1&RBg$_MGd1g*bJMT4FZG)rF!2hD61sWLSnYAuZTNi5SS1>4|sX z#enN7|CjlP3xJBS`^pRB<pNg#uj~r8!te-f(2#%147Y#@S3n5L@U;ospjXwf0#Pll zunBCKU6`q%ntEUh<e?u2q75TYP)4F+k%C^ddMzkf^&?QP>0z-+lQ;J=(sP@gL6o{_ zt2FDmeWa@-5FAH?KEo+>pF*th6Me~<b*dtjM@E&?2p`p!Q%#m1*_gE1DSm0koleWG z-3n%DNe*`dp;j9bf5uDrNQYXBhrWOb2B(jB8NI&{48rgWsn7-aX|U5<XMlLUZ!in+ zikHE_45^R?1~;!-3y~0Lw>MG{PNfKJI18^pu^DQy1$JQA>T#CVFro=DqzSSpDPbeK z|B^>$CMOG%1f{a9rZR3sVkUNrHwv@t@DDutxfi@g9n}XLaI;3Ke6+Q*Ps5B$YAVUv zTT=<0HYHrwwo_V}yVm+`O}nko@|`vTW-BoZlt^aTqHy*Fk<5#S(R&Mz0KJl<kHIj# z)_V(SFt(}S3xWuU!QczjTW6_|OfIyKNPLK0FbB>cz06y;jtHr`5DR<TA&4eAe+#%B z>Z$K!xT3mg_Ov?$oN}tzdjA9-8^)@WyTGxiS<YjVnISWuwE`O;3A>5GiL5=LD@eVH zK1M36sQW(FLBc|oDl&yXuxo`X{69<<tz*|y*BMHp<dvt?oiq%lH%tq&APba;|3f1& zBfNBYKMch48ofyT3**HKw_uOnd&__*IjKMhI1mHGAPwv?3m~Bj%rFhpAUTf!3J2@U zf_MvWu*<dlfa}XkcRQ|ot5p?=U1_YD7rUtj10@{WV514ZrYK>iTCx~cJgfSeXhd@~ z8LQEQlhw16|DedU@r(T&8y&R=L0Xi;d5p%^WAQ`6t*flgiDXy!bys;SpA5>!^(z6= zZM*x8+DbQH3Z@#8UFOLy==L}@0+-lqr`+4U->VB$OubPI(^BjU-~a=vpbCu83Vgr^ zYJmujz{P1`LXQv$y}%2?;LBRPRpOhkD6PDW_{!#LL%47{xPYcRVuqQz|DhNglAozC zZ>(vFiwJX^Py3{rF1RL<tH3i@Cs5$PG%Comx&d*3$N){(ilVC_z^jCmKFh~rinLNd z)>7N?j6hpSvI}-BEUllEyUR5!rqn<j{ku>*OCjAkwNMP4fDw0xwM^ZA(+ksrSctXY z3)LIbpY032fDSet0;-@6zJLtKpbX033ynbA>_rHVFvUh4#lPSSx8Mtb@Cb67uX78= z3CC~@VGz>L3dB$gWJY<igw>kbL>~&8Bsq#%k+`LbF=TDPV)TM2%f~P3$8E$iHW|UW z7y=}44)b8ab&VQBM<_k%-l`$clTy$mrDLbtV^-&cmK;gV>07_E{|8>PeG@G}i(od? zI?CBuN=%DoPMcI8ts&Y)5Var*xxfpwaJ3@Tp4hC?r5!n;U<bS~+NEvUwNMX+pbFox z3FvSOwQvl};LO^<4406A{@M$_pxfSSkH+9F&Vb8z%Gt(!+)!-`%3Tc2Z42h95<vtL z(H$@!*`d_k)l(#**ex*=Bi8N=JgbPu#nYlGThFox$d~cfnp?<n-MQ`!-}4<Ccb(U; z^}#0<!pJtl&iLQ2Ti9LmHP1?=Vpq|S;2)rb(WAr^2$HS7i^`H6rsT>)v+xVKkdY%o zBkZ}nK+L@+9*E3<33HGPaJJ*s8|tSW4&Xoz#L%BKE(@=a{{~mk1&0#~w@`>K6zVWN zUbEl}aOTp)y{-!Dh#nyjJCWqG0HK|OXrTk;4T1`91A-eHJ0m!XC#krpSI1q>a%YlZ zX8_)=%D}Tp8MO!m=UqK3u-@(M=I1UO^^JT)Sfo*h&?<#n{oNf<dBV(EQ(q@so?M+s z%Wd4);NPh1VTmCi-8b|C5|G{soFEO}RZX;v>37<_ny%Zz;0%x8=|vsWqaEYUung6} z%)8JCF;tjL@Cb`Q2#pX5so>0jXa~0d#iT984A~37?ef+O@qk*(V71NIWDCMDPX8t^ z#(pm~+*cjgiCg^%3kL0Q3}JGtf}W;NZ&B7?u3=_G|1yX%lWYX5ZjEBIdI4&V?x^w4 zVSm?+Ts}#YluF<nOKImTH8oGEb%Y(evLc=Gf!I!l;M4kjN_#M+#HDN3(cd}Qbw_5i z5DczVLu=Z@ZmPA>%dRFqh!bD&7r*h&;PEtGU7c_Vg;|)7P(rjF3dxWR9?uL6DaF6g z1*!0#ff$I!Ah3F{pD-Wf_9*1VP2`x95VRl-<5UaD9I4<OL~3mGtW!#a3z~&h6;$!R zC%IUtC?@KmnxnR&u6XsBbx;j#gU~ZQ=&jxr9QH&f-{-FG<Wr34bI?ktQmX5O4DF=Q zHuq9`mDD*vc~3igpV6e`_nfLAGaT7A3=ptj|Gk1G%OEX;2yNk7IEz=VT+(n&)K$@9 z#a$V9@#5Ig<HwG_M2;L8%%n+S%z_C!Y4VseZK(oPW5&xBsZ&?3Fu9V35G7EJ8l}3` zE6_`tEQJ~K<x3dLU|mu%gNibkF=4(QVY)@N<w=qwL5}UHQRBsnwI)jAM2y!gTXAhA zL}*apz*nyH?$x`>?<!QNPMsoEnA9l5pA>iMq{*?SOqC>8qC`m&BuI`NE#k~M5hBos z3Jn?r$n>8-efI3RbBE4rI&tE_f#Ze^n=@z1j1dC{%oi?PwrtU&B}*18Sf)&oBIQYw zCQ6bdIT8d&4;wUOz+kcBf~0@&@{K27|K9w0^y$^FXW!oad-(C?&!>+b-@kJtLab;3 zLk0~SdH`aGBc@ZLi6@?rV!0`j%c3|fwg~PE-^3^*w=-^YgEly1gN=^W_UHpO(?}bn zkV8O2B$3V*(F`+4B$1@D$tua@F~&MkY?Q)yH0%^qR&nJozV^CHAcJI~i<X5Z!iAQH zOpyo|v@9}<EG&5m>lZCe;!>oQUYcf^WtcJ36~wx*f(f1o0p%1-LTMzFUXq!{8E4F7 z<`z3@@x>TGpAz&bliHYys$&La$rnsm>E)NIzS>fxEI~3WqbhZwQkqtZsbv-?8CsGS zS&q!B$RUONOEAI=>rt^!7<){U{~9Ti5ys70{0y|wNHYx()Kpu|wbx{u4UXF|9D}#t zf)kE7<C0_0x#y&#&N}S0g8_yWK7fIpfAFbqTyo20Zyt2hRd-!>+jaL{c;l6KUU%R5 z2agL@V8K5cZrC9R0+C4Kz$c(saJl5LfN(f2C<H@{F)-ASHV<FJ<6=De81au^4;kbT zkXP*NMMxrvWD=Aop~S{aZq(!w9bt8~u)zWgaurteVnrZV?n?6Kgyd?{Nrxcfg-VPr z<z*v~CM`))E>H61m}l@b^OsXJi6jsvT+oRXQo5KU6*_yF=4@x~^eRkc_6($!WR^-4 zt3a~~#*SN-66Tmc_r}Vo|3|tq#;UIh2g_+L$+{FRX-e@F)KKM0=;u<8yvvoGSy`3U znGIV^)=OHJtg@6N!AvvFJVOLz(R>9KHH<HYO*YzW!!0*4dIQ5*Xp56}IVqrk&e|h} z0Ah#iw(IVKNd9?;Ug)EjetPN6wf_2Y@5^t$7G(HO2LTB*5J7_(bZ}v3eH){U3v-*e z!w>HWapPYBIWa}hSmX?K7-d{}vKzUKF+1{+t87Ljy`0Jw1o7EHf)<xhO{8e05Jp9C zfvKc1jVy^voR&E9i<2xPZN|`&E;`XNop@~ym}t~3Tv#V=%%Ks@NX9ahv68(l1yF!G z#xazkj9bis7s)V&|1x^W!(#x-7k9e_53%x;BpM?XZ%73%utGS)IjvG3F$+d6!j{Kr zYG`qxi(T&W3I*=PFGI4~U^@4?S&42kmATC6TBJIV6=F2M3KnZtGrMEeCRw>DLvMf+ zoZ&zSIn#ndwWfmv<7I0*E$CJc@X-(KWm1!y<YXu31CM{u;Q}OB0l#dZ10Mj)Km=<J z!m#k5;z(#h4_lwa*s!4v#Q`?*TaCsz_Nx;WLPh!;S^s7PK$baXfIcc9PHKk0BB8N? z4rCGpBghb56eAbG(8VsgnZb-~@FO6+3Ym=IO<jz_5`nNo5nP~#Gz`R1FMLKco{@}R zJYyNYNX81||AxdT?huJ>yT#l7X$&9!P@z4XLlc!Ts6Z)Wic}$#;R@G5l5CM9UA%}l zgCPoNsO6drnM)bZn8qS)u2rr|OspCM899#5GN;Q`XH>MhLfG##sS(y5K193P*akzp z(H(FSX&mGzhdIuPj&vXy1Rv;t2HIKy2{s^$@OV<ITjgq3=cBz4?1u&3qXGDQFa&`O zjC=<>Uo2%wq1?4EL${<@#pu9GU;fg5_sbtKH{%G*%;<jroRy9c)49P62AT^@pfn4T zq$Le4RJxc&Elg1iUVu|0Sz1Xjn4yei1cOPWa6}@ya0Rca;SsK=MK4^N3_LC47&Q!N z4q1|n|G+T=p-~j5Kzm5gxAg*`yXB!T@K!{>VI@({z{DJ!(YHuh^l)3!=+ZXgP3-DI z8ls5BFC-heC7DqmXhb7lRGQeCA!Zbdc}!$#RmaTKbP>D4sq0Xanh+5yHbAxAP;=KT z;V3exz)O%4h&P0&CQk<4*+3Bbfl04Mcs>uNaD^>=VGL(j!yD#shdq4Ze1H-V6j(ti z|8vUlO-HQ?GT$p9<gA9#Qm(herCsmZOZx2<Mff8oXN);m$+%3JhDB`6ZZ@Q7N|SPQ zvF1p15sXa~gPYj3?sb>Oi>v5O7`xcnB@$r?o#-SKtgwY^dvOdhC8LLm(i@<D_*-T0 z|I-eKf^!iSy3m9c6mCBx6Q6Bp#A5_b7!N%na;cF9OvLRefs$?(sjJa0W+WK7=<Y}- zBDu+lm%OMt?@D{L-W;{JMwWrEd=s%N(e$b`_f?JjetN9_>V~KQ4lq)G7rf_0Ckc=Q zLV~@=EfQSd6<Pgov5kFfWM}vv|EREpoeiH$!ovn1&=*-xnaUxIuV4pj&~aWoOEA<@ zVz|uZYg!|}yp|}KJRX^g0xQ@cCv(W3IIOD@3nXZsio8f7m6DizO$$~;7*XbCH^aFR z9GZj`pa8`qJ`?6EghCd(=tWVKQN$%;aV2$2)S&VFLw*KgDuBLo$w4bZx9$1l|9*b6 zaUI%2IQN1TZMen7=QgNDUo@kTK1)R=9gDYU%1M$XW2Q~DY4iGpRc>S{tX>M!QO`8K zx<a+8clw9?0ut7P)J;(lDPW~GC)d^*0#tR7JQz@N13t(HgrEKP@t_Otb7v1Ie=$n_ zSUY?IGcbZ$*=<-x$XRd|_grhN%U$;JzUoF%Ut0v&cLTX)I3i$?@x8{q<YnKFr6w7_ zOA$@!f*Dc%MMZc)6%gVA6QBr$FnPk0R6yyq#!!iu$Z0r1J#o>!bu&|vG3Pw>+2jf( zlQWcIlwBl)<t67^L;dV#X7s`iTrty{*_`v1Ji1aG4Ms75J_`$uw4`M;|08)(nkvAc zw{z=tsbkzLQ}||v>Y>qNX?EIE{qmRVv)<ja6nX1LYN}m}Bn1Pu4H$=c5D&VWy9Zl9 z2Mn=)V1s<wm;WfMR4R~xQG#t-khY2tS>l2UnK8P`CB(Zi5m`L@(Ifm385eO8$cqul zn>=Nrw|e^#BU`M-nkIj%CME$mp%cAMnTDldg-0L+M<@h{3x!!I3fE!@4$3(;%e@`C zxH}U*IhzV+5We9%xjZSTAzHpW>mjL#EizdKV{nF0NCRj1ts<%$MZv!5>Y#DrB23wZ zUjQjz06(F-rji=Jeybd$ODVwMoX$Cn_Jg`PA~l+tzdW)p{2CTO|KgBXV;`@pHCtmO z0lXGpn<VczgRFYMXKO%EguD9~2mQ#q6YGJqDv-WY5VrC*x0)r0!H^7bgAFm3_)$E) zTDM_(ydN7Z8PtSj;*n+olEA>h1wx}GV-kfRx+bwhX7~kZ_ytDbghv2`G<XA@XarW^ zg=46blkkXOc$!92ltAG<J6pbxONBh?AuVLSJQE@`BRS^tg)X=S5rQ*ju!c8CG?=p? zbd*9yYcxu!t|}7-@8gA9xCrqhDe|ivyx_F+Dnw9gulJ)2MU+2X2@MnBBdi;i{M)+Q z(G6zlzoWWD<_JJ*K?1W=FiQFW8gPev5SLNhD!FSrx2s7B{{tmWm_UB9zyVpMCMcf< zNe&3n0^x|Uhhd*_tE&>^r4!u66Y0f~c|mv!G9eovdMmP<!92#wLC*6xp^=M;_=TF_ zvOoxgHuwWeZ~-PDghtSXUpTXI^dOJ;g(bo=F!>6lKnZi4LcrX@I7@~==!z`-vn?#X zJxK#xP`)gj$1psGu_41e=><%9gI-XE$3#qYteY#!xv<zGjrb^N$U}4rKRztFx`4>? zO1g>ck;720r-O`I$w>K{FBRz(kL)SdD3(AHDncqrqw1aG2s@@Su<0<KsL~GQ@eZs~ zK%I<E>9n4HNP-Puf$m8~AP52sBp9N6C0Jyb7=xII|7pr{GeKPhCKYtN{ee9H0miH} zEMl~`#Olh-OGYJwEM}AiD%pjaK!`b*13r+0p11-vz=d!C26B*wvd{%A8z<Y_OWcdX zMN=q&8a^u|OiZYTl@rY31EMt01?B6|Fm$;$^C4;og*9-k&w9s;3ryX6LyOYBvA8Z~ zz{6R<Ak>T?O#4IDl*mE6xAX$Fr>o6diLaWXuhyxbJ_?aY6r_>d4c|DV-iem5Q%R?S zDoIK^7TAC-_{8b-BvB00tpcTN_yAJ!kMG$#wemYxa<N!SpKvR@5wx-SLBSLZ85Z21 z{-F`9EG!x{3?I2S`%E$<p&VO~OJ>joB20rW|M&ww&<VIS6J;npVdxZJ(4a5*pu`zR zFKLOYpwQhDOp~+1XCMSZhz7{?&}F!jTL{q+6}~c*EyAq1lM^9Cdj?~e)mgRBbljoq zBS^6r3pr$lSm>@=(9s<QuklNgBS97PTRKlO#6zUb_oE}4%9T^2zdgFYp3=J7iPDlp zB;p(}v2!F|lcepasu1V~FeOv#xydnw*G>YZGq?a2punj@CGOO=@9aPrQy->upTpZF zydn|CW4B@oEI$RHtgJlx>`Ea?Ah3i5RzL`j&;?m|gf@7CE|3E|Fi=)V1!<_%T|k;$ zsD)sNg<M#MyKI`UkS+>!vlmTAR_(KD|G<PtNCsa3LtZ5lS51TDi><@NlOIY3Rwzv4 zt4uq1gv?ySRUJN>y*N>w(VZKo4w44%3x@1sNbyt6KRhWQ4GgABFZM#jL@c$9#Hnt5 z9bsvWCk0Mf8-pqRy5cyFMM_CWqK;lWJ8j9=3n+wlrB`y1*PJ9=P3i}DpaJgDyY1vV z4P-G_3Ow;7JX*XBr%b%4{3X(8y!@%kKCP9>%aI*HEWzkX&B>g+U<Fo?1zX^VRXByy z!h<{z8#N$=TA&mvVTk@@np!Xhh;Z2~*^&wU%Ql=^QmsN8vId=1RU7)*pT(0`O+FFg z)v7r@R=|W_Fur|!gfu{ggi78!{{u{5l~G44NGuTsJWSTp+`~)bT~P@y);zydA=_#F zv_p)k(TTr1`iw@jKVZ?AtlO_+**|8X(sI4hMnX=OOfcr`ju6lRnM7O)rdLoxg$*dN z?g0?+0fO#at2Yh2fL+S=c^?}?Hx%q#9_ulyyh<CH6^M;k`@|U<h6P&4h*8jl(~<)M zRjp7s%U!4@(6f?os)b`H22)@L2DQt(BuBnvv(6OXQWYU>z=Txw1u}%*G7MU{sa{?+ zKFh>}s$qs_zyztd6VQ_4@#Vc>wOTm@31_&hOua6&ur!AxKe2U9r6WW^O^n$zQW%*! z)!`M_aoZ5_Dc=m&kzAI#|FuLbT`DZqM5&@G68HdT7~BfZWKaYpD7a32y*9MUK)+)v zIQ2kTEKkGZ5Ic=ZVB#y#@Wsf3PaKJv8l)Lx{0p41;ffdqO4tcGc!M-h16HU7CDw(1 zbCOIsIA72vWe5q3A_<v=D0EcgTb)&yAcQ$+hV9M5!z?~L!INjWlU`s<*y?67sTybK zg-6&~XYd9>umTrKn-8VtAG%OCG~YNR3u$l$$C+d6s$)x=3)R##LF}|4jg>euQnmGr zsw?Cs)vx`6(xEzFa{a$6-CIa<;O5)_E(jM*{%BAvMG_#T>;#Y$TQOHG%2NJ7fwd)a zvnyUoVf$HOSdNin|H8`nEJSC*2~a?Vf-q)HpaeE~138!jHE`Xf`9p+=pdUnwa8gKL zfCy*cAUSm6llaRure`e{A?787XF#)W4r{RvXJ>d-xQPa_b_R6r1wwF?XJ7>@2n7zc z=5D6vsV!eYIbX3rUuVG7TBx!rvExzcw`Y||`@LTx6}3@2QjHws`m(=ZdE2-hBuZ># z;=HxvbSeVW7D@_%762EJ4sE(~hkvL9pFA;sWkv5KWy)pgaJyVvtSimUu@c#_&u!1h ztC0Yjw^}9)hT9oZv4lm~i8pwIIcV!t(5_c7h*zj4vh=}@dg@(RW>av6kl<7aePU^@ zS({DXtuDiy|9yme(#*6@YjGB$ayIXD4uoCchIh8Oy7sd&v}-obYrTGBUJ!@2@P)qy zY_I)VKXg`}F>GlyTZFbqKyGZ@q(6s#M2Hqi|1u=Iy;}gR7U`%CjpmjW*nmvHWYPZc zt?CDNm^OVeB~=V%f=TJ36ydk>4G}C@bHg#c(y@^7s}^opArnUVj7?HNh4Lz`p?(8Y zWnE1%za8vBJ5FW|ss&`og;tn`CDxLdEga*WLTdhQaGnNh2!%kPArUI?uny;GVC!H= z?=U}`UcgLDh-+&|>#e3|?tW36J6|qxhD{)bW$17J259kn$nk<!m0CX{eJTC56<k@{ zR0H4u{~q9omguh2or<P#<18@b)KawTjt>X|j|Op0FVlaZh7BNT7}(bf)V7rFK%|sY z3vp@LevLbw@%vF&cZ+4+j!(rPg*V9yO+W-DD1tYzgCS=HT#$vHVcmhyPa(E6CHIJ0 zScY5}2J8NyE{W#dv+^s4-n16;DM|)2$CI-Fpg>>0`Sxje1~E4ZenJ~D7k4xd1VUf} z*Gd~OH|O~VL&5AVe9k^8{~&3YhC9#m4pLT&uw$?-KS1B(vc=!C)n7WQBU4k6RAbVQ z?9D``4a(+?-ryau10HJ8wIonZsq!95(hqF#@J=6ja{(nT$ly;#B@~a`f2G{PlQHu= zPY_{cb^mi^8xP%DpA}&Qh1hikOIQ;t=mJ7$6joSnTqdu|aUcl#JY;riO;t!^AckCs z_HoQ^?bab{S7U51@3o$TGEbXnhz4*6cXS`~IVktBNB3$-g`iIbZV(}Kes}04(d4Cf z`_{Q(od&;_LylV3$Qfw62*kd?<)t%QSwY*$h`-bs<c7B|0fzY4kVJ8{?8}~X0W6*j zFR=?41d%6s&;Kg?2&)ob)1XA@zw1EPrc*Xh<)=)~y^8hQ_OaZSj7zA5OTdvHM}<y! zgEhH=Ls&gbAa=l*SbcM>&RYnkuafK1AP=H$XP8D1vihqY)$Z2%FMfA1zlAs8_Or34 zvH$<}vS;fdq6V~y24o0#XXu7^b}e&9n|Fuzcvs`&opU<h=UgZTWXN4hX<zr{Lx7+q zkd`c2uwcD<<!T|rRSs97LUrmCsfraxefrd?lctWDGF1v$Ns=T;CLJwGxhPR0M2HR* zDl`ZX%|Czo?AdeY4jnpi;=l>&hRvCxWyFB_!e!|eEl#sw!7^ov6e&-hC{dCm$q*ks zY|xMagT;yvGT6<-mv1fGwr=0TjVpI9-MV(~;?1jfFI;&4MqOC3qJ<0@Hgxz1awJLC zCQqPLor)z(7N=XbEd2sT%$PDo*|2dF^k+{xcXIBr`G@A9)`bqaOr$cUBa<X4RsX^r zGE*l|r#c;?!-UD3K%g+mf*9)|Lxu@o9V|G|mMvV?uV2@teY-ARymoo_{)^WyU(hx& z`=$O@u=ehQ35#z`n6dixmEq5?fB&-n{`)%<pn%RyQ{XhuJX2sVf$Wk@fzd=`poG&v zSj{vG`r_b$2@*I>GME&hhBpN!IH7?94)~vc`?08>G5O7BUwrSmx85(zm;#M2wFEO> zc;D@!U69&gS0r@<5o8cT2{pISLlIGA5h<f!v{6Tzd?ZqCl$2!BY%940lT0)LVpAVD z<y6{FLBT<kQDY#b6c<fB1=UnlLGeTrS|xEr5I)#oLt!nfK*9yP`~wePi~lm(Xj}dC z<EW&Q?uE}kNo=qJ3xv^NLk~U-fdpepI0l(ylR2dYW=nyw*%(Eg0h(xVkk->qd-S0i znXb8nh-@m=W|D5ZUGm8#k_b{n5nZJ52q+LuM9L|sFt<vR2}LKJK-A&FZIRpw`D1wM z@!|_P=t<Kfjqb%KpECEg*rJO6q1d5`3S#m|FBT$bZ-LZMQ;opXe0WTR23F&YHPu`( zM<aoZ=uC<Co>=d^{lyz^eeKS;ZhOC^s|Yzek}K{mLvB|jc1I3WkdjO`_mD$SN_mk+ z9d(kWmXvUL(rhig6jN(8nVAz$J*_E}n`OY66jO9+0hLr#<+<lpNdI)D16X2_b%7R% zQX00{W0PI>Tb7<fLI|3|Km!ek0Wri@jXfsC6j7n-)KXk%wwY(KhBjIprJ0sfuB!pk z+90pR_GPfQRk9JXRt$FqC7@uA%9IsNG_6BTItLvr+HR|IcHo{Y?t0$U5)LQQsOK?! z?b-)##`#@buYeLlC}A_K5VG%v69P<4h1R4pM=~Y$?oBFdG|~$psaPm6#S`l8%*D66 z_#($0ugjh^oP-13cqNB-GPp!qSKW0;CV3FdF+V9$lonxhvqw8~*`*^WsRU?38=7j+ zbTpqNZ78rhN~`1qHOfq_Dp#=@)_~9ht%-$DA7}wP@Szs7f&Y+E^B5rsOK8FqqA-Oj zTp<fv$ijF00~Uc<0Ssh7gB$E1F^eHpsqA*Qyj^B*tr7znJ`*@v4X!76SRx({m$;a` z<`A&?)gppr5=c~nH;`CE6^g)wKuiL2qv*sZMq!c8d2SV~Sja(Kagc1ej26`K7A|yA zN7R7_JgPe%d3XU1PVj<89IM?i{Bw*#UW{G>0#JaSA+bk3145FNB!Z^ljAXDvUkjTg zCnZ@8ZKNU%$<UC%xWS4mG{PFsNW(3tv7t`FG8&MarS1}$$Ya!QKJBWJF>s-XaEOOI ztNRgnbb+#z8Hr^sQ_>q@;R;r$5hAOYR<xv)5i4E7BmW@D%_JrfiAX@=e*k2O6s0&o z)i4ncYFZO$h*AbJAO#G2dtg-V1O+HGp$S(T0uXj^gRr!K1ti!&H2(1p7a}yF3SDRl zL+DUR`2`MvVL=T$^(n<L#xZp}Rb?zAM8Cl*G@_}MX-<<9T`7)njZ+CEcvgu->_J&q zNCPHLp^=T0(Tr!5RvN8!Ezylm7D#fR%GP%>J&H>_<v|A{f*}oGv_}~1l20zVhr4;{ z?s^nDSTb-CyiFd=L=^(1C><2AY|J4Iy;$Bd>~IT#^-inUv)J~yXP<X{k6j;QhAtSP zj#~Iam_8yV%8qF|mc>tg3TaaPs(BGA-Bg?WyZ<5pQ^Jy#h-qkLx{1-&$tDFFC7$z4 zmDKEc6+U6jD_a}O3NCO6ust-ka2cU&Ynzuy`QQVCsbQdc5I0eg>MEwX8)YoBDlW9@ zZ-AQ>NehQ7n~>>=u<;d37J-{dAYu((P*xy{g{4eff{Yr`=^3XLk<a~9bflx>x9+GN zASHEN<M9PLHZdQM(GEX%<zDWxs@2{REE$2=S2f}))@W1%d3IQyHoVabJIvu03&Uja z;2KuBR*bGHvT81Mxy$zmLmHd-t1r-(RQ0XTbltK=%U-rv`prxtHJehEIHEI=P~wW= z{8_JrMy8_agm6h~)6&M!z^9Qmf>z0=R{tt^K|#rYEE_<=KWuAdw?OL3T4sx1#t{M% z4913s@xgC1dX>mTrK76an`XqIT#*W{G$uV0;!;|Om$1YUT;hXpym$ptpyCpg0Pja| zHr|VH&b-WN&U3N_Kcaq%J4Z!oQdj3XX-G8~_oa`!Y<Igv`WM3n8l@cwY~X(ZtU}nh z1tzeO3~&6x3XR~#GZxm1d^H2Xrxtbg0#sLx-F0K~*=2lmVG3XlGrmVn@nKoq;w8P9 zel)8YWI1vr{*lCI0qn6%X0q8cbrxwrQJPVhcH}uFIf7N=(-8ioHGmc>1m{T0mTjBm zdSBTunwV%s#~i9rIVLhc?C5ck>;I~dvVlz`MNO`Dr8p@j!V-(%0~eKLhd`jB6Ox#O zNHTFHO^}gFHB&TtuLZ}Us@SNhi?335<hoddBN$MPYOp<>vHsRe)CIB-sU=+C2o*2r zV@*XMy1|V`bRiVIm_~xDAw5>~LK{EV`CK);VXM9?mzjoYIEq2O@&t0QCq^-MRP1bl zxa>L6c2bP*r_(W7dw)CgUu72&CYUIWXs9`$PlN*6Gn9dW4otUcncOEJ_~6}KTfqi+ z0b6`SKJsPr%M>=i0*cyD2fqC`51)YMG<!5NL;Rbp6rMzrK6h77w1g$(u!bd6juNBD z_9TW?Xq<(dygWUxPk-v@ZT~?UJ1VDid~GBSQ4}K_zJRKSsrsT%;~Yg)k83iTK?qE6 z<L5yaI)Xuoi3RCP>eYCLzy!Qj3sc=h+52_IUL<UeLG}2#5XX3WB=!@3XMJ{58Da~f zSkSpbjLDdk<d2nn*UnH@-2n~W{TPt(-MG2IP!w65AX(Jd2~{jvRwRLwZB3N1zy+Ma z<4N8KlHj6P3Om3+2w<LJzzyf+({O>F-eATTwAq`%8A+jD!#&YU{DBvA5pmdoCRoD% zbQ90m-j#^g+gU_JP)o@zM56`Obg<Xypw4%&+_>~eEgYXIqyu2h4(;q$yhPuCq@RIQ zNH<^tA<){uY+tH%-~TPVK^mk|H3W>nRKuzT!YEl-(3N3<tlzwF7+%32FQ|hlz+8#h z$o&zPkdz(&v6xU1L^G{j0M3kK;ZK!Z$u@-q&veO-Sr*VBg5r3aO&HAqB@k$o8wJh@ zJxPTG86H=-8<Yjq2Mhr|L`n(bVlLW+Us!`~VP2;oMi9u2nF-uv5ZtQtO=pDEtRRt` zEzxuRfv-?p6;uHeT!ABG!vDwyNkC4=Az?;PiSChH?}d(fLE=E993Bzh9<fJY$)7qb z-xpTZ&0$rji5mA+LpMBv8YaWS*kK*oVKj7uH(Wsx^g=HzjPclEHiW_)(3%_mBOmJA zA70(<$O!z^LjO9nf+dJU*d?2?kzFJ5U&~11+SShh;!k8<+uZpNkGVv*HJ|}`792$2 z(g@x>(Mf4hjh-}FyCt66a19B3z&MDYE>a4lAZ1c2<x(<bQ#$2SLS<AwrC%Jv1#C*c z`G5}1O{q-9!0FB27@RULSDYzPIz=NQ$blCuffaN?8?c^Bu+%q6f=lg&$AMfDirf;) zj1#&7P?3%t1)p^c-xVrV?EJ#<i30ukf-XHDf2l~X`HO@|WY7hqz+giv5JG|3p+8!f zHjD!%yulTy!8Rb+CedLuU_&T8!Zz3;9kL<7yk;9x3`PEjMZ!qCET1~G!XdH;d-Mol zh9okL<o~lR3FycSO4^M6bcB}VMkoG{OTt8SIUwIDjhhsOkvYvO)`^mxmR9(Q1+5mL zY(OU@id35Cd7@`}s^@yLXM3t=K3GZ<Y(NVTM&^;33vQHTs2NzcnOK5`>6Hc(^#LLX zf)B1`9_Rt<-5C`v!WGTs5#nB6O36g*rSJV7V7d=cNt!XO9AU<e%(c#Wz@sm4TJ1Qd ze`F8UwIOWU;VsMof)!6dMuRnU!-B9<D!c(V^y9+#BWgZEDriH%DC9J(C>y4q)nSZ9 z%1C`I-=#g($9&}29TWSs&vo>liy7yWSmI;p&y9^lwt3=8fFewO+uqHj1i}h-W+y9R z;QzYy2|xX$SinFFY`_+PjeFv0o}Q;sk`3CB015o!m;u3J5To5l1rUMd=q)1>C6PL% z#vjlDH8MdLsMH`#5wKX%uw;>4;*9Pk+Ia;a=wQo*%8}`)BVo!{dn_L_go7a{ABj3& zW6BGP=G^rF4Dqa}@gP_=xTr7Gn!xaADe*!Ys3A9mLL2C)H7M({MgupzK`LZ}HRS5F zx{_p8tNJ0Sl3pZ<N`oOd!;{vCiAgE5B@=P}Uqdw3j8&VpX<~D><hF$gnL415(F#o# zS*xrm;q9c=z+&RbVhe--40O;3@oB;0qF?YrrUdFm?NAS$O5X5itB7T+Fqcoz!T%lz z0v)L3T6TdTAc9Pk(`8|*ZD{K4fm}|F921gb=$zbinChu|=z6eAIEdJ*n&^oxgFW73 zYw~P?Eetnc0`{S1k9tEl5W*bvLNjDTH#B6ja%O=g10mc3Hu&Sy(jh>$X7TV^E!C!7 z*~jvs!!LnrxB_P$k?YEsYjMIDwA_!)7~pcw-APmyC}tMX$mE%#BH$UBoM>m%)YHCN zji0DiSj_1Pd_Xl6rNJsLzWGHQSY8WYWtj!na1mFk99Q4C8LUJgo2-E#6zIlw!5et4 zAQS>1#Kd$l=>I@MH}1waVuU!3BRP(06mCnY7F89lBRfXb@<~IhzA7^;ga6I3h$7YM zJx(iJH674?-!@nSgm@;=1y46nZ8oIBBj{*rT7x$90@3xtHfTezE~`K0DjnX-wPI_E zbS<#G%kurvG)RLnz(=?$A~EG3xHKEuxs3c|Y1>g-0e;*zaiZMLMz4JAOpGFDJs<>H zr@3V(x;;fbNf1wN;GcX2;a=Vb{J}rC!{X`%ZRNwgaWJFUVm<`H2G!@=BnE!MpfP?W ztGJ41v{O)Y?j2C$5>&w($bskfLE<EirS=LHsqX4(Y9$~cPD$wQHQ~z6?qAxj@EH}V z3f6n@t~hK0I0(aHTGeApAH`Iw`LgK1U~l+ZLo+N$FJwc4c|$ThLjM|sg7nU)H8{^B zG{ZAcZGvfo_F_UPBm*``9gm9f(|+--mLZCyuSE(2GC)Hsh{IFO9F&SHVFl;@t<2fw zuiC;Gl(cO{TvOb&YtMw!-1eBa*=;F`TXm*l1GDMA_9Wuz0O8W-2S7oUg)m=$@GMu# zKX@6Sa*C$_fiP~R=NW36RYt)L(W?Ls8>|6ORKXJ1upBgzAT-e*$iy_G?rd1mTxtoY zp6n4LF<<tjIiBMb3Z|sxZl(F=R0Tsc<U%n_1AWxTGSDL<Z87nbZ;XENA19bKjM9K* zFE`9W7pMU>WZ(BHYaHt+)rRkb-GUkSaX$a?va+FT3NqE9Z~r0hhcO(IF;oLF6hkxQ z6_i4;cTDMFA&LK;E4o62{iv%-VhM9P=a+=CDBlE{?15*Y>6@I}Wo)Oq@vBd^@}LOR z3Jk0**M$eyGEw7&zA0?KZC=BkSui82=z+n+vO!NQ^IC!%!>xuW-q}jg2FWs~Hs{{v zeCnc=;~SkLVBRh{mvgELk}&*2GqeIRXoEY;s(xrO8OqhQ7HQM<EU=E!9Hc@yXhT}v zLNf$wK5IiQSZ_ZHOfzW1Hr&F3MV;0DHLynH_EB_2CuzJKk}!zFTsH%((nyq=%(98( zB%AB}ptMRqRsqIcON+!y!z<nq5GjTm0+Aa|uW3$7P5)I$ftw0$1uxzP$U@>Gb#jM| zUu=O@{$dM?N)kBi4`D&7L@Z}8%^3j25(q&RSiw#dP7^s%535vl0Sj1XGwy}ljE!S@ zp*6}?={S=!6n`j)N!3Q@f;G^`yNDt21_*`;460G4Lq9aLa>FBF0@5j6H}tU|SHpof z0ya<sXIjHHG;PxrI6f=u)oS);FVc$K94=`?D-=UC%ue_`G9;5LQJr04Su)$D^p<Y& z|7v2639x1LO5K)ekd?B%S|@h$Z7K)11Xoa;js**B030B<a%0&oGI?FtB0JE)+SKQm zVN{`Vly$S&R1*<Ra<_LQjS`{8qq0U!{IE4UX#dIDr4gHvI3}^|Hrg_&^~-L@QN=8I zy!90?12}9#H82Ar!83pOcVyNxk-}z-5_pD3gEy4J95BK3bi*0@v4Il;A#?*`Lv%OH zf%QUkhU0T)OXSx28i<SGF))KOYyvtg-+h&~FqQ4uT4{@$G;330j7Q1av9xS&B5jN5 z-HpkPC$Nt%P&^IZ19K<83hqzC01Ox|5Pa~H&&5$gdtdxRHGF_B7lx;R3UHAM<;I{E zuvweI!5IiacUyrW(B$9@&aI^0u1Jxud`X(y-kKXRqLnpYj;eHoGo9CYTNmcKaN1(l z*EIb3G4!`Q|My-~CS`j1hR<j>2-p=|!T&hWnxb<9Az1H>zHv2dLm;F=_BFhx|D$UT z%tUf_XXnQu;m3%{+=sn~X`eQ%w+|)z-*c?(wBfpP>Uwih7EH&hO#cBX_xRs2jVh)x zRdnZ@s#al)h1w7$!A|?5IC<1ldnPQkm~9?#^^gy-@S5=rautOT;D8PL#7Gg&oIw|P zzdM6AD0<f=?xF02wl|}hqZ9_FdkIO0vRr+~?-%-lGPJKTp!`+QYQh8fUyJ;P-(fR= z!WBrZ8d!*@H!CLG!Zu(7HgJPAV8b)?!XwmL$b-IRPqbE99eyO~G8nuuw1TQHrpv$l z{H9MNlQePCdab*5N^S(ZcCwDm?f(MGD`)YzZVS8Ks-gq?ZC4IC1;OcRb<HU(In_fy zTv!SgWD4Zkr!Qmqz;zT@l0g{Yz}S0%-;IWxq5W1b&b!0=$O<up-enn;k=(!ePsw@h z2IgSyz087`u;nHvK!Z2{gfCyqloc$v3?V{i3#T=7=#Uz<hY=}8tY*zxHH{lDX4DqV z8n<It()8liYfi9c7eQjghz;8_ZiH@Sa|!cVsz}_TVZ+!lBS)b_IaaLru%Sex3z;S) zXb|BsU*e$UN+(cQR%60~b?y2KEHANR$?h_{OIO;oxY)MEWs6o^TC!xpg7pfoE4_MG z^+k2+6e+=iM}7L#>64~Ri~lP%u0#n^WJr!2En1WaGonL>3Jn4T=+B=%d-mL+b2?6H zIBwXmIdi5=nK5F(aIw8bOYSUKuuPdE1<I2qN|GQM62ylM8ZuzCSaHG4KY015SGRs0 zdv@*Hxp(*e9ejB4<Gthi=T1h56)j-MprOM@kRwTwC~5KpiWJ|xv*g~g#WpT*z@Z8+ zUOR&gH{eJuj??J4gS0*R_~SD`1}UVFLl8kE5z7{#%n?W=k%SV*D#=8X6gxp|lu-r~ z>=ab`>T55(@Un|8S>&?C7Ps0`3oWzA8d5B<!1AgqVYV{H7=gqQB^Ggnaf+aXlu?Kw zq_mud8jZT#$fb;2y8npGXrk%Hn>o@*rI&6(dIS@0tkEXSm#mSACT(o8#wKn8VRM^3 zfvS_xLdV?bsEM{@${B>NtTG{~p0q?9fwoeTD<p$4lE|{m(gm%xe0)o;xahhouNwXO zE3g+yDQv|~6wAa!N+^*evdTQnY_rZh1FetI?l29tIN(^#wbx{$EkN9K<IOkVgj0gJ zBaqX<1{q{<?gJ$HArIVe#T}R2a>0e?pKd-Nfra*DutA3)hCqToC7yUf3jL<w&p$50 z7;uRy%1|~z1s81aGzcXO?Xy8H)DSZdKMYYsTTMh!lNCQ{(N$7nl##|7Z-j-e9eErT z7qvhYvQu7+{QpJMB(-XCDpQKN$`^wkO^DGglak1yYAPDk&}yRbrW;J=AjG6So53Vb zYqlX2r<rci6C-V~N#>DTn#qPvLxa*tY(kBS$mfR`UC1e&1xhCuQN)po$*eL(lGB#O zI!k3;M&+^8Q&D|I)frLw%heVQla(>YY?Vw`%QDjp!(T%itu$g)LpIrEYrD<a-Fo{? zifM^M;#%dlT_FS##`y;yb7h~M_S$Pl_mmCTZI1>U;yZ#~`|j0u-z@sGZ3!cmSmKN@ z!ieoPHjZ7;L4_Blu;D^B<WOSDA|vr)j1k+|MOR~-ag`cf8M)-R;OenQx6%rd<xXFY z*={DAJpYC&POd`67zc4m&(g-FpizWuV;hP!qM?m$+`<lX2*o(K(F{IiBN@FQL^8PH zlR9Zb8ysvyD!dUksof$FZnB04i$*4*EHEfW5n2HovbMGr1R1_i2PdFWDPIKeQe3&) zSAL;4Uhpkce)AEJ;9{y%;e~L8^GmB<RG7oeidK#r(PSicnGJE~SD+CMX@=z>V{z_4 zvjM{wnx&iF_~tkFB2ICJ;Dh8W2L>x3!3J<49ozj8kbxAWb<lN&3$UPF?tzcI>UE#| zz>zmv*uoN=fP*49FAQTC!@v+^FzO|YG{It+!v>+D4Ry#v6sy?9Qj{?kbqp{dOP|PI zf&U{NnG9v~1Jx0Yct0fBO-aU($}++s4MT)OAdO-hmY70A1Pbj-L<tH5tI>^QV4@3+ zpx{mPl#FCB4QzH=Axt>9rf%#>YOILbOITR8L%k4DXG2@sY=|X-90M8QP=qs(c?@M7 zBZxyJq7nC&L?tc}aB~qH6xFvXz$ET4vYJ(`Zj~#ECE|;RAf*^FH!RH=%MGkKkZjh- zMlLu@3vY~8aGF3L;{d@2I=~|fo&yL!4icw1)#-Tpfe#&gU_IJ`*Y6sMFXHvb2~LOs z4#Mz-FMt6In><j0j+L5(DNK|NvydsdmrBWi&oLOwm|@B{m{_7ueeApCj&cdAmH+Lc zmq*f6{*)0wNlAkf;keSynCT2>%9BiD14%cYmIgv_LrypGiBGygh){F`C@{fBHZaJI zIi%v8FtNrs2$70xSkRqC3vE1&LPJK`QyBu;VK|V9jJoPCD>2Jk%lOtega+=3Q7qiy z9$Ll2Bxa&ol+0vw#VascuA^n7!{$V)tTB}IHn~YDwDQH$IUXmb%aH+1H=qRA?G(J> z6>mP!HI5Icrv*Y?<b3MWg#74hH%i5U76SBCF-SFf21D3`u*xtCIn0z1^Qwrz+8D8p zuYBeE7|7CEOOmyZ7EFAL{N7qWBKh){GYeosj8TnNki)ghT*lgvq7(ym>Hka7<j7An z5{+tjgB!XaiAg|fsH8nYg)X5iWjT1+Zfrxd)(Au|Y!c+qh6$cR`H4K|Y2q55wr$9O zhA5n|v)2YuwnZf9r_|CG2`5x8bwQOBc}vAtSy7^mYs{^1Wl_mtlyaT<jA)W;Mvx{8 zHqTvSbe}akX$^-y){3d>oTDCg;3Ib9RrI27_YYm@E|I<S0TAX@ANxFVUsH%d461;I z0C54T_vPdnJh|Uth0?zc%g`xNIWftUD6HZ`u=x%*qXyg3Wblh$%2Wo|xVmhv8W!eL zjFF92K%*MUP$r2Bh(H9gc!3w;1~1Z(hFc)Eok7;@HXzuI$!0^c-~Vog)x3d?ZFr*@ zw_ut#ym90fCYfx|WO7oL0%b>egBY#ghB2%JTf1rMWk%$(s3y!7CWcwecWLM<$~+hs zDQ-or%;K8c962v$RL&eFBe9ly#@4_lHez7bNkga7d`-)xLx8F3V8DV9gdiI?W%SHx z4lZ~60}>ZlL8N_0X?i803GUSo7G{70Cse^d0CH+nN8Os~?KeVu2o3fwwCb)}MwKLj z^@&=kv9b>4a15rUEpI7dAN38czHXV3@TZl!KB^$butqM5k?g)^$!91QnwN<7PRP#T z3Zdx5IJ6Pja7z{=8uW#nB)j9!lAE$2ff{1LZDe;}erzi468}Bd)+mBlqZq}o#*`ct zcPtMv;Itk1LEUn2C)y=ddoi4uU$r=iDyCLj<l?TrSh+cmk&JdeR&(<_^8dJTba8yb z9AA1z=Fs#4w2*ntW!H~yQU8zV5`)g!qsU1Qp^;9|j}c}d1R+S5zP7P1ep{noQ=@v6 z7}DM;Q%Nzcvr<LmdzD#hZR@?Lbw?uXE#jwdRwl0G$}93me{`lGq5&LQK^u(0^O$W* zP;6)t=qFgL8?=EC(m?PCukWY^+_>QpQXv^K>+r^{YtD(XdSS@Mjk16Y@xr8?Fpp5= zEm3@?o<^)1HUS+PWv_Gw%d$+%I;FM<uHe8-p<qw9`2S+|AnJ-zWa1v<aduB~FwSx= zCqje|Sw>2Y*y#BBjC8Dvj)0&CWQsZR=mHL5`moOp->^FRK?yb>k=_M9fPlU11qzhF z2yj3Mu)uiw<3H373`8w@sOpnI>3SNb>gccjzQ<z1D*yEFMLq_tYy<!!OaRXg?bObG z5HJDVE`S(N8KwaoHUS%sVFC$AOPFj>I-(h<0ckprCb*&SLaXsUD-|xGgMds1DT^DD zVaNg{8@eGC=3tu+Z?b042Hgn<DWZVv%^7-79ge|DOs{TY3*cspNRE*8ybQPOV$5Xk z2^~&xqEO8qqv9fmSA6gHFlP@OWVwd#<6h$n`TuOX{EQ5fK;^PaTbyG9w&1(q5M1VA z9tiS}`oSGsZUuN}s2GV_pa2SDU<QWHc#_UGLTwDDimDi-df=}@O34uiY?UNYMP7;4 z#10c348q)};C=*1EbPKSF&Kaeh)D4mjv*X4K^msv?$X8;>%>gDVH`ri4$?rIu%RW~ zDcrVU8=Aodo95dnD<+b`+PDF1IO`D*Yn;NZ@+_}xLa<Pt5yd#KDV9MTWT6x)#h-)_ zh_qrGxp7Fm5oK_pROUh)o6r>uhgCYpiX_fN9wS#QZV}?lVcs$LiiIBW>>f`_x<n^h zN(a#R@mjR2<vt(?{sAF3v*yfW99oCxbpOETfbI!qAO@6YUm~erGO`e%2SE_gsve{? z7V*F44-vY^{vy%9x{eaf>U=^*WN^)Wc8$Vf@&JQP0Y_1Q-iC+%XT<QX0#z)5SfYU* zC=arUf>xqV7E7^mF&m!JvM{Ui!0kJO@ez9A+(KdwuI($8@$lSDERl@wa!?1^#uw6| z7z_btfY2cHXGvmaQ{>W9Z0m2DXbBZ=;TW#B9L_M%G4~*6SKw?j4s*^r%FfP+_(<w= z!q9m9Ofu)_2vn{ISkC2I;LtcTT&xd8#|2$>0jPMc2PmyRW?%+TAO;`_5T&cWplXvi zsr?S-BS~ZGvS%|!@<YC-z_@O#Hva~e`fry0PaM~36N!`8=EoC15oR(>!x-?MrlJ_E z!WWQX8Kwa`OH3%JK`5=k8<GJOkaFBWODqvD+-@QpI4cwwuko;f8+>6axnWIFXx!S( zJqHym>jVSCQaVj*A#w;md&n28u`NxnuKq19i?AD4uPzOAq4bh37nCq;5BF*XLV53t zHcAT<v*V7X9*ggD98(OdYcgMIMDeHvNFW5Zp$%8mJ5*Fx&jsfwfCajb25ulmkHA<_ zU<RC^3G{_ua$`pgF~1ZfHc#z(s4hcHse5vB>y(s5zRqJT5jfX}CD-a?Mx_(4bV%3^ zId4*D5W=;@0UY$x7m|S$OaCmzz$7DFY)wJo3JBp%4|O{U_3*kO6p(S8zB5qvlxfBR z#vY*&dV$@#Qefw_1`X92iNeXWgee%6C&R%Re4)x1@GZ3wZv=Eey9{N(Y*QDm;mmPy zS}8CqVI41OLwqF*>nv5_U{yWGq)-Yne*+4J<8(w+b+&5-_$XI<RcRZo4CpYu+`|TX zU<i%?1yF$e-fKT{RFVLM3)Zjc+)oi{Q`J^Yz>X9W!)Fq`^{o8QMxyjCsgy0wRc|mX z0hi?M+BLQE39rIIOzYK5pDif1fg5n43+A8~Ok$c0g(@d@vK}Z9EGSU)v^;&`u>7<c z9w8Z|rac)qPn*$fO8+Ywogs(9!4SYf9F}1qNHOj(1wc)9ELQIu4Ng<VEcTqRWeEe# zq>!Q@gScoG5o{JQ6O*~{jAuay`Bn<$D05b|1^N;pX_r<z3{rZhmwKz$daoCIvsZh! zmwNv}2|l3v6bT4&fJRZ^KAZpwAgMoA^Qj8)49MU$!Ilp2fPV2{LMWu_uJsUF&3htY z68<+5#iv0(p%NEt6<9$pV8Io{@xj_B3FEfcghcILMqRbkKXcL=Z)mTyffGRNIiJB9 z%*0GuY=ot$8-8KNC~t(j(<>d%h1(OztmXvE4J!qA7Yw%>9%v4_p@Y2hg@1U*2vtl1 zi-?C<C`1^Ek^h(}umKuMK^q>$pQr?b{gY%%mV#fG7gk1P3e<@Nhk;#z6*`snK=l$P ziW2^J5(cv}Fe(vxCF3rqe(^vtyO0gYfDCA(RZ)sJdIMIOF9>=d2eM^bSl|N$@*TJr zkrP>w7kPT2S3DFF20|cMwdFmAplXM}2=2qEQWFcLYY;(A)S#zes>(s4?tcI4VT@E; z@z3k_4@SUMeZ=*_*s861?Eteh!~9b@+jSX^0UM4D8=5KaE)Y$-!5O+B@Y)0$K+DAp zg>zfD7bcGzoDyNV;TCYX90-9Bc-Y()mxUQuw45;`KvxGrI2*n+6`z6>skn-XC@fUZ zpkmi9oBzm*Yj-aht}lHn;)1I&+RO?Iv-c?UR7*qnSfg{wfHr!z<UBNau?r0c`2&VP zGaZ?tWv9GIV0WPQ1zw;=?L&B&6%f~#Ye9|ad{laX^fXM_zbs__S`F*Y)+AktNh{Gw zpA-{kc{pp?N_z>|+Ri^!7w)Q|Dy-o-A0ir*qJ%Z#8LENs)Z_!l1Q(yVad|iu0s*nS zAsePyaBE=>5UU$53)>LZ@ua#?p?b8=l%Aep8M2`iq(Pa~S!A<Opxjw+yiuN2mUd&= zp=d96`B^X}ql+ZeRDqA6QDb^`Hld9-r69A9Q*O|-rR73E2F_t1E84Psl@~T(=N$3{ zQ2zjv+iQ5T_9D}-YkAZ)o$g>7gj!D-m0P-dkaX)7<0N|%MrwNOa5}=i3?_|pZhQKd z>=vj6Xc`}o8=ljzAR;NqW*V4U8=U$U#z9P?n<<~!DV?$znqfVEthxnP-DvDQYZ!<( zS71H&28)98rhyZ{ff}xHomY1&h_J3<_ir@u^<a->^Vwz7YziyN&93lw2Rm3$^^A0u zc=fD}UKKcmmX02qIrJz5y5V^*Tf(;kT`Gb59MT7dpwff~)0$P10;CY}>ouziVXTL> z0Rck-j3i5PH<wgx!PTarsDX!5w;|X{WpXU&wkGK+xStatc1Rjd7a5LwxvQZeNdK7K z2%!r)%iGWt$;!ruUl=B0Fk!i&v967popMk6G!?e87{xlgrxJ+E8uOk}2a!P>bYT<H zL73h;xQEb+<2#<cYyg#zc57FReG63g+n*`JL$*hw4)b#0QFErppq*>a@bPE=Y-r7p zM2}V%B7DLposj;aY1hLcdq7^0fLiV&Uqo9+2~iAU!$;*;Hbu!=t&V@~FG&S>rhT*j zZVk6{+gu|UU30vGljKr%nG}8eK6z5eYX~XK1ZglK4J2qBvY|^92w($tVu9GoL*Ws| zp_{eb7cjvjI;%~vy1K(#yxlV_;f+k_(;-B68St|doRdF+8qVXKwhAy)!~YRM$q}DD z^&HdeK?jpmk1Kc!d%&A3HX74sp@noB+R<tCX!}6YDV@^IBME@&X@_+Og5c+Z4nKy@ z!@1VJT(gr%{3Gv|>QcFEy+`X}+tpv(NolE;Ak6HFlYVa9Wn2cALs3cM4yZ>Ab&&x- zO(7kSVaTV!#Y_xoSYc^Wfr6GYKArv99k1K1{F=4<JF|N7P>AxPeww{~aVNHg&YGMZ zf@6EAm)VBh3j&znTlEMOp=Q^<$qc^-<F}-c&mo5$4YS`l&d}?zcu7tSf!5%c*Jw9D z3Km{h4U#%|mEo)7AJ`$1gX&#;2mFev!`IhYMZHI(=jo~kLb9s0RsZ~@2}}}VjW;=l zre(>d*GD*Mz1H38EasLbcRZMwM0K%*QNckGdOjH(!f2+!fmq=U<{&AXp_y$^V6i?> z0;L%O!E3ZSs~=(7L!olbjheAu$_JIa$AsJ)A{lhP6ij#7N-wUnv2|V7u2WX+=iLdX zh_4%zapGRzEn|D!anLizj21JE65CZ5o1rK32w>`=xdkAC{L4qMpuvL(6DnNDuwlY^ z^9c6q=dhy1ix?N;`!_BGi4`qm$e^La#}Fh*lr(AbM2eItSg>T#LUYR&E?mHX8B?ar znKNwIz!@5c4xKxDlJ@!Y2N0k^g9;TwgecLXtBV{#f+UF&rT<D`D`m>0sZ*y<qehWh zOX}1qRH#<Tbw#)CD_F2($)ZKemS0?e1LM*~nDDM$yb>#3{HyV=V2~jT6K1TkF=d!D zD_h2SnKRDLthGXi%-J+&(Vl7Zb}P@7M%=nlt47-z?c2Dm>E5jyoA2Mhvk4zgeE7EG z+j@n<#4WbBZQMeI>P0A3^WxaEX9xb9w|Cs&!BZPQewz97p~1Bh=j`)m&YCq}Ha1yU z<ok{nFFw4hFk!)h*}@ksdg1j-U3JN|3My`$!WJo`d}3B7nrM<qSd~yB$ySg!g4H64 zP<2QlPyxbJAAKaXhf#FIF_arY{d7hdVu0}lPBzh$MgJC9OfiKNP(1O35=ta-L=Zmc zV1r04tPsKq=gfmoMpRa5<&{`wi4i>i{BprZFo<MBNkb%&(n>A)7}HEO-IUW#J^d8a zP;eA=l!{9=^;A@cP-WFsT5Z+US7D7+;aO=t*w$MLB1qR=dF{p5UjPnP7=QXH=2&C* z1ykQ;@oCnXXYDDIO)Jo3W12J7bmL1PX*6=&Gu7A@UT)s)#vO3lVYf{-+jP@RFM%`@ zTQ|)S(hGIHbkogoy+&KyuDSAdt9ay<cb<99XhTje+mJfyGNEQhUwxehlV7I1Al9FM zmEz*pfCa+x%7F<g2$zEorX^v8V_~S_h8=ncV*iMUj98+Hf2g>}9Y(o0RE#r@QR9s` z(xe5CJ^m<U6Gb91M3OepAVZTRTwu*V@M!7s%M-mU^UGX9Lct0vgh|7gK$Mx1N-e## zrp9i5p%YIsvf&0%cGBT6Q%*TmNS{?<<w&4h5egPrhoYsHT5G)(*IbU?rPqLc#p|D8 zh_TxkFOPNlsb%GE23mX0U<1uCu2$oXFOj67hBn(w6P~SyS8L6#zDb)MH`sJT$Suts z$IT<RU=m7m-f#mga*kuiI5vtSe(i19Zfo8$-LyhZGo-!;U#OOyYhS19vdbU5l?q6& zEC%9Bmx2p2$kx{pQfT3Y7!rK7!3QTy;{PB{ov0$jab!O+8$b0_BN#Ytp(DpH0r>>T zW{#|+$xW_s0WB=gEdTuU*N+gFXIy}@&NlQAgwH?=8cbwDG@KX>PCfz3(ul$$JTavy zP?;K4K6Eufbp=CQD~s0>wJ5ld4MF#c)PN`jptb4ZFzkXGr_%MQx?yHicw-efIH3(~ zB;yfRPy;izk(*jst90HOUFaUyjZhF`9Nl;hHwa<GWK<40P#og4s0G9-R%14_p~iWt z!L89WBZi|Y7pQEPu1%$IcZG?UynYuvN4Y{S`#K(kKJhPr35;MJ`Vfc?p)l$(EJaCy zSc@bEBN>%p3_1y)#yI99^Pw*ZL;nCm4@xEj7~t#ziHM*5Hp$6OW@IB`*uV-{z&{@Z z;Rt2|8WdhKKsIRsCtNU^7!oL_1vc#tNI?<Q_B55MS&c&%#NeS2^|i2xtx+H}o1`YC zHveGCZ7Y=9Wad*Y7~(A%zDS25qydd9q@fqK(FQf5F&^7|r;5E1q7;RLoNf>cS<j*l zA?7d+&q48?>m1JLN_QK@T`_g$i3T#nAq_)#;~B}oTNuTt3^JDSZMr+m+IojJ0s-${ zj?$O$)`C0<DNhr3<j~bVL={9#uX=w#(Zg7zJvhLKdp|)W_%f!Wm^AWZM1mv`d_YMU zu)uwE(4;3j8MC1pH6L8Ug8wK<Ig*l`GL<Y@rJ8o6F<8oymI`E`QIN6+T|y8lR6_&> zE$9_tmW7xcbc+W+_^3!p$}hHP=B3(}DaWKsGL&g(-R>5<Wi&&ZR!~+mc!;{%ptD-) z%qMh?wZvXDqZ{L(P8w2ytb1DaSNUYzVf_gn^OQy$vB*U_kdaV@c7~zKnC9*91JO*O zF^#?Rokb0lQ8+S)Ul8(_St<n5uy{oh&Lb&RPFg*c;*zB=f@#GrM$?Vi^hZH@WF(Vh zG8tS_3_?AscDFmfjXYtgA|Z(>QF$gIu~H^%vWWq~Fw3L~MXPt}>I3&Qh_L=CD}wTh z)-re&v?!`AV_QYp%>PE9Nu{k)YeOM4<0j3#f+{|p!P_&s)eKgop$nTRM>0|qjV#W_ zbhlF6=&&Khdp0MYp#X(*dNGG@I_rs-#b@Y748+q}gFIQB1~Q_N4n;^q9Lb2C>}D6A z`JfATa66+!c}Gz;ViZ9d#cgis_)&pX0=Qd&-XcmWl@eL+VS;Q?a+Q0?nQ}pVHMOZr z&KI&FAV~++{pkg?kX`QD`Oa3_hz>q5N-;T=ysA7eRkh%zShAOvbAqn}^|U9d-50-H z85D+iOH4%_ldY}@p$M4?n79VUnF_9JH19LF2iwhVoS86fY;lDvK;sshP{%Vm%*F8- zcC)-mY_C3NV*k$}>lTk-Y#Qd!i+aL1#+IEi6>-g*Y-uqX%}~cCrV)<P#Bj)BtjshY z+FJcA8Mc+GXn}+W<>E<sj&<xUSbi%~tRQSe#Qk!ZTS~Et*{HcY>e!kec_iwJ<fj`@ zLY?tU@Pad>AMB992Url2ojDaH<z*#I2CZI0kHNj~trLs5ny0Ao$xnI&rq;wlX*z=K zL5#vQq&9tEc?ky8DO4eYNu5_0g60_0u*NUaaE0k`qa4E^2RE8AjcnEGbUs8Z<D`Xb z%Qj~Yw?HC`DHoe#H(kcPqH(p5{!d$*2OH!VMmClajnjbfv@WENG47f>Z-4tg01}XF z>qYK2+W+?45lT0Pz~VgUCF0%jPAQlLDKR+IyUZBN(Z+bxNGS-ZNJe@yC7bjCAW+2M zn9n>y{=p6yJV|Hb4Fbf0CUNxE#HwNtgN(AORa`1%mrs$PFS8OT;EtTXCP(?D1)NO0 zoUJdOCSii<s-I1<@LZLtCTOz3j5*996v@y=HI~5*Xb^)N$S69FYg{^A7w77h#l|=u z5eg*U!V26d_Orl$^{i`_pZ;{VGrExra#+I|&oKMh$wfOOPloN?wjb{TZUHiP7gcvr zhIe|mcN&sqewQ$Pgi?UCQiHTThV(s&H$M6nU69vr>vJ+J@Buym50|HTSuznQn1U*} zg8wYof-d-iFc^dVuo34#0wKUuJJSQEgc3x;5-!n71%wmqb#X~!OLoFl@)b3)=V)Uk zD0^24l!hp5(I9KZdv@^(da+EDB788HLUu)J$fs9CrVPih4BpUuX@Cj6pbej)YBQt_ z;t&nw^kK}FPD_^^>~~q+a0`S0S#!Vy%@G@U*nZpbe*VNysiO^}VGXCjE&IoRMb=Q; z#%)SAQSmZ&ZB%aNCT0G@Tk5uMSe8fbCL$!Fgn}1H5kpAzCQ})>cpJD9=;LN2V=|T$ z0x-Z1_<#>GxQo2li@sQbCWs|mG7dI~gZ;CEKjVXH5)(mqKu7}=N&{a=xD-nGasRVd zL0L0$P}nv8g>q}<Ml1JLv=A6vI9D+@YLcOLbn`;Xa16(w4bzYYfprUoV;Y`?3_bQ^ z(AG~|mvp(}ea10}mLrJCKnPA0D}jhC_9T$WR*2kDWBzC@w9yO$1r3}qTKU(A*M@dQ zrfrn5T9FZe0%(bGXMpzdWcji$3aC8H<6EIPQda?Z3u7V^NO*-uW*CTX`sR2bQzRbP zQ%(XUxfqN@d1qX*4Ie-P#;Aj$S6*oXgr{d{V(^SXVM`n5K-DOF_l1p;HfddRa$!RX zRaiE@CyoIE7$y{I#TQNg*FvV|j_^1KR{(X~V0Ia)W66*X#2^ak&<xFRYyY_dm_d{c zyRvHnd1BCk38|0@X>de{$&fLIhlIIoff<pzaU0F>4CxRH#gGokkbUT}e+=c3APE_5 zCx8Q}3zvwACrNGzs3^(9TMS4EBK3gqHj}4FfrV#yFjZ#vc4mvTlaJSCvsg(hV1wf@ za7DSCoWv!@pg&7#5<G||=S4s?VO2xuUUYIxN<obtr<G0Em12Q=#bitY29CZrLgR>F zUASN@G)>8uTF1bMgwO_aU>(swDrJWn(;$Zg)e3$2mx6hj-8W)*2$=)PhvY{H32Ai* zsvTO#Y?%31oDdG|0h;zGn%PF0xFeE@@mi{RiB48`c4uz=5}S79TmQ7lAs-@>engXi zWRrA4W)@>+Xy#n{hEqu(GR5gr$f=ynxe!Gaq#3~_ya1j2!<10f1X49sRkdF2RZH7h z6s{*<jJAXzhZQ2XU%1zeVKbIwxoITyX~TDpGZz^xqzu0Bj@s}D_8AJ@Fb&EOL#iW( z(;yD5pbpK@VOVr61qzVBf}qe5EL|{JbC8gN+K{5NPn?Bx(O?bIzzK!Zh}!~2r$#%N z;ZUp<b8i=-CCL|bhk$nno9Wh)8Pb4T(W0b?n>Cq=GrD>fgE7FFW;fN7J1Tj!2yoi~ zq(rI^5b>+P8mz)Pti)QZ#(J#CIuGyg536ti3>PLga05HgGylo>1X2|fSP+D7qIz-? zjoD)-co435&~c5%M`8siS`i78u&#t+DBSo7-dKgKKo@vXmcIvAF9&MwqAAALV6|fm zYg!F$I&7hU4bCv9q%vW0xUgk64c<@;#ejVS8bo(^piUQv7@M&gYfs`w2#s(Hhk9aF zx3MH!vX|w4lv$bM)C~~p4gJZma)^I2Yg*${hVEz?N5)zK2%?@EAQn|G^$H8FzzQ0* zQENeE6mkj6b0J<a36T&9&*LE>!be?(Qhy+>c#w)N@>1QCdS8Gs8lwfz1td@)T|lq{ zJ=G)|zzhHI4$1nqa2vO8+pAZ?C5zy!#z-bmWvzl1w*S~Ul|?wETlIR37D0XTcfS;A zx5qX81(ps1rgl-U%hYoDYL4!SSDsQIIM=3c&;^Zff5sp?6V@K8V;;}Y4C>(x;;^S6 z#*ZQfkR%3~Ps9!5P^i?=pzD{Y(6Xq8SeYRvhXT8Z<J7RB*&YiOiIVt#9m=Vx*|X$` zHo$X|Zgh8?=us)^lED>|tLjG&6r--{Qiu0FiiD$$#DP1iK54rG8vs8oL$~fbGh9Lk z8^8j_=mRFPw?8;>L{l_}rkzYPxLrlA5#%RZDRLOZxEnNukozd%I6`q%j%-7GjDe2z zAq<9t2|U*bT*M5hCS>-wE!2Pv_{a%A=9iYK8~-P4humS9g4zuQ`FuxYEDEW+pu@W< z`$LMerv!D8$nXqWq&kndp_&?!9@;L=>#2V+FQ6Jcu1UQdg>D~Zsw<kR!evrW!M&#_ zqZSxb%ynir%6J~bX6Nezla#A0umPIDtGx;l5&?|w%Me_02lHFM_ZxB5sjXM#zjbni z-Fc-^QBqBqjfH~1UNeO$XN3$bxo9I-5$uH&91PvU3U&}H6Q&Hz03QlPr=?3;>5vPe zP!6YChbqh~+9A8#phQg62p*e|l|{ptHATIPYZRFdme85c0GdEdvydns|5}>ra+)97 zE+i=!(0hPQyovonWdI|^c%(;M7I@xUf&W{41~n?HU%Y{0%%f#oN%Xq`f1t*19L^QN zC0sDaI->(UK&?F}K>8b%Qi*5_w8sGKRlL+okA^kk>8_o?K?;1Hy~lE%Rzmvf$Y;t7 z)nE&O;JHC|3>~}~#;eIMYr4@uP@9kr`&b)^qjZI7v4?pqw_pe9#{`Y=EF<g6uMEo% z*{B#jq3J-v;t<hx>WIe6k-W^I9qOSxyP8Yfnwkg~MhnHuEHJ3*cT?MC+^bT$sfw#d zBfmMT&Q-o*3`t1RQ{4;);2flEoDV}P&I-XLQXon#0IemV&ZO73?wrTnD!B1QuDnFR ziEDcY{FP~;7F0+)|NMKDOQx3+bN?z7lFTp-vtS2Zpe)Ydj>>m8qzl5@w;GGs45GX^ z75jaO+6}2db#qxy&XU=#456`nSk=%B*+34Q;0;_<c0XLaGrh~^;(xwuMrSn4<mfx0 zT3ZX^7Eg?#%fo=#3nHuf6cUJv(rkE3-NjB#K8^%=(?!*13<g(Cw_DBC_wx@)Fu!5l zRHg(#K4{j2_P6l7omXk4dSZ=;3n=+@zzFQPyEkCUG(wDgLhYg{iP5jW;0(MF2;S5S z&k&!==g@dly8US$<v<L?&<&4ThX%^gR|jJXX$O=u4uo(-@D$-R%-NldPSHSr#ZV3b z<=;WPp*c&$zi>vv%w#@GFaMcXZnvc<rE01fvfI3!FjxFXfi!Ppc7chclRa|W>9bRC z#?35n0a@@5?f~6HjuHI;1PfQ)p@-e<Y@OQ;rQI!!gzFSn+)LM3-e#piU<qLUe1+=` zeC@rjYso3f5Db^lYRQlc$3PkS4PoSRZT=ll%@7XjvAO~Z9)G&gzS7a%kPX~`3Bg9Y za#=Z<?JN`SkT-mp;qjN^AP$@$Yq(sx9o~`JMjw<IQOzr&pc=g>S)wL-JfpB%*9(eS z=5FtXo4LtS60?fLea$%@Btudp)79fXrM^(`4^vX)x_)r(Km&ZH<bURrO=@~i{?6`Y zmGcaHQDNl;EXaj2O#fcmL0z86={X?s0>S(t!AbTDY6=Q-iQg6MLhQ)jiS6HhsSdeN z!hZU?kxd-IGKh%TSj{mGYLEuLz*z8f=r)|v{Rkd@xtXQVmyw>!sjb>Y_Ti>k#5vt* ze^JaQK0Hp$Q4&%|%-naQ2;(pMWl0Ub%2my<gl75n>N+~>xvIWN;KsY2@&uua?qCDI zF4p7al=(~Sg@)G9i0ns^OWqkl_T21}kRfK(xVpE%nFc9Z7|@k#81Ky(ykH-oP^h=y z3zi-X|GHOi4$-Ci@6b>R<=_l=jw>3y!llfR&$5S)ppfG*2M;c?-jKVAO5ur)!i!F! z(BKW!;KOk~>HoZ(ysfS9BTj(N`?C*UqAHop6fe|x^nlW{FxG<<0MkG$zp6gX9#2yt z|09kU>r(A+G5~M_r}CU{5dF~dFE0aQ67%ak^I==_{VS#NY!q0zCr`nIzXaDoPe)HI z?Z|Y6Wy#*`Iad<wDX`E5T@VVlzzocQSMb^9nE@X{7UwT3eX-`3%m%3JB)e(f2uMV` zX<$UnGQ)=c_Sym2{C-%VjSizN4ztGmdcWFyf9bB(shU1p(wi?4&rv8U#Y3&Ci=Xk) zEX{?)#Q*^Y3>Si1v>eQW1<MpEQlLChq9n-?AU<@^kRgM`iVaHs<pUW~<VcbwO`b%V zQsqjPEnU9Mhp+#iI~yNXw17c_h7KP=jwDgi<jIqUQ>I|aa!|__f?U3U5i{n@R5otl zz=;!w4xKxDy!QD6NbDf8hY%r3v`FnDN01~*qEtz)+)SD@b?WqK6sf(WPMt!9YSk)N zg$=)Y1q+reS+r=`vV}|XWL&x|Ti(Shv*usQY^6z)$`><czk&%1c3PM)W6D}9gB@Gh zvSrGg-M&3d_wL=%qD}Kw3>vp+){Gyoc3in}Y|WiF&lX*}^ljCxU&nr(+pRghx^?5m zjnJ)7n8t<Yw(Wa%_U*S#hi~n<^X1BuFOSx(STS$feD9`)w`p*5hPK*dldUylRzoc{ z2Y-Q(7YY9-lrXbhF0+iX$!u|q7RD4q%&@`+TP3hlNI?<BQ9i-TE=}gDgc3?5fdmpq z)><TyvkobQEU^Ij;}5UyxMQoVu5yEosm>@v3^2ZE${>UmV(1}=BswApi)_efqYaYy z2qrPdB(qF2&n#)Cnr_O-2A+aI0w|$~lENsYlwyjYr^F~@$*QixYAZUt+5@Z~$tuJw zv~X<et+?i@%dWiiO3^RC1S3pDR}fQdF~=a=a54;av2d4PjL`)&Om1OD!qgg6jWuIl zLvXg*mML%<0R^n48fvmZXA^J4iKZF*>N{?}=B$BlI`^^*ubXYSS(TgbxEZIBTY4cR zTJZnUllED0n~hGs`H)3!xn{)CW)pOXqb9&zcf&Q;18bdiRt6n>ke6R5q|m}qHI$4) z4?l$E6-`|s(Zmx|T#-c=Gl8)Z8g0Z;M?`q^5y(IKAXLyJ;Yf1HCZCK_se~4CXsC!L z(ozR5HR1?NG;hW^XPw7{=bt1tV4;OJ-~1`4p`fVqsH6_c(<!L>q{=F+wA!kxLc;=t ztU(ezE3LH}g$u?=@%n_)6#oj0L`^wetg*);BN)RAGh=3#G`e^smC{`0_tn+%rByZq z37mJgUYkKCom`~xrr2H|N7r0s$<0RG_PFWgk!Gy@_K{n-nZp;(tyQmd%h{t`*=7IH zef;osr70#I#Ct7VHv(y^6}EgCg!RD)0j_YD3o#@ZvJMdrQN)H(`K!{1JDC{98EL$6 zEsZ%I<i{X~6gdtgm7MD2feKQY%9gK$dCM+YxB!cP;MqBT`RC8MXC*dZlLj|?DtgYM zl*Ut2_5`&v{Ap@}B9x)VvNc6{O)X%16kS}zBD0+>ZG%}`Vie;x$HZ+^yQte7x-f@O zIHPX72nK}u7Apk>4ng(GP3;aBjda9<6XlqOv5eCzbg2$H<T@R8vN4WF5aK-6;zl#l z@VQ%H!du`nT@bI6Iv++(UFj%AEMylAUjb-WxVcsCT(i5?tPn!~0-k1uM?C)x8O$-r zTUf)Ir=o~S%q|q0i;Sq3u^sg&dmaPX9*Sfn?~#lR;2VRJphUhY8RdL0%aZyu!oDoL zkA9aNNk965NluQWXFm(t(D)~(q5SVoOcNkfq!KkiQEgCP!CKZB*fmDgC~S~&(WLrf zK};=-Z5(`?hAtzSRt2I9gb2mnBy>j8^o>CZ664@-Bg1$#V_o9lggUH=ocq+rhuEN; zb)+@U(v1^5(hAQUZgC!TCgTykNT+wcwH|Sn)1KrE*L%qIO)DN}bKuxSImFQnF3M{f z2Hnl=aEC7i?TcT`Orsh{rHkUZ5qS#J)L={mvFEu+6L^f#jA~RpwOs$tkJ=NGS40M= zl7-Jn<Ku#qw2%--S_zUd;}Q&7(1Ht85`LYG-#q345={aXs6A@}(1fPH9spqo{S%5Q zm$sBt^2tw9%L)Qvd8k<~>Va*6gp9<NOTCQ3tbMtZ+C=nA4uVQl6vc%wm_djUCKHVj zV&)2;ImX;cGlqq0-8A$Ajc)J|a>)8-IHmZW?KqKi;dzE*$AQdoRL7i)72-at*iUOv zW3b(rhOfG)8-&{KHU_#^g2>pr)SNM*!kZ|;aA8qdfGCa{WuA)oQnnV|QF<36X^#5X zF^`3eklzE}$rc&Y^3~L3Si-3cbjpGaU|}9VHEMRXtFxYML8<>T&>zuA`2?idX{t>d z;8k0x)vGPAs}5vKjl?=uyOiw{y7kKiGj$jZGNwatql_(nG1o4np%JaxjKBV+!e;Vo zuP%&@U!74n-#jjd%}@s?#6hg&@DQ;+RIKHqHLdY@3p~l_7PfAY;_rYbikJl=Kdsn| zYOsqF=|BdJdu7nl4(PPD%H6D7<51uI4tTH~Sn-Zm+k|1%Fmim@UY-ZNk5){i7_;7R z{|KZ&4w4Qdg9G@^kVup<a;E09DRkAR(-v$%43^yP&4fzSO~!eCJ>vq<U?563B_Rn- zh-%VKNmV^PO}$rfrPUNDORjnKfo_>EF6(Pn{H7IyYwiCpFyRIn2|eNsX&^)}ctNU& zo>8xVb4@g9L%7<-tD4P7M=P{w&BJ;V#P9(pX1kG!Ihgpw-8m1po^eilVzxTj0H?Dy zi>&()G#!@6MLMd{jL?qupkF+#fr6|rBDdDHX%yZXGgPpGb?9Iqa`K2YI!8L%@uMJ( z(Oa-wQZ0)mNGbJlAq|;aMW(EgRdSi1BPp}>ZGaANwsXQ2&JsL-S0~~HN+|`Mg{7g_ z&;>MLR=J|+SY~e!4g4BdZz<`!m<_G^&0wcA4H;8m;?soi#i+wwY85&Y)ewdaYNtuf zcyUo2;b?{IjOAflt1iSr90v)HIJ#s28$6hJM700HQ|!f34%w=UTym@#>u?NIw6r5F zw(XVL1P!^24>j_Ukvz;cn){*|UH8LO#M_C%n-Vpew{SOhQjeunkjLHkRLHzsnbH*C z5D|EEC%FMQAbjCwD(d6w_Yd!eQU?3$bHwRn-T)Tbsu-7Apth30j?Xd?@D+KaGch*% zRvP7)R{4Kvp^IN&!Vbrj5UEI=V1Sw0=B!C|U;SFUYWJ!*;_yZ;$iWR{ScB-xNi41_ zC&eUo2Z>B)G3E%-i*a~k#QCgxvZeD)Y-HUU&Bz8gaxpA|1~%*h0;9GWx}a{S@Y`yS zZ5wH8Tez2q-Mj6rcl)i8;-kImn0qs>FDw6~mKw8{^0zZ{t|pL(^dUGIXaVYKJnWLZ zmzcABh`bF%lb)f24cIC0!n~g#C8?^os#>K(3O!dMJ+5lB)B74*iXaIpxw5Jhv{9?I z+8_?X1zx~}K(GQe&^=O_8{X@^nscz5!#N2fzOQ>6ZUBc;7>8-tp&l|iAQCZa$p&hP zy6d}^XGpQ|n5<AZk9#sUeQK6vW43B22TmX?8gn(UE1dXSC<FnV`t!Ee5;wTgza?w3 z+wwoT+btG>p4GE5ybCUqI>3)fKz&ORMCvy)GrULgvmsEt3*3N3a6AxXi4FusoavcA za5&5x0zWev6+|V^gBllHud3Oq1#15^M5rZ5yTP&1r5yx}9^|jKX^dT91tOdSTbL-! zP(ljvy(W|uoU;`eB0g%6!fAuGR@en^s5RyICN^}IF8q#Ous+UNk8U^y#{!RW2n7~v zu@{pfD#E%q6bEV8gnGy^=i9M(sU18dyVz)`GCI4~iYPS_H`y|tH$pc;%q`tAD?3ue zJi3^?bHpv%p1)JT1w16dt3>AdH%v?dO<Xe=;D}22#8D(kqw1MG_^!))lT=K>iCaNe zq>7BA8mnn9T2vHAOFgk+y-uLCv*|@&+?4*(1zVVeD@cP{sD;Xqj1LkXnrkozd8T|3 zzE%4x00|IjltvzMwpeHdder}+qMIBpJe_Vp$46MY76XrT^p<T9HndzvV{=Dk@uu^u zMrbI9XBawH)5{*y$8F;_)L^Z&3z)S7!~nCXgH)d7F~o(WvWAq4=^;RRt2aQ3M18wR zCUHPUqBt~r0tw8-n8AqY+5k!z$&xh9OX`_EAVHi^$(~@zRdmT#behkD#RD2WSPBcR zsYM6MN%|t23bGVTxirH75n8~7OR$18U<F@L%F1BMrc5IyWJbW5N@y&ctb`nE+Au{x zhi#&dWVy9wIi0DStW-dcc}h#i8Xc&6B6@-`&3Z>|JU=Sbuz{imd$h+MOQ>wiL)H3A z)j&HxOtL^U$U#iZxO4v=x~nqjxiXSEy~#vCic~=4!pJhy$d!q}3G~Q|$Ouk^gwj0C z5Z#%c(FCR1vz_n(r&7g0<2>0+FVI7@M8i#4DhpbwK}f3@UCfJJ3Qk`P5n0d$RJejJ zz=TxL1>*#;rIedwT&Aal%9~R)s+_P^t3!X%k5(v$=L63z6whZFvF)$}?mMR^!UT8{ zN6c}$?}JPDl*{^9mvLx?<)g73(o5p&%OEp5*6KrW`$K}<zvMYk=2^@YX-q4Vw|ToB z?6Eh$+XF(f%q1Z+m?}KZ^vsT|2pb5^7T}0e08tV3)DZlKQ7}>P;t3UP$rdHF*(4yD z6cmobn(UcD-n9S093?B@3=H8c3|3%;RbT~NaD^_w8&){d#~`=2LPjQ4FehapsjL;9 ztIGG=%Wm2_MPQub0L%F}I_#Lb(&2_cFwg6IqDIh#Gu@o=IHGS^!?-*bH;u=6bOs$t zj=g+8-ndgeT&)#Kp@0lGHY(PF^bo{M%v&8)hBQ>*vK}2d1RnVj%2cU}1Qaog)Cau8 zhp5ycxYSJL2wmt@PZh;aeTkkC)u1_18%WXDWKjTeQB{h`7i`rT)y<of)mbIEyXZ+2 z;lbf_1rKS1E(ion7*-AuCW=~8WR=b*ZN@0I&Rx;V!=lC-;smc;oh=Q^F1;LZ;k9wt zoa!(!@i70-Yca!AFrxHW!((I9byXK+s0TR|hx0=YdA&pa+{ZEc&%i_@{Nq={JRX33 zvJw$gg(Otp8o<cZJ47f1z6+8r1H8a%Kns-;3~dOC)leVs0Zf%HP2B)o*jSI%+>iZ- zPQV}5)Sr@F(alqumsC|hVS`xYimw2R-0Uix#JfnVgh<Ij9=+9GS_Q|rJv;DO5AhJl za4TayRwgZ4ziGxN96kYw)>_lfbWj9vNTTwCzVL((FHMi6Lql$uzVqw`Zn1^Y;T&+Z z2C*Gmb$t$GK|gS~A#tDvcx@fGrB}H1OZwAO`{Pr>46uSZOal$rzJ(YCg}0Cr+`%ne zABq1^ip&a&q(sJ@5|(Kh&qRVDkX*`z0WYzI%-!4!R*9a$1^i)wk!`9Wh!dkhnmSPk z(-jCX7=u^LxR#woM1ffx!Ml;0-CE_*zW@cnK!sPJg+N$?W3q+V`!Csg&QfcwCZx{l z+&QH^sMhJG^Xmp^2&gBP+NteEXt5UWyM-|ITCE+O67$+_@V@d05AP%2)3G}8LzZcP zQ#rMd_q9{`oj>|Dqq+r{eZAWaaXY;w5xzA<Qn0T=bx4C{3%%o!lRDfX8KjY!#PAsd zfgrpFW{3yI5{sSO(DagNz+esL<dWzaVYq-5_+S$Z;Sm;!5<ZGkvN#oHVXSiDn$-WA z7{1YwTRj`*#lYa<NBChv&{bXCAahGn;hnkYEZ(Se#%EmOdD+YR^rvX3hfN3uZ%7vT z<kBnF*2nTzsS{gmZiHHpx)$SxWC#R#TGO&MTjQ`MZ-@nV{YvM9-+949G1|j_EHXbF zNF~c#{#7?Wt`tE2+Xa10d2@tD>?1^mL_u0)1$JbCXo?F}h)IUriLhh}W&sk|fNt1i zkJY4&=ID<0=#K{JkQV8YCh30YnP3RzQD!P15aClzWz*f0RbnO4TiscdrG)L8n5AXf z-9?|=6i~>6<eUXx_T{!2;-Fnpr^HudMqVk6MqiOe<Y)$JNC#;s1))Q>YyJPBZ1omi zLyv0)k6svOZLSV%=munRv8qdBxs2N8u%>!o1aJ_#wv88SgXehOHnYRm`@7>l#piR= zXNJM8KW5B30x8HG=!4a=KRW1qI}!#QGe|B7nR@6+?o8;qSm~<h4cLbFDe2D!?a(Ia zfA|NE?&Oo`8Ep6f5>RQ9bt+RPFF{jf7F<<Vmc_1Ew6XxXS<b~=+R;iu1y>-2Lr6|m zkOfwFg<e*<w(_9M7-nL2Qr=187n0H`y-w`B53SoUP5=kC{V;5`I@H15G`wbS=-$u) zU(4!-TS$Y-QtP!oU-_tyYS0g2xI*W{@AuWu{p8R2rN6zl<G#M<wtN30CIi%c-lzm6 z*uYI}$y8K(0~sReo`+4YM=rB1XxxW>+{;da2+r&ZCV>zbhm0=Cjy-LY=$UL-?ba?? z*d_|2Kv@hgG*({O7}bid!0jLzi^ARQN5fH)+tC$4k->-rE9e4HU<Fuk1>`OawmNFc zn5gGo!lnKjAyeXHp4Yv!kIe}d_S3>@?#3(zk1dv`ZS~@B?3T^>7OBge&tb>x2p9AH zPGr#rao7ZPC>HyuLmm^mv728$wBLw2LbfAtz&>zwbC?9BG69?mfo^a^?h%wCltwiY zmb%O`u<%8aDJ`H9fP0w;_JJOl84xFd5!b-e{=gF#iJs|(5Mcjp7|03NeyZ_Gniy{y zfmq=hpPHG>@mJ+>8})G-_NW~E1i&crE4Tz!7!hUvMWYTTq;_uT1fFFy+M^Yt*<iKn zu0v^UhI)`Sp)0?rl^pQy(lVZwY`#A22;Zp7TJ#v5TL?ol-qsN#TRE3r=8)d4iv?5g zN^Yv_{pN3bk>`8u8@}%A0ma(_*XKS?@c;EF$Fvyg39hp+K*nzD30GY4(e&~`GeE24 zP#<*`2mu&4hkw8aRi`tQ9|?T;hj9@3P|}GI?w?Y!lM|Lrf%v=v!m6wy5<=1Otoe0E zV+%)c6#BZ0PPhb8ScOjL0xRfQSGb^{Z1PO|uV6k#Y488N6gsul(48nH5bIXv)=>`a z#3pTu91!D1XUPV#4251Zb9Mj5UQ=^zEm!aG2KI>a@Rl(*<py<7gbmAcI(5IdRVaCe z4L~>e2`QC4*57<Sbj9rFvUzwz9pH#u)Jb2d?}60Jyig2fh|5+p4z)m$mjQObhm%M7 zR9AVHKL;2H0X6|InJ1<4GOwj+=oi)bR=ROl-SHV@lt#J18g>z=Z+bnzghDJ4!f-Mt ze{$hHR;B(uXu9%eRbD4{Vrm$NVrYeKu-5Ok;x<gWZ>`$zxP>-IqIAEGZfN`NbN4B- zy77z8`ap&@#zyOZ9DK}2g^Jr$qvL`Hh+n^W5iI{$aMvzf3K!yP=+KreS`uZ+f(7f< zD_0sduIji7)hSXUMUMK^NfXLUl~z`wL`f1PNRAfKOq2)_qC<rS0qXhZ&z_)n=n#zq z=cpStXU>!vBL>VDE>gE>(UK(#mML1LJZaKINs=Q$eCVJdLq>}gA7GsOhc6%8xN_&x zt!wu#-n@GE^6l&QZ$5ne*va_7qQzMoJ%9{Bl0=D;Cr_kkor2|R)h$xFd;ue7%+fP# z*c^ouCl1j&LHGRZIjB&fLx&LAq`AmZOi3<TuDo=K6sj&&(hz!uY7}r(9ye~p2#caD zi4Yx9*M(~#!d(Up3j7u9J9uH@jTuvB{`~*>W$KqXYwv6t{P^;zRjXg$n*D0lnx)$$ z&D(z1STi7j*cf==f!Qdy;5H3z!_6&i^wLc?4?5@|H{4Lz%N!YUlg)(<ZWu^18CJ+m zgA1y-;(`bwNFa>O@E1!f=~UAUe)r`^jeI>$<6e8~ErZ^9<&h^Icu97*ok0jKq!4ut zMI;d|6j_83bFO&w5lADEWD-i6sKk;>Fv(<_O*!erlTSbiRg_UkDYcYSP;Ew)Raj)T zRaZ?U5!P5em?Z-XD{PR2TYxFLD5H%!`siKw{G-GMhn+=(4n72N#A8Y{F<E7LW|7%u zoqbluQlpi2T53V{(HbDH#fDQNw%z}h+itv#f{GqqbTP*&q<likDW{;K+;YslV$pNa z(J~!Gwm9^pE(kGMP<Kg&Ck%Py5t*KPK>9chkJQkYpMC_&m<~9K)Pqbj*$4>ZfG!%y zqJ!CR^T;h9Hi%+~CU(=yBiuBDVut^6<Bd1mqymbGDY7`Rg7zLr?||zn5>7hs!ia9U z<nkyVkV1ZIUbo^2qwRM~UYi}Y4@Em=l@(o?rIsBX8<LkLoh0U%EJ<SKOf}(z2yBC} z`9~kC4MoRkagMfBQ%^<3#TIyCwWkzZef6hUWDQ#A22lJ152R_Uy*As7N}9z6D<CEV zrkZjJ*{5A=B`T>>nK}llqLKf06svTo78I;X!$xbZG~oux&}4RUN+4@k0W2w_AV;jR z$aa+FvKCP!owU_m_oTJg@{(<M->HmpdEW{t?zr%sTaCFGYf}y|#dL!s#`W5ZFNodT z@<=z<Yy)D5Cu%q_CLVT^@bm~blMEpfR*22=6tiftfx$P^4Kc%v^NcnFrfY6}=EmoK zd_X#5^0%=Yqw>ltgXc1n+9mWPb)ZEhD_tZb%<;(1Lb5r{feC25sf3x%geIK8CRTv> zNz>j0wK&0HYIL&NovO06t#Ac0U>l1LY;YE`(cx@udm#*C*fx0l0}vOG8w}`{sZIUK zQ%`^bWh`@<%xH!)o&o<{ss?8oq8M&9iIdfAYU8-axr7p#7)9l*&;?eIq7$Fc+~$bo zxmAEJbkCvEbfR=R>}W@ItP6(zRMxH7$u3;98<)BAm@XJagFlLphByKgJn*TgLD=X9 zCU`NuiG?T|-3Ub>#&NI^VJJg{Xv8?QAu;c@$YR0UPcy_JjZN4HcreN%{Awq^^_)x@ zMjB5X_a_k5@xn;}R3k(N$SeaMP-mzZiRLor#h(RjB`=AI1Q(Ge*(hyk8QcRCqjnSz zHU$h|2%!k|v=u0H1uRJz0t(FngS1>=5iXP=I@77nz0j}{H)KH$X<!3QHRds&0+kR) zrG>2d&6=PIjS~M0cZb70@inudjjeDK2})E#6PJ(!6S{B-P-vngUnI#$jJ2gQiq2VS zj1sl7<3@q7OpYjP<&f<7p4!<Cl{vD{x}dR%cbSr2gai@utig@!Q3$7nywD+85sK;o zjFK8kg&iuSpiO!Ye1lxqCcx1#;Oz*NEd5c*)YHn?!IEYC+m0=78Kq|p&}KM8V3$aO zoKbY5ttolnF=Jw@o2ZE=&eWhZr>T@ORP&ls(b}G-AO$Eu;cG|$rw?o(&O%)v80TCk zWFxCi8U`b7@YJCX7~>cp0&#Db(dTB2h{RN_3N@|T!>j%fE5#kOaks(E&^nO_CRia7 zmpDmVzZn0<jCu}d&N(CL)VRil&~kMo)s`H)h0^uh5s&tv554qL4c-xB9LWeD#=z$w zZ#)PSq0k=ly0=sjVS^i(xJ4!@`LAu9h!C|%n0Of}FHe4QeB~R5ey9=MbHQ(9J<6(9 z>-S2Pd3BaAt7Xh^Ni&;ash3<T7BGc1%(wDpXvm!F(UR7t3=R}datcjfv6&~XN#<+c z1VUmLOM(ql<FS%`F^ttlLu-V91edLw4~EdgPjz;0n9)LL{mEC-y1_K2Z6azD2Z%x( z&9y}nQx}$?heu>WOepc<MZF}(WGO3jqkERL!aS{z((;W-O0Ku+sM3|P6qVAYS0B^C z2xk8TvKjM&k#?8oje*S}8Iz1JgO>N8aXcav3{$U#mY0m<!IzU2qc6SIB@IQSLq_<a z7b^Wbu2r&9z^){4fd}%kutG^nVb0}5Zg$oO^DLMqX<#v1f=ozYn1Vamu+!jVl%#-o z4AvC!2)ouNZw>*)ij@HjSP%jhoMRqui7~XJy(meY0|v{Er(!hQsU`q1h@Y)WXiXJ3 z(G=OpOk7QBS33yVFwQoV(8L<5(1kz%&5B{l?QXZsWsUsy%O3?P>e_fMGrP{DbR^R3 z+;dg>xH;1Nktt2@yvLhnV;qDagd{)2$>lX;9CN_LII7pk1$ihCx2O<PzXxeNYfS$d zQ{AI<t$I}e59wqBMv}I^3fBKIM8RcMwS#x2WsCkyOb@iMTy1kS+1&bqOw-^7KTI_c zPNga%=97uV0)!r@5ZTIROQNK$wtn<O>@fU?I|_4S8|Z*Bck`j%^4T{diecPrDEAVP zjJTgPb5^vel_M%)2QL&M4V}mYLse4cD|>Ob#X8nTo8ugR(?Ynztyb!oL~uA7e7S30 zc>AC$-TV%y9Jwe4H;{2>JX^zF4Qj?S=Fl&cQ|v;|uy`mk312`f$Qs>f1jaS#Xs3#= z8^ahzIi_Ka+r5;(^YIbQxB6+E=iI<Aqn34iJ`o15`oTm0L<5aZrnowyXmtP0$xiMH z_0ve5DOAUr)v-dtZvF|eTt7>)H=qO;o4x=3my4t{fnnqjX4R8DO@_B&fz=fe7g*D0 z08~Jk*5Ra^(k$6*9D+?q!Xm6e5nMqgOoDFk#^PPsMTJr4L|$_+i@%i)z_F3QZAW)_ z2Xc*vD;*rTtQni(QNv+OocTwct)B282!>!n!2k>+bx(unly^}`qKQ|&Y=br=1Bv|E z#DEWW#mK{PLOuA|$EZ)H&0O?(+Wp)Q%LIeY9R#UmUzDI40X5i0pcRAx6ZjQfti1%$ zOpvXy$p!TRheear%t_VQN!3|}{0WxV5F3h>#aXlf3v7TE@ZbMMqS*gQiWXD~0oDx< z9bk{?$pV(j5kX*Sofd1T)@u1(B1FO;FhLarLL|h*LWy9QXhK`%+vA}izj>LnJd1FJ zROZ3pag`Leq?wwrM|1f|roGu7;Yd1!!zQSMi~wQlxgMYO!i40@5hkH|rGoAi)rtsO zcd<f-_|%G6p-o|fovFhngo8LxLo@8rrQwdusZto$&!>@LsHqOjh*bdnTmfYX9P*4> zg<l;;P|+w8PUuAX`2-*06$epM8Bkr;WE0mMV*MrJpfKVF!~rBqB1gg)4I#n>SPI=_ z8>eVu0_qb3I^aJEPAKYKy2Z*)Ac7;z))KryAXtJc4h=)CL?-`?peE>6=I~Z;flf!E zk>&B?3v$OVhR6MIODma2!nMa$iHsiQ$V*wnG;{+wYyy6L5`rj*Hgv<qjYCoK-gqg@ z9Hc@waMuwk2zPM<hxCFGst7sOS2t_|G$h|kfebuq+NQY&{cKfNRiCK!Pa0a@f-x8` zX-Uo`kd~PQF~u6v(Hb5ylO8fn(+t#5upb;G1t318UttYkk(gH?Vu~RfIXS{ccH~}= z9cwxY4Y@){&W$`RhK_Apk68vv7SZ2;BH<7P9^iqi^g&Okn@mR8<w$}h+zRA`AWQgU z<7wFmk`WmxOHmr78X@IK$>5oF-pNE|4(ec4V$6*oLp}ctgD6y5O$Fh_a6=mOOT(BY zgW!}-5yHu_<;HEpGwc*52_K3)+RCX5f0)8B)Wb5=6wK+7UqT;Xb{dg*OH)#xEEVR? z@m#5`;gqzY8*+p%0pypsl>_lcTv4Xcs7cddkWf4gXL@F6IK|b7rbKSjSAfM~8Jjqf zlQ692YvP4#?&zY>5HDC3w%O)pMFu|c4Y+NFkR?$|4uxt^U?Dhy98`h4RYE~N4&>}4 zPc9z5NvB5bn=ABNE>>Q4@?x3sLK)&u4Spwc6=RPu9Q*7gOi_b2c*7>3!|z;SfpAYY z^g<v!g7(NKzHkHfRAb7qh=-&?AaH~7%$F5H<ADD}!#E5BFmxrl*av>F5AJ|rkT~dr z-dq_D1cf$<g<j}GP)W^Pi5pTUtM!b}(4mMPQ~6;SLRyg1^<hzzMh8(1XufDfUY%fd z6O9&I3aMBKbc2riXkGNEvi=1PWkZdv00Cy30m7YU4H1xe;%KP~;T+jO?VSaBfe>85 zOya~8J&tp3DdTlQFlE%2R%e%8r!JOhz?B(ycIS8qBf_<*!nN6@{_BlkLpmq|GXTgS zVME1*LKn!T#tAC(C<r$^gB=*E_ZZS4^(i6n0yprfqXsA_rNgADC%`_}bFmbs1(<*x ziG<1$KBl1>?&J0WT`xJN913JHk)N#?Bs2dN=T88IW=2zK@Y>V~BK*auu$dSVpitK( zTL`ScID}oZ>IJh#Eni3qJG8*HUCIvKCfs?OKJAkyo=U2eThz2lAK-y%9YP!|0TcM0 zx!MN0YN@))Vsv`RyW&ikF3Xom2fe!Bz-=D>7>Nx+C3uGCn`-JO?MF0#Y%^wqon@Er zr6pNLV}ewyygWl1$mOA~2=zG3qHe>Z>Z!VLLpX4PI^M{ok!L*0W2bs*k=&gAD2eq| zXo9UFs<t8Cc4*JcVbN&<Tp?3I8stHq=uhNY)U_XIhNji!$^4lZVksh8s09tM!#_~% zUd+QhSg&6Qh7L6CC2sAGA)t?;WZ3_1E8Z1OaH19<^Z^sp<Qq^BZ6HEI!B)CfLQj%l zFqt6a!E3zk?YvfpcK+?X790)g>kZ<dzcSqDq02jJ<t8K##z5>XOzg(q6rx4!9LQxi zh~qVSNE)amfP}8@bOR%x1Ar`Wet2Q~aBAzKEPBil{uCH3<zvs;E<Y|Nhw6-nG7yN0 zpD__+ts&%PK9h=akkAI=)!+%R9xbtj(;}*c67&PwXfG9~jie;O2jI|1W)|1xjn{r{ z`9dJsnpSZ3fgn`D5?I0e3c?`p0h37)+%~7&-Y-f3rQP0bmw6c)u^<2kTvB4o026R9 z4ldy$aGUL5@RVmg6oVn8gX8~VS2k#apQb{FJSt8(;e%KMPi<~DCLtnW9OV+9x(F;M z6et%aZeOO-UpA-<zwq>}Y|D%)sg|m6(M*-7sy`x79Lgbx)*&UtMDPmlnhde=a^|iw z1riV95_6ODj>WMNilJ~pvQ{xQv(rCtfsl@*ZT3)PY$CQYU}tzn;Ecu?qsATxf)^}- zydeS`mty?pEHc$E9pjthO{Z_+qICT4n7QB|69nLz)KdxxG4`u?B5vX~!!&rqFc3qY zrjIo^5>gTB#sa7nUI;h%0-(|!Ckf#;_-TnebX~UIei$DyB;S3gPjsd7g2vCu)*L-X zXzWht443N5o@&hYV=n)H#4cyft5O)55KZvX)iC4Q9z4zQ9&ukKar|kMU=@}L9aa!< z-HjRw8%%RGU$tF)<PAwH-OvD$nxtoev66~2s*v+<(!n0A0pVG}1=(t>u-n_xL_E(i z9n<YviNxa#rR2%$zcmC>_Oo#XGUp94AuB`Sf?f(IE-2MQE2O84M6#Ww!BAB&!iMg> zL^3yo0wMev@7)wPutM~Jw7hgI7N&zJ6vMk9!<$8yoK9s+Z&k{`vKh|qELTen2T)?- za?pW9t7Xm{ro=!3bIvYZLhfNPbEXHm->)h22sQPLCP9r#HL|V13S0msKrL2hw_eZ? zDNq1)Pixx^!Q20FTM+4{)dkrRjdPK)iX3<W4ln^72<NL5Cu`A)t;Dk=JWyTNEndGX z|K4J=pei5lvqFfJ0H<kkJ*8nAa_zwB?YJX>=tnfv=|cYwWMe`GGwQuq_GMc`GNb}H zZmh&uwt^gt>~YtNh|i=}*E2x)$2?aav2Y73xXQ+~Oph8Z<I?RaW=;zoM)5FkAKe`W zG4T>H(CSr-zMm2oV%IqJpB$Fh;NJ?Ym}9|1*=aYH-^Gl5013!VVt}tbdGpuu6Wy6_ zw=O{uc)=R1FCUVkYb*{z#c^)vH<!+$bnfqe=k0YyOWziFFDhjq!%|`2p!`gwg2EiY zHiLP#f+_!08eH~SGHk=1aya*FLo;9kB`Xi5C&(d%0`e4y`0z(5v_d^R1CESr%rTs6 z(_AaR@L*QoOy@X;>QVvWaEE#*Pt)O;sDvFRlhO@u1)^wC`=Ol7$r;p%uZj?p57rYj zag;-IjXmwNVLA3@`CM4-3N&pC#M2Iyq_vLkdH0jp3Jz+dv%I0!aJqSY|DBv?sR)iB zfA_au?{$D<XA5E;V9%0Z19U(i_91I31EWhcL_;+wG(+zcA>?T^W>-ab^do>H_iXxs zK%qzD2oTQ8_#B@}s}H7jeCVz8f3b3_zi?BQ;cUxtlVG2MEtqb<;jIrHTZKtais+D6 zX4C)O>iWfr&@u(G|CQA-H4|6lvlq$-$bdUsxwYp5_AWisH@(w8J=90N)K5LtJN-XE zLEO-04)j0}I7XO5L8x%zK551m^d=dwWEcp66`(I3yrite1_m}x`9VS?M8YIYLgLl+ zC4k?s*zK_(3oB>@v#8+S@_8TQdo2O_Qf^DW8pAONG~~;VGd#oOJHx<VKIRiVGNx{Q zHA6k*LVCU@iik8JAuL_;=}tw@hZqRxwtmFBKIm?^c|}h&WJA3OXgY8LYI}@gZ+_<g ze&thsOAE>4FT*j!wrt1XsAh+(n_5}f%;38ME1(r`dkNp4#3l6Pm{7vqw<3ueWFr3@ z!n!RD(*$R5dRS*Bw-~(N@&f%}WnEO?z}OhdBfdk`-#`B6zy4=$K1?k@<P$iMU_pZi z5hhf)kRiN(gD$LK0Ye528$EywL6SsClP6H5Oc9ACOBO9!ws27i28@_7Wy-K&g9FDJ zG;!$U#IuLzAD@5*1ub+45u!wi7A<n*2ofYolqgk_S}BtztDQcL8bxX=DN?6Up;|T8 zRoSwyUcrJTOBOA+wrt^&I~SKOyLNZw<+YbD-(P=&1r{7wSYczz4l7f<Sn)Dt%OE?G zEO}aG%hRY;rdEww=grlsSra{4bhBvUyb)8>s24VE*08}QJ$p1Z+t{{k>xKU*6gO<y zZU+}`ySC_O+~)MkmW?#FYR$L-BUTP{=+LvPd)}P+^5w~sA%|x?-dK5Kg$E1%yS{Jx zym#%=oeS43Ew*Z3nJqhZY}iv?x#H@RPCBtFlT4<n1gfSWaU`jv5-IACLV^MW5TE+s z>5iOoiX#p<;E?HzGs+la3^2Y>iHj{xDhUfLM3MrECz?<q2_%L9q6ZsjkO2l3R=8l4 zf8b%r$Rm+VQpqKmY;sA5aM^%_6)2*C28=Y~$fGAh8mXj{Qc~%Qmc%&2jVhK{!io*y zzzGjJ?%=79pDY|?sG^K|kSV90N|36nu-d9CQo<68Ed9_@i><caic9~#y5P%em-hNv zFFnBu6UMyp77H)3@0{uGGVQdpuDVm7YepSL6hViZW@wAGIMK4%hMQ1i@eMfOhHH+t zYP!MXkyk~F4LWrcDW;xhn$ZT;>a5|6RPIEr3{+1Y<5V&8G8N|1VAlJKQeGq__pV3f zqR&2A@XJp>{#Nl1KtTtzN|OT<q(qXY9DHz*2oaeus6j6LBf~p3?C?W4+z^q(6H!$0 zBrURdQKTuPc!EY7ar8k48)Wct1rk26hDaw-PMM*8`cc{Cmk+|{pL0S8VTBe#wm}CU zf;b`xExGKHB$G~3am+E!@Inh5ssIs04>^o;k2(La5U4wgLMs2MJtgTg!KySNFe^d5 zIt464SJBUvL>H|OE_C73rQC6O3HMt~H7!ru#<2aa+EJ&y4m)e0n<Er-HW9`f&}41g z8f~)aC6HU1$xS%NX9G_1WMp%$8(V-ur<+q_&5qQ+t^E$$Z1+Ad({I_MdoM}hLl+lY z>bnmXwA6+dmH)gFbd-7xL~ts7`R(^#2@5I2>Vh-eBVjr`WVm5AMl3@NmQq}C;)-F! zIO7^Q9>U`uWoTiA5LjTRWtiblndSKDPZ^(l+_B+<n?t5y=OBjgvyKF9BqW)b(ONPF zAqc?>XJCUHJcN^|@njEl0?Hr`L6kh{sVQEY3fRInHUR&9B`o|=+gZ}Gmio}*ZI6oE z+{R_M^x#bx+uGY>9`h-`p{_Hh`iyl(Q;lAv!VbMiM>rTkj&UGEaF`nn<RnMAZM?>b zjpGI@hV?k;5Ca(DNCz^S!MGqs3p72HR%cK*4b^$-hI&&*w_qnOy3ww7=)zs@*u}fv z@#l9V6cB;zg|Fl7t3mz(n82QgAq{b;dLhDI_O=HG6|tyA7Q@(#YV@-s1mS!k1JVYj z@Q?e|kCde}Whos}h6}J@A{DWL4>Gcm0fMA}L_^6+%CH0>ETIZ+XqX$?)TXFOjcOOP zlLoc6wGKk%Yhc4lR{UtT5+2GdY-5z$;P%2v$<F^$m&%kIZ<s?JPDWJJnwDp-6OGt# zBM_nJ#j#pZ3UP1)8C4ujt$Oi@WF%vX_AFLxtO1;4G-D38zy>$c(TZWHgPvq0qp8lx znKWLDjp5uD90wCF*^%o#b(D{~+`_Kixyvkk{2lP-HJ}0+C|}51iXoXdFbgSCdW>9H z!?HJq?RC$4l?<PZHg=;N`G7|uTS1WeaI#Y_^&l*p$5WviRjE#us#Ue>Rk4~?slMYM zorp*aU|^*i@GMImX#y>$@FFZsEG1vq0v2|Oy)rnE4Z)Nk9q^FXVglt57$l0;mco=s zOkxsHp~Qg>bd^smHkx3G*D6?%HdweqEsFnYTcaE$m$=Doo7=2gxBxT5Z<gm6%P8&Y z#yOd1IAgWZaP4bh8;xh7Dq7hHMH{#g4QoWh8{Qa(IchOF!G&fx09{Tm?9hy4aD$4) zbuK_<!wq4L!xoz$M>!lCEzt;0w$F;~ccZ~t@vafIkU7SA%~KxqTne<ma1R~NMHjf- zaZw_jEGt}rUz476go~}$CGLeUN)UDu{Cdz)0yd%M&D3CdeG?uc=rj?LfeevU5f>(= z))-;ZMoAb#5PEO}^s#^h8{ox1-l0_$ub9OxeyTv`$5a`|>>u0s00~-Yk(~{}XG$2L z6oh8LqH%#HVDJJ=M)W{nLXAUt?MeUDE{L@aDrK2b`I@~JJE*dq&4edRAzR#*S-Nai zFWl^=X!DjBZS@UQX~fKIH)9QIbi;7jU|bmMAr0wxgBx+i+;VP_hGg`@8_a<XbYn#v z><Ez%!{}l<ni0m?mJwCk8I`C&<qYwJGri~e7P#a%u1W18ZnnD}9@|AySHLS?C`~Ex z?v*b>DsOob5(<MUIK4(*Z$xK+*o7%cv7e65$3pd3QGXNy5{yHX@0;-{qxx)V3q)q@ zpn=V*<UgMEc$PsnNlJu(173c?*Ds+fFrOwtgiUQubvkC&l1b&KSowqYdZt!JC{06o z`ODXwZ#M4&LrTd|wCTO!>N5ZBX3T5{TGmJg5qt5t?pgzk^%zDjz|jqQlCC+w$;K__ z@Qmd$=QdUJVKce`4n_>49?@XpY@>xv&PYq)YNROZT6dV&u{U<2CUvPFHQ(G-7A<;Q zwMl_Twow4Gc(OL|f$`MW3emKt3Ih?ZM`U4@Y=M$4+Hg>lu*pt}>;pj%<+RbBcBVQ+ z3maeo&Sao7vI@{6Xnm1Mu;7GUuB0Von5#_c+NQfoZE8@i6V~FrCrIe)%7B7qzPa3G z6sF~}Zvl9~JsZQ&&al&n;Z%8-(Po8v#<ij8#T#xB@iA6o8qpXBI)K3mX>>!<jl)JS z2qAKAki2xV;!HEfA&vh{v_c((FsQSD7{oJbr{*_@45txu9#03uTk7dKrQjPMJE}`} zMSs_-{bRQO2yd|~73A?4<gb54NMKVpSgvhqy+^|2MBU?hiz;?8pk@+BKp^UfS6~Cc zK&jNO01fbE9O4fmf(82LB4UXne(Yk_N(*8D2a4tkFi;GT4Dis6$>@NB_UdYo$zK$Y z@ft5|u)>eNBJ$Lx=q$@^Xu)>0Df8Nc;0B{xHs$kBE8*OX^gv@92!RlC>sO*>8nmGs z$RYN`LE}DyHn!mw0ztW^NYR|AGqRx@q(KyhfgJdZ5HNuoo`EzN=UJFf;hfK+xMk<k zL!;)XqqHyR?kNAHM9TY0ijTx^gtP+IjOTbLfk9|3>YN8CphrUzX4f31M0RTHzQ>Y) zjKhS=|By|6goFSOuo5jXNgP5KHsGkLMDBPD0zCrAL?R1>U<Q@|3sR!3SORI1?19p4 zf(j4HgrX4eME$sind&Ws0ws91Y?@XLQ4(b>{7uZ}Vg_lj1~=~pM@!At%u{%<2SMW* zo*@lxp}Qtc(!8M?pdp^5;R;RTIzYo4LSYWTaJwe$R9ep(x&aHdkQ|mUpg>L<A1da~ ziCQMg`EZU?(r~@jFw}gG)JUx^Y$pywD%DPiKkg6@nU1CSaMoaoc@iml5GMW@=8;B3 zry{1Ogl+%Wz)tKwCS-nuWK5<=F0mv{G9hH<9M&htv<-mht_hq#B=oKV!6Zz^1PoX) z$<R%ha)Oxl%1#iE1Utxs{>1TyCqQ};ZCcQpR)`pjF;dEmZfuY+mXR69!!e#O^h6JJ zO7A%^fe?B@8<6iDt799iAqiUn8c>c{rlA_VL0HQ1q0SLH#z7dM!4QCf3m1nPUSl^f zp%<pehf0O!Cd%ei2Z!>JG13d8`q8~)M^b+74R0r1K&tyx?dbZ$Z2U+o7Bbcb$q&^J z5Uqx$CerFEve&eSdlb>9zAlqIjFWT#eUc3Z*x~F>@-}hve)>TPKH%*d5SFq;OK2$u zW}yE?P(lk3=q2Wgu3j-GK=3EuZOW+3DHhL9K<M5YYnrHOZLDb+FAp!GQuBV{ZkExa z*o>UgsPweq7T%y2k^wYI&m5nHjJSat(19KlAs1pH9M%y!8UYiwp)FBGK(ztoXipnr zVHk#i7(}PftV1jZEji?J`8=cf@DUBwYv-!Z`Zg;2By&Dk2-WCtKl&s5HdCbnsihq9 zAv1_z80-(=k9w-dmn;$^?JwBCXT!+n5qD(7SOAoWWR!4oNK4Wo&R~^t%mIT_37`N9 zN^ybKifF=w3yucK&Q0)!Nlq*%I;U(Y7=+%WBC$~L@gPqrm+}QyNCu(u7%Sz>Fvb5c zta5L5aEDqi8Y;uJD&rZjVGh3V8EDIiszDsUNFB(59yWm!h=CTwVGao49DwgpxnUh& z1sTKv8gii(Hh~z(K^?}S8Jt7ANP`;)p%J{{hXk|cQb#gY$D+0+LpL;|{1N-y@Iyfq zkMig;k<Qh)Vt7`{D*QxWR&@O&1d$jlda7>MaOz=Hb49vN!+>mK$_EHOrbl3)1z6w$ z0O23pfk>U?#kdt_9O4x=F-dhGBYY+anjl??6Uc_<+iWs{mQyA=kVAS>ORYvIMv#M+ zshRAp6SS-s;bkc)56l`xO#^PD_QFl6a<n|};IJ~aLZw<*?-|%r^{T-do6!Gpnt?f> zqZ_iJP)&gou%HU)VHk>m7>a=$pn({+&=ByF80Y~VY=!n5$2M-k4)$rbP}MNO16!aE zG1Raz5tbJ=OBV(*4(-e6NHkvf>(v%=52d1Ok_YNyszNTrSW7d)u&zXw_5L<8Mu^Qu zJW@7~Y6EbA62CQV(N1Q@LD~2x?#3zzWJw8(U<PIY2hu97*y>$d!b)9H@YIc%wp7YU z@D{Dpnfw*s07Ty;ubS3I7%|IWF>j-$lKOD4VZ+H8MGsFc12m8;6?y?aO=srFa^?sp z8nmH4fsY(umL3Wf9mt_j=^<tr3i!aNbV0*8{4y+eOSaGmReRQF(J=q|7!y{9HZtSu zqbhR_an%lWH4mRwMW+@*L^C2|G{R03l2F9{7V)PX(Zh74sM2SBR^S|LQ*DjJTVo7; zo21(G$2TkD2C&2kI3fmO;H+xtfK-GfTq0fr4@*A~1P3>RvPLMK0vD-5Oz-Vqr72*6 zabUyDDK%?NDOX_^7EW39JR_EKrO_FHkQ|etEf>yoddQy$2RcS|9L9n6#-TpDVTtG| z(x3xYK(+TA4!J^i3|Vhy)u_BM)Kxz%FdS2Mz|*7Tt1^jB)yRTrH4_hqhj^e?K?tdk zAOv6#fkF}qMx`ffXY>#;Qj%2SdvX+GXv8&hq(^;3eLesQoQ?l|8A5&A*o~FMA*Nsf zJ8@@xCJ5|y27pXxzT}p~WEK6l0|zfos74mK6tHd)fyFe0$aKpbt8uv#avLQEUFe0# z1z|0i`dlZ?GMLRSLmDe18KyB6iV!pwE^s&wbB-eoLLt&<4_0LORcKkaYPfW)BN{|i z2+MG1RaJO@IB3~xXz>E*<m)ZuuwC{jGn+Vg%CA??Pm0s8iVulGT$D6*?WP>Y*Ah`9 z!3Rd3bw@j9T73jaE?@vjQjU*gebpHg|3MQX;%$}m2<+CZL@}*|jOzlqZ+lH9>?&}z z6p^JY@v7_uHDN$LK?NCiJ6({HS*V5NgUrHH^JeIR6C?jluTq2W)J~@%pTH76Ia)L7 z(NsZ|bgDs53ko<QZ8T&U8zgN$O{LP}EFRx;hkf~%H?55nQ$sTfTo86vjhHf#mU+Jq z={A#Bp&4pjiq;TJ!K~I`B(e|}rXuCa*SdBQ_3wL+z<gpeWYmWQF5qm_xt$LJj#=ic z(K@Zwdac>It=;;q;kvC;vS!}ae}G^HZlInu#_og+CBlS%&5b#m6Her$m<T31k3wG$ z*gE@FgcdjQ(&mBD^r0nJZZf%o$CErYg;g0tbH76xt3ex5;SC0DheJA*N7{@UPP;<m zqvtV*s6j5pkc2;@Gx}0kIEVF48+FJlF}3BQGc^B*V^!2PYx{;;nU~o_d66@r*-t7# zYN?od1IC(1GpZ?aYg3b_aFh{eq}cke2fA7YfP{V6VIJ@yuF*Ta)qB0$nyjDXAEaPh zt3(HS00mHB2#lcHLPD*i^j-V66$v?T<HRSbW?&F6-i8u^i;_SBMJu{up|^9Ag^^MI z?K=f-h!b{`Ew}T`6JkTf8IEC3F~J(1p>xYAwM*rp#8S5k3cA2?mE|(Ep(R3Z0hM?A zZ+hFe$zxMo=hKG!y^z;vjax*OmerazrIs#5e-*m>1u59C{c!Di4Y5X90@x@<*z`|h zyql|$?US|uZQYw7;5f|Pc@*NAB6Q#dUcmppJFM>R`R;0Re{s@pcaq5n?~sj&fTeSh z85;!?SIZhW!q398D4c~Vo3q%|FWf7$Ij_?&I-|qGZ=7K_z|u0Ffpg1g`N;Bzq>&n3 zg9zobj8q#{T+57(BM7^pPI)`iR`rLuC64Omr-PhUZ-*d>dYN18dCM=5l$yy|6v_v& z>SR>HEHb+%sq6AjB($2#sr9HXKo`KA%=5upr5#D0YG&vf?(Dl<Hv(w*+LoqtOf+zi z2m8(k_fFz%I;*qK!^XiC+858%p&|N`<;JoT{j<b{(cd(0Y^cMv5<IA3(owG$tYsQ5 zJ&jO2a9nG0oMY1yo>V}(EkVu~-qZi!OB~bi@%cC#XkQgpuTNHMhgO9ynMVrOkKCE{ za1Wuv*Qqvxu=qs@@w&I!*qOC^TeEz)8URC}1=s-}gtXd$-buI$3f%5T)*J<N;0To7 z+k-5h5$L~l(rNCBu-Q$ZY0)T>$xHY3gRaxDA6q-UY_ci4vL{+RZ_uK1(BDDD8UkSs z9FDbiHZvZ+GaN1uBJPYRbnYt@GwRfHg~d-TzB@7vr!}6__OauI_{XuYm}$M%SLoK? z#ia01K=e>W_vNLi_KK~UU`Uf*XLM^JhI{dk5w$#8(fCJxbPMKTtb@Mw=lCB;;R3AH zzE|J{utb*96(qb(f2ovzms9_+0T^Kf*WH>YU$=%Sx&}<I6FUb5!cXXND{t)S9XyA& zaxJ$i{ryvt!55ey6j%@LdH8Q+4m2LFh+?DE_1+$<1y4`98eG{L)TqP<KX@xD=YY18 z5g*hre2$9NjsSv|Em{O+$$|yz)hkyF8?JhY3e_o66e*6n_^Fd7O_?%P`dEpQBuS7U zIa-8rQKCeM5FIKsC?+64fBNjXd54b9I6UFFVZ-K(&@y7cfZ>94i<YHXuwa=oMT(Rs zO_U@_f@Fvf9X4plfWczL23-H(<vWWut=hG0+q!)VH?G{dbnDu^ix%I%b0I>kK=I*) z0IEP$zm6L|f*iT3q{$N~QlL8j&9YR>7NlH^iWwtRC>u9$;PBK*XV0BGd;0wOGZWCD zLWf!=O1a39qmq&+Q36@1<3>%LK8+&vyW**cs2(<Ks1Tt+Sp*5%!Ua7#bY0Y`@4C(_ zyY}tbe|i5EEWG$&!pfI7W=xs-_3YU%dq2%tuQ`}{MT_q&|Fr%5`}_azUo`holguov zJY!8Y3Q|K&H4HxZAb=A3=S(uzJTk{N&ODP}haNifUWo0D*dBVun0MlM!F=}%cP{d> zOLa0z7u`V3(Xw1Z3Ms_ULq1A0QANOwlF@D+;U*GECc(y1OE1MV$V`9SgcE2z!2wie zL>2V~WlAyS6jV}CWmOXYM+C7I4PLddLI^OhgAZPE&Pk_Q{oILXo_g-dXP<ul322~y z&NELxO<aIN2q?&4gAIiZftV6cJkgkASwJS)WL$h<)EH%yp&4hL#R1xARGyYvOsu)~ z8cMQ3QX6i$>BgIH7X?SraK-s}oGZz}V$hAY3`=8lGU|fei`uaWo{Hg_Cya^ck+@!n z&P<ca8_D!??S>vs2yTGUR5ML4m|((<g4K-cAT{B>+n+P!_VPw5$#nZ6h#@XREql_U z2km*zvZ(BK*Bx8zu*2SH5JEgI)T589oDw8(77?k@Mn{5V8%ZZI>0}`=MM=|?RazN` zPd^PcMp0mN$;B4`UtSt!R8Ww4)eu0WDT54QZGc5TaSBRw(MBJQbka&Mz4Scq{6k3t ziM}8M4UPga1QJOoAt|L$P4O6HG9$$)7?**nS!bS+suO9YnU<Prg|yTXY_ZXH8*Z8G z)=6);=Blg2z5WVpumU|-EH1}dmu$f-I{PfN|C0EgddDpDMkw*Um#=>C?#Ez%0xH<c zBab{&jWz;8`1!lfpe`RPfh4n^GxzO_d%x=a8?Z3s`7R#81!uPljEg5ekc~Jt%ww-V zt|F0;Lw-^uN3wQY(#I$@>C(tio@Ud@bX>VI%Ur_zr4~&+Wiy#pW#vN;U40eS1+tWt z57YYZe{`My{{L?my^P}niDE(3Y@ma}9A;~ZVT@z2aH*weYEzy1RH#Pv89JD%G^kR| zYFgtO*vtlRdfVGZ`sN#p0WKnf8=P_sceunU?pW6;-tc(wI2HBoU+HNN=a`WUOa!7A z%g|TnKGZt?jIJ7`dxV9^B_VeuQ9>2627Rp2A>4^bcgo-)v>+EA@7z#3HLT7I6SlDC zG)zama>b7#B0b<xFJsn2l1Q?bl9hyPWKyaLl|VDTl=&nmEHeuFX0|>tO{ywZ8G=^0 z;uWy?<sAQr696xX$xLc;lV~ASKjwjh3%p<jFi=wte1J8?D27s%f?#B{K$)_gO*3r3 zV5!{yW*XFZP-GxfNlIQtLXeoSR<@EJ#aL(@7Z#2=%~4q57FRqQ4ljq|G0*R!)x+K4 z?ik8&Mz(I@i}-XiKh`?pwLZ5*bD;}$0s@c}r^uhzb*LJl=)yCOK~8;bQFqw{*cZt& z9^nlyn#W6+bJTc{9kua|6q6p2=4d24j>II|<K9d7NRvK<FDE+@B$fzyhBA!7kV%P5 zBBLUOo0TaELkNQWyy7#lWC4GitZ7{cb(TBXbf<HI$3Nykfl<QXfIaX*)>OHeR=RR2 zv9ye*Xo*3#Y49c*)#Xf9GdD!E%2gw*P2N5-OcZ`1j>p_pGLQ3$7s5~=(m~t|t5d`O z#=VG|)$|=UQDh?bEW;Pkm;)iS!3=$B(VVSoXSp7M3Dm9YKJbLshT_wUKs<t5S>zWN z*CVZf0d!#BxnUV+)K*+5OnC)yn6I4oBZ^h*Vj0O;M<nVokcCVpQVO4FP}Z5BfV5>K zm6=IvmQtKyMQ4ztpIGi^7M?11xy-GTC;RaZcBJ70Bw)c%)wBZzBGrMG!qfygHOmXG z4Uo9Bs;WS!RS}j1R$u)H-+1#kAszFqgG=jjn(5YJ(U5p!{0<neDY-80PCd)uMH+6A zo?~22i{(6`>rhv&K%}A<jSW}lo&nig)N4PLyX=6w2(S~C2XX=}*k?hDM&+&l(X^<I zh-z2+(7tJGV;@Np9`m?I+JaAf<MYf%2`N%8m6Rzbor-Xeu(L+3i3O9aWOJVk<tVqs zllYhiH&QW!546C#YP#A{6Qh_)f$dV5YO2|udWOwJwNzAsn+HD_!e6e}t9si_tu8{= zz^%fK^;N5Lk|#qM#dVC`X%-j*CM^XA_7-ixL^3SL&1x~&oJjo7IZJm8+Eti8l+M>N ztU(AuRHK_72C<2HN8%E{D6R!X<Bf2H5Qjm`ArJu)jHy?>I&y5HC9zwRo}`*SQi-F1 z%x#v0!rPY(S$)9086$@qzxlxc1}pf05}Yh$DC;!a&BX^kg!YbGoFfhY8(@KT518E{ zED+4x4VwftCCjI7MpPNpV0lpkrPah)&aje%tY&pWzvUU3dv2qzUifNf>X(K!yrF;p zyF+PFgAj9whA#+gSsyaEh@I}xG@^mwa@pY)ntq*O-_`NXaXb}i;6*Q(p^SZzh<BO= zqpDYZFoel4jcSy&!D|g9heCA5*PEzp>_)dIk?b^nylo%_S-y~tRM|00UsJvo+^SsV zOlgW_{WL*SZtoPQ`Rj++nd|L4v7-_5Xa;r9t)>J9;me8f8rUG{U3fbcZE9W{+cwDb ztMZa=TXhu)+iOCx##gljZ{x4-`)6V;oZ*CiIOOblB55hZ7s<%~oHJsc@eysDa~<b6 zhMl3|TTpmEAqP;(RX$i{l+F&x;AV%Zl^zjW^S>)<k!MeAM&$8)c?V%5YM~c&hhoe~ zG`8`QWQz#z_0hJtRT+?zeMlm+Z%of-DVlTuQ#O%+1mnQ=*_FHP^Do!Rjd;g9eDDEt z_snWKz?#;$HYureH!^xZGiK7<cNw%nxpY<MwQnf_E9~`eVbuwEW=wi!aE}K=qxDSt zC0EMg9lQr%!VqbZ^$52>PN7FFqxX8Jr(wQu3$^oluQz)9;tS8v1)39B3sxfiw0qB@ zBFr*ItcGH)#xMyrYb}<1LV^)=q-!DJeA=TDEO7`*ml{p~=XAw3NV_FuRrg!l=WJz? z6+rM(U%@6H&;;hEemj+ZW5`K3H4o<y3f%AyfUp580CzMXck9+bN`)zsK^aB?251Hp z^d?nq!$G<fC4-k<urX)0Q9^v<H;Y$REyNIn19^WIXbg9Ob7g1{S02ZZ9@*jxzF=7* zs5>pVFZmL3k>v}kw}KxciVS8s$nXeuU=79~bGySsnFl;J*I5Gve8EQ}qlHkh);z}{ zF)kKIw~}kGwQEYEgcc<-akFDl$P<DD6xUaUz6B=Rw@78eb>Qc9D{ui|mt1Bjj^k(- z{qPU-@DFP^K-JX(^XFyvw@PC681L3pp2By2_=l(e(m`^wDuu{Z{f3Cb#DFREfQ?sQ zX|+rVCt3=(IE*7rj+24TvU|tiJJXN`gfI=ppkUclYLZ5R`otmAa0^2ePWX{>tC%|) z=M2oy3wFQ?y?}8F24Y=QbGVp`x|nl1M}e<a5XF}e3sq~XRT05~F?7@s8-qPJrV>ea zQA>9k!-g^`qg$DQeMx~xVZwb}GhAFaKQToDA#e`!U`gaimSs6*^Kcex*9$KY0xHk~ z*L4G@1Sv?Re|L9>-*sm9C@P+DOH|cCP(p}>*Hv^TkcwDL!qJHIg&YVOi4-Uu4M`m^ zQi(1?SG!jp$p8v-a0}70ksT>|ABj895DJ0+a8KqWiWs+XBgilE@lBBS9+~w|sdkel zMo^HMVk!oNK^QSXxmv6xV;q5uNT?)AX;Hv7ed2Q^gQO+A1v4>og<_J0R{=l81r}oQ z1Y&8H*{Pjr@k#994xwNLAD{x(RZ0k?T?~{|jo}naH8vC!UTL<M_10#AClheykFhbB z?UfsLMm-KFU&FyGj)#y5c~CO+R&d2%4o6p;Wem)qVX1Hn%)ksAIW3;4S1m|R({L`M z<{>DFlA%~c%n%IGaFNfzftqM)*Q9|uxPv*_gKhO{Yot)ehkOl1gv%FE$*7D>!i+F+ zoXF`>#}-m9lYQ5yNZr>`UH26$AQrs;5O&)MrQ}E`gu)JU5CZY{mW*NpMMZaY_&|4P zW@2DL0H`+dIiKc*Rji_3c=J_9$v21jp9YCmkT`*oH+h0KnUuMp;V}(<WemSFIWuXY z8b^8|QVowFYTd+f9;!uyN_zFwiKeD|x42mWb#piuBMm8hF<N{(qML4%TD@tEMp<;j zxr}>+QO`IU9TlWnLKH^fCC`ac!nK867*l=$CsC@aQd%hU;11^?1Q!5@*JT6Q6$Dy? zo_4pM{AXrp2A^xzHuIS(asxtzcQ*jpreW2eaYPD<S#XOvpp7{Yp*0=QB$<_Gc>v`L zn2-jkAfX(HB9dC6gX)p1xeTEHmLV|*B9)bz^onr=#!bd>3xqIPxfd-0Q%$nzd%x$R zya*k{qA)+`bHNCzH40<XW0W)&62l1zJlZ`X!$(X9l^vB^Q72L)wQNNeoo4cV(#E70 z00{E{4`#QkHEV`WGY`-30U>a12ZTyr)&ybJN)g0VWK%(z@vNi5W`2pL{dk`vq=2$w zXT1TZh-p^ex|p%H9Ly9$6$njv${oxC9>VYo8pa9;HmP{UL;gx4#}EyOY7OJmf^5rA z>VbmwBB2y{gEmQMlG(5h+lvS#qn}!_&?A&WXN18ioa=R}ADgNg1*B?YvQ_Dv+J}u# zpp`7emEp%^EC45CX|tjK3uR=NKVmr#SWs?oXP$<!HC@wgO9e~KiZ%e~hoB)EOe=UI zLwJR^UhEZ+V3l|RHzX@`wFjxSb(&v~X|7<q9n2CQ%0LKda17+}rw5By{-Swws|?5R z45l+``=q@dMxnycy|Y8T2m4<vN@%+XxRQsPol3Y2b+K|(JsP{Q99vOI2NOP8G9yc} zQ@ET}Sh>u$eN&-zSkbcGxB*-sv!d(3XNM0y<qU5~N<GskkAhUn>J<E^cVciENE?7s z6&ko(fcmDU2zZEy_oh|bt-}GJ0eV_Ha=eD4a9+zeeTzfj(OId`1*z~)y`#2yMYr$4 zy?zz9w->%#lxV{LAfY_03%;O%y?3drMm(A-d_1>eKe<rEF@!@IV?-xWO1V8bMlvO{ zQPl^)LqVh|yPk?9Tsotq;`ag5@T3oH$5HkVL+}A`=#D*Lf32H;cF4g-`<{JhOVJvL zf~YFHyQTn{hymw-cy>%LteCzcfi!HVcZ#PE={UW23vz%7n+ZIW3dGn{i;lVs_(TY) zu#(`L#5MRY6e*#-a0zeF3!6o$!K1!7nW-<@ixIm#v4#)}<wnF|qc_@G%!ec+v7@qO zoIeVUP$#4(OLf*rz+z&+T8RW`(uFX<CL16HVtB`NQHJAu7d}-9!dk)fcb;{}U3M86 zlu;RZNlWqn`FCfEDyouI_j#>RTbR5-wf<?f#oK2HCoBefpm5c23JSf_y9-ea#I=}v z7K%@Sa0~zX$|Ev4nMaYzzznBo2caOLHaVL(X`4HDP|Pv7x;czpd@(Vm5%!yejjMD{ zX<Ni5g;N<)C)=FXNHbWsvfDU6TP7C4P{-yR7yP5tORY5d@DJ<&1AfttRg*w}%r#B$ z&hsciO;yMtytIk@X8XJnzXY|A@VmhKrbNPs!~w(LYS6-xyvFjiFfvWvaSOB1!(<!9 zfQo2&<=0$PInKbnJ&e(>+)oodss03Wn4m2x8b)Hfur1nZC~YHKD{Cw*F^6jr80%Ux zoq)3ck-se=GEh=7O}DE5tJ6~VGDS*e?9)EltTXa6KVk6!K#*KajoZ0xj{lG+NZnIV zle)xORL9!7UTT+j$<=%q!uc48(>e%Ec!0p<&;RT<1c@tUwJQd9aK{VR2;Go_hJm~g z40d4Azo6H9eIEW4uN~Q8+?xiW@Oem_(X^<0nH3%<atmqj2)>ZZQjEiXd(u~2*}-gl zLKr>V>Kn({e0L<qdgKyLSla#@jm8$hR5!rPhRrLx&C%A47k~&y?b~lr&LKV*J~a*@ zz>ZZThp0q{Li?q!6sG@2rqDXV&7CT&(Hdh-*0e#GXnkjDtwJrVE7>ie+<njn`rQlv z9kw{c43Cfo!LSRDbBUN3(SB{^LX26{AYq@!wrg9VunEL`eG9D6!z2CJCC#u_jM9P& zzn}U>2d;cWca+QA%z4BTtTEb8=trYLY~)iuK?bW<X}Q=;6$gxDTQSs3_9j9@;&U<L zjUE?zp#{NBRH?LGN(H;}ymy(=cjJY~Hm=XrDwz2xE85D!Le4@xBB0^Qwa$U$-%ZzH z>w9T{3BDjkQXG*GUCO2`(Xkv179Cg}+3OO$>z5Y{ypRljwG28u#mZtsz3j_1A`lYW z=ErBuy-5*62b}-L;Lo=`zb1X9ea6)nbuHsEv3iYI=swU!oj(HzAP(vA?ms^NwGAk) zx^tMptu$uLYP9s6w4QEnOsmL&xmCc_<6t$lix}iB%+}g%$wq!Sajm=-sN^jYSr#qc zIgIP+O63t3s3Xz~vUAb$I_&%e=BO6Mp^yf^gXX;aw+Nj)3?t02pxtkN%tV=M+fL^V z&OPDIbdY=6Ielz^Ud>loz}dKU2`mF!MgkvT4e&1SXz}P#-xfag1Xyap??{(|Opk=@ ztZEjG<aMTTW1l*1cx<Y|D|{<)YE}-<m}}+gul}{kQar-&2v+b5Q4Wz)&U+E<@fyiZ zEQtw|1#>b<-@{&uyFOy*{R_VEiV^C2k<H5izUIUSj1()37K`mTs`JbL+`C6N#@!Po zI%e8^F3nVkvI9&r>Tc-V+!Zw7%`5;k4NUd5Kkxr=3U7Gtj{=V_e%xIjZ}&*!Q}s6c z7!%O_v`{+|h-d0+&-QISr)t&eHEhEQoh-QE3;OK~I8@g<yw^Cmfu*d8#$YZ(#0-Fs zS&6UsrTqOmbPKi61(=`=lJD}+P8~3h#VfWDgc~s~4G^SAjr#PdlO}|jGF4*8kP;<G z5hFTUR51}EjD-pf0>lx}ACP_ajHFXC&Ph0M+^{**vdkDTV7_pn$z_WcoLR77nKDI+ zlqXG;C`p23NDv=7Y|xMaqXmf%*8aiESJmoOtXZ{g<=WNjSFmCK#f~Lg)~wcl>}Y&w z0Yioi8a8|Y8FD1a&?ZlyNa;CcXBM1VYI6A!Q%sqbY}mL-c`{B(I(P1j>;n?e<w1iA z9m1HX;%7&WBub*xkfB0^nmTp*G-{MU*r#NlLWOG8?c1(&?|uc#w=Ceagb%lc%lL8R zxO6RNzRNkUUAH3HN%f1@b?eu)WB=9Ndob|f#g7*+%)EJH#?Buz#_ZOkK)r-9^L5_- zef;^)ljkqq`+sIINyC>~y5l9g?XGifLFO9NB{>Lfv1K?~fRn{HSYFX^Hx6-Ir8ZPf zfekj-2s$V=g&Lwn5=kVYh$4$HLgbK*GW#f`k@mO)vN+)X=n)RZS~}yUm}a8srkr%* z$)_iRBC4n%fKZAl8CqcBgCOAP=PWL}^zutE!xXbCc>c*`gB4hCD=r;;2x5pN?ouMJ zpL+T$u)(;9X^b)uJ3}$Xe0&VD$wmU{56m(vL`Kg(TST;oNGq)&)DT*&AlF6|Xg1qC z<WM&aF|?3E2_=N^I0u(|?iWnDz-5;NV~zE{?)tNpy!F!S1(Qd7Nl%z#^b<zC{K7Nu z*8XVyPncg)N#l`Q4m2>q1sP0rxl@mmkU|SD%+QrrKGn^`4@1;+pw<jZO_LN=WYI-O zFPiZX8g0C>50P}-(WI1A3eqJpimVAqEtKr(Cnul(JSwTBnqq;43pAN(Oo}VE_+pI3 z!snlJo?5{zxNPXbhar%VGp{H3vNH?7aN44#!o=WHNW~gEiO?J?Lo`v%I76h-ib5NW zG}9`{WL?%;BQZAGYRhdEaW(7>mf(cjmX_kOHSWPzchSY`W4a*37hGgDTRUaHL-tl* zm~jsiOyr}FSp0qkPnfmy4km5uyt{>!H$w5w>;<7qRcmc0<ks5^!xeYj+iH_-#MfLa zXf+gzX0b&`LVGdB88!0gvXJtXj1I?sTuI260yc6Bf(`ab3Mib6^9ZDRXjq1aLy&=; zfAGn8c;bsU-mHze*x=zcX=pPDyG~A7<va2Jq^U44#+W&=KyNNdvO;yntfS331Nu=& zAz^XS(~eFp>DM&nwA0+84)r%#D8#zdtdrwfRbABL5pPHZtQ2%M>?DY9wbI*o+H(s# zVB!|cz*{gXh^zh_tAPuY)_-`Rj6k%(7_zF?wXmhNt6j}P7z&r;#DyElO^$K|G02G! zQnX6EYa%fE%th#xnbDPQB&S0iO8mtVm%!u;uS1gTX4j;l#3@P)V+ssdu!0RBVq(YR zqFLtgMKFd@jAJBY8O?Y`G^SCFXMD#$x)A~rsOc>?5ZRkdHk2mq#ZEg34D1La6EVn) zX5I519q@2SJm?Hjn$ZZoewK(vc@7f)k%+`3EIFy8xla?9P)$KTajvF;2sf;71uHOg z%5GK7YW(w`gBBDDFJK}S3WAjZXT`x^G!R)7yhR{paSII!%Rb||pe`5Kx50&?3#{1A zbE@^s!<~wMrK(W3PI<~wmNIgypp6Vi<jI0;G9f8?2qi2T35f(PM)cB%=tu_=MB>3D zKRTk2$ly9A=42;*`3V$+qA(xqfR1mm5(!9fjx{D!p$lbbL%-NXh?=EL%1hIlZ16ld z$*D<o@(UJPrUgI#5ezc()1Lw*D4gv9UzSN!`8wk$p-JQ+IMn2&N;HrW$;N58c^s%v zslWZ1>Qva`MH>jgi&uT^nFwV6DtFShHn-g(52>g{Fm;KnV<J#lx4;AeYgt0)L=%P7 z)ZZyx_$hLQNJQtd+-hvtE_ZRRb39yxyh3*wyy9qx`!ZrmkT|3=1WYDJYNG6D*Ce4p z2`Nf>ixshmg?UgVqLa<aLn(XNu$1W+8z8|7+7hxJ(B+PE(u>Oc!m>WXY^2-!(_;EH zsP9qcP<U08&wl2pM~!Btrm0jXGj%Rf=#+j?d))n~rb<#ls6n%6RVsABi?2m@sZC|- zQ*XtrTdW}!xA;XdubM1nQCC_Ax(+UU(S<n}<C!IN&{(ksRN(kVYL82+T7hf1b+Kz9 zrdbi^LW5ho(r6=j)vJ#G=1I@h0Zd>=O43f21QgpP0e4hvN()v1m2GShvm4GwKeohS z5L=}m?6AQHDjG73#tARe+aneNBN)}PRxxaNEo=*=(%E)|k+wZwOxMRgqiM2}t%)Bf zY2&G$PVKnJ4XRL!vm98;QdQPcYT?9twqw%jZc=3hcbSpP?`C;$S2kNH-Y|<<K+|gt zLL4p>r?}xT?pyRF*KF>4xwpc#5)YB<e=QPVcfRuv`7-c<Q?e2ywk{?E3k=Kl>66<1 zQ;I;Ku$8blg{gcv#GB?cWy_?A3#`Di77cC5RGgQ+@WsI&9Zbyl<foe13^I|CElYLm z(wBlpBI*P3X^_VMnj*`uX-Kx8s76I9p=yg4bC?4!WMRVQREx}7O<Mx@R*OK?g1fcS zvY4|v?XyKE5P7(Tbi;bWHoN(1)r_xv&)Ojv+Lx^+!km8h%imq|5Rx*Q5fBOdhrQ0) zhzTCj7zF#e7d!f3hfQoza@R1YT=)aZ&~T?A>S2p-7$5z>2NKXEM>fqRqj)Us9#IR@ zm(j#9eM*dLZD!+I?+i1I%r$7zC#j<K7Jk9b=}zlcTqQ4Af2GpJlW7q_uWd~^*IF;Q z&BnLA1;ZGj$b;AR=4}o-UA#%JMHet(xb`BBe~Vk8)ZPub$jO_nm&>o7`RpRP+7%Hs z3gVzmCvesO5nRzmvPr@p&G0B1h0;2pl4Cc3g^FjKix^k@Wy>TC&a&XMaS1K-PF-5+ zc{H`xTkZA$^>RXm&(^nIRLz5S^WC1tXzxp!KzJV9;S$$=L1*%WvZjkv$l(!BR?gO- ztyJh}ox0u;1||q`4Dw<fLDLdG0@wSCN2FoRY#u9|<GjMgoqabRis1}hUqckReb4X$ zu#5&gx{sJ{U-LXPqFJXzMmPHJ5N<dU9$rNYlVAhcNPOclW?9DbzsV|-E%-Q#Y7@Fp zu{lXKlk20D`y=fc1DbI;$4Dua5+5Dw8AgFAA0ryx(m70tpJ3A|a^Wcsks4G&E^69^ zHb?{iUg)1zG9hPrj^;xkVR!^PKtATHK^~-~^-6^|c!XMTj@}bHt06nH(mq!xL35e6 zQD6-l(yyXf5x9Gl9^yCA@rVK|v?5ZS8A~G9iNAs|ETE7y!SjKos3K9j04?Z00enL^ zlqfg)fX<pck#Q4~xeHV?Ek4@3KMEunqd=IW3=HfD^5HSuN*_q*HH8o|oBFMui#^#p zLE}0u;@B4E^17tUmfxE)8tg&t;00qKgfviw4nh!61h@67vRyEaH~6~$$(CudzIJmr zI^#aIqnyi8mvQ2+@vFis#0Yk>m-NdKec=%=43a(}5-=E;*m*Qai?9is5`tQR5Lki# zad5*p6cYf{v~4_|GSLD9L@|+5Ksw1h%|p4GFpR?}sn2VSS-Y{7qOG3s8AwV*NGYeB z`!!&Dy-gXmN&FPE`>Ei-1zHG&H6VmkpoO9<6;Av;1ClmSEWSBlhE&u#X=AVUTDCL@ zhN3f$Sp-R-VmEJ@uUjma?$eaEib73Ly*+!oxdJe|%0dDowDm)senGTE)1C$EJNbLC zGHkeoA-u-Aq6>foZTv>1T*|B1m~#k$YqZ1X$wSggnZBqVb>uvfn!uAPBx6)0p4kk0 z#I4+l6c+iw{CdRK6E6DcDRAkH`0ADl(S<bV0%w~LkZd!ETrY{#I$wYfQ{2J-izFNx zWUq5`rCl&HP>>L=Nse_RyOP|Ho+_7enT@q_y_IacDeSM9?4f<ji1T|Vd<i%n$;p2y zxG*HFpIkV^dJ_Bd0o}nrYlH!I;5eqdP29W+cld`w2sJr^3k1w4J!G+tO2@3ko_6F) z(2K2@YbjhK%SG5VoI^|2!xZ3ROA|~oxEvK(U<FKAgHVtK+v^`z8mhhgs_B}xW0(U% z2!;e2%vj+|D*L^q^Uf|<$c97?>#Gpqu%_&r%(Ro7J4=`RVi*4EuNI-JKl34)%&XBn zM)o_j)7(2}{7Ilp7$^Y(-LZk9TmcG@grv+(5f#9Va|apt0LddYJiI*r1}siiQ?2X? z#2T|e9FsXkaVbdZF-Tb-nyRTwAu=Nakxp?-<EonPd<0C;1*}mw7}T0hj5fXmw_pea zR&dYcgHIn^#V37`2C;=*c!NNALC1uzTKrG94A5L02!d#<w!62N>@x)gG-AA$9JxsZ zn^1!rtO^~&C7GSti6RMGEQqr(-vOQxJ=CQvlT7eUkh!RGlpd>GnUjMttqjDjw6X9h z#2e*|9K}c7V#MC^Eq@FpNsOAtp&C}ug)T^gTF9SOD$jIVx-FGYTMD;ecttD4Qd-?o z=HNsDVFgxD4zgmm3Q0oAL@USvk;_y`%i+adG#ZD{p@}HJd1=u9L$OJ`lTbWOO`p`K zKBd1X!kxjR5(~p3UI<Y{P1jCKixNvw&~lULSuu_}t&e)ZKeW^tWzHJ4QAT2v^C?SS z^FT^*MEJSR`5`t+d<9u}1y*<jud@a2eAQU>Jzn+1^duo+=z?C+RlclPbW<+evxBK( zNU};LV^zW>jJIW78gy~1b#c=@lhz$_6d4gPV!YNN%2vPnmp;kUW>igY<)=sk)G3Nh zhq*L#Rad12u`=0(Q1dLfpgbV3yx}Cy(|WNyF${c#$M3nZJ;<?{v#s0Wz(`pUQ2n)Z z0j}Tz$e%MihCMD!h$T#z5UT0VS8dXCtJuDr!NPHlU`T`iM&Q9H4Zi8C*ol>eSx5sy z*o9%OCKfWulSD~xVpe(!KOBO|&J0GI^*15Xkv$MN)8tv7<-6D+Lnw01A%IOA;Ls|O zxN69>rS+09id~AqhmFC4aSS=pk{&&3K<lYgmTNge8pM62M_ju{n;V*53o@kfq{^wB ze-tiqp+s141yyBLR!F7%an%%>Sc>&nR?JAR;e`ka2EJ`3S|wasJ<KhYrU)?=Lg)fr zaMk`SQ^<WGT(nHe1*a3qq|237Kl9Acp*zu3zxC^@(=522B$$GMM!+MAGo(ht!!*gF zT?^*4GT8<?l)SeHIq0FvJ+zanb(sf@nc(G~OVwBZu;dv>GCfHuTTmrfAT=`V^c1sW zg+O@46bugfr6z~;URed->G~V5f{yh)VvPjf#++EZ#04Ov(h1St>~kFL%iqbJA@H+Y zm&DuvuB!mE5iPVkeIcUM(bo6l)^2s82bLm1l}$LxM&Y^Ovgk%R7L#zy-MA1r5I)Bi zt5+C33?XT)6pjq=xj<XnR2lKqPo=5m?MI%oOi@Cz43UNJBm_)YSp1R8p$kdxRpRDQ zDqX-~k2GQ=E?iH(7Vn)!;eZ8J&{!qKK6gXelubMR1ujpjw}kj#xyszn%!oNHFe2(g zGZvCOT_Q15W5AQ5DO%ksx}pvEgQTtFt_VQ?Y3`DZ83z)G$^&$hkt40%by1gTwUGj3 z<>XpIzOftwB8}L<^O4T!9N6j%L4%cE8(sxlSXEmfr53uT-xx_`%No3WNRM5RRKNss ztFlw}WLb2~;%MCA2-Z1B16^3M3o$!T=@7J2R&U}t8e+Rfq?9+!w>ZT@0zQ;MGe%_0 zJDz1mzVk^X`PQM0lL)4PW@dp9XaV4f<7y5I%i3u$;kbYJ12lnJa<n7f<wN5PDLq*& zcU%lY3cZ{G+uGvPPCY%deCPH-TOzxu=%wfSVTDNWx;X<C6r^bS9myXC$$$pgCne}d z&@Na3poD(XbW1k1-cP%o5QKb$?4<?&w{^=|mRvhqyBc~cXgyFW>>L2AD`CvSFn&<* zF|=WRiDKT<28L-2O@f6nS{QIF3Rr}Ha0hSn>9C+?(k_dQVFwww#*cZ6)%5|A0pX3} z!$~b+t!?Vz9TcyX>e|}CM0Dq~)oOo?-bj80hegs2Atkb=Jx$)^pb|U8=|r#b&OmT3 zQ=V(;tLy3`j>V}EUIEWn@awS#P?SUkwIvaQ$YLpM7e3RWE(V>@x!El|;5%iVz00Qt z<EO&{RQuCVqCDCU(1DyjZ35?_GJymN5Vgs39z8ypCTP*Wcu~$9sge@pe5Ex)lxnf` z*WWhF)H`e+4M9khA0b5rTIhoRH;@IWF{SEF*lTKTv`%Xvj_zGZ1^7^o>-N|gZ?kFg zXYIWZTSx;tumx~=OZrOL5?@)&>}Y3|!YL#T|58xK7RGw{x0BA<2(70if(bqC*2`v1 z42|GHy|4|Sg=i-5o-Xh%=?8b{fsbo}4!*+#)Wbc@yn40m><Qj?l(nvnYL-&x7DirO zQy*T#A?AG_aQY-Q4K^VKg+S2QB4>qw<c+e<<YODU{n_#8)`eLJghxn)r7Obh)^x|z zPZ`H+GHtg}c?2s!1${nNv<lE=Es@H(WtP-4hk(iVp7MFov46A41I|hJE4a!A+Alwt zppdjcRoyCr0a4ok3Rd&~u`q3E&#Zs2h7GtzkbCXjrE{yT9@w$%trXs;hH69RSDN$f zLHBSVYeaUjl%$d8bLo^v@B$=-n(QP}=DzezmT^sAE;|6$=_7R}mPJ(_Nh!`gN+tv^ z2!(*ecPmzM%)~QXcJc!S;JA|)cB+wIuT!1X$usV9*l9GK5ZcT>g4FE+!fWOgFtKw8 zo@$Tzj46{oc-n0r8KYjYZ;o&h7Wb`1sjd~h(c3Y8``4I);U4A3*3*>QAca;=16Vi( zZkk?wuSByx>m&4GCZ49HONBM~^yT0^O^4OHX6RW&b&|ZM`{@l}eS<cj1r8x4Tue#V zBM};MD_nLv1O>+bKdae#K|e9}_>>-I)Lb-UKXxXGFu_xKnyxT1e}yxbdC4b>5_R)5 zf%A8z+BpefNp(ON)gIiwaLLG-6-HzZCtLNAl;zdAAEotw1cgJef=958BWp{*ru3k@ zdVg**ha^uY#l5e`Pu|DdvqvFqNu1r+ACpykw`JIcb=XgkbSBhjwQW{Bd)dn^Cpe9l z0Q-BqqEo@o@?i(8gA+r<Ut`T~V}f#KOw;MffB!HklW~B`6Qk+i++*TgH9tho<P=_j zfFm$Y96AQ?Al$R3PoF;y0YMxzsL-K9h%P2tq*0?IN02^3l0<1_rIIEyX-cWGQ>RZZ zN0It;3Kb#$FN847oQVq6s-3HTu5u-GC{b6hj>1Z+R2I{ww4OqJYHKQ0s<^IV&3aWA ztyyz0*}|nOtk$w-&uXoz)>hQ0O`9r(b#$)Kq_2iz3iJk(tDih~?mQ*<6sf|7NsV&p zQf10ajx(98L`kxw${;&#)R<^9qKbtIL4@e=PalPQ5Z*CpFpfYsaNMvtBl}F5F=D`g z;i8+%7A;z`WWj=E3UMh?o-|RSBuNq^LwxkGL4$@27%WzVAi)kFynNojgAXr$Jo)nG z&!bPTem(p4?%%_Y@9rNY3M*E$fFXm14IMs!48dFyN;L5V6jBg3g>YH;ro|Qy>h=Y0 zVvJG$#%ye0=o%aZ6?Bkk3pMl*AQDYP(M5=Cmf0d5eN>r9k)4DRV=c7=Q%tN_VaF<j z6*d@PKm`?4QAEu(S6pv7)mB?n(V|vay6A$*Ua8PB7Ft(c$rh7JDv6{laoI)JkVCD) zN*8m;!c$Ly33k|FqrmA>CyX`bSY#uOBne26V73uw7kO5QM4^pVnnJ0m#^GzQ#Wq`Q zw}J76ZVxsHoNx(B0R?i(H8(^MKIkA_buFww!UeL-(_MV4vf8SvufiIutl#yMPp$a; zGsOn?>9?N^J@^m=63i)Apm7Oe0bGL+MmXUZvz>t<8yardAswih7UCZxlK5Fg7^%qr zB1kTh6q$@GvD6Y`kG#>vBcq_w<6t`Z1k{*C75NI7NqH#?mr!ll<XTY%f{RsHUbU9O zYW?e$m;1^k=DmFdMTixEvDv1Zh9#ERoOEge*`1WQxM!b!0vhO`qLF4ALaNcB=xZ24 zdxmYeNjhnRzg=3~amg*0#1TON5h`^ukh;PKSp1U@KC?m{wbWBnUA1@c{BsU=E3ly7 zbT;_l!w^RhTi}5RD!AaXTkIww7!+D4o3t8osM;MLg1Bu&5>aFkMj2%$Zb+3)2IFHg zvZP5T@CM?=BbbcB<6%D53*^N38hK>DNj9t`F6?rp<-%(L9B}CkZ~i5ibRBj7xlm>H zg^3+&Jo3|EZo&ko?w`z=c*u6bNSS4qshG%#6&>=~%7Bn&=%I+lOpriuNbBg$k?z)8 zrNIq1g>jlD$J`M^01@5M)?r7&Isf4EwAJs!AHV$XW4+1-B;e<De?0&wAc0Rj;aF)) z*4o-Op)$lRS{WJ$LF{(7Y>9|lCGs1J0LKx*4X$u8a!g7R*NIDj!U}UZMJ#O8BY6qt zM?eyi>x5FIeWlJ{odZ}c2+@VmjV^~X>{99=c9#|o2}qzYQyW}Cic^3>a&G!WoP4Je z;K7Jwdb*4wif6peBu`MwW1jO+12fi4k5P^)!)?BhGoAT{d)@oqrh?}GsiKJr2Badv z2X^rfRn0GtubKxR=b^_xLJe0~*cE<c;4A+OVORtD-+_>&Hs3Id3lf4`0y9J{YhCL@ z42fX3O!PMut;i$eDpyG!bBRn`LKC0R#3R=5hIb_f6dN-P<tk@6AQ}ZJ5aXAZx<m^Z z+5&VkToPM|xkHEbYnKuGAueC%7oN<75LHN`65o^<-Z}Ai!7~XZOjboJrc8OEVVUz3 z0<-9ak!G?%;LXlRsWfuWXW$E;(1>O<L&D%b8xX@CYX!)Ewug@Z9Vo1@rnL}oO@BH7 zRwB!0Hna_pL6Bryv%~<m3r%Z!bvwud6%wM*bPIVWvfu^xL^uuqR^o7%xJ2aa-~~)n zA|{G?)8uNoLKfmOU#sI~zq*8rK(qlDG92bHkNFm5%4M0YYo;?X_7`@!OJi@6)5qup z#XC)rc*Q&3XS6uZLb(ij=xmKTY4a%TWp8Kk^jRClM?O%+@j4%X0Xx`7(7UduAO6HE zU)6&(S6qMuEXa?qfCV5$7At@dU64c_L{Uk;twNQ|C<D)lw~vAp5ELoIi7FT_QDzXO zDMbk?DN%(vjDjV+dx?#5=O&xp^d~vh*9*b)r5G|r7ju|{P@h87&f)egzf|46@|7<j z-ZW!_!9)n>unH6E&SO=rlgOf2iLCPJn|`_?ptLxMueR*}G^hEZ^vK#M*^Hr`+0$Mc zd*;2LaY|@!y(bLv8G;Z{<BomZFL(rMtG)6!z~aH$AQQSD8u;fw0V<n;1emtQI(9d> zNpAubc*zEG^nshy8%Vw7w-kNWq<D(VCFWF<E)W7v=~6A65K|ZvqL5x{x@9wst4rG^ z(-whvge`=NOdbZ8DXXLHahd8&AkFK9q(DU=tni5!%T!JvJ6sg=v?o4+ldE1OltT>l zvP6}4X6LPqdMCwRo^|iN$f2imK4m_9>XQ!ta0h?|ykEWAInUoQ=+?Ss$o_;a2uDEd zLl;ZH0zx*j6<#0%F_{pLax$b8B<V&#o5A3Xq6=34AVnosQsR~{F}kxvp$hGV(;Dkk zUl41`D|CV4;odgLNZsi&UAR;u#}+VBEld(gA*D57;>D>=*Oa#@Ja29_oZ{qi^IS$= zFp3#kWW-s{-U-h%8wY^&OoFH2dOo@8z^;1ctAFu4Zaen_YqTIFVW*SeAS^hsiY1P4 z4(-^-PV!lkb%Sd-<mhZ+c0}CzOlK(_$}5YcaG98d9!{IMRL-bI9c!&?W9-x!v+&d{ zv@r~2(dsS)VivFv@~lTr+>#gB$V35(Q&U*YH(de~U9bZxq?^shY%@<&?8wP9!`&<j zO5meu_My&MUVfLAowz}(wSN;FOl7LA@`aB7bf_c8QiZ@8`aSoZ_3HJngFWnGA3NF0 zZuYaIJ?(1$x~;G#h6`}51%~9$Ld8b5MHZUgkGyxY6b&s#R|{sSx!Z=v$v01e3zU`) z$s{NdvN@dg5u{BC#1$v;j*Xg@wfxIXDaO<v-o?0fp@khDp_Ch!T&XrrIWA>Ou@$!b zc2M5fC<3ttP+WqlPrNEthnHPYau<urTUnvH2tAoa+j@|4r&`yVZ2$(XIc}zJ(l#Jx zRjoby+TT9+yH9qm=NVV*fWZe?Fxa^R8s5WFjuHTPHoe<Bl5V3UM)}=nyJa$O5gd5( zJ_*VdjmsoVf+Tc;7o<TYOhQU^S}L9YO9z3P?quE(%?rlF7EWm#stE-vumZ3pm67NY zQmmehsa#Q1Adq0pyu2KYAqFPM!CrV!ofun5SXp*ek#;S@p9ISAaT!BA&$Fe|n4Ogw zt=IPS3>!58o6T1oq0a}{K+}NV6G9<DVU0C>0RH%y4A{W0C>WtVlp|rm&d8s$EE;81 z%fES)wt!TLARdbRA0$M=;7CFw=z$1PSt&K3<$+qLso-m&pi{-x2oi+`8U-sz2___! z>V@EOF%uvjSqbV|l11P(Ax0%&f)xb9C{Ug@8Jo^g(TZe7@MRH+d>1*DMnaI+51too zT#q}km!(_^8*K`6I7isLS$$pqM+khtHf&uK@?tN>57y8@VCBz&rC&qITO;Y6vP_f# z`Ca`rnxkph(CtlEt)amIU}aPS<SjxZXwczs5S`>9YqeMe_94do;pe@A1|9__unQ(2 z1uKLeGZhIVB9|jRq6F?*?&zapEXF9<!8COmX>Fnu?VJtzTxW&iDDI%~ff=+R-59On z5MCR${S44_%BSdn4t!gwT)_4D;y?M<NAg$u{6iMN-7vbFg590GIasnNV}$kHMad1| zZPc~U!5K>9-tf)0R8Wdw28(QC6}*8a6pm<>63F0T9`4~DY91=2kU5s%1rCKe$^tuj zK`5-kU9f^w(jy5*r3uFW-mYa{$0!DkbV4h+i$Desp7<V?dEyQJNq31Nv+>|*eA!r; zSEI1g7~qUVwiiW0!4byS8~K2!jEX+R!5z7eNHS()7Sx>C0K1`If{hKaFp>b(8-#_S zqD|KHlp)M$Qcg;chm917X@n&}LLkUN6$C=#2_Pw*gdKv6YKh}GMj$@Q7*u{`AZFz& zU_v3b4l8u!<$UEc#oldl%<hz>;$RainbsV10%TMdo)9FmZP(8wq(T;-vo+)oN?Syl znOeD*5yschgbjV=(+XTb68u9yET&_^XMDOxy8XjAtiT5(ltQVbW#-)g?F>x14H!sP zCE4Hoaa3sTUnf!jP~xqKBy<6520}<s!T?g|Ha*5{ri&gzpo@(f3g)J6t`KjoV<6-K zU%UeB4Cl%fC(Ah{3Xa-_Ca1?pnG-oiC$vEoT*4$k5nE!HTW%LZCM2^FofoYJw29f6 zfhTV?-P5s^)Hw$bcw2R(=Uk1$F3RVXVkvrH%`|)fLR}%<1<QgB$PqS}7dF;|P?Q-( zR)zc>8P?>ZLE8TD--3ct6{G>5xM7Q&R1AJ2y7Ue|!YIddsE4YMEmdG&u!0^0!d9ju zSGLfKg5@K6C~_i3bn#<0sl+LTOij=ZC1e7gOhQOp8PEM_XLW{mfmdDH<+C|t(xn%* zr4>9mU({LuWT!ysn<33DhCr3VL!D*muL5h^{lg~+;}vFMpbZ*-mT59-CceFmOe&C@ zVpxXZq?}GrX;x9=%pA`-!W)iD!Wrdgol8}jWo=Tb=1t(mf#_ebLLNL$BSLCanxjvs z>!i}2pmI#8VH2im!YSEF$V9>;*lEZJpa72Q{{^4$ZP9l2U_-WQ&5#kK?1qw7O1(kd zngz|1f{I4s({+#l1+2oH`D(C|ES6$T9GoO!VWEEj$V&dtyfG`H>BfZ6U$jz7;DIK< zjfUY(kVS9?Bs^#&90CAl*Oi5qWLW4OS{`!(>V`%aQ=)4*erQi%!W!5CU-U%Q#;bAC z>&1EhsO%lli_)HQ>fV$=(IuQj8dO0gL_%eFE4RMoK`Pr8F;ACuk<o?O%t+f=<wmSd z<i*A!bG%Wg#1%&ZLO+#k;sWc_`~w!GtbPWI%N7XCKG>N)7GzNfo6aN|e&&Hf(9Y^) z-*ko^@Ie*WK_b{7x0)2W7@IfF=DuoZBxat*5UL7cLLLMHCU7mrscY|^;McmS*jB2r zDd&n!7oFH)@|r{-bio=#!t*{a4Q5$)>7bC7(;nchL&C;)S`=<f?2;B?wh5+yj8FMw zq17eL1%QE-DlXKN+sL->)X*n8v;cmtKz$t&LrHFf8CtWp%_Kpqg=y5A!s&)ZnnYax z#2Zw>8Uz9&e3t62F1WUCpGKT&Ddjj)9HmmuQ|<&P<N+nt>*n?D<^?Zuwit9hEmaZQ zbk*S|O2#4tf}K)=C3Gv?%B_}>i1n7!UHV&VFba}(Z{MQP-^x>4A;I`ioncm=4qy#F zz;FD<in&2C{9w&EumFC3X)&%OnZ92#{^w@a?A#3SwC3OEa@c4(LKRrSBJe?qm}U)P zke*7g;T#T9GVN-`NuVa@x$@dhJVF=5oN@v0Ab%|%zv$Cm)4m?>@9<ugO=#Ovg4%L~ zkHV#?dd6I`jNOKn5BhLfsbcq@5pOh~#lF`(1x@)zX|CR<46F|xO|jHS@he;Z4c1V@ z{S0Gag(+gSAOFH1ggMB>&Y$LPF5T4RwG=Su^35RV!5Ro<${3F|@>~QbTnySF1+Um0 zD+VG%?d%f9DG<UMu!1bb81NeM*xsf#FQ*+da&_e#K~6&3re^a7LeIq|^`dGftLmzD zXD37K^$78js!<Wws>a@vD&H5cKCvvjN-Qfh)yxMX2xGhP2e1el7xJ<f@65y|S^x|1 zGYa0J=%3zjRu>3?)fPe`e2Zyb&;>1CXoYKxsPl@g7C$!aHqX*2%z+iGf;fw1IiIsW zKJAN@Wmzur?lp4nNx}eD#yj)L(0aie_-H+6r*>-cChv1zT8}?h+nKrl;u_H^5@Mub zqK~PN!kjhqtc2uQQ}I8X!Aat;yYY{p`OnL~-*C7j7y`2x){G^MvEbnW9>gh!4Z;$< z!6A%D-z=y~S6Upq^h<A$()wwJ*7Uj3gcY2^llinyYjX;htva{xT22O!GBuw>LKS_4 z0v|#kxbYQTat_nw4vSUZB3&vz%JTW8(~&ZHo^rSK0QHs11|S0Bs`YU5q7(mv5)e|a zz%>xSoBteP6Pyj&FjhwAHD_Yfv|Jb_{q-3#1R(SQA9#UK3W9g>WWgzRD77@}Qga=v zb5hb~O=I3o&kiVvGx2VA#ht6A#)&v8a#1q|&cz^gmW(%b>mu;~3G=chXP|T<Y}TL< zAHz0mk%rL^LnL^j>GlM4DPycG^7i>2rh0yXxDofPcwdQ|_=%%<_6h4b$N(0<HJ~x~ z-HmCXN%vhh2yaa6(un~AwJBx!o3#{hcUM6b@BtqPf&^WwdH-KYnUsW%*m}FJ9UE^r zYN(}x!YHgl8gv0FJef`B_k9=dl(+XfA2l~|VvqLRH#zkiI6^py;_?jL^~N^xQMmH; zWm>i3T50$|o2U7puRisFJIsUoq<Enl`k|xUKeVUUjd;~mF$o~l{dx_8{YP^<)J13J z7dxw7Uw3vp+IIJW9LRwXbb%m<$ahKFf_j$XwRC7rbJDW^cY9Acl~*~u%p76lF_@>Y zu9GcM^D9yUcz_FdTYdzoazx-Pf&%}+w+x?a*DcXSc=Q~d7;*2ND`}pS@}48%bM&?n z-bV<~Kr1);xI<w-%!e)%t3<P``dvDv+xRj@NHC8f=N2;^0QMd*^HUq}-W;~Kn5qLW z`N53~946e0P;)hp`K-&doUDQYUUoL~`hL^&#QQq2jX8C(b35xCu}kl<!)1yfg6#<< zXJPWQL%Tj-HT8J1DlT0pb9IIr2d&0en?Z+09!(3};s)dwosoNS6M90EEY>7KvA#8e z#dSmBo%><tbi=!ZS@(5&roX8M9^3&SECG?@fdQZYu_%gEX`VM68!f?C=)s@F#YZ-% zbpk4MK^u^QOw&5W_qW1Z{Fr+q*~=i0hJD9d5lSC|@$kVRs4*gV7ge9USQTljt~}pr zH28+^aX9G^aC_Am63%mEC9rSLM`8PDe*1Vw`!F<?a>qXaf-s^arH83=_osp=i2pKU z=FWR|+szt;cNZ+gUz3Kl_B+A-``1IT(Ygq@I`(5jwv^8aDa_m_<euDTsPg~%#d~9! zoB77~XtDR)CnhXUDzF^z!Dk3u-RARMf|+MhyPaG6g;(r&YRcnJpAzRhCFmE>V}5{f zzM{{=KlBkF*}wh2kLCjsNdg3*3nW&sXdy%Y1`QfIdH@+R1WA%4N|ZEt@&t;MDI2kL z%#uY*$SqsAl;rZ|3m7qC#*{hp@(df9Zrs4J83!kwK2~t7k+TOVo<2kW6a{qj=pdzo z3LQFx2rAS>Qxh$+dey2UN07L7g(L~ABuZl`RWf@PZQ4w0*=ow932t1to#<YQWF^q3 zPIEQU?MoN1U%7(`7iN2yZCb^Z$Tkiu$txtSj<8my8a3+ELV4sYd7~82pU{7X0tI^K z4jt91amKM}QzjdjXUdcrBL)l@lqN@p4EZrj$Bj~?K)Kk2qC_MQee}>_g9gGDELM=X zQ0X7MeEs_6^Zp%tc=6-Omp6YNeR}o(>)E$=@4dVCf9KSNtFNwpI(Glw#ebi^JAC^2 zhroXD+3vptxjXP5fe11PAsTF82#6pcl87RUFd~j4k3jN`B$H0cjiuRQnyDr@T3cfc zA*{fI4%G0#!?Zn$G771slxoT;%n+ffvaBYHtShm`5(}-e7E=tdx8k~FuSX(T<B?4E znoF?4wA|7y#47P}NyUx~ixS8pn=HrxmOyF0tETcXGo}g|1Q9EiNJNmMNGr{>)K+7y zHJjXsZMNEO%MA<>d-Lrh;f5>jxa5*JVu&Ds@Zq`WWN2Z9>MqD6y97P`6x2{f9re6- z=1~Wjc-m2w)pmxl#~oAsBlWv^-eCt<|90k?ht~B1Y;d50V2E%+A1b_XqKYmePNOM0 z!r~*}v>3^xlt`@2C75EPNyRwUSfYwG=-6Y%J8C5AM$wQ0WGNn>!i=h_(#%RSuO2gU ztT6ROYpqMH?BtO^svx8<E)71c%O=;_cge=e42vr>xzcK0tK!YfsY43cxLrZs2$zpO z02!)}JoQ|y&(~;@DNx%8E!0qH6IGNr<C;KD35g&L!UsyBla4y;u!HBoUX4B)>7?D; zRi10w;Roud+qs6Edt~jEyIs+_=9+J~&cz;El`an-e1LrrhG7-b!Ptk6z);x@n|(G~ z-?#|zBx}cLDO+vXs3{IQmRLd#|8e(3?Ob$m%+XCA*#xp;t%xl0UL_e`tgT1_StF3W zGVxd8&_iD`lgrIga!jy_oSfo{FT+^ljo$=q5J32lBitKl+yk{e`Fzb!Kw%Pe3_`!) zZ3{$a-e?NqE_woI<sxlP2ZdxvJ5!-M9h>{^Y2|KgTl=wxpLXauAN}*Mq30i7X)W8< zdBXXI{`yss$JYM54-cNR3pywv6KaTsB9g3|ZHRf!g4TzoMJ*ALh;Oq&(Hg4YB0e1s zafwUUy4ck?$2~4`lABy)z~V5|nT0Kn(8C%C@s`q^5Qe66*qBB*8Opfsbx_He>~yp) zqX<GyfB4C1PKGkq_-SRb{|VIIaI+ia$t*ZnU|!9j7ri7bM^etQ6!tVVwEcY%jPC&- z(%{!0@|h!j=xZAL%GO3Vz7dXbgyTEj;SONXuN`@8hbrQ64|wb<jQPMv{~Yu`Vo`{I zaMMsmnx#Mnio}5>fneWG^tUQ3!3$n!O>2CYL7*s3U5wk2yWS<0MaWBD^Ah0*D`!G| zX`&L5cmtIx0n0DN5SOTP7{pXZBpX)DVpU0mk7UQOrEqXGMd`!GydZ}=^kGJOO4(~- zqr{g8Y9+Z5(cPdJ#RM|yW{$!l5VUBi=~QO}UJT?q*}2YL_2VApOXK<0m_It+6QB9i z=RWb7tFFaEjo(;@|2?eczAz5be=HbQ01=6-3|)kg%=3`6MuN8ysiY+)f`bsM0K9Gm zu9N1{;Ej-}BiZ%HN5Y&+2!}Med*Q20jp0`%9<hcuwD5&5#O1zb_^`)}P%<`b-Mr#8 zOw7d2O|`3?57SjLI^fO=f7pZXrU{26T9Y<R%#9OEl02C`Yl`5s;y5W~sY_wXI-Jr@ zJK5S+rIisM<TD@oq_z%zr~@77z^h*Kx>vvU6|j62tY7!K4nCq$9{f<nK&@t~qJa^i zg@h18d*FjaVrY?#R3NmZ)j$zhOC@B0i5IYdNt$qLlQ~(9xjeZCP=+!o?II<-q>@Tt z3Kggkd#Ow%|54K}1Y#|g+v!<)>eHX*c49*XW-z7VBaP7xG)QS`$xh>1FH}Je(yS^R zgg3m~;6|H<@~ReqBgJnX2RRbCVx%So9dn{}Q`>XveCbOn@!3NjbEQXqqqYutq(dF` z2=IUfTwnqp*uV)susZe_4`9>-9sHmlLFqWggAy`W3O!`cE}J2XM6^Q-?Cdr{%aSs% zVF^Nz4T@596V+m{MxX4%2019(jiI!;kYg!sT}rvIOkxscno=HsYY9pOxwuI_l5t<! zOXNxpP0L*qn{?<DV=k40HzJv7W;B#8R6z@G;L{PUx-t`GHJiFQURMwG8*hfyW@BY< zSrKxn|DdHaJCCjJo|R@{qm^+Ua#bT5_q)D-;A2;ZPV_t!&1gm=+R=?}pQ7Q%Xn4?L zv5csPJuuzJd+e%g>?~VC7b+pP9jky8i5rI`I#Cc=G$moc4Hr1-HxzkvldDCINKG^2 zbip>ZjmuamYm12GVui;p4ND{<A&E%{%npGti?dbNWNSkVxw-x2B5vrqQySH|R_0-J znR=rb&uB)xi-R0EdWTJ_jAbqR?pDRyO+_`2is4i*S*!P6bgEU5d=_}G0J)u69qqpP z9W*@+oezFK9OCyZ8y($I5BjMB9W+P>KiEiLvq^TLGO&RSD(jH9B`a<q-s~eiTax3o z|D*~y&_Wg5VC&Pi_@lmy5wCmgYm(-OT^$@HvEilTV+*yVU19cD0^x-~MC>coHq&vN zob59qz1zUN7@Nd>Wh|HbPBGrKYNAO8Ik8AZNQ}342Ssl-kC(hrq?z-o=qN}{s+>SW zr#c7TcUl#^d)%Ri)1cN4yXNs4=)lK2dNpx}-y_1;s0RZY5H@xodcLDBWD81dYGYYQ zy%Wi7BkA_YNS-7NI1qvt_EsC(*c|7a3@OiD>+_$-HrOZ47;TMybfj}->5`a36($jh ztymrTzQp>mv9k4}c71lo1iLb+OT;3wMl}?~f*0tZc54z3yt)xD+-GK9e8<^Q|BsTC z&#ZUWz023{@s~e%CO(gP<TsD;P*onuQIGf?JX9d<9?Zrb*nt89-~!HJ9`?ha*h=#< z41h$gSR7&q)a#*^MYHIpvql0Xs=x`rWp6Ob^=$2LfG5{xFUCmb*J{k9bPvZ;s`r== zD<s1Xsvr^;A*fa<+puo=WKd1M&H0|Mm~`apl4-hXWY@0m-B@IB;vk9SEzQJ_&89_p z-VEQQ0KLR%&MGB3xQGNc0O00N4Eql7@*#dIt{w!89@5bN+NS}J=2p(Z00RI46;M~o zu$|0i5H27DG9>~>?$jJ2^eW<jRL)tVg@HIw2!tSS2!$mw%0zDMHBK<3|6;86Xlz}G z(1Ui5*oLX7m~Y#-Vufxn>v)g{eNdHxq^Q6Rc48;`icq?K4Npu)=jb4CZ~_j{AaLZQ z3cTP?hQ~IdaLuOBtAN7_nWc)-OJ{~)QrHh6U;tBAAOtQz6X0(QuaUmWa92#_o$LV} z7%)Ke>}dEy4iAtH6L10B$E|(^5;mX@SAg>lspN*><O~QSRPI?gOC+=a3vgfws)Y+k z1Pod)5+%{aWKY*xtM+UUww9^|Nr~u+&bET2btpzFsv_%9Q6q7P6`czacBq)551EYc zPG-^is4BI{jJv#mqhv$0&VUTaApE$hqB?7N7DcSm?;-GR<hF=9|5o4wLf{m(2LQ3r zDEI81&Vd}l#<9HT9m<go>2L$i;UCzcDA}ohumJ`>AX79fAta=-e1INPE#+7(#Oh`V zW&jJSU<;1NEnkLjD5;vb#ROjr#(1aa7;+?qZWD)%%6_D_R%#;$lQ7rBFvATbUvYMj z>DNlq5_?DIwo7GVBE?`5Tgaez)NK50@)+~Yiq>mVp5tfI<|jA62FAe}k5V=HjE(|r zDaB@gp3)r}AS&sQ0k8octg^n`VLo8s0=lyECh#H1QbQ1^)jUEAW<Ura>9b0VASGy9 zCh;I^QKV?^wf3@I+{6`!Eh4EbUI-IBgK5hC@*{T$`W$jG|Fdi~NT&L#3o=pih*a`V zW`YeaY5Qs;{I;nkq3GU*!#L`0-;RK1n!~-W2L^uf0(^if*J?Ezlr`z79>AfX5Ttva zat`T`1}Gs8c;O%1!5#L@9TrdvHh>^jAZ@;K0y~TlA<8U0!U=@n1AF82E^3k}sgiK+ zqwG>Ok}w5dYjH$rM@FfbdZara2S`>CNt1LU#dAE#^ZAH0B#AI7vaB&p@+7q@wLEG* z<4rcaU~tYLGo_Fis}QVkG7I;O8L6j0y>J7>pnn+DLF073TGJk0^J=)KAK>8}+~EL1 z;1dD>2Ik`&#sOC-biVrMAMSt;{jk)E#j=9n2#AwK|1%H=V&FGk4c1U%lFsZ#aWu84 z(-LK@F@F^Ih%hAmvPg>x29=amk<>{MGj@<l6Je1gw@mDKM+vi3Wv&XVM5{iR(+g6< zEvJx7?+qCnC1)feQh3HWe&%}4X&N2jAM#XAt93m5Y;3Z|RFrZ;y(drQP(kM*1Ok8; z#$g)9VNb=;t%&9yC?O~rH9{7m<SgXmRPDnuVk4Zu31UD9fP=gssiLaI5#!QESuFM_ zF(DOlAscfqgD%)S=*DL2RVS8WVU;^waolE=+(=T(Y}I7m6H7g+%(isxu%$Mtpn{el z4AzV!+AQw!F|4rgX5?)BdZ0kB=O=^G6%Gwf|E<+$vGuL;C$8*t9@G_S^pqXo!5YS) z5&}R8=EFljl+U`Of3~3oHh?<f5k*h!vh2|b@Kp$AKwqJSY&X!N8c_so^d+Jb*ATK2 zan%x4a0MIoVTJUhZj3vtZ1*a5VuvjxU-6ivlrd$oJ;m<&uv9*`lv8bEZ;A&cQVe<E z?q&P)SU>abLep7sHd8i$22fKwuF_|Z5)Z$~R`4N0nR0)=)g8vc8M@&d93TL;!9$I9 zH~(QAWZ*XqX=^`kEENeO^c4kS!2FPt<xWpiAt){jk}g{;*Fb9aXirobmTp;4w(Qmg z{q}FOS9`Zta2<AfIo4whw-#;j-GGNz|4js&gmG}3pbGBBWy>#S|I>2Wt69zJoW2kV zsL~y1H+16^Xvc<5!2xym2Orp>9ME+f+(8QhU>B-#{`$uqwtz&1rOrIBZ6X!3EW!wk zKnRQ=fusmI&Gu}a6B3noChAg0Q7}~HR(iiz==jolw^xR<w}*gK`n=apjG{`z7cZ|A zK5<cHtg4#MjB#gjH%3DBzJUDX&is&ZW|MWjYPM3I5eBm70^)!`){1}ocQyZ4X<GAi zVbgnZ6Ib-~9M0Gs<Zz4UD^Cd|4i*(2D_DTqh8`7Z24<i*G=lUz#PkBTT1w2s)OIfE zauN|XVMBEx8S?gAxNbGpksnzT|1)uV)n!!K6OohfaLISOconO%iiyCBtGX)1I-(fm z?wc3|dQ@#0*N+RIF&aZ)10Z2q1!Rr6ST(&kX#$uj=K*y8EYwzaP^UqS#gIWdAq3u0 zYfUW>FGLAuzzFWRW;kSz{nczq%n=`P1fi3~a4kp2cjpvV##p$88JV2Rd6Gx9V@tAd zkq~6Z42aG5wAQX=f-%j8v8(Q830`ywKmvZl>UnS`S(l?3^G<Vtas@cFXKgujaoLx_ zSb*cFmW{?h*kK&d)g2Pr?+|JmRsd@$cy}$Uj%NS`>~&K2c!B!ZcmcWf1bJI<^dM9C zZ4o&yeRQ17*{0FClC3mU|Hm$q-MOmHmxvoT{KV9KU3L*~5+~(%tnRL7TDhPvpmRG^ zp{F{KbQzF(Icf6LLos^(cyk<V;5S*oAQlP`2gtJS_-#CFQa{+$Fm;4qW+kxY_13mi zUD`E1b$oa2k`sqLX?kvB5vK!NusgP|*V%B#&YLw^WP_)>&=)^n#-58hdB!UXmcR(c z*1VWSsl{nI(zJffNvv1k0-)gXq?W3=cyyCy;vn>)c?GMHCO%%<@7|OPAW&^2<ObLV z1zunVdcXn+(Kr|>1KS#4jTf$0;yDYFZACUEsgp;+nXePsuLqmDm5KUvTBg~#r{Qz4 z<GHbyXx@xRKV?*T|ICYDokg?JPYb8#v#HpM;b2$bLAFnuzD32V`(wWA+dbO&AK>5v zxYDB)VnR>=1&-wij6jh_kMta=vl?hdQG$f!TDc9fkn!4^^_qyXo39I-!`X9(Ib6eK zy0x|&ao>4Yhqz@txt=4tsJn@YaX@VK7z&`^iJ^FBFt`2O4=6u?5~lTY^&7~MCV#^C zox+Ga^4sqW#B8eJY6+qRI8Py7K+0bL2&#NI;bukUCV^It<s5vQXjCNvS#8(0r5C%o z6FXs{JH*$V&Dk8W(cGsuxtiqJM1<Oi$9u9lQ#j14gOwAUR9SkY_-3IoXf8koup!To zJjfS)J?`63{~4WB`iC99z#V~81_)dRZr}!TfOnC_fHZ_zKA6E9yrMGoxK}!xD`}7y z`=#ABu`zkXq1XCgoz`nz)@dEiji`LPTXADzp0OnaA$z>3P|y2w3ZTFV?)X0e9SLrn zKy&=bspG%lU_VS7(yu*K?kSA%8{0`GPX}ZdzEA~NAOv1u1yBG6BxK~~wT`j8I1RD% zy4;VO^O{$hQ_1{qZjRMc(vb6-*4rH551Yhmk>6EPORwtQuZf=Td@~!opJP@E?)aIX zz{cmSy`S~YXkZ$$xZ6AaQ|_CgJ-$8uXg;)HAW+}~P=EyDl?HZzA=;*Z61=3@nz)Pm z%a0eM|4=;=RbAhiyVd*s)nnwFZJp?CUFdVY#0@^}kjT5~T;XXW7$KX*TbwgZd5VsG z#%(4BW*|V*R88&ol`jAec#~*EUQSc{i{HU?ADY|E{!`wmf6jpkLg2sQF#;v<<qiC| z4`}8&!jbBRqGr_PKr763e!^SYrI)_K&m8F+-|-W>;3accN!ID1zKB<X;qlzznHb_{ zJQ<rnq&N5>1l_ElF;h6Y1seF<-QIr{Jyhby9@w6jS>IFMsUOav5klb>m|!5XHssVj z?|avGKP=Rb^Q1|A-Uas53HILSJl|Pe@gpCmAD{YlJ@TP{WI4I=fjzv9hsA4BawpgP z{}$yx>n>-Wc?Mnp34)*pa^MDfvd*47Q>GCMtg`GMo%ZuzJZuFXwjChm^_w>@pTUC& z6DnNDu%W|;5F<*QXpmsOd5zSJb2pDxhz%=Nuz(?hBn=uibm;H_B*>5>NRlK`LbFMe zCr_YA**T?WPb@&OWErZZXwfZ5w{Tg?^vf48P@#$uGp3ByGg!-D-HMfsS2k|Ix^V-i ztl6_=<EUNBwyj$_aO29IE7z@EyJ+*m85{PiSFV7$mYEtAs#B&+lWx(n*r=AFS%CWN zxl;-hoKKq2+>GSN5ELkU+~{%R#>tW}V6X_efdr|4|J)($N3pi;+qiS<-W`#k|3%)n z=e?U}51c*W0)Z=E&OG-&b{yZ~n>Vh>1ri}!q?RG$WXc{aUB;BT`6f=Cl_v)kO4PAp z#7&<@ojRtf*1&-MdJW5$tls}=-6i0F0-_ZMfN1fh9~<~(WtCO+jZv6WU%;mrV~!OC zSx}QzW*JU4Z6;F^FdZ?&3n%7a0}b4z*1~EbT!6(m|KI~pb2#Rx<BmM?C>%WX7$;mm zwDoA@k+t=M&p-3vqa-~4^i#<OAB41mcHGHe!*@Oe(b7vJmS-M%lTEQ6dl_Pg6nybL zH5GmJm0{m~fi3t|e`6sC;97c~#a5qs^=Bu84Q6!)gl`fS)nRNVg`s1R|3xNQhdW&c zqKGmfF~kr-_>jX5pq+-Al^~r0+l@%3s_Lq`5y`4>{}gxJJ4Lc;>#arh15ZEyOmhSU zR$|GWcPshO<xAtuRMVL0sTUMvX)=}+n_S2zRiY8jd1!+S4vHtB;D&n^o(c|H=%Em1 zD@I|4RcPUbjTsf`dX!pbX^2XU*cqol_|QWSI=mq83#qNP0tpvPaZZy?-s<qf54*bR zk3r5_E5sP53MD&(d{CuG+jWPM4&WU-1QO$Iri4xBk*S`UKtY@4wA5DX)O>G7c-6UE z>34>meUZzTxCxeP?q57_^`M*)uFEbM?ox|Xv>Fb@VZD}KO4EoW|8Cl;4?3*K;tQaW z&_YNbgy6`j8Mo~=j}ohjoUFpVZ8wkZz-G-5z-C9%up@&91Q46T6lQstdH6DWk!InZ zVoFha^V9S(eHEQN532d*oO9k4&vd5S^qWsZ9d%+Crn%wOK2?^rO`7GaFTec)EOv_@ zpg=+h2qQtGjduqx{O}9CBVEPFT}=G)wc(RDJB4h}n%{pDD|iqt9l<r?EjR1anUT&c zZO!qqyDpq@F1>To`4P(Pg6zky)r0CL>hz+gzq?qx@;+wuq*%jDW@4u=&v?mLDp^sM z3U)9QPyhv6h(>Hs#k>ky@FE3SmGNRFq=G2#f*@Rou3$qA|13x^Sbr1QmWoBVlO;<` zm_ZLuz6UeLIWAg|s~LqThpqI{??Lekq7d=(!$Z~Ye5Es8{<r|SM`dVUtfP$UKm@z3 zWy*lHOQ5I<wi*^}fC5ZNLoaS&yn$peglJ47bBu=%<k9MbYD}Yz^!5ZQg@gsdQX$F0 zQ@HIdYfLUH)3d^d!}sWLa^?d=&Zy$U`CSfkLmZ;|L}$MwLXCV&aTNca_&)$ju`-y! zm+X>&GOuMZY@(7u3toh_4H%&p^EihZLcxxToH35L%;iL2MK=%XGMDgx(myf*gA0V< zj(N16v08Wp?U4s@%<`U@Y8W$_We9SSlN^PtRT#qL|4d!kn$sl5NlqX#Eu7)3Wa+lK z#7s7ElU3^^7RodQ4?*EFRkUKJOo>2LvWPpYG+2y~5DeH5gdOML2nK)2(1t36jc$ya zL(vG2C9#7NFqoc5k{P(`A<K^|GY?KYBn3fIvpqPJ7R|`FO-pvue&0l=Ov5QBro~iI zF5M<35u-_}`A<@knP=-f6iQKYZC_vWmp>P{%8<l}1eAacKHl+<h5lxuSpDS&dnwVZ zf^b*QIfL{_&_#}ZM{tF6<}*WjlY7drq$V9CN(;Hto!ShMF2xy4_sZA2PKcd$#ikQE z2~<xGwNm&Lr4>ubFQta<cBnBJ!dCEyb3}=P|Gv4US2vqRhze;qaOCXroHvhuY(onl z00}Zvh>{hC$0aTVsYpjEO&ZG8r~AVu6SKKfcJ9!xz+I<r?aI@4`t+xT6>971S*fDp z>!_Y-EZCOXA{d<QVAA`7W&cr8(R%lny!>oezstNi{-YXCpujPy2e`m36SjssTu5X1 z*0{=*kW|BFU5UFCb_N%J!{smP^b1eI%5$E|{iMC97`suDGP(y;Dr8Y}-4&!33I*jZ zKFG^qIZo#tK>BQxI{Z~A^&=B9Fy?AmJF-3UF}})LmH?liIC@U=Og6k>es#NF0sHvJ zyCv}cq6Mwh(aXm6bS?p*OFPGI>7Nu9|L6sVpo~*dki=NF&3KIzUW<h`%fSPyJ2J5X zjp8w6-C1F=Oa|i^vo&!fh3n$h(>QD5R=>psGI4q9PU8;wxbc+dH0f#2*ELw5r1V-+ zwFu>su<~FRU_l~ym5(cf`O?Fqn0PULL9m{K3m;H13(m~iEpcgZ@I{$?-<*?s*4V}f z#xY9mJToENS}A;%T9EatCP2%p&N#O5VHaFfl^s=6(zV@$U1X&gh2RjD)fK0w9g!{f zXl|dSwgt^Q4lR`VW2DZKcU=44!l`<#GH%&h<!oO%*SS49_H|=&du!wR+NX`fF})Hz z?0e2wv7_7<Kl>>*C|mbMFuDK?{{TTF4Qu=1Zxc=%#rtK5x6QogfCLRL@By-pT07Mn zw~JA2Zmz``b|A`0oNN0%@V%SX8oIa4Xa4eh?_1c+P4WP5lFwr!+e`hL?vopR@YRqY zwK4$2b}L$Oi)Z;a*7gxq>Glq%S1_2caYrS5@Dc2M9L*<baml{)k~W{5Wiwtk%WZqo z9OHN9aEBDI4;)mS=iGJvX0Xci*%^TcUFZd0pmhZ*Jt+Kw9jDr`)fb<SsP9PAUS>S; zY{aX6bOW^;ST7zyF7DQnZ0y)8d$Q2YR*|}O<#zuGHQinF*1P`Y`aV<Y6^wTQ=F`}j z5;*pPuIyzq5Jn)`LWXsv|9Ht;-SIlwY6lx{{K?-4Hr*IQF?lDFaJN^@#$w5rnmKwm zqa5wsi}UP%66@HT|NQ9Z5Wnrd@(=y{_K1Ekgn6I9z*qOtN58-dlrGioHs9%2r9sCd zVompd7=v}sQ3*0YC1kZxsS$FXrxGQ@W@hJRe>7X?(SGcfdI^SLH&%BZ7=m>-euUP3 zS+jHS=U}AN83q(#0P|R3mnBga5+oo!PXGx^XK4nwgFG@E95gG;$AiOzfb8%JO^{le zw@PTHLMt?OBnK1cwrZt^a%tyks7HcWn1v;{a&A>rD0pZpD1W9ze~i{0f`@QU#c@jT z3$WpELimP0A{@vg{}2TThYn+2riBF`0dAWIcCD2XF7{fR@=+#dfm1kR^reB)w1HZ< zg(j#IC#Ym#7=Kp;VJ=vI6NVatXC<Mw0(4*v{a1W;IEu`HZO1`}q$oT#vLyd74j9F8 z$24lz*Ir@=dZAZ#6}We>vx|r*KyIaWiWrQ-_=|b>e!G~0g}8!)$SFfWhC`Q16!vHz zu>mr$2isL?shEvxWIS^igxYvFM0g5VumTq_J+jDoofm<DI5;gdh|N@pdnYExh=IMR zZYn2?_R@v*XnXSraABw~0!KT}_>3~>B4}8H8^8iuKnr=pUH<ot5P2K;Fjd1rb;%Kt zcY}xLunOZ?|BkWvbxRm_5jcU`w~T}ckMXFBEVGj4AyV|XkN?JC{g{%JxPmMgT?1z< z|MFP&S6$X65;Q113i%4#MSK`}l(=C$@6e5Ph?J^A8wmIh8`+U*Q+=csl3}N2|6+@< zHHcA|jHE}CD%p=@If-KVkC`G9&4iPj5@9;25<DrA1$l61V{|8^1w`3~!Nhz`>6Bg- zfT}W)$~P+vBZ_{RF*YJhQdtR4fG|~wOdyv+A~SA)7>LV6cJ7EW6$q9pc$R1BW?)%} znh6tw2wS_Cef<=dF=%iGc}FYo5!W#VuCQGWX_$w3X;9afz%h{$=SCxTo57QqZ8#2^ z00jt>|9MvOap)+6lxb=bICigPn(nxkn;DwcX`S6?lQ+qh&B%^}lYK8(e<ImvnmB4! zf?cgK1*brp!DO4jiJKWjB=R|*^jV+wd7t>%Wyyn|{Mn!W`JVt9paMFe1X`d58ld^G zifwofnb4RXd7dCCnY3tXfVh>}=bgLPl_t5CD3hJn36`U|mL{oaK!=+C5}p(~o-(M3 z2xl;_xdE}co_gtj2U?>xdZRd+qdK~yJo=xnGJu5Xp6_Wlt5{mC*a=clgB*t))wfEK zxuWAqp_NIJ7s`&<<0ZE^qFTD8CV8b-+7jORohBNdJXvroLY@z(9kK``p_ZPcz@85| z|D=nDd^uu@$s?x~q@b`d4zh3tLy&(RXO*M&fD$^HSt+G(DS;+>q1vZ?Vfv_$8m5bi znq&%>DXOA^=V(P|o*@uwRiXrYke60geDjH?7DuPd!J8oFn-eLdrusI*2^;-z4!=ML zPrw46$~$Yic~82ch8m@a3YS|stP@D3;7O@lnW%{>rDhs~zDlT@DvP@VqaOeRQ}74E zK$|rZr>|;px%s0%SU24YLW#*M3px#zkOeRhBMb<kyb7&_IxN51oTm1N%zCf*I-dGU zo<5nTc+^Fbm0H&!16rU7%D@h+SXJ#gt_Fyz%ORLRdZ!Fau6x;r&(RI2@C7u0|1hwa zoV%)o@LCeS+Ib=~ulstkXX>mYOA^qk9W82}G&qgdaRg=X2^(QhO|q~PyR#56n02F@ zJbQ7$1XfZt4!Gb3LEuH@NF~&FM;{Ba(25!>8m}W;wa*H#AQw=(8ndYdqZ<GNNk9j? z&~UPvn64VMXloFjH7ik)wjSmVL>ndNund&o23P<DGJufMlQs>wtGw!@@EW*+JGd?q zt$r(6ohm)j69O_21XFMaqYw-T+lDp*w{Cm64&k#@1+<t8s}*ap_;3#6;0%!P2Uy?( zGBAzQ$~#Qzv4`uTg8I6$3$rwMbc#DxFrWlk5C^L;4dcKLib)WOse_$c|Ga7&v8ZUg zaWuSf+lKDI4&$H<r0@q{paiKaJr|I@+Pk+N69V2#0^l3I=ZPKRyF1>SHn*$2*}J$p zpafh%2ctj@=b)`jA`nB%tp>rl$}6W^MGp5c9NxIUxipdYdl42JB?x5=r~nCo@CRaW z23%k!2K0dE>oK=WCEe@256CG`fCW;31!ph@e*g%8U<=)F4v5!=1hK96d$t0+zXY+A z%cs9DJX*}#o<@4Wdg%_&i^B734bwmkv;YgMKnk)z3)L_UC+x$}(U3Z9u~0d*6IsJf znORnR#aNuhTAV@1aSrG}m}a!aVm!uVT*hX6#%P?zYP`m5+{SJ^|HevbJnq0oMry7( z{KN-*$MqY-aXcKpVX<!<$bvk`gj~pme8`BL$iBfUYl|E%OvN46sswz$lw47gY@0L; z$*JhDr8srVr^%ok%BPyi68T{h7o<}x%BsA|-u0~$Q<2%m%CbDmNZFgQOv|{O%fH0Q z%b}lDr^~<`%>QT0Y)i_*e9XvPr<!#ns!ALp_Q=T`&C+ZnJ?fvt3@fxz&Dy-p+}zFH z{LSDT&f+}I<Xq0?e9i;P$es+w)7;MPyjjC>%GmtQ^jy!n<g>nH&-%R27Szc3%+CNF z&~Kx;ye!ZLebCKu&2NOz49(Agc_f;9kqtf3?_AKk0kQH7|5_Bi(aG$}NJ1pWlMfbY z%p6_P2(2X3Q4qy(4^vfI4{g#g9m*c9%m%@m|L_jykPhfD4E3-u3Hs789n_Hg8;YD+ zs!9&#&<^pi4($L8>TuIUQq)pC)l^;8R(;i2oz+^s)m+`xUcJmb(#-bI4(-4XN=?@C zz!A_a)NIYqAPr*aP}cMy5Bwkx=D-j3(9&(a*P3k6NeS0-ZP)Tp)_D!Ue0|sg4YBVK z*ZeTo@<0!SZ9HI&*p%(g0};}UO%Iw4*?2A4mHpYB`^`*3EB3$-Or6y2a1HWMBNu_r zuKn7u9ow=!+q7NVwtd?;iX<_d59&bI{9xAfP!Em_|JuY|&l%(n^-vG?U=LK4pnhH4 z(7nnot(3yM*3o_4v@FT@fZg2P-QNA(oc7${J>D-Y-sFAW#cST^z20f7-t7I}uR7E4 zJ>QUQ-SmCm<Lch{z2CPv4!Hf_03P51KHvmi;0Au+H!2L>FvoK&$M3-458lU03E>bf z;So;Z7Vh8}Zs8c-;1b^984lthe&G?$;Uw<ieJtW8zTqE!;v>%DDemGgPU0(0<1G&3 zF^=OCF5@?D<2ml*KVIQIF62R8;x$g>ajfD+j^atq<3n!bOFrXB-sC#2;XuCQRqo<U zPUTl_<x}qEP#)z+9_Coy<vack>~IDpwFO}ChdJHyGllZzZ;l^w4(D_Z=W~ANb*|@l z&MkfJKKb$IaW3e5p67wS=Y?+PbwcQij_8Np=YH<!Tv6wMKIx3!=#Y--hHmMS-ZPi} z=$r28o$ltDuIY*n>Zi`>rLO9sF6yi9>a8y5mCov^PV2Ky>akAggFfoA9_g<R>%0Ez zJp%?>Fa-et03rDV1u_5t04x9i004jjHUa<${{U&J_;A4if&~Z@DqP60p~Hs|BT8hj zfTG2Q7c*k4$dRH$jUE?*<j8R3$BraLqP$pg<wlb#VJeiFaAe4tE^pR!*^(wgpF1`7 zTxpSkQ3ez~gxCYX9XkL}qe`7hwW`&tShH%~%C)Q4uVBN99ZQyK3kn7X3?Q(UfZMll z<I0^&x31m0cGbGo%T}%5wsQaatt*&s;KFnZ1CFbBF<ixo5zmDjS#agQmj_RlyxDSR z%%3$M=FFJ%U9}BDAOg^@-@kulW6PdRySDAyxVNGmV1U4Z-@p&d4UV@s-rvTPD__pM zx%21Hqf4Joz4~<I4L+>u2QRnx@8H9W{~y0qxB&zK(yLFeKsem>*6Rjv9KXK(`}p(g z-_QRpatCF=M&5t~7HHssSNRse2Yn0z$b%0eB0~V~xpe^vBzyoEaBdOz7Kgqehg^si z4nP3|Ba#?bg(R}r--|HDDC3MY?!|x)0L%kGJ_z>c<Bvd&6=DF0yk_J-%P`>ETLZwt zODB-XFu(x=s3+Wf>9tj5dTyz=<!|d<3CRjvvZY>^SW>8<mo>KO=9_TFNf!bnR0CB% zLFTFFo<VjP00rIr;|@Id0MLS(aGk<J04!+276mfcu)%y3P;dba4p6wj3O2AnfC4Mf z@PPv~Y*6K;G*Ccc0HgfT#1K?2{{VvyAy8VW4XPdxKnOO-(1HST1}p5a#9C*-2f6_8 z&W=3t>Fl%6;`U(xQ~ZMuJpVXC9|4_wu<I%W?E1$bZq%v;E^JgHh64jIz(pc|^gzKj zsKmjABz=59!5M)3p@pgekirWja2%ij6c5I+=n%i0Q3)Iu1OP)HfK;*v1KSp>@x~kz zd%y<2;2G`6B$pi4V+`;T)ub*qiAWY~U{NInT3~@o83Aa~4G94}!EzE>^g+u7s~ph7 zDFJMeg$~PLp~W^622ja_;ZooX8&bToNB~2OLqh;a@SH>(Q)KF5$7rXmwu}dSz)L^x z6l(I^bk_|4T)NWW4gg#r|N59Mr0l^30|7Yj1t4@x14hzftQzhRf7~&OEJQER11U)_ zy$v0J#6dxoluVewpVK(92Ou^Cki;JW^u?AGhj3x`+O*ehyM1os*{t2X_rB+ftd7I( z*#vx2YXAxaK*B2NVKGM1XHa-0Dr8<jN##CZz6BOX#F1X9>2-4G%&sKA!PiItB0ZWt zi?Kk)x5qF4{BwP<i?X}>uK)f90#Cvaev6AM$RwNrH~<WY!v@a2;08p24G?=cg)S~Y ziv<M16#?J^7$|VM&V7z+;{wA07N7+O0YV1>Py!-arywLOq7QV?0><b^!y4Ameo)CD z|8~ej?=*)5!&8t0|B^t&No_zwagl)%l+XeOtl$6?Ai)5RxF97YAy;mZK@)7CfOZ9; z2`e~N2->2n6<9F{Gqj-^*GM}YE~|%djALz@GatNdDLuMk;d{K4rf{t)OM9&29oK}n z^}vsfh)g7$+=vey%JGqq+zMTY_aPS<Oabi)(ULxdNni;_M4rTCg)Rv!--xn9?g8Z~ z70Jq0y6Iyodxs+<Ny}PFrAlg<4=#79%U<U4m%IcfmV^n+U>ehx$0TMlmx;_~D$|+F ze5N#`Nlj>4bDGzzCN{UJ&2DD%o7@DaH<jrZkO|0^=u9U79Kg<Yy7QgzjHf*3NzZ!P z^Pc$3r#|<||IdE<^Pd0>s6Yow(1NCh7XNsoIu{DbBRcd04~-~9Co0j3QuLx0%_v4U zs?m;e^rIdPDM&{u(vp(&q$W)%N>{4Vma_DvE;Z=~RDcS&$&H~n?co6cu+yIM)TcYO z3Q&1^mES-msAVy#PlZa<rBX$yL@nx2t1?uiQnjg3ed<)n0#&O{rK?%}>Q<kMRj)<` ztU|47TCvL1u}TH4Yjx^Z%Ze4XQq`y*U`<Z<3daQiz^{P)t6&2Q6~7Mluv7`GVg(x& zz%KT%i+wC)3(MH5M7FYqZR}t(tJ%wH_9~YRtyCO~SkX!rvy?TgX%S1=$#Qloo^35- zS1a1q|EjjKiFNH~JNwty>Xx&<9qnX=%ZqdJ^|;7Qu5y>l+~zv>xzLR+P8A^C>RR`@ z*o|%ivdi7>diT4J+%5o$3*PdY_q^!MQ*hJE-uAlpz3`2%eCJEw`r7xt_|30=_Zt-l z@b|v}4zPd+OyB|=7%L4pu!0xN;08PR!4QtHgeOel3S0QX7|yVUH_YJ<d-%g34zY+w zOyUxo_{1nqv5HsB;ugF3#W0SsjAu;a8r%5BIL@(-cg*7+`}oH|4ziGkOynXP`N&A- zv0u%a<R&M1y-tp@l&4JPDqH!=SkAJRx6I`(d-=;?j<74>sDMg@`OIievzph;<~F<e z|IKjjF$-3(f;ijx&UntVp7+e>KKuF4fDW{v2TkZg8~V_0HZ!6Z&FDtc_Y01Ww4^6Z z=}KGr(z8)Q7BJ1}PJ8;(pboXDM{Ub3kowf9PPM96&FWUW`qi+GwXA1NYiBWFomgRj z18xm~Tl?24zcyL0r^4%6^H~KXK(-33vTUg+JK4~FwzQ*70su_=+SH!5wX@A_Wm`K0 z&0co3RUqziO9c$ZcC)Fuzy(vAns4j|fEIwD2y}BH4EO#*7$D7+FcgU0ipW9|6hVb` zw|ff*2f!BIoo+O<0RV1*iW}Sjhl<DH;sCgK9Ow`S0MLOEjG%+aIX*WuaNH0e|HlIw z0I>3m#{mr$ueck|(C{<UT;c#=!^C4A^Nza#4V+K{BQ}AChi80l7yo(C6=4WApn>8s zpZLVt@NlEo{LDPJc*o%Y064f|4<I*0ROrw<IB-G{NdN{K)^PExR~+J3S2G+mPWO(l z+z^Twx*Iy~yN=TV<&0=KRN^rAwsSr1VJ>{#H$M24a{>sP-~`|Cz`s&tfe~V7JjV_H z_QNBd%XH`X$feSUutNn8sPEk!q9XPus9h?X*Lci7KV{ED#r7E&xl~q<hEjZi5u89h z<@tyDzi)yOa9BO;H-B{6YgzOozr!8qApJYY0S&E4!Y0HXmErHO6^zhA|0~As@saDE z@6Jy$?)`3l>F<FlsV@Y`4{`cF*nfY05I!9Q0sQO#Vfc7JeWT}cRe^iycVllic*{q9 z?gtfp005|03W_iV!+?5!KzjW1e*o|YdB+Fd2Y&&mdt_G?=y!lSR)SICes}PGO!0s& z$O%ut38g@J57<L}@CW~g2c^IWXE1{_czVT0eI5sUCdgwWNEIu{f-LBQQBerTCkQn- z6&DBy{NsUwfO4Dwff|Sh?<ahCAbnJEghl9M?<akIum|>6gE)u>h{Fh_000oOflzUQ zJoF%fz<-J`2pjkZ`3Hokw}Jqmd}C;YLI?m#sDwB;ho@%>S)d4s|3DRbsE2h(g?zvX zQ&0*un1&F@g-RHRt0#toNMoxfh)S4-_Xmd$0swVze5GIrgTM!aAc=AmiyLSPitq)w z@PKsag6{_v?pKDPm}5*)iuQ+te?Wy)2mpNW2Z_K4ihu}(5RK?G2!g-~z{dxuD2IG# zf1T)y!6=Mqn1;s)hfslxgOCU)H-5AfjfK#Jh0u)8SQR*EioN)aHdc=}XpE_dipi*q zxzLEB@F49-ONT&z<OqIua0m|~iw}~BQ&Erh2xIsNArPX6{RkCx0Dgub3WHDwvIt29 z2^D$(2%?|`ijWJ~D2uTOAr9$)XBd$)Mv)Y0LQx?Ij^K=o|1byxX%&yiKZmdy0DuUH zPzR=9d96?fR49oi#F7{YlQ9VhE4h#D*pBCja=FlvhmZ&c8I-kTkc*%Qn~(^!7!{F7 zkxuzybSM=SNsD7ykcBV^xqy74@Q8`flj&5K0FVgaCyi=Zmiu^?GG>ub8HoVEjsS27 zb#Mr!Fa^0F3aV(AI2D&035`PemTwu04pNR6378|6mZ^xD(WsN{NPj?in30foina)R zRR^MgcaB*Hc}ahV5So}7mHn8OoM~dBSqKG5nsxbziy#V&Fn*;80FK}Y4CM%-U<p~! z3X8BBKq;F5pp%3-ow+$;W0{QXSdc=w8jy(yxo`%I|4<CD2^Gg#OR7l~$XN+Pmk9u{ z2&xH`LfM<4S&o=_ogDU&P1u`4nU_7;ldxF~jBp6Kpo*5TQ1FSI?}?m}5SNeu74Vs! ziGT<{*_%_LpZK{yb%s+r2^HP>n-Cfm3TlnY83_uCPLS}RR*?%#X9*`-m+;x0s}YhJ zI$|LyqmSqa@HrKUkO^Q(2|F4IdzGS)0H3j-2wXs(RZ*8RI-`YIqa9Y9hybJM`JPn@ z0G410jF1b9fSd{%36UTPVmb-x^q`3#3c@K0UV5IYxd@2>pG+DR{RyQS)}477p;elm zj!>kF5DRCQ3t$SSk}wI9fK!DE0EOxZmoS`?|G=hQYMc@Jn-fZ>95$)`iKil3rFGD! zm=_C+0H%`=s#Kw9k3<PkL8yf)37K$qm5`nh3Za<#h;vG*6;_&5nxMydrBGp_|Jaz7 z5T?mBsFM&0lOUXnaG+Cxr#cF!w3=Z%3aiU%o&cbtVhRAOstBE638YF1rpi#<3IL`$ ztdS54m{$y7dZN#Ysm;n^c-o~3dZOmp3B&20q>5aXU}lq02gSe%Nm>WQDx$FZs!;)% z>k45zimQ-tp4A$r#G0k!X{zqYT$FGLmyij<nG3%fs$goKx%#LfTCfpzr3p%;L<$vS z3IKkp2(dt>nGmt)bgx(8p4=)4qcEJB|1b&Pim20?qQ}{@?+LOYo1Q#NvMDMRlrXGE zY6!8=tuBjBnxF|*(X!T>38SzHn=lHIU}lFZtUP<3#`&{A+hA2nw2+XhQDLg48kd$3 z3y0dY3k9`MkqMRHo>F@WaoGtGd$c(#rbK$4@EW!R=ChCx2}CNUhARo&+O1Jxw<=2s zPy4i)0Jk{ho{|d{l`sj=zzCL53>0gv01&FEI;<ost$@2=Wh)7%i?}%(6=p^Wq@W0< zFbaFs3AB3^k9!Gq01ZqR3&dKnXG;l&8>&THx(z0zgqpYjplB}JvX#&Yuq(R&a0viV zyXf=@pD-1b3l$W53DAIdOUtwo|Ep+vYq-SQU^t7sqzbdqi?X7?1<+6l(%T8yYfI2e zyPW_PP%F6<8w*;>xf3h3Ei1D#o2rLez6F-J+?u}k3bUGU36&5F-b=C9yI0mb6|_6S zQSrK_&<WBT6%iZ2l>oelTfhb!V3e@HD4e{W3jk0{vCseptpE)aOA3263eXD`6&w|{ zs|l+Rd7v<{aLc@NE5s-Kxg|_s3oN$_EEP{nyA&&+YkLWx&<Qu3PO?i1G&~g(Y`ymj z0H@Fjijc)o(ZW+3z)F0?NQ}bwO1F|*yPrS|if{^@fW^lp#!z9yQBlG7TMUYTvYF7q zam&1BtiEUrU}m<)X6Cj~|8c*U(8H~;3fFbTp8yI+DhjdCxm}FEf;_}4T*&`5#E~l% z@(Z>1+X;^B3bDXfr*H~bd<t1X3NE~Tu`mjkFv0eVznTET%<IYg)v}K(xsv+{o$v{< zK(56A3ZOv8$YsY@92KX4%+Sz^GCaj&49vN#!u86_^aaY1`^&+s!^C`~sSFCAP{j<j z%20vMQ-Q}=91EJj2+%OeR7@4#9KhO)U%u?kUEIacE6fng3D7{!UYt{q3>Bz=3RmIE zP*KeAJjppcy|U}gkNd&*OkWahzY|==pU}Mkjm!qUR|hQ>>b%Mdz0j|)39Y~i7@Wt` zOS=*cwNhKr>{YK#|J=ppT+TNPy_Aftu7C=p5Yot1(CI7{Kz$0b0K2OI3eaoE03giv z`?NA`(KT(o*K5O7oW-P&xu_5eKMeo~y<A^?6|T?<oG@lo(a&7$(r^pau|cp=%~zUm z!4<sJQE|hlkPDme3Qz$G$K?t_P1Ip+(5L_ktH8&oT+&d1#a5lx_dCCDonFIy(>XmA z3M~tqunD@5%3dAV&lT8|%m{~#6^kv*kKJBzoyS&f&QXC1t_%vVzzMA&3!2T@e6<RY zY}-|l)LE?vq96-HO%<eI!&FV$EL_^?b-m?`#mWr;H>}Pm>k2CC)z@X#tN;M6fXv{q z38G-uJ}nhC|E%1>Jqjyr+~5`2RXqxdeaGpn(1X3zM+yx<on5Zr3ao$%;9v-bAPp0Y z(1?A-irvrT{au;N+~^J7H0;ytz1OtBqR;>Utnk-4W!6|B;SP=psH_M9O%)_<;EG+& z0S;cWYt<YM0HomD1}zPSzzN_03J<Q=$>ri%u?nof3Kvcepm5NTtk7co-&W1sAO2lf z-O41r*?<iSDBcR-fC|+O<H<GOSMdt3u;lM8-5T!72A<eIJ~C*yCm}B6tIgR64GPe} z39$eTGY;j-1q-k+6-*u#)eQi&unEOb--0dOLk`|`y(dwa<p6Mld{W{=KG0S1;JO<N zP=4sl|Appi4i#ul-6$&!CpinQP2s=2%6QHvd(P*1g5CpN;_+=2GM>2r;M=d@<jExq zzC9I-4i)pw3VJOKn~)2$VB3`b)vRslB%bS<o?Rpz(zFc#wr$(8Pz;+O+p<98P_gC* zf(yEU3jlx%wqOebLJPDo6{#K-%03kfz6rQs+sOXWkc`l`&dN-^>(O-z2aWCrjnIGn z*Q_uLrN9Z&;0mjb>ImZOxPb2fAniYr>i(|gurT9%oY?^%6%@V->pt!@T<+%HT&}$C z!M+N9ZPscI<?oKyyD(<iP9D(?713@B`OfUTKnt?43%bDXSmErrQSDJ-?@-~}?@sKQ z{~hH30Ofvd-4UPgI^OWnmGGz#?DI|OYyJwWFblDc3$JkP1rqWhuM4^`3xOa9Ymf&Z z-|Wo(>?$u6C_f&k{_eU<3uf->hwkL_o%8(7^VSvdL2v3(;p(yg>BS)JN-rK+&-D2| zUR{s|p^yq`kOnFP6?fkwF7M#101hfk3-oOjWgqbf|J!KKT#P?vK`#}r0Pv3v&$IC6 z<6-x9Z}O=i2W=1v(!dL>kOuGW^qe0a{Lb=&ZupiU4Kj}A1`i8sfAbLj_|HY_wJ#O0 zAPcZS?Ycnb{J!<M!THJJ^vMDM!7vANzzeqE`EQ^L%z*sJA0#uL-LEg>YA)ex{|^<o zjr-EI`=-wJ$}SB@3J&i+_u=8})DHl<kP4V!1);zTyHNk3&;><s1@uq-$*=kVK?{Ju zfdC8wki`ldCri>;0eE%Lpet7rDPEMAQR7CA9X);o8B*j(k|j-^M43|MN|r5MzJwW5 zrpSvFCsy3ZN}4E6;8@L)HM65GqD6J>;)SUTrc?ls@*;#o&6PK)jvn1*P#1u$LL~|$ zXmFO!R)!oR%vcjZO;@YDzJ(iC?p(Tc?cT+k_aobgu3kmds8f_8aAR%RlDoC&F2)9Z zrI~ZAsKGgH0`;2Hg%?)FM7`od>`|61U9ozyVl~?0+KOy(>V+L!_H5d<|83uv$@j0p zSFj|)f>pXz;aLDe$KA?U`L0^5x>yCk3&1R1X$S=ZP%BWNTUQ%v#XDM>CBoBvOZ@w) zHCx>6-M@z)U;g~Py3_ZDrFt|haE43~56i2pb}`DStWvS#5$bqh5SLo!AVfi2Zt<cK zUI<i9tI6t;WtUhs0SA^@U=ip%Skhz7Cf4X<u|*eOgfYhY?ECAy(SiyJ7KJ#81s7Uo zIZh~|2psaeU<i357+s`uN*7ije596Le!(Qk<-R+pE4hFw?KGeQRPDs{)RM7GGtWdb zO}c8j4?oomB4{jd6p2L_TZ)6LtHv_aB^Wy}2_`xQcL|0SLgv8a|Dap)z~mOBGRzA| zX<{MFu#A8+2)GknQ?pY~KLs_^gDARBQ;uYrWfpKYS!EYmf`n_pr<h|Uji!E)=oeY8 zV4{}dc1Z;jJ5pirLMEB)D65!e5lEU%ph;C0SOL%!xG^yjHCt`B<yJNo+cdQ!ROck^ zu41PI;Fbha`32X5g0bZa7jF5*7-oK1Cc$5dEjBuT4_a;}AZ?L`6KI1HR~BpkYOPy` zABH$$m;6dk(;EwdGqhBpQAC=<fQ;+det8LHjazClNIC|cDguBv0!d_$OJE^{5M!R= z<(H@YRrVl$VUkoDMT+qi;f-!wSVf7KX1ZyoO9k%600%m*{}yOUArLXoLgsfDVFCd( zt9A|A_ZAmWXe2dQt^nYQmX!&HU%6BEIVPf*rA6psb^($Wu+TCHX-#)i+G)cNN8D34 zr4A6WIBO|}6KQDC5-yb)bl2rjHo_GX7hDJ>m|uK(#+gQ}VB!i|m=Pvt*KtMmt>Oqa zI90?P&*;YeAWFP<-+zCxH)=<tMHascntHlgi0Qbitu4>F-CG`c;}!tgbvMvd<}m0M zTr!6@jnh?UhF|Q*7E+huba9qwW^uvAxWnM|TX&;(13rKKn?}Svi;4G}K&B-Y$Zdid z9>bGR<c7KE+(HkJupaF8r9JL3p%=BlmGo-ShEz<i{|jk21~a0wuk(!%do$rhF-*aW zY1x7x0W98rFttA#*05Xs^Iv`d7?N4&;%d?`*UA78iZ?JOgBb*XFjDad02HAY(t#ZS zj$sEvh_Df9NW&wXAt=nbP9{Bb5Hv&~ojY;lcmWKP4b`~DPaz@^@PXm+26zx#@S+r^ z2vl8)wJ&BI>KGXbR4{~b3(w6fcELDCm5vOZ<wH|{8;1{L8zZF|%|>^_NEdW>gES+h zL=*#7G=hYbNQ-oLg9w61iAX4+hzJOXJl0Ph{(<j{^F1%_bMDXQx<*nxQ8-2i;JIS+ zXHCREdVJ;%N#P(mUuYvtNa0R)+V435?&kTNqg%pZv)_$}$o}`Z-<e#gny16NO-f!@ z{2-E^_1yQP8FB>XYr6{pJTnyF&ti$PVOh%l;2q-N%G)33Z{$sTeL06N;wc}~vWLM7 ziW$$f{7}y|EYiWp3MUo9nmyYE1WW~|&1$yQ`WrdSGN|Agvq57xheR9*xcu(tR&F0j z^8kYg^MCXuc0Hw8O5_U_tY@{_3SMj39|@i8_yVuNu*jIDiW|3b=|6YRHnx9%oR-B@ z>D~JJ8hD@carcb;sbp3Gs5A#EX@J;QNJOLklM{?6W(nMBe#}V531$OR)4isZDw1Ny zvA!aE83V9cp2(XZh({%Bb4Q$2T!Yk^p#oFu!$=a}awv19C-josH33T8QVRDY(k=m~ zT*hGE7~q%@s2LTSgnJ986>>{6BT2(%`?4VG0TC&VyM!Rx3weJQdukJ5d!C1|zqN(- zTmqH`_hG?!{i26aLH5F_EkQ0EEz2%{XQU%SC6&a-HHomX&Rb?Q3P3Xx5uCz3J4aCq zi%4DS0fpf{Jy&jq+pYM^wZ1E>hw<CJ`HT>&D}KI$@95jGymj7NxFIvlWRu#io7#|D zJQbQK#o+IWWSlbcHa{uM@&Zb^2z)_(z#2?<9W+GX6XCe-wU(FC=sp-ttLB=ueAC2N zdhf4Xte;8}1_0XEpNCUE89L1Q8b78f(05_nrO%lXZ5+)vcvZZWdZ!cBIC8A75T=+o z#hK6bBHTbVKZ}B7MsmzBd)@iA3ULtX7{-x}WeFEqul!I|<C}^}{v9R`%JxoUj=M)W zqV=M=N<QP3YEwQ}kqkhp1w6@x5<11;sakhyqQhuHC31$rIeweY(P)h0_AQ3B!LRW2 zJ;LqOf)|f|B8y%&ha~6PYy3>-n0`P}xjR^t_3e&$0|hWlemtF39V7B2Bt|iw|G8CV zW5LYm=69u9MaI^{ZPrJd93*U3ipNSBXO}0x_q#vz&sVoNjsBB2ouhdZB49QDG(D0e zJP_jl)_=i`Q{E*41JB{likc;F_hmBdt36rm9E^Q<KkIgykBkpbJ+xI$vy8T@iixch zrY~_ji$Umr$SdZG6Wz`XzSm^-U%b*gHL)-Xxv+q*3HMsXv~e^VNLSEu8O%S_r%~y- z{4F+cu^K&`-19zcjdR8KTz@d`1SYl*pX@`E#XRqRmiF{!cVu`jTaO3`_{cW7Sf?ky zGQBMVTH}5I8&^JF+r@IZ@*G#T6A>lv$m$z68LzVaRkQ0UQ8eUfW!6Ul;f}1{ZiNfl zr>XDKoG?7Z_1Sy_m6C`i*U6E~#(EHo%~ML}ct2738w7D@-WO0H*4`DDn2MwFwX0Ya z`eiUDcPE0u^R#$QoSSzf{lDc|RP2Ia%<Wy(53J98s*L$*p|Y)mH?AS)%U0O_B<Gf; z`Dpv_Eag*L+{%*m^^iBr!ZE_=mK4_y7vAqbLr;}*Fs@qbKjC(&e*|e$XiHlkt^dlK zoa|Y=DJcebq=b=2>Iy_3df)s0fo8~9^L~zNnD2J`q&~{(T=T_3TaS|ae@ew$X#qwP zwWT#A(Nh_DRb~Pw8xK-dff5i)@f8~0!Kp@S!D?Hn;eUjQvARAheO@PhFp;jUuU&CI zl!zkv9Jm@znoRv0_FRJQ8~qTQ-bk4f!?#l2T!g&SCius9$hp?QZRdeEQ54T%@)AJS zn<Ju)9&4FG99GC43fM3O^sh_2U^CGdUHM$Ni$*2MFLOw!2s_w^Ue==2It|DiU?+;8 z2Q@>h51VqjbrmBi6+19ix84i(=&^66C9*pV$yRw$TM(ZlvV+xC25gO|0@N>@GQ>;o zkVMiCCuxlh7{DOTn~)F6qX9|K04IvC6Xj0aU{Fl~9;P8Fr9L>FG?dLGRXn=mGvM1y zv^v(3eA#vNj&9K8xUTeAu0p$0CdJ$pSMgJU?ar7xxb8bF^`n=jTK_|c6lY*OMCT*q zS~sS06=D`Xfr~fDv!!-$dg!r9@xViW39Da=mrsW40&rdb%?S-7@(?}k*B*!@INmRI zc)5-{SOF?!2lYYq-?4=vBPl-dy7>w!)<$FL_}Z#PeGiezx!?K;$GXpyVMxT)Pw*Ta zI%q^G*~aRsnUKbX35uj1OC9J7b??4Js8A%dp<&V3{+HsnD-G|Ck9<JZyfA_UctWMl z#?yalDYzQSq)`loz_I-!ymtoU?hx;gXzzhA4SgjRu0~01H3VOi|1`+9uw?Grh@E_% zW2F@75$2g+5TU+DyO-i8E0Wt!p<97qZx(1sagXlT26&(JgRe<qV;CTQ>fR2MP@Qfj z42<#_D99-fs3{04HQcg=N@;8PTh%+mwJl_NnZd|RPa|3G$?6=lY7K}TGwn4}b}FbT zF%DIw_pAY|G&M@XIfHeFksisIYr_U%u~5ICop7!GbSu;3pJPO3{T`BWfDzOoUMN4u zxZlk1BHYa|%8i1Dn+GKsj^s>9$w-*(L27N#kA?>W0i<hA68){2sU?dKEoKj4^jW=f zOgm<7R!og{f>us7=uGPL{<hWwtq2MDjc&-b&ECG3Np~yF0jK8=oOITGp+9>W(EYC- z#FBV-Os%6Sc6egeI?|fYY!_VQk!c#^X13oiV3C^fX(jXU<D4o1VG-1BP*>AX`Gnj` z{LxN4XMlKFQSddCWkpybdV>2vRyEapZ_P4_q&wI@^)F|7SeP_2Z7A@=;17sha=UM> z`05R7bN_tGzZ~QIklD}c<+(M_2ByX62dvJL`49RtKYy81IOPAMSmF>QnuSbhSb|)* zFy~!Ln{-hm>AfL?m0?sW?};YNe-d{iUg|;V3nYg{)JIFSNDUf2^D7%RSUiM2APZMv zjf;m2Z%|xoO8V%=dG9P?Z_Lt)E@WAmdY~!ZE8w3p17G#>Fx;6{?2GmroL!rYDPI`> zB$PQ1L;M%W_D*E&MWXs1LBon#6)!pJTJQ~3Mh}S(FNN5`X#Uhcd(mf!VWbsRozYn7 z({EVF@Kn`8X${sb$gY;7yX!vePnkWovG7a2?h3Ugzvk8xRNO%ZdB2H0%(M3-zb}Q4 zOkFAO=5h&#VD|`e-5@jytZGDb-g%kPpQ5ALOoa31vOvpd6X(Au2jnJS7>5$Cm5yhk z`>L&8q~$|dTB#i}t$OZQ8NGRB$m|@|VdFKtU_J*8oD`maXJgAz-u3Wp(GT{NQpXw$ z<6ZkMi|)1`?M&C+aQCf~>rI$?Bpq6x@xH;*{7!31OVWQBzbso01=AX@nc1b+Kz#}F zVY#Ns`7JrQ<DYVdvNx7m{gUsjY2C<$t`s}VJ?1TX{;u~1ZPV>!Yd9pM#>{T`jeRLR z1<mLTq}S1dwT$>tKkTb(o}X@|>`bQQY$I>xihVpKQ`?Z9lGj!jEFYomh&9mU?&Sx2 ztNV2e0hurdY9PQ2+8$^3Ys_5Ce1^)Lw$mMo$3ynpEqe>Zo<zuA^g-S~itjBDf&j55 zL;B=S!0omuqswt7dXKR53xmazAip5xnVb@1wpsHpTgt>K0|HOUtHhs+S3_xQ3$KO% z@fvu_4KVG};i}q-JAigi9|k+%-Gg<KewmU>zpmsBFW4~Ch)Gr-#yM6pya$WX(n*8M zgvi^X<edhyVe@p=Dv0@}y;w5=T=u@MdD8)OrM9oi)_%pCu~K_ged?WCZoC8Wr`w$S z1|GJSx#z+hc`aGuF;S=omEC5!1nth=Dk!D6O+p-k9jbq9e6ZgXl}p}&B%1)V19vwi zbs<)0@{)vrV>4;5gCIReoDU(XZqRKjGG&#nxt)4k_~gO@=O`tmmftxnYTvB*HA9K5 zl&l&`<71-l9(f)DXw*T2E;mD4TipM4mWzm1HP;GiC|;9fuE($FKfUkq+BOkLhK40u z{3Kbz$&wkH(hd)-o53ExO3?r$K-*>L78%Z3S~drp@~dSHlk{GIUGwx&FZu9rZz&D! zzHv5fx3?v0vyrjqVwUL@fQEu{lF$M@hVkQpcqIp|E)Od%TKf$y4_cpmsBJvdw^={M zUC5O4b51zePyuE%36q#5nW117%WIagoA$Bf92{6of*`#IvK_qU-VGntfD!hZS=I-q zy-II>8E)wF3x{8Gcd*MyqC}Ze{Es^>>?^JUFmG?MO07mbF(110c=wMv1)Zn-Ky5)t zM?GIi-Jdzp#tP3VJvLJyW+L#pK$kXJ4JH8vVrEGedthMhBg}(r3y0{T`K6mP{`f)M z;EcohWy2cDwRJ_|dFGkf(1_SP|4F}0yjR8w5=7ebuc1qc8SvVLg*qYAId`v~?+4=T z9PrS$w!6ewXuttE`(ARET_6!dsaM;}$qFijhGb=eO-e~c9-qzTNRP!Jc4&z85ooE0 zU<5!MhQTg-^zVlSl}*$#<NZE7UjLTslGou^Czd$y{*&br>}t%GR60fIh#Vkf*pjE* z`fsN_+bdLoT?7mS;SVpOzJ_)leej4M=!OD1YUlz_!(0c_!fx>KV-ZoNgS|XhQC^Zs z^O1>Fh|M0!B$KF`sYL`qtS*U55Mb!}f#N(Ox4T<M)8tzDN=Lt2#IT>ScJksfjQS(f zyXwOz-rW%RN3HjV#OBbIHFK>!vc2uD>^>BR!CqHQ(zl?E%!Xc%%^Nsce+KEx?cw_Z zJy2H)FiavbKOh+kg?wEmS-{DrNhDkn5h+2?K(jlb$&$0Mu9~+qa!)1tB+{)oD<y{9 zdgi)MRq`02Y62O)Rud17$GNJ9#9n)O#OQ3?Npp4TXy;8vdzu@C9LnCD4>Y1|&iZ6j zQ+#W7qlAwxa(`lTbt4}^2e@!ZrUzkBP{1&r#PR@af{NfUB<Xk(mW+vi7_U#SyVe|7 z5X0YCYrrbFX?vf~u}OKRRK4yG3vBx|-(Yc=?i8#vlor%X`M{KH2pk9fJY1gL*;tRZ zzG)2@QH)~2Th-TKj<loWit@pM-$mQ=bL+@tM-<m*eE`6LBaCXm<~1bTFtv32fe{K~ z1CTA}e1V@}qJ#(TX-r-$>R~)`ejb&9mI}s`y#cdT$WqSF!+>G3!)qVQ|G`3mctfje zL7Rt(orm^+BB?EJa;bh*lRy*kp*bFu@J+J070qw<CD3vwE7sHFn*H3UD-lil=S;dt zYSJ;8BpIVfs?DIDIIs!++#*)hJmxdeDFi@8X8;Vza7lYr&-Cyi?b>JA?9evpFy!FQ zC%*qZunJAyy9wYao1IX*u3%#PK$=3Zm{i!>c_>!{Wg~hvjwW7{i5yh(;c)<M!5Ji? znQQ}(_18&K)!K4<%1gfXMk_OkUMmTDFIHVi&!`k^x=EcDK)B*^`FbCibc3I$CE>5p zdXhwy8MHcbny%VGuc4uM1xQ5qR9f?Osw=dy_n{7`AMYtQS7(!6VMetl?xgDemhU2m zsU*o?|FK>D`;il+?k2>-C~=-;@Ym(C^_ok|72DPi)X4x?+VqcpGuYJX^@Zv&LH7a4 z1WvY)I7v&28F-Y0{gz~}L~HOrSPSv_U$EgdJf)5$G5@c5#-{bl53s5G6j#{7lk1_e z7fB(*Bn>n+_KJI~_zn4+2FsNc?IZHOG39@6|K=&I)m>yp3&o<AJJYF?JVE#W19=_` zjgsiNltT875#vd$;x_g86XZl1k9y?6-idH226+V$`B7q?NB&ZS^CeQsp~?i1;I6;q zQ;3r*8A>!i&E?h+n`Mq#C64#zNfSBTcDr@l?dI=Cf4MB5RgB>00XynrdRzIBH|;hR z)e0_-Z5!B*t-N~a_|~O%m$qeT_8R}?T8$kw@l4lx*dvy6RddJ2i|D~LMgO3=6-=cO zM7R=y=Jd;mSBg41_@%rzSI&0yZt;as=~6tCbL)6OdajgNBkEzLB%25^N68Nq{!AS( z*SJcxk~|kMR*K_VeJS&+rkOZTCE>F#&C~9-ohGX_F()<A>QZMP>`$Nlz6amHU+<tM zts1<c@QSvdOYZH!ltPP%Sm!(0>u0TRRRBEM{^mxqPqM_?4Vrg8FdeQLJO@@KiOe0; zjY#Bo(R;xUeSH2xkSMa9Bou6Ct#2B5ygP}^02F8er8i*o^+Fg85HWE=qQheN&*%U> z8<Huu7jBoM2ci{D%U)27Ves0prnZn?RG=<Vb_bzXuon;|5r1b$1_xu@fHo-4$+d&) z5$4T-{acrq@b3(9aS?t(x28x0TJ`ymY!j}jGpvV$d-AiaM*!cBsb&vam?_s&4*V$! z%JQ)cPxhRYtSL*;lybP4(@7(6Ux+XnEZxX%gls@OG!jV_^7X+MZk|m^(3OEIaRzcE z5n!CN=;K2+bNEK|8~&XQCHt~ATIDUP<TvFz_7!49?me{Pjvrq=OIJVRCYcvUI8>y& z|7Dy^=SUABir+f2CJGw5>lQMJw<p==R%K8fi&ST4(YYXKr27@da?BGThC-ltDS@QQ zz2_;ie%{7NAete*fyNlSm`=m^RvKFg&<{&pT=DYHdI%hh`s%&bDX_Xh^J_a*v*EZE zkDEn-Rj}{NI}Qt}OK2Yz155UgichH&Ui8o&R;8=mYaBI~Pl$h`GWav>qiAJO_i58j zM^y-S8&rMfo&WV|9rX=b;|MEG7dLhqejq-HMt}e#oUl54ETefruIFh@1B{Tg={-C- zY!9w<6m!cfIg;2%GLUwGH!~y4O;M9@k#=lNaE|}NyLHD$i(Bu-kJJEW(6Dk+X8>d0 zpO#TZ#1Eb9+@b?7@^8g2?MO!ZJft1}2*ftl3UkBtzRvkO99R+O2?!ZrL-^QfJ_wy7 zVEm>s*7{tDnc(54yk%}#%@xL+|JhuaIh(9h?1vy<sen6KS|a?UW1MX-J4#P)D>f%U zd-zMd#kE3xiM$VB`cemT^kF1v_uer&rHlk73!^daToYdG%6a9KnPr^Z9Rx$eQ+3iE z3?cxC=VbuVoX(eBiHjd&P1z*N#Y&098#&=g(afS@B!9LMyU%&7h-16tfay94aHYJL zl$4C8O`wmvr00c&G6yxs@$kGO3PyjL3Jg4eh%JPZeMKr_;vSYdOAr~t@d2h1c1cQU zECZF}&6yN!-^A*0=7CqtfT{|Nn|T|GvRY7)97$mQ0KhQASAYn%SD$ptMZ~3oJ<~L* ze87`euO*GK_YIe0`(eO^vl2MQ4a3FVGt$^t$&wzoVDKjGW@cUBj+{PTPn{2o&d`SN zr7$N7KE9bbQOv3oh7(b1duIMXLW!Qmi}-V;nWD2^MrS%q#kPD5#S}wTX*5Wb{1v?l z1~d3C(@)quFNTP5EPD#o13mmZW=N#8Ra>y9W4?c;9o#o|zZF^-`!-cwyPRvy^AToM z0y82s#_hzKs9gE0AMIe6IUl&CW?Q?Ei>)l8c?ZIU#Zpw)5lp7c*sYI3iMnT0;rw)> z4o1c-gj{yO=I_F1CvJM%${lz$JwD+SmKC(A6u7S7Bd`2>+BJUL!rHb%wWcgR)NPAy z0A8ZTD#a7*dqGo)@H3jVxTT!a+TIv55RC1oiC4_oVhAZE@`k-EAKcht($#t8uM2rC z0=+DG*ZR-0jt==8w{d&{hHbf#ZvvAfWpDbz?5Q$M>vcmbzF;?t*7wpqK9;dW8BHk9 zsq)k%;cVPl3XPtz8TB+WHx2$LYdRtX9o$y9<PBmu`q7Dl^Hkxnn_mQ(m0%+NMkTx{ zOj5$q&cq}fXP!G$iLU**0@<{7+Rg}5REEArI8WHHYAQJ&W%P?KV_`egS8Ao2nJb;; zZHT9ww8mymzU1hJ>K-F{ti}}1a_JSr6S$U#yNH_!2;$F=33a!YD9tuJ#a4;(N`IK2 znT*F?__PNFl5a7;6Cg3CZyKn!ju?d2SJ8LiC+_~2-S`@{!#z_Y8{bgQ5FkNR$a?iI zj9Zx>tlTrj5L}5FJSHoqCD5aW6S(@DalrV<6iZLQjZp?8;@@tLO}v4jkL29B44d_B zlL^RwZRnbYh=DM==W5t#j<A(-`e*P&JT=CU^FcLFb*6!8-h7olQGCV=+V)6THqa_C zfnEVZ4et#9BxA{nxJ!*r5_>#4fm)qkQcSWPLon%+gn5u+CzzQ?53f#^Ah0_dAlJ(U zDdYt99v%t<o4sj`qKrQwX!Wp@B>%miZI8dSs8xE=MX(o4dbk+)rn}ipB=xSn7r1!E z$zC7GC&C4&gNK>={(iZB6*{wOKdD%aV6q^MaU<1W0X}!-Q_fmT=bf&*kN?cHi^cJJ zZ$YJZn@2(?#o1$m49MkMY540%evs?gBc8)O+t$7vfp1CgyGzMCjeF|=^Ak+(--wDl zmzk#)Fy;QNRPR`y{%`Nt>IE0j!JZZQ`9P{%oa8abbRKh;kr*&BpQJK(Qa<@lW5G~3 z;(GUJ>kA`FK4(L39!=yYkBeSh|1+}e9wUuY%_y9w{FLr~QKef`MwML`L(RwX-R@M? zdtrmjs<qSUofA;?oKWi+ozT4r<@d(|5%iue&5VWtD92q~QiPR#8flk7>Ea>FGh==| zGn}qbE?@c~BXQtN@CAtTG!Mcz?s?Y>MlHffI3?b>y|EFaZVT4V4`Hu3+BTxhe%}dE z&^)ZW;iWAHYr%M)_8*7L7^p=uo~)%;@J7{GDmT(;ZJPh<&%bG)X~seyVZ`^Lci`n3 z!uR)&)Zdp`BoV;o%BAn+><1kbE#i0mcUSgXq3L0$N;_dA%Sqr<mMj8%Ad+(e;p+{@ zNl6sT^{_PkTJ1?<S$H=hYnF4GKBgv-33sMe|7)zo_&6YwrjYz(C`S-m%Cw(fxY{hp zV6wVlhT()Iuq<7J4=)KLz^H_ctO6eNtA#I~dCF%q4|H%U2fW?m7v%p*mUfqBeWF4u zi+ni!<-#-N0H*?uUr`|{F~VuMb7x|jvw*rMXoL)<R>djTP}3$XDWj<8R8qn^+!&S- z1W61QmB2g$FgdMa!V^56Z(i|U%bfB`=tua=;xr{d%64PQA7@J{$^ZLd<3P&?lj2oZ zA@V!Fr*SB4iWo!97{EO^#HE<k!B}}aBS#^eay-#4$Kt__EZ>tS{L9<dRTD5q32ftN zhJJQ4Du4?>3l+NZYZi8tG0pjUyfz}Dw5i9pQk`p7wyeDa?S&LnspTb}$o<D7jwIbn z$4SgkvHdMjR}c~>l<vG^;mI>pCgG%$h^XkLSSnzj`Jz1kONs36j+*KSn^6M$aXA~B zA?L7Emr~Ff!Qy!4R5^~-Y~H4k99OBHcN8VTx!0A?u)I!7@R*$@FLU+HQ4SRlq7thf zOKb`iIdjG-NqkTXp*~Bdl#XL%mfRl5f-BxtOn<4c2(o1b;{R}ym{C-EISH~nJK9LF zk~UF&9P3@mU9MdTvhi6|07Lwq%-<R_$SY@$xqLJUEzVYrk440LE2+zA)VqDp?ou4g zh%*>!_2{K827^Zug*r!-?%s<m@C4S)ZH8k6;5)*OeuvHH>pgseq1ff}RbiF<G;7M< zz&?P==k1tm50b3aM5vGX9;-X;!cU9U(k`gWBm@Cpe|4)&zZC1kGpv+0NWK4K0Nh+P zc1$6Yx~(e1jbis~qbh8|iWQ!~a<;wE{{$ERnmga^X|BhSed4m08&-%~DTyfOl;?BK z?`PuIgwQkf5K~8as82dUT*RKdd5iM(=03-&=OBY_<CKN0f_tk2X2@!0V`3zn>N>AZ z5R3P=i0+ZteW^4?_&Bo&#<Cm$V4~RY*PMULEk+-gli8!_wlG3CmEoPlXJskB_*Fe5 zu#=o;eq(B${=Au$!S{q5t1&#`)HD%uw|8A)!hB6@r(}JvomG8`Ga#y=aL;=RLrZ4e zVvH@$#WM%ZnE~{*Spb;v%q+jShES{72N+egpQ7N{I@K{6KYYpF6qcFi%=y#&s~XT< zf2m50enct1DD};UqH5?Ta-lf+eh2wjYL`KO6>TEQi0JpO$h^dY7_@dz?AepslML&Z zDQ&&0(15>+;Gbt4ild(1tP|youX!Um1MJ6C^r&4;Qq(8O;3?Xtv+q(Q^=K%yAv)B7 zOhu|oOwyGYi8OI_Pu$HQ1h9^6oPyKne^9IElnN?u@*>upOEm@UDcq=Smdj*E;xyTb zS9Lh%mp&>heCdE}JuwJQ1QIatFBnt;a^#6R6}n2lAe_T@LT4{_!$F;$S}|u#Wzxmh zLAW`{9vdQg45aW{Uz9jvi<@ulnI0u#La0-)*A4*>DZqe#ULqiTpO%v-oinC1?uUgj zhVACH8-!5y;xVQ1S=(C}co6n462mE~Blnqk+jaQ{wF)y%sX@9ygI7-qJUB}eEJp1( zVJ&esiqaG8ovV@eBw#j!i+h7m8Bb4`WddrvDiwUHpo|ss!kxx4i$O`xe-AUm!2;Nk zEIAV4-UD|r|3^ka^~tn_X_=^xhCIerePMW92u{6TOagjf)EbmH=zI2yfQiPX(yiee zp9`mreY#8GsU1_!5*({$@>Y}GqCn||NK8KgR`>`8Jz}Y;_hQ*QOLFyvoXcQx2vx(D zmO=W7&V?8*Tp}h$h^7I8$SI2zAPpVWZQK^#d%1$@&NuG#H6>7Plc~jrcM?d+%l65c zKLWS@HR|&<V%7nGVT9$(e@9GD*!|Fgklf}WH&+Q6g5g{uq@G%gzdw?Wn_HpwNZ={m zbN*d-K=C`<zzPW!nS$P@y?nvP$DcYYhtCO?>*sR(SX_D3XpfdYKDuuB_p+))1xQd$ zm|!~pRe4SbeMu-8)0F137!x+Bb*?eg9LFlERC_p)3~u?Hsg9vyaXbnm(2m_dgP|_V z7P3~aoCQdxF`kYOMT(a*H2n>*w{VKxe#(65E;j@M5@asU75sz}Hin<LA3d#*`}}G4 z!Y08CcMD!8fgba7KQ^3vff}D*=%}T8Ek&F7Nmjy5eJ(VSN3V_m+2G{qVW8IZq*l@v z!LDDgK-XUxYSBOQ1^NWv{C+m9viBmgq0&N1YdO$%Roc+$1Qq>?uaa=hQ>^us1Z|hd z!efOLG26q+@J)SC%IJ0cc))XK9FKHLp*gOipMx(^$pK&A?jje^AX-%&ENB>r14Sm2 z!!E;B+_$%4&p`;GR@3*vi7(|=QyiM@1%E~o)%zW#fD{GS(|}6iW0z*0ug6S+RT746 zdVnIZiF`wMLfEyPJlzwx*%qrpO(x*PZeLFGIIbFuN;r<oHB<4$(ZFfsp~ywHd~>zt zgI)Y>;%%PCw?+f;#X>4hSPj(9Tyu*G*O{KxSFC50Zml3L#9BR08LN#`H!@LAO8p;3 zkA`iOW1XN`^bud%pdbt`&QSR~`cC-4uJBEw?2aQ>qUZ-ToMsY8IgiH8h(k4co{6{J z!ccGNJe>NfN`QViRj#y3EbbQjE4^YV)F72pxX|V&o>40PjraS5FB^?xaGTu94pDRK zosucNDu=pHb5e*ra*Md>EsLkBSO$!xdP7AJixtg}3_n3lSSgk<C+^a83&!&N<xU}N zV!$3>O8i8}z8{=Q$CazVpN0zUg_6$>wI~hJANZ_rZ7$b3+x@e~ZeK*YeRaR(M7&@x z)|-<^SEary#P%~oOunw{wBft6fZ7lUD2~Jl@5x~A{J4`@N!FvDDy&xnADIiE;C$2~ z3=jI|E5t8Uz&M3^mIg^Q4&B#^ZFW+NZjmdF(xg{*9BN|!O}-VT8uDG~E#R(0bB+QN z!ng`UxTrPOr!pe41Oy`@Uf*mFYKWxiaFf<kw!&$sv_P(c<LtWRqemR`L^fOU`9nMA zZyY<;H6Mtv9Rq?+747qZ|BH#6aQMlk=}XNnt|!2#em5~TQxi)4;zqCBIO9`lSp^Ph z&{vwUF%%xhH5>9H6p1U{gXp{O=_(Bc36pNB!~+yE(ZDhGf?An@sOd?J9=oZIt4X@r z^O5e-B6@Q7Tg!WX@H~ZxXg_`5o1r?6LPS%g`=~aljXO$j2z&m(rd@w9efXd$N{T^^ zv?ynWBVIKRz#X(?<20VEmF;;Iv1mnE4H-sV7IX67kp=Zs!ozziM+lD;Qs1L!%p>0W zKOq`M>U2G;H{d5-B_OWc3P@s^Uk=wm5u+3B-6qK;-)=qW(u|}OJW%>v9<6-K?H5LS z45h992|;p*#%avGAY8MzUz;a>=+u0A=y_ees6y7EOTM*Cg~aQA9@-I*bX$3edZ44# ze`DJG!&zaEX7>k=2}Ox3;t{NIeXM<neVs4Vj<YhpU#Q_bNBHg_(jqz<GQMH8PlH$p zRnndN0&!9Tk2C62bchk<QBbvRVQo<BN{+r%lx$sM-?%By5w{2j=4)JKU3C!tP8xF> z_hi6qTWxI{{I-wYW{iAs4NM$7B%pQN{i{uQjq`0iIhq>9Fopt$&3DtBS@ge7U2XH_ z`{qI(E6KpM6m+VzVVFaC9n_26F<-n@Uo*Nh;J~Y^O2;GDO`&ZBYQcraRSRBNE@9;W zw7EJnwMKX>P9f7_@9*oO0e4zGx&ilD{6;5DN8C#4N@cf1JWfMsUBi*cLDLXda!1EC z6LIxVFwMC`BEepS%^_gyR#T9R+E3ixPyLXKvBZWyvr%!`V>){~_VkxN=DY8cUOgOp ztGVKN>v1YUGbcAK63=NlZfy8N*j2Z^?u;*Ue?9C5qA#XHS_5T@lT`7?%~*7OcH5I5 zGQn`>3cZU@n3|Uc_pVJ3F!1-*cxjNvSlL@|9XXym=oy#qJz4)3yv8#8?H^{dtqec+ zQ&8Iv?WQqVY5m0UeKyUw^3cCvwh<W!T0u*VIlh(fl9?0SJi`qn0_7UTYUw;3$sCFf zZT{xS_%L9%(i$Ab*Oe%4U2XR(lea5uqx&-P8O#@-w-z22{Hv9#I*;jUWZ$RkqOK>> zSz<a<^IponUr-6AZ|mQU1&P;L*X7-~;E7N6=#%2m$_sIB3z)CA@5>8y?Yh1-k*oD6 z%)MoZ56ag0HebnSBI7^zPKGMwF~%&H$|P&)_y&OvmVImuSG)Imp_gr8!+`~0Cpn}| zhkiO8(IrrzLOZ-yVO8R|b~oSLT{>dBv9`UF!{=>tYXS|IZgFhH&WkMZrs-*f{4Q_| z&6c~{q>y-@pXuHT^U2E;_li)Cp^hSTvnZYop0|u{a$#$HLH>oEex?<&pDS5ImBeQr z)P&xyDe{0B?>?Q6UxV^{>t4=O4K*hwJ+zYbbEEW%Ggi3H;;6kxo<P2ZywA82zB!;j zb*`mergnlibXHg-C!#&MrgLrkg4%PivwOs!&rCt`*-)tGDJ<R<^s9bEnD$u{Drh2* zTr6t4AW?UsHe)j_+jFomEpr32-*Ziuon`#%!=R+HaXW_V<)_#d+{B~aa;e8QmE|VN z?VF}wo<?Ae4|RU_A{Hti*c4QV{hJ8<nDy{n#Ddpi?w5pmPW_Tezr4ob(&FW++rG-( z#yf*cX}XvxexIbchdAWhmV1Urf~1Q=6as~Z9^p48E%15;Qp%M`^JJ4e2jOG!pA4!~ zyZ~$ZD`9LHh8d+*wN=R%RBI!-m;y8#EnUjb->yd`MjhEH*)v*8I&pyj{ZWe)sM~Ts z?Wc4V9!bgm>}FLzsj8F<*;H|CbMm21zT5t8o><?1GM6&>hUr<iQkG87L^W>~Y&3?+ z`D2!$!&?oz>F6#QVsV*cRZ{yGv0U^5>{HbXxsD({6AjZKpQ?=Q-7LG}!*6qo;JaUp z%HaZy1zKY);zdb{{13Vk?+H79ZRk1D)W|lUpqJ0Jj<l~D^FFkAA5cH<?|(+e`1<7w zRLo3~cghz^P}e~ltx*xd=GA0L3}LDRkS;M*4jbO`EgpFEGAFD_vT6Nv`t1UF$$i-2 z(M)AM&g3w=Bw~UmkvhSZ7uK+DZpdG-4Snq3VOINkHYMoGmdCj(qc~bH)T#QlU7vd= zz868skBFQIs@qVwpyT@f<yn)iuWN`g?V}u{!{VNnY$S^)VcQ-0Jg~&sfcN@)CJ1jx zZ}0xE^xd_+wx_1aJVpMubtQRsUThcmpLu)B&C_Q6USc$3E*IHAnP-DUB(H~n_{DBL z3DXo4;J7h<oBwQ+rY&dS@UbtcSD|bd^|UcjJ3w~5%u&hBjviZ@$ir7)ptt*!<xfPK zaEz3J%u5!=e*<K1v4SyK4{RltR)W0?FsTsW81Z@YoOfH|`LF|ah(S$0Sm<n<Yb1%! zE#w<X!ptkmOqKKG@hgRC6eTrtT%P}=+JR}ljMM8yj(@B$pJRxC+Z~aL2oafN6W$lX zOFK`{XQRdz(ie#mDJ<h&&g4YyXa<vBxPf`t!|d=8eePG2qfB>S%Mc^Dfs7ViksD<! zue<3~@jr6I1NBqSi0*fm-_qSs@iDv;cZL1G@AWIuKKLC46J>#{w1=_2$v3vl>=(+C z!eOSot4=1eI-MBW8xM;%&Z?azeoiSJ5$r+~*NmY`jG^n^EZJYk(oNn?an7GII*K2p zrcf~sOnnk(vb7sabIi88%+4serQeUwPG3wQ#%zZhsWv4WPPj>Be`w#+AA!$?=ds9r z*88Nm^d;3a8pHV7$UxrF#?tkOS>o^(=hZ7ennSwBh3^I#m}5tH0ER;mQ;?@ym?lG{ z(N{w5k~it1`~@aWF83LKJK5j`9t)6+qr|z_KId$6`6&o%y$GkM1)U_R)QoWV+%ouL zW%nXmWul}j<mDo2gdtJ0@_z8ij72cUHfM7wAFRY|{@?e-t`I%G_nYH#RN<K5L5r$o zbnRKrs@;?Yr+X8MR#t$ZQ<JA)#v~~oJ&PPnxbuc9Ur189*4p}d!gPsQ!4>=ctW+nn zsz#${4TmwBR#MNZ^LLE&vty8`KF>OiA7}&R&X$$L_Vb5rl?PE}T1qnu*fuNvH!c}e z0INN&GCN^Qr8@=L;#TX^SGE>hgvbaFNAlaU$+&iBr5F~Iyc6}jHDDvdIMK6$FA8K8 z(({Xg^40mE+0>&17CtFwAfA)4Q4TObjdn{A`yO?J{0g@i^3wJ1IeCSd^v|c5ARZ+p z?n9^&2&`eA<y-(t<Xg&8o@8w$uewc`cgslDa-?1n?fJ=rHeY9_VJs(Obt8;lX(Bs% zxpr=3-}szhoaKSyuHt3zHhA>#zN};7PQ+u`Lx1jp(4Ed87RCgZgQqH}h^H^lCQNyj zX1azy7wj-A+rD=+&zLdSZVZ;oq~hQE*geY86bs2pJ@6En7KOhkHIOwkT|VOwn`V0X zF7eBnAzueXT>Te6!e)M0RFtS>SO~{_z!hSrxaAbt6xDaxp7Co{z94k|X!tTphrM9C zJ((1y0JJ7@=2VSqPUJ)7Wz1liLF!t^CNHlyx370{a&$HT<*G(zJjI!QYnAioYD|G` z57KTAt^=x@+GF+HPaxu_fd(3t*6TY#&~gJvn~!92@ZE1~vLv;38Q>^WINNG8P*JT_ z{_ku;{z47~F|8-2KE(g^Byf`%?*H4)KkO~d4OK5%z=$#4V}?rtWxd+_D_Sc^o0aEN zEHv`N(*nM?-*2?*CI|g`{Qd5eZFY%w9Ya^#eW5;_qdr~;eA91wpTyisp_@int4Nb? zo)DtT5+cc!g(<DcZ|y&BW<=zoc$kQ=ak>!ruA^*e*TFOHb*mR*?T8F7j^GRR&^Ny} zPBPf->b<|!{k&BsoBGg`_dkR;J&QbPi@_D_tuz=;QN(`cOmWjJ_tZ^Rdx=T&);=0& zvo^MfT<Ci2P*=@lY`}w7vPy(ApKVY~m3tGqBG<c5WnTR`jQEym|MS0ZlzY?71zQXb z;B7i(<B1!~-4oeHkH`4))C4rDxoc}G*t-e}C#bA;i}7(ouV8lbx)0NYZK_2|paX7d z+l*sD{JR}pcaFARU$>jN|G)kZKgu8$(VgJ?Kc9blt|Vj$AAc&(gp^g=^Re>YMnXCx zF`TRPJ*bNB`?Wt<VPcu!2?kMao)PPmB+%#WjqL`3n(Y`drmF34V5&p*i`}Mg|Co;F zw%fFWxkw4zzpsnsjcC^HAaa^yks|7LdcvnQ{oA<T<B0bQWxHy^qT1o&HJ^md!gyc^ zM!2!c;Hw|&qty!|%s@yIYv%4>2FM8Wh|vhb2m|@@`Wp~GXNSGWArxPxq<k}>$={Oh zP>J3_yc8I%m_y362S)lIiu9N9c`$;WBSDhQKioiUA!29YUQDx%c&7QaOv0Oopz~3$ z@0Y+8u_>t_Nd}!P)6#fTC4{I!0=roYgEa<n^9tZFg1F7dDL`P%A`}}{ar!f}?KX4W zp}Mm)`fkO0+w&<;FBOkjf<g1^`(agIndU|Br5YF!d9fpOzx}K(m=sxu7(Ye(@F`3X zGLNrVZ@1_w@@W~f0h??lC+x2>IRrs_R)jsyLj)a@W<C{{_zq|5*V?2*k!BwnMumXM z=_7$r3$>BoRv=y#Ign%M9|w6cP(l#)5>J0vB{0gfHp<gK!o6Z@$=cj6^Nl{(oDXAz zszjSACGhc=v(22aPtPH&F#L<mz@6)&C3K>rzG?R`aD@@3eHOiOXx;2b1kzG1=v9!F z6#u=XPOELWYZE4BRH8<|AOuMlILce!Oy_DT+uR^vf_O-R#qR|~VwGglcVK`JZ6N?) zBShLNMO4dVtxx&Pts!x8q8=x$V7a!+eZ~kIaoQ2Ci+c;l0^8#JSm1jms(x2$b)vAj zEJaCaE##|%kTQ2cRrqZLheCpAjp%c$^2M4g=ecc%>g#N^`1`)0sSbKF){Cgw1;mn) z>8cHz=9cV>a0aSU(Ol#)JVX?~Wf$3ca_^yCthEf`q3pO{L(F)|(PW0V{Plh%Q6c3& zCCc3N;$oAp5h?NbmlbQZ5o;ONlI@BQ*_F%ja;j6dYLrb8thK3Bf~=RVT3{5z=LLit zLNr{NlYf*m<~x_d7Ngjh21;CVLPWuuAo#ZY%7_vyf%!#gGTV~8C>=!^sjL|gr0Rxb zUaGKev^`{v#6@ju%#ZR`d$H|%@hI&~>@)qoFl*MfkCvqXv}#~h0L>~w1xS?{NN=&O zvx-h-vKu6b2HWapd5;{iwG~sdoq8$-C2&#!(5!87h%$<2?7vepUO6#Ny*b6UE8N0o zok`=uZacy}W%PHvhH{wCkc%>5qSEGNaL~c8i75Ro6}ib%#6mXK)6PJ$j8y_*`A$hq z3nRMw&G60K+@0$qq>RbQDWj~jHnq<(6gKmHB!+e-sOC_OCws;Mt1J|4ideD)$O#!# zI-`|VQq{QY<i=h$QO|FO22l??_Y@vUTllHU?yBHC*$uug8JM0TqR&KPXAP}K|HsV8 z>68#9fVtA^$rPJV+np#Ypepyz=*7k0!aatC=PIvvinDD+&pIcWc&Or)nDkus4(@ld zn|Ew!>0})BhdaDem5m30AP%4e&|uvX;T&NR!mx^Y=_r>O+*FkW{SW~?;DE-|MsKnF z%w~=)<7CL267Y`7Z`XLQfJ)z?C(hkd!~R~l6trWI|IyfM+(336zM7G>W+i8(>AAJ3 z_|mro$l2%_tMH!tx;WC=uKw_Ufu#L-!{aFcG!F-K49n4tcu)<qq^VsyX}=bn<49F% zXzeW*nl0x%!pW3(H8<A|`r6Y}U$UefwY&Rk^`(VOS$FOB)4drp^(fy^B>S$XSbUwS zBi7aSN5ejbMae*z$g+6K7;y2+K{WcD7TXeV|6HUSKwVxg=axs71MBi4!r(+CyZm!V zl&&)s;8Zpu;Ke9L%@sq{*6LuEAt&1FfQlV65zCcelU5!_6iUH*(hQZRb0^S^-1%rm z(ykcjsWRr=Y-&4tG6BOM#P+Ig_;+V)7817IVIhd5-}h$b+h%4SK^(oo^CMW139Nu8 zdrMaY)uyE&fnAphu*>8Szxh8N8Rq&<PEAvz=c8U-YNiKMLK>i3DP<hRinbpNmA=S? z@)MN%gg9V$XP5H(ovJap+tCvEC&Qe-_a|cc;gT+ki2SZw^jpjTz`}}%_;!P({!xTw zd4x|JU*IA_gv;q7HI4bBkaI8<7im^zol6w^2)j>%(eS<x2=TjYacOhfGqQ@uI*PK2 zan}p6-`-;MF4s0I?^IL8wy8)qH}H8QxH1$jm8@XFpDC8*`j$vSf)BG4oJAq_b~+~z z&H*$(GLYXA(HaS)@+8^LBT^XdX5Zipq2lD4;dk67tBa`rT*=s*nto5?x<bFUDZJ}F z8{Z+@(u?7}J<8$-Qih63#`&B6uZwlVf@J{{RFm)H$&sq_4&lZQ6nc6HdWXLyFzpQ^ z&H>=x=9NqM3*UC?*iR2@q-C2ro4{MkqVvG#|KspQFx$j3?R7`8$V%#Vxrtf$D_Yh} z93U9Dc`qi@OuL#yIg?$4C|4UJ)&9M(Q}2+{0J+yu@p4Y{W*ukqI|a<M0xoRyVkkMl zi@6_ud+a9yIfC$yW}Srt;q7tnP)_a$W);W$zyuDM!z2)Y_uKdU0g>SH_MqQsRfQOS z_A(#k^MdQ20)F4*Z7$=*mKDA_lBl&YEkL<Gf%Bj+VD(7bf0M<jZ)rAFa~5xj#C6KO zf0sH02lhE4u5bZJFIK+ow8ieYqE5qG(d;p=nfgnA0%8C2@Z#9F6=h$wMT+QK|L@+* zGPuR>?#Y9KhBB95>Mh-6jKvZ>38u=kmPJn%6A@9vpaq^%Z~CH<!a=1~r`|?CpDPZ( zu3P|KO<O$#e&o{^C<FU)SwZBT#c+=ILeD<ObCTLQBECOUmKI3Oknzr!l`<D)noHh! zBs^ZmR}R`K;jS2HSfn7ux)W%5wr*%%(e!fk&)RlN^!lEO;q}k!u~}-2(2_m!%>7^K zm9xU8onM5gRfG`Y+N+<4aBe_li&YcBrkU`W)%DreHV()#hi8P0ND)eow@s(sMDE#Z zkWCCev6Hbt#y^GGpXy=Xu)p5<cd^s*X<mEN-<5s%#>etqCw-Ua55@K6{^9}t@}%*P zvZS0N?(oDd=JUyKvF?6jye!!70-U>S>;@~MmfO8=%UdPSW%955w|(<|iCD@shV8=7 zp`EQRV7rddd-OTFT;!j4g?e@ej+eX5k{^W#Li#s;kRQ7BSH`A*DW-4e{@N{SZ5B#g zTHNn$!xjT;1n2uwI-z0?t1UKk8A*`P`=)$Tv##|sHnbN{g#V6rH7$l%Kk5BVSkaUm zSn^l!;kzUXBt89}BHI4$w_B9g_g;M$s?*N6{?~#?CIHAKYB#xamr(sh?C0L5b-O0$ zZE5JmUZVZ-X+QgOF41xa$#R!zV#V0!^8V<WlwhB`^<EFN3Ci7GS+~b|CNPZoo@OmQ zYcFNm;|zYk9H~qXPO6vF__hA}KR%{SA*OBg+{tf*o3kX$t@(dBtOjLlr@+gL#dwaC z+mB@LiVFSFO~qZgrY|etQ`@%Zy#`%dK)5cH)kXP=PKG?kj`3OqP!!4zSqnV({uZnV ze;xO_@9S{=md*#;QAPk@0)$o)_?jFGa`{JZQ4JHUw^wdyvZ_!m3=GpP031eM>{rXS zZIQa4Z9N4+W!d$NqMgQ$+s+kCE?ESLzFwY}UU14*1Z!O}l_IZiIoJ9IPiad9cVJl5 z#{&NH6gY-oLAb@^hV9wiJ*v{nA|wMa%y@@?#hQDP%5yVSM>M9eyRM5h|1P7@KUUoY zK3q2+1|iw3Ez9Tdz!BD-LqNaq?z`_p%rCzsFxG#kihJLSEnb2rC>C~MU*B$c7yBK@ z!o~eL!YuWG#OD9C`v4#NDWEE%ftjIXPgRfMCGbVi`wKPymE&Q=ap@J<zfBsdt&0CO zu{pA;Ag%}u(sSO?xt`NJ-SWhez!78l)`75-ML4kZj?O~%`NlRDCGdp#uvLS(A5Mc` zt1^f9FOB?8`dG(XzE$q*8YcbwuGJt1^4a^Mt+JciqWed|_v=siFR&BCd#`~nx$oaz zY#@#RQBUqX%W@Ac1d9-Y?QEDnf0IsWi}kc1@J7zU^k^x>G7bP;w(`OBJTek#r7c7T zUZ!G$=2dhMQ-gEA(<>L1uzh$kTL3d}XUJ;dM(bj*YiGzxp=#X4Qk`R|$1A(W8UMLe zbTCrCSH>~Kb|BytfS-;%K?0ANiZt)isn#w%vnyk&O;N2|ZgA_n{U2Rk5H}Do+w4Ux z9?F*x4IK3N981Mx0VYuw5#!f|NC%{Oxn1&tNJ0TLhzFIjB$4oxt`WIMH!OXLS6VH9 z{^QXY3E-5XpU!kKpuABklykYVS{=QTnJki|{I0@ks&|WBqK``*Ti@+$Ys|bh`&O#~ z!TVJ6G3pVg`6D?-&EB&wc2w3w89IIEhl|hCByE=uMzrFXURD)NW_gG?fPO&~;ApR! z%2EgDD|+-j$|$G*ja_CvsIgt9g|XL?nfhk<cDg#4sq*5L+Q3YfnUa+InHg{IRHdt$ z8GmKE8rXT!Orr&;uuyxYlDL$xJ^=GcQ<^pMNxx*qQsA4(G-wx~{s%iUm5-Gs4$#}4 z%*ukR2x6YVm*7(NTaoVfCt{&*lx%dI*6|?zeD<I@iH8}cql`<hgh}CS>EYVW*=9Tg zB5iB38%b~urH#zCWR#zp4^O_}dn0@qMIZ%V?sfM>Kf{-#&ddjDAkzqZ`f)-7EK`AC zNIlLGFfzdjgnnp9XJ?E_q+O!L+35Pu`GPjoGiB{!I-cO3=vRHhF<OIxM^%b`ucDrF z{&7>C*HdPC@}3U@sI7+NOvtXU?=C7UM=V}2iUm7F?PA8Mn9Vhs+RJCvq}38-qDQ3Y zuJ@nLnl`1mg;P-~d}%)#JODLN0Ro_0ajWVib`VVsS;l4`$t2t(0_3Xn)Z%Q)Pgi{E ztzww{ffeLj!@@6d;Xb)mCv)Yg%4|OMNxToEdY|^_E*d#vY-I9&ofW38Pb+1WWU8vn zq*#}X+iu~M)jxOy>glsp`C(yx<BfxKAsLglEir)(P|@=c1kn?W`1IKkmzh>kn_6LG zF>XP}W~MU}zgA#V(Y{ZD?jXLr!&E4Gf)m0d+?%sAV~{Y{`4FvJRet`MZF$sOU&KG# zLUOD!iJ@<nzcL%|_`u@!m+I?}E>r;*e1tq#I)Ms^{mZ%JF#PF1DkDBq1w^7iGVI|b z0;{H%j7xp<Id^g?LhOywfUdr^>RoCfm)6%hkLyjhji?zkHdNS5c-FOdcJ()XK*NvM zD?y8Dt7*YGNsHk-X42z1!WJ)=qk6K>pyu~`0lM&ba0m$J&;^kLHtDIk$KDR^QtnZe z#>C>M1^1f!RQIS@2oj`Y=xFERoQc6qk;Pf1VLJQ2P%Eg3i7Bcz*)502oE|=hE~IMn z^+a;4&l#wfjFg4OjzySBzKZw>PQNYT<8B-{Zv#cL0H+V)?dr=po{EtZd=d08yHb$X z=V3!CG$A-}n*VpHme@u879*K?T<BwYu7ggXqIHD6udh9`YrL8D>r|6K37Y}0PozN3 zzzOB?t@P5#5%q*WHu4JdyjydDYPe{(W}9Wkh$L_L-p`ULx1}oSl*pV)J3Ce=h@9Z* zm0Gt50@#f*TMkTZ(5uvZc~)Tgeky>_Y=L2F$+fsc$Y5~R_k~8z)bA0r`W8~?p7dl> z>7?tuQD6~9jW9mZ#~~5>5QKtPSz3rNdkp-E4eJu4BS3^FMbG|g{9ii-R+Dp9|5WGc zcd&$S1YMokV`)a@^nEH%#+%)uOtr@pU0Atx@oizDP528h5OB*HG`wEhYB&eRNxhu2 z`9DSH9Z%K&$MNG1u6r+zP1ZHDN%rbqdvCHwNn{HV=`LKet5hlqA%qZ-WRGhkp%BW9 ztb`=$dw+iaoc}+Mb3W^J-tXtrlws8Lnbi{gfdm|5SXGqeQ6ef>JOxu#CuUvdyQGm< z{=mlRVdmvRRopDKR~gTqeNM<y><9Uwx%Kt;C9*LUw)RBqV+@#7Gj`W~stfCTn(+*) z1S=nx0e4HGo%Xz_<3k8wgmb;?!hp|1n+G`V@^l1QU33#SUO4*<VH_MM&K0~!Q%<)} z_la9dc#AL&_m`!b))Q^!^7_(J7_y_9(E?ktpCqfBR7+H1UgmGf<MKa~Pn+S8e_;U6 zsl@_9vnZ>xD-o;$?lW%}vE2YEF^o9g*(;?NLaL=rp43}a<$|(Lg35H^66XoDm`5_1 zQr=&kvqE)=sqc5(v=3D?J;_gbZ_#Ucnp!@v0C6vQM?tu<rrWK6=xu4sghdMW`}E=9 z`3n8RO->`r&oX%~F_okhEDf6?9FIe3`WkrP{dIteSj^=UYMVqQceBYQ-h`o%%LW!8 zzz-9P+KSjOoTBFbS!5p=WmbPhK!=rx3-0svooY}<16V^$4~7xQpNC&4G!$G>=1f?6 zz{z86o4lt`pTlGZ6+-wU0L@E*rYQW_<9qF}pEho<@FcO!euqe{U@-%;yQj5QiXjy< zC!Bcv@@=_OLSbifPOFGLi(F!Ft_ADUlQUszhC)yr6F|e=I@iC*t|u%@&{r*2Vqkq3 zq+kD3#H&R-p93i34y8N6Z)-nSSw~%T#ju|A$*5JuHo}U!g)R*F5-|p{708Ua+S_uQ z`}W-s2I|9^*>5K8&tJnu*EL1zvR3Ptd9;QC)ESgn!^muac1&>sE>$nkBK$G6=2hd0 z8cae0$83QJ&2=^ht#65<4K&Mnr$&|3F?^lypDQ@NgWUAU-r;M(>AMH7GF-dOx=-k% z)sY1OS2TL4gy!Ukoyx3`{bH8I>iqX7$DQzPG5*}p&-htx<DiYB&*PCA{pbGUl0-=` z-x*nD;N@eSR4hXJJSu2!e)=he>V}D3&JJkiaBx3&;;(l(`wLxPH6|g>mA97MKrH17 zD|0e@yJlk9MsH|4SdbC>fy_eEr6Z`R$yM$@v<(vhn7Pg$jN><h!2&!<GS_d5rJ}&_ zl)R7(zl6$*dlA(t*PrUAIMs}-y^dP2+PdUMzI=5(CZa*~P5__Y<Bw*HspJ5+Yo*F= zt=^xOE9$DU5^n6}|F%FeULXnXV-TOe9ANj4L(gAe*wTz!;cHt0n|>@fct79+mgm6N zXZ=;g(HU)#`XGAd)cno%!>eU=ECyBI`6riRg2>%-NWY7!92H@hD@bWSxJ|^M_Cmv* zN54igZvJ&FVql4yCyDa;VZNB?0nK^Id=1_hGz>f0*2f4e-_$Kv+`z6G2(?@TTTf$w zdinQwx+?>3QnBMHgsTGMZU~zL%QT?1G#;#*gAC?iF@~wZJA-Y<{T`SmiJK7_bJz}* zK?!A0)fcKU55+~m7zx+iIH70oaA#%k7Zbp`&-HILa`wzsh<$j68rTWvZlB~HISalA zF#n{8f;>sVQqg$;r?NP4VE5|uyh6%^fsYD{N+e3MjAbuZex|`1#*h?c%o5~E3|&i+ z>wu_WpsT-$hRQ*Z1=xu_NKG1M2>>2Dwzi#NVP`;3UMx4`DTyVnk#V_y-zfT%Anv|H zxbo?(F7RVAvl{%uz!-`;jxx1(>gTo9oAhH?O?jqClmh@|<<z28=ox9yhMRuLL>X#; zf$jWGb@^pcH^CK(QʡqiR}@+d81R_=?GYy_a)4_?lb8Zy<psmd<v<TW_SV)xS8 z;66Gw0)>a#qH{ch^Ma|A^p&+3`Hu8&_n~lhcN1UO?(Za)A`-Oj=F*u2RG&~5fx7{J z4UNn6`N^M71K%v_4orpfe*?34PgnT5IXHqb&MY6z5DRes`{cwcD*AVx$+J##mGC8h zL)<ovCGHi%PDDcr02ET>kHv!4%Fwg(Fq;VX(qwLgiSnVQQXT>IFA$_4#0N*i;os3i zqvWAAIsSWi?cB4aqQt;F&*eQtRw2uWJ%a63)K!p0r8kG^13h;To;+@sD=KsE);+cz z49MF7S<?jd?0jYpZa3yxz}YE~1s_<>O^#@B+EZ>_W?=BFN?!~(SSvRmookbGw=)Wr zn}`0<6)^EBAkWote3Wpq>S)7k?m2_^QsX_+f*C8~FET&eGlqy3-h)I!vC1%<FH9PQ z=6-@jrd=nLXTS+J8SQn#E_-|~x}Ojvj%Nml%=tpbxsadsHVf#f!o&!NV5ScNlIl!F zqnXoFsM8-%qYG5798IC`4=~&h=ce8M0FUXTFcIoKXyijfJml<rwhi}vSe-EoyWK@2 zkQAt<9R$)TLXX+=iGLn-3{WgI!C_iRkc((Im5zkn#<NZPy$4yy5rw5Ra3Ga=hN|ho zkJ<C5T2KPM3>5t`Vh$XDK>VOU1XK$Tk?sh!t%JL)`23W4a+?E-xnnQ3bbn^S{+K@> z{lWA-z+R6-Xc;Rqub&J6J)q3V^)si_fgo@l9E_tHo@k3c7dgsW%riee++mvoA@CyT zX>I6+bcP+^%yQ-tW6sTErl(~j{=~E=<9_H~<NTfnPdopVG<=fN)n-Zij(UqJL?YRZ zj~JT(GbRF_LzJ_kHc!kM#POHD?J98+M;V%x-nmlhlFlao8d7x#QHm%A@GzzvW7tpI z7KCN3>8*da%SvCCsU6*c{4CRyr9aC+0R6r!gXc@yIFcX^B_9pg5rJT`taqL=XXhfC zVw}zRp*(Z#(NoTfJL^>t`-;6CRyv-ER~bAl3)SwpZ9{+)T<?Do)j2x-q|7n=ddZ!{ z*FyP(r*FERu;gU+*HZgi%CDs0;gcH6<$m0^8JVu9K`lVKIrYESXsx3vxQ_NoyDr_A z#lr$3Jz5JB4T7F2J8tknGt?-Yu2H(CE!<uC{UJCQA$hf>%6c6=tH!x|s<4p}Gcb>W z|Mq0iX3;K{VwEXTNp{tmBzJz--MUh%mry%D&9)N(J#k!!>_Ez1Ltkh{<uU?WZgubv z#eC1}U}Tig8=>>NWulh!+P?4TH2#zu>)^>vUD_|t;m)&I;DvQ(xCt|+x3NZd<7K3P z(mXTpN11Jp%Jz@SXcXK~7XOgxOxe6Tc<HlR-Ako$h7+c&5G?Q-e{zlZRY@0O<9}!B z3k^@Qc$T&ZstoECa2vU{$E7RleG7Xbu_+T$naTL`Rm9AbsEw8shl-t1wx(JJ(H%&o zs~QymT7tzBoEoRt(VZA{_Y8mcaaloU3oH`d4;0G3dEr}8Pdn139h&9spu4AY7M)Q9 z<l6$B+)j-XBf~RHhGfCdmQ@e&Xpbg(2a9wqgDm2@*X1YE?5zU5{N2Hl1(B^|a^Ua= zdf2x<(LEO;OD_#_sV|v9J$YUJ?|}cKGE<%}OBOBM*8_xD=DTLJ@q0?2*JfjGWoVX5 z)u@GLr<lS!Z`~3Q5`Y8Ua;<&7tr#8fd=zM*$x>9ynB9*CRBEjkbbY^DOO&C_TV4-h zS#<B9`@y%7pTXxDohU;4DRl1{BAer1wu(`d1_)`^Inhi-?H!99TDImMKZ4tL^eM9h zjUqmFpyBeMFuZMOt@}Z9p0-uzAiRT6>zX;(?!Q^S@Tm2hKrf+6$mKKJ=pRNduy`r8 z%RBNaP;1{g)Ww_ws_6F7j@mC+rfH!ILuQ{4WpcF}T%Qzmcddp?%2h#z3#=Cg7LFg? z38uFx%7fjKw3qTiKLDU9g4GxYsYF0ku~_SR?mG*}`X~`$sEW&T`(LPmU(Z3-4~^l< zsHWQ2ZU(v6hLOyPEp`j2pDlg2PUY2Tzpk|!T1pi9H_A4C3VHXUv%9Bpb1HXOjQF77 zP`3OKw667{Ckt7bX%<AgcMWK}zay`rO#YP9<I(R6r9S$i9}QEqucKAu^As~XZ-=xm zhkS64Y=Y!`_}9UbHHx^p!yt<V&0YL+7~Vs2G-7#q9<sN#@1O<+TOmbVa6hz}Ret{t z>R9`o<A?CKzDx;~17FY%-SHf4^Qix3M_V8x3-TkpTNB=qP5&^}dnYcd+N88Zx>}im zMQg2y;=i#oTQr+U^l%|sg}^*Ej1Kkehex7;#m3eMs(}|3uxh#b_dVWf+-j?<OAdYZ z-^5KXZh?Pnk0ujlazwnh#;nhHvUzoTQD2{#)g9_U1AoWgf)g22awc=|G2MyyP)`ZY z5ns>uc<ax0KiNnufVA0^QrE}ot&hMc?XO=O=J|9H_7iWw_}$|dx2w@jg-j+}=&rPB z%nIuBE<(GrRVSlyDB=B)<v@<yXBDr{<17y)tAyIAA~h^CC-xzhGt*KDDF3%0Bq&qI zqdT;tzCC{Ojdgd0FVp*oiFdR7>RXk_9Prlcq_6edG0W{w1wvDEpFOSV;M@(c%@;jP zMFvxm&@B-WRQH+9S8OA#p#^F0J7yi~TJPMrTkks!{v1_fnP!S?mmBW#wVwZ*wMdko zKVqMs5#k<KX5vyAWyF1fzV7-^DD}y1NmY?blz9~zff}TKdMS(E4+V?oCbQ84N;ghK zL(6vgbJf)%^4VmBD7vi!`B4l#th}V^)rn7QY#S}SN@dZ}2RE;Po?lR2qlh~<7MArE zKPZf!nOn9ETdfgTQ3wOm6u`Oy@O0!S4}CD{Z5OhL;)<#VaR{VPcfg3q2%edX1Fd59 z_29UtM+cM_LR02w&S7d#z^m>!-u$T5QhjkQp84s2Tn{7ZR|gB<4@F$fvw8nC3;dTc znxTjuA$6K2fp-$_7LKAM#5dY78}P`hkG4O`DPjwS*WK(95tr9LWD5=DhC3*NsqfaI z?7;%PsJ2mf5e6Oe1*{Ki?b<<K#UjS3?ap;z8x<KJfdV?vdH?mGi@x4?yk05n^IU4{ zUz^Z`jo-%+Ffj}ih~a?$Mj5hl*Q5J}u!vXH?M|WtM>*)V|8#pi-jkEI;vcUXGvfba z-7PFanegp!#e!*bv=<6L)HhLY3V%AX4|L9>7+W^d|Lro4pif|(t>70H+zw;TkL&tA zA|kt@e@Mj*R^l&Ehbil)pX@5WMSZbB^zZCC+tb_oceZZlFFP;{>?)#lIT1ZJ8}Lrl z!<==e?eF>UE#t2#Y%z%7b65+J9e^4>$;#cdgYcpvnO|&n#rz5f3hZ%fXZ2d!lussJ zt49C2;=ADl{dq;9;Gmnfq=@~HuPG_g7S7N2ABk|w|3jUyOkaUNWWO#u+k(F~P_b0x zy|5!wX#oN@IH}+Or?d}UxMP|8=iZBBJNw4BFZKcI{-OFxclc%j`%)VoHO;!8;Jqra zf~xl|{9VJ%oP!L<91Z^fA#Ea;+mGkI#ygE2KU4zq!*>O49^d%0MJf1a>(~BJv`XU3 zk&Vwz(_aL9a<%T?p0)jM!rt*0HV}Z(StVRY=W%3aZbkp8(FH>ayQEEt>xV_-Ohjbp za(Tog)*E`0q50D4hiV@gQ$;KO+Zd($CkM3FWElq~!dcO-Wf{kSTKA?FUk>%C(w<vy za@QdpPLt!A_N6wZ?jP5ktK1sHRz80W?#%);W4UPig>EOUnCw@e^G`n%=oydvjoGk& z?9rtt>=l%0cmE>nmi}_%zRbjnG;XDU*{PowX*rTgf*F>ZD`bmvDHFef%WZPF9gnJx zrR|iwN!%%d%r6TEA5^4#fhd12UnkYDi9DX2`5ivrnap;2WYlGa@+RqL3-_9J<>#={ zS2dURc!Fm^=Sr(zYg%WUQFkHpt@IgP$D!VjFD`%m^6z-Q0rt80oVwq2lJc3DPPO2b z{>)mr?>X*c9MU>l4xfAPYX~!JiI(T9D9I1czuYlEpPc~p&wI+4@c{ls#`+vV6>ROt zyBl4&CLr@liSPOti96Tnp-q{|7&fq#02oyjc5lu^n2BYm?$T<!32+{giE5+~5R%5x zI~;3nd`s0}TC(hKb0SUp+pZa$w*|~yYj@x5Aghz&B-Tucvf{y_ZtH>+bBVo)tG4<x z2`e_bxacu+naCnr3)1lOtruPa(__|6o|Z$F_xvw}W!WK1<XSRKDwFT7wq_0(C(G(I zi0Ux7a^TM$NB?qmy=c98mwxU(xzvWeDANHWOGq3X<))KV&u(><L@J-n`7HTB@!RNg z%sU<fTN@-N#NH+3<;U2WOn2uPbI%n{Gf(fc<C1qzkfX__4noBZLr%+lS5=?iL-nSY zA@9`m`dK!<m}L909P3L&rNrDN>iYkh@pvJbQ`-*s!i$rbuV_^JD90P#_fWhyD5(Sa zt|^nm0?9kC#Xi?48qN~?=Te^5W<-E{P-Ei)p@(}?<?gk+m!!Q)maE0g<B<cBRuJaC zrA+muOZVd3WaKL{7A9zRM||#gKc2Lq9R=4W7`hfdaEs~vRt@Kf^yExPlD(@t(I^?1 zIa=?ES(&<W<?A&zF|8uH$jt{Av;D0fhZpXz1<w@KFga+3(8TY1R@O1OUkVt09~QIG z*k8cb?uBq$x|en%CSB}}nui?A#k@X>7hn)ix(o5j9o;5@p))+E8R9fU3I8Q}7COtC zUW!`2b3UnPiF4%dW^!m~AdkCCrb;lmtbi8gecSu9=&TGQhI_T}n6^ExcFJrJH^6cx zE=BfoNRH9HCVG<ClV{vV_clu4lfM=qUhBoiqt|2KKF9fMv?5@lN$hRUM@Nvirr`Ot zv6?BG%=lNk_qtM6(--wpk`BfFm@}>-0aZ2tk?;kV7p?Gqz##BuCtOatq`p>g)c<tC zxL@2ECaWC-Uds>Zbj748xc7dQ9a|1t&ANnMKg+Wdo*S9DI?lK*t2*w!+@n<TeK2x> z$nD($I{@!$Zf>Qga%)>U5`QvUIgQF11|uD}lbKy~;r0PeZl7kKy#nVpZL@-DGImpU zjhxssGW;d{U%9rjG8Bd&7;?J%?$<bZZrHWT-FM0-qP(LCU?<+!1QeG%sx`P+B<-6Y zm4YSy%`vyEd@!A|s;R)UOwC%pq?F-LGt^fh=SU!`VNr6re{6WKu0iB2Ou^o2TUo&c zV}V6io}t`bG2ILfC4+CJ*6U!(4^DrD)8<t06fCdJ|FX_mqjbkYgU7p`qSIW(CA{@S zZq8+Yl{$Kqp@+ZuBS-UmtO2gi<^mP7<n-~(gNF921`f9oqP>Qy3pSYn6K9@+2pL(V z)%C&m+@;T_<@PHiK!Pk-wKgkP^t#@w^o;Rn!?65q7ww^{IwxirhXQRf*{V3Q$dEhl zjO9@}+u#eaht1M}>`$jG6X#0zpVGQ454skMh}`d<dk#q*AiYXXs<9Hkp1H_u;w6)t z#aP59wQrZ<_<Brp{SgNvyYU;<VFoPP8nGksz4yH5$m4rMW{%IUyY`s$K7CrgZpsjW zBo~PlbQ(^X`!FD_lnEd`LDYwL*EGnXOeYvW;{K*y<i>i<3&u0D)7U(l6I)f?OG!}- z-(DKsUinoW_l*$bEsg2xiksZ^9X+QY>_~zdm)+%m@>Z+kFSBYF*<+hCZBCDwlBu>< zZI)(37N=UzdD-OkJPnO!M<HeuQ=YzAQ2^qOXGpaWzgNCe@>oBsN-+Hfyr|bixDHW= zcB*mkOIBzB5ifxq%vU{H@Wo(nMDRXa)*o2d)#n~WzNp76!r#TEq*0Q3cY-<0Hw@O7 z9QAa&Qa-ULyk<qXCyx?AXUy{gmt?1R3+FE=pcZ7mrKKCb(&#eWz9iDt<pcy4bMo{l z$Y_4H2k>2Q;X#j6(-S-wh`i#Dy`+Bxb|TeQ>^oi$(I^Ifsr>NU+#~)G<`0ZMrE$=0 zA8+hS=WHderust$EVhlF+(+Y4BIL(wM!oV?zHs;a#gOOaE5x_PG$%EU%N4HO;#2|0 zS8B|CxefO?FV!Jks-#P+%K0mvuD%}#;HGVChT<Mq<>Anf_b;<OC4s`rWxMeMf^T>3 zB+q)231XlNrl)85n0oJz<Lki#!JF-~g=wPcL%eDG*vEWgZhwuRc!l207BTlG^z79= z3zRQ}@2>Z98GLF8(3n!mS@sl<pM*#5Vrygv&JPoq^EzN>PG7eqN59E~`@Jgb%<Sh2 z7!|GG3EpvOZ2Tt(84-_tj7!?|zIFReaT^cq^yhy+5$Du6#cyfgboIe6NUcG7VQrV7 zD+6-gLgm|>BuyTrZ@FEW#dB+osNcP26r6A*I#?#z8T>2i0%@vbEd)XBua1n~d&Qac zK$%t@R-1Dt5n~}tla}@TNWgbd^J)!9>DQ2X&y|}w`M+QUuASv?@8o&)P~F(K=%Nr? zPkB`#{Oq}RYebaM)?0W$fxyNu<dfN2Pq*J6h1wM?G@X~-!z-UKL_~Eb2yvCfCA<Dn zI3xns^7y`guJjK{KE<lHgJcLXSUx_TWxO~Q{PjW#^GzDor}@kM)Zgbr9)0O&^0Cd9 zrbqzTv}aQ1{<!~mi7iVCBO=})^JogvB_TfuW}h%@-V|P56LW(ST;^9Iowm;T39N4; ze&sZhU1NIU$5q+7;rj!2o6|7{nD;q6{tEtNHed#<^q-yT$g!*^1nRF1X&UShu^nVv zs!E+D<@eL{Hv%=-TBzF&czdk=$HfQfzR9dOxGN~<p()HML0PIe>+(niJ5<f{m%Mtm z<9O-ZDP0azJPhc-0aVzsqrS&X%eAYGt8ZX-<wPyb<U3C_ysjX&FH%_fCH~|=&kXAL zlOAW-@qsYl@l*1~^JmPPEmxP+dY;!F1<P6^x=vXc{w2WFb78`ntpt1}K^jY3Bd-sU zm|L18L)2si8Zz_vT_cj$MagMMqh7Pq?9gOWSEv=1FVeCzf^Mjlxl}F@-KNrTPRq&A z8YTdEzyK)TxVclk1STxlK`Jy{wJcJsh1fO2yd4b=-!#P?b&=z0e;CMm)Dp3@4lGQw zYNvM%dRJ9hSWgvkVs<?DsAYAi@!AksWY#D!GvAKO*es&kA+fLOrJ5=i<%Dh~W(IYN zQyIQ<E~drc=JE3!4kG|V#)h=_Q52l=>P)FB?o}`E1h-kXmY<C_DZkzq_}7$ZPL|<7 z*q%s*XK_mzh9nx<vKc0cBFiGkrg3e^rMKA@T4{U&?l6sL!3w(sa(gAx*QgWcsDtSy zYhlDAp*qS|UHaqwWn(Wr_HZ|0W{+lhj6fQJzGFlm?=(L&CjcEZRF`F3lVdGW@sMmm z>0C|dmATsa>xwq_?PpTCeEpsBCNNxQF(pTr^4XH|9FlC8042w(L|gV&c<2(OJFYz) zAehk}Wm>x8$oa5d;=U1Kr(GzYY<4(cj-i}QglX+S3^H;4Wc_Ycjr1u=E+YzSC)s#d zpZz65<RayQE@i_5Yt`H~+f|)j)kCa3m*k|sEN<+OYdH~p*RZ@ezvPJx+L*L9)Rt+e z_lP99X7ZqwOfs`FS4Bh#Y9!}j$?-5HMDo`${S-T$Khv~Lk}*-!1Q_Kr$yd4cvel7` zVnJ&Oh?XtNg$Y?%@66sYJPDiVA@6Ke5pVa0Xc?_$$_8`MCXTc3hW45z$TrG<tuqY~ zTrHJLX=DvE(TtheR85I<`__LYC<kH&a)BgASC#vov?>qFO+f^Z57Y2BRG%H#nH@#T zz}WQ2A4`S^5@xN#LrwW)i(1%XBGh2?CB~>XRM)DztC|GXzjQ*l=}K7DLbc}2Iypz@ z(Hd09SX$r<TTHUw#o;3lgp+RD(w>bO1*R^czbI$M`gRP(Pi9lFZGjoH{4=6wkj>2M z70Zb>d1R@(y2*BZ6;Ew@LvUYPKO}3yt*9g{CL1}V@S|LnH(%SS%A8bdf=+gj)w7k? zbNYo<ni+FYfPdJfJ0S$4Vdk}D>^zA=mTmT=RYQk89s879KR~PP?KFk003fa8S$gGJ zTC*wkIqcpB(NGpU2XjISAq0EufC!jZql3}b$HhG5{q#mxDBge%!7fSRfGeBT!gR_Z zdI;Fb;0vS2Hk=TRx`^Xw$_XnmOUv1b);ti`=D$hiN5SSM$j`J5$y7t>UOU;3&ZhI` zZ}*+AU&_>Jh7zVo`pWg^*3KKlPf9YzE^s3XR3{9w$dYSB3kpnQbEw^)658rQGHb0# zXbkE7q@4v@7hs*!wHhyn7}!mEjN2S$>Mk7*q2J-?Z-(AjNf=k2&)Z5*=$+J?f)duw z-=sTF5DrIwT9FO&ifuhzC?T({YGG%%#~o&InpL0F^sMfjtW4x_w0JT+@np&klYQm2 z-leDXjMz$#+hYw?8yZFOT{s&p-^kNsqTG!5-sjzzsct?Glu!TdcH4*G-@pMkIargz z)KQL;+zur7Quoujq4r@X>rhK*!@1tdN}XO>2EsX0bJEJSgYmT*3Fx?UV~Q|3WV_j8 zMD+OZ3#r`<eN;VtW9xh?Hv%t7A#hWkNVZ{jAmaHGp77fE7(+rtcc~sFsl+)2c=tz; zB3=NMLzu25AYSaH2Mo8E;mve34VMyRmuEVYHEjw0GqR`N_X&9YC_uh0@R*=G&$W6v zy%j=$dN9*kn4C1xjPHHC9>qg}vTlvw<wm64pq%_eUR`Tk38hq5Bj?{Xs+SX=G^kl< zdNzBydHot|khI+mnfaMG_oLdkq7eF1&Fc{y5FhgRq<}DzhUrmBl7S>fbxNT#rBrBM z%YP^>u+7m7>UydETrgtcUwRITthhrw*$ynQpUIkjOi2^6yQ48seU#0Gv=dATfFCPx z)5Xr|11>~9@~0IN?r>VQ9HKQ!+LW9k+PRQN=L((lrQT6AFz}jg#22plIXK>|oGiOW z?B(qB<X$9Cd5bfiaC9$7{`W8u;lGjw)s|i!>m?<Y&JgmH{pgY|z&upnm8c4Qka3VO zd}m4TUb4Dt2;?Ik=pxP<6=?v;*BnjCu3YTjF>Tjv(<+DP^Endnlb%8pqm$xRH~>nz z`29QI`mz1oJ?=!rw*&z1D@DQT2jE6hYY9-zlNx+=e`4+Qje>8FxDjj$WDQrMS}iF* z#DhzpVyURVVf|SpjKaraeM2x=qn0Fj*Is{vWt|)G|5fvChiol$Ci(mgDGEFML-4B$ zZ=ENY_f~vTxDyXk<Kvi;AE(AE2l(p;<oQ7fCvksZKtR9+sn|sW6Mt596;@%yybf8i zmS_l&!7|IHQZXWW(evMkVDxwThF5A~cfbTWh3=0{9j4g6O1F9Su^<yBR}S$=I8Tam zGd}SnaR=tVn<Rds`X*gTG&=#DFhv23zSPtU<xJ$Hz#5lt_jA_L0={L8tPu*Kk9yDF z5=P)avTos=`smo6@z+%9r5DQbixMyoISUF_<)-dx`KZ_ZSlF3Hm_;>Y>ER{iZHJ4- zl&{?$*tJRh@@bZ^D+iQy0{+VIs}KSrAlW4~{BZNVOLB}^YEoQk{90<#+7(K6;K@&@ zI;mh1*5Alx?i>g+DksWn!sK0=E(p1pDk2I5?fq8<(x^en<*+g&i~=)<kP+=|$Q}iR z*V_)sIOt54FR}Sj$|31SsYiC%W*_~KDHcS;yCQIm_&s$>jmz3iWhUptlo;34IM>v0 zWu{oywRpR&{V(@a_$VjbAHWx?9uZn+f=KLz!oHrz#X)CnNR9tN<rOJ!or5k`KRIGv z9mzt>ad#v)m+P>=PPClyS!6|5qFHT3LFT-t$-1#3MZbf@YZ|c=n;Bo5N-j(#_y!71 zMv@;hk^f`DutkZ|Q<Er6&ht#y&30q$l7nkguQmVp`{@UfpY)$Ff<a`56u3y}I1f-G zape$E8dM8}v1KDr{gw+Ul-!sxvg)=L46o}7{d;4(KjJ%w9%At&Nu?25FucO7?}Il% z+`1Q{i}=d#lX(+FT%}8g@2aN~?U-T!!0i6MS?YeYU1~Hf+Uk9@&HLyhZ>FenrVD|o z;ek=H_^5y0TcJg}vh*KvF9I{dzL7fSPo}q;*_1v=z7;@utMJKVWWb$qDWkS;SQ4S? zZ%>$?O^>*mS-3%N-gzPvWNP+xQtv_vB?QQGL+kJNH8Ul-QY`LAo13OuoW2&Vc`e%Z z_tn#>@4cC>cQ7TmMmb()O0oI%PdJYr8w2p}5UDW=?+^3~=hUdshR2JQa(j3l$~N4u z&^j^|AN1tampn#*8;)1Qz$|IxH5<gz%f9RvAA1fj0A^%WSEAx}Xumq*@7{`DGxTJy zM*nv$><984-J6mk6+k#l^)=Z_!bD9lMm@fDC9#=FJe(<t0+Tgkl4?(N)Cf)ZedYW# zgbYBH`Jl2)5p-dMn-ayqo1_Lp<Z9hutGj>YDEl0ruwUIaN49frBD}3BYUlJVYY*wU zWGj5!0v~PD`m52{o@^Y{2qYT>&hdy)Ze)GCr{tA)+P}JK_d$Pp;?9BbeafS2h<LkX z@pdx6#~6cQI{oaLj1r&XA*7NCdd4?~H2*u`zuz@J5G7ZV^u5TtOhM;ZU4y^P<klcP z@A?4c5W9S*woJ-gIQmKQoM+pXB%nN_l#o2-o2cM_xi2sy_HTbXGSTi^OvHX=M=Cjq zDS=KsdAF&~2t1%nj_3Pvo$ZF}0Fg+&PT;#y$qPM$K~ymXr>Bsl0xoES5XG<y_+}Cl z8=lC>@}E}u=zJj#j#9{!j$AY{WfJAiG>R1O&lcv5*YyY4i#42Er`RPBpk?w6^tMc# zsc3<w`ocUJ+Q9;-10!*0*=Xqx#U{7JtSh5s?5|sik0ksK`||esfdrg(iV1jg?N1w# z<@lG(biLr~!j)Y(+T+Z{!M~m~&g^$;&NgF3;;IWq_Y~eaMEkQl2#|Of&KesvP%&EJ z_o}pDG~XwBXZ$QCf|XATYJ?<;u_|0w{XSN9y6xg+a1NJfy82EIArL!h=GOQh-SMBT z{Ex(EH%)sS>@vC<fM&jER3X}q^h5*YCU!Y%q!o49yX<djc;^<H!HUs)^tKR?A&=CT ze;m~PBe_bRzvtQep-uRfNY!ipX9Dj-MpT;~<Dnd`7`K01`?h)u^PC<b7Vq}hh?~vO zfl#-F90C1*`#kpu?Uy2{JRVevC+-S2EQN1KX!(wSw|t!uZ&*kpH}FtMl@qupv_EFB zzzy>c#4rbdW*J6N!hmrS&EAlNjkZgeuh?hI4DV5;-n#$Yl^O$IaI(9pcY|?)|5Blr z$(`W(>2KHnVGwxY{Oq0$E>b0CM3={#56`nx3uQ|cI{Nl4Nc?tOelb8#w5L9V7nlb` zKjQblbANIx&IhLt>5%bF0}5Sng~Tg?4mV{~`KfrWt{#q?fe*e5c|m+HR=+y<J$)1S zZ({ao8RVn|&HOGYTPIeZ<`l;L#iWBjx+8Mr+;)fInrrvNQez%>kT)j{sA`_&S3*Xf zzs&d(26(-?pe+Y9glYR$OmV;wK3_slQ_P)PKYYhFd~UgGbAkAY6Yq~f;~y@J&D3^J zX~&H^U9w*@1Fo%scx8J2cw}J&$I*_R1E8F2;Od*x`)W2!qA&eY<{26O_vWfQS;%)K zyh(>bJwo<kF-BwMB7~kYL(V^kW0t}5bw=Db5Jsc#n5J7f0~zSI>t^{bQW#Q9XVL{< zO+8&;#@1E7BiR;N**8;o=*=7edUL1#ohHG3W9IWkOBj3rRa6z##CYS87@uFRz42>r z|ANMoLZ8{3H#-M3r(8f#Y~4VDxq!0z_}u0mZu(ui=?yRWg=9evw@O7pI1}G_ey^9k z(otWt14ri*_r4@J{F!3L>dkYhI!{~FUCq|n{M$9c$Pm)an!Fv7*YpD^$$;gA>qU-o zITp$bp6ou#&1rt*pS?Vq^7bZtTm+XGQ(Xt)lPNsUw*Tv?TyDXo;Hu6buPbxbm3_~X zBeE2H4vA^aweU1@;7yKvjOn)=){Fehac195cW2LJ`PR~(vM~fgm_FWXdTT$5v5V;9 zD%sK7VZbJ`%hRANyUEJ(ID~t-0pG;3W-?bM%f)oWn=i(4!e`*l2Aw|0i^bx^VVM49 zS3{h8zX<I^h^XA|DR;#EE+t})7)|z59iYs{B3vr6t=X@s{i%<k7O>ma^h4%Q^^$cv z!xdHC(5D@`6$1Sn;PGE^tOz3u1qoJ76|;YgP83sp4vWNY)|G8vidq~F;WBDl-2<y2 zb*!BCe(B{dsF|-^ta2A_ZmPNNZ&E)GwHv%@D)8ge830{r=quQT%PoAXYayD)#QyaV zy^B>`R=(yN=!DC41e+TWUSU+9QmNvz40<w;=#Ct2BRp=#$<nM=A%$hQJkG&0po4vo z=!b0zCr-ao<?+Sie)s}GUR4+_QuE=o&SzRym>rEQdc4R^9UYR=?PLaa1a!GoH07-- zBbeMicr1$LM9Yx9zDQ)OEeBDvKFeCgR2Zz+Ah@P*oWRo)BHh$LJ^yvpvOWJ&Ib+f- zwd|#^O;8$${?m)$lVCQtBXWR8<o4G){wq*CNS-IlPJn>Dn#FQk(DST8vW$=yMg66D zr&y&Nt7S*$270l1>SGONST*2Jb8j`6#`gH;9T~4V*t4loP9X<T0bq9Fe4KR8GapzN zE)(OlrBG4?@9g3Vz>q0M&c*W%bk|LNX07pvL7kYb<)q5K2fR5A$nPqbqb6jhlLMdM zdgK+_9VmO(KaCL=p-pkM3xWcNC%|$(qTL-|G6~xm4u25La{+|P%QG}`xNS(sa~Gb4 z*?aL-mpRlg$&e%bbw1yHW=q4oJR1@!8eC9m*nL{CH}+QJy5wl%uI$~4<^a89g9X?n z05~<v(}d;gVkaU2AE^n9)KwxFfQR1YhLxRwtlYT|c$!O8#dIHR2gUK&MiH+vyZX+) z;F)q@mytj%oSpui^5zRCFXBZ_L4Ttin(r9W!Kl513uEx@&l>h+lqUJ1*%R-L*}TeU zuL&`Va^TwB^mEB-RSc#N09?xcQOy2vB9_zc`n$5r$x_ENoGq)CyrkEvw3hh<CK!)X zeIZ7L%D}Rtvos6&*lulSAe<FU?mtD&qn4VHZZ_s4&VRgv?2NFJAEznXT%~XkP+hNF z;DRB1#w_}!IA8aAVuNy?o!O6ruFatF66k%}k*b?};WzamS0=dVCVRc<gcP4>{~0QT zi{ts_bfZ@hPctJd(yD6e1?|h+GHG30JSlICP8X;Sdz}P98;Tl5<0X#|2#fx>XyC`) z37bKrO9zCn!}r~9IF>aE016p95oXFnb~`-e^kMxc4*L*OsT<U4V@<JcM)kbzp?S&S z`8*d^iwJgY`l?d6&VsF5<Yz9$+(RA-*jyL`n)L!yU=|qpSHOV0kTsP&cs#~2?G-83 z<-lFHcG_^8n+Gn$Rn@0DD*Q8o8`A<y2=^bF%Q(2nzP<B=vlquZ9NSH>$vHb@&LaVI zAoEzaiKB%W9l!t#>-fo!VOT)0z5X4h$8}F7Q!GXG$RS$>COGO*A-4J$N2!Droyy&e z;$4#E=W2Z|q9;OJoVx$ki<)j)z^JiCcvG#&PPUQQGU(JY_0PUm6vFWOOb71q+a&7i z|1`?Yv0We$fQjs5Kic2?JF74?cmmIAi=tbE%)@TooP}@#haF?|Fdu>DW4N@P8gOKp zvrmTrdxMgwhl$olg}@jF9&0e~l<}Ps-O^;HX|Q_k1ypGEQ`>>sub-U4ttgYyV>@#J z{VzXnIhFU_7p>Jpx{M}8L4BE4zx^;MDOl0nJ42KZ5xn=&Vv{Mu$ARL?&FA`9Ph@8L zs}Ofj*bVQs>5eraqjC8Bs}-o+-6yZCeO>c>l=cnCfd&XN7DWb-ne)g7w~6Tv)_vgP zFYnof90OlrU1MtLnMZcYXivbbElngU6ERTX!o!t!vG=0^KlvYb&;Bo7zdyji$|MXj zmscRns4Ys1uo91ep42PJ6`p(z9q`tUlRm6wej_%ZBk8-#zZ1S`ywMdQBf7N_-Mu1> zRlA6dF*UN<OGyEy^wR<7>vIw~9B7F)cBU0LVYJCUAK=9ywT4RNIB|EsQz0F=JojE9 zawP);O8rq9bKc{+Oa~`7F-B8Z+N}uCHT%P<_o25SEf~KX(Sy0khXess3BUC1Q=;zk zdXi!xc^`D;Z|My8>FRceD-_5>07(}y{>L6TX<znAI~wzoy+&@zKR$&h@}fBo9WB_Z zKxSVn!fj$XPr;hwXO4RL)gI^Ra~r`c4f%g@si`BB+9rejvT?&=#uHQgJUuhq3kT(X z7alx~)5KNJxn=V&-~b%kEY?8LsJ9Ma4gr`)2|8S`o_`m;iZ0q#7}7NXw!{Zd^>e-& zI2qal&d=>(llJ5lXMZ>83C?BLYz92!#Hvnsii;3oPV8W$5*qdm8!=uMeG|stNZRGy z-lD~}!pWJxfc)t^JKc*b{FmI!1m3)!f%LhtEqAbB=f3hkRT1t!_qSW8+*-TxizD#^ z<{($IyxXLU$L*AH61z+O>p}yJurdDDVqK|&L?^lx=oez}^IHkc5=IX%%1bdQagp^( zAAiYQ@v<2W;WjckfY#edTr@G#voQ*ryJ$-GOsf#Oq-eal@&zSdWPm8cg>)dz478Dh zh5Hj1t_L9BlC(=mdJmoiw*`#b&tBqz+5L3zR5ZHZIUjtlm%cg&u#ly!qkM1;c-}*U z!%lO>>9UBU?2B!Nn&pOv=9leZ!oZGj7C-q%B>AlRrC7#f=P$s)TL9fWgKX_UN?gWC z*vckKDt;G>FT3rwNU{?yz9CCi3wh6E*AptbV#g(MGuB9}?}@=EfTrS)Zvf0G9ZY68 z)eaMB)h?S;<)+i-G2W|lm)1;LFB^fMQq!5xRagYI10Jz(rpjKt`~(O}B2`JIIZz9h zFKg$12%`o@2du1#E*Tt3W$7D_zY{~ApmS9XWJ?SLtkL?+-~S6Kj}b1uqhIk*2nKVJ z37U8+%ynx&S0pw-hR+(VODofRz<xI+=phH9zJ!GyVpaCg=Cc3p1<exZPKj{-V$hxC zZsTv?d9x})0z94|*9&cm@>`$<NkJLx>%}Uv(?7+uOAP&Ote!etDYX&M9)aqP2Kl>R zd3JsM*=wkFu3<qB<E^CiisJSE@+5V!l_evAm0ee=yx$vNxl+PWTrqg1W_`VO7OFkb zolx|>2DwpN!<^caqI1G*oBIBkBlxBE^G7G#hfmPh#r2o&8;vT-`gPtugzgtMmBkl= zo73eSI~Y^BVD;BGnkzS2#QOB2gPm&m-VAQEvcexXZ#3Azo5wcVb~g(6U@gR;cI0LU zPtRLoMH@#*m;3X^x#y{}o82`Vy0zVJY=$2hY|?wx<(#SATAsc-7dHD@pEuS)wWgpI zV)C@&%?g#xzAq&Hf{?+kkkWMdflth$eVgx+WXryE_l@z49ECjlJV3iA4@_;oKc!H# zKJK(xr6)L4AiOpHO{OeczMs*y)?n*nz?u^x^xcKf$;$6eQ_z9W6|UD$RK4Y&Zf|-& z*!ujqy61M)gZj|f-P2R))!l<za}H8d#O~2WhsMRNujyaUk5=npz70XP7o-;F+wO&k zhAsW~bmp^R;)CZ)4vGpX)p}0VUtPApNzLj`K~;?uKiDX)-d6k`uQ(7}_3hsFddt-J z&)uI->i!4AyhLg9iou&BVcUbb8$5$+>)StC^60Ny!txIlcTWAdB1#Ewt_jxM`l%i6 zwbH%(x%*4f3jeR=y$e5hy@swHbZbSEv`<)xQ{5!b@PmgxVDS>JDTX=?P@u~2INh+= zee=&)_>U=bJ-|?R$55vSN{2wdMfv|jM*L7U!%cLn?T{SvNV+@SYH=I<ED^9<*5`E1 zv^_~DQKqiE@;QK{?WDAA5rJT%kpv?k0!BJ{hT4C-AEZa1E~0wel+V$+nW5b;PAt|- z5w%lkddo`4rf}WAKNi33fKBG4O=mr2WuW1O?u21K$4|}|10l45lZYE|`l;6u{Kw!Y z51ZMaNZF7$1aHRA)Q)YwM?d+WMxJ{9Q{dD|eeau}0^N~<Lq7$_>tF(5LQ6l5a)Zyo zV1Vc!7+eJa0D0KSBN1}a`-q?e3<yE9+QLo}f>YL$W;YK3*u){e%5}wt6h64atft+f zVYZ+iD{Pv5$uNuiL<wznyVxvO@O*%koBgusLlxUGr=Tb)^G7<C7UZD1XCqHcNZ$n0 z&IS#Y7{#~AUyp*O>9D-4KijM(H%az-tB#g)!Auh__m-)7#D;h@Fil>`N*JBP`iJkW zzq7>SJK7SUC}FGS+J$ZkXOqzU`T4>mI<UX-ths(=DDP~rzS(P^ws(bw8N${r4M9Cw zLSX)IOXJ35?Zu&O-8ZkcKHU!A`0`FCcKb_55R-^-{`~4V?T(z!NbBn_eZYvF3F6Vw z`uBXFv;Nj^TRNB8Ij_?-D0<hfP0sh)>fcK6OW3VpDB;z-dE?+P|Ao%i_wDU;`XB=X zpnqZIYCZwVU+(LHBu>sJvWN!Gl0aFBBJ!@9>pX$=itD{pe#Jx4R8b<IXxjdRL!OI_ zK`LN$niga}Q}t8eQydexKa!<;uy)Zv0Z{I^WyBNYpQE)s#-{6SPg(G=afutfBjX^Q zcb8!NfcvgwW!{NnI^g?q;0-QFe_*Fz#kYqc!ut$LbmgF;T$-2JYFg~>Z;AT?Wr2K8 zXy3=a6_R<bPcs5W0c*vXS4sn)QcYyP`)b)-2`YIKy?5TFJojEtX<>@&dU?q!_{ECy zvdZ<!s(@H*skc2HZ}hz3)0K_t=5Li7HLVAgQdMn?a+|e1Ji(iF=NR#u^~35Lo4zZ0 za$5}(rz{PMKL$MCde!7|B;7QhB3DzQn-#qMdadmFcFX3gjqNu(eR3~akkSAa0ujRh zz#bjEQOagMe6C~wVfq`6gL8(|wj+7-cW|sC=!hOJrI5&8KA)<{KEd$K$i6?P<Rk02 z{&8%zR*BW(p=ed*oGS|FdsKk48rToR%B#9LL+Fmp-63rM?B2+!KZ2_7Rli#0yfcS( zM2~CAW$o6tTitkm#pN=K@4)F`ul4uk0ltLEwkYd^>A?5Fv7ddKt{X5*)p~7wj+zYB zXkyMy&?tBPLEmb+fE@kzd!Ec29JN3>T@(BT5Ue>|qCTs<vy^i_>`&=+pPE14QUXT) ztQPXh#I2Rw*MGWN_N?Y;y-FmuYooSbQD+lUplk=LUadLaZvEZn1LFsj5_fvo!drjP zPKWcs0PGHaZ}c2n$KHg7t==9Rg6r+xC&P394#s@Wy*-$`-2U%yF7;;8pD!6tZXC_N zc=7jd^|}%L-{I<u_8-5HPCw`Xx)3;SYKNTK!6U2+A$#>t;q}Zu;#Uh{=Xg7r-FJw5 z!-b3*u6bu8cSz*%nJTPVS9`KAMuld;e4g@(rxp*F<D<c0VsIX0Fn5SMAi0(*4I~mV zQT0V2{XHCd%3sn9@t_~PPwSD=t~1r%ndf{Kr^tJ9NivOK=WgOt+KkT1@HP6x-EC&# zEwg|i@{8k4?EBOMHlUESZY*NCPupUU>HdQS-c4G+8AB2CLw*AhCO3IC$UI24Dp^w* zhe+`FqeFW{fz47gv7!;>lk8obskl!^Are&z=>~J~@ZKo^Fo9vEd;-mc8a^bcSzMAd zy)%I6rDC3eX6M#4hamNJUMYgKrtAC_+#MI(Zi9V*zHf$;Bo6f`rxdHsjAsL))Ov=? z0u>+d2eB^S^Hk1O?~j+^gK^3&Tdf8-A>MtXVeU^kJ=0~083OIF)a3`y^k+)weZo?K zPk>7Z`QLX2@TZ)VI+t&um>tqc+FYg@#R0k^SL`IIMJ6aXmTl{V&E=4r2jL*ys`+LA zCi11UvL$Uauur7w-KGN7%1rZtqaDzJ5p9*P_+(ZHd3@Umqc2H8;y;f+=ID855{huR z@9tEl{R?9lx^9<jF;)q|!*B{TE+ZuV3|6HK{owme-OBOkAcow_+-90M{*ebs3)K<- zAiM{Ma25Xr=5)Ie4+fACu<}EmAmaJHX}bcOIjB(X4eTs{S5f^`mo0=i&oU!&^&WR< z=A~|IiL^0cRFpNk5DH)gQZ)-1fM{iyxVoq*Q20{x8YMJ@f7iW^-auscQSP~Hdh9lu zebCgwjS%EZpq}MxLT6`v_h*M#j7>OUC=Pv>8q218InFl&cv5VWhr4POfz!d4EDGQm zKdAJB>3IfnQ?+vkVUw7U(JFy&kK6#K^O$~x?(?Cr{!cc)y)H}B5}Av=HoJ-%N{tnS zM)6F>$`IBiFT+q2$7kfyLKokNvhcxZr{2jecTGZp_!ae)G<yw0lSH`QziL6~m@k7p z=(=eiE5-IoBfGV_HlATL^)z6ZE#QLC)*AMEyGiKgRHOxKby9#-p3XOtl$&f(b1CwZ zTFUxn;AQ!mb&lVCP;=!g+@5}f!Xhr#Z$^SU0ABobKm8q2oy@~0dZHE7Y|tEec~ei* zHyP%Nku$N$cx|;b@}J8v^h4cccvqS{Ul$lhh2s1zzmxZi*dU$JIMsstdcKDr9OlV^ zKO<66_aAg2KWwKxy+}Q$^o)rysN^1Vb+s(h{U%0s1tDn#4`6<QEz=J63?8*Cc6nv& zL7!@Uylx1|^Jx0rf!ZzjPd_Z>(|7`<x_E0CT>LWmQJRN#_jh?dnU(Ts;ixKpx@sXd zyqR`GxrftzAxQWv3}ov3js5SWXZgp>S9%ztObLyjY3T&>M|QAN@}cUsZi8qor~o99 zQN=SCQw;0&wiLJbD?WB(`x;qn=<)r+)x)tIx}tHdC2pq)SX@y$k7&QBc<<cQ?6)}V z9*=8S_#F|qS8+VAYq~=goo^<_P<Y~t;bI<Q$BAsT|6-nM*{|N<H2KO*cx_N?Lyfyw z#QitrsMLDfy~;^juKH4yK&B#<mY#4<qPgSht!(+y1oatcnnKQue60WR8&Jf?sDt?| z1qU+DA2POz0i6+ncji`KHtHClv#2VtIP|6F-N05iYT|P4_S@^4<6gm_=H;Vr6kgbM z%MVOR0&Su%PMa-29S^6^`h)p#1~QdNdza6?VT+JD#+7-_zvCcp6@Ja9%~>5-K7ITZ zSS3kwbtZc@3j?Z6H~f(H2-2wMLE|kwI^g|2)l>Nbx@_(D-k+?H`QyYf#`weT7pUz% zsnk8l1HavzyUXfL!t)wTS6wv_Wf*w19rEzt`q$q)vy=F_XW+}<cv$BRXlG2yX=J4{ zQX}=o&7COqXGw{dL!LeZ69N*G)Is0I$dmZ}uDv6U<J$3M`Nm7v*O_iWG?M^31Rjrg z)PYFDAm(@zNEm|F8a|b5#z;U=BFwDvK%*%#r1OTECis~NAW{*T9n3%n(~%TjBrm8p z05p8XRQ&NKlV9NJfOxN7=Tp3=uAT-(caUeM<T#~>z)m6rfmpa4myAz-R7-XWjB})b zcm(B=A0?GaAxndfW&|ib2a#Tgpo|i(=cVHD*IiP<*gP=zJosFl@u9{kA&u0x4*sLR zlesk!N*ZJs1A<Qz{@N~%;)F=o<g*CmOEb$L#d+MsAphe@LLnj^^+mrmAsO+S2D-+3 zOP;Ecu++F@wz(5uk|!rHl|I#!N-Sq0Dc?w^q9}GundKnS6kG}f(;~9hDA`O!<fgc6 zmdFgPa;CCE#AOWfIxTfFFyY803tpENs!p6U0c*a+0$_T25ma3{P~8|j)W|A{@*nEE zHI*9v^?V#l9HOC|oQy%bVvwc?VBIyFxeg)m8gbq4wwU?tjX<!GLdf(*lI)mB_?%?l zoX@5?_vw`M{}^*%3jw#8Fpx!y%H<2J6|w=YB&WPw=mI`%ijpx(qAF*nG>dFY$F0Ya zQ>n>mqc>E)<JDw9_sdzOr-`mV@1S#1ir8U5A=Dtq(aj~dkr;P$aJ}wYP8u!SG7gc` z0nZ2TV&d=qCwkj54{@*7J!c2sM9JafPlk8KbWuVc{g0ya@Tcnk<M_e7*S*)e_Ab}T z-kW?~+qFfw_8y^|R4Ntj=vsyB)y1_(c1XJR$QGGpr$UHQDL=pe;5^RzbI#-Qem!2V z=WF|^*jyZzSN`lJLNPOP*(B!9&=UZgKoWvWWj?$mBogbD1FS$RB@vbLIpx_owY)qD zSeFEwC+34saDkDPS<zr*BE8pbdasOs^=3hK*(qze-p+_vl4<1UY(gtE0}<B-JgG86 zyof`HXCumCuu$7n@rqQ4ZT`ozz=sb!VR3h#MBX*!I7vrKa@|>ZdO6k*iKU74&P(aO zrLoOZ?Su!%WUgmHrLv)YdI3e${MEbpb#c7Ob!7T@a#b9(jSTfu$e;g}83*K8v}Ps6 zJ)bi{Jn{@_ED_)Ge@>ZtK$v^-=_J1z1|%S0FU4RP<kTmgsg*<ISR^bJ05th{O51WS zYaueom_Fc1#ZXam_LD0^B*Vc%de+d82AX5DqC~s<Pf!R`=u@H3`AS;F&1SHaa+o59 z0(g>{Vv6ZwiUYL}X?3O7v`XDkrC=J^IXpl#2<9XKFV`$K#^jp7Q{#rRG@W8T4%~X% zAJIL3QN`xUOAru#CQ*`D^cZ{|ILaxy|2uy^D3y@Skm8w>q5uPXmBJ@W8R`w(yGlVR z#n^j@tQ?p#5A2pFOsN4{>6}V?BmL#C>|YsGmto23spTKf7pxWQDbqj^KB)p{MCO<L zYUi>dDl~@=mXchm1_wegHPA_$7-Xe$eKCmjyfg`RITA)|Tj+|e+Q_2N7v?fJNhs8n zV>ZeOv9&Ull?{Bk4DA&;(e4Hd6$M&|B@7JsQv)Q_loi&{#uQHkKg{ri<?_K2gvuJ> z1$U7T?*!i3uMqbIzfe{pok^w+Vu~5GU>|adpV%;BJfTHc*eM$J7YzgDBIK{}DBefV zxgZM8zEt*+p|PH@XDiT&-*xqEWuO}rTu@0&&htcJI@y)lGfMq6+AM>wISg9O&sHi@ zS1Nm{(2QhQKDy=|x)PECi(#$1tJuh>ieTb|)svxlHjER$TYTEdRj>l798MO~dO~;8 zo<g;ixyYeb(=CPuhWOHJQm|)O*h@}^3?YQ4G>`XvM9zLKT?*{!xg`c!nTlZejiFE9 zZ%I{XM!YJ5A|soJQe!IP6AryW$QGB`mzV7d^<4^=VC{jyt#pd8{5n|PzB!=R=Dhmq z*(*d!l~HOgA}tr@`<3%4Kf@@7QCJ(67F|kaC_C0da7xu1e<dZ^Ro7k<kqmmRawc^i zUVKGdd{Gb#tEWP1CSY9*9kd6nPhYjCD|TQuIvG}9rA2qTBr`}=l{Ra?hQyN@Y!eE* zZI{hO>;6<U|7q54Djj(X4U?{gB3p70Z^pdZ()by2>tOj4)Q_0fDeao2Z0c=(NuOQ| z`csir?N?W-ic{-K(<i8NQZ3IA3=vf51OmpU)5aBr*ja?-BiiU}JD6yCjZe8QpLS;J z!AMoma-kM&l{!VnZVj!P>WVUYWTX>ZvI<l!xg?^>S4r#AIONikpbk&R!saktaAYrI zSEo@PPd2qbGr9SuK%b9Jolu8Cg;uSoj%1`gB4NS8Lr26bs`4MY#_mj@&fBF;GXYvp z?S-Lw=?`H4Q4kq<Lm3^$(E1^|8$<3lV9x+1j7!(StHCR$&GhD_B8jipr4Wy*#C0b! zDn)H;Tn0yx)WAiX4w*jMn3_y1Z2G4`woolr29Xvu0#<}~<RU^0;S&~cc$e{LHDcHm z(UsR&f?#;<f=JkTp@D|Uh9E>w2NH|gTXzJSzCgpJI<KDAd|<2_xZfdX2P0Eq@ql$E z&`Wn?ly-Fp+BHJ!Hu@NOKB&&FC|FJvbRu~IK(wVL4DW|j-Y`c%Fk`8yX4`pVf4j)O z!7X(6JLY6+tEesYz`%c?VfurSY_Ey8I*5)x1|dfVsIwj6u91#->ZrEPK&i}RyhYtN zMycR7L4kY$a#iu0j<;`IVc)A^YhQ$|UXOpyWguf=Du0LmAV&eA(W#v&<<~>dzp(n` z&c2li7N*Go^OhloF_YcWEmsMHe8hHIz0rdlXillmQfr|3cn^OsDr$PtnXwoPQyv|n z>zXM=P0+HAy4K7T$jla#p+$P|Ka2xM*M<lA>r~AVMewo*9TEn+iCf0+Zzb`h*3EjE zw;kQ@rA5w6(=+7*@N^pM1k1%X$_#jPgtluWKN_A_2TOtvWL)m>{`$6agj%d5ed97B zW9Dv2C~s*H`Cbj8a`}CJ@(=(FWCBdvU?zt%H-y_LqE(iwX&Lb{pVO^o(M5JNzYhLJ zmf_Ohaax+*qpz=WU(f&hv-IgON4vMiY+0D2W8wW@So?#a#TsZFf}sq6PgEnyY(AVP zx7j{Oo|Du7&sB!W6{d%X&$|ZY6Y%&Icrh?K5;b(>*3p+gKOk5)UGs7Eu-gyWYpes$ z)>#Vy!O3+kK7V24=+$*5faBkaH_{A*TD^~4r8`*R(VZsi4VO_zmE7h|U8iMJ2Lir+ zEK!P=E8v-49!xtO%BcR(%mictaLrfnB^d;dJC}y<Mht3$0l5LAu`XWO2<n`nwS;Gf z^oHs5F6Yhf%hbtsZjPrGD>HQTomIh3^OivcpCDc9tXi{lt6RZVh$`%7?AR9VjnA=) ztIzhfCQer<0Q^=Mba7-I@&Hb;S<8-^|AuL!b&+lmM|9|IXVScZ+!%S!1dNQ#jq7~r z_y^CMfY%CrGTYnA-V-q0TPX+N4W7`vmF0%fuZ3ajVsag?b9<W)Gg{=hG~+h|{!A<s zEGsO3<<niGjajePW5}I=R|D|D4_l$D@FS~lMASy@1fqa>BfooPNpM#~cTF^GugYru zdEHkQ%e`-JZ8Ef__?LJ6>Wd>g+Mk;D%7u@BtacLxzXTVU`@Dwr)xpWYr=bGGuM2#6 zW0D}nFST_oQ*vJ(?|ucH9rVCi4i>z(yB0^Gg<m`V8DL%?@QuxoCk{1a4mIo#0qmjK zo1>A!BPLb`iU7lC=T5@wgAR9u)UveW(G|592<>~@m!n2OwNqf0Bed@4S~84r^cy|W z%*tAHRCks!X`M}O<7Mcv<D=t$OUHw2AC<4QaI<W=jIK_G{A}x8X`;d=nStpKi0juy zO!wdoWGM0}qOx-pQaJZ&sy6CBo_O7lukwFB7W__0HrIc6l*qyyZv$`A`|N&jLQC@p za>F909*%zgZRZ2L$p(Rb_-k@UX6fPEmVd|nUq=!ypWHqBULyZV^7-#lIfnA+-w@=V zAOE;sOq7S4{%L*+Z#|pXYp0G*%A37r`99`t&apqg{9)fLabNdrec;VZnZoKM3xNHw zkp~=CPn^=DzJ*Kt0cZfKv=gldEKSUOML(uaKnXvmux1#~=|+<^Q<*LsQ?6B{e+x}9 zjiE?Atjx08L}$plbw&&cd;gcE8v3C(`^qP)g3Ay7f%ww=O5<~EZeuj0itGSN9xe1P ze52BV)ww>ll*AS7Q0*?52URO_BEqG`RTdkB#$R|ic1e|*W>i(Ww$;*VHf-oWvvd^Z z<a5FrWdk8py5#Ho-u+2}{}Bb8m7>w?DYOL|mEW!aqNt)GOmi)@YJz7n_ICP?UW50= z%Ct@F?nZpc8K)6r61Ti*OxY>i7sIL?x~A5}VN&4wD|~A-Zfj@pk5Aw$Mvt1D^lR)U zFRDTA7Lxn`CJR12T$Jv<a+U1sbyqcsLAYwk{;t9CcABz5NtdnCJBsEe#%Y^7CXh`5 z1?KjxYc=AD6)pKh%ORncrt5`%vm$gzDqM1<VKsc&F->@O)xYq1^L(25wM$O!G2hex z_&wHWL@0$>N-$H(>_3tgZ!KyK&fZ`u^3;$`+(ekelr6rX3X6ot6c3ub231~9N63el z$bP#$PvLa?fVtMkJL+2Am#-1d*zZWS?PbI29qgs^H&cddC$)BDN|>JE6ZQ1y#hPsT zf1ik)T@rT~#!E<~{NCt(Ex!CzlqGa2+<Xc&Rl@0Qlc)Gjh2Z_7_2<=;e#8~38LQ0x z_ORl(;G+bIc0w#ZgazWI(B$axsP8k2UKpmy3@u#A2*71K_TSj5Ey<TyDE|#Mc8-{* z@L-&RY%NtESZ-I^yQGv>;h5Kyt~h@?lzpRXtuHqTafZ@3-T&6-SneYd%Lcgq%4t&m zC^dCxEJyE6%5dVK`9!|{#*Z|b5t0(=4PaBgU3$!MPi)5FMdkEZ#5YQy=Y{W_7B*>) z{%w8*#6REFpWWz*z_2pulemlrY0^vLMTRv>$cq266@RpN8|BzBdZnko52<#ZCVW|F zJbRg4kvQ*{5n>8M)x3e+Z$O2l_L^n>W6&@#cUfqVt#iMU#eQ|NT4FnIV;Wpk<k6rl z*5s6Jl+)^TyutZ>so-`=6>_+}<N@!!3CD||A{3d^AFh3Klvf&GXefbs7m`uhn}hrq zk_7E2Hwa-ErQG!5!>Z0dYrURD?B~hsxHC!cj^F4xx#XPc-s<{o<R0q{Tw68zxbi)u z_F&Xu!4vtSY(V$^bKytMVyPAvl8Pc=l{Y$mQJpb-&i*Nc;$qE)zk3O{J`&PZ^(Ni8 zmmiI1d4F`1O4qXyWtvuzjc)iAKWguo?`%ntAO8aT3AqK@b(n}vk<8fkJS?jsSf7ar z3qQ~1pw+-Obt6^*0pOwk%aa+=J3Na<+*=Bd?YFy$z#zZPzn6#~X2p?po*!xat`vhy zYe^lbWl!Bq(Q|VGy=2z_xJ08bljG|Rd1PNB-<{_yEq+1<t|@nEFTrh1eYhIu3T?sz z4BXzWu?7kC^4oPK3qUp>HEkElaL^<<XR#omyxz14t<=inpd0_Cc&0u<;Kl7GQ=a+` zBDoq2i5j#(hARo;ICZf^wB9<Z+a8U%l#8#vWGSj*$onU<zOOFjPD|an%IEc1Q`cA* zmDYbj**~L(3{HeLno97RN&}|WVgphcFJb{e(4HAkN`}FNG)EcGh-ZvvZQczS@2bwG zDlzYh41=j>$$&SWb7cju^6n*?bC2>QuN%pKi#1Vi&WqU*YRDvpV{kSt=Ik5fHxV^v zXzC>z2cF+xcxZ?7?7cm54DHy3rVRNf^dO8C7gSZ@YKBlz);L!)ajEGSBXz!R6}eEE ziPQ_nK=kE+wEm#k`LSQk`$YMaOW!u83C5H{=&z+dIj->OzCmH0Tp@@&SGY+mmx_I( zv!&7Ax>=rRqm3S*$095|N|5j`_IT}RLbE?<-a=t}5*t@@V#uAQFPbRrCut6j9Gi|_ zPozDL)49Q8Us$@v7A|VYy;08Kz8!lf#5GaYca?#1=q>%vh2_kg;kSw>W<%H&bj@Ei zS2OuXucRQYAM2aO<o8*Gyc;D1S-Y>Vlw)y06-MhHKn-uwmX3&rO<p!M$?<xgYg|8F z4J2ZNodo)C-iav$%l~U*I2j6%F5mS_paxBiUVYzwa?d8<Our=FW~PCX1dVX`qwF#w zEIoyQntX`6(mSR2vV-A^yg~{DSQ2KsYHA?#(93E0Ld$EE+1`KYmFk)L>PTr!Lg0(9 zFTv_groNn{+m5lw&kttBV13RB1^kX@^GPBdgGSP^2iob-bYurRDUQ3_(S4tmyYv6a z>aGM8*BC_5ijk}nBP;ux_xb03D9P}`ck!#<9T0!0pW@k$XS!j^khK-F7<c$+rY9*& z!xrl-{0ehol<3_Bt(Ol>=~;0w?E7Y~XplC%#zjZw3W5^kq9zG)6mRD0IirN{jL|Ce zeZ&^vKs?q~rN~yMR#MiqnViSgE3+_}$ea5~%FHhlB#D_iSaG@<t|GT6d`HFdg@Vdq zf^Kc5@Bo+^{i}LS?NeJ{=vJSs0?OP?rWh)>-6ukOgTZ|yi(C9^bKEU{R)=*CzC4K^ z`mvw>n`z<bV2JxtTyi;dK?bH}R%lx4WoPA|dAFQ_wO_$-#44Wg4)U7Sjptz6ua0F} zoY#Rq*@y#1afL$eYEuI#_htY7?Y%hy;ZukQbp9+}!*J5sU#YkJ^?n|S6JYaAov$@z zr3RK}O*FukRr1`e-%KnXFd8coE%w-1v}e9P9O`^@kZ@-aI{|p=OGSCnTY!8%R&M=l zdpo+$cBcLK*3k*W#cRXyhPgu>zv+9@JD-i4MG7xOn0fF>>Bi|9uF|T9@9Wkkc%<ob zbW;gKNV||*WgA;)P6%=*Inj+GoFQj=UV?c5&HdTFtSWimC=$hN9PL(sdgK+Epo{5N z&Ym(iIYo=MA@&3x3X6h)1==mQ12>RmV}jGH_P@}-G%MWmaAVn%Ja6y!zSKMP)Vzy@ ziOaf0P{&p<vf7gncz%Dc)4khpCH0P~!I=*`<hPnMjYmp&!DnM@chu{1Mn|vue_{!b z_x1IEp2R!lA?;^=9K7w`J!q&{e_rr$Zd3f;&8NDT0$#o{{~k*A965lGD;SH!BjQ}D zqxxSue($_d<l-*yhubRvT5~QM*i<y>wT`C3Na3B}G!+t7M@CAV#KRNnLc$mEX8;|? zY*OxXAZ$5-f9-OXr~03SX46)X#|go64(#d~D~*M?kuGy%QT}s;KhtlPUcKV?jU%st zu?UqbB8}85YQH4-en^xUDr-UP^@CrDH^yi^cWQ{4=p;ae0_bwMm6|8l!N$O2w+Y4k z#kj`r9d~>PF8ey}kwodbSl>XAv#VK1K5xj8xmwB8>$LB0CfO^srk-2>Y4takmA#?` zcJ1zU!5cPIHVr2W7V6=Ipm^tm>p{rs?`kTG1Wy}K_&#{@4@|4+KL85x%4&8&RC>%2 zd?jebNyOjx8t1;odLW4D&kVGd;ym_IK0>v+KE<o%^63Z`30%zE)pV4-{%$xMI<h-w z8vzF;ylB;tijce-3tj2rdHwr^&L42wL3hE5`X7-lA1Gck3*uZ&ly0T<Ehk`F!8xy9 z%2DxtPMYKE{qE+?T1`E6P~viz5kH%rpG#$&M2XQ&@t9V?%U&Oi0a<vb`b5MTVB&D( z+#?|kt|_f0VJR&gsWU7T9=2oXz7N)5fc*Fa_OJnoL_>gbNT?8Ab06#x2$J?BxFafA z{|s7z3_AW0TpPeE>x~_SrVmavND{iS9K(7XP;{0?frj3H=&akRvio0$1Qv|jSi8~` zk}EB`JgI1pI)auDQ6mw0r8QPF5U)M~@!u!hxn`2<(v}@%lHUZI#Ia-aUdTth`0?8; z9*Pbs#ud7D8|=jGqqt{QOYmk-P0v-24b7lPuo0AgvI<=pVNN2ORZ}dypb!r#-gKMb z;Yo}G=v8fS=lRLHQ}7KaSUQ<7dSp24YdKy8Td4v^%oUGqRB`glEwQ!6D>RW>sbB1P zJ0m*J#0|Of$#5_`OIy4#XZzcgyXa1IBL@1|X%3G?knX&TYj(A)j_Px-!zuYfjt;@M z=I{iY$3dP%_bi->4Ni6NrSo>IjVHtl0iEqd6L}QxrCG#8TN#iESRS=PTASbvv+J+k z1_-2^@SCpK+mNvYca;gZG+DnYk+X2Cdfb?k1fjp0G#Ft?Djz3ISiN;6-C1w;NggK% zLA+Op_MXJ#kr7{0f=L$AVw=`u1?*L4@tZR83lH1oAUI9fsG6%UjaV*MXFZB)_y~$N zc9}3~RO>Pw9*niArc({vsQ+0x`b8y~fs-({GZAMa#k^_DGBfEXgjb7%5R<LX0-#`E zo8Y-U+!%#(@gxS3E^7qSX{kbXN5)ug#ofV=*#UO)r-P}=>O~Dx^IsZBUK$#KQ$fWl zC|?^}q}I3fflgRX@KQbP4P_7LV{ZhZAEc|81pTpSn{DXuJA$Z5#rpt&kLhbi2Z)6b z-ftf);5MWN1y`#;0?Hee-H5EY)&j@V@@{cA86RIfwvInh?QD=Ow4XA$)kL31lKjk) zyPaBj-)8ejCH?>X6v}Bh6ZJp#sEG-0!7B*P*;&{3!@ZO5iWRvC4!?9DK4i$%@)_$W zqk!$2kSxfzNc``6ICE2?eTlX8&LkFL&qU~(o^D()R18X=+iFZc^Il*q7<}ud(|p}W zdFficEWv7y^|9MN7!TI<N`eYro?-2=_0k~LrZsE&L44{g*moT;mPD7!#GpE&v-yxp zAU^vwct+Ve-N-p(5WUR-3Je@c?R)d!t=-D$=-2EyNj|QO{kL0#=SX@@tq#qv@5V7U z^eLl?J`U6DNzh;Riy5kroEk@;R)R?+=<=wohZ8XXN-&{9ygbkUd?0;KT5c-dzHa6Y zIC^@6;J)G_5W0BB$R$0xPY*nWsk8Mq_>VNVKwGmg`Z}`;45yMisN1;#m(~A1>!W$w zi;d2YAiKItyo;N&jd616_gl=^T>QQ>=8^>oXk84BbUyQM1^o~mkfwqxpajir!pCF6 zJx*e4{uLjRwO8O$hMQ%^py3TCC-o}yZT6nR1q>ulU~EPv*fP$lu3@4Nmb;dAMmv35 z+l_8WaYhw%Be4EGVHpuR@9F9Oxx`t(f#~OSK4%Evq-}c&c1*_W1>(3w2ki9*T*`?- z+k_A8-~dmEpAE6)nBX2sr(aIoZgv~+i%SLp1hCzc>an|d1N@ArgIlXRnu9rdFrV%? zXy4MY?B#Ur*U!vfV@w~ru7G~aIv1CW_g^Mjzw_{ct^|3m1xFG&-+`~z;iOEhdF|;e zBzj!73C2R8Ye2N$Hrj8n*<>5+Gq~cT=X2&|L$ukZ9addOTy?=a#C>&}n@#WIG=5Dw z`A~wRq5TC2?N@S_ikk>|#Mdcl4?A6!tL1$A-(sWH@JMgHDrnXSb%)?HY!3;*Ld5;o zd~9S~CO~ErI6WTs@I0K0DbanK;2TL)0Y?W0PUji<Fm|eIOZfQd`KW{~`qmNDx50j% zMAwIlnPi{RlBN2d^}HTEl)t~h!BQMaz<d~!q4zQF*K?>*b<OcYu6Em>Bd-Rdt}4Sd z_vPhqU5INd+=c`)j0S~=pj1hXy$*h1SvZ?IqAxYT@s@+%iKBib(Gv?{<XX3%z`3`2 zdO-lcxfS(D&^73m&w1;Dxc`|ul-}HP!9r)@)^wNuR^TpbaOlJ&Mrowo;^hy5YEs8Y zGL!cc4x;7k#@QzLDs@e-4rEBu4hN0?4uv?#y<K*LsBhNzlA#ZuY;IZx`XPt`<)0Y1 z0vT^R1Vp~{k(h5O3HJVBZ!kf?I+-o6Z;=AMAUlw)uiGzp@ut#ju~&QxKv!;9`Y$%V zetSfSh=$lA=zaDH&RMTauz15dI&B_z)roo!n@x8T<okwO)RS#zE}yGHKK?7q&)uO9 zOJ@QUf@2hj!Jaezz=|K$6F853isDTW!N7!{6Tu;!>R{~vx^>U@{Z8;*fv<D_IQ0~+ z#Y=4LVMsCAT63m6XZ%)*hNF#4r%orY+n(;A#rG^cJPA(8bVg8+p&s5Y4D?`e#ov?| zc=FLtVs}tCxJ(x^YfjXQG>g&mA(a!0)O;Kt_~{GbgAjq^5P;#s%1;jH?rd14ZfHDp z#v|GC7RHQuH`qUYmqtA`z#m4SkeIrvbLQZSGzF>JnioJ5FE&TCLMJ^uL(V<p20VE6 zKswcA)aoI)AQTd2O7v`T==&SyN(^D-B9-oi3|bA?kf(!Ayot#nkA4tNA<;oluy!3p zY%3(@pSMpIF)ai_5<e_9-hIpXI07BULNM`IKhIoIU--9v5XBns<~Ho*#V6x~#M4U> zCr)V`&m6B^b#&1jP_ynXn&H(4=|SI0+u%Mw8IKTp>}vY>?NM)f#Qfmxkl89I&*N|9 z%*5x!Zv>5RdgPG9hhJ<wBS;@YP*1P>*U7t^5_!IbWhg+f2yg%Z^rTyaRUgJt!%NI3 zWCt=)68Hu#cr$HM=3J{$pT1+P{Iv~>@4gUg^PwXdkftM@)<wmDKw@B>XCr0Xn+J5G z)gn{&`rEx7LiBa+v$b;pVN7>PbALJbaY)RZZ&XRhn6VFo)c{6ed!X|+<{`-9WOL`k zQMv{sA_wv%X?;fYmVnBwl?Ww=Z|SJk1$`$S1$mE*xm{7^Df0KB%c3&w+rt_bPme6D z&mNWCJYJd}mwW4|GMk>}i}rs#y>*aA{=xG!aO5FAVDRV!a?G!8X8H(%`?of^HD<5z zlQb4)^ON8*fpZz$*trm%;Y4I>xM3|idwXV3dsh3@up|1@o%^=GNy!>SQ!Y!Pe5gwP zlXAUDK8uCV3Qvo9dMdI03VHV%aBAdGtry=<s;60Ir`%l}`<t(MAn3ibKBij)ieHEE zJU;NT`C_97IWC1_<(&n-5!Uj5k$!~iJ|uqV-is(ZA|WEYPVQPk@6G31|4uY{EXx6+ z=emvfT5=uXMiZ^;NqUqi`Z$;5Gg;c0%J%&h+4>72Sdo;3dP?h~X27sh`;Ookd4316 z0O{IT>qEhVXDhWG;qN&Den;F-k|&y#-Vc5pSIX>Zxd-;p@H_wh<D8EC%kO`^L+oO~ zyU)3O*t~7@_{hI*@wt0=I_Y%irFA-3_o*1iAYI1WgQzGokmRdf2{RZ`Y79XOb$a36 z6)To7i^8;c&Q~^n<yLlYlDpg<zG+#Yf`5lN+%)G^_J0HHFZ5N3MyE;P>O*)fc%n1< z6Yp|lCOp%4Ds|^@ry}H20~wXC`L!?DN<LuPPHTNWjk7QS$kDpr(&SjKH$;N?EksB) zy2tn*+m%*d8*c(KVir}H#H};s9wmte{iI-CwI3etetmzv6s;}!S2pBC!TT)zFPn1M z&WYm2VCtnSR*PlhV<;TJp#^egkG2AglfJ~ksg-H9K=p;~cCrl6;5*-aD|KGZzF6jV zTljWzj%I}&ficefeQjEY=@T92%su%w`PI_A&x&rfcA5`VjkQ&`o9doIk7?^vLZ_=o zBjqfwzO}Loc)P(~0@rhHFv(iGKmLl5s`xg!(M<JSji{ixwyGm9?g4mK2>-Y%nT>%J z6Nx1921g==q>!|F!U+`ckVk&hA<Vk096u~oRoxH2Mmw|yM={RWvB}nhQX%Y)+l2!H zc$FzrL*#A)gKWD{8JnAEKAv0tRv*U|^KK|RBhbGS;U-6<6i+`oi~9R+`jP&O`lvFw zZtAVdrwZ`QJ+Fu9Bg);DS3Y7SnH)HzV|q>Oy#_RJ%rPV7zT^l=RakTyzpgPlsBl*_ z3ys&jCs~>u+%8#0_)9}A6TA%tgfH%iu6gRjWSF7JG|@#EnW8OtO>JGcv~)94JzlKC zOQnEs@UNX+coTqi4VO@ClW>pk7vpxtd>9bB<RL6llcht@ba;TaylE~pE?S&wf7zLR zSY*;-GfnmO(v<(pjh4G_Wv`#M)q0>}riWbs|Der6S<BDWZUou)73jKBL&<K&Fa^UN zR&yQ2(&ALOu=Nv)p|^ETYYtmA<%lAjAX^(-CEHXU5+`!zsE|SwjPYcHOZOD`$^huf zTUcvrHU7=Ut8k`iYn5NAR*DP1!Wq36E8p#Q1nD#~c0})~B&lT~Vl9=-n}^a=@jBj? zFFkhCMq0NtixcM`jM6`moc64mvH+YU-&?&^U2qJ~jhB(^<ML<MSS9d3oGX)J3MW;R z9rk@0C`$Tq2Te&1hi}Pz2!4yI-%g=tw*VE<BUL_@Q}kN^^1ZS9$M1fQMJ6=`QssH+ z_N|N)t|UsV$@Jt~Uv3^vb9A7=h6#;Q@*UN(M!H57Lye2W(6fP-Y7X-^t1Q&;A^Eo- z1@lfbs`NPdj3`=sSBZ$#*&XHHd0ggOaZ2E{`|sb`FZK(;nDVf^RMC5>u%{Ii_M#a3 zAh|nmyShQnCbF&ghdSZ~urON^wO0lklaNn&a;d%C60??>fir`d)3YsDY;mRekm&ec zGbG>X2XQp(?edPFw+#38Cp9ryi!DNp_*=a$s5py>%?0)fbgU+Rez1EjxR^NGd#ut4 z>f@P_=vS!hN(6Qdd6m69{#-3$E7&x`|JGi&($%9oCwU}=MHLroMZD?2%0vTXk1Aka zamtAqD0AwQ_N|B8I~6fpC9jAn#K2t36S=@Bl80KWa%YFUm<*~=!48_{=UPR`K$!eK z+)(L^+|>zfpH^vCZ`s`JyQ^PKJhHb-I;&1*N;k-JN0+iD*;Bgsswrzq)lP{{_H=ss zW^v9PSwrm=C8^jbfA>M?XpkMd(#?$oQD{${&TV~maji*7w7(uopur?X2rM2BHUm0n z0dR~h+CG3`w%#g0TQk*6Vu(`U%67i=5gA`@4&{vmq}@d)NRIdP289@D)b*BN9?n6W z(c@Cnhy?k$cj5`9zJ)KdaLNzoGY_(9`986uvr>N<EghFQ|Ni5o>LWFst<>+WZPsh0 z(*Mk&4jz8tySOBz0%ih@g&EZiik;{4&X=sK)z}ohr3(9nYB~AZSC@d1NbZFSzd*^n zIOmB5l^YY@?5j>hGX6dLrL8l&!pXoZ^7mG2gE^kv3mRJZ-hXTOb5{fR^;U3hrER+S z0@gjWoM3#A&Ml7-;hvE2kA8RO`6DTVz}x&z?yZ>ru1+>J7W@rC1NE(=`(U<bS-ss{ z{nHk%u}_~5f;3s~5+XiGiOHcyYdq`u3I@N+JC0VWlzh&7(T%8awJ`hrWR>BDsSo>? zeXvsZou1EpPcKd9x_j{sCzy!hY9IVs<p(Ahoc8dw-kSZ9>I;*BzCXD_TaDf?z035$ zp3Be^L?!(;t~B^2PmXV*Im*1A6WU5udi_!01{`4htP)LA4Z=$o#@R;2ay)bD<!iSA ziR<WF%C_fuEWj8(T%D;ri&I2;bi!wSbBwHS-y}*>kepQ&Mx9bOggwe887*{*xM#~D zh7S5k`RCE`4KUzQm6E7O&8%hUt92+pu<b4FC2k|%D>h8R0|O0sTrDb`?aD_CRHu^^ zR26cj^WI!@PrQ^oC@v;}^qR6+Lxel^5OERGDM@Q8$zJ*NcT>mTkXtW7;NRn21WIcy zaO~p_J6>1;Ca1mDf&ZAptwq}noY2>&X0{2!uNXF77BsvYr{ZN(3*{^r#(4**#)=nS zc{J5I^=W&3wu0xsQJz+T1^>JC7nm&kD5~Ejb;D3pIK`6gsxaaa$zZ!yfnF7b_IfDl z?7_H}_3?*TVus9Fg!pTXd9Fq$Yr_g->F!ldeCkxq*6v`WN&Z{pH&On=NF3tPj<5A4 z+`v*+e|av+oTw|z=|U5o{%a~N5KAktxgejwI%*NJEGGtu6|uf_Yaoai4U&wZuQRBv zxO`eNcaD@2<*Fx{nr5*j4EFF<3N2n~?GDdu#cv9iWW3v<<nO8^it=CC{=xbCIbgZv zOHfa;B-8OGe?IEi5=uu}<M`CB4y}kw`375z^Q|!%iAF_jxLD<^T$A$eo>96OfcIfv zaT*sFasMjg@JYV=a<Qm}_~GmCuN6fHEY?i#Pa`yA*)o!Q^Ir=s>bZJz7MB~^iE&Ei zSCz}t#U=Ti?bQm!3Jy-pq-ZC++)NCXpcNd$-t*dCzWQCEp0A>guKV+s<t8Ts{-0Ju zJHINEeDP~+OOeLZpO_zl{CTxA4%$FgRsPX3?1+_K;=eLUKKJWOPq3ockB!d@wU=Tp z<x2Jnu-+gUId!w$cIx5lm?&096piboe;3pJ0n0A~aXuPJ7#As?8P&e|U`nffsf|ae z&}BNwj%6n6z0kZ$L{DT$&dx4Kl`*?rWn3WbeYpcpewj9E#|5OzajeoKQaw~M?|=b; zZ%W2$B*GjtJ}x=uiH&ktgid=v3x3R;8`)eR2lfj^K-S5w!jy~bPAF~)O^|P_m>y4+ zJ?*uMGsB>Xi@-@XX5-?P5oxPUXxaX8hQ`Ns);<+Vu1}sF=#Z0+t@|5qHu&7FUJ61C zv6UK~yD#TUc(Zp7(jzbHE0Fk755P(?jv5l(nJ2X5Y9@x3EKV-tv(2X;jtQ3YLL&EO zFC+^9P=0{1`yykkh*LLmKZesD^;C~mY@b6kQaGRjRFyRtDAXUe+snb%|4$N{flqn) z;DZp`nxZ5@qls3-9)~){&oJ4d4TV%WuBd`U)VCia3RmTsi&Z0+pVCCD1A0P$-h!tP zpH{XirAu~ukpdP;7JRB2NLEdIyHjDLBtv)8fg$1n{Ywym>$U@?SGdn<(JFCG(E045 zhw0kthJnbQkB=*{4z`F)^We6R8DT<N2QfC#=&6maTa9>N><ciIBFrE=*=@%C$dZ$J z<j)EwBYLJ4>}efoAf0TWvQvaHT$x=hNOi_xLwdkmSB@1#Ai)Mw2-<GN;`bH!_7RlY z6Ab;>hc=z@p5wmHijLn-AJ5c@Fw8Fh?kKLcWemzAZBS-US6DqJ$i4Q^|MmpAEKq)~ zkPD|Mq^Lgf2*oMW#pZ+>Nqa8B<KnSn8?Q$(tb}M^CVutxJ#!P_ssx#q64W^i6g}ze zej6$9%_kF(Z^U};-^Hm3%`4@YD^6~REQ#(_^eTnpu)a8J=IlGN<e%8H9?D-r6v;p) zEw(w*$T9i@=hesVR;j0hK0cnCSI4#pk$z}T6qg=EbdBa>+HgKA1z{X3#*u3k2NgA> z1;|_mUu@ADUT8gEOcT+57eqepOZBDjsFw7Njta@;Ob61bfJzUtlD;5)?q+1F7bU&& z#dRi$s8-^Ax4_9aaF*e?og^Q0q`_xjy5p4qYoQ)R3Qj_=Cy34ZiVQCJ(6G;vJ%pAj zff3`Yj~>_*4K2zJHHKU`>beMx6#}Si2vOrSkJ$XBvvTm|Zt+b+Uu(|-eURYCBclio z<09m<B?61mUq87BT;37b0?wQ4K&OTmX+6?U{vkowGu)*)qx$kWD|d^!-7=8y>{dH< zQkL_XiA#7sg0$7e$*0j>>ebi6PD$*Vd0ZG9pZ8>FqJm|-34Bgr|G@nFh5~~$kNdm$ zR`giyQQZ49>q6aYo{8v_r@&+}ni5E=pU$=`ODOFvsx*{-=u+$VHp@@|eNKswpi^Wt zP#2=Rdk6|B1w-VD)tn5JN4g(cRPa{zS?qz-C}35E6_E&o@-1I0ah&UMcR3d%8Xl-f zF;FseOpi;oWAny%z7@MQ?CSp!4^Y{gDq_51&>LG^ls=wvJU_)ypqEBqq5_H7U{i?U z?m$&QX-_r@<Y4HS5ajk2IG%O%!HMCv;IsXZGlR(R9;I^gr$6w|hP^DV_LPU?W{<kn zRQx-CfR{?X92gp?M?S4q6WMDHR;tr~+ALL7Vx%I3JExwh;OUe`=B(ZgETp@5xWdXh z^c%FKhwa##^sBsDY0jTOaEC^aTryHaa}gW3Mgip}kuFaaZ`fzu<m#8A)oZshcJJ;z zE9rCIf4{E+j@;5$BXK;n3sn5eqn;(DF5{yj5ae;n1{o`x9sELfl?C8fuL!2={9!au zN_WW=r;+$+;E=n1%W8Rv*;Qw=SI;Y_Sr5$-Iz0AnxDv#@59Y6<5g>O7QfUBa40i<0 z1%T@3Y3v_qYPH!1Y^HdbZUiUJg&dt3-m-&GIrx+(mtP%<O+O?=In!xiX)Tybykyqj z|IqIeGe{Pe*`?8wGF(3pst^dLYagss-wQ*Nz){V?eusU1L<2c{0}TP!>7sW_QoDYC zWsk33_etyG1*p6{a)N0z1!{Ze$5jyj&B`e;pmj6$0DMdnUFg3^O3E5O+WoYZh|#IU zZ09hF33|xYWLGCd898b+#cJRUlvk$i7F@EXh9&>d=acDCCQEsY_)1y$w<-7>+xMtR zq&^4_RgE-|*qHG$G*B+@5l?2KEW=(74!knH&OJ0fM0DkMesNmO>gW05{9SNIedD8m z1hLOCJ7jcgiIpS;L$#;nJnPR6mm52p^_aWvzP-7$-<!1qD`-9E-Oyda<1}>Wz7$fD z|Mn@xgY$W=gWi9Tt?T~gT&IrNrN?dgq%x?Dpd?y-y*SvFZ0KO>TQKhNB0@T9#?o(< zC1O|s=?M9#MdSjg+)*eriG~*d_>;T1S^?(BF1`sGmY?`?sQbFWBI3G$L+ptC9=@=% z&c1%T-jKB2qQFoE;-vTXyIrkCCTj@MDY?1{`WUE1r7<;2y-$@@14&lb-ms7>R^4e3 zRKaO%`6>$#sKGde-{9nmFzLXap29uJA(M+=U&MB<_wMI?pmq7fb=W%>?bY$QsS?EF zDbH<BQ&7+))^kQ9UIh}(c;O*h#CX_yn$(CkrI0v5)+aS+l`lRrSN_@A9^}EUlqbk0 z;BLQbC_@qzFb3)pLA(z`%Q2;@pqr}pD#%0wFn^;dU9{z1t*W7c&ktH_@g9B??ALHQ zO+=4cb>`O(utB(y^qucVVWj%r{&V2{_;H`a+qA3wlA7v_OmxwVqQs`Ku9b&fJZW9d zYXEZ{4WC5qT0aV{6NWYoLnm{s1HovXOMs}bH~xw@&)ZYBCgSOUv)*XFDS>HnW}&4< zL#3zd0%XTd1%Q^QbIHu>mNFxQlI48Vd~rM%<pI44kMAJQpN8rhv&u@W$K+JYn|+Fw zQd72Pi87}V7>cn50}rFjS6g-~yFW%@ok3`P7q?6d0*Yb<qSyRitkFha{n@8_EBtpQ z{_-BaN=3ptD;!NeT+JJj{44w#X`tjupC#PW#kJ)T>1a|$D}L&(FhFV3*b#|7;!9{! z+bOsz+G9a~?Xw<MkdC*M3#a~WX2w@JX*I&?lNHiGerxvm#e<sxUC~!Fekj+=02W`l zp)|mXB+!a#<~s2L4lH*Kg{Q{Vn3~ay4cKQ+p(FC8JRIB?e$LE=Yv~!tkmypGe7t#- zA9(A}`>UrGM4(l=529Y0UXM^v#>$g^-nmAne$w6hrQVDD(zo$vQu>15IA3f54?g59 zS%0VZ&ksYJMGtFGsKu`OBWreUnJz~1CT|{!hhmt=*NmQ^xqwwI-|rpM8uOsW-z2tp z0GM0t%r8+8JtM`#=Jc1Mo^q1vw@Lb%8V2s4HhdbTcBTTPuyjk{o96tsCXx>FzBo0I za^a^9uY|rtmg*UAeJLGRm7n1EK|QjSJx}F~+JLs)DDY93nv$X)u{H2?4`lNl^l<te z(&U$NXcrp~4YLdlkc`U6MDYg7w*()D-tj>1bd`ZVs1l&rKhF(>pFW;s|7RV5QIX2M z0?Fg<&$|{Wr%I<35qb0Hr-Oe=)}ZgoSh{DSJuA@b`>BfeX#w#ieRUbFV*WGv;snCs z$oYuE`AArAjyeqz?xL3Z!`OCq!SW7&28)$lUzy7KL?@9>Enr)uS{n@&Aad;Bxkj`c z=%_2_Evuv$^u!O3jh(TgZ>L9uF<a&c$gQGo{mRBM$ZGeeg=fA3O)VOhSI+b1w63b2 z_aFbX8sl#i`2Fc6zpWD1fRCbY<RV`6<<RST&%HT{dPvVJI=$U54Le0l>QO&6Mo_mN zzk2tqzDupA^SZv)$$e!^{^+%Yf<YbRKf`NE@dQR$k%!ct_u~Ys81`O(IV9!^U37n0 zU-JjG%T-1JHeuGLv<>PTl20r+v|j05G@qz%);%VSJR9=N89>AoHYc3bX($*-Q|LNH z`hCKaT0iQyU6gFUs0LIIh}7MGZSnx^+oPsKCoO8AtRPM;Mag4(CNB~@ALAqvA1F_7 z&dlp{grovW#I8$_jWWZcg<1C0@EEU;k>d|mEn=1j^cVwCoPk{{TYb$7Kdb=l4XH8F z)L-?I6txO4_IU?}di^81A8B=;f#H{@w{o(`{vB;@cWsE83Y{L7ZbCX&4WMVGrDh~~ zsR8pjH$)=dx~PS4vnwrSFtWe&U2Gwsr>nTtaWLCbow;gEn^W5q@>)hX#xhqeUvQ)? zBpdzwKlVdft+c>l2YOpU9f!1_D`nOR3$a@1!46f9_5R>!(K956<Q0m5YwV^_CeEXi zWHwkD_#BUe2x>)OS-aa|(!WmAlI^=o%*xifZ(*^+ZdcP;H;1kS=;yw>Ku5ls6t0S^ znX=5)<n(!=$0AtTdwT-eLwXt(+Nh!B(-OL*rMsSyWL6&LkbBvjyUMBEU#3cs0{OKy zns&JmJ{^240oa#k$Ys{f^rLuXO9S3_=4;O&|08J3hufIX;{)vaX~-9-`In)~|4<r( zpWL435RK{K(qc6@yAolU!k$_?W{C|RbBVIGV7@SoVdg30+^g?`#B-ik(*!s9husAg zPS^)Sg<~WdOp$oG29iiv_2<nL6SQ|ybLm5Ale7;H&v5691dn}CeO?1wrFJ@*f6BCc zM9XeSEISV!hofYjYp?i;BAr7vHXp|4D?l{!b3ijNSs$J)E%qmm&q%VEIefDWppn?Q zge+9*=jj9V#x6kwIiBR;I)=bGVL3w+Wh+tL{d{4!@8bJHA7V_41Ar`%^f1O8TVzPf zfq1q_YD(afa~6|qP6RrpG%qmv`?G;H`*3koX`&*c&=XNKZK|HTqgujs&b8I{h?Bi- zCYlPY#NoVwXc?KhLD~{|z(!h3efB#W@~6END7uZ!%uvi!G<%QpUsP<Pl$&k4a{cqP z$?unR1y64_WRN6@Hio%;mil3K*~Ow9erHQ6eW4P~M}@K0J4e&*VZ3qtG1zP3f>yn( zm-q~JZ%t^Vm6}Po-+kP`S?Ce2dUbO*!W2eK_j>ZHQmBPiDDD!?ex-!sum(x?`3LPm zSw)sZu4uyv{Dx3TeK50_GZ4)O0PCk_+yFEJ?uh^JH%Kv6P$VqpK6?XE={kuwO)UL{ z$rc&rkECz|LYGrK&D_jOr|f}!VweHv)b_MX`*z8@#|YYva{uzSNWRbro$`j@-cm_q z-E)2Ctx?TyOW)mb=l)2s^PW<%AesqbGlhp=lnUip;5mUnBG>y`+_3C>Dfj=l?{4U9 zf)B}Sd!dU;*W)FLxh;?F1fq>@oP8$oC+=C*7m{Rl`*RbV8vFUIUfxh-((k|VPw0D0 z4lMtwD1~u<NSglFVL`^{1<BE}_I9bV`_GvnJHNT9V@xs95-@YL{d<l%F<+JgP17vq z7-;(vGmuI))K{VbPC38|=iL2vV#Fn%xp9-Do~8XTyBGhN)$%O?Cej_qCm+*7B^WhX zkqWkKZ<2`jFN0WroNTG{OMMakFkviTEu;{(v?VpU4N(bSWm>OLcu241b(ZrTMdMBY z^Cz!xb(zXs+@R9a--u<)0|<Ds9Ma!QkasqgO($AX?udrUO|wFJr6<e=9WsZogu_a! zV>tmVSSB))4Vc%rf=!-1N6&4tZwjpQ7&sG^@t+a{0+smkk3<12&9*^@b@eaQtbYG) zoiuEGIz8-Su(<zaR#g!H(j24^#AY}X=*!PNX{@f_1xm&G+$ZIV8K@9aSL}P@`h@y5 z^jk(g85yK;({5VhGt0`dMkJq(z@@GhK3911EN@+<dpidJBn1#ahz0a3b2#KEZ#974 zYh2Ktt+Xilt8Ns^)WhZw6(NS_`l4?t!jjs&A%Mq2C$Dq}h`fOuf4&R-WvOAMY2Z*K zAtsb!TCSwR_ic3)nS2PLh=wP0#(+fWyExSE-5{t?oA_@vqLmB1dV3vuLZqtA&Jgf4 zN1kvgewk0UXDJJmFKNtRz%*bCPypkT!N{sAE?@%3_P+TO^NGb!R_Cn&yhg0HfuMx` zX%7cMsZS3QynSlQ)gZ`pJv`NX@cPswJZP}ahVM(D+C9a`E>7!NOf*TB);AM!F5tZZ z1yd#36nNXbot*>BN*zP<B*c^*SwzWm<-BQ>j(sMD5*)UfPqQzb&}*)l8Dp@~YfLlc zL^@V}xr>OE1tMU#@9zhrhd~@ApP7NXs3CV^swo2QuYej|z~tIh;g%{S=Rwpt{1wMf zinSNoNPU%R>+DA{qII3*G@~c;w&!?dRr(6C6Xw)J6_vGOR+>qB|I~U*`*Pl)qXG%X ztTWCp=z*p)Ggz>jHs`E(R@W68As`G(=OxB~43>d^ZMcV6=IVPQ<qUF;n~FmT<L{iB zNdu=>Jge_sxduhnJZ<{?Y}M6~5Z5T7)XvZF5zj3~M3)-7a!6$~ydz57Ff|k}dM$j- zN1!4Sw;HRX_`a1`VjX1MuffV3vVRhFxrSSl!N-P8J!`~ob_~ZN>;nH9lJwFD%F~~` ziVsP5X)q^c+jw6rMS_y~1P-z|gA&*;8TKuLsL)2G^?KVdC89ouB)?<gH!a-TbDdDX zI}?t?_12M*mS*f<(d{)axq@2zG`dYl{`lZ`_P>%eC^6Z*rTDVM49370YjWIY*5Gy_ z(fIJuJT@*+?wp>ah~sSaSVd8oj$}$Bx?_R*eC0+^t8|!t;ypw(tr7Wep^**4O;xTk z&?7+Nj&0h(E0R0+dzq-@pBw|J5xw^YGFx2q<-*^(oa;UNvJKKMLvsQjj8y?16Nw$0 zR4XHAA=$p`%C4yi_Xb79_De027MY?$<oZoti$~O#+4bX2SvJJzha1w85dLp?U-B6b zUB`(($J@MG0Bjb(EOxMUVNe^IPaQ36#(B3{n<}+Y@zZ9CF;oG^{@IiBINtkh*v|dw zyuFBY$2Hz`;V1mnJh0`4$s}KduzgEJYfrZDb;}jf+x>s?Mwae77wqZJ0QrPJ%M7Gs zI<zWA*Y<6r?P1ABVG!cC!22mu0^-z{UmDjEZxdVJjGU=b@=p+`>gZy0ew8Va#r)^p zC!1TQg#J~&IC+4BAv!D(hqx)hnT``+tu_F^xR+#BLZh<|yyEJ*ad9^G+l44RSqEtk z2Dnor5VAA{m-Q4+QTwFQ-hkwT#UF88oS!4pPjwviQ%@u660Xt5DScksH<lhmNm$lA zzt8teXQoX3_ZwkK*iC=~z<8uOeV9^KZ1~*s)r&n3MVu>D>a_5W>{`b^mGbqZA$)^n z5b~qDG0{a;`$2(Q#kyJI2LO58&|<MP_CE@wuUDp=4Usys`{%4wxYpjgU$i(<%0O%w zWdkKhE<HV?MXB8$Qr-R*D(+vOTA0ij#ylAC+TY;Iy+WqcLhh!rnQ~zPLzI4XMWfEO zVsGLfGVPoImSMCS_Rf^{aqO=azkOik7oz(%;K}-fQSA55rQiDh>5?4Bq)eNHBYkC% ze51QcAnb^I=(`t0zSxrXLT-h^sOl&Ggf=t&T@Qn-86mvAA7T-7UY`G0q$*eAj=+G% z*Skk`Wjn){suLLgm~0@t=ca5pULhn}$nyX&hA1l7fg!zX8EJs(?)WXX?%2FFrk5hy zv9x~s1HOn|J+d&%u>w*qMF8U^aME{oK_21e^F^nZ?~M6?V&m<N8RpjUW#;n|NSw$J zuIE)i^7^vuR#)>=k=(;EFNRCmCCem~!u+sZ<Sm<%dqT)qFlSuSNuC(e=|HHZH-MzC zJAxRu^JY4)(fSuBF;*gV&(d^^30MfG+UPeu>~?P-*&TcA(LhtIRLXmGJ?x2@>QN|P zXk2F0TE?Lv)7CZRx*LQ2t6a1({KNHZ`9=JOGy;58f~s~ms<Dw7c<v}xF?h`!i6sE= z+%q2IptHNkKhn+IeG<Ze%$eG>>3+$k|9oWP(y-qrDVk)CLrLR($qNk<5^Vh&k0oTR zUm^7Qe=`Uwefba-m;tXn&tKS%gn365m9``K&-%M~vdFBn=Eugns{V9YP}Fcaqg029 zz_1s46QihV3H%Q|1FOE9FX~S$lT;`Kh^9&=FiAf0mU7U4nKS;&e{bK8R;G+j4?dz~ z4H0vf5!<0R)n}E^V*RXE@`KXFA2@~F3eUh;@;UeJ__K&zmFJkH{?m#t$&lcHPeQdv zC99D>;W2Mi{8&^QiZIxppg<YIb*L^o5CWX&O^;CbFWrMw0iHcAePa!F)yxeN-BXfZ zZ1tGEmpBlBuo=$|UQ!`WsxrB3ukuw0N}zPW)7Q+9*k}Mf&u*~W^wTu7rfA*?AGDX} zxX{Ia94=K&vqmoD6t8`gY|B3MLg_3{e}b7-Cm~7se+-@HBb!|qho3|cJ0Y=Y5<B)@ ztr0=Y+MC*&T5WYptPs?$(P5VwwO48Fy;o6MyQua>X?1%22hWG|oO7T1+`sFx?)f?~ z+k|Hm3anh}0wxyNgiL2e)DDbc$08cFScPv`jD>1Mka}3gwUv6Vu)x8xPh6Cw69|sm zd6=86NN2E{V<!N0@Jc7Xs<eF_o>;4MG|F=mB>W)y&iBLJ2zkBXF~n--nD6K%`>!JG zzK5PQ`kxvu0x6%Ei<nA_3pPqbt#RR2GMwJuR8IQ1Hq7Pv#Fas`uiUHoe+4MApKvEs z410&UqfQL1ADw1GfqUAn14Q>X2#bM2xDrCV3eAUidxib_w)q=#vX>?sZY)OH9xq}_ zNq)NGcR5|U@>%sysYBH9iO3ubtpYQvbcZltwIIDB=e36%ap__b^`a{&S{V~Oq{2N+ zQ9Pk{mOnJ%AdDF`tsIn~VDlgQvR3dwAy4Z%JJd}^H)yD~TdFw2IKM|BCzI_?_$VIh zxMY>fixeGBVE-D<uzv9{FMh=m%s2uZ-VD$OX=!XxNtta>hWsb9713&ipBg2_Y9~b? zrv-=dqB)r3Jd#LogSzb2+s4y-HO9Ou#J6`66xAeQ4-ePI6uI(JgMYEQ*t;>~3a!L; z+&b!9Dw8@B*_{h<idq(YVcmZ`@hqz^Om2C`qBh%;VmVxAyUdbwO};{XcleEtP$NXQ z7D994#wGNEn8eMSRy}YPc4@N>4^Y>y7%cj{q|7s+Udxvam`N_23vyAT5y&0fKn&ik zsp6HRnB6>_{WlKnB>IS0-G$KK>~DWi9zx+kYbkIB9nH$|QnaZS}B7mjoqENwuv zA>Icf)jgb6GU6eMU!NHUaY_7lHhos^PF%CRT7m03v3X(!ZtDAfoyh}R{<-?NBmg`o zTU*(Xlt%w5n~lqs$J<OKzi=&%WI2jt)xXZeT*F{d$YH41(Kn$Z*RmcL=)M(aJy^&& zXU;SB>8`|o80Xq2adS-sd7(JnTh0vFPZ6po!>C8XLchwf=_F(d4$88j!Bdg;pvJ+n zDBXKIjFn_zfyu13X1Tlj765pS-NMh6`y;F|s`|P^*cL8+?b;7bwAXt%a7354veK{J zSm`q4#|A>X3wgdzbym@SNW|T&Zc5KCdAM0a8yxi&qSBpo9a*>GF3)b_|5YrBL&&M{ zhpV?|O}TcAjvT5_<Q02N%UG<HEw9XmQEyhAoTBSV`n~(>^aBVu9UGgBo6PEu`)%EG z?I0KPR@#R>e+<#Q^~BmgM#|MwE+3AtPktoCV<gVfdd9w^jE`=j+rph1lg)~-RR3YU zYS`s%gdzs7-tYNU&pDOn*)?&Ds!>d0_&)9O?uL4(@SGbbP3>c+Vd2$9o&!1A3^!go zX(kIdL$RGl*FD@1Bb}~VpF$W?WjIK1TQ(B?Ko^Jz3bM%^gR_KRH}P*09E+f0!c zlMo_#eUek{zI+??ktBN2XtTy$r(kZEQkk>4bJE#rJ7f>IwvCc>)X_JDa^?_sX3JzU zgZF9f361hN_c@!NJ>n8aoW<4oCng_VcU_wo<E`QK1PKELcY~_fh~TdfXvTk1_5*C_ zs95&drSOq9v4z{BIQ!tXnM~^qwmDDq!yXeCBBep#7&fo@1@c^cCJY8nQm4ckTd|o$ z*k~@hhk-b%PE<Y*DF5DBJ6KzrDey(ZRjn<gPvh!f%l9>Z!7<=eMQ#g;0Ym|s&v&M5 z#r)<E<)q9=2HW;h%}=H043VN?5uyiyux1M(QP5LMcWDBsU`rJp`3tqbjE!>O%<R>q zz7?V?9Bu7>#{+qnYPl1|%wbHl(3Om3bKeIOg*dztPOMK++%B7s6aJkkT1_fj5|Kmm zaTKs%bJgoRmO}Vnm`@{V$$cfUkGvgd0B)H}NA2OMGd<5@U*&FGp}(5xGm!}Ix%#b0 zBOmO{?bzjzTi>*o9)+u6hFRQIFR3cb%l}$zG*YG~z{4GIaWFCaQ{BJ6)LD6;lrsdS zCCR){D9$D5JUrw{a38|p_#Dt4D3UrdmK=`@$hhmZxX=m$+AcYHUxdUdMXwSzev%kO zBaW`BA7UFF4bC0f$`ym3_rK3K$&_o!U>PN{O|4f8M9A1mBf;zRb8F7mSikHKG-<x9 z^Ur@POKdh*&$DE;u(-vioi0+Bz2HRsM7%?NCZPw@0V@6z-a-0LZbf8~N~0e_Vg~y$ zgZuu7_PvLB7GmUIS6~gDq7yLvmr53f9+^Cn#qlZ+JYM0wR1|i%o4GlUN26GHvWAs5 z6mym@{UV|hTA1^As5!TXdq?@NY0)5=^ZsFK$*X&WRJk4yFfMn+dyX)A-&RP0SJe9# z>hM5nsN*W#>&dWXjd!u*Vl%Jzd`i}NX(~e+o)7X2T~smpLJB`D+Y5L+<W6Y573@t8 znqQAEWi~r^^=B36@p}s9Y5WnYEvFFich=fF!<@9$$mgB6Mu+RXv|5p24raekLIq6w znz_#>Y|Q6_o0=WF?)ALB>a-a$F8r(`iKC?jPJ3fE^ai|ra1g{1a?ku<D~GT+ypH)x z`t4wUbPD`w4vo2M4y^jcl{nF@>bfiM-(K-n;RD#eZ&JKg^#5Wv*wKskt8&2On@{W9 z{vE{?jq_oz#>DR~GQCUt`rzrW;x=tQLpSa}G=;y*c<vQ44AnHRD_7BKz@7KAla{8O z6QtL(&c{w^Enk0oX^;2WcoSyXp{FKkz>nqqjv5O;Xu0w-(cQ>!b*_}^1I4{=p0^*j zJJlf^eSZBxAb&3)p4gqc{PB4^|H;c7z2bX2u9bVQb&xLC5l2?q8;|5U09U~!B-~f1 zvT|0fg}Pt)t5JjG-+LPHFS%O>x^L~?^kAE@LUVsbR-Q8bl_2E1*X{B5|7pfzSkb;3 z0~`CY{8R!Nc@_EQ0zQ521=@qZK0DJDGT?|j5r3f8uR0b+kC3vt=;sHpqJ8x88V(IJ zJoUSqU=Z%s^7yjA-w$RQ*TnhTPUatmfBz+BaY@MZ%9y<dx+-6>0S3hRfAx8&o-%g} z07q$g0Z))m;$+-#{`2J^Utg1gz6(!<eTOd-j}mcwWZK{Q)%#Yn>pLslgOa6PnXB!m zdFQhXUCqJo{g*SBm;hy9)gta#D79=VYsKOUx4vwJMK14b6RSvyV?!XTtX^ZQLghlW z)9X8b>6NM$>pVyEu27V!mzxY<+>`8Oj}l1C6to!;G_!n>P~6@QK1{?&Iy7&XDm35V zit?gi!5TxO+!To!0#Z%>p~d*}>Y3HNS>d_XX9#=nuC6FoOYUW#g@fTd#|al=-rm7d z{S8x_7V@3WVK&~nunh^GL0^@&<L$BO5!ddbwv)ZNdEAj24d9d*Qva{ej!-EG+@Q8e zFaI$sQu~mKs-VgGu|pr^vDE8pQ@Qf77Za^dRB~-{Kw4Rf<77)_k)o1ms3A5>_}uYo z%;g3)6Q$1PWIX&$NuE|sQ=^HYOz0+){c>i8k?bZ!G)<4n#@abaZsKe{T;T)RBgHAG zW#Ix|F6VL^SQDCd0Zz89?}EEI-bovx_0r@lO#5;k{MM$i_dNeAQeeGk*2HAkDlx6A zDprxXj+ZFK6C{!Q5pDroBTA;ykIG{lO~sQvEUvPIS!ZZ{h@4GSv+&9o*GqKw&P_?t zSY8RA);9Dj9rfZ^xD^egXFbyNpC7(+0BSBtGSj>L@xIOR;77cZa6iU-xiMxGnVc%m z7;3SN&&sRcJAn!#%RDolaW{L4JgcJaPga!Krm;~{x*}kxX4$m6p$m4KKQFg=<v{<n zSS!XTxXsa7IgQ=zM$5%w0^|shPIL*`=?3fR^HSGT4bo)Io~fl~R@k&%vt<<P-)LS= zDIVkXTbZF)R+d&|`svb%v(>$lZL%<Jfq|ofbdE}9C2x&<|71f{vb-u$lo@T(!ri|j z*|PH?DSSfhKV$Qomv5fNzh*<%lkv~;d^qmhMT^0)4oi30rNKv-Capi;1Cr$a(MXia zRj|)ps;miK%2Hak@-R_eg3ah+JCkOO)!GP~<4TKjbCq$uzrsYWa?@gGpL}SIkQ?D+ z@XYLg8#K!}+7`t&-^7hJ4A-?anUk!#eEr!<E1Sv4?cMc%V_8!M$kp?eYplcd$T#-Z zf35F3Pd@YaaP`?X)1eb7HCI?jDrQ3a!H$)bt+FhQWlt5N$NLbU6%Hghf7?quDM>i7 zA9}lUA`TQjIq(^=k6lbsdqVd3VhW5sscvTdA~oIOGcR)I@Ar?_#P&jyUm$0%b#EZw zRm7qoPoBOz^nkq&+ID48W%jBCUB->A!}}@ZAe9W}iYj3-F)_HZzjjCVA0~$fBL>)= zuJmk9Bas|}E^U7c5{fHEZi`O;LMX~_xeAFN_C9Cn#Zdu61=Iz<3*j${HE)*cvf|Vx z@px)>0IM6tR){$mC~B(WnhK!E=4AhyE%zrMp#kz5<Z4fH?s<?NZ>gESd>B|Ik$f1_ zo3}Wmrj){#BETgmNPpx~uJP(m4d)c6zJh4an>?=+j0YnF=n+|yM>{NC&Z5ZTUsuJf zWULE9)&fD*+rD6e=djJ>p05#2b%h8RI;<4Ax0h%6b<hWa>c`}Z+y?Xu>bU&=uo9b( zUOOS=Ox_Rap^o~PuEB~@I7bqox8+hE-C*=mKcZ2FhEfzOSmNG*qLezi>2#Ka&6Pc$ z_uM25M<n*s><7NEtF1-0K5@fjmq1_0iAfU$!A>>^ip;;<CYzb7sI#B+ivQ%fWKGL> zy45#*M+_#eWy5*fIODycTjFnzs#8=za7&D!$t)q}{BDlfxM^zzA}|8a{gkdmYw-n~ zGpICe3?8Q*UJ{+Z-za`KXUO_m4*Du24D&2=NX%3lK2NuW{JLkTDH1mFvRW<+fDUNJ z!p(k#NQzBfcxmk;rb<*|3R(Mv4JYU<$NQ4mqK_{;a=!I0<PZ_%gz-3j&=vUpyyrR< z#qe_)#ZF=}ayw?vnw?I(mOh4ic2VqKm?8YWs?CeTgFTC8`N>zFtiVr%k$Ephw-lj= z0Sj*1TKQQ=`3F(JR7Q5&cFFb6N_aB-t~sb$JhCAa^OE~5H(f~x7U$hu>;bj##4q$r z2?@royJumQ$E>3zl)PwI!Ysal{8{StGUNPd%BOV9^RE^*&VD~9yj3d^bNBrvD%T7} zg)DNW!2pMqRic;>$zg7JuFT$eL@VofKECTwRk)0}a&VglzDL26kEkb={mCYgG3D{% zSTf(HU|OgvsSP;-`!S$RHcQo$*aT>qI^hkE%TB{`baEme=0JcXhI;7_6^;;`OTs;E zl!vH}_gnXN94}5xKLC@~I`g4ACfxu*_ups0b>!L~45#J7D-+P+wd%_{#OX*qTcH`d z>sFg^>JQuK>*Th^@ATLwgy;A>UflH0`{FnfE#n5J$(zihcB?r$SiL{_r^(Trv15cA z^X0tMDcd6+q4io@jvhdt%FJq~>^Tr70ha-^7&Rv5@M@!3-+1lC4Q#^fi|7F{TdpQ> zo4?(YBQIj)(&%ito^l!5F%vIPXwa5OVWk5gp<v#DJNyl;g`>e!Z4*SWxAMizhZZGO zY5Hc3#haxa@|sMw*mpx6;hDu!QSR)SPz3<>_roxTI3s<N;dXeHUt%o?IPKVa0Y}46 zrF7>Uwf)nxu<##4m{rfhyqDib{Q*~Nu~&^VtzN6vj#Q|3@5ymNLuA#>Kip;WocgkH z#Y~AYzWI|HiAQ=53N=HEV_CAsjoYUgGsKw9kOuJzVQDEm-sJZjU+CR8dwdfMEW~%> zB9hZ&E}SA!81XLA*R$ujo05V;4c}^RSttm>%ow(O4Y-;t{&Z$ek@{E6uast5+gmrb zsJR+Wv$P^3M;W)dd0H9=zE0U7ulWdfi<=J$57Z5HWQDf*u-2G-@JxPM;;wL=6)ha2 zYofK3>{S#+b6wiS4*#21qWSK&h38;aWvEa`vErSQtbZp@ZIr~E79(DO4m}FMsPZ__ zYm1U0HIk1|M~TGiC9(7nqNk)7U1Pdd4^wksU-MWOWgz$V;^(oP46i4PK|3>Z>1ha4 zjM%xgd@3fd_k2IEVy*Ofc70V=>E^wKI}JCc_m)9&FHWv%;$W9K@PNXVQ@wj6yv<d( zx-cvkdDjVU)hKcfJ6k}yJVrDt!)poz+g>1RiW%0M7~b46v}!^^%+1)=Z?d|<!rsv! z%a|q$%-$a(Iki=J&6%gn7`f&cxh#B;>GVXi$T;ON-fodX0Qlf)tc|`<(%*KOW?FNl z-!5PpFLIY6Ih(X17Y?yQ`uA81Ie7`}E7t6>-Gc2cmf9$|_8j=nJ5&1tDGL!8m@MWp zO^bkA;mQ!H0G(lX6e84$wa^Miz6;cPIu=TEL=wxDBF;(?RNJ>Nm2;v+E(<~fET9kn zD@Je@>Tw7%$E|sHt-HNQ<9^r^7#?OKkfpqGC@XqHpADql15sZ2@xXOj$7!1A437vX zj0Ja}$EGwzu+}|vKhp^|x6cuV9eJ}u&*F@_ql|UvU#uw@fQUv}h!}17nFVpOmEmFJ zHLe{0u20BIDoo2!0lnXRmTMX7Xi)akWcp$zG6uGUV*YTb(ywQHd7VjG8y(S<pa7ES ztdr0VWgxnmyRS1%OnD<b?7p&b&~M$g^;Pug_S9E~7{bA=cAAE%h%5aRk5JkGDDV|` zmtKY4NC4g+nPfms{0h=46ufq#dy(f)<`9Md5P}!kS}Q5u0|24X5XK*&jDu5`mQjq% zmTn6`fN!@Xhpap~T}cWWDMv7VZ>C&c$Q{y{K&%g={J6YS;D%X1ava<Cqv%K3&ZEVJ zQ!@(%UhSsFfv7y}H4T6?HgwuBD2ZHq)iI5(cQK97ge+8~2>(n%F2<V;JiZo+RWvYD zZVPzbm9d0pav4BYil*ecrLfjLFzdd>Cd+nHjv>#^N1<D|GxPxj?EY}a!g(5AgklPA zj#26*X#NQQJB_6F%dXzbGm!QBCjtwg1FByjgJs|mTJZa>X{?|m7j3~j6zut$rZf8H zBVm|uLb_<~;|Hw>sWybl?F<DjrN&emKNx*WEz^9+C1=H8i(ObnZfLxhFQW}hDZrGq zYa?%tSd)k2*2650Wcth47F=mNL!)<TRaRllf%BKMr!}tGvqO*aGUd)8XS9F}EROo6 ze1<U0B9%Q91;2%Yb&A2XW3O{x083>!LJ9C&AfU(IsssgVw)HoFJB*b-iL@sIuE8$o zY~?-1m0^0@5bEG!rZE}z$ag|X$3hv8nb%yQr%{a8Gcy&tnW}1yr9`5+<Yg_iwO0gq zK1?x67qY5PhhrWKzm;d)nv!r4D{w1x9+tJ98ZIzAa%QUoUB6wnRUga>Dnz7F8+H3R z7Um<>;JGD*dQ<>EJ&+Z`kHS8=cFU?V)$<EAahQ{{wo5JAjiI@===8M6kr><aiD9CE zsT-hoE}&_cVwmq@q=S%NE*5|Cgp<L-F|5o{0|-K%O5e=+%ieyb;V4^UHPJ8jK?7x_ zBnzfe6!YzG4>lLezRP>`w##2{N7!{yt`+#XN3q{+FSJLOM;pRRw2FX`@|%nNwO!@W z+MKEW>EEbbT-W{0>Mu1MLTw9ZUe_|t78Dol6KMpVZThKh+r#<w8QG~-2==AKDF(qA ziArr`-wfL@45yIBwDJuqCCD>Vgj77Tt#hTvb4M#@iVkSQzvc1TdslgDd+=4tn_Q5k zMB(nKajtb@Z*vi;UHB+0y!*DGfq4>J9sSFUBtRy;eyu!}``U?Ojn!u2xs|nhAN}P$ zhCx@D;xK2>3wAo4XD{-Y5_~lFBF*KX;VXv{=$Z4&w*(|B&1=I8*s4KSazYq7N-ER2 zL@$!<>r)S~-!Ykmb>7`|s7m%GLJK+{VK4Inu}%rCgO+c;FcpMFqMw+ZAdOGylU_D_ z#MYE-tEE!|sg?c?XvVL<pg~=z?n5ssOQE0eS7K-33b9-~(<)J3w-->7lf~Qu8zMZ~ zNOI4!H>ot&d%1_)qx~Y9F&v0>S9)<AvYWfb<0$0Td)}Y=9c!d2leLGTi5{$OarZ0Z zz#!<SEF`}n9Z{_nO%L?tBA0$~pmSTPlsR2NZ51>ZkU+tLJ8j`pP(?q+o~cAcp;oWD z(&b+<8ZY6Yy^L@6+llgQVP%1c=$91?=fJQG#!a2=XAUb5Tz^A_xmt_4BVF{1hpIn1 zwk5n{90a+P-<?&T%8Jfst!n|h#eoUzpGu>2zqQ<_kKZJAvT0X?wTt?Flj8Hr*D6~N z(^6g07d<b=i7tllDQdJ5(?qSIvVmEZDxbRGeJ(fSw+(c=7tuf~)H?+IjoF;qyOA_^ zdHCg+A5B3G7m-+N=9$zWWWG*MJNwD|?w|uxov11xO3KhJuDL?f-mUNn##8JvJf*9C zs}PYVQ~pn<DB|aJ<uR)jHHurebhj(xSOG(L2sL_#QEi{0J0zngD&wCJERZqt)ZtZ) zx;TPb`FA@v_jl-OYUK6o_I`!)N+UH9H&*x6)Y1!G;~XuMlfCg0ctlpN<r<vaH)<Lj zC>8z$A#{%&%K#)Cw(KM0rSdz`FX=vqR_n#mf3a>*qztK4#+SO^Nz;Y@IcBgsrGIAt ztyrr80EBn<fXAJ;IohfV1<Y5`%;?z?uNb=IDYj11OC>ksM(!ZFw8+I6H@4{<^+BfH zDf$luOs}5|3~7&jx6HoJJ)Ken!F)zeQR)rruJU5xM22w^Z!e!1>|J2F@(O=~IK|og zP3<=ZGLhbPin@KP#zG+5eSO$Vw*99g%haJ<_Ij<nc{Ib=<c#~=%Hfp=A=vN~!_6s% zplu6>dyyY$yA|Ag6{yaq6O_ov@%aqF`hPxt6GruJb+m5lP(J!0>3oj6NA`eglJNZ* zWn=810Yf?#w$0Pl-No1%LT9_?(^9~gmB)Va+kq*DWMpo1^|#Q{p-F5y6EdLb`Lsmj z>|`WcR+yL0mnChtN+chM*@v;tZgu{wp`cBDd2GD^Tu8Amoc0Wbo(+uMTYm9p6K^V5 zWF+6a;LscTw7f_VE_vtObUDLjAOkUknx)wAt(l_o_{0<kS0bH2@`jL<9P?D_t8$*X z_lK;G`R%m<bK_dg#0J(J7=2Dqpu@eC(CBBd??QHev;33T4KK5MFAogdU0x?q3q0{- zHIH(b&JQ|UM%116AXabadkdDx&@b$#iO`3vT)vYc%s3WBN1UP#Ut@UO!G2<y%29=! zdRkY8m26%|teau7&Dm`3gi<*fhtCN67OjTE9&L<|$Rg!dqnIDk7J#@re(*`5QB;>* z`1EB2f)>Rj#xx&d{Ykvo;?y;|n)i!X7?Z}$_9%weT3(M1X>?W?R<;F4u4q~j*l+%b z;i@E|Em<54O57--H#da$Esgb(b3b)xU)GLn{Tv}lQe`<PRafrr@qer3BBcx29b1n@ zxQ(%C*H@cdH!@#vnw|#3<1^QK9;yk>Tpl;BS(86d7!=*UR>$x*iXkR-+kb6avMpWR zlB<{p9&K?hn%uzV{5x{mdoJV|Q+YSN8--~VCc$tog?gMcQ%i?<9bROz6CHf;=SLZ* z2|QbIVPcv0VNz#k#n%4xR<7w|!@BaKScXUb49`s&!fR<5j~P;V+k8MW9>jYM3hdG| zOw2TqpL~sDe3;%BFi|=;R-(A2PTs!DG%-=@BE3`jOv}6%-QFP~aD4y3Efmz6dpL^T zs;JJMcrRb8e*|<L8knaAwAu%&z{eT)^qI?Np7HOyRm&N}MGWD41A=8u6*|21R+|lu z@UeAL-Dw_tPG1>G6diW$I(NXxf7=l&G`c*^WXy*XEki!~652*Wng<{+eK^c?|HuYn zF`qnV*8qUeG)Djs1=Lb|RP!N-`K)(d09u8CLt;8N)qExCqV~V%qGk$l<Aktk(W`KG z<&a)UhO8-SDQU%6;=3JFv8w^71=sK(CFD#x<M@=w>4ZjRL)emnxB+)*nMq2%t0>p{ z2m7GYoiLDXHp|mj>>-!o=*#)nx@im}UPOd^|Bi<Ti@_#Vz6U?#z*KVpT1EfD$H8tt zRu~zo0EUi3h5{JWCY46A?_#|$Gy&{1KSaC5^^#^nKXXQRdG<Fxu@MPguXHnch=3<A z1xQ3c+csm$pLAE3`nC7Ul5L4Xm4mQ(jMNz@3v=6g_xt<px=wx4nms7wD+pF)cm8Dt zDQfaqwaVgXMwcN<3V;iIO}Crg=%@5xxO*c*?fd=sq%A0Rl0{7^!l0bSg_%;tz<m|J zZwstiE&4g_ZktPN@0)`=cTVomxW2DeP-;kkTo^!FO}6_$z6oEp4PF{I1#d6Uf3~f4 z>t_ZFE*#i5`pwsPy=SjtNwO%pNbtx~bfsK@-7Dd;rh}Tm2$(y9;9jH)=Tjv?#AZqi zGO=Doj9M9Grq40yn0dH0-nJI#aBuQQNvhL+8Z*?LVvl;)Drf=G;@N!FG$EySci??c z|KlswiUHYDHZ>9B^@Sa}zN*cEnr^}BhGa*%g2J7UyUiwoR}1ooLM!RdGem%AqHk>) z2A<t-{CKoI`N}T)-~B&7PyeG;S9W&>8Ua^I%CAH+ld@ouPLcZ8RMA>(2^<9IW4Diy zB?uPc>nRE#EqQ>zr7LLTBAbkKwlU~URDe$FayW8_4Q0Q>kcPxv7A$s(Ys=9UC9llx zR0v%k@uTJq&Kxa!td-t4av7*!iW?Se+lxyzYbWku0x_5xe)F&jks^_Jt4Ep&vk{{j ziti)7nW*HFz)@}cJvgnjk#bRO3U7xf4q(oO!SUFRR9ORss*-eyT7_@sglSv3f}QVP zAHDcaR|z`7w@z27F>J+9AVtlh48z|-zlZseBe!S$-RY%p*||ykG)=n;^k*qoj?=H< ze8(LC#r5^#!p##TsP=8xx1Cs)7175vVVq!<_{||u2&~{3{QC5JC4Uqrm=4JF1q%SQ zD~XdDf9Kd!>lp<U(&%N!WH5T5Av}gfh@^lq5Ww{#?SX>6L~*e8G`l@7xWE<Anm3$F z3F&1jb_J%OQI>5pCPmglztSYH)uE-Hx~o*sas{^D7R+?%XtTZ&)ZVt8?AEs4-|pMd zOCIu%(tg47^4^tijwKm3cl^p`FZUFwHf>;vWCi7F1#W#7$4}j61EFLA?%)1+Kx;2) z%?Rwak*IH%8`~I<PT93=lKLv@;TE%(Q(>j~)qm^Ue`)h&=i^4%^qkOCKN>dR&YpK$ zhA;hhwa2mvs`iw~Utw$^=>fu>l_|k@B4*l(3M1y~=0Q;?fPldWm86JD0|TNulT_jk zsmz)`c6A&9%vO6(B5Kd~BV|aVKg$-A7OiV+c#j&ed-=H3wax9@NONrxyv!=ig1YO! z6dPw`$fb(gP0LvliA|lpMHTvR=MICo5%0{VIAP&<<OoOb*h_&0PJO9FS>}@{W}$hz zYx}%sUF5C;YFG*C$<D^54%jXO0Mq&M=lC(T0fdDWZH%U=Q`DXom!*V`2?A>uAM+n8 z5HcsKSIA{s(8KKPnx<vEMQ>Y+!xY`NJIC|JT}tMS7T@q-Fv4TRX>5wQh6ws9N`)x{ z)I}Vr;(6v4(}KYzIJ;r8Dfl%$YlByWZ#T`_ro)}-%qoV6Eb-v`5~)wQypGvh1`}Il z6lJYUFo9$!FL3xc@r)UG81)Wi>YGEh8^W=+*)j@kl(Q6WAdA=B%IwfBGlVT<ZR<1N z`X9)|1VImf`X&3KA%0I!D!#6>ewErrrp(L=o}5KyWf`}plWv0Cn<$#bKJ6#pJL>N* zxX&8`@%p|SKGf{P`U=&#?2I#|7zh|ZiHFhP^dM>QBg;$wLQH#9(gWB-@p!Bld~5y? zQLe&CfvzW7-}6So?fW&}pNADUWEyhaeV-^l^dc+ua`+YV%ee}i<}5e`cQMZ%J;l~( z=;zizip}kGe4crVlM|e0$V^yXcLw{z*|OAMbrm9HF`hLrCw`}q&|Y>Ez5<G3ii@Gb z+@_7Xa>o2LWyMBNI$hMzs)SWOa}F)z6@M|hB~a5fbV5Gkd7ZFz_k|pd_65nQj**UQ zRVyCDuMN#G?-!gr^upG#L5qERh3)-lWQpjM2+^-tcKFl!Wm|ach*hnVABchG?qc=S ziRQAWAs1t#CBVrV)4}jkm5WaLx7JJmtKSPj#<ExB2zNx*nGQS$M%Lf5ybYWg>;B<_ zSGvcrvu?7SZEOmhqw21TOZ(}`&48HoLfm;f7q8(L4WY&%o9qrNG+XTmra;aY$Wt=S zD<=}N8p>Sv-kPG``rA3epyUw}9{nuLVTe4X-N{71uPOk3rNtN508i@^<PWDClW=DW zxC;?Al}#Lr*+qaVq1Mu2)<2yBvye-iK;Zi{FBw^hYJ|P(>L9C17!_YqBwnqRn3T=? z1HOX7W1GvFXe^5D0nP!Liy>)Wyet7zCleWT&x2R~=FP2YXHzyv{Ii$0I`5L9YD+O` zH}x>AsRa<P<Jynni?9q77+6wkU|)8C6uA3^*h24^{pqN0*@ICF#Dy|KY&KhyUDKtj zMzvmOoyYR-)zXlSmXR6%6bILChyg3IkFH$jh~BfX)t&fEgBnCL<KFc0b31!>^X5KH zNW%*Y9>rnp3K`DlA;)iy9RSXpJIF$~W4(VGjb^0Atl1?1v23fVcVyG)3sFr3CAryE za7h`(O7jzwJsbNBXNLM^=BAUqJHk@hItg+D7MofRZ{@*>evQ}1Ogiyfb?RR#iiYXt z3esg<h()$|)^+kP;U0SHT^u()b8d7>Mm`5IdV;~U2*}0Wb+r$9+=6j?RdRLG^pE}Y za&Lx<u_<4*udWnew_#S&V>A@GAQNX}-qU8jDK^~D)D-4b7Zv0;O9NcK?4r*F6wsb? zs6HkPIKtn9))?3DjcD<Wnl8vynRw2=80JtY!H&clWp}GgZ90Kzd`fQUcb~|Ro)WPx zTf9+4NUvEU&FYR<H(WK#wi~ye(S9eSo;2~daTjqTwHWyX`c*g%4z~<(=iCz2SK=hJ zwgq=A-EkSNznTK)ap{{i_%ej)@aC)+{IdTrzJN*aSfOl1SI|0Nm8ZvVXjK);^3}@{ z4P1B->@cw3UOhZJQ*=fhwK`Fcp+j#=)2MIV5O4uC=$3(QQXn=$wdqHp4JFBcN_Du8 zfhg4}Z5AMAbJ4(`<zsc$C$HZ_B~#w_h6G5F`Zm{o`-OI}#G&Bf)_tat%jdG3Ct<I1 zquGXXL_YB!%HX>3zOZ|oc#K3h?aXL5b8c;n00sn1T3{a(wp0U(=IRX2Yq9s`8LWRR zrxwW8kh7`^vi%Eaf}xOv{H*mz8bvdz9Ikk00p<*1Q+HZ%dchmtXf^NweHumjX#*6) zQ1~UkyC(8!-ab_73@if`90ZF1S_;&ls2>^RkM@EZwK4eAXsjq$d@WiFdL`jdVshj$ znJmK1ny>(7q7+~uzv;<CY19Y&b%*)ysTeZc%WPR$0W!@s48&7i#lMxL;QJ)8Rw{p2 z<!yWI8#Z<Bdzs{2j(dCLn{qGd_H=X@DYGD;6#&AP5+%=yHP4s3b4H))w3FdjoCX1c zKO|v?8g(LZ{hat)U;sN7Go0GOLTpbQ!d1(ZRu9S5oW=4kwKp7Mqk5r;h^7;R=L(JG z(i?F$cjJ6S!HSDC83a}r^JWs2#EP7@e^;l*0f%Ktk9kZCJ0wb*D43SotyGbw<H^ms zOAbxwAWxAr67dFzgiuWVxDG^n4S!P{Vv<P?fH1rZuYOrieo28kMd|XGvkAYv;tQd( z@fdJk(e-MhRwu+2ab|mplJrt@&%_d5zkW?;#gYM2@g5s`&qEj}u1`UA{47evdFIje z#9!y->rI66?SlS`<^z1e{Y4asR)+9<cwnkq>%1PC-_S;m)YJx|ghatNbs&=s&@@NJ zv_l1!(9DU}L2xhBHX`TVY<=}m`x&QbnrQFa>Hg?HhKZgRem{Yr3$o-c$>rj*|Gran z<Td?Wr3=2O^U2WuYjhcGn6g-vzCs_2&v-x>o~t9y(~(}7lNJ-mfg@l^nL$c9_mw>c zWwXW`2UKdDBiKkPE$GPSS&3e%C~btUe-)Gk1TXI!q!KSOHFz3zK&TNNa?Y$f^-FN+ ziqUW7eSACGMT`APK!U9rp(au<)y<?!P&a{q?Fo-z=q49uHU=IIt{-H>QlVT0ph2pr z|J059oFw|4j1vl;k`L?hXT^9$!P4iE(HgKA%sp*w*_Pt;n5mOSV3yHZP)0J-@YRr9 zl@o=A@i`fF$){j+?azqw6G8x?Rm+zqXe!RJoK(0*6GSe4V<a0BV^llWPa%k=m0t-c z#_6e=zEY9HL}z5(n<yg^$+g4~x4y)wVzC^sL>IW9G4(Np9N0kC^`MgCoILKpS1*nt z!CD=HrY#}5U*HM-z1hpNX768j`XI~_@6iN8V=h>cfxa;cgjgS64SJ-R)clZBCN$b` z*bsGjGfg_lH3P<E&bq3RZmIe?6PjC+!G6P>6A6=StzfFp!zEIg@=hwIQUR^eKYF82 z?!78n9;LvBEgKnG%=^dBbFjY!o4ypXywX7)wdo2aljRPEOuS5J+<VFXk5mcK4nr2F z6<tzS2mm!uD~BK7<<RPTTyk6`mj%TqlZ!^O-)Rji>T<K%fgZCOe-`BE%`^~AC5cVd zQGjUK5M$*KDrq~gpEDHzEkr|J{@5quy2+>}vRJrPMF!ODJ$?IhqKp;g?+Mfh$zbYb zQX4&E=9}(dMg<V0&T<G@X7e|l=Z}95bian0m%u2skGe#AsuD8Z9#~)h8HKbP#s@yt zgG7m_EU@1<FM~zPheTs@z`U*`o#W=~8BkqJVR6YI{;veZcZ58}IN_Q|RYiVzm#O_| zAikU|u=>dBe990Y*FNnh%P>u>t=LBMvS0CKPU?yIv(&2?^XR6Rb=jI>>^40Cx+q^w z#&xns5*Ew9WGf{@$tEQC`Qkt@ke^AGhDOUSE*`~1UwRFt4TUN8TTfoF&Ngh)00T-Y z!lr|~N6fkRZ7~0Da>OYax|!B<YF`kvoa(BWZdS)x8Rv<D;BumOT&cg>Inac?D|5Cm zT{Wc0ls|83MmCax4)R3RvS#b@AApon+fr?kr{Ty4sE`B!$AtUfbKv4PBR9;Ggg7UY zZb;zoE@;$|pM0Zdsv}QDw7<xN{t8^R?SOs?q;zlRKN?zcjBv17b)u(SqS=pa;FUE# z=QPS#em9}`{L2-})E6BC8U8H<omN7sfcjzzOt3DJZ|LsojOrMBDlu~wbO|-K+&_`m zo)P>DEOF+HZsnsuU!2@oBSWXVqND>ATJAt*Qg$I@XRsH)6Zb+_Yjy_{7i0hYNpw|N zPX;}&k&D|G5`Fe%X_D{xIb!10eHt3WIPY4pl4G*VnH6+??#t>*!_bE>qmLa*2iuwW z=|2n@_K}%c6IPp`2N3Y3ROi25c~h64hHyPzo==p_A${y8=DhDtIUL558aW#0+dBt- z{OJ{k*j7hU!`?vSQ#r49EU|t_WJ@7;gv!)Zk_{!x6QQ$QU#-d_<2(<+Y&?mc=f2M` zF*}r7XAwRu%atyZ?MxMHRtGj#E7~ejINy^GiCGO~hSrT~_!#hjo9Br^JvD%qA#rvQ z8>*o)D5{{}+DVa(v~}e4zw}#skISMxW)Bj%3+*4w)jO-$KKSOLS>w{Py7Xr6>J;@V z5ivj>%927sgbgkTrB}wEZlw%aWxeFD(TeT-LblUg68K8)n@xO6rqVHlQE^3!d=O3} z=Oy~`i7RcFbjSPW7wk2HS~<ZynPk=5)3zzwn%G8ixle-3CPhZ1+0JV83|4md!aCAE zEt2W#QX+>R!$Xf9t+Fdz&vt05paBz@FItJe+d89v?euStoc^W9=<$V}OMMF0;4fu0 zC~brWCHa=g2vVuON+EC5-RE1_{!}_loAEiC39td6yL@CaS_YiZwJIh<;v#zuBte6V z%;Qre$SJN06ARVwMZp?!aA{B3!P>=X@36ZYb|b^W&CN%6rN@~jV}bqxg6qPXXhxt4 zzPT3%;WGK+)Mq`@yKVopv|F|sYQ7>tz{UuCj&7}97-FT1|L!?_ahEPPEp_3J^8#@~ zeUozRs#A!Z<-@B&nzhZ)o5XH1;c9(IiA&tU4Jq9Rpq=U|-=rwc6s4UMlv}NeVgi)r z;ro|q|5`d|oU26>MHTBV3WVT)lL;%ye*bc!XPCY;lRGq42F|~dU$a*Y4v^awlW?s; zz!~4IG;R4e+-bFJ6yG*7HNZpYo6^g>7scReqWb%Td!-GDYjK~m)-Hj(@nmfFVrB>W zEGRSsI!-#MRecu0@7$CFUuSlDbw<6Z5lmxA`R~Dcitmu;8nvDt{k}#VQE;nsXYyI+ zhwZPuH=5_^2gq}s&>u<)2|zT{vFFjKY0ezI&BT97!?b1p;=6q9*s?%8Lqui15Cj?2 zR=@@j7V-{EKQ!f4wq35yS)(j2q)Dv4zHe0xVA8ty6UyNUxgToR4r>mdHA0V!?jLzU z6I_N8_!r`u>f-dg>Diy}e9o%v-Of4Op=Z}?(qdQ?JQv1N&iM2LLY$hRo#p1L=wsSn zv;k)Tt1EGln#7X>LTG{ddp=b!8U$?~%ezpf4mk9?-&5Eb%*2|0+m&8f$noC6mT`(c zoj)bYIr0Bo^7~4yei-X%cL8suQtaa01V{DI%pUy=<`iD(6pOG-gQh_J0@PP0jW+8= z=b~eMC|ysb4?T}7DV~aaM(6BWcWJrKqTtj3cPr71<&Yc#w&0*M)Vz_vDN_Fis$_q) z8Ww)_HEyPgJj2M4Yn|cnX){qJg0gtS<<S|(<DKW$asH7ps#;qfsJaqDmN$#@s;JY` z`)=?-@?mh`t9`kS;kqBz6E{E5Ke)9<IrE2{50V9ZpGMf`3FyaIJX7L^o^s@XP^dNZ zNBW|PZFxyFg%EHnJqZ<iRgQxqW&CZ)pAFG`Be_n}UnBze_>AwT(^S(LtH4QMPBex< zb8V3+0d?Cqey8c(q!y2*Vb0MjV#s8G&&~lE66$(~|5id*hJ?&5Y&=QCSCs;Mc{0c@ z@I3zZ8SPCO^BHd<M<fVQODw4&-)(^gABQgLNz<&;-(I5cam=KoPM#4WV?S;Nh#=E; z)JTbu&V$friscvFY{D+}su@jy*+tbne?T3f`r_vL<H-0)XcaBs(5TesxRJ6p(D`=z zrTL*D%P}RjpzlBSTW9eqtpL)OXm;)cx?qtkjDJk%{2@+DsZ(-!s$N+7U!pE?axAj_ zW4YnK#mxssZW;0SU2gp)N4iCY(4dwCj4upob~edVPxL#pL9kt8SG><C3T##uT70oB zXp$J0;DxejKuqi(P6?sWY^iHKNn)15LNVzuHTQ&FSkwh!6fnH4@68qC?%-|kQ&2EH z*Yr6q8G8de|I)^BXY|L{Yl;Bc>|U%JmDVE^`neWJh8oCDb!?77$d`!%O2ArFQgrHs zS?WU=jqXr}*Tkbt{|9q@>2q_owXhLVQYt&(XzNvDoXfRsoWkSi@@H3KF5mNw0zXCR zMcPwGx-65VE3zm0lh2=XpO4<Zt$h7MCiV(7;_SMSn%I|#!2Ei;A(RHLW>@mQ+UfpW zgLi+t^tHDSO*IP6fO^`VG6O*7;ZOFh>D1su`qf_6sY#t^c<e>JKRampTratY697+~ zB;JraDq=P2_8hP<;1Z+KGH45hxEVHr%*J_R@Zn=}BfJ@7yoC@_f+E1XiPi&8dppL$ zQZg-)5ZQu^J}AY=f)tB+t6393r5=h)xTnBrMjVG+y6Xybc@hj_GcQajsZGUMw(b=k zHqfA9XN{KfP;ICL3g4@*#oL{ZKxxyla+t)$@Zuu(sJr;?gQf=cHR-;?A6(k|#QN|t zS5CS_rnNVpG~GG)a8z1GmNPwBnR}DVmqSv(OuDsXJx`9KRAo@|QAjxk$0>Z`rl0+0 zcP9FhiT|d7{S1AUU@D+Cd+q)Z$1E2#>%t5YP(7S(4;?nEtRI#8Y-RIxg*8!KJEj)L zAZL)v>U90VmM6iG)W-qb-KDc|{ZSedVARD#-z73`__)}cncmVb7=b}->T{^}8cP#Z z5ODuD9ic|p(w|{iz4CU>^&q+WKKrUCy7aI5fpQ)T%)|D%$_qaGG(T?TP2-%t4iH*5 zA};>^s>at=ogtMf6n@8Yr0ImZ_AO~^Kz{%PDB!j+Khp)c8X!+B%VW0ajbiI1EQ6Jn zf4|h{IL9eC_;qq_7RtSWJsFWCmZZy2B$NC6V^Dscr^{@XPN8#$^s1i5eX&*|gv-xm zX)->53v{hz#++N%ZBFG`G|rzC>q*Psb8Rr%yF#sk`)?eP8A4*Rxn-z%ymK-uuDL&B zSjVk%+WFnkR}nYp+3FTws}qqVU442yBr=>CgMH6jx%ypC0Rw5NV#G-QSXcW;uKWbR z#4-jYjsg)+1Re^iOk6VmHyy4Z$Pl$PnsM!)(YMxKX0)u;T}hl83SVjz5Q{(7_c~-^ zZPhs~75SivEE2-e&w1H^fN8~XcM8dHe;-+y-SP5TKGqKJ-@xe7D9qJdt0Rpei6#9x z54O&JY4WD(rhpyDRp?mmc?#4{5P%$FeF_*X+|z}Du1B$ID{h3HLX}Gz8&qgt(7LA# zI{?wXa5s~Noi60;W2HVCzqxQ<`&czPw{Antxvg#7v}`$Hg3vj1v~X6teVgPpesI)V zU?(qzS4W`JRTt$XP-JB+s4LC&VIM10*jyN*J*?wGuo>#z=fy<X84sU0$?3R(w0zKT zUZXrRM2IA)7QeD}+&G(FcUfOJ2%I2@9%k+QLVb1T7lH8`6<tYeiL*If@lVDCfvu;t zLSpU%3b<)%pC@`at|Ja{M%E-B*aqC$ZFpI0X7Fy>R+1!FNe9Nu$kdeD@BD`RjImh) zYzxAGPB%8N*yTw7#@j8i^^?Fb5I=s)#aR8nC_3S+!!-AxM?zr+!w9&ANa6hwUuZW= z+CIA|A&MDYe*pmkT(ulX5Px$^7y1f=>5bSvPVPH+xfJsXXRN?2UavTLW}4<oI?J5k z0LM$_>7xh?K6cp1U~kP2Nr3q0i)mX3xZ!ky(~{Ch>wNwM`p=onXwiN)HfV;Cs73v{ z9}ND4^6s9bxnu=grQpfzn&8ojDlpRcZXS{Ggfmi7rcCAKuCeS0tM|QR%V#(^;T%c! zlqpWG+C`CFX)`KJ0&O^-RvdFjm=yctWUZGHt~MvOWbRUHtSOv(86DHH-gS|?cs^J{ z{0p6%?D-7-`ez6}(SUzx#iDvxG0S)PyInySOmNzR&b<VOs!It@ns=Ks_J3*9Y;#bA z8vgv2Ka|oTe8AalMkBAMXyJYni@Ou}G}zUvgJ(E7mBHW2<o53+Q^A{9eErp{E=401 z54J=<ER)PU+?O+xSS}SjmCin#W{F7}z7O5&4j+@xx{rzR(V*hM-EsK95ynV(Uirn6 zppD8w7_z6OO-Q-cYkm0j-Fz-{SoU~-)C*GFE;=$^ZWrq04JqchNzirC+<2GW8etKb zToLl_7yQ4Oci62U1DjhO_St8y6&sZ2>S2Lf;$q&7&^Gj)^Qod|rx)yv`RG8yUsE1} zp==_M%ossV-mJO@_!bT$ag(;+3}1S3<lpAR@j;Im(_0rg$L~`K-${Gt3X6duLO*v% zykte1HVCO`99z+^XM70xoB(io5kzmrWOi@8iFu}Q<Cuq)pic+%yHoOUJtbn6^UtZ{ z4A8Br?=$~+3l~ETbTn~BGG!2UpD!k)p(p7KA62STmYc56N-$nqEMgF`NtHgnLs>W^ z`H!h^M!Qh&e*SekFTV67xLHjqcSuagf;vIflH?b&``BoX|JHQ{x~yO-V8kg^@ZTGQ zZF7OGI?9#-33Paw5czX-e7RpL0-n(*g<b1dYqESGd#<!8r!xRO(%lbEi+A9?W#d7m zE1e=z`K8FSSMK&)!7x*nO<Z4>+)?)5^z_NE=sIJugl8pJz8;TGt<gyM;Vh?_qLkAZ z89hT<{B0@mKWn#OXM6j$)nIe4FC-3wS29K_DeKNG9Rnyhjr=_^MqVG`^%lG6Mb<YV zj^up~QJcaZ2EXaCAqCFYdQ$~iE}sQno5@7Wu!i0lV^ulHkixvaeOL8wn(zZbDDHvk zdZkC1P;`u{i7vEQ2iF^TOQHZ(_g$aHmn|p4UG|cnXpZxJlv8crN0i$gg1=<QtUUea zv|s&l%N<EB4+YmRaHf5^q3M-BNE4$Wd?l&2vyA8e>2dUMTqzu^BxHLc3qpTEy}atn zgkh(hSe9YUEyuIZlY-hi%m%QT6PK>vokFgu3{3xF_Q(8;v57YfE3Z5k+K_+xv4y5< z?;~@1QzdfI*;Q8F^%5h`JPsw1n4Fm+>k3BmQXO>0(63)2EG}E7@&k;|50l>?wLzW% znLM73-%1_7`)aHDaRU-AMlfcA-KFn^YgYGoM(*R;75JY3Ihi0W&3?Qq6k!x$ZT$rN zDYkF=3n3PM39zzzKmXClmlNR453QU2t7_QbM&di`*+V>%DZz1EMj2nG@1A~s%el}f zVnrW<E|r{NDuWP9`&5YdkFf<pb$Gh6wR4^c2z6r&3oipfB6hs9kIU-O<Oy5ADScZb zUR(&r+|!5agm^Sw!kwYA%?e;27TMVg;TC+tCBzvt<Q3hDG;c46WX6SdOXx^DRvG!5 zyCe<e{kuot<hJhY?mNLRJn=;tr6v`{UcyCP%e%+JyYFtib<y1Ucp|9})rb`%IuOd! zSN}q`>+m>pT}=DOenxc7(j}8>XSqfYx{5zH86(Y0r2~yo{Ci1yv4^MD&RAhhOryy1 z&=JD!lHK1Yo_Ea&1zDTgFs{nTZR~1t>XJGxHmd46>tYc$=s)|C{4WNg^^*n1*we;2 zT;VomWJN-g`l5qeK1pJ%?BdR?7@rFWJ9lNd5Du3`X&kX@&&7nHgMLNI$KV1qM0#aH zz%E&gK2QHyk-`Hvf)%HF9AtN!bC8p6dwB5nc)}*pI3tNo^37W2nwh4YkX6i88Panj z!i;(5bM5v%kJSPlRtzD;+z3KWK^a=_g5Qcg{bM3P@Ln$#EDXpLG|VfKPNkQhTNYJH zl##*99P})Ux&B42o0JLQcDF{`HuW<pW`;IVAgx+*_s1xR1qt8$r-+$%I#tojOHY?g zVfxW+2csOfsgu}%FT)JFy0-o<gj6t#i=Lf#iIIZ4A>&6ixmA<wltnm>XU&T+vBUnA zBprAmta4{pGL#v6b}m`&Ot^!-rboS3QH15sE&SO(6+?LiM13T)eXkw90@AYj`cA(U zO=stA8QiT=*0<J%&&SW}?<Qp&CONxK=to*U1G)lE@r=m1kq#1`*cTHEkzDNYuP+M- zE~y^AWOU%o;YzyJ&A(5rgQ_J-M|z5-nDF@(#%gaEs}(?cAXiB-aeDn#bur>e)68m% zS*-%0kz@SjGj~6*00&PkVb+Aju5~|F`3Eng?z~8E>&x@q@m7m9E9*lcz=JA+)*Yk4 zk)lR1LRWu@1emVrHRB;Ky-;J?*c>jlH_r8G#l{aHufFt1qzc?3`iaeW?H6tmCHC~E zaCr~<V)(?)jUwSVh0JL4Eux^u^q=m8b{|9IC3jpu)WU$77!wI}X`Z+z_n<EWTAkBf zo)7vcn7*>MzIHT(_U2C0&vING1jD#zUA1hryHK^~Q)ERWm5Mb=-LEio%}C@|Pv@Wg z3l@&JfY+74!<=L|eM6f)35UYQ!4=>KC0%t`PCea<2YtCkVnqbb|Cu`Pc&fkufxqu{ zab4>!BlF(tlD)H%xLsUadql}53E7m<bzOVUM8n>d6*9`6l}#!#Ba~T5KKXk5{`&oY z{&+vm<9*g^JfFbeM>2Psf*VtK@AWXA6|%+JyRKd+j>f*xxfDqpKj+~J-n8k2WN9N4 zn?C8bfLQIaIevnC2YE>>^8o=KmW`DjU`ig(mhK~uOdKuqHAMP|z~xY^#?TYjNc;xr z5h~G=odR1xKC6L6{rh_}e%;ikt(|VPRN{<Q>rZ+G7n7fSj@+Lfa+J5vv^E;5b;zdC z3YtDQzjjO)d-p4nXkOA=_A=T;EH4wS{qk#{-H9U^1IBr-S-h<-PngTwEbnOQt^85F zk?d*&!+LrzRirsnSvCxI!O}I>Tz1P{xz>IJ$v1!UCy%!R-tt5!y~|fa1C4nN*W&5b z=oel=E@|`$)1L!m#hJn=FIqie0#7nnLGL1Zm%UO=vXOTn+TkX;<7$25IAXp&eU+c6 z(O3MpJ+MeSNTP)LEF3E{1^((SO%C(E-TNg|$Kk{f6O-fhrb)zrd#mp?Ew}OvCS<4o zwlYvuD4~hgnqg-7*`y_=_mt_E7fe6T9!x=sfrel9nPYpekKz7sIFB;0lB^#Zu=JN% z(Ni`^6>cT2KB60PQb$M$Bk<SmQjpRnxR@l>3tK8m(#O}Xb^RlVLwF@B9-q_+Jrs_s z@^;z6^&YuxtTy$A;~;Sn?)oiW&w%dRd+cNjV-@~2a)~4vy}8S_BSY9M3MXEQ=)K1# z%rO^l!Sc-9MPTJUZ6$^{VOJwnQTaMXrmCB0Gy|3h&=Lhi{=z;=mvjrQM&7nv0)L~* zLb^M7c37j9Hs8}?zE+b}q@|KAzfZsh>uCFh5<B%3FEh+78&TKaM$w1X$vojS*cK(3 z<amHI`8Mb|ddg25!8)EyW6&L)@0&B>MN;G%x1%y*WlZ5oX*Z8Ux8&jrA)W8fzU>M@ z2tEI<3k5_@_7R0ryiPYIfX-S2vh+4s(}m`-jT;;PUU1b)7proUH@_lGRM5`aH?-z~ zdG1W{Eh~M@CRa~km~eDPbOwJDjmJr@wk7}Y2R+$kt+H#++tvlVw(imhaXl=TihBVF z?a4HD@dezPVkoQK=aqH<pA;2w4SNVUfTbl9rn-BD%nROxzreTkdR&tyJ>pnJ`rmS5 zGVYXejPW`59<$03o$1NDBBo9H48Q9mL9hkRb^F1dT!ET=Ed@~)sgRNsvrAME<Li81 z#SG2+y{DM>$)L9Gdb@oZzdrMq+j(WT<mqbVjiu>_39QWZ<QiunNO&qm;LW>kp~e_R zdoLAc!AUAa?{p`HTbBG;8mG7LbzAGj=QF!yY{m!ef3-B{1POwQxB)Siw`p6`Sx`N| z_Z^9zbFomR5PK>A%jI_msjYGmCwj6643m8Gvaz&S{oFjNBIzbR)=H9aSpJ5ejDJgo z>wD_gIE(unNF7}_{NfY+u6xFjI=$=ztOVd?e4T64!trMMpT*jL%D1|GVwv|daPhed zXi5)jG7|^r-_BT=U*H4d2~$f*Ls{u^qN%1p7?9keSx&}-e+fXnqvt?ZSV2!YMBW6R zG7BZRrYXk0r%G*uvF%;b)-fsr#5X_dzLqs2-gohlKb?BGSH6}tMs6J~SCiFsjFmqa zUmtQ1b+#^^Kx1_e-}j;vBa4UFiz6U+bCmcdL>F3nQSR#u{<{Ga^sA*b&t{0W1T&g_ zS63ybUcdj2F@x>o%dPiR4mkMY@lFi&iT~ueY@-8R*?Iq2@TA^$kbz&&dO%%70Ib^I zpg@*1b>?eo4(J`T+S9kFP`*Pl5*bzItB*2(th&A<YK#;Z0BHB_nKX8b^k!PKRWzkQ zgnXz75_(1pJdD^c|LsvBJw_1U?K;b}N-GBS))T&d4SWOJMU)dTY45CmRiBb26@dGS zr0d)9ye*c4Vg&VErXA=4WX%Lfw%d5;da!L!!_@S8R5$Eb^8M;yWUGNJ!XWpi#(`u@ zLB`;#-Zb1F??-OcT2tF)GzoaE^B|8TzB+lm&UL%{Y_UiUcH7BFNhg(de*|a4ZW}-a zrKZ4-e}1y9eigW-Nb3Ain5zP){28ZiTzN?ZkKX$FlOci+yyiMxYG-u2xIEB^K1>M0 zR2#L+b1XfK1!%mx-84><iMt7?Od{g)<2uV5+3L5aBP|b8(x{Jxi0i7!8x;4BDEIRF zY89h-!sZOFi&V*NYG>84>I&8OGFZ|05BURC8cyZk1<U9A%iq~JH4^dfJ3riKR};Hj z-f>6G0AFhm0IuI*kkGFl_{a}!hPdgPUA-MdYOnDB@Vm@Du<3dkui6*gq&<#PRT;(* z-WQKL9EaliFN%jCq@u^U-~H{Fl&j$MH~IvYQ19mbup7vw9-lA1F%8CAW2F}5`lw6U zZ$P4w!D>+g&+XOkgOy*j(K5MwK(l{A@7e-LE*2O9ptt9WUL)5Gxi!>>O`d4Z`kmp= z1T@l1jLONBp9Yf1A;H16SekWVpneTu;?u?Q$-4UYc{=4Zsm@LDT0&mRpEvsQJ#Qja zG@^I4E~&!o9|-#2zjvtXu2Ea8GSSnqF6@-p(EFL|nzLTeX)AN`!s3mlX!F3CF^$X_ z-H<k>fByx44AXC~2qJKB0hU@uv15@m8)ID@L2m8Me;q=QPoGrICY7TkQX0P%*L*jQ zxz^XX`P*gss#yXL)S*uQq=QExV}hWo%dmP+bbt;5TzwAVg!sU*6muw-NWc-?i5QP$ z)Y{JU8NH$cC<(Zr(nq?|pf6RjaEL*oHOi(b;1AM`{7~W6Oyk{5Hw{3Iza9Xh`bRPu z>wv-Tdh$fn%`-AEH=~mdzy&&q3^_9n(c*pH;{)N-1PeGLj4vd|VJ@y77%S@AH02^Q z&Jh}2w-#^2277(ize3`&dq8F1#ATI90k&SJ^Q~(V={b@^wW3#3;&Qgd<5<1ihNq?- zwSgj`1>X;dlu4Q^lIm!4h{=l6Kz391WbH4HwcY*w>p$KQpBy#3hMr2FyIu(y)%wl) z7&BeP&MZ77uD(=3vo{XhVFRYEfoiM5z9f_HT~}YQwe~eKpsJfB=4M>yTAn>uPW2ED z(qn$nN4P7LVF8~=tfg&VahD$ktl0@a-|D9lsBAc6g&390%8W%)0}MO4q4FIwotwzi zL`w>dQ(C4b#GT)Ed6eGI<K;5co$GQ%x=aq^CtZX<v_gAxI1xq{f!8063Zqnb4I1`` z^|vrDXD-IcLjxZQvD#V}x(Yx1Ty%Q-fi!fkkMoQbK;f`j#j$X8z|BxN8}Sij_tm%6 zNQIa35O&E$Q4lMfRwFJigauJxRb?7#2tW|z!&)fCr#4*30V06`JX?_$E-aueeag)6 zQlRov<ffyt{)3D-Q`$yLk0KzSky0vjv#R7utl~JN&`3koT`!h22UlmwzGTp$KAR~+ zwvw#`qpoi{NswbXAE7A6K6Azo+5yi>4W-);ds1$+_DOWb{%BVqT>4Fx&~1RjWK5j& z#5l1Lu0=%Tf)9PcOcamQ-gsU}04YB99_B{@Cp<$@$3p5g_lo(R<4|lChDRJr)+THu z#*a|4gtdjm(Ui^SE2jw}c9#!+VjTYp3lGtrK-f802C9{DRu1VbnbHDX#Iy6Ie)OHk zx1=Er@&cf(F|>VM>^jZC_gD6_pTyB_*ferf&jrL?`oT2j8IwakgQKciC7anpp^DEW z6_IpQ1}jCxh3CRbC%qt_N~bd55FKSl`+$9O(~kqlx~#w9Ks{gOp7s{Ctbdgak#`R3 z5N&97vGKvGQK5PF*28uhrJtwU(x<M7S*Gr7p4P?xGD(}STElN?U0|FN%D(!<NUiW^ zdxX#M!FFIpU~K!RU5Umvo`5lmR;E!EmHi&uPLy@#H~icapLTPAYVv6J*Zlo2&B+LT zJ}fWy<qF3*v!v4s7oZnzj~jiMe<dLR{x1IO8Rps6;9ein0p#G-!_x;Db(7qw`GGZS zg-bXMz%I6fP}k`+n?Cppdu5Mkcu+@pb&eGC8gH?t!rzVwbPL3Wy;Fa$05$kEedUoD z6Bf-fW1xm-BEiMIwU!5o{mPa9l6%b%a)ST({4NiJ0D;}fWzJVn1X2Yrs-!~FSING7 zXh>rga*X#llRvk-WC5&Ip>G}J8yKi;K<6>>ycz-__+yK@^v9eaKP9sAE|O^?Lz`B$ z`W!)E0CGcmc?no%F11174993G=w3{pXtJcLhaKBwrk1nVEqnMM$M?s%aCMOqFJ1LG zA(#ErCYmkL+b?u*9wQ%f`bs}pZf^>%&VaB2X-3?z_$p6#wN6HV70SN!>B^x}hD=LU zJWu3c4O@``Ev^jb7Z(2u80+*4f~K-VGzBkfX*C*-1zZY1lC4273AmH6QhSn+V9}7~ zs@8SI!f1(-ASNqGlAWgiyy$d>5X%B{TqT}Uyqd8KtI_+2Nv=rJRWB19H0sCTPddsy zc=Hd0!JFb?WXd8Pe_Z-Qxooi$e0IwxK4OyC-jvq+4;c<RG*!=lxHNgc>TmcGT(k;J z<y&rAihzsBxl1Iq`@*d+Ikr;wX&Y8uJx_{E_q9Bom_pH21y>!q*-|$+A2-n>bWY7; z+%tQLF0!iWKNVBepU2r{;c?@!X+~bp$Z=}IU?!W1v+A<P#pGjPf;Q&mck)+^yw6C% zYOa<kOmDlH3e)v!m*hU$<OPiCWgiiPDE<<;pBHnca)wML3@;6WvDkPD>o8WqU|s9u z(5H}Nc(#;Qw1j7RjPz9I-Igdlo0wlPtL<`+!07lW7p$U!)WoYiImi7&J-F*1N&WlR z27{^ByW-Vcyx8vw6Y2-X<0NH87Cf0sFu|EWFVP~PAikS_KH2jkZiW}pYyL9=%hTdK z>tE>G5Lf>i#&!P2@P}6s?QTs+bxsC!bELX0nw_b2shAp3W5XXGZ7b=)r?={Tq67H5 zB@dy!ue`8CE~n2I*ftevqy&sZhN527<|gaSFgp<-`2+DT>_DtGG|Y7?<I;9lD9$xr z#xxJUR)Yox<-T7r>sC2OdW$XE-^m@~<NM2x!h%J<lm89mc}gSR2V5BxsOYXIxTYv3 zhC`(|Lg9WQw5uIBNyuf>4TAF#w!#3q1zn;i9R0xTi)|5WdbMmw-w`!F(f(@<V`geJ z`55&rUhsIC+l_uglx^Q;KQc$;0?l4EH16G0n;n3et3})rzuL=$Qf;OUE7~B+A)o1T zbI#2TF(ex``l!Tz4mMYRTz2L8HheZt%k0jR!8r24YGitu+V#`BFPxNNfZif!u@2k3 z+8_6gL;cZ<AL|J`)*zSotm(V8x%la<n<#ZX1L>=qiddU&kN56BU-ZczIyfV1Q^c*V z!hh(m@pWg(pBR70(-#E7I>mY0NtVN$e+F-7*Z_wGxyrA~PWwA~zLJe9*loUdVlp~^ zt8wJCuqpy>W$*3x5F1~k%ir@%@RL`&+%Gl!?hyMAW)qNMr1E-5++i<9X^`5Z@X${D zzcu*Fp;ou&k4P{0{_SdOszlBX9gsy+(lWELACwS2`eS6jwl9}N{)7)2wNdvJ+E0WV z^Yjha(u0U3_3l?n!K%|E5)PJ@D5_NbtiMu%B?gK1$9_63dUc!@No2<wu@kvA<-g^| zg<SI0qMydq|A~EstDZ(J6TAMw4L|Ty&HeRv`m6pau4Z1@SMZ@<eOmN?*qa}vm{b=Y zrUrY^9B^v<yIM~Gdb%q_=38jJa0K<5aFYvs>HY9m^kBxvkG~%AZ(6=kH@A%W<mrW4 zRTGsqjaFsZ|2a8wl_*ccT0?NGc8<NC%f^by1^bJv49}+phJT7C6xFN;2rSQgvRj7; z&o{1D@-1zvt&{R#5^P#05m6Up*%E44fL{Z`KL%FeMNWC6^h1(2J6QlKRfV!x4=-X$ zD(=L0o7KddU6aNd;lBzHykUbB_%fXhH3uy-^!_vzIVSa=dhvf#-`8QRSdGHi?qx)c z!{tGPn@Y~#3T{rj6tXS=oMB}WF(VxEqcDL&^{nUEK?ZvyYxb(K{cEF(X9jwa)O9vO zmA8~bk|_3`46e3Ft%~l*%}J=;*vx3y>^YhFkiq3ifuneJL<%cb8pC3rhWfkp5FN|l zS-=?P5Pl@Bge&@pTrR;!tD3l(mTY5+l7zdZnj9Eji)^3#lN<}$JF_@+h(bA93z+41 zK+aBVeX{CCg`4_@fxE^yhM}MG#B-NP3WH@E$FMljs-h5yjw3iWD18qOrklT=qgFn& zJlG{d;0zx6Yx1?kt;q2x#nKLsRRW0DPHRyIa&sGd3}>jDj2%&oX|mP(`*^|y9&OW> z@50?X7|$QrfM_OGgV3ov>*9r6LeyHdB?Q=!30ip3<ynArH?tr(%1Dc|#(~Wa%QL<! ztR$npOh9Qy-t6yQz@<@txl&<<wGn;4y2ru1(B@%QtUJ@5wbOSW?Ohfm@KMf;B!WxY zQ4zoi{58eNN<TbANDPn}E|;oY!~MM`gcCVm4-tLoRJ41xjkp-p;cJ?n_;5+d@*Ri@ zVJlENU2N@(2!TTB*zFe~qPSM)mKh4%$`SwbjsoX15IYzJ)?$<Gnm*Z($Z`1v^-7&F z+&<amEft4nN_K~hViyfkD5pEg0ywO2H^<|8GbET^h|qXVALk&RSZ}7JdYit$cn6MK zE87uE#$g-T0VooC%{0Hjd6%UR3)8BErJhXHE98$gd2TU@VT;vQF!K9IbP;TV^6$B9 z$BD<F$bn2B^<NT$Br;PZV-Ky_^<)Bbslgc+Q~DTea9(I<Z*@P?XJ=;Le^14~DM22$ z;I1f4^;V)LXDwrF=~xy_OWl@VZy*>By#;^*!C$wPBpTm%z=5Jl$9tO?P8}CX;RMP7 z)@V|=q8rLi<>X)HLyXkokq$*LTt$N#Vi_^h>HbR|`#D+98;8`~xY&Oi<+_Z97Q!?@ zXq_dr#~o|@sdz_>@cvQU`R}O9a{jmz6cegQ4LpVQD0QIqdgma?!pr<12d#^ZtCDEL z?<u}hNykA4m?q8Ael*mTnxAkcWo=Ze#eKKR`h9JR>At+q<(ue<0@91jc}_N*hfEwg z8>{5U>VntfQiy5oA?ayRU$fo(<$fNUYF-ML#uC)T9J`Ur+s6tBI5si^u8mzL#tu91 z^!>#wmzX8s;b7J0slpp_hQXE+C@>0p278nou{tosf>$t9$!}kWkVT~3Lw){<-zmKa zzAoc;&%FE$bS@Pm!G$pJlA4UxKJ~d<f+u)1#uP=B%f^$u2wtC8SxrD1{!_LCFH_Y{ zmm&prepMVOESUW#>;L<0z3aXtB5~4+00SZnakj2xtkVdfxk5(Z4%r0nW;@Zx5`?~% z$;#ygOgef6;ua6FwR&AmdN`gfqw8QxK|i_+KG*(hZ1Of#n>IiR6vDPC@R?g3+m`dv zn=nfzT#EEF6YTlx;G3<|rv5Q#_aLN;ADSY4UW{a0eV|b)i{gQbN)&oMf2qI~34cas zphpL9oWk<dm@Wcgc5BN5PW8{Xt<En)y~h&7t-O_Q)4P~lRZelVoWwR^y81QEz$7bh zvjgLc_ZXZp0_W=GOP5N!U3p;^Z+7{e9?D%8<)no2ma%v4=Jn6I^@Xl4?X*z>J#EJB zBveg-$4IkBJx8$w>ikW!Uok5_@$81bsC-VRiXeERaKrE%VWc9qso>);#;YhN=ptvC zi^HG8+ujcz_$(}8U3Nc6C+<j&JF^$%-SfX7&W4RK2_9%txqbnAh(@T~^bL%LKlLzC z7lOAJFoPY@l)jYX-E5_^?hV34NsgNf&TIlp*7f7U_YC}_d|5Y)&1b)1tgq@QWZKs$ zg#!Ic4q!zD;iP*8>z<<chB4|A&Jls@!lw&UF~TX|N5YorBC_uq=lUoC#}VBPb~tNZ zr3-bl!Y#@^%wKV2MgFA<SCj16fo2P?ireQSAE`w$)fD)J%ApEQ$8eX|MI!2SOlwlx z4=&xHrhYy^v}53h^{LjuRTYZ31+(AR4!hhR%+@OMi&=~CM8`PdI8IGhY?qZxty7vS zqF?P}$8Lsz3X)Czlg&iLk|&{EhL!h1!mgt0;9IIvg*t|_$RC-)$AM!wD!Z^Ke18Lp zgNke@2Na<<lqSZjj*wx}8FC4cPkoAW(?lQC&`p|+rl9=CK7=~<3A1FSx>BzUK!N3; zl;DSn)|iG~=sP7VZ5KKhhbwmkoE)Pjg)CN7X*4z+7aQgrQVI-CTnS>{k-Yms;b#1( zUo~^<1tgmj(qTpz|6BO5R(dx0qLy=3&vSby2U-+lUw#U^>^qY6^q?{&PSoHhcEi0g zAVd*-jD@-LKkXK-*k+y*?Q$UGf)-cUx|P_d5a~tsyK_Z`r4-!9LRF)19!6|X+Q(m< zlKDs=54tPe5*k~g!Yu5$<EfaTAYoUQZTV2)+~mLByN`-9aU*xtt~;T>cEU)JiPvY9 zceCL&nru_z{;1rJ<$cw6@0xPc%2apxmP9`@<hcB`4rO0{fNm9bP{9_k;s~8{(jVW5 zaN+`r1$QH#eY)qok5vu;KW7I&lX7#G&(mfrD&%(>X<Qs0ZoDs>k^{Pv+*WDzL{dnz z_kGo?yq-IiS(CziSk!_86Br8ziy*tt<rECF7oN)M__7B`M+UYnN{Gnl`#OygY*4sJ zx9<h0iX0Drwop3@i~j<yA*#c;miX4r=GXDNj`@QE7MrKe&{HE0VI1>w7NyR6D{9^h zDBP;}$C?Y(&wm;y|8o>r&}v)9w*3V?f78|~^Hp5f3H`IxH)BV*#ew5g$xrbJL;t{` z1YE}i4d(q+$9Px5Att4a132pZm*Q^WtgH~chLy&mG#pt!E}|rnO}wAGyzb~<URO|D zVol<1_GJC<Uv~bTwv!{9NKVkTwxR+Q&I$ou$@pVNv$Qr|PG0kE)lCruC<6bMFfE_@ zU-7mt9k+gu<fDMNSFv21Ai)Jkg1>tEr_=K2RKuD%i$3#qYt>v~qgB<9DGsggtV*b) ze+8vIN~389uGX(khQH<0X|X2_hB4n(maO%-ti^rNG2WSA4`LPZexZ|@x2}eF^JV+b zO>D^fI^F${v+}^V>|jXW3!F{^>6jw!BF9$oNZ9C+$XF;&N9C=ZZNq9Ly>kDvu28~x zi?*#u#A~f7-N$^#T5XA+2U8ze^z#<o0H<~!AD&-c8_ei}an}7^WcRx<a{XGtl{AS7 zq#GE-o`Ye<7v{fGt#fi(w<TP!YeKemvW1z=`QlLZEwGQB3V27P_|j)UGwx4=>Rp*; zWs@=12f{Gnan`>M{6(h2O5|YY3tvvTv6}Q)b%|BCm}#jSKHFLXA0q{<sn6JPi@~^o zFOC8mS{$z(`Dd^KGfTYB3k8~Z1<h_u8$?elY<d5_wiZH{SGYandug`$L}eVoKRJOE zy~qy6B2+$Ots8F(FMocLChRgbo|~t$SdWATB5_)wPck0~ur=%b+;-5(M{prdGogh^ zR{xG1bW6sYxp1Vz;M+g3BIzR1nC_qa&N^#681N*B($Bvv=pMG+^$)}HM9`w^%TT1i z#6Mo#6aKG}%Mwp4x-W`uT*B>Ji!`!sDtxe9`8&*UW0vk5Q|Nb0P60EYmITgdS#eBw zkV%by*&KmG&iqE;3qAB)ks_y&NJ+==Ph5bc<GP?3j&frx@{;Szxm`!Xu0{X2R}neY zM*A97z|xhj<oXuVz!#zAEq)w7fZ?YK9wCYZK5B6+YYA*d@*QbSO)l{-+x;--kB}C? z{@}!Bb>7*v-qFT&{fq7R6e>1PNmiqJyVKXL|0T)|U`?jksydm!0v}#=$M%Gc9<@n` zX1wj7?5SULvjby9^ms($%?e1C3nm$>?g%^paO%-W=}tw7a2edkK}2Wam1vkHpN%g& zF_U8_jYbz+#H);#NQq~1V1Acw255qIAw?OvYNFkgF7Pr#!qM@(?Qmn|WVuPP{$u@@ zn-&rH@yaU$96;-7`kqDKO7M>->XyJnhx2c5yVuP=U#>l7<`A4uP}TLQY$?6dCj<0q z@|njhKTMasGg0VYz9*0c9Gje6@r45;Iaj3X>MP*5jHg1<37dnaWIZ^xvP|U`63|ay zXlKG#npx<-5c?Kkh`3<!CF7%o4SE9$Oe&&mXx#T!22ue6TV8~@{7}F6gC-Y$|F0I3 zMyY8fAcqZD9GAS-+u-JozrS}^nw8Jrsl3q!9RK|LJGICR2-*|MQJ-%&8NKi&tB38n zcOU(Ou)VGZ^j(g4MolE3I6i3vtZJKb0^8GB+*FW>jwA4>Yu?NksQut1J`b{S2`4c? zF=!BS;*{4iWV~M|if=hRjYCX1`&R#aBM(4#iI6Uw(ef+p4xB){hPPIO=wZ|u%y@`{ zmWl{}K2=6D(u85Gkm3EeAGnDDNmDpL3bc#VJFnqtPF}Q}LIIcmqtT-Atd?ki3)5$p zoust6QEc$vEZbSI6J>r~F1<KG{L9%emY-?PqZhr_qS!Uq2>M(Ril*GC7`!3K^eH?N zI{rim#E{OtpcTMPj33uC<?DS7bq*4;VeAyl(!Q$Ah5H6Ib-U7}{MFYn!{sB-U5Ht_ zhlRZMm~A4_?~wpB&~fO2leDg>J3JaaACR-u@-;7AjPoYhUnv?#Y$f#4>){A^iBoMp zu)Z1Gu(Eu!2d>NV^u}zX0@4aTzk=2{Nb_J<{Sq+T2}pikVY_%x66R5bYz`JR)Ws~J zh=!8dTZRtmFP#h|5xfIV(((+Q&Un3<SPXS{qmMTlO2F$85+E{qI{L1*8F2b~om<w; zVSM<Mk~#>^&S~{W8;9vtXoqrBhi3!&9kkqB_F0Qlf(TfaA>NFC+mS5K-X#lY^<_Po zjXVEb#qj5R_P#ps+1&Wjx+q)|kZ5U`xm;FsytwS&rI}u>p-FVt=KFVJntW>3%RrXw z`*A=TG@~&J0K4M@7z2yFM%M?9L38HuG^K0PCdm&Ow5tN8d~Zb#nrfe7im}ual5wgc z>65bjMVsUR;a^*%jugdRPI{T_U1NN<Mh1&y`?lc5;Vk<%^&h>nd#c&?DX%W>`V6QW zW!JZSU>C>3VMNg>Izd^o8!U=sY@sW0T~%9__Gk8J8{MXckPs1lbt5?>E3H@yVn3On z_e*F0VdafcG5dW2UI&#PH}0bvYfa;5*NjiZgVmH@nZiI0GH&POMDA4a6OY$25^9&c z-{i$RfcqaDf&g{Kw)g_^3A(ZXFz#5jfO}v=V9=82jFxk@I9_7=C)|1eY2LtP$Y32q zcuEpSS1Mk^2gM6<^}&zBEgEHO->iD#S1!Iq*>kleG`iaZr!76-y&2OrEF77_(&!NW zkY;QVT$~p~nQIiz<4tixl-+_h;hW+TS7j01Lp|6<ODHbhC4>X9{3*%0SVKL=U0jX{ z|6njn0bh?325Vxo^)mA>MLTN7=`oA$M_K};%YTm81)7K6l~<%od#(zC7r7~{k5*j% z^BLoBvq>)o9P-e0pe0PVthH&08@`KLqj{zeFk4L<>dlw4bSY1tipRH9kMrD{rPn$_ z29FFQ^eW7=&$h)F4l&lYYi=DT*Vu*b4PGG-UUj4DzlFX&Srb^8deXi9j2N3VS^z9+ z045{`Azw@GxuMA?^5T!yttqDz04giGBDhV7Jyly<Hji7(5@UmOev|Lbl5{C_Xi3l` zkI0TiF1!;9?d(D37Dxh`Xx!s%y!0KjiFAv1vEOk*?KQLXWU#T}Q(Jv~!Gp4Fao=1H zrkodHfw&#MeP)n^i`A_Rlo-B-aOJGKH*it>Tqg=Z$B6*@vs3Ty<=`F_>#NM|RbGZH zGMz4dQRQr$3Jl7jfAB2suhD?U<A6Akf3}iDwufCk0UWp&3hw&twGf#AM|VF1E9r7D zF;U(%3*9AZi1&N;+xqYpwKj?iiIZuU=AvCmEJ<2`C`Me6vwov?WlJBzExy@D1qN}% zg4)c>(>b^c;o^TZM!vlFcrNwP)|q$oREsXCr3VDs=vOL}OYv`NdV@|Ew0N>>O|_(@ zwbBFJB*hq(Whre5s-BYo6QBy8g^5<qf6qF~YRk*Qjo$q@l{1l^Vp2-Bd?mcARM{iG zY6QQ?K)WVpK4b4xE=MUf7m5tb>}GIl#xH@7rCEUMKlNT8(Q4e*?xMaCjz$Wuqlpud zZ11m?3hr7zyIA4NrUY4JsSIQU>MD&!>j#v~nb1ZS!I`dpOUw>X#n|Hg24P7@*4uG< zkEjoA8&inSx~f^Uz2iG_F-6aQq2fu6`Ebm7HqN#5aosR;x?0_;k-;|~&38AK@@rD@ z>5tb*PRt0V$UifQ&f>&wU-nZ25UKH2(11#kT#7G*0s>@fBPMQX{;P-K)+=Grr$Mqu zDZL`LgGx?xj}>+re_WM`yu#Nc0g)((WRn6(;%!bg(!=uXc8xxz6w?)QUtX7P<)dMa zeB#6{92XQF>-3k==b!$pHliAiGu&EU$hW>Ib8$%iFUEQ@p%Hiz-~F<`FE`~^!9)Hv z_g$5R@hHH8PH@{nX+&uuD>oTG(kwh=c`M_)Yrn;vyWk%Qal$m=vB-FTAtwGf&P<c5 z+7B|z4h^%|)JjSVb?;UnN>*kz3eG(eCYR~=+;aN<z}zJfUa9g{6z7(cAMOiEfvIz5 zS^T@ejT5^sOMB<(JDz-cN#uSN>E%ze%-1gY4@1=6zOlPXk3EC}{<s+}IwM3*KW)&w z@IlENUeu5R{X$MN>~mhAkm{hL0#$a)rjpIn1;oDx4W>gs^z+YfdAU`w65svd0Zj-h zE&fRA?_BVXsKW8_tcB`yWyU48pnzhYbqMA2UkNuA6HKIbT_`z5){?3J(H44~%ITTm z_%MVUu<O)9Ttn7G^*infCh6OBab+5pONIPe7W?tbWcI>fms)YK`kA<W^FxPAdW;t0 zS*8Se$r!$;EX#<96yne?4Q>BTvD`P@tqbZ4GTJThd&l6`^oz;3&_;3ZyiI_DRcSar zL?Yssv9l(FO9AfG00XgGr0)vkuCPKR&I&9vpp{9e&ka$BQTP8W-|e7-hHL62<hY<g zjHkbe9D5Sd9H<cs%LW315#@_^G#2V|MQh#eWQ??hV(&PLrO~mC&IlY~ZUVjH=R$6O zQ$&vIpe{s1xQlM86b8SP_lKLx8bcXc3EaJF5KABB&%VlMF+Sriv*Tctd9z_*f5Z@u z5I#mvptwt1xCaSF$rRp8R5SrwBjlp3(R;M{b@FVmJ-SQw#;OI}*H>rH0+|tX<0v6n zKE|?8utyiUU3gnk7rTxPUo}-3U-jc6AdF>`_%gK3DfHG3miHpP<i;Hdi&Pf?5jDWT zyv}gCQSO3vq^0+U7^cVl=)c6SAf(fbW)8HS>mrsv2m~~fVdZwJT-@d^8uy#I=$$Q_ zoRSWH26C8&0szT2#{7yLa(zs&);ev+G!f~ZmN2PJu|OOtCNXl`4}>HYStHiz0DCxt zlzYf|0&d)$Y-k$wjq$vW3Rxb^ku+#N*zFYRqvw<6?jwKEuooTu)9e%y0*<<V#=U?) z2*zuPIz33(YapH!hQaP;-DCh9tPwk!X{0&PYf#_@1d?tU-W@_QPs`?Tj5Q64Rlz{0 z2nNSmN0nw;95G5UJw>rjM&gfwqG@0viah7b_>qLT?W1R>85ebA85e+a-8DOn)bVeg zF#aZFe=v<=s-W1G&{;zf`zUGSa}NUwb?QYQ`a7~3`6kpUDd>+uc;vmzG`%c2Q8YBe zXdJx;CxZ}{n|oD)clA11F2kTChojDWJ4kcR^a0`Kg8&~r#@Ki!F4TRd+|R%0=?-Wm zuQIP%q#r|XJC)l5V=+K2YmUuhi!On7x5p{C%PQIeH_(=rP|?SgSd-41IH*8)9Ykl$ z|Nbm`?H~`2c%&<uVd$8F*9tJ4Mrt(Nh;>WuQ{*1Bc+`KF`spUc(lJ!1D;JM_{Bf?p z&@^a{36cG+z<7ybLqe*-(H5!@pInGu0R(eRK|>X}7)k%J8Da#dJ0+x9+C)FPCzMRL zp%&SPwr<W>mh+)RKV>{rU=YsmO>>tb<>znkS6iKZN4PO4-2joLyu^Y&E-|PR4cZGe z(dVjtPypA;mRl+G71g>saC5J;=<N`iuU`U0LWYS+c9)jD)Z=Isle=>*%F`#Jx0L?2 zrU_4pos1eX_Aq#EhHK;Co&h4y?i!*|*BEZ9B7}9c{8-^|DEOy<ZF4vD`9_8LlF^Em z3M&Mnr5P@e5Nt%@T13#v`Din=qCt~h<U*Qp;Zylr#m<LiWZ!t1J?f=k6U;Xk9=G(G z8Lm&w*>y+`JwWRr3^5T5k}Y6%xmjrfQ%(2CdMnP++9Z0~i1bqVX%R7{`M4Erv<op> zgba|X2=FRX6^>`Rh_y-detgcs!<_m#!wY$3onXf3<}=PIS%SpyEiY49i;8nfl`B+> z*F)qpA(FqLIeDJt3<+db)tc{dmOF`^cEZMT5{$L!6w{vl=qXgxvNw~Z!$?4e=g{S9 zve%pAnYmDrAJ9@}Q3iD~n$Bm7pg{^(qG(#2BPz-C+frhm8k2)_#AsUt)LWH=4~r(; zU9z@#Sz<Qi`WzPymxH~uLNIOB>N2Sw6|gPI7Frpgd?VRQ_Ss+Vf_XK;+T-9WSUP!4 zfqlj7$NHkR`w$%mh@324y*#~x{^hWE55jTPDf>#joT>8uJ(R=-gTZdLr3ph7ll%I| zC+12>tLUVLWo4*P=sUd{N=X4nSH;-Jm#nSkJD5s~%~u?G?1n?E9Tb@0E=aN#ESc6c zR!OH};;RFQ`X_?r#vn!}Pxb;)8Mn1bJRCc5B#bIDikCxx*r0fwV=JL-An`e%$>4OZ zBespcb;9SfZk`P#>2rQ|J)r{3o5V$h)NvZ#APO97-!9Q?O@^uN7O?%1ySyEW^4sJ5 zPYZgG#<E-oKDlUE6lHGvm2MmjApu&V6tIFUlEaE(fM~CNRSwRrkNW9oRN_MU+njvZ zj!Zg_?#hcoFgz$JO86T;x8BLH(s3#jnQL$z(W`IHaN8H?e08u@a0jGX_^H-GvBzMk zh7`zLn8yAC0}U(D9Mdx&w@_nbsegH)_7C2^Hdcbfle_z&>#j3SP9Mpu*rGs+;_~FU z$ZVTbl)lnxO=|66@b51?m)BEKf>1<i0TA-B(fGL=YPO|Hd~6=31EwEU|BT5U_%J7r zWsL)*2|cXhE?Cv4QwC!xMOMh!%IvQ&PRoD9((HxrlK4ApX;gPFzM<=8g7VG>N1i4R z3Mj#nLZ_0Z(G{w2pN_s~;~`$o{9$!P{>1@{>H*fO+e`2_-jO4AZ33EM%#{FeI>!DG z4#pOMC;osLYX%#`Ae~2rrxx_-?aa~GW#c#3P=;FCF0Uk_miV81MlVUesL|)z?4yk( zDsZ1ewNQ)f=eSPLIH4_%xNi?J9??QebV*{y&v642Lu{|N3(lC;$czDy;hXJr`Txe4 zE613d$C&*oU^D>WcfoJNK%%wapkO-XF}iXRBKc8wfM_(wRA&IfTo^Y@Rqi^BdXLvC znSWbO)kB0%a1mtbj2w#Asx-Q-6);s0foq+SbOQp0BY=a=zc4hfMJ402G&)xHkhd=l z9}AB3v#pOolM5IMeV9E==mmX1+|R({H_g#nBbMhTaz@Y@wi3Y=nZ~})+w}XswQJ>t z^;s=F_)%$D{S|#0A(tyBM{giYry`pdGuQUVy+Wg_^yH{t@#Sd6kx^qAq+j->x!2=x z^4R8>Z?+-I@sK@LNY}4dF12=$1N0K;bk#C7pNgH4@Kg}=i!C4KvP@SPLYu5b;ra}? zf*z}U{GFtLfjEnY3JrHRaX}ik=q|z08=-|wNsu=MqWL!-Gks?>WknQn%nPN<mk`AH zGX;OZnRa^%_OdE$^bzIG#y#`cupI5CqNK3zXdgr5`n^w<+Yf%tt0^q;7m;zo-O7f0 zH@`0}G$NnNX+Dqso+cFe%BN;DX>JssF52(N)e<*v%%u8zmxD=fiDPdrz;OxyVii!R z>9GFS%mSx%Qlrh(s<;b{#&xr1OUtKH9P~V>tJjL)=|yrF`{!ijFG$wl<3c3|I&KNH zwkevo791{{)~vF`<DEt>mHXB?W%zyxNR#InXT?W0p+TLpbjzlN+2}&!u6MzrMw2S> zRgVU}&PuUA&%_&oD#C)RtdthJ)aVu9bXzv|m$VX+)m1c8>O3UqV*CWWRMJihEQSYG z4ZYJiQ`mmiW|{HNTiGFQ{f3<5>e(@$G1N-v?m(l4W-OFAq+8#;s$VXPs5kTEm=9hy z#M+ysX&0WO6D@$u5BEZ^%_LVgT^R?Tw1EX{LB>8TCm{AG4I8X5_Ql<eehscXII8R& z`t;Xf<!_qtp{v5c5%z~6^=h8u2c^w~m2${I%e^|Ty+_9Cm7Q&WA(+rkW5B-$1~e-# ztd5ULjkQX^!MyOZzhj%VWpza0q1X!Bh6!7uyymF}M@SILR{Ay_%g*u$nwiY;aR9yi zo-1Pf$==d;F3t*t*XSP|kIb<2LRDD9+8+&e*Vq1zzqdpGe%<O<D_G*BX&JivBJOg^ zzfc9^1CmxSK&e#pt<^gBT`=T_5eWDFoiXYS`q28TsawgwIk_9>6PzQmQ^M>co%Yeb zy{fh7p8{U^S_aw}=YP*P)b6D1EV3<{umz1{Tu;&Jf{t>0*?HF%lp{wC@)u08uTH&L zIrwBoYa+O2f=Yw8(9=eizg?rF<VBTb=@`T4F8ZKGBhGz>!x-FjpHKgS-CY`HbI85V zwS1$O<7#d1@HgBr3Ss|&W2hsG{1t9a{ZsPWG2**%7xsnZ6Rh__J%^!;4_(3u7>!d4 zy1Ba6#RwlC<5w7a%)XnRxoz<9Bn4;8SZzaZfZV1ViM@n$Fe>8kRp?@^wcOw9gl*Q{ zSuq6p&OE@{aDLCdh*Xv}mI3G(+rf#F;Y^1hn?;ty36{bFRkI%_07!FDlS<DjK+H8+ zBE&F%nWwwD!%qo5IKI%EYr3M7!hb2^Z3`=wg{sKOhKMUEKt>q@EqKw=)3c{PQytJL zzxGv2@=`bzl3?ym$b%F@)y3g%D5@TVnq|C+?pepXb*<(e=*&wj0nj@4JwB^=zaw1o zTYv9l(&RP&I-2*Y_gKV#UqKY>ogedI{{Q`>-~R2?#ctOjzdi2k0M9y?uO6vtA~Kd2 z$^7H<tJ?if{d{_1I^zI6jLU-@+Zy=evr5px?zu<7v-_SOUwVCcesRZ<IM*D0%HX}b zt9cHbNGE#>4y9nk&dG<Ld*v`upnAuxNqr9UGfMKD62r3dpQ#ur2D=ux5UX;~Gv_y_ zzjp$Cj(>jtqO8JAx#aU}(X>}a6Et^rmEh!=(2^4j<93e|@|b+z3_ZP`z*66gMh!Bo zrd%J4zrKBMoj+u^>pT&;&MT|Uan(iQ>FZtG`lC=FcR-u-PVXM(1sjCY6NN;R)Tu?+ zhF&n;%p@cfx6m!tZRCBfc(ul0=2^9xaXn5q@t2>MMw`)FIkH?&Kpif4u<mBR+-!;Q zn@ACaJ6+^kp%m;M#hs1vJ`E!;Et(5q6ZzJDW|zzoz(eD9Az*oIMwMEcuG0C^#)(#U z2!)TV{H$^E6AAIYc#S&fkI6nJ501tBBa7=jw2r<ob2)0Ctu@+0t*C)|5Ay=6cZpu< z1MlC;!6*Oyt0q~yt{vYgi-bWOTB7d>$4!}W`Bh;zJYB1p%1%rC4VWzJ3~@}^JVJrP zkpTrt*n@~0N_KZ6h3bkz$B04C?*5LhmRBvFC-q<$%^nmmno5}oUH>Ak{3)t_4FwQO z6`@xmYsni`)Wx-C=hR5Qx`n&jU0j{1#%$u1tgxwE=co)6H;}mJ`P_mC((HEh{EufA zW6OIO#~{emIxOLCs-yNTnIP>e5TyUy^j77CO<F-Qz2C#CKvxDz*YgJwEp_?6A{UoC z-|EC!eD(NotuU8W{5icEBMd}g_5lZabo`dyczmDqYe!o7kI0EO(EklG79+dB1MqVa zp~g3u3D=(wec#TWXW1eSs^4N7&i5HF6-n1|o-84K89&wDSr;spe-6V6-Xf)3OQbhz zw&<5`{vPy9CI>X4yZ(q*sOPF~#Fs=JorV`Ysm2<|bz1@??_}Ag$68-L{d*VF%)DQx zlHm~291>+~3O(MKWzV@AI(75ue<}edC#L6O>^HpL&1D@PL>|Z41ExycopbI!;G{2O zER8}fSfYDUn{~q5l~;6sWFSK}{i?R-)4Eny%>Go4fDkGKj`>mwI8u<QxEV%0VZJ7@ zD|nQYnYL`pgdZ|3&~f0tLbdS1?3p^k*8^KSpy}bFJaN(h01@zmFvxRXW4lPb9EBbY z<Gq!GcquCB48lZTXDN{9LH1N<Aprk2obH%P`Dx0SgZ@*1!qBBMfc;fY40u$Ghu25m z_mU)Q_BvytrnT3@P19nDE;tUGw8?XR=^>ImLc(Gsf{{zcgI*UAI?;UTUpkpjA+Dn3 zGo&t6v#fHWtN1BtFf7C@`vuKal5utD{)SFYbFZs(_++Z|M|uD^<tiJkN>0f&!Mr>X zmdk!cb`y7z{oN9~n5Sy!fm9GYs$f);<#_24G?`z8H`P!INuABz&tE5&<Nl@_1}*kv zf1}-0NBvQ5htl%*dv9tqZ}0@Y{`%w?;;u=5l<L`f#SpCRPAJwj3E;CRWRI>`;NE1z z>r54KWzQyxB;XvJriummCv|S2dDC)Er%F^N+%LJ)Qmrx$OJt%e!&wGQ-211>l<AEw z?~bd*3=bqq_uVpyhH-KIx5B@+8>2LGhB#%Lt~90}CjJ1iM)nE`%q|Y7LY<5%f?if1 zm<(L_C<l)KDBO11x38i0^X|KwWA@>si<EI~nX2jMH(nw%6fI{WlcohwdNViZB`kRV zyJGGWU9B18$R1qcU7Ol*%W+;mwHa2D7#Z#9W~}z~o^20iwMExiwbW)JXNrFlBLQse zy^aiMY<$5{p>x-UJ+xx#ZgI4iw;)fqmC>qn4y4LEI&tiCz!0XC*V~Vd$97F=_SI;# zcR=aI8=F?Mt+RdJK`+~G{0O@G3?_K!9pd;6$3+hTuzw)*@&Euxo>7m0P%tkTfSv;U zXCctqg03hiO5Ap^wy-A_E~Nj6R9DoO$gSY<d9bc{AQf{Zflsf#WGGYAyvlZ{zI5b) ztn=_Ay@s-P`6~XKpNAUCN1tj&!T9wXE5?gSnc_G8Un;I@y4t$IV}AH$_3R6Wo&<h_ zrkc41_sOaoBTdgfHT$d#KQ?H7KHnB{usJ`{{Nl?S3LUcmxutfgCk`cH_qL^OWgtz+ z;0gIv{n|*b!tI5(uNu}z3$7#z7#=Tz0Y?35yJts=TeG#!BTo$5n!bN(@!wi_*VerA zr8A28%XU>IRlg@w!v1~xtAq8iVuPnf9j&^YGYz+Q;=<d0?=1Eto(dYjZvS(zF<EUt z`uhJ;aU)NS-@N|s@6o~5m(e$G?icC1?49-Ha=I@@LPaVTsVqtxi&1bL(Ipz%%6%!C z+pS_LhR<6VPA4djAJb=(l}(Em3aVH>gI$@V!SJ1;&Pn(J$Qi=u3A&%_CXg15vww@m zbLoo`=(%kn4_7ic`m|y*fnEe7kDq9F94-dX9N=g4W$NU&i-D9qh>-;Y0`71kW2UDO zWI)r*ZD=r0sjzDZ<;}hC#^?1*Y&@&fr3-rg_M+B0IY?YyTf*F9sQhV~cmSh7h-XHx zh|RJoia#%>5-O0YBku7aU~G>ONMZqZ3MiTCe-lYsJVku1D5k2WVLVxeD~;S6snNL7 z0>_O94HLuoYM{Vz7?qSojpYLlBQyC*MKiP|@*?7E>d0op;sW8F9&y--U)b-u6kFPW zKsdB}P~`a!tW2|4UYjm9N!AbAC{!An-gv)LeCO5rM4O9XNZhhc!`w0??oHUD=`bo^ zWrR`d6Hkp(ZyD4>zn6U-y)XF8vp!mEjkCr#mU6N;fT?A}L4kii0yeRwEW^5j7hbd% zjwqg{$Ket%1O=e#$LbCy0WgVey!4k`I8x53IEabjL{9bG_sP%}V^3uP#>@=3_opdw zU<RRAQ#FCcl#O&|p_{n`{|VQt-0~AqtEckx=ZlCPli28u^rq~h-Myd%x0QFwxLQuL z!Rgo&mqX21+v`wFqJp&JS}Y%!ga<t92bZ&dXT{CL#yPp+qH2HKJ)=Vkv~E4aQ%P%a zwy(``v4?D(xMv&J2eDCbjlZ<OxS~PMUbLAm?ux1Xz~`8_{idCf^SNqTad8>+i-~-J zmxP?-s3iU`!J`hi-ShG+Lh;sw4%43x9vbk|ef#m6nrIC<fg_l#Z*?O<0W_fmCnf{g zA`UPb1Kb<vIOQNwGP$$xKy7CcL>7@{(kmij8oO^Jt0iJf6Sh4ME4OjNl<*FN`Ayr& zA5t;=>V@}_D(%|6%Pa|^I{c@YNHk8T8-3VQ$i_U?r9D;1eSNW)83ZulV6IV+y`@L; z2u;*4pZNbw3&87T1b|qSpgre+w{VAQTRSDE4Pv?fn)hj&P*DkSeY_yqcs)L0Wcna& zi^d&)PJArEKWmg_+*+GNTt?=n6`cu)0X>rp(Qy1@VYR(ZgQ-ZQWdIS2x+SQ%FNe&D zqyHr8tEX=PR@HuZhMlg28d>0w8EG^@J)5UGU;QwdaoW7jOL2Og@?u%JM3IE@0SzQR zragciC&TpCx)+;T;_oUVANkhc?K4znl3TcSytclG0%rn1l&pnPt|FuJ=_(<@I1uY` z9~e1=J|AYScM4x^mw(u2(u-@kJLJ`Lkb6Z>M6tH<eaPnIrGMKuFN*oboB3#^KBSb2 zD1v|xPVFb%EX%?Ie@y-k9-#6+5G55s#;LecWS2TbD8V=0K(wJ`PwTy~TGg->1uTBS zP*{lQ%akC1E>}&CK5)O5W(0Ir>U<-f_uxr11**#i!b-K$J)R`{Wmd(SKoo;oC(8ny zii=5N;__W)-rm{Ot8*KgO8V1EDKBft>6@CG;|c0PSs3p?G24!w@p3x?%De-jIKc>O z|C)^{!7vCpjWc<3&eZ+js|kKDKHV#Afj+zYpFgVwod9drCAAPGrI)6<J%ZGqV&cqY zKrpA%Rk_BxK$sZuZ+tWk$N98{b_=xlaW-Nd^@_jmyh(cEC$`^W$;tHRl|adhDbz-j z3*I55(0S7qC)6|RKL5gt30E5te2v0Veht+(zGH$hB_EzipdHWn<5YBc+^~DLxYfrW zR*m0TN4@p-;;jo5xGIjs0HbvKQdyNZ1weG<O&-U|6y?rO@h=3<fs&yL+#D6|FdE2V z5o49xxYt)3%)kP>ssiVG3ed+DQekEVIL?C$^b*T$pG+68_I+HE6SFmiUD2ciuw^hY z2UGcLz0?8CCZmMlP?$*?_{>5OO|1mOMEt3oECN1J#kP;l@!aUA(F_tUH7-`GPN%3B z6>?ES+x#ZAxPrR0K1&x{<Et&pXp6FjK$AMyMMewGF_JuxK$mTadG(|k`dyPxYU3OH z9!GUc1J)Lis6t1XFw^QI7%#z0uC}V>mPKR9j)}$%-BTuxXFOF&nCuI}czMoyaa(M% z;VPK3K7!s-mKAo3n~GW_$=CS5dvtXtk27JgPcn#=a@G3!hdR6HIs*{fMTJncln8A} zB@kdO$@9tFkzTySbk%$0_|up#y@c(Oi#Go6ym?(yt1H6f!W*82_j?EJu8~IfAGC?T z&}p=`>4M$<dv393uc7nh4VX(YmE)_<|9Cpjs3x8^if;mhKoShSD_wf;0wy680Vzrc zk#6Wg5NT=%AqhR8G(`vs3W!Qkq#Hs<N+?nUk*a{8py=Pu%cu98{kl7QW@paM+_}&F z8LHAj5jV!gSHt{-T@E_A@qx#L5r>?FGG6=4v|qmk`}|^^ogtUg4=O^>gY*pzow!2+ z6F1J~rK$RYU>>M;k*T;J_o^^oZ{Mui6ftO3j7^Dr<nAT>STjxC8-0*<O41N>$*?eB zCFbd)%Gb)GiE4%u85acJ?p*wgP&qJxMT;kFpbWUw@qU?IY=E#*N}sx?7Tl);vx&|9 z9mO<*UDgB(vx?JNzxw1~*ue<1fs$?FoHD#OF`KvCOrmhonI5Pf<Rm?9dqSOWgdZzh z12ANRD}JW5T$gK{>${TxN~HH(ICw7IsTwMsac-F?ROdD%IEmy2cJ6(buSnZ6h)%AU z0{>{2?%YcN5&Wl_LbJ1{4$<xtX-3ad<ZCIAlZ>a=b}n7~_Kaq!;>nxEDv}dSh{t~A zY=jl)mhpDb6WMsLe<~8M9e{s531`Rg6;iljXpjqg(4nh*O`0(G2QaWZVV)D%FM_o) zt`*GQ0O&9#5_&}UQ73S*M<>X*^EK12x3RABSEoFmxZ1*iJx0N$aC~ih$<J9FqXX<I z%gN2NL|Lbl<$A6T*F=_8>a&KcEp%8ZGU0|B-;)7Y-5#Wd2C-mqG`JxxMfjS0VUvL8 zq+_DaCaD3G*6176w3ql|fVT~w)<NTr+k*ml4mV$pVk!73Tw0S9tiKR8=?jahCO-$o zH)~R|0G_r(O<1u3MXDQCH~@P|OKZWyE&xCZ3i=XBk=3FIx|8n#Jc4s1>Y$jTNLpJx z*RpRC9m>~+gp+(ZUm)RZDO@28*mDA3t|4rNCcnbqrW9v9YoMOnr1n|!Jzs_a1g;Jm z9B^d!!oe0fi8r8p&w(s5BVqxU6=sMGP(*+Pd0JSRa^2V38QdYrq$xV3R0R40Nw$J! zmC|4<jwvOaIdv%s_Z2TJJHj>%`HsN$xp=PbBWsx}dnY5OW)JpKldo|0#)1gXJt^)L zUuq0B<By2gJ!sYgLLN9IK^Bzv0ttP_xR&C`&Ncx}L~>6e^W^*zz#iluhOp;{Kzx!F zGGs3A&VJ?*n5>Ecm$fEI@#ejhf*+BKx>%XYP@sZ!G-o--0Dw0nT^fD!Ig+Q)5k5({ z$=;o3W+bd##J5n*V^Wm+9F;4%4{OK6V^Gk30O-<$sm{Y*Fxc&A@as^ZkXmq}0R|4q zE2ZVqL<$3x!~|Lks(iUuq-fIJu*Lsi9m_BjuHcq6@+FPij-EDxD!HL_^SD;=JwiCG zq_}G0Mv*X2pD$N#NlyM2?awUSRTFsy#~I?wQMU{ui1O)iA(rMcizv6PQ=tD%@wt3J z?p@_=t1k?)j@#bk%{M|Sh(dE2cUqu;9RN(#!@BmMM*ub6!%g^0+TAyUut_OIsT6`J zn%<irFu)}+c!@W&h9}{mnC&NTH;`Ae2Wg^lk4V8^A`xs8Z~zahV?ny4${yiiXG*dq zoM2laP*8eK!;iAlyeO~kOs^rXhP~Ue((sXG0#@-hn>5dGJv<J{{jnHQOowlT6#N#g z0BB_&m5NUd5=GvKj<uFSKzS$jVM7G2++}$8au##~8np+V*F;p%AayKQhZH?x{uaMy z#r4+v<=xj((-S8hkqWiEEk9tdSdd~ooOx7!jXIVPe^g@z9r7(9X(F&Syhzc!(c-cU zLb*q6RatjtM}5rJP^Qi{Z?_b@s~)zi2oE{*gl%ae-vRKWv&uIts2d836e+tP1?%!H z69wfhK79D&OiA-l;dN!vTOP0uBu~~J?4l=3Tl9g5RuLqGvy=9KLkr%6r*|Xaaq%$6 z1ftt=+6V*Q`G$9;-Z9tc?!#Kqe6GCI8tB%UBG)b6E+qZPy<dlijrhVtl;PtnXb7r^ ziG+6|p$;{O8cog%ERN)aI$*g*pgVI#3Xw%9|2<SU>M1(=0|rhH+S+>hrIxpgQQd`v zKF2@m$5)PMA^;j>902-$WqlchFJ3|bnw&9sSk`bg8|bNk6Kq)uk)%v(Y<qfhzwRaL z)=GWZ<TC7J7;opBN6dP7+u;xR`-I11^vr1Gh8L{z7n+DS3|J8>C)x<n5??LiR5A(h z{8w8`=dMuvEpk(-gm1f%%c!2;uS`-LK8`G!*n1peb1PT#Nz@Sh1-`xp1sg;|hiLE` z76+YCB<aQ5Iov3h`Sga-^Fnlq>c_@u(I#%KBCd&sWn<0?I^16c-j70*&cTOJ56N!q z7W9VBdU!vf`MEDg#WEbL1Rp@P@HI4g)zppR(uuELWP@&Z(aW|<p7Z&^8*PzG#_j!d zc>gl2MU%4zXanlu<0ym(j5`H@6~)$spr8N?=3>-7fr4JBhu<A;S;~0CoAN^53&xd@ zU3*Hj^G%l8;hi$;ZDfp6dq^U@8xLRedNM$VkFj9INa&~|g6W$O_Kl#v3?{Ll%`8|a z4PK$iIqKLn;K&%E!(V7}7SZdQY<c68o)&mKzV@aw7nEn!Rxl~X(=m_iQfcoebOBOu zrEU0_CSnSSc*TI#{|5<UrN=CTj{uUzzA)Ye=;1;~zb|DQ2Amk_X}trFB5;kPZrxMi z?OKL?^K6_8xg(G)g8FrTqqXr-DEH)EvGp6qy|9*<Q%HqmxC9P%7vM@nLKnCIbtHG4 zFKlS}C9ns7O=yUK1H*K<$w+#m>qGX5dZ(Z8F={(cM}fN#59xN>SrZZKkOF#JdC=h? zTqCTk#r?@WTjmrVt~h{CljCxuQPf$`3KXnm4pxDJj_<*zmf=J7@Zse?c3wnRJ)BLe zC`BqP)*CrYXx<zyYWjmbZd>#??5P;M$-#Rt1N78s<W7(x0wxZ}hA=<1!&|6abx3HA zBQ%5tQLKi9N|m$>A{LRYa;5Nb0vE{<VUdjFJ%ucTy(F<<Yz^>FSz}#z_-;Id->=@f z^o5FeAG1S5r>)#03BI~l!I=ziLRA(6CUL%;Z_-Db7_fyA#Mg!T@xA6r!&k$;2&&3J z%p&sB0_?{u?9;+nb?NW~P&S2cf9pBMo%g`X`)OMGUC;LMg#9|c!=0keU$9pabm}m7 zZat&~Y5d=PN;V$G^A<+49r)DI&#}{2yEw*{H$33W32^hq?7&VAJ$|{+RZ}-HKg>O( zIUtVUwKA!A>0PF!HicVBe85enF4o6-maQ(PKe`F|@M0)i3emk>4=@npw0lF0>57GE z#C}&3opWag{-gu>#GBFYh)@}Z%kGYS`ZN06H?u5rZZ>ILV>inyYbLy6=6X#|+cN7+ z`q)VQ)nRdH#PVsaWR6bOqahkkACl*#Ns(3QgXa=6>`n#nl~(f%u8X4!h?TJc!bC0- z;cGf@^X~9C^5|PW{QL*mnlw&E@>nI#lsA9@1_w%kc>l1ooaxIPL8hM8<BZ#bB;&OJ z!YIfS!F+`H?oA%pYwRMlBfOCus*@9HlYYAkH<49<)FM}R$IHxNdt=TSJpA|Ff!D~F zbtb%4BZD~!z4Jy*Ws*XtLXvJ!610pP>QK<0P|gGzXB-`(wU|8MSkM<*H*M5uHC!-B zXk82A{hQ5*qt%1V=AjdCC7*&PCWw98F~8k0zq^bk$BD~-kYge|lkz-P5=^P26|?~X zIuZJ4ux@R1>H?mFLg$RoB)PGm4Q_RBG#hv%neU8|S&7vepKcSfdGjNd|IWj@P)xaS zBto6xqq;bO&+poM4f+IcRUOz1d-UnlCj2nEchwPIO5@=z9XWShaFzm#8oZj>0t@&J zd$Py9#+{Og<eJOkaz_BK_ewl|QMBiuQ{FVFo$V7_oK8389gbKAg(LE_ku#`!?El7M zRbTU+LOj_Sj#1t0V!=E&Td7^hjN`D!d#|oYY`IiiioKfJ;aC^_oe-G_o#rpAaD3Qj zQyVV&h&}J_m9TL&ah{R-9$u}@xUmIcwIr)-<P_~=3>}$(OiC@Ai%o`)??H1N5kilV zFP?0+0*F<7CCgs0@)E3wGp~J_JD1LxSi>561j#0BDBB^W;vaJIK5!bVKCw7i%78!Z zTISW7r|ynj6z5hfMNSbAHp2+?VdmK4JS>+^RQS_wcKzcNtNg~<uWb>?-d)(L6gT8> zo$H3cjBCUu1O`9-rmg;L<Qt9<&Hj&n$suAlO$~{bB9GjRx;fEDdm&__%9qWucYJw^ zRQnGfUcg-v#vm04o*%Q!-Fn1Uv%EL5T6K}j8+P&Ty@nj5`Ne|<I*)bvfq6=_wQFR^ z$hQV0G=yH1;%Jt=2faw0a-zl+zktmT);YCLhF(V=SN$S)Vw^Yn1J{1n#K;(r$})Q% zBHNd9oCQlfJ3Pgr;cbxk+%dWEuMS&C^Ku@tBi!ESopSb%Q@k<u??RvYav`fJi72jY z{QgpQN?{H%>~RS^ddBfEyEpC3B68&yr{6GkcnqP%*>oB?fug_ig2kYgq3GdP;-fDd z5sXjY;T2t546Z&J53urTRvY;LQ5-_jj3nZ;ip>yI^ZEZ#96Q&(Guj#AHq^+m{94i0 z4RCL5gz`UdY>x-AEL2VcUQHrj+S0Y$yM38}$f;_(n#O=GX0*T1*sK=dY+!Huo$B&5 z^mVDJt@~LoSztU-uvGuCuQm{OuIAeNI=c6>sl;!MQ?E)qfmmK+S@+jPE$8|sxx62! zuKV|AOP(f6czg*QE)Wj|?{P5{k06AlUy?%w0oTUB*2^1;yabsGlO{5ELyMje8xQfT z%n%iM^+oQK>&~~GYcv8^1k!G1j1;?Mj;-6@C;vC&0ZcJu1TsT-fbHbpp0+n@Jw3aw z|301>d~#a%Wy-P13p388invus+l$hRhu8o8{d>rXmmRm%q87M$djts>t>Y`GMo?)v z0ay2uAfc&n6{^r%+=`Msh3Fry6huA$!LSB!@9!X&#(bh*V${Ab)U8dZzT>zAFp7xx zv<5}P-a~^rI{(;&sfR-oDoZ|!d6Mbf{xuF#twdP8jmpzrZCkb9ujKg2mZBR1&fd}+ z0=8|NOb!KTtDJzH_5D6UIEcnks3xdlP3NoP;uO8;89UgXno+0TkE%-`A3CNzo5*QL z&o@E%G0pq-EMZW!LILV_cT~j@aD>9|!AyTDrThY`=i=fPbj3yE*!Fr;zWvs^ok}qP z@Qq`lE#%#Oqc;lNoRy(Mu!xm<8)ZsNDF6E0_D31a!~OSpR`q9sHGt|Bp^6C1nbcEa z9}~%UEWs<5>X+`VOi0DSY~-_XtLOHg5(~L5@tZw7*Dqq?#bM~1!l^KK-$r=?d(+*) z$b#Q?$^AZ62AaSx;O>qNdgdc)Q+WR(>Y(}zP{{pIV4cb@dSCeAJOmS&FCDv>D)N>m zm~^i}K>$<l_g~4?o{ZT?aiXD@OD-|B<QoEV&b0bIEGHX>x|~!}Jmjy{+3Ibw1(s!V zh{t<Lf&fZsNQ(U~Po(H-+3g1owcB^C9|z`3%N1b6e>EeX1wP>+IPbLBvz}dtEVEi_ z`43E6_acJCf;05LIoF(g*m3!l<k!ZVwlYQ}9`E*IHh#}Rg|r=#rOJ<s0=Y^?r6I<B z)wg}}yYu>cdGD1-KL;CSiltre3gWrH@-Iv@kmVF87Id!g&*cy0l%>m90U|q4t2GtK zXEsy6I-}B$<q$Y$wx3mbi24rIT<hVLuMPBlN)@Y%<m#m_9D4%+I<;J^+X8>^WXAro z>`0Y};(y~v)^Qd#h3K<V?7gsPDQPainMl062Mz;}T#j|%L&1h$?1~bN4b@fFQd`T| zYdI-dSx9BEItIJJ1GFq~yiz>-++a)mf2S!XYiGZU-^P?Wm3jk~DTkp;Yy~Y?h3%8P zyd#2g+J0Q81bSf>jMuVIfkz{T>{kk6a>^(3GTo_cz#!oS=F=tG{sGgovmOG>xtQB+ zJe6*Q^{Os!((1zHbC3-XT^pxt0V6B5kZ^w)!Pdb{04$wed>qhifSL)gXNDB_C_B2P z+xd=52Q`((+?LDnkHtuw&6GSIwemztK~BKMo4T_&4cAx5u^fV86%~jG+&V^l1jj4W zp!-nSC_ir?++P~NQ?c$$zRT`xK<zRgK$r0oIJ9%uZ*A#Ss2LaDLZ&HBru4T6lEh*J zY_pc?D^G>W3f3o(N8$q!VRCHzXKMRTjBcGut?$dd981-ycY@=5&97BsgDoI=j%3#- z$GB<&Wh5G?XzW+{I4G70pwRYlXY$Lk28F92B3kb;rPo(^K?vsf6F@g-X0uP?eVWqo z$I;@SRbQd!EXI9Et9(NY2<m4#&4+zeD7-=zQ`nvDEzl#bdd|&U=^Qo9=5?+80vqtp zmsX28f7|s4E~c8NLQ$-f4w7A2Unlm*3f#}?zXP*qE12@~1&i-XgktKPvcmyDpS$9c z_R>%f34Ydcf-qxVIFap*>=Ebc2tBm86;dSx5MX(Is^*QqSVTh%()TeKK>eo-p!TJU z6R6fI|8>Ro-pkrOw`FsTsTOGwAU?AS$x>}}OI1|T__cTm{iP&h*F^Ry9Nmwqs6Yq> z#mV%?M#esl<xDl1=9}=w@cJ}TE!;7BRadZR#X(wx`lLg!Zl7Vc(Bq7eeKKiq_e4rN zGF&&cj3X~f;sZXjOFK|Jf3-jQhOltNI#_H;G0?uM-4}8{gXiktHoA~OQeTDwd8&gl z%vZi^>1<-9)|CC3P2{^PRbq?rSjCnJ8wz{D4bF5~gGqd5=S*?I)Fvd~wL^{UoND!2 z%Fd9^T?`SP9|Wzcif0_wlZflm#|n{H=?4REWydWfCIKyPS*F9a{(aF=DfaAr@w}pc zV`7$l{mE&z*%B1urDN%2o!%9={fMaOPI^Saw~h~)^=Rp&K{|R;(*vy<llW*p=3eat z_Z6vB{4vm{YafCsUby=*J6Naz3+`^@c|USt+x1*t3Ot%>&YNvX_9pB5o4t7R8XnCC zECLk6gKlI+khbKyBQik9zcJa>R(G<I>xyn_+L<fR>}}C0o3Q&;gx-Tp5Fi&ZQbZn7 zR0gK&kXD&%N-OdGcjtSy-HH|#ug9^8ulhots`+ub5<a;iR>M+FqQ|GJ`_E^LV$%0^ zt40|d3W<IphY{xMPxbz+$@(9$VSIn{j<X&T5c%6GsqvA?(l1)|d_L(w(YM1GY=BJ1 zzExF~;FgF?qvYj_k&9nd3oXB&h?3SPV^hW3b|7&89T84<Uw$JMuR8t%eym7Fa>!RY z$-3*n?Pdx*+&5Lc-xsN2BEU?V>p5|}?RA>aDiWf#o7b(4h<HYn`0J9;==F~(*i$Nv z-X%Zh{&xykY!U}X9_szmHxNEmDLSS|QG}-+bZNcaOB6CkAIVV?I0NZBYSfO=$3kCd zjr7SU)TSh-7b*N5<ZGOOw1j^Q^vYV-ueyFjK=J!l9qgH{daQc?(C41nuE9*sR3VXa z^wWex1R#ACO8y2HDtF4H&!hUib)F(RP=C6(yCIt(7BymBhZ1IBityszH>$k%>sXDN z_AqZ|ckW%sgyw6%il7j{?k$%(zz|zq{+-GK{ea{pw}z>NN9i_;KP#t3gW8&WGwJPA z_4d}ZsfW5@kY8JA;rLS@y{NNc9G+0E=**MfrWh8JovF}NA|oZ0(1r+<_q#9TuShOU zYR;&KyiaOL)@D$a$sf$AWm6>)^zP18vaL0TXFfENm*OpTs$9v0PnXF#NmRvAwGEj} zra_cc^<huP^&W_LO?luTWGeuATM;^wsui|Jeu=)NT6r?OrAD{<WTL+z2}eG}Ia1Dw zFmbeUg-UbCF!+dB2q3|^nb7S<)3|PfJ8Tr!JxB!2JmbfG<y*HJsb;^nAGfgqQJarG zd^}~F#E#=qP8`<y@deElP7S6*uHe$19NAvXGmWtpo4iD=A1DRy4iY`paL@eP#|(Yd zl5?4m6Q$Im#yq3J$Nwf(!l1Pgbon_NmN5+RWd|ayb;9af^;<ZCOR2a)a(=YFj9p)N zrGzS;C;|{n{t!*3Ege5{2ja+lN_rRMnx;OIudb4VS(sFs+1w^1NEaHmc|>C)Y&IS7 z8asXF$l>&E${YlTSB*C8jdr$nO(3Q+z^aDSSDw}@wUEdV@?kKP;>xhN;%ya1J=L6Q zmAgrf+)Ohlmb{_c;}xIUIu9w!97x+F`wymFF0P0^)1KZt^cPPgGKflwRCyLrZSahK z7DON)qO)p^y4=sowDe0plfi(T*-6v)g+*33OC;T-h4)f7A*rgIq=UP962lF3a3w`( zxh_?08C;<X)%?Mr6k8y4n`5OQ9@do14(eqP!E2A4TaAfQ9P+`DG2yL7n;en#vg!1y zCnlPgZW=a{M*cx<0HjTGIMfgTj18HdSaPD2>}|VY3X2?W4H30Xi(EE35^(b?hkf?Q z(a<#Y7TBXBIu~6&dJp2?1o>S%IFL2+?ho})R+FkgAf`HE0K+jV{WL(eU054Q)J$`4 zdBsX@r`KvkLUp3zZ88;m8Pm;2$fFBitTI{#&#jUC*Um0GI}B+a0ip>ao2VQSqYt-a z1Fbm$eA;C^WIG%hK1dFxivx4y-gW47R!!@^QG~4HLO3LfO)Dn3Im3ILD+qpa?+kU3 z`rhv4ms^ngVdOi`)UGcab5Lubejt--lP^b_lv4+AkdPf_feQ85H%N$KYo>`Q_v?u) zfGF(<PQ^Q<qF(*2E>pgLGNPD#^FHL?jssB5@yF9Khkoa1nCw*#h&>w(#i`BrI5jLz zXk<eL0D|=2TrOknL@~QyL!(2XFfHLV@=GPE;wUv-s^5xQ;|L7$2RTMbz1$*cX>v?c z05DLTLUaV5#1T<dywTO<uLtMS=E%BhWKStl)8Gl6-f8RC(|_`&kfRWTP||MwW7S0q zv5Kl#O%9wQMI&h%b>($xaSB%69yR(fbn`TxHAV65BzX0EKc)uS_21hj;zp=%!^yF8 zq}cG+Zb38Tz?n{EiYtL!+60Xl%y8aJE6wb(Potjw24Oq{hwnn7s?S!(I)zzNTph`w z;yS@sX0LLn;zl_xi;QQsV0#Z7BD1N4I?Ub<aer}4;jNXE0OzGOwRj76Qq{@Ot*Z7% z)QC;no*gP-oqQNRXmkokvdNyx!jYeZr$rZ&Q_s%j1<fS$^`6^<SY}T|{=HqXNewLR zR(EV5vD_$|!zBWo;d1kLU1Z+Yml`HcB>%KgxIm3C%xv0w9Vy9r%}&^p^2F{y{0Za; zyqQ?2X<6T!S6kV`S~Cw7pQmI|N6o2~rqFafDnVja9Y=~@KI%2Y&`v5ujnf{WTxDOV z>suJC>kEkB2-$o^TbvCNFy+^C3bN}ryx_P!M~;@Hcx@7$t;u<ncZ4_G0ZoSkf%%Tt z-h*{y{W{9IdXDHH<AlBw_azrAN6Q1kTkxW1o@GN+aHPm(a#!i(<hpyb<5aBsWYF8i zC5yhp){(UPbsCeSx^})WV>M5Zq+{swsl4P-AKJWd&>NzmU2mPoX3WH8TAFJ$XUzJA zcN`aGI|hI2rhSSai;$q0dZTFzXp(1t-T_C6B<F@6v@_lN*IRkvx08uK8tvfk4kZWP z?vQ-}En)d3BHdM&<Wwx-n2Pj@B%GaBrFJ<laduIAOlSNJZ4wikKXWV}Q-7h}uKj7W zkFS7QtX$L;>YKJqPL!PR5#e-&&i*u|MvZ3l8l%FkDd(V&UG|j|`pjr2^H+itR}|%H zhY!hJUij{XUNx%Fb^jZ;-ttOPENN$znx#Mec$8QGJ(cJr@XJ$--APIz!0ddFP?qZ< zey~-}4BGC|Z%v{qDX^<_rTyIS2L_E+iT?Wb)Evp)r_=h!)Ys7J+Bf(qmqj3YM>!y6 z)M)x5d6V4tnjCFSmVp+jcdY$6lO}Rc-prmFDMj(N_V~>gh|v#%obQ?bSQV`}Yj~XE zEX8is6>zeDtxt_&Sr4AC^t1jZ-cYiUUL44#)2U-gJ!iHN5G;3N;cO(pY5!xGP2H=* zY3cPk#I=Q(b?qX#KF>gUfs6`h+a+&iS_K^WA<P~GDY#D*P-my*ZOGFgNmeu!Vt4!9 zE)EL4PU^OB3R8UU?Z_$joq1aCLyAxRX8T~`rq>zoKq`G%QT^?ok_&UmsfW%Y4nKZv zsMq;Vc==UJ*r`6EWImI<tgxBqDi>gZ^VzhG&Vjav_}w6V2*TP~T_^bkEl{DgNr|iK z_9OEf9P^JfBm_e8g|_9jXZ~`87@zgWxCcbJzXA1;qw!>2>V`q2*R@Ef!TiRxYg@t9 zoKEz#%hlw^659<q>dC5{;(u|1*Qu{NIGWAvigVT@slEo}RWg6eZ69hOEG>HTJ<=3s zzvoq;@Ugo~S#Jk7ALFF|iQIfdskpv`n$u{G@H^GUVQ{@Y65um@Km|pR!=ZwU&&KEq zI}`ur!wm!Np`3DEOQnw<`AD+DMK}Xmz<RU`Hx352(x5wbY0-P@hk`tBT;tzME9|bA zJ=i?8E9(=eAG{-cVKG{Y<Tv`>;Ceu*J~i{fz$njFv?AGGkrK)uwhH;I5Nf%r4slgq z{PzZzDl*i3-Ktf+)@EbZ^hp>1<#=_JPJh92Y5s_4Xcl3;7U>??&GQ-LcJJ3V1TRAV z)Ni%1J3X6xa$b`2V)5?J3oF)TpVh`fAi2(>UaOhcKd9Py$U^Xz3iuvdaH{4jEem^8 zMDNExJJWKDL{yZC{zM#{6k|;`DrQ?4ZB0BoQtIV&n7C@Q8~rDa8hAhs0UA`{n|znr z_>a=LPM#NfXZ7SgyHP-Yk12Hh?v7g-n@S|R$dd^2-k#W!?cq|&LORlVcQh^cU*t)H z4uyE)s<V67TaE`g(Fn?=%+8JUnl-J59-(Re+l;k~JRH2k_^QVm<0B5GDKXz-X0G-v z&&ZH-``<y9ARi?;4cdsh^p(N~9^c;cVB*g~x{R9dN8kO_Drsh;KzVO<1kj+xNC(Z> zg_AFD%G-W^^pEH<_vF1Uj^xs~d%M6ta_*_K6%<xPGo9HI7Nnew59Ysi#r<@n(dk!L z^**(_P!1&=jL%xOHm9jek%DpF&Kh4+abDU_H&`m)D36&gJYnam;(9U<JU^?feTT?K zM#bx!SC^%Vdi7r}+OW?K6f1gb#L6S#R!Z;7Z!2Do(5D`%E|M=(nPX+&6HaRzTe*i9 zukQwXRbCH`ivJXMea(xYai<{iMmVXWB|yn6UU>t88W7J&n{&0^O?nxhHTzRdYtK=g z^YUY+a$%^*dw<ayn_>aSt$$W&gROb0wZakp>4TVH_6F_buXhK2xpFD{_K_X;$<txp zgG*s0?_L?vt4{f>^^Lw4()S4z{?-}$vC=9*^yL*ClEdI?L+SXh&Ud+faO*Av<uYE@ z_XOvVeaxv^o5+H<sZ#9qgoQp0=v*@UklBAtoz5BK4vdZ8qZb7~t`E#)9Q`}MZz3;L zy^F#P9eLRPlrHSssr(>9U6$V4B$&8P7h*vl{w%)aJB$uSg)_d%Yo=}Y#hA*YUY+&= zUHkF#uk@e1-*JIyKc4(a-3wS2qWszpdpmIb)v{IC@<*dh;#q4-VVqV{;2SB2q(8i| z>~Z(o3NP4a|AC6S={=l^CO|$lldVVp{rQk9Eo7MprbaJ8tGeaJ1dJm`TR?No2%wkx zw(;BTn|0Eb={)UM0_GwX)iAvB!8<~mt_A?ysxh!c?N0OM9=^*x<cP}ALgTAncDBBr zWYIAcKDE#T#mP#WBJGIn1EuNea}T#GT}M3~!aO7Vr{0WuDV~anj8@?U-WWzMH167Y zObGW<<P0Khx70RdBUPjyWEn<=zawA17Q7G~akK3(XFl>=#Lf?`^}+m;=bwcC)DFJ? z8VG+6Z}7bI_ze)RCS2%P{VZ`}11$CA<UmH}bnvw34<SPIsO9&d!Cj}PkvyFI{jNE# z4VPzdmm)v?F*?|se0cupKW7!!I{oKMh$>D!tLC}eRSWB9cWnz3rN7I>?pO5C6aUNK z5mao!ubRx}=L*^yU7O)DluF?ci<cr!MhLxenTr;%k&3Bw<p<^hr|k5<6@$+j83e6~ zM<H7&dDl->X;UJA%3ItD#(f`TZhXV@jfH7w6-wn8ZMVqgn(`Fib*)SZ9(Ak17Tb8D zT?butHhRHljbU#G#SL~l4T|xnve|$P)2c7fi-*`NY&l9B)E?J#v)WdLI}vRq_jP2? z>U_9Ff6gALH*NCcLg*4L_>SQUo-arzWxp^#DRk?kx6R_>10U>%=$pf;$&Wdm_16T> zj~EJd{Zy*1$S@9#opv<8t>+ePS!qy=E%r3HlQ2AqS-qvRmMG6XfKVvj461gJ*`2`^ zFP5(JVvBxFBTjBB+9*GpusNmn-1zMMoB3`o=Wzx|8$<g#GY?$$16)Xxkk^oL?W|ft z3RE0;@gvmBigb_<w;KL(aL#D?*|~Admdh#4ZVqwpyV|b+<ipa~_did%(qC`9eX&@n ztd4zEGc|1J-X~b(y|}17@bnetfND*9VhyDp{`z#Jnr;0k%E2sFCTWftee8&F<~EO2 z1IDpBA4*}a{AYEqi2jT)7#;jIbyny>&l$ZX6S?}vm(}Zy_9bNE8Bb-)14n}z<fN9< z*~>CHl?Gq`=r2aUGR+?!-yt0YPh(?>@|LdzxLhg@4mf+W6~(5R22}nQ1R6Jf*V(uC zJ<6X$3eF%DDgsM_Z8NW=jwx)!uQe>h+_`SN{o0sK7drv?Do-X`%?)DXECqfzjJn^< z(LK~}avaP7*CVB05NumBB|(4!aCLWsb+IP)z~5o3;1sW0P1sA*|H_TmjDcBh$x)p* zw@iP#xh7cNVyse|^v$QARto#}HtH^xALh~naf5vh<3Fu^{JWkTty^X(UHFf$n!#Zc zEIMpmJT9W2f63c6dE=|4@_{Djo3t?WnT9z-xB*XuRDH-|z3|%msr<H03pt6J>~f4u zYja&Cp+C=3eX^mrG%Ha2yuTDORk8P>A{+3Ew#;M->t4dKr8a$qcs&3a9ut!feJjN| zQ2!;LNqd|&`Sm<OcQWfG31cz8nTfw0or$Whls%|<<;y*nl}II;>z|pub=|Pn^h-l7 zD%z6wuCz5;eT^s(M$)&8d3;`aBX~94L#0-lhYVHqD83^MNNZbi>3t4v_qR}Pd4G>P z@1eko$Z_!B>S32pP9psTYhKVE<IqDnfHr2`ug!O+!7;Y#%5u{1=SgX9Ja#A;wAgPr zTrD1HJ*?k;rlef%i!^5XUiLj_39mWr2Yy+2O5Gm?!=FDGL5d?ONRxh@j*4un5j19^ z-m>%_+JaggrPR(vQOcM%?*mB*kgSK!RvR>T`GU{5-n0!rxHPKyouw&_rQqX5#?sF@ zCmmxaXk}E_la$s(hV~#jP??H|*!QAwkEV8KC<5W`BjPQM-nLzVT5a_tC*=^Q#^#Em zHj><RW5j*)W-1~Isx0XhedoAJ?R1sBiinyP#7HnMD?oE!IL12lUp;Tj%`cT@Rtf8d zRCE>(FGX!hqy*Cp>T|X{3{+hstl5tnm|p)CnA0$5VM?3GdcI7mx&Alo`EguUfNDVf zR5e+>4bNdmOS@ve@9q>&6^zBh#lbG61p))JdF!F^|JH0B2b>%W0<~q<l*W~=<~uVQ zo1dHV9c`bq<^mK`#ir;MVw1=WANK&UhCiaVB13!&N<k*Ew;-c7v)LJP=1yj+dEUjG zjpQsglli(b{cdy?@8vYD&RDhho;!43nw!Y`D^;4ew6c8(tK4oa78(z_vkavt8qB&c zI3<hN;qXk=G@^s~8-7GU<1>a@0y*|nCW3))NURhc&}2+Byv}&R6zYO&XpitcwvZFq zM38lAoieRr(TKwi965@=S+m@tw<~+z-@s-?H5}6`{z1A|HQD%4p<HVA&(Jc1+Y@VP z)4^%UY7||Fg<)*NH>Uk{Z5LgW{EIYUU|s(6w!0ri1<4ei!uP9W5Bdx7bG)=j;A-uy zz4IuDEo0I5NNUWh`;D+1E8xE~IA?uFA#C!@U?1(s;Ie_{7gOpG8LD`kyy2TX?-GI^ z*U8Cqf-<$0YLzqc>wmVo#;$o6#>6N$2kWgr?-h>OwD3IcujkWOA`9Gl^(i>^c(G91 zOmn2oy#(}zuj9Pv$WcW6<dJ&=#1KxcS}4{ExM`Gu5!16NviE3s{wnA3+(RC(lQ;Nn z26uZaSj&eG^y~6Ex%YcVUYNaj9P{|&#Xn4uu^$#vllADIo<@q_I5OOF`A&SXzAv!R z5^Ij_*S6SC2)mVRofL^)*X0l#q-tehn~0y%FS-jO8w|1W4VhG&`>beHpNrFZL@-Kj zME)HYpPDQq`bgvC@3x*wRJ~--bOdOg2`>Ow2*1)7I2qUX@w2{obO!%jmdJ;eCpsgr z0I0c8$ns^yO$0D!*}JaxQ_a@fgfHglfx;SN)v&gqn5?=!Ewa+o{)C*}XnIff)B_!? zqYBRn*Zh+-HRGk8N0}G)F08%u?bkp}aJ+p$6eS$?B^2GelIX9Z)Loiqc)2nAsG3OS zL~T;zAqG_170;um7t(k{NzC@XWiGxXf3@}Nlf>CC*MyUfL3Cm#mefi2_K+)k36CQ` z-(NIstS%xe{(C(C{#TSth`(*AM`P*v^GR~<Au|5GXFt9^f3c&5k*41G`PT(TnPAE$ zQ{r4VtoG5C^din*Wm@YvMfIWEEv(eV6HaHzbB3b3Tw~Q2XHEb>_|pKZYu`BN7d<4t zZ-Lc!h%2Vd!tAty=(%&gcN_gu^|N|5Be*ajONJ&rWxM?5q}#QlZ{BB%nX6$FT5^x= z)974u?k{<2-sLd=6W}k*|E_?f_rOmr*eUX!xir?^;GnwQq|aRk&$oHls?29KX|Lr{ z|HU2(IUI#aboRGYEpywid}k2tz01{}EvxSlRiB|F=WXvrNVG?n-r2KP!g6`x%q>(& zdQvXtQa05}IrsyNkE#{c_XtwW?;ktc;#6_s6R#S(ztAN3==Pl|&<{PZ4zy=N-oo-P z)UIB_u+nACoz(JrQ8F_1=b-cFw<~EQPD%o740dM+{M!>{s|$lfRd#==Vdl{j<h{|t zCKyG{9`!lmIg%(lxAk$Nxf1EE?H}^fj*GT?HhN0-$N89=HW$5UY$vOyuFgv;+pjG$ zh{`^)?S7c!-e~k9vH!W0ZTO<oroU6Agp2BeL<yLshJDXIqL@z7GwIdQHQ(1fbndr) zr+{)c!Sv#GuqXeyNW;N;*KZ!duT(m~s&bVW&ozx5j8sSWasyMX<@k~G*ss;6waH%M zLiP*H3hQt%6zQ*=gI%;h1gOrsSDvTMQ%Xz9f;t23b<b!~F^AtKPuJdZsLZhEb34Jc zj{4543=mY{RVos4sx4rZL85dsT9_rJzKHq0G18Ki{?f%<!=$I?@oS-LaI8s>)s}!l zxKFw!#DJ74Q)#}=F~l-0arh^9f}_e&Xv47)thUKijs@|Lpb=ureP=j+ny#wrQ}X2| zKTn&hQ2jM@d#*9qLufRL348Gl!~%&?))oGMGuI0zz6#+4gv6v;4&{;AU@Q%Tts{ms zGL<`s%E1_6_Z01Iq8baVKBnM6l|4r*ze2K%YZ+G{^}I1Xg59OIM8B`A&&!~%f1W0R zvIiudgSSkxt%wg|F)$_Sdt4b9pc6x$5LM^E%2G^0_iovGj4YTC&K!-$vl(j=H%-91 zzE)>J3~^oitLtecAr^X$QU>X4af^4A>`xN5sS3$pTi*{#bg;5qm8v7=xMsH?0TV7G zr{=z5y$lX)Ip=H7xgx~|tb<QZvyt%TdUYFWmFWIr?1Gl_Yt0@75f|Fx+q01BtoP8A z90j11sYC-SvyR>e9rggEvMh713lkeCcO@RaGIz)g2(SUqQZNT)KbIkZ9NR`-A1;2R zF*?;4Pt?WbUy6q_-U?s$=+PLhE^)OyIlZY!1K-)+R4HYOyQg%F5>>6mvDSA4hnZX0 zEY@_70%=1_F?~SpT)W%{v2R3$#@;1dYOwy<T2g<B<#rAZ48&qi)+s3!KahX+K$0Dt zi@~DB*1_}H#^D&1N^n%k@m>IxS<F(Md-c;|bPr%mqlP~BR#(2?CIo`3;xJXg+e%Vk z{`C#nL86L;B2WjmC2iZgD=vn^yfneDGy{66)^)5EHQm`!$5eegHqESp=FQp`Zm66! z80*Yz4F*5WVJbO;PZ(~>6TqtUL$H$X2W!nREOP5RlE=V0mA@Da3{JhBSamxfN+LZp zq}j|B!MaC@3fKEvEbC%#J(6?8$X9=C%OOhEf%s!Viga*XV~xF{itXmd@9rCF@E!$L z<vP2);+zOjZ>KHCcPT4XH5_ah+oSX2Vej|400E-CAsCAS%h@sI+{5K@M**=+ar};8 z3sac}PRW1o=!o0Kr5!o9w8DuR(37&GDNp0s@RyGk-lLiTn<0E0{!?|qhb(Idmcue9 zJeB2Q(Sn0DA)!q9XG+S{2c7C4t&8i*EZNn15yh8NNtJAd;b1M3@R9d@I+bW;l+)DF z5*)>4z8ty``N`?eVYjsaQ(B5?t;&?aVzz9E3XV)^ceEhkopKiOC`9rkRn^cVwG4@o zW#<PppPbjj$Y%BY1=$+SAs8X*AC7A{?4VDe*rfpG5v`I124v(gGPF-J^iMK%DT0Gr z5_HT-$D=OCW(%dgzBkrKvUnJcGe-3)Jkv0Grg0MtXjQZIdcV0Lqw#N>^hN#Y2Mh^C z{v;#El=hBN*aHoCq95j9PP$`uf-z3Zj~o?f`in$Ke9tMDo*r_l5datsnqygZI)mr` z<=~x`LBLM;aV++$u?8SPgq<YHyEDa|LHzFBGQbg~hbWH)1BQDSBglFp;oA5Dm&r9X z-9w_7^N^v*&V3&^*Xd{nR<|U!_eAo0DewKSGDLYp@JCOyFo2SC1Y_;Mw)98Gj&Tef z&7@MtARDP#xztVqMHizb`IY^6r6!>JS<vCBlympnI5eD%z`~GPb9(#Eg*sI>d}p_> zRb06>Sy!9Y=dQ@!JJTS4h&^!tI{qg`3aTlo+07T*Esi3}Q`K#)!J<utcaiqWSd4aT zS~E6sWQ^SUZRxL%_QFz%`Woms6f85?Ehd2GtxJ(~$H<__GEv7SX_ne`d7lnGXyflQ z->$2zT^?tmu`Cd<2$CE;YJw>i-_56)BJm6@BSn+~7)B>_fJMz?Y$)Z_!&#Fu_7a|S zJ?|7T=N^l|flDYM+@B`B7<K&t5P;N`Ol~@nt8;v>+rZ$nH1f^q6Qf)|hff;_^D|^C zA+eG@Ac<bI1Pgsagvlq+&380#{_DPU@6KJ{)I4{5?EzC&0JMu^lXYpb{H-e9g0`9h zNo2(e#-~WoH3eU6w0iWUlQgk%Y@}!F+V2kbuY-W2_-0zSsPh&3ffR975YHdo6Pwz= z-sQt{61X|eT7~>><8S=tSDZ7uMQLdJToBJPLAVZdoQ0OyYvdA^Tyn2^bU-wI3+C6& z8Mvk7`C?a?0P-pa3AYfupMua<SRekocbyN!<jr5}Vt9M!adU^Ue&tHS_-<h;NCXE8 zh)EG<fW+f<0h|uDUVrJ#gl=G}By?zM1w4N_?vleLAyltWI7m1PB#c9Q-$)Uz2LYvM z^nbly&MlUj^ynj*r}r^p)hTM;B>cwr7XK8XAI(C(=#V6|%T17Nbu&PAch@zSC7e+< zVT%lS;pLwa7lszHLwiT12xFhem&@EmVWldGk%HsLYh)aktCPGad|AB$c4#47w}2rU z-U0x4G?v;eB4MDXTw(3pdkZ`Z=K4W6j7T|e#cv1_umcGhrlhU`z>j8<)fEvcT9hu6 z<Y2BrV)E%?G}gOEqg|-BmyUpj0(L39P&B;vkRXHuMZGY@lDb8lf1G&2lg)+_Tx6<s zpf!4n_`dz%26sEib@Q8a!$(j@m(WfeHoQCISYW9mP3Hit;EYzT%hNbuZsS_LAl*ng zG~WmS2(%LK)aW=Ov-z14>oM|jsYUZYm6#~(B8rC{#78pXrZWVrQv^`#LU!E_`TWur zj(U|uNz`D%#op)aZAQw*6WwgsI)?Qo;n*VK7@Yyv?JhDv+xm7t_&vg_ma4Z|b*)!5 zqrzBkl7X=Mg%kl{B@BtF!OoHsYVtkebmd~~h0?(4dIxW_jvni}BTGI3PG`Uf?PY8z zzPVrg?3)&9BWkA1YX@Kz@55($BSpLyPJOE}#?}L{I#kO`0s;V#a1fx_UUIoj$N6XJ zyG&Rm$e?$~a^loCEjt(;0B8(Yi!o9n#ooK^f$ax27q$vFbIl)29lVFGVJfq<t!MU) z$%whxI-6PbFClLLO9$WwNw#yw^rTzsw>vagveJ&J8F}Z2`QHwIFh5<-mO*E5K0{&G zQODTP4!9!;YE|1&P=~d0ZTcL`8^o`hs==CMo%cR{&~vKPoNt@~sRsbfHUx`cKliIj zr~S3tPc;UIloFfF%wNNZz_|s_(<5xyQZ|Kf)Oh~Q#0t2Ze3p+tMti4I_1m?_e|t`& zux6;<&s`{J{h={-jxai2%{G*;!H8Cd@>xl;6}4Kaaha~)_c{##N9`$Ac5|+`KlyY` zdk&1(>@iYHjqL1JGo-P`C%0!k&Hk`0mz#@`0506W66GEhE>{gKSml8D$-LJ&okUtR zjo4b+6Mi#1&h{jiwD77rd}t;)?Fin@=8Zi9OQqc5#OPKg{a3y)>`?w>ct*Dav^F)v zmM4Mo1+!FMi(h<Eti<LEN10QONn74B%=5R%6xIr!ZpjO<$~}Q53mD}Gp1FBaJ`$Ib zA7opk;fFa8RQ1zv4T%K#LKsCoR>jHR64{kSo9_10`kmWutv$52tFSCEE(mpb<kk>e zpg3|^G~pAc`4%Hq_XvZ@Oq2}x29a(G7|0JTI5oL7)p~XR{p<FksEgH1fX%Fb#G_h$ zEYWO{YuTyMcj!GydmE-??sr}5(o9E5%%$;iKL~6FiPyXoC6-H`gYhc@FUw3D`PD?s zSudhL%yfEPRamldap+306=|9vWMAN6cNT3T27)xQ{@qEu@^QA|(g$()o?1Qh=Ea#I zO~+dDNaWvAC3suhc<SOn(dlwC+X-f=pUqmP+ZW2}x8=T~)nt#4LZ3eIKQ-&(4#9VG zO836%hI;+lC?aFm<V$qL7PtvsGc8p@cSC>LXs@-Lr!iXrkBL5EzmZ+xiNQ$?!TU0Y z{_l&tmZ~=jVIV`x<{(_w#Gq`R-MJxH>dHnT3WbLD9Fl6}ktZ*)*GXMWE^!*t=!Tyk z*^Xb4w{<-p@<ke^6^P@}6Mv&cvuZ2V644(RIX`atv#xeTTW#H<*b2JxS<mOVHa}no zb%HnnmMWUr&cW=B<F;C(&gXOgB_9a;#LdfRJCa%*C$uld4Cc%#b1<w-HJ#p%oeg>X zdgiQ?#Wco<t#xC9Jn~0iA^=)qUUBM#%Y(UqI4%J|=SHW?n~<6d`%b8miQFR3dxH8b z-{T(EZa$W<2XyUA*S?R3&PU9?Eef0%9`Q^*lS&JSt+FmQg7QYqUMf%Sb(3;Byf(X> z%KKf>rzS2Mx9BCarFYR*nw#7caAY6yvfH6g&y&zR9_y`Qk>87)+ls4%Y&GBlEV5;G z;p-HJzrvh(yQIg5y9s7W&KFd#$Mllri9!T*O(%p5n(IvJJTWQ9bGt@<GD!H*6%eYZ z4g`H2=GtamWp^(<r`iL+R2T*T+}wiBwJSMyLhIVqMW>1CLtDFzqs>*)U28kPgiN8W zK}8Ma1z!7o{LO6@p4WMTbM%P~8~75*IOr{dk(+}|FH}PhJ_MyE64USG(0L!54}UIH zua)3jG$mQaaZ^Qw*;i!Xf9&}YMfKQ{EY|%7QrKJSjhL`ctdg}a6*zQwCT*H*DmmeM zn<qGKrS<ba87wko@5h?>YU0O>(1ac#*W+plGT8G8*kg~C{LKW6!dLV^l3Two9Ufl5 znt8jAaff7-Ssdq0_dNJ4jR;s$`+}l6$E$_G*_S!As_*V!d7O|}Y_3cj;5}vHPh`cE ztB0qgo7mA3JRkW&{6u=*WgQdtO2P`yTt#KBgZP{32h~+M3m<tnk}Y&)a5+|)7h_Y9 zFO8RG)U`9!kM>cy@oZmjx%J3K=4D<>kWmlz>vKF>b~f)VSYV2|jeJ+L0G2<tv5@=t z^}I0Yoz<i4T0u`*Ll&Y&S{>5>(VvWxZDaI`S8pOO%<W5i1swKCqoEdGHuCZdNL->J ze*Jcz?jb?|e{pHB4Q1{g8SGbS@#WG}3!c5Kd(YNY{91WERN=rgTAJvI^k*({SmDMH zs-lA^(<cs;RvEjd6i{Lp<QiCr$m3AQRrG%e&(4kPwf>jmI{1EG8rk$?O|D4PJ{rS* zGilmFs*R9|H6!IV56W4@qN(~j_ihUfiK+Nr)pN_aSzhlwr}`gtT-^jC{On**;ytRJ z`U8>h9Hpp1`(SYO`^|fWBn}{03FcKh!BfH7wE6=Pa`ho)eX{ct+cRQhJb9M+1aD#P zb5uS(A|RBMOcD<6&d6+RqE)9WT7Gwb<%ri2Oj4~8J@mNkEZVhtPdAN2CD4xpgL+*e zv9hLKOf@l^iIE8uP*lkBwAH@uToc5xtis}kd35-zU4Ztf;3{0RLP@!e#T=nx{<cp% z*@aVZZ0g#fj!itxNg5o0*~N-XU3Whrdhv#x;CE!;IZ|PgiJXFa!$2@!VN-2Pjcxfa zZZ}7#S|Z2L?ytE#Q?krana9V|SKoNd506$+uW%^T)gMVq1vOgVpwcq{!A&H#iMJK! z8!(LZI_`E<ovt2X5tgY=zm?JTml||Jnv+s2BwJVCCoze1d(LFGjq80Lb8X;WS<*+k z;@AP7HhWsV3^K(~^{Tx8+ma{WXhpsjo<m-TOJ8|J{I)KnsRW{-8qXkIOvDhL0|Tv3 z415_r`ow;IIAffzxaYHHpAtaGaG?_gU5isyr&ZqN(Dk~);z{<$J}zf$&c2`%EQG;m z*o1yykL36LXZ9)FyiZqY)zLMH=3g$ZEJZn;-59jHkTT<jya#La?Ms<>vwR}T<9ucO zppxr;hLL-U;FAz)hAGiC<(Yzy+b3$oF;VKF=WM-qvrf4^$lsY=RG^5qUFN{IVO0kz z*UVP4n$F@vGyR{LbbY=56U%*W=O?c#!G$Ug_Ro_L5h7IwC4va+1_ptGzNZ>eED#|s zln{YRkv`=%O$$fdFS(&?x7yR^E?^GbR|M&RUX7b%xJdRr>3p+3Ma>F|vI&^g1R)fi zmhq=B{CPZ&b17p+8-BK8I=2NI>$@eT{cnJQ$CegJ8r?f&+JaoQ<_^_?$YlrD?VRIj z==>}hdF_%FKhMwJm#3q-6)HjR#`U?VQL2}25mp7GP;!c0cQ0v}C%qGVYX7qQOS%&> z3GrQ~Pf6}<_^pn6un4?G_X*+`J1@D;)Z@c1lp>=`E_(A9ZITr1^B@Yb%=h_m)Il^~ zG=&{JD}Sb0O8!$QeY|w*ZVgsmB0t^M8N;u43@Zq&NY7?tsBf5Y$v+ccmCBVHPxyXC zc&R?a^(I)LTr*~BrAxG$jehvPh=n}~bxPBZPZYRY4{Nu@aHpsiO;$)on8&%Ai6 zr<MDA?Z0#Bc7a4bdOb$i><E+cpSZkK)S!6BSbo5}F<9>4*U1|>iGxr7DVN0mT7OKv za))i1k7uRh40RU|2>g?)#3$7`tz5m_<h5RV>F<7x%uoA{3htPUM7w8UzY1HfttI5L zD;jHYKa?u}?NPxluMGNU?d->MzT5;zX1g*v#qmGd-ZQAlFMR)e0!c_A@FetV5_&Hp zP0%D%Y0{*Z(2IbesG#VVl7vvDcN7p1q&Go84G4mO2nY(+fP$ciU<DhS{r_ine!Dxf z?{+3H^6Jc)J7>=G<i4-#a|x1s3-7tleX#JV1SLL?{Lp)I>F<~+j&JYoyS6CWJpW(B zj2tvsi)s7Yi|hSd721*@u+{ouJ!)SuXJ4L^661%vS%ucA-d80HJZ+O>eySg?`)D`( z`RdBrzMv`?)%xL=8dOCSZcV}A$+)Uk)N4HG)wWM<mouz>uF18n&joYZ#tILi5zA|} zQCvaoNE3f7fXCIg!!_F8D3WpNIk@&=s4Y>zav7tagY#+wDsztfA{?03B+j%GzAQ8G z)o@4^>Kz`G9m3Uu#H)5_+vKlRS&P4HxsDT|O<Nz<LcUyW<rRS**!Gha_m`I3IRM}} z-!mkKu)+jf2@9n>gvHnF1MJ`8{#%wcKPE7r)RP4LRs_j2h$a@_O}j4~1Lc=$41o)? zvn)A75Sgu(+#14$XffPEu&NN;W)+GPdW9dt)z~W=4soynLf#ZXsTzU({wkC@<WH5I zcz~AP<yk^M7FZ)oO;t;+BuTa<arVJ`ZzoyU4~rw?nn?oH?KmkeTuIFj(s5-{^s{bj z+}+OyzDG;k&gEp&No_An?=Fk)`Vsc3rJh$yipEI)sy?8JNWc*|d4iZSew0MAKq*C> zn=Ii+`Kw4qm7l_W+vbAJ9mLNP{v}}vE7(^MfRoMxu;jxWrQ~;{Jn}BGWr!dI*Ib4A zh6iy&SoPD&n@y-ATJn55gl<iN*DRFP7Yu}r`4l79bX|HL0z4&410?B)PO14M>>JKp zboQcnEt&Nm)ak@jwM#+pO4URGVlalQ`i+r;(xw(}zf~I?WQ|JtiN48^?#VM8hX5<p zgwamIeLscw1T{z~h^rRoC-b}Ah||tjk{vqmHIZK)0<`Ds8#?J6cEWM_VWV^4QUsi; zgF3&{K`IVV{6g3!9N0>dAI+0quO>WMmVUh~MSOA*Uac=-%Kwy#d=4bwYvP7Ol&rKr zDEn#beNld6kGmOz<*LT{<;w&d)Z0#yZXF^>otD}il4e6BUqnl-uJKEAf&Zu=kffdJ z$oHiR1gk-De@YEe<?AfLDqqR#33ii(dP>DA?;N^!P>&%XFP3*;ogn3NT3D$7@ARIZ zEdT;!{&!SlKmI6$bW~;qtQ|&kbkO^Mamu)PEZ_2n{zUi-Ep?G^x?c$TpCNjmhNQP3 z2jmMVGP4w+5PsS>ex@J@UB(oV_+FDh)UtvU#q?OLayAYyI<4#_fSapAfy>}?Ei5y{ z{M3CcgrqMui+w|uQkl0{X7I_@@c#n%-vK<$q$3hF`ko`o!VtuDkc^F0a)~wjM8#z9 zC<+j)N(F3=${d)Q$DcZAtD+ON&gPRn%MSqj+g1F~YIG5mlho-10Ze4Lj#M}+-PFN7 z@35*91kyWEb1ds?0uC|PDYNqqNrF+b3y!Jtm?9Q>m&*V0E8+5Y<LYFYJ71Oa=5RVf z{NI2CRFbKgpo>9@%YL2E*=@X|Ru77n==7OoyF(==_t=TN1NjI_xjGn-4DwYUt6n%* zTj(O9zy~Dq5l`6DtI)qlM8)q;gcUm(=+PY~r`0ZUdKY2$toQF4Zz-WD_94C%fKSxL zC#DJkkOpY;gfBe=^```nTIz<36^vjX19E-@6U;d!7D3O1%kS0Ma8Y4E^c?>n6?v12 z`N8H>J|uH@!3<aio2f`3iC?E6(E5km2Z*FOCFqG@)JuS`M3-+G;JKM-OBfE;Sn=_N z9)VV41_2%z89aS1)SW14FD#o=WPE;&mtz!onTRPW;wvH{IMIA73&aN900=AGkH%ln zg4#zxj--8y8Y+^TSynZxiFnJ1d__G;XQ67J1}(FRTZxXJgw6Y1obKTHf3f*rck|2Z zMVn9}t~|B4(GxPkB1{00OC&_+0=mS-10eJ5QjyIhP+x@qOV1hOUKzNEoOy8w$D_|_ zK}@qSH(AI)J-(OJ$R#$Beb(k52?X#4cL0Dk@2FN2f2NoC9E?3q^gAi!cNgFl=i(h9 zabN(vcLAOvYP|JNLeVps23_;56MTlT=T6@8fRG%!eyU3!3cm{gEPTQco3{uEZ^B3F z)tv1RxtI%e{auBo0etUBKHj$o>xoG}U1fs5GC3`zzC<(&;Jryj%@<?#t%`ZIhcWn? zvr=3sz9Wv2=P-F)s9z)>t=$-J{S>uhXu~+PxIg+X{t}(dp-}J+Cnh-P)8&Y%`L(E` zM8CI*d>%hz8r@RwhoRd`IM@he1qpGJjUKK_(ObEswi1&I_1PfVpZ}h`OrpQhi<ja` zYFQ-c_AxsFpp%4dcSBpoF(Ir}2>ZV=QQ~4%)>m1+<dev&ap@2Bv){WBXR5RP6wzPY z(Cv7*7YQv+$uyy4L#lG`1^T_M67Qg5@?7Z>$r#dJ?#UfyI|<#1hexxJCAggZ5;=PV z8#bFa?+lVnDlFEEG~OeOP_v&bYn^4lT!v-Jst8pq!hS6k1pu7Y(KITYMnx*#mSu<m zGq=j`(ZVVhQ<s29iJDmJ^St7e%8dB`9)D3?NQ!=Ac2$lGUb2U*08q8mYmH(+Fu+5j zmdp5~bxLI>sxB!ESB#Ee;ta|s_jt#F%1Kfsq$;6hSM@zv(xcS-?#>JVz&FK!z(koc zHnNI}s%IfGNkuo@%T$Jo4kp(e;Hn;@Wj+QxOL378Nxb%Myp*^E<HgD`=RhJ3=p)0` zNwNi1NUP^a7ejc>9-$o|Zi&i{^j1PhmHcJ(`R^{}FQP|Ch-h}~!{P+UZth9vkhu<X ztz~SUxJ+UdAsGPj5?c$|t=Bw|`xO9CBTn=(lpXnbL!u^Oj8s3gWcgeqva+PeM891j zIe+L!<^5_^0dt$LNm7O(2wg4&gN+cUAoBp2KdG*obgd4MLG{Zd?-E9OYkrO}v)p)# z@bGRHx_dVTwpSxXk(52?C!Z^!36a+W05=km<44PW!2?uvUBV+wFT#TXpiB(7>VEB- z7_psG3lG_Udc80SoAjlcX9k%~08ccF*$Z?+@IA(^R~M=kFl!>7og&iyh}ZpnQvS7( zB%a;hoJC-OBn%)S6<7MbDVb+39{<;ylG2y>)9{X8*&Xg@stW|E*Y3nOW;PPD4JJua zYY=I;AGdBIbe}mu2qeL&Y?!kV>lA><#<zYfBidXbb`KD44cvT1AL8CiHQp`rEv@Ro zk4tcky*Mm6b2@PD%Yi;Jrf=weF&U-H=60dNsEIHi4qEaLw-1RY0?%`rMKC)2K&qzn z8k^YZ84__jMaaGAHc;eekmA>=vSHw-7%LsDZ5QDuwvF#UN@6Jiu<i=Dxi}D2MJSL! zB(u5{YHBrV9$?l|q$pRUxH8(}+j`?~K7M)T)5~$aKNk%yV7&8m-!C7SCS&aJkRw%n z#kUEeEJ7>*TmWVzh*Jdreuvb&E_Pu69<FHc<Zs~GYlw7zp0Ji=pu8ha$r(E~FSSVU z+83uRn3NF<1_(JU!q%^@$jW{RuDba8swM+;JqzhiLfAjAJN|;eE9voSXguvsuRt*I ziZ@PbR*HJMP>(XZae)|Y6dvtWreOg8Azt_R4q-ylMJbQ-CL_gx6`9COEngCra#%7W zwiZhe5eZYXm)LJ$W3c|Z0~FMV6s(?vvKk<i^vikx_gpnvp54J;lz(ko!&7ka`IV~Y zQk1Fq`nNK}bumDH2o+VuMwa|qk)d=QteLpYFE4Oaq|W@lFA<^hV%_0=TXj6#pWRCL zL1vOZa`1gQtge*A6}^=f*HhBTU4##i>yLyJJzfzmux6B`--zAluBNu_xFh!gue#5M z$V`Bk$l@vZ-KUleH8;YtCB97KBqxSmU1|6PVb8oTyJ&Y8>Fm+n=sk7g?}8F#6@rIm zR*C$pKCmXaMa4;d7*drJOLQ?N{&+Ftr0_yRx;u+?+krjd>&0{TCD8={jwJReR7d|y zlA`>#`slS(rm+0}(361i9f_4s*VmA!t3-95DdQJBiFlR+^&ZTasDA(mW%DmCONu8+ zWe@6dP}f_M-+dbw4&4jseD$0_*^+s~6Ojl9BqxIs;Usau1HTI4A~Det72E!LpS@(x zZEi1f16nmBX@V*qgG{aK53(c=U-*O2t{u;n`1&Y6j$;feRQ2pn*f;2)n~G_kd_H*F z5&1v{Oa*fL?!y6bAdp4Ea>3GtRNb20utXZK_Uu1*W4-q;2lAC-F8oF5HZK<MeYwNU zj`F|T5%Hq``}j)B%i9|9@IA4ZR5MY)L-ucbfhkkSMBezLZkBtS^ZS>^70-l7?)?QS zp7oihUb|cbre6*48g{SG)_TK{T(cHevSopYUHt0Y?dkX7*8<+hoqRVpc=7jipYV$D z>F?+Ek7OI&K3!sH_@Hq7<kb^RbNl2Yd(pRle5x5*O5tI9AKiL4S?;Rd9co%8zTfi6 zRX6T#>fZ;~?p=8kbctCJ@_wJ6ns};1!O7ysv3EI%DD}A6z)%Qv|8WSfouwaL=pjiE zNFX~`(WNi<IV6L*-2Q3uYZgx!Hpr3XH1)C)7t^o$yZ%|a*|&yG4Tet#T#=q$56GdU zf1f`i!kZ?Ws1PIU6Zb$48B`!^8<Sq(63!!b7%Y`rD)hNr>QG3{j+adHI(sa*EHL;+ zaCu=8HxTD3wH{n~?sb~Nu@JNFkgJ#fAw#Q#BZVre7}DvX1(#|HLa%2Zx$xE_gJKm{ zR|GF9jVq3t2)pqx7m*kod%-Hav3^eOL*vcXiSVY@yC{{Q>l30UTW$^inmLLst=(w3 z`_JQMD~r#%`38^2vy&YY>ge?vk~TWB`|@j<>h7mLzgG|M&8O_!H7s66Z{>VnmDy~i zGcuz3@$yYk16vpLHwL~;XDFF!&1Iar`~F1JseAwatxbn){<DrAD(nc09!6<QMc?O2 z{#tr$=+TGhQQ<SD(*f0Yx%rKLd-I+i7fBNFIqI=;pKp}d=A~uG_8XfqkZ+ng{Ro-= zM98Qo*M9n_l8I^8Bg)6auZ?zJ>H;wBuCK>uOpd;aGN}3zFToA*(kw5sKlQ22$oTw& zX)cIY<@YhKYoDSHbMy)hkuF#649x{!w>{tOWMX>7^u!g+PlF?ez0b3Io+~^yy$`Ua zBmKWh0o*TGZ%f#DDwB^*Sv1#jZU`^P671HeJUY7d@^Jh{$B#1)&YPwxOxtnh95?{8 zUvY3+KZ_7?VXLXW_T1q$%Yt14yY{csJP^r)c86}=7r3@HeG27nx^&59&y@d_?iG#q zf^&PDTd{u<c5nQ+-emk8!83c<<E((K-g{Y)rN0@cdiigqVS|KeS=a-+Pn)q{vz0Vi z;!N&}zkH&K;)HR+XDVVR{4MJRJ~}zak!||mJ}ds)XUW9|^8iHz<;0<x|1ijEWEP!2 z`)ov%LPRy%7ja*7g5xV`uEv~-Q$(*sr-milT;k&TpJ-zq4%%4zf1!;b2+9AAHpXz| zb~EfY#{UP}7{6cj|3Dk79UB_{A86yyaVvbT=>LT_zQYWEHqPzz{|nl<zkB0JgHw~w zqyC<c&(2G*{@-Zh19pSE!CWG_uFg>$v~ig-Pk79koOzZOZ-;!Qy8YzW&un_|K8k}j z_Jm6<m-s&ZSKpLE9Rb+GIggTm?0yw7t>d7L?>+ykP(_mA<)Dp43KKbK<KzM|ls}l2 zM8Z<^31l%H4%%4M7+`UOiHiPAfEK!vDt`fyM3PBn)-dI6S^B5Tb(XB8t3BOa$uxM4 zkjYZnTKB&qDeNwC!Cb!aU7n5Z#=CrbbEVY+XP1X3xBzO{YSD7o!_{IcLusufuqbS; zG_<~Ptt{eJ+H++eH4-va1fi2&9=F!`{%XRHjrZ3QYZfR~G=JUDYNq_n^_u?`GMZzq zyiv=!UN-8|t#FQsstyOS94VUYLpx~Y+zj6S)yAxfbe5w6FkihdE~xv~Puc0v0R(N* zy*B%s8M$+F)``dyZI#;`mosN-aULO?VfuhG49MdmB<FBFG=?DoZTs4J(oYAyg<ISm zC>97uq7(b2<%ss(9(NR4Y#s;Cr<gC=J8PK!ghaQI$zD(k9Q^MEu)@03aJEx8-U1v3 z7B$<b5#UHAiLjlA9l*^xFl+|6qD@=S-ruy$WH%@0r4;yMJIo((<&2s=cv(ohUv&3F zBEN*6$}IL9c7z2SV1d{{Ua<)9jBq43Db^-sR146F9RcnO9DJ%_Ygw+7_*l3{^M<Pr zAN1VQ(aKA&pN1a1dCorKq9Em7OmF1RS8?xKe!folx&P_sn?xS<T{bP1c9k3Bpdzq> zP~uB`OFw>-3z?5LjVI@a*zK(Xp<8=v*HWkB$+CcbKdPSJ*>IgZD5`%=%^5=yb?*Rg zyIL)pjf#XAY0-&Z3D^hQTuPU6cJP;~nS#d^DRfakgvOuEVIB?p8JOSEq945)L6hFG zBjhppOi_P?cx<f(D0RO3%@H83*;gCbcy?<4Z!9}$jItv!e^k6q6DlK^#Pe-IgO4jM zWfw>!(U>1qQaZiKUuN&Tz=QmmRH%gD_z-+L5ED9%mmD4&V)P{$&NnWSoE1S~!#Ynm zk_<Z=fKcNF{}VWN?f1F$yXk|U`Qn(|3j6i;M+`-CF7rwvB-!jCj%Y<yO@E&BfB+^; zZ6Au!91)mO;Q7&^5sXO_6IJ_iH+h|(|1_Hh=ye?Z{ZJzf=I|IdImdM!8OY7uu_ELy zka{$*oqy}&f#YR`<Rk0$myixsxCL&&Jj#rREBBT3$&^&%P^@U;;C*RbWTLjCsrT>) z?g2^|_HQ8tnGTx%dw#>@*Q3XH+t@1fC5mRsb~9cxhb`-H@E%tgF{O@_BB}fEVPm9% z;ib5;$-IY^M+Z4}+)a}MC^wXuO|{T3nfmr^)`Y8aV6L5xl^O(q(pXg3fDLAVHy8Hx zFNA+Cw*H_B7lQM5=IReY#1Wp({l^LNre$19DT;8!(L_Ge|D?VK%SbKdD}bg*sL3#v zmw4=Y3n@8QblhmJRLl+)SQZCB_u$n>!^FFZUnA;`yyYK<=mwU(YpT_G+}CQn-j>QO zCPQA+8>?1rD#FzvzUcRthH(K{Zm8)2mx;$0Cq^14{%{|#+Bxh{;9NHRMUiaO57LPp zif&!wC`HozWA-wCT{O3h$53h=m;Y7KjT@HEj_HJ3D=lhg!^r-@Q<Z$OMY=H!CJ@bO zhNS~OU-4rQ2V7}TvU0vITHcvon>jII<)YfyOoD37*y1UjHbRK=-BvkK$|FrWxm;v; zdCq@Ix;nd1Q<Vt?=EZ$3uC9_hYQac<&lgs;op&l#De@N)cA7O{!g`A~W_a=Jr=I+e zZ;{h{H6B2F5uS{2<B!F6q_B5-@^?NR0ILz^vK$7^_ZH)iN-vY#gn=@tal)Fl@5Eh^ zy8~z2F23<dKUYM#Gn@O7l(+P<<yT;^TcYI_Lfe6{jvFjCfXe7Qa1<shw|>zz$ZP0C z6QBx2F1PnI3;8Dta*e>qJE>?0!uTBp>ppIFTBG^+?auQog_g$tXmP;>muGm4JQE}9 z4#p304`-1J6`{Mn#uaWZ3jf;4mZ~6s$jF3+8MF|cyvoNPSS5IC^CC=@&GlZeU#GOy zlBx)zXsG>%>0(gkK7eqDAY*R>rc%%tra)7lOj>lY#V;cSzXAoDPNH4={P8g(Q@5)2 zEb@nBJ?v0G?Z8Vez!1_7QDli}IXw8R@iP%&@Yr?I!gjm}b}7fK@7F@x5z8v>${_d0 z{S!<@m`om$N%<B(Dqd8Wh)K37pBbBzNRlP<{SF&k7a}OYO^KQ1Oq0;~5$D(16t_z3 zc{K{YYwZUq`2T!_5=1hYDT;g!JQ}GNMh9NCM00pg*KDeZy{eXIUE`tPjJh^t8V4ZO z$%J?iu^#o``$i)LT=}8cRJSj}r<YHvomqV5%@`lOnuXgU{3fnuE|LO4v;QW87P<Eo zm^~;0io;45Ohxqe+-=#e=^GRREe_qh^U@DITG|Uc79R$yd2%KCGamUv*Z@+sne=WB zzooh7`XlG9Irk;vSvPH&(+)hQBV{sg;H+{OS6ZhG^r>GPLKc)lnoeC9;d$7{n4R=2 zMp@_Q{u^&AxCP6gwzPA1K<Xje?4)lp2ma>tyL`BVJx}lwq}rQm4Q_p~H}Jyyou{qo z9na}7p?Mvc9c-G#01gEbFXbL+r|*=$2|3NnmdJhl9X@=gG?F&Xlh(g-du8s2x$Ndy zMe{w=W#+^UDPq~@KbA)S<=7KeUV5@=a>C^JsT<xeWY^jscoX58f}htfokHvj!Ux#Q z_QW>>z8NpEHSy;+3~^8P&+V)p2WLV?Hh;WfE<xIvY#9&1-0kpF=i;B82mjMOuNkBL zg>Z4v<iN55*3S&wGY9F#m%Xcf#9grE#fbdG(0t8H6=Mld0#ep3SymCtp#qfEDDgU+ z`<)7k9lGSHkod+W1r~GRSup6rQ2ss=D)|f>5-m0A1oAgv*N0<Mep2uFC%F?sxFG%p zmeH7Mq<}6m8$|B8V&xSDa)JK}HT`n!d4h@)#w@_*TW5H4eN`ObA@=Yu%a^E{&b&JT zV2p;zIk1O9wkZ*M?xMz<3Kp?X-=3l8<B=Mc$pxCaxLjsh3AS*5n`xN~ruV7kZYPzI zjudM$D#re+Xb8tt`%@HfWF~0QixofsQ@2tblNkIwz@cZ!kOm|JAD>~L#&Ao9&oXlr z!2wHLW&=~EFB#B8=G&*OyC91IWOh}i-gp{uJ)O5BWvh-MK~V2<22U@7M}&2u4k|bM z1TR^FLF1R-&CxsXq)~gG0#at)40BLlFyK0K&Fx4>G~L@$U4t1v;R<fyvavfUF|wdB z40yJSeYOB<ZpU&hXQlnjvfoJ!dmk?=nmF7G=Hxhh9tZF23XHn(b|C-}ccvJf{;nq8 zJ(Q8Q9oam7=1;ee#E`v+0}T;#3Sfuv90ObTN7dvk!0oD3J~6?SAE^&{^4uGgycHAZ zImnS+CYXzS9fvIgfF7<iv4_~=9HhD{Z=o9#XwPOKE?m{i#zJB~hF}xVQX=fNU|~2? zPQI)KD6yAMCKPe)1e+;=0r?L7^_+5~l_m<>q=8OL8A(bdcJU?L*h0*50oFl<)1ynb zM-^)#(=0PTTB@stf?s<hFEJTL>z>u?u3YZe*REKdCGaQl@F@c@Myc4CTx=4b$E~HC zAC0U_lq#x17P3l?KP=&1F6XK)k>4qRV@qC#B0H)O6`G}mq*9<gV?+@wRXX=;91Q9^ zEmJM6Bnw_=VvkvXv2md7{*8S4`M_3p!2pHwCk9|`RYftWFn5>9+$$du6ZoE1lG%u? zuR>Jjlsl&t164{aeQ;_w^R=))9rTrixM6a$kObIrJZMmwV}JfCc_%Yaq0-x+%25n` z5{4>Z7Yyi2m*FdTu!VBrpnN}0-cY(2pD?b39N4=Ch*v>9{=3JM)l=_3uTS;t;h`2B z!9erHc49!tv67;6;pYOQ7M1X%QtwhQK`Fi<8tHlrR4Kz&w%1j%z-!w`%xoPFTUZPt zXQ~hk5S`<OESM={^<Bk>RlY6q=S@2Pusgs^0e4FQ`(`*6?vP|XAutv4U-U$ol%f3$ zi2Qu49=1PJhh1(!Rx4lEY%I8-K(zvWQGjPS)&+&B;LIhcb;Rdou$bf*!<<hhGUmdU z?@{Db@G4E<Qo8jyQ?Os8;UKvIHdOseU%GGxnOKDgzff3)uTNL1FDq*<4hMbvn-P9e zg(&Q_GS)l1t^<!s2QWRQ$g=I?B=-`imaYQxx?obcm`Isk(jluDT5fIrO((uSalt_k zP~8I=QdaNc(L7$($WyJ%OGW`Fr34%r|CM3)$~YY?UY85VOsh6b%+24H#S1G}#DZ@C zEVuZdI6WmWs<C!QSwM9$8@HTQDPGz^t*eY~eux5Kzj2V03I)p8r)3ql+uP;#%Q&7E z4z3;hAHsiNR4TLXm@$MS`OiNvfKw2?BIHox;=%hz4E+lQT*KG@Gi=1ocIxgR8)i`D z?I_O+$npzFpuOgMSc8LdW~D+0JnpP^#|_wW*wYi2xn_&7vpE(ou;CfSX^Uk&{xuHq z3NF9=JEA+UZzJ6#x-_lZ)pt5^WYjePl`O%5^xop?XoO)42Ofe}D%k(}qz<g&qO8Ga zG_b1YK<JHV4DCMuG2`p63Wb}^)u`LU;^;>xfD7GqE)Uy_25z(u40_^f0nTce%qnEw z;hv(V#&Piq$5Jq+w6t?C?U$^_{A8Ruwwl-#>nsEISaC_Pl^FZI{XcJ1>l)TyE^qdJ zUU!|1s+j4?N43M32jDR%lne+_x%b--`~9~P0HBJa>uW$X{RNVKxMg%{Fwc#%%M_k< z!Or}ga>nJAi`ae?)^ex?(NR}g*4SBvXkl@7a}SerPi*MGo(istgt{7zn2F|e^Ltz- z+Yp3nwc>S67ZP;FqIH7LT5H8Q#-<BYU?WjjcSG=xA?l|Dy0sm7KWBK`dblnb`v;=X zL>g7yLAEBg%m65jKX+@R71UnT^f=za4J9;(`?DCWM&#ZUJ&?SZPo4rr`>~VO;7#qm zOnY808&o~9{r6#^p~EP9^v&xtqg)s7xv2EO_f-q;mUSJ!nOWVLR&*W&MS?aC3BEa< zjzVT_QF~)}u`T68u#WNDzmZLe?Vh}-2H@Vea<G9qEU}F09K-<<=+2z6iwXBO!v+`^ z6}&vgUX`$7Jc{j<v(G*kG~zyX;(Cq<Rp{CvE+exiue@dG_e9H|F#wnpglHWiqi$^u z;RgqvYE7%EfK=uCZ5d#JW~(Z*y7J_4;|~H>G5tKt9gih%RKEl*A_llJMs9fqE<iC2 z0E$2V(FtDc7b5ubrNEs@)a`a;Cx|8*fo|xo_mUOE?jv0WX`E|G2^qPwDL{T2+Z6wp z2U53}2~xuw_cOt7<-=D!P~9X{+rABW=#CKhb_SF}-?W+D%@|3`oEFeZqlU%%>19g` z&r!6l%2%?|MXzCFrl~K%8`~3A0AHvwrV>CkRXu`r%s9r>CmYSk^N#+QY!0x-s`O2l z83Zj1=b7!Ok)qRoNRE}Gi)%kL(_hR9M1pNbGc!~K#A`HqWdQ)5+H1|YK0?&8QU5(U z(Ejonv}2%_cS2YE4u=&g_*($GFs~-s3MW4}H`Uo&KHmEB9uQq$ibuEcYPJ5wwt+9! za01GM$Qly*MC9;u)uqs^Mw3^CvL*ERNkPkKnhmDmY9u!J)3a0zs+ly{iJzfifY!uC zqSgzQB+WTIq5|Oa+MjxvTLu>2oUQT(sY_{ZZ!J-@ngrdz3$eZDTWYvp%yG|7EUAKe zukMYYG0kdVmksuF?u;-5ZS96Tk%{WIw|#wShTigG6FI7OvYBVFY2`WiSyk{fdZg$K z<cwrPi}h=SLp$($%;yp6aU`M@z%)}|LH*PhFM%3%Y_Xjc@eWio8}+bpg+p~;N_g@^ zYGqY*x%%&t@Rm^H;h{qngD}6I!ANDke+vK}&EJCVoI*7dC-*<SL6YCX)X~ZTSl`Ro zjz=g5b<8jdt&+V+mm0P9nVopibkIma$@rz-4%AO55FVpwNHzO>r@!WJGj+4AH{;QK z%S>Q4x@CU`)ffF1Vh3{ZVZX1eaxbs?9Ra&ZXf^U$2MN6tzS4weBVR3WIow;}ZQ=1_ zDH+}u>%ZbO)QTirTzOG8*`)02H9P6O&gHk-T7@pJT36viBP&;Rq*n{G!4f{8SbDYi z>So^Mjo*2jcmle+9eJCIcKL^DB`LeN&fI(PiI^lPboYZp2X)gH>=EbXs_vIp$Q8ex z<MtdW64|%vHA}k+2HyRcc6XhFTDBH_AprR#8?z}!csqXw-NHgTU;TuHJZ;$=xcjk< zTJ{0ck<s8WWu0^fLl{c$MQk*FxMu*eys!*!up{zqD;3>h|4DD_^L-!oxcav6jxlT> z@>PBZ)s?f}Pn`tVpR1-<YX3FEv0rZQ)(U?XG(EXB(CsWfyWE^6DE4<P$!<Eo1*>xO z(<lk;a#uk8)P{r~+GpQbM+4OM#raI5y4c;_c(iNwM>Bc$A=`WMUZ0`W??h&6CC=Ot zba+NH2@xGiFxhNJRNQqwd9U~Kq7Ve#hDUEszG-H!dS2O-#Qp$4Z7m32X3p*(X)OBh zVm<NaTJyNVulFO(Sil{3x*Sx=Q8~I)_WtCEwGZ|Rr^IatHtVyW`W^uMD6!k)fqV@( zfF1bqTY5*enZ%cl|D?V3IpWO^`^#?@9NMF@S%}%`0EZ@lgxPQ2ZxD~bwS5X3YKLxR zA>NTTMqh&k``@8EzkNS{zkTnw<`BxQ1vy7rJ6!z-GxTWh)mWa?U&D(Wi3pPQKT<}y zZ|Kx^X!@G`-_gcmc?5h`4%A~aFnV4QsD)n*@0%zzb881?@_N!<s=9E8$^9{yDY66x zW0!}`3WzFUb^1vG3;FnFS7?a5SCFO(;N0L7JYQ=+N4Btf<hZG2|9~XSqi~fIGP>o} zfA&+jq%-I++{sO-)>+rq1WKfv__{X^D$KigUWVV<a9W?qG2uRD>!I1@?p|4kT#;>A zbEdiWa7FiopL|wK=g-3>xZWB^L-*fIKdAKl8TI<SK-wQ#&MIlhhd;_Jt}onn%_(Rj zy^h(@TwahmSM$f=nS<90rzO8U`4V;D6;ITWNvASJr_4yokvLJ64@oz9#5MFKZw=f0 zRr&EL@;ZS_ww=VyZ)z_CK=hTaFETG~*SHorH5>$<qA|i_?EI65T{iKuS-!zqZG*Ri ztIf*RS<7if*BVSX&u&N#zskF9?#!xo9S>PDBXN5Oo|YinX(@B%UFcAUwm9q-0!_)5 z=a_G|<=soPS1IL+CK|22hz@Q6;9PaYfcm5GP0EH_81IcFDip6Jt~BxCrs6dnMLFQx z%blaL0u+A)K6bau-h|(*eIHEzq1`Zc4-uYI!~P+Wt)J|5a$LtiBwV$^g%_D>%b4Co z6#EYI%7H!%Vq2@bdZt~st4dkNgA~Wf^h2#a2iFCBf7^sM%VBL12;c&U14KOlJk<Xh zUDu=QvP^?T3Im4E&rt5^zMF27amMNcyDLc1g|(+6=^lJ&R>l!MM=#WKL%z%P_K7T1 z7p%)Q$A$)%uJ(_McAlti8cf%&E`)Raz*`k16u8OpqK0{-BACo7{@T^PfGYxqfq2t~ zo(5c`1Si;PNYl1~oq|hoYDn_Iqzc$kjN9(J#K+5;O3rJdfG_77Cxt!Y!sJAJq`66K z8nuA`B|RrVY#%5}kh6TuXwT9`0Ek1O^yFWAeGy$4j96kWr2SU4jWPrXVrZJ#$)^Ox zx)ZJrE7b{x`8-k`=sGuBS9AgC=b!Bxj=dl<{L%2aVBMset9A-L<pRF(@!H^-$4667 zl56Y;e_c{S%5sL4_;HfdXdA3qS$$;u`RfUo6}iGgl#QAU70Ck^s$MMDj27E6kPPA4 ze!&E)Sj%(C*o_-EuKwyYZ3`V^3o7&0D-Ko0OeYP8FioDBrM(hn<tB^Bj-@?awFVqZ zWwLY-jr8KBh&{Ot-y#Leub^XHa!%WY&gB`1P#-I+ITF9vWU0_z1kRmk2|CpIu--p7 zXAKguZ``r#IY1lBSw2A%=|Mb@KyZi}Zq?XRmZR$5Tm@?$jS3Hro2j^%9p=-;5Xiat z5HZE_7re7f3nRpJ6s{w~awZ&aFjbGrBiTLTl1!hW=|pQa;clJ69|}Zh1h4mLEe-P> z^MeV9SEpJ)Q$kNQTdP%dAj1@|ICGi$C%w$IIHGLt01K0NQ4*T_2^;7K-$7;TzE5wm zoIR~=g1F!{h76@`6AzBmipKBUt-;eozV*Y7bCNb}773!6`C00%mij*k&?~?qKJ1si zwFi#L7widzsyQkdeF`U(by})?hx3_iXLuu)?8waehhiQydhWKFvKuzVe0{4hX1~!) zZF~sf6MN&_k%U0~w*@7G3v(6kHv^snByHf^szY?Z_>Ut)d4Iho%u&c|GDylO-OEA5 zqXH&MFSZfmt1T7ZGgE#|&G2Lsh4e#d8k$&UjpV%QL)GJItRdvEUjfnX;CSdn+H_`4 zR;@zeQ=i3+TbZ$si+7vH&tAs$F*s&grROUm4|mOynOZXUG%Xe9qK7@bi14uWQT3;s zl%F}e5qpuQnn}5;UWrsP!LmdBX>(b;c}>1*a|d`Rog`)GRoLuvl5)@x`soKevRRV< z7+pF`dAOt}PI3#{kNvyBZ!^X=Q+&<I!sOV%X>l}-==*7IiPweOl7070E}yn-53f}# zJoH`-JF3WogOYNI<L<uq)rMtd5A9T^n=$fAYwd-Bt_J$%?jed+UQF8o2UVaV_b|mR z32Y2C`P?v+;rp#8KRWD$Iy`ye%7oyNj*$qn5n=BS{~k7pRx1!ccY(d?ft^H~@d0Mo z)a@xv(J%lwc={(|*iJ??T#<s0a(L+r^z@z9qA3nnJ3Z2@^?K7Bm3Z%_yMK!yfW0Uf zYT|#OsdfvmrSi<iqA(}IXI6MlvBGS5j&64qgt>}7QCnjttNck8>z`?NANFH<(cYH8 zA)4ySW5*!}-}N7Q(BXx1aPi(c9aMKIjNCeGxyNFf6kfL!dART9x)da;PQt(eX}{Dx z?d!sK@S6um#?ya80D&hBiuR8kGoqO_qUzED$NdJuAG2{y`cY)hr+EQ}PwJYXdl|BV znYqL4_ZMLaDm?My!Rd)_DGa*~_u<%#Z(A#3Hj2#UU@Qu-FA)1~Y#AfqjeSt)ey>e? zBGSSwBzsECvDUoDadCsmL3%$H+K{uz$&`k?&d!9k5cEa0UU)3JPN8nMnbrKs@Ko)2 zHXK@CeWN<->UW|LV99-O{&0?ODs8HU!!{Lly<b(>ey$bs%+kp?>h$@u_(JegvQQrR zDHh5?H4;Q0PBGDts%Jv5V+BYYuOBUWqBm=Z#EDPZH`rVenFnCJ3lf=rDI+(Q6CXT6 z&DmVR)n@P#s5jr*M`fqbPMShQKD;|9j!4O;`RR-cVQ`x%p`G{=X~cbz8eYnjpV+;- z4@in6UZ8=1^I0F3n2V;X2tq_AfJ99S<)r}M2*{MqKdyFp$Kj4AOLIN$sR2$4cCtw( z(`Iouc)rx_-?Miok1$C;4NoQSQZg4924;bmL56}1NQ*WvxKzz&CO9HKy-qI?*V;`| zt;Wu^>PFq~+sGn`j7iK~c$ZPoPdt@VpCkFb!7OrS)yLu7!s}Q~s`UAkDesNDmgeG$ zk)M+|qmvfuHxlKTLriFZaET%X>z148tGF*EyA(0LcBcUpDU|pK8%ljw$UiQfBD=}0 zb9zU?N%|Y_=a|Wn^OHi>pQGPhS)I2tGT+4jzHEQKMz-GlOG%lYUYzP8QgvgK($#s5 zW3E`5Dfe$9!gpW)M6~E`;Ez7AKA679D|-<;*3^;Zc^9tQ<m!}uvjHn}v6d`xmzL9C zsDd!jR9vATF1_f@p!QMwU^a13U<Mv+Nv?(@>NOmYM_hURA$iD}5lDrHAYdwscebA( zM)RcXst}C>YE3e|Z%?vh1`jeU(~iv|Ru#4R@;Yc${ckC^)6N_Qp+nmO@VehU0oyQN zH+V=1L(7@`y#{Ikz$oin@`}m(DwZi0>&YYpedr_I2SL}hB>PeOeAnroi}(IXF!v`B zy-xW_(TDjXm`X;&W`U;ZZo_m!OIL%k(iDk~S6{2Sb(P3etJU=b57r4VG$rqc<>&^- z!5kZC$MJ^p(U9GAsDKUK96|T&qx;0seB&5l(eSX}+3p;Eu_oM4A0GBr%4MBS)r4n* z2bbdeArYq8niOC+H6*iju!?Cp&ZK<EQtxcoeoJ@y0$YOIs<k!`0q+MXj{1`5c2zVx zydiGjfISIjV@dZc8P(~d2R1Omn2gYwQ6D_bTHic?<DgonlUOt#{J4fQ+^>)BVVR;4 z0QUvWvk;8^=mM!weTI(=Dg2wIbC<cS11SSMf>BL(B6i(9d<@Ws2O#c;Xfk?DMlG4N z^MlC-p)?0Kx_k4Ok0t!S3Puo<5pF5uyE~fp4Hl#c_oZ^`N_Pxo_yDkUE;Bztco1ty zeV1Zq+Ca^L2hSjTyEL|cTV?>|og*ExnKx>XZRf4Kf8Eru{Y8Jtl^BiS30$o8j-%VS zL9Oupx*Qfe3FcB_=CKLWa%M;*z(Ych`Drr7j2K~YGy_gbK-|=%Gv{2;E#j=GI&cqX zeX6rnfW6hDk+E-IV4$Gx>_xcKjOCok<f8Kt3w!HViM&QP?`l01!B`JcZLEUq8T%gk z#eG=1ZYZ~lGxwn!q;KtLu@^kZjS;BNP;0gtH)4FGO$FkilsHC_4t!IG5vW+_N$US7 z$OsEfSx`Z+P4D~)V^H<s3(W||Tl!NPqeRenvEWfkPSUN#M7(C>-^^CCz7BdQuIEG1 zgRjVsnuseGuKm<%<*&61KrmF?VHWHZGitI5)yyde?qW$dv|%)P!8IZtVrj=eciYVc zI*dc71LEL^5wPII>7aH8whi3AB*kZ@MWT{X)&!q3H7t@e59*`q0Cb<|sm!X!A>(xa zJ_AL886~s4P}Q6qQ^a|$#4DamHyPB|MZS+0uT>JnKfE)wXF(m^p!>!%DVRIS=5g5` zHmSBudbAtdx5RF2{(j)#)aSvekKMB$of({pvUQx-jo_l4vq1nL0ZW{UnDAjukS;L} zXTm8h4&)OIA2w_uUzcRepljaY2qi<J9|i52E1x)V`eaWI3!AR59Y|zW5@imam9YWn z$MtDO<0-m>T!&`p-VJ6OUXI!U&C$EV-vac<cps>3J_%8qH))ymwqdxJq<CtMnZu?n z7Hp;~<~0Kup6w|rFI>!x=fhYu9p+>E%EwrvJ{Lv!&-BjQo+s#{sqqcZ`ZasFm7pCL zgk7qSr1--fy$dbkXqIelgK_Q}CvFN0c72l`BI>45;kpm>S^6$&IDn}^hnx=5T?mCw zO(LD6S7$BR4k4k=$>US*RoZ6;?Lrov4gQ!F$RQ-?ODQ&%;&-Mkgid4#-3bnb`A4@E zPd=+@sUvT@(iCTk{F!CreSo31>|0n^e)auysBv5h{qG5iVtP`o{p?2)unQAh7>HJc zTZ244RpZ$~E}?}kS5GXFN9O|oSU~M8?!=Oh<~?W9(#Jtggd;65&cUW<$@aU+-5^F% zv@>IIIOPS+zX5*X(DR3%WK`=Ah>G$jRadT*@lN1d1-f81B`F3h?juw;3UJeB{E6>Z zrIlps4k=H;zmzVs7q=_yr$(kC&6uOG>EWJ%efJ#a5Vw~WX2ut1N0S!KLY{C(WWA6$ zF>zpZIzZIt!FSV>i09)ACKH#$KUGTSt-GFe^iUr~n02D66cJ-!S>s=r#|%t!=y{b) zzjHgCN*c5qKJshWw@>y(klfMCN3ia!P9$u4(uhe=L%gnZ;Rr4-Ou3j}at<QhAz8v4 zP2JgojF8Zj5Q(MN-p(a==z92P=~dIz2F6F*qg!eS;l)HXlHUvjS_|{-OH6Z(M0{Yu zd~z7ROc8w>ZqjbblTXHhB*VW$Ffsr7K1t7KXJ7piKbqa+cF{W3QInq4GnFJd7s%_L zdx`pLmD>D=Z}%Nl<s5wex^{30y!N{D{zwg+JNresTHOsnA08hjRn{-A5?=R2uQkFC zNK7@>Ef<kyn%LLSSYEfuh_~aYVn3LhV)05I-4&6mx1M|`G{v`W%<*OIb%cvduzY=r z^=;bZB8GZU?kHfH>ZM4JwQnY4khM<m*gBhLQ}?n3wfU54ElI~^GsgW+crf)D<}%x7 zn-1e(rh}M)yo|7MSZLo{g&%K|ET4y{my?e$&nqL^KGM3w(~{$GjijubOw^`gt5YBJ z%^tTw^nC^<Xm}`lYkczghrr`ofi~r?rPrT5kzjVcTC7d5$p+n*vl!+jDdE(&5wO9) z#OiO9B~33l=g!{ndQ9kX*biu6T)pl5>I6bqZdoCVanlIj_EGY@A~DQ7@31KIs3PK| z;JdRP%#P3;n{|QaQU$0Q;xhzTpu#H7@ea>I?{#x=&bBTV{{1;@bx*^V&uJ_zMDCmc zX1*7jX^;Y@dNE-!Alw&k+c(PO)3tbz$rxywO4hXS&SWFaeH@^JdVMfo&}8(|H0B)q zm*3QeEptqe5$?7&h&G352WAr>c|Rmg8y?YT@-1n|qQ)1~iXW`qpnR9OtDU$#XJEk% z*FS{5U){*o#5}c44_U;lTEzx`P({>PKS*NI9T7ZfS6`3TtwwkwmPZ)|2$-e`Go^?f zF6u5JH|o>Qy&qs?F?wiBb8zYPktLeuyamR5FgUpG_iC+x>GUi#2c8)FwImlFL0sZ4 zkVla4X@y%%xrj6$E|}W|J`W~M*gtvfDmS&Ty5<4$dcD-t(}+hdAKrFq6dzW6cy{YO z!!w4de^znz)mdsuWst|y7JYM{kOs0?U1UnM`+(EqQ9%>d!J)uV>a(YjC{A)+?Z-9D zgHX4%FvU-^Yp1%>wz~X;0n43_mxU)kHAfi97Lqevt6;8fPNGvD6#JC3F_L3(bj+TH zn826S(o>ZawKk|AhP^FWcD(G^C$m?txKo$Pyq(QIv9)X%9_=YUq9#1&mqHQwp>gnc zkIYd2(e?w^ztC@;UKS4S*$Ow%Wts@VPa<~qC3d>R=$|0M8}(7bkNb~sya3}FM^UA3 zG}~$VrAd}eg#gSx4(6HzbG3vXVa0$1=v5ZX!?JQZ8oP=3()2}Mv!^HRBdhm!&&b6O znew)Np)erzO9~iu#`LW#2Rm!N^xq#o^;6Nn_SofEc!Z`~6k?%O_<o@1n&<kLl$>Z$ zIjBuLy!PNWQ<`e%yEP|mJ9A8B<6jB?w)oMb1v#01l)J$jKEpdjX>K#z28vwrq1?uc zc3xE2bw4^X26jX4@bN3BrlvQS!wU176-|xSly9xzY^QAPdHPkU9m22a<J*BVuxXof z`|m0lA>(F|2)acmT<1olw--ay?1y*p=@2)YNK$hs=*1}c5ya=HdoHR=j4u)@6|wz8 zhJZ}o^~p?>$a#&mkA^wB(Z~(oK2^ZnSZODiD3^xwYcn~RnB0VC=N*?C_iPaR0^6FK zB0#VIm2nqu!N;#&j9r#wUY0ZoX@?8EgQFFg9lh|82}Y9WnPmKrF#H6m!A8Gri6BLd z2!(|<z$uYiG9SJQUyGN)#xlm`QkVrcebCW;no~5=I&tXNMW_uk-NGF9+wI+j^K{$y z-(Xq8y9_-$55(6R=9sgUa<6+Z8+w-NI`Doe^eEGzV%Mtzj`&Q!1WoKcV6vZnjS&UD z>T3J`()IVJm+)5;W=h3h!a&uN(U$@)J4*<`qu4b68OGdJv>;zn59`^GLf)YLM#q=t z<SJ;~7em{1C@1sSCXQQUafTEcdq$&jGNg7-q0=>#Z)5UjqV2$gv<uk)B48K*?9FHJ zWMEQQ-AOpxi5xUhB-b38%kIv6q8yy?Lp7k&qWQuJZt#=XgRt3}6CW92e7%8Uw&C4H z;dX~gMIdppx@v_|5eLpo>-5<y-f|i37Q1fwztP5yE#cplpEe(NwV(O$U1hP|e=JY! z<5@7#L`2HF*0d1^*w$)G)i}|Pl^K+fTDYQ7LY#Ojj*?>YLwnP{Yn$?%l_gpvFu70G z!mi<CczY!`Qk;8c>C7-4Dx%zUE3IOfK3zc$!YsVi3GZEdX$4Odw<w&gzfBAKt$Qfz z$%Unj?-zrt78ioQe(1@4Z#FwY^E+ua^&+I}c`x_+$lt@e+bd)F8uz3kDLsI&TrBjV zf4z0FDzbB!_OQ_6KXMjv;lP5@f7Onn0Q0sZRyE@x1)U<Yls6N2c!x_!Lm;?*$!Y0C z?3C66=X|uztZcWqgRE7dgAQpGnrN=n;%uv14JJQ2rF7z;7yhn(Z!S~Sj=TKeLr{A% z+tgsy{j9av{pxsI^SZQr2P*@)!V`7|mIQZ?k=I0T!%n8`{;4p^G2-dC7+3t2#9?2B zYu_wTN)VJT-mkfj3w`xG4vKc*cO0Em7vA||O`$oS<pr48x0baK5LTw%ZNVp*HOIeO z&Rdmkx!5X)MSsn;628-bk*AHwN*<bbzHX~Q%XEH}C2ib=i<tk0vs9Lid^dG)@Cyn^ zn-tBTKMRd<Yb<=ITrPx$7Iv$0(8j-oJi_H1X9*ehdB@~(d2wTxTx%gHrE9S@$I7FI zZ$~8xx16prLr!p!0zh;9*Yt9^`K8<%Gw6oq?dZ4YllOcM<sZ{K{R<H*S@>;5w~^|f zW%C%KCn;Z&kY0Xl;4dOv``o)<f+kIvCP63M-eI-#`>#9xXisTPstR9#%5_>2vz;jq z32|<IZ-fdmPe;j@h9*ZTR1P8)fEXXB2H9TV>?t#6S3yPRd!qeM=$vz%sf9D>&p$Xp z@|dcnB75g_mW<|@y22R~dAfa|KgJ4q$IbD9tnp^e*c~Is44Z{M;Y!LFmAgha;BiFJ z<P~2!?Oma#-D`X)w>^RwuEuptHnlk>7@MT3jRFq4IzE)!@y_cm|9c|V%FI#3az-T~ znSS=^@t~(m&zu~bZ)rcTdS#=X&3#edSuK3t7BBwZ8{4emamE@i4b!tdq|#W%`(wJW zKrem3ojXzLuI!lr=V?X0nnS$DV)xuETuqU{e%=f}z$?7mbrj%62=_=18#A}vg|-i- zJ8+!r`HL=c>F0EQU*ZBfWe}h0YX){A9uc{hY!>Uaa~D)iOj|e*-uf6>YFLooD?II+ zeo>Ay1aMhchsg(@$aAi{Df3v-4wL)#dX~+7d9q*D%kguW5s3}ryjb=*#p<Jg50LIM zNOXon5TsfdE?d(H%gJs(97`0aLO=O17pkLpdsCn`w9E`J$+_zVJuckn>a5NUyv7Dm z>^H>8q+P-5swuSbIHvw^67LPoQ_5-+1&7vh(!V-9W?URNp?v|W5_00c%(=c%`HSz2 zPSS??Ub?}Dt=?q@X=259^7(`t9f$VEPe9c_FZp))H(IOyOX8<nLW%HYI#j#bI(OS& zR+f;)Q;!AAtr2P=3Kk6!Genn+^aDd&w`htQI@gtCfrOpRXhn*o1bJ0QJig{VYeF|^ zyBv&MG%k9X1CEVLG{;$Hg+y~RUN!g~i_*ytqh5D@0h~DLvcwxo;+CNEK1JQ=!5bCH z3H%(edUURFHY=TnKW_d00ZKa4blVSe!jdgiu_qUxo?jZBMx`ve4OPxyfkRmylufro zouW5WOlL(-FnV)LP7`x8bV{6~uRqRnOY!ejv~vn+a1L*;Z7fMJSLE(L9%aNOurHW< zsAkCI>bHY}T(&D_E&^Fzmis1A$KQpz)GG?95BId5TR=%EuQ(V1iTo_dSGeXGx(+7_ zFKv8@D7h?cxvr7?sM%6S%Mu*&3e*y*UO&{Mt#}jYQErNPKwKC?1~UW1#zRFdf*U+8 zd9;c2ei+^BS9qMLyC8n2<bE^Yfq8oReib>^1@zQTwWkTS2)jSh8R<aA8U+NMw?%w7 z$5l+TTq$x`B2N9<dHKok;q^-Zln8a8%W)=g@iQiV*d*qN@>7l{?Tx2uxPu~g<gid? z6s11QDTAXs{n|essLTyCZRB1NDYe(F?i33O9Ve<t`s5_!a>yza$?+2*jwgalwqZmu z2cg+6gnw2z_5Q8>u<<}M$Dlh)0QJ)2x%UTeX?a=QdMvh*!%&*vDd(|pz8>wtwn6$k zBs)`D9Udxn-(tOzD^KN125FK{+i6e_KWyr{7lAM4;ArPF>_h_E;W;!B?`oQT>%O;L zk3Ti?^jGC3@&m0oLb@AMMtq!V%YQ1M@TUBA=Q}eDUBDxEG5r3BA{@xF;9dVeNIDO% zB;SXPKOib77`Rskxc5dgD*;h+<=!UF+_^JHA)>j(ZLZw8bCp(B?$q3xX_~n+vvRh+ zm9M|^{sqrDJe(WObzj%#^FXX`;9iiGG6g(gfMVoJl&SN2`N`<34o+InL#bv}|E@Z) zGTi6T%l>qd(Etrb#;QXa&MdkEl(eC7_+j*Vr&BKI0Bv=C$vYFXYSxcEo2;F<lp_7c z$V#{_pLZCCJexW%2C=fb*pfgrRP!T0oHBZUvY3#V#d2mMO9E{>n0mg9&265k@8-Y_ zSq>$~-=~IgRk-Sl+5<*_Qg%AY?0(6CO}JR9k>cY?3}?(ZFH?J6ww>vaq;c`tgQJeC zCaaF8_{5r~P#m2xQ9oT5V&_&V%oFnX(9%M54dq%PqOdX8fx5U|_l~<`qICax;aHv4 zQaNAI=*OV1@tKr@NdDnw6@W8?&8cWk^)Jh<(eacU+|6W$J40%7_j?&@nw=5Roqgf; z<T&~zTcmwRXf8}?I;rc`kmA6I5$ee4q1zv<UA^8b{LIRngB$;@v93&zv#*;(q<EpB zp7|rwR1Zxo=N-0?1X7A;Jv%mQz8U)Z<i<~5e{JE(^FIcKg?bQt?6f0E=O3v#<3}ib z%bLv%5WbXtykPJ48G<45ftQaj0Kgj;9_@3~Gk-33^2>VZYDY?~eaHA*|7vC1Mv5rF z;4@{U&bGA3**Wii`t;<8J5h7ZXK^tjoZ%q<VVPy1Kq~tOfhm#4e(O)}{Bk?OB07e2 zY)IODFHVN0&+utBdldu^7*Z!oKtgDXq8`5Ho|<1JTt_`ZOL)jvkRD2VUv<ei%C_rE zKcf+8U_bHj3na!i?y4;<ez(}7bFj&RK{<e+LCN(-4J1V0M^t@~T@oC(WN&C6Y1k-z zw7@MkN>J9$Nl+z9c)}A*`A;sMFihuA)dkNk_*yVsw3drQgI(V9ox&CA@7SSuu5ggh zDIIbb#3u&fDPy!le;`GTn=3exx)(XuEJ#Pzswiz&O+613P3YM8ErjT?QT*^PzwRk_ zSTB~fcg0-fopDOOW$66x;gyXZCn*zt^9)`b@2ao}5eM+#_Z(88?~F@_loR^o5(r+K zsaGA!q?*b%cMEyxAfOurKtXIp7LY;E*(K07P`41W|BWT&pw{`oneq03v%6#eohhp9 zQu6%`Ox)?F*Mp?iG8q_JqU=l6P+?g8!hJj>_|y4Xn`8QefDgtYC4P)x=>UdAkhR}x zs(hDuyP}I4jUW(pqHjUs`njs3Ys0US(7VD1n{_l^im|)YjLiz{;fadjE;+?VcC&|r z&Zh9ofwkmrTgZa}o?^_Yto9KSVvnSSF1#brZEt^}eKs<(*acHBl2i)FBtzjfGL4kr z5)=bfL-(zs-dnT_<CX~g0A&L2qW*Y9FM#-n<YFV*CwK$~97?VP5Cv$xI3(uxCizoz zih4g)#m1&bgw~2!`L~^iPutv-xc3Fr%}0wthL`a);03$!f^>fT?&%?}jq%+uZhpn2 zBN$@jK!S@{{JcWiT@^BlJGv!^_GYweF*@H4Rtf3zLcBA6>}u{jA!_IDrz(nbBi>If zG&MW9dO@u3g5$N)i?R3JV}FrI$Mhmmt=JY4QOZi&I$lR>1l|Q~Ir0hHer4y8;Nv}o zT28L<lz;>~L4w`xgbgmd1sY%Ke2NMtMY-+FW(u%Fu3YOkIy-a)3<%lL<d9nyv&GDO zFpCEI0DSh9A+b`^!$e5PawtpHmnhK<Igb^^Es5g-V*8K4Y7QlLlw52sGWe-)YDOg8 zwPbAYbk)cvDE_Ii22XbF4ZBzr&8BY1^#}o-J^njpr$$n43ka_-o(QJ!WXFJ8V`N6$ z3A<Rp;jAO5`@t;{pqZ5K8D}$RTwtkvlRZw3j5rddojWdgOJ*bq!q`z6{>T%Wjb*GF zCxc?Zvgz&hUyp<vLi&XB^_A5(e_{ClsWM2D!FM#O%;&6>vbnr<V$G@vI9kPjwxY)- zvD75050+uI_yNGR5(bX<fA<FE>nY=mCmneZt$MigYq&jX;z!mj(0n2K;=syPg2MgR z-Gy%M18FQ`;V$N7bP}+olMKmFrS-uQiOPnBmI{{Uk04^S-s@uJs?GQN1BlALebG%z z^*G{X=U(;Zq_dPyxbTwfY4Q&h;`x5C%B-!Mx5dDesS_~d_@?lFkSF&k;&5s$I}Xp+ zwZ?~p2#839Yi5PM!0c>q8OiFLwKAgE>Ja{Tk|2@~E^V8SYOA78h{~lz(~P=LwH_k5 z^Xf=yZ9@gzj#w7hmv`_{jO|_Y0SAUgRqLeHY7$>BOj=l^rzTS65@N3ald<z)(%9=O zgfXe5Z2_<B=Ok%v&<?lEDKfN&ordTA<H2V^i?5R)wQiFXmh7T7IPp?Wy`~{k<0ZzV zrvxZWj7Bd&8;)#wqD>{dwW+w+nh1tk9I=@|N>qKrs!CAPTr1rd`G@kA$o49IzVl}J zy2_E2R0vVFGNxx7ZAl;<tHf%w6V%BK$f<PlZ)>Po4GGdHx0yN2GRbLJ&!LVd#`o}` zMR*fpc>8?`f~W7GJV@^2m{|Y2Ta_+Tc2+;XeDOW`I7lTK*lABkFd{@fRVw>Djr`j9 zma*6>1J6<Om5&}C#2YArd`O=~{D=Aj4lzw|ATM*Hx1?p1y$UT>GMrcgF<Ji2bI6Zg z0e7E3nl=F`?*B1ZyH5$Q1Tl!r;O<K=3H;=)`7He4Qx&PRIL@wr=qqh@h{|=_-^wlP z>M=jd!F%(S!8Q?z;Y~u^aFJ!vRX?v-gJvnyp|3bMhA+7+Y5}ny9fjQOBr&5gb7ot$ zVd<(hePZoPHlgR3o!CfxWT>7zVAOMbN|KF|07OLa`JSYq^75t{(x37z5!x?rf4wBP z=!*lX>?G(KRd&O#`cefo+TobAYM6Vn%yilBVtcQZ9ns|4X~`j=UDcg5^flUpc>6b> znxP_o>AJZyv42BXzEq6y<;OM0Ju&UYe|`a*GT&w#XeBQ&4x7_GNzJ2rAp9waM7@XI zL>iD-cwx%;ZJ~kj8YF}&f-jXf<rKEiO69snlT)vt{mIq}7~B>b{TFCfTTN87A!w-d zap*Fl9<MJ{<E1wIzuN8Zx&(e%mgDj9SW6{JIN+6!sA>+fqQ$4GN}0skSV`Yl<4bS- z*!zDkzhPc%Y1ae+hB3&|Zo85_*nLspbOXcQ|5$%O-eqGefDI6wQxH>{Amoxvq^u;? z?|Vv#iu?Ih=aOXJG%wpo&z>+mXOq9`5{r}A{fh}W>$Alr9Kc=3qPBa;W#88w(jy2| z@qBJwz0&ZtL{=rAs*%KX^S#GVZw?z00zW#VWMF_iIt>^oN&=_sTP(L*%oPqAx5QVL z3;rZ}!O!pbWN&4j_nXFg;;v)%Qx4jSJj$lwUnzf&j5+hIea-(~3;J-yvTn9ijn_q^ z+e?kf*UxVYr(!22qyRwML2a$vFAt)<`_wCY1yl$;{n~eyg_p3)8>+<914|{G*ekg2 zXsL2jazRJ_HPV8{amt+4>*369zxz)S4^dKWYY!ZB*|^5@OQ^Ntns%sI|ImSoWxleA zQ@>pEXQb1C#<|cRq9>0y%wuutL}@oy34>*lNwtMIQF;C=uJaM8rd4fHPCDV5mbG^K zaqiz!Z{_@fT!(+cBUj~=*vb&1P4s=oRWXMitu_eWQ9L=wx*x9I#z6*^{tGQVSR`?N zXPpo=rGGPDIa4`eO>($S)+D*8JXF1PeJYpyf)a1R`)GBQNf=kCuFazEfE9mI+c-Ce zGkiopqFR2_w)!ldAJlgl1@Zpw!@sg4o3F3*XUF5;jk-EjMb18To0Leoo2^IPB(g;O zRTvV2XP1aU@q&QSZcb!>qPX^VyMA6kYt-MT+c6I(9u`6kw$XDuYnCc-TK}*k?a|_j z<?Q`rOVm|P#MFoC+y<L=J^FC7L4hHCVlJVS34-v^#~!SLwe038lAX%YZ-L!gY?U*s zQzdeRUup@y`{4ZCdjOEQ$u0t78ST~;?+@YVPh#kvJ6==`mbU0_$Ekg^&?-`%vZiMo zI#~^*o#QQJ%&}^aD_4!hsnn_fRTfc!jmsZztMM;}G5A;q5_Z+3?|cHk-Dd@<;6nQR z%EGjS19+}hm)~L#rx0VlrHdGl;)1f_nhy&u45PYl6$!*}*l6E<ciz#uzr>!F^tJr{ zOwPVD*?xD^QqSnl*n7pxq;zZThcE_{CpT^2x6~*M;vo#RR*hOts#%c?e`Q4<*h8{D zE7#1N_&2Ocl^)NS$?e^Kd+tubf0wMEa#+WzC&aQ+gKBzSvjxwxICNvaY1|qG3SVh) zXvXY*p=EOYXH0o$6(VA<O%O38kOE#eTE-Ov!2Kd=3X1XBZwnPUm?xz2ne%Dr>#FR= zpq@=Qy{t9=Lc8=)vs&%f>G#X$f_u9kv0iBJc5t7Jr{SG2qFN<Lt4|Qz!6L67ZQ1N} zg>vvx`n{&>$ZH$il4)-5ooE7Gy?^FBkl$SVjkZ46X|t4xeVZ5FCVxj1@<{x*rNe(O zkc=H113OzmcCTgM8-JPorg>mdV%bsmLiv0R>(4J~u~*sDN3W;?n!U2!f>zy8CQr$8 z-%hR~IpSy@as4qDZMV9E#qk_Snv!*YJ3A@)@X3I<xcpaIy{bd6Q?|99QQY)jGMMsS zR~W6Bzt`^rFITl=D4;3@KKS;Xv?2~>{j2=*>r;W-XJemEwt+!vL>^kNddhE*Ys<<k zb*AmN@p9oC<wxBe_cwhn-TJ28^C}Zgd2!1@1%QJ#0j*D0NoXhS?!<4T-uC2P2`x?y z2!H}&nL&DBE!ZmFh)Gv9TRjjf3p|$KpADs3>i{p6Sd=|X_)ZCGrXKAcjkb?Msw!{w z;R36*ebw6BT~8NU5B--P8;#xzUc~v=Dx^Mh|7fM;zm(*%p4%uuIbYjp`#P8Xq)Zi% zE+k3w)Z0Au80)OIe1_Z9N#Yjhb-9q|@Ay<{_y5txFPWo(^VDXTwOk|!QN9gje|t63 zy*AXqdcG$Ekc$k-4Sc6UdsBA{Vjz3A-NvKvjb<m;s#W<yk`Q8pV|%BJl-#>zCH<yR zrMAvrIHJv4p3qRzdW{ulr(xhe@h|5Zk1){5?qu}#MRDZKZyz2l=Kt(h02JL%TUNYx zKbI0DxUdZ>iY_|V_52=r0{7-Z)3cO!BzO~b*b^U~E>p!sCu{Hq1y&~J;}wO?!^8ak z9<Vq8-=x;D(zhXC^gZe6fFuEcwul7gpDMD|mx&m{WZH)ah_08w$<fful)YzDy4iL= zO@}avnx4??)=8=~PU)R1Rtu?LiO~f-4cX)2bs|~uJBLF#u`jZRa{nFe458^vzBNkj zN<N-^u{fd^KO?Bryeg-zMW@J79WPt+P;3K<tFY<Ws4ca54I4PqvF}lI$_B2;3j`=q zg|$J8)g*%N`E0q|f^}{FK)`dbU^1yvT36BBPqjjbEi;DE+N&|=nPewF!^PNqS_MYq zd%yu&0ugbeR8sjJyQtY#Z;eKhRn9gKz0*6mTwU^@!Po+{5{7N|_9hj#xnx6iR$W|4 zeH<qafzqo%JMjWmO`eb^9#4CWoVcGn8JP*Pe41DlqJ9#nBjEr1k>zUKrvp55?4FCw zTB0PsFIEO_HeK2WXLn7BU!rfPU7(RXkppS6+i0oJ*tmt1R*qoZ^sq9|cj*##9Bt2c z8{+xByUL*|<^z&<IYK(GAWVX-L##jCB6=~^m6qE14Fq;!X@&M8n}dZ06LGQvJPTjw z(hvPL42q4~r^NV^p0RTHf1)brbv@Z1Uqm|~M%GGYkq6;#<D*n-HsU$$Wh#D&>`a&D zNhaO1d|q=rWS6u&YK8YER46+qYS|C--$;rP^YW!We&<~t5F0^kTdeXf(w*+ylx&Iw zp`CaKa3ks)b=QnTd}qC?_&dJLM)D{hd*sJ&m7UyFh0#g@%C~s+OQWvGY%c78(}J=? zdB1oNZByoqOOb*6p|XV1WAAIr6(gc`zSp0(8zHMEAGK5qcp93r`I%^+Z{o9fT0YoR zT?_@*w;8|qE3(~M^%q?3wy0LI<RZ+c5q(i-Uv!(oZ=mHPm}~i*A}k18O$rekEz8=i z*M(@|6X>}5*S|!{U!)X)ff~U4KVa`t?5HnRynW%GNf5hQEeZe2z@Vgi8WFHjF2LZc zmlCcf;ZN%|F^?Rvc&eCYH(G{T4^P7TD;D|>eMWCj&&~@uKO@1?Mb{;m6bH*1CtB#~ z%OC>Lij0&z&Y(xM<l{?LdSgA|fWyj3{w*e5b&Z4xbTrU?4xXu=<4$AOh|<%K@<cw_ zA4tFnm=pjMeV`d8I&WrBqJ5adS5?8ax)*O^7h4|f43!qtaK%Zf-#xEhWo8M|;*U1V zspWGM;F?Cu*LghFYJ`OTr0OV+nChjc)Sjy0#O$Lebld2xB41c9Mtn^z7HGo6u9s-D zsh#d2l|=84COaTqP!5%Gx1eR`Vlwk(lO!Zm%C4N%pY}+NXvd0uQA+T>w4u`Sr8+t1 z!0x<RMtq4$UA|7w*`)EB*Tmuk<csiP;%VP-)=`3c8puD;zn5`6M_KfZ^3V}{O(B8N zEMDcf)^12R?!{jtY=*Di&l3PSVfaFq?lnxiDB0VWy>f_tJTGqj`xgC<asO?JVZox3 zaNLxtI8T#=ZppQGDx6nHrnU50{^zD#hLsr3Yz@~6u^OG^OS0jCG6MR32b13XG>)|z z9p&kyj(p>dI^xmRRRnf677YSIV|U$Ws58%v+*o%jp#lV4#wGFrTHI9%V8>4gVj*>= zM#HY4=7~Z5N)Owd1S#|3oQDw~V>js}xt*944+vv<{pVu5S&OMIiCE#3&12E!fv-0l zp~6#)-bBQ}&Vz9#^PchQT`h@$81A-TGB<S6$hQ32yIo(7p@VF_iVEACZh$&>>n_$Z z|Mc%R`@KfI@8^?=qAK@}rd?K>22(b#eC*k(HGl2Uwo!{w55aYGzo74r0eS8Lfer_j zP$G+2jm5yj!Kh}Vy8nr-KFNrWFS>{ll6R2%4>HG~k?#xFQv|nIw@?h$+1^N(_cz_c zVg&Vn`&d3zIMV@jp4oiN@H#%h_$tI)ce+wCV=hqG>GbEE;S0qXcH1<sAnEg*h-D8_ zV8Dk-@{@VWJ#H3fSD685(=@zQ_v}Y?y~yv%1fgH+UqO_3y{gy0nzJvZ3!WEl4hSJ; zJLCbvZX!9x$uS?Xn@u+BVk93%ji(sZZYGiw>C>Q9=UjqZcE)S5xlR5%L53{WdG|V7 z$npedGr5!cID!nHf!qiRp_vyj{qOG~J{zD2pMCb+$Yg^R<T%?dm=?9!=S&PyNB!+> zcqtj9Na-jTX=*yqdGMS2f$8;EF61%cs8ne{!4#rebZ^cbr|(ct9aW7#dRlOBpt#~7 z*>n^U@|eQp?Z0--He_)^(>?4wYukGFCvR+EekJ~^7Ru$UwtljwUisABOh5DfLgizq z{EK3grBopH+56Y})iN5af8}}BC*xlr3Ens#Z^2icy<7@q7u<9C)t*MGF@BDIztdXI z^NcM}CkWf@(Ip}l5x*>F=D&<KQ+=hUKHbOGYo2x~D(*FtR_nzBz1S!?ri>9VQ+~mn zehzZ7;ouxX)VYGn`Y39Y=ln$5;Va7j7Nd%Jb%K@Dh9lLBC{|gmXL=wpYQJLVjV<Q) z&%PC+dZ}aX>XXfv#p7DRk`LaR-xyH2B%cw>eem-9ZQR0-sORmSXEA&omAYHEg_~aG z-ajlH(zB5~JI-}UHsOaq4jTWPWpk;FORS%ZpeX5&#Pa#HtBoh$`!;qcaG29eOEdus z=TtWe><q=JH_Yc8C>7CnMibnfubPhuL0<T_te(20Q0cm0Agh@x<&*dl+Zr!G=7XB( zp}oiB%lSqyJT7HI$a>0Suz*xb7*1+dNP;g!w@*7gmF(vuv3r%kGX5Cz%sW+jCGOA3 zP#G5_VPx>eUm<^H-<4Zy>D9h)VCgFBtg-Bx@sJqd(U#n$e}teY$jDCu-q`*4DQQAN zMD=!~pbg>3zr2@#K{OGl-(~rPF!$K1X4%T$q}7Udru@fNMFKlRE(9EHjov8*&3jKi z2pFh_Q%`}GyYTV}&s{{tN2Ww6*%f1~@n>|<H#9#3(3&bwg9_U{JeJUbq3Q@s9s|=D z0c}5l24?|53FP)j3RupoJ^pnHb^9qCe%WxWA$e?Vhx;Act843%ovXxLfS}!}ILAvY zsXo1YV4@_IP1ME8&ftta6tg5Rx<vWTR?ckj8O=m^1l`xKUT^vCuaSbpoPgzpS>!zh z_xD=MU;}u;eo-%D1jnQ1YrT4X6oPkz%ZHFpkeuP);oyGb{S;i>sKXSl+`mfGudCow z7q96n3F)GKFROzyyasw~AA5Nf$AuFbFsGD|UxdqH6Bk0Z<TG{0FKvjGP{D~Yg3U|< z8*$ezwagjH&Su6SE4QAI#hu=@NJU||AYVUee#;k%;gU_Fu<4Q8@q*fT!AzZ3<@>8P z<RU10#H8^B-*ma67WpG#rTH7OkUg|^xkzaPfAT~7Tw>MZK!G~^`;i{g@Ku&Atv)zG zW|PGFWb&zr$T%4RM6Gg9o2@k62!r;dc$5oW-k`|12?oUUi0yHoc-5WzyPN)%i3!k> zxU2N)bik8#a7IBAX`0N(g}`JFpoLuJ^4T?M&e+eriMxc5L3ydiW#J=u-iGE+Duy5R zOuV-M*_DH<f4*qjr3%<h%c+v26hP|U>^n9U_n34}l|kSfF@ZB#>HoIT&>4lhZCzTQ z(f=mVOiKC^<ylw`C90=JuaWX6s`4S$Q@x*^tBz}n(o~r~szDo@tNHYff}0!tK=%6( z-XltSNYqIY7<6Xa*)h|e5GD)z?SRBaT?De)=tB%&l4j6QWv#MTaWwt!omfRK4vd1N zBEJirDG&qSC!8tg*mB7($dqfEL02n^wznz2nz+}B;XbLO^r)MfzSH}p5Ws4*kG4>X zb>ZNl%3XThAkfg$OX&H15PW3wQDz5k@xo&snH`5^16XF!^h3RU4}74>1zg%X+yyCJ z_I0;b=`Hqx+>GwOapBw;W!-i;xqaz53C?#by}P?I0qvtM(_`bU7(JtF-w~24L1{X> zgtZ~v<3rpENzf1@ex_HxIK=;_3D&L3r0~@s?<e`{c8pYr2D!}OWR3VzMY!ew-C*1> zC&AS#!?_bf9svo4rfr{E?E=kTKb83}%+(QI{`%=dC$pG}+eb-%IB7Nte>rpLxwB|N ze`|3a7B))_AubFy2dja>3f`3#d!(V5)y>x1eKHs#>ru`>KFbDmwmKXT@RmHUJ#F!d zog>1+_<FYSk4A1ODfMfz5+!(ej^rOQ4H46LhsI$eI*1ln^WQzb@`)PnuWj%ad|#to zzByQ~T2+=)o2r08Ld%+P8y15Yo>Gv{(vZbMLri~8>N}{_t5##jWBX?fe9K9P8%JCf z{sJSbGp)S?-yhvNdgLzYVe_VUa%;`zEErJXB+s}=7QaCQGr9_2(Ct;&m+n|!f9JM0 zDU)OOswJGv`du7ndNW<5@+D=@o`L%v8OQc|)vxhQmwwU<J1WpoZ!QzKEIXTE;CTS| zSm3sC=N9d{>wzk_F(*WqBq@C&TwW5FJ!v(TCA44g9S5HcBL!f^JIliP8NKb9NgfYS zDq(44t|qaXa!yYjP^n|joSYF(yeo!}V$eDL*pFl#@?lQ+&l~yO?^zo7>rV(bBDppH zS!oa|s8D>xj=t{Y;KnW=y(-LEDeaHgw;vStahsc0)xTT1Dsy=R!S4+R<?xJ;n3%h~ zQZ1*Bzf(ACL-p0Qjw6>c{`QTuuL?1Gi{1#cnWJKM{}+FA=5mQTSSK7Hf!{b;mk#-I zXX)o<VOdtv%%S7c)q+jKGIBMeYwR3bnch`zz10Ffz<DD+D#r|{u7m`W%FFqFAA)Q- zqMrPSRQ<V%21P&M0HhATem5YWoWb7y*dec^DqG?#{Rn^OEbf-x4FO5Tv;8p~BOqaW zPSu&|#-Fl5vfi>;$uT1V{qQy11=H6{aiL*1Ib3>sG}I%W=EYY0EG(t@i<f`pcZptD zi~eOLFVmPa4|WDh`^fVtyCNXJ7Q*8efv1mRwWpVpghhhog6@<{*<eI2l0@Ib!`BSe zf-C;u$^`o{q0mQ3j*S11=c5E%c%PI<Mbl;3rsN!WrXRa5okm)0R@mh&@gp8}vv1sg z^HOhGxV!?TJ)DrZ_K2r9)6t5{YPCU%5QDtNeyf)0?H`-qZ<)SNFoN1Kbmj1jxLc7| ze_UzK&th{?vbLsma01_5Z=5`I{bn{V{B+0c3^tf*Wo}v(=l8W2w=G$RPi6GU=4cY= zE#qnyyJYZ1`#=`)RsZJJ?2`uh^yFdl$}7*t_3}a!C9vH51lgAO^Ol@^K#h8-cy+$$ zTK-*H!fkfV7dzzoRlf4FBspK!O;KkL@Yc|i3#l$UhCR8nzn&V4G^Gglj~qYgR^ZI# zIkhzKjMEc*-ngB26Ewv0x0XvGG#=b#FPi}?AqdHbROm4qfWz{<bhWF;@QeM9n;~Dl z@mredjDQ-ynna6`Hb`(9b6)O7;KxpWtrkpOufwK0H$Ue7WqPsgJ%KuT-%U=P<{p8f zva4j{2ckNfWPs^*PSc4fQ|2dv2Es+@^BUJR3|77u?J-glSIJ+EFW0RJ>p&JA%G4oT z!vEx%79@hIR`V95au)ai8{4=4Y;My0Wp9*~U*nqd_eyZ($Ao<p0(Ekt6?E8aAKs~q z^b+v@$qzKoKTtfvFfZO)Bshya6{w3rzUzM2x#}nO%$_Z2B-g6y8uD6aPduj5g6djK zDiomS-*V!*^;U^Uj!5+m4$JH<S9zOCn+26MU%O$i=h^(cr!V6&E9U3#^Jl;)->?f% zdo1!lom}UT{GLv=?QCUUOTsJZqQV09uVoTHg@kjt7ZM&Ceo1JdCRACA+RIANsl~2O zB*L<hBhbr>ekLcC@wrb?NvqE+ui*xs5nq^NJ0xAQtPIS=dpCYR!<4WGH!tuxcqzA2 zd3u#O{mTTJ@lWu&x$J^|G-_xKSa9+e=Y5@RfP$2`*{{NgdwGG=+jhIA+WD7?@b@Y{ zZF51OVBn?eK;pa6zhG;JC3)^v{g<vUuYVq_-!!ko^GpN3BQOH(_zS2%7NrtBFA3QT zHcm;*UC8{q3lh{~<M5fxbc6py@hwE{IdM5FwTkhy1U$vYV(bnCojNx2AC~o9l$?wg z`oo{~qs4iC1D@?aXzHrR?W-NtJ$_^iVwTJug{{qbwr4^LVOwHEB_+zvU*;&Tj|JZ^ zZc1&K`+brf{jgHa>uL3JJN(*XQvoyX+4y94(tG)TC}6T{@z})%bk|igKETXH-~74$ zhVZ>RQ*vuRu3L`FdB5k;0?8Dvk+bcx-p-X~3U19ungqwPzXl0vW9sGIO<fpDKol;k zh_UYocw0{2%NpD+C(imp@?*S!Va(`jhr)jb%ZseV{eR_$-lHSn!2DPA*Q@KuwHIzh z*vA|1KVxs-*x*fD4G-@DNA_5R|KUTr7~kHy{_pIHSFf1llt9<i&Ai0=L)o(n5h5Sw zMJtLStBCL+_@~fvLC=_;AeoIv{u6pHHcr5-OA~DozAsXw-h(JnbJ19jYw~-EhEFRB zVsG%B>|M)x6vL&`BHpm-R|MKteWI)p8+==AlF@OTbI(jA=)HQOV`f>Uz;g>%KH#y5 zcirp54N*?1KaP1_)Xy=zr688OpV8pk&Ou$6?vmYUR;bo{v>rKa=!Kk~W3kH+dagv) zMF=<$06cGBH;*$)bLLBN=KCGx9C%TNjj+dXe~<OfPd33M!#f0iDuEm*SoA0R?f%o0 z;i?NQnonMmgz(;W8KbzWkFONgc><oYCX45|HWfaYC;Y9`UViRy=lg@$Sv983xBim= zn9>~s0qsgAD3tZa!I@uB837lf145czg=r;U(fM_QVx-D-V_~1UY*~Trl$G`znc63n zCswJIs(`XAdw)Cv824R#?Cg{4Z>}D=)EdYznI+KSw^RT^ht%75#F%F&U1TZcDJz2H zfVbyfvvpiE<MX)ixlN$cYO^1);jP@X^dtmk1_|hBT7DiSjpbV-mcnCXe)C^SQEyr6 zvu%};5vCh`(8j6mNAqT&8(+MHgmFvA9CfFTw<`)C=~O=QdIiW_kW|>z%9V986R?>P zGw!?)iCeciW7iO3lo9r9CseS^<bCt^_J}w3bGrH+Fo&l`zZ<pm)2%*)S&=77u0Kx| zX7VdCkC_jWzkOy!*(vEU#6LdWX`dbw>%8$lv@w`_BcIy=+CRV(a+WrUNf6mMNf3eA zK7K0=zT%c87dR|#qR@EW93dYwir15>KfC@~@nH|Q0MI_g!~wj4YO@;!J$WT`bwOp_ zNWBUf%6;{f>MI0pq{{4#)|}|Tn1$WNHqMZXsWVW_IyugSZs)O{s#aJtGiJCjsZPGf z0WvuU{J1ylLDWE6*c1khUl9k)ft7iOK;Eqc0_Q<ond4o?Si17eN~R8vsJC*e;;WjU z1zH(k@^-T9nEJY(x}DpYzk18vR8yVDU}H7om{&76%hW@tm^FL*hNanYrcUVFjJF7} zbcatlmf+MUqPS(fECY=TcGlM&@9$4r7Yxtc(ni9f_k17C&Bf8Q^ntw-TJbV>J0sCw zrky#K0yi_ge==OYK;UO@XC>199V9Ex$S@f2d#Pk5c?~wJPbOt+5Sy#OM#1(jC10~s zaqD#AsJg1x`D<#m$m#k_!w7~s!C|smNvLjG7Dp~a>XmD_%WquuWj3|@#;V_jsRxhk z4R{5QYn*BSqIGk5ftPq4t|I3WO#o|&GDtQmx9!7}$K>-IGIXRm@^dqiMtmFL_=hM5 zg%mjuy_uvaIV*WX{rJdSqY)lwN$2{Y#5^pP{$RGj>krdG@X{#iO|WhCj(|xKEz4MW z4E-#4J?%2vtqtf|kk$kQRQ!>9RZe6<E0Vo`<s1W7P=eMO_K*`5(cmpry4=20Kdbzp zdhBaaM~mp!Dx(lrxQ<w;tjSwxIfk%#Ib&t}1vh(TVZwE3NS^U2#nUK2?j{RmX(cq6 zb<k9)$@}3|aDYXy;rJA5n0WdxpP|JR1|zw3y8Nxb$GXyV1TaKt`}^-i_dHcA27L=m ziIHg)*MQUTP>kazmU213gz6O(kw@})m82DdM?BkRRL%zhPJk9~&w2sO=s>j@GeJU} zw?EuEkTi*70hW<>vD5p~Ps$p2g!)DT`;~>#ysE^k@hoal_=F>vfAoUEJ=MV}mZ1KW z=<oJ(C%$5`GzT)udUx&4Q%j^Q@17RduOh9l%}C}GCGF6Vh&)D)Uifvg3!8O*tURp; z&dvf67CCwk>v)W%j&0szy@fgAp5yS#7Urp9;i~Iq5c1c=a&5+1hO`nAJ}4x{FF_eY zXLXV7rFELCE7}^~X2SAy2e#AGAEcblmzJVvDNso}2ey5!S<<A(eo~(DB^PGW@mkth z?5vRP%%jU}>2f0#$&q1wxJN@*1<MGm|B2Wpr+`|lm(VoTG_!s`5n-;<pKR+YIwc;n z!rV`4n3cGBF4~OD7&a9>xVXulF9P3yF>pe;Ay^$?(hLts^i4w6nADfr(EPvAn5UC* zIzI`t9)&F}8L5=zzbLvmDBqWT+Hh+)<wPuAX6S*YXlFz_fnU2;Ol0^+f=QIj6|3_} zVO_STBI`}mIeVAy^E^reRk0k?dPT$BNftjLVzq{idJ{|%aW@!4f)h`R3u5zwF}q-% zF7lw<)@0myT6y`iZ9@_>djXlQpfaK`c#eTdAz8&-hn4S>J@*{WGrL@9teZ*X{!EI! ziLRv{o;3rKnRLD%enE3sADvltWiU=xe||e&#ZWOV6BpW+zz4s6+2H)CD#M{2(#^Zk z+x^@mK#RYZQBF!fS=s@EEE{r-+9tJ8Y4MGIs?M+<<+j)LC(IYNb@J?D*s3hD4BqPv zh9$Wb%P#D2H@WQE%EZHhOWG2BPa@Y8N>O40q9UF5W##cvlMIJJVbFyFj!ysuIs$b= zMQ1_;m@^Y`e_eQLwoh}n3>N1orjGq933fLZFLZ!!_%tPcc5vzE(GD9C*rezv4x&<f zS!(&7hwq+w^eX#D753Sry8xiDT6d#_!@b7)YP#VS((y?6po;Mj>c}>4=AFo+3W0<u zQ1^hwLNE8z6-GG~jJ@H~8c$dFd%uh3WP)XTIrRG%Ex?xNKxh8p8%Vdwz$zlA_M4hX z5Boqa)$xlJx74fsT8V|Zl%ReWb-+_61x6Su4y+kWyv1>!Ct|&LArE~g;*6XxJ{jA# zhO}@UkPSCIO@bTI#{UhRWIrgHLV+J**sO*e1TsfxMYHCFxOmZ#nACFGE4^T?%(|GW z3f~k44lAlzej`V!E`7lIGUJ-<Z+^~x$*<!KQwR4iFM?xs59Y1=_Z|8v_tC6wlL)>z zk_ed9rkNFEG^j1)X3y$$)SA~^!Sh@$+UlZ<8>U!j(l8(sR}{c7>f}8VINs}R&BLv6 zz03?P!qjSfTM2`?@S3Ac5uS)DT!7!`)XYKK-Qa3QPd<k63$Qy;(ME(T!g{xv4`6`J zGkJSN|7lj3Ocu05Kl6N2$*A;cexEv=H!gd7gemJDU2T@t)}~KNP%&>u#Cr6XWP_=y z&$nNyk?%zmA3i$iS8$H@GTiTP>$@%}UU2PfkQSg7$q3d-{K)KB{huO$OQWa1cIRRo z#sTv=p1}O-22J8KeIJW->}1=@%zZLC;pY`n!3Fqjs^Bk;&=>n@U4t)ty0{)p2heQ& zx&Qmo|I=~FggnZ>KFo9`5}#XJx?}xD=8?n_Y+_$yyxjhq!A1M@Ss6$+8Y1iIp#66J z2aEQL*E$LA8W_4M-DLxUXCz$PM_P4JxgTqh%HK^w#gv`UO@77kVXHS^a?I!F%RysN z)BgR|mHQsf=W1iX2=l$10PgxlwYDGTdTFlx<sEE46u1}eZ@D?E$i!`Y?s5d<Z#Un( zdQOW0Vsmo&KU1+zX24CCCyqOcF_2}D8L00*6*{x<c(S%m!jP)W>3ghCwOD<q$Zyj@ z3vX{mhM6vRc*XA%3Y0j)-UR>mQL-4zw%H8ZCQH#n?kL6@(>D;p@y>%ex2y=HEnNpE z5L-D~aW?}w8cVtV2y7~GT3SGw<{;awBN?3y5@J-?MUcOa#fy<a?BOh2>d1y>mQ&|X zJraf_LGuAGZvwTU;%3C#p!ruaE#^omPs7jL=u|Z`)fnqHlZcH;7WOvW0v&!O+nhiC z#(SjsSefuT+UmVlsG4bPEjR1xN-T>a#X=&fBA-{CI}mKDRmI2@7#IjMg;u+A)RRt- zl?q6Xgm^H9^$~}m;~umDO??R547aA<%)cA0hRmr(Ht2?5Q1*Vd%6V+U(zh>gy$2B! zz&gA~)X779;Jo`G!<!P!sVGAHg1Wv-i@1bOQh5w2&PvnBl6{bn#9(R%0DknIG*}?> zCILyAq&$Qs!&>b0h2y)`Smtm+mE<T6b!r}&*^16|DzHoVj{ISI?xtyUQ|R5MV5<D9 zyCr4Rpebq;Dydv2w$h4NNFnZ3a=qnMEALP3pq#Cqc77Ir8g|8MVL1JruUo2Re&Id; zP#5`gB};iGv@8y(C7ga(<H}HGf{T&+*Qvv33iEz|Y*(i~%V*-#V{KhIVYy+A<hp`t zip${p<OYjLVJu5YicxTlmGtOC?my;8vVf!7)D2NA3vrwa$`{>qxbf4h!eN|vs`V=9 zGAz&8QZ2ji5omDsOrn=8zLWx<y2_v!h?t6Fm`VypVP>}i8J+#wp}>RgoEwvjRtn5~ z2~o`fF+6KIp1n~nlDT{^;6^qQ5}&&>h%CfOW*?kW;*h$q&oQ@xo1PTCaNwW^D$?9n z+*a0KA~V-&aZd+Y?|C4WyWvHpY-zQ{i?(7pwmKdVjsMh<XM!{i-BAT5bO0Gtv&Yh6 zQjmmY<vw8Hn-BZ0NNooSTWW9KdUewS=I#mO55nALHO0M|Jjq&%6YwIkmt?Z71`wsP z;KO9*Pr~_WM~Z$(E~z%e{ky5}np4L*m5KmFVw?IB>|AVjx>!W$r#Pg^p7K8nq*E#S z7z+G2g-KUxF-$Q7-IR40;PEz+VPAavJj?w6mU<Id)xA?|6oz*wtceoUDZ%PH6h-u4 zZ9ZSvzTlQMcNbTNWl=1hSb@8YAo(7LW8FFARlHdWaBl*HVAm02lZeLe-g3u^Ui7ls zT$ZI(P7dLG<udL<6Sj9+!b&ye5gFxo^(k4m#KT>*SU`M+FknRz$=p)$C%*=QazjC2 zf;{oyKv*6Clu}seWJW78bNUKPy;icXF0u(YsXvq9XQ4s0mda(p7eW=u(2QJ)4f2bJ z80$Nsxl+VC;8vlDh1=li*g<sdNX>K=@qq?=ts$l;!4X)8xR&V<Et-}T!Fz9~(f+Nh zyp#c~B^#Pi0nnQmK+r!mksfMDrv#_GQkA|us8u&4h61Y(U}+DJzbb`vgaIZ}_2v=x zXI^O}_C)w^)?cgOk%l;=iF2s0av~y#FHtPHx(?$7+RLSgrF@oY5YO9p@F_Z5Ih}RW z1QE^El(b5bwRhE6VZdvhzXGH)szkz^D;UbOGzZh=eM&}{fD#R4u@*~CH?tv`@%K*M zgOzshYF#}`eamlTdz~0Ku!=F`q}lzH1|cmOxM|7=YH>TH1!f3*!E^NgZW%pPXe{N7 zOiJW<&GE9#XW$)t7zurj^mr@PFcgp=am7gHb+Cd#CuIK2H!WTm>K-^I4vshBQbS&- zZ(`Zce!}TCt>amNg!!02tdX#M3JW8wpv)F&?(=l$E+0dT=lHZn&{T%kdH!pko7+B9 z12Z_@YBY>d;Ky3<$N?ff4&hU;G=b!PZsITzz?v7pNh^4)ghDLuu{M^nT>#%;w(G>L z+rC{C`#lr-<rIq9az35))NBWkh_&FB3QZ|wtO?Ylww6H=mQ@NXZif1FL%PCY_a|Y+ z=qNxdxl-Y2J-WM|eDc(U1+cV7ip(P&>gwSQ_N@X6FL$W%ziGbu?EV^X9wzk(K&bZ} zTyK`ONBT;*ZKDV)X9^mzxd;D@?|JuGU8xxyH&r2*!pqqUR-!+LDQcza+c7$)gUd`< z9yNh`C?A8MTCDhtQdmJL^Y=x@Jb<N43aRt?<p48KqtMO0&9X2!0L>6<sOM>pG~`{C zXaZG-P^*=w&*tdPpA_JzU(jUXu38V)r(#IWkW@rphsYG75kM@HOOti`9%{?R%7}k> zhGd2S_Pl(-peDu^XtoyY#tLI`;Y$wfhpc#(>j^A2n%&?F&9!_I-!qV~XBaNiaBfh; z&neC8`X}th7&g2!ODY}Su_&pW!7|$;9MXrFP-svxZ7DK=AFsg2CVS&|)&DX8sfnZR zO7~dH(DgP38<{VFl_nqnn%EtgNrw5XFdEXC^2mI@22{F#z&`%D2XqY=rwmlRE?E4Y z11i@ACNJPx3Pbn3JUE78G&z<^*^*Wm6O|h_hFF5pNH1>0OBs%6L--n+ZHzuK_DB6M zDx2L=oKf2{K5%TI2%3zBC9W_&C}1j}!{`bypft=SeEdE-YNu<MV}6_=8Hof<)Cur7 zM5ZvbT)+1i<xiUMaCsgn_+SkAI)$F_VzfagP;v0WgR)7^mwyDr4dBOsE%z6ajKWEr zm8|%NK9Wxsxlxb2XN!Dj15Ko;{PbpY)S5mej*EW@G=Kw#uczhyPBX67`B~2}C{0j! zGjWQKdqagI;kNzc+5Q-~NDrco0(&0Nam(jAk0D~Y6yB``-=t`ME_+i4IdiZ0T<%P# zb7j&4Rh7)Zd#n)P&7bVEvQSGCM#nv-dt_KL+RxVlX4uw$Xb|6<R|3O#M>~(O%6Of- zf{Y%cw%b2rNRa%`7hy6DP1R!SUSWNuh#020xRyyjZ$`u{!O!$TSLke0<k2G8<#+d{ z$Y>^}IONJL=J0@b<-u|Z3ecctNaJ6oTrx~+kaR2xGc;f9c>eN<BfVek1j(6zEESw^ zf}^8OKPxhOW+pGn5&56YYB48ttr^}p$<h@d8ki4Pz6V#F5}EFXP5Vf#|GoSVgWTOa zBUW<m&ynnY0ve1raYfd`Gt$HNm??WnAtn&R6-F;IEX|~ZzvIIrzm1N+kuqOip4g*G z;V70U-m}B?u{=Ee7fS<CL$VgWBaMh~)`;W1rM^<>4h6P?JhdVE?LG?I8XZy4yY@X+ zx$y5+(yFg~6Y`Puy8jB({j8>N3NsZAjp}B)D90Rz-gv5pJYs|u7pUl5TfDdOVMlVM zs~E}KDn=f?AH1sK0_R8WHW!9%Mxc_So`u^5!iV>aKWVY`b)P`1P2h#yu+#E(HS)91 zZB8bQj}Xwq^Rdcb>7OG4DL2?5PI<`X^T_F<<t$bpeDd_E%-1LkhG^zn6ex8s`!b6g z!zwgwviAGtc0FSh0>APwqPw$G%w!y??uR<m97N!kMj@-Ap^a}$8lIcHpW172&0spx zI<wXN?P%rwfZ`C~5D&rQTWdaVz<@YP|J=diOMea(Erz9Mr=`U8%?q`GrCK*9nSD$c zX>!aI|1rouIvcZ?v|Rh4Nd?)tA$&6)F;#i8+I@O~dsyVf(8^x^VnSt#wS@M*-wts< zkHveEb-h$*6|oP+IGr(reknLAd;@V74^xyg(MUeo2k7ZSFCm6n%y<01e15hUM}fM2 zm=d4(QY<yBFH9%d@AbbLhNBKuQ@`G8vfMF7Do-FwUZkioJ40jimC88IUMgGEYM5)z zG>L(K6WL>T+zWIL`}cFmQ)KSy9nzjB%1sODi)6mJvQOxSyk2I0<2#nPgLb>|ed$tr z(G|}fzL-E%6(r*=E+*Q&b>xhPp2AQE4m-<-D^tX?&z@!R)4CKEzYy;bzxuBhhIyFX z@;UqRRc0tKZT9iL5z-C{3>h=|Hh(NW`IVFOLiqB*Zn8o3odbq4jUUIg0kWT<``<wZ z$iVxUu%AKEt1})4Z^501D7jUWX(>ep<XrQ~dlt?eRENhHAmcWVq^RCSi5gehOs$bp z_*DH<=Do_Q4etr+gI9(!`m_NyuGa9o>juf4<nc<|nJuFtL81(;Ws<2+gzrfJXfF<P zPuX`Re3e>}P^cQhy9R1z);b4J+S%43pr~@~Wd0I}R;^i|VF9i@bDO1GI!#I7>sshc zzLG0&u+^`g>ij5imfNb$YToXV_eAH#h}p)1$G){f3s)W?>{Wn#ls)I@+r#UVoVvD} zizYG@k|gnt2Z+4vJ>TL!k@j=OIZK?iN@Z3FHF{6ktxNs5RV-~*J$!p*VWw;1eq$_v zkfJ4EMf3rE2EF<@VanC}IvGLXC*Bx)pq~F}+%uCof<5OZc%Brw)><_4$3ItZ?6PYA z&w7tSi>;L{KEJLj18KSuJxtg*A*yFt-)`F;A*H|G^I3xN1?>uT1-I>UC<B#!?L<0& zu2~Z7rIss>`~)*&y7sVX>MImijAn$JfBI$WthaP-gZ)N(CU>TG<}R;(ec3mepx0%R z&R!BPl6Te(c<+91y-_fZJd`g#0nZK=*l+2H-GdNYu$;{2l8_{g&moy*ZF*pUU6<~= zO$3-)l(CLXsz)Z1bm&OAEZ}*RtXR<7qocM&?nA_HLo?DY6fm%BG=kk>lP%oT%7%nl zuog$Uj_?i4;iSFZ#gq7z)}ZR&?Oj)RoxhuTOrDH1i1ClMe~P19WbO|Z>d>}D@AWdR zpE31z=I|=pJ<?RIxXd2}8{n?vy6I3*+AIMF0=mms<OO>zUafDh%+7p#8oJ%rEcnjq zLOb^NM!BSq`}RdUZYlK&!k2@fGAHNHqZkDNFq}djfK198+TbS(O{Q0v-X#um@!|B3 zM0_xp1=vF{4ZzPZw|v*?!-Tl(ZUp5$cFlz~G_M8=4|z@AHVfa}JW9)J18dLbfb_Ig z@3yYf%Z%&(@ldQm3KN=1*Pgt=*fn=aI2S~O);Md#R{gv@25d8O7<L9$7oLZnM^XUy zxyACS7teCbPBMQOwqj}o?D$RZtt><aYV+i5lK>jBH&Ln+x}L1ik9IAqT%xEg$7#H0 zkd7=Id^_QHT%>1d&G#<i;^ffaaQ?H~r2oWTdQac@0o=bLM!$Yvl7P7JkL8x(VAiYP zTX+Ao8*j$tKCY7@9-97(K&1x=Qn*3+gk%|7K0ZM-1v?@E3`qz}malfBfQpyVX=T-X z`oApn^t>~jGAvTJIh&j}eBhG#4qM7RzjsFrSPu=qs<&Q%?mXZh4%b1OO{G|z0s)sN z;~83h^dub(V~-1$OZS{FBCC-&EgMtTPzFGT?98M{Um6#DLm$P&MVI&_bk(T6^oM!7 zQ}k_5h}GZK(mkP8f=}K=!o?oP3kDb<R?R#$d3jGLlF40*j!K>Q1SV8DYwaY{fI<b~ zxuYNUKjQEqcDnIW_T;5Y`3W3T;jbosqM=gW37pjmm-xNP)KDNITg=S)v!In|xvX`< z&fSLy%SsM?nKQuTI*Xm-1{t8Nc~kKNa;kfxw?Q0`#+Fi(Q4FGNQio6RP(f2nJ|L<b zYS0P>B4sNxI8g5lPdj;-ezW|RmL3E*`)HgB2++yz`3cZZhsp8<+N-@h-ROA5{%trw zW&pz4=|~bp+F(7YRPPN^uSoyu;xB=EZl$FCPBt>YTgtJ{flC}R=6PCog$s1jEggSa zoBs90g@o2?@HVXANv~NH9#U_xW(y89GCNCTU)2FPsnXoADK%lG_#`bkY#J-!jIXe1 z_JJr=2cWPQ@Wt{PI%AYlJ&f+UjQLPQ3Kty`bj5?z<BPH|X(r-8zDkBjZ$H;=*+*^P zso|u(V6pc9J`#AL9Dnrs`Np?je=XThp~)Q?rFSxFC*(|Te5y^53UoUPd4i&Y0l1DA zCux)mh2BPE1+;velnD&3Y#^A90+_`Gh$~Ws6i@|Oc)9_=_xm&k!}8#@2zWN{<9) zE}@a%MK^V_O72;mx0kE=WTLi7Sw62Y#=nK$_WM|@nHNnm!PK85dFDFlJWtS($8!A$ zH17l?hz_@i8DAA?apF0C!HPk#LI40$*6JaYP;BD+6<Dc)BE+UEOY!89LiP+{4<2x? z*_Yb#r9eHis_fxJ!4&So_93}SyR56Zp7jpy3Aee+&(WlgP>u>i%G?K*AE#-L`JVXc zsB@~DbD=8O7Tm+{zMi4uHk#n3sIwe@R+Eob7-x%P#yao5m-OsVv#aqj6)H3uN91AG zyWELlDdQCypRT}vS<gv;Kg6})Eje^gklilSbT9R*=MQ9(#6WosD`Sw|eQ+w?P!?J- zdi!Ij+uwhaO7SMS*mQTjWaca8$&)K1KK=;>rW9(9(#ghCv%QM2vL|$IB6k;&LHrMI zrb>sLcFp$-uq#0_8Q)T>F_%g#Nn}N*Uuzt~|7{rD_ER#+-@REs6A-Veu%Dn4;>`9O zs8@!=f!S6*qOHFWv7ybB#r)v}E9x6T!~o@4{=|cIK?vbiy0aA#j!_B6w_FEkr<dIx z3CFHUJgqJOlGMbSXsRvs-*sE&I<LoF`@<%dC=vsD2^S+ptc3F4c_&gI9XOP!YSg1v ziRCJPF`#UQ*yU(^Tke~qC)hYfw_^bMoY49ue1sXqjWZw6{s`7<dmj8hwVI_`7mD0} zV>6Zm-aUTYjFkn?{@$#&_^(`#eU;DuU<G&a1hrqFo#u<7jK`na1=Orn{cc<rVc_Wg z9G871`di%np<4(^?HYcUoC|sb>rr6|yh+rI4W{Q$4#Q71^UYwc|KsT1|C#*%KY(9m zW6pCvv(0JF5<-&0FvsSYvpIyEat!5NGuzCW93qG27@{PEq*(|dBvF!6tdg9Q4!%C$ ze_%gcyRPSTyPmJ-^Zua1!6<w(Hy!}@$s^coJLe+GzL!#BAHTMG(u5{sI&TLPobx4~ zOslqLHZ7O0)vfKRPSG;F_mD8!?!%9~ag)@*0>sCW+PmVQR6H~ML5%8YQ)<a}`k(h( ziZw?j`mbTVRg28(6HHvu@F+96%H<ZOy}O$9!N-TMkzvEKxuie7&rbKRjnjT>Huhmd zRjP$!7$)ji$-Mb16*_GNLsnle^4|4x4dVQwW|oV$`CPp(TXmDk)K2=u_KA6+-hCWn zrjgV@i5)?DM~Q{Vw#q(+JJ0X(!~>$O?Cu|>K0W*K_f$n5%l~_%{2*)8pW?0!kE~m6 zd}(+w^damMy*85}&&kiMK{YVA-tlTzYV$I|CmpJ7ZKPGzeS?u21BD25;)Pw4D_WSu z8BFJ@I(eF)mtRmqL(itViW+x4N-GvijV$bbMUmGOX&X8F&x8E;sIdGSN!~hND;OMv zBY#{u&#S^)G*Q3)`wV%Ow}MaXp3LbCj0(vgDjJ-n1g?xfO!ZhKpP}Lf0pMhFo;Jm# zUsV!tjZpuhCxccXo(UZtp;vZ8=NzjO(xDyDVv-RW^!2_hN4@Ner}D>{XM84dNJygI zmgJ?yXK`m=l%cZ15na@7lcFIydj_-uWSUyvOPXyVwV2vv*51@jby_5I!I^}JOkz-D zTr{P=lp>Z1-TrEt3Rn2DsF?<srB0~i=R-Sk1rHt2b0Pg?jAqZ_Gd;=)4obe<2^lF) z!C_ebV0tgMrCH&s7u-d6Lnwv?h8d{m<YHq0ATUCprzI>tm$1g4bnRyWL0q!#wAn_A zg-<Nh$rHMlPnnU?_n=e07vHh0sv*I7ep@SEZlk0-vGiEC`eVpCP)HC)GYC%cfP-By zWYQ2Oq|Ksuh`(=+ztxEEOgb%-VlW(|zo(~`icujS1LvPPSZ*Ntk`h?sp(Lk6ydci_ zF4Z*kP%frRSES1D^3!2*Zf~gnS+=mAOprj{H{;Z;yQnB=np0OMpjtf4(bxzLv9Zqd zB+FW}xSS}fI2PG578{ZF?hTU7=(F^KtXSqpDjxS=(d9JmL)*`$cvMq_C)>%mO5a_} z&%>!n#i=)QN4+~C3K~{qYI1&b**tDwW#sg|7~wlf%4|fbP7btj0c8dOaaa_4)L%{N zYP{@ZjR_!={2)D<^bic`O#NuW2PK=B(c2Sercq@#Rw&CRW-0m5OYbdx`NzK{k0u?m zUS&YkJMola3qyLl=6&VRst(Fl{m8YF!DHq|V-IL6d|WdB+41C^-QYG#ee=MV!VheA z$yUSdPUOq~GjYit6qCRGU=wK1i6a}5YaK<jE7ldIg;DxO3)&vHFJJ2(sZNWupLq5w z^(KQANMOBc)W=i*lEg@cPgIbHxXNQG7M0L;)1fpN5=fA$zdS)=+$9y)#QU|8se*8S z=&$+G*xf>kQK^L|%ZW(X-M|uJFs1lgi7AWhuRCnpkIk4Z%HPtFinSLChvs$<3#G`% zw>{VZ1LDw=n&|K>*{1Oot0isxT3d2O>;Q$P+m>%oSK3a>O?LnjO>{4ijRwzdTWu!@ zO14A)GCMThvQ5@6{S(XLb6ii-I=m3FM`C9uU9Kl%TT(9Rk`>JyGl6N5&u2=DvFX?W z0a5!4S>x2q0UiM0y)?d-Nzov&-PbCsdz8(#+p(cxVLTwVGjylmEM(6WVrJk3udTXo z<@5|z?~iF+N_k~7ina=8W|lNMI}6FTaV}#x4wO=enUrPrF&|Hgo2@)G*O8py94;t2 zl$3fW8v3kCCOscIPyoHR(ja6ubWU3#&6Sv6365EX#ZN)~oDtrSv@)rZ?}z)b2`T<3 zj4(#ipE|8a1Bc>HDBR4>0J1-2Dvqo2&8S0qy>oJP$Arqz#<da3VeL0&e1#`eNcT;S zr09?*B|MkHI0ii@Q=GZmC@<abo_$8~6f5NUm9FX!HT`h+@kG=8U(SiGvWnaH<+RC{ zi&HETSp0F;@3%<-#VJk{lP7J=J*%!c<#QAm;^OH+@=z^nJ9Ne5u6j8|f#Mvi?Xi*g zcD;?V`JV836k1b4F>xItorG4ps^?(`DYB$){+Ys1jwdaAt>8-UFNN98EP-1jH;NO< z+100$bOuTyZIQewX95>peMCgP^2$x~o`#1jlY>8~f`RSjhEq`6%`ysA7gT-;D$<En zsn>r>D&fkV8z^{S|Ezs-wLrKw+vSaB>(JdRrfp=ACjk9<M*_#mLKbPU(A$3Y#D26% zP|ZI6?(H)HdGw5<5mFt*c$GH^c`I39hx58~m|m#SO+gKa?5eS6b@Y}~zQ<BHyr2VY z3sEKGWJcN?HvRTuN8d-yo7#nkPoa{Zo9b)tNq;QG4J}^KWbw9l4GMPkStR){7V=ii zx-keIhl2i*<Z^2=4(k-s_3$j;T-d9$=z;sUA$Sfh0+ak=9xvN+IpuA2pIE<q7IuLG z6X**+KaCN^@Au{4)1;g$eCjEjEO;D@%z2fp11AO@)@*)s_xzua%M!>CjA(-R;FnAv zJuGlfdu?=AOv{;E+=rO;N;g7C3yFH5acj%ksYZ{#(@&?wbid%#tu<ZFG`fX6zIEpY z6aJy>wAFk2;3SB@;BBQkDA%~(=4VJ=jilNaoG$}{g%Sk<$vrTGcOaDNLI9W0?Vrw- za=q-CxR+#xPgy0U=RfD9S^p9?T<W2ZFybPaVpX6$6#oUWAM>=W8Ojn1Mcq(HE5>Mz z1f&h&><w95a1hGp1)Qt@2}W&!f937V0(6qx;QoL{(3=p7a>oa^z><=!DKf^!I~F?l zX9WuZ&K+DT?i(NteR!D${n2Ce;d2AdNwzvsCe!u4mlq|t4*IU?oC|(1@6lRD<mbp6 z%$|%j676LFAB>Ik#V?ZraIgp6eg~2Tu69y11ETRE%vevN2|Ortd~U!)N7rlD2G~lL z+zQ(0`|LGpDfS0No~=u<Iq&XG@g%f=GkQ-6R*=dMB<BuMT7owot=aw~`PY~FA41gT z0s;?79@Lqeek@@wEaYn}nF}lHd6&sRBj3@?t<RlV8n?T=puRIb<l<B*mJq`TF1;}5 zhCgMy)G(u7;J>jn$EDmCag>{ECQZrivt3f&BC6y=lG5PXl|YgfhE)8@Z(JVgvbfQ> zZ0^ws@eK}@CezYUm7ys;WZlu=$2}@k$C9sRX+R)w7)pB}6hCoN{QNh41-vyeqHmxg z?WpqzC1^HO+NQBv*$JS9%m!b6JrOqM9UdWjzj12A_E?DQ4h5e8v|IAuEFx7~W;XN_ zKQSwv+2EbOGebX>PjS<}?J8+1`7eC1Z+z5AEp1k#B>JV$^(Ns^XjSsW#4nHY0&Q=! z1nUj8Hgi8YCkM#g+6XGhipk*eo`@I=WHDh}@EUq}@*v<2AsQ@89)~CD`L>Gr`s)Zv z_r#|DT;v8~J{=>rO4ZhB`TV!JS7U#ad*#QsC9H2Y)G+<+wf{Pz3Mol(1|7;~5g*U| z{)JxnDm)kSFtcUzS=R>NyAAhFk{S)1^S4H6Cc+m-MsdV!>Fj!KLAC^0MhC-y&M^Ha zJmMD-Vnr0m+g{ZRpW;74d46k)1atKwcZwfr;f~41nVm}{4Zox~iX_{;OKP@h2~ucG zN&cLWH)&PcK+kk^Yc|q{`|h^-&wz6pmw?#~eV;h3Ad(Tvhv$6Mvjn1+2ATU_RCFK7 zKv=ZiZ78-)<<|agLm8G(-FvMUx>ag{zKB@5@zPnv`EqD<DR%k4@x6O?gObdr&OV80 z32esIlbnA>^Ss;eFK&gY{j^y#kGQ(;e4clM%wtFRQOrB{Wv(`oPo16fqS3?NOly^7 z6-P33Iq+o#Vz%O>y<(B0^2KpuTi-5S<9)M)gk0iU2DW;K`b@y@hv&^*H8>IG4L!IT zHzwqJ|8K~x`1q)f6v3b?Gdcp87gD;}p;O14<ry$BheDl`7><(VFQf#wUim|Uj|2~Y z;A;WJ-f;bu#%~%iC#!L6ib2maa7Hm<(7Ec(vIM=^&am{Y1D`F3#|2XS`55w6biM*O zW;3$=M<jqbDdT5&p5)tIQ?mTll-}Y^?o<U@bHvX|Xjpf@Ov%eyfmV#!jGZ>cN*;yG zu~k0wkNHfKd)W7qkNLv@<#zH%#dn(1VU$J-WDAk2Sv@Ybo@0`oW#-O_p&yfXejkUz zUMh~dqVS&&lxP7Zd#)epU;N9F$0oz^Uux$nIas3}0uLc`6%}){{=E*dh*WD%suzy{ za97E*YyczG+a)P)+i{hURGycVef(6reOK|e+ZwCw%d~q5v@cc-fs~mv(VueSZy#nv ztV6soEQ%QpzwYkNKlJl<mBSzIX9zz`20?b%4^Xxm0KmNyjfz4JqzkG0H3h$_QgP$+ z)k`XjLMj1r7F9NhQ80L_>ThgKb+pZZs!XlthVKh=GfSnLATFg?)MS-;4zgUt&um0q zCOkS1YCbA*hkuUt2o=MFKc~Ue*53)0t4%9Gg;ZhKY42+yKJv-Ba=a;Z;)!?86uJGb zshgh%^e^re_k9ok?cQ_UkB}JPAzD8+&c1ax?H(U<I2$VL-Gg{kAY^fHsU*!0NJ?wu z8{yB;S0YCq@|^zuzT?Wuu{=8u%?(fiXjJ2BKfW}q=KChhV=eO%!0=&P@eoor)$mkZ z+^pi62rr-~g%w}C{2;lZTVO^os;B>1Pee1D+(hL<C-W8FshEs&@r4~aQzjgMRN`te zy1;pr{gPbyw98F?E|3d0q9u7!nEx`<G_NtRbn?Aw*+ysKJ?C1LrchPPYxvh@nqX!j zz>0T7$*}?=H~?-g3T(LAOBk8yPR0V9Y<L*~ONSZET<xJtLbuTuN$;l{^b8GR&vu6D zH@8(O<?vZEX<*ZgXsr}YED=t#1;MCjhzSco5I}TVnO7GKiJHahUbH6(FS$;`xcBjs z5n;$X^;H(fpB;HQfgxJHsVN*`&woK8HBZR1{_2v`dE+MzC#_thtl3*8U^p(&Z7&VY zttM6wziix<q2@FLG7_$IDw*_tV!$_a<N1Vzy!unHzXhBwVeQ?-d~LcoIp03kp-RQR zU+|*nUpAV^JqSBK1f_@&$aq~<8qu8v(jZ+?^K*(Y7uDB#V5+OhYSin_rCo&n=T~5P zrMXf0TfDtP*DKX4(EA*ZgycMH=~tavKlw)4f0<C{;C&j{4KddVH@^ys6fLdx7ElWQ zXh&Qj2~JuIaM;+M^5{FWQnrh>9M#QxDoV<*4?gd*mud~5bukD5IZ#WUzCYR844WSG zO`UjLll)4Bd+e)9;mbO{AsGj0mpHorLKUlgJ8Tu(|Jv&Mq>}7K9bUy2yVa2J6x_Gm zNuQ6~B_qHe5iv8DXDXW)cDQ-LW;qT-p6Pr??++28n$Em1pr3(#Es|B**;|vW!yEfS zjH}W#wcsl@@0?fc3=IgosApvl!deUGXay+WWPRs;X*TqtKvaK&fnTbZY+%?~OMwzk zzXsl~UvfKy1P$M#Ys<;+&0L)d8qg`A#mXAK@Z9d*Z;#JU>&kNOKQ?upc-nwII7rBg zQMy^%i%tz##c&(Hy%lVs*Xku}h3y_de!cbR6VneDr=uwqhf{L>cnbpeBZ%4*K26*B zSR*Jl2D2wixW}qGhTuI)nf$j^cy6Ol?>zEOFtBy+kA1)QVm0MZKR)jhjRV*Sk><?^ z<}LLFLpA6_0#{MIztfb11t%ABj;2c<Btc97Fx6}@S{77AwAB9qRfD1OG?%MfiWw%5 zffQb%oQhy*Cq%X0Nx4xGX4SbkAOYPzDZi6w3JQ(DuH_m65lAgCAkns-tLa)RFP!&j z99Zm3qX8_>D*+l=Waxs}HuLim=moq6QO30qx%k3FNWw2)Ec~I?Z)BM%<!WlUuPn(^ zV#H19)Y<wHdt`=jbwRfgMN?n4n12{vsF6o@3;Q1C`AX(LlSgE?#j3>P?`I)r<_hRv zZNax)IJsgXMFeJsH~>uNYN*nb9hQDN7uPf-mpH3N&8*~n+&`q+tiU_IrAj)sO1lMM z*%oMzGrK3=%bWx?d8lY*Ij+2qA4zD}*)l2Nv!|jRwpnZf-new8h<&uu&Et<w&3GGA zi5;~pg|nk7H07$!YB<!xsZ%k{QItRKdc3Y{j6BiGN<q~rzL~BEm-+Q>$;jr(0<sM! z`NNIl;I`s4jBRDNtBky>aeH2HoOMibibl72UQ<Y6<;V&ueYuV=v~Z&)(Udm`2YRut zi<T$H$mSp$_~O4$BT3O1`JfP2?4UXFMPgQ}{7%=ew*j8XJID9Yhwe@_Pz{+vT~uj} z9LE!f)$;*pc~&N@x%(d^SIq3dO$UOxXP6?4IBO<0c4zcm9j|a(v6-+2Q|-(@bhT-T zBX%p0o=!QX2*}o$O{ZFCw2UJ1oVc(lJL73hixL<EmH3#eYJewjLujtdRR5h=8K(c9 zXj;INR#2+$MCFCo`#$@fv)xEKC_s|!ySdOCpUGCgi)|C6o2Ti0n(wQGPO?s#H3=R- zWF&VoEhAEyVDm<v)X6W3@Jy*nTa~(Wn?KP~y5jy&rqPb~fgjRLpOt8mOhG=JjffAm z>4NJMd-(E%?XIOGhV^T%3nSiN`WqNf;|Au<NRTu?*3D3xu<N&lRYaEt`*OGsZSywK zG(;s;-XHHBJb?*)FW~(n-5S2n)v@)}`O(*0V4%$wGr2|nGUHo?Pe7#tR75_KMKQ47 zYgzp6%7f4q)A);Q$)qL{q2smtnzP)s<tm48i=fnvCnFKa$A#Yx$xV+;LTGUsV$9PX z9__!HI`{3AHehV}SHq{DbnVScMDsZn3!oC!Mi5Z8aTRtu<bTnoGEZ)wH?r<e%Pz;% zN<<rGNU%>%4T@%;j+WRPR}a+YE4TLd)34GH4aq6N%p35ngCH28CK^#tY+LevZ`X4n zd&W%$U-}Q-*|yG05M{$7=QP?=OF6fJa(=nviL}Ejk!`W7)z4S~*T&oTL>d$<>cY2! z{yT%ty~Sh}?apfjqTVnn+7vBztULhG(mS=bCzYZ<)jHIu*ttx1nwmtoE=ssd=8;rq zpy{etwnm}`q3AII=(%Z7l?d;CvDw)S_sqifKy$XCc?X4Cf}Zc5s*RjE?ch{pPeK0X zD>qwB4Nqr?IJ{*63=I;upWMICS{mB1j%u~qA8bN?yh>S;oqDZog_0?}apz5=jB}YF zbY1V$FSVvz7B3n>$k`&TFfRFX^=m(dSl;Qf;V@g9;3IT<5mZT^Q+b7DR40y0!TZ7} zCKY`~jyHaYD%Yx45%~vsE9LBuIW3d)<CBA%F}r)F<KB6K>y%dRNpF{<y?EO3?oEE< z{#P$SgD>9vIraXy>BjlePZ#$-aR1D{T&H*}?cQP%R+)XeOk15geiqD6#8#+G{jHn- zQ$ge#j<XN+F0g+_{M7C}@=Qu5i{;fGh0#>pI=PS?WtW`=Ht6*FVGmCau(QH_;2v8* zM}Ell>QBm=4FvEMUbZ-ubb<thP`}7tg<JkCtOf(|w}4O>w}Q(4!e&w57DCe{aGBr` z_hxpPZ~v+uxS$sNan&ar_sRZ{XD{mw6CZ?mM$(Ky`(<Q@WilFcUKCn0Z(}1JVwPSs z45pXxi*GrbYaw*?`d?Z08<b#<`Le<6y`b@PgPiV6@{!VQfYEp@8b3>4|GtQa`tfw! z#V^t&0<wa*kY=6EWq-iKw91cIuocq)A3J2Er2tU6b=??&T`fmbg|}<LSy8@<?+0OC z_$#{TO<#1Vr-v2A&M=F(Ym1hy$)2RzAT}HtG)mr}to~V=Yjm4Pw$hdBKZt=%P@M!7 zUF10LkQof~cako)UApGn-}T+I?w5qJ>xz_)A4V66owfYp)$hK@C0ExU=u18_dil<| zh|89^Q%QWfh~}^1SIT?$xMbO|f+E}sWOEgvi!W|NAkJIR1C?9o7Edz?i3Z|_v@IVq z*-8n*UFAg+;hN-Q6|^6(iJQ&{NDWN5!&GjSu*zddx3Kj7W$ZS_Yxbp_Xj#7C8D4IN zr8kNUs0Q+yjZR#%M2B?VGEG`WPx~j@qm8b4*lznfEDu85i7OM50Jvz|3%uiHW<Jjc zZOkPykif^=>dT{LD5xaC2Yy1zj#rwM$(f_1#>eOqJ$-7iGG^#k?)udhTcxKgE0%4E z2gWScVrFM9ffX|e3$FbS!d+~=Q^m9Ut(Z<2nlVw9l2;gXTrD~ZZ0z4fHnpKTMAz8| zNH|&%?Hke9M)ao=yZQk8uaRUmtA0~M4!t@!Fq@`)^5cdkf;fWPh^rY<#zM*4XOv0J zVCDG2M6Le>sE7tq#`jAc1Uh({Kd5wywL^bzVYk&64D5k1nZHNJE*rleivJg|5Dqs# z#M|||230A<$G%2o5m8p2{l<CA7@`VY>QmPOpd-(b1y*mgPGzbt8_iOQHI57<22hCP z%Xj_pckz5C-fBpHEpvh)*?S5iH!c6%cCf4o#Qv{eZ<(!vHiC2MS9j}gbb5)@&AM2H zzPhl!!^AcB7rl-xLpOO{d(ZGNV88BwK3Djv7BKoQ33=4c5S&}iv&7u}GRm;*pQkR0 zB^6-scd-U!!gM9x5OjKH$-=Y0fO|!PPIs%2mACnV8C<&{F#i#Q>=Pi_>JyLObjn+y z<}r(~Og^*smc(rK$*iwm(ng1(uns4jVaG=vp{wFPay94xdsix_LwjIT0rpIxlq_GF z%4o7+*qoA9kVNC6R4*v}23^bmgb8TK)I$=mUpm9*#I;bv)AO}i=$QtHM;TPS5q#H) zc-g)GuHO8GI^h7z&*%h<k&uuXX0bv{IdB$V$?NkyOTlb$C>q-@It4ox5d>g-Y*o-Z z?%<|enZ8O;Uo!~hlw33{59D69ifrh*sw7Wr@W%yPVH?oXm1RR9L;}<EuEsJ~;;jl$ zlRny`X#fRnLSq%o4yCOEiry5kH`5!ijIY>HOxHv?x5)cP?i<JU7(1aFKeJhU@W?BE z6|rjD{!a9O6N5jdfF<CDc$G_kP2R|>!I6*DhK{1qCl5gKO??vh1@nlSvWdV`>1a&E zoN^PrE2L2)yXN!>F^p@(0(Jj<i7C(xw*O{r{t;yYT*4O{(Hj_N7(^h+E;Dv0b=5n| zdt*)rq6~rzy?rHe&B{!xY@`<L3Y{)}Prg62@#V8BEt>!2-VvsOP?;<C(`(8&6F8dS z)~k$dffxFLP#fH-y>I_D^y4C4D!}SI0>Y~wWSeRQV8fbwjiz4sK`(iu_4T*|tG<7g zCufx1TS<^G!%I;A1u$&T{|Z=K5<GM(?aZ*Rr@}rTr!lf(TOkWgkTa4GgbnEPi+4;% zvu;_fhS`C`{Th`g%pwfUCs`nuTHpYluH3`qt1)ydLN>NY1_+2y5ZJ)fSIfB&LvKXH zKufK1AD9Iv3!x?Kh#Q!I?77y>W0!udB*03*BJ(iV3_UMI<16o#!NPC-_{x_)&8;8t z4OK>00@FMFK#Hyz)-zlu+lK^Cbp~(q<e+bt;g#kt6Vqf6N&xcJ8U4NKp=mAyeS&i~ zq8s|JSP7Iw;}w{hjUK-*KpU_J2O<EOZ8O*!YLfPAvB0z-gHM-q*8zOlq5twK$H>^j z6Gzmp8$GqL6<&Wup_4uC2IJ&HD^Ll?f^Es=x%5j^MNhX^yH>KlA{a7T#ts;z&MJ`n ztg#f1K5q~{jFuJ4As&H@qPc9ip7>fB$lirWg+u44cKsW}7x;BaJbFa#vU{djqu26L zsGxqTKnr@~2L{Z=Js@@dS3X+HcijrSKWEM*qq$ZwftnvfHRVZ!Z7E_k#x_62n7>|} zQBi6kc(j^4zoB8?xmvFM*m|u_7zXOgn}FX()2zU2@|x~75SeOldKFsaF7z_!3%ZAF zNVw=4T#0%dW97uYEh^1?M{V8;9lY4s+z1ZMrlw_XUxn{Xvu`NP8Vj~*P^uQ->vtq> zFTAcb7Hcxuqse27IZqzs<1=|6WvxBkXh+0xC~cvYBHw!cak~88Esy$>oYl=91N(o0 z{g*&lfgLe6j$jVY%I{uiJx3zwBD!-A8dD$E(f@^FiQan867<)h?|rM9I-L&&lDG+i z_z<=8!4IMw@esOczPIJpT^9>kvue8g?68chu^e6sz%J7UzdGKm*LjmIaw?71GY~r) zUbXnptStH$rB3f`|K@P4&;4byiI4uaM1$9-|MTvj`S;O8s$q%|6Rs<oR!2HwZ*u+6 zC(}aGx!c}BkJRvpeIDJS<rwR*p^Bms)IRiy;XpXM=8tWV3Qx5@F>IWa6PNVHnQEfg z9n5G;xOv$H4hG{mZ1qLpk@owFS6Z1wM?>m$kdesX`U7vU4{1{hRVIe~g7suQ81s~O zQvHs(s^HWoK?RAHYCCZZh?n*&;^{Kr$|kXah0X6WID%H`6VFQRlPR3k5{RcY@yyG7 z!65WT$514Pt`%lv4Qq7>hTN0QR(dyq0eeiYl7EW{TnYXu=V_vl2|_saiMt-4;F?$< zrs*KG1>b0vLU7_YTe#CN5!-k1Lb#g$rUF*s#%m3eh84_ojXfi>+qKnnUfZnxJD%g0 zne4YigW4RPj-e`|Z%h!jrtZh)X?v%aj(Xsr@FMl$@j$lBtHQ~Gv%?QAsmV1S{yN&R zydjYIJo0#fK)~q~%m$oR97^b`8<_F>WrniMPA%5GN4d#CO3>@q=jp=##`EO9X0}7v zQ<9C3(sEq;gAyS0ITr2@k?PL$)XTc{ceDXd!hbI#6Q7?_TnvNP99#;BFiT>HT6|C7 z2rFR))pLiH-PFC2Q_tm(wk?9lq5`puuBtzyio*K(tk+t8vvAgjSLU`d`}J=$i@>aj zLKl=5edVTFz!A)VF29*um>yRU9p#!VhzA9^9bTaPEa%)%%r!BUdjL@&)7DyP-R!8I zKJi?Fe5^_Ius-QN+PH*)UOh6af$dW>U_M}&6N2|$eI&<q)SK8`52B-l#%Mr42@5&4 zU44C*5y6xVwy6)?>ni&OC5gL$<Zy|m&P)j0_1Y^>(4zraH``2IBjK@qa<PXOs7?)z z=uH0y=RbtP@g@Oh`)9V#(Afv3fFy%Ue2zpT1%)K~eKmn&q9BLpCf(abz|KrpKes8H z!sTtX*c~T392oUf(9;CIMb3ZQVLz*>SYs@lYw~@z#|&t*+IyUu-+AfE%Q{DNM|J<) zJ*##evs?<!VCl;g&o6eT(nrkrm%|)(tWh`T3x!RgAFWuii~0{vC@d^U&VV3Mkc15V zMH%6Cz67T1?<&Uji6<P2+(&2T7~XiT_w3#P>Q8f>di2CuBJoM3%wbjgr>n<tAI9xq zh6YQ_KK%AD?d>lk572)&@7^QkeqF7=_Nyv2LRp;rKV1EEmeA;QLoU`>(8)xW(o>@V zdG;<_zKkF|%2cu8o^=oXw)^?-cmi3PF0(giTz>Ar+0Z;J0?QayW(EVv%xpqh2{2z1 z633-BS0;Erixr2WOIrf3zj>Cp-qpQgm=7lJ(6DG8it)`!v0^b{(ip%MCA)V@fMv`V zMN=XcIX5onj`y8s=LnCDoz63|%ta12Xe#i_S@J9UjyhrAyd{?Fdv#CCVHIpoPU@!v zrf~8P0Zj<IlN=1Ny{+V|>KeCfWW|rz-%p?{W7|^B8p=i`NBRw99E+YgD1Ip2n|Qo7 zcKu?a6#hmw|2i{X)1N<CjR~WOim5Z!09@4nh_Wt~pA%r^0^yzpn_FZEA!-9IrG2m| zg4#iF@6_n`<MMe7l(+bR2RYo$iLzeJv4bU@@17ksWE9#Bed7!8j%$#$6cJ_$&IyM9 zA>9PWbljA_dE@VINH6nZN!7?EZ)zE6nCWH3&4szl=UISCJ&BMc0!<@SB+zR#$5GYr zGr-}Odjv-3N;cuEX??v3cisg!dNuR{d;v`8&%*$2e%bp4Alxm>STOEkkIEE#<s+%Q z7y4a2Vj08o<pCN0J4#yZ*-<K~W<SSBcc4B?{~ZO#2v{8xM>FlhU}IWuJ!8i5<|V$A z-<;@@uh3uVB1>KU=li%u2nVB(lgV&OEx|?^!=cL3m<Ctt1po!2fh^-5m8Hr*hY#}A zlzJLM52u;}p(iPlxYaRU>jhVOcBe|iwlxsD=P;B(X<Fsml-jP!`c|<^d5Y`OdU(rb zFnzVzsB<Oi*76ZwjJcRU@f1Rct2OKO-^Jmg4-w)?Z)~q0UQU%x91Xu$er=(P6S&oL zj$uqd*3@GGj53si(4ot)PacF(ObPQM#YkJ$<vk>AF~+_ZJ-?!whisw}pJ2dNU*Y?) zWrEc^1TJtBCR#9fw!f#k^?@DzRgIe))7G&vLR61_;5ELH{$#BzZlV5e#qqC~>vu_Y zVHbeWO4iHQ4w;N3kJV!0*ONO)k#O-acs-r8BM8+74j_1Yg8Q2<a2*w7R7bLbAXF<w zNFK%Od_Px44O36zT_H>>qaL~ox~uW4sFzSieiv5<@L4J4$->n4sQt?rWU>%ofx0JD zZ5k~O&3#|x%_+@tUb=jbFms7@fBLoC-?D4tiuWq6O<xX@yfGq)l3-cq{ToyNd5qzm zPXAY>O&qd=c35*+d3;ZC$W-q&<8G+p!0_dDQ5WjRe#1w8&M0G&i{Hp*sa5&i*UKmD ziDN9U6}(kdU(00&GFX=lua7dd9J@FHI_l*bC)o}F8>6|Fizv<FfJ>e*&Suev5#n0Q zzp$gUQ%0>3mN+&tSQAnlmKAz*<Zc40%UvBnBmxrxY3u|ILR&LD1ty4;*d{CW81vLQ zKo0_mxj}LP$m@A%g{CcXcgq!-bxX>%KesAsvCCZE!QB6LEMTEbfClOCQ@9c%kHbJg zTKC(s$Xi*S<e?W*kF2ZD&CZ%%pJ&dFlDORk;LL%VluV%b{SUyImorgAo`p?36l$3V zQ@nr}4P6K_WWHleMUyG6C!ycb&{VF~ThOJfe<+Jwy9Y0?<P{SIH(G96!Sj$39u%L7 zeU)M7P1V@yNqg?8W2q3YM@}B2D{6_BCupZXyvXgHMw;7b;>3#BcM5Cw3?k<`G(gHv zw)_W}V4M<=C1(X2Gdf|Qo0DNOL9-Kf&|4-15l-Opiogk=YS-~!ozBU8l~~at<gCW% zEdc&T?zCIp!9;Z0dB1r?4^8IhsSFu0W_~l-i`Bj0DsJ6tg)iz+xi|cH4XeKTL<A2G zrR?8APJzE*1etBla-%hi?G*v1J0*$p%#xPXtomOosUNfKYxXpqE^}9*GBPWPtR)5J zo|s&VR$Hfh8zSeU&MM_VhnpP3;-f5n=dGJ8xV;#+2He@we#HGq6<%71xRxRSxK?pE z!}yI(r&%8#|IMkEE&S$bEN1>{k2&}k?d7?xJ0-ajf(TO#!H9(e;6|e54ZWPI`S=U? zM8nF<L)N8Pk}1w}r_WTkBISRsx7fM|H2wU*3(RbhZ>zFUSss0sce9o`>*UK7l{RT? zUO1q7bs8Qj^Mz%K)%DYz8cBe{YO!&xB#tdVKIX5ZG2UpF5XS$ArP9*)sP-g!v5&OJ zM3j(Egif4b;O=4e#v}c&zs2?QMNOK*soGtATN;7&Uu}`xycD?_gkr!{Qy^=ro)K-L zy3}g@3db!+khE?lM+55{aI5I?N$;SD7bC)-gd-dR&@t68-@Cxah+Z(lbCC{(IDG7D z(Ks$2{ha~_FOlR5gaE>!dc>8K(y?>eyejF9!M2d<-nL41VQVWh;TP^QH-&)9169V$ z?kmTjS@gQi_7&wYU*!|r{&<_y`<Rz6dX`!G`W;qnL5C7H$AsEvV5|aH6?381Pxu8q zy|PL<S2b58On!}0t43-dY#4KU=Ze77j}*gBwi}i|elkf&m>l`cb>&jI(2bGUMze{F zaHEcU8CoCgEs$W}bQ^{AFYGyB@xu|92Q9Zl8$ahzyKhTlC{}<*eG?bhH1#{Kcjs;U zfP_P0Yag@J5df7}G3JhDq(t}xPybW8^IYijJ?@o^I%~SZOU_qO+56N~@y#o+^y3F( zoyJ)onfQr`Nfn_*jvqHuoYo%hi=1xy=#}@G4-8E)87fOmS4VU0$VA~yYt^(j&h4G# zlDV1)AGM^WWE_>3tw_lJUGGp<yVm31dcouVKucY^5-;0%uyh+kuM!)e6Hk3Hq72%o z_rjTQJ@`4wtGRY#LQ8h9E-{)XT01$w6)vb0X43s7l*H(gEv7RAgi*RLGi|;t*|&2^ ztnqzF|0K&?ko*(xx@;h@`pz3a0m+NeYHAMQLD8Lc(_Hut;r=j4Y-(Vz_s`>Cz0t2& zi`zdU;xmjq;f6nqV^ZO+z_c~In|sx0lQXhLe8-g8azPSY8L3`l41ZC?b!=Q^m)p+N zS)D!(MIJO<c<9r=vfZT{Uah*25ORtq5wD6fSZ^SoRu5;ap1y0383zfC{kXy7&)8eI zbd~iO9w1M7o8%n|1cbL#ZEvMQKz0x3=46>~j)@Jy!OHcXq;<5yIv41(LTM6QQnHY7 z>V`Dg&HA?BnXjGgvygyY#30u2rxEAD)uMc-U%9V8l7C3=MJ&XQZ%VB$xYCfY*DYJ0 zQ#SoS7cCCV7@_AQ5Yr9Fy$f*93xAbNs!cTBgZ;qgAAo;<b4PJk0F|&40;=;qhb!k- za2UKe=+BV~Vivy1?Pp4841{3;rVM}!CY`Mg{cZ~n01zy%n7WSHWPk_AQ8JeSSf_`! z!vJ&^>_}1^%fJt$LFzo`cbTJ?U~MHbrz+<g^<~)d@IPx9-oG_?0#3Vva0p%maI9Pe z(|@0#zjHknze|5*lH{J?;r9!nY9RK);p}n=C_f*xjZCZwD=Rmvw+cyZ8!n~%XJpK= zxEY=f8VR<MX=B`cA2}ZxIvB=Gu4r;(tndJRkmfBe?#(X_5gZV|pQz8=kSYZznbjKQ zz-})x8F08|3_DgjO@0JNE0CnB#=uBu#T5j@2C-#>_-CdNOHd%F3}I0`V~VIzHfDbM z(v;d0f#r#V6@jw~8l0e~3%opsMoWP2>=yjv^zrv&u!+QWE_??YB+>#0VMTdIPiOK< zZYIm#ih}c0sRT5`3nte6Hlds*S{PIIdV3k0Ow$p(%s?7PB%W>Fh?Un*T6vj;r*6WV zA~?A$;KBD-iC)f4p9eEPJ;2S1jgxW8<u2LN097_?JpoGKc?oxr%DIpbfneLw1oI+x zjS=}f=fRq6kPFxf>rjBkP+Rutr*h8X*ob(}9wXMAm!|l!&v?H?qwn($J26$`OWd2U z7h0DX0MFXw_k`C9>PQrmkwOQb1K3X+#tR526RA@gr;(Y<HBvODY}c<Eynf6W0AAP< z0#I4y1EBI#N<8!<7@<F;$_IaJwM4{A$M~uL<wdk@sX;*H-MKQJQ7B!Q>U=|e50<3) znOiG|d*e07Dm+o;k}#_u&YTa$gqLA@oQq~0nNu{_Kr+@Q+fr}n>D!tc$r56_inWj7 zt~60D&<g-A_NW0awk@Zhzr7Jg?4`;NE^_z*tV4i8wj%=jM&TykXHA$bI7R1Eo+<~Z z+(`|^i2gi-<0_)EAHY%L4sb>cJUf-=WCJyGN2}!)vT7GuW^dg7=1E7`>773P@0HSJ z4yJ-2IGYJ8n9fQ+jTnkCDSQ*!f#*2Mo5eh4Z!|J|l&5Y>H*_9y2(ur7`RR;ozn16F z@t>0TXfHEzD%|PVQF;aU8E?v|0wZ0GW&IBeCqyB7<vEg?PuJ4qG{D_9AgDz_<~0^z zVafDofN|UDuEsvYgfaNRz&*MV6cfW1u*V@)n-J?H6R{;bM?`bVV--Oh_XIfRa9l(x zJA<mQnQJUq9oqdxj|o?LXA9YqY{RM{-MIToNBit)?JyTAnz{CuCPB=X{w^t<qlIc` z9hR`Sg&g5aREv}WwJWUbsFDOQG5f0FaoFFPmai-&mH-{fTZQ{ZP^bWq6s68ex8nEn z>7eSVE_>6p9EES0x_vd>_VpUwb3fmH_Vz<~_TtRoF5Hl_tPEg{#1Rc+;E_lNsaOO# z#O3m_HX=Ij^S?IPf733uP@VoqKgFDXV^K>)8V7WZQ)JKWexAl-KADky_rg=B*88Mj zt5Vq<iZU*6D<?MQTDZWZgD{d~M~;Q>62c}-yG4r~LhvTNg<rd3@psoHzVKq`fvQ^! zzd8u_J!UaBlKuG<h;7;Ylc2Sn0HQk<e&U9(bFc~U${0HPpK*HF87DQHEU}v9RaFEJ zPKMK+S*!#@IYFj}%_-h~>;Xs?KO7s2<D;fW@B=4Q7C&MqlGS4dc}+ctP>4*r%05S9 zzelCU5;*^nP*Hvt^0M{V==ZQIFY33g1(9OyE+YIJwKS$sbs2xTGi=JcnoRgD*s;kt zH%D$D&YTUz;n42IRn?6&<CJQ1do>ug(E<M#C+(&tE$MHyErcM%cyl0qPeMCpsdgXn zoB|-u%&RgOW*c5)v>q}>`^f{HeaTIP#FVkI#>ME`Xt;q65@K??5PsxJXXE^aCE{b3 z3QVqlHDEKj@ab(FX$CIkjG$--9{(V=Mt<J8c=P8Ob#0UQcwue>qG3F?tbdrDXvEP& zi)2M!kZFU9n7LbyGU_jc34$0<f~NX%V&(1Id>fLBOp;T^#nd7jWf|$kzViu75FG&M zKArOP3^XkK)7MMvYOP`SU!UH;goq@dn9R$fr)4y?cD7b-uJ7CP>nPkhp4A;_;OwDs zL>fWIjm%~C?DsPJ=XD&)CrnU<a5DF}?kvx_>duAAYhBuQ)Z6r<WJwc*J`4R0%QBjE z8LAZnN2kbPaY+z5*;ZKj5}onB1Gy*!3>tawoBrk&&Et3bt%1b<o)kX4%sF&YHK}ng z0k=mqj-%S-k2B%Cpj;@(wAC`ZGRh>@h?OP;EQn-&8%z0QEE&z}uh%K9xuSn<395z% z3oUE<7kjeaZ^6P@+zDpJLphQ~kHSER<u_VCi^^CAOWyUHqN8P!VBU(N03G0@(b&K3 zanNaEGP6!k4&m~e(U+UyIQ-d*Zifc`Ufy$=SFEC61Q#(K!v!NMgC#Tzn-#GUxGjS- zVwS?iSwI0-#;5w6BkYUfK68z{#9Z+s<Z8SzKk`m_NtN=oD#dHYUvyYcEgS!8NoaLD z_tXtab>(POcF!q7VqUm&Afb4i$*5cTi{kQigd}~*@6p9*kH+8%OE?MuIvop}<yo-+ z1nkE$v_EqPFGme^h!P>z?H{2)UzXe9LNoC<MXDra?kgi5+^drtTq`X$IEZkTR`^g= zw}vVq#iZ-xj{%Z^Iz$cHzkAc5xNfrY{GwaveHH21N@3`d!~&DFP#@w=BHY`Eg`&TO zr?UDT&ahu<;Ho0q-X>ThOZf>rdOJQ%M>5{WKT~b}%J@JL;)nJj1bZ~6`4cL89gzNm zQ@f4E7~N&!`quKbwuMD*ZTS!`vIUaz+hlZq><Fv-hLG4;vUwR+xLX-KUdemSS7JOF zw&MzMKZJlyW?b<s57t<&Qk4dFw>lFLbw(Yv_u);G!6~O6pP8!EyKbv9Wi^0nlN4b` zY#;HNadgm<$`_kB2uF;}aThUw#rm|&&w|&#E{JH{J`b-S6zJT=bfz{)O!P^rF?YS~ zlD4zp0;s%V$>JKu92htlSOj4gnPI<4O!%jLkGG(gP78uKCbX@+3VgUh)}OU;R*cm1 zA7peL472iIiVHmc8$Fo!ZhX@NzHxj#pdDZh1c*%+*p)os9hVt*4n%p7p5i?Z+BY-} z_FiRQPm!4!y<raT|0Atb34x`6y>SqYdVf|rtA@=dxX`<q?v(l;13Yx!+WllbzvRCV zm%>ij0}VveuYepk85^BPtvI$a+z9{^z*g1D)T4CnB0RP<$4ZOs2Ggs{58z`W(oOl2 z*&f$rbTU!ZnwcC@^bK9_MUaV+(|UK#Ryd+Y{qp`HlKOt=^erT`93C=X$!qeA*)4Zq z(D_tVKC55Aqs4(jNmf4^v}|$wyIHO9qh=oDgO7(<!Xa<IH3zAr_&rTB?)CIn<TOHY zN~H&?`~HVm{qt0h5~fPesXW$x*JqAEXZGgt%aA1zttFrKy|ls03zh9XmDf(*?b@4v z^4}Z`Sf-f0I9Ok}c0K+#0``Lc$$$Foo-OD1Y@TU%4L_S#%!GIJ!Ce=#&K<n3om5h7 z`_wsXz^~u0MsGtD44qky{7veW(^{N#L~ML0<@5^;aqTImK?89t2gL)-^Ub9k4|tI# z^tYc>|Bdv!UOO*2uUGLPYl8N`V1^YmuDJ_u(oUfMDXr*U<XN8m!6_5i+rLxr{eySh zbN2+gd+KDj*{=k+(U8`TH+vb4%@4@oy6+G-S71NaVj&{}UVc(pQ8*c9`#jU*$ww#` z{j@;`Qa|3LD$g@V>K)(l>*u9nC!Lu^+oHv%mxzAeK5OMYZ*D*5TE=b;uu%c_Od9l$ zcSAny_WfuRt3<e_Yhk&|Hh)X!!PgMQm7kMUWBf?Ah_Pm-=Q7<alV|A*KRCbtk|F#M z-+wDSr?+f^YCmyLUije|kZvqPB)jB>zv&-@4zu(@{b7*Wp>JcIRMTHx!e8Fy1$M$r zuL#?%yYKtN;eZyCQ41We=*X$mUj+k90rxhoGHBjOVHH+Znx{XiewibE%Au|PlJ#&N zL{4dRN@EGFh+<P>qM|Ktoy@#Zi%&5R^Gcrs_867bm6<}|ivqHUelg>OQ`J`GR_%>% z@4G$@`8X06+IyU|yRh^$^})jPc&|5&UayK&r_-#MXc{PHfD6zkfB-)j8(vm3NGXYr zzs^|25%w@(E_d50UtZCw%rmdGFB5sn@ju<X$Hp%N*c@#LHL<yHly{9esDF@)pt;G1 zX2(PDuxQCzc5NP`A04z54r#ld&bLWG?|5k{kC9taaF+F5J4t1Z_mFRVDj^!sJ{d66 z8wt-yobzpdN%2v-_ka8Qn{0#U>pKw)0v4JsA8eT9b8<lzC1FWSRDSRGwtIaLO(1&Q zptx*z+`#8q&=N@`aA@YD&(iJ%x1U<~mMF3h;`*F)fJIZ|1$$YMM3&FOf__>$F1bM& z?e~O^ugmx@Rhx1tlBKMEokP68p>8Lz2s0MI6maXz*NU;LNH}|V0!bQX8o&PRzE*v< zH}g7LuITbw$u#1nuc1^`_4s*YmEw9C@F(BXhE1%X%GfC33^?J&ua}>Uh)S~l#tyP~ zgmPY-(&shNcBnyB9dV6(!qg-yEP8*43cAf{v2>7ZCkq(SSpiCA#@Sy5j<%@c(G_ms z@5JSA&7BUl5;4d1yYhwsYf2l}LjuiA?JG9lE~A&TSZVyWdrw^cdn>0^Q}ffl@$Icw z%k2ulr<r{^yE1jFkFYNGXe1(}e)1$5(q>2^`o&DB`km0Lv)>;6JjnR=<XXclma3Kw zCLIf~#(yqppJut;+;=3JsA#o#nVra^%;!Augln$D1j-?FinRya^@98CtG{n}4EK({ z?Y!!bW>h{@ei61C+sTBlHA!S|uWDtv9D;q!Wm)#N{Rbl8?F~l=6!*lq7WDyhmSc&- z_|^WP1aPSJZf6Xa`fTRT>HBZuTKw+)Ct;@dI?y@U#ZnpTj^SZ7quZRfu1}24X<MxW z|H@S{c6=Ro$u!!@U%`Eg8h3C-uu=8bs(o{p=k0y!uI}eD4>LC7`WY8zdl7zUyfK<X zDS!4qo@Ur(0BQ?MR^on;yCkzTi9PQVFPXSbW4-&spd^*yu{Cr-U>)7jj?>+gfwV6l ze=)gNan$c<>{}BYzkZwXb20VPTO)17f&gQSA;U>*!kk&>)pPvQ9oHV;DF5@9{)+SC z`Tg7!PuF((r@uuOuyG<yrz4O3<z94mFRTf^et+a(r>N5CT#JWHo^2SrpDtKQHW|cO z3EkZn{FnS90co>@u^J$BPMEWhOWkcWM9#iF6)HO!f&ssAFl^KvyIhuTMX0cV!NgVt zSuS(GavDMp=WR(Ix3KDMM&-E2HK!?Qjk3P)c$~K}?0DXh_d6ciFJk~ReOHRPY;JOv z(2{d@>6WiCUwr{A49H06`E=)KGKbA_QYvUkjA^&nVgpO`S5#tWzBt`1#Po=aKkiD4 zmHqN$({nV7iTSpDgn}>+-%dVaRYtn<@a0WBq~PauYxm`QmX$46khWEbqv>}-?hYjX z=rGEzp9#Cukwf_P4H@9y?8^nto!d4i&I<}@D!!5C@5||Fyf~xa=Av-t+Oo*&PQUX3 z*J51zJhRWyd~>e%_?x`^v-VfYlHedXNwGJsG2TIHkhEI#E2@$uE<vBo(fH%Oa-wF3 zSeg<u->C2}-!XC?${;MRWt%xc!*R5cG%d$cnZ|nK+$n;Z&MMC!7HSaKK5>gZBg{8X zQ1>gZQ0yHi(gw7_6V*ys)2_KYSIMM&%DsyFtBTSH&Y~=Lh5M6jfUUZ1$T1nJUwOT$ zt=7X)>EGgZDS=9dD;!-8|2I5bqR9_zeMr9=Eh?CeB;98bO)*hZc-v8-C7r~{VL;2v ze(dzN8RT@yI1&MG^M;WBo&=$2eSJ#_kt<KI4NIE_ze_4RExm-XkglwEHBmEF@(fQ7 z)b?=gbBDwm{=KiQZ2jKjR8jnTl0`se%)2Q9AD=*%5kp|v{@weTn#{jeA^#P+pZ$37 zgvO<Yx=Rs?BQoo&32s`yrp~YZ(|nR`X01<;$|=zQ**!ZJG25!cGp(s0`8D#To?zq0 zojX5!V*QldzebrPB7~l8Wj#zv^Ve%D^G|0he|Y2PE1!0l(}Rt63#(7ZA3lM^4{5_o z6MEGc?gBH`K3H~3vZ%OF(w|c*eB&+TB@YC*^CA5QbdhXfv%EI*L|Ql^JniD>a{sNZ z7pq!989_GwPtv1pe7acmVD2kYzg?+C{@iW}e^!v<zw%`_+}$*iR^`to5`TeaVx<18 zDtVMdTmHkI!zO%IyZ$TC?J9p+ug#j~C*@bY1pfD<qiZ^)ibJ#==PNhX*YrQknFRk6 zOx+w^H{@aM?%Bnz4NiR=ihJ{#V%O$`8LHD?l8NzVU#$?d{bKb}cH|hxdQN9DI}S*Z z;_l6_wKx~Dsdg`Pz3ruZZ{JrJpBGXqs;GvbEQYL%uw>)mp#JisZ^u{aL6VBKu=2~c zVLA$3wX4_x{Z#}{%$C1oBbC)j!D}N#+#^u6Hnp`RoIBB|RN_##q$M@{d$fmW?YhlD z>zBTW;5R43_AsUPG20&s)z_su|FN83W#YVXct_%gk-4ho*xBfJzZbQ8qdZ@`<%G6% zzx`Ivde(p!e>vdJrFOnk^fQKjrWT@&`;6H8AMAOqx5$VxVep!2<J(2=5)$U0rJnn0 zzjGttj^qen1aL=YW`xdvHu{l3$YU>ZOf8js3B^x2kMB^={`VrY?&7=gtF1N4=K%Id z^EY?L_xaX~;HRE-PqET6n&ba&$ZoQp1>l^I&f=NGMJzhEw`1Bq981y_Jj?-9OES>2 zEWNI4(Ya**^Qm~n^N^sIY9K7P2iS;p6H3+|L{z@;SU8ENB%hv*%H{x5#n(k%4)0z2 zHTCl1cOHFKm06}#;KTsBsP$~)!s}l#Vg3>;C<}lklKU#`#sN(jA^l2VllItjFK9Mp zc-H=K@$9Fx-5IRmJi<GPX!xc;;qUH~n_lA{{-RYrzcGPkHvr1dKR<Mz|9W>}Dy`u8 zpOaaIUvDnl+<$fc--gfmf1iAgkJg|6<wD$KoWUQTxyf971JZeO<K4}JpEo%v_@C=H zxD)Uo-5YGE<Ubb4!XkL_dKl>cm^$-+sM`OJAG4VaV_&Nw`#Sa|YRnAT8~e`Kx6-JT z_A#3YWh{k~Mj;}NU5K$JktJkHNTpC(Znw7E*XOtIe{dd;bFOo}uJ_}5J)gVX?h4w9 zFdgcUiYd6P5=%q-(I2SFr79Jq>a5atM-Q;CsS28mU3on;jA6*3%dOIy2{4KPx(gJ8 zcEN_OGXX)6WC_!0n&~XZa+$`s$+4u|S)LUbzZ8~7EQ{>N3Y}(!Z8N>5S^gEQ=m8eR zkDV~U4qs(Qa@faWF@Y8A<C<w_9Ma-q(~>IEPWoYz;b|e7oESLgyaQ*yIEQ1wW~`>2 zUFBSi<y>~aq;t|(npd(M((K`YkPx8!6S5n106-TC2m|LqMj!yb0|>#D9QeF023(}y zae!aalZM&vROC>5w=YA^IDUTMe^C)jOjmNOi+pxa-Sa`vv%0e9`M8L|BFFmogYIT0 zKg~a@zdv#Z&p_^RYN!~y=a8!%JeXHf!-d@Z|535A>eVAkPx>C`rs|pc*#9NPriXLQ z)VG7TottZ3x21gl^!j=8qc@#2Flw($3xBDHBdHTI)KdHQDR;kfvCHGSch3uq6BdRZ z*MAt{5i|C>wl;ixS+UQ`VYsz%?G-=bd9iC-)5cuO$+d;yw&pLL!d{}=uI()@dEjQg zB`2Ozm@xoNG<17nHR3c?pYZ0zleS}q5x|9=uvPoif4{FnYn(<p{sw*jeC1Zbk<N~b zzW}!aIk<Ai&JN}(ut<ZP$g_n&?Wh#Guo;Jvim~4va7o4Y0szXZVu`JEy5KcPJ{-Qx zQN0lx&e>aDv7D~kw7Q((5+$dUY2uR>e%0cA#oKGvTdQxg@Gz|vE=eYCC8ox&3^;w* z?Bhx<*<R~io|jKtl#6aqWm$xO;>UOS6t>p;g2?|R#n|%7_cxEanMK?>=HBgoQbsv- z%tX&N9CI5Xlq03Jr>lERLlJ`Sk|)H0Vw`Cp$}s-Ov3Gbc-L4bDM>gG8?&I%hmSpRm zf|Hy{h5G3-9I@AOV?dcz?<bcWU<c12Ibu#N?Y7Hi$<zV658`F$;Mj?C<u#=}_<JEM zL_1q}o``#*QZJO?DAD(Uc;u+p!)o!bGqJT1%2wP*zy-{Z(|N2_h!YiW#k~sz1!T8~ zKg6!OpBmM{JeJ)>t;<L~lgGoKJt!l|9P=0*yCtez`x!5ap6@0K2qqi0=pz%Zek-&5 zY;Z9>(635A`=|%-z#an5^^VFc8R#r?nF6WzRF@4E<douv&Hi2gK7tq4`!PzAJ@#YF zLE~Y=%_^bMhL;GNVe(6leZBZesH0wWJjV1%a>%CcRXKz<6A!Z0=Gu^Fk5&a^W)hnp zcF$7pZ8YKIB&E9NFBtErn$Mq9%rhsR$+#G3M*0E40Y`9js5B@p6$j)VK6v|706?`Q z%8HpR$c9qI?N^Jz7&bmavm3sji-NH2#U!Qr*Xu7E{@Q5zu=jw!a%^IXrw)b$7TMeL z!|oGavl}WGVQtRsfauBUDIINbw*hv?m7fSnkp^U?Q%tc-wr7|}gcV|`-5iOcAE~gt zz+#ftpKl|_xt%H72QYvByLr6hU!<k;<|SckM#{P$G3AO%`6knqqmK^fP*MgldyVqC z&O(!j4FC-WG-N1m&>3){0*uLgm}F)FU3nAVeQo>E`4jS3A@J_*Pqr1m>e;*AOR@cc zj@<1LFT-}A-)z@~_~(IA@OJkH?tvifiw`15`&Iy&4JJ~|M;E?#QNw_4;eNj4+nt{P z?@-eK00iF*qqJ{Am5d1DA#kv~s)U~ErAOzZdKd7$a{cVZFtHOnqK@2Grq9vrOPdJ; zd$#y?_Tgh0Zka1`o%ii!SzRcL31u;{6R_3CB^-N5l>C#Yhf^<%WqkufaB@QIL-Wen z=$X5uE%HJ2oZ1{ct3C4YO1ROGIMAZ9YvEKOh|vwRAYb3;h#|5M{tyx)NA{}!pb5ty zRWp2*@{J!BVs!0|a-NaO{R41@L7!RZqvY40)$fuR)Y^<UL8^LsphHq8Y^8QV==**= z-Z_%Go*Vkx2reURHEP%YJTKTpgEhG5tkl|-i-?omu9NMzjuyW$QXQ@G`y=KWvQ+w0 z1Z3ZTi|*_^6J^!EJ;rZ^o&B`)2&<7yDRdHSO*|W`D)qrg4B>oM;uKF(h<S%?)n}X7 zC3RWuQ#pX0DA&JUc|=;<)}eLy;2)EWgBP`!12p!e9_j8GH1;QKdHAn#jF@KSCp(xS zC-sjlrYt2wd27Zebz-vS%*IO(&zs|`fL9g7im0>zr&%c^Wx*a#Xg#_z+z_ApNOe-f zetJ;YW`!>9KhWo?*zE(X{8Mv@e$@8vcL#weM<iAN+TV2l@Wvie5wNIE@X+?Ywj%|4 zaK-PnirL(KI=}H@V{*KQT0#KwajNL?qf55vfIesMMllUFeXla)eB*+**lr;@TBszA zFh5np+SW_yN$^c&HrKy=c<fZhT=6GqaWQ|tV}z9S;ps%rGELV<cfJK=+ors#FOI5G z^AWx>r$WcR`Ku2|S!4eDuc^{A${@8>Sa`*#y9^$-(h+$8bKlGl>v|FAX>$VpCEi?? z<M1_A>;#7h@cQ((Hjc*(`7Ah1+br~eqeYTN^}~}gUR0}}LM%@VC&u^F3X<%?gSaHz zPYgJksRplGPQ}S9H@o5jpPhdT@3R$s&?dD9H#AO@C~S62Oh|tDXKv@5>W+AZUvI{h zulDY6RdKg+hm0rBV_;`y4s8U%kstXkM}3Uz#^SUO9|(Lkd$V~&-4O!Zy>Nv%;E&Bu zJYnnAz6{<UKH~r1ciN`libh`eP}<7-bBgPfuiY(u-Zc*8lFOW3w32uqrB^oHUD)M~ z{0lKh$bHZCWu1&xoBUZY(*KvQd{tp5IO)5xg&x;0izMaV@AmN6ZH)E#^VsgaO^sPs zi*MhU#nABA4m)cv&;>2ClQRFd5WA0A>8MENyl=w)xQL<b%)VUN8j%r>gA=Q*1h-x5 z@f4fSQs)&%v}%)!?39uAR27Nj#eYf5e>Q0M4&MmOV`!E0;GO_Y?AlIras%;i9HV-B zDQWLOHOlCF`m~iqHjSjp?t<I8$SYr?I1CA4KG-?TzTN0z46NzS*y|_>4D?So8wUR< z8M&|u8uL7?QVVzQZIsUSBdNkAPBDW5UU+AnEzepISKR;Ccq+46Q^13}^Ge4MafU4y zFaEeI`T9$T8K>V+1rcmVaJ!BV(<l$x?l)%6HM+G8y;<0E5Wq{Z1qA(HS3=C&tT!Q! z=f{K%BrFjmx4Z&~DzBtHeDQ)rE{3B@J$O18acOQ2W^)+p@^c*ikJtrG)-RF}#|lp9 z^0@zPVffl_UjAP-eltmTVfsp~7-TD#Ls~~2$2j<bB!=@_b`H-k{JuB9)nQpMv2~;A z1o+*T!nVxP4{x{u#O43CzjV~Jg#KD5GQ`;!)QAR#f96~sPlr32l0&<^c=()x(6M)i z6}Xfn4);<&47hmay#IZTYXaKdiez-yxqaD)LIB9apvndCGAbgQOo#bl^00IW9AKTf zjDiDLxztHR_%*ESHFDI^v{bOr+0uVg&0^2%+0xZ45cyR9D?Egu14dsHa~;D1C(&5K z=S>S3R<TMfK3p^MqOa_wrW=>*Vi?o;Y?CE=HW~c@ERuEx;iSp(w7_`FF%11^5Atcj zu}U|}4?c-bCi-FieTqSH(u@iuu9Fcb2UPQSuxYh?#4Va+mYjG-3y0%CGoMcDQ$_}m zk*9AQZ!yOxSz!JMGt@b0r~T4YOAwpO^z`NQd^}=DmUf+rI5m(C2vqZ@Gjw~dbSlRs zb5ZFO_+1Qwvv@&7Tn7qg<U7zi{Ur0rh(2;s&nBlO7ISqVV+4M644(NU6@HhT`Isy` zbvPa7&Oq04RJSGbamf5h1V}jz(q)v<k}<uM@dkdaRXH>NDI$=J2DnN7zL@)dS<sTK ze>Ej*R?~r99`z<?lmbr&M6xuq#QZU$yT#b)jJAr5KNX5M$VufqjepH)b!X0rlyDCw zA!>0K%kap2AX^RrT-U@r+L_MoY{^o-qL?RuQ_>ja1D6e3xClp<Q$e1^jKrPMJYn}- z9yj4S1~t=?XMr#PM!7W>X*M&8bM}ZF&UFV46P~)qu@DhZc-^m3Qr|zR7L$Ds$c8BA z*H&B)K;#7bD+c8w7^+$R)0v2{Jk{8I(Z|_1TO_Bj;OaL7Z5f&4fciF_cL#^b{i%;R zoByaFzv=6RU2bxI6ygT=;;dg<Cp?2$sd-{X@*W;}2QQjVgV*AbJbYo15yr%^;N~+$ zIbU?ZC=!%%O&^})>5zMSky|M*wL5sO<tBg-$f_#^jgE!ASF%M4uRnHFtfimq6Clzt zsM%MTR?V!JJ6eSn%2Ia(NCpXYk6#RPFJ7C;Gbzk|6{nbsM_9<B$^_7wGl<&z83}Q> z<!2B%GkI&ziuJ$hi6kNKbBn4q;B(;^ng{O=4w++lr_B&?QviRw$@y!E*@(U6uT`Au zSZtBX(@xTp`kIpoh&(%s1i9bM)WVdKd9Y7;3SoIN>GF4Y@S;sb9*$M*muqBIV)3<T z)DrXVr)0&bQZ+ua27{`v<mo$M)E*Q#-n`dji+sp~mr^sJNrfQg{AvV1iZ4}nl6r;^ zy@iGArXy(tq^DI`dS!v1wt{JMPChr`CI(f=y-HBHy*{IP@>ls`TcklHyib7S@k>j0 z7Ry1(WsGy>$+HS|7Kojv<+6@tz5zU7vphRq>J%OMi0WU*--~p@+_$O#sAW=yENjck z%o5EkIn?||r1{Ug7KVk6@x0qN3vQo#;2?xtBxf#C5xqub01b&m-oH;RRp`3Tx00{7 zx>mc%UDM)K1z^^-%7&5m2a(kWYxjy-VJa}F1_8Wp6FEGlv{sAMM^?VD5?}s#f6Pg~ zWg2mx2Y-x5f(DD<okcn#tC6jx_xYtx$~6EU^_Y)n7}YGX!pv)z?f?4VA1k?;7UZo_ zWCaz`5s&ehRoZue@0@<ut`=ECL-q_J#;N7KMs<U~>J)4rNw3N6qV0Qk{A%FJwOAdD zep}5acd191hDQQq6$Z5<EK&g=YxsIqqYYKKI*g*kj%7Wows@DmULAvwK_K6Jt10=_ zxPPrdyS8DkcmsfGXyKPN(U6mbCSb9_)wxbix!x;7t_p$7$7Kr*XxtCr!<=iVI!y<c zn$Ta7fB;zyh<d<8NNvb!uBs!bxni>+c};=GN8TW3KeI$a=PF>fy2lk;m<bYms)3YY z4JfRonuct^prjF~Y8=LS4e9FK#%mM5?q7JlP3{i0qL15P{agtw-lDGfc&!UrcB_4` zt-U^@RVl1RMCi%xS&dzVddNq#@{tqgo1zc2HCKsO@3gk1e?{EiL}JS-#K#&2bx;j> zR1+RmX7%{)T7x4UwUvNczr{x=@2V~^f95*DVXX-FR?yd$^aRA>?iyP|vK1Q^4z$W9 zm7UV*pe2<i`qf-^e(XGmw0+*Op@VX^LRMfAY23s#0mPRKu@gY_sZhN?-M+N$-7)hO z0O8!ax0Q!#!D)kzV*XTh3Xk=OjCGPwA~iZ96@o58TZ1UNOHRB)Do74F$V=xnBHJs_ zXw>@iM>ztY^E9~TI>_J;JWIgbb$^s#kd?gt%F+J#qJG8S9N)$6lk-px4p~J*wbD94 zUwbysWB$%{Tto|Ke|i|Ym>M4H)(#F`&)+-xyw@51*nM99g?1S_0LjLRq&@G<YJp$e zwfHT9T<~xv4{?tth@0>KgX-k`?yTEHGBb5|Z^<;_P{)dp8i7xJx$yhErx$|6Yn6I0 zT4U<C39SMFz*U`C6L8jhbF1a`k(yP4j+Y<KC1ZsXu!Fuh;p(}5{!k}hu`Nrfjq#`R z;QC+y`Z+*DwewL;G=yOh?D!(`b5W<lSO=7dsYQtfB1Jg|Fxm6%BWRh}>k?|5{0&4c z@)xop1DT3}@3PG8$xuxfcr_PUPeD~<QMGe5oWRzBxxqt62YN5O_;UcIriW4(e$l=O zKS_bcZ6e$GJ<y#n6e#Sak}ay0fA{aLcEVgQW$bA3fk?@O>z=nTHJHv+u5idEOs5FO z#G!k*NRDD#ZQIbm8uD32%O^DO{^+=H7%KeOOQ^AS%V=jiR-|NeJPwO$r@e${kI2}f z+W7oN+>?MmgCZB2UR;nS*o^LX&%HI9cl7yaDo=RVGH~(_ynu^r7(!OdqWEhq`;N5) ztWSnK>?2qY36FJzivVU<$MHq{b1s-u!{~y|@sk1+Zx}-z#%vdj{JGVVtRYgSgSr{q zN<d9B4I95XltfzHsuGOu3Sp)*yHDcbTk}dtv}nJDw)fvL`nTc1wVr}KL-%g;8))Nq zucCN6569|fW`9+oy6|vc47`%}au=%kM@OV)ZKQs4xW!e_t|yn`SmNs6@ra7Z;0h;D zpuSvKJnyCBw`QpI@NSG;Ay1|`3u@*&YvwU#8?R4X#8@gJvnbFK0670=hW8NFx!W`6 zp+2{XF9c&Yh7k|>s7FAjSaJJ57v=8o8XP?kyme?W6&g=Nt_Lo{&bQSnqQ=SD<9eE* z7hl%~zl;nPZxtXLDbSOA6f6uSdr<f|7ioF)Wxzqq-WTtrmTt~&OzOLh8}5}eo~fuA zMI0N2CX7OXOZ|15rPj}zglk6FIwD16WDBK5yqKS=G)K37ClmIv9VcujK>gj-cY#WJ zn)s+VF06Xb)R(I9EnV??VD|}-=@`*!9BS{MuIb?S=e}~B6%kjCL3u9lg3*p^3hmFV z=ShJW+l-d#`>01pF|^{9M^6@{YEf;YaA!Q+Z?D!?6{?ZC<O3i-9((!p^IE$AJ-T<J z9k+3>dktoYs>h0q^Y1oRk2|`(zZ)WJJX3k(fpB6m?3u{(!PbY*kfW}@o1&dDOV-tQ zDRXoqZ6<ov;`YdtzIYoCRf!Y!#vofazZ}W#vCKqO(-6L*8*M;$1r3pnd#X7EaoJqW zC!^XiS|UQ7$-@W_{V7`U>!r^!=07<pnG7G=r_;E%4XAAWUvFVM32n8aqoOWv7O}{p z#gY7Dv!4%4-Ff{*s_U!lRq#m++T-)<tu|CA7CovjoXUmy0)yAEaIuH5lRQ|!BN&qh zOT5&-^BFUJu$rKcs^9!h2>lk@WmHJbaGiToAv$S?;uoRnLY*;r7h5XNW2*5eqNqqc z{zYmL|I2}?tph(`;#x{ss7_2zBMsHKi5kNGY}kaSlAn4D{$XN}otvn3?9ZG#Q$w5U z)uZqb46>tR6=Asb<;iQ6L)y|cTNH5}qt&bVn+V5os5kI(*AJudyi)Ls&siVv6&an( zdBv$l6;Y6!gYW9CpKqOCroR4?wu3n%0$e3SsuxkMI~deS+&{ilcorUh6@v`M{T$-{ zSX257P`5UYpgKo?Z|H8-^HAe_L@ysDf3b5}?>8WXU&Pa)B6~>%<Rt<dr6p9Mipv!^ z-*ZbQMD{u5Tk>!v3Z}><EuaF{3gSDJ==$?1h&(&gly2;;(?Wc2%qzE`rW9mv8TnOL z06zJ1_*TM{f~@a&1A<xUUQs%fGHmsuV%4<<d>qtbnK60Gi;|3-F!iFi1)C=STzOo- z6x5o$vCwzR_e)5}#lQbSmHaj--K-BDcTXW!6b)QzR?jlirD$BRqk@+f)%!hDKU9GU zP4v`_(`6KYmiN`~;e|q{ke^KbaM8dHs4T3zm!%Nc%=`-K$dv^`vf*X3*XMPCM#}Mp zI?0OluIZu47k8zv<!Z(?ML#rC3i*@r?cMO5!*@cS{B+DkUQ&p1ym#FsOaFE&Jif#+ z7i@_lRbul+bE0J8T$Uh3AcV(;#wSsynu=Gam-=L@R1m$j6$Hn!4E-7>eLZAq73=!p z6ACXZQ*%78$rD;v9Us3#J2~h3qnY;N)WqsUn|+rdMh?nps&x+S*wjd@gJvZ&$HnMl zq=a?4riuu`!BVZ%4cIQl{!s@n*0F*RWS%d;Wnlwg0c3?e$A=IVu!!8M!;I52arptd zq?b851qE+gymEfA3N33!(|7EG{dy&3Kf*zYJcop?-gL58k&a#vGmcdddI2PG+kaTC z(aZCQ-Q<MBJQy$GXeF=4HLY$@k#HeNR2U7)eH!5z3&A&E(WgutWI`<B)Cw%#W$Jis zO3m8kBhQYh-8j@nW?Z-NY`>Bps_;?eDp_;lBq<~@yH7O8!^PbL$UD0t5|o%N^YFdQ z%`%x2X0>V$qdcJ&lvH8$mPO{Qq-KtT)koE={+iK9XTa*QsxRF^$k?UrlJu6b$)r;3 zaJbnL%P-oyE!WP0VaUE=+1j$4e&P7cyZoiRwvYLt9<}#Sgro1vWESaf&ss5PZST1H z3P0`at{3VIG`@<@F5k)XI9;Ts$7p`vn((M|uYrV<)fh?Czzh`i{EFP()!fVv+V#o- zE;1ay!1jC4+he6AQ8#jvDh;C?W9rp%3qA;X^CNtU#(04^$Ng7%X<J+K&I9QIJPH#L zDLM^F&$DMHK48V0*V?0wPWr|?Nlq1)kIkn0NC!$fwpOSFdDxGwNW5vDuQOT_S^iSm zV$0Afv507MS8%rY_~N)gXy1c=yC>R%bCg&FDXSm`(VtH#4T;UC)M$ohhp?x9$~u+3 zoY5)8o$a~ibu(J2d+c7HR)I&3>u`OLIUXc4O8b!1t0HBFa2+_jKMrfBq3v$ibga@D zJmzid^6d^o$zVr0;g@g4O$`xy-Y%0%GJ6Vdt{7Ydie_R-MtNfvtOgV?L?)td-bF=2 z?wx4Hz0d<jJIa63rG2oy%fLxVyUna~!pv}~GK;=ei*9j5#O~Fb?(7T;Ey<e&1r7vy z6}SDWek5|#dAyYS_@SL^!=jzmiPS@DD{<}tZ&^5cYKAjJCAy@d&oFc8=JuGK+?!7z zWY8!Jzqu?Y_-cpUn}iCPD9>SkB521>9qin8l`4a$y{Xu4yp%bfM}G{Su7Qg?Np&M1 z-|Eq{Qbqugcf&i{AbqV69b>wq%gwJmofj*HQ$;MxpDJl89*`D{osM2NhOM_Z8&*)6 zD&M%{|H6Q7NJ=z<SXj07DFyLw4cLS$9H?jLG1W0qr3BHFEpPD1%KVZ7H}P@Iq!#ps z>cuV3JA6gXej{ZBe&xMLZP5T;LcxA;J<(UJF*90$FvOUqCkj8lcKU>}NbrOTX>I(y zKCVRgDMm%=C51h)`O4(Ri<8Q>&UQoTxa%ekA7oBoW~mp1km{Ij*>9!$Lvt9Y&_74y zY2RZ!uD4EjT6RkSTw>xk496|<u0$c#Ll4o7+XjG$h#{2WD~INc@CN%b@L^pG@xg%7 zGIEQ6xo3e2HI;Ib@8pV;MI<Je4I|k;gTs1>*=(I5A)sTLWeDJ1U1ivI?ZDw3$)AUb z<vvq&`F$uX!1HG+5hU^~dKJ<I5E}?V5`3E}t05ttN^Q)1GVwfS%8!fDE|r0ukTjv+ zkaC&tck=3r4uyX6?AXP;k*xdozvsbpR&Dv!1Fl97QW1Avt7!Ek#f7Gn+z((9rOGKf zKl6SGdvpQyA4I0H$Q%wysaqmvv`3+U0)<8|SGstt66Rp;%SjmJy(R;7@qyg)8{sk? za`yTKsTnEKX43f+xp=?USI17&w?GPq&6+FgXG&GX7M+N}*|yUIKi7-eD>g%X&n@LA zzA7#m+IKFkK`3Bwy5C-bbZrtvBLRZS%)&1qEoHMQ8ImNWNY2)NXKA#Z$1I2vx$XvQ zS9u8Cuav&(ub`0R%5&#foU?(CzQ5}V48d+Tr$Eq9mGqF(C7D*`UcEfq3aR@oSjC#> zqd5_oZU`dbhT4~_P`$T%#8xm@Xr$N-%5IBI#Sxh>Nkr3ErjX2MD1RtTwoYBMzMPzQ zjwo#w_Bt=|j75p31Nqnh7fq}`m5xuv%h{rzGVjU`MX|PxhQbach#KHgvj(K^sJK6c zm8pAA)#+7*{3Fx-G`$G~D2X6gTA4R;WE@CbwEdN{|BOSv8rTl>a*KAymIoe3AHOY; zK|TuF!>gLFJXR1a^Y1KHenAO{AIk`<AYc_Ky)L<3nLAIDdgUEwlF61q(P!lUo#<6| zKNFapLCs5?bbMD`XIkSG^F2lU@_@)bkkAz!ZN7JIMG`@EN-Z<&7q(Mj)S2g^p%6Ey z`RW2`<h?*Sju|1@=Lh@U&N`$RQlva;J@DR40}afBl-vNCc7I$#Tu`ojr2}Jc{1V#c z1$$EW#zbW@tccp8rL^a2l1KKFq^4UE7#6-)1+Z1Kgmg<(T`(zCCUEy3$sFJGH>yE) z%e#Up_~f?LZ!n3x^OjXIj*nfFzr$rh@%N-{9~BkI-yKGte}Z+`2k*%KoN;F%T+)TY zRG1iL9o7ZktiJ+NP8Xy{F5a3HDJg0`RhxNd-wsjFexDlF<kr_F*&W&^C{xX-j;TMr z^cj={$q7(H_{bOPZ#y~$N4MRGf|kvrK~BT*-|H-K8`#+^Ebr+U<I&fF2GMNwmwF_s zOGSyebAgj=sd#3@sJ&eCD%TRPbu8TK{C+q~hvVRXC<Mp8=zf>&dEjlX05o1rqC#~1 zKn4Y1XFhYUB>Ymmw1a~s6TY`gk(2oh?F%>8xRp_igBRoO1Y59l@OQ}qoo`yVshTh% zJdM&*b2q}`38zz;sUCsr{_i}4tO<+5*W>v$HEreOfmRKZdL~YA@7a?jd}sPCf&P!~ ze|U^khcd5Ej8v=vi4QTTpwAaFcSxKz9VhH1P!}7!-$3h1E)JfT!s-D7xmP5~j-2Ex z<qlM&ivvq14+n7Bu7Gf81$66eDd|V!ftUQzp5`)1*nX34WfPc<6WcNcl89qdwn+pY zdwY!pq`(M#x_^ZY+qk=3uB}9pL#4s?&gU9T^aZ1{a1h#oX)t3O+=6PfbLNq_d-i1< zymYrCO|$OGs6j>{I@AjKAG|p=g>}uAqve@F>}FcS^Svsd<@a<E2{)q#SV4a5!$-AH zI`uEUTZ^=jTu64Vs@)M7n5_p)OX`jbnx${ScbT~7rrSbZY&9ZUolvS*R#DjsW4qGW zcRs0yln$gzW$qY30Ma7Z$d4WirV$qn>HNE^Rfb1B;l@@RZwizm4$oTZSqZyp?O2(z z#0lK4+)&wfPqN7s!~UDGZzRIv(f)3giQc=qPPRsa7k)s?+RLeTS*iCr&9ROD9biXL z*zwy>-5l84Jx_&;P-lxoZq>@iVA(!Y_Im9=gV%E=4GeI=OwFEya*%^muo8t%w1ALe z9}ykw0Y7HsDQTt_#~>cQzJ@gxq8&Z@tkoSZRHYi=0RDw#{u6g?!wP@4yJp;7*mD4y zRDp4B@2yENRhcKbnK-#tJN4N*MXj=0a*U%kSut>krwRK(^<cucUE1>X_zID}Zd@z& z?#{NnD0LAM%!N4yJzw#1V+g?3+l=OWjIm{gHK3U#`OH$6Qw0K?P{qe@p~AutZG4vX z36^Y~?en9D9?|kj<W=_Nz|3uhL-Dm|OGio?MqD63M1gV?j_{v#_ZcDbcs(O<bfm|L zWhP*Sq~t#+Dk(2w;9HcVFt95>hOK|AFR#`FVOZ(6`0sv@8(q`@0T_^D+Gv85xZqDx z5U#aJb`W#*w?N#QgZlP>foCZW_q45w$IU<;dD1Qg(Dv5i1_qvkdJz{3<-N83r8Hb3 z#qs;$y7OcBo-TYcs1F~@rdU`27Z@Q0^-;h}4Ja)-B|C;Y&|dJ==={izD_ofHYt-EI zpc(afvlQn*?2Gpk)!Ke^(-a1gYR0X0%kFJsuWB2nYhH1>(*2g$=D%BU5Osp*2i?0d z%&-_-YTOcsomhlK_>D8yTYoFTqcD?yFXX#N-FJUI;tutUDqxdi8IhY%_o&vH_L4sF z$y9Q+>|+*VjZ~h|$8I4FFR@})^ODhSe8$VjJ#zAzSr)vPp+{dF#6ZwPdk#r=WL3L~ z>B83|^>)=78Mg2p5YBJ<V3A+$^d=%iz;fbA`|woPIEH5<jyUgW-9p?6AgB4r)nFs7 zY)*`ON>75`jr{pD>0vkN34O^}W8rx=?#ZyIT|WFGD}=({N!vKm_l*@>0M_w?U8o+8 zlAHe1(0!)CW?wk_qCcCC_lb&{DYarSr@^*<4AXUx?P|-l-vgQJ&)K{N)qC#C&pPOw zTP9k*{k;gOF_sfY{!DT?#$Wv8v+fEtl}EoT1EtbJH@!}H4KT^obW=Ys(@A*+I4f#5 z;CbYQ50gh3iVv;|H#pH>dgnbD)R-i(;68{RUpEemI@)~w*i5IM^mn7od^^qoF4&C! z+-O2KS`yAx<wQo>GdF!g5CKo9T`Sv6omJ2o?~-!YYZcJf=R_W$Z^7JXut>}uZ0{t! zg3JQu_@>j|$*@od*l$Y<oCrI<U^t$vtL8De6TxT8%KJo7VcBYaZH-S-cX`aceWK9$ z56S*O>~lKDUmXKFC=Id28uSnQAG3kSth70;Y2&)2aki`k(ooNuN&I8Ta34e&sU&_@ zcQCbiK9`Ta*Gnm2hsUx`ehWAq{+it~`N(xr=pc-H8|Jdhod*D}^rUDdRNeyygOcku z=(*wS$55X+&w*ku=62-M?XQ8WYGJRkU(x}lsUKZCh0!9#Q8I2|_(2l)a8x{v260`Y zzr@0R$}xD*K!<BvujhqNs;`AfowaM+N|5~{%~4jhNhU*LF~Z|0ijYho?QZ}`hT|Q~ z7PZvnUYwpP0<Ya<dqRO2KkuCcKz2N^XvYRVR*ftD&5Cz89Eq=$=#RKeXW&c}mHG68 za$~7-OoG5a74Ah}ysuIpreE8j(AYE7Vm~w6VOoOm*u)U$^@AzuKl`3Ng71O0w=B=9 z$Ew)uv4$kU_oWuh$)9*jm!r@wz6LEUN5LZq6jq342+oEb&zD$GgL~SvMDp$gI?TNF z=DhmezWsb;K)bC6)M3qzo(cn-W8fAJWonurYc80+SWS37#pZCBpPHD{Sil{gRRZ<r zS2R#dOazgxpYsoN7aBO@&l-C;O%%D?+bz3d#%~!Ti!*Q{-cf$uo_dqUZZpi=!D2m8 z(SRq;hU}p`x<kGwTNBu4Qo-)i3VC}m!b=J6vBkRZI`C)a`<%VJI2aIL&afHvG)Q6C ztb#M8A_2`v7I%!!El?vm?%+NoMLe_d+JB=!@$_d9kitwFg9c1r5nQ?P2xD+I%2Zvw z`>!4}K``>ideOf)!`EjrT-5VX`MVicSX}`-4hIV;W{0Fe>My=C)}Pe7NH!RL7ykZJ zh<7wVe*ex}XQbUFcWZ6ZJ?zkDh7JEEK5$<4g@0$}o^_LFiNWw3%@~TZbr>lA2IkYH zB;~2|{L;^|YZb+V)(YqTbNZ9K{EoFZt!enl_NTN<u`$!JQ<qjhsxadn{9nl=91u`U zWH@QwlRF^}Fr6`2n*Mu@CzCaLt_%z;dQ_A;(ARnTGhKN;&+VfH1*}W~Re)#|2+*hI z9^+~7)EmAz+{7CEC@BRWIQXX6e*fTB<_#Xp?%Dcb{IwF!hfm6!k^!9*RQ<i*t17Bb zPGMLt*8SR7<ELd-Qz^&hP9Fm-$g|1pIQ|CY5+l}veYIxQzh+vr#3q7IZS9*JhuE}7 zx5f-WJuBETmp)6G=NMr)`BC7QV36`A-E<n<y^#2AS(o5;bn9G@r3qZo-snb~TrsTt zpBMHwu)h8Rs64aqUa{_o59-xw`aeTY2%k*<G#cMEVS7Zw-0;E^jhjLp%i!Y_@R8M> zH2v?jdLeU{*hW4HF67ZT{8~d3*u?=BP_yyc&2Ormg|gQ&I<)YzH-WDC&Nbyos9cz| z?~fmHU^<OqLGHPxy8fQ|v7p0e&u`B*zZFH%SES(MTk5`kDaXB5L8{%%P=`<dvTw#b zM*Lw*jfI%H!<@1=MrhKi$FQ()J{#PB(lGQG9s8XrvL^aw<MrudFt@b;Tp&QBzAA== zu0rd4zCRZAtZo4N*_=!j_507nyR>II6!Vd~4JC#CIAJbfMq`+6f|M&jR-1h`a_)tf z!j|hlI#eyiDj`xW-VBqwjtIxQzhZr>wvCtn)Zc^J3gSFegTFnv76Je0S~0zIt!&Lm z_!PtMB((V$Q;-tl06U6TO0bBS3xOpRFf13@+_ZPNDE1VZ8R@slfKRtR^w43j8-KZ+ ze0o+nmC@S1V2b77VZgWUBndV6^o&29r)JlGCcD5svnxySb*9VjQ(@sy|7n&lPn{rO z=KKt6!fpSSIkqzKg?X66m-bFOk`|=N*4l!;R*#)hhoio1X83NlT;8nf{~Z&1GJ#A< zklVT{s_`az%Q$*5R**8=m~#~Kd5QgwJACBl^CK~<AB=~84w{P@X)@w!K+2SZz-C`4 zdW@k7`G<ZRzwvxzwr%s6BC${Ie%iT9cYZw(+a5qO$qp#YIa_yegB|8TO$2N-)yyyL z4%^OaH^#8*qyI3yIhk*^jbu1R`U%kn2~UJ+v8yaI+E(4ApCJ^MCFgss$WOlhnrPBC z<G(0=@;krMw?QdvQuCjG-=J_<M*cq_J%Nx8)yEtU4&4>o!#IZkn2f@ySZp^FDXYG2 zLY>g`kWecou;Qiry=%-m&h;T_`o6)f5M-J24c)*7xjLl*l%VDY@^USjO_n1>fUkdD zuUs!Mik=OS?kSg~8OMP04X<00KQ>f&2$A;qU4JkUGg2<J`VZXGAb#?$<t-mQd74Q< zwaA4nlaKYKj_1RWr%;vS%!6k^<ffMfK<IP9F$s;~{Fghu>9WR&>)VDa134O=HAjCM zy&uYb3Q+b(K2tDDS_XK=n=kgVX%Z?Ru4c(SW**>0@C%gu>~{O05XT~WqB32^SBMH- zysqQ(i2B%xDB-z#;q=(jgBtRy<b1a{&~~3q39bkw^zZBEc^cuTZk4|azH#Owp$7iQ zsq79v-luuu+&{<(=Lg1#LS$FXU_XWr;e;B?%V-QkcQn1EchcqT`He~6(2ni9Zd$bi z_vJat=@u$i)NZDzq^r@BV2a+lwM^N2LO@y^FrQ7{hj{2SfPbhbrAWw|@KFQ`7jMjI zbht_t*#VftMY+|ZD$a@{AC1cN>Z(mL^iUt^ukkz6easp6ch~((LTyA&Wg2|UQ*pBD zz<w_#jPXgK7yVxQx_V8xNQ#_K3Nsc~pU>+n_78@3I~gZ>d*7h@m3@O5#9G#)Z_22Y zW*YYMwcK>eIFgwLOJynA4=NwDYF9lB*|L)hOX-4&I`=NYly=WhqgN|8vhNYBe-(_X zpuCMD)$I3H2Ih2Tg9KVgwdTRR7f-%A=rss(a`axGem0ulqHCh=Y#{O@m|!NN8glj) zs6YP*T)ydw)xh?*5^tf|XP8T8mr=AkL6aJxCR0oT$22YEx{JZ_c@Gibv^_Z1i&}fw zSD{(6p64O+t&GcFa;QgGJkJ}fsnV)yH+sIK*H$Da3%*^u>$yltt*SvRrKW`+>|kTK z0Q~HFZJ}nyoW?L{bG;rVem@GkU%U>bw@(O*0$!(Qj80*-Ow=D6oqft}MOIoagrM|$ zGR;ZHa=EmC?8&JPq=+@y6ax+tF%^1cp0w~}ddb<~g4=$I(Ikf8VD^k^YDjZTx}Irz z5<?fEywL2KFp~9Xk-9a+d5JU`$@^>csj{lWYAyGe;ixQ-QUVqA1{VAAZB|f@E#t@b zY(lLi$Wb-dg>Z#yulQs=vEB3`CQnufk5WI2GZdaggbg>kM0}ITef;`L*62s{^%*VT zj!v)TZ<pX%LtwbV_o_t!h<BZ~bH%lN=f8iSnQz{?D`fZxLqEX=7nypDu_7%#Q%7h@ zrJsFepmkcdE|&Hm268)6<%sefDKHC*rOZuid9u2-GSYL^$nUl--1K{Q<}{EN{4r6v zYDS!ZF{}<35tGQl?;Xo2(@oP=wXkz>Q{6>Q`%KfN#~%j}I<Cv%v|zzV+Zi{rcQsj! zBbQu~JPmuZGc66H6)t|C>-@pI-ihEV{HY}_eT%-)p8QTcOEZY~?bM;_A0NaMpJfEi z3g2;!bJ%l>XJ_HWv6D8c%f5D@G_qrprEL+0X!3LrIo6wFi>4n&`a?9&ulAIPivTwr z9LDW;xl1Y#sR~}7b~OdM<H8RQ)a;sdYEkcFk_}zLGKN$RB&$E!wBv$p`;E}|IOmjO z4ga>LzkZQoZ~R}D%^bFOe~Tf%-EcJQ!gzY;e^2oT=IJ)a&xXSCyE_Ei1f_DEoz*3G zg2Q-y@mA@FHHt7ywi}~tG*sx4$l)?pak~O<HPs8-J<1|0v52!Fb{KlP@2HB1kLEL- z#49;LqD+~IFo#!i-}mT*hyzw*Sm%^+yBBJu$NE;;e<cW4d*@x1$CWT|el?lbQ1(lm z9Dtcts@#aAMkLKsy<Ds6GNY%*6pEaYAI=$-RL+VSs?3p8KAatSsLg~ZFKYXF-Wbuo zP>zgofPV%Cb(p{o3aApI@sa1qhkuYI8Z4&>N(2&%7mk&>*sHJ${=d%ej-Sg2kM7pU zH7@Z|FF5xg2s4f*T7kpAJiE29ydM|8oN*1veebFfeYGBQSLO-d9uW7q8d%yT`)u>p zo#pyjlg+!b2mC)gm65PYqJoqZkUCT$e(Iuxtasoj0eyoEdyyvu#0&?Ee59r+3ITq{ z_Y5fSD!0k~Fo}%R0iuBl%4MJnd9s3~n+FE`1a#$n!I|OmMjm}d4YlXoHGuhhymstc zxsL;OhU2N|NHpobUN$l|CY=j0_G_5pp_CO&Z(I?nxOQgf)*C60nYht+*Me+gTnt!m z{^<9}?Tl&K>toG^mg`#j^sf!c#+I|RsrJgoLo0X>1_r-blRINaQn}Q``FzgTp-F2T zfBNOEH1vvp6{SzLfXeFL`(gk3o`Ep=m(N2%#>zTVDg<0(XxRW%egt#a!b1F7EM~i2 zHw+hxLVvJ$n|J8HXLG&iKmBR)`r65;QM_CM+sh06AnRha)05SM)P`>PAq(~|kH#F` zN9(Ny9St_MJQkBu;uEC_mg^r4GP8&hvpSuSby3%MZ~Ax*@);>-pA|PYby*r%rAzO1 zcMg=@+CO*ihrWSlM`}@x%NF#zN55`<l?6kwSCegCWE<9=EOWe|k58Ab4k&v6Bl8q< z$IpG=m`MD}Su8>)zU0RMH_DHJi4(BPKvJGJs5P!doW2T`t8s<fiEsX^`5@D@*ewsn zqQP;WPYN3mLrT<5FK-hcpuWC+MaxmPw})2?@gf({5GkHtpUx}=dcc}4^Xw-lsYqfS z7Zr1W`}2fM&(T9sN1$4{@0b=9MjId^y8fiurprU+Q%v~921J*xna9_cv8vMwvn_o} z4a*t_<VBSOQsokkC!rtrLOa7@L(n<-jGzi4@#%l&LBFqVHQvFXfN7AL%`qyDn~IJN z9yq1AAk6t*kSlTAl`Dp%eHQH<XnbZt@N!H)(lRbhYXm7rcCB4gEq%hhg2>-_H+MTM ze`H$Ea;xC$Nteh!<^piX7U5DNWduZ7wR>9K*qC$!KhaGC3n`^_hT{c#+p8g8apwnf zLPc~Sj3tMYJ|q7fKT`MPr^czJxd>U<`&mC_k)6q&-wTewDrP|1z=v@7V;*NSTADY? zI6GIB{g%8}d86z{xKSr2rw;NSRrqgv{>A1B6NbWa1^cEy(KyoQ(?23_f)oSMw+SsF zV_GCrN)Ln8y$5mI#JeZ;$6<q5h8ZyAjYs=ZJ@o|cC54h64ZTb_R09t-)y?_-*c;Ws zdmh^*A=i~5KoTZi<N3A$!wyOXussg>l^eIWqzOT1-vp^mh>i6Vigt3oTW9Eafh11} zY4U<jXfof~WS>tya={WNljIaJq!_X*TwZssw<YSIBECL4Hx_ndG+0sS!3{+pxdr%Z zV^yN!JP2~P*wmWnUIsFQkJ3ur7p;4gO6g{TKDs6wX96}s6HQlp4S8Z{Hx;#}^tmNK zv^|*M^5*32NzohqVj*`h9n#+~N&qSOs;XgxqH!$|(s(sUd%y!r0onhM1}=~eV-LS; z>>WHi98P_DrUEs%%2X}S^VH02)sy>}L^tGs7gt?J3l#%fmYN?bH<#=kYuvjpoKV8I zTdSNhEA4J8TT;A~Yf1qrQyFimdkC5Sh@8T6SVjsyKy7O0o=vfX%+O-YQQP$aNX`7T zn3HV$`fWU}cLWXLrsNYa2*QPKHJ7|SnZ5f3;e-lVLh1ZDJ?3H8G|vl1oJZgA5yYDV zOjv4(H>adYgk;QJn7+<1Ht8ADql^u&m^byhoO=rj2Pag%g%O5aw$c(r_7ra@x!DGr zm|zh4B$cT^tNB|Natxo>_q^PqBJn~5moEGw4HKCvv*LN^T9;f=s^5aB(u$K9`|g7D zN_@qhTJ!>5Q#Hr1wEv&}UG}v?!7H5~-l4V#`@L!QgnpT+-tawrGg_e`9OVv@-9jwG zoQpQU@K#a1*Hs-$OnK{iGmvl;3+&SBC}6XOoe&Tbt1~}l=CXhNbuqAU7+XpJr{;R- zzhgE?n&c6R@<y3twZ!-3;S@E%A{8^bxYq7=D7}mD=WQ$`@|qT@)3GQ42a$MTPgE-; zazUD#wo<KxP&?F*28g~TRC)uH5`Q=x9q2UUo7k7OGa==@DB^tzY}o)(@OV!k?_X;q zDb<mTO9@!j9<x;uMRlU_kkH<5S6?3uG|G(jvmh%Js(LEjQC7W^XkWq9W=g4&(2IZ! z#a8f9l91QsUz;kr;3pO@0jw6_gI?L9du^@kbWV3`N78kJLF#;o2tYA;k&s`llrk7f zXooo77DZiqdVBh++>01f6QXhH4pGN}_@Zlt;HU1YZl4#f9{YJ$_gAuh_8!!J_mjSN zyR`Hc)UC%FZBpibU^dIp5B$*t%$k0~?1-}oFO#(BLhIVfK#F|nU3hALn!<;gi2-%P zm~gyCzc)#C7xruo(k`NF+erb_cN?(GQ&g`hm%|RqkgS7j+$nNosrwytrqJEJIpqu! zD#6l)k*m)$(dM~cy8*S=a#MkrUx1p&MqdwLxV;cEUo12o40|UvXhe27P@{Nd57Af( zY{>6B)~!`P6(LEzi5U_|>2}Q>(*!OE$<b2fuu2(!_AlI?C6vYnHub7yg8m2c#xH1D zk7(O`!f(FA2bB=2cSzT^mhqH@lqO~+72_yc<zk&HFSJL=hhbg-vN#GZa4KK3gyxxH zuS>i(<I4c5U`U9%XDz7DM=n)cZY7d&r0dqIO<zJd#~3$jvKm-lzK%M$h99lO?1J1Q zZ3(?-Ahs&4jwAYl6VS-~!qGX}z*NudR-Jz*u>m6)Lh{fM`|daPr=R14;v@31aM9Vf zton_wuw1-)%ywHuDGUYu#VVuq$o_cOWmf|iS7X)1szizbKG-0Vc*H*1y~%d>*CXJ? zAS67D6+k8&h5@g75cav#QV4LdZE#DK6dY~rN6SW5$#G`Wnn;gUIQXvXBXy8d9(45! z-O5rswhA<m)+($m{=;c?*b{BYMEd>rYW?mhA%p@|S45^zv?8&3<+3fq*-C5owN&Z% z#?*Y8zI1Pv9(_rI0E;Io+M>V7OzP=YD|IVRJeDyTn+xPST1kP6V&S*p`v1=6qBUVs z_^zTCfat){p%+Kr#wT1AfqY&`|3`!rD9&_AkyUk}kLvoj!n)N|5x@mdTNCr47NpEw zn{eUT6S^Zs1%lHjO)5li#N#e{QKFyScN#x(vl5&mI`E|<M6v(V7pM0RwXrkEJ@4SF zX0b%!x5H+<2=jr5jov-g;e_Q(=;N}I8Kqo<ph?ePbPpi$UjiH5AP}n`L=N=UJMDC# zdj&-xz*n@lJV{8FQZ;-~wo;jNm7E_g^&B7jRZAf&adB1=10ofThnTY8B}*w>c79b_ z6VCl0qGRt;Sm|n5fD&VxodVO6iL?EmqMYL32dZK8_uuOHRRP#&!fWBDE9)n~=F!-| z>CJO&{{u!0(;rh?qK4{KqdRp>3C&c=UOc)bm|$%v6|wf#%s29fE`j=$D@3b`1GS#+ zQZjKJec+L6c-8YqSp?Y~lqL4pyI<}8LJaFuTpiQ2f~dpkfh|YIx>Xu7qWg06Od^P8 zk;KbDMbGK?jECxd%cVzd&iSv#D2b~%a|?}?h^By_$u?EJ*;v)IOLAyOfR;<eM6Tkg zQNDzvw;;jWK{TPofY|%UCAK!$y<2U-Ry@eILGEhK!*O*T5>TZS#T+r%u>*^RE~M)c zN0SU+>3@_a>Xs5=#`U9T%T1iiW6njJS?E^L-y`nm=}>#R4^n(f31;p+j?D}H+w{wF z!8-$_5KXWtlWZop3s^Sxc$sS*A+!`7D?^PE*d`5wfED%rl~!Ijp1vQOCGFLvCgrGe zsWB1XFR#(-#7`1B6B!Zo<Kmw+-1%Ej_J;ji?T8a}D+=)e$bhJNBF5vS8Tq8+p*Y7F zqA`W?P@4xc;s!^8iQ6mw6rM1luCoK`A(w+wl~`AAjK04!B&^C7m+L~qg^q`-9ZV2< z>t>o%Jn1iF!dr&>^muEjl<wE1s|rp?!*7h4kRH!|%dtff8{Yh`g<Pxa)u$XbxbM6x z;t1=gQA$wsrJ9(TnJuI+<eT{2X1q{ivzc;}Gw0v;NZd9PD4I(xBg9BfhtaLc48sq@ z#=CP>CVhQrB5fcEF&p^izlWS-rz4Ac4z2#n`9UKL)Qe+2<0)O9$7k7}jlJ)E+t7q% zDMP+LjLqKDeJp{ls(D05rFS()pD1^jL=-2?$CiNvWzpJeH}n2pU%7y@uaG%$QJ<8O z^(n{fW6TNjz@s<-*F=~|IaBrEEGpO-cf!oHC$xE|_{@36krHL+A3^5UaC2NRyOBwo zcD5RdJ_f75tkXXid6olg<1aK>`^K`|Qd5u5N`ir5eUkJMdqO-xRyTDIgr1FK5-mom zAM3PVYIz7fQx>AFe?h}V>5MBMb)Rn<fmx+LiQm`U`z1&Fn99eP7o}&;yvMJ$oIQW$ z%=hGLhwDuvd(3`xE8$zuHW$O_R!h^LARn%pQ(opip9$Awg;}q<pR|0~=7ho8N(`Kg zJ!HF-^Vr6iS!|RN{%0_u%4pPrt_GpY28k_eG1c?F5)VM{q*;7g&`H;Pv%7g+h8+(_ z^UPO37F41!kLtKnbEckE_OEHy$>uMo&5?I@HgwlNh3+I)o_w2|@E(%oW2X5!H)hI3 zZ9PSfVa6S@G`D-W?@#3@AOf*KnxslNbV-q{ftK5a#-DwSAox4>SF}IiwR$&kw$dcR zSBesG^ULkuTXyBv&X~;>ER%Nt+N3dX!Q|iXzdr3_@V_K3PMy|6?j)P~8k;_cl>fVZ z?M(B1VfNQzT&Q`E-nxbvN&QQ7kKVM9ImhnsPSyKZqM;PgSk9{Z^53X=06?dTt)AN^ z2=(soEgxR@I*@<pqKdPWYM=^J&4Hlk)un);t9o^RHTg~0G#lLC`>RmjK@Vb}iaXO{ znEv!agrAL)=)iRUgZX%D&J;0?^JAobr_D3+S83?Ea$jS2k(=hsGlUE3=GE`#ekhGy zy<t}H3;n1iT$5;uC+bL<!cuKM=R1f30&#eYxOJB#zP<OkE@4H|x!MvxCe%^~*(8DX z>DtPAb*so_N%&k2r&^GnCdjChUKLmX?bZ<msyFI2guW$S?|5)TA^78teolJNYAHAb zd~r19ZOF-k1nR*vCo3UMIJ0SOJizJSaNmD?64-^42?B`6CUb0@t`E(2$HFW1CR)a3 z?14`fj*=e|3J>RMxR-l9&WUo)Hwf#`v&@Zly=DG?44vgelWi1-pOG7EW1~m80i$Dd zD~wJlk&y0`l$4ho8ztQ!EiEMi0*+2;5fBs*2@|j|dHECW56^v{=bZDquAl?UW7ny4 z6p*JH&-=EPwIG0XWGTY)%@x4JSim-~(U3(go7Z?b)%?QZfysUO3gz*$e0|#<`MtAV zU$(d&sbomBjk(7}`g3LpzuxeN6RE;o?kn<e+m4{kcB~Z?;N0;8I>iI#tb^Xp06pJI zx)7!E_qNQbJHLzV>I_kNej6!JaGlAdzl)(~ljhPde;jnUHdq>d`}I@zcPBxv6KN=e z6503!bNa$$M}R2&2HB`vFTx-m>h{1OUp7z7S*_UHSums4vVXJTAHO)@V>VPL9DeXV zf5rB<+_S=}R|7mu^erf0dDo32i1!H;H`lWv&`w5oiAl}0N1Adb;C2a|3$i{fh3ZlI z^&JD>o9a=disBaR@2pd7xr>4RB-_il=A{YFpo=-PNp9ma5H)i;jzXzQegt205Rf1u zqFd0;%Ls7U2r=qgawO+<u#N<)<vJ}*sR4@=xsRQIN(R8yYQLe*=ieDo@}Fs^jy6yt zOv_<5lP%K@;kG*(zQ&Y?Bde7jCucbfoO;wu<P0aV1R(H7&wRio;AOAscnAs@1Enyb zBB3`{&Gg0PRyl*!oe6w7KqW~KD53!PGN{NxhgPYYe9H18lvpjXV;7Rdhpe$2?aEam zV}>k<+-%me$_QAp+ET~exRfH;Ww@OR8J&CWxnra+4dT!8kCu;6o@*JTXW>kp2ivJ4 zC0$Sb+lSd4eaBD_SOWXKCx#(cE>yislR1p6cWFg`cXfF5V)*m@_iI-;{5y}a`MSL% zf~LG=C!vH%aE7MJi0v0cU1m|E2UDoBvJT3^yKUp3H0b*jf$h?bOW@B_Z-Z1DZBhU= z_Iq-58g#-`aoYRrcWiVUtmNxVs_ng)fm-dxS&7SZ%U1rr$}wB8g}KK;?wZ5IP+`OH z`&xzH(v4MpPc$Cnk9KBvIpopNSe}e=<YaLI{Sf!epz3408vl|=feZ(sg6^tteby!3 zd>eC}Qs>H!gQ7Bh$?dNzcQr9Ybew@Oefd9t3IWjAcp*g#7Woi{Xc8l%2wRg@jlq-* zLtLv}R9#EyOa;W)b?w68_+##w9VwviTX18s$Gd54fhwinV(m2y6W1b`GdGaaA8LHy zbgyF9Bh$41__{;nO-f+=ho|{OsS7b4<_I{UsI|61$Rc%W2`w5~br6uX*tAx@ABHoV z(JzxGYM?2Qkw^1fT+XDXL8?fc^FlzZR9kM*@hx2OE7^ugrKgMH0&89b#jz#2Fm*9b zxGm{tTtvIN@Pr2YJ8cD?nj)`IN~U{9I{(%~Oa9gw3Cv!0Uu}_@-dwJs^k4VbhP|4& z#Hb(~@%gs_DX<0_k1)2?;>~$W)YgJT+=wEbnV(_HD~*$RNUvs`@EPyMNde&&q>;1y zj3DMw9O=Ww?l}eR*ks;<2E+2rpLE}dd@cl;mpc>U6vG*As`XmDD~=)+r&m#Jwc792 zwG>B|s&Vr<1&>x?^s>t`0Cbpdc1e#leGhrGT8khZB_R5<XaTaB3P;s)r-=)XXw{)A zk4<va2{=xonBPc2ze+zr<Nmd#egBn^n=>bj<NfZ}v83Hs0`<GFD`yLQxm3JvGe3%k z%_ca`YOaiY&6C1!jYzV^v!%8#)fe%*qK;206f<|}J!@wRSRNf|+b>hD`R}J|59jMl zEHbL@R56%<sIIKx#IzLsks(`pRz`RpPw$Kpn=_*5dhWBgk<+Z(M*3gOM<$C+SIdA( z8t4UWBV*Lk33h!)r~H#8!(|^e2g-Y&A5(k1_22Q`t#+L~@DePUuAc2)1hcC|c%MPv zy;NMWP8yd89SSoV$NuQO{i#omKns=kB9aoA-^t0Lt43&Bk8pk^4{PbU^O>2GWS0`_ zI*3?-sIQIso4jqgURGESd|`=cj%6LId6i)C3VFaR^S|d0n_`=M65FG0e31eJR}3b0 z1vV-@w)RXf2bKSH1du%i9#vC_6xpj`(0+5-htI-3vCSTd&;`^!bUJU=yNe|%gdW03 z*2mJtsL6bG$xfT<4<Ze9*>B4O`8>^L-933%Gr*L_Z^|Ih1)Hh7b^811(=P>P;xE|e z)|sT~?5wR6suyBJ6gj`ixF{&Dj!wlNIYpBQ10wm=%Oh^6m7)oO)%bK*qpy8f`5<<Z zyl9?vA$EvDUH^2kR&xptn8=V^F~d1$!Ny|8YLMt}=RCPbd;IFuWCdTB*U39K`EXxx zK^xPI{Wlt#{;=HF=^P%s#msk|Vl+6hA9UcKq%_ywdYCXhS!u+xRIx$4f;l=w4N?7I z<=s5F1<#`oCiXT6e*bdcTb>`NE$UwY#f3enVN`Zw3-@iObOr^1Id4<hSgGiD^;lW7 z*?g&|j~|z3b4lwEPnzNoew6)G*fHZ0igMo_lKU;#Q{nF&$qa9C*CU9X`bC`;a<}0M z(2E%g$lD-~OI#^gNI}80(_{ZbBDyfQe4+FTRbs=;27e}}KuE;m_V+uD-)9();;OLG z>xo<gxR#CQ5?Bd)u&kNOKvA46-$^UURIOAXpZp8!@A9rX_Po+ZESUXGgI)*n6*|&k z<B{EslQ-md&li$-5g@|`mnO3{8|Vvx=j6Sf_rLtJ@0BSGY!M~xqzPKlS~uyB6Va)r zRLWDB46&dO5v<ECxuGBVzdB4efXFt5`*zb|r+Ui9BYg^|g;Jc(iX$9JuuqTh9FY`v zMn<4vQk3cyPbZ{1?>(z@SjV6oXznCN&So%Uy8~S%Rr2J{u4q)dU2x21W$=zk!Q7d% z`uKnRejSo<mQ2N@FVcqw_5xF`f}82=5lLuO>0^W2wV9mRjRS1>XKl_Qc7h$@MoFKt z0}nhnT5RgJKUpbWy}Qlt5t|+WVTNn3)}S`P@*_wEkK3!CkN2J&;`gUvMsCC=%6V&a zOpxMp*Eg&oM>I3myqn33H@LbtET=&C?|yuvCoDdh$Qekcy4U_>f}{A4fm?q_g``&G z!;_yn{Xc&uv-e@Ysp-EiOwU!B)yKy!|N1>eJJ$;unQ><4fc#)=`vw<qrbzs+T>^Er zmM!&R46g_4K+{@}Mo<ME)?|TSON`qH!#d_{q38G8=!7czO~S=dB}0=FWKA9J;D?>R zj+OW<s_G)PO#eXHxYR9SYJG%1t0lxC;Wge@py0L?+#7__a_+@&?+BX}1cHiBzDHfB zW2%3O(9xU#%~ycmMLD0xWk~k#A{FZ?kLUS5NN~GgbZ8nDOiy6DrUH9T@E7Rqe)3yZ zmpcx4Mj?%eYVSkqJzv}ERr!Q}%4q^b+=VP}fDaMB`~V*-^u9Wav%QMPrHaK%lI~(* zooABnA%Z^NI0y=VcNL=5;3L_CW9F9-pz%iK?DooIxPhHtd+n_LQUXVD@B$~ue&yR= zXofFYe=MsREGWbRaEQouyI|husv|~6mnLfZi&#z53-l5nd)pkd`<zoV%DkCn%9*QV z`2CdFZg2+IQ=^!fCbpKUoK7(me7t!b&dFatQoDc^@Zl%|jh%mB{n>HFcm#IPPR)7! zRHv!dlvl+Ahh1hs7?0QnP(C-OFy3>)q|Wm*B7ve74)&k`MM^By+qDz#^<KDhf18G^ z+uS0E+=&cAn{cw|fRs*y?p!}t^w6yEhnw$`x-~e_i|{CnbovaIQOW{d%TfvA%+Wvz z7;yaU5WbLT2jXB`aj<oDa1(IK>cZeKR|}{!nC<=9@yAGfj%XPhxZKMfB)m$1DpX|i z+BFCmJjA-SYKo0wJLlIaYIukk*5%#Ci+8$=lc!h}DY}PQ6(i}K(6>ZpEGJC@{m+Mj z8_-XR2)-L5oJJsyPUo?$MPa3t&$W#3<!AK$=u^O{_LkotR$i5n*=-je%&fH7TH>JW z-d~dh#P$fng7<ZB!nFJuzsWt06(i6S=Us>8@14V(O%Ek8`;zv{<T43RGlH`}o?h4$ z5Dwrn7oNpy<eq2??m^-XI%UQ~_NU@t006%P*{_jR<y>lIM?`Pz9kd-VwYV`0q;=N6 z<-a3>C6CJ=UdLLt8d)X?tBp)2<fKBq`K*p_i%|}%Cd>sh{D`~FHRa4SG0bUlCPDhh z^e7YO{r&~~a{J3U2#x%RCvjf<CLyG$?zih=59awCC{ZOC>>!4VmE!k=jP6A`RCa{k zc9A}~L+ufxN`bIVdLB02jBo9>;T-<o+KAsTJ-&TjiONHP6H&=^EdhZ`l`#w-{2AA{ zNG343yc-sp1+5eOK?+}w5fhs651HOSK!GtoY0~c=?DR0EqVXUz)f&n#Z@y+}$SZ1a z6*-5N?TUxVni;0+g2=D}b?_y~pSAj}3$Fneh_OP8kF`^E>WqK!eTfks1yZ+syKs#S ze?$?AnS0A#8ziGZ@hjjmeCTe~7>FAU-3XL3qNGu}<_`S#F|gkmkfXu|hG9(1ci9m^ zy%=T*XX|itnV5La3z-SQZC%chF05*L+j14N8>kv=X*SGKGgAp2KySC@nA`j5S?nPY z8Y((Mld2;OAVAC^WaW-2pBs~rR;xmTEOtmv=ppl`yic}QvS;WBIa5-glrAnJhHV05 z{ZIneyl9Lvfz+AA^0$*WJv9faepdK=Gq2`(V`7)0K_$26I4b8pD%9Sj4xR~vv*En~ zb$dBHJ6m({-gCatwvtRwzL*d7Gkbr(KVJ=X;SINtezwTR$-EII<Xqm>+*`$iujcCa z;UaxhVp`*nqU7vBFhSc=aAVC^kCDG<AWAuu&c=3W8f`ShmzLlC#p$3kOtk2H*iM|e zT!Kfu8Q;Z-A>WaZm<`@Aw!lzzM6FC#Ff~)+);EJg32);x30iEk7(^K>JG+eGlCR>i zZJulEVM1nA6d;01B!e61WWl?E6VB&w!Mni;ZA}_%SL^)ESOdHjJhOD(&ON6$b*c4Q z6BTULdz;GuQg;A3c^-GwpRDk8l5~$mgObk#j@%8enB^#jGBw|{{y2t<`)H_iJX2QC zQz7#M`j)i<G}7zL3a18ovRq5z!ye|Bt&R5vVp#Jvsy!axIep<V^%0t+4qj&xwl(qi zb_bKRWM2*eh(UaJdOWMBfi|scKXT<66tMW)$sZUba@($TuOb_N+%5aglwzz&r^SV1 z4!R&@{7{4l&@+WTQLt7x2$V>A%#Yv<%wd!{$Nu9py_d$c=xhN7n|)Cr`c8PIAJCJ@ z^xXh$TaKFZ8edf59eIk(1HG$#E_?=HY>RtjWT3bWg#w?sy3JlJ8{X|lnuIVPvFXJ6 zrZpcSBU)8EB>!8|HM5xX4C9BH%&iz$fV1KoPxvYlP<Oj7Fd8KMg})4gDjMeehvnc; zjXO6XVo;tFmF}})eDLdWHxr6=^subfD+PIh?jva+wE8h6(LF)I6R*v&8ne#4OA*3X z(8|>V<+^UoKlp;F{7cr52r~{d7vKvIsAB#Zin(Kc?K=!BkL6-6<|@IUw&Zgzs){YM zJTScgZ2=k@k*6l9bX&n?yZYR_GAWg$AaEv!9Xohnn~+zv^n6DkpG{keN)VgsZ>%sf z45s=#Z>cH2%JKd@3s=J#Pz8h2y723q<KlxAsoZYteJyjg7}I!}<19R`SRx#yFjRR7 z*A`g-L~<{is-F?HMXAV$vJm(e2Rx#W<mZEz5INIf8$sO)OPA|yyqc2_(=j6D{x_B0 z^bW*f5dWPfaE@G<`8yKJIBuG-+vvsU`bMy-cwWJ#5v8il#af*v@~bIQ3tZp?9f?!+ z!izM~OuG1ZzBOL4#e0R|%k7>yI!4LZC8p;W7<&3*jilGj_axm>To)4>%1@a?m9mq| zGd0xt@>-m^dSpJ{;j?gKP8+M@6X0mZJP}BzscAKTJ8^?=y$gHQHaCOWL3|-%IDvVN z12s6VU~L;!GRODI*4@^!k)1*@H=`}2I3qcVkB;9gq2KsQ3NGKY=Q+HH7Qw_(by*j@ zF@MQN!NQHN=CGFQEH71X@TBkEF?&==H&WTmHWJXRDWLe<97OIitB%jl6Y$#=GqSsJ zpDm^C!{c8IPKiud#;gpRGfB}?lNroo-zUb0HfB7lA*cjSj;g{Z&RXBj1I-g2iQ=>7 zaHcEq?{r3*?yHQ1R3~(+H#2;sZ-2=TU%<*1`vgM=<Q_$M(#c=gQ?%aZy^&m17o<rz zua@Ze5ThQ9bIpk^wkTNImCU%o82KcM1+h-E=-OJv)=$2tkR&5eyD4wvaEqc%KAu%) zuLG+(qc)<~;{@?=VtW{k!5i>3xsG11z7rdsdY2YU6g<pX6<eXimaSUux|HXCh&|=| zv>$wIT_{~7KT$PrjP(4`qhZ$hDR8xlrPo<tsXIEnEO}7k9dygo=W-)yr&3|ep~ALa zZEw?|zlpPnB@|S>X*HvE7fW@0yeBR|E@6u`q2}=utUyNB)6%&#&oLQ>G&Q_e3TyeH zYk3gw{EO0V%f91-UrsGnoW)G|!zT+%meyTW4^C?rxpC_k7kw49UAYtotg^?f{b<)` zJpwexlpz|-4J9|K{;XhQAn9ZgkkeMR>nvOKtRt_As>_+kbx(iXngWA3h|I!oja}yw zFj09iUDUk>$)Tcc|7nAR30Tt(0^g$M{Q9CjOR?ndg}1AaMSv8HOYp3kufUwktBS>q zN_SjsAB0}bRix=53tei@SM3F23zy;RXYv$ZbT|bT_r84p%Wr9{upv<2O1s12V<M24 z52<KqE`0htG<s5Ok)As_sPA#~)}sO#6TS-Bf-aIIDA4I~xedSZq}td1_x=GH(z3xf z^|9Y0!Fwne6FbSr8vKfzUC{5Jz%OovGuOtiqB9qOV9(nPrE#ejcWgJjuk(NVy=%A7 z6eZ*+%?Dcs1V8IkIZ{}NaRVP*QHmAs4SBbo4pnzt`VO4v3e@|vCsuDd@C^(IgL}6< zC?f6fmNt6_!`{ia@Im%puYLGuoF1t`4*2Y9KFNmHOq6>#>6{a>!1W(dV*oS7a*dqW zI`2FJ?Q-C7m`3SQe37|d?F!J+JtMB%<ufnGTHTckS>x}owvfAbcp~Ho`(YS2PrLF{ zfvPd+u0s{0<qoaGkMa-zdGLbE$e0$l2*Q^t1ORjaD#Sp}xI}7B<rpyVa@ZjRoIEm? z!6{GVQn?dKL*D3gpBpQtV0-pL@1B@lf6N6$rhcwi)^~G&B=catT$NM#QXNV{@EOtt zfC9hLkI4XAUqc%kEi}v@G*#pXr}4EB`lIM%Xw*?gSzL{vN<vS`qep%(u7=J^mu~e1 zqwq$=LT81{XqKq=I_*4)Cf}s*yf1iBiN6Q!a(;73JZ)9-URB-m@b8%OdG18`(gV3P zhwv4usbwfXdiT7=?nx}&_;en-6yW4Ng%vJJaHW$DqYJt|d`%1)mbZ_y&@@Io%nAOP z`gW~V{=YC;f$!Lj&gaX)|K|Ig4vT|9i{sG>pN9uyIC)>C`ETL8-gJW0TV4fBPTYH( z;p=9`mh^QwLxJ076qx`IBe3dDCDmLQdp$enUG`;lAUYE`0*-8%u8(<WLGg;At7gCl z8Zx_))N=$EY$+&3b1bYIteayxVrKaa6ql;o1|Yb_xXmV)BqVKUmu@<5B(2G=gce%a zQ4eeL*oR@p%wmasq3h1nbzS<3Z{0>=vDTfn8~B$~&!GzOwaaNNl&pFd5pZM5CFv<4 z*Bq~*K(JS30^Fd%S67j09IB{z$^_WT)^gq+QrdUXl#;)MrX{N9>1Du_mJyi<sUHxd zhgv^eLuEg@)EYaw-^|TjiO|ikeFMT(luK=RzPbf*C$VYJb^Jhd*nb)~R!*#QU4Qtr zC(l%7dVR@IGHK3x$N2Gq%|(_%D|2p!R9&%^SKmQJ+NVl&Ah3ZE5JK)jd!ErFQwKq0 z7mfU@{9J~lDXn)xh;K!<&2obr%`GO?`Bs{A=8z>F?$fAO#juS!L{#?nqs8dxyQ*;6 z@pQ`KD2W?$Fww%G5JR@Xz&9CVjp7zC*}jO;IjOq3*^q^+7hAc=PxH7$1m7!yHtRP7 zx}_obH#^gMfH_#tusZlFi43#<wkX2wE|)vZP5mVc2OFgGwchx+g{bJ1R}vkCh)iYA z9p@K5>pJ$<|8UnGZ<SRDAgI*UTJ>b=C*bbg=i?j9ULVD`EN8WZLRsA&8$|@XT$Fwm z=bEZG%M}7$tiPXmq5MvM3s6U-P%Kg{F<=KnQ+dWgWbO#r)s$8EjlYNnVCx9kNbRl0 zv@Y54PGm$%xFs-=r*B-z$m*c=vCGe}nA3vz!pQsh^;)J(-eaoytk}f^@eQtLsw?#@ z-svmpn(J==Out>i$1bCy-MpD)*`i@oVwE6BG8KSm^)fBOYX(@T6zqKR9y_(yi1Xwt zIGVyb{N8M`#>;0G`Rj`X5g=7;k8L!P0)R>f<F*u@6enS+D{1Ml$5cfb)NtSpdIC4^ z43lYG;0uB9VsKKKj{;rcA$l~siX%$IL4MR)+yrg_li|h{n0D)fi*JG{q8h6KF$d^a zxu%eH7lBlYKoR=0$7+@ab2Z;c2;>Y1Og#*J#^=<fZ8Wx)jl4=FCT>H3l*i)*%f~T) z-b2RQ+@wA>3QHZmd36a%NA$6qa2yNWD^bR`d=275c}Hx>R}5!}BKDAyD>^>)yGo^f z=AI5Mb>g=pnW}}W%)H#D17>y*^8MLZOVO#Pw&su&zY~EO%?z|%b^5Z<n=GNP#DBL& z@R{c#Ih(WhJo-Zs30&`8052Wou?~`n{HT$H%}Pmc&{(?LD9PK4O7zL@<t$~HuLH^r z=%mcX(S=sRl_==;pC=U&L5?tIS5A6-N(FxxHY!w)mb1Faqkn=u$+A@Xsx60>$>>EA zV7jk4w>;%L)Q+~|*y9&e8vP12A$reDD3X^_gLXVIAM@yEHy5E4ku}D3{8}QNVH~Q* z5U#!kf^3C`a)Lovlik;Nq#JE=p%Aq;ENqI3k4}!B0!X~?LJ9`RTtwAFW-3auwtZsl zdjL?m(&{U#OTqY<WvrH71bnf2#>{?otQ3_vRp3{2-%qxNXB?-kwz+SPY7^$v@zYX} z?#d|4mu8MfbN%zHz6qcyxl03e6!m1(o0{%CI_w|r4{j$X<aO`~?2V8Bz=&{_znU6p zas@ZeX!?AKuUsf!b8U02H1sVdE_53FOn~*tX1+gc18(S}ox7m3A9eGB&V52?dgU^2 zTc7wvM@c>&{tHAX8<3vDPpzgYd`)=pQcp*EGmzdFTZ8&BTd(<tlPNS1&%vuN?#qzA z1DmcytAj_N0XRxNX8z_LjW;!_6mv0yQ+zJeaY0ebYgd%CZop4n4f{vZ4k+T-5D-Ed z_lQ})fkHn+M}Q#^^QQj>lpve2`%2b>?e`xncUci3o;7#6uQ#0Y9_fMH0si{5GX+!Y zEq<*~clXSlMl|}AIvb+eMwJ#h*BY;(83V+zX(>Y5YXS}LbeZ1MlC75dC9XSVi_kkl z@#ZTwYw83|_6)J`c6&jx>8kfql1}_QqFHo3%X*3%R<WCp7%slIeRT~mU>$&+>bSAe z!$z_iZztL>h{yes{^Ir>71FD1O1YHg?=@;AT05<$`^DW;D}Qd_lbnxVB_+TW3f76B z0MhLdwZa(!A@k+BsSu=I=-2|aRDedW4il5)ZGn-aJLwph`O3QWtZ@0Vk^J5?!8&U4 z<J*dRhQ|8oYH%qv{t3l1eJ#GL32weNxp!%0dv%jW)N^B}3k=^u-MBQlTX&KbE%)9N z4OImdPC!eH>q!D`kJ4u(z-)feFYA?(9?$p40Aj>L)$1=YbxlG&DvbO9xN)%|sN>m_ zjGlguEk4?(QkkTwW&fV&mF#5i@7>`=;{g;LZ`BbyQ5SVZ(~oxD8NWO(b=l6a?2hML zI*&B&H*#|z)`l`kKH0E$No3pFsU!x=45m|LZ&Ad-sE4_yqhDs{QL1lF^_56-?ggtV zYmM;*fS=L(?`cj_>B~P=njgmByyy4e5GyV$XBokof2V#2u^Z5zm^oMz{$<-|Ge>E> z3LF+#gDN?7o6A975AdSoT+5n@rQL`5f2CMkI07H4CA<fX=6vv!96F`X`A)llj^~cA zoOE;vPZ?`SfX9E=JkKm67=2yf#;jMyYaPAqSm%3suKmV7J;a%uIw4;5NB{383W(+= zN4#n47ym129xmqkdH0&r+*ieCICyQ??bkPW_GB+mxo^CwrJ^5))4#%5mfg74_VtoJ zYCcp6FGE17@5FF>-I2|@Ba}s{gQJ3Fo5FWv1kMl~^^)8mU6_<E7sh||P57$Etp_+d zD-9MZ%?L!5St>1{euNw_jXemD1)SuQR?Q@wT{HG$#mAW5>##9klGj(*$Y)|QUqzp_ zTlbmL-Fsw`8;00igs~!#ovfkLCs0aW#B&N?uPMgsQ%JUR_mxT+!=w1fA}8^<7|A$_ z)-Q+vU0y_xWC$&n2_+DXyK7DfPDJZ+?Sf^B?!q+uVIZ#s4Z4NhyW$!lnrDmyK&rM^ zQrdT;Ml;degRt_$$b(_?mLpL~tix%+1)^#)buZ9ie-Y-7Pg|BoZ|oTSpaeE6try}T z)9N-2{DI%IQ(esv><#e|_?Rf64BCklNv8~%9m<Dqkk*0DuqvHoy>Ol&Ve$>I)H$MJ znb8~s*iZuDvJuHQ5gc+%Vl=7W^pXw^5t3{ED)Eu@3HEZQHtX%FtzQ4V>r#`HvoWwj zY*oTb;}n-Fk=PaJB@NDmSw?IX`dD4us~1+aNVDC3T~Q<D((tpSm?5ZtLmHrrJ*RN0 z&EQ!^cy;^1hi?SGK&GA}GQj><<eA2wXWAvwO+QZ*)1dFEj8OOD|L%1UK-}c1f<}OC z)2Xb79;bhQ6Un?Hx^=@^=kP)-4WwyA1MKHUH4BR6Xn;>@kkU1<%`7Mf%D2}Xwzfxa zTg$}%$g++F{)CVdt#o6p;SK{RS6xbS{xHLtEGrg7`-WZ4!j;K8O!WmpSL4_Uwxq!? zzz<&{F=%l2lZ#ub^9*fbVW%!QR&S*sQHD2q%@O$ptPZdCQws|eT6z%_dhk+HI2A^U z;sLU#3%TB2fV#Y0Z4lE4x|Uk|ATUy3pS~u!5HVS}Kr+NEQb;>x$eIShhCRA05C#^! zK&6fgjz%7W#F=|aOWhiC_s=fAh0t(esPcz*u#{~SSJ>PWrAeh;%HxXXRy(~Zc^Z=M z@n2=QTI#93)anI$1)GWedGa&Bad5qq?8UQr0)6aMw%N}5-JSOFPN_IDM@`p!zP(I7 z5vJ^#v*=xIXPF^%LLs}T{4gY8lf)VH;s%3uaG^^u45WGyY&1d%x%=QQ48sy`$s&c} zcgihhz})XAi#!Ru|9yioZGy3`FJ#XwpF2L_BXv4uWd09bM_}C?LQ;bb!+O@~zE30< zT^{=}EHvaA=P;}{4!MMuLg<4tc3{?Pu{=T0f4TIVSu)tD>UcWYFN+9qGKEk(h2$dT zdkSRNI1+t$Y1n0as?AjztbrJ=q23KgWLI!W<w?fVSEbVHH`P{bAdHn`xj=O$8%l7g zfKA2=ra|FK8}I+_>pJT9l=Sq&ILsK}O7O?(;AINbqZbHrk+h|NZ)qWnBeG1|86W-Y znl+Vaf<bHj7dUVtDcVjULI)`CP+~84e9UOx*dpLz;iI5ii1^GLFfw)xGLFT4I?t4J z&a38Vs-**Ta=au#`K`(+QrW32Ue_qRu|ICMTMAVg$XDJk)IVT`msY|bXVJxBviwD) zz7NB?;#$_6Sbh7VS-fH8NEpTYrr90(e_fDQfwpnBt>ShPFKiL~P8s}xlrJE_?hK<X z(C9mcl&UTgq(!R!M3lZmm@fr0bW~7dTr`4<PrM)g*kmb#Fg5=|nES*_YIKHKT(nrB zD#0aLw~CwZF^9g_vaMXC@6wGPn2t*vrAs1*ahk!N7Sk0<buKN2Eyb0!`QQa+AM8~o zNznHmQgmH80SS>QBzKS;v;dc`r1C5>_|O#btqT{?I4R3CQKzf<3vqu2sr|G2)CO@@ z{E#O1z7eX98kA3&XZvsy(U*X>dGaVM<eG(EGaae@QFFV6S2KJG`ZkOHpeF53$hEdr zXd@0?B!yi&fi9iUJVtaz_%hWyL)T29)jP1i9K9R#LNEGZ{HDF6nQ9eN#3mTvR47VZ zN9-sGr%WO52G*oUf=Nz&)F2TVz3%6CZe=MwWM>KKH1*Q9dHB8mR#n=CmstEgI7TmP zGAVo+c|jC?NT0=kk?Hb%()-fEfY97;*M5)xDus<>(IVX_4vyS)WL3_#B%r)HSR1+x z3ZM6H4!gTfLf01Qc6Ola&4Wq<7*Vtz|D|K3gfiV00m;8HXvrjDUPG<XNbTG>K?PJK zWO8(8ek>wI@6#oPkGGxBwF8%I)u-J%ebt+cA_Ywn@q_I-w!sl-`K5ZKYX^n*aL<e= z7}=xw!*Lr&n_<dOkEVM|MiskWS<9jO#>cZ44||LN&!k;eOHFVoWo#8Vwt6&o4)ZsQ z;WLi%_3u&YamFNXrc_}o{CmV<F_(H&_Y2lM?$B|A=yAKPi_5Gm8GnSJjA7#X#{4%@ z^hGTzqN&IB_e7woexDtWQ`7J_1*uIktWjP3Kn}{62=&H~3_8(T<{9(+zN|8$a}TPd zT4b<hqXMF=b$ZipS~v>+z^|QxB-@>~Hz_4{r{_GFDs%2K<s0P_yBk#_Y+A-|eHeGT zh4|dZVP%J)_{%I(Xa7{J)bV%fa7%l)NGTU4eOXND5v@SCDg3$~(&u~xmJNM`06%M= z%6Xww!vr58L#l^6_gj`#r5L_A&EGfy0l0D)W=MCZS~cY9ELC1<^TO}Bg?}#*z#xaG zpYQE>CfdKVw{NwxYtDr(O^BHh0%nt)f428dIR@HYAO=ss)4*Ww9<D)_wh`xhr`a8L z3gv&qKe<D{hoEn*gb$qvii*E@u(Vt-2Ui3Deli8TgVJdgVQ^BdysMKMQIiOO4~VVY z8r_*n<3Ls)b^Ikjcth>3$TfQx!Ak`G9LA<}l_7O;aCtTJbOMQy2}N4gjVZ1z3c!S+ z;dH>_6Buy|YR~<j_}EBNJDVE}N&6ytt!~Y4o9-BRL8bO$T#f1cgkj5xnsX5u3sY$f zYD@EGDkiVTJ*WtHMAy8y(kd3hb?G(7u>SRV)beD>12im#?CjXwU^U!i^Tn2LzvALs zGO10!rFZpc95%JXQ?=7Gs9Ohjg%SNO95FwUDV7KUQFy@)-5vs3U$rp-+m&2m_<I7s zSfsB)P*8&?aq5(^h_Mf664dd236V^W)J$JWJ!Q@j&p#q=nz3xOZf};4^B1s`vp3On zEB%EqnXg7x48E$^fAjwDY77Xyjh2#L5vaw&Xk1_v@sRSjuMfU&f?dRma4)Imr=H)) zap-|`<1TCOWu(LbkJK)UgSdwk;yn}@|5rVWmuWyQ^Rpd-Xm2ICn_Emgyn)=<fB`mJ zhdig-4ITGeY*%BS>m8~otnahd_;-8<Rh<mJ65YRaD*O5&k#F5hb}GR~S+6Oi9&epM z!8xxiZDG?{bn#ixvQwy;!-XsQ)a*i5xkk?E0m};)E3mQZfqE{(lcDz)f$+v1_2_NH zD_aEP0do61Mq$ZW_`zO@0SO3%yg!HBk2{Ry*~r~EyfrtTD9zYCCaxmY*??iA`u)oP zmmbH~k?yO~HZA0%9j$_j9x%Qq9Sz$)fo`0D*>|I<k?(H1z*gGd*#vM<${Gu%S%7NS z^z=M>E8f?yFnkGw6OBLsd6XfDY6F5qBz=Ha4GmKPCYrR0`dpHFeDK|HraDM%j$AE{ z&axx%^-Y9q>_$8s`P*k=Lt{%WNOYO<iRdb;KW6{hRknAr`xjEQHQn{%dB)G;pfjDv zKm9G~s?a;2LImjok`xE?d`5<!zJmurR}G=DQBZ~<Tj=YP`Y#NhDxXV<f4I!aAa*5$ z&hO|gG5$Wgk!yE0l?R#0K0ApbSq}4U+`;JU9sLSL-%wV&_VAoMS6Z(2$zY+hjTyGE zI8fw#{D=VEQn!7AgL_~8MS8RDRJ|;dLJi>@r;n%j>={ed;WhE2&Ci`ZKg;|D0H6Qp zuZn%xwL?Ide^4(O3O6JeY6y#+CanEnjJ|(n)^S#3J<dAbr~QtR(r8v0Q)mD1Z2|>b zsw8&&*X*X`@M!U8$(r<QKdzeGgFAmrgQtr^S5UUk=vo{eAvBa%&@ci5F7W$T=j#(D zlivsiM5D(A-~|EzSfV<B)^J%wGp8V70a8=id)kV~&+H#Uf)>ZqvP4iVmckYS#=<Ih ze`$$S8v@PH87c_<zHyn-ZMv0XQ=5g-RSByQ>t`Hhm29o3?zPq9m3pIcmr<IqV{_7a ze{#vF_=dc{afSiEZHAC^z>z%l-uDj;8eKGv&*X|etd-h5ueZ0X_uJ?s&Su_-b~m_% zbJS;%^w?TIb)Cw_Ua!Bk5xgJyA>hUaVu=Pw*3D7$I~&_&Cb5DVXmA3&oQWvOPbBcv z4knQVRSsr0W30;=HmjFC_g)>hQ1f@_4pVy2abL0KnvRcBlV<bvI*-dsNAyP1LPeea z_=WgOJ3y<$fO)gUM%mk<GRW6ToWr~-2qw|2BlNs`5D3&E|D|A>V+)ffX>&O<Qli-p zdGiACbfVoSc&NsV;Fa)$<F^^}yvtRzKxPCK3QPf)58+mz&}Dr@)YBmars+M_28jGQ z`U0T&+FbMHS|-3c0U~I1%Vr*9BRzI}39%VyQLbw+@=@~xfZK)=jmw>eIM@sg5CD#> zWozG=X+#0lQVoT61dvW%=$0XadQ}4mq3(+-<|}cfp_)T`mSr=>-OtpZ;Win|K45oD z%3jqs5PkI3+(_nG<NZkG57bPI67Mvs2svI90FifQq)J>U7z~x-Ql<nhHi9YKvM&3i zOPKA5#4)5E|Id%Qxw6yyi~x~pCcoCp`xCFdz#B-MH+O;wzKXZRS8Q_aiHJ)5z?)CX zz1?)!49}cKpO$ZdK261z>pt#9K_$h6lHXsY^;CVD`s!egIUqmsF|V=*%C%)Wnccr3 z%-Vv;R}kTnnp@(@6Z20=Fpul%3A7sn<!BXL3vBvUoe8vy^J)cCIw6bVVXTUPPOx5X zVOAQ^hIBbUo+buL9oZZ<$u&69e=9XoYaZb)yj7jETc2S%Fg$T}yg{j{P#1SxS8?f5 zP2qI=ly+3?)euDRHO(P`kA(_@1h}*p<5!DPzpO>y9+DX-TDb_3e*ysP{1hW&W$l3t z`)M9>U>$Z1+l@**qC*u~<O=`(INL8%ZzC;pZrZaF#`vpxMUZ~tXegTF=GKG3Rzj)n z{FaBX=xyGn*FI5@eOBLE0a|wZ0q-v#Jl~y-XWG%R1e&J&I~!*UGLpiUA9E+PhkbhT z<KJ)Mzxft6Nxaw=np?{%JqVZ~PHB^lDxcNd1KR(*ox98O{qguMy!&Bk9vsjrUHmSc zFFq6Ksj`z`f0>XaxW!P5_EC~dOP1;J=X<DUdOFJFDzHl^C2C%MMy9NT4K@#AT05V1 zto~8xeqN2*H`P)s0s*wz`)oUJoEh#Cg-`oN!+Bgm7kUQTjdr^RH;H;w2Tn9`uW&k{ z>K*#ITzGYoR<kq>GtDcpB(iX^cDk!<s#&J=M78xB)K-zEQ2&xd9kE#~yh%sCH%Foi zU4weZP9r#RPzh8$<ER2_NmEegxN;?;HrJ_?vUceuJ3po5*1BQ&RvBXE-f-QE(9m)N z;ui86FzU`%Opn^Le>Or9aYAE^#YHt~rqzP?0YJE(J-756D)?ZOnl(*cT=IKX`Y4x2 z)LbyLZ#ysSGH5;;yx01bJRX1NB-M1wGQ)q7lD*@EMh;*?1KYf?-lOC%G~d|t>S~x< zO?AJkcWN3=SX6vjoqi2u6`MlG(1(-&Dd2*aI?)J2Z|gKSedLs-_H~!xKht7Hh9D*D zt4N_rN^%g_*)_l^Pk?3#3zWENI~q)R-5o}-3u_wXF?I<*KEhKq?@0u}LO9mRR05lf z#+MyR)G?SA$9_56w{$gKvE~%u*_8)+agB<8G_vx@%)s6+8p^evH(He!o_<T@{@gpx zs9L~;Eu-TF!oV7$IZX0o4f$-9w>*sfi#Om2`E5ycno%-cr7gA9kGZzBTZAwX31jRp znzHnnz)#j~sC`4c#^krUi@sTE`rOe=mjA#6o9mfon`)qyij#smxKX0wOK56~ZVIvU z=y7$dYpF0LDpXjCwnudx-SCfod6DM!jhiP*6Rc;7NZAJfP4z8Jb9cnJxCC!U&SmR! zWKE?vj3Ll?&;LU>lb%q04~;%tLUP$G@sC{XywuJT`2FAu>>9@jot9*~RDJc%SUW(h z{7)=RGDTI>e|Ftf>Z)CupR6WoI6?=FLuNP~bfZQid@M1-!un_a%-v)D$>K2`>E($C zey|1-gr?-YOnGSZ61@Y=4blNXCsffr^nu~_uj3hXSUyoK2*3M=JcivKgmjThF%|4t z?Sb#@3^GXO;@fp>(`Yu+z2GZ8{H|;vN69wT*#ksHK8}^e8s$GK>DIVWwbTC2g3`-~ zc%TdWJEAjA@NL$H?S=JxNJY{4{1VZmDK3x(*@2Jh6ajigc-y3=S}HhcS-aN9C27?E zwltR##duS5fK+j84p;iw9HxY|(tU4>iT6vZ_iJ+}g@Y4fkK44=b1w$TO+)6>t)vEN zOIjs@l%z}h9<0bIS;7nRz$$B$<Dqdo{J&Fg(rNzuZ2kWDr$!W?UmP`gaJmtSw<3AP z-~D8V1hy*I6w$vb!vj0;ustt_c>X8KW(A$mF-TiIB3mz3?hf-5%*wQwvndnI6}=2K zTIWRtq{`{hy@k5_S#j;6Y1LktCW{OVBg)XUN@LkjCl1Y=Nu4{%s2RU3i&TpbJ34Iq z6nmz7RP+}O$NH#wa`o*|%oZ&*(6>z&m#pj-EMpb^OrXZw;M66BTS1TQZqc%fd~V&~ zB?PE!gME&%jx7YCINTAFop|LE$)zYm`||x)FLX^B2QAqNX6^v|!5^Wo+e~f8R)wd# zjsi{^NMz1cGiidHYoJovvdEV}6*oSh==G#9Ex@Uv%sadcNe<#=s#F;hD9=PJWyHQ( z+l6O{XwxYyBk25!#D`KzQJ)V2>1%ly-Y4P3t9Vcu>IfH(;a+Ec=il>>4;_9mN71Tq z#3wxDkl=NO9gzxWe-w7@ewL;M(tIWQbl50P*{Y;W0(E9TIwT3G3vMq6g!(1UsR&lR zy5L+X!%uv<iACK*Q^`Dv-}qyS5Hx$NBl01u?XJDrY<y&uOan4iA%ftF7Eb9?Bcc1Z z4b`dVAkfj2=*`wh>%=l4i4GSf0FVV1d%7qnhu*8mpUbnzfVDXXdVITY?Xrx^5W`Bb zlXmHs2Gcpdr^M+3shLdaCPIK$lF|<PztL2Gsrpi)vVZ&2oggAWs%X({UFFDgXs5I~ zqV_N)XfYBrhX<(#@M0fGMkBNlfkaazG7$kQw`NJ`1WTM#SPLf(g>c!LNtHxj1%!qx ztTnQxs1mIqwv6T6l$FMmfPJ;<^%c@^js~fiUQ>3=xtjhGP3lNaYu4bTyTJ2Z28^_~ z=snvBx=zUnGQFjGt@z{Qm?zX8P6St6znH4FWfHWrT0RA#nLkQ?etA%4O8gVZ(HS@; zLg=@?#soWcc(g(ypaqST`D8Yxsj8#3O0aXPaAU9Gv*h5jWXf{tlwW2ueFE`xA~>8- zpAkna|L6o7rG}Fs1Dtggi}DhRnz*?9GGZCANTST5_-GWOoDNp$)+{5Xv$f<s&nCLe za=K~hNJ-1#j|iSwS_Z0G<%*aTVx_tswQmfDgjWA2+VAD`)VqPTn_f5b!xVxDPGaxa z>xZbXB#7(j+T79|k^!#+q(lR3WFE1=nKva%R(PhECx^M~f>JMjtH8gJ#=nRr&iCo# z_09@Y4muYt5z08eTTQ7kj6y*K(<2IDF%{?asmwV8u@AI~?LDmLwL~x~|B1S|km2(k z3T6}~-gQ)-S+!`j@7|&|u%lf@o-Awc9?B_l+Ts1Ip=C8%=+#c}*GrZF^Jp8<c`;{+ zy3V+flfF}A)pm}7f((v<IIUlh*O4Qgn(5#bg9S@+_DOphZjxA(AWWtZV{hn8*Y2hQ zZ1;O=kH9b2`-*D~--m!ds4%*}6at)BokJO0R!jM|a=oVtz4Zzg>{3VF7;rgHwN<OU z$>>X(8-OaBzLl=Up>3)<$VoT9@W<rw`;?fI5w(k4Vzw5GFwS_@$oOqke*OSSA&)rS z$8!9nt+sts#SP*}1xYV~RHh9C4ix(J748k(JL;x<NJ^b_fqLrk96HZ<TkAL;B@d#t z%5nXW?MH6s$@5g#8OkpSU2(BH27omvu@c0=o;?Zzuz^HDz3Z!{W$^}d=SYo2cGX1O z0EZ29K|l55Z&SV`qu=Yf{%9)vNvhXkC$)b%Xt>jRk>+x!7hGbLU<S=7EpP?Xc;c2t zsLUn9R5)|N+$ZrEq5Sp)3L$j!zDs^rKe1o{!j-}P>d(Adyy>7Gjr+UguZVlbmgz0@ z={`=^)ElAe(u60A$r69fwFhw|K!Wo^?>-ul!4Ga0RFp`J(@r_3D4!xK#LQ|Zv!50b zd@di<UTQiuldJa7sj+@np>|Vr6YWQmFNr?|LU3gldmTw-7K8X43b#3LE>ooD`EBWP zHyu%@lF|<1Jc-{mNXP~OOfpw(WQ!+B*E6TGKFl^;{ko`3jd&c9Xxc!S-naN0osQQh zI0@Ydae>xs%vLiI?24!l`Y?h&pVuPRT%Ns{WS=Zu1fkgzFt`N$j5VUu0*MG_-j!ch zM5UapPP0S)3=sXcQ2_Pids$*bDdAf*RXy{~GUD^nUS$#Srtb#K>=bls8&i(f1dG{a zCw29^85^I9X=B5P3F=B$F2EEWR3!Fs2(z={ZC}mstwhEA4SMfIZ&QL_L{gg`0Y5F4 zWlSd)z39EDgFoT$2&AdYfxGLq|CbJSb+YwjSFRDayYed~5=Z1s0HG@5Iob2kI0`nb zbt0~r=maY?l!B7h7b6Fhz8O__(jS1bF3osZYE|w7)U^7ohv+BOD?Ft2S@%`mPC2{T zw-qJZ4|?ueX3J89)V@UdTVzG7q$$=-gI7w)L$)Q=`<0}pe<uK?7lF2kmPN}nt?AQ$ z1dO~WpG-~Uwi;ECOC9p_>>`q0gPwLjx%Kv0DGW7PhmQBo1(k6Rv5H^)OtMz}I!=14 zNjf*)4&m`66O=B{NjpC+{EX<ZMom_7%RWT~t>1L%Gj1g|BwJ=BTI#7}+By7vmIsp} z{=1y${)zK;wd2^i#h45Bdty1%HyQnW?Ny8Q=kl%wHH^FU)9;(oC)ljl+Ii>O_cXk3 zsDP<8Hg;SL+tHMyvjl{PqTE3I#^1Znf+*c>YY?mAm3cL;kZyVUTNXpplka7Se`UcJ zK|8Nx!B^;Y87avAs=cqNp{Z`rI%OIMa@t{hMcUC~Ets&KoWs3I&HiuCU?VGLiv3Pp zJe*P@=_LNYR{kOJ%)wvgNBRU?^u5}gQtVfH(NAL`ImD;zS=YTK8FZKv1G^^K`?+m( zta_<&4sM1Q(<!lmDY3*vdW5m5G?6maDy!XYPzjParJI6ICgqb}XlqxWaX)l+X*G7d zN|TDs<7^(^tcm0tklHOf@8*u$*n?3yp1A0Ia)(aSMx3X3gRdUL>L@=|@#GV?S{e+$ zNZf2#x9BFEW}w{{H?g5Jf(}r&V8RpATYVsi*j07cCq!EyPJ*1|@XbApkp6EwE8UFC zV2JpRI*#g~3S(xEIcQ6hc1e4#V|A2ZcYdIfndujs?oCdT)uW-+uhq(dW=4CR$Pm`w z?}W8^RU%vg;NZVN0xa$oaXmh*z2}pLz54{o@fNwYoIq=S3;QQ+2;Eq?cA#N4;!339 zyLdK5s4w{Mt4X(}L*mJ?(`D9HvD|*gJ?-kd3B()NPg=$_&lL7L0mQMv%rnQNgYD>J zA3aK=20~(dRpGyP_ba_fp<skbGN+H13stHjlQLBd+NhV>{=}t5$EV)`nqlJc71hRA z!#{YYU9{eIv2nE--gk9PNA08p6pCqg_;7yL@%|-qmrOs<cO%dtJ!Oc*Z9r`_mH1oy zUH?D7a`q)8i<xvmJi-(dO96On+jy1p|KVb+R8Ri5I%p+N@GGJW)u&PY?lW<<#MGi` z^_}g&(!9DNQ`dWQvF|4P-@H>6lZ7X!9B@A36#nmqNU>lKgY`HTr}39(`yVriW*0O{ z!&5qKpd(MR>uZk>2?PUQDWcgxnk7QpJSm6i4lyHSw{++7JjqH$iJ@%)0BxKESIWJX zc6oVtxl;0m3Hd_{p^*v@>h^$J-NsYB?__d=I?_zW&~zuZ+h(RmzDYLCqO>bYu3k$% zh6l1N9R24cKiGuzC?Jv#Jh$J|tKOyT8me+fd(mCIdq_<hLQkBcsi>ma!SClb7@tlM z1I+JIRcV~E+zSRBR{bi2y8jH|jeSCMf5rx(?TI7UeXAbk2-)Qck)9mT7=n1<Xf6Tm zp9Yrs7(4;f;7MY@t@A_6c4~We$xj`|!q<FmMM4L3PGT~N)ZtIoqY$DOVCp24*f3xx zb7f5L;xui2nsdfoZLo^(sS6^USp6>)C`wj}O|p+WGyF-F8l0|~HFRUM@7hhz&@`xV zpz6Q?UN7>q1Ukv?k{erzm$|Yp_4Gt99IEX?qcueBT6yz#g*fFq#XmH0eLcyx=p==6 z>Z^|tme<3^y-<J`mMJDIPyw71-~_O*DMfeL+#$%KsdSRQc#~Qc@BQdz9n-o=lT;u* z=Mi8x??|fr!hDZt&X6p32@w7rezN;L@M7<%Gw%&K*u#Rx^}obRM7qNjm59Rdh$}6T z_eFlk{_rU#SiGnH^D6uRe$A_oWPU&SQsox>>PyvWmB{sozn9<nMTa49;+7Rh(kztG zZzTNFdGWk&rdd@bB|E%)t#|OlqQc8ihjY~pyu7l4e39I@N)W(&kJV=Jk!dBhJvlid zH?sX{){%(qtU4rR@q5|EPdX-o;|_<22ch=*`@yp4{s+IS?iaxCh5R7gG;*qNbRsmQ zr1v?bYkf*kzXWhsCqKNXux5yUTbEt3FlpF(Sb8K8Qn;fF9NG5H^uOlO-<@ktXCA9$ zjeM=A@ABI{#&^H`_l(}@@Z(?1FOqe=DDAx%#~uHC^2S<)|B1oc8xH@Zj<InhQ*nL% zHn01n_kNzw&zSHV>CIH?jyu%g_$)=cfY=4n3tBoy&LGpG<b#Xz8&2Dt0r$DM-~J60 z%rp^TjPZ~Uzd_J#Pp}j6^f*uMPuXg8xtn?a->=UQ76GcbqTKWsk^l_@FV%^!^KcSP zBq$E-R5+Rn589<5zsoMS?7YfB<sHO7og;9)+Nd!YJ6j;(IFc?LBJiw4{x-*4-t?Xj zP#Z`wI6ccIDVhPLp`U1XTCN3`DyxCReA;t|mXk!*al6aOtXPg(FEcj$tsX=LwNn~P zvqBLf6)F-gvE6^?^WHPjA8D_0RT%D2oHRZdzJK?(w9&T%GZBwDu*5#LxDwxLFMiXZ zBrtfSX*l4Kaa~~O=&U0{4tH@>t+*|XcgM2(q=}DB%I!B7^R1UFqpy19{=)toqn%%C z6w?@LPQ4gyqj}6DYyY$F%OL|&x`l<<@nR0@*=FKR&sHVTu00av9;5dA`={40#79*u zu!$vHInvN89(&`}k4z?t-JZt1<qoYAXF+?fg3v}nzN^9Xi6t49XrtDRoC5zg=T3If zD}5AX(RUwjR+Ikc>#c*LeE;y@hb6X%UAkG8?ht8^T{;CsX#_+iBn3o3K9n@LAYIbk zA+4}<N=YLN0uq9VsDSAH_|7?V&YXYF|If@l_ssRweO>R@B~X;P<?!>N50`y7iDX=e za9N1~(^K{zHlZ-Bmd{CKm-1QW2&6oR-^7Gev_zM&{H!>=rL&3FHJm5Z4bt&8nLTsb zaW#f_mbonRLCP{MGmyZ&;hxHVmVwFhmA1(eVDQyP*<LNOKUSd_Eq{eHS<J)Y?rKBC z@3yvNTZj=K>WrrWPatd}wg_~5U`;P*JU7Q@r84tzQWz62j(y;frbnkmhI=%F6D9XG zR8-$71O!Wd`Ie$0E!mKDWLm6XiQ7Rp<>labk<eYs*(!@E{&8Wz`Jl38&a`Wl5&WH8 ztHO=nj0;;?6}aeR03wX@dB#vUKMbM`LNvC&gEMxMf-Vpb{W{a?)Q?tt(=8dUxvbhv z%CqFw=zBR0c=&khU~9WV3XT^DSbbC#<_CMIfu~Q1kEA+sPSH@F(ieF%L()4@-N)YL znYvY4dQa=l(3M~ds?X6nI?SF{vi}w-hm4*Ta3aYB<i?s0l%UO|2C2i8zI3%R-<>Xk z5l^i*yM9r0eDQ<r`+VeyIhOXpis@(7yod4~;@nBqbAE_qDsQF7R5zeoJ_Y@#9h{-~ zyKX*k?Kt9c@>R3WC9WBtdR@1pYU&p3Ja@}ql7E~n{M=>~X}Zd%aImM7#hUsl=1C7` z1XELhZ#%4)cp`J(U(7URPDwNGySQyaE!-kD!~Iu-<$s#bzr0`DS`d5pJ`$NGqA9YK zaWEsT&D4+!>iV^+|3}g;M%1)RJ;lH#cJ3o<&KPTA#(Kw&dDl1TSA%S~jn@H#ixR!f zwA4+EY?s)bGB#w3R%Gl=`*6QCYZU37)R$cVnmg8OgaAlN-Qm~{&ZE_0>cmmn@Dh_m zJDDA}p6rN^`gzzuT;BBHQ`*lt;vUD$zWir|ztuW0ftqSgNdp3KcT2yZ?$Z{DSRf&7 zHCvWcHfXvFMoa{I5%0?f%$lYS(K0bn=q?>9s<1DrbWwb0D;dTWc2IW{h8q1=Z4o|h z!I&-+$M}!bLWfLV4b+K#<@*D~pW=-BdQ%D)UbBFrHib}}ZryDjDa2^$;3eY*<MR%; z;JPWS5=D)S{tyjeNg+NbKBpu;WC5m3TMdYW(AVhnv**8zTlmO_jA7;#bIZyQ1lgwx z^bs}(WbjtXSQ=WieiQq?4iH%$Rl&W<n5ck{WTp$?Ni`7cw2!w`u16E!%sJ>6$*Dv~ z?xCt1>|y`~p4^ey^aGo68($Y%*}I?!r!k0FfK;?x!%o)707N_?*5I}LTvno)A=8`D zc)4rx%#!H1tQdYI6+m*^r+mWTp#UGJB%(l#9JPa11qdm5Xbu<MOF{|^6iUllk}Nio z0#otjrstX9zV$3Kne85L!N|M-#-#$@>`Ov7#44yK%{#VO@iLmxGCeTLIpwaCCqv_P zsneQtToULZl8#r%yelvT%Sp=}v*fA?Ycr+aEXsG;3)f;+XwEj;f9mO8VwC*xw(WH> zQf|$xl!_eRqVoJBPk843X_REVvPe)p8M)xXunF_?n@uTc#CTn#G^BykDcy-&?HmG* zg=fDi1wVH&;EKD|emu=vVS6O-U!b|c1cvePri+PpKzebfVG*sLup==OVOFw9RW3N? z6z{f{bybLdN$;k~9%d?i<XG!&yNa=>rftu^*IG`_%`d*GmBO6HYm0^K7u?mmlRwLA z(c_A$QH#^ZInw*!m%I<%Hms)b)KY1mHSe)4{(A^%6=C^MB8jnHC@H;3<bgVTW<;Oe zGwWIA(L9uni#0;*()oalB)%PP(nyGkC)!ktS`-qddxk2Co(Qg<yR5dD?Y}L`tra^R z)3w^e*FvdxbkcX4A+IYc_gkGc8(eYbs%V5;z<?l8t1wo-7YcAtNTpTVh-vTKtbp%q zrUBKC|210VfMj(iBpn)-2#Ejw9&+1+EZK9XpLSDNk|&#!=tt(_M<`gX6F!?S)e_K> zVWW9zaQ8jQWs^Jg(}Pwt3w)MKqP|5+!U@`Ff}}d#@YqGAAc-68VvX>8XYGhk-?ahI zP0M|Y#Oaq4nWb?HH`RcOOsyLSzX2wW;c|y|jTY@P(-ZYx)i=gON}AKad=cfRPcAkQ zzQsws>fRIeLub|v5s#l8;c#z_a-iQ+Guxzn1pq^3PY$0J=g8HM<cKR;Y~^;ah;t!r zTePvB3=vbP;SgicT$O#01VhXWPi*Ut3Zh-oquU?C_eXga8khku`E}Yi=k69^ZQTst zsW2*VQB~e}gBQGyNrS8#?qEH2iAvpdBn9FJQSf^u46_9x^bOhyC+i`1av3{r0BU^) z5y9c~>#~qkrDP`w1b&VFz9OlimF4*C$X0d#eemMx<XP|0XEc+yj#}I4{Y52izE3S_ zPC=zyT-&?eZ(~|bW;@MDQ6IcFnscd(VvTG-d$s}nFMOrx)RdF=!#C#VXryBrsz$ab z<^w*2e?2!{k@A?Km0C%I`HRoZpq?L%M4?oU+AX(tDYRp0{|mygw5|yJctJOGn$#s@ z5%x|7dPQ)PC{r<$4R2wh6I+1gm=c@t^Vom8Bj7Us@2abZEhjfbD6jUO#}7QFOZ>6- z*l|0bQm&u*^@|*7WXvsXtibEc$fNQ4HWhZV-?`bVY^R~IX9UBk3Q7~s=Wd?>VYh9; zu$N-9xG3A)^^qC82yS+TTZ1!?RrlOPPlm<&8VJQbu<0AlKR=nGi{(#vbK!!TUhBiq z=V!K1i&$Wo?B|5L@y(Q6u_(fIGy3-O#@;q%_sjg}X-hmK7{PWtpl4Uqg96!EgZKwP zXtECs6uL5&>n_-;y#XT|JnbVauLhQ3qR+?x%lm}DAWX^O3(L#OvTg^(4s1jqr$uV) zf0nLKW|?a8T0OVa$oP8Q|K*n#vzAQKq_Gd>Mpm(UZ%1QL4#xrUIU3l$nm)dUScWDI z?jue{;UaJ6O-^6bW#e$o=5k~qUL>J_#vzxMyWo!D{e7}5-C$jks=PppII+~>uE9w} zRtimu-98n!-q%e97v|rXT>h&~+Oky4QW%qQIJY8`KAD}5*p?)#Hn>T9-IDA<9!OXj z%YaH2+1%8$r3Ve&*W0$Kd~s(LSy1MiE9#3u+32<;aI@5*g!42MvhzJTBJp{4SOZi$ zuLId7N6xf%(02?<2gIu}@ia>VP5b#41+5r=WNw1}SuaP`vIA`z_mrPw>kIBcOY3bH z4b&3m1N*{NngdY_<Pcf<8Kd!8S7TX6z7UfMyU@j=M*7|$lQ1VdYMmwK82jWr?2UWd zB7X-kcv@j)eOl<ImhAS`U({ch67_~bk&)|K3X{)%HpVbMk)%kG!0kMh^xNkH2{Ht= zQwPn^ah)U@dMgau-e>)|9dD#n0`mZbbwSbSq1izR*2>Jv$4S?D8>=_~jU%vkuk}HY z3R8TFsyoRqcyB|ZqH68PI%76;S#&|b1>XQ#1IrXZ@<5ytn(*-9ispO*=*B&aW|7s0 zNmii|+qE9rwd-Mv>_?m!KKY-eEJG|Jdwpz?;n1-i7|cPF;BffWL61^9b+C9nE0WiK zdO$Rh$k&2lV8^1o7=b7052e2-{^ZZK!9(h>)5zh+yW05<Uxb!e>?t1E+)M47EXC;L z#Y}^^El3{NmT0zvZl9LOfOZvGmlf`os>|5lequ4tUZ!pg$}yPGLl2<$ibDo5sL<O_ zS@(2yY}dl9*(9?P$kr2>wL*0E{KR>T&>F5)kL3#=-BBD6?hR*{AQ4mJi<)8yVzk7L zl#{-Fa4#fYUC>sKL}2qw04OjUV8?O>gmLoX?}?RXj;O&Kdc$BY#!jG5i6~)b?CVh` zU4uQpe<oEu93T81BNiTE8?Z5ZtRUO{WR<kM#9ikiXAk~J-t5vBWdnLYzg*9nJXTpG zdf&q^SzytqPq^8A(57Qb$QzCXwye5}NLd2sqw=-U$EjMS+MFyw$0dbDvpl&1{56l$ zk~9kZQ#0>9zCDp$ie=1&lx*as>3;o8i1~o7!7#|<QITeOMOBCAc}8Yf0W~Z`NuL0{ zi{|`#<XBAP*mmUPx&p_x=L?s^%stI8kmy%i5SAgM$m+0RMTl?^nLm)=n^Ul^J>PJk zTT%I+;s6<6I1g_)hZ)Ir+7eBV<!1lnQ|dZ>MhX!6JDU!}9^nOj`)DWn+M&FMRJ-;v zmXX*Bb%^U4mGHBF2cCRL!Qc%Owc;kUNbn_Dv!ck|Bo`&dVXt7U&bwI6+>b;{DkFXW z1@4hq@xU;Sgu{n<A{$rgquF0?5h5Pm!}1&B`L;=7(jRILKpnOY?;2HErbHI7YT+N2 zD}r`~B@g&Qv5zTs6>e6(*{TT<bQyRT^8z=Z_q`lrFr)fNM28R0Z7+sKg>!C)-QfH* z0yDf-a(HV=T|SglG51JeqJJf>RBuq{8WhVD`6kD}l6I)LY;4pElIL(D^!|Y5<t~d5 zrPu>1_Ya0+Z0v{n@@{cxji_ag-|jnesW2??rPU}|(_Tzm6UoJn&tVKl0in0Tk6IGM zlt%h*4yYdtkxG`R-|FsHE)kW&ZjOa;#TeNe=`0(uC#|2>6=)u+>3t>UR}Mr*?GilZ zg+jwQE&6!6X&vmp=xs-*+<Ux^<nQ?CmV+Az;Uv455S$C1$2i~Jb#%wFf2sfhT)-!A zQeAn?p>nr}{D8XBNQCkU=`9;lm9uMFZZVIfA+J1^*8oIk(I+^sJ$Uu<B9q3^$jx&B zt!w6)a8_Hz;r`)8xb##BlQKxq-c^5qiHyskjk{R)YA{~U<0*IK)4RC0NfN+>5S#}8 zKeXRT-`r0U&YJobLd2hU5lXm-tJ!{<x&E6Y{VLm%Uxz#{3R4;G;l<HrFC@#9St3c4 zxV;RjJry+|=44s_B5Psd<p1G?yTdp_@ey0X`W98eGonrkwM1RtstaR$YyQb^v<7{w z#6^f0u-(TR(8tD1#<_GtbvvH=+O0exMT|#W;nk7E2fWvnoxUXh>EX{G+Ect_1o22Z zqWO)Uc)x}Xc{zX#5?7l|g~@1k?Olb*()mbNljaiiu*PDEWs>wCrQoD$+_6vg#=_VK zytw8YxQJ4yXJblVy=Z<!D728O<ch1T^{ZSJ^XOo^%fdL+!uiZ1l^GiNtbL9jHR;-a z*BM!?{TG>AfM>Vp6Y9;-pU?Axu;z+N&dV5<vuga;G`bW1O=oYmk~2k&D^e2F%VpNr z##+n>dRk71knAFrs!>-y>A%XaQ!Y9D#~LYKj#0HDBVOQ~Ui8w*2Emnw$tGzZf#a<i zDyToFYxKM;UdP(#nQN41kA-B%W&d;37k>PTH3gIDc8g8J=P#yvmV|@Q$HDwr?ZfD; zi3p__QiW-Cr2$VR!Jjt^)G@ctD8xbMI^hhW7}R{2s#e0ejrc{2uQIn6y^@CW#{r=q z4zE@4!?Mn=ZR_>gA$q@Qwc~HHcb)3Qd=PzDxB1bR`}+^B6KP=Ylx2kElDyS8Lq~Nx zLLK3^oI<KN->*_ZDt)6xaVg>tj1#ry&0W*r6DU%n2fA7Ba_%HbtmFL+D*u%(X=IaN z`CvlGnO)EZD@U5A=O(Pj%Pl^u?fPu|7haH^=t%TYj68pmru4DN&RT;?`;1kzkCpiW zJM*ugD|Kv4Ek;yUUgp<>diPQBAJTL;9X$!$?6Vek!x)$yACv#aB)}>Y;#}I!^o<)e zPsG20)MjkMIb+W5x>_8!+?@ByJf78-eWg)8+sbY}K;}}bxh4ac-P^1s;k;_TRBiK) zj8J6P7~4|6h453ckW*ahSJ^vJ-j4WpAmJD<<|y!sKw?Lh$Us>i#_@G8X~hp)@;k76 ze@@LilvubKtRF0}$w$w@ZAQYUj5X-gm~fRDl&8vRZ~67k+w$YnFr~<agIPm?c8u9Q z@Z~Az)eWGA1dx9g*&J=kHK2SIp)^mbfFmV7{8ImqGcva8BIivz;l&a6NFS|5SgsyU zGxGLPfuxK6(c`;yn(s9vT4U%Or3HJdYWOw6>l*KWjij)B%2#eSuc#qX{LJ}K0gFph zy8B%BYZw<PU_30s=Btp|rL6=23ItN667>hw*LUf+LlBTV*BPtN&Z}zc!+=Fw{A4?k z^3EB^kAM5v(8T<G<ec*v-`X(W2uW$dSr+HToU5<0;brL`*|`zlkGr#vR%Ng!H?V7c zoH0ShZkrWD4H-F#LDLbKihjQv&3}>tYR9{t4R;J^BDfM<nPS{h%?EzNx-ba&9e$11 zT>~xe-B=^7dDq_B;BKaTD=(P4L7qlNZ14=y4GzL41Q`!wZXbFx1Yp>Mp9kSiI_lJw zD*7KVohhMytxN@tFLo7fcFsYu+-7~WBVn8kC+%pB0D(wxKKy%dw`NUSZ%&+z`RUjJ z8DFS1t1o`@$qxg`=i=G^s#cxzkAfcT&Kf*U7k_!ToQI5;mFyDQf(h+r#FKDb-C!^I z6L_Mo6x?4k9H@HMKNitGKK`ep@C_F{9MyZ0bKEnMUEMM3t>bbO4_4_lHy*e>@p$uG zFFKunqVG}FRMnV<g*C$S>9>S(InhP3!3}96^8ubHMQnn~GO60+o4%Dl6jiGdDg`y` z{qJg5SIQ#-xkO3mLOtT*>qgM|#8jqtZ#n<zK`yrs%Jl~C2y_bp%#Qk^7y5Ipn$^$F z%>U|AwtevI@y?(hdPO!;tTYnTM;jc*)DU*?WvFwURC?pv;jrr0H*6K~aGxLy6Mg<( zl!w@>>PPy|#X01A=VS~3GQR83xJe4H3xO9%6;(NP<TEZafPwF|1bA~}5}3K&*&$F~ zK$}NfTzVg=hJF=IO(IAJ%oJb*MgEaA45N(zUs*f};)?)#p<TD=cl@IQ=4|~eS-(qq zSF_4HmG@c$8TeE}c7c)V7*D&U=NBXCH-i}6ErE-Mw|;*Z>$LMpzt<og$v<!?2W5b& z1e=WsSWySG^b?DNkyi#pn(zdA-4uS2d(xU{dFYM7vJ|x_Up><jp4Y|Nq!wo_rQ^NQ z;LG(Tuo~AAa7<WxI$V4^-h-kEd8cKJ1#sG8lnY^h?z3aMpY_8k`DmqOu2TDc2uIM} z^;;sd`*$9WW{U@TZB@oR{ndM`?k^~1)JigRo)Ky2=Va2TsRQQHZ=&Bz6yB}SNcl$% zDrinpJ)IDnWtTaUnKM=-YYhAJV61FO5<gkg0W2l8#o<_;WBEo9qzPZmY?22V({4n+ z@n4DkQWSFOa3H!r?USs{xxREPptx{?jS=_yjFZjtn4Lze<@%cP|F)^x<GV1et}oIs z^AX0!(HkK83_2}{Xq*}(kh1O%ea)WgEB3FZe4<iSv!z-8d|+~?xUU|l0$JLrBH>8L zb@yM8GX0DO19<@luvIw2`HTWTEOfxwV>T$ig+MFIh;GHp^3F6n_Xv=jj2i)_?$G25 z3dM;c@j|q2i&~YAI&U(1)N^poV3u~Ne>?SQv6)Jf?%S~Ak*CESS7fMxPoj#S6QsL) z9b+W`N%}dDp1*Ia0uKtoc|j-K@GAB`TRCz0Jwyvk<oE<p(S0^{sC?@5C*pp{ZFeer zVX$7J<RxO+2Nn6fdXG1Xqwglo4eqm6A<GRt4GW9=rTf@adwmJB++W=zx8G=y0n=eq zsNw{vstO`LR`}g?`g*qeFMm!pfxp9?J`+^criTT04tI+(93!aY7N#AcB6|Q#Cq6yz zlK<3kb@4tRt^BdoY`<pYV`7VqlfEU}JHeaxZ@axV|7^5E`@rHQ-`CQHji-igrpbdk z<;h}!{#~!d(Bhiz3Z=_?0}Nlj=RI4(2;>cISmvI#2YmLW+7h0f|L_>R<zjiNu|evT zYQZKb*#hscz$dn9RJwn)yUkpdDqC0oQQgjJa;db*NOrzTWk9E*-0CePK_VSdbh?}O zYP@D>vl7f6wEJA(%a>NqI7;a$FVauK(~!n<nhqu6Q^mas_p>-XiC^^?Q>Fm>vKU)$ z|COU*qL1XK+if`hZ*-OwzqS<&kD`S1SRhQMWH&_39D<OksHCy*o@c!g>_7L0xA~Va z@u{1Xi?mn<+ya|iF3u_caOx8Kn2pcf$?cid*rEkP#??b8U+n|EK7<tWy5*h<6D!## zyE~oJLh()vLT@gxyzQy(ZYZHG5YRFxBOvMk=bSGBkJ2&*Ulnt1_kv5`w)aRFNX5zb zlCX3Gq0-x0vHE5k?3l-`Dm@LlcM9kJrW7|+jO@F8hdZX`p4G=+VPu;v?-?044U{Kr zqGQ-bND~_(!<-5evV1u$pU|i0r+wyHnsfTmbpBFG)DwF5#O`;#pgfA<_MN9!YfVwl zh)87$$`Gdg^<&rqI=%fM+ChEvb^d&Psb~{AL<#jh^HfVGkT;%mIUEs*BNuz(1S_83 z?VJFGj+T;g93%LE(6^I*?wi@OYaroq$>vQ2IFb#y7ES0?U^v~E4T&&Z@VcPyov6=P zUd~Gk%^b(REzcZED4bU`)6ecDc{ytZYb%LGax-J#7VSE+Bq;KyA-*OvL15Lud#{W^ z1TEA<bH<Kda(0LV{BcbTGrk~IP8DgagB&v&Z=0Y#a(Y3Ms>j{Plc`2=iY@~=exqKl zr<~kPm-$|KA&k%ApVbKCoWaVF;9l~{Z^qr3uFxCJu4tLK&V3t$75`y|nuvAraQ%vH zT6}@nHJbIBMYl<(>5Jz&Izv<6-7xiSGA^5l%rq?;BZ|@v3{}Nd>hd`n+Q;ZDw|j-Q zxQwarDc&yEcv{Uc6V90HWukAT0W%IbbTx0`$xrU*+z!^(vy2xMO<;r@1-R&2yCNwZ zw-Y_hmRWF7Ep#3NuHMX|HvBpB>bgQrwU#tmj`E$qG+PDkwz_Io_#xj>ZznjH=xRwp zLs=wW6_Y*(0olgZztO{@PTd8Hc<)z3g+F_uJNc;{PkKe4aA$A*#TKTZqokBycg<%% zo(HYce{~$G9O2$IesvRfX8()-j{2@ov-QXL0NHkYnw}y!#gKb~Ktvx-ev2zKXVkk% z4X8AOf9-DGW4t{GHr}kz%CjdkBC&^C_VSvWprg7E(yVkDr|60YIVj}D`wXN-yAqza z@;%q+_kD7*yS=|02Qe2~OK~!5K)s9)Z$%&Ve9x|z=Flrt=U{Vsde;{SWe1Z0Iu?4e zeXOLr4>83%gOKFncCqUU6iW1NU9^<+-E7pTXLbvf@pJ5Ox!Bx{YHWpeBwRNxjtOvH z6ONTqxEF8W0Mp70L+18=Qh0AA{8879`M)R?w*G8>S!Nv?ALYoziuR9pV)`h1T@P06 zn!9-!ztMwj1bIjay#||9xa0llL}iPhBlsty*=H^V1APKJM7YUo1zV)LNlVe4Wb7;R z+DA6;gM?i7AF1NEs7IdD)waBB({}bkq6)}h#+iM+FYOOX1%u+c-DT~XSwGMOU7$^x z{hu9YE^ClT2wx<$Tz-Xm<Wonk30t43q4r(k6P}}rjXLgR0}ElKYEVED|IWoDdH;-u zE2TL9XG8h7Y<0~KhR*ojXqA`qj=VigEbfeLy{qY+bn9{dB=4|aq;{N;twv{`rQKxP zPYk&FjB3+?N)$Phc}7k%BG0r;q`i11t{}HEf|5Ed9#AfjzV|7Qr39wG#q(mIq}n8L zZweegf>1rzI0h|kk(F9dX4^=P5I}j==i<P-&G=lJsMq}oeVCNwn&;`%{yY%BrRU3o zn{X}UgSsX#ccUwYVrW;o4p`0!kar78-PIA|l5ve(J8OTnoC*%vwh0>wCnPZA6aQaT z7bo=}%5WsOshJe{c>y`Owvr^;7>Sq7Dr23GcBH?rsm)UjKI~5!f0rs1A1Kr?9FzS( zHG-YYfkF+y=0y{ab6!8?R251+_4uu0kFv7o@c@9#Z{&|qP}8r_Y}BPP=ygr(K<W|N zMnZGySV*@1AXKjdPop#>A*>-;6c=CL2{+D%u1g!Y<f41{y-<$SKng%)H3o;OEoN?U zU4E-|GJFf5IC}fuLA*BBV2s!Tv;{yROf1@9MhyO|r4R#M0w{tV4ZJ~ZWTEb|frba6 z9rnZ()%op@EDc`^<(;okK6#NJfc@Xpgf7KNAsZS#1F?My{JJm*nnZvE_ktf0$bnE| zFk+#q*jq<9!suY(*AdqgH$$BenOQHI8A0x3PYmq^hog>Vi=g>x6efl>^!3%<2vUh~ zYluO;S=k@uA}XR*l?FomN+Z3OhH;phCx!B172nJ~Zz00%Bj+t@7c?Xk1@R}48~1*r zD1t)0C(B5I8NJ&1Fw+4%WVt5y(<awYArk;FQBDIUC^BOLsa@zdfN*|x`}Y?0iG5v< zSxs>XK>yG)rJxdR^J>|Y=t<c*&hyT#d4asa8GnW=8udc9`zMo9y`&Zc{pmLTHy_V` zM)@JY5S)Yr>;Q_fWR{#67O*3y-8kooL#}I**w7~9S{R2HhC<bzL<k_avS)c_Oacad zP%b)AHi3DVa{kwN>5S);!%_x(XS_%*m#t@fr7joOR5fzUXo8+8aHmY5)P#xs5e~1e z8-=^ziz^y>oTt%S)F1o_6uw8~Lq6mHKw^pF@tiQFzy|Iea@K)MU8zN<3X$__RIG(e zSO-#ZfPKaXmGYg!X967K{VTGLzgU8q>Gn4~)pqLX>93hYEB=*)8sn75VSystx<@Hv zht$o|lg?Wkfy4qZ1)jp0KyC$)Q%*~e5a?&6--jZGoG6F3>v%@@x&9UMyzYYt0@u}h z5>hD?zV<Q?XBW?&P`K37xzXkb<LBEO=xwKkvS<IuqPHi!6bw9t&ZYX^eHChxh{KDV zqG-fVr-d%5C@cyjZ13>Mod$jqox+}exg_BtYz8(&b5J{w0tKRA5Rcy^g^wCPi9G~| zg2K*7I!@8bPgDFU`DUTL75L3H9g`75IoU*^clD^(pg1G(&D<n7XUpaEKDr%2SW6cA zX9(8&fzFm>mmrXes;k_8D)uaDL9L1P%aa6(aM2-W?e#)%^(K0nR({eOe1(8Ssr}~k zqPRmepl}J-c+)IIsTrnWARpQ!$9^Nco$pkft`{)av6~jEoBk+^mj~m)J}CYOUvdjI zzL%kFThdzVaLBNr=rIZV>}Fu7)_H)0V&ECqQX%5>&aEK2>o*mJbLe%GFxa<O2kc1a zW~@untMTBKkPf}DG4;y3uK_jl*8a(Ns0=3#kVm1EBX!>{#i9Gk=*yLOWpZEUr!`>z z-dhpA#&QJG8hdtM-`k(*OO`+o1)masYVkiGL@!A=J?2=4szfb&`5yLK{`D}4Zk9K} zPV)bpPk1mv$+xmFc!%yN_U+wMS#<Yw(sa{^8C!j|GFm_cZw1~Wd1cQ}0vNg!iOLb} zsjk^^rePdq-?g6K%?b7s^BjmjJ`VJKbUx*%n*0;`#E*Poo=+~E2)Xkc<)^!P7o%w+ zPzg$u{Ar!-Q$N%&mv5+U=q(HuJ4!Wzzr|fP2#GMvqY<ezN1|xCEoJkksO!0-r9xyK zfnCeh{O`}=X+AMgyw*Fx1j=-a84xGI0VN%#$+qyw1Z^jRHXUv$rr6?Fxj`S#!_72! zM`G(Mgp#M_Oc+-?--LkEHlwr8zR7w^lGw|er}7WDa87NqPaixE^G^-D?fir+NUuuu zg~zc!uOcrAg={Y{PD>((_K?Hsj?U4!6mh>Pa>G;!zrhx7NeOtG_N?6ez)4Ko5Z+RT z`k{ocJ&g+RkCvgc^qO-<o|UJNc!V=~n-Htq@z~jo>NIyTN1xWX5u<dUM^O(Bk@MJi zp&?f{B+bXB^r!1H>+Q6@Kfj?RXGKLENqJ{@PE-BN;gI_8o^;6(Z<%;F7tsD*JV^zv zmD6ZyPuogR-dL*-&0wA|zE1D0m}&Z@j?DK@-}wvG6ozF?y`Mc2L$hcvO5ANi<IRIN z4$VdI@kLVFk273U(5@1Wh>UQGYKB&ubm6*F>CfhxYD;aMXXNkC0+#Cr#L<M*W~lQC z$)@-RVe|#QX(PoO3f>~k?qyy|Vg2J57Ubt_0%ChOq4giLFufnDgy{8a_XBLuS6Fg1 zqAPXZRjb=*A#wwM!_9QhiWvjOFNWJgN}kEMsFA?0V*_Dg3WDK@nXR(4Jc|1q$0Qth z5>fih#6oN=SjO~5rfoIo*R-EmScaxfz%>1=ZmrORS}c^&5(=X?O}2-G_tH$J%KR~6 zfq%TF28VwO7+eeBIo6jAN_rjZ$wJZ_EMy6L6{`056@|*8kZ?oyy<gTf(mNVvxH$&f zAUR>>Hnn7X8Xgup;t|E{{5N}ovbnvt*fzUX)}-=<-wVbmqqr>3a{#)8K9?94cC;!- zh|J5vr9imnk?DE9JWg2(AAbq^NTl3v1s^;CyMzXUThUg;0>sd!?B=FTnWfgVNU)oX zr}lHh3&TYU6G!5)81DDaC30JpYd{{Og6z!V)iij;QuB54H^w#xIn*udt^6OBZ!8nu zxD<Ulrcy1pH2(6O=gLEdm?*jaQ+~Qb+o&}+%p{{6{UY(Ht4PN;!m?%Jvglva;!*<B zk^}0*(pJ^V=v5#O9{Z)LJon%8AeT0|jK);3qlpA_0*O7{T!xTM$D`?cwntt(^3Ps8 z`_27#a%$G9{Es0;LI=53uN(=AOx&LQts1k(53YpH9Gqfh-UV88?^qU6rL91wgL182 zN%c!ylyr3L3Jj9;{}4VC`-fRLsuA6^3^kvZv$QAIAreUUSP@g3vR`h9re@c>iIimE zoktz~ZU+gcB%8dJ7ng5$wqN1y=@bg>K(js*vIr%US%IQ3Ek9T}!<SlFEW}DK{YY`_ zQzX1c=j~b8#ml4cw17eWKNoda*x}c3%VVZM$@&j`t;KAu!%9Jo0{+oyJTK0R<ye5Y z4^fu!HH}>-b_>E9bE#q%Lic*r^V#fwXLpZVYfo#o4sLPi>19_+^@8yduUQ&@uq{}9 z6gJAb1&t49WH0%WD8w018|c*|6^uH)1N|@1`}6ZbUUqTG(>{!{OFY9D2s_{2JWqT8 za#U%b)&G_V`y!gbx3P$vHGR-_uEhkDw3C_SLaZ5z2p+H;PtE{6+W-|u*r-G^4#|ZZ z2?(SvTaSU!!yEB5LF~Xk_msA)mdT=)ABC@5*n#hbTt&|lQgSEmj%A2!nXs{aIP;V& zMKpiDYH=U<@b^k+@91}k*5pNS{H~3f2pYopcS_3p!!t3DyYtgOEf*q(cxJCSN4PmC zyk<+cYFo8o<-cagrF@nC7TdN79qU_YF3;x_IlQ(E|FuSe%RIOGJ3qcPacET1teq;& z@$J$0LY5=B8Ex1)n@vEM&{obPUAd(}rjL1!t&8o;m@0O|-0+~eB@suKGTV`$4?>jP zk8`b43Aw9aM}}<eWs@T4=j`P-;cMeBHdu*ELex_J`mCQ?UA!Ig_|MkS{O6ybNPBSZ zr@%}h4QQW$b_daRlZn&hU(m=KQ20jPra=CdHQYf(Q8<eEZ5a~aeYbUsb9)0M7BD}1 z_fN;s(a6l$XZ8FYYgJ(_&d-HCsx<6xHH0>8IlnyR<Qu>$cI$M{@qJO`1d2Lt>)U;K z#kub{zgq6t`fXDzOl7~=?tnbsxdc6VBzEmCd@9dBRR6cU{<mYp;iGle;rOS+#2{h9 z?Bd7OudDC2{#ps&`@==HaCDfz`8ZWrxw7NU>hYg{pEmyqQQAOaaYL~6Z!~WPNr<aI z=#hqTACX+ARDVAZ*+oM6w-QxPuOq(<#9P9Orb8{CPHx^mOJ3>TINyCZKJri`NbAi{ z((W@ijjEoEj>n=KRvW)w{rOpn7ClkO_T2bwtMof7WZL}S?|3d}g$<!PyE%pR^PK;} zlDWP*Jo%XS<}&Z^W;HgIK*Dj*mt*w)^8Nj9?3}&z_;>)70QB0djs59+^Y^~{{wk<e zl_<OO!*_M#pXTY`T2Rs-ZjJ&H)Ip-sZx7DU2ne09%}7IGe>8$eFIT6rXfU4nhU?l$ zWAX4SlzJSyZd1u<;t$g*o6*?<Oyc=T4=L_=r7dTpuJBNfZe#R~S_F(kuccz9Sm(8{ zEvwX<xpL!T)g6mzJLS9b?<=j$Y1A-8Ks76lL;r2fa<lVX6`x3}`+UOR07ipnH|&%{ zt`;h>0?qdCTSH0VoCfU;oBhn|!c!SiyItXX9%DD6lRkBNp8ZoXifwQH@}WRIo>R=b z(J|qC*F7m=*`_BbaArMd_?T~hwf*Vgr^%p_{W-=vw?c-q^Siz4(676O>-@icnJ(6U z!>L&J^Khw|_*co~=jTAVMOzW3a1#~3X820k)VrQPzfW}k+1W_7x(5F~claA+Gz5qd z8-CmkCS!Cagh8gX?`!%jt5e@PT584vB=*Pxr8Vw~%_w&N7`6v6ML!dR^Q)&05E5f& zZYAcxy{&l3A?JHB#t(gIl)n(vu|z<b0;d^z;&csO)L?We@%&+%N~`+is`<ey5}g?u zr4x3SoivL_%ZNlC*$XECX6yxUsJXiAW;u6`@I_qP86T2F$x!N{U)uW}vjcW31%kMX z7PcuE?GU}P>&&kw6~0Ecekn?jy|jE|+oTRJ@+E5^S0%kEP*R-hf8b&Xla1QD)n{;n znuHp4K&>1Xa&S=H0Ar|n^YzIMBe@e9WG@#9sKKSCmqNcJ#*vR@4f8cOqM~U?O)4qx zE==U8MZAoD(PG7+4XIka`*}+K>(x{0_W5+T;||DVNuBv|_uO$8b*)If`PZrWUHM`A z2*J*)U+_bgYd+5j%M*lwBr`zX9Cm_--6@e|u?gm;V4?iu_I<E}oDAT;AS0Ist}i49 zz(5d48U#Ry011R$r=g%P0zx&b`~NFUr_o#dcdmumR63p^`Cu$pw|Q63RQBn?+Gun6 zhySlI$5J=zaNumcJiXSckJT2<uIpp1)r<A^{r|5nZO5<Cxouvb$MW>s>ejmgejKci zx7BaF|9^BDLnmT4(cbuZ7{{ZZZ_v@SGoE?F?bAfZ|E){I&X)bT3NBfl$<Efp#fAst z`G#F@kNz)RcC~$bPi96zH0%yANF}|_+Q!@=WX6w>yGj}LD1I<lXm;C}>gjTqbOgMJ z4kM4ke*f4bFVg$)?(bT~aqOGS+wb4KxCFFvnVGrY5s8R2fDlUNLyw^#_x7?62g}CT zhat2CHzVm?oj6Gu9{o?4kIF+qpcjH$F}&&L4$*>T6<cwlZ}*DKpa9}?yv#kh2Z{2# z6`zxof9-vKrA8sN{XbpuI#*k?0({!C``fRLwS;z3&F;CB8i?6cmOilb*x$*pj}qF= zbV~o9F3T!+v!57IIOcfh;!RQ*Il_=P#YQcsg{Y`f<^?%=@H2u;l!RU%j00FeKNw^@ zsn+f_2n36aHi2)a8f}-WmB<t##hyWU^)+_Isu)R`70-4x$Wmb@Kpmb)1_h*bBFQkj z+@13^ROHWufcGJ(LfA&?ow!QTWy$FZrk}=01js?1o*n!m43VdP6P8@g>QF7Ju>y({ zwS0o0&r{<*X`<zL7*n27mkcY}!!oprAfXeie$hRodGRI{fD<M;mo(TOZmnxDyi3ke zdoYdsj2uwwlT?<eQD5McvC&+OWT;V-c`^XBeWvyI))&Z-3GJtC?Jc=0M?K&(+Bs>! zNIE$CwRBQ>=j#ke^-%O|T7${`Y(__*_H5Qb?&xgpks=B=Pid@TTm^QRG_JA{DDlHk zJB$6Cr+RVp^ZvQoi%b|0sRmjV#!2GVKs|=f*1d<R)IL3<BRV}(_c@&OUlran#KU~v zzrd{rAG#wx<K#Fmwu8Ubo_}(Uj!L9eFbsRCW{K(>p|?z>?!?19NqQM!@RCcl&)&$! zL#h`J?##eiz7p_25=6%Im>`ZjVMe||9FP1LrVKcEH7frgHNhZQEME{jb`2WUaFnu< z6SD#LLknZ_rXr9OEc0}}LzkdDDcqkO(`u1cuL169?AZ|J+uvVw8p9mU*HwkgeGuRZ zL+yLM!SSoNmqPI*jH<gI#3k4V)0_SeXt+;g4UeJ(g<1iEi+5Y1d&+P)lp+vH10W*P zDyS(f1H!NWsZ~!-JScw&M^G>SRy|LPr|JwJp&){rZiN+)(Db4TxVH=5qr-Wr)gwtE z7-xhKTF)HK?f@nKLB5=~2~7ahsfHyfIMe%H9EmVpt$As>{-lXB79GK!Wgy_6NN9k9 z2=0?!2+O}P>VS58P6lTLX5~9IG!?=TWr5HNF&1GsoMrqwt0^vsg(VnkFb}9j-8hLy zSvq|Nm+t9=ozeVPrmRCA_EYWNED2RViokz9-ACRu%N=A<z=2HBQJ^hJWhvR>{rf;^ zM`#Or4P_8eS+4W{D;dd6wuLEK8VLh_gq+bjVNOD$Rj0#fa_lu2^+<G-gDJTwQz5++ zO=A(gjoJN9w}+wxC^S(R<lci_7H|_W_rh=v&B(5!$lVV1*b1ZDbc*C`Uj_rdcTg{4 zDm3`U#wbj;bD<rN?%8|c1BS>cLCF561E?r3ki?58YCJ$XkER1GGOl!B<KM5}A_>$b zh2XvjPQ5~ME#`0<npy~E1`33}JTPB5+k1{qmy!yle{qD4K&LjSA}^n!@GTqY_>oC> zR<c*r<Z9|dD~Ri}!y15@jARoP69vNGhf0ZH|9RC#{Ua&Y%bR{0Ab>ddIfHm?uig<J zbJw-Zl$+MKKn)pg-p;5|_n*9ou_1EG5EV}ISmhA27bxDD4X?|6S%G<yZGIdopses! zgcTyV6w>Js7j?6g?#GCcJrSDPLLoC^t-`k0Obu!#^^Fje{9_S5(u(T7d2CZ0u{hgV zZY!L~#mI~VU#gsTc8kWCFvVLZQsQs_CrB=k4<sm_6e5tx)sM)V?10Rl?NFDxr)@uU zBL>2d){+BmG~*jH6ldwwg(AVorcd9{+ilS?JIopmgy<(#?NIL;iyftngZYd%9`^mN zm29haRnlgt`~qjbT$|t2PQ5vob#dlT2v~M}Xeo06n$ZLd&=>WAo;QSTSR**t$P{Sn zB)#!GI5?d~h%c&uZEIwl2pcGpPxFjT9RJL~v^BQT)0Ey8yc0$bLOx0?Wn>PHQEzXb zaDL~V0iJnC=XOEl#!)rl{C=>fNe@u@8k6xH$Y~&6{TdxNtb4y*<v8h)g|gMEPh@aM zXv|;Jq(@44C`=v!-I?5;Z(B0xP6=GaWPC4hKXPp!d=WLGquSI^N5^N5$0<tA|J|yo zm~%yFns=fyI3Z~2rbFq&Fy@45thj$3LIbhdrx5Zah<gopoV0SonUYWa?3_$}TB?yt zU*M&>KF+ATbugY0l6@m3#)pj!StO}RBIF&T0U220a`0`+`1|!!drR`BZ$D?B9!_7A zzT-}rUlNz7XL#zx5=5x2gJsL(ddo}K)DJWxb*OE>^&)l0PfWMrH?Bpcn=|4gJu1vo z@@vSNI3mMg4cy21Y$b3l@!h!^Bjza})6Ffzq$$qa7^^eyfF!R}m<%(*J$>Ib6C)eb zcI%jxM>~@G^SWFp`If}?$<h$%_qo!WQ-|@3!6>=t7#?;LoZ`SKW%~8w=iL;pP@i{E z_nZ9O?bi+_s!gc^8R|mJ-(TJv3EMC&^O<c_MYJ=OY{mket4dpt>@VST3C@GOA@BTK z&EFk4v_0Q7Jgr`y;*h$>@tpfxG=<4EbfR=m*e6Ztq=d~5wafo@=O*^o7+udVP^E?_ zRbi~AOvo>KhagSZUtH9#bmg1Jlz(-ezmKqiy;9ax;XEhUdAwN~&k6i~==b95<SQ~- zLiux|)GzT1%?aTvR{_Nnq_lUAoYP{$u6(nn9?p-SC|NdC$D@(}?orRDQzO5xwCfeO z@DKtHivIF~Dl7=xCqjjUBAB7^l2FoANIDQg4FQ-dkUQy!jD<&E`Meta|4S(pVcUK_ zEPx1@2VbANnA*cYvXJanU(IN5S%F~cuplQelu{m<auV?x5s7X0A1r{x8B@k1ps%mz zuALEIv=Q<UWRAHPKZO@BGs}cr;GObtz#bCx#V!;T5i;uycJ`$Si+HdYYPf_*osKe? zjRFW!-ty4Y0x0=BG+7OLt3rVJJd(;8p%Q?IEq{Jz$sNr7%$%8-zXI`hA;ygO#V)${ zsXc$xMwA~o;OXHo!o>n{D-+>y9xD-nNDD=z0#sS_a5^1C&{8aGg#ej%2unbeJ(Iu0 zJum5)m{=Wp4hH&Vv;P1(lRHD;nBJ$cUJsr;dL&Na&s-kxwcI~vB(@d;)IpGG#))*v z(8k`U1=j>g9CU#>TH;590SM~T6vZltpoaJ=IwNEj!&<c-%4EjBoOuj#_^-q7MT<Wq zsuvRD_2@puGr6|s9&NE<6#{{$(uJ8p1i@%lsW^}cWr7#D7zIsJgMJK1W{gFoOh<Rq z#*<6=H<yRnMcF;^cWf7Y6)I)@pw)YC5F9P3=I8Y&sx2Vnagdt;B8(`QxFd-0K?@XT z;vj{BEK+fe4bS?$ps6_MQlTKVF2YbKk#r_H^gP)((~A+~AgIfv*@EEWxqry#8PV|U zKNM`>o=4oXboGq%2hl;)I!V>caV(>>OHy&kUQp5!DAPrv(M2jnV_Z-`k_i-O&3Fyj zOOnm>OUq0P4+};}K>|@Q>jr2?feT0|^L<;oihSZV)>f?}D>w`B1`6m2Wn+aTKIuRk z?IRl-BG=`SUL&s+E2GRV{81H|;bGPSmJd4YBRh=2$5H9`zXXMjMpli)k$z7t?8t(e zWJ3#~*<OexZ)jElbh#Z`F`cM4ni{AZ2O^2{9*Krt2mgp|&snuog#BN=wPZR>H9~~h zJ-i1l>xEhwQzlWQB+5ONmlw%vj{}U8JHFtacVtlS=YDXZ%>bz4P>@E+xG5I|6Er&z znz54^#_5tqQSP$8%=GJv1u1{b{t%=Lmu}1)LwJTG>%*;9<}S$RQMndee=Vf<LI%8` z82~^gjL7cIrSIcaVnM12q=?_kVF_fifFh49pveMZH+B7UAR*MONNiRfVg{Ngi7*R9 znqB7Rg~A#&U{qEG<iZlvmsz<N+4b@{RGS_H_gp&sQ`Ci-@e0tm255@f(_~412G;1s zief60QtI!}P*}x_K*UWLRZan9+6x-OS|&ymE*pj-H!~x?MZ0-gF-_fj!X*T4G=oMg zm2e0N<Xx1I&QyRgRg~YMR8p|(h(kp-A~d|J(h^qT1+5iEgs>t<T@asja?|$_v7ufu zy?$xg%t^zLSQHEqlSJxJMsAWF$Wm4ctIZ3oY70bE$04c|5hV?^tFE=7AQ-~s+CPPb z30KHhl};;U&sW6KnYftA*SI$N(3pT58_07J@EEW1<mtS>S-E=4snb@7w!l)d!m8~R z#AG9K{Sw-UaG5@V78qBP&s62vS252Nhi5e^#0H?D^)3#6EZkw50g-+U^_ZnMftQH} z3RPfC>Bq6E+PJE<F(Fd#T5ck;u|N%0-T=!5fcj}Da<!HW(?H!<UNRDwomEcm9m*Nc zIC?jwPXM86o{HCkK5vhN#Wqo53igB>XyL$mb_2+vLF79$LybD20o;gad7y;2Z+%^Z zi6CFe2G3;at+x1wJwPI3(g~0}pol>M+7Va$))hhfr;4JlwxpqIlKZXj_o8JB$`Sx( zZ;e=FZT57lD&9{d@8dOGe$AzunHAIaoW$3?G7>ipeHs`2@w}eeq_o1d&V5{Hc}yrV z2)TkrbijeGAVhFDT}cB>X&C0IRM)E1<ss4~tJe}&RF_{-Q_{s8b}pTb(0?=CSqy2I zKFDqO1C>yE8%k`dauPw78^7!668I92Ncsbv?uACFA>O-nw~Dk_yCE2>k;QC14vjAm zeIhI_t(t<cM&pbk-F8av?xCD^X!1KTOh==ATt_cVAqaNEtwVOa3elLV^`~NUG}Lvh z<x-z1FcVi%35jaRP716G5w4&RdH0zOS<%4B*vKhWgRE)DX+*%~ujBLv%_B-(RaV^} z1K-mjQ&8-9&*X9)mTO!qq)`oev#NB~3Xx>pY-aHO26sON39JC1Dz%49t95k8!*<|r z84Ly~!rB3^(v9j?>hBRoFlgU?h>j@JWo0=jGA|7%PB5mFse&@-BX(SeEOHSqpCFce zkaa}d2wfP=cMH~10O<hW6#&f2VB}%K5F`7*;CPeJT1G=<&4u-_$4pkB0kpgTQmY2b zn68+Ms|p2mr^WZK=pm#gdXe6uKm#mc0$I@uLuB<=qx!9KyP!dRZ{z!3S|b@Qq&Y^t zN`e^!PYWi6+sdb5Icl(w%dsuAcs$$N$2DRPgGcEK$5ETGcu_<wC5$jVK<FLpQl0=1 z{WlXDCcoq7$0pve`5HTC&agA`k7WqCR%<##8zpNu^xtm=!<>Q<-3f?214QiFI5%?U zJ3D+9C~B5O_=byZ+YCZyM%xt;LqfyE1jg)(&byaI6-@Akgo#WW#Lw<=8R8_O`)c}z z_gs88Y#IO>QE>Y8nS<|LC=OcB_T<OHF#=SK5pD>XgF&N-!I9vh?yfEwgDH%|j4p`! zJ|$4&HAhXg@I!eD!97d!{k1W)N8gaq(7jZ0yrI&P(p2ni@2cRgHG-ZBS&tIzs2LBM zTx9Em)c~U@-7_5P;}$)%#ez`x%-OAu1=G#Y;QekerZ!I!Ru>vreFBBDy?wSWs9Q8x z6S}x-fcWplN^s9&8HZqK9-<C_SEJw%VK_2zN*6!U)+0b^GEXPf-h8@*>!F{snS_vx zhw8y9;$Q;>kU9i>+iJ0086h1!7jC=0FbQkGtv3)p${fLJiMF)Cwkw_8FaqMuYy;=U z3(=n3MUKK^QjRq@WEq&PD>c4=!my7rud7hy!=cG~9SYuL4{uU~Bmcray&zC{5SmV4 zEh>b!p>R<CdW#rhH4n+ai7Xa_YYQ%QCQOx50bCxm5jnFbwhV<<y>vkcg+KGhY(qbk z5j$P5n*X7q2@_46#RN#q2{^`!{2l?M#<`7E-4^#EH}`sw6uL~Tg@fJ^ihVYjk`OC~ zh>I;myeNDS09sy%?mn48CC#DUtxk|2HG;SJ>KH_XQ@!KqmK8gG<U(UyN4v+z>;J;y zyCC5J#ATXXZHi3%nwCI-q@F;one2&PdojfPy;x3IO(--42i2n9cEM3(qXZ3%u95x- z6T2NS384tTPujOw15oEoH-q|iI5@Ws)(}}&{mp-RQr9~kUoY9!<Lx#?)>y01y;-BS znl=qhM?nm{$ThvlYlEQ$I9MS9RvEh90ucUl{|u<Yn<U|Hy^at@@Rrb{c1d`p7re#` zI`E0y9|5l~fVX&U7CU|hegA58ypQY?T|WBQVjnjRz$0uCoOK7Nf18KM^)#hJx5kdr z(IGcc#2ZQ2?}>KbI=CSvEVO~b4cK<I2bZAWlmEU>=Mz5lEUu{RjGJzPNr8P;!YuXm zqVUd8cq9VS?*Xpq-Tq3X{+4HiXpuy$d_n+raKrBL)x7mTpAhzTbCRFB^28e4MNjPe zDsHY;t=CjlG>jDBBBK%Ddy=I6{~!fk*L4KzzT%%hQNim^K5~6)b|fNJ@_)G8KmAa5 zN(do0C;%7q!aI$RNT_M$ZXt3|uvr}MkB|eJzHe8xT}baky$#xi1=^3S?{cX=D@}TM z63E4S$y@<oy8u##qAED~=*xMwclD#<==&|M9Z2J^=eJLJJx`lL;oYHdt*Pq`z?;1; zkCHA~rQkIvs!Awz*1zp)TO={*u(kW$qdeM-z}aLzx<<HQdBeyn1jMI-!l0KdG8Ebd z%olsW;tDQQiCnv!;=i(vn`Qoe|L;D+<^HA1f0C~M9r1d?{b+u_YMA-%_~%IVl%Y?w z2}M=gAbM(t0KOkEgoXi>od1WRGmnPy`{Vdy%#5)%_FZFU$TIeAY&9Fk+Sqr-*w+x! z`Wv%otRZ_8l8~JWshE&#*^;8NRcMpcSF4|Mp1<!o&$*v_@45H=dB5I<8v@F7_nS_# z=;ZAc0`oeMv_*1Wv(8nN{`XbJWu080;&_!*=JM9ASj+zbOV+jSi36X3+{fL98cokC zkg(6AbvtRJuB0A9vcR*(^fn2};Grl<%vE=PesI44(9{eKI&VZ4q%Y*$kt&DKjhnR( z1f9)ZHh;flSno`oQMCOR@B6Wj;v_T$f$Lu0!U9KOQbG8fTkskJq`!KQEqZ9HqRjhS z*kq;U|DcLKyAhX);PZq0%QH8esyyx^pV>Y=ASCR!_?@;IbH}*VBIJ`4?4Q?pbQV8o z)YvY<cxUn;tkpcshVI;n_kSD*m)3NMNZ{!Ym6C3yoOs>#5^{Cz^%uqekQGDj5<p~I zNdDWG`Ckc-VZY^B<JB1=9odGwhe*13h;&HXz_{5oNgN;t2}qj1_Ii}Hh%;qNd6U0> zGO6owiO`IY$XAhSkr>s{dv9?@N2j0(wl38nG&A<dKjycUw9f^@F>PkjG+UY#qkOA* zyGA~%IM7(xx<pERt$r}42|QKxL^Y|+Ugsg$z(Mb^LZp%7QEx~QZfAs|Mt}uPD!UZY z8YkIM5JbU>l&`Aabf;XuR{pryjwnFT+uCnoyLew8_Ad>xmOFff$(C{eW!M!XPi@+x zed5#7^LKk0+A3_175?sj7iJ?QvPM`&9^T<MjOHEUtUguQ`&p@o8%NtS;lB~`L&_eX znnn>#UTI-R<0<Vr$6BC}Y}>BaOuate#?k|3--8d)eSsH(hO<oGv^nNlh-|Lq5?+&; zhfLqyUd#7qt#6nyz3>;sUHj8=O<8b3!&+CKYzO^J%*opx7Z0anX&IrtwFUO6w@8OH zn^Kv1jg+4u5^x@Js`@fOma4A5;D(m+_6lmTic0wNVI<o8dlvHE@RjSZfG{4qH2HM9 zVcuddd^OW_t{YiMVf-jA2~1s4*_U*9*G<TEJI6{G5$6HUV0^27CtxxK;xNxH9|^k` zd-u(S-yTd4d)G@wQCFCGo*oI`#YJq>$DNk#9DYi+1x&LqdnBd(e4rX#SN1O68JS21 z<kV}dJw19R`b<7jh&hy()S(jP7hG+N`<Z{NN=<tgZdl61@<Zv4QIGY)I~_yS>_?ZO zM^jfW9u~fBr?E*|cWA2TW*X}z<ec!tca3|c|LPQ|UWc1~ef*YOP^sdp6bhxA_)!Um zEN3Wd2e&e1lN68F<RP^WoWaBU+Z=}>5s#R5`?tmn9qT_<r}zer+bVoJTo;jnY()lu zRj_ygr4TW}o@F(PDF4xzrhUPa%ak4KY5uJohoESCawDt+j<ba*Tv@(+{_05-S`mFt zX`tkc2v-WwCCc2xS;@6*n@anwNIj4#zx3JU0nUOU{pO7QKTcAs|B|NU`!Y6gf-D*- z@dy#*>rwz6F8GI44U!}U%RL)0Ci}ICl~sWO)dYUGK@d@1koDN(EB{djjUcMGLUgzT zm(=*6F&dR`m>2|$Z=*>uoU^=|h@vlIzb0*!S!prw+TMLFf{`P>8gY7js&h0c=Q%6M z2AOOe7%9`)U2?aNeGI5CkY=Sm!T{X{=bgnY!kkIB35+}W745iaQkZ_x3j`UriYTK_ zs9}O2s^@k@OZRa@Fru|344HjQZ5HP758Y;Gd*G@rWqZKu>ur@nbQTEYEkM^OYzhgF zY~xCT(lRKupbIk#Rw$P4MK_98QG?rC9i@C|z%tVE(2%Fb>}r<w!dP|RoO0?*X0cBm zQ`DMv(|gofbc1Z~Jw}SOa~Du0lR-d!)gVl{{bCLe0)Eax$@(7|0V?~L9d(_9HQCAZ z@8U|3t`C{VMil&jP1L2pM-`U-I~uSwhVh6YipsTTH6jg**V7aq&?4dPAcW-Usz7gp z-n;;Yu!1#&Z>kZ6iYjW<JmMc2@V)o>B$*(lYiV`l^)ef&Tb+TL16wDqnox9qi1W_C z_9+8T@}>9>`b!sBVu!H(z~`8&4}qH4@(sf<nazN`d!Fvi!z@#WoTkkNHh$Fgna}*4 zJEQ_R<x*-^^UzL}*{qZArFDDTI1lga0kOcMdw%bt21Rx5F9!xUW@sDg2wz%|WJ!(L z0DE5%ufJE41wh5EZXUYFKo=h(pNsN%d^RVn4WV}9<(v0vq}(fNG<tl7TK<8qwHa>I zXD3-vmTJg|w^36mUk@^Slp_cQ8}-=L7u3QUNiL;OSDGO+rV(~*0+PV_@1;Yj-7NED zKba<euPu*yDKFKEL&N+Y@+PCCu5fN?8#Eax-~Ue<;0(p?3}-p6dOma`>U-n&qu{Ef zRVk=#qSmRe9Gk)UF4ziNS9coXuta-!-6fhF#v@`q!f;h=N81P#_=(<qF>ykkL?&lj z*c*O1dA++xb-XbD3M(5Oqh#Aqcl}7x)()LC<5}!}nXh_;E&X6`=fW+!MGYlVKjJnB z$i;hLTx-SzPe*t(;W)t`rK9k~HdZMAHE$L#Pyv5(D$Lk`(e!iT?r<^~<;?GhX7D?t z5)lVL3x|!L2l#S0K$vgK>|*Kp1?Bn=B`W&vA*BJ>@XeGb9%}mwlKvw%<&+eKP>YE( zl%qxjsXtk67KF$a%MtpUsZe)$mTb=Qj#h15U=Hi_MXKPUY4GpjeZ$LOy~C5qTuCQQ z8!S>R3+R^@#7|g&Ys62WQ&@&^@Xv{xr6M6z8y}Jb_>R@_7ToSbMGYfA`YN1onxxTv zhGKhC@`=4j#+?2{=8^q9#NS{mt@wW%?q13guGeFG)y3W_o|%_!UKrG$@4c#^6%vLH zOr5`dp^AiFMF<D7P^x+v$8-k-&TvRa^b;(4RD20Cr;GTdkt57M?_<!WRCNbYkto}o zkVtrqT#|Bj%gdQ1JDn$zeso?!;Zw59J!H@9ME3LcnktPa%0N_5iDOkwwcPz$>(>UI zvL{~c-jtqD772orWI{x<=p>aeA1`w+Kk-7W5~1M!tICx9S#*o;Cf@G2qMZF2$yDU! zC44()aqyg<yF_o#38fPi7r`!o8Uud-K)ZGklyd3tb1l#`n*!tA<mm7}pq&lg9-Qy2 zkv^V^&Nx%>hxt#emifrz5YQ@Ld*fmrZ>KrSrVWfebN%)${v3Nu_7wk{D;$HJLzzI= z`!>z?X~hqebjJ}$aJ_~{Dbu7IG@#k+UGM;GZq%4ozV(gMXv$fHf&VwtVGL+3i9-9o zK^kRC;=Y;Y0|p)35=VM^AneN2EGK|*^YG976?4my-iNAw{Ljo;R%9@_ibaG8$PHN9 zj@)PJ=77)LtJvTaY{H&2;!c%6M1rs6`c&A<WbT_rfXSz`$ZI-R9_c3?*r7gh4$Di= z27#n?VNFk1;Ru!~y^BgsKOjd+8$L`JcvLdQrqZEQc={WCeuQkPeiGMVZm=Mt!D1WK znZ>f@fNf>Wm&Pn-u^d=X|K`u`W5GfW5?2(j*M41QQ`#9Hc5Vi?<(l^OY(CPLbi?Q1 z2K+bJa129pgMHYZscHxH--dXV-VI$qPxiAfWI!UP`p&p!<i8w@+Z|@(SVS_|wheq7 z1JW!7+eI``EQXfGB;D6h9&Y@y*NuE;Vg99Z4sE=P%dGhN%0C5N)=RLwGky8pJycz> z9sqcxFGj%*?<j+TJi)}WBWZ;h`!ro}NnU<jVcLn^5hlg*V7g5A2DRx8$wEUpdGITg zJJ4F#jg3lHo4L$ckrm$~Q&)8T&w-Pa!3S3*D>^iwTj#>JA%-8!!qAR6GQgB6sq^Fb zrt$*uZAv?AO@MCP*5C$DcYKL=(;TH@_`{aL5xSLsevMr2ren><97rqzK!3&r7f56l z3z%QL0=A`$h0k!V&^d4L)nyhfK5M$CX3FCE5sjO*$C2PbI3YTk9g3@O6l+Umc2Erq zZb<N3y4ijDAf>{A_`z5KY78Vo?QjjJrHR-k!B38XB+m}J`;ILnaV@7fL^Uv}4XkPL zm`n%Tkii$DRrhm7isrDe{1sUL90yljoYPeX>15kb#wiQv)|t!xdFg0Z#~>1Hj>LJn z;uK>53)E%7aj;u4tRn`nhDQ$LA$Emc9gPBfP85zmM@#+k#P95hMF;Rb)5k;(7)ZU} z7JWUbmb227{h$^G6FSlc&$bH^+u9Ip2x61F8Pw{=5A}^c_3U_Eh;#gHHudS~(j*%O zUDD$h;st0pPITMoPUJu&aGa?&{kdXT@y}$=#;6zF$SJrrkACD2c;@~V@4-7N!0E)x zfNkJlRWAm$6KqcgbJiT0{bOwG)glt?jk&T!CME~owUi;^D^p^#@Yt}eZw7?0ou%ym z0)Y5E_ClgoR_%B}sdJ95Gq4Rwf`gbG9-x%z8}A$rV?S30N2~Ftit}3xS`+E%=5L)t zHD(Y+b0t6q9$?|USOluekz}yCA?JORYRRZQ*Z~(3+zvLvUP-#7RFIBae&XHDZm@Or zHM<=w1Es0m##-Giu6NB;n>Kqp<tQ^DaGn?=o*rBeHELtnY(s+L=f^Gh8%@(`3)420 zbI}vM$M$$}WH70op|Xco`(*Y!8VkUlvFkHVjl;&LI3pCwrPAVZv_qF}=9!KhW3Tbu zdWF9;!_=wEA1aQBS~*GxIp^b?V}83cu^ycQ1MohGrfwFsUpEY!z8}!WR009v$!_M& zk8*MN02rTD8zg4E>*KhEcVQ_x$1Nt*yI^Ymplo#N85$d)gufH-8}0WW*}H-1G+z!R z#Pgv<eyN{Orq|?B^^ofZ<4_c<p+TW_Rj1;lR`N3IC+@a?>{EtHMxfEO*!g)XIX$jH zG$Y$C+mhppU};CNBIBpChnx%Rk7r9<yf8LdeA`zblb5x?wA|pez{2qHETeix)Yjay zZ)O~3_j?~spW(Bt<uRyGZ3#l~nYx${hjl}R#W2&-SiL(t*C)(QzmTofGRKj(bPl)l zx+|F;3WJ!Fp{Uc)hNg6?E;M+-&he3nU4%!5)vID$$9@7o)C%CsDxAG%6wqe`GwbGM z%FG-+(4v-kxgCr}3)Z~6Cou7%Sj>Ic-&WU;)4k|YSk{kg*NnO@=SDrcBj_~;8rh`` zD1aM0=ui<f*<xwonICM<(f_Xd!jVpPNFFql49WNiX*5jV7D_kWkP6M4e%TXvc~39E z3rbt)hnSD94N*g0E?NToz%tXQKMg4ZUL>*Rnb?m;&&gz4*7A!is&GE}a#Ore@(!#+ zM%_D4ZljA)lZyOUW$H@o`y!D(<qm!Lf%6wafBE)J4)!2jbUApTE4a-+u)8oo7Ye=5 z!Q+um#X==Q(*qD-9T?<}Fmx7AyIg9$Kk?g>E<F8weAy&j#smPcRWOUTU_gy!?gdiK z<F$;ifA*pGA1^)8=y@^CFSFkzXFKP_%vF9;)!`Klhdky1C$wdTjVVXAZh1A`I0|r{ zdciKr`#t?U$5EX;m_+K|^B&A@S}1inm;w#nW`mp{;Z<JY<i$wbtCzR^gG$pmh3t?i zjzPeLNi!q?4snKG{AK8mO?h{>C-@-w8LtLX@ZvScg7IFKYJCBKyPx*BeE`a7#BmCr ziMgt)(6(&du2xXF6eO`5<X)g=e_6M!LhiQ!Uxe<#5daw;3@nJCc|w7-qst8Abn4z) zn^Y*;1)60f(P;?{<h<Pv=!V#Z`TkRR*ZdZ8ZHeWhzZwqRT(0Idhl25Y9y(;^9Srzx zEo?~GT*HV%46_B=U|P-Q+K!XuqS?p+a84Ps@mJx8DYj2{F2(%z8Np$*w`?IaU!bny zrPO6r<F~n#Rpx?WXneY6;ui1Kx5NafBXc#_5*k*TZasAbr*+NIHKWe3GBN@}^Gf%L zc$Zfft(PC1IdbfM(TgYo>wQk=;`&21$q*Kmz|@_}TJFx&t>(l(uLc!H$fGXOAeMWG z^X50a30ldW&5lPMuL(j!)zTex=a~JK0m-Wk(1^?hL*LJAQz|<|ZKElGH+(r%EiTmJ zJQQ*P+HM`YU%00i=(YB;VX;>=E}zabb%1f1JZ84+J79D#QVNW=njtJ41ClMdP&#*h zY}nm6ms(UMc65+T@Rm93F~WNTk0%jT?)B^3tCBN$_tDG^9Fwgjbds8pOk+})557hb z{<L=|pjRR0YSeH_x{fLfH+4cSVB6~f+Xm(sOpX@1^(y-Z$A`j)SPQ=<|9SOCJot$( zYl9aa#yGk#PtGy0xbu2o9yYA#<k=osfM`_}&Gx6ViMSI1Q(1EvHM7pQ?d&sxwV`<6 zIG<C--=qAVKOjNFtf>Adi%;y#4k((B9_j^!{(#_<+PtoAxvORb>Q<ghH>&=<t*?`@ zpZihB7{~c@k9oB8g;5?e_St+<Xe5AR4S4v4gXqMgF_*BY^;$76wJ*5tq2DhPlx#TT z%r6r{2ctk0%%OkkU_!jxX&3lC1JZ-z)1y*ZrV-HDj8Ob1P<VG@Xxq-N!Uvs{XTEKr z&|{&63+PZ8``>4%26vOEsJv!Z*O&{u0}#*m&pem_t0>fxmD+M*KJJk*rzpu*+mth` z?Sso#Zmn1GK<pZBcLc6}4PfZn%kx_rzKR0qE*xi%;;5%ypM2YR+bpSfAi<z;sLS&c znw~pLpBdqKv|#$`dCzE8eY}`TY<SgtBz#2VAfM$_#yzJ1Q!G=Zo^h<oaUZEQ6Qnb< z_3mNo?{}b2u%5Ho1Ii6hBZ27F9J|ikSZQqvbGfC$c`4&~q^@J`_Lowx*ibUmA(a)t zIfc2jqZ*#>+PdTLd^i2|6JPAM!+)ID)(g$x&yL%+6IY^H7k`y<n0>F9D*b7vSA2mD zUYZGqq`M@3=W{-JJty@!bFYn52CiN<&CximbO<q~o*{DFD}e(^e7d07^2+O-(3w-A z;oXqr!^^G3tC8DBWxk(g>3+u?VHwKAY8+c_O{NYDT?~=Bn4I-%?75K1)OX8m(8Vu| zrvH4II2T;~HzshlK;}0uyQxfp;}BFaX5`9i-+1SFN#WVECyu+xzT)hgOG3$;5g}xn zXUe%t^}E1xScCoX@V%%|Y<k22UJ7?%K7Bi2<CNyzo#5`o;0^ZX;fOOP3$6h_<MYxT zaeNcElE-cScNxp{yY@>+6r{PqwCrYbj=_qZzCOE5XdO$<^|IyX;Wz_OF-*iZ0^`vU z)1H~6B3$Rz8!_E+Lr{7+`yf)xY~$-%KNYx;2ByYPjet544Oio~&?lv1Q0*&`Q)Qjy zSl5Y$x|3!4f%j)viNo1p6SchORjwEu@tI%@JBb*oV#0JIXN~c`@3Klp^3lNsTG2l+ zFT0|icf@}9p|#YV_<knVceqO4Bndc(5wxCE1X6#&q1!j9%KHFE#0;qxNj)Im3gse` zr*`n3VDEMi&VK%eHr$nGN+ql2peNHc8q;n6yyf=8VI_$a$y#SXcd_?R>6|J)94P)S z5TaSOT|QdJ9(DcXW&aj@3GbN_J$XHBxX|jEW82+WW)PGAB((XNen9f`&J$n$S^nAE zc|WUzeJ4b}2Q2hgyN23Io&ee|Qh7y^WDs<KLRQW?Jtu?DzmYtOlc-6Y(!AA25X4j` zr}1lcQw(X=Dzx>0R3+!oY;1cWh^}kb0P#B!ruA*y5I|qHQ@THuG;TO9@gL_Bc4APG zqWgVy?Baa<DIxdBpJEQ!iV?9~ovvqhRZ9HN{8TC358^_gK={Ucs6up%GE4H*)QYMS z?{{Z7f{DSxks>1NFxDj=gfdX3FlUPg@!(c)(jv9q;jI<#R!|L;q?eqg$_1ZD-sF(t zGvEoROJOyrKil96o#}RJho7%s@5w@brojOqY*y=TlIW<R>1gSa{-o}6w)PW}O>hqQ zRT$iMNJh+wOf&n9>6*4PZ}thz)0>iwt56;kiymx$9svE9AOi@9)xNjMOEvVyvuM^+ z_aN;%0)TujZAkJ`8!Zd-_eZo~l-$bdbX^qt#tpYO-&4dKhB!47&X0uulRw8by)LZE zqFz=2OufI2D9kIYy&8nb7CC68EOj*6?2nSXpW*KE2WJ~r(AVrc=eGI`o?8C)dwx4^ z@N1xCw2*{NT7np>sxq{}-WJd382fyrM6`B8184#XYW?Sfhp8$KaKA_1DUCI*1M^O8 z`Uc6m#n@v#)pKkO&(F=oL7qf-w16Gg9CTuJt>C${LPK`?Ixk{fTOYd-$#PHAw(`fh zU{^=&9tY<3)5^2|OgH8N1nKetyU)V9!7J5CJ?kP#WbZ;iPVF8z*~JL>s?=qqRiBgq zS-3Z~8u75GV^|L0y*Bj2rlQ195^t+GTcf_2#}*%pew&&%G!!&r{|2D&;&i&lo!4`u z_UCUUpG4&T=k4MDc1(XgMql{Ve)Wfk$M*j|y!b};0iB8LP7_YRm2Y|cmp>?k7KNn2 z0mRBph8ux$=QpbwMo<<M4w3A_T1hv-Ic*2F`$GLi+@yz8fbLTi2J@tS>qiH3jwS03 z;?qBuZ+SnmHP{?OHmu>HE4)I&?~<S3SSN+z06KiW^oc>7zCs0N)5E%2B%Vf)4BR6q zHpdSg`g>$pub@4fSClD3elD$(8ia@>EN?*#;1Hvnw00B+qJ@<`6&cS2x~J5S&a$<$ zrwm)@?1ySrqQC+pUoHEIb^uK5PERvprEF9P4^oWAj>~I5$#87*EY>YhIrlUIy3n+e z9Zp)49V@jqB1}W}tCJiu-(-Z!UBy2va1=T7EqYpY##ykUti5#DqVDNvJam?)Ux1Ir zs{qh(065HvPh$)zpg)l2HHGN@c3`4i7VrVngirQ^wL=m{Jo`ZT9os@$Q2jP*;{wDe ziW~#v9q#~NFEDlWQWey13PlhVE0%}eSnLp;AKW<6!+kq^^=r2KyGChQ-Zwvv(h37C zknjxNP;U>kP}tnZu)$pkeb>gBqT!2z0Gz4MZo6iH`$h*>^QHk)e9!Z5=xt@fAv{*~ zX(8KJZsFJ%UFD0~aIRDf6@pnXH70pzoc^!ty*u9wp^3ikRq7!4y`XexIb=?2Rwghv z5j~jsU|%DFxLcI#S0oTCgwDL(mqFnah*5ICBQ#y027~!oG>hxkFqRmaxMqo7HV;6k zXGpW&K>^aYx;YI0$K{;~qHKs{lNVULS68t90i)}a+dA_7X?V6oHo{j67W+rG^X@Y( zt+d;+<V5#*B}T1WdhifRtVAqh6((OA!8FRdzKB*$D4MLd)|ffSFHLB|Xa{HhtqU^U z8Kkto{;QqJk4)Ez&l1KHUGW=vy%m!Q_=`Acywum(G@KUUw)~b2?rWy2ZW=!#Q^S1m zg_D;M`s!D(t%rHX@x1J})M7VhoPELNaNKo?*SaroN%!t=7bQL#GvcIQUTO5r*2&x# zYmSiH`WbY21s4CFBtri7L-B?KI}2LG)+ZGpr5_mg9sSq-zPk+qu&RaZ`v;_6$~YQY zoh(<1l*7Lkq{nD;MZZD%(MJ<A7#q0~wbXFArg$gsey(H-Y}=eaaap267M<_6Ehy|; zETeSY9F>(Z6j6{JT2H*jiyww>iVdcL+ouRZy9Rfr2V*4U0BokUeq0dWVOcci78+K2 zzPjVBOo-}-%QCm>*RrH;6BLm7oi;}y>+YSsC;j#qQt@rz*iT1vrVPnW&8Bek7Y*>T z^UKFoBH*}B(}-FCq7mTiRF^9ZH0hqC3wFE{FA5pZ+f2ZdK$fMFw?be2+wa6y4P+!$ z6k_JE|G`gv$oI=>MaZSA9IyYH{T1@H=?Mp_tdyT)f5;3go@}ju6%QkjwX;&qQ+LB? zLh>3k_2vr)q(HuOJ%zFyz8)ixYdGBO!l392jIC<zJ5iS=ki=;!<F{A7kud%&V#0VN z?L*{oCMhvCE@3g{L8TNUov2V31+9vWoM(m@avnG;XqG$YM9K8Z%`ZPOC>U5_N_>`z zT!v&vf{w8VLS(1-V>GK)vcHo0K89T@maaoY|B(pkxO)_KmPZ$MawxP@v6d8pX9+xg zz#R`)(nSh_bj!y2ZeMs{3^+OVeD+Y`hMQU&^bcgjh8)Lk#f|msFXn7UVD3v>eYCPG zkHel<3En&<ocmUok8XRU%QIzmV&LqoSTJJE;u$tm2XiVVoJ|McI~E4d&6C;zA)Z_h zesp0eHLqVL9pU&p*<tJVO<Xdq-u+Q!84*iJIGQXOCUxXKfTNZg6kz7#ULPA0S1G9& z{Hi0X`KKgb#Oa{3Ib~vd?qpURP#dzZ^5ooOFX92*bWeh0m-_l=sZy?6Ioy=jbt&`2 z+ZP{BlN=R@(g_ShU8XL4HurBpi65P>aZWtXN)pRM@1K)xQ^faG+H_AM4291Lv(8Df zc5e#;Zo=y4xa!>u#U}g#mJy>+G>X3x)+SCKskoA0M;_Ui%C6@)Oi==bFJkAibN43R zO0xE4sYVe2wwPBvR=mb6E{aNAsU_v2c}?iTCJw}hX$u)c2RtjLZ_cy05gF+lMD=x0 zPXc0%U3EYfz@zc_>?#R5%OQtHrdBkdO1h<peKoZLKZgM3M1UocC;kitP8p^Oq^3~x zpQuci?1~K{NUVT;MmH#yPLfcquujg#vR)Z0`1}(FOOLYQT9vim37cAqvk6y?w^<w> zs`cB^3~w96IK#K{>Y$oUd%QE2{7AK)SNg`AbA7Yrc)>!R8sp(XIP97j&<`V|;Y09W z6YzmpyrjdDjGAj1`kEhx``DI&2KB4N?91Lu0;#tVkh*v|I!M!NL?iXhe?Ket2H5Ck ztHblfCkm~+E5*#Z7{(vxy@QnTA+LMNl=fv=`$4t%2%^y*IR&5_?IPbh^V*!hw5jNW zuUIfdKf=JdTDy*|c`i3!<V`pP4^F=_{#<J#G=NjXi)SP7)B)T<L~lfz)L_5;c^)9o zR-kuny7qbKG(TP!-g{2rJWpoT+#1^Bu*Nx%_&H(K3XsOfSFa<7|5F}RYk}WM&TMqd zUEQ7n*9>Vq3Dh2BU`f3C5lYse<^6W6L`l94E&pm$fBjvq{1U@R0<r&$mb+0ix_c1& zGN_;OxD6Mex6b`^(6QX*!`R+OM-;FraxBwHoMa4->w~%TgM$I<b3qE$#;X}Ndrv+t zOsWhrG;8sawLHq*1WX>m8yYeX583Ofu(2q3nKX#+rFfoa{qA8KaEMq#1;CKkH$KGH zi<u&a07yi+bdZ00&^z}>2DQq{@kGNWFYnuE4NHdcuC>g-n?Z|O{c)kep|A)>-SG=+ zI1UPM;BgiKOO40@=LT-6*9ag3eS{c_Jn|4(lIq-=S`)WpVn7vi#9JeC9)83daq}hS zJ)XW{^RaYIQqZww@l7hPo&?bZC_nM{uvj(8H#_819PcHpoX(G$S*sGG`r0=V%NgE8 zwFSIE-^^xnO<d}JrOx=_fVky5?Q$31-84oH95)`oNvz`XuEPfbDYt=JmChHaSq$yK zrF?rPh|Vj@D&pxkmK-e30jY)1j$P%dRdCgT@ObD!ISjiAlgfu&QK8SQD-JUiS;s7o z)He)erGy*G6k;QYhF(WbF$Pl_hiEC`MiES7iN{(b=S#0w$yY-RFk$lg8k#>nbjH(k zNYf&p9J$_zhELUnlUtAYkpK{i2X9CW(&6!G_C_lBjmM=f9{52;{6@&Rp_1d%(k794 zD3*#E9aMQnRwGX(JW}|-$aI@Oo8vu@J9^cV0}yFw<)d2OsmNNqUzA@hYu1}+P)k6N zqc*JenJH(Kly|u|>cVe06O8~7RVpD}Pr6YJQjltebvRPI#~7Q^c=W5ZIY1pBk|qU9 zgD0s2eLhj|E((a<y8LQDNk-GVe+@V8IRY6~%O*&>9Uyn#cAY7!R2BH|)267#rK%Y} zUzglK<tVAj2nU%;Y&-!=C29>voW;}`k>?a@xyF7`xy9j#arb+nuYU;n*uUn=Q_4v{ z(;br(4N{2<?!1pMO|ez9N5xvQr%_muL5X@TU>x^V*c)G)e?e%lO>FS75~=WWMlhLB z?08ruiL1VVm(-P1ulRT*RaPA_diXT!4hUDScoRQaW{<&~D3kAXB%0ue+DVV9wf0q~ zr9P31-}fgoZD{4>IHFn?zAEFmRGsf;rML-}`GBzE@PMU{dwn|MQ7om!y|npDOCi>d zM=B)E!F0f{FU&nm>fB$6Hy~gxgsVp4%5h{Xug0vL@&1g__O|%!9S`=&YYvQz^`m)t zZ-*L?h-NVi!&+W_HO2Fo$`q-5PDAu18goTv+F*ONIx^sXC{g@L5Fz2|D=e>B48f5C zdCMge{%P}GoHQ{`6K`skX!_)g4E-uh8jfq)c_r~JwjyS<s$7cn#$#1kVnC8YK9bEn zqM*I{E;pSPjc>YaGguJ?&tAD<C3N3`)r@>P46ed6)e4D+IxpJzNNDQri{fQsjXsX3 zRD8MVqkNq^lN|C%Qo!xRlJXH86C3XgGHH`8$^V~Ou_!D}9C1VHPZWMUw%OYQ?{&Ec zAkYSv@g#x@2=~97Jk@OOCoi2JE}BATS#CLj_$ds&%VU5lZyVz-qPb4cka*Mf`JYy$ zaW+vik7zOiNf~CPSik&9<@Hz2pH*(Y)E2#e`^vN<(ID@2{EKIA9b4?PeK7G{DNRhx zg?6pqLjTKLdpRoMEO!IX!3Rr{UcGE~`Z`yMg?VJgqj4vsF+3+cYE&b*pQuxKKk__h z7RS0KDz;D#X>?b9ZPR^2TqC4=@~zKcgt|D%*doM)p6Gq<bGGq5uZczT{;1l%711QS zW%h}h+D&);KbjBBUjA*klGHXj0Qywf9;o$3pLpC}*(^<zPKp8<kRvK=5YhTJ6f_B> z62VYRO)JeOsFF{9_eKITnV&Isc!`@fes&YDbx*E-jM2-^`LltaTix4xi#H@1%n{WG z89ljMHuai1!$SuZHyqErDZ)ze;XOFs?&%wm6~Yk9nzOI2^=qv01V4H{vm0Y%=#@2{ z7uw`q7`cNy3DaR%I58AhQU?HB74kO~w>QFai_b82Ycp90c~Vp<q&j`hyU>6rg%EqT ziZf&;<zBf|cZ=K@EvBh4J0C4~pfuf$*0{+vz~0%^-miP_SPoiEe+>*7E+{1l4UW`~ z5H8-1dIS+Z$2u-XqKJT7X*{vN_3<GX^I`Ca5{qdFRWxUy$pld^9!n33Wr1OJ2*v1e zytm(VoAud1z8`xvLvg06`>{bz@+rZdOcM#-td!6AT2@%}otl{<s~|@0OoS1YX|xOK zQ{^>Y=-eDG8l}F(SRa4vwyZDF*0dC-s-;VO1PC=5pKYV#0X%*?d@)QN$Xmn3@GLc| z;v?dRKixUIX<H7$p>YJ&zJWL>mmE%jgc5A8bv^6HAg)6kq@(`S55bQ|S&JkajbFoZ zc#l7{xnXQ9TeqbZ!!({!s|#X^4w>M0_YZ4{IGbco$+c+z6ljX4wo3&&w*%NT&mLd3 zIQ%XE?=uFxA{Te`0cx5QHkH+BlOByd{IO2ejR0x?Y1tC*ZK#cJ>&iStO1jRbj)ndl zJ$29MyG_LjGu$I(uu=X)$myH6TrVq|Sb$WMh{j#f)*eJTV=mh=MctM6ok)etd%K2W zl8E;u<vicY^WZ(7o`zYr*xpTXQhf1CW2iI>${bYc7U?j~3-(GIwI*CCi7|Yx*O$kx zxC@EtvZ{}{n8nxRz5BD;;P%XEqT&3>>LXt}cmZR#vv`tujpx0TD543As}Rq7&cNs% zjah5i8+_vCG<)Ul&2UNADjkb`)Kszj6F8~iTJQZ^LvV^ZVDV9c5|3XncGaMHcZYpb zC)03;(Ov`ueODoZpgQ6-;y#6g3sn4X(C8-Ccj<K2n2a|<{ljSY`wQTMcmiw}S0&h- zT=fU%b@ukHzOLvf9XLZLo@mf@&h>xmv#QLxj$7oNH)IcHt@?KwvlP%gD1q$f{DlOU zpZ87f<5~Uq-F_Tp)1+4m4@5YCPwqH+xQT$z${GOulgd~M5(h%FLeX9?(B!^B`y4~h z99(Ue-OU>TXNPSlzIdT~!@i!jA3ruu)uu?3axedPW2fslk!VV495qQkckho4=7CWJ z(OB2n{da1x$&Y&h`vjdo-FVL3*;fR4p_hAu5z980^u2iX;7p^BE_-K4_xH8UmzlGj z>_b8%(%GJ`Qb=d$hE4rf-LvQM-MNa2TqK%-PVFxBW>}0m#Y)+&4Bro>_V_e<|Kz{A zBjFH3T_l%UUFCaBeUs#~o?2A;VbtXNjkxf&R!IK!{~1$>`i4aLU9A6ii~S7!zlT{y zrR%d{KcuXAaTH$NJSsk%x5U)fBWI~DYBX2N*CUTM6ey_|HrJgWY;)-_K3$^BF~s)r z5$8I$o`RY~fK7n}3lwTMfZ^?l;n{}JOEV8vMzulw#?@>#Oceyrcv@gspnxwh%y7A3 zCubvxw%Xd40Nfz{!sj4>6yOa+NOs+JmIeauImv0(H?14y%{B6j$j`{p!{&!YHH~w9 z-Z0YJMIHR~<&6h(o2}N;8}dznc_H6hs%7xHINn>bs`WkIRc`mSZ59<i1?vZHO4y2@ z!mN_=rM=(H-@kI|#G8j{e9vL)Fg(h-mMrUKFgBs}l>ZlcBz<)%`+pi5?77g4tGHZ@ zRXLjftwwJ6tcXLFAieoE@REB3b_x}jJzV(YRnA?6QCf{vM_pOe+zLq{_CWo<G9(d0 zQ5kO<P`wfx$G@&Kt$P_$i0h6FLjboDFtQFxw$_~yHSJ^Cxe{j96@E0)$0aWf1+2T} z6ZXfQA1j{zn1GOt>E;0tuyQ>Akt%Wva)VU!s6OpL9KV+a<pJ`oKwoPzZ*s*?SlB^3 z?8Gyzl_B(|@!dwmw?TsX(IS>CM>{))$f;uL`?NnCbK;J-CRK^5RECN9#^WKfbFl+4 z;E&l?V2X3rR{~%SDrH3V#HJE~vk5{&mqZBfWN=pb&NXJlj;D{^y<?v}^GrsG0Vrq` z&6LsBoq@ax$Xw6PZaSHG9WRzvE1-(}sjXpK3;NcWHe5S0-ZVd`)|B_U_9@Dpe@5qF z&NetwZXd_H{4iJS&(!hQz7=#uj0G4WU%;9TyAp<dYkg%J{Rwh_9JsDVICpsebY1Jj z_}>WG5N^=0fAF~%WSPIPj!V8?dXrvjIcJyB5E3v(4bq=y8HE1uxf^wz2*j`FsPwiy z619=a2zim#&oX|QR<Ba8nYpmbxu2ah?NN*6$%~%sH5MaR-Pauz>H_~I&6UUXM}{iY z%LnUD7rm>@>-3eenxn+IWYm_#im0k}J%~FEMp>Hryep0MQ6DZ3h7)ctX2vLN&~o{8 zmbM>RCGyit^^s-BYm@bAB8+qwS-M(-!Uo)eT6a4C>Ggt4i)^!>>zA+ckiQjH3Ci8V zd>4?DL;1g!P%rJj93Y2!b!_!1x?azxtt@Oy4^p03&i{KDa(7d;(6o0yL)97fzI&)W zQP58HbBG#9X(_aDI$efV{&na?ZoG}(-|sI14|8M#N`tD7kami$j|%=;JA@Ok9n4gD z4d;+jwUhGtz40j?@Hw95<RcCKwlk0K742yUo!KNu7=qMeQps{x$d93S^Tiw@2Pxmm z-Q)@eggb4wWS0=6&>wG=g;cIft2FwMeRhT7<7sl^0PyB$!Gj;d`5dd=d=ZWz?~pLb z6s#<JnLtxivyFsvMwrqSs~i%2QdEnV&SOIBy?Ud;M?!WCH_0eY8*x&RHh>OEc!>3- z9!Di9a99GXr3n&DnYCruePc0hYv>jwXT@4gx0>7XeMs)&`u<d)21EGM6D@zGgmi=4 z6~Tmfg4{~g#LsLQJLlX28v-Fs44{vqji%A@YMkUBQy0}XTmSdiXHXfA@2>}_Vvq)s zDlCzIwk$Ur*n8pW6?FBva7fvv?8w>qRQZg*c_(ma1>-wuj<LpJscre`p;E+F_ytlv zT}U4Br8_4Ejgn2<urh%s$wu#vReqfr3uw}_J?+9WQuJQXpHa?~u@X9_D2h}UEvK-f zSWrU%C$jDd{}n_MM3yN4+wrF3U%v>uFSsCa0=-t0kR)E7FuYTVs)3|9fImCrHC$lL zz;z-HB?;<a^|6`#`3SLm@kZ`#QS-2ndXZ5#gMGj~^9<s;><d3znue(kV9_YA(=~3P zGuvu2M_~VcnZ;QhzIhq5W;CRm_w!sY<#tO^^Wpp=JETozW{6vHhXVM0Z#+i>Nz1w> zKccN!kfE3JBq@B0quKIZwA^JdLUJI|>Hv+qv;avh%JzX8Foe$+1&gom2?28%PK6wg zfE>LL4Q!zee>GHsH3Nm}p`Lsa-a$R3a10dca%F|lNLkYe-!%E9@BEt(B96NnV>F$% zR9gelleMP1RA#U896Apl+@GiN;Sr2`zH{VBjh&1+EebYA1?F^GuiIpJ(>H1KvW@QE zm4j_wv7dg^^(677Im1K#31U#IJafMa_UgdbwlQR}Xq;yoka?%rfo$Z%BNDzxP?pHA zir1@H$!V`bm~0QgWge4qEbby6HgYui2(PvTR)xJjGTz0XzG0P=kDv-&x8X7t7**kQ z2al!lvgUb@%Sj!{yl-*fnJa|qZxyG|SJg6|MaXaOBGAgVu)FQTU6!krF<Ee9w82G6 z>Z4ny3Y&%H$3+(dTol&q9gKM5Lxi7}P0B0|`0{h@4s0z5iUQ}aQw2@Z_Y}Vs7JOJB zKcZNa6=qaC+6lzFFe-A9$511;lZ5D{jrj;%3+J>wclOfMgr8F<;s=)YLNtnn-h^L7 z&gof5g2MH-LT;M(Oqc5H+e5{#_Ph@zbW+DsLMA4sf;0yQgrdb*+7iEGE2|Yhy;-92 z9fj#xwY7!&|C9wnbrbNa;gyoD)dEg0J|mzBuwwPl+FU4*%Cp@Rk>RPy`}2jy0&Bs5 zQJZ2s!Exeqp(Hq?pVWKUmfLIUXoUwWOpOd-JA_`&SXZcgbGcdFi?4~Z(703H3^&nE zmN_rtJ26>0%$;iIPhg>FkwYV$Hxy5nU8}7&*}%g!3TiFC^dYHx-|q4Ng-;x{LsRn} zi8aP^{(e0HC(Dii;Xj5L^#4i#1g0EXP}dp)u9N$k<mkSt6%Q$zgXomJI2G)4Mz~d} zV#>-i(+-|_C1gKfd~I0kU4PC6vpT)|r9_>pdXwh43MwU};b<Ra!310_*WlEjwX?w| zE5rvqki0m@JqOWio}?CONWW6cJ(kf351avjduRRgv~%Z%)7+_B9Zqn!w$DDlTSj~y z1mr14vwRCAQ?0fn+%Ao`%OxC3M(ZJca4BkvD-l*^%aE5nAKr~FZd)67f91Ftx<7~2 zxM}=yd3P@E(z;?odi2bJ1ThYkO-TRqd*zy#GS71NZSIJ;pniI`->yjFHUr*-J7|*m zA4TW8TFol}C)UV7&~0ZXLo_=k9Wc$v7@eFMT04MC*$DnG>9`3)qh4TgPHcG3nD$I# zwW4;*c^`EB((vXelvYuG1j<KvXu*~LtP)qQ{9KA8-!TxVtIYoKme|E7KDdRh;E}Ds zE7Ycm&+yRXbpBQ83Ru<ft2U}usG)X`C$3V3KUW<prt+`T5B;J8#}B=d`h=2$17<vc zKr~A1mg7`CB7%qaVJ<J*A>NQiBRM*Ku0@Ru#b!Q5|5}Z%%|r;ak9I378mGzj1<eOg zw!IvGS#Vc7GUVSOBzy7C(d(b%V*}yYXLVO98S$vPw7Jh{WizrO0LcEJ2>5@MJb<DU zM%yMa24Tp=1Kh+0eTk}Cyvt_}D4#R~&CJ9jIJRiN_dhg{|7|f*KjI_TV~+c%jO`a3 zQLL?&+*0O?%tIm)&|OXPa%u2k<*VJBvj3vx!P(A!8-^X#<HJ#MgVmBFE8D5>xzw*p z!MRv0Z83>~TE$7P;9#Y|by}oQi3m_3g7VQp&F2Z*ru7+eC1bvnaq3Kb+HYDg;{Kuh z#Xh1bZBO1=DU9Nk9#_jAwO_3}G}hKMs+vGJqYL*T2dv*<J21yT*Xw{*q`GgSG$Rmp zdMIuFyL~}2nac8c14>`@)Nf2c(^)9}L%^?mL<byL7XUV@mim^3d)r!e`2dEVvMFdr zm+{(=YoYIm($zJ|#GrB=_G<GPj5WA@G@(09elAG7Z$RIWpmHx?WuI4Fz861sW<pd4 z_4{1TadM6D4*v>_EAeG;y-_*3k4OEowYpa4<d#l|_ES{dj*wrZ@V}=5NePE&>ep-0 zGU|+0T^bKRXhyCe8!_dx>o}V#lyY_RgYh<cbzSy%8#-MJu1R<nMmg<7`8Ai3N>i5Z zXxFx+{nD>_qLd&{;eFm)C*QlWR)80G9at9ObrU)yn-cLBS%;e6(Vs9V^g*B~>Q6}w zvn9I7gLvV2y2xjG@6}qQn2S1D;5GM_!&VMrdm?+4BJ%3Gr9RR`ohxF*Fwx{{=`q0H z?6vs`?7nIRERTYn3%m5P{BQj{HSTJ6^=X*0#B!u_%Sn;_bUsBsh9seS9AS7oH(pkN zB^8E}<EgTEYG9MYfu5lvGKnaKi-=S<VyR!a4|m|*7ucZMHhlQj7Hnt67=E3@qe)Bi z5<nTp)>ZJAm+GOlJMb4<5vv~>uw2u_qVm1UZ%6S8iCQL39i#6cu~qNK-VJ>@lSUD{ zF26o3|4Ut^ZUrW)Bh{B?tg&jJyi2*rQ9tj7z8bCZrgLfCReH1E@LGr+l*fq3<#{$` zXHJ`)L0O)QLHzlorMueR4LK!XH>W19LT)L5Zo-4MA&1+ETWK;8%8FY%qo8jFujkMN z!LA)K;3Lp4VQa=8^n0pZ4wFy%wrUmRh8$F;><<paY0%t7zxzD1;gga?b!aW>Glb$2 z1PhXElk*X_;wS6Ct~|J7_Ml{%IL3@-KU;v3NJ6Bz9us<Yh##bb5xnL?P*HL62%?O2 z56By5IJ$FIQ*RURPyaF&$?xX50=Tl5)O9}Ds#Ye)t;Wc9rAe1g$*6LD+LJ>T-`f=R zd&EP4azPEp^do}@&|tdoQk6h_zu-Jht+)$8v$a#JflqF?3e?o9G1|Ilnh$6n3<-5F zgChhCO&A0Jk&03ODE0bMXpaKo?HGj-d^F4h8XB+S)**X!pwdAw01LSaL&~~!9XBF? z4Un=0&5~0q+gIanl7GaB+V~0*`1h~&@95SX?m-Ckei9m87GhNi#QiwjECzh08y-7^ z65tVSs(n@4g=`_rsO2DY@7&NQM5@<BsuQHQl2KF<het_KoUKbvT!&7~SVXdTEsrO^ z!6#gj0t~O<c#Hk-gF)93IFukS^9@xKBwMPi^kjv0OY%g~^Z4zi9W!po;Id~QAlTS1 z`0wlCp&Y|gQg(bG^@V3y`h*$7>ZGY!hw*hyFFrKxuG^KbM~!Jt3Q5POT5?&g2R|Gn zoG(9!SFnhn1;%^syMOLz$d5~dcdy9CP)?oT0e-MyR_(B|VcD92^#HJ($d`*)f=qnU zY12}h?U)NLQmAhFk<otP{bC$!eO7oGm%ztO)aFZc7YAN8e;+JBO?skKJJ1qyZt7g? z*Y)=)$R|^u(=V)DkiC<9GwRYWSRSp-lStUchyX3EvKnulKM%2WgQ5XI{LaY=vIt>6 zNwz%bVjE9LNi%cWD>yC=F@G8L>#N`}Rj6w{eg(%~=`X6?V4Hw=9+EAvgubIIcK2zL z1sNE>G|AEoL`5VD=jaaPme)VKzdUAg^18N37ZPJix-BHXRV`Utt<ZJ?VH~$+hrFz1 z%2Ewkqui2CYLj<KgZEbJz?5kU3H3-6>Jr?-6fa+@Tp(C;cLrPP`IgB;mAa<CKf27~ zt0D7H*%^fJeZ8B=z06m83*VtMVFT$O+59+2Au=LJByH`Y5!dGvfirQ#d+ZAes-9{< zsO+v*FpDs?`WfxKYM@%1e6sCKqN9Apd(mEHy%_*V*&%LmP?YuK`8=|pU5vv9-)gv) zDxa}ALoYoMih8iT-&iHIfD8MQx&h-R)|e_MMEZwfBW`vf42#0SWyt}Jn2;?H@%C)u zT2A7l*i+0(e2rdLwL)T=%%pNaxy=7go>?{2l=yR+(6=J>5ur!1|MEjU*?<<svwVEI zRWd2)tFdv-?Oq$zUSxT_uVBsLfhqwOmA`LUXsJrWfELb9K%h&I{Tz#^z3(ta_RL+> z1qbZDk6zS7&spQ)Wbyoqqxi95b=?6dsku{nW?8oTl1pxyJa<}0CPM`-S4AaRpBc5j zd#2Ny%ct6k*v&>H(F7gBgjhJ(<Z{#7(K7YNiFZm6jqA-ejpcgC8y|e~p3c~82e+QJ zaX8Jq!|Fw<X^$=6P+Ilwtcyx<XLS2}{!W~b|D(;m(`|n14#Mv1x&%SNuUcYeK>Fnu zH>`PITJTPbqiKIRvXLqvBHf&jZ$=sa24yt!fsCF`wL(GJd$V^`@@^!46h3BB?y#EA z+wvmi=G{nP6yvPU<H(z5&nRe@jY<qAFGj{z-E&d()9d}F-SoSl7_Shr@^hVWLQOSr zf9T#Iz6R@5d;#;NF99j!v?n;YEEL~f_9Ydud<BKR+p57hX0mGcTfX)EcM*G<iB?1G z;X?O{PI+R)T6eXQ@qi5UY-8PM#x<GB`e`xOAcZ5>MF|6RS=%V5yGU;LqY}zpH6fr7 zFKf6s_(B2gq5wqD-uK;pdZ(&s2oMUXIKa^@;RttbdGj>P@w_rpnSb7HMz}dRi6%_N z>b{E-WO!bwR!FH=BJ`Mi?y2YHx!Rp38D}B^V+X{I?7e$_WGy?WYlX0xGO>8>nJEo+ z0GHFfgzR2s<!cMUOcGZ$dV&6LeppnZU-~WCK7~BYhw`+e3`@q+8w?V)&ZX?H-92*t zw{?9VA~$vPMz=yHkKCUPgYE${%{T<1i;rJfHW3cILkMF<TsYm4hRAH$u*>~C!0_c~ zoBk%WSH8CLd<U^9j}9;ogy;OLN6%Y6W-3lO`v`Z+q7%KejA=>cH7~peM>K1^(}Lw2 z{Og-L7iX&_xjcoorY1hmRn96)XydDT()j24<q;(Oy#J~ZO}1b_cJQK16Hkcy{nrT> z5Pph4Jtc(Z@7dPR&%z1zBZRngp_jf-uk@g_Z`(DI9xqNT`--3B2O+Jvj~RbZaLdRC zhJFesSA&Keju)7s6oKxu^M#A3w{dF))xy9Dh2ARBI)9aqs|C5$vintO;(gU6PqFX+ z{<D!tesA>cb@dMGHvP?|qfbjr)pU{NL5p@F_iDxSj@@dp^8|hPAMfhs1<q`b&Bkej zhM{zAHTwN))T8w0E@|n#%TjK;XsK5S?Tn?n#xE3pefg^dHABw-CnPvp-en^rl&AFk znGYKIzhTv5*_^+2U*u5l;2-WusEED#1B*kMUHf&-fd05)@q@nN5~T33-vE0N-kL3T z#Z00U_j%KkT7Fy3TJeYTq`%MLkGBs|)bsE2lAsUbS*Jik!^=VdLx`RR76dH>!}}39 zh^Vk1cv=*&EfkAF?ma;?uoTQe{gD3R$NAv@oi+^1M$<!;8iXtM>k_HAOEvCJf9!6) zGEuSEZFGw-*Y$qbQZLWKX@j6UF*YS(2cpSjvkglww9|O1+yj^oOKf_lUuO_LmV0Ay zH@aM}ShM7YgMdlPQcu!{m-n+wT3_F{4TUSLirN=ruwfC?TopYTAb3(DgeVTL!b8OI zeqh|{fyvmwAH3agc{oQQP}p!He}2S2#kKcc{YO=!R)DM8WW9*EQ)~SG$Gq*-#+}4R zoE+XM$M6%c!Ifc)cRrckbvrpn`6Q*K>~X0lkbBNFK1M$<oO%BL44s8rQ*Q%?4=jK& zV58d&25xkRpl)M>k&ck=P+Cf)^cxMMyNuBxC?G8;Ou7U_1w^D&Fac39e)91roa;K* zIoJEV&vW0Wj*9R9{{HFJ!~gM||2K}Nz|M)JK{EKzhQ*jQ)<GeV=8q-w0^~LVDD}~z zk_EW7k3|3>AJQBa+!9tP53RICC^qHQaJt-otyy8xbG1V(?(zPjxus&5^;6k}nkVL# zA&T9L_*q4=jZjh&k)r)H1cIlB-x9j5KCVz;ftyR);v@u482J?0x~BUShy4QZ*C7NJ z{EcJ}%Va?y42|;g(a}P9=W*Fkh~>yb2H{qm=LTLdIB5fa*OxLUFCN+B7y#7R*`;G{ zHOLs7)`DnK29V1_*0X1yWC?`VB&55(AJUkypHh(K)~Kr4;#AAJH|c-(-Xq775))t@ z3|Q-I48w`ym);5ba`(J*E)3OpPl8;uLL|q$s1>D%w;2`~bD%%W7hY3sdP^T<p&m<j zzvsWUYH2u9bW%Pb2uWy9II9|AbB?^d^P;mlYjoN=5}K5~9XJCX|NF<;8jI(z8NS~2 zPHvdj0iaOJ!TCuD!vC-&)wT)|Q$)M)TMl3>B7QrNFh`GSF!?*1>~t-3WNH<!D>H0v zK^_@5)71)<w$oZFjODjmbzh)Jhfi<t<%O9i9@c}?<+9~_8w%t)SuU7geQtYq+lLRJ z=_cR%<x>d(;CzRB6r|WN)o6s3`ko?Qy>Qu8`Yxu0VD%F6qDn4j_`pRuXVF}1H>sMv zM(6$a)!^{MFjFCa--04S>=Vu6{7n@v6P-um>K~rp{vUVWb1L2=3DL)0e4M<*p*bq+ z%*LHGo&eX{nZLyd+74X>^|Jb=wvV#{ic-mihye70ONsjW)x+0jUB>5h=^Wq9pIL1E zdtEgJiniv~eUe!)(<A?F+D5w@Ok5PVOFK`c&+{F|5g4}F(;AzFtlVmkA|zvu{~ceb zMFUX4JSu_TQw8M6B^wCZAfD9V6to+?JpoF^2s=|GJMARoLycf5gz|IWl{Cdg){G84 zGnZC_{J@0#zfE1@CA%11Rq3<~ABH%53#*-UW4ZexzolIZtwx%ykE%zcWJQs4MEAdq z=QGjVWQM{2X4A|kPFBwf{_{!?tXP?KDkn-C^FVkwqg)&$!f`CP%?;W$ASjgbXUSxs zYFO~AzlYKG@NEMqa$<j*H!~aSmCO;k5!Bx<@i`<Z#$L@Nqunwa+f+^d^w7As*pn-m zBBPrXkfNC%RZ-dl_7g{QsxihnW;%T`ngeU)`PxAV!XCDUrG(u<;kx*wnan|dYojkA zT`+ENHYTsygjkArR%)0tC|_w5g)G2Zm?lT2zxh+gcE@BiDRxcI0)CPCs1~0p)@|<` z7843FJFF60amN^y`sT{gVItEABkuZ2<@WxtJAW6Y+%IXK^kxaL9?bYs)P$_2D5jLJ zAd|pLLQn!nOEu<C!h%jSU_2p5bsnPeKA%XG9XXa)Z#0yWzGjus^X$sNFWGg+q^y{2 zDM5n?SF12@T(EwX^_Gg8sNh&u<YaBS0vK>;Ccr%dw-o<=thc^nqInAJfl_by01pu{ zRE-2D_}Zk4ZRHQu+$1K6d&nAj9a#1z*_?eD=xr9oR16Ne!nYHZ=N!nK(A9Y2Gk_Wv z7oE@Qn)Oi_Yc*6ou~}V$*EB-&WNl7yI{ccWp$IxeUMd14t-}JdY85c<fzdRwx9>uA z!6dd#_H>I5={vY_!}YF*NN!TjP@<`$o>h0ej#iD742M~Bx=x)&s?r<pydPnklv|k~ zi3(vhE$%Vo4nNq4EXsxkRI<HyYJ_Z#(JR5N?F-qN?S<ZchN_NeZXa=Jlf0n&vG++J zG5(q+^Cbmy$vP@9M|ga4z&eFpLgd(xvddK1ZyQRzTJ~Qw(B8*VUiu4Ra3*<Kj<fI$ zx}8w;R>~X#X4%f-l25rNHbXHKjj@ytpp^<_p^}ti9u!sQT@#t187g%RWqO6oN;9MG z=ln0OL>#WbZYWG)VVPUbtHD(QAqIpWPPylLkb|ui8J`h<PbaE8=<1R%4(2>4Udtbr zd1{IyOgqbzSX^^1j6iCQwsC}IR*S40vPbmK7u>4SIrG$~?O~54*SHABOriY!tj@OL z0+#6c%sNg)3iWxs{*XI(B;nXr%szLduu_^TJ1$A#tT$L9J4kG&1$HZxyowxdgS1JR z7mgt@953=edgOgq`P6<pLR#WxgF{rU6Q=j~VTi>q5p=Les;e(33|#h|B6ltGQmz-@ zb9X}reshGacFe0)=pdJ8bfU<%djOQAMzBitE02i5)LooNgqh{aKeUx;2+rv;@*Kep z{k{c3%QZKriq{N&$Ieecsr(-5h*u&mX3^iShW?lc((kr57zS&%KMU+f2#W0ZLe!fF zwt_R_w#D=0V3%@}9F|K^397zzTvdkHpD(5BWjOjdH`}srI#%nK<fu6Z<;LZVbOQ{o z%8BR5jg_}CAmph&#&Pw7Q2bUbT9U)MIWJR-p_9Huc_|IdaeffClqGj(9Q^2nUkxFO zDCmwh8FODV<oN{YGGhfMXTpG_tazxO%QPEvw9Hxr(6pPQoRhwiI2d`&@r$n8my?AO zFd+RWm}9wj^HYudYm~ohOvFRNW$_OoxQp83;aX<w8BShe$U8kFy%ltC;m=B!PiH7E zDsjCHRhka{dN$X`JyGlk6_2|kPzrCqre0?Zmre%}mZG{mu7cH@zEc7?!(iw0z)_bq zDdX%1M&<Z_vPy?P=g)@S(0k0*JClYvz38E2^zKZ`n#vpT{5<$gU73Q)sQ+xdPq`*{ z!Mp3(7gV_PWREXBs;B({gFySNC+kP$Iq-ujO^_<2*btHCftY@I2D%X^fxZsTV-F|z zk1ryfexP65=>x5tO@cxNMhF#O%4(aWzCp+rq=aD}*A~D%)9H~43Vgd6^3@813lmr! zgb9}XFESVQDmNO_2LBTlTY-YNA;UP+l5?NawD8x4wdJ8mL*a3x*IXO`TxXj{CU<Lr zk?8Pk0$9~H3V8!qPvF@1X_mdTbP4fn{YuolSV>3pr^>|mZ+vr9m;qA#))?17i03Lp zowr;4Z+*;bJUhYDN>p2}It;!s2fG-R3{kz|fTjO?Mgtfi<vrGO?qJ+YusI-mOTchP z>lgtqkoAd5k(dwG4!tg6Z6r(KjjKtJuuPSSzw+EuXo<+TKB9KrEAcZ@C#sWcYYsNI z?mSp`)^Lcc@jYK$3h6m5=>x`Y0KtA#a^t>WvUerizurDmlm2=9!bu^Ibm<zTz+1cx z(xHQ>Fhp2Df!Uw&Y^vb`);@h{;SvT$sve?Z7ZGn#g_v_*&zQ&<tgA+Rrs_~;d|Dz^ z$eKO~kLrqk9LgDliapaNMkzFYkP9Q!a?Q{<KJe2tLbE{)kvJQ{FTMr$7HJwZR%LfE z&EwiNyBv-oQ@Q;djAay*U<pEt3NlsizeOf)MnOD?QD}1xtQba<*FH4jt?#jn9#UdP zMJIWS?^S~Fi|_2=vdW*Uxn2OVPuIE3;sXa-#bkUUyT;Nrb|bYLOY9eE$|?@PI>;aw zd_Fo(T(uB9B-;XF<A_IC+ah|$k-2kP+Nnr3Ere{TJ9OS`Se>^|MZ4#@eO|p#$9$^K z=~F@}<z2<)+G*nN4#Z!maBl<fEmSBo*?6K=XZ66?q0(~+A<(!7Z%)M}%_T*t%2kEI zKkUFy$fGkNXA}UC8UTv;$!Zh=b`850QklcCpYtEYAB6UoCUA_BEX{TasE89ZC;F8U z!de#*E^PiKRI;{=-}gs;-Ana|HtD%}`1yHQl?wlRHN>)Ss58s4iF2jrGAetpj5I&U zRf%AazbZ7QE7v{7agjZ7wz1OYSqTq&{EIRK0avI^U>gJj*YN~SOZE*vMEf%>0A<ty zAx7ulhNu!nAo>*($UTue;^<3lsxs<J$la3YpS?oGoBUfzTqgl-XiBk?wS{yqpW|`` z=Wn=UJXfF}TX!zp$udvH&qiP}J%8+`n19{zK`s=1QBGAD>R~vojgS~Gg%U&(2df}? zj&l1Vr)>Oz-0J}2HpjePhrpQ>4YBv#MKSZys>rlWOsGl~`z%7o(un=?^3|zQ(g2O) zX|9B0{8hzXyGTN%PbGJ4ZmdsCUE_+fA^>0!@u%p=x179!O;SoR9#xPwL?YrepppR2 ztJj{-sL8z^AH#RT_4_hWEj`5P2F=?x%5#aoaRGbEBAyQeEnaBl*v0e9yhuCag|Kg8 zB)N0l-foO7ssJIm++fKH=wyGp<R;ktf9<UD>rEQ1b)X?S1ernX6$V;wNw%>KkyO#x z+tLKISp03834)eiW>tomfC)wU7D-<<pIa#suS|rnqzytPo+BzMP84f+#_wxa`*#~R zg}LVZt)Al3vjzhr^3pw5(rtzBYfj0@53*ugS+(atATNaTmV;M^DKKa{v>E?YsMR-$ zujzXgLJd(IUB)zNKFtm!P5MBGs-Nr}Bb&7-7|Up4OtjLxfYHx$&e7IShmd+!d~P`F z)F@8BR=ZccUUv#>uM2QhmaDzWg+&4}b!Ggw3ewNiajR9uY6bK-w6iKB;x*<TfTe}P zU_i#N9He>_(0Z2}tyiJy9(W|ex9Mo1+bOqkTY{x6LI*Lu(maYa*^_R$Y?~D4;Q>j_ z)7ojcSH`spg3nRYw+6W)9*Q~i36#;#38#u(HD&LdtHr4cl~ZWFY(PUy&-_QpQwUb< zAnT1rkaIr&(a!zcS4ga!nP5br5U3i`mZ4jM5WFZ<tH;ZOgJW5Q+?~X}N4JSqsL!e1 z`_5o@rAp7ELLUhA2a2%Uo$$YR9lIM5?1o8VyD%YD`2ul{um$;{eUE_~EWlYkyfiuk zN=R9IXc$C7fb|dqAK1&$WyZRQa@uM3yHP842&yikdP>Oe15yMAxW`Jmho(!<_hoH1 zEaUmxTERPj%k4f1`%r-^f8aCjRy~yhCoZ`uEf4KBc%Yr2^-<`Y-jI`-&^HyHJpgFN zvtSXdCuIME=O7M(AEa#vT<M3gtYVdC4xG^wdEy8y3;&;^C@_eY!#;5!n#dsq&&JhM zbW002@}H|YyRyzzslv8B$R1Wy96oi`(u3=1ZmsNdf#rCPuLlzIv{2b6g4I><aRmRV zF+s=ak-Kqx?#{=YVl>uMd#pG1gP@l9pLrMiG%`SFlsgLQ18NmlRp7|)1)(iHikSOd z3KAX2m_Va1m7N%mCvCDOdS<@!d|tpeXFmjtjSV-m-ooBg6eE8R{Aswnd3fSaLVi8` z5h|z!!F^_Q@|%K?>rI~ja^cVAr#fy9KtjDahVYLTkp4D>w{3fqv>!z_pQLiR*X4xZ z(Zr9cGZ_MWag<2CX{4iW%_UQ%v^c(3fI!Y%TAOZ#h)cxl+$13P-s!4|=W}+=bG333 zlOKPFpMO6)lFPZmuuoNMJDi^U0SDeArhrz~OK~7AL@8KR{wKOhi4FKqlmM|Tj6k(A zNg~{N$8#JWW_DVzox6`z#Ce%dBrAOpOSaLm>_U^KGPCmrPr59|sXQ$wSIocooiAGz zQrNv-3Ya$wOoW^pXq`|W(C2qSTwI-9#>01tys-1n&drSc(C7Jt0EyvQx!B_n<8^V` zTAeW+w??T<e!g*i1h!v++0+_qMwHtx!xSKRC-li<B>Ud^a`>qkVV51Xn%8@FI6<3X zOZXNo)VQYTHK4Jqf-&lUS=x?Up>i>9B8s#pQ-Ypp7ISWfkh8O1WAb>usc_#jVQoHx zV2;&6JC}diBQpFD-7Cn4CQ)F^X^Fh3l4zKw39s#+F>u?8)07vrR4C14T*ITHYvwrm z#g5vAc{uwtmtH~bf9VDQ9lj24SyX9%Iya2D$Yqqok<`j{`8Cqo>RGuk*Rvz|*-_W! zpiM{~&#yi1;}A}D>gb#?!b+wTw4W?7bPdE(-z6uMLB0O=V~0tjg3D{dHy6YQJ;bWe z6A6}ig>gx1PepMh*W(r;+741u(V%+|I?-yue0^s#m%GJXJl2OR_rdU(ZG?bp1S3;y zbBS|;q4uXvzj}K1jO~RAfP0p@dHUXaV2<ZM#B!`Di-J2M%M@{J#>;vz1*{88Hh1`{ zv!kON&#s9SO=P&7g)P^Q8Q$22U*a6Xs?FuU(U@NfADaI_co>#P+U0{O9vmC5Yu-CQ z#D0e4HB}6s*@Jes2C7+F?XC!1Pv)3Fa4BuTh1uTAx7nx6=u&Ig%eOeIAH7d~^*-;c zfDjd-G1wFDa0+L{*U26ZLif^6Ph%{vSG7zRJvvR2Y$(s(j^&@nAZLJ(D;hU>`CKT9 zdD=eOe6?%JHQn7G7rDa!eAq>CX9C=>8FKb7;TZ)VZ&awM&vRax<Am#DkY(wh{csSL zyD!%SnEUkf-g_K3@GXQBGS8|8#4Vei0`>|Z=oBuE!bi?1jr|>Ym}S{r$8GK_roVbY zd0#kEsy{cboOMKK{Pq7M``9~$5;gzfXEdXT_vFp39Y9Es^C^ymWB#2%_JwsW+1j`9 zj6la-eKQTQ=fJ1)Ra}$m`#vs9;a@m^EWkdry6zGVB_B`XzHoobML1#IvMUf`&TG0i z)-FI3LV0gT1Wrp5%C7CBe=4eB(2DyO2&vjs_W-e_{I6koGkIG`^D9CxXfL;D6Q{|w z|8d|lY23@SlY0ry97f<Y*LfM%$!G3dmAPy(FE$kBZO(VQZo0#IbCpL`ep+-QBEBlS ziXTMr0Mh?sA-m9Zb4TUe5TFsHsIL%T_1)ybwGnZSF(N{!En}(vcKjra%M^PJ3HSal zH~9TZXx`Vj>q59NhD&!$iCieF(eY2W<Ff_FdU>_00HX8V@!@95j3^Mufn;rf4wiTN zuFkRWz56V3*J$;&&t1V8$Ie7VHTkY>%S&<Bi8^!8+<}AXWx%t`**1Jx)ooX69`>G- z)>=$RX5n&N+_9`NE>iMY(ZHeVEo&`m9iM-=*zC}$bW8gymQ&Cu6=i%Txk*e1*yJAw zulKpbNK6ns^8wpXQ&&yThtZqfHZ}G*u9)=QmAPM&Rt8hA%WT|gSWK`jSZ(*7O0+$t zG;&F^k~q!tz(X(kt^+fda!SjfSZP%@Y?a8hTE~Ug02VRUULrwnM~viH%qm1W-pzZB z6;{5&WQx$-Ng2>rj<0_|`?%bB<^9?~?8_U#2{5khxPt@05@s$DV0E}#)v@cMwXf7H zEh)gBXbXRbHT99B)X04XApb!CaA(06SNWo+^>(TpPXte;P4LF4^2zB+uA&d{2Rs#O z*atkPn(D-e?7Qzo=JNg7Yc92yr3pBz?8=A*87`Q27u!1G%Dh*4d}Oxh32?wC-+5HX zo8d<m_lw&n_Z8oW-!p04W`>z6Jv?l0x(DpRXs$$5r9R*d;8TmU0aSWb4c>%PsnD}p zMtji_mP_aW14!V@6XnK#j=%5A3?!VXm0>N)PbO4@6X!}9*sK0bhW!U6gVaYIDPpb* zsGSE~x?KL6{tL*<e1^fh5V2PYn=@m_8+FEYB1Fjv!)H=iR#qZjP3XGPlt&sr?7a&v zzF4|<Afn#T>drpN2Bgr`vAP9Kd^F|!FzKg9z><O7L&yB2{3@8DKmP!$eyt_ooIXjY z!DM|9l4luzi8V<MonENPZVth@`kWQOaOt%KtJig?`ei%aUcMxjqBoprklN%oS{@;c zti5@;T$OGM+>WlRv3W-sJ$>2n9?n?0$T+(!M2F?Fu~)<5HHX`=KYm@lGsKzGFSuC4 z0{D-?KBONyGFfT$PAgTl!HIIx*pPw`TPGr-{D52{0O6;R1$AMstJF9?6x6Ph=>*3F zx|7@!-dE8$8mKPhO1087m+vu;k^VlCsG)}4no#i`A9iJ3t|<+rd!|!LEN<5c5xt`) zM9gwXR%PYcs)pi@j+RD~m35%Ft1q0cz3#h~U{#sS2&Sww1eUC5VbvT>0$PgKIbllo zd48RlE1vG+%>V0H1r7ohZRz*PcKaCuptl$OztqAF0)<8zs=|n7_n*v=Ga60aoC(g4 z?_tnOOj<;P`g?t{V;nay5-%`Mf-t~utVpvk#VjyPyc}T2TCw8g>F8`X>id(+c6W%P zZ{dyMVBBI@0dFBdI}Lv8XBjZ@g&x+a=fj0N_ys~8)zlhbaso53Lcm<@Jri#tpPsi< zq~vg6AI`^(H<NmdY*ACG;}1|PwA{2QFO>-L-NH2bLMdwBr0T?nrPoSl>Qh+Ym!iBx zo}!F%;<n*VC&11|6!-h={2I)!P2nAClE!Uy{#!28oY?K^wv-p_sFU^?d7prAJRsBs zdiWdlmRpZrEhLJwBE8fndyB)ckryEZN_6f(Ht%o~CD&@y*UZMTSU}R@eY#yGl>Tn+ zQH}~mPG)yJ9iaBOE`mfW03+>Obgz2YtY}iesA}#}uMhT#&<u98psKL%oS}93v;KU+ zOd?3EgXE{En-c>JN;VeF`Cs<s5F0EK+`uJY0Mb0HO6yNm`!dg;uoNuei}~hCJJ|CI zbfw&5-gDJ(OI-D#^C`PtewpGLA(tMAwlA(Ik^kdKMHei)qCKDPD-~8>b5s3xTfR*V zTKHrmWKOGvmoLMwMuP!-<1eeyQGVQ)o)J-{!GtRFyE5J^c)s$vjw*X~oDb^s?c4>y zZefU==>!iZSh!GJv^LeS@x9f-GOGS49Jlf6rKSC3Axz={j_p6*|IB#PsQO#zj|MwN zO?mKuX|%wLQbUcKXztJsPrkAB(Inf=`BDU1ID-N;&*vD!NJtBBj*}IbEHoTaM)*%y zqnTpt^0{|g605BsfP#NmEZ$;n$l`B$Vg;$@zlaMq_O~qleOg3ICUv2p{vsj?bqtv> z$K5V8v1_wBS7uY|Zs_sR)-_@-F=U@>W`|5F3R_LIc}K>#KT(`c%Y4BP(t31rPTlc^ z+SvLD(ZSat%<({8Hr@cavBQB>{o{J{L)DCc9@czWGZS#NzB6P)6!>jZNM>)6nR(z% zRjcfhkfH~r`%hG@zTp4Tnbb{S@v%K9F7&n-SM_Y6H})UqYt&R}NuDzyhKHB=>u(80 z?vRb^_UHX|s>S$lWSyQ3zOty7A_J5Z2^CAOISH+{QFo}iJ7|?bX>H&42`ebjd{aEE zB%sLBVv)6wgeZsjW8jlQt016CO{USwi%yfsJ7ui%9J>%OVFOxRf823QiX~4d+TOD2 zma&`YHdcb+WReOu&i%yZ<CLzQF|ZW#d(!eW%O^NeBR?OWi%@)&b;UK#E_4ng+%{*Z zo^8!{*#^WHo;Iqg(Tw+bm&DggVFOkAkxq{}zR(XJdvM8Uyb80Ch}MAV<fx^nh(T^C z`UU;ZseLw5>IzlM#_rIclV%{2978S(@84^DRZP;s@&!-c?zB3GQJ0w`<2oWm+q0<s zEX8e70qKcE-U38|K*-x7AP>zQ0(c4EZ%wH$8S3>~l|po)8r2IIg#$XO1lCFeBW^74 z$~<-4<V&54yY-wm_$0BB7xp$ifp4JpI%F=4yHE#v$3q3l$;U>!PvYKH6_OccxP!o# z6`UP~X96C&UYvL^D;n-m-QRrX=7Cso$g^Z>$d<I7P3dMPF@Fle6e^zDH~I7dE=%we zeqv9q&$HZiMcfl28~VNAVu4>}2aUPaM!kA{Ln1@W2eQCQ^Ubq5sA6bgJ*g&+xx{|2 z2iEy!xR67-)hmcR4A|>?-|4~9-DG1gx0uK6)lcG@v`;Z*^K-^J{-rkVrHSU=8>L^* z%k=L*it7wZaVaazjstlKFx}0SV=P}6xnC1)ixPjrGWw&N&F#pEV`P3Vq9gE&2KIGC zxu2;{XH&dG=X-s+lk*qmRoS=GfUo2s_wk(zC!)+NTE}y8P1m1S?WtR>vHUA;?rHST zOhowkzDa9M5c@roA~t|p_>joUml%82*O%deg4!d}jP{ZpXer8~&=5qbds_3xiOph_ zUTF+D-2)Kh=n^V0(m|bqj-p`|%qvzAFrdG;6w*?M?I%8{S;DMN%H7@5x=)8aC7^5_ zrBZ;iTluwr{ILE@nUUdizd5L<ReGp3s$%_SGv|q(9%`ThHgpH;^?**8qaoDPA`iHJ z6JGf*vu=<r4xpU~|1_5XUSW(VBc2;h=ds~YdZt%RZ7EJme8WO}!3ubN6jc-vW08kN z5K06z_(_)ZgS*@<{v1zo^=m?uUoIoVjvop)38!QGl9kp~`3R-5qC|C1j-IB5%m-(V z<>{b44qal(rM(n?e5!3vvj5<{qV(oU;EYN$*$EDdq$G0c@U2)DFj|Y7($3ZF>2(1> zi5|U8wSwU*8I>Tn`zy!Si9V_hqvQ=$jXyAq%gm3d4w@b+#`X<|Y8%_YR!b9WzOkpY z!A`XmU9y)>C&J94MaF5>H&s(yg*#nCxPkGq;vJ^b-!Wx4-~H0m@KTl<_X6!`K81kv z)ge|lgWg3}S`jC`MzrLt_h}Ot{qwUNW`*MM4*1b{%_D&37bgakirq4RwJ=AEVKC9= z!lw1sx$urgtN@QZ$E)=eqvI2h7eg3W67DvsZ9GD{<;uT0%CZFCleWx<e}uUCCQ{v@ zWxCL+C{0@b<oXobWsw5-@6`O7c<~0oJg@PZ+$Y8BdS^(mGf_20a<KCg6e9+jC^Ag! zp!@3^2k2+EFvv<n{a1$jBLk`;Fx`A*S(j<@yz<5QOI#t~I`6sUc%3`(8#k>;3U$sY zHycxQQAxggkn;iOo8dF*&nDx9pA@slSGC6HWWXvt>3Wv*u81iHLd*wKA=+LU<<DUb zJQnQG&5tN-qL7L+l_iHWDNYSe<Ip^Nvzn#6Nrw2ONcyRvBx6o`32KDaHjPn*UZ#kQ z0kFIL=KJF3qK@%AgbzA3$f>tmnnCIGPQ-0}IE=3&XQdhQ4^J1=r{~v<4l%@Bg=e3O zXs==Eqh?a_eP?Zbl>&s%QvOa6KIT=YrR4O9NAqRpThc@Hl!x2L@IbOFs&-HO0y5~~ zK~izm4vUiUX|GSB$K_8~`px@kxBoRLnzKLd6F07H=sGktPIoeD6y^YSQf88BJ&}`F z&6s9+@B)YQQDctc!9r`Pkr2K7GLMwl=6g~fjY`BVm4ftm0YEsnc>4+L=lVki#k6|d z!0T=fBWm7fm8ZdkF6gb_T`<wGH-BYuNJyGtx69rj&5Ti}%P0=u0p3R(^k9<B*wU<5 z6jbk+J^9A2m9fN(!3xb6N5|*G1~MMG%fr?y$BT1wda&SD<F1;hrefbNBENBc>4S%# zp0aJ6Hr}r%-9+it(yxjSD8iDJ+?7%oH}xcxPVL|GYk+3zn3bXK%zDr*57ez-(90)G zyeR0;m<i(n+cKh%hA#cDKL>VBts1XuA)s}Z<)UUM>}!S`Q6I+k$6Qwr0pJmo4N0f< zF2BBur}E(LWY}(8+hrA_K%Fv2WBPUSLLT;h5A%e`nhp1Panl2CrIun7mFUuw>=u=s z_QW<Tt8qc!99Xgi@bf`dFgHDzdQeR>+VI5B8U9@~(i29ZJ+sl&_x%VKo4Ii9_$=(u z^zqPoi(@DETz|HcjIe8b$JBn?yM+`XG4883#m)UhP<is0vfN5C>;^w{-Xq0nX~Ibu z7Vz4>bpX{8m>zeOS}crlQ>Z~xC|4k~)o4l@7^Kbx3umS2IWJcqfzJD-X9jW@+25`! zZ5kMy_v=^G%czJ6g6+-I7tvCW_*a@P!U{O7h*7nI6)E$t?3}rjB*ai@y7Uw>%)PC! zl40V}136**InRm2aX7uaC3`U_U2=S}%Kbu}@XI=3A+;^h^Nl&Ah6{tW;EUI_086@I z*#o<@A-m3G3s%~2k;=n1IzqrPfxJ))SOJt28+TQq3hE5R#{ItriQ`uju1ELA$uI_c z$_^qW&jdtdfBiDcjZ<xg!FYIA#k4wVruo-m%^siiSy=zh_zDwa)!G~B0*mgI8-CqY zedOS>1TkEtGiK=DT5fs{Bx~;^Uq%c(ZeOcTTi{u1i~pGXG!*7e$S)SIz2p97hwA2a z!edo|jtrLEpMlvosQ;SrXxUjR);T9S$HET*ZXYy~cuxbuiPcMPo}BchLQXBN!rvH` znkcOb0pm9jFaO(qI)s9M4_Lo*Rjt4{k!rtk((7$5<<KZ!x;&`bG%n_A<@Q}5#cc_q z=MMSU<k8aOA+fgAf}MYGcAj`9A;9BNL#Y#hIxXOsaa3py9H(JEhr`Tx5p|`8cGnC4 zCAn4~dA=MXhzHXD>7AMmN-<&w|I1KS6CE+zcTeF`!Zbpe(NOEeYKtz%>hWqF?vxXX z?S7xwxi4>@Pq3X=qHB5=;3w}VgI_Y#(2oKz)h2YKFx}IU+kNha8%6Wc<&r>yoJ8%Y zQRAqREq&w`%!nWMk@ltzxL1PW4$OV=gr6++Ypt%7gZk&5p-d7rE!~TX>c`21+0u88 zP9UQYUH0S`-+dCHH*buy@da^+QAG2ky$kf{J0PvQA<HEfwI08H6tV1kHzYYIn9lLc zyNT+iV7$l^O!ppKr&7)${%K(f%G~jN){~bD)-28)KU=6C6mr!`nTgAm)AePz3Z92L zJd7>)E2r2np?BAQ+wvk^y+F4vZM3REj&*;hdT^uGeeEM^*HHZO7eE{Htsx)TtWQZk zP|SvnQp<q*EK+a(=Va5rJeCSN_x<^<JA1MwKyxfrsJ2&&<?<h#rMv&waNeqG0=jm; z*%Wi?R|{7>av5FHr29Vfj3v@<alw>|TOX%1!lKhl_EPXDaDYl(rRL?W!NP5z*n1Fc z+cR6MvoR5FEIR6L)~W<^f*CJ=8e9viA5Xo3wanI=_t(XI0VIpFW~#7Br)|4Lt<+b| z=oH)jNiBNLm#01RLDL8F@)B<kf~pyu-44g+-v94`m0m+~n^<W=74PInt?R!au1gRz z;rl42q4Qwy+M_FV*r#m-J~yzgyLfLk)`8Fe<O6!C+I@K=&%Bq?b-w1EraY`d(X}be zPNF5a*JJHUa65JDVts^26U61&>}*L{ij8k#QP~Rox^q3l<0p5D#vqsj_P)CH%HMmT z^}urOSvrFGunzyMDfd!!&&(xfdgMH}69eMN*gu;f4NK?nu@@;j$K9cY61!>S7GD-4 zd*TQZHr3@7c+*r&gvTu>SKUnX0q%TlRFUZp)w%!^w}UYpdG1n|Ww>GYLMxZIovM8$ z>zlv=U|<tMvt&n1-XPT3yPxK4FFx))d;72Ub?D$rEsxKIWvE}OfXaQ7Ulz~z-&f-^ zkGCPW*47*vAS3o93;%GN`>;7?T{V@JC|Sv1@KxhKc?>)0lfDeTa{4pw8_ogSnMeN> zKkuhOpBgoN520z6)RntKgBn&Z??8NXWWLRCmzGUx^gtBemn_}OKc4oxz5$7U2>zI` z&TervyaXn0G+ym1s(`;FeQwIYR`(3g^ZxJ3vDz02jp#DXR+bbk<4ey+o_K!f3h{c3 zI$r^!KCm(yU-#u{f9f$ACi&GBNG29>-<YLexYl^#CB!x=5oi64!}Le^<F64$u(Zf? zz?>eR=ey^gbV^lCoHG6TOY{0;o#bncay1QF4)}?{2Mn^NUoADofBm_OuwLr<peIeR zQk(~7eg#jNlQQML(d>i%5D@q`!g)PeHwvsT8GV0@(J6p&TV(Oa!AP6?A)+A$P}<Ap zN8l^zgwm(g4Hqt%icKgTn6*c<>XJT0_TN5lEa@WglqE)Hb!-f-dRYYuc8vMhV+OcG zFWa{{^*~O}fXdpip9c}eaaX9PleE{99U8=35WDx4|EmirsKWaL2ssBfT9Fa#pC)YZ z!L_qSuyYq+T3a(D^x-2QGrwPM{8jaxXOVDIS>CU#4P%%2?{SZQRriWYnY;z<`sQCd z9`!JO{n#v7(>*zd4OlqV{x8pNhhZNtX8^NPrbnKqpAiYEE~QlaZW_7<*Dn1WhXP`n zq=1iq7}Q+578Fed>W&&pfE3|Cv{uIwqnS8~3>}rqA-W)k)Xg+%nX1neAgmtw$wAcY zX%Y+GL1k$q{;}i1rl!iJ5toNiyC!5TRS|d?!2+y=Vdtw1bEM3hB5=>@Ebb7q<gWS; z#etRW!K?rW4I@|&j1xnqisRj~7tp1GgSXEE08&8%fgB=%B?zL99QeBUTj#QVlR|7v z?Z`eX4D!`|vKN!uBpwr3rgmxI6S(i~beYj83@7Jo=uoEY<cCk-$Ev6S#n8lFSAXjg zbLR(ZNyjjlO~d=ONB;xyD8=dQ*UCc|e1C0M2`0J?!ui$fP-4~Bl_dL0uQ4!HG!UPx zbLeyY6X?uiQFcyXbCU|;O*+NvHR?54H-lbOC>zgWRHX1Thz%^LJe3K3Rug4#7xWdi zO|>&4_~A6uR5ZSSxFS|8Y^gH!RKgPfIY=j!%HznDJYwksj~K-V+n>nJ0cX28RN^=p z;R4lVx?D3v8k&&n0h)>FE=#LqELs*K765J&M5-4<)KV`^lQ1YN5di^4+-S{#p<*{M zXlBAi?6D#!lXcL_r5%<TilS-`^|!8VmYu$M;zO4rOi4f_08d1xEg{yuyV?bOtmui5 zfqbtuHr-@FVE|J8W#Q=e$i>^Y4bD1Pl9=`e6rra_OeFD##4~%ZV~>b=FQ!hSG3x1H zalk!t+j61O<Ap9$xfq(-)creB70vBaVMhdlmQBsDorlOU*;I*_KlKEB2ctQKa3y(V zgEY?|Tm?Q~%&mcNXu)bBd6&2Apy-J}Q>KpZeBpq*CmDNls6^C~MgF@z1q<0S6U|Zh zRvO^f^<&XojU_g4<bi&Im|_GkDZ}%&MeRf%m5X&S>qphi_DP6Hv?am?U7Oqq*vm@* zORVcqalzN~iiCAm)_dga!yXC3uI&lI^{cH3bxL0SdyVRB(g76cK2|9}ct7yB;eScd zh0^>QRX}%4e)W-Z%>-Lq3R46gFingfuUO@Iev0;Av%Zz4@Ek=nkmy+-FQ(-3+z<rs zkbOFBBr*kNbZjO7Z#H}{pwm9yYXtH`;EGvQlz|u?C3$9c(F-zmntjW@Vc^#1CB+=? zANJ&jO)i#Z8X}ktY7ao;RC+vXWr~Xb<jJXYjfWhQR#YN6aCj;^a30~zGMBU&&)xZe zkoWNWg9)h1nit``YfS`!m@pd_eJ{=R%rJ1I<|F5tl%V-hZuv&xkl=N$Agbr6;wN`b zwSjx6AnR9O{5_FxL`YFR)Z0oYW*dj;O(_$T7u$93hj^gJsSva~VI$ulR~o=Of*i6> za0if+!RRG&v~w3!N;+Y297|G9!(jFs;!!P9n@FC#(Jg%hcap6ODoOo@haTIAtlEJp zy9rb4as0Nt8<RRJy|B)i;M`^h^;@S#ZRoMHk`so+B$b#E={Ddi#yF5T??+#wy8ddE z0*bu@ss_H#4~BtROyOf{244k8hOZ|#@H_U%Z!9R~vl<jPsMWv^m&xnZ8F$vf_Oc%Q zxrlBARQ+a>?5co_@KK+q;Hf&3%hQ!e=27zLiuS=8_6tHCtq|-Qjf1gh?vvdwt(xIi z$Yf#Uq=5$ciVY}4LGMfRNPdE^PT@!Rx4h##FdoCM#sSor@)a!(%V<<SqO)@d9QcdK z8@{w?NY6tJSQ(14hr%7(c}@PlS|Qsr^T+XUt^OWJuru$|27CyL!^Mk`WW;Hkl#amr z<>cdkG!i4`N=0Aq;196o=Wges%zM)4a6g2g0O_(2q3|i7eJ@_&gAyoyn1|CU-Q>2l zeyKPGc~<yB@kxvoM1kM}mM^&U9?%VYlUsuKIWKjz*!919t*FRUtu~tz>{?n9U!!r_ z&JhJY&8-IVi_EjDib}`g<Kck}(5VxG$CBv=MNvwyy)?O8fUs@SCUTGdX-DdHBTh$t zx8!SFFa@+xbHO7z*=vurQ37^6svMlhX11Cj6nF-E(yl;q{QA-aVv)4$>bq!GvvJGV zL_WZ&LLu_74QtZykt%#mus%XQE}KL$Q|vYX7(8i$NHf!<#b-PJN%gi=%E;RoEx!%3 z)j5WfCF4R160M4^abwb`f{w_yNKEO}x6(1IJT|=sK|!CZim|W$pm{$b0X3CXgwg`D z8Ud>noEHS(ZxzL^wuZ%P3Sn6A>8LLwtsft-=Pm9&D-i~DJ`9obDSG8lw;qlaEItk7 zPi5*(ZwNm;O1>nrv&_aj{Llh@U%@_}!!1QXP%J_@D?mX!${y3DVu~hwF&%$*;`qJP zNV(d~_lTYuF!)Z6-Q$?kG&c{zaqHY?mH*1c=%pAt*_BQi5k=;5#gd1t!|c6OeOX)k zrA@A+s2%xi-!1JY(W?6`>~=O3Cn3?K&;<q1EWAqbc(WBnV^=YYoif;9Rpo=prsW#8 zJzJ3ZDWhyWBC3)Hd+RSEdu!nBN>iU~qw5iKVgQ0=X8Q476B#j^_m3K>EA3Og&@8Eb zF~dmcz0=kiIeS7K;oT&$Y40UA1SfI`zkV(QQ|bbwsXeRv$?Fl}!99TuZ7AFHD>3VQ z*4^AJuJUSkXO<)@=W3!-_7Z2Gc2V$t>$;4+N2y(FLR;@`?SX;>Vjir$3-qgjK!?-Z z`MeF!@!fF--#kt$bydn|Gjv3d>mKbbwYA4YkuD|Y?fRcU{k>lt;itFBE`di_U(8SZ zv<t#v+`f5_J4yLD7x4Ur-a9qr8iJYcn_^%Y<%tEE+<gKKV2xWpzHUn3CI}fE|41ct z)VPJg#0!K@3(pI-Mc%*8pXGJ-<E<ZLA(cv-<lnQIRWiK<erYe6flYzdL9qPVUfPer zxOZVW>e)^UAYk#@*eiKlr|0+;VkdZ=_4IgNx&<Op2(vNB6<njh8u|t=p@UI!7gG~^ zs;CbA<|jr`o`|4UP-IH01;lozZr400xHx(*mn^z~&xmdzu7%&Z9`HI8$@eJm9;jCt zumL|QKF;(wbNz<+U`B#8u#H8Y#542o=0YQN`O5RiQSs&wPUl?VE%AH}<@L05$JU95 zj4O1}E&G`8*gzE4?#hZw-Vd$wRh(`0Xa9S%%9Aj+4hokXf1MigRbZtEJu@A|a+_e! zXSpMIAVRvLX%a6$K7I39JJ+l^9PFRW+T`b!x|*bdV2T~F`rXPSWV#T<IZreOuhVY- z>I8qNy_Gp|N50=4<xZ@4?#4AM)-m{;jDJR5eSzN*vRoa?+@9-(zhadm_X)p{;o=@2 zxwBU~e-uwyQZ!RZx<!PHSZ2Bt7>uRG8T)z8{2rokA2X&yMD|43=g#_fX<f9-_S|2C zW2*+LC7i(kyWK&8-M-sdV#@Myk}^lR=KEwq15YS{%Xc~9@!ur#%!*iF2gO!abPbW{ z@S0q>P6k`UB2CDP8Nw-Og`PL^G-d`eL9~h)+O~lcEclv>0OkO${)^nQkgaLz>|ZCz zl_~=JjEacUyztVgFpC8^7%j(nE5fa|HbH6qMDH|fX73TQG^|KsN*@ldU^k`8-L2g> zcN>lVgl_H(<_I$rB>IQs`R8$k)wn9pGsUxMhpwjmX5_#NWOfn4b_t8*I{E0in?O>& zND`)UDx?v9OJi7h&TzzeLyd^=4SFejQJUX%iPf(d@|<<=FG<kV3!G<r9ObepXq%MD z1s0B}UK@NWH~dO&_)bj&Umn%O({iCtq5KT9=5W{p_$@&=WRM5h|HmTgq+%s4;b!W~ zty+XqvvNcwvF_lislwg_EXKOdzCs`UAI)CHyT*XdAQ!(@3c9%6^5RdZmv)N9&hVO? zdxH29i!A?yI~;r{VC$yfV#a*izGrOpcTJz0ocCWDmk3xIGP5zXNYyxnvdvLh;iTFR ziO0FiI9?pV%Cy3hJU!7~jvIE37MK5<ykHOBbNAW33b(s~77mlzZD!({S>;MMMD-JJ zeViWHnel#aXQu4!n+ELm!><Rb$$PH$gLC?87{ZZLrhSsMK*DjAP0~Dr=ZQ$t0^-sw z_NP03&+lv4p~ScD!*gJLS-u2WD{Pe#e{RHYuuK<8E9{b0V3lw-8=<i7OkRRKsbZ%m z17%|J1}mx)Z!M$Y5V%<%+w(+!N#X=bv6fe;Kj}%x9OC(Ri7-vsJ|t{#k<k5xTEDj3 z2WnC8IPP|qd#<zcO|vM^CG62keg(br6wi=y%uT-MXeb9+5diNdp<|d+xSDObX@U@g z_)uRGu(=>>wxjj-a?T3Jouk2^x;eh>S9sdU*9rJzWb)5X+jy0oBLFxrNc#4xD#VBQ zecSlAs?TF#88OZG)FfXUcCyMe%Y|G)I&U(#64#tne@qCRiz%(Q%&gO`V#SqiNjDG4 zxF<Y}n>|fJ5q5n0K8;-e?OT~LuEydXyl|78MmW1>rio4t9)cVKv^EJRa!>8RQi1{i zIhlT^`U{k+kt4JHqa2p6WfwPakI2Xxl4;X1Q5ZspL&nMqRXAO@?isG%zT5Z&4(nd0 z=Ag`4QptNaq!pyV9K`Pk(`JjwN3N!{_!)R|C3pj`fK~ea)>(fc68uitbNALb@wH8^ zz!E{OH7{1@(k1Q-q8mh%e!@~5&MMdTw_hVv!0=`lsbAl`wukcs&?f|Dl>?{T=N;jJ z*tJP1gyiB0(=YM9Bgcy5EB{cyIywO=dYmufah^!*CQb$j8VxX<>QN~QX1VoWSUp#> z(qE*1?I*-0HCmQd2o+!Ul_Fob&W-Egl<Oym@z2Y^hvRHX=0Qd|SXZWKi;ei$KLIcb znS}bh&RMqD$xq(4zng_1O&~5G(xyibr^J(psh*zwj#W|Rj3p(=-dsZRG~uAMMbJ~K zIl3-}pA-}2<J;#Dsww(sT>%GX6?J6=yE0|^w;8-6QWRXFWYDH0xt({|i3{@eYykOY zGGhsCwa7k)3a%7rAtU^6MPU@8GV5Qk?!=hE{4c^RsCNZMb{&%r8XB9b7)2~OO-=r* zyu+C@pXn(zUtEVRdZ$j)5{@4ZzZu@}UH=y-Q#&;je6LH+-4OTXn<V)ZWa#*LQI#zx zA%t*+m%QIeGW<M#z`>m#1(&sne>q9C?;QKZ4gMH2URIYN-v5!zoBY{d>MJj}<;K=) zTbQZn@ad!bdmmW*iKsq(m`q@xslsIT_(+!7tOMaIXv>YP(vl}g68!6$``L-Go|z%; zKBqZyAUk!stIS@2AgbfpckAnzz2{g%^Oc%=je93%5!RJ_*U36x!ups0%2U_UX6*&R zdG@eBNo?T03|SkdOvDL!HsOTE-fF@+W@0fxGd()QfQ16i+b3VN|BBy6(Ig>PxWU4E z&g;)T2VI&8I$zxc-yc_ARZ4AT?VDgq7hb{k6YYIGCq_OC#?&=5`A5m7C@CPp4%lUG z$d`9}bo#rxPj}y|to);o0pGZQIHFMV5N|-LnM0Bb_{AH<ZGqS@({*=e5pW*w2#q&s zuadtD;YR)xpAdOKrQLt)KHDbIoQj%|YjEOt%9N{-0BE1cQI(cAgE=|Fcl|D+mWEz_ z;6-nR4orUjymnvN4&358{5N`bM$4RBT5$i2^BY4ilw|3UU=rxZi^N9<r>h^NA0e$v z+j$(5e)?vtZy*vQ=S(G5b)Kpb7TZ%BgcQd^6?$0}=UP^9#*@*bD&4rd>5_LHsCsRF z6Y0%lBt-Ku&$0a@9!vLdExXBU`eozbdpa9_lKpp`tcYSC*}uuT6R4qQV#DH=ot>jY z2^|RZzKbbE{wf??P#)TO21oPxLe+5({dD)C2vokIqW;nC=tp9NJ1&Iqw0a6fY(1g5 z_N!H3?l-DNJ$(2P?*tC4`lngu+1^Ya_+GXl5oJR_VOKCzCMJ$AC;zFjcEdMYRZ}rV zJx5a5A)p`%{yHCV`{J;9H<)1=L@u135C)%zUJcQop?*7%9}gAPV9Jjt$oKO-I`_?} zkL_E(>&uNSaS@Wrv#HFMm!yiZXNQZSkO_ZiwM>g?TybZ%Yl1*WyiTvCtWc86u+7_2 z^(^*V$1d_;puk{ggSzD>cT+6RN&{zwUGwB*J5!bLXE!V&vCf0~0DVWo+Eha&L(38z zZqUjq+jL)RGsN#tn6mOn%gU#Pot9d-LblW^a~~qcnJKp2i0S!`iQs$3zw~ymi@ZH| z1*FZ)W``qx#?8FNFFKHEBcTQX88%8IAAAOT56ET~k*g1C1;?s;?}&E~NjH@Eylf(y zs#{Ss{)^E*u{nrNGsP;zC$D<{Crh?{y6b3CMnI&v+g$i=L(Jg}mOTtYDI}bF7rv>; ztg^8Xb-Mdh;V13<eOJC=Z~zZPXhg^?n57B=khrV1=NJ-QiQJ_rLPp3=_}{{i)xgQ) zI(zLI$%#L=*3jL<k(aCLmzcb@&f}8F(b`XuBRozkI)tNL-So_w!>F8>mt`nSdUc(& zJ<;{>TJPKlTAb;jt&-I`g6HolINf|PS29i{iEHrr_rYq*4)qMu5jDcpbhq01)V<W^ zlb>azG)dd9xR=}O2bs|wqoH~8baG!C>y!s`jIsK=rPx+Ec}++7LamIfZh4k^)*VOi zf#giQF%hGXAhg7S`OA*Mxkh4t;n{oY<iA9~y9xbLfO!0ui%IlF4JeNYVQ(2P-r!ie zU+dII=D+EDYUG^sNOjqk?HwZ08G-AVe)g$#C!)H-N7HiHAANe_mnW-eyV3FLhb!Og zlls5gJg}rkxi?m!uT(yJk2$1jI1+?3VsbuF=PhEiu1;lY^!5mSj6+@{A5DP2x?10i zF|CO?we96>4`x5Ewt~--b7j#sL(E~xOvirF6z>t~1M3ck@<-yw>qRlUzgtd?*gLBC z>u^~H>Z?RHn~VHr*v4XX5-|M)flu9JQcTZbtqC8g=Sjc7t5r4J(EW>~SzR_@=eaA6 z%vz^W>zWj<4Dm?FUdT-te87rjbXn&f*=(PA?=Uo#h5obKdo%cKOz_z=f+ZNv(J)a` zC8yjqk`;zTtbP?Qv_n8mhjnY`Z%8;aU5*j43$*I^v-(s5g87UeA3Qcal}z6mAm_$f z)sUO+eDkP3d2|!^@(9zvxIJdW{7Y-U8x|)2^j^v*KU0USILxhdTc1AoZRP#XF|rf4 z*=*0FQb!-CjD3dj;Kt~%PDQhP)Sf(R)VTgrqvsSveEOj!kR%9zI0QAK5FW&2P7$q$ zBZMa@oeyW*5ry0`IAy>t>rnc3T`<9oJsT&zKPyR3gUZV7umhNcd<+Z2W}k1!q6XmK zZU4Y`0jP)Ot4)SHmrF3==nE@SMa$QBEkxu&2A|8@w?fajlxpA%Y#?LjG|s^A^%iGd zaxaovt!m@LSjGqZ5WE<pY*vY;{7YA=NU3sbIN?;3xHfP+3)c^ShcU>d+TlCnM8Yr4 zROntwv78&jW8iJ5RViLzBHmM2%(;0ldn5ijf|XUp7qt<uz@nhGL%B5C1sGOJ9hM-P ztgE9WHL?8o<@kjnwNBUT-)fa|T+hCRtv|mzO*&O2b57;5V`3S!{Q{-&9llKMCp5dG zE<>866wTBAnW~jKNehI(fUgiyi6$R2hoBO12qwGoq!C&KIO&|A0AVgPj@yKaTI>;K zhXbQJJDo{801CeXZx2GOMvD0&OKv27$Txi<MdrI>EAp1_+pP6??=IXEhQpu_=mO0u zEGS;HVGvC~Mw-<Ww=2w>kJ?!<xpMX=f_^+z7r!Yzo=08;bLVR}>1^kce&}tV7dcj^ z)FvXNecMLa<*Elke2yV74z9EO^CW?Rv~mQyzXwVT*kPfe;8va}EVpATYSBi19(7)% zN*WLRI|50+aZgCQ7az6=F4AfOXt@@poMHS*;XXV6XYIYBnu@!A-IWj^kdQ(`Z%OD? zdb5QddJ#m52#5-bNS7vt(2I}&(m_B#x_}fZVn9H;G_fJllqy|BMLE3hcX9SOXOFRO z_Fb-$H8RFpYyO`(=krT<3YC?pj?UXP8hBD{-^<}x>B@+`L{*-~OCx`C;7>&>Z>8l; zNs)%57Ag%>=UjiAj__W4$Y2H_XqNhvfBhIBi1{N1L3vN=r=wLOK{11zf4Sz!jLpN^ z0!$0;xRf03ejOw%2M);Y3y@SW!i&$GI2Q9qtfN`+Novv7Dl5ZLaz4^&#^4H9gw+)I z7*j)FUT82b3KQMJSvPi&BrOE%7ie1mb(&NbC`Qt}(z3x$&T~JvA{#B$YCPjJsa!sz zyH9=0dYV<Mr#XPR&98`KzWi?eIhZEeI+`5<z$Ezvvo_nlcm5&p`EP@u#?0MVLOe^( z`yPs}sb?Vvv!Y4qIY<6axS3A5{=P_O`=-Kn=%C2g=gN4|2U3E;x@k?C1CkC4!+Q-l z`~yuRiRp@y34nZCo?9Fy)6kNGNXi4~4Z!Kf<seEOqf(I<a^eX0Wy-Tcv}=ERolWaf zLOt%|+-G6>Ssw5d-3&xz1L9ygd_c;X?%clzpM@@20m{0re<{jmp$jb_+;K;fC7Y3C zC<YCmKCulbDWtHcmqS7Y>zOhFv@sj;ynwQ0*S?#yZF@-0x|1!|3UUXBbBr4$k<xAY z7uYV7871JwN|6#ZI5kYs&h_gBPuOm#Ln@ph0#;36u^zQQ*%$IUw#ClDd(J}!(mdN@ zsaUopk$KD%v4Jibc?R#YdYW=H`%dqaS-H^P!`Iw@cJ!hzCFn4A5wwSGQTL*^yn%jh zoh3c$>85pjrxt0zzaJvK6vv*A!9c{-l_<Cr;~tElIc2#UHMo79g=a|EJ)pfv;=8R# zlFJUib^;rMg)k@#-D73vKg+8t@9WBvhw_OV6F{qxaSqxYcaN!|8oIFZiUneIISLom zm(+zV(;hrT1oH0*>}AFB;Pp^O0uXOc<+wSf?&t)NGf{#-lI2(^J}nm|`lMu>2v=wE zlaj|oY-@8tX(x&07O~7ch~0w4Jh*BJ=~Za|rNEyhC@HrXW}bq~xSx&DaqM!}z{CMJ z!l(}cT#T}L*T$*<JsZ>o3p|<4OMk9@w)KR{yCs#ENSHcR?%aX!Jcx<;Fp;sqAT+4^ zT7Jm|5eyd=*zSLQdeFV^5bx#!8~^gJvK2)`KoB!Bq=Ex-WnBM2(F<BiHeE$U%zr+g zH66ChYDM}X0kN%8f@xiS*Y&LffqfFx+i*!8+j6Y!W~-|SZI-xX8yWN#SCeD^+^dHg zhbTd{Nb2hC(VOI;l*eYDxdALQ(35AH3|Kg5cNU)drzi42?(GKGEA^DSb2<Xw;|xxd zVB}lni$V;m6<o5)l2N)!_&blqdOuE|57j8CPceoHvZTh98wH4EtVC5$%f~{QeEob} z%&SmVU5y>p0lYFsj>3v#$b$rN+O~G)geH1*`U2@T2;<Z$+GN?M>sY0T)8a&rQ#ssF z91j_Q%DHHrBM>sknP#vYZQXd*5+616l^Bz74xk@E`Gdb*=h^7I3y=kR0P>lW=M*b) zNeCHOfmB_fYCqh<i%Is&rX-+0g?S$913`E0v0iFABU1#+B%7Ox(Z-^vY6YGOakWy# zZz8HAQ0AJ^1c8Pwc(G^zw#P?z(-%X^tGM~q^=ZOq<1BizX@;E~L1?=!_UsaulMm5E z))?MP<ak()G=_3UhMaiBxkon>>$H|!=Hbhc+D=C%TAX?MCN*e)39&<7P)7m6x=w9P z!T=bi7)94jp_M1*0;o8W$-)He0ZbCs?RZzU1!st8BA%{jGbg)ZYge?nEPPmYEz}6| zk6jR44Q`R{$zmf8ckWaS^GTojXnh~(5t@O-{!$ElX=XxuWTqH{G4;VC+P`QW9eh*2 z66##RNIokflahm2;@v-fzIXG7C+bAw0L>PF7IOLKP}0jwaMwr`OJA++TvNs|C#}Vw z>`)CE7X*zQr7@Dt1--pa&;~`H$n*@K;iB61{b9lA--4;KOTmj9Duh~3al5v4>w8oN z{V&wi(<|=?4`utwlD<*6!$Rii3=pjD@}6!lwtEZL=l-iJg>u9o<bCdEDL~&0<XVD> zf^|Cn`nyLetCDH$zB>GP7HJtgDgqdNj!3<g>&*+~Emo$Y8)~!(9sOlaBIZyKVBzeF z)r~M?MrO-SMOZCd>5aSW1(xej?$Ph;G`-EV8+(r134w6b$!w9l^GUG8bxE3ZD*hZ* zmSFNtw(!?6bNEfaH%icDpqyEr$!fWPfy{q6wk`jY|9pnM*eU=pl(YWL36bPjW6l=U zhGN7GE_EYpoU=tIM9hYH!ivJ+?Ja^)OXiN<tbXpiA#}H&E8o`qVMRZ_Nu3jmW-qyU zPPhNgomUQ#?r(;I4kNcMlhubBX?O>bI5y4W;6LZfvwi@~Yxe|^#}3a01w92Ra#@$0 z-vC4_ZH5Qn8|9qE2Pp6wTt{`SzakYH4+Wb+uA-0J*{6D1Law6aZoF{o-Xc&;c-`1$ ziLa+9jN`Q))myF2$eSBCfAKDed4I=IuD)Y}0*5-q{%^o6+Mxh2d@#4R;>_lI3NQEy zCwE*$XkPgmM*ql4fT#i+n_K_7CGgIycxS1mnIge{5HK|_xLqVT1rnG*32byd%NQti zE^Gpv?})f+&E4_VzSeWNgyT*08GUnkZXL`ci>ADReWRn5srquvN8RR*Hz`{<O01wZ z(`N!{!9!NW%we!rslQ~4UHj<3wAc4BuFPv2Wh&YUM{WWvnPj%<!X0jHc)HxKj1DUs z<y#$!OT3#6R4BA9BlK+^HW|S`rX{dlly%ZG+`%`cdT?EqLV$3}>e~M_mvo@rpEtM7 z>sFiL-#Lz%@s7InP;f8%Jn}?Y$%!{BULHRv7xS{PoCeDVJ-Oz{NMWTgiXOXeJTLvD zcq4r@>S=#GUP>JMRumt2$|)lby2!|q*biGFR<JI(8ZE)D)9{c7xH1K0c{iLh`CFwt z*Lg+!6rTU2&bE;j`VHd7n+U|z3l44zF`>#_t;Aa8N0qHgp@f_>ORu2CAknQH-UU2Q zB7&p`y?YCV>O!|UvjB7iZVfeCh3_#Jn;SsCSuga0*D?`M&?0}|9zwc7tDx)6g<_kJ zmgGWlwK-k2+F@0=l_)^sxO!FMvJXqgNqeGvcyP|u?agi6w^uR~xJ#A)h^g`du8mCH z0!$QvDG)GLBpNA~?P`>rV+otz09e4#k{w*xcY+Bad9WJqeylU@3PBw@vpLJ4&*{rD zrXCSdFXX(6*jL2NEM%4`s>1d5)rBx%&h4YlMz~*WV1K^n1Dg#>>#zuOL=|3JUv2lh zUcxTU+EPM55wSu%yjd}JXmy&aSedg&M|}?$zKX;33d1lWO(V<L1%B=e`-A;lC(E$& z@>Y&RcT_KkGrNk980=a-ZiX*7ZHnqqeCq*#pP7P$;L)|o$Xz1J`q{Wd>>Bly2CP_0 zTsuA7@7FG!wYwH$C3f<8<6sAu>{oP#whr9EAzkVKm@k>l{4f#6pNdGWWX*79drx0w zTKMpL51*8bKm3Y=j-9!kEXGqjx|W3Ni_?xe-rvhg$H`%MIlzfB6Jaq4B0>8~!d19* z6h6unHCq_h2B3MZeRX$mClMI3%PM~Ir+U7!N*DWoD?WR3Oe@DzjJH@NG?IC8caT(n zQVrv=2E#oY$_j&QL_b1cD()j3FQO-$JAljcCoK+hF)s*Cq~X)kxk7iiauv?O7Dkkx z;W(M(wPal33*x4(r+zJ|P#TcTgqMI8Dx(m}6oCXz9Pf~n0xLIMI@xT0OW)9M7K_i2 zmJ@lPwng!CpH$3BOgV=>3Mb*is`SIX>oiA`frmtxHn?R9zub#gsFb_lW`kb1z2Pm+ z6M!fC<5bCV+n!c_<7KR1!*|CZz=~ar8SE6h4=_)jlkCo!7Q>@B@ViyWPV2+jIV7Y= z88mnP-&H-E^g#)6b8#%5v^{OKzs^m_my$&(M%c+Npa*n+ow3xuTZ6Mt69vOk&eiH6 z7i4J<@VIs58(*FJ3-K`tyPPV*{jyGHw*;|ZLy+^2@Mhd^6&*Rf%PiWKU-U)tP{2YB zKBfV;Uxhp%LMzEb?hH0&U(J!-;}XopigNga;-_-W>qddNtS4%FJNQjX>m18%A@H@( zF_mDH6pL_%6X*38<G79|PGDPw_kckrnZrl*CI)<yt=QtdOd?|8i5p;bYmEEB^uOIM zLBQFGV?n@a!Z+nO@E<ogQMs28%D##ycJxbk_(O+f6tWtbiB3J;=2!KFRE-BUwH)j- z3{89TbqjI1Mr=MNg#RQ=SGnF@WM<QrwViTlvQcj3&_@!yMH9V0%qiIagmn<%qi_P& z20t~zc|KGAI6?p@6p%B)&t3=v0UodgsJ@O1yxZj*Tx3^#gk8Ib^>#7>j5M2M{YOT0 zcp~|qoJ1hlf^MzlVB%I(?J*QFURs|_*I6_D2?EHDrM7Qr+Eth^C<d0wPSb10E_Ha~ zp2zC>nzQ`8TT<N;P+!P8ii49D#Q9L?*%rb%_3zQ|;zU|t@811WyzAF87Ax)gKs_z| zNd>;(_yG>_n$0t%e$$!7+xf&V9J(v*^cz4zFV#C{;66qNKVm=0Vt$x#*G7h0Y>vT> zL5p3+1+8-Nws?2!+5yi09qytbzfiZ{8tHobjvP|k8mDuZHy8cN*@vYYv3%V_Woe{f zyf5Z(ucsVOL7cnKDJWQc?gDEjH^IhI<n}jFg#A1I)*E`H-h^v9iEIRZmmU|N$3Lm> zY{ydxE3eQ57qmzX`vh74=CEQ27w*G)kYDCIR_)@6Qtah@od3FP>E4~M?#Tx&Jpd!T zpYDBO5f8nFKSO{*l)_-zRsuY*PhC!I-8b%YrsNEW@pT(;Eby{`jaz(h?{SD}fH~pV zS-(P6UmWH1JOhtANEE{2m)!Cu_Q!R{REnbHX8}9m2-CI5-uI2BLiWsjyxWf2g&0ck z&VxWpo^d1f>*tM(h1W9>2B-36IbS=o<jsk5bmyRX@J?HXr}kvqKIG1C2#E3EH}Tom zKU#`tv*gUNY~Juv*Ms4{DT{qG!td^|KVglc!^(mzIBuldiion0=wZK``}|0LgEbc@ zz8j(QcuD8f!9vSmbhQdY;p<C<-w!LFRpYY~aPUZDS|!dG8`eXFr*6VB>|vFKRE^%y zXXW9=Q#gb-LyueDjgV(zlWZ5NxL^do_&`C#r!#w6q?416mjWR?$H&~Lndz7kCM7nz zSsD;cXI+@{OkI2Yr>cI9l%k~R02()W5@3GcxLOCrP^4=gob4$jl5~|XBD*E{rRrLT zrRc)%$H)M@S(J)M>WRXa1ri(vcU7#;#;b#~_$h!WUp-$n350WhrKK3`b1&PU!5#7J zR1Xey-TDo)lvxR!QwMtD4Cx09M2B8FKaO$<B>()C%c`x04f-->T`3h(xfG;CDQDIZ zO9JJMlXLI9swZbBgt`i=y07A&rG;L2mGj*B<VJ&Lq~g!X<fl28YX7t}32WD~%4Px! zZD_$&Ov+@rjCfk#G(ekGKUw!KKVzY&FuAcr0l<k97V#safJBr&?r=C=iGR-<ANcmA zsB1HiTT7_7Ii^_SPx>}?;qt#H)&;dV+)$^^NAKC&BKlD<bw}93Cww6;pXQvX{g`<T zX+<I@?yL0rq06@6WpS3D_&<~}yD}oS^Zu5FXH2_rmMCv*<MM7d+U+RF#dw#h>F@Aq z;yYBYvpoJW@*+dYtw+*)fOl$0GX#2M5^JYduQJrc-)+b((aK_pzp5e;lQY7v)l7sY zIl}@uOLOM>^5b!yyB*BMsmDj7=kHvR{o!;rAdaEu3X`_5Mzz(f+C5KoJh50@Pxqh` zVD<*!9ptfw$xh_S{@jfU-Aj+JESbS~2e}>bGgU1Dgog{q`BOp^*~=M;zXBb&hK9f; zL)QW=P95P7pG>#Rm6&U4{mWTVTyGm{ejkf<`Z6y_#|t!mihW9Da;JZk(fe1-GPb1O zX8w>)m4k<$x%H|LUTk-2=xt|i5T0U{Qqx90^%qB~e~4cAjE~C7bo|*SnKIv7@S^Eu zBg+iN*5|APEP0m2>?6zm4X=r8Jmtmw;*YL5t>gFd+3Fni_~>t9Y6LpQYs%AG9|H5n zsfhU=Y}m)|ZRckO&wL4ax&Pe9f9RHIx48hnlvjb?pDFXZ;e<;Lgm0vP`ic)`?;cds z5*h(m8NeJ>nAy>ZYskjSwBsbst)0IkD8VN{9UqlG{*w1J8~47(`jsHFE1;#nl+%3I zS>R25&*z~(XJ20ZhvXnkstGTDxQBhp(P@7$tJM7?I`zj}LF8oTXE$kBB@}iYIH{87 zVHBMnKfM3*U6wTM-*|ZBfm7n;-6bV_GOq6Yl~Qw+cZ;Dc^ts_jfu{v58mJD@;+L;7 zDX&3;#$#%5LtA9wo})SwhaCY;4$9j<0=N}`8!B#=7Xi!w&XINVbVZ;KKrPncGb0=t zal>H1m{aCL6gO?bjWu1|REod@2B3ft$5k--oq5?vuDaja%)qlJZypgNS#KYD&C)~m zX4x(eHcF1c@TfuW_g8U4!spLx#^ZI3`;KK5Ucw<tK6BYhY&-~Sr~zJEosIEgN8~f4 zc00#0Fy`Pxz48*u3_@)@v#=n>`Rv|~<Dv@!574tkFml64BxJrU;1Ux-JAt8>0O3m$ z<^(PfS+nPRPS)xf9$LeF{h}v7J@;Fm9pSst8D_NimLXRD%GP4P^ujIfw|F){lb=v= z2%%%%mou9U6f+tmiJCRW-68P;T;pu`f`GWd+j{CbK7+l#f=-S0wCwyjdUc!<9(zx@ z&(;n4-NpG@Mz1wh3xZ$b<h!Y&9HYxdE5#TfOckOr`rP;^6N9lB3xBqH3-lR)J98#M zrg_EH{3VE*ej1qCGe0-<qI~h#OH5VwmEU>82u9AT5wecHy|aR#HWxlhP@6sYqGi;U z!iqKdE}QOLGQ(f-w96si(H}Ax#%YD7J1@S*IKWEZ73da%obeXCX82yB(y;dvGvc7G za3+~aO5)D(l+NgR6}HN9b5%!YK0uZ(Pi13kg%H{6RUnLkRwT3zoHr0cOkMJDn>EFP z$7ZjqcP(GI*NV@0@7nHShpSdKy_jv{zyEtW)T1`RA{5nYhxWLFFG0s30$BBog3FXq z?349N{Msp<eP+ptf$QH}6h*Hgfn}f&3&c~ZymX}Z<4{z2)5O)%dJRzY6NyG9t8xYx z_nZ3MD*L^8t03IhW3%njc%BQ*YjK%1O!|4(YSVx5ruDLxc}!Mb?J<<kXULCAWe*l} zfmrwqU$t&qZ{F}t{5!R8c5aRQ>idwonlcBVN)58nF+D?DCjRO3&oTW9!cB8wX%E-B z&e&C?)uyi63)KSJ&83$?fu95P*wi5F5gMk~58Pgi+M@fIWZ~rNUNyFs=?oEKydnJ| zZ=af(?|<(3qCf2X9i6eJYp5f$Tz$A;ToG4$cIkaq@nX_Tl7_i_Je15X@`kJp|LN2s zu3e$hvtepFEik^;jo?fF==ZR->guJtf8JlcTOy0vP;2@;mUFvpbk@#7`n$y%AaeVr z-eaW5_itIF)K|xFV2tyQ-sZ*HzX#9%K2FwD^E<VYc1{!0gErVl^(-4o?EJj-)&?@6 zj{xPJF~b;1{v=w<O-)~ec5y%TWLIeDUGlu%&H^40tFILG#<jM`1E9I)821gCzkdBu zQj{}!c?f(yn2cTE$`ug-odo=XS)Jq|nKM8r^aJ_uI_XvZ9D|TPPv+S<pIY9wa<TZT z{*=PU3_{gNMlEjevT7`febC%mTOp$|q`NG}y3WKlo#k@%0pasbt)xxTK#0{f{O&I| zR&^TNi}J4wLc?>6a{ER6%kDa19g6}#EezB*U220NwB&v}LEzFDC1!=lEODu5t~{V2 zxU}TX&auuS<~~I*futY~2RWJ422nqM7rA}Gp-=*|Vwmrypaiwc603Uua@3zm)=GJi zD3_|7m*i#sMhD8CEFXmf<{6c^2~-gq^kZN*OC^kXsm~_;JOQJ&YTwIrjtB<c>oc7{ zIXnk_W6!vhsQK1o){M%Lra{w#SL7^Mv6m^Z7Wi6Vbh)(^FVRLVpvsxU4=|;Z#<;^h zMhSqfik=YWIk#7+l*ep3R+OxJ8Bt_vnXRK8fnvw{GD^f5!92&FRRS(hne1ep$~}k= zVaZ)l(p>g|t=gDHdC;Eqn5knl=F1LK;7&=gLpQW&UaLYz;{(Nrk3jmy2FWz3CLN!; zHx{YWIakrcPdfNFPL0*xuT1zoawpwYB6MF^{TEf@Vq|f{mvVUQ40oKI=QGOfZ~%~} zivdoDsWEZ>PB+6IjElq<A?5Cr`f5YDdx&V;%E|x*%YL(Q2v?35yOQsY%_lKqyD#_Z z%dFB^90ixslF_Q=k6Bm)Q$M1rpGQ?_)PdNVe}O+?8wmG#<7{3VImq>HBySUA)o-@v z1|Kc*7pcEio<K!170!Wc9;_2%NQ5YUt&-q-v+m{z`q%GyTdUHp{Tmz;?Ad*KKVc-k zk3A+&otjChp}ffn`iPMqHq2ORy<+h@h8hfV7L^4NF9d80^UzN`yrNpoLC40<0lmW# zgCenK(-l*;IfBHcq@{t7q8R;sf~4PbI@3jY=aY?GtJvXFBy_4Ru;iO+f`++BDi$da zOO%)rS)%Cc8GHXq8q`M>EV?hDw+K<~k6PV$)|oSkU0Z|=bSeV%Lon;K6%D}{Ef@(! zxq0qzaJ}vIS#BentFFNk$1A(%JBD4NbRRwzX~16OC*-Ejz@nyVNS5E3-$yWhC|wQf z@0-$iQ}EBrAkj3=<VXhd#?w1eXeiz`X(R34nw!+WXb=o+6d_u&GL(gwV*Be}9*TRP zosHn4%)9VEwrE1#dAN4}iwc$Sn>a!U=#Liwvx^F8bUsTmOp_W|IF9h#mN|F8QY3q* z8p!+S{l=2v-Jee|tY3p=8a4{^d<ce;&QCN&YoR7NMimLwWC)fRA+QTtv&hX=%Pn9Q z8uIZfIQkZ&kce(`r%+*}CTdR}E1SOsN9=nwvB}&0M-AR>NW{a)tMM$F_+905Ly-4f zPH6iTJNJ_TI)b3z7T26K)-a(iUMyoYhq?QERwJ45OBo$5?}Mn!X#XsK!{|KO&p@YM zSaK!x?(kK@bUxPi2HUEZjWXA*!f1HZ!kLc&#t+wXMMCPXNqTAu3t~eMpTtpW#wK$R zYYowlgb7uFzYWjQJQ>KDvSEgCe;^fUx&4+mp7*MI`MeI_KMq?Cx?^NH3rgw#`a<$8 zKxc;E#2CH!*t++-CBRAPV+ph92Bju0RCd5MzEJP1wK<|EKC?h^$qsJul-j2eo>uzl zW684uPC$QV&CB>}6Z996$KGt-p-x!u?s5C3i?RlQP2g99uWx3%78~es-~|J`OeoX3 zY3w75=jOHFYnXBVL}aWpDrHH#Bm_7kZ|xx!{44tpF{{!;;Rw6g@xqsGFJkhdjs+D^ z&J!~+jlcm^BWBB{FWGNqcGF2U3|x+JP(d#GA_Av$7~W%YaG2Kyz6?bgY(@H_&5~^M zK23pER}HMm9Go<Rb7?p5nN!}TKEbjFo)x=xYV|(H#x8CZpnD^W?nla~J!SzhHPi?8 zTO|iJWiiNSO=KcBMvsP=qZ_nxMXAz+)5-TWea`;uy{<MN#v63&$18VLmvAGU5Y7o# z&YxEmu4CADJQa&5ig;e?-7}glQV_LhZ%)OXw2(|Ie+7{L&l{#tJd1TSvLu6`fKehH z#;Vh>KT#UTg=BI$W`+xM);s8;f-h#}jDm}mV2gibs`=IDu5NJ{bKjVvuNaAIw>Z$= z!4HG#r}fRCfM={P!@PuQkxlGjLPIG*iUGM-h***Lt5e5D`OC8ToSm||($IGXpN^jt z!z2dE3<z6mL<p9sVT)bvZS}?vNZh!njyg7Wy;b-g^+z{?9*2_mN$?M{WY7vyq9uNF z$Fwj4LydP&{Y*f_$bQh_@aS<<0NvYr7IA9@qurEpCL+4E-e)8ZEie_KdkwQ;AOQ7o zZHSP}a+TGpyFJ3_|6VcK0taW9N0fX^Sbk1B@fm-kAVZcs^mdZ@HBc&en$-^ZNEMYt zI>q2}MYP%cNL!O9&TY^&dZ7rNRF?FmI7#}U%xSH7)t#7s-%z)%pPlKm1nQI&=}`<W za0U=kVj@(umF6HSJcM<y;laeGvJhQ#_qctbXm3p)UVEaqyGPPv-=qk_J!*?P#N&Zp zsoPIdk^(-mZHbz(>!x`jHt_kwW3mTEKLR-$i8!v~2XSXLxm+jy<o{uNR{bPz1|J;| z@1{e@)a*(-1?CLC`arE-=AI~alsUFzDsgN+1c8_Qzz&WbLy1&mwLZ5wt}}^a$<?IE zzW(W=m3d`Q93!ru@m<`z^s45&hbg%gY9LIeqE9wY>H~Rq0o`CssbS<7_eh3_)JSDi zq#AeghkOQn+zJYzxR|dv58Y5irBd=`22u^Da!+~qi|k+5#2bFddT>ip!h;1E?#>&L z#4sCb-;ccgx!f4NV*Xo?P|jk@s)-Vz-XzbVzLN^bK?Y3a&g_+#gJ~2}U9zkqOz*~( zi3Q#H9?U6;^JQHG_v}Z<Vp8en73_y^1eRXoP;t*!L#J@9<=dBf?a{BDU&&XYAwSRE z){IPm(h6m@_`YB<##7i+?vLb(iyNoWuk6rD!PZtJdnpCqoC_S~1L>QbMQW^Zefyz5 zoef+PP)|Kf1-|i*?_@E|$BAT6sd1SjijT;tZkjGuuiX7L>rbv5<#qFZ;B)ZOO3vAk zvTtz?D^!HCflXW+wpQGKT|-?iTQZC{Vbh@0_BY1#V?|SpzG(s<y%pozpF7eUs6dnT z|6NWh_fyv@dgX%DpEsxu!CZ_f(C$%cyLs-8k!-?U%(Fg8jrxj#`X^U|Z*Q++3_c_} zN^z7+VdU+r>VnFTzho0=ky#oGm1;(*6{^nXv>D1<<Df+vD|=N5EhS^|71?W#$Y8#G zM&(vWEJp-KqoulVLlset<0n^&m@69;g!GWAVJNRb6xsA?mBo3~RsXg~lTQX;M8E$a zp2{0xXkU>c@ucfH=5eL)C+-@Jas9FJJF4|c3oCr!#K$hz$a5A*tWjN)=0m`nwd(Mq z>c^-FyGnW1$Ge)9xf9RM{dqRW?wUSv`(AND3oix~+5lc@a5VJWljjecGBGG`1jwxQ zYNVa4+?c4aC(kir{+R2_YIyOdwALW4MfX(0%F1^b-Kqi^i)YpjRSLxxo5VOJof@C2 zd`NT^A|n4d;^xyI0ou;DFe__k+@!I2i}j~|RVnzK9WP4P&B+Nq-P#)=JhT(~mt14W z*Yds|ba7g)BO>sPUZI?hEC(!`DWot(TKDuGS<IDSVBAWUyu+G^QM1NUFUVorS{tN; zM!K+O5)oB5FnYF?tvgM(LIa^)A+n$b6PuE1&KK`K1gdGVzA$dOqN21)Mw}55ez%T7 z9I&wYRC#~Gd@94-x+vS%j$PR+8-iJ#%wq1sp6e=0YRWfi%%^|()b607M2*D8Jb!7a zo(#7qoJW@{x=4~f@)2C0?n^f)-z-TQXaPHRttk4voIg7k*~Q6^nKA<3fno1a=np;- zP+_EFcK%lNqL-IKFhQTXf|n~z_!9f@xkFP1@*S9$I2%hBi`g8^T0BMsj@6ODM*I6( z1z<j<zDf&q2;)jsf8DdLs4EQ?c_W1hxO82u2o6<fvXW_`yU3|IVy_%wE++D8&0sz9 zFz55`F*@`$@CpB-TdXp@mVMUOqGj?`x>d2OJ#d)Dbo!NhNb6;l>%zZY$K~}as3o?Y z5Y)<kD*u3-aQ{>LqK4my=Mn=s9RmqE1A;PP*9Nb3bq$m_4$dtMaJbY(eeeiO&ni0_ ztjptf<#4GD!(8LI7^I6>wTM$(h&;tVMCTut^KI8dS2c(Z_vZ~qvJ2}e!~sYBgZv}M z6T{f+(ZVme!ZOx-Cp$)F;8^Ai=dV<3)6B?{<LDW@Qm<pwUANJVnbEU5h{L&IX@-$a z$2Wug!m)OVF{?udGjBGJPV7jztbIBkH{LMS41e+DpPOrB{yg>-{^shLQN-Et_>F<B zi&?R&FR(Ahsl$zp4ma0Hef(!9>Na{DI1%3{1N$ZuG9x{Aqmb**6=ly((uRl6Nen9I zPbR>}I$sZJ{+*1=^V$XwNk)C)@F|jM)89Xhb9K(^o~eccZ@(n!$cEN*W{z9szfB7r zYOq80(!CbF{gNx+x(T!x?l>HgQD3&%#>NKKt){*ImiG)J=wql`HLNS%$N;W)$6>NX zTdK&7ZNv`%s04uTV~8UZvXYMM^Pjr+_dPjie1ncSX#;<uBk5$s{um<h@~fBd4}}6z z_XXZReDVI31@gd~Enk3M^!a1G$4JTT4@YCHKLEBL+ic&rZ61C9*ijRj{Rf$L4^jC7 zk#usa)6q-R*2goShCf$MhZ$^;5eyOUL{PwuG2}+!!;u%CwbZMA$;a(FBYvPbKy{3C z(>pWyvoLO90?&IP6aZMv(rZ4iUH)?auFl~cVtE@;!TH6}dsh1P7qFAV%N?6#dE{S# zFZL(Cr`b7$SYc?^O%NTx76N4Y9HL-8OW*6z8}Vy<Rt5!}17?=z5Pv_^%uD>chDt_a zw;7M;0FXT5Qz87*-2LSI1@%oG)F`51?*26taE*#ww2<5MUepL*nn`OFJ%{XaW?Mu7 zSO7@-Od~mcMKvwHmq*M1NF5XqNB(><d@20UBqJBuvV4DO7iJ}o*skkwshw|1w8&1R z{W^=-B-#XeE#2u{Hr5gjM*y3JSc;ci$dfOhQEW4F_qR|hNu4Xnvn$kpE2)C35pvkH z@YQs=)iV*Rd9y3gv#WWXtJ&w)GQCzy!q<|$)(V|gP3qT*X4lFKR*N^+N@~~Y|E&?V z)~o+w^22G7-6;C3n7hITLfjLku;E6I?ipR?6+HPn@xLI9iU0t}Fapd#C|L0Xq#Xkw zC_kyLuqzVE)(0X=7QKo^2^-~+>Wh05xs`6t^w&Rror2Rz;5Te28Av<nPVue?mkwph zUmeUdeD*)|ZU4ROLUH~HeG@QhEFXVNN;#-Iys0(u#Nx40zEM-<TPjh6lR}!SeD~D( zRf2%A>OA>@Icu5hP;<?v7VpKueB+kd&+S36g6f52=PMNET~<Mp=XLW%3}ArNaY<qE z6;;@{z@)X|>rj@`t=Zw$XUlI2brJ<l+ZtCV%P&+pjkGnbzpJ}CRAAcP{QZC6TYJma z7kVU2$gJb}&SHOBdq81F>)!I%W8+6=FWP>rzrU<VN`2A(^IL=g)3NvO7ahUP2zO6w zbCkX<;1%U@CbYBjUX~Z(0RKFCgy_JKuV}#o0KVhl47Yv0P~hP0Xaj$^azC-rWItBt zp>p|rjD8Ja%!n!awIwHihP$gJw%>I;6dA7&6NzZuc^9voVc?|yB<K=V`UAEEt_9|7 zyb`0r=~1GkmZ7ppW6POaI*BL$B?5?N$)g}9ygkGWM<-?NO!nI>mZ{Deb{0%%EEbe= zvv~D-&h<XY<vjoC_{j{nj}^-WVFx_R;3bgMN?{ZyYx$!%vC5U=B-J(dYi99>D<vx5 z3|C9Du2-&><pr*-J}HcmS}QNf`1nNnswA<bqPlr)t*Wl?SZckxaoU~>*8DApueR-A zZT%^oNqVEMhjZNm>d0NS(J-vKF7qJuoV1;eKtvFlo!1m|qC>Y!q(%r;kl33UXuD_` z!Fvr_05&foU5xT$vAh+yq(qgwqd_k=uA9M6rD7vsba5kZ5#uPpS^`aHzef1(5Stu4 z4!}?A?wF<m^a9-(w#L%?a^Kg-@o2^v90eaAM$O`8WFWu7;2UVk$TuYn(Y#G=mMHL# zEbDM4(NI*Sc`$6;o)2BKqdPsphwcE&s?bJ@2HKyrGZe{;G0U|##<nBNAg^CAXno(( zyJX%7ZWHjR85cy2)0&B1H=^V@IaRPkC~M;Je%hF!q*k#RAFf7%QAlqc#qNS!qR-0e zmh9?~xk?Uo&yIX;W)sk`s58udmuK56PxG1x;_j-uc`3oc=;1nYK&I_--DDGa^@XMP zuMMhL^l1auqfOd&2iKjWoqqABN4vvnTSt3i2B-e+*LLgt{qep%gAI+01;~^Su}xqt z<uQ6|-D2#ii@za0;d`jAhNu6Ilm<>#SNG31bu<3@xpjQ(*>z>d9;E^BZj=3JAULX@ z&ZM~=fl4Zbh?BZl?YAl1!-Y(0{aWqZwUIb@5!8Ux&7QLzCE;&#ewU`rVE;5)KB)+P zgY=5`qlLz9dlBMpzfQdc3}^-DBFB)___sf(=E+pnVMIfZ@Bs_^Ofjo+9;sK#ekWlX z&B*zvCE+4KcXxn4=3d4oDu}&t%#0gVAMV!|yIoDbUHu^u?%S#UaVMG09w+#qrT*-K z!qsqi369yYUz>NA8fQ{M;2P-H*W9I1lS)Ly4F`<ucT=;5OT^R$2F&c;kO5T#68bwV z7V4&!MewUaa*Y^)RS@7yEEPZ15NFG->-Y@IAqSFAnCy4WY;8;;Q_^`a0nccDk2yXO zeu3DRD(@tpF%Y=*w&kkeu29!-nQF_xh*!v7ZhluL$s1&5F<zag*YHiRKYmo5LkG>^ zazih0d{o^q64P6*XAllLPQ9{0;rdaMe2&o-<}jySfSrFLw_=BKl2<MiOX!vJE`mjg zMV&l5%Sp9Fl+zKokT<&AuTh<5&&>cVK;rc+Eutu4)+ImYqviP5*snyTn_ql3`C(~4 z(Lr4*VdaSNJfrW0i1IF0`D^LCOs<n9YfQwks054X-*Ku?UF2m9Ot$zV@7eD3N5Mh5 z4$V@zY=Cdd>!20W39@Ab=~cy~<t@``YNt4rq4o`055?U5CWSLV%!DrO9|lUlQ%J<U zpr$ydr6pe5&_%0X+VDT8X`P*C-7sAtbL~0^Xm#aO6#QFdl8k@gq%JJM@VD9x8j3jy z9^wMLYi_PX93qbU1DpL>nQr+wJh=*8<mq6m_3rX`Ie&9Iv#%!6_Owo7y4cUwvC;=u zRQN87?GUQoj-;B_=YF2an|`8*_f&!SCT)Um@GLel0O87MlR25{8xL4yv(WI(&Y!w# z<-J~8r*j2mU%gPZl(}DX^=T5f4);ee;LW_j_d_wux>RB@Qe5U0k-k(iUs!kNo41RL z`(xa}+d9v0C^kUkP-Mo&GfwY_cl2XPr%bW}^J^IScK>0YI)aU*gX=Tqh6lrVDU*tC z*dq__U^xz}C#Dd6H|iMz&w<pAm)O)&DoH~vy3qIG(6fiK?_vj<CMcO(d(o%jir@qM z&-_z=6lzqq9&55z&g9m-Vx*S_kG`QP6_jF@RkvC-L;gK0WR_i7FuN94kPhOnNz>7m zUQSO=ZY&X(r6F~H^S>|g_w%e?H4FVcS%_#VH!!^kDW*e9IY;4h?;wCW2)IC20hlt^ zKFpj1%^W(`gf22zZ~ay?0Lbj=V-SfWd$lD(bA8GKK3^8M55s+?RgX=--*ot7k}?;g zQs?vilXu&vrh%9@bkj}W+&?obW-V>+Mm7W6|9sv~Zs}NN>$;B3nl0+%o8A6Px+4<x z=~C1qqP;95Wi01QHa@5;m(e?-guwGf@M=|2oj0(Nd#Q7d2``<zJ%Vz;@n5;92slSu z%qhs?kJT<pC?m+$hkPlLLY!(|T`pQyj&^L~q-MYH*NLaAc);_)uZ4yEGmw9kX3As6 zQbza7PXArCNNJmTV)mob;qTg|H*M1`qd#gx|E@bD+uy%7J7~!LyWwu${xL;%?niCD z47gL~W~z(7A53R+N7Pif&4umuyY;PQRsC55VFUnN{(KqJ;gLt3zx&8~^A2-j7-i?M z-?)IQPyMx=#GPMt{rf^2bUpcWQ1F=d;`Um>s=C-b!Xc@1&&l#0ATp0|gkIgQOBvLD zjV1#Y-2!dT@2&bh!hZPq?`O04KWqOY*zC`9z{B#t2@g+U!xvn+M(>A<%@rj&t7rVy zx0E<OcyxTE6BYjZ)nEhnUGs2OPiKZvXXaCbe`I7G6u93lzhH1ik+n|1^fDc>h_ml? zy>H`x`8gf-xe)kF4;Au8M3bQ>14t|4GS1E7TNbF0DT8WD%Vjd#XK#ce3TUfiEAhU^ z0S#9}!`pDMy)iaVdA6#PdX$c6K*77cL#0SqnR3|MIp|}51QrE^#h$utaC4}Mm$w(z zOlEDM!yd^aGQFXj^pnVMcpve8d*H3wE|}AbWkVh7wl|`@jupavGx2~I|HHDjkR@)L z<#S7<0muqGZ$9$X^6A|uUkR+d{^iia*k&4qOv2m<;wQ$2MyjLUd*3k;w}u|$<Km%M zyV9W6or{d~aAnn-C0tx*E&ViUFgi-t=$nT+6nJIJIU{c|eNqA2uq9o>EX`d90JXF- zyV5u=V{y#r_PtIrd|}K9!0hBGq(4+@!Eyd5Gh#({kju8v<csCO8hOY&o~2q$sz zX2$DSI!%%-2Y`6fZ_xokT(>MveY}J{Kf&}x+++AXC(@Q}I}V!=%~G#&z2L1ympX>| z8tNz1HLyMbtl(x?pRDoC5&kx1!snVz4E5bNllm^|u<GradJEKm=Xqt?ub?yijOcPe zf7Y62*FfW6rSaHl1Ml1`>n-waQuT^br3X^gT`c9}F#rLjsF9|5?2{%Cou)IMe8z)a zb2aV!Dq6)OjTw}x6O3NywlS2v!ep6lx|$B*c&K4%VQu%&Hv8dS7n5TbLAZ^jOc~)G z!^02tFw(#k6AvLd&Z{1F0zb>sel{7qtx7x^V-Y9{@A73mO5<f^c<5Il9^jG5U(dni zP8w2vc;ABv&J;CO<{g{LP_kor;K9DqkPc9@KF1)vd}u15?81p_RR65YtJ#lyp^?rx zcsH_+LPD{&B2bva2g$Yf;HvUAgY2+Av%@^k&J}mb?a*MKwaR^I$6iv$uD{4?q?CsP zd2lRIIYn^NMZ%pt=<13*qO1ILJbH5VJQrZi<0jXWo{u{oH~#9&`Yo7snj-Z{vVgNI zkF6wIvaw*TPuqnC71AmwA+kOOJVXp1#yLL{2YD=~=bev-HteAv$)g@a05gop>OcVp ztq^8}+LYuOUUuA`W?{*B)FE=>AmriZy|ZM8LP()@S&Ep@S&!<9n9&8<=;Gz;nUn$J z7jANFzxDolaB)Oi(5S2<O<u+&EIIOz5up4u8dLLFrcTSF9DMpW{Sxd)o~&T6w0M+B zLNV4wmjPb{PblS~v1r+&gw{&U8C1YUMFML@wnk-0OBQ=6)Fb)g6G_vZ---~0$3BB) zP>^+AFp4rz>bF*!I`#zYQg%aAJ|qW4^}dKYcFAN(I0N378uj3^)RncrS#FV24p4O& zEuX|xRxo!}091v@LEY%VGcdG{p-3fsyb@xm`-HU;Wm(aXgF3&1BHBE$dcsKL<Sb+X zfRHL?klvV5g}i?uV?DImzKYQY%A5o3)<h+uYMgF(xX$N5BC6j!cBg&RE{v}^U@07C zMPH7oSu{dBj9>d0Qj03Owmw+<g@AH!sogeG3(&b1xn1=`3e|X$6~iF+JH&JQ18=o8 z4vf!TW>q_FQ)d!WSCVnzX}uBCd|k2rqnh!j43>2amRUJ{NC1cYjzjG#B2l@#r#Wta zM>T-Q5xW4eN91c<QRSERICTq^bDSN~pv5fS&dgio@sn(-avCLC#dm+~+0_^%XDIp@ z)mWjR3Z_+_yt1uAng1r#mt-Ifjd^hl%75(9W}iIvxB1)yQC{0k>EG(XF36u2d;wx8 zR~!@A=SF^61GuZPafi`)4uzX+Lf~5pVvvD+d=JxF80TAtD{*sIQKz(V<7rKVCBH9z zs3>Vv(w{Rr#@fu{sQ6Fn%e=Q3@z=vnqwRn;7DbdN6OeYg_7dvW;~^n1NIjzL$=CrZ zKKJ?dS}SL4do2v8AF3``Z_WPHRCA!k5TVvJRNJPCdMS<SYkxX}r!mxfw>dl=4Ma`0 zKh?2#!LHHH7{U0us^abOtruZ1$Qg_$vyb09zBb4>gk6JivWn4x%J`+K!f;Fh*oO3+ zMu`w!4&UtTzKBw|f!Z^EX-<C;CanT?fgHemnTBiC>KM)zD!pI=BycoS3py}HUl>SI z^JakN(P7n{lMp~_?qzSPht1M+7N1KS2~F(tCNlJhoP?&6B%nk2Is`3d`6Dv3s`K2@ zD`FTnh6xbn@6q2t83y$josph<-jf>DT`*B&=7>@c>#;f0dnvEiUdC#+qW6Wpm|0t| z>x@hUtVjKHpL<^4&5pjemOY+Fecr>lx9T&c>E|@VYHdAH0b#E<a$cXr<78Z~u?pkq zCVMbMAWvc2){hU77D;!+d3nOCJLCCZr#lXq+P3m5^f0&%<W(E0%?w-~dR2I4@PxjV zg$<VH4OVsxR-e&VaeQTVgt!)ldUU3C1&5$@JZ+Le-Tl$9U(x;JcZ0-H!(WS6beSr- zGpKz-#Io~$fYb3d;_PtsrS<L&BJ!Ox;sp8ZJ72vdJ-E#}dIGz4EJk<65IX?;2Q@;~ z@#$`A#DP3~r*7nkh&=LUTcUbQ!YlW-5nHG?GDFA{vCq%EH*2srbb7;n;mEEx+e%&Y zYniIQZ~%}+?t70jnhyW5AO6SxW`~aa1aEj(h&aRz&4tzevUs*>aq@+uUuRB!9r<r& zbUUr`#1;4I$4M)xZgR~V`PXy!@~z?S;eO*klW+M4rPGmH08(vcisUddFw<ml_N}!* zoAtf7mTXTA9=tUeX>q*#*6P7qK>n@E-?x`9PhWWvV0W2Q&T|_5*Iy-U;!f8q|I6?E zFF)M`fZ+Uhkoh;^-w|8Ddy2sOD7N<@YeI4Nm^`VfH^$y4ob0W!eXx1W6vg*{<}?!^ z-2ai&6!4b+|2WNa+2Y6lE2sHgw_^0aavCiW1SRPI<uv$+2d4iUPQ#8H3vm7tVYc^Q zPUBJpV*0<vX>R|2IgO_Je>u$!1H>`(=tak`2Ds-5r>To}1w7L|;P*Q_|7Lm<{^84e zM^0>JG{rG)VB-cY0_^c$P6Nak+=WB>i47)Gu{zoR<utAT;WXnd=>Op~TtSz{uOK4u zOn{?$Pajx(I!G{>yNHsY_0;(SRRQw-(pWgpNB1Qf(>#eYk)#;ZeZpxZMbm*K?`|Sm z*#q^!KG4IG#mT7Ws}4NM<GME5%>u>jQJeiO_h!L=IgN+7nQ}((e>lzRlYCYP=YKfO zP4~k46Y1u~NxLlOkEtJ7-W1bPAD)QBFB;jO|7B6RYMUL-%6keNAhlMZ!aJEl-0E1A ztgM?o{u#lZZSiW9Sk+f~>)uHiPz2neP;s=Xo%53bOa$=mV#2S`W8{D%;jzl?xvLvZ zBjf+cGp??yc?x*efdQ)j;%FmqCgJ<_s-z}B)V>+V0LXg}b-#ezb7l~j%!2_<>r9S$ z@E?dNFz_>Vtg6#rcX8|dmag=6Pmchc{=7fjyNg-*sOtf7Lf>Skzo{w8;sqzHk<!ig z2^i2Q1ruckl&hE^!0E;wK|mR&ygA65MrBlOo%U?Jsp`f^MxHxSs31=BO?7vjkFD!s zHg#Wk+NLP<UB%r%;x=`FX(Vx*b&+Bm$+tK>+0=C9^$R<80PbUfG<$Rg1@nkK{?o-p z{09SOe7U@M*ufv}sR5@a$CQA*X8KQ}ErV7<Tgs^C;kO`~sTvUXPIhcW4Tk-(2$|2_ zn0T0kQJT+t?Uac$N0meo4Z}tS0HREE%fMQZ+13=pkF`1VDo)uyyOhu8Pz!;~^Ez8+ zSDYKR8BN2rphk3U^>@R3Rc<Z`n8pmP*4WY0lVw7>-d#YoSETgDoUrT$Rdvd;o%?$- zT18=8NQ;<GtqFs0ivG$Y>hI8OgWRxO++>C$zjVTUNg!C`idHh}EDloSpY*EWgVl5u zM_5<D&qQoor2@*aBN}9)9WQf$OXt2RO62W<$`T-C*7#LI4%L|bxXc12LDa%E-O@(* zFaw+L`ABf9;1U!Z>BSZW7U6~rmwXjxT3N*}CPG1dSQ<d}5u;`;=uR;Myq5B!sxxsQ zAzw~jFg+O`FRV3s3GD*l;xHOL`qsJ_Nq7&H!H%Fs^^W>1IpU#8pWW`{0Ee(GTwG0< z8V!r1b=Z{npEEKFhwm~*ZJ&~aB*hVAeFw|WMv>v^af}0;Xw*eU8kp9NMlYP1(Lh7h zs+>MRQX7m00gh=a!Tk3`6of?tQsT=ZFbD`|c8o`ZB`37yv`rJJ<TSpnMSZz_>S=#J z+~^b(`OKLX1D|7P#u*ZTy6AF=6`U1a6f5t3+(|i^Crg5mC&B=gDAJ|_S6!E+{F7GA z%X7jmy8UQZT@+IXCLA#?tZfvGLfe#x`=Q0(Xm*or!XYI-^TI$JNte>NAJ+~ce)lp^ z%MmN0jXMlZazD}cqHTkf0gJZn*WwSlEyWhQNU%AT3=5E$%$1TjT&b0L1eHWEr#stc zkkop$e4Zfex|mh#7~h%76bHDFjqdw_QrfP`+Bq*1m!zl}yl#)07R7-O7R^nPIj$QU z_aUrO5r_iN-p?-Tm`7hMtbQvD3z8v;B#I=kN7dTii*o|iWjGPKyaHimTC4}M?2Z6b zCduwy_v??v)^Bk?OR6q!<@CQeR@}i&34iL4|7{{muNIoSRpWh|UCMD{uiyv`y$qs$ zAc!sbt)&&1UCwUsmVGO5Tt4mH5}LMl5d+u<-S*9NK<W0SKSKn&ZWYG7@OmH(;Zg^y z`~x{|e&iA>T38`IceV@R6lq>kiIcm1_mdcF<6TXTxb5EuAX(?#PL!D;`=Eu9+{!zg z1F_b(sc`;7Ef$EG`T8sGH3`A%cH=sqZG$r|-k|krJvzBwzgwQleEAT^%k-22KALwV zSmIjtHsUV_*Wd7M79UKncb3RSF%v~9(LN2t{T@Kv)(&Si%98#PdhO{<)_I<Pr~K9v zs35<Lr;Gzevy>b1lqlz8^glvn>goigpk}oHZt@jT=7t;T<<2;fL%)W9GH4DF>9N>z z(BhLA7b2!-Y$tNRm`h;QQ0@0bM&SM<7TMHvnilSJ*mxvlH~Q2cHLZpGxa`~Q{Sh<6 zA*w`$mLyMxU&D6t8>qhJ)VGw7E@!7mm3(nVUkDiy1qI_Ndr3hkWLjL@rMTusr6IG{ z>*~V;qWzp!x96>5ie4%sTC}<aVtglq#Q52CqCwlycdBwfJ3@8NUTuu#&IhqUG$M)6 zeFF0XUj4t(H9-TnY}<KTaD7ffK#VE1@kc`OA$70jQ)-IkB@@Ok-4Y+j@=;Nfrtx;S z4{UO!sq%N)aYx6p0g^8OKp`#y{@G1T>wV#tlKdo_dTit<BRey&AC?ONg=lXQV~hFn z5qC);QB)`Y(i2W&cm+D~Fnqrlrn|!UL2UZzre6V4_sg~<iKovDWr-1)a}^{dUk>RP z7DM+#f|uMCLLxYhw7m@r)a_=97+E(Sv?Q%}?NbWXdp?`R1M-Atp=Z#t7RvfZ-vb|X z0Wpe65kv-!WuliHinWtQu(Bn+tr1Ksu!Woq<>E#_z(J(Nvo9s80nIGhzKXD@4|i<A zpHnS5DTTEO;Bjt)zomB@bgTIS#mcsBkENFG|JzoS?f1N8ZoAZ}s$W{x5!pSqrQp8@ z&v~bI%;zoVM_D;KvU}I2qkk&k@#%b=VP^lhBzx>{2I9((H*X|h4ac!7xj9EC{gME4 zpwF=>mUR6968GBnO78^*5JN{P!)K~tFEgj!GuXw)isTy%luUJCTf+$OZF&~esAgMN ziW9#Zc;)|L=sf(P{^L0Qy>pYp9Y<C=d+(8*<Ic|BD>EY%QX$njhqKSwtLzYEhf<s) zdxd00BuV`!?cwKt_<ld1&*SxeKc6qdnA~@f1@~e~PG9+R{g!&y?b;Kul~QP1IAHw< zZtx?)z!jr@m;l32t}~61Dz{l$uCVyVBKl!(gV3vomya~j%g#0eL;m3HYpiByR)}jA zQIDnNc!S5E2f^bZ<;u`R8{3A3KX>~R74Ew3`-(SQZs)S%4%z=YOyhZMqtum4eH65B z)OV>Uy~A7A#qGf$O1c?E^ayWkW=4fqP{7%ztcP#c!%x{oqnoABPOg!Q`4{0@=u624 z4?4s5Kw-RX3WBtxpdB7LnyPBK@Pe2v>|4^i9Gmph9`021(mV3n_mCh%SX}TGRjDiA zq~O6MSY-I^uR*t?!c$<`QPJqD(cu~MR0<HD0iB_)X`$DGDO?y4QDPJh1h11qmjt5= z-=*;7V``|;Q)1{)O?QMEy5oDQ*$n58ed&eiaHyJ+e$MG@36Q&AA|Mgo>B;B|&o9A5 zU~4Y0xSizNg|V0VU=bwP1w&XsIl{dUk=_SQCBee_(xca}%no1G+o6KvGo)nDCtBe* zm2*^nCaA~cAdm1ltHX3IkxWEIhV&~644-hhJ=5oUjKaIj6G_*QpV9Yg@zYgW`i23o zjg)?w@nqVXuNf(wH)c6aW9eLsxE!tf`w%V8@XvR$xGs%WQiTn;roVX<Gu{phHiUZu zbklMOZUpg?1hp@RxB_%h8Ti%pTPcN9!{el^D+4gJMjXI@V~S|nMck?)IWa}=Aw_7F zoaNyR{%pE*$nCtvn3A9?V9>R@`MHSxT=<M9{Cj+ylR=9l3!MPY3(qr)Q2f*f9k<V8 z!Ly7%*FA2!>GsF`>^c`DmB{rfdC>J%xGg=22F1m&_mv|?5%A!BSTG5GGaTL*&Yrpt z!5wMCqWj?U)Qq_w^p%kesrQ9&l_F?l5s6d;jxWlM!Km|7QeDw{gjnc7x_1y->w63o zbPZTcsm%{{&O@v41WXN_#BEt1pzv>36wgyjR1Ty!apwAgsu$}p0=4Dv_?W@y;<%mC z>7Usz`w&UZ=@)!bYF}Q7Ff5GnLG(2jxb`7q`{2i);Cpp(ZnE_mS&=*>!bG4NFN-m8 zzgrN4*6F4ipAgv&MpwSNT{U;xx8O2hc<o~}+NvJf`vV<Dusj5_gtUP)!#OTpso-Pf z?wmdi?)ONz?xDeRvm?RMK{<Jx$7M+q!{t_9j7Y>{;X%y>QR|gn1-B^C@W`Wbcxf~8 zMm^$cAN<YM9lnTaQyoNcLp?0Jn%nm-!pJ&56@8;Tio-XStW}Hz-CBQHgN(R{unP~} zC}*BeL%E;@aV#@)wb}=qZ?;P8n7Uw$&bc~FBeD*zax4BvX>c>rybn>*oE`}jn_Vx2 zw7?_#;59x~IGOsmX*d}G@C`-AvJWhG(Iq|g0uc}XdtYyCPvHR-L-6J9qxnvY=MEQ& zXYcX;gJ7O&n}&_v7oYL$<t6S`I1HFKHkzQj<~+x)CJKnujiqKr^}%qj;Ho-NDKUjG zGJIkYP8&tgW9b_@rr`K`=?@Pe{q^q~>Jx1dz<#T88v0XeE6b5@>zmLAh>hbXUFL6X zv{69=6qNXLsHQCX+F^boM+D(BUrEh?us%zC$Q6*Q?HRBj_rfgung+VR8|ydl(59UB zyr{J0bm-kew6<vifWDLJgQy%S<d}h9+bT4bMU$uDr$-T`ws3F@Pohuj?$V>uo>r(x zTasLx%8f1+Ikd8Fmj|XxiVdJyqW1(a2lwblKhcM*p&m<-f3I~0Kk`RbIC-0)?_fKK znu@A`nhP6uH7y9z9~bkb<8t&3oXL&e!u$*7=(Pg$Boh8D8IB7vmFhmL)SdG+q@KI7 z{>uoQ{=3XQ96<#TN`h@#x=zWo-lZFec@Ok#8e;v3?djrg^s=0pnp`)sqV?;~2k?mQ z?44Ajk{WDGasGF7zC>kFqS+t9eX4^F%Ee2r?+n+=o>L+Z3D?rLxjQ>w+HW~I{q1-R z!C#Z?p}a>_UFbtPls`K2s8CzG0UFr`3#h(riy#5?FcN~C+Y5<!%7S@HrJ)t~7+j#I z@CpV?#8Y#fZVq4EC-cmMM_22L>xv35H=V{|L@NFBX)OINx1g@=kof-Vpftli(HYLK zUww$qO8NtF$b}pH*qe{WJlg_qvc@J~3_)|tJhRlY_?ir-HC!fsryHi23R_jf?0S=Z zSWEi~;>Iu=%ZwBnLiG>BUcyZ2Nv~X58~NxrT5lyoPpigAyEsDG0^-gryV2fy&vU-> zp{OSMu7g25&%L9o9G-+hDd-uG$Lh%Q(L0G~e~(B=%j4$j*4#36A5Op-V+csZ6Wd?? z(Cli>lCD)<1lbXupo~fdn$m3H$>`xPx#+2Mw1Yf4&30n`&-fw=n0zuZla9U}HgNL- zI^n|e&8{e;cd5nFiNJaT2O0fPq6hUGz1yJ<1r36;ZEI0n72@bVf$QEYkk~-apjWgO zz0lQ{-RJIQLSm0sKVhZeFq>)C<#zar8#-#aK2aCF#0Dgxo=)kZa7Aomd*icu6C5fN z3t<z}D-&S+EF}!BK0dQv+I9Cx2b~|=&FLFkGL|x2gx)XB`cti2mE)7e68E!l>Z1y} zEf~F0VHi7aAHxdlwO<3dB=(jxvfV^axU$;!A)2PsGe(Nab{`}Fh%1n`L}e#MJ*Oo- zn`9hoK2RT}j8wWf%VjqK&7PIM_)<b2EqQhpig^J)=t})_$5$Vn9DQ5#0BZGf(munc zM5EE$ifG!40l3d@(p59t!k=(M{;8o^)6u@H;lBnaeV<!>_>r@`c-#<<xY;*`uzy6+ zT~?D@Tw0lp|GRLb5s|ZwxluODuQGV;?<}I9u`1WCm4?faS)gXTaMWqPmxBK28p;8h zV!<cB<F=K@XzUw<ZyjMh^Dd%CzaTlC(BN+MzQYPgwv#O`In;Ez`egsp$1nDux8Sr9 zs@e^A8iwUj1CRc`25%rTZQ<F#Y$}Z{+ZImS=SGXHb6i4mD6TU;qQSzLcoaa1+gKf6 zNSB*Tk26jC(T4FIfgIpCxx)9oyaRtGRUF$=th5)!)nZ&;-C-Cu>!#7G4KB>AvDIHg z_Mf|hfQc738kg1?y(^LmL6C8+q-pqVpQ5~&wjIIAbhb9;>MSYaB@1Q)d<j_$)L*wn zPBqQ~eJ|m58$jP%&pX?kliR_W+dM530tzoq{(IzT-OXXwpo73%&K-jL`Y$Chf6R@1 zF`MF8bl5n0W5hhM1_hmNiOLGy2_0}li#*?i9gKo~eL29{rS~(x6es+7pYSpmkyJkR z`qvg0y)DxcJ$nHy@3npY&bG(X^%NT0jd5gwEj%BM41v4@eL~aFdklj;WdAw@^8tz9 zcF8=pc{{1;nkL9C`<}IagUAJ^HXaI&-CWAGet%7%T^Ct9S3kZ3YmqK$2K{NAgU%#{ zL5A4E$k2$JzXsn=pT%GzGt^?}mEi?7)9|?F>fPnnvsM@$;k`g%WLh|~8`s)GLu9Wb zvX#-`0Q7(&lCHeRXS2u7@nKjPGd8)Pd|~0XuIb*=@Sh@dfom?Zck*MLud8%r)Xt~! zBjYTXlU|v!7K{9G5xLfzSkOqTf`C-x;{liaOBn21(T`?tTvNMWhQ8QxWOXe^)b4MM zdo1jXF~$_%ac-<%JGqySL(}*7^L>!%04h8DTaGdkW1|S;{Dx9F;JSPedFFfA>u-Z= z+s)qFyo%_~)jg=);*KMQR(SR0gV?XKFv(l!hlAFI1{gZ`nG-(vG}TS;V`-A@+A=sS zzCi2aEdz)3u+)bi!;lG|$A+>S6SmCIY9Y9$zDly~g8YpEp_^!>zq|1Gy~uOupmV5H z8g!8MA#Zv)hxQxM?+67c<<kC)ocSJp1|1T$4VyXWn)rT7X>#P^jIGWO{OR1Cqq?Co z-PPwk<u5<_@4R?s!);!ygub5t1uPfj#b4?+^U3BSdj5Lo{x$#G0twpJe_36o04;FC zQvmd5yI=b|bUB_Kgq20C)0ku`AkK(Zc{7xescH1a6&=uTE+iJ13Qfo0&PvD;tFiXy z%`7x7uB}L$+vCk~BJnFDnCj<b;S)r?QI)DeTC${37=pTaw+Q-uue&Xq<0KFv%81yk z#g$|P4u${W%4T~m@79cslWQ9>5jQ<9)5af{#PkZP@i1RL-1T83vY#?3bv^JK$~bu@ zNl07O03a!1J^NkSGK4YNSV#MCML=4uEo`M#;>`(Vk+EEU!5Q{aa>UV-q^(%fa;y5= ztTKL4X0{^9iLBZ+u9%SdYA4fw6s)?ml||03;U=?gzQznt9Sr!>Ivf2N@aAnq0(w*B zxwXkrb3%rHh@aUsg9IW(Bi~@)P7>0UtLJ;zfhAGV`?y5_T~)pS(`A1^u9dE9m(uzr zfBgJNt$RqFtg=$Yn2NU$xNQh3#A7S2o$R<e3kil|8z3_fVzWlIa5f#W>Sm7Wrao$` zEOi(p$5Q=>K=P;-*^~s6WC-#M>FfqQ(a_qvK%q6gaMt5t`7`+$NCnYEMkeRk6OR{4 z8q4Z7dY`w2E;oN&yOJel`fa7o;J0Y2>ZnYR0HNVXvy%0QbmrfVnBje`p0mRlTm<>& z<V(5tQ>OKF{ix)yo#w=Gpv#KrU_;b!a&l3~ZZ+0TH-q<R^-L=(w67a=kX`+iD_<gX zX=0*mX$>4itT};ZoIZBhLRO9beu`=`8d9aKZO>inN|@ou%~>4hT{-<+!Awt6u6s*Q z<pV)}T;VIhVkzVEi~mG2>GH!wqBbLRk=(VLD%Rq8KUBdIr1i0>>-^H88V=Y8&1IN; z<shNm2DOe6itT6uuNJ+ld`h#YSzSh4UcPC8$;Z+O1(}6+KD@-jM=I8ibUbIsZ^y*k zD~;5gK2xHbI+a!TcE{3UPGRq%btF<TU;W50_DJlkdcX7d=`l5>mYP8DZtqVm`ghUT zoZmL@iZcJ4t}J1zRFDT^w^S-&AhQcq2`VQWH!_TF*^OtyrJjTjI1EbN9TokhC2D(P zzoJ~cL8n{xxN9WO1vXXeQR|a%RS<|zx|&<n4w50{%DdyYXfj@$hohAZzapy|xE;Q5 zS@^Y7FBdk$)_2!AJsh|rH?ex+T95NXq{?+7A=SScT0e)~0EHvW4Y>xp%?8%BXrD5) zY{E9Ep<f@DQ$bVd6noC(Gq--eJDq-m*PXQC0O)XQSG&u-9?szCyq_ntgHrl1leO-g zH^WnHrxsynOz3a2$3n!Yebl?azLfk;%8}0dey^_9s~Q`Dm0V>wm>2|;X65O3%pO;; zu^Sr+q#`dc64ImAa%%dSnPTWyh^L=<vS&ek=V+f<cQhjnf%FQz?yQHCv}5ti4|as% z4rpD}2)sQrm39sy_M8I`QY2f!X*UY3?$`<xp_Ikt1dYd-$v6q;K{L*km%YuW5&Bm9 z$bmYRJuW-Vca#9@q@QVs`}7B{hD|)>;l5Jh+UDloWO~kunN+ar0KxC0-kuH$aeqFW zv2J<>Eizf*-O&|Kp<FyCLv@wr!SrZj0H0yO?EpUmR-S5Sp%_=D5l=STab&-b@K??2 zw&J?!C#g9d&l$I`{CGMwgX>83wU4WFlG?aRJ|=t4q}8vQ8m?q+Bu|at@@4&qtK>K= z5?-V&@M);9Cnxp`pd5m!uE0816+lumR%IoFeXwO((uTTrv;;q{Xc3jQVna8c2N{v> zW}6kzKtG|Q#>jISJ*irkCF|oOn1Ne@b{Z{p#MBKi@Cl7l3)FEaj;ua)JjId?@MEz( z`^8s`rO>d5E^(gu4(iz3r`LYQer|xS=kJVQa0+K!Ihyk!K+tG&X|JppE%RFrm7Q z@2Y;3B)t@g^2e~5p!|7`<ac}wR9t#^x9G*<B7XU%c88>(I}{|gx4ixN5w@W;t4IQ{ z{>4<<I;+tGHayBqXC<98VJdQd03`>^W{{cfwRfQx`C1O*$?BgRf~@>C5@IVxO~lzQ ztsv}6hR<GBobIIeu)GJiOMmiJ5=G-DiCuxLz+6AqxwkJK6BrVO=<^TN`UTvLja+)T z<`M^e2%>(V>8?wZ^4Cx$Lul;FL|It!REL-K+86FDL(xXHn9&M)l=P=O#p=s#3gZaP zoDRcl%1uyG=uO;x@^Cpc<ARW?@nav@0B67Q@F_qTPEr@%R&Vw?>vyMtM@%4u^Kk}s zDS(WyJG91PUcI<e&dt?Q<8on#JteA4#x`EHy&PJ0LB81%<wzonRRgUVARXI;OmdIL zwpq-?kwEqn=X7O@&5@ZT`#gM+HPca{((2L`+-X`(iR4EfMTKPLOwTJ0pxXVUV{0nn zL;#DbmT8cnUXYHz6-;m)!5%Qjk3-=*EDFaowBML04r>;a-4`_NOBNhhm%G6=Vk7Da zCvmC0VTz^*N8PH-`L@q9q+0*M1fsJ=1B$TFpAhNh5~PcK`{T7T^9ECVYWJ)FwoMXR zFJ|vuq<45{SZ&MFy>X>ku`<@`)s*qpvf!u0xf?>;W_}-rv{g<ppJi*v3Yt35tZO1B zF6Mjs?CM>Lyeoa`2=E~UM414=J5y+KQ&@jGt}svC?7_-JHlguuf08(+a@|Ogcjn~L z*~?3oAG*Cn54yKLbNqY^XdN%D>T}!1fdy7XVbX>bFB&KX<+Vv&_3<e01e1UVMU56Y zWqRCpyAT7lmOHmm8uJ-jk1sm$^VJkaTRs`NF`Yxa8~9@U4F7SGuy5<xo%i%`Ai7gi z5ZC{A?qv3GudaA+x_r`UFfo>;yt)JPF5COPM;6z4a;oy6=&o|gjuqo$4t0be#-+%R zfAyfQGvdK*p{)$7II%`Ek^7)jR??kH+&yJIUxMOiQB%UpCnj6n=PMr+w?~I16%F6_ zoLd%K^{sBs9eKzEk`{z?QcapxIzh^<!x7a`VEv8VN_JH3%e8MJ{q@AI;3e|@5&uMG z{q)G}YCg3ZreN84(TtTKemhW`oYF#(Zl<M~5x}3|@E2C!Sf3>4Umr?5(5?Te$jx*S z60l838WN*NGl8GjPwyTx|E@(psVWuY^jfoA$dRhBRkGj-DH}KDDr)X-tmCKCQ-t~T z86*W(^V3sQs(dOHAr{YGo>%||?mg~hZ)~eJt_|r^1J?B$*uakqOV7rW;qr*nJ)K23 zHqCHZCZO_Kmg?fmT9KWC^n*CmJ*B$}lomeTeAQv~3o?BFj8_h7K<tUjBE+N+YHyhM zQ}7I6_+;RNE^~nKGmSbppew%BA=s+h{esK>7q{F&#UC@lpT#LF<jy0VVlfZ<w4!O9 zqJ8XhnPw^i#Ki~KuF~f?G=`<sN0b--dBxUe*F;6P<J&ZW;k+i6gf{furG~1;MRxLz z!co_q3_fv=)GV`R%9;w)qV8#=NLH*p=T^mIah48&FOPA?j9w2t#W|S_mgKXxkdQ7) zhH;{oJi>d0Aydte_tg8u+P%Mtu$Oz7sCwVAy3V32zrQX^7L)s<7}<cJt!h>3$fgxk zWYdm&Ym0=$_pvxW<xC$C?+;S%kK{7}&$S(zGe{uL_(C!txV(YJuw}27ZTDD`ETZC@ z?++1F?i~T5hAs4Hqn4k1T6WVAlk%r#)W;TlCsGd6eyhnHiC@w4y3z6U1*5-@!PM1o zU!<IkhAR9SmMu-m5>NcD+mR`cp!rK@hD*K&1H)~)`J41-s;LGC+^4t<i^^reD(M9q zJ&Zn`a8LcOGKgMjDuRVHqFrkc_PpLxa<nkHFZ=m0k{m0q#<N9@+d?S&6fqE7<`{%! zW9m_1dzzNnZ)E|X?x~F<#eVwazOqP)Bll*D?mAvBJ<i-GH|4;1#OIG0V_GY+Sv_Qj z;-s9O6E!Xy@Wfsab)b{JY%Ty87C-CBs-l)H)Z=f?oVb8JX_BT{L>g$&VxO}lG%V99 z<tEZ9Mi;FlM|~2|l)M-S@PIN(MnBC^KGnR^b9AdQl_*Cmktut(Oue;?<9LI3B*sl# zgglcQJS&S(7Gl_yAPZ31nSA37>s_Tw#B&6wOE@&S6nbi`-uusFKVr&D-YVY{HL7k@ zWJVnQA~#NGd9+eq>&h#DYRQl;EAD?deWkJzl@bO99yZo4d`Nq_jHu3;KtRRJ%1J!O z*>?tJa;GhH30t{@5Zn;FyIi_8rUVwEmOGY^)2W4DaEjTGM`;wxb%^zTb;O9}#tdZG zSWax&jN$X_tN*iaVJH_@Xs{3DY?tAnE3_=s=KG%Y@Z6-+lgGQIkMr7&fga?L?WD-B zIuXqD()18nD-Eiy?`2+?u`|&>oOaaPH_aX{1JEpxc@CN8I-x%R#mYkc3y-LUr88PZ z-V7a~5Q52yQiv`Mq(5_1-QSv1_HQ}GoDb@eo><sLIbC6GE2l~dHSdcv$FU>Nd7?h2 zBb*JP;fBwgd=i~(=biM^ot&I(|IR4v=?;{S{QQG1qNcP62>zxH{n@c;wJaHk?VMJj zHMr8C;&Vl|g&F0QYP!s#>4B@IFG3_rFX7_#AOLE<k_xm#{@T7w9jLM|qEY#mT-8ft zxK=H&TXO}s1jX$cR@E~pN<|bKKJ#Z|5M{^iUt@EgHwHhhAejF413u$S!+9qv)FU|Y zEDh=?y-0=v&WWy61;mj{;4w%v;yPh=w(MC^yTG&kYB_!4#2$C1AqTm-|E6)enY`^2 zJ7$p<zie?H4S2*!ir1=IC>`XB{sF&60xjp7vfekX+gq4_lFO6(=t;NWKvz*q8qP@; zA>G~Izeq1@wzTM?INL%<p%uI0BK-I7->xz0N10?IY>Jv)fpBPM`64YE>I{$`NkGGG zA;tjQ)+f;=*dr4?Pj+3Vo?WH_PU#vbv9>dhACE1M%)gaQ{Z7W|3m}37ACnGrs+Otk z;f=$hsH!|9e{d=Letg`tVVQ&%Pd}Nhybv`%UGdeVh>C8?5$nO+y~o9Md*)GG1bxev z<5bU+w9u@h3-QHdlE}@$>Rka;|DT!oGNhBl)Kjl?m*_;Y53~!K+*zEMkm$X0GJV?% z`pId&Xua#J{IdVvjL3joVB@f2&%FG_m9i~Ftjw^f+Klf8Yh9&;M>g_d`*WHrh;@Bv z7P`*WUr(r;W_wE&-f5#Pb{a~w4RhI*vb_+gVB#A3jq#ZZHA~j_?Qb&_PtYrh_b9tP zEe)<C{auS0;ojUa9?phV;u*{2;kCWQjhzhYcE`r{*GX^jl}v7rx8^I=5m|T2^MCNQ zY{gL>Rc9Kc(anbHZOW*p{W|jr7LmDm<uw4EeO+D{!%qXHR7j2-NX&WmZzim>A6ID7 zQ;zoBEHid<zPBzZ|77Eng%O)6)<1k)*pzzZG@fyvJ9xYNEH4FXkp4aq>Iwj^h29~3 ziou26AM<<#Zfyt*Z3w~w+B4F-K9A+K@$OHj#2A_3Q`}ec&cTb3B)2yNhsK(l>o7&N z^<@NmQ3@InA3<|g=nNd%Nsi+K>v_cgk?GM`J~yjn+pD6^!j9BxJ|{ZT>SAZ7xi<AE zs{3hcnN1HQxNiAYgLy(^ZT6;P+x$ifdrGg9hs8gScZmT-%98%F0bO2+Zo^PwA=KG0 zz*V`HO5HGg>iaCi6~Bgvutp`$8Vq(wCyI*?6Ys@+dBUK1NnH{P&r54?Z40~FcBJ<B zZK@{f-i6Y}t<KfP)Wmp&7DxHortZ4X8udwLk+eWdD{m$s(V+^lCM9_i>f92vJXyN) z!<;(4dPGVFmF4>mNN*WsBHWZ~37Qmp8qBfjoj`sH-}ZZpwUD~Z#f<&UzNjapR;Q(+ ze2RK{t7Yzm(v|)nuQUHGxWDSO&Q8gCf9}{Q)wxCu@hN>KgK+Jv?H|s*;IUMs<=C{Z zT)d2U11P@5m8@m7Hr5LiI8zRPOWppfHN?`*d?Dik^&A=xy6L?<c4wn2F_G_9;>4%D z@;k^%-j7j9z9Bvkzi^pKMTGGhBDVJ3{I{@<L~pyi(9v%}4KUaH2HjR`K1W0QBLbd6 zKQC(D#?SpesWx#l&G2HA_)hM^@&fv}a{Ahb_en2qk>IBmNf@E@iqFnKbN0h=WtEfZ zz2Ah@C#yzn{m%-8<#Djq`VLw2P+XOdp~%4}X@gwOQzPE<_ilwwCasmj!l#`tR=|LH z#r^(rsMuAgJKz3{A_D%JI(6q`SIq{tcJJxxa)0kGJweNkyRM`ZIp)BcQ73z}#|{d? zjWp+~1v-x|QAa91&_YTje<a6I9d;M|K6Dm+uNaup>Njk=;5FN<k=uawN3eO%(4>pg zV~4gjEOjLlJN%9j1W4(c<M;avulB`HZ!cSX`|sFjH&gp=M)C^Fsof)5p|^t*B)o7< zTtD1c^9#5j(dgTME`4DGbzA?v9d`RT*TZsPr<%IGz8b|K03Y>;Z7T%-#wu2vs@h$t zX)Hn<MeCChx_%)L*Tmxky0>yFc5C5=kO9hJX+z#Q>f{35d9JmJi!tr9{YtKV7h>xw zr$|b&>4JPy)05|%Qh4`S@sTg<)S9x=7vEDC-F?C<HNOS8T=Rzm{>h16u8Te-=;^yD zY<kxgIYK`UZj}CWloQ|Ja}aK_PCu8&db3|lLGJ5A!Mjp)<4mesrq3mt?7ptafru^( z%V%%<!r}ZsfVBk4VPx}Pg$%>8#v+=RnaWp@7FNq@)-pRgUJ2Ht(4XSk6|?8$9(F8I zJexHb1Ze!~RhN&EWxP(41_2<ci`r+x122CI42n4)bS;w_6y*c4^!egOOAO%rSOL2- zDY<`xBW20k{@kA#>IdI2{KKGJPPIQDjC`r$lJEWRq^PXx+#SfhOu7CzSpOxqpFNs< z+e|2K%J0KJxS})<DlbKir5VkR%$<FhQ76_IjzjB8nVdWvTSj7%ThJWcHa>~`ULFnu zjBhKS<7z(&{(EoieUZtD3=N9Aa5={RQR48iUxXGn3MWP9!!9Hxxk*z;OoKAb-f6@4 z2hP0vn74b7VIO|aUeh-us2XytkSFZV|LYSjd(RSdBet$G_o&5rLG^dd^!iRl-*h2K zrg_TGtIHuJANhC@JI~@`sq*x%QJ|>H`FH}?eb%>cn{#^ZPbO9>Ca|_T723IJL8TOK zE4=>i-1B#{Qv2|Ch|trh=l7r^S#hQ3ezG;jxvfJlY(w1ughwZUmJi;?0dA~;{h<i9 zK4U5dW3Sh>D+)N)0j0aq4Y>M*Dp{^^N;8*{Dc~q<<+zU~8DW0|i^ltt{aU~}I%;6s zr%09O5sn$zj2sl!LA3&gqJ-0Q`+N3Hp<iVe8r>g7e%$>kYXIy8$N9|Uma_{2aS(oc zTcmx02`E^mD^Yq-4ZDh+b32$il|X{A8&P*;YmUfyvPE+N%?|x`Rc3ZD<swHFlV<CR zH;oaSgJ};;vP`so@$9<r1fHzUQx^HK06;iO&puu^Txy31H=YgWl?zX@GSAUSE5BUd z?x_^;5uI;DdFW|g<Gugoc^1T2xKVGHJ9-#$vP6$+Z|_t9@fC$YNayjTTI`JYf$!@@ z<%n*+#*(+|+yL{K4aaKK7@zqY*MUo5*ZF~?V9w`d=>pV<V>>WkyQ2qG1A`+T*&Pz` zM(>Fj8z(4?bOS5Vig1zE))dCCyP5E3=2n2&#U3y}y9Gm<j0Cdb^)Mimn+NM<^x&j; znnH_HB3qu*8!#!)%`ZkGuWej3L;WZf>o6v7{q362Wtf7g<&{Z&<`#azPFxDOk8Yna zam+YG0&hU&<}r@=RxV5ENoSf>LVGa!tR^TNe$w;cL?zyyhJ^t7eAOasCmN+i>MBxo zWb4_#Ify8p!d3GEhNyT5VD6~y;)RX3o934i&Go}aX<1CC-W?)LSMcyy*!m&zPH)~V zi~5`rkOQKL1y&ihrAS;QpGRjCxdOb5y_-U|BfEb(zr{OVs+Tab+ocyNvQ*rc1kUrS ze=2_1Tf5~{!xJEdKY4bn48M{wcds>G7=nz2ob;f@LNMp2Q*ZuZHLN~#%01^K$`w#g z5^sr})~qRxJI;W!be!Fepd-qvfT@`V6mXl1MV}CNcg5Jq{QA1{kYOR8gU6gW3?G2z zy>!JFYq6~b(Cq}d0%yBsSdW=<(E$7^{hBx(+6%siw_kf)iVvv`vCY5ucvUn1*#y~I zu9U(uCcitB;ThRhR(AQ-FAMm$QtVr|?CV)Sk#!8fkuHx<==m|*?0~nh9g_JMRrx?m zZ0q1T&(HD%4rT7G1Ts+lK=nh@<9|K7P%i*r6A-4<C+7)AsR20x;@Afs9j>l#A-&Nw z3pxwV+)o<hV=q}ezL;`oV|?S)91bs*Dl$!CSd@A{juc<y$UFP3_tvuI{PK;l3zm8N zFC=MsJ!Wm@Do0Po!ADOz-*3BL93rCIdxy;b6sMNeu{5Vc_QdjJ7V!of@(Hvc*#vSn z-e-$$+-&N{*^}oK466iza0r8GEZzr5AoszqDaMJQ@HK2eBQ7ymgnA#vg_Dlsh!SL5 zvq61UGZ6{!W2&x+D(@%*(pfQS5uOs&QoRP+W3jd+0-0K1z;;-aH<d~(>w^Q%=n$Pv zOFF@IK>V=m;$`T}vSSxhF{*dsBDfx^&3C}+wFk?@c268ZhD*QlZ<$3I4TC>8@+9yC zL`bMmzo06gRPt9RKtT|kK?l4fU=L>i0^Ut3C;hdB9-r+zXmn&g`@U$>gE$HK7S;Tt zgkb>C*$1J+?@`Expa7t}h_i`{nL7SX_POz}IFf7Row;4A6NR_E^|Zpr0C8S#d6=A{ zQP)F>5fOVovF^p~({kMhSuXA_CttWpc&#%m*M}2D`!*yz_mwgoS*vqCcZ<J|yRXC7 z{X!OE!Zor;70qA)B*e4Z^IQ|7(_|4+8ZeU0wFfwz`>dSCCg>tebre*E4G06WT<PuA z;$?6^+7P{bH5YeD8^NhSR3q<a;<Uwvr8yZeZ;^l;cucU95GcjmD3d%9#~a<3Koq*V zrS^JuP?9RbMyi0Buf!3%eEd5X(9;_4=2F+@%q6^Nd5xFksEVN=Ah7+&kFUQx(T$z! zVJegJ7;g++1j5ZAMre`OEvUQys@3b|b7d28!g%-g$~3!xD;`Dlco@@;jvcGc?`<44 zu|RXpg&WsHfJPMEu6v(D=?^G@52b2VzgV3J!|zq3cQVP?g_t7hokRLkO0aL14`)C* z%~mAMxt*c0EOg9)4G0*)rmY_JPdG1~Uud;|)Dr;hyE;{`=(&~6J3G95^$}%ZtNmj) z#M3@1m(Z1J8}yK>Hry{MofjaXP~;S0;}aa2?8im9hs6vuNxpqtU&!TL=ss$ya(^9K zAbaYk77y9$8f|(v^Srv+=mZ1>%w>Y2T|+jEF(vo}@hsfYj!dW|-<9QEum57*)Jus& zh%~=2GB4l(mFufT?--i$J`gD|c*$#8KR(@K^7N8hi=~%@7}IhCohZt{r@2uIZod6m zav4$N*%Co4$8KaoB&7467j?-Faz)@NN!|ar0y?xLhEJ$lIneduDNRNj7A379*q81p zl>PLXFe5N;BMk<RsW<5W8_|D!_X~aC8J0I}n;?x%we>_@D(m#HH~aXAs<%R8L^ruE z7N#%QO=O;+E4>3Zi(dG!{3KKUgRIo6VV(+AHBA+i?>c$G$@+xO@6&>P7=ndc20HT_ zfu5k+f}@2)EYp*y1LC{5EJd@_PY&5>U_c2Ge<TlFLoSii6%*ye<L|y`y3|Ms6cR!7 z<58=!bkZ{J`hg~%xxRt>h4Mcgfj#@+CIJw-GTW}Nf^`@#tTH<5z6?Uj=z&)f0=R`z zhlvYJ*LgoV$hoeNuX(f8s}F^%7upQ8ujR#k<{#w&c6=!EPX*V!%-)v%VbdP@n}qh~ z4%kF6sbvt8<`DfSCYvHt_z}-@34#GjWOI1{@-*k)=fIA74aDtzdk4yJXlpbKuzacT zt>u)sd>2a}>$#)>j<=HqkfO0$QO-%+>@S`{4rH3kGo>lR`Lih%Oh53m!t**4s!671 zW{~20gjO<7In6`{1>z8@S_%_>G#GhgwDzFE(dDhFbxd}X<rVT?<>6z)NIIvHWQd`* zP+Q#~%I3(Vr_)ALd_;C}#p519ICICoLby%HG@GJR@*b{D=#U}jSX&d7fLhj-E2lp> z^VH$wAbrrjea;Db@9$gZwHM`#HZF5B{nwtpuar?Gl-IcZ_gpI9(ntLL`O`N0d0mi8 z7qDmL?=W8Un%ak|3#&)l4JlBH*DYULr3l5ZjmDp1aeleOLwR2$Y~<+n-aJ8VXGwJ( zJV7ki>bCosP3he)bq<Cw*-zpLX@%^(=5sGw#2FQRkQ-W#YhHuO8M95{%ccEgHR%g@ zp#Noyqek>8jH0W-`oI~X{yVRZtQ8_o*6l;S%oB({_Eu50{ryy1^GqYqopmq9muTOw zu1NztUVSSg&&*6WXTa*xVD;#cMXZO5ukha=*^|9?lN#$+%Y=Vqc*Cu6K%uY_L=@O( zK<s_s|29s2GE&%QjLjIyO$eELBCocvHQNyhj(N|li2t##_Rk@{+D@BW5nr35*iBZ? z5;o>uCF31)doP|O4zmKd;wN6O4|ysS+<7HDfgZ2B6<-ZyMT#A%i2qg`lV?trd>uV& zI49AYPaRnhH7rR{;XDCbOXVlvi7-<{?lpN~r+tRx7Fm&$(YrS!l;k9S$6+TgPgt=C z&g=L7udf`mQm=CsKYk>pFUo{07%5PU<-?4$*2(UJck<j$I5ke4X6GP6%<)>b*X!0H z+FV9h-q#{bUxiJ_YN{+O+tzdS(;SMpZ_7<BiNCqv1p>aWidrzxx_zVuN*VX=<Z_Jl ze^`Qb{V69DCmzkt#Mx|xRs7YS!cGkH_*OaoaS%ylyD$z`31jFlrFEC`5Y7B{V%8ip zz4hpK^e6rC0dMs$)!+n}PNP+#7RFk^KB63=2C+VFUzgmsg_gzFe}=hT<s(f0^q#?B z8KgIO^lMv<WdiSv)1UOtlZ0Pilkw9iY$4q-co+`g4XVWh7@6eqTtzN-{0f~D5W_Qb zJ+XwO>?4G!0Q2S#qLhj=9t*?mR6C;bY?jXb`-;2^;Wbl7%Y^$A>tN0!H3G6^#XiQb zt)cvt(rbA__;O*0JyZ9Z1TnlOl8d5Gev1pO5&aC-4g)KiCAedP9EJHkLZL`u^rIbN zjsAi{=(&Au>sG7TKm1JJ?qq5R*KJ>qc?GK9kSIEx<NmQ<oYr@TSbO^^8l~=AYXuGP zji;^)o{cTs2S`*NG7s30OW&VYbzEJ?I(0SQES)(W^Xllm_f!av9K~GTjAhLb8JWH^ z@sVBU&Wi4}b*IR|E0uwIqhju{5*Zwo1_ni|J5_i-Kj?!^I(yMYh;@q-v<$GihCY(O zk8F$SXW`MOQta$+xQY`#;^XX3N@EE8TUfrGb-W=j=e!ir^Ax&t>-L@cI!DB}tGw|{ zQGA~tku+HyE+|K5<~dVdU<h2=s0-F)?s`58$Y>h?+*Rf>3bQ-|!WCQ;x}bhXJ={nJ z`#j>0q<-&&qX0jY?j3at>Y@`AbxYz3FH;FHRG>)+{xZ52S_641=2ql=zxGZv@oipX zR{l+CbG{nhi^nHelJnw;{{Hn?J+I%ZC#%?NrQNVjUB_+j@yM?v_TduC%KG+93-);$ z>6RCs`o2^I5^OQ}OJWl*ZIM=Y9;Pogpgew8mfK&5a(BEIzgX+|V}(FDsyksGdUDo5 zJ9ECqZ&x=qG(q{D{@TvHp<ubcM#^(!r7cWhx~%Ip2@(51TCJz!uPlSJiBp5fms`8h z9OGt&NzsO!Z6_z#oSliT<5i`N=(DS`0!-r1Ox_=~nngF_9Gb0^#p0~oqygeY7*H}x zs%RlLLN4yOrrHti{ukHZG#7wJZR1^Kh`@XwKA0<TgBN_KMt|mp#xzsL{^foS-ij&T zM^<mF(928l7|M9MRD5h^?$Zo%0mAAy8n4W5Doy(<)EUcBjkIu$a2=_Mn-WYNAMFv@ zNImngLL2WHiI?)zL%dAZ)^bO^bf>QT5aBBCo#%X%ZBk6Yp~w;Q)ksP3cH_>iK{F?o zCoLgn{E$*-=!t#!>?f<_Y>2GAl^+kx%1Tg_d5&T&&B&%iE7#+rhxm7S3Ph0d>)W8n zQu#mNe|wAwLgk2ELDuBOjK~IOhQc>idHf%SQm(8TGsi%6FH)GPh!&;im9E#aJ&kn2 zOOJ>IR@!NPYDJzRN>9a_G*LUyw{Kn`M!k2&^#|}nP>leRMw-Y}1P2ja^*~bs6!$nU zu0AM{?<1ay-|Kwk1X;PDak8IS*Zr-Ao1d_02ve_FH@bB3WodDfY>ETjTcw@+udmo~ z)cslLZe4)H_wDdiu)Na`aE3~Px^m->g({ajclP>^8kh@0PZ>3yyl=sOPq7L^4jZ@c z&>_XW&mWFo!Z$i^s}Apw6xq)@g0mu=(y>b8ldSC|(i;6dn8X=-{?UXu5dD5u*gvj3 zjNRHwL`(Y9)8S98ki^-CIjUpj|D4(b{P`uhh>kqbyDOJ=7y{p#JnO53!G3-Dqx!qe zlJEq{tlhevCj5$m)D~H*ZXWFd5y`*&v-rP<?4KMFMeD9mS?SgX0$$$#kmb@z`#)vP zQ6`cY%E;&RQ80;osc;evB|B3Z+gni004S$Vt5BTZ<_dAoeu@`jo>VfvVAZrjgjOMl zx#xc?q*@)ez>Sw}RnlYRx#L2DS+w&)td5Az8Jl5%sa9OJ`Xb|tU&@YCE1dj!**a0` zx+?yPk`Y41h?KGwqYCh;n^#AQ@CN-_;?|!TduhOojYxB1);gPgdZF2*>>r-8H;xbX zQkD?F$9=*_DQe_IoJn_7R#yhpE7%VWzxpPg&Vk51IQP~$K-<Pc^v8jkYPJsBXGi7w zzCs_-?h{>B1TCHix<y7Z6c#xl(}yh*$CoJX!ExaD$@oSG{$03ox`ta;hven|e!vEB z3m;Wc1CqAJ#%ZA(O7~pz*9NQ)w=s|cAMcaGgf8W)lJ?Mj%@916N9kR4N3SUnHKY8V zcy^TE3kzA9my+ctaMSzX(h2I1j@0=#jn6a>pyLdu$Oj(k$CJd8=lheDS2+ZgKb~Y! zYqqVh5+ZBg*snhL93#Ajw|xPIc4pI<-6%?dnXw8<Deu)%L#R?hU8w6_RUlU*%JjQy zTIliJtAC@w{rYE@d#a+UZcumP6`l}+(B*XYhkriF-ffpllI4~V&n0lJSoT4>xjvMA zqxhd>p76|F7~E0<k^Cg_Ku)Iz1sarfVCKYtg)dm;l<d;cp{ME|t)@aZEiSaZLeHO0 z(2>6Q?h?;KX8B<amMveSIDB7q`b>;;)g`Bkv=!|GvM4RVK-lfn1Jw-K@5ZMHtD)Z= z%}!?-pU(WC#rRycicm4We55omDJ_yJ@tbu0m;8t^>E1KkaZ3ONFG8@p`a`<aY^~e* zT=OfbnXNA(1XVFf;>w}b1;p(o#y1`<u$YK$BdGyPnd+JQF&LtJ@j>V++~%W;-<T#G z)M0CC?dyNhTsl3>B!WnB7r_&*{Mp`nC87v1R?KB62|XH-sPsDbpHtLZ&kMw??_K@Y zj|_j4)vb)>unB6@3fa0*1C##GI$OOjB<Ae7zF7<9za)RX{X)fu$Qx6<#BiFGG%v4B z;)N`{bxi$jTS}J%zU&keb2#AN+P%XV(3=K98%Z6NiAt;&ho40JbfQ4zf)kfl%X&;h z!F@?rv?v01aS!E0jE^$@(@<0hI?T};F)VdyY?DxWvafWwgn3utbpEX)a7nKI>hT!u zp3V1rITR^2V_{H)GNkg#QP=(3-<=Um2Y>ZmDcP5-*#4+WJLv1z?5yoEhv(4u9hIAI z(U@a&N~3r``bXc{(`^o(fMR2JyUqQQGteFkrDApV)lC_5+z!-*r~-xYaKTRLdL{ps z_|pEEn$vvACh_urr2_M83u!Ne=y|#_<m;e--TCGf@3+|wO81|4D7z;1ixC)taSY2u zrG2u_7I{rH?3LOd4sN~s)=`u5CaK#m8c%Tb{+IVhb9Tm!HX_DAUHUnwe0McOhA6Iv zpA&qPjODxBhZa9Fo3xSZ_+munCUEbPl#c5OE?o&&F29g)zsiS8lASSo%7nsu%A8;) zrXkcX?L9Pf|7junwst|dJ+g?xBDM4JLrdwRST~M$Z?!}}`!dvx&3K6gIJ7zQm5s%X zn-FDu=G((w{137+1*yfy%zk|F-kLw0q2rxHi1k&!;Y8RJPKUhj@e{`?nW9FDMdJv$ zglq`H+`#bIk5BaJ7YAsFy$a)U6fa=rxd;Wk@o6Vi&d+sa`<rH+!Y5(1=>g{HKLPPq zfX^WD6h2c3yBHwOrvi*3^jP{b47E=DxALm(9u8MUf}PZ%ATTDTPzhwCW6I_|JE*DG zYL~^4SfdMXpjUMun~Pgp(AYvTl%u#Jyeky64)yWt?|u^fcl7s%0?+v9gHd+Pg3G>7 z!M}fT!3-DuhSF|AS<qIW1JW7kfeS0qDsM;c=-Y7IJSb4}Ysx?PJpbL#Cym51rO=hu zY3Rj27Acgb5@zc1K>1FqS?b)p^$E2I3S_;0kig3Z;)8q+>MsLdNfJk_BTY`}1Y^UH zhH2(s-p$-|d3L9F=#q$h(xXCKpX<^<HPF|ZZP~B#>fr}!-I;&Np)?kdD=Vp%7gUaq z&*!Fc0kw3CoHPRv&N$u-w2s|SbWgmW{*<fkbW1RvO(8Ax6;XiL2f``FA8Uu3pG6<> zTdAH?bvVx-nC@$0c0TtYqA0M|JW?QtelR#fmS*WIOj9qhxA4~*vmbjd(1udajN6b9 zvi3thH-8#1prWba+g7ItM0K-^d8)S#@~)W~L75qukI^J6K;u1ahtTjqYOi&mPA~1- z3q*<txvLHe7~v{PzbQ{RzBsG>wXP>E5)id70?O;lP1>64p8bRLAgi<>WFF46Upt$e z07{R5tC5dnx@5>A=cX)mUNwt3cDX0=03`o!qON_iJJ!Ikj^zo@OKD#;bvCiJd46%( zZHh0`wYT~F$-a_GSFhp&v1f%Uw&-#@y^Ks#osmaeX1Ejx-7XkoUl>w(<TkY8Pu5Nv z8`LamT}cpmVE-mXN^y83yw8p~?k+TT9N3}M#x*k6+NqQ2!6G39fCi12B5SJilGt)K zckt=8au($Vn&kOP0_evZwsiZi(uh-$!&DAn<>$Q@_bM{oL$lVGsZY}d6oT1+&d%WU zw3Q!o?{xS1QiH(kLKNFtbazbl@s{bR=oyff_4$G`SVSJJTtC}g*GbRKTI>4Ew*o(R zWbM#Mx}6E1*R_<y*QSR)Z&*)w))mm4Oh9k3&dQ)wUT1>m+guyHQ*SXwso{8bUG;3D z*ZBsOf);XvqlxcCDunJg30b0Vkg*2a1tCu_(lwaM<cXN>*`szg>*0IWo#h+~vliu> zkjfiX+lrwUIvLcSgepM8T|Mn@>l(EpNf=z79A{g+^zZk<^TYal$=)4mc8?@lIbh3y z7nAyGItg2i^^>t0LHqy=k=@AZ^J^@I&h1h(hjPEmfU6tc`+zl=hrlb<<Iv%#uFqp_ zbE0FNI7Gp40OR0e<q|~vfls%b4>_UHY*2ypW5B!cgV~5OT`jW(6{N*tZc%Ka8atEb zu?LRI>RS15s~;6=<<IX$Ud)qT=vs5KvOL)~oY~ic3^Ft3dy1O~Ft}ErnPC-sQk#EN z@y+SXI9n~H0b9JhG_B5%sy!)V76k(#;-$Hy1$>VZUb23MI^SeEn*X?K80M4B<B7Xn zcDN;V#^~8?@eLLr7=%)e!AN+DpIMe!ss#EHl~DT^bXtaO@?j*FPyNnFJ=zklxB*-P zK|ZbxfEtUIa@-1_fX!dIf?a5>Or&-6&qU?ue%6q1#&H#6!CNDI>M5`t|5Gg!fAU6J zfa{R*BQ>$W6<2;hNQ~dqf(v`Yj?HRX4&8_tqC@CRxuUV_Lt6HmjKb-`!Wr}3;Y0~$ zMR7V}(;xR@>`SF-!K>-I0HAA=7?!O{SGOdbWO|$EZ1ftMQ@Ik-X(F831}3}&>1~$2 z*;{XtOuga3IRTFN&uTejoQOSde1G+k!8*&YczXTWztxIbZfJg>4`zTiGjc{cW`v25 zfbzgfVI;hTmBR73(J4NYF}$NJfeB}E#)p2xoVkV8dWc|?-)AKS?ec`n>AV{Gtjgz1 z^23noPH=0AusfR_@b2uU2?eqU#H4PE=G4%;RmCI{6*l>&5GG=?Xm@AF0e;xu?Ci|k zr5E2aJBW-`KD8<dDVYTR5+FIJCrUR>p7ShU&E`2R)h?^1y=va~4!9bllzbyZT=<K5 zQ5AcGta6(RXFAMm^TN?Zhq#>2m|=Ji2#7lzsDG>RU+rg5*6m<l7EZi`3618|6iLVj zy3DT$yP;iwHijVx7pyeEM^E2c)rs-%9kc!<mnTUQ^6lZ_X1^_@JgwMH+!)!G`iz6e zV!+&O07?B)KQih^CGQvue~7r8+gPC~KX_zMy)lB#*;9nQcij)~ctad$@9Hq!UCp~T z?k>ZFv`qI+(u~Yb3)%Op=o>H_jvdQ>?M>+7Ey^bn1n5qC8Cn7x-lmnG?c=o`p<%LE zVEVg;d1RBA?ari=Qhm1CpDNLJ9bd|35;%cU76W<1!05Gt?BAuV0Pzb#kO3os!9LQ) z7)1QgBe{5lni#~y8lO6d31r<$m}C_h9h!BCUy)I2?`KMUroqQFz}(yEv)G#Kt$^Gv z9FKlPYA@w+=8;>7n8E_JyS5_3L%otM<j1`bmk;j3Y_B@-YZ0GRBUP-;68KM5SPg#? zeVgG|JvysbkpfX=oR6f8ofsMYrjBnr;}$>zM?hADtM3ygbHywZc!W3-vn#T<ZaeoP z*krF}-rnJ#f}ZY*J*Mx;g$=j|SSoK^YPPBHu0!C(!&l)>v{GbsQ{t21$V~0i@d0&R zzz*${#^;c5U9Gum47*ZcObY6<7Iqtz-UWHX7939IpQUA_s8srm2Jl`t)a2AJtH^Lf zSF&aG4e90l-CX$9^U5JeVP=&tvy&>ucYcpLyi;iRYQM6IuRGH1fhPl!=7E!aces37 zHPz<u{n0ELLMj}1ge&r<1f_S@_rA!vE2Y=(m<1*q2IKA~hxPTrum9Nu(XwuJ`8SC0 zw;L`!Po!=#MX67zgGwB$86Wh;l*(u|N|ngRftTeb{T5t&D!#$m{`ALmPl$p0;q2$) z=aGV_(m$;p{E7bD?X)4K(1W5B>m;=&iob}(y_l0z4!%roliAC7s^MZGKOvxV{(k1t z+&@<}pxjGt_&|I;=5KnxH0n?_HoMiMdRdq~#AK)}`!$xJB~kEu<+Ps>Ltc!lLIx(G zv%?Pj%9Qr20Uewb`!*qJUvpF5FE7&v!7(N3x_<mO3lFn>Hk>{P^OZ2H)OD|)PEERh z<SYSJVtlzJ%CQ3+3bW6a4~Pmw$khzdx=Qk{$@vFCMXZ%Cfb|yvBHx6pc<m{QQ5%>& zpX~?h7$cFi&?*fxmY;y(Nq0P!QNg=%OsQC^w-O$)8tulN6|cqP9OcUI_;U0BK%w+* z-Q+HW+~H{XO5TXSG+s!{S3q2>lNmlJKA^_2*`i~lxqVq|M|@0K^cYLoGWj&NFd>@H z_Mg@R+#NZPHX~?u(}0x|5S7Sb4ip)MV-HZL{(+DdNMOwp_lF&5P2Etoaf%BifyJL; z*#RGASR#1_0A^`m{2eyToq<)w|0y~Tzogp#jUR9!f`Ot4ju6yv<DM0wxGh(1&Al~u zR$8E<;0pK56lbR8%GLPdOwGzwX<E4|Eh{bSX+4iWfB(UK&g(w+>)hApx~?}x#Qw|a z!t_gRU}fV`Jgo!w;~WG;{&6r4Rwu6^tJw$+8>7Hc2~Xdl-F*J~ws^UTxUPwGKgmKL ztc9(&CZ$iL$o)1OM!U&kT2J4p_QQ64fk(?)?e4-oVZsa;kT7j|IZ_zJwVLx2^{0Ov zL|AVsB24P98T;?7Kb=Y#ksE{&w$w!AJ8`8WQ8B^$#`15p(}V`0a$q>H9`em{?@)-t z@TT$o&T93c5Khg^_$wCf2!%!~3dhZ^qjqQK_yLJ6{N=IFC)PzvXYsn9Fm-!+W-Smu zP+ZKA*v=}v4F`wRA-fJ6=ptjRg9CqaRF0Tp$9b{2vYKfjgbrRU&H9%z3UJeP%W66% zS{6>KL$A!J9h`>&H6TgK+TlyXvOz}@Vg8Obe$zL8&#-Ytj~`B1NsNN9C|T*?N55*# zaB_}_s3-!=q279UNQGmj?f*!hmw^3pnj$PG9XOq_hqsI)h}#`Y(Of5z2p$f&@Hi>o zuX+{Pa9v+xM=M<BYWTaGGve~{^7+R`p~L`tA||FFmx6=VDM|#E<62&=wnq1cU|frW z(mJ%M6A+#e;X&N-XTZe-x;7(6_w^=T`6IftPQrQ!^Nyog`4lh3qZTFbq3JXMjMDrx ziHQb@4%QxhIs+H-$ClTjV{W6H<ghg$pl3*uv>@4IVwq-V+H7)uszW$6BN;U=`GA2v zNU5vU<Y*oH+Svpnd{{?(Y`|I0pIdqIz4~j==B?<zqiMYM)0F`dI>L%7>n_5NOLvr0 z_eb!rr}5dXIE6;}a8dmm`(d^PPoe%|dGTw7-|*VE35(>mRlqQQa#n?7NWUTSaK{zD zDRIFbhdp=N(9(<y0o>?fp>@YyhlJ;97kfJ22h+8qM(hrMf{3O%T)&sC?F6}|JC^>e z;t92Db?Cw&D3*>16!|UEg?WcVjr(Df*3hIi<U1Vv78(Av7QTZ+*p`g+)M44Gf3pLB z=dWRA{6t&nn2a?EX!eU?dkN<@Iqs}3zs2z9z~NiAx0^b(Psf{m&BTDL2nVG%afKoP zG{yuHloCB=dGd?+1rDJfDD}0%HPl)Ofgu-hHU&yWzv-*3``!jYGS;`g`cT&N@j|6q zv>&R+z;cl_@nKtB+kwP_CR119r;V9_bLN3!AHv<;K;p@Mg0tV?{d3~s>Eag&?qM0` zn-he~pqg+KX^A;oD87$0>~}E)V~&5g62q!C!L<1a-{NAkEpRn;ShWOG$vWt*S|Plw z2!xJU@C|*2Ls8bmDSn|07hwv$r}n8s&Zb0)th9BVZG-rE?V?}$1nVTBElvL&>!$yV zp#;ZwW|d=jPJyXZfnrFLk<hxtb#Qde#=uNHY-&~Ec`l*1zVHCx`slFb)wsyD#F!WL zN52jUoS^AnE4DeFcILM!Y$xg1A}~9O;y-6ymeh&XSSPmM+2>b@CUF!k);9MQ%*=RC zpW9GsTZO*^pou2f;WU*7M&R(?q+5Dlima5spXeN2=;+1~RgMMsh+L^9PV-KXX&uzD z4&5UgvSAkdz83zD94uLfsRT*3nV44TS%nIi#+ELAa0oh+B<z%w(x@xdYb9MBnBr}# zwG6pto_;~8uzu?tLAy7yaSwlaBT|QQX-nZ2Smg`9yxeEIS=+CKgf1}Ox|If=NAMr| zvwHlXte7f(hCPpmfX@nn<yF@eZUw~s`z)k%yeZi#{vbApUcBym{1gFjGfm@p+Yc6p z9z#Ipq3>vj9)|b>aOH_sT<ebHd$h*oA@s$3(P$fuw1>Yg2EvA(I_PnJ=f8kol7+vn zMY|1U-&z#`*C}5ul`QlVz9@_B54|(}6n@FVvQYN$d=mdUn;g`Y^2i=DDvQn@!pfLi z&+K}&1-jl9zN~5^7r2j~ITbL1&#=`Z=ralIk5Pg!fw2(#;3BkoAFgR179K_rDL3*( z0uOiy6t3PYu{7!hIVBE5`HS%nc-;AQ82P7xs-CZO`<L2B#O+c7<yLV2u~Y6%4fbnd zQf;DxT<BnJqABRqPPX}RCA}8g|G@4)^}mfCK(!{@=>P6Y$fidoYvJ#BJP*o416?m9 z9oLXvG(nF(B&811FDqHuhfNv6>gQ6tT@;>@YP?;py~c@2IV*f$$`zRNiq>(ua7HFI z(eFfh#N+hJV7-cCu!@Rj_!GneEzX`&Mx)$XW6X@9y1%bFMO4S1roxHPG$2To>+!9F zGh&JzUJ`6O1ub{+<{pBf>tCV6Gbz@v|9BpITxbhb+K0+*<aXhl%h@X^Q}eQe;%yWe zBqjwzDTS0D9XcE-+4HU6E?u%y;8dhP@z1AA>H3+@vnnV1SdVt`{3ueHEY{c=ZTme_ zD@3ZMPO``EVR0y{wGLYvjVYwp90+y=l?7TgFpm~BROO&?4v)~ICa7!^sT6wZY2D=B zKrL0M+|;eC$7*kd4G2HXl-uy8?3<1KMFbH+6YO@W3Z5L!;xpnLt{eCF2VS?<_=8Gg z&|N}DkE{xQjs5MbRDMLcC|SXE77E#yV0&7qx47$z{vC}T7Deq_i-Tp$=U0(#AatN? z#wjzT>u8n^_~uFT8f<-?2S_|{F1PDP<y!<nQ|C_25Vp-kvVo5HoghqF6Te88#128D zhcqw?_~<owjo+<}3S607&GohH7hxtxMd9-CX3Zwp75~&F*Ch{I8(5{5po3FV0P-A) z@Z((&b3|X45>0flJ3uOiL{m$3)@kwnH2W%J|AJTze38B2s>`a>Xhd)9y({%o_&G5J zM~?GudT8sTh^bYWTSeSiQrWb1{9_f*OJjK4T6c)TfOoP!8HCzR5Syb3W)6(B{yF7$ z8r4W0F1~QrB&|;ktT`$xZY?XFxk!-nT9Wu<G5QaN1CrF;M|LDXsBe*MF~K?33H9E- zrIm(__7hH)#T1WXlosFu#z&8Rho`M^b-<1rvFF=lC;REi<LBGn#6>9oy=vlg*DCc? z@w194m#Z92x%`O6;s}q2ZMf)n2;l}pf#*#zod&a!a*)%w!1dj^JGga=6Y<84^B<2k z)!q*;EV?~~KM2GU6v9IP8=1ITy$<ErCYlp6_Bnd%lw06L-OYF(S<$p#KA#tqKPN!Y zu!feP$dlHQro$0yuGog5-pbLji;q8ypMPWU5!2&`jWH38V~%i$lC83}ns?A{&0*@C zZeBcw<fq=((p^pLC?iTn>tmk_65=BNLgu`fx0C<*_s$QA1yvhOA7?_VZRG##P+zPM ze)e6_u=DV{KM*J?I;m9VK_VD?ObGeU7$PBt6%Becp{=&d*{QwXccd(Fyz39|?vyz5 z`WwmIsz0coxcXO|?ubjH6zZHZOn5sWlTi+EB{aYTs{W>yAk+zvyEzD1&V_<OqOHqf zK5M5A{<(cl!nRVEv)nNlp)+h%ZX)FY!ZxkR8gWvbY!uEU-M{IFw*H>ET_ssrcMEeI zOLWGynq-&b;KM>BKJbw2W%VO9>&TRvAYLH4j*_ESW%SwtCfPYw=Vh4Y_j)eCa{Ws) zHDI>)liIR-R=s}j`}WeC9<jlM&$u%Em*TT3Mhc4Z|D=D=@|On*^Dp|zPz<&murlw~ zBJV8Ft>jybhZV+YFRv`)eaBKVm+`^#?FlpZb)~bu{3tI!F|Z$8<=A>q-G5hj#DU=w zt}EaR0&q6Zhthi^*F5^|%hZ@c=N%d*BGzu7MW>sfe!!%f!>044J(D!vc9l$(O2;3V zt4ac%Ww#mxpXGRJMJ`k~8gET6X-34C?^`EzdfW+Vllcz*9r;oln6GhYPg1sP4}8{o zLI_*DKGhjGW~J5eq)h#~@)3?UKbofDm%!lrw&k$#v{+pIlr2lBtew&G<3Ho?-J-x) zrM5#uV6p=qU<ym~n#CR&JM^?lC5!~GRcN9HBwjCXtP2D+d)~baH|pJ4>WP?tBJkyC z8C=C<g561i0CECVQpIsGP?`#=PlZ>j$+ki(gkri0Tg?v!QXR#+Qeq0~(>FkthHirX zP3hNAM~&Y?xsvL-CY>G(=rbkP+q}cS&n@~Y{>yNPz<{{3>O(PRFT8~W>kmo|vn`$G zG!CN;jy8Y_!P#ck%_&bUz9E)Mco5^1r}fm0uRv?|kTj{AN1|J)Tb~hqocBzwC|g>0 zU82O<*={3OCk!!cr}@P8n}3cfRBXZRA+g?0ZEPaL(Gwt!G-?PuK2t{GfBs{}BuEqG znbMvI<{tYDVozS|qzeGS<^P&lgq+OtTc(@<$RiY$NMPdR?&f?5CtGbQv_AU@4`8I3 zF#|R`4rr{HSQ{6Jh$Etg#?WVJviz73Hi#Tr<7eS;K9RyJgD)y5bG(T12G1(C1o|_? zyr)5rlv}n2p~~QauV=gXF$oS8Arv_zH8pG$2?#V5qrJ~6Z5-ritdADj7=|mR%bFcC zX~=b)-*TK3bIpho(w((U7m0L9Ocat0TXD?Oowp}E(>7ArD0WnT(9dzc&+8cAdPW*X z0F)eg#oa~fN33+Fy+TE(;<o}tykeg5k$d^Dy+Z1DcPOhqPn#OvQEmbxEhS(v*DbQx zUQ<x6fDE3+GgX`+K>EUk_mm52yjda9UUK7T#jx0yNRz*U4njv^dryqnhR~!%|EsT> zNs{&rBPOPZvJ8>&`~3Vj=2S;BLr}A^7S`pd=O<=ZOabzRcUBZudu%X=<zJ6;frz>+ z?lF~bZdJZfDm{9MT{%fvVAC$$fpL2jrQKAi@a%zuw<ZrV2zmH0*?`<q$>*2Y-1!~K zgrsW=5_Vd$Mts*<=)M~qxbHj1C%X&)aygR=Um>pgBI?hyR^;B;Y61dB?~VHX+B{xN z`BivIafZoLXOCv7pv#jCeu}EU;H1o)rF(0;`JEj5i&YfT=|y;&Y#R4Kj|2%*nqL;v zPXp|il<E!aO+Te5fiRFDg_M80ASzvIXLT`7RN%Er20yBS8QV}>ou1sP?ZvE;u#88# z1cex(3|^iO{NBgS69_G2kIIRQ9D4}(qUxEW*zy=YYnp#BfTLdC4=@0HKjUuuic?T& z3c$T-b#de?AM1Z`QDZ@Y5A^x9MrWa+2iha(=sKom^{ki|?NI*-HB;(YQ{Oc)OTHB* zqEk4VqdmPw6uy+{SU8kzg5B}8-X4?W7v!K5)#X=ta^wp-Vcjw7iJe8SO3idN3*R#E zk_ODb9)!U^Yp1XDOfDVH3;$P)m?4!~y`*^EK|ERf6c*CY3=^i@dE2llXibAW2lJ(i zcdUYo=oTl9A&*0?MRk8}2^fWv6(v;U4$tFZYH<<8S53~jAzRpNM`7eXj1wwgHTp&h z^fY}xMx>}Eqk2^v>bT_xcj+HiR1nBM4Uk=nb2wyik)vrUyg5C))#B){U7?IyI=;NL z-px3~f^>$?L&&5;+fZ(&7xO^rC6iyBgk-*wKg9U7nA<4yB2J7qSuNW0h?0lk@1!@` zH$oTp!M%BBV@J#>>#v;y4I6gPL}I3A#!0nnjw87a7~iffqJ{h5FU8in4!`v<)JBay z#yqCbWHso?@2q(mKRy6q%45f4!Xye9pbds0^m%Z*{Myl9<OS^m=pxr+g9m6?(4~_y z(v!d8?0>Sv`vIl6?4j!Wyxe(Wp&s^i*ts2Evaq5E>nOBCw7!Gq<b3T>-A)#&L7x#( zmu$e4>%sMK*G=543PP+FNDVhb%^fVz>H}l)59}W*G_2+38`L-6;f_kxEHk5%(|vr` ze4-k@;-ix5k!lAqbnJK?{2F)_Q{Gab)7Cj3zCSFSt{pg>o4rte`Dr1gg5S`?MDF?D z2AlD%LJ~Kj%)!U(W^X57v=F%VUraFSI%2EJUkhV~Y7g!8nvnU*4?OXGXefl?kpOmW zMrO_kzBZ%yt5d)txr7dtXbtTp_Zwso5Rt@3TizV3_La#H+AQ|84s5x0ynm|nTI&1c zb&SU>7#G`ghk_-8pbt~<*W04nZ-u^l_EXBaj^A&~77#5^dobQ7fb5_;=^5QgQTBR3 z9@k3VgBa~R5x>vAm3c43c~Pq5>e4fF;^53H-IZZUy>))s>NI%7?w+MpE58ola`&^K zqP%0>mxG_94%z-pAw|r($Qe_X;m@&i>i$nYiSun5DEGcY{U^z}xzrQ553#Qi0KKFH zCz6@Y`bIBi=cy-PNa=&ksHCx%CWV4DIAmdLI{F9aEB)#f<29ZOjm#KkJo}ioI9_>$ z5@?!;h_5NqvYCHEnY)OPqy%d2shloEJ9((<UzlQvZXIild|NfE5)a8+x^nMtQAp>s zj^J;WIhu1ezWo%oYM+Xqugx@H?M&|KhNi$x^X3ufEb6vy-IbZmjk2vrU*%3-$SKPu z>+?~c(q?}&e2p7%u6!^-HaD#GgT%^i<atrbn%5}L4u;<qr_jaC_R6Ttdz_O!u|){2 z1HY$$OPUC;7q8i2Kfa;#r&6GHElfiH$$ZQQ+~^RhRverT4_rI?Gp2X>japS~gTB0p zWt-mV<N}q@p=IMz6{?!e=k)TsnV0H|o}t%2Tgja|^7Zmpq8k0Ct{vtLbM~rVe=gz) z9pj<=4R2<7z92oMC*UoZjA>rWbLpY5cSW*v%L`&^cO2$Yrhihh`_Rk(o4`)?rwL`x zKy(t;(68Ji)Lo!Jgm!)YD^g&74gIx6$luuuO%n~<Rk>QdV5!N(%;wZ5XA4*|o=tMQ zCcnXkXB<bl0-dT9_{fLnOdT5A<S$iaeyP~^XEox+4mIOG+R8ov@Z}M5P*mX_2>+Z( zig`$bCnK+QfRtm9Wc%}Iy3|ww-}K=e;UAl5K2vn3_C19_ga)KM7E-#W=OS==qZ3jv zBXeOUxok$Tk}ar7ykKT#_Mg)Qt&KC6)-DGZdU|bMkk+vFTbK92C&+#?QkZotCquIB z`6k)0|L_T#0`Y)pDrztEmIE9I#;+h^sWE&jY_W_Pq4*it%nP`?pASC|Fei|eZ=UMb z&(M%J)<TOvCJVQBz|}$GfA|uv>t03=A>W<93@Q`ZIZx$V!;Z{_3+*v89R$10kZu-f zh*@c$Ea{kC?dN-RCsSnJcir|*s&Hubxnq1sxnQ8yF0(UAsDSRVd*GJ(o_u|aKk1uj z|Gts{-PB++I&Y8v%xYj6&W!DPPTw-fFgZw|Ajp{)dD1QW{R^~mfW!l;W-Q&obJ*db zFYJ*HJcEP}XA4)yoOnV*Y3hV^KRiC~n$;Xjc+c>WMME=c`Kh}QQz}Gv7XFe8KQx9I zG!kO^5i!Kn_MzjE8u|Bd!s1}@&i7$!?}-AM8ArYciCsY2l!=VYnW2UhKFOM)L6}|_ zR`8v~_qvkN-}z*JU>D740<wpVUD?gVA}v8F1f4hM4!SE8dprqwI$e5uU-Z}cWS|2Q z+r>Y;$j25qwmmEHNh4@-(X3rw3stAUTNi$|>2iav!%2q&Yp@G?rzlTq#JI1B-$DfX zcm}o(z?*90FBM-hjbog%g!c;|4Z&A;lP@jR!as_ooST8Xwigax1($Q-b!`3z9geK$ z3><}>XHX{KcS)nfc_kh8ptiITC){Kq_xhLy<R5lzf`dPg;m&(|=LY-EA%zY(vu=K% z7+0tm3)yil>`(AR4Y8!eqm7<p6W(IEdq=bctLfiu|L`L<$tI>G8o*Ut<ptbo&tK{* zl6G;A1d_=&BDQrQs~VWBGQrZA;s;*^wHGUG2PCe|_!_tc@yL5B##TOFuc7v#1^k2S z6unl~g_2RQ2`zyP1oRaN-i8#O=L&AotoShpPO&YhOZ2koc*5j)#QSHka{IX7X|TtK zy~-23?BWz0hcGr@Yxt~gTC^g@-MJ(<cD)t?3J<&3kav9&+oFX|)r@J@kPvP}NLV3l zi;psqtPb%Af!NbRvj5Nek;h2>cOK!pN>;i-e^{rOqr*$KrvO~ATt~?etMQ7Mzm7X) zF<9y_?kGXbx%7_|_Xlf$7x||z$07i8IRNu&^7Ml^!J<&*?M@lHU&U>S2*dKD?RAKr z+LOXV#AoZsmlVxq|Le)cmfp4eZ8Jj4weay>k;y~!C>b_7121S|+~Gl9Z9;)7QmpAd z+te~N-RJ!nJh6x0yhHFi0`l1Rz)5}`{+b<|WYBu-eO;UzJKi9*z$NvO?~Tz8xYXCI z|9xX$XXTy6d-Z74r_R-&*Q}4U$Rt9Mw^<QCUno^NR0$x{1n5=KB_eiHRVZZRcoITn z3$x2^{P@!3fGbQwfJGLwZ_)V<bIDh~ORZu}`yoJbJfhOUj~bs==qu<=D=s0iGSX!} z()C#ZH3krt(^C2q3CUWm0)$Bm;&9kPxS_sxF=JObuS3X7177$+G;$BN)gdT6!iiQa zt1&F=y;#;=0DFuO(yE0Tc*2I!5QYK1ujA@id|C5g-EK1Bs-jO)e@M}|+!|MK8X-JU z>-=G!^YFL)l=bCizXN7fANpyfvg7~))++(@6!R=#JHr~ho3-1A$lN6CJu80zC&fo3 z0wmsFr0Sj4KHm-7p%~pZ2*9o58SizgrnuI8t;Pjo9XEP!tn-&K+!Y2Q(gDFj-;Ogg ze9i*e1qi|KA*bOHHSYv_C0P=pmyp2v<s-2Qcf|}9O&$CKGsJ^L47!BmD3H8b{F4q1 zl$Oyp4*FgcF1jJw2(7sGJHP&SZI46U2QI|mF6hmw_XYy~*f%tcD@1hc(W<&f{d2=I z;*#y3xOp0Ek}W)d5L%xRAH&K&+GVTx8TxB7A(Y_V0dylqvS2Ix2!F%JPOTq((ZPwx zt?>xkjf05hx_}x@*Qpzd0Ew0$1c>|uz1pq1WHXc>$B&Ldx}`@&cUL=+_`X;63#}cx zl1%$6azaX?=>dZ0I(W-H1=%E->bo5fNi*R~HKv>Ovr{Mk8^2@WisU_ycqXE7Xy<-V z3!BHmZrYdDv7z3b8plkGB-cgD1H}zq1WV|#YX-}YdPpwK!0ylRweG@Oxx7>abY%wq z903n3H(uo<$Xd64VP5*w&ydHG&P~JG*%glff}e)b@sK;NciYUExV>MZwcqT)alSok z^<+8n_w(4*&WL6|Y0K8COMAR_h`yw|2%QTEbZw59%2bbo-Dfh-(GGCtvqDs-qJ7K( z{reyVu|{4GmcHpPVU><41=6WAd<8Sn1>}gX=N)#ekpa#K`j;qpU4^Xg`^-%f;@?75 z5$oTD=oUclljVHoH2&9(xX4R*-66P2gAeF&YQlSjJS46C#B)1%sX%N7`^H$kci(Pz z*bd`;Q0uYtai6wAi<XX?6kOb#fjuI{kKA#n8Gms7x%?5z#5W<NPsRjmu3iz8*bByV zn>A#ViTL~@8uAibQ7t0;mkYf|tB;)P+&i*?0Hb6BgdA+Awx|4{!-&rQyeg&AvD+)w z$gr`dEV2OAm(N8{`N2H|yFlg#FZpw4<oMsq)>*z4eTW}bMCiH(HeE0&=0L8`mvC3v z$f3=GQV5@63%w?3+(CC=8$_7q-0Sr_{<+I&jSOj<fdQl^0Qr6%n}2-u`aiZk!r?vc zwyn!razOXtriEYHg1@poEBQ7x05s7i>$TB`^ZYZz5uLphTjIDc`tzm?O2a12v=~uv z1x@#B8)l(EN$q>t;igDUdqr6?SkP_mnBB7WMO|gmZNN7PvB&GUJB5MRDpkC^ULf+{ zlr+G0VbCB~?0KnN0XiE}T5C$@0ZKgeA%6z)*JSeAYDTT9joT1za?b$7Z1J_ukY3nJ zt`I>}K!I{YmMZ=oZ=`DE^R!m@w6gGH+#Q~Q8=ThXeIKw9sRx&QnJ>a-gy;)GiwGZ~ zS)m)ge6!CSafQ#1v_2pElR1g50Ch9Uwe#mX9+E*PRMt`<j~@v9i$oQmh5sGt?o>e! zokYxrUzKo)i9<NQ|6gAwnPHzMP~dWFcoyY1{J20Q;Tdl|Q7ViOfG`&O;IVA?0G&k} z(zt+lR~eP}cIc>74gk=a3r-C(A!+t}HoN>utB}t<h;@))*eU%*)nkDl!>gkPpIS;- zSs+#8I~PPoC5L3Y$QBuFDB-f~SLrdIROCjL@EEr=TA>2=Tl7G6H820^VbJ_F`KiGW ze1-PnakCTj)OI`qGRcMud9)@Qw2ms54QZ9F+dP=T9YD6(Fo$~x!PGY4fwsLr*z=dM z71HlXYQ6cLGTlFx2!eoNv`yX0F}p#8Z@A)}_07lsiLQ+{j%-fJtW;wyb!G*Dktp|p zEv2a_KARc7a|plwrnE3&L8Fm(BP$AKo8dx!T6Z7V16*szsQ0NROYh=fZL4bV4cI}V z+O553WQX|m)t(Rb@qHm{sLPk6D{EoUhXdJ{6761m_zt;2yMLbyDJQ)U(s;7)QEhqk zuo9pQ_NBJK-FWSfx-I_BdWRtIRM>`&*XtLH_{O|{8_)JW@yzCYMEGf;_L%vz5=Sx9 z`5lm~kVH4Vmj%m3k@Ec3hLYfZw8`h4Q%{7^YX{uXy*XfYc|pzA<3Yc4FItu<5O7r> z%^qSQ_?d<Ct4U1WbAI(M_7y-|=<HoM`zW{a(*i={%dCW9ne^z_2-O=}7GZ4Yq<z-` z-%_IhvL{_c)pJpD9X<-cm$(nNw|3bly06M?U!udIPvFPrgu0=Y@uX0pC$-Oae<cAu zA~LNaCwh*&e9HGL^Ep-SwLNT%3x9+VQ>C<d&55_o#w*gl)j$6SS-|{JwdAz)?Gk98 za!!WK^YUJK1iG%hy_0PBhJ1G*>UDy@Vu9NQqwjZKB`KRXmikAkzgi~l4|VQHDG4GK zRDLAeAB$V%)93Q$@4j`nz?g<5h6^JKi3ex!<$^Q?I{*d7-LYT0!MG`<ltPWg1D-&P z!9wGswOcvp3m`-jjN7an=J+Zu*tV{Ntr2u8HyAG695vsh+R)VT-ZsL7;o;;4r_ELf zcY>0~^JdzkZ3Y<7QPsensJym`^+Q_7EW>n2hHv*<s80Ao!e?g*)t7d$=rV(Ne)5v{ zy$d13wlDQI$8&{)#u6G4VgOUrDiu6qB}>UFk)l8^Sgzr+Qh%s4%)90es|($k$oR@j zE@Y6UhJ8W4d`2mkgPt~dFaL;I83<bc-NE@HN_1?ntpMX}N@rysRfD+i{G}Mlz&>cx z98zS)R5SAGnL)}~7V;_;M;`3@kFc@`hHa1tSycv|=i!P@+~(NX|7B<_C*F8e?Rn85 zQ@s!sXQfaSY|3AeV9k=34&>YzZ|PxYhfxllku$x~qzf5UAziagXo}lfQ$?gyS5sy1 z#cdAqT#v!cmTr<WlL*b>@VDQ|_aI$!k@1SDU@*OcZ{6F6vdDh}2hX9e`oDw_7_0G5 zk5?>Ig%-1LcbS?~;#1N1Y08JlCQY@M!?G&kg_JslLkwx1OoCg>og*LSqE4Uqv;Xbs zlA&iE9|qM00uEz8qWx=>b$^b=+&zeJ){iYhzI-X0aMgs=ZChssxE+d~Qon=?t%w*1 zkS1=;>@2r0*y0>yQ=pO748v^4y5E%F47uQ7)@HUcIDyFx%6HhZTv>61R0Pg}9wH#} z)g443^+A`B+E7m=V${8Xp#0#<rQoW-LP1_7MhEDT_qmH8u35c;SLgUeX^OJy<@q_Q zx)2H8tfGVzlXv*REyLgnInka+x6cNBD5=kh;iHNFL=6}Ao<4+>*QKi!$~D-dmCTwR zKjEd#y%Sdo$bHJ)eWY!0x=JvR9RK`6NKMdG^K}Cd&5wi2w-0@CETf7zU?B!IeWy|Q zq5g<MM#nnbgjX@1^I3fF_rjiAyPPQ7<lR@iY8anyKvraDvMl?z|2W2v_314Jz>6!C zvxH&Ww+`@P*7^#4)k{rcF&$ySl|9+m2)vYrl(lYWnssNHh2zkln>QenO%;s*<khRd zeyf1|Sna>9aU7TGj<c6vD6L4I;)ab^gzS6$uq-NGd*v74rMXR32)cWY)AuH6;=aeR zN*%eYMzOGvEOWJI9~nK%r<$JB7Ad}K3Q)>_SK$%*$szfo%azn0u{n9y#8KEveqe`} zyCqi~ir?0I#_O9i1CWD-4ALc0>-UZJhlFfeDCn+U1X<tA$fq8+==`kpA+bSJI>7QG zuxnfa3zqHYGM2&f1*}}TXmvk+<xDEmN8eNe=>&NLMH%xN<XQ^NN&}1QBb;O&Y}3~G z!I9hFOCo1O6We&K-=YfhqGC40FK$uwdOA5iykJom!E0M->v>Tt>(HZ=>`Yx$X&3j& z+4-1KM0`Qs;Qp><!mn$E0L`>qVkFb9P~x_d`1Kr^d4@)T<x4fq`#JW*Mz1O+n(_VY zlf+HoDudN2%2&)1`wM<w6f1NB$CJEIIQoeYq-bY=jLhK5GCt6cd_IqrC$;L2O%78Z zASyM?+Ji)w($TFQyvh(TP>>=A@bBF)lS@mh2R}6<^&^CnW@IyWY{r`!j2XsZ=sUjV zLOijI=AUWkdoz+iq$Tcu-ey_GJ8NbM!+8D@3U;0NVnZ!~@H|mj?v&SrZr6dsAi04f z2~3#lUM$GfTk)6F9GrFRpy$nbgA&cd%<p?yh(~?rO^Q$~Gt?h~#p?55KILu{NCcy~ zuV&>^1jl8Zh@Bg<=kOTOT&lRE1VSkT6;j1CnXX5iQOt0Lx|>b*bn9f<YAQ}UKqSEZ zY>!jCP>pT6>3UyU{4_zgc{AKKvGjyvBmiW1Sf0tEW&GVf0{r{!4TZl2@m^m5h-Idu zZ+#Qk-lvz3Z+@hdPTDdoDViE|v6oW#f_GyXO{k4CsTc3$MEeg5d*jSB=PtB?hs-c# ziI&!&4pU%8Ug3B+e|oKKc0%zZb@A|5n`(IREK~yimE~C0U{Kycv^EF+ifN9P9GvmV zomJBGD2VtJmRI9T93Xp{8^$4pVvPxy!GIhs+o=w@SIDb6E6bEniTSIWN{W*1JLAx9 z8NfbX;beOTJ|u48!Efp<;n;A?m)ZsTB}V|s#S+(l|GYV#=f~5oSZtaJJo>lb%Y%B1 z-Otyp2p({)mJN||w1EdOUZs~`1CwQi>+T2DC>h^`TKR!ubeRp0#co@+wM$VbC|z+t zX8Rps4tV0j<-I3la4h5*MqeiX$Ju8wIl7~rf{87?x_?KTPyDON(T)@bgzU^&{SJAN z#yxePKk(@hjfA6o>#?>q%(!1?#C07_rRGAZhNT*FjK2pnYKxCQQ*wvqSewVHthR6a z2gUg?rlDdjmbSK1@yJOxbz4yrGg(r4h5u`X6ez2eGL9BGDg^~JL+w&Pf5Ytmygh37 zlV%#~+l(X1UHQ|!PwgRX3up-lC%F0YfI6~_0`&_4VpA4~J$?HE+?XJv0%-2dGhzgf z%Yyc8H8rneEW*&Z*|BR!_cFDeldh_MSG)Qt<zad9kM14Vp$NKO8kSryF|%b(4JsV% z*qpDq+-a^wDu712)z@x)7?T{d^{PwZlU!!Lkm`ldl=CsYO2fz<h0W4%X1&-ZF-qzf z<zc40Wip>;NKN-Zz{w~5>N7r;In5VpSW*}92hVx99QmJ$4O63+0N?N^?QMje`X<kq zVB*u%&xn*mKJ}g_6L#uTI!9ji3P6H;9@7j14q;JH#Z_!8E<<Sr1b93o@k;*s=&Kbs zn@&wSyD-1=_WKw?a)?jwiU}lAFAZah4YB;GkZT;RyHZ<{=RU_oUBw$?CA=rf*Ios7 z8ZY#vf&y}O?5R<K8)mO?ydSv!@bi3c>z23TdYxR)F|Nofm@K_82jR?|A_;z<{;FIX zd(~%jdNecfjp!}@?XsZj`WNT4ewY#KwpenaNaoLCO16R3E!V;iTJBDkO_jysZ8%=- z7>kpaFQ?i!tFst$pt;$>4^2jL20{Y|@<5!TqMlobV1(PqbB%iyCnT=lF30?L)<#T$ zT6kZ5z!mcH+VO%z4t?-X2H7%QJCygh6Z7mZ#-Cc*_(7w5Q+8GzydhL7**eRg$%u=| z45n3&j5NzT8fS6x;=}lx5yV-eG9Sxy&xt-2QR%S}W3g%;(XjRz(fg7H&=+CV;}w~F z4q0{p5bKt?GJ9>H<CY<h)c@$L^~tKM^;b`3Q~pPUeRqV^ct8UG9RG4?MKZvgc7k|0 zK}we788i%#tTb!S)Lk>+?179FNdWG!zBKE~qSDS?)7yr8onPTuKw7tlp^GQh6UxJ| z6xI9LsI&_<w68c$`=56_lX4(&B1lQhDHigNBc#g;x^I7bIJ9P&Fu?WYKV0+y+X!&0 z<2_^wY4G0{(!=p^W*s@>+gzQEjDCrGnnkQSgb8wAoUz5<I-!?VXsmegUX(-&BboU4 zrrvxQukvu|rJ<qZyTopy>idiAKz#{=@cV`z+ZMl-Fzm+|TirRhfr?tnD7)#f3i$f( z<E4^H_6~<Z-U>)|&*oibWzL|$U8cMLAiLuz!<R0$2t*E>rbk}aT%?I@X#*W}nO)PK zR?NG2CJD#$ZWpY|H8d<AXpb26Os_qK$*?reuxc|)4jeE|6Z`KEE|`b*1E8637{5CB zJj?ll4;}3tX$A*muG7An0P10xFZE~@_qa)R@Jwdx1Ygoe^04InB)Z91x=Dp)0fX3r zGAKh<qz88JUvY$prexSBk0&{d(~3CSyL>UR*J$b0>xTH-&RSusyot2ZnK%d`_Wlc= zz6S`4aGUJhiE@)x$iXE@VlFGd6Qb%2Df5Ip+8t&urfcxh_U|%Nt0B4>qFI)A7!p{Z zpSEsfIpcNR0h;!jYtSH>*2qIsNIs#XEes^zVIg?lBhv5yO(%wDOJB6n5#kTdU>BR! z4a=0>9W5?mjm9v7C8w3>M=BTi{ATzZ<udGj$=+_V1#H24qWn^am;6F4C@(E$HA7;l z^umFt^f%{hpM|a*w|kc>yNF*A(W{xM-<rj2GZA&xS&sLjIx++M8QNP6Mx1J|*CRr9 zW-vk^iY&DaWqk}Ue=uuvV%<j3i}^pf+!4oImM^U2<NXf~wiPkc70hW$q>{;w5VZm# z!MqOdpPq?yxP~;`-Y^CFLBJLrM^=_E7bPY?&>c``xD|c%%s=Y^R(FGxZV%r2_&7jh z@`z27BTI0SsQcP<fWa<lkbvc~uI8@txiX*FORzp9Kz8xRmg1S8s^Kd`*Oo%BT~utp z2q}z9&I~3#J=SHt)a7Jc(ykcslwCU&h$~PMkxt{G1w+iEw>b2XOchCepgh~)poKLV zCM`E-GE#*MmoOfoXL@b%4<=_`vv>LkefH76lx1J~5*YXo|L~>#?bD>rbP{B;oR`7O zuw1P)BR(iE%G1(Me~L)|TEw#PWD@i{Bv<8L007oE>q?A6@V}zTKeG-iRYg`uC`+KD z5@`hc!E*il941Pg3zl+A)3-dSUwgA*P{;ZZHn(f1@GRec8(Trt%~~x~PJob2pD<#M zAcxC`e)73*fv0{uV!EH8z*Fb`NM^-0moFk~w#0?P_`@v)!WJ_YD(B06p9ad=Om{mi z>7%11vJ4<L|738Q%6aHeE$Z8`Jb7nZTt<qJmQ_@{{9u`w)va)HX7B+(k(Hxl7*KX7 zHyD<S4Wz~Y9BZK0AVbxxm2c&+v}X(iq!=YSzAu!Y%j(1auYpv_LRgCYq(%MA+7EN- zd?o67*ka3`{XO79HG%87LsYmgwQ^Ci2(bDtShw6Z-W$^XZQ`W;3-({z<;9t9Sq3Uc zF!c-siOu!y;G;dRE^j@Op2*G7XV>w*Tq5P<R5IgcGviiy<5n}%-Hmgpr;$BV`NzxR z>r^QcS)G=zJUh}wmol4o#uRN1zf)ah5&O}*?GHQ0--~30(z<cow+IO{@_YKrq?b7+ zD|cci|E+R`XA4rhWRm~tFn|>X^M9ABZ&pau?hbi~UxQ!|YOik{Hc>CKI;1_n-^sJB zr3Fx3B)3ig`VLuJM~`|lNs#oLggNiRn-xy2<~yGM6SG2$)i7#vTd2MHlgEcuwHp$B zQcL(;Xob2EH{w!B*m8F{Zk{!B>Yfpzu08Mi?%iP_!Jb9_7$QSrd;Y;hm$Cd%yzGL( z79)6zf8jenu*HY%fiAtJ{+mKPXjogG8hTaYemhrRH=P~W^603N;){=MM&T5`{UQ;t z?T?t6;}<N<<Cx={I_j6rtQ{Xfx*HFWM=M&C0=z*`x3=$50ZY3wm_*BGZcH+a^=>&$ zzML-ao33S9bl01C5M^ewy_|UMVf%#_4(<l)DtDC+A|V1#6x}Sn+-LZFa2aZrJhrQR zxwCv8<sw87;Dd8J;Q>jY%<IQP?(DK6>zr<<WbzmApCe}@<%n;v*KSVFqw1zA$lm{K z^4oGVl)&{1Z!-hS{i1g>v$~*0ulT7tEzYEIWq&7yuAwX=``Fct7>Li%uZ3E>@}dvY zCpFyqWN&jN<o?<H-w2Hvw4rF`VQ{O!<3cslq9O0Mb#|4I;G2G$YEr=EQ`u8JpoT}! zf9J7W|D+AHFTX7x{8f4LNo~4SxY>Qj7yfg?h>tV1_#>_k%+R?T39z2GepOB>89EcX z4?6k0Nn!oSw;zpt$iL9n$%G2hjE*uRTl!l0L9(CM^Z9bNH-r6($XUaD&TQEYi->_z zw)kb9yrrfRiP`-1!QPw+V>wMiYFJLl7Qa7^KQPe$mHYkcsrKt8uN&;QSsi?pSQxvM zRT2sNu!hM`$WQ5kQ)j1*wx|0)hunJr>5OB3R<5k?v}H)-sjjBU$AH^-Xe5dB8$yD- zBAZMfS3p0*R2%~^J+fkQFH(;PWb%oduDI6nd2=(2Yuh~BUgwne!gSrDg;-kGAdc;i z7(r6wCPLCXIYUC|QG<eFI4geEsZqu}|5?xy#e4l7|Mhp7(SVKQ=k1@H{L-KKIJoFB z<(9`<Ee44GND_3~)L0vTUr-U9a1hGqk2wT1XX<n6*T-^d6ImT6p5@p-tL##|#E?-o zmMl^39ZhjG#}<96V71EQK+xTsL-9jD4HqNt`Y3|$JTv8|0EVc;SUtgeooOz3IE)07 zl2PUEk(164>#(hSsZGWr_7k$?bBoV~`;o5lwx$>PTx#uI^m&ziP3D7D`YTvx-J=|T z2+geDWiJYLFBTk`rbb(?NwB6^q*pl;VOf^mKA)QdjLkPsF$~;3AOF5+e~A6t<tJ8l zHGU3D7+_>fy~4}nJQ_hnMDls>W(IMoZu{YQhjR=-rjWf}kzBY;8c@0>xDBd6y&3-Z zfloko&(#FxfsBI)AE0&+`XI;G?o9nh+KT#u<r}_-AM2dt8LJHuLCbDXVH1@|e$A7N z)tD@O$E>8C2PHUQM%eMj=tS~&wgD^fW9{%YG-9~i){^Dk!RL;v>pVfNUDy+lpJI2Y zW$m7-nLwAnZq8CFa~=1~efC!F;oIYkxS9t{BIPsjVurZ!eIH$uBC!vC2~X!<W!~lm zNRnE!T8D@RAy}-?IVQu4hFEJ?Th~#H5%%D@Ao$Pc$pbBml^j;a1SPBG^-_QO=AUy` zR@r|p7Ab^+7cA3w9wl7s2A!8^w0`<A7Dq>HY5!gVo$-WJ`k8KW(*~%fhuf{xeKe~V z^(*InVBB{eVad(|7VDzjZAS8*E1S=A_o|vN!}}rAojBnIVzEqo%6@m2FV-a$Y6af@ z)BxnfxobIDwjaw@4g2C`{HdA#;Ucj3;jCHoA(Fwl1)65+ebfGxC@A`7uJuOgD}xqB zpd0af!-rw5sZfMKtbN9Sae0nVJOATH_h1i=^nQn@^)BDN@qnc9A@(*kpn*!<E9=WE ztIJccPh(zXA-GCF$4Kt^jWG6e)-GMJY@!jFhG_w-{7eIh@M!4sXtI@gIK}#IqfY-= zs%P#L35q!t{6cy{CPO2FHbO@r+TtU8&Rbw*_Nkw%zq(`|?mCX0U1K!7&soL%eNhS* z!hFpU6F7Ic|6@9!X{}RB9oFkj@VcaEiHm>YhcfAL(6jo^HPM$;m0ObPzurV2f6-as z<qV-A-m9W}qMiU!yd*d<93)%@vTw?j9b>`r9Hv`h38p@hiBY3LIe684nD>CD)t=Ka zJD7KHgBenUMumxj$O%kY99i<qN*xcGD3uvatO1cS*U*3$F}zNn3LR0fb{;<LH6880 zp!B~qxN?%pQdjU(P9xQ?{%VI)^(vx^;qRp3KT)1*nk8%xT>4RNoKZxOv(m)4fLFUj zM;z)89d%47xAjbqOX9W&u~^L=Fm@XK9$RlwGL%-KtvkyxXTn4^y~+!)W8ttHXAZiP zdL;+E-nMNwm8(Yft^?WUY-;YQ^hIvS9LF|$UC@i}1AqVU{8RGY`r-qv6@Ho|&Hh!| zNB&zUj#F2AZpbe4tD=8}3N%k9{n+&j50U^u>XG5Fe}^5yF!a$`OQ3iYqXOLf`b-gZ z{D*{X1-k@-X96Uqc`9iEO{JzjTX0f3K2$1<={yYH_ST8j=W5Nl5%P8c_9P$n6?X=K zZG-^g?hqu8xSRf+F|;oLjC*5;kc~bmApUZ5nb(I;4~v>~P#}SJ1%az3!6K?%J+oA7 zMuNDXxqP1ateUpRD3*HbzJhqv9lm4F&p+07I;}jH%(D`kCGyZ-cm6<CPh4-scf?L9 z!x(zlp$ndY>1C8RKaN`t{3fjnq&&>iS#HqG(wWU|^^DHcTsYQN;ZpRZ_GRFv?d9JF z4cD(BZ~Qn*QxLPPtX5);&Zb9)_e`1Bn>8UbQD-PDIVpIrsKuGrvZWFMCMFIdmMMId zdG9$@w+2JTK!A|y1b0UGMCB&07low#!V7hQjsh%(G#c%%xNnP^%6x8UBzQ(!i2_+s za_<6W!#A^4k`ng#tKb*;kC}49igBj#nL4ZH<9{v0FZ&H8i`Q;XyB^VeOfyt+&(XYi z!|iHxUzqAj<OZBNnOM|%W6gaKp3Dgju+zHQL6OmYZX31Srf{J1&DO9JRV1wW6j!W# z`;pZC%`3xT%QkudtJgOjrcqVUeb(D@(R?Xx-=YL{=aGXW?Ap&~qApQ^Jf@_cReaV* z&DZ@K@7E{f09HhT*%^!<eFWx&yWy~k>0HY!z6hH6bQXv8f|Ro4{6zt8b4Q6$gGy~# zK(z2{w#wDE*)gd><Dazys3oxG#Cu^OTDZcR!Sk9ssn43tA16BrAKOX@@Jcp}Z%BPI zMgLBGTG8~?vT=fiR+M$n)ANesyu25xb-y9jMz0_2YWGNTsp*RLW2PxKbJs&tTN56F zvp)$z<xEP5<buU)2#vBBQ?sT5KDfF{Z#ry@sHqA#9|!@$^N>@*u@IFYUb8DpmJa_l zp_*C(p)f%as>(yeh(jQcT8h+>OIxNzt1W_`9j!zpz<i4OLx*tUG;t0XP)$)ISP5P$ z&Y)z8eFm9b0cfXP`k0KU?Hv3)7jx2r;CKu#O8jnyR2xaa(-=Yln1pm@me8!!(==(2 z4KJqf-fivE@?9qAnB=0ISl+BllH2+JJUCWk&iLZ+eLnvOFq8M|v8)kAvgABhv?e5S zDrMXK$R%xXeW;nK)OsjYza<v2h?Aoq`E|yOJIB4_U@tE;2T}1s_T@#+$Q`xKwek`G zq8fLVE!LQuK!^G<M>#L0I?%cY@8hHXT2%-6k1S5cloyDB=w7qDTv!Ysmc5fB`^J9) zLpe4`)7Z?0fo4mhyO?GwDg=TVjB04oG?4;EHOKG~fBG`CJ1F990HExKlr<b?iQk>B z?}R1b^8OYOlEY<G#6+r=HqGV#JYv>W`rV8{LBnzaH_fFctD`f(q8k(Z7uZEN><$@^ zD}p7D@nSum4Qp3kwp9N2fb+j_Tb|-kV&=@ScrWi%Vd?*-LfzD$;#X7U<uQWq${WOr zDgsB#{gBq?r8h*>^!F+?d1(keN_z4@1dr8EffGGpFYZ2Xx%J+1<*o#U=V*blpj|RW zq^z8w5*m2c=C=z5m^r0u#xiTHI(Tp1F)CZN=_EhOOFMb&$6;1*80oSFRuKOHJsX^n z59=H=+nXrxb}J!w>IkaxSQX?u2C@Neo`W5y>d<B^Jx8J*r{yTFk-CfyQR+=HHwvTo zIdC?oA+{%=XB8)KxjNE=Xs4qSk>PytPF>zX8%X$6GEbj<A_Rz(EIqqFt0MGLUj3~l zvfVI3Q^90IV601DEl!R|_$o=QDLj>p3saiUh*(dfy$~>!P~C6?nG!A1r2sz&U3v$m zTZSBcmxK3}Fb%*A^G^)N69XIDhWOX&4uW+FRsV{Z8t$=Zub+sObfk%q>c)#zoC!$H z7nX&IhwWavDwFk%RtMt!1tm+FeNqKAkNq2~*2||ZuC_dhE%Kav`z|tcerclq9_W?D zN}A*=Qnz`(MwYvAxI>PJ*o}@(V$`89oYc?I%Y?pm{CY(18PhyQKwkLIrj_f*_8@b| zcMtPM_00GGotDx|JDVLz@(2mEymFM^rNlQZN1>oC0A!yze)$nsa=RMk*pPwG76q<c z^U86H$-iQz|6)+rO7{dAoVSG=vFy(lc{FK&Nz*5s#>8TttVW&(<HjU4B&fo4=1@$A zNYxqJJj_?tnNW_93xrp}r|wMuz;+#)mz$Ok1CG1s%w2Vn!Nms^GMstz9G^4mBAtSi zi+Uti^*3**l^l3=lB}DboROpU1YENS4L8be%}?wwo%}KD?y%g!uSY^=Q`!Xp*YukI zD(Sfi<#@D@>3CECi|elW3qRa1KPcyMwrKiO5;7oH;kV>)#3v_tj*9{ndl%KLUxdef zUNQH7%xTZvII90r=UL+Y9HBPaFlLej+|o>!kQfrg3^Xy%>W|G(jR?x-(liW5HPVzr z3TzwgdC<T*<&~z{Y?&_hdY9=st@^&C_jb7JpU#aixw2qnX1&%r_D63uA-!Szffdx} zjrG&8Z6ZVavS>}ZjhB2r@6i#-6Eb?sSJz=n!n%WdOy@`o<5zXvEz{N6WVa2>o79qI zOyQTpgDPiiw%Y|tts%T?pbS4=`(ZF?8`sTdbyt^a0231X)wm*A)2qkc<Z=oUqXV}A zx0`M*G4ukL<NuzQuQ!haXau<-h;=ULj4j74ll^naS;hLzU<ooDohGP};Wj(E;xH<| zDIHi#!8+5&+lDi?(5AG~)QV9{)Y2YK#**k`J}n*&F{NqyP<zld`tH#eP*i&#hrKH6 z77KI0)xgqJxq(M-2G-Ky?3VkwQQy_v8G3_@lAU%ohh-&s2{gD_9}7e4MyBhUm8q9o z|2GP?`1`uHu~0t-tnbXDqKI`iNH+@|{hERUs>ffp@ZR%AxM+-a#f%14gU84=2Pbdv z{z<g5qcKWiMjbjpMzahn_EAqd^|?0<)A|PYn|*j`M!-x&63YLY(9>>=7IqZ<r(xy* zVaR?S`T-&XYWW(E{k}VZN4<uLwQ17H^e>~cijnNgf-=;E+_hLUelVBc(X22P2bmK$ zBl`$mUYOcp)mq8^W_f*~m+6%cmlkBfmC(Z)FNAwB7XY$4Z(38RnQq|Kr|c{}If2t* zWpgn+3Hy}m^fGAW=r?^+Jp_+Nh7Wk4+SD?`S@kUKu(xPpd19KyC;K}50u0+anh|rR zPtm;D!7O*+$(0g@<fg2twzz~gpT&Ni`Cq2F{UTq-QCY`^BdUQpE9`?KfC++#gc=W7 zWIpnc_cULmb{}{7$00+y*W28ys&vt8$1E-P3`IU+Sdn)a+mBSP9uC+gSag6@P%@1S zY8qF3Qm%sMLhaXD7$9Zpraz)(9AtsSDh2V93Kz_YelALOE%pS%9&nlb<8tcUHtT9- z#oJ`#vKa(e;r}Q)^LVJ*HjbYeV+=Ex!Pu8GjD6p?Xoi_F*6e#V_9cWANi{RZP7T?$ z*s>FnB$X{8$yO=y*prq=QfYbe&inuQoIlRzzR$VObzR@@&)d}){miH*M1PU_6L6ea zq<JcF8C(de67l%==dq`M1kIwXjJL+EG|*zQq}^%1H^T}%4@I>Rfs~$Sxj><v0~GKN zor=h`of5WQ9`M3*i_?iBIC1h6n!E?(0R7z3!Q|e}weSIWxQz88T@W^a+9zb(M2Jvl zy-c!fyM?Xy91j#fLuB`ea<pnC0U9MizWy{+aTFrV7F9`rs?wok5(UO2!_#2QVR?y> z5+1#!z$R8;vdF`Y3KyT7$2m6NSg64tN^NDD{d>@6XQBqrb<?Cq@k?0k1mt6MiP43O znJ8<$%44%V*(L?<$-kbDMKcYgeFGi}iD_Azhq5lRs>CBn9ix60p~DuP70+Iba`GGO z0ldwko0BsuLp-<0do0^xl@dNc6}Z%+LyB}I<@f`Q4?-{3*}G3D0dpL#r5`2Ez@*9P zXALx(N&)Ku_xl^{&bTP~F2qN|@T0@ZXP|f;2G$?ySI|&OqDXl<P-<Dd9-s|cQ6h$Q zkaQu99Lw2D1u+mpOyxftjuJ0R-A!Vx;>e3WI@x}F+fylN<<E#Jxv9o`m5Pl%3IOhj zY873NKQ>@cAyfK>gU><NyRj@QjoKl-_Qim4A@k%F3JUq`{9|~pU%sPnSpj#M4xCWn zlG|}<0Xs-(Sa)t9Wf@+v+fxEWFz6`O&pUOOC7bhr#^bN)0wSt>6Lg`goBNRd0A07g zMUwq&r}rsJK!OrkMVUA`j2~WCNf;2Chv2AkHl&<0OJdwiZjB~V0ryZrTICueEy{r_ zcSrP`-jkZBArthl2|HuEEX{B5X60bWV7hEsoV5xNQ2VjIdXL#8juRRbJcwU}TDSA< zHPnw~ahVh{O*FXX4`Bm6VJGItG|A2dpO_Xg9NgnW^RG28gLk?ia&7T9Y<JXr5ho~J z^q*xfI`~?1KO*}8`ih8Zj2Z(?WX#*DXBtjtnT)yO(~twgKG=70F&JP;gFGDk?ew6d zF9hcgb;wlJfdKc9c{C3;`=AhOKW!eIe{3~6a($=S<BZ@WKEo^)TA~@{qY`ymMZ<qr z*(dw*nY}>;ag~b#QO{{mrTq_aD!3Q@muL2%xJ78oa&$CG(l9*Ls0(T~Kf;oodfE|0 zDpad!d?s7QdV0Oe654;SDw@K!+ACw>r%1{I!LPRSDE$prvL7E%<2lwq4f3Cl+^|nm zYA1b2+?1J6!M%?j0AY3<-5E0MuTgv_5>{AzsR&di1JFTdmiPH+#q|N9gaO6yg$W}{ z85Oi{k+&&?EpTWyj#OOw=5Avfg}1=!(DUf1&(D?}>I$uOhpkLOzRJiaQ0>^E|31Ap z^^eFCB$t-?`(B-z@DWmT)Gri_J!%KMQgtm-AkwVAJV<}<xfPkR(m2v=+x0QyVU*0x zD(SJ9KO7r+C(G9R={E?lwA^w$_V_=*NpJeRh{3v7=?%2@zd|{W8E>5_c*dSxGsOfW z7Rv~ieS3$mz6}~Db~2i>3=1`d;x(+4f;k5wB6x^-AfZ5`q%c2iOOp{xWqKs|y@e-p zw{mlpqjgz<ld62*J+H@;YGSR;T3pR`!rUND)dEd^vSK!S6T_hy|Ccl8a^d=qCC*J4 zg<2mAd?J)izOkohk`ls8*|6TXyQZOptayyfprCHcFAm4tuGO?TL=gy+`pkUXx(nl! z``Vo3y-jqzO-hab)7Wv65mx_7=^r{w7=WXug>!O5uKYvw{eso6kUb;!lKIBbzfq}= z$OUIgq_Q;=vDUCz>5GqLxCrn!Cn=TNWVZ6b(n9pah|ix2+msB$Tx(sn_30J~-zXj~ z<5<ceoe%epspWDFi9S<ENWHd#`gEE{B`*6wzJy!ti>7|2Ms=%L<H%L6s<aQ+$&($p zv=$am1nW*Itf$&p%$nDxP}~RMf^lK#-tOlHZS}OjI&l&7l_3V^w~QlLBJTRu;RB-n zU*|qg8P(&xX$#{21Y;67)*d%XrAr!3GOugFn>3|qIAxQ;eeI1tB8+5-%qaD-GmB!X zF>ZPr#7^P)2Ys^@4(}u-44JS7rE{$f!g+k!UJox>>6^q~Q>-%VS$Yzuaq#EnU(i~w zcIaGos($;`r(}=qcoIi-c<7-N>h{8u{*Sh!&wj5?nr7JAXQt`?_o}tqfQ<0gIZ1N3 zlD3z9Wu>p^{&Lsc7lR}3QjeS@<n&_?$cKU{BHx5@cd$WUT)!Tt?91u6kv{YV%Zm*3 z1Z?hw48JW>Ia6R|RuSQx4qs(7Xg0#W7Cn|*(0>%q^3fJEg7Fz7MV=yY*!+a!_is-1 zDGnONuej<YU<Oyeqn@iY!Cu{5KNdCHBfIX&m8^UQp)fQ?<Wfc-*C_h@)aN^?78QDt z)0RCFHq<7a)BW4`j{RsPA^Syk6AM@O_E9h_D)sR#C?JGrcK#>9>7CJ$uSUrB{*(GF ze%`yeqQ*vHUj$S;Y*{By<v1%QFigUjib=kgQl{PpC|l=7Xu83D+P@}VBnMeK0c)Dc zf;?51GK`a~)f>1TKlnjGb#Z3m4*Uh%&ad5lZ>XV?dwE|)O({Ys5x+7QJXAXcGVj_v zb*?gDamZLB_od?Zz72?%>SR=A=m}O)3E4K$IU+TS;;>HnI1D;VDTTr=%Ln^ht()CY zar&{BtNk_RVCcy2GZYhXIj0Z8GIy}XS>nMRS<$-Q08O62lyN6wCx`{sgLv_DFH_S( zVRM+1X_0xd#-wM5chcEx^4r}7s!yI};&bq%wdo#QKJ78VZ>Id*@3=Vg6fQfZ*4Nd( zdi6buQ`E@Bgdxp&h%qb{`B%{@)>@sOY8bxK;QL+dm{Ec1vChk6+q)<CUN}<R&B(E% zH^YWSr?1$>|MG4xr_jv~T6xDBuJr1?G66>WTOj@DEt3MLIN=9o)()Cca>4A2k6X2% zavBV5R0ZAv|2AN>eKtn=2DwOi$xEkq(d-3p`ErbHfXA`zvtIWpcpiS=Bk#uQZDa4B z*S<O{c&6vp(%A%s>d2w$>zqEpRen(;Bmayz$RcG6es)8uD%x5XJ!C{+T^OFZ;E+^v zv^(_cp!rj6pWJRr>6uGW3m**<2NS7TQmaEHZ*%{6AcuP%AOGXzCvF`p(;UVaeg3%f zC$g0b7{8yepRWDEn}~&3fw{T>$!bg66p??b_hriAa@+K~`raDm)KqfxwH+G?H1Kuo zZ|=<5if<*+f@ced4$fk|{3@0RCo=9@KN#G7NATJ`Dz-9n<5;}EmWt}i?{KeKe2m(h z5A#*T_kTT;w`EmxxUAS88|rkdrIV{qgd;P!`%fil{`0`&+*GJcdgxy-d;LQvE~aHy zz-G^rSMF!-Kw$ubi&xYj2_0aShLkW$*hdEr32MM*#Kk#!eHAw#7FJ0{(l!0y*}7X4 z+Eqp(;yccJ)TKo2*d`$!#xb7Q<O9yt2JNm&jBA#-L*!U2;KdWc-*waZ72z1qMNJVS z=dyv2r-hoQlwu{VB7p`Eg%kW$hF$OunTg_O%iYn?J4GkRG5-27@cWRh1>+U}M+?0e z(LZ;kXpFZ9ec#GwPuvOwmU`pPv9cDH?#-JdE)_rPY(2Kr73XyS<;VH3=QDA9%32b7 zjLAAvx0gk<mo3md97?IZX`u1G=xXOT5yC9v7F!8VjufFgmBT`t4A=#DTQ;APP*Nt& zo)L?<j`3Cs6lPk}-KBeocBG$Q-@m$h@nXQ?L^I2-SZ$q51ynhcpwS7~=4kc+G~yLB z#})Mj{)>xqG@l+q;@Xy-Dl2-f1Q#&dq#A^oR0#wYaP_C&TN9U$;RN#_m3o+McHw2O z`}sapcEESPfOiBUpH|*Q6xeGq`&WXmP9PTS!9h{|mUcCMF8a7evxv&=M|$?$`YP&Q z51K22V>)WYMl9DpYEE{I)k!#5*@jlki1>19aTD1iWeKD#vUFH57u_hVdo|MdEwI&U zoXY&kPnYDCY%>AaC+tL71wva5jO#g0z1tLbjyWG)J#`cDMV<N}HJr`h7PTZ)%cXce zz`pW79gUFtFKSCLosj^5{fz4Xfe%`*gRZ>{i{z|J6cY{ba#!!L4>!?P(H4DQC-bi& zB=3OL+0bPY!;^#%1@t^7UHv7qJ1QkGy%_pi#JG!1+W0RFaEPagqAAa-R|+but#+0r z$7kJ?1_<gZx{pL=cE|74ws?ald!|3=j`XZ=+Qw}5kk=>O|4vL0_GS)3X{oT6!ay+F zmPe8}d^XfMEX8uKdl4Qv=dvtNU07w$8|YM3Q<>TZerUHJb>D&G5HAp|NAGw5^HN(L zfbTw-<(p_B^{MOMuiv;>Fp-9=Aah?MBvUkMY9NAVkn8dZb<%LQ;>&i0{6QYRyOlSZ z6gnysAY1OLsc+7Efnx7&+Ev;J_GWJ}<L44_;MYUZRMxVZiY=h`RY`_C*Z6Vou|}~* z+hBW_P~s!Krw)lRIs>(148Dbt@))bLEZrFQ&l(jm<@XfPD*w*Sau$(yt7M$NU$l|+ zeXBhq@>yZTaX|JzN7qIG)QVs%9}Rz7PgJC;FhmYFM5d~c4l)k`&XNcV^!qoj)a1E< z(Wa=M&I?e9`To>)$0(qZK~CW$lR_#_aGN<(;hmLV(JX$|*HZudQbL%z2k=JdV1a&X zbX?rK3&1GswAE>?1est}?lS-QtMc0R5_mOel^F3OnJraxMEz~h=p&ewP8n~OW}SKg ztvn+y4xK8Fv8D#<6q{?jb+S9Y7-$?rL@e>I>&G*Wg|_GCZQQ{~jZsI&whb(pxr&m| z4vKoeOWrN|#<}GozLRF0zemO3OkUkd!crJpx~U-!`jeCev(jS3W`gP@YEx4hI%3Sm z!fwa++~O>=Lvf1H=&tw%Ok&?v#l<*NMQsGu4>Sb%NGOQG5d@@CsAz{DI1iAdi)m?A zC@31xDN2OPYgJ0K3a$@Ut&6`NV!<##mO=SXkZifjm^{VxGsvm|*Sl?jk?$~{2|P5C zm)s>Uy+J75k*?NVd>xa!2o7r`-8GL%vOdkCavLwrC>8lwYeTui`-NN|bS~>&UQ&VU z_QvH#upT=TkT-~YWu|+$V6}PDsQlY^Y!RYBWL4Ap9G-Dl6bh7$NmH9zUL0mn)#-u~ zpsJ=2v9m0?h=^@E@9TpG{dHnoOBF@0VhirCxRwCRig)&vCKNfhIEyB6UZ);I{4DD? z_vG%`!PK5q1(Gj|jH<tRO!YmGev)B{r@GTvrZJNFpp4_F2~xh-oHrMwV>8Way7Kfx zha}&#;mX_7xiRQ7Iz6+c;?Wr$%&WR*8$nVzaD@Ww$&2LE6r_>a{3l33(x(vI6XNB? z9q!f%)0uD+JDfn=&WA8d<ne06S++HE4tLT5F)Pri#UQ*BzLHY+U&HsA)G2o>BSosy zhBYAvh6E0KEIZ#@IGVmUF7v1w0ieRU0w3r#+RGq#Bw%o0J-Xz;FAIcvrD-9o(5XFd z2&JlQGEFa?Th*@DDM6%5p4IcYNg7x+L+A6k;NBjhp6r*vJktAO`Bh|%Kv>I*kAg~{ zwY|RgG2*qBfZ)Lmg%7S}du2+OZ5_0VY$;OU8pWuwMe?n4>i|ruefydlI7+2_ICdKq z{AWU)DMC#XF5pC2tPgy4lLX!rEi<pqxlNmj@grwke=P=_;2MY^Qmff*GAwyHXRE`% zR*o7!x(EKMA}(<94<$>*00~<t{03;BYElI5U^Aswm+cRY4j>=HSfEPnKcA%q`irH< z>2Ar{ZqnYWrtZxIJwrD9sYgS~gEfN@*U4!a*eKU~-Q1i6c1&fE@LH1Yb^%^IEjBKR zYDEnlVPx6B1hs5C(=DwBN{y=(pEOw<ZThW-j@)SoHCE>~h&i{O%hV3f*==PhaQmxB z!RERSM%{~qnSAy&Cqyo(V@_{}9o7~jU3q?#7uW)T_m|4R5G`uTG6n4_P|GbsRJ_Xj z`KZxv`sA4reV~91^R^^5ay8y0P<OfgvtNUW;HJ=ee})A*_|YFl1RY~lxMd<h=9*5h zx;{f=94bA(H_h3Wj*%G@ST^@``!M2nN1~NN;5Ny%RcyDUYT;Ms!AFWV0>iJ&U6J$< znPzMfl*g2RDLE!UHY$~wFHO5CIZGJPi&f%_%as|MpFBgnps;d0-0eIHa)&wgiJhQY z@|M6GOX^P%N{eEoe%!cA{Ckug^tx#|>s_0QYGA*)aPaduYec2su5I$aReV-ERtJ)5 zdvOdAW;5*lzmCAv%mYC(_}(Zpj=Nx}TWx-JS!q-&(DFu^0%?v5cjq`Vu(++6+-~kQ zPe9m7I@P9D7EF6@voD!x$Q*s8ppf}5d|RwR8J-M;kA$_giMF2l@5zHFZl+bAa>Fu% zI=0cfgznCTyv>|XZxeQF=_==#xl(|q65_)Pe!#Iy3cyE$tIt3a)d@akFDdZBHrxkY zZLx#8uSI_#avAEC^#H|bhH`i}tyNgyD#~gqIZNOr4Ov`?{M`SQFbN6~{iPY}qR@>w zGH4WH`uXI*=4UYSd7Dv&i?sZYWZ1j-7|@{x1e?zSmC{O)(wEwAM;_#zK|_C4U*7M* z>GrHR_@lN}hICUHQY~$Hi=)32G(^e;5d+oW!)i$rh|EZg(VOT0<yP_N+fbIZKCjn& zmaIPbtBuncD>Je^vGr^T9^E_o5rkjHc`rlfE1#*cF*2j6BkEk|`cD|?G$K~HxCd94 zo`NqcQ7k&|aLq|^Cb!_Avfbw%&y#SZ{D4{OMihi6?1&{u7LWNCBt`$Ie3lGC_vfvK z(og>C!O1L-1tCs!iVo@&pWG^F(-z_jNfIzX)QHJ4uoQI~UHb_vJE^?EhQ3~nSXJ-C ziB%3r#^cBOl#lnnr}SvLCI$Rm7ck|69tcIb6+q*i^1;0WHcm7k%}NmWt8M9*%|p)o z>`BFS$!T!5PEczZq|*>aXaJlPQr4N8;<8wzbK0cHmz7ss+3vnNEy=58+sfrJqaY{P z)XWh))&V9sQ?e=Ip)L!Ot2|z0M8=dRn4>=qk+iGoK-eYoeK@0${<3;!>%z3QE97kE za9%=vF1%Tvek-ZH;{!nX5u1MmuO`;RkUstNzd}a%%yi1u5ijQ%%N>mQQr_Ox#xx<O z;&v;z6AkV;BE_9?_zqBO`K^Gf_Gz-PNC6mC$xN?YA&r5S?GuakAWtBF7YE(!*F**i zet!p2T$HKLEnS1LMw$l#P#&UYrguDe;b7(Npb)T=Ci=J$jKxsv^l*``AnRYH$16it z6CI*TcKGJbOjkY|CEa8kx`3!(ji+5_pdU79R_Z;G#bMhSh7lvL5zvnl+R`YZbZLNO z{IJoYwvxS@zz4;OOPd=4gIEkxqhiREZ%~7$`exKB_)-W69tR*_mMm5NfnJ7KKzCt- zS_%=`zlFW1MBINtU@{%Y<7RQ`u>z-$yr^C>F~naC@Vx9tt}g3ZcL?H7;ryp8wer42 z?tJ4Muea=QGd7}Y?VwQFaRfJl0UMHps-5jX;BxGHi84k5QlXzfrRJY!M1B>zoW4+R z-;S5+hM4eH&D+(`=(nU`2iYI?MnU?=*Vpw&i*eE>M9G+^>YZQtc~;dZw-?Z3fBB%t z#)aiK!$3eMJ*HZado{8^wd`-dqGg+=MI&mY(vmw+i<_yiP673xz;`!||J<BE4UI(+ zgt%u{1iBOs>FmIn#OKSXJ_0hER{&)B!d9(h2KBtufDkI!GXZL8VtEI#rEAvMu>ly= zAc#eJp^J;HIWEpLOoeGOPhL-n`z5I)7GI^TJo3}7r8C|2m8;F^2It?UTAZPAsqceb zJrGs7r(Nt*wr&AZ;goh#y%Z8EaS12m0C6r}5$~&4f3(|{xiyA{R=CH5qg@e*K#{2M zI5k_&h>*p~0e>A|;6;;}D+an+uRmDI6@Y(4oH<aP79GWd4Ul0<z6s?<FbNs`N8}2Q zd=WWfkx6_?=PxFFbzOCp7_=DJ2HR>b7%)@>tlS~}c;4!xl8xY|6DcjI0%a@uga=3S zAbS}YhGMTxSzU8TMd8%-qjH3gWmH1Ba$Oy~6Homr?wZeJC2a@i72u@o6nt;#V!H;i z+P>Mu#(~!ZB!;WRC$z|^p*1QK;=NspkA#o%LV5nd$Zt>MHeaL(Sk)l{1qU5^MVVS_ zL4j9jh!h$P0>Vac0Z1{9_!EX&b<Xc!fdz6dT8+1Lm73-MRUZVQ37Ry5mY&KYfx$Kh z1)!5ri1Al<(^GB7L~+zYd&fC2>WtFa=Ng@DU~u9YzYnxCPJse}+9M23-JVxFbO>r~ z>{2h~8X!Om)2}OjA45FbRYfa3<=f%;$I0;rYVglPqyKVqoqL56*eV8C=J}ZyU=$++ z3w;V&#qI9mzAwl8F!bF&{Q$ih2LWP{@-U8S5dglRN-pvbdQJv#TM-DFf!?s&|7^Yj z7n@NAFOhxy{7@k@xBMy7#u&jsH{#6aU~~xopnHIz$8jgI@RKBuy9Pdq>=t9gQ~99x zl`|nq*O;1K9|r862F!o9Ha1i`vmAW8`||cf9m#skrAoczdLh4St$+H?NX{JmE1tqo zPek6L&icQ1X1y*}HQ5Klry^vlMIdzZm+stQk+}7zha6Um@d7~Uc%1I2hr9|b7`*u7 z?!`6lix9dD4U8MJ2NU{vz%$SB-JnT0zPtZHAAn?4^3`sGvTn!qMXum+>445R&y!?_ zPWQ%%)Qb%vGN{u?rpN2aif;X@lkKPz#znBTpz$iZ{38_HYWh9F5tMqDXNG>$j;Iy9 zqp4d;mgsX7X?9}z1cdN^L18;1i?J#Fjay?tpJ!-JmEbN)gNT+|>+?Wkh#`2JkQ`lG z@K=td<(QMi`g2jkJRT@76NpL~htCr)z48HfadOKmUJkrm-wt}brGI#@rZ#GE%&G*0 z!E>Yl^U!vlz@g`gYT`I8lSqVoxfA}VPAfQ<t?|}K@g1MRjR_AqD~Zs~TL~}E*xO`_ z54QIZjj|w;#XG!mP>GC~BoT_%b)1Be`YV6~Cm{5$CW=k3ih8#Gi2b+Z0YjYQejR*~ zb(>#6f+_IIMr`;lc-_j>%&}Z1P^7v>nD9g6&TDYLLs7Qc>4)i6p1_^Sk4K^_>pMRn z7SG<FFT3~^BKLO%p)`2-a|_S+edgv}pX)dI>S(-8G}I(mpQKu;EttzaScwg6(Srbo z2OQ*{RJHCGD3%YXuz#2((@e}L+9NMfNGYa^G!R)Nb-?_2UC`FM{8et34&Qe2o+`F? zpss@`H34&U$a%fP>TC|M?P5p(gin1lSKifppYy;fgn>rftxXcg1Ov^@?v_1VE9G-$ z3NlNoZ#sQV2bHGK$ZDQpGjCrSSLHJ2F}F<j#=iI^R~ku&5H4$O(TxLL-WL#moxSns zHMlE!D%G}~w>qs)TxeHM<xO6b98ZCf_XZp)8qC1T{O-V2Qw%Z|N>M+CnRC)s^@rbd zO4P|#4xp2FJ*^hHgwu0331{21syyv~w=nc4)-eT;?!;u8`~vDpjBS%Ja0%jaN#gG$ z+?2{kT6yy5t;fC9BJk3EaF`oYyl`@>0+c-v&OfUP`Nj`?7v&Rm<!P6K|53m%L;BX{ z$E^eD(F7j)a)Ss{OZf$_z-y<c^jk=)hpA(V_)};;#;JkveBpAl><YKP=dj_i<+^8a z)hPMC#N&}2w`32AJ&_+2W+L7V6@Fj}?^GLovDRw)yuE34ry}4+FMHelNfLD6tV6Sp zZh&OXK$m-KO+fRe{KBYjs^~Cr#5nR(Xq(Ktp^ny%lP@+Flm3+Rt}3^@dHC<?_O%62 z<1+60A2jCYc!xCFr~hy;{ptDTr+MUg%{U~BHi5;XwyyAlJ)l8}<2591HRUGg^KIKd z!KMT(uiil1!G&s(|4Y*t=j|pvFcdzhzAaI0kIJD$i&RpT<a3=~fp4k!w`XHkFiEA< zQI+J{;yW3dXsar*I??uEzcjafvwL^20D0u?juBtur-#P!1b#8mvHpb@vXIIr{PN}k zPs;4l(gcW))Vvq+|D4A##|*9VxT|poYxJH6^S?{X9kTkum*KMAmwDC+#r?c28m~qS zvFYt@`}v20)z1WdLFu1+wLu(3X$*F7QShqeu?OtZsJG2OF4cBr@x7fo7q>L6Vw+Ip zC1oLhY4RUqX)ViisTm+-8LHJaV9e0B&Bs1Y#4L?juHKLPI2@onJ0PZY?0B-XI7pT` z{s6Zrp!n@_x%mdEE6R+D(fo9P1*}fC-%UT{Y~?$Wv^#(9f*c#<fO|b>-|>5?u&?z+ z0Xhs2k$wR*VJe8bA-2tggZ`r0&L0wBTB+d6s+XAcOAAjGaj2;Baf|PI5}_gM)iO-! zlP`abT`=@3^~_lJjPpnm9vVvj-f>~(c8&Ju4NF=tL>Lhu%@?XwdP%JNh-P<H?lS&E zL;VMDPQ8FA<_iJmWc(;-00;qcRbik;=|BehA~9w3MD^p0Zlyu!&h`s(X1#2IB=@o~ z;3%eQo4mCZAfK6rf<kxR$;$w-s9s2Hde{-*I2g&u+*rAyEPUP}3PR&*z3g0Lcg^lj z(~D;B+fI*9uT-H9B+cl6M7&G(fT9yigCQ=`U)q@XUA#qgmNt>2Dd$>Xx4TX8@kxX< zgnua+${AFW@9OzjrQa~uAW`cX-D!BjMg8J%`m@09DEGTrq869@o8w;h1jxMQUw!xL z7Jtl|(S5P1&}ZEtv&F3vbv6%rB5rqU7RkiCXi<C;wbMBe`2v6B3QAX!9x>Z;<jRQc zHSOb*#i~*_+WXwIM0vxwQ>L+V`8AfOfAy4XJhlelNBg*zH_1lu|K>#9Lm^Yc)>QGi zA(FbkPM#;4qO!sg@hqL<QEvx^yo~mit<i$2aUvpa0R1t_#DVcx6wO!>^^bRiWnKW5 zGZ3Vlb?*KHJ3)`YY31`0B0?T?ix9My8!x<wv_-_{>cWX<(LtApl%v6diafw6xj0@- z*mZ_yk@0Pa^AXjl!lArU*SyU-V*BHt<>5==vriRDr|O<vU#zvFYA=MlIT~L^&p7Ij zo4%3;yj;UDXI@DR=bBt4%uWzi9V2q}Ts<?_t$XH~NG*!w@O2yad_5tcCV^Q%R+CuI zyaX&JAubqLiYQzZ9LS$#Q6&;!nPxgY5W|E1pq0)EqYo|a<1xZeUdi}*E;J}PM`{OZ zLxzQX+QZQ~(GNnVZ^6ItO*;U?EIB~iXIOz$=3uyPa}h!drrfZ)lankg5jqths3@v< zP@i*tPu!!>w%b3{?-*>8bi?OP9&t7Ec9vO2_nGO(G1(N|@c0Yxc%zIZA*%M<9XLV% zL5s#>C5y#$G$`5VyBUAQRI*5aQfJLky%<VBTU}Mc-y9H>dAUx)s`6qBB;F(Y8=cb< z{w0^~H;4i3(MU|&Ju8t{o!pY)Xd%MBvj#sW=?u!d22_5$o%F8Nn6(e|3m^e^^;CYd zePGy{#}dK~s5rS)lQ)jBv}F3e>%Ov171{l4^VMoE@+JCSBIX=0FW=<udYmOYAZUB< zeVv%$8Ei-{#lI|6RMiYqdd<Q;u0rhTrlaZdx}Jbh)A>F}<CDi=Qb2pw$m;{6=dspQ zwYR~kjz(kN7jt4>#(o|B@sb#3Nt(7Wka3@MsBtiy>Z;Duvr*XVB{~>KPtBsgblPwC zwj&xH!VFu^lTNt2e?!7!j8ZiQ8QKFctRt<&fZ<VaD?7VKtJCC;#Coh5-ER><LnYdS zWX~^D@Oh0|<xHe%XoNFR!2n%K{E~)UQl@Yy4TcNGA<?gwt;csT2c(-(!V$E0C|7M@ zqF$SrJgTO(nxA5kcHGvtfW#ay`$~v#<2{%85!KmFB@Vk-&K7toZI=IYo)iqAee`Dn z_#z4wQh;#&(PCrC#vV*^`wGfvuq2z%wW<H&97%1vF!$Jem6+*)-=$OXYqxU_HP}52 zhnx7~F2&Nr4%r4}swl5^<p3IL?&=_5#8gYojLEjr8&&b#xTj=Q%lKi+x-fo*nDdd8 zO47|I_I$&Lvl`My9X6K=AE)tmRdP#pGWda5lS~sFTwf)dn7)fSWwBo3G5vf~gK3}a z$c?S~P0dHeo6V8aF3K@vf<_vO7S1-RMeV(n`$zl`5UU`w;!Lt&XLM#5JXebo!tVmK zdec353Fb$N3hH$(#WLPFE4wzh9ad!T3zNP|OILnelN+R=bkWmvW3K7D$js3+5f7g% z1=%Fbf9+4f2Uig${HxCz(O>09{2@mQZRe_88|3~QwK+H(BVrvSNm7NoSPAFqq)H$L zK*brT@l8(Z<OtF0Lph&gqDaxtc0LYSEJNBg%)fA+WUH1&6_bG8R3@ffN2}J58-%Yd z*lt{(*nVr0shb<OPBDs|$o?+UG!;!7GH!9^H|m<^cMxxq9HWsHl69rOmI>My74l61 zvAGGcOwrXHZrd^a@yq?Ebi{a<$==C#JnFD&&IV&CmKi0N7t=~aYf~@k?X&fB2guPY zgCx6PQI%MAqI2VAmwNl7jT1q#KS!VB8?kZqPN(GO4W6z!3_IfBTezd=N4?@CJsWdR zE6!Y_DszUVN=JmS?d~6ZLsn+aK>J$-8O_^u2L<A_F7M@&pP@nlKP+6TR{ue2_FlP* zAepKlvltGK7P2oQ=oRaCFv_gCZt|bp=atGDCTVYX>E}`4u82wXsp1vn=`N<|3L)Kg zqpb9v<@z0#?OU5%64G}kQQ<ptl)81UAZxh9Q->JX`<+Hwm8?Yt0;xH&dLkf{elIgM zQ&4mdEy`Zz5@>5HfA#0mAt!rl_<Ob>o6Tz4b>?%UN&$U;&>OvJnbvQQXonT3Ka;>8 zqv<13wDsh`7hcqQ0`~<-<?&Saj_#Y)*|a3gtN%_<;|AM56kaHP)w29q4O3hS-qd>% z8w(wJMmy#y@{28q>`Z2bvy89L<{X&fxs0<}D$iqV#`XfzMpjkQRcF4)q$M=nnc#b2 z?HlQLrwPl6%_=!xmV%Kjy6w3<dAU*>I(fY><mtkqz9*zIOxK#Fit`>Yb?(_rzGZqJ z9>;^S0>XeP8qrb*$`?ANS({t(TvURq@*;B}$9qyf{o%A`GZbH1uqu*&-2f}sIXQEl z)D6ezc=U+pI%m8A1Nx}rx8k?6_OWUa-KU#Um9NI5xg^&>C%O9F0AN&l_!=h%tS27@ zxGRK?wU20~T-$qxmNL`+zGV|^9F#t?`r;qk^09Zne6#)2y5U`j?xIDp+wo3O|MwX1 z=^`p5YXwcy5cJAUqW0y3M0uOaP3H1Qq2N@%jP0Gf%k??`ru<R(S9kBnBZf|@l>2Ev zo^rc&=-Zudo^4933!^6W1-yR6!NuRw-m|B8=^fUJvlH_7#x@#vn<_DhRnKHXIqtrz zH-8RT{BzXI2q$ndA${on(+AH(Vt!k^t`mJepBJ6-1+_q13mDH5Q0(AZbCn9tom6?R zJB-WmOnM@=raSVI3l7Lh)y_g&%E`VF=-CtJM84?0gMQ-rauiBGT5Rrj5olk!+!cac zWyY?(fSHmUg$JM-?GRtKM(Qg%sp#m}9f1P?e7=Vc_yYCdnCUA`WP;J&%OSqYVQ5G= zIv@m?;we>*fp?re5d0D?xN;U7hORco)Y(J`&qT1M@lAJ=oiUUoEH<JrbV~OeI^f)0 zuM-x=0p9@rTiwq8u~>sVX?!89tJA2)9mE(~WsJ`ISA_3uwM6-}j*Hj%U_52s#`hsw zV38r<^UC+=-06wI3ut1pAS784hqZTiQ`<iy96*ZENpxq#%Iu?^za3@VhMe0G6zIt$ zaSI;k@QDE?BX~!GPVCtq=+sQCxgka+>7sClY0w5jYaipXhfeTLMo-&m8Dc>mzd9IT zHcD115r1AM9vFPSIDx|dQn6PU+wFN`!C7F4eya2fOHV8%cjFW%wC3s;)N>u4yUYBI z1AKoCcn%ud`AziC6&j?A>iWJirXY0D;{?@ZI%=@;^oEys8v@&kpos@ysKrh|Y__mV z_VxO38dr!%0O=nX01U<gAkzy13x)$a{UT!R*||OJ<ST-g!clTMR>02Dyn2Q#43h$< z3s1X|gNe>xw6f6I-T@h>RIpzVYOd4Sw-7m83OTpEbI>cPJto+9SFqg~*xWn(&j8@Q zvO%z3$`}IMy(vuz=b!H9e>BbiVoDisrlLd4b360qlurYdUfgl$mD2P#{k+SSsE6%n zF6#>)sMyb?m~9*Eo;S8|*)Yq<$hCuKTMu&(jt)e#Ex*C?f4K8dp}2nO|N7Yn^!FOC ziv;&~1mEcx3kGoMEhp*6X2Eye-UMT4AY9ti^!;i+c0CJJEePfYW*!$`n+mV2SM!7* z|AZK}G!(q=IIQ`;pbB2x`XldBK5hF7#Vt<ax(6#ep4F5t^&W8jMn~Q2h;*MmHPMlq z>drqOi;Sl6XAUA+1caKX3W*x!#;eM9rFdl(?cL^-6Z!8sqo#N8%1=(edy;LVhiy>C ze)q^w?BM9QE`KpJisC^Sf8!D4Df#{CGNUJEh*k0#j?w5p`3_wQf1{CFc9df`#Py57 zzd+G%N&(PAYBWX+rv>F@qXS6s(^<yc*e)yHuMy}Q)&-w_Vj2cL4{ll`!zBCwFgUG) zjQ5JaC2_&E<J!``O5t>Tml&3mgrPKezoDI)n&MyVub_GtcGgQj50koGDM>DY4+O}B z8Kk>OsCufJw~*0gB8Qhi{wJW_rfIP#B)(=BqxlP6l<p}XfL<K&gX>mjgsMl~%_xh& zZhgln#)}9?qQMz1qy9wA9f;YE;6D8%PkDoI!O{PA1l@KZ0(M;5bg20hXDYK~)es}e zi;=!3C%m2o&o|YWFD?M9g(3A}cVrtHwIj?hO}vI0J{R<RlPkO8Ytn1F?s?_Tc=h>Q zxi=g5AgSUdTcEWPb=c=B*|tzrmo?d_H!#5O#fFa#NFQ_sCCtTMoA)US-A7mMp^v`d zTk1z;VIl>HI*&liwL1K#a7+ZBxKu}7&*_ZNR|>$g0zXOpOFZJ6k5~dGQIyCO>)_;& zVoDGV%wG^6TEm;04Jah;^+sk~JA@vDR@s3fnbzp4FenmJ_!AR5bx~I@oND0NJ{ayw zOs=ax{?R2kV%xJ9P0&fc?x<g5@C$DgiLp#dms@cu+(RGwig~Ek;;Cx`a-TTTQ`;}u zvK3_cHYjgpmYWq@D>$t(AJ^*TTZFuQZGC|A#^GOX=bc3hXiDg8mABoWy7W05O<8r_ zk-P=hy=9w#$s*LB3pYyQ!!pA$ujMPnrg#oe^X>E#*snA+W?%3I*b&E7rJ^HhO^2Bp z$a9|UYG+7LWtB+)I*!gGI-u3Nr<F+$ms>IHhTRoo9B*moD@qS;ZnzK@iSGQS?OG%I zPR*<BC!UXp=E9f<b)hDAP!AUF^A$^LzN;x8s2El)9H-V&woh69IE025HWwf1Oe`$+ zaPgW#Ea>!!V)z%IK6v!uKDy(Ya6r&~u<fDF?atoAN0r4pL+WBq7dLP5&8a+UXB`*+ z5x#qqw`9lkhd3{wqi)8OJCP{nOyn8n&Lm(+a7OG<LVi{RTeBZ3#_neL4T$Ae3Yu!_ zv_rAKp#&WbXG|F!$1e1Nql^;|JiB=Wy~NZrGhB(sl_Sv+5vlRvh90xpTK08KLE;AX z&Fzii_sy@siA8R|rO(#rU+>Vb+d$plyiHw{9!suxK}%6Tg>*pQ84hg~ga*0&6!&@B zs+xf|s1vvf^8d2Fa8=anfD8CwhUs<=t_$=tjLLpp7c5rA8<ln0BkqRi7Z1}8w=jB$ z+<+quj(xm~PI<2@+BYhfUzv8cG%gjYz5_LO);PD&ABr1Ph(Z&qVu5>EK);->E73r& zNmIPueOl~CPUrk4Ut4U1@IW;bhPh?eedtiL<sVE-h{0ZAbEpBPkWqX11lDG&;<%q+ zPnCsbbA_GVmGKp+ydA_r#1um1WzC}&%ej&o-Jh5z&Ouk{$iSy$x%?5AFP-nl+M3la zi!z+*X~%DiTofKC{=&^`rg!%Y1Zx_?WcZf|b~O6-hkb$rU=&*3pps+1R~;VZi$?P{ zxg#Z^j8rHe6eGe1l!;@3g;)uZ#P6yxMob0xG$H<%sj}oy1LCsBw04*})->s<dH8)D z-VxzATi$dEq4~ihHQaMQR;q`$`*_Z?J{7U5tCR1MM|GZE?&p6F_Vqi+yl#26n0*`A zkr|HUU5yoY;L3n(_M%;iTaz*0a`^ldQpIr3SLV)$RozfbI(8@on=_=zCDQ;OfXYq5 z(tD?p_<=MY;Na_ypkFLR`p}qBJC|JCwCDggF@L(m9HZMgC`jxV?m%qd>%V1ss^mCe z<Jz=7mD5D9d$(`95Qhu$RYviWJuU%a-B;`-YrO*a-=5-rX~JVCqgy=pxQ2{AEPmx! z1ZowHyti|{2CpLueIyuH@FABVJP`d&@@}{dR!pSC4C3Ia3wwdDv_5To_Sq;eAIHDT zBLY<6IP#2GE{}o!Ge5)PdB%GKO;xwFv{0C{QJyZrGlt=QwO>cX^1HX{UsoKx>hQ zIDf(VkBSFlR_m_DNDE?{J&~Gll^C7ifjJSuhF9tEn3sjlW!$;@>Gj@P(Zi{QR<^*M zWu&q)?m)y}jZYQF2g59Vf8_F|%5>uioYC*@GK$WJiN>+v`A=Twy-NKp*iL|`pqB() z*y#MMO$#uL06*LzthC>#KXY%z2=f;STyeg2NS34JiD=eA~G<nOmrZySDy8bQ~& z;2yr<4D3fHAk)vy*iWQ#qfF~n<m$|8&sR)OAtPeBFYKNm`pHc1JV1WEpBREV{(9lw zvh73K1&!!QmDexcw_vEAkD7JxN=IMLV0k^Ri{Yi3<QP1I+?Zupc%TmGi>3<(h(gYr z{BxRZb@PSAQv2&~f<p8BayskUI$3iGV^43!{MR?8JtGW6Fs~u7l~P7*koV?zcy+{+ z16<te3Fd{=s@K6zH480I1J+$ghh~cm-n8;RJ~1a@?ju-%M!siH47n6CoUQ<L-aIrP zi?;Hj|A7}0BM3FnuiIQvm(9GM-qo)Ak1ox5<*-{ou^i-9LHeR#mEWz-Rr5gtuJ!US zN#T&S`3F!;vD8PT#vqj;Vq!TZoIiTzcKhv^fwUh2AL-EiaQ5GBu0W!wi53=TGDvhO zDYp0j!}xMq>Mpze<5$z(;G@~D?y0m3li2uAic77%(r;WlYS5D!M-E{hstRPI1s*V5 zreA%wd?Q_oMciehPQ`Lhm#loe{qG;y7i(W+0-qLf$rWq-SM3*oiTZ7q@aKX(Mf;!# ze16UPOQNo@T$7gGF@Kj14_QGBmGIUcVq$|%Qoi-}O`71pu>wNTXs6So!UOdMKjco@ z3VTm~+~vWL<UTofU~F!X-3IW%PS>58Iwtp@dgpND>At3#xSmt2b<Qjo;oW#ym)Yzl zC4&DoO<J-JZbIiDbLN*gcHSWGd*o6pwFdnVbd9<A@V$7m3xr@z3BGfB&oDgh+s4jb zlh`3>KRQm~G+&dP?!Lj~^FdCoxJcRIqBX?NeTyaI#VNSpiaW5312F3d0I<7$2m+=p zTQPmbg{0j=aTOWJA0HcgcF;r;N=&m5Mt7y8*HE?mi!jA4x!q1$i`?{sSN6<D2)Lh0 zRFy7sTu<%m*p$Rj#B8{$Lc}vk$2vzjBkN)<ua<<-a#auCxc6f>?V4Q{(s_mNhFA6C z?LAw!d~1*yW*iCIXT2K)bv6A^hcfMem0?xryQgAwnh9h+fsf!t@dx}164Lba0C%LV zq9`wj2W%va1>_Mb3Nqzkc+183UE3>ZHq8C40X8?C|BCKEBiH<X#4J4!+x%^;C2}`I zFY2oMsE)n07V;5VL*Wa`c1B!|snmmUsZP5_y#8_T{krP7vR7v<c_(h<u};V&KH_#P z`5LebZMTmvbFPlQY}umJ9GSvZsoo+m(Nq>XY#SyV+e;j2jyzCGi0tPrvD+*&a-F7B z9P6biYDQLPrMFh6`-W@XqmSRJ?>i>qP#$Z<Yojw9&OBN2IAP%CgY1_InTp<ec3GX{ zTIZ;JX?l(8I9qTfxAr-F;8LX}&>n*`(aXM6xtVeTLPvXYJccO<lD?zit98vADNAL_ z*q9|;c$z3p=d%fu-IJH2JuI#u52#cl=$dOin)#PynL>x20)&D_FHx(LI8f$8v}HQ0 z@pAq3W7SA{h%=1VdH|r<&(hF~eDu&xV#bxou6(pH-_ZvfdB@E9ZswRKOQ7jt4*1hr zAzPiz9J=LcjvG*0mVTu_#_Xfweu{fk)d(<e^z6t%AwF{~jUu0Q|07>jfmwQYi;6Sw za9>Z?l0ieHi+b)8vM%h5*?3$$;4Xc(ELmog%OC2u1qV`S4Oz;SR0LfW@Q$gP`@`Dm zBH9jyUse|r`cy@hU<TjLHT#mM2+W+y-7w%^m~%UlI`c2?;LlUddBfXHh^B<f6}$|0 zt3>;YTqsFLvick^zUb&3j#E|3^>w6o_cBxcF}CR2`^REwrj*hMU)2$bpG}IYHue6; z!bdZd)OYc*5zJw8U_uemr3Tqr8#fn~&wFbHnJR5u2Wb3shWIfA9PsR+8vwufd*YvJ zpNy0}V`Z9A#P3NkQBaf)4PVueh63Nx4gk%oI1+E?=d}#J_glF8yz<61M;wwf`^Jwk zLv9wmIQ4NRN}Z`49jU*XwK?3Wb*G_DY3}vz_AQ|&6#<p+H=8_;o3;0c0y|2D#_hIs z4aa25Qqd=_<F+DOeh7QGi+<SV)vkQVv8{$xV#tQ;Uy&7ynYc(lM0crPt*s_3X5%cP zz>?7!>rw0C0_`6K=vu(XXakglG;w$b{leoTF6$J3RIoLZe;FoQni_yof2YLUO9j`c zk4>!z(DbQF9)kEFK^)qVrtt*V6f_!Pl~i!p{~dnm-g1HH3@;yL+o-dWd!gs?^<2E* zS>@@moSho6x~W@-O%!+y=S;wZT6ArAiJP+pC$IfvPc}$-N|i#w=;5(J0#(lTE-eGu zlv<qibOrq7W?0Mb4#eTSb=&jIj@-cYK@}bIF)f3iXzsvmT&J@HAW3EOc(O!l#nX~h z5OfC}d?LGNS$?ND|L~|&Ji~7^!P90iy%Y_QYI%`XQ_wTZYYuv(P`%f4ms5JyWUihX z<QZHyky@vN)=3DRvu6twq06VeSN()5de|Jg?hGt$nER9$rZ6v1q&{VCL422QK?iT~ zcAGy?r}4_KL&I(kIFG%n)gu|ssa8q;v-A|W02vXTV(T;B3b32P=H&VN`PTJyh?$f_ z99gO2sGsO-YQgFOS^KyjRfp|@a&xzq)W?AkTOr}}1fd&4$PE>U^Yd}`JD0{owpT=j z9^Z%1?B*quZDBvyx|tBvm)<<V1OocW9U7PSyx2zJJ&(5Sy5nB~z&Lq29SKgD7}KP! zWkox(qpD2B&mqW*&iUs4wes$2!#J~eC*?d+18f>b99(l!*Q?e0CZb48cULV>a8**i zhf(64d46$bI2Qo1l1FaZ82ch>U##VMWs2s-&}%q2bkw(oyKG4QsO0R{V`=YcWHpwP zZs3?E6N7QxPb<t<e0$@S$&157f1ncg!pVk75H~JaXPZkmZB;hP3VO(BppPp`{Thkg ziwO=skRrZXY72gK+EmdHYb#(Sx?7&>Ps1F<+IVf4AD;*}#L9UOSYJ><GubgXZ;q;6 zb7U^7hjA1;konPUzhKf}JQ&5RK|I6rJmb%$LM*SWidX@8&4N|e7w7pG;rhCSrdiuP zQzmI@|KP>u2!VQHM1N+QuSsPz4~bJDvV~eAgB3(hEmMBIEXcJ%2c8eAx}l$ZUoIH( zs#a;EzAlM@3hc6y?h9|rNE|?JSq_W(`e!<wjkHUg<OeR^98P_38^NyyGpKG<{P>r` z=2FJ!zX_&BiCZxRX{iq{!V@Urh?l1ht#ac4`dTmmSTq+AKFagUj5aT4t2CK|uMZ}U zE1&>HtSD3LLgoSj8d{&!A@B3hwx0S&sGRukFun{P1_3`Xo93+sRwdlL9V||$WD*5d zDXdV(6E6j}Bo_9A46hR9IpC}C<*mn>&@ayWN4v-HFOWI8xG|c^iE)oJ=>~k6kwA*K zUysC1^`;NA__$xV@C!mfCLjGxH0Qe!lDRIfCo`)7YeHdkY?=Mx7LZDAxps#6cWijN z@l~0BsgF^Xm0KCoj3b-pIh`;c%-D+;W{#-W@K5Ip*e$o^@0;76e#eWv7BjC}!P2;= zTp@hDrB}YBHM9BrS1eX)uhNIOCG#T_%cqKvF_@tkl;d2aKg`eHnJUsh5Hi&OOr(S# z(B4D|H=atT{jS9+<<?ywj`_3hD`Be|?@2&wHJb1pPFaPvo{dKr$9~T^N!)V%@%Cj2 zh>t_ssuR828M=SCWPPKPRyU9@<1`qcrndo*u$<bZR+T^|1(J;}6xecs>joWCihudM z2QGZLCZdG6pD4L~WHa=sQ$$SW?<}$U(G8r^<l3}v%9`)OFVB|2aZ+L{h5J8^aL+Qf zi|4s!-p6OUC8E2%rv~{Hly_eUcI3SJJk%%_VW;$jgVYAAohq0g{DYS$Xpk|HKsL)3 zUA=x^{a(%hs{9JR@TE|R(^qNWsuvQA?D;#RosPJ&;?l?EP<OWUfJZX^%Gsn0EdUTw zApq?hNnuYKD5GL>b#5T{o|y=<RR3XPX8d-hk1s2s)7<8s78NJNbT(y{ihLU?6lmty z)GKeF%Z!m~8;-r6+yCGoT)}8uS4P-U+OOuQ-@{u7b~q<sK{6v?l>20Ojvp~wx}wOr zJvEFf7a}DZ*4}$8DLt$`)xG^8eY<ygRW2;Q<@hqUogTNynBE<8V{Lr`z-}wqmpO7u z8Sqy8X-~{AyP47dD7#cWU7QO5xc;sYn24UeNa#~8I^%=^C;pR@m91y01e+rTZ}XT) z@W=*2p5QWV5Ah!VWz3xKi{T^IQDJ>VA~UI-Z`E4g?*Q>)D0gp5hkJ(GvB0`s2le?k zXZh&1j+yGG@Cr*bT>oGy<3>?$fj6*gya}2l*N2fHCLjy09?rUn7z$6y38tmFQ`1A* z;Z`6_X}$NxyixntheI^$;|;YT?DX6zyjHWSe~)TOxVbqDfDc+Tr-t0Ohtk9?5_~hs zrph1Dd6&luN>oy<C-@bqOe!8>5djh1rz_BTq}~i)A}OVm^319BbIg@l_{=-<h}p5e z#c=8(UFb?hb#}j2dAMoG*V>YKa%oWZsIM$AKk%E1T2QCdha-ijHI_a+2yL-4E>9O1 z&X927X%I&nxON|#SD~q56|M7+wWq#TJ1BCerZ#c$RRzmlkknco#8-q{7xQIr>fP1) zt;YpZl)&@4n{b~wr_3xJ%SNlI;F|tT&ax=IeX{BHm7Pb0!Ocqh_o;<VBV)JB_jxWC zPKZ|vJI@2DL7DyLW7#G$%z5T>7|`&hZxBZB_06n>!UQ|JepNiuSIDwVIV`$&jeGS; zQ5A7(W~^ki^ZXm$%06UBSx%tANS!$)*r7(|#K?X?P9*rmyAd9j1XuD$C|zayzfZdy zI2n?Z-dfmtOr=QS19xaFyi>ZPuRrJZx`?By7IT?9X@dKz`rXB=LwD>2i!nm=?PRKI zi=#rOU6SJc0R4jgyV-QEnH1`~hJ(x^e*_f;1*ayib3iHnQn6p8i9*KceWh||=fATi z%q^w#a9iUAkck-1rjKPL)myL%|FmR^*A}|me|Cl5wqeG*R4Czj-*gw%xFX%{qhRMI z@jr^r!=LK^kK!M9x!1h*=3ef#$0dYHT$iqO?JcgoMMjkB8uz-mbnOvkB_vsiRNsqh zQ&xqRl_-@;B@I8n|Kam_JznqgI_G)x-#A&+RqF*3Y4OUmH8UET-4cb$Fj=PkwXc8e zU*Tf_`(92p*@OnbNgEy`D;4}>{&q>a(8KS=lMMfbp<fM`pxH|}#8C~PdgCa5j5eZL zu%)!8`o$RBK*)4KMGGjqg*Qys2Ed2A1eJ9pvYFV-C37Tyn)tUgg_0@DR0Qb93+C-N zb_4<O8U{U`Uzk86PM!77c0Z1=yJ`z09kQtOihGqxSqC?-dTM$jY0)S>$%}|eI%eDm zah+l(^YBqAs(Y287mgb*?Xfu1s1v=Zkp>^c*`zy*Bh4Lk(t4oB3}BN>IU$F{$RwKP zU*YS7Cj)RN=@kB-57d29G-;zF!waV_?Vhstg8t~lQM^q(i~dXcpedM8>o6qv!K6qd zHND?39dA2LGqIt%^Agt!Q|E*(l;<kCn^@j;zpTQ}Zeyjk9sj<>qE4r2{SrLq2j?fW zHMmb@EB9g-b+P4R6YegqLGTxF*<&rjlIs|s&HUxYF=-6qb$qt0jey)A2gTd)tr`nG zc}I^I?Hs1CK>BdA39Lt)`8~C}#kt-g78dsHfEoy72gJbCi%12HS9W!ucbZ=%?@>L8 zuyw)AA>y$idzAiNOLUF3m~M;Hj_$=*nx9tZO6i?0y28k2x>-W@(=y_7=5bJcuHeIk zk+->Gv(yP)HOaDO6nQ>#!Q`pooy;;m{k`c~9tT>rOu;6j;7BivOT8$-GzCk4W2#Pz zk#bMq(GPO+oTkPt&|-UDjL0*xanCDv#;TFSRN(PG+7qNL(v4~ixQGaJhsD}+nxi-y zd!B`l7JF?{-Cx}Aje!M?J_|H}?fbzRny6kVk#}24ohQ7sZ&QPSd&!I^@4gDi*1Rx! z@T7uq^;*Z!LrgCt^a%fXdVdQYxqmQEa#@J<q+^m6sPqRS%bigGMJ(+l*K6LCz05dD zs<vepbq@{n^h^a31O*ohQMMFl#*;cJOPt~TI#kh`OxfSA@~Epr9ZHo{g!?izEQS)R zoca3p%z(SEA5)^{?-bi)=@s)@psjxekrr%VbQ+o2lmLsujf9h7b>dIH6mj=#76<H5 zH8tOaa6kESoaXcKW*c|k@@cp}2CfqXOKTkQNkRPH9yu1xb?l*Lk<{qNilZL#E>FM| z4h`GO$pj<};Ea+U`2}D`IrF-fiNm}`rozXP>73ZCY{Mb;p41f%36a-%>C&pA!E~$X zRu*1DeArDCd&3~t^n1?1bID1+)8d)Hrr&FGw>Rcjiv|!f+eVW(e|M+VTEcK027xt$ z#gdg1l9mEvXiW||J@)z6fC;j=ukhAVSZ+?#cT1l~Sw5PK(QFkU#x7_YqkBTOAe0dm zE5Xa%xp47S(yaB~T!yV0G5N#u^z}S5lTxPCP1EC9U}|aR4z_?;BU_!C*#kT(Sf?ds zi=CxSOw!S#FQ*P`fd@fQD&OhZ8$zNlr(?2{18%s^W;iF_JofZSU*$^j{Q&n%S<#DB z^cD?hdwX{IRcyps<zu+bc=zhZT*ZG5;oh(J5aW>)nk^H5>-*y{vd-<HmKq{e(}4B` zOAj)jh4!olEFSQ;{eIQT_wI|A=AJvvag-W$Lq)0uuEBN9ZFA8RLNPLTs30Ec`|U+b z>NLFs?~ktnzc@ZPm5UZPkU0zorl<aqPmPV)WRn=D9`!8Jk56T=OX*_fFCXxG($zS6 zp+}S+81}<%_5G{w^KcG&PJQKyMU?o>4TbWQH*5jblvr_259R7i6P~XxvVz+A_x-t3 z<-;44t$K-^{_u)z8HUVTf1$oZ{`68dk*W^_yd<eCyS#`c$%6c0BxPE_g1}AOwWC2F zo+@PZ5gsPXj!yGsS@c#Bh@*U8ofgB!&d9e-uje)m%r7obvK+SmL}#1!05?%pQ{Rt5 z^!->(2lQA$-suIk{ABvPZNbALKgr;*3zB!QVzS&8sO8ZgpFi4inhV<}-z5*v$Y95* z#8v;-A74;>zDm&iLemXdv@b6CBIV(cypaB~;Gog_fjC%j+56S1PXlELtpb?ea>kL{ zP)(;k(!Nf2`9zUfR+0GUvXm^PFk#*SDS|je<P(^Ivjtc;a$~swOct_%mAOFq{q(c$ z$-=lcLZ^=Oq?1sr;LKDo{7LZ21sLGW_qkaA3gX;z<B=Vn%qYhI_}LHL(cM>C`*{^M zW?p>YuTk81MY-OH%TQgWt#)5;?>Z3_Lvw~hz6`b4eulcXfj=_>Ua42NJ#zsXp%Q)v zkeEiQ!p*fz%5!`0>iN5^1$!mOZ%XZ7$okQpcWiGnZ3<gpFT*gdIWYzoM=JV{vvo6n zP+4S^y-LI+{9s9uCcgMgz`0>G^7q=UD?KtWv8W1V!8zBK%pRp-_lG88yU{&nOC>5R zAIE-A%OTHkHAU<S4ocSHNR#mAAttnDA*cl%8olt$VJ5t<Iwzc!VMvEHU%~|JT-OJl zS5G6fZ%4U|bc__xKF|_8?x-X@8vFe+*IB1?nr80)H6gG1sM87C`{V!lD^+GwRG<EG zpAf43VU&KUdO4Kyyx8^`ngQQ=G<{SNPQ_I*s<#<P7f&u;4r8J+{%PW|tZ|crpM?hh zd0^qE%Y=E(Q2_CbIComyUS?EG%TkG<{I%YV<oXvqEtHODl^5RMB#oq8{~clvQ@aLE zSb%sOPO{gM4mEO-xRFqCMnDXvjhAW?LtEVlr{NfFm-zRPG<RicatrldAWurX1in;> zHu~grNcM@RA$@ttKYfOb);8Jp^O@qHx{-P6GFqGW{9m7Mq9$DgFWvo1^t<;rA$%S* zgXOI1BYFMXi|83(3SP!&bM}EBRCy#NhS?3AB6aLU!6|kzRDcLN*O);vfS#tbN{w}N ze1BSPFFFw(enikS|2+3($M3$A!4bt54!0&>V!C~j6$yZ!9Zk{jI%u%*=nnt@_X`AN z&o=5XAbo6@v8ZvZGg@0H*k)mXiB|Zk8Yaln0{RAAR)t$#Z=dcX(AamUMM++|W{;K- ztfvDmx9n>KEmhYW?XDYTwFu9K5l`jdHLZj@rmIaUgdZF+oGjUj7=Xd+(J(0v`1WMX z<Kwud6fJ?t8;Ck+4!`BUw-fKaX)UwTIE6GL_i(H1Y>vU-V(-%IP^Nj)ya@BalK*^x zKD63b(n3`_!0;(ko~dmDoVAL&kni!f@+WgaG4t=5sU~4R>MbKy&UovazklCrE7%t& z42mp#OD|G8O}Tu-TYTmwj)_*vcBb_#cd(WRwc>*R9X|j<jGx>(s@1WK{|Pi`e-ME? z-3c6>kIKg8kxe;e;wO(>A%EpDAD0fWF&BG<C!!t#EFSU$z<!qc;7=MFxQkP;QhPrs z=tP|TsQdDaZa*l;uC)hl5>5EEivV=>zdJ{8TbdWU0K#cceSI&AI7(kGHk}its&KFl zE8Y|O(Fd$f@nRRxWNe9tX2T>WrfnJo=uWpGk+CP*3%!7PODBnt3^vWK`l84ZzAg$1 z$aCLNEKorAS`<dgKTY%^-URHOiM?6#SI_7nj!FafM?1z(zH6J|mEkDrf2`cMspI7L z-0zgoIhTP`3rTN>Zu*?xMmI3@k&1H@I*;fF3R8;fx@$R<E$uaHoz!~yYMtSjkQS|b z5Av-NQ_BNa4vFmnM9mcjyg5th{kl+&hT{26(kblSBD-RHywmmb+0O8=bDFy&A?V_# z61HJ8MZv*nOAbKTPIsk{SLbk<K*+_{VFwUu4{(FJ-_x(~%Bf>;fYDwXG6?w7=Oh{t zogYY!`P9W(CEqLMc;#|cpS@x^fDHA^{?sj0cWe<9R)1$&ha^vL(IEj~#vr$*D4%Op z!ezZ%r<(wAZpyjr)St4+O|yZoo2Y)gCOQw|^R09NVFJ>KF)g2`y`oV+sqsktf`hq` z#P9rt45XkQ&`-~fr#&fw6dGkuAIRHgrY;uEk<=d%=c3Kg;m*YM4x71ghcEPZ=z5Me zkq7cKmYE@k0ICk+Rf%Wp0^?Uu7R>I?9B#XP!nn^a7v0fMI<XzESP{i*u^)l~PZtx@ z|G-T)fa)KmnBphy0Z{-!t6-ABujp;t)iXP$+-7q2v9NJl;gp(%oJK)oUG%*<Q@7?S z)#NP^*a04D=;SN4cf)N)yW47z-U>g<^zF@65azP%#0zF0-5U@CkhIsk7BUs&QA{5N zVW98F9X2_jbhH!k_}|y;Au2>!8$_u=-9t9SgMxK`6)Mc$t)QahlM}gS@g_eN`zbuY zFG0j-d|C#R5r$SLA5>}joa)2sv}d^vZ~~77(hg@kT7SBqqz?mnST_RDzsiVgpiKT( zeW0;vZn!%*>p2UC%kZSv$ezN#+FL)`H9gjim*;lhTo-EF<2=S_=klVcYWFWo*>(w) z{cy>0=d6(<cWemlxu+xJh%i%jgFc{J7a0<PI#RU4?K;^{5l$w9jui;l?8%Fxvf%P& zpxXuBJ7Pl%kaKvV(8^|psEVrJ)TVgB2qGM9?Ke&ir0Y!Hoj6?uo?vd8WXjK22ZoqT z;1^~GtF|N1Qc|n<cyc<kg-m{DUn?}%^f&?3aFxtu$v=MBZj}(n<!&;o-+xFg{D{LC z?Q)qMn5}9izO_s~Qa>hn&Jj`iu*IU=1FrH~xxi2}!=VF-AOQ+Zq@GozvD9OmNip&I zAxBL1;frwxcK1h95iW1rWqu+3+OH-JiO#)>^Q2;=7ZptD^B>kZ&yjtqOt4sPEDv{S zh1*75?Tld2Tgz(ILeD*Uu^T99+ipGS<DgR*b*>G&G*GLsar}AoOopQPeVun7H?`ai zCBFQ?VfwwDuJ1!w`etYCE^)AYt&Ikd1D1u{p&V7)$JPDIH~9c(kd84z9cey0)ZJ#T z5gaQ7P)Y{}#O*L)5Q+|V#)9^Ur+mc|uG%~zRWT}WE;00)<XwYs9>teZ=VvX$Ru8KD zv9ud`JY&{j=NVrO%sg6{%p>utC|?v<=C8mh93!8{2C^zTUd_}x+lTbo8{n&PCt5Lw z(fRJ1X?<jvQuYe>)y>+6ee6Z^uviCx;-ZXmEb<F9TY82O?lM-{+_3mI$$aV8I=?$6 z&UW{x_!Hw>T9Z`>;7AIs8ttNwVzzfUh!Qqms)Q^iD{MGn7qSA?&G+B=0uGYLXLfK= zMZCGNgrd62w6at`hm<q&W&CN*ikanPzpme`E4sGwIWIq2XBCU@@SKwvX&aV?=krio z=8wf4u}B<DRZG=H3K8^RRHjv-FJw*pN?SU<5xibCNl^S)Jbb{?&fz-<w#KxHjHUPr zOuF>QAN>Jk<a!f@8h70=Dr%eAoKE!}(*y=BIfh6BGIFT(*>Y{BC-+lVY~v*T$}Yac z$8!Rsu#HUPFd=fhfg8YzV2y$qJSu*gCPRw2Kp7r)v#%5XEl-Z{&Pjpp7P3BebsZy; z&bEsb^0?Noh`x>0X<|62s~;^D`qw*j@qBw1=O+lJDG975-MGO@vJ$(?v{2Vi%`<#A z^Vpz$&Ad;qOz8EJz7>ZFcTnN8zoHGa?b<Pln})dd%LH_orx5T%gpD<Iod?{jHjFgB zWGMw(jW1A2o88&!#vHRhbib3>bdUZ&g-P6t<Dr1GxCgl5KuBMbN@(INySA%1ay0B` zRw$_XMP9tp);CK?UsPn6m_&GlnSKF(Av2)tooE=7njzYO`ebu8ns@%IB5fu|KSrz= zWf}guMMxmh&24H$B<s#iqnwx+yzmNhNF871;8m||?kmz@7l={Lf?54{ET3@ML!n@@ zJwi<hY;A%7)6#yEFpisULR~#bxlIZT1a|80Kx4Dx9(}t!gF6<uld9mz1KhvLL;jRS zP1jmbzwFoLMw`!UJ$^)uN|dz~74Ur5%M+}5C)Xo(P2>3I^Usa9?%wSFEtbDuU$0DE zP9TkU1xQGR&$^zyBX6kZI<qc5&}dO~Jys^*?&rp-gH;mvS0~J=UcRrlYB}MO19uSB ze+vEOF3|$QXR(Zz?56)FEeOQ0r7r%Z)+%$U&R^ZdP{SS$`~SIW@-c&zl@ZJVh(`|V zr&b=#Vk04<qEtv(B+DmR7E!Y7<jvxe766J~4^aw-g<)c4kHvSK$iijBE>HGdcXEpZ zw#&inwmoCYohVIR<DorBMv^n^zn-SsF-p~Q7s&+XF4lf-bgDT2%}b1hsL@mgV^+F; z;IDHAA%@fOVwICE-JlDk@Di`{XTTCISnlA0Iu1I*7W|h*aESt~EaNSxkXKn5uSCf1 zW72-oPTa5HEi;5`3(Sq43JHhm;N8c*2lae{JgJ2Yp`jKQmp4T{@*3jODtpE3WE+?_ z#l(=x&eR~B-pnC)$p&Xly0d&zsY41I)u!lqyl@2(SEPtDXF%n8q{)%L*eOp5f{ym+ zFO{A2jBgxOvz2c|3a-x;jn74{i0h2b7h9#136cwG-R1M&&@R(kwuyTn-FOZK6EmIp zw8XGch{Gx6QBxa~EwPD>Cyv-GbLqOnH3KK)B;Vj!Y1jU;C#8p#fi;r-!1cXSc^Y8@ z0C_)M#WVAX)73$*xJRKg-nv;^S&*^}fV&NBY$BjsQqQ&oaqSb3%!+kt28<?<g&6iO ze>t{zt;U0-X@rvcD3*Jm44wSQUW1#Px;hi3(H1fawkcdfvNYnN9QluTThJ+85`>!J zSd4u^lAg}6A>b(2i+T$rDuj2<gA$LYzhZ)MdznP-H;{``iZ2K7Fa5j~uj{&}p)&^0 zyquikV999`wBIk<|1*D>H9^|BO59wv)r3H1GYFEyY3NE~r~`I<j?1`G(Z@u7GW`%u z)DX5{$TWc$6%H?&@b3Zd&7a}7pYm&nuQ`xISUx5nIX+fNhqZ{y*V}|E3jy}{x9Ua2 zvS(5=?heb(aj<%aee`3)aZ+H8Hy6xOZ;ePleXkgu@NX#LbSarG@w{!|Ia#UL602%% zPk100<55s@pbf(DWKc6o7i-w~wlo>$p+stRl}gZ<#4obbbf*W@H?h7yu)rvY;|Ik2 z)$=d}S8w%G{%rO*Yx>$|mdiXc%BtGWyHNZz%14B@Zo9-*XLDtkaJLPfWMV=}Lj7yR zZ2^uZs71x@bTB2g?jhnKOIC&_E3(6r$gtR0zIN@nGVsUp%xs1hX!!QuMS{rNSlPGu zWrk+2o43x}GE=4fdj5p-gqh@51agQq7Fm3neNRU0h_J+N*3Giqo4A<gQp=oLjb>`f zAcH-;hCxuma@q?ret*02L>^Hy5_Du868Wn@mV=cI4<s+R2^iZwLR1imY3W?oOoK?S z2N+Me4D;06l97j2b8;w6lWlD=O!97su4rs*5E8z4sH7?$FW<=C&uF^)n$&}kn$96s zZ}vq#mT;ivtrN+kw25B?>C}mP(+ppIF5u;iUzb>%q=j>8snfo6TX|C%VsS2JMf~5; zOM9YTeZN~Cq|LB633Rm$G59C>ImZdGp?A7M2Dq}~RmEQry2})|9B}dVn)>!TMG9E% zl6|{kNP#2&C6OVOO8n%Cmy-1AI?F=pM$V^S8LkWO@zWSvcE9^*xVQ!cHp_<pg9h14 zid2QeSrmG~W@BE9P*iHbM?!ha>M)B+j<jIxv$K-<+>!hbFiSe$LmOA&S_i9F%>-bv zFd9XE<;yQfhjExc?)nAT@IB2avinLgdRp9(sC67KmH|qny-UDF?K2mZ@0zMsXZ#71 zzyay%Hf9MswwCpHu{OL$BcY0eRr%dnebnRSL$7uatY-ff5oylquIvX<CiYO*;XW?j z)G1BK4G@J-1R=q}?};fR?%LmcL?+rR8WuZUR~H?N{v>E?sUMGM&OXF0yqCiap3 zp(V}b4)3I|h3$sob)Na|`adx)`uMNe-GiUJC;007imyRfeV5x38aAsq<)o?Mta-c5 zR_Puzy)?03BZknE{pubKQeL&9;f+^Gjl$U%8wrDPJZ2iG!Ki~&uI@!s)oqa0e7WXi znpPy}`YcG3{YvKh?5k!vhdhdFQIoLf)&H;B?`uPd?U3{CXkMO$>vE_YMsss>nqBZX z-(cx<Z+P%ap^5Hw(#s*P6cZ5+if@c2eByDDN${43ChV3XnVxT+&123rJQheA-^n72 zH|*}I+U_j+?tZWZRDG|(cV5@UW7LZDuXpN1El3Qvy`5?^G!r{MpkwlGcF7mFgI8VP zP-6vMa1=2D(&gz|Itu}`g*30Pc=X-ROA>gs>cIoQCw++Jwpr=u%`;pN9d`O{ChSR{ zBr3*5(y~{SS3$zr#n4Lf;rY0c*kTDCG57N}c}#0lI2e4))kWbMWepEOg^8v|gSPSO z#o}zt76W>Fm4gptamB{`dW!=lgFQYSvkq8<XNjmm6t!PR_1*P?UmTZdzN7h>z1Tqb zVvM~9dnJ%_gN)K@J4|@8ZZM&7-yJ!-lyfv*4tV|>fTF>MJn8bt^xwlDY!*OTCUC7T zjUOzwA^=|bBlmIx!q0!J8Z`U_<VozB#)b}Hw@aODK=*eM5tt`egs*|t`u*6U{jsT{ z7=$Rr`@hghZyo{UCJCEK;h}FT*y#>3V#qD3zJ9R4XWX{V)pnB&w`KWTWgD(<H=8XI z$qV9VC@$KG#RZCQKNpmi)Mp5|SxOjRUpn|SprIbOa94>L1y6v0Q*<IaK@_cOGqpe& z6<vD`0>p{K<RmRlV?9mYnfr3|gv_r3E$GMW9YXB;(;#_hT5UY=IT*jyNd&~185y@O zLT}&a*kPF3Sk<mMM86fxCwiNpALKPSbonaS93|Rh&H`a)TaH3!M1SRZVJw3Z&Yp6L zB==NY*-<8y#7`hBa%IBp|3pr8brtMK`#rcV^v}Joz~f%<nB_0LWMflN$E^z$Pqf4b z6(&=Aa;2aNbQ}}B2QpI=2CF6ERp&X-^=V4p12`OBjX9{yvHEJ<?Lj-yjlcf;&TY_R z7+4?rpCLb4dcgnekV37vR2v8SU_!58kCYyy%c;Lh%GfXfD5L-MQk*OUA~`-KsT%mj zgv)vpd*0*8qJcsSgZM}t4wmHKtmTfgJKt{yJI$NC--$SpohNW=uo7}%DN)@NE6APR zQE#f6!VWv4uuvi6C8>vAP;r>p{TtREEd|0wrWtw<>Xm_&B0-0ETEgh(m9DFlPY!Nw z&bWLggE()hNpR%xlrp5^_u0nJv&N>`5H1~n;Y}=i{4mDJ*U~4$rQ$))PtK8hrB0UQ z&umT_;XM*I`qIUd*t==pxC1u`Ga>W5!;p7hbBQ>;t`S8mk|^&h{2yp6rH+RRSwM@~ z$D*Gn=|w!_ii;<~(FgUW9l&CT=ba<`MxBl>6<p=Su?)>Yh)XKifC=`T1p^P*>cRnM zVT}|%)r*!t2_p5mP`TV5CjYew{P}0gS-O5*F@EbJwkZ9=Br<W7!bLN=@ZZl;xnq9o zgDDZ4r0TW`Iw8U$nRgaptKY(>Y3GdE(ELXRb2aRU1g8IfEBos6W&GWj5*BFa{#Wgl zP8*|6&nzibk*5s<9C|mju0tM4*<QHx;+z9#b=@oPC51)?+(mCdMEzboncoDqS#5Ey zHA{rmFwF$}Rw=A<kL^r-ZKN3XdjEw&LYko#n*M|`Ugxv^3dhFPERNbZ7`CGTg8S(` zqY7uy;wR+G2NUbfRW|2-6Yx*ZAM$A2#m4`Q=d0g4LXIgWzbt?JOI+eW$9c-}LdS(~ z?P}6#rC)7{3eNo+%LASIHE#$xkK8yrFWydSIy1|8rk?&qih{rVeqe>!=XRTZt^bQJ zvJfPi+-uKQCpzq<w>l{Q8bW)V<f~j9QcVU*-f~?S*D@{+?1!~cxJs_6KA!W6X|^N$ zF8S?5erXxD>{EID>y>}ds&DGHe*$Zq&qdEq+CP4-6<e%X)3;v`>t~W<cj{rB<B6vu zAHqkje|MaI9y01kV{078Ctz<|x!c>6(lr-AYR3mUrqf<1T&(7M{}SAgvs->^P{4!N zFkgt)`^OT0&_r_)Z_}V<T>Z_KAV2dKg4NqzGPt-P5XD;8F+PO(TyzT_QfF_1@+apY zCNUhqGB=<NjPp2e29u?!{6CLFfY9Z`1CFpFsEt^oK;*(&7A;s}R2=2)sswu-(dyI= z*Z_naq1c+L@3G<BlXDaAW0VZ#<yuy{;|pApd0KvCYsPoL@pgawt+2Ubb1IievhGtU zdvGS-dM`Jym}!80KRXoeT6*e!<g744=$RUD$ESDv0~g@?$XYHBw9{1BP+1J4N$<sC zhw)$z59z&|Pguu*&9=ZK81PP;6Tv5Jfa9jjf^Psx@&aQ>-~^@v^#v_OesM4M-Lr=W zSI?b!^I!5BxOzREAjMy(enP{uwoJQ<^K2sconLTPF&Zq6Nk+-%N*@D}k0aaJHvA`Z z1s}wVs8VmaX8oBccxK{tcIN&3(AgHdHo?yQEM<;D|EA_<S-gF@?#8CM805}?YD?vP z|F<Q7_XEOCX03x*4W~Ck(_8rb3bxP>ye+@n`32DVDNZ&8p%44vPMgPpaW#Gl)A*1} zPGy0Ykqp)QdDu*tKe6V>IAB|=K@>t{rxuCB5dcMe6ebA^=Q!jMfk~6vW9oC0M~2ql zf&|?G6Bv*urA%KZSVeJByTn7el{rBHV;R+TB=m=tLVE2-S$tqMAq}#8Fv3>O+C{UY zx9bacVc7yxsqZh0mh=EGcDny{$gAE1xvB1yk}vgQ3k)59QOi$P3R>QBgr>mNY+f%9 ziTX^=+GDyx_lrvG?<bjyRs?FtR^R{BVLc?AFe^-PAl?5V1Q7kR1Z9Tego%K#NC7dY z=l2>BU<x1h_>~O$SF2oY?67(cn>9s?17*BdFE1}TFQ+0j7sy!|SN*|juyIGLtaaYF z>NJ?@+AEBd<mmkgS;wE#guZ}Xw4Bfj2PJC}!N}oM=kY1cQh&!rC(;RalbK(f<A<8| zqzWVsF4Xm2Ie24pK+Ln)f9sher?5)dsioy0(Q9Y=&bR~a2+RS~!~YU|<KZ92FDFWT zy)7R`IRqoLt%TDc1*bSyi4Fw%d}{!pnnRSwKrh1WPjXmCjTfg(yVW1#CwYGvlDNlv z?ehI!lnfEfR}Slxi*bjgWD5Y<C=t85FfC7=L_{+e9*?y}K_`Boi(f{>qQu@hjkadm zv^;tL;_F<D*y*IlZIgA;em8R53t{1`8yvg1GF>>Lp`|0urSTkp`@K76u1Q0X(*26! z(51H1sr<$r*789`cHM8ESxAdmy;_fnGIM@)WA9U6r_MESx_`;K-W?^~8U$DWODlIA z9{_2I<&9qkL!a?8I4EaznEkP2A&9C<pq{+p)HV0B?Ue^F(MJSkUJ$Z(%WmK-wB=11 zez3DDSv{?hfC*GJ^d47u`+A~adAUZY!}Ska79rsd)^-HPhp+#niJT#ut1>}lwd!Y- zj;)QUF9~vCekjsS=3i-w*XO+Gw@I0|%Kzp6v$o^}+w+qXF>h6=U`_=h5MRhJS3WCc zpp3w!6qMn);FNXmG0qe8Ig=#<NB3b_F*1H#0o^3E(z9k;bb<be5@Ry2jG@^1=i&A5 z-J8zRJeCNal;%L4WRb0v!ldCjviRGw9rb2MUrb$MxDy;K2}ynJAasiM39O=a(wvZW z+i)7<m`SX=S=Vcuv;H}!;!{P(S8IGHIj>7Si#eb@_aDnu9O@SRr%cS6rsI3kr5>Fi zWCZHGG&42<C+g}HeD8X9f^(KwV8aLCk`6Wfq>PuLe!5(-c|@a|CrcVXTxw7!yuzf7 zpE<F9949<BF5F=uHOyDSwYc)J(%kyxvi!+j_FEH@QHjdZuzGMWRT{)G<jaJXKjcBS zjry~zm^aj}AagR~gQdD4U$Ec(%w^^KvxEC<HSdt$pWdIXjf@roD#8`WES0P;k?ZJp zm{Ju70}1MOjlD!bNc`SA46u_`sD`M=>o#g>wqxY>x;~tiq4Tc*%OthXLV|Sg)#DtL zYIOt_5Z*`5Xgi~mQyNJdjaDVhjD*(*&T!tLQ+@7_3m8C*s76booEQF^I%X(~bPge1 z$%he-BZ7f&zh;c&x3d2xu$L1Bvi0gg!KN<sP-||=K93uwiwRYeT_KbnzniETe#MF$ zFZi98aDq#P2jD5pvZ6$wiWZs)f(|1&Jn~nJRMg1x<IjrggDHkJ{Z|id!rb++JKyh~ z0gG7}Ub2Mvy3CG|pK==j40KVIS&PTkq09p^Ilcah7vs4%oLZTQ!L_Jc*a;qUYYog) z|Fu0Cth01=ncam=+|afScl1(O7fnqX)Hn>>3O{ilGCIMn1<%hsJ&n1mhPW*j`>th8 z@(L1{>=6=llquD~#<V)UIas{^7B6F|A8phRKc{^5zY~P@2lKJ%sigz1Su^LbsUisO z$J+d`*QHZYubpci#GCeT6{UBpG@8Ov+_4TfPXh~sL8KnxJK5H?@*Fo60~a3I1WhDJ z7OV1Ozs~QR$Y>n6dxaF~zf@5re$=p7+fmjJdYbKu)+cf29-R+ZNy|s}I)1kegsqm1 z)^~O*OWJM^aJfDh>HTDC9v{~8sDIR6{$-VKQrdju{Toj0sj~D^^A1BC!{T8Bhl!Gl zLcRi|h6yBT0iGs?T%l~4X#JnPsZMT*tYz?}hnN!A4oP-aecQ!>Z*jGq1;%kUXMU=k z*&2PSENAI_sYsHpsD5zXBa20kY@Kf*?4*eSIFaB&A4KR|e4$`YH+ykSm%Q)9z2-L{ zCb#6@WPW2pUVl!pv&~!#C*Y4fN1qc_QgHH1%hHVZe}2b(s8vs@uL$tMe9X}Sy82#y za>NS?z&_V%`deiext-xEA-*yC*?J_!;&y~g%iXxuH>s=*^vXYAai%Kq?z@fH>+Xe@ zL~6kkUxIagtIIrZ42Bp-OcDk2c?fbHbn`!SYEz{%mM`kCTs!bYZug2=Jba62jj7kY zpqQms^>Fr53Rd^6x$*;KcGFBz_kd&jhC_3wC+4U~7t-ZYr2f+Q1zypPB&Z@NpVPHP z{<*2IPTTd$rh|Uz6qQxy$t$FL^c`b@&Ox+tshoVHR%fT>B|#hzclL(*L!p;ysD4;; zJL`UH)t|SeMB|+={8W##C|!fRa?aTdK0boaLhy$wezk%`jk11uhZQ%epq-`QQ_f+1 ztg-tveymP&(ClUkp*GWJ!y_isEOM-?h4zhXd-PHb_XesgdTUpgAa;LMFv$k94(d{W zvSBo#8O^C>(w`*TuX%|y7ERo2ZXVO6UetuH2oK;`=9L4~%H`oo;UFT{N}g5NX{73# zub&^g`~QQbJ>F=whWUf*0rK#ZKVA0Rw@uHUJ-p1X>cUl7ut=<+n$lOe!@tkBV79;@ z7Q@ANuq6vx;i>b&S?zgl2us?3b*)_uw(B8$FgD^lnxdwZR4WSNaJAA>B8JcD=CWP! z8u57|cvB5ZL{DNS))l$x&J-c{-wjPoY_!^oVSZT{xu~wXg2CT<Nvpgc{wt#%nHPiI zXDvpiAGuGmt6letQGiVI06)UHsj(krIgh!rtRH-|;j_wEpj<HtX@U9kx2;`LUxmwY z?O1G}F{$H<+sjDJaq%b%n}HdhF%H8>)OmXEakX=4@UHvHLT3i&<5!dKFDu743wVG8 zWxlW}bg=?!vB27r<@N|!T#2i{h^(n<=+1LTe_F+MWH*&l>CkALEi!^tAb&yTO&|2P z*1g|k8SUHDlo5DZ&!Au*t^fd+>)P#A5;_o&P@%|=M~R2&e9TCf@vJsrq;I!En2v(} z$Hz{W#Xh;FEm^wy*@hDrk69sa^2H4l8!?2u<dtY2WXvMwMgvbeqUTk$pZes!mHomF z^%Hwt{S=3*XYw=?4&V3q@?DBZOk>bes6{nnuPx`e>%i8vR&Ri;@ELX{vR#>9eF*@+ zkWIt3vpM;;&@}S3@UPlWqW+NlzzYxwIefalvQh`Y0;;RI@H}7bF7MmOe;Nr;#*3O- z$V-|JC|hCFw>>Khq<`+{&kCGd%5Mw~4vsfvw<yiE(i9W@D(nwS9X=e)#e;ev0%FGI zC-v*OB~wKoDX~jd`I9$A619v?IE012CQQ;U!Ur8Uca9fDW5vP60IO1X_24VLy)7ME z&1>YkdO0zjq#mNpxeBU8Uq{8AT;%yXe+5fkqqv`aZR2Ry9EE~!zmKo0am72pKE@BH z_o<F+HhqB25LR7lJ#@Qf)j!Tg&lyjreG5$!X=bUPYB{Gm&6X69GlVn-uL$m<*0Mk7 z*E(XPcc6XCyxXf7>5rIar#SoPaJpzA_T0jFA@;$0ZG*E%#RnuNaJp>BzaQ4<XN;4# z=N~opbIT3Dcuo~Yu9@^NqwrgCux}3-I)|9T+9iAM?5X4NwFmd(YtbIHhv2DI-T6*c zjiYXd2N?ccc#YaQg*oT0qnX*F_vM=;V?B<yV3{oz6WW=}>Bwf(vCL@Nvq49$biRvB z>~PjCOq$k*;1eFT_WP0hCR;}oEzk?^Kk#%;a*Y_Taf{!Hcm1MD{<jQ*`CF|K(pw4J z`djEnno9UM=Y+IHRL&*iRWD2q(XG}?IBG@QeypHHYg1ST&0Gz)8&&^oU^hSFeTHv? z)p<$nsI%^z4j;XX6S%J=96zuc4=#yrJduP&nwXNPXZBjHowACEBXLm`(J1>cz26;3 zd9dvZCrqP4JKqF?dlx+#i7HSq?0|gS&q`BXCWq-A1SqJ;?W6xL_(8M561|W@j69PS zgZ)~+#AhYHx5@MCPLXq?_oKSK1zMjEQJyrTzZ(-7>Z~Qt=Ow0BVGx9Jx|8*9UXa?n z2Ku7<LYp1R_cI2qF_iE%wCK6)zzLHY!Dp<SC3vDho^L{6RNlwFW*dd<>FAwMowk4p zAJO*8__#-urFeV{A&og2-O3a|ESsinS_b_6k-wiR`e0gT#j0?fp9e9Ik#LQBJ;d6* z+45;Q<IhL5teGwJM_*9_mQN!{^mel-2^~J2;?q>;iZPeh1dWCMsQ95z_7}U4;{CA( zk#VRGu2s#lex__EcAtWbL}<*+98JlE#p)g)U)GHY*IHoC`WEwPkEcg<Tao+Hqxt&X zIcrZSqy>zR^HvsFy5k>u-hJqb=j>ib6H$-`ztsI7XP%0sMZ5gB9HCOp#ESp0^!Txe z1IwSq>$K);owz&h4(H3Y?OUI|XtZ)l;*3hSW&G{L_>oL4cY7HQaEcAHD+aB)ff9~c zQM<Tp9R1C#Nr&DO!i!%CvSLS&&Xpt%K35eH0o8ER?&RKo8<DTM6@y9m=c4o=JDT-g ztM1DaS&(IA*OAw6_nUdK9{yZ$#c7&=cJSGYRR(wV`(<#MzUwxeI$4i_t-x~*x*JCi zM(10GRdI9QwD;WdHg9f~<w<?kq2=8>_~I__dBdtR^k(Wo8uaG3Rn^;sok6bIYEe*! zdvtJEkXw&YSr5G2EVr2#<o7&q;78@Sr$ZTbGS)Nap5q4*pdn1a|1pNq>Q$z<RX}p= zQkCk<)=F4#fBKgEA`u(Yj)@y|(+jgg+zRO2$%;yj1qDkJ$=FC1X9pzbqMp+H2W~*g zlyiXf$RNJE<-E1iG19l1y>rt9f2oLP3*K=H2G8SqzkTUIeBE4NL@E_LbqqJe(ktE? z$A3uk9XQIhn66?ciZlI*>+hKrG~);;Fg;o~PMg84AYX#U^GM0%=lZ&HwuI|Mz@Kjk zpU;#79g}x^gCBhjv3bZa_=k}{fb(p<kgc`dudzDwtB$uJKjx^fdo4v))D9T*mz6Is z_CW7bOjX3B6y7s<&(xNHf^b1IpKxB`OjwB0RaP?Ab2@@vp_-6-C8Qtw(lD+6l-cKa z&~xpS_?pm2P+F7AQ44LQ6z3pK4xtBRK4*}V){5p}NwvaI^{e41f_!E|S-fJpjyf0+ zwZZ%i#%|oJ7fE9-*KeELzaytiehj$frvHYF)n0bFbTysz)ebGpH7#6Qu5$0#=nclV zvr@5je1^}Hw7K)5l&>xiGB$VPe@|b#NEc;{@Zn8GEsTy<?l+aDiL@*W1g0|BhDwUR zo;O4FJrF=gC+~d|-0biH=fr-?J%`&IKSZ`dQO=FO=Jh3Sf717q03ZxMHOV%B@_WGc zku*p)eDTi13r;&V0T;=B-Ua`iKa09Xjv;xvd_IG66+J3jk*VO-U}>nmJFBlrO{jFt z6}9JId&=<_-)JX}({=Xn(d3Ox{TX@XM+`Vr=~Mr6K~V;`kgVy?aQ=vxwUzEMpEu4| zpPD&ptq9m}2&!9AoW`oJ^3_N|MT@2MKGRGW6YVF%ue_IZx%shhp}BC=I_HU(e8+E) z;Lkp)w5?>5)cEsPF9Wx0k^Un194S|HCGySL^dg)nu0B~CHoc?!6A+62Z*Jtjdx*?} z?UmZM8Jv~oW#c`JcL%%{1}Tl5q;|c>N~Esm$v)cs`R8&^p!BXwJa&BJEF{~{*Zt%E zu%|qQxi!D<Fg{ik68oM|J8rJh{`$rT$iRg=Q7SYP9K`)-2?HUbrU2B%%#`_|z(1=2 zr3Z((NC;vRa&$h2dtJzWDGN*5Buj1g!|Ze8(mFblIjr-AY0-nhr<%R}eqItQnDX{? z?-y~tdc~F?qwq<;LUl1=RU|YOdEeyu&Omcr_T(uC(rsvGObG^eS5UT}8_qF97@&#O ziCoN3fbhS^cv*6+yxCDynsk;ImHLf*M}pn-DUpUV-O<El5QH#qd1B?_;K_E>f3Bb- z{7z`NvwtP-Kx_&ZFM0ofyyX5c{rK3k;5Q+Bz1aWm-XEhqp2_(8F4(@)9SKt4yY>*p zE19~O^9l>9)c2B&9DYX-9uVqd@!_?pb41NMsyNuHa2*4q$szpOgwJTDFk;`=<4cq@ z$7`p;Uo6#Pw9I|Ef#Nv%(Ng)oqt$U~4l7faY+k0q;vMD50n3O@rG$YaucV3y@^m*m zqu<Kb4TS$JrFBQ*=J&n?(W#{GhS#wmV@B1xFZdUq(?rXbxdPFN+hv|o?#A(#JeB{m zkdPB9lNE~Q+}x3fzfdtabONW!9fbKRIP56|>gSeU5nShlpOnA-=JXEa%Fy4(ucOTN zzurFl!4IPK;!vN~NseIcm5)_E9b6Ze<@Rg(p8WfjP?z7}7b5~n-zX_$`Jn%etUg&k zc)vL=1C2&)vw3qJ1+U~bS)XXTA?(Zcd=@H__{_rPwX|QV$PP$ouScME=-<tU-5em6 z8UW$wF{0yEOw+izJN&=D7g0NQ250U)6ka@>20cvtzZGCLIYBMUF+=&NaR<mrj+k;m z)(vYwH|+dw@RWj8xgrM>0u<QS0MZ=p8SxIa1bPL?AinXipv)<tp+2Cv`f5=~hv0n2 zP(;6yPZXP{-@kI<Zsd#m7rBqNzU+<vu=J4o==Hu@F?fe^=rc|x3R*0jQJ^=mr0ubS zJYWb3eUM4J;O}}jdoxr%FDF|Pt1R5OV56<au}O%TS1wg@Xx_CdAdj}Rc>A&8CZdI! zUG@(>p*bR_-FSo~BS&LVz{(xjgx<jXo}D68$Q4FZfx<-5E$&PBs5#vc>tfxYY~e<$ zYMXkcUa^nALLG0|9+6Xp!|f-H0o6FRCo{ma-N9Z0l8ZhBjoyG{@B^D<Ft7A&6Ar6S z>*;PZ$>>qPOxa6~e#Se0(#?G#hx&kkw8rR+FreIBBF>N)6-f0Gfk>DFj>9u@dmK0y z^v|rjqaoF|T`aLc+ep4GBw=<;>3Y{jg-g3Y{EbMDngK4=R`RO3WSL34*XaYc3fn$b zdqt7kyvrTxXwx3FRUCnPIP@A*72j@w{bVbj6`F6NBj;!x6zq$3PJVkmPX&<_U=?)8 z#C6AkmRCK^fR(2(W`8=GUYlnX-qdhye8v#B2L)#XW#3D3JVNuIib1mS$u^OM_wISx zF2lZ7zc^IZnRIoLLI(@HBND5vGA0`aq29DCsz^B+WTn<#^p+T#UG(-I!2Fu6=31}K ztqevhJ;!rZSyoyEg~uaH&me1q5@KgPLK1<-jaP-l2KH-d7eX3tz}!5osDq~SRM^?^ zbcx{Q+=g{Ez)Qd#1r)UwLq(+zeX0I{t^+eWBNk)E4IKmcfrGtjtGFrsH;f~|1=~&z z1mrdsCBq0{sR%;#Ohw21XFQQ&_kx2IOhMTqEkRUeBTT-JVP8q1zUkJi(u<&@-4QSI zx^56VepwJj63MICXCY&KGpZhow$t&j+qKLG=Wi0Em9Hdyfyc&u{cy%qoug93+Me`c z{h76u;Hczj2&hQGV*C`6P2z~rGaUpiD*!HF++rXQ*rGjhIu>JbL)x&aVANltgkWkW z2GIqKpMXso4f*X-z6{?JQ4LgM2b%Gxb1;9qD~42rS$SnZfse9tM0>YBSkM0DX0Y0M zQzvM-W3X#NL$WD>qdL%LHW(ju*Usvf<UM!S<kJTSaxO}OeYevN!MTHG!A@ciW}+1Q z`=v~A?JztUukcUJve>}!MwABM<#Pqs*8vlR6+|BC1BU?Wu|;Lls{Rff1)ICyGH0`} zd=lwkDT86rZ4pc$q#WO1Gn|i+_Jc#(O*7!D9U|T=rD~&VLf7F#D=PuPnx3*=wWpA% z^X8e|U$cMuuildRxZ+>ZWc6%$Kz$}g!}3dx=wBP~$b4Id-ofmf|45F=F26Ca)=)2$ zY&)0pW^6Q9APW7QKuqQ^$(I%=edQxSKa8*ndk&z^Imej}uh@}qwp$fE11Vb)Y6X3g z%rMynf`?Im<7%l4H4dCn+GyL!<~U)X;XqXAlS^|B)UU#Y*kC@0@}nDXnoe^S5P*1x zB!|d`Bi9#e1e)H14{O<O`3pisdWTA%s}aS5Mos_^_yP{HEVp*o@F<6tILMZbO<A#^ z-hiEDWJ`urRZ#)S8>A=7uIoOOft>AY;jsEZg{@Tq=ayArlmO~Kqg4}o?`X=uuIz|E z#XTkKh2&XJYdBUr>(HAb7-b+1=%<fQ;h@0#K1q~!xtvMSC;om(1t77jPBJK{v}BxX z96;Fs$S<aXAj+-7+^$Spo!pW12B+&>PkR|_T9>s|(}C)#&A;=ik8H+{J`_}W=0RoT zc;*~?1rlzZD$K3-yOI<*Yk82H9VPsa!F$>el<m+mKu%18m|1dgIWzHB_N^KpE$^NL z6cgKJevM+j?a)rqZ;?E<$fibLo>jD&TY7UBDRV+8<G0aBCT`rr!3x>59)kRpRdXd6 zQ5ri;xZu0!$8T6WRJQ#oM4jBv85on7tgGG3)@Y68n7)#>x2<JzWFp$|t5b*bol@vl zgWCWC$jcH*(8t0r2V04lb8IoTce#!uRu}UfYp-onMNi3|TU7Ep>)k4m_0L2bk=6kc z{!<lrZ(5(Yu*=Vi{35ElL_?&HJLoZPwFGq*c-+chq8=M*0VGRd!HQ{RYr}v|vc#OY zXnjLuKi0HOs<1WqU?|Y*X|Ro}%hR>-q+$D~+(3~7Q(O!JH={<|G@nzsGfq-h9Oh2G zLiPM6in;wAV=FZTx>ich6^?%xnn-GYj)kNlQ4;1p+|tV&g@nlk0dD2CN}6U1NLVaz zLeT+?z0?4?F7q9OrGVsWlqZx6cJN|lcZ&$p1IEtfRyINJ>*j*YTMRN}02a&oURxvT z1j+JqC}Yd!*pc8b)|L)gu!nV3ErHtoc&6c3s@2%2$wIEPA)>(OK>7YOwD-!sK|x@e zfxogTf|qDEDwH;FXt~m>UTN29@M|{VST&u%;b1z_x14XKTq77+y$031lJltiWuC<f z_Zvg8`o{<Usdn~Uv&K_~tGq7A-C+3N6=YvGzy5cAlAMCxEyfX3=EkUKS)xk*UnF3+ z&}@(R=A9QwF{p?(h%J{GsuazD9lFK8rFe(m+Qg}KJmtz;s122PBp9!*LAQF*WaX?A zq0HPF!#s<4(k+;wn4oyBa&1zey=H)%%7TO&_iyMwp)N@TaVzgubJ{rf)@r08P7a=s zyb~|^P&C-}w}HQ~U~500^1~<0=G7(fA2kgZdcc%TN^#R6!LK!XV))JKs@n|9<sp;> z)ql71;KM6t@d^nUn{}NudvBbW5`4Vd=yV!u^JA|%oNs0NRvF`t!$shZ(a_lso#CxS z^`8fK&#x#&D(3c~_Kw?Do=TN`O7RzPDFZ7T^^<ERpk$ubhgQv1BI+;tx$1k^<cC$? z%1o*hW-IP1<z5$jAVw%YKbkJK&2nrkx|5P6dm-qPefb5>(2tPVDz_dJFNzr3+}@q( z*CJR`w;v4-vHkS=&E@0tQ`&L|3wU2wWRh@yHcHbt#kA;|=z}6P?UiuD0;gAc{wEz> zA=;tW;~cZ5C8)L0eH#%df?X8mytPh<e!JZjFt%|T>T=jt(Jtwz<CbU|-|<f5I*^t) z?b{@P`-}}?j|lw0h+bb;-$=wX3JdYa3A?nxX3r(Nnx4_ulMu|bj=Cr6y>rGVU#0M1 z__7%kZ4L#ep8G$5^vK$!oe`?xob$Bsk-cTG6aegT>I%O*UYQoF2&QD83ulCg<kHR@ z9TGT4&h$W^E%l3lt{f7JgunC)gz5QN>YTJGKtwtVZE(0Xe}PAkp&8YZM|v#J?uy<G zxiI!juuJKbGYyeLhF+N_Ykd(tV;=ovR^7iQrL5m^+rp=QP{7>4B2hV3dPUr-Owg=b zw7XCc#tE1%qfSA9TOG&6b|42#e%}S^7*X{r0Q_O`L$r_lLS42OKGKY*?Y&bCRTl3f zirP`cqu_w5g%?ztqT-k1h8Arb5*QwEB)Texyfr?#;_*qF4yj9(BueTZXmgdbAg(c7 zGNI=W$2U$pE5a}9K>n0ssK`}agNq{B%m9%aoabX}(mxhuD?QD_jyO_T(Gg6}ns1z& z^Kwv!#9*b^SQP4|k_tnck`K#V;{=wIT#QVpL3C#;D4<=(IEIk_gXD(_@b3b^XR`Mi z0G@{c8q>$7I&)n)sL@F(Yh~8T&qQ<au5UX@AKm3ryCnq51Vu#==(j?T@g;jnR|aTY zVfN6Uf^Ij&ePjI6VpU4{MSZJGxZ<Xv*X<E+v{TqO=`k~5B25u0^XZ@BBY5CObSCFn zduTEMq)|wsW)eY}iSDMHFM>o0XA68{!^?C;ef(_V#2C1Pw&PM{@H-Qv*J$Cba`dP> zk_A3)|Mt?F2?$LgOhJKRXWc&cV^8b+rId~#9AV0^<cL&CL%N*2gmt>T`u7#egp%A& zk{?_Fq47@WeF9y0Sm@msm^BktKkcyFiHYt_75s%cni<z{&!Li?S}}dT9+xglNcRFq zo)n-<3u4k(oSF8}(<u0B^D|Jt%;0lQp`{8#<){7gQNFl5a!ry4x{z~3<pfz&83e9J z0RIi~5f=I9Ml0mri|#SK31b2Wr~rLM9_gAQmG)c<At6j*k{14S<FEijo3!Q}m|#%g zfiBn>taO{Bv=GXgGNLy{gfD}Xr|^hRHHf+cGSmi%xDr$HP4~RSsOb0f8yl7yb{%$y zq_?w3(?5hbfo@mX8?M$rghUg??$pb@6H2?2WK`@?t(#FD&C)iQk0qmurBk8zH_HXA zkU|xL8f0@hChxa4u~~R+PKDsF>WZ`4<__3gd7XTHg!r)%5xXtgn|q>nzMZ(YF8(vI z(xt94YQGLoSI+dPpAbX1-AhM70posI%q|^dcta>G#Z@xjqk<l2g*(E5g>?#5n5QiM z68$cr>|B~+wv?_t<7nnCl8%DQsBkvSaVEuNLYozo5y=rDIsaqmEdQEp!!Z1eZLq<B zXLJaRQo6fjl(dvINJ)c~5+ZJ6$RtNdcS%W$fOJTRv<iYsm#849V7$Ei2lw^uy071P z9tYR+C;sSCZ4gG=!qP;}OR8<)n4?d%cfY*`C9aiSYsE;{21}n0usP1&=YVPmn;WSO zqJK+^HRv?eJWl&U60>DZ)pZll<YmeLkdK=Xx)_7BpsG-8(aDBhnOD(<a#6+FJ?q0u zTac@A5Z0+dyYGvBELCD^)mq=Snfc%G<1h%9uB@t9szsH=y7{Nb{Z{xuI&3Z7R7s{Y z?uO2BqVN%`fD7N)R>NoNXBa~&CKp}lHH?m2;~ZngB^lElp^|e$J>E#~x{(5bY<bh* z5WBTn)^<dC3DP&03Qrc03~vs=N1Oa?mbq3`8O#_$4!DyR8~IbCO93zJ#av|RcL`#t zF5;&2it2_L{5-c+8O~0geagviYTaD2I*O*_NTGkv5_~=?LwyZYVSko5kz}qa%caPQ zQ&Ih}Dc3DWIaDL6xGu^L#ki>6ZIExTqE;Cp_=#PpgnjQsTPxonQ|5v~8fgrScUgb5 zSr;#`C=7(AxiH>)g`V;&R_&<wM|)4#bUb7+Y9JNBUEw!yRNnE@Su~OU;o4sPU8#ED znmriP#UfJn5FAuh59u<??*h!|FHcmD>r#2-WLl#e0rE50HQxnokncEOTH3=Z(#RsC zJRRca-u9vaZiMmFD1kEDL0ggeT8t#;tiuZGW4q-<=ORJYInJIV=+Gs3FFvDC8CJ%^ zTY<g_fyHZxhjm)^c7B_JP0j;6%0{>S%;3)FW>1yeI!k<?e7jffJi_wRNT%Txx~c5K zg2LXg)K_<w1n2GFPvDKyd?*G+;AWw8={0&Z0N;GB$%eP%Eb~r|WsQ5hdmELzO{ANs z%4Y%RrzHFQ;5#W8q+liYl`vO3=?+Y$H5^YG9d#zJu;gkYQ&*p#u4nPw@jBXME`|)} zJWmm~vQ{_j-J$`MRrO+Mh^c9oA4Nu-f+^eb8QR>P0!nM}_Qs7ZeK6Pl+0&5$RN1(^ z?D}J7mHwBPf@999G7^G?+bH50SJ+$xG#20SL>(k(%#|~h3u)$QI3hVxKxC|D^AlKV zw>4|A&UI<y%7{5idj-SCn4F_smeO-nA)5~~um5EIGnUq@UOyZa*{CFFRrKq!`k~RQ zk2(&nrEYxgsuqB;+Zt56^#N6q)%sfLV0Yd(sh9gIvhgncljZr=1Bue;Q9tZsWez>> z><ggDKx<aPzE!)H(6BIZ(CCnov&!#*{`7^P*Eh_ozskAa`njDs(xV2c5N&8JJ^h)# z&>1@@94w!}AYeD%C!E&0mq-O$gBt-=bs79=-&GLmlsp;g!liD(r6w=_%HUZkcre_~ z^|PTp8Pc%~?ZR{ZNif?J_h-kQHwQWy3NW(YS;*$OVkYU5>VDF2x6c(C@l8yLAi^Kl zon8{{R~NbcETo$f`DV{g>^$2Uzuv8{;)?Ij!8bXxZgcxJE3=-p6v}o}e%3m3o#aB5 z2utfN{%!<HhMk)zmv?+y)PyrFgin@l{B&TugztOd58bB%c$**>XS(^<)zaED0*4SW zvx_EqQ0ZM6lhv0p`z)R5jn3#um-~xiUw9S^7@F>|Gs+IfmoORi!}Re8!vSRte}Q{H zA0M7*6jH5<c@-Br6)vl$W|5JhCAV@Ig^UWtd_TVjcOReqWePS|Nw7|bHNOE`D7~6s z&bV~$Y@^{1x8KgQXcASajT>Ot((VhKX8;PGHoIW55y>jDjQjAu@PQZ|Ko<g|nPge< zVD7M`Jj`cM)JcS$n`nppex_<@t^0Q%aZW3-KhRl<sxVZqG<xaFrpEr;NKu;AU~}X@ z;bx?)kj_9$gHukB`LZ<H=+R4bbH{Qjn#vEPB6F^%uS)|sQJ2*nyQ6ezNSuC?@VNht z!JJa@5|%25jpUDU3JP>GnkLJI4Bzt@JklJxa^P2<8rxw90%x9*uW8!_KYqfW4*OHS zAxLH90w<dxRuj_<elGZZl!{ZsQ_yWEJAzp*$WcEn8tsaJQbV=m={<fTPnIdfZ=$-p zJk)f@-W+ZeMClBU2&ak0OqIX}BAgxz+t%|v_Pk+Wm#2cuySKKx^D*w9S+Z0UMCD}} z5go2S&nJ8i;eVo#(y`0@V(uv=8<pyd<;Md9+>YLpxd`hfSY!#+>}Y)B>n%ITaP7&^ zw~kNQ>iB3+q)*do9E$V<l`8s}K|6$}G<N^<aK~g!K_lf`mX$X~N!m$ijV(hZ_%EI7 ziZT^1`361Yh_1%5`>!^O@?=xKVz0XYTcta8N#=4>#a6*jUZLeE`n-a){i!sR-EdZn zVo#2#qA`fL)#x!%L@uOaj&-coJB03=sqnA(p}=Ve{+68^N4_5~kl`%583z%z_XQrQ zM1Eo^`AX@$3fD4&!?2VdWaiaT;)4(G95_E-dm-Z-4AJ=3Ho$+9(daX-dvXl!W#x^~ zQ}{}pzkKJnX4E@;vM%t->^wqFZr`}*mu>L<Kf$JwKd5xgU~wfsEbs@Hc%5q}(7(h# zw@xYd7K?qcwD0Zpi{0zlVqTWcXJB%lu;JOUIh)wt?Y-4cX=DcX(mdS~Z!;YtK0jc# zRWpX8^Tw<|Rx<3MBrdb@zsM(FFB~_jO)PYCr<(G<sP1P!KC`^H6mE6c)T0Bv0F;1| zlqr@7+e58rA5QZS;=07_%CC_zK&%Yi9D-D$2gD=z_;Q<E%5<QtPaS<^D#r;ammp-} z8l%VBc!t+<oz)lv9jR+{Y63F+SWN>(YB<om%3V#J%NHg~rsX8uD2PBqT_!c9kmt|6 zXWbZRw1mwlMWm51TnbSPp%AP{@7z}t`Qz)>^1E+0`|<FL^77)LYac7+#A8T_G?oXN zRuAvLTf#*2LT2fX!FkzcTwW##TY8pgW&~UDz%=9U3_gS&oj@@9DXf>Qsa>spA5}Y- z-@8e{X4)-i1dN%h7&3X2$#RpAuIM1uB7!owkAIdH9?}`B(70O1?cI9BBI!&OC83m6 zpCv|!1xN)!BmFdihZKvci{}pjC{vIo1<j=yIfe_~*F%DLlPd=E5Hu7Aq@V|hGsA4J z<#L)RG@o^U?ROtm|9!fV#8<ltO~rR{?$UqJSQpaEpc5ummyzDn2yq*oQ(&sKqg%=o z<hM(Ng}DDvQ}dFQI4YhKxMhSD4yh^9FiNX4MkO-chgu|&K}2GScstu}kJ#Ko5@u2; znouIZunz$^s0nMmFxJ7ktI$6u$JaHX%nQ@eK*t6FW)js@GQRC5+bRr@t_w+sjDT{| za%vYcK{cZLGto*85}n$Ai|)vT&D91~k+hJ6adsLJSOuQC`G@tOMeS6&VEyW&M#0+w z>2JH8<HXxlziKL!zM-5;$9z{aCZVLqF#Pp`1;Efn8(_<LPOJ(1WqvJRXcqx&LtUl_ z_TH`-28kRbcQoa*U(V6TZ^F%@_dmoEz^{z8z1@8Bk7UIs&R5DT9@22kSIC-ilDdh* zi5n>zwYFsmiol}#Fxn&}t)`-_eAXa^uL~`e#?b7ZEOL-DCF#aUkTG<JTpXFTGyYA@ zEHp8RxS3K-FeOP2BHWR@ZPjHxw>KDBX=2e)p(RQ*-|<c=RBk~f^a|B5Tnx>JU;b_L z*7pK34u!*5Sro`LxJHO=rp9yf7{_HA#yln*k+p#d_}S05D@r64EtZHrt8k~6tOW<D zvG%lf9vKyrU#ruNxDi`<t|AEnoao?THT4s~LMW4JKe{~gLFjI2!5z=B7sako;zr&O zvb7svENg<A={=>uN!9kRcMl@dqe_HPUpaAgkaLnOGHh?7%e2eEWle)E1_E%mzfwGp zJ~_Yi#1y~Bz55lvU^3=db@{$zknGaNU<A;`P@W{4d70P7&arj3iE>41O|@~4M#m9` zW=lg|mdi`f^S@Z&4<S@eh>3~QIhC9l3Es<HTwi+`xrxMm%(NkCok6QRzWIr<mMz69 zH3bjgeL0FbeK7x{M?()6*2z(HY(;@g46V5S$jHNu@hqJ_JSmlyNuTVv@2S`U^o!p! zLc~!s2#a~FsVl%Vb925k&j|zuPx&Tudhf=`6XWp~k0vsyTSSODGoFTz(C}jd0^5z( zzb!PJe!|ez(=>5c?G+dG(>7HW3Y^<{KEc3-`z`k%5{r0{IQ@xF9xhBwkJ>IPHrR&s z5gb=B=a^zfr!zy_GJ5Xw5+qVX>N%x&f=j0G7~=xp1m0NO<kNbRSBGxL2D(BN!c=mj z;)k%+jZ&Jr;FWlnbk)+#YTY=j$AQINlAsg>{T{msGrBxT^ft}EqeGgu=jZ-#>rvb+ zAL0<uY%8Y~$o1eGV@SF<`W9CDsu2h2k%L*|D6Er86Xb6<Rin+}lgG^!-n!zolAUe0 zF*3MfhZe7A`>vOxtQc*gNlQ-&wi7{6>?JLY%4TPuaoQV?v<03jGZ(1~8cL?S+@$0s zsnxq8eL$k#M5pCd2BIo`>A4Ay{YY!Ii)@@_?xs3=koQN@9?k2a&F}x6ja;kTLYkC( z`Y2GLn=@%54K2-HlK5@i@$!b|jua!(x{1&goQh$XC}I!`eb)QsP%Q6^WwpZ)tiW$Q zsOF6o;Af5H8!i>`cj5JGle?C&*>J;Ri*D+t){FSV**oz~goM+X{0h^p8+2`4mem3` zM5S+4!PDMq<|*g>2XQHexn3Wnt}_7G4#e)?8??>uXK4>Q5_h^c`NEov!OvJU%vT29 zfgaNVf8FVM5D-A_Hyc668<Al^5i)M?C`1g2ho3Ebeh*(H0*5FU5`^xpCZ%G;7;QI= zJqeL+`EIH~I0{0<oC9f8$6*8gQNalan>R}ggPYHq1QDK8O3d}Y=`Z)_`p}K@!T3=p zGG;=%!T&g(@avC>!y%2~kV8DZ<~q;Zv%m|Tk2|r07FZy$V(rN`Tnk<r$+bxgQ=g4o zekY6NI9}IE*ntBwPpS7x1F*GjmVk?$P&n?2_P+jFfXpd9>mGse<KaUMM44)y_E_w- zZTsqBcJKRZx8r^9<pGq_t}bjVQPlBL{c&huiGjdaO$l6yXdW}rr(huJ7e8OrY?SI? zjB#;EK3Xg12^<N2qW<r#R@&`LX0~<x4TwGFjOX2Yfm%PRENpWGWKr%e?_cuWrS!XD z*SCq+zOl1-ek+4?CEVq$5s#<4zse>hxT37!+O#L@mPl=sw#hYeU<a;6R*C{b&W3A= z<RIk%q%1fnNs|ET@ncKvS3YVMys8qQ!0^Pa&p-Kc|C^25FCMoNH!be+izCNngtijl z<Ag&lffN$uB`vJQpr@2cz=|r_Qmo6ou^_tWy0yOfZbCcAdhIt{#HWbF`q8W`b;NE< zlq$$nyFqo*{&ZrxYvNge1KAi&e9-;$rdE|yEE|B+(wnj`w?x5sboAzoOQFd}|H7&* zGg*v%yje!-6h8|Nzlq`0zn5yKC$^x7TG9Ksc)P)?R^?SysR+qW^S@8sN!}s%Pw5h2 z8TCEqKz_1uXRAR|ZGh2T2eJE)iogpI9e)9*sW2VI+`SpIoK=J9vzf33@dsxoYq8Pu zB?FYv(YjP{b_6urtl%QJ5t?=?bJ?eHC>R$jk~tE=W~gs;Zc0|Qxgi-vkN$|%D$_vR zq2&tQA3gZWa|HacguC+6{FxG7C`nsZ?i0xEZOE=wA3$s<P}u!aV6V6xVE+0(E5J|@ z8;l~(=XgE%Gs~hI?XgAyv7AZ0g@JMqHCFd1fHYxC!(HjbpNkh7AIKG3g48PE^Kx-_ zhkAZSMa`-F%OgpkNmY#;JAOv@NfwM`Nbr57<PXKPX&1!T^wP;@xaVc!WRQ}1`17I9 zSAo;&r?YsK**d~0KrIA~4pRB`8Ot-A{o<6$9)qWC5<Tp^`ZpFuaBU;FBrfo018R)o zIgm>wT5#i<scQACvI-W8fh7iN8f{YCjOyDC=rJapmMKY!DX+gtxlEdtVWE?F+D@=# z%)wFomS$zuVGZ+9)6bCO=;$LvG|)ETZ;UlO`i<3f)S<|I9{HKd<PTNX_wH|J(rkbv zC!qA(jCJc`ogp#N<X${b#pHL_=lr2U%gZYa+!E&ebz_ngdBPtolV33;NH~y``uj!5 zvC;=4ho`zs6fbMYS0e3)B;_9MyiiY?r?K6j(d8s<$WX9OLI5REpaXxN+;x>Qmy@j= z`h71u%3UY;(zT(WVUy*72WFH49XRF-t+LQnWp)ITS7ysXP2mxqO{lGfEqmazRMB#4 z;xc(zG%x7|wcUbxPtYY5r6CFL<doz7_~^0NZfc74%$?TS?o$QL<)oet4&V}k2SH%h zgtT?xU(CK_@g9X8;eA%=L!u3G1W?z+GOrzEKM0CfI#h#WNq<}O2|1}3NtI?pNd|3v zv|QT{w*=3NhWZ#ek#npsly_xW-XL993ienYr>=t0YdGj1EXnE3FwDVeH=a_@khMwf zhB@9ncm_d96^Z&Z)HNCcYYv`s4A0qw?Ft_KgTU)9rbaz7xX3?G_T?A|<xvG<h{8F2 z#OeVeTgO=>Bfr#y7EOa$+fajFWBlhV_)75xGTF%fWlgns6OlzM5voGI<l~zqe?pUA zd!e|~Y}0;Gu&nUmy?Bx8W!pcTTyBgs=H00)b^Q9xUD0?}T%w9AIouTwcHmlb;$v{} zKlqLJ>rII{ijn2rT$>N|0Ngb*NTDMnLI6?6Ng}-B5G3m{X+n50BrlZ2&wZ6DsdD9d z0m3TTlY^uAfXiT=O9_Bpav?aY>h)sGdS6^g=&tP>5}9p#eO6!m)`+x+*IUpgF(vX~ z016H%)ASQ*f{>O)PJCpODTDaz=P(`g>xOWp_;bA=s=H(Y?J4e0QyIRRF=GWE#x5fe zH1H#gA~cwwcqW*ULl|fo^8A}+X>621);P}*w!)Xo=3KZ`Pzz*}<%#yz&&B=Ph?SGk zX9d*j-}N&VIqwX-!fRg4JbD+!DWw!2Su!4jxW-sGpHrZSPM#0Xi4VmPFCc5zUGUE= zAi$|K5P`=_8FU~hnAi-Mge3W^Q7s$@o;&hrev-W1gup-42Q5;8CH*iOD>|b7$rUOI zVN_Cr)|cqt;NlqYu9^b}mL^3Q|0?`mndEF)aM4O6n92QC?jbHhPVFEY2Mx@-4V;H@ z?5`{jDl9$a&Gn<H?qZ0}01yrk&uMohn49_pqCpPZ=^w;_*6%m=*-7hsB>do{EIP3< zR#Ih>iS`dQgz)CirLmWU5oquTIC-6_$K=0K?aCyx9-(*6agUrhbQm=8^i7rYuJOj9 z!w3G>B(6!Nk&DS~S!m&RbK-q)5NZG*{##^SoMF|p<NzqR`ppU2q<K+6NyCX%dq!z{ zndVa#6%TsGg*oZPb{X53|GGs)zAW8~8tNN*djHLpm=99!EjQv{p^$g3@3Ys%5*QJ@ zq){VMqw*rFEJ2fGxhFSyE7`V*Ym{j#^#bS|j)*fO!<}>DE_Oz0+v(^3aCCwQs)3iN z$M!_2?5BxZyZEI(pO@#&r=va9z3*4F`uItXH18cUCPsRm{pp^wx$&}_R7$H&GESbp z^j%rOoJLw#>3D_4kRQR|4KTS}@arE2S1+RPEH(vv7$8ouCw_=zi{~rB(P%ERV({G} zh)cSn^?N!*vo^!095_Knho_mw>P3aBMi~({<wpxc=BX{0X!n^-3jQRv9#~{_IOf<g z^1(%)aJ{4E%E6EEW#n-3tpHb)r~=Jm^@1z`aJKP|)9-%+&B^n4spS~yW%SlV!Bc?H zUx}|tJsx)WjhvILwF+}Gl>8#w+hJD_YSWLPy){RJ_?Xy#VUDd{Ao3$(-Kd{q_(l(# zGcS>7&2GAynV$#tFQU1Yf8Tf2?VeYHPxi|#KiG};4I;2Qpn7bZ*_aYSoYX^25MkoZ zRfkCr4M-mQb2Qwjr+MlFl}rzPxS1S{+BcUaqF$~F$nbayW#Ay;a#z`62~3m#XHhdc z&Q-pBD%!g;nhX~NT)6L|D4VgzTUWzgXjg&KF#`OhE~^3`X;xq+S`wR0n(NA8tNaqE z$>GVp=4++inP=6hs_ocsX^Cu)Dcr|y9;|Q5IlG%Rn0EJ5IeAmCEgLlYNQ*JJ3LN&; zE4yUqxA5NOHkEPfn{m0iCo7B1X|bJ<Lzk-%x#=46ew~QskU_sB)aC(4*BOWLe}E+Q zq*;;YIZ1F!Da)N;w)Op1HZ!N`dE)z{4_#~jEPB}zEv<55PUz#5M+V(oep+BBH(l(0 z>W8A=wUbcjz~%rLjxCPDeHH6V=dD63@1#$l0bCsCJTq2@37Xg4Q>;!1gOVz8qV2bY zQ7g_8{1=(zPlH=wAKZIzn^Em3i7vA<=|?R0gknAdCRLSDxu*COpU=ZI5g0g!t?0L? zQOf3lF-*?!N`6l>$~Mscwcxr2T~bPnS?E{qs-GK4UlZl<NIE*_y79!+bRNDItW>Wk zUp@K3WzJkWKhH`<-#5fj@8Tl?lJNngVb8N3x<gQEd~&15?y?(Q%0AIsFOdbzP3Ac7 z{<unxx$cdc8ikE3cWxwyu(ED=HQwEeXZ9PDFmIs*S~Yh6fH`eH4Tc|19<B2Qe{d*W zrg^PtWB(B8e0Qg(gD1R*2`4CA^Y+aQcjeKRU_GzQRmW^@Tq2c$RyZd@EmHcyUH_aE z|Mknp&qLxT6s|ION)s_<84t1VA9~wpx6t0TbNrCl$4xGOyHfLZW0CG6qO@KA$CK<R zks;LgLZ*-Lr`Hd^Z|gC)$L|_kFdhYVC0H3({bP!C*EpvB^SsG?d+=xH*9L9A3wC7l zS9CcUP<(WtTnDnO9Y4(e`Wp~jj3clGo~C?jdPx<&m>QtOU7$y@oEJU5leiP;eV#+I zqHiGof>lC_y`j^k6jy54i-R4x>M!vHl<t15i!^%AZMkcmT_l09Vo0F(#$WB1YnnPF z{qq>3G$xe5fZc|#)Ekox=HJC`-(e?2S}k2xQ=j2R3{d(%gIw1Avr4p;CwOOO>WW5R z4pEui-imI%04dz9W_|4*qE5A}bMR0#0>yxE|5cO!a(Db6T_bb;weOyT14W6e^+nQs zD7&wWT?$AW#@ki;(jF4uzE?Vk{o?p#4zged>B)F?{W2z#VfC9onk5i-XW(Kb-vP=W zf35wFAChPD=_PJ&$<h1veZRp>C2Ug{HjI&GfL38rKEuzQh^u!poSQ*~+vhz3B++yl z;4=QoVqE`lsP(s>zyHMt2f^47oG<MC?LY15O5fzo7-bSwvhh5TZ1gqy7JNh-N-rT1 zef=lXZTTKEiO%|$r$<8-`5BhK!{Yuc>dm~SiTkv>AbtD6>04UkyJnQaO}F`V5bURU zMJMBYpXxA+A)k+ab!^fw|0?YxEkNmh#<uK`;~%X#?rwiQ@p(?Kb_VF+V|{Q`Xh9xS zd_-~Tx2U~TokPep4gTWDP&jouniFa2bx8PpHSKC-|6$#&9U4BrV_&u49`6S1KklYZ z91TFwzBKz#F~8_MvQ5#vMUhg;8#0~Yj%~c-x&7ARlOW^OZ0nfcW$p>*H_z`3oZdE$ zN9t)eXMYlnOE1Px2Mliq#Idje9|0~B)R)9ZQ2Nu>_g7i4_@4`vD-Ozm;4IYHg1b^P zT=Tce7)@2Y9_Dkaext0K2PLuoV_J}unowL5mo(IVr<2|(-0#}f_71oUQ9)2nWLr*N zjcKBNcEEvn$Q36>hU8zjwQA@K_3|v%L3HF~6q%|JaFadh*XrZHj=TKpcDcW_b4TKV zvA3jc`*xo08u!PB|3=6(4l3SkN{PYVf_Zu||HZrFcH`-}aRm4hvOJbJ{E(JcAFzes z;sz2ZZ&_7f%S&i4KpDHcymKY=Je2qn7=wo(4#RSDFk0Ee6MK$<+hxi51bOJD0&>nU z+$<)EAZ}}xglOhP3WwD;f3`6b8OX72bbDQUNAz8Tb02|L^sd-ai|2HiN!?xX<%Uyg zYxvCVOTyBeidM$dB_kgRx{`GA9cbKW3MDq-;HX6aSKt)7-F6mI;g+J|PT4-jTH_qc z>s^4o^R;;3IbaMO%kC2Y{I=odP>T3Hg)i^hU56}bSBq8s9_49@>AS`0tTRIX>i!qf zq+2{GPFOgS763*bi|=1z=i1&POvC$7f3q70m<2R|ei}_nh49Lak13K5H2(em`E6sm zSpJhkgau8}&?`19@d94JL&VJL6bjmyd9JGOWVot#{yZ;<%}pN7_1ZHBwdey8mgZMs zYZ<A5ze{t<5=2`T%My>awDTM{tOnt<0&E?n)@(;?jApU-ciy;Y!-W@&bOm+Iy?CNs zRw+eM!7s0D^xMoll61?h%yI}>+Dec%l{b~jERco)pfd6T_#(W>Zp>2jX4Po(hQ}o& zZwVC+&+9U*du6^r_B!_b?@ncDJYQaQSz-)4wcN#8E=Afy0q<C}#cV?kF5rFh&N+H^ zkGcBZK$Bf$o(S7KmFO;RguOy&o>rAWr!wP{w4PVj@Zx({*;A>1LsQDj-7VKxu*7|G z)j(-NZ7>a=?n<kaLB4M-OI(v@iXR6tL4K!0`&`tx`iFf(=T2FEgMIbcuQ_Fa+=5^; zSnMb3a!Nf~)fPBZb$s@Y#j7ClpJ$?%_8xm%Ev-egG)ZEkTgUsclv7Q^2&;QR^UHr@ zN{^e;i`EgG4#vSSP@yfz8F3mjLw@zEYsIYBxM7BX(oo}tvpx8WO_bdz7)rsOlkW<4 za_|?n%^B5wrqj>~cg#~gK-`<UNZ)Lr#2kkB65lyP51)xO9=g4j`($tOOf}A0NA893 z5ZCjS&|mu>)pULx7bls!zd2GnMhqW)V(xLD`4l@}*s-pk-w{!Es!7*bp5ZQkwwb2g zo41i4`muATIF`F>S42UhYwt;UQP+N5>&Nr1&y7ReFAiGgonL%;zESkz>x<)$FTV9b zdAbjW7;knTjq(?Fe}5(Wsrz_Zo2Tbw-tuP8k9Y3H>Is*#8hU<xD*vc%y&ikB_l)&Z zXz%aO^B+=6YVqzJSmxH7eg8TY{xjW<WwBcScMdhP@i*cDwz0hcpA_ECjq@rF0^B~? z;G(Q3rV#ZWI6IKM|3zqwQgU~I{-f6e8&^(*k@w)+lMNlZifh<Sb1)1%B+3-HIy{6h zhMcAn<yLs<TL%@WtcT-jq|@l`c@Oiu>2m+o<YUY~WmsTpz#J{QsEwJ^UvWDkF}003 zP}>ZP5oQUeIoGzWGM>xs>p8kQmQzWyo_Dg@KS~ZcSYzGs9#vhJPK{dO=lQccdX++k zOt>V#OXD-9%_nl3<mhqI@myC=OD5e>_>v&ace-##nT#BmreHZ+hN(R~vtU?2Say8e zGK%4H*<S$>?WGBG-?_{>t1VF<yK&1FnS^FBLCNr%aqEwBd}YR!QszsqOel_X>J9`Y z#9Iu^w2nnu#kR%opH14oZ^@Npuaddx^V+*hCTID?Q}Ky`NkEZh_SW#0B3{@eoI}Su z-yI6<`dqJDIWCeK_fmHsydL$twfJ}R_*Lk{^nL2KVoDPsE&8q*ymdthgNcw1|HMqZ z$U+(2GkvVGp?R{il_;0s?ln#hi_|NDOcl)XWBLYN7Fk&fl~>|?3~%I_XHK<Y#7Fjw z?r_X!7hq9vBm&?)gTZA001$%%oWMN_ZVCW#4sZc%`b{MRu?R*H$FZi;p?Hwrut2}L zY$TCQ)^}yBxqLJgqn&Wcprv9wL&&n$alEDSRkoD-M1etT)$4qv(EXM1)+f`&nz7Ve zhHcfe<@y;SP7`f4^H0pm4GRsQ)xN2-ZT0;y@vQD$qsveNmr;BDQmglTt<$Uar_0ZS zHYN&<o;Q4W5plf#;nnlTPklHj4YzSe)7lV;QPg>|qj_VL%x_d=+}X1ADo57uBk6YQ z&U6WTFO5l;+-`WG39B=(irarjyEFcfD@XpzGCcMN6vy%W+o${Nz~YbFE>|NCEuc52 z)FhI`bK8?C53ffae_kAKp@XarQgQl+6`sE`?d`T@7S)gLXu=bj^fwT9UuI8t|NCPc zR|oV{^i!Yn`UhbVW(6TrYR~~F?#^lCwxK1p)f`4g{P6kU1Ar_wLv2Y8F%1TU##V^} zS-X}GSn1jzG<Ix5bfo!Qp^YSkaR5L8ZT*9BkQmJ&_Sp{Y4YJOl&QLORVCLonfVf&n z8)nS!L84*t*?P>m<U&rSyfMauG>!Q+s(?u$ZRL8)EDX^B-gYx-u(h$94?jaLRyHb% zCQgli2U*+2IKE9!Eva4o8A=nwqep}hVYc0JZMrTp-EF$zTPenLVG!EFVVlBo@<U%Y z1}LvNnO+lEy&%c-Bl{~A_s>b|Q9MCt9^l8LTG1H86=kpn4lfnK)-xE+P_LlJ5{q9b z_^qS0QA|3ubrfd)SS6880VHSi;jkopYyY65Uw(E5#GXp|=hNRm9AIigbmn(l1mi!V z0fYlsm%hGRiLF~bp6>q1V$8t=Qy%~sPU$vdyY^cW&8nb#U{g^CM}6}xeV1VJ;5Ii* z45-rcGoy$4?D?j^pLzw~p9~a}^+fRhC68-X7?LaCuBZ5CtkYs`?%blVxIrlIYjP91 zT&x*u{Gb2PjFo5>9I$ke9?>#eG$uE~a;d+x!G4(4*M+z#&5WGp*!@_(iwrlLr8JNx zGu>tMXy^=2IY(VweRdB{(!8gUKp9X^@oPQC2h#t>Ms?xYJEU~d?WtN7^_hutzV|wc z3pd73cSAnZjO>A1;&HEeA2@+iHO`3&85}W9Blyu-qu*a6XVqukGFEa1S1Pn0O2P&7 z*S&rJ?N0qUzA2p4rQQ3kPzrdO{X4u@<)&W^me)*bSm_vt_;=>z(>$V;#sgCWBB6)G zIpkgvh*FyRjpr{Z`_^as8QRZs$%ecq4vVPMw*5&hBZE2Z_ffN))0FdoI)cNI=dUo< z?O;D1BxBNsw0^`qA;W)v!8DcSM9Ym0Hirda?7Vq^TGp#XKonUu@$S%``3iAtFk0HL z6g*Gmqa;K_07u&~8rO(tXbxhCf(~IEaA}WaGt`Y7S_QZG6m!GOF;G{W<}d<S!v#zJ zRvANgl81??!#L^a6-^xyI1zX7P&sUIJIa<!gR0Q@x4iD)4})@kxx(u*VTP4ELDO=D z5JWHoF_&^n^(ipvsa7OGB;UBH!X`Og2XR?@Y1}-oCA0d{EyF<<vUE}@2?~MgBG@{A zF>iWDaUvGkUiOffQ!<!v6be$8$DXh3U;0o|O#R;tP;n1ufzIdC_0`uRwtb5Q%!)TY zDv<^Gq<LLW2hquFQ&K^$$x!wk^N!WmgiHwF&V~@1uQ4UGp?TX1+_^4j-7=IEqCrFJ zxocg_RQvt>JoaK$w*Q$IJYXBT5#P;JdFfO!8d7KDqD^{>Y3b#U!9R8dgvEC3Kn2ur zMIZohTKmq$F`ZOGOSQ4?zMzT_kxq$gj7y_sKF<_J2WUb8i}!Pcf;G&MoW8oUKKU-o z@S~2+<wgXBxVkCI;mw$>7V|#yCV=C*shRn3VOxZ&#L)IyQ}yTVa77`vr@WU=F0*>< z!Gi}wQMV$lU{egqWpo0SP>8Sgx|Ag_W>qC4?2lzy21{CaD+3Sfw9@TCsj-$KxZNj) zjSi6fV**19#X$?Rv<T7tRSz~r>{gpOoyUAIxhm<jlOpe}&S`m5JBcJnAqTp*s11W- zKDY?#Iu5>sJY(q8zD}Fy_(<+KU(!>O2UW;Iw}nF1FS#*><C<yT3Ho~$>ZMu<iew<p z`k8CZ_2AXjLR3wYn-}v^VV;Y`Z(&$Ig$~IH$wz4;v5D%1`@18*uf&Sk@J95<8hpjg z7kKJiboQIHQuZfo2ItD*uI`F7i{u90FDX{9-)XtvN+B11vfVAihQ(6&Chg`;QQ0wC zS%!YWBFilJK%KJ@wIk5aTRE&ta&wIW;i8L83g&^=zcs}}MTt#Ax?`y~y1<^SfyZu` zy_i0B&A&1Nw`l~}v3%P-T4z)M)8Q9u%fFcmVMFJ7zWfN<RiezF$FL!&L2U|Tbs4Bz zpv7GdB(rlm5rneoBKmy@v~wPW16O)R{D~gswMVRw4IijC7Dj8~^dAEZ^~1mXcl};3 zfhbl!S7xoX;2G=Cd?s>{t`OBalpXpqX<ueiE<s<WLQrb1fsQv|`)6(vHt&qyzklHV z0ppG3{IxVGkKmU0=S@`WdJkRF=J`zyFrX(cgJ)2!{+@sYwcq{f0fD9T6y8Y7rNScX zvL;3gbw`;)n<@_RO2jo#GN1%LVQYrD$@N&)5toKo8ldBQE9LU$Ij;;;Nw#~Wj`V5{ zirPn*oNuz?#q+C!)>^KN(SMWw!SW{Td=JV!;RFU<-K1Zq1TX-EQD^yNn|kl`<^v-q zg;Q%@mz;2Ih2L+#O|St5q^!c7XyMBjSha0_B}=BTl*^Z*;bJb^C1!9O|LWUaShFCC zR_N$9%O;Id){_Si+(B7G=F+8ar>)wi;RPSD1MjB(a9bCBe;m5JwWffW^h!bZ4{h!& zBr9s`1&~Rsg}nG>-uBBK5Q(H~`(^`_Bh=&C94HaQ9FeraOJUUQsWuZF9~)eryh+Jv zJ^s$LY2wCzRN0)|ymHr(YdmEEaS_Yoa$NdY*)Lzi>2(^91ZuS2??pJg|AomDMPx`| zVuP7R19Et%1+@AL>-+XS9H%$Vqmk=x*)>uQkey!WMDHk%<FiJ>mQowdg-}t{=3A<B z=O-G5WBftyIb-uZ&a`_72u}QoWzu$lmLB-|vdjFPTeP!!P?(mKoVHvAxLf9nyl|5@ zQ553bmTZ_#F-9Eg_Yu62)hu^=+vRO!gK5qEFZdStH~upZL8>YoP!h0A8LBoG3lj>} ztOjFo46#x~Bn0u`FgDHlf%t$a_ps}08}J{K!XGzX-fE^41{jIaD~Q6ROCcuQ(nKfQ z#5v0;2Y&m2GF*GhJw(xRdc@;h6}bGCN{R|lR|=KOj)$5P;jYAc7vF1h#DlSTB$h-a zjp%$rq;<u?*F5^qp9kV^S&^QAMvqNChRNHxt6O@5>7#;$889B1Ae#ur7p0h2O%$XI zekDF=(M8HuTcny2zEGjV$>RSMcHMu}$8Xo2N;-T@m+Dnqtg=$lT_sS16fbK-Bzluz zSe&*kf?x~IR-<Q>lBv^3?;^m}DqN7acTWeH@;KsYrj?HuXqscfL<0LQV_>CzpRPb{ z7DSe%z(vIbsb<cRBPyPLE~;RGdOnj4R++o}cliZujwxNP+E`6q_8@M#yw>&U{}qsg zAd(OW?dl}9$h3J|Vq6d+9tUzqf+S2j$t)d^N~b$YTT&tc0EwalT)dn#Xk%;k5WVyU zyK=te^citCrd;wJ;c9LRB)#NHnRlvWn&{UiIMut<R$Wkg_0C<sICz>O=aw{&j%N3r z=;$mmn#E)AN^}^j<%eC573+A)qjXqW8k=46{9+o+HJu-y9+V5lxe!?*NjUE$N^Cq8 zug|?z7o>DFZ0#}iT8vhF%JnTLS2o=_0pW)X7=N=&y>W(<IVcn00E39~J%lxp)Lm@A zTsE{<PVkG<$I{Fp58EweeByy>;-oh?vzs<^n#GoeX!ps7rXg6(FK`&ybKc3!kief_ z;qr0z!J0WiO+M@Tb}a(_N!f6im7K1-Vx2p9KUQ*{FOm`qd9R!+QHt5ZK);;3`dya= zofTz-l@vpU!F?S&M|M|PpMtO^%7nL;JMGz?ogiChJUkfDx|i0?Ueav<KF?)<*McHG z$^8atgz$^57%rXVVtUt+Uojb{@M8r$RVJuNl=wOZVmAw~tX<hTv^UTayYn-X>L@66 z$FCqRhh4!`>8EM$GYcBLy^J7Lf?miQ>ws0ytOg%at1?kU85HuV=n*bKG$Xo%84{Zi zz+na7ICxD3)XmFAna3|?1t{Lili3Bmb_sNAq8+;Sl3BtEQryj#%Y;iY7u}2+Aus5f zT*<FH+jH_9&x&$?XnEOEW^{y(D1(CG59TR-9PB~t`}F(O;I(t#^yiWJ7QT!o2^C04 zHm?E6d+)*3u>gm>aASQJ)GjEE07@wRPdq`@8o3MZ+#tjK96M>>iK@%I5*wHzf|f(c z70;@l(f!AMUN$MHW^(K!@X_0VsGSl@SCV&U$rYap_)$gsSw&g`qwzi{6j?dxofad6 zTfSSZtnUMd<i!1O*VzK&?eMz%ci|9){<&JUjoT_gk-Q>xTx(aBOSla}gag;1zuiQ_ z%V1(EiK&drkg)6PuzJeU;KBXMHR`0G>VO_90QZCxuMZN~(qYuVBcKvG(99+J6hqTO zEB%xM+d|D-Y2urHV;^Mt6Yycen*m}=ujId<sq^t1c7x|(*!G^(hZ?>k!$tvKfnUEN z#%}zfo=~Bopk4N+5AsolBOtX=PN|{G&ol4P)AFd?dH_srT`CqhYla28nRB#wh(1jT zYKQW+)8gA1(KVM}R6Oo#ad=VvUwr*1&j1v!<FKxkf=J5a$F3Z~ut7I31HLPqGf-cZ zMom9-r%apbU}V^3@%OUe$%qCm{_eTFm9ICL^d|XJZEToOpju8=E;XR*3qm<6;lb_x zpPPAKb$QVs$pFxz`U39yLRq>77Tjeo8hX_mr-bm?S9tdNWoR@dzL>IuCanPgZ&+5= z8HMwQe22WD0xVlP*wg5#*Qr<D@sL%Y44pGX71b17&jG27z<0O6{ADmI{F!<LNX$-3 zh)O2~b@4}*_|O3Ub$wnmEmtUCJmc)|NPI!V`+}Xfom&(w{263DOHb;^OO&r?+<%TR zug#6SX;P7MO%be-QEE)T$}>Z86l}I=gzhZs0i>uoK?>b_VAtE+;z-aY5>&GG|3-zD zUm~Sk_K9WfW2uQh{*%U*2zGI{BmP$SzUqUD^<Qw`Ow~YBwM-cA2m*`DECJ0|Kv;d3 zV>hUq1ilsO`?~{9%Uj9|KYQ8kKEdk0xT%DG(m=VEa*Yp)K|xEj!32jvnpt*{mDK-) z?47(sq>`i}<|7V-uXjYCPtL=$B9!`kYQV0u5o+ld2HnHYX#n$r@pP9Fz-6Q$30-82 zCX<JM|3O#gKcg~#i9p+-%yn3deR(s%rHxY6P=QlRXI>X<dd(<;SK_gmpO{OT)o{?X zD%gU!`Z3Og<LC3k%_k3h(Ts`l6Q}8cOZC$U!<~CzMKoxYG@gGjUK%|D<DCM{k=v7? zh1k?}HPB&liZZRAig&!}QMGNtMDi&Kl@EHkI5ia5QLZW3Ur1D~3L9j>3*?Bxs)%_x zP0h$FCbWa}U1!Tq0_+H@;0el2*gQyhN%=P9*4_)Y+<Um)eE4j|GHM!`HqyTQ8tOVF z@nsGOn!1FYl0J7Dv0RygnZJPH=X8>~_=QOlOG)o-!NFyRdyf<8*Ipv9S9?R0L#*w2 zTrMifGf1>7X`@FtwheV9X4)%;xx;lQ3cU8?F5)OLr9FGRt2n_PAy|{1AyV0t-#6bi zmkuJ+4u{jFkQp=Ma!&JbUS3Jsc^UC}D&F~AGLkBI5gNRh@DJRN237unY5`rLuZqP* zn}<obwFz)K2~_YKqgv~>f}7pT6fk{)w0a7z&$Sf2gQ_pXMo~5n;9Et<Wt6Qqyb5=< zBkPV&S0L9@m;65EfER9c<55rF6|T$?ofa7=fcSrN(@(+J4=ahU7vH>IB$<H8;%G6a z3D@&{Ff9*p<9C`S?HtJ4ojB><D_={6&xm>tE*j{n5y9%7S9JH6R94?RJugGeYAoHk zzEy1#{loU`AenmisrX*}#Ms-K7xSyHyHLR^n~uoLrWIPqBEIm$asbF#1TKD9V;C5> zNSbGLO<pnt*C`{EIs!%CECpK4elr0nUJcZiK}9o!7Yg5tF39S;fwSN5ysjIFny?B8 zGyS@`PK{1-jJl`SvD*A7y*;vTu&_M^sHAipH|s_x|65B+e*Y%<eIB??H@oQEfL!|W zjxufILE(n=%7@I!J~nLVT?1Ufel}=a%3iwAF1H~UxPd@FsrjHle^mO?(Ilwe?&o=! zP7BOPzsRR%3DkO@22A94y?EX1*AFdy*D5+ixc|XR1MSMaU*-&!eMIsgfU1~%TF5ql zdw=n@dHV$<noPlrS2$cr(xWvxg`tGXg70B=^hX+&E{Z>y?ccL|sidsOgn2gJf>tw# z^UuTdWjEdl_-_bM9&qK{NA9t9K1*+?K=HPR6>i;k0=?+gCwlhFxc8rGfS;$n!qfJ@ z6oK`D+eQC@EJa&G>RXR}L0+GAp}^_vyDoc$APW^xF04%DD&lc0r&^}(o6-|wfsm*I z2PrnkP&VMKMX&P%!<gq0XGy){CH+s^!LL&vyT>Edk?ViQxBvS-rH-ySZ$Q=r?w8~C zc~0@gO~=JS$Iw}1IdG!P^X+TOvHWe&?dwYM*F~XX@Ww|lfVR&tXPtg+R}X&uSZ5h| z6dh?Le#H=EJ;eX~QrKRiFFHe^^nH}Cz2TGY7wR;f;jG?6VcS5`^TR)5d=C&8u8LEd zr4G&!2D-&<x^+_F2hXotC(fYaw`2KFNcC^W!fIeSa8|8xmc?_DcpFq`+&_7}b{YtN zE||ZP|GG^XoXiW!bqaU|f0P~p>J~krOVegzz9OIpPL+%XPNbgC9_)YLD1Dtm6a1y> zoz0<7-dJT`^`{3f!n3Vwe}y7f(%$!xHAljqzAG)*a0uKkPC0#a&T~e7aF*3~oN<0y zu1UQ`4^$k2#b%&tBj`MJhH5^c9hhtV)6Q;`|6k|RvD)=y%4YyX6N8h5(sEzQfv*kX z4PX>#@1fNM{0^J*aE|$gUJ93b42<1kQ$JnMXqywEy_&!xLq~z60FZ-MXqv?~`J{FR zWH|Rw-Jw+dMd}oPPR{s2az8ef?t*75HM^jb$fC^9A>=23PwO_#g8}uLhM9neN<Pce z%kBQ^DFjYd31J}2;C`8CI8#l}9fN=J%1xF}@OcQY1p)Ajo&jsKuWq&ctfr1RJ+p}1 zj4-YeNaqlUI=q5Yf_?y8+?!U}02d&7>5-HXi<sg$t)X(YhYN_&0Q8v_-7v{`At=wa zBFD3k?bn6;2l3bAv5))0U#TrtT-Fk!mL;H}CB_4>L9i?qrS~N>_+nM)A_{ZN3!FUR ztEFD8y@4mg+~BKq`j}GUQzJUHnR-0S5UFVhhzP=Tu(Tvf02=7sMoYPRvev`@*8Q}= zYiBU+SYsws`LITMMe~?Mo^eU_zQb<M)!$%sbs0))x@4YCrTodEbK;khrNF%P_BhY= zFN&NbsHPGiVYXfzeHbZWB>sG}#Yhq@LkGMC)4f&jo^t^uU+DHz%BAUlH}hA#=R}Yz zWio<G#@jA{)OGdyjG6|$c@^mcB503uQ1d@fCsSYl?`FCo%-+0Y03j<jNCO`PC1Zcf z>@pEG1%70jOYt!eZ%|qu)f=!!J*)pu$=;*(397|XI5ucg$TT*JLp$lP|J1F7uV;fa z9%n1{#mK8TPQl(MkuiXG6~K94CYG>`wJX5iQ{aN=InsHLl~nd+rzFazF=G@TB+c|W z{KV1?HSia*qW0C%g1hU|@jQA=YXmxTw?}d#*KO7BlrX@3+1z>o@Xdmmq~YTROPyz6 zQ@>d^=z);e-MwK8_f5O-%`yw=0b)ap@0{@OV|!ww{z^Z?+lszhj3YCX9Ed4w)l_Ux zbX9yRvsr42@j@l~6R~b{Ea$+7Hbx->e)t>(?>iQevE)!`YFgk@Mijk9?E5#CSBVsN zU<{qS5YhDO3~TEgF4X9)^d3#@R=WN^d51#}R~pM;r5`NX+=2OskfJevZTkjwHL6=8 zR;=KVFU^3vnt@WgQNa2!Yx-mfd#=Sjr|A@qYN7mVpM!Z_hGM_)m(p{%@!P=muNYUw zU+F#d`k<`ui%+5~3(sSth)OI>c;kH#7t>;g`DNe7So(&Za4+y&=n*m9wnOPJ!%O*^ z3Nb^G&S5EI%}13?E)8cCX*Wz=nQ@l<ZyiSf1cQbD0aLYR2}C!pImJgpn|4xvh)+TD zVUh&Duqx?+*}E2eQ}Vg6&pfwQOE@=i*BEmvV&1RhIr#%S(fgIVKBC=KjpOai!$~A# zE6^{N-EW4Ok{!!qplE9_xE@ErZgCx!&e2R;A$QRpVWOYQt!k3+lx%&21(=_A8kC8p zjp^{Q4UpUl$`~@nh`Tb)Im}KJZq>ku6mEcIfump&_+AVZ)@!yjq2uSIVaCX3Ucjo& zFocC12#<bk+zFb$&|bfCt_A(8b4(WiX0+Vo%3rmadN$Xwq(;Lk5}Ee+#F<FigjHxc z<QnDRBMx9YSlj;XToxDmsAkw0n)mWBM)%U#J4y>mLAv3ny-q}<<GU{G<TX9>;3dtE zZ*&ce3DMc-V{m>YNV0xMGxp!H!xahXB<XDeGi%<WCJWnG8i|@2&~#CwXP6ET@hC*? zIr3j8mKi=p1L=+=0uW@7<&&QAy=GSPcN0HR9}SEO=nIc9Gwhsg8vqeonqmDZ4}gB3 z=P)1r07Poc-wgyOh(Ohrr#VaL&@`7iPlGb;S5owZ<T)p}GYxc~cvOL3YEeMTY4Kx- zW}vt)TJUljn;vR|;ZD$opxCKCzJ8rKWK&DbI(YQzzB%Rx@rjzW*7c}BoqANK*QTjQ z4HYB|YpILCQl*c#KW%U_ty#wgwUwi%7Hrnpq13nXGJ@|U$MqB-!5V%tP1qMhzBvDL zkL>L>H*OCVkX=6yRVI%IzF=+!C9~OTbH~n{JVFU4$lSR_7G2*7Xx*o`_@wwqUo#f{ zaJ9<nO$7PB0P568;w#Ab9;NqUaO$|7ZitQfjV+PqwUf8LhRCK{CzvY|^1I9&uD6rt z*x$UccO1jojk1H=-s;?YNNTi}Z7d*eu;NSc4dW(9tapLx4y1ehcyUwGbq~dgf#`~T zj>Vu#eJPew-uk;QKH?B)!#@?%n%S7Sw5I<o|4}Mc`8aqk@aFzwwvo$hXc{AZ!}P)+ znkU8r1F<?HEX^IC1U=WrBFol`#+k=O9Gl&_<6-sCvm;IFF*MR*1`|kIjdeU<xMHF= zA6xWy(%JppyHIQ<h7drj-BtqsMFI381`gcVIhi94-%WZ2PF*Q!*M8;pIa0ja;N+zs z=$hh%skq~&7nV@|E0eWa>!1D~j~mo_n(ho#GGmq20y3$PY_}jCxKaxeW!>b)gg~KE z=m*_R!=pw8n**<Xj|2sv{T@^`M8}?2n@MWy#EHy8Y>b5}p1gy?Qg36~CT~4d<L&jD z+ttz!f;a&{q_^JPmaA@;e2D-cYCCXY(ED@%qXnobaawHM;H)*vbVaE=)1$KYceZ}q z%7nDZC8~h%p2o0S!Y`SO(KH4T8MRtjGb1{8kk(}Pl;Iq>Q19=w^KIwhd9|20&6p>L z*P$+*b6bevH?`NUa<lV#AMIc#(q%g5<Ub(BlgcLUeZ=b@HLmk|HnGU;_(S^@3Ib|w zyXg}gMV7Y}-;GggkkjM3LBRG^o~Az(plpryx?3cCEsSF@*71n%vuUoKbLC3|oEu|4 z2`&f*2%FxgzJb8=J9%KIEV{MUX?!}cb16SRas6dRUXK`-FWbYnGP-v&FA*+}gYY}i z{BixFg*x66KnK>Vg4UwR(S7140cI#g&dUwbh@9|><elf0x{IRN!TT@o0-(5dOjrYw zX4tdag4IuZT^Ao_Bb_^=BgU3S!_@jis+epvf)1I+K+gfzmQO@6+u3`uIsf=+&)Y;l z_HJzP|NRntO*K?3do;fJ2j7#F&zhT6<FOcmMs71&NZPGufo%Oq=HLGmorgQs@Bhc& z=QxLBAA5##Y>qub(sAs)IX1`0%C6L>;Vh1Q%#dVnLi9zHamdP^h0KyDm88Yb??1S& z`@XK%bziUR`FuPIjI#im^pD5~@0#xX{qZnEm4U8Ten~P1b_bGJ!<hR>6eg}pnHp%v z`w+EST3b~f$_m1C3pj$hN~Ui0wAGNX$`GS?dH}6XRpIF67c&B@5>1<KgQ3poL}wpJ zyaDv%Z9RP4r7Tme_y4`<_>W8$qVVaai;BOn%cLfZT<Y1nWNxeR`4XjSIJZEXvV2R1 zs9ehR21YN`wKCNm{G6BA0eDegqPCyJh~ZNXSwBppWO`Xk>3V@~$|#PGOO@S?F71re zpDpc9v5e-Zz0^Jv{1^)W1{A1OWV!Wj4%;^KYQ17Y$#dIGC~gU2F$Jv`gkdA~cgJA6 z4lnqM`gTI~faX3klAf>xEn`Xl&h7j)aDR_lyTfydjL-tBnN*!$looAm6#>{@ALSvx z0RTrnE`OH$8{qdz+@0$8?v~71M{VpP@DxU3Z=oBFATdHH`=k4{qn&6wAOQi6ePj}* zl>g@|;23t9h!t<^AXyJf=~|}p5KCIX^-qN;<QS+k78*&t?9&Xr8A}tY=o3ga1mZ85 zHyGZ50N9#Wo5XWWM^ihO{zq`V?ZCyvjV@xo++xZAaj6-}ty`kpbM|ct=KGscc%lIu zY8TJ}xj58<jGB-7h#*Gf46Ypf2jSlhoBWMh<fl8igtl{oMaNvY8X}a@`=ZS>)x5dO zDiV5ycKHcLKHc=iyIbTK9GO!h(MtK;NUnZ2tS<`~z7H|Q#zC=EXk(b+leSlaZTi{q z9Z>t>G1vO}S-orieARxGOC82(G8DwfBOXE6%E`;bLspq2&LR6(*^u$dkMvhRjZvmR zqCq0S?n^v;0PkZ=gz*j4x2NuAmMn2BxmHyMN&U{xOd=_K$<iU_bJJ^6mmc<X?4n=7 zB#eF=S_)f`u%kOOWbHz7Q!K5KWthZlN}@ttPhJrZt<K&-hS&CAZ*Whnv5cAc>n+k? zH)ymJKmy$l6L*I(t3K+y%|XpB_-U)~(04%6jnc*P;Oa^@IfxS|0m&>^_WDm&c5;Su zC=VEpJGKf!{J0(vEr~LmC-Mq2K?dbmO7WYLMX=RpITn~Ul}||Jie<I2Lp9w@U#4kC zm2Mw~OAmlqZys4Sbeps7z*tvpw}mO24X@T{eSH3}7ClVbXJH?Ym{%|H*g3LbKaR`> z>r`9xEZMO$iA&<CMv)tWue!%pr_<;RCO-sEO5Ek$aD|1$j1bpR3F`#W9h<X?p|OVH z%<q=vGh(dvndW9w%%lVhxYmR=44qZ|avyfK>j%YR$(~}>*j}iMm^E?fHFej@jS9VN zWWD>=0l)6R!81)<r=?I8lLp#IH0jqWnYP@FO1V=1mMXr;Dq&|SQWa`Q&`f{-q(q+u ze%G{2+gMW4sj{zseHW3GZzB$kciZQceVz0qNtsc;lQ=x>k(5FB&HiHGMXgS%MRV`9 zen@waI&+jX@si#p9zACu5hv5;swJI<wsz~a#V<{ffoYupSV+4AOD^=j@NlPil0zTd zIkV#N5iFygXSAc<;~!C|)07IQTRfQ_dfVV^L@77~iBh{??DvQ7*4Xo4Klmi(^0VR5 z<7=+tDU^PCA<C2=M#R-%s$=}@0P&=qL+%s}W3|^v{a$U(VHC7Zuw0@t$u1+9QzL&k z;C;xh@$^O%s3&Y#UxCrBdHG?_GDpt>xntI<+&r_U+BT-*ola`Zqv`!wv4)cR>s+wj zF{i5MloqqJfq|z>{5CQQHbgX7tdLD681!fslr{PUFZp)s1e}wsIk1m^zj0--!KNWi zP0bL7!%#%E6$)L^Dc3GkyI*YBwFlrb5fwRxY7~p+M!x6bz0?UC$7!;RBdNn7Ft-O+ z19fgDbL^bcNgP9VJc`;~(L1lNT&6V4QC=O;@MzQPZgZlB8YE?A7W)F$7>k3Jxf&>E z?$~)PALRno6gB^Uc7U0b!rP4<N=BE5rU9%j%H5s2Od`p>%&%Jo!7f$T8j@tO$k@F+ zXsz^!uk~=Ky;&<Ms>1_rPLkzGwROPEQ;G*|u~X1!ewE;*<wqK@A}HYA>y7XAc5n9n z`@<s~n)ImAJPYQA_+EbYRg?;PL>8;5n4gbv5Q_P4ajCDC98c%%%Bo-ho7l|D0|Qh` zS^P=7Hz2a9;hQe=GzN=@Q*4g98xV(`WLxDgakUl--IC+5qC0MvW#z&lE7K%-*hUUz z<A2UeBo{Qltr%43l47=x_xfLlhX>}t%?hKH?}&g;_+>AAFPXgl?%%36aI%uRKAY0} zI;&UZ%<>aVV4m`MRZlcweVz&7Wrt4HO_Q=LJrdGc;U7p>r`+R7hf_i6IvbcF*qz8i zsS_aC$Bbl4kTNwUQZPewMDDURm%mBLxm%ej!xEQLB0M-4zUo-JLdA`7tgb6W(|2i0 z%c@Q9RPxAf@$azIcdqN_Vy~?~tGKjYs0Xn1chz~y^IcYuht#RgnvQK&Wb0Q|itvFv zzQbo8=&_tX2OCiuc_{bDAl~LDMf~mt^jCqBm-oAXAhk)p85DbQ+F=;03Z+@<w#C;= z{a*<K2TrXi?l3E}YCA01N`~wtQ<7%q=d?zNyo*cd@bIpJVoPwUn`GCi9ZwO;nP=WE zd3Pt}GtPt8Zwk7e0-tVJu`*R3{t&H2NRUqRSzV~NTOvEob5Op>UtGj5?sfVR`MJ{m zcFXMWzP?Q%QbB>Pc;=FcNU1gM(|ACLZIjwru=}zQT^SLzgd$=^wWUNfC>KtjDv)zC z+H)dTxcf_5Y$#Bdc-J`2AV^lnQEp$s;Ancy?pWH6YaYE@K6$KhHw6eJ^#*xNLEVRU z({_W19XPzlt0ALRGFD8#h-!Rc#YR&jO$hVlR<Ldh*UiBZawOfrrEXVN`?4)q8Hga# zAwz`W;rxmB;~6$2_wYvBw@e9-LO1ZXsN(b)BGodOw&B)joEqnL_H23&AH?$12Tnhd z!_2`!qCj26#4ou)+lEwJumM6OnmpS+zGPwSV0Y^g*|h}6vI3>Nct;%G`SW8Z`Evkq z>C^XxP-1gvYQA^qUBd)F*nqP<HM2s!&W>p7mc$}Qa(hs@?qC1ePV{;$aorEU9!!dp z3|x+v+D*)GJ1EoC00t;^ABSZI3D;7L@URBTwX&HMWWp|s+;3R{fx1cm|9yE4xmd^D zgN6N0f*Q#r#DskQaASh!uJv6H%EVx(iuG={G0ZK_+c*;Xi}g#IjOIC1R#Ft^x&Eo= zIMnMi?DBy#-#+X&uVDg>dT(!tTeN0)A!A;jl+XB5SmVK2;f;RQ50up?3VCNNw<LZc zHPZfaBD<I+UW{!$viOuvN44z$8_QbIfYNGK{XRp<k5c#-9-Jur$U*>jR!~IICvR(# z1la4hH`Sm0S$+pu?bC}sIt^7?ARmMW1=Wzd=ovk2e>nZTENSyak?nda5KV<GQtGQw z)hW^cr285N@T#zLa`P7s#v@9grRS4IyR83dz^1Jy@o;6-ulL$Y^Y?v-%u5J<nIZgP zrwQ*&LYkRGR^UU4&cFpqP#4p>=9Hlt%Wy%7fe!SN{S-FH-16oN%f+Zm0ig-Io1enJ zJvXMfPC?z)$v9h*XNQOL;!W&_P!hxSROjn>pXjr9-*-g#-fQ&eX8`r6pO4>tqZlo6 zJ^x*C-LCOM`wZ?1VqwY@SSL)r^&{~UoJI!;_Sb^1PQDDphnbA?zfYfFLW6P!FV@;m z#RY1gKDGYb{AKmJx$8|+%>M0YsKruMmHH)t?wj&TjwW*puO%ZsIY&soqBwc~IB-sM zwk1U_eNOy&JJa?$mf?@Y&&zEO;*!rolSKTo#U$u|?^Q?-DxN7izolGQ;Fvy{7;*fb z8u#RJ{iMWU=fx|Opz2?}<B9k939Q3cHg`eqf?|epw)52TqGWlG%AH)tGAk`Eqxng< z1J`41S~AUo#r$xt&7>NXeto}53uO3z&&`|KoX>1TDcBFN=AS(WLr`CU-scc{sK+Ml z{ex@*>-Z9yx^z>)nT?Viv-gxczOb%$=f#(0Um(q8oSst>nFoHkc;^D;_-TK!SZ%@m zzuqX#pissKQy{hF<Ft6$$XAr-jYG4~Ljvhx0GNvr6=cf^nA3y&L$J-+y*8Yz#o)*~ zB;W|v808#f6qI*t@aT~XZmmFL<v_!7ORZuGfXX$6hNSxS*M(iN^AP3GJRR$z{?~O- zAD7AVnCTv*`Fri_qD#y(mgZ_#ovNVTJh6kZxeLYRKq|SWHc+xLU0A_QBGL|N2xSNH z&pn+iCd3|rDdKQzY?W)4CP)4@1$}lwGvwZ`l(P5waF(<~Q`j%n_v3{Zf9jfS(J>QK zn594^6^9rUl!1A>-$*Q<;Kx+VvHL#48z1`_HvaZiv^$W_Tg8JNDb=@nq;uCz>zSBw znn3U^$jDx9{r<9Dl_R4(O2NG&nyEYZlbl0wR>3vF_m;H_o)$Z^-gVz=Z{r;baFqow zbpzz>sxo8w8IL^lUxOl@0|q+hxjdoE&|cBI>pb~FVSud=5HMcF6AJj8bG&R(j&3-5 z@-uzTlOrPgRh3aK@idJ$GUB?xN)#TgaGpA2)jR@v;ieGYO^i2<zL!4$MngDse|`2U zf;-`dSimq(taD7oT&$hZ*-RthT!=0JPB(s&=|6K5EX8yF&kleBx7_BJ9qt;HmYbps zLA}iO-y|i2>`&%RcJJG2R|e^KjWd=gs7OkVS-fMU&HK+d<uN+Ic(#4?u}qFIhg&-u z1=$+cGTpE;zo&?-no~f0#)Gvu`KHdjuF!xFR5%zw_1aR|z!&g1E}P~qDlh$@RDyH7 z0!;{TWI9Sj-^gT&_sHgvwlyeJ?pTk0oJv@ig$lv|?5t})qgIKB3n%Jmbn}9x#<c2e zz!~{^kirbQ9H#zauAjLC|Fw0h6nvp;>>is^rN}+&k0wqw>Sk|dEdcCjjtjF>Ta&)m zZF#uFW8-HB=L}D<?aqap`;|`DYI%<Yf%<b}ImJPOoX<X}cm#s~JE9YKVkY0CKKr0j z@J$Bz2OI(z%c(5$>X^KL;H~i}WQvq0Yv>`h$pqm5n3&X6<)#_u6oG~Y%!Tf6FYLdp zu3c}4z~1!I6ukrey2-4ax`bryzt7Ybsc(uHkGu2jfK=mfbRmHHl0)rB4O)oLU-mq| zQIu&U!Mt5Ll9hH4Y;}!;mNOQ&+QQIoslPm1_d0~^W>YRe8or{fd0F@Cp!~r&L*IfM zl^qZp$_c3xsQB^JO0Uy)u}dJfZj6hUbHiPuGHmL9L-UZ#Hvly{`GJ4d@~m9L6sz@L z`H%myKAaT<zp%ZRr$&xE-?ydXWRSw33YP7VZ_4P8U|H6-$sOenN-yWPb?Lu)RQ9WO z5rRnm<znO!ZuO>OM_d>^M{W(!+(_s^sS3QA%GUEQkS=+zY*1qsgn<)c#_5cQ{vhDQ zxPm*|TcRdQz#K0a0_40`r~kS<!BPfoyxS+HIcw|FFpuE@uftdEJ*~8^KT|2J7yD$f z_=k6s#~DWB6-nZgmxD5!Uk_LN<Cna3>iC!@Imkb_Zm67!q<RO@`#x9RwrBaMe4?vN z;FX`epmsyQ(I*5EDelQ&byI942M#p24}ZE1rjU#FLZO+wK=V?z+ycbROl5|XuOEEI z8y3&n$AwgksU0Jr--~uF^)iLb5GCCj#YWvsd8ri|0IF6x3SGHaH-~v17o~>N75Y7l z;ZX7<dD06!T8aFs7}<<WN0sKFj&r%c*&gDu3X1ea`0{}|Kdwq;ABB6RHW-{#RK`}h zzF3epEboKVmh08~QnJ+ayDazU&BPsyr-j>8Bo%T_wj=ZHVb4=r#hhkFulWq;tk?~i zg1@dd18DH8{nkoFNiV(M8*HNSfwus-AQv=R1IVw*1%eh-K|teM->(HgzUu)CK>^Kz zgIClA+7JCSBj%*(kN<)gEe^d%MYl;Exsio7oU9+%hIs$k6t-5)HXY(PQ&;{CiC53> zgGKZEQ6r$eo*XAOw=itcr!m#~Z#p~gbV^8OgHo!j`FNk^J|Rhs2h}hk9~gwSDVk*# z=vVOA%QKO3hy9sCa^jJ|5jsdUe}}&KkX`geTYFQFQ@Z7HHcpUac)0)<iVmR`{1_^C zZrx`B!AC1h`$@T469kriVI_o&c+j19lGmW|&qtJaAwu#N<8`awg}Kq>-!3+syUs+o zD*w6<NwI>1rJMJg&3`-*?%&I0emOV4D9WB&qj$`1sZhKN?UVv^KFU5bbnaLY%ni8z zUtPsFUO;KzOpSGOw9tc<@nUzdzI_+|Z_l#<k#xHtdpWA4*OK}f`QyiHF~(0F*XRp- zG8KS)9Yl>3#!=wHW5%;f{cXWqo}alKTy95SaKk<jZpbHBwuL$$aXU80IeKjQJ2GEq zVR`&_eEh$ik>+^4EH&Pu*`aSj{4`^AZLo?vcIYZ~BLO-D#J@j?tbWe;GqyUhHi?Ds z125iNE-HGeRwB8T{=ic#NuyN3hIvyhfWF<p@cKYtrdwk%>7cjY3gO0ER!PZe@vop8 zlN+MtWHp0%Td4GXfqg><#U{GeY?dV@sPb-b3GXOBz49Hr3&!h~>S?T!(oyXWSz;WY zzQU6D-Nmf2tsb51^bY&?xgXwkvrN`PfXVykAUVv=<c<8<Fws|LfDopC6P)Q~BX?&2 zF;XX13W_Y*Qivc@;~_x2esN`9j-S-viZjZfD7%&6qBL17e}Sobg7ECU>0GLZhUxQe z&L}*U=9h!HjtbO&_4HZS^Tv7U%i7aS*XR2A+L|o$xc+BzY+T@b>NZ?okk$7wBp?=I zZobDG%^RoWuSLB+_K6Mj!Y;j)Ojo_&)%q$&X??%i5)WoQ@Sq}iDxfGBKI2s7OCz0I zTwk5pcc#`^!|b5x+0ZuAr!rK%u$J=1Pq*}=!vcw>ZJh!Lqql3uQBR_c&`s#;D)*4g zg|T;ZMP6CDM;H!wJS*d$*p(ksdb;R&#T6IdlL|eXcU@{UO&H&kAMP}bYHAD6P!46Z zh<xG%f8(npt2y9mYhZ}Hrv!06(4@?CHvP9q??)$4tOF2iH{aY_cn9V%$fnfsylXr6 z+WD#h6*>hici^Pj=eJypZ)RCIan4Uo#l@}rpWIjozOolp6c_O$#iv;m=v&IZz3NT% zaxh-X`0vxGxTqJUQd(JXb}1k=z2@>mO%;~`JMKwYn&S@|A1iqJS6<E$Ef6aF^oYcb zUd0IOqXMvvq+U&K(&K|-7*l3SGaaWyhW@y@RSA9aBcV|K$7o;$6PBkxKJlj0(&RdK zS|#;J65@2((5fQ+$8`rApJX#Ck43Lj-Qby7cG|m*)mKfZaixmK=mwWYR$I_7uoBkS zAM&t)(YpDo;MgM%-Pfk|eIqrXUitvhn#R{3ZWXRZ(IX8hZ_kz30ua`a!6HTox1^gD zE$fSnARzV{#*2eH^+T85_9z&_#fE~uJ`Ay3!bm(u*Vu=vW9^l5{aGP^uy8ur&OhGv zqGX<a5sBl*xcnhTz74EY!)242Sl?Nw-%|v>z<CvLv}#zneSlLw1Z!+#<aGyfGZ7Al zg?yhK_&*E&Gcw-f;T~6jY>XHRstOr(BX)l+7C@IUK698}^7nZfZ_Aq9hOZnCDKRz= zO%nl5Qm+O0z)6qLy=Ze!v^D9h1hFPQ8}x{Ym&CH$OAQkPB*wVV`j_YvemIs94;GGB zO3)pil}5Q}l#g5QTSHr#v#X(Cdy4D}jKwh6<VGrL7p#0rsOT<3rN6uR8m8#%dkRhH ztD$>LBA&kX4zTp)e<ONJ!B0Sw={|O7+-&h;z$@c8!Bt;+|DHi&n7h^Ap<YR-@V0NA zAwLU~p*|Cd3_3Sy(jhj*UA~R#u7fl93$Oe}i|=uNHOk=4cb{dP*Kf^lJAvA31Xuxt zx3U2?aijmsVFyZB?<+tqW~Q%Q8|1jL{k{*Qunm?r9Vpk@;9?sMq&%=TPEa}_sFR4u z_yPZOh?-%Qew(-A=d)Sv&xPD_Tjq+^4PPbRlcBpLBV56FjNw~;t06m8vS;i=v_x)7 z!4^N7xs#FR$OJiexxoRDZt@ZoX5b=K-Ly@o_m{|d;$;JSYzFmzxjHT}>Z9G&=bkk) z)_h@U&M0zuDUIjBiUK5N-NQb0;%4)7><>@QE}E}YpitjRoFON~&X@1DuVP@rh?Rj# zSpR=w($P{-6<$N-`1hX6+nxwZyokG+d6xdl1K)XJh61~ZANl^K{U<f9C(W*vPNvxH zs%-R_n;@i10P=<99mWITU&)Go5tR0KKv4pxt7`LIY-oO}m>b0NBhuLlNbt5ayBVJ8 z;3Rk?U^tp{R(<PR{(!)+Tm!QZndRn`ov%?cYOeo2XBJcg;rKW4u5OL<HqVofTzt3$ zWf*a!k|>)`(E3YgVyp?kA_y;X@0ruzJEqmIj##vj9v&GE2aS@AY5t~QjE}pIu756N z%WM1nk5qRZRdRYE_x$SHW)i@7NKNUjsS2TwIVExf4hJ9r&TXb&VtmOQ84$~QL4C(W z-_!>U#>mKaN|5ml7B#s@lVUE1seYSyB65mw-swSk7~S1`b+5sRPijz6u;%XwEFfe+ zYHI!={ZN6N{GSWE+-%}kRmB5K<}r6(3DQfYMeZ^t*)PQh=}XLGeC)2>F-_9B@bw48 z`Po@~hDUrt+-lYP(15=KTD!Is0mJW>SM5or3qfSbV_I$8)t~XwCv&v0tjQ{#%Ibm% z`dm`J6Lsj<UM*`qL_l6aj%9m!9up@O=<x}IqSFrRSDKrTcMENIlYbU2pGFfFG~fD9 z(@|!PDG#=4aJq2KyhMMFMF-sLb}A*VIT_R&pMl-e27u6y@^cABVdNcAws$H{m2S=n zGrx=t0#g>5NS?@Ac3w!d!f+cNE|rw-V#RmC)%;bj*^_VrN^B5yNP6YWvOY)aXA$~u z<DDnsL%SP7sq68&;-}lJL1Th6f1IyQNAUUMsYo=Ti)44~KX2QIuNR`OYRUxMIoq$` zceZFqGWb<F5KQ(mmT(AjpKKEOjCZ%`2o3-B9^+VvX6fVXOMcEs8!%S*aw7rBWLV6@ ztP7R~ay;$3L#>1xoZ%mT8X7m8t{3F483ZR+#gjR3CLIedPofDjrbHVFrZumLwbRMR z<FW;TioeSu^d04+1r0odt9JUIpic-Yro@Y3U=>T^!xvBV9h=ThmEKoHJQ)c~gDtF~ zglNHop;Ch%jp+mK*7%d${e$rG?In?%)xnH3hFyT;TELfk&FJl7^nSelehzf3DVYZ% zuN`7D1(JFu=OFB{!js4^TZFv>6>8y_@CvgT2RGk_*o|Yh_NNh&GgpykG8?$i->ss+ z<Jv!6PXfClb{6KjglH-rEogqCDiE*I`&bP&pwf+MmufnrS9Hj!JvB8}cTNDhZ2W`z zC4<0|Jcbf?n5Gc@pSTGkPpRm2eXCg3azVq{kEx%Ff*x^<upacXqG$=A-b>?jFcZ~F z5_aaxfNS!jT4eU;Abe<vc!Um@+yQ-MTGlh&$NE~}&i6}E<0>Fy`kp&1>_RjfQ=&<U zfgNfF&NaGLwes)vM^5H}EpUwT#TIUdCf?8}E7X9h44s<%fXWFtSAd{n`JUG=%F6NU zwqDeZUXy@Ys7>T&xc9`^JfquXbJQZKikiBs^6|cgvI7lD7(Bz)n$j~@N7@{|UCQKT zSO}N+8FQt9@P*OBDhC^>3Y}OVmzFl7{?5~VmG7zLG@uCSB;ep>3b8eISlYLu@n}@9 z1ppnrGtA)qHToITTRjDp-<n^!&rc&yr>6c?MVOA~`xCVCcQwBO<+gs!HYHUdh=t#G z4U=#nJB(+OM-(43Rw>0LNCSx<8ss(&<U)y&$(ItLp1N&&%YosL=xekgeLm9kdDZ<` z%{9@e1(hkTNSZ9FxvZA0t!lKmu5W*RZtvJo?vuw6rX5ek89#oCnk4jk1OggUbkht< zXW74+yf>ab=6Tkz!?w$1qG_S_UFG=~o|h4pbZE6pXWw}YzDuErTDEFe69;X6ez7f& z;wjSvReMXY=FtZz`KUrQ>9N0pYCbQJ_VSnlcj&_*2VwCb`9>xLyRoR-;de+{a#$~S zN093$dBre*k+Q?I7i802|5|I-uJ+SSCPPC$nql^2-u}+V3O0_Aso1*=xglieYt=gZ zfXOFt3IFkb%c9%VkCw+ImBo1#%W(ZLO|{Tt-q4o&7oV!C#o!}U0NofZQzC*ipyvMd z-s1fIMfHFOn!v-br?;O5z|ChXzDw1z%UaIeU#+}w<sF|BZy=hH`H5tmraqa`aB2$u zVrNPV0L}@uF*hYsJzg^{%_+0?wWQ`H8PhY*o{4!ZSm#DMUU=c@Gp8IwEA^)|y+U#O zE|YAu$m(}!CZeN?HX{6jG9lide+RbQTZ|=`bo@E}pDHRwjqU{hKW(xQO%+S0vW?L= zx=3))3N%n5JU!YmSMl>Z86KK_l<>X9m#uiz&>1eJ!4|NV8Lp{H(#%pAtr<rb#W`q; z8T=##=K3Y>SGjXt^EsRdvZ_P#yQL2VrE3j*0mrk@MkOEAwN8CLqJ@8ZzcHyuqa%E% zM;dxftcFQ93m((V*E7yF$=TD4iu({nh=F1bSZzP^O2D$%ykY)NCBD!b`nqv8mT~qh zS{)y>0TiA3eZwFnqO)ZONr_~87J;2Q69ruzDzD)(n5Q**wdttIz9};LB_lQ}EU7yN zP5x<Uf0@h2R5^_DJAg$x`X|Mlj85AMt^4pPC?~+)(8j)@*_m=UHfQ)<C+vua=IGSE zN*=jb+h`sp>=c%|F|z3}PEZ2MRZR^PggLiX{$6o<{@3$)a7s(OD6!DnxFe$Fe{}Im zVgm%eDYcXS|7?wmL%;i_w6vG4>_lq${7S3Hce?H1aeVva-s|IY)k0$bcg)<6@ITO^ zLEEc{2&*=qU|ZJDf;8ygp%N=ym;Qk(C+5w=TctbPPU$(<6_Z{EUA5XzxN%YaCPTs# z>A_o?i{8$V700mujz8Whu4v^8rQ12<QkRh8xp7PB`yDG<#HRI$icCz`Pi?}>UsE4C zm3<6Uwh0>ibX^ZmF)VR5720!Gp9g=b_S%T{U&mDV8(E(GXyhC&f0()2=kBCL6TWxN zYX4YPd#NuO@3Lr!eUMNQz0O36XK5xbEZ=qM0%aWf4VLes6~}CP>dQG#zdMXYX!)~< zlBDNpFxg=p@3ysIh888q1wIk<I;R%=fg+JUbOZc9MnDN*M|{g#vPC}eehEMZU|&m{ z)B97SxNq&}w@}$1RC0G_mA592`gB3y*;SUn1R(72Dk)DZYYh7$b(vEN$W~5cbl7Y0 zv#qvq`Am?T$y1=T0mHXXlFusTU63~V5>Ovhyp4^#9axMpzWf=SPv7t;a%xnM{maw_ zj3NGEVwm&24X}^02@3fbum$Hr<5|6{jq`L1q65Yrs9b%P`sJNAFT$B}1cKnQ5^X9P z<~SW$;#CVpd37K@pUq9#CGE-_gDa(gLY?cJ+Ryd}oY)Zt+f2ZMQv(n--D*VbQUvIq zEY^|3vlWAd<#kx@e=TcHLl#tB4Y6D{%Pt6JQYg&2_pf01P7+<U%!;Z%5YJg#QxHag z$z;PVlWP+#?af<LN}^5WY6<;hapuzJdx*wooQ$noB21x`PYp*&;%kP{pGplm3-;Oa zRsfbV6*uwyQU$`9`RiH{tq@-_du(L2=n@4rGc2BI`K{DW5sOf-DUQcf4209ZB9ui0 zw`6;OxUWVO094YH$X3hR)FDDJRNxjDB1^)v-|pqQ6pkh5U8<~4*4YzzL&hBR2OH%? zhTPia`zqB+>GmmM8Y#~XAvj9?0a&Otg&u?vfq<f@D!me2Xs&~AAwG~l)W2U{FE3BK z>hduzgj)WSm-M<cvEg|$roLg5VgTgDoQLrYA-%6#O-ad(xts-|P5J;MSJ@S@-}VwO z0cs120_bG3R#qznr$UK8#8)yGJJ_#YU%qxx?G87W8GWWD7o*3`kAgAJa)mn&5UX>0 zRvrG@XH213ApMV=b-GWc5wC82VYm&TOw(9&i)EDNaDYJp%%QFqH;|#rG~{0%NWNYJ zlD%v0^jqiPs47wCUu;4CWhbde&Nz-&5B&DWV&`+{QRV>;L+(=S7>GzE)x>DBc}e2! z*CCQmw7^kXnJbX<*si562VkCeo!RP*AtA3^@AI1h*)UH!Gz*HEu6GorWo~6oq4MJ- z`Nisl-t{pmd8|fh6+Wnx7`h(9EUzuN)gJaIdT;Pb4QmXw%in!kv*j^T%MeKLgidUG z6l6~%h$dilJR}loHa|5zY|e|sZIEoeb?Gy@y)C7d`zlPVe_gJQG(Vj&yT)c42*{r` zvVX{-Wg7p?iFQudEyddN)NYwH&2N9z)`@6kEcY6zTdw~sC*#N_l~TUh%_gTn8BdV2 z46Y~3umPtG90HH<lGHJ9Zmi=u8?!GWDU=1ko~Iu9(+NCn>;9*RBxYSmq%eXN2T;*+ zjSveQb;S$dM`x~(#UIK;-e5PC%(esNB=!XViGc;4#06M4AC?Y?@v5-AW^?Iy168_F zdLei}(YAfc)R6mn=2s|DR@xxrtFt6$QKY}aN~p-)628m(^ZO2uROvM-(@YVOOjk7u z%o{jqnH4Id$%A9228SnYo)zqJ2kvIgR6iX`Q5hEX>y1G_J+MYqkV%O=TR?beNu6$x zB_rd7K+GrbZqT|H5ZBK&L?($#umK7Hz^Dm-$=sBc%S(E7C8rsmdsw5s^+w3C8w!Ls z8j?MkM)Lt%DWHuaspjaPM6l0m$*~T-v{JfvZ%OB)t<?>i7B)_1N!H*nu<*-6vVmf> ze5I92T$Xl{Im@;#rCB9#w{4CuB0=re=DvWx<149(ji+(u8EAIUo8xEIa@u-(64(8c zv`R4uJ!cs3vDGbRZ<`xlYcG-LVb-e^t=YM6VQIUO<<QLCAq%bavT?PNw=10KOB076 zut}YO?UTWkZwTztwgIGiY{YYj%&x*^;@|O5@WugR%#a^AD=L^1X|<L=@1y%i8zBmJ zkbEFF?s8R(^|$MjGEiJ@r6!MBCS=%N{ox1KX*V^0M;ng4L#XQJ$6DLVlTt=wj%WiU z*Wq1%$@c~_jwc<q6vL~M*Zbc*Om`U0#j0n%^56y3&BuLSL}m%M<T>03DHqcBC#{#& z1{2QV0lJ3t>>hpRxFYu4ro49JH*`?oP(pBO9U+Pe28Zr(b1^k5-MIyOp!iTbGg4hf zo%>;g7E&j@ck(>{|9(%4#N(xsBW|}dteEGU?9m}n1n+}6kKC$g)>FFuhAz}?Iz>%E zbwH?7j9xR{*ZGH3M$oEzuEnt&r#x=nmj73M;L?XP`E-C&+l#|r6%jo=RJPk9KpuWk z!BeHzk(PDN)Ri>Ch^NmTR6N=??ZGeug5%8e>|qB<c46l$eFFwj8A%hLF3uG_e~k=3 zMkz@H1<G!yQ5KIGu~d}_kzI+Z(Mtd5ys=VgpFkmK%-yq&mdT^W$lkbP7C=wqh+UKD z`PMz6UWM>(iJlhF*)Y`0z_T1=PT%^`B5w(<>ydxDEphkq<b5L~kM5;P7q){bUulD6 zJDCSoKT}wuKqXs=woCVg1$+XpK{`uh`qWKfQ5p6{!B#edf{F<g7Gvgki-(RCt62~8 zBKPUvC6lJvYs175;B7yt>>768z?kgcaM82ybEudn;|;l|q7B~&b|0qYX4SXmm2U_% zs?nkIwZVbkFc5)Pa0Yd)Og3+npCFEvr$$cWD%dwf4#xD@lr4Zm@|T^2hb#7>DaoU{ z*~kdB5#;HWCZK3qnEfvSgA<D;O}&YKrW&swWD3OJ3M<@r7+7i=d)QZ7l*6pu<6JKL zeKwJ1WYj6EzEp)VJwdQ6PDmU+i5m<bTS@0?fiVCtM!YKnuFDQLsRf1)1q6<<j9*TC zW_sr|Mwzarcr6I3(zTHiKGx6xs7A!AYJ5grbxn_IXuUb<LL1Xc)&6{ZUeZwAeJA$K zFf7Ev-vvBwL>E6T>Nye`LUPDl;XVV--cu?;C3NY!W(%x8FPVRz&fvZB5mCx!E*&8k ztV}_CX1DucaGNpn@`}-P%ktv##CxS`mT_!_ZPjpE>b6I9x^{QC%;3EqTj_}H8<oRk zosbRY?*Tu=&9#eLrOUG(ZLz%3XSn_4?&<zxx{~6b+zFFI4MvK*(1|gMO&$N-d<FlY z-LR(Pa23*Nw8BFE^#&7OG8=X4NkyMv0Hd<#J=gSJ1q=3(%GGFE7XC>EBM`s%?(3v^ z98e-CDhApJ4V@FgkethuyUFhM2Z)o+a+!wtiXC#uz^fUOf^zacrzJ{v^1C&@vrv8n zNRvm_E!Lg;?UN+MXnc_-H_zhqkB?H4(MZ`P@s}kShe+_FF4S&<^$Fq2vUC5>=tBe* zAuv<Q-^$ulWi>Wh=O9I1aYpWiTfb+MD@~ONfuvB1!BeITJpJHATKGN|qae}eJ)R+s zOq!Q7Q`Op6WlM)(e1uPZ&%P<K$?uA;_z;V6D!_#7o>av-a3PWf;GODUNDvo+BPEm< z<f!86eHTf7+^V*87j2I?6C^Q*M-8^kMJ!01lJGIzF_tR62b1uEI(tZs#e)N5Cj=rR zPwufZ{5QpO|4@pG5Kd(iZ14@dttiuNxwlgDtBmbu3GUdZT&}}Ln<^J7wS}VAw+PG2 z6iVjb2!r4K_`kDa+ykUIUeIJy3r9C(%huE4`Md8z&^jHUylyUM{yWXwn#qKI>)&77 z_!A^tVc)_nO>r2ac*p?!g_c{=40$<_!kNRSpd&WRM0<w6w-pTPEchBC<uoyZBs^D% zuK?w>tk<DT{-mrF^!Dbcz@BVi8A1?e$KZ<Nv6|u0-V~sg3LF~<_p%5$PB&nYjx!^_ zRI~Qf4fwzBo30)3mu{kT^w;D-Mz)6EC*H#^g-9N+TR6%Xi{aeew*DQb4N0Ym8#lIL z{Bk~j5$d$}T-%WP%YF_81_XBzg=ll#ux#gY<&!D)GphI@fZSA_2GDLtgO*yK5y%bi zzyrkD&=)R|D6xywZFmBY`K0uP1cSol!eUGvHE0s^-nOQcCmAtLz~3yJd~Cldtrs9U zVNtv%tDe~Op?E`}3VFWlmT-#EaDA#F3LdY)3&uwZ%pmws`odZI43)3djR+Te!qhw^ zrA+(L6tx#cnD;EBvJD1*Y%}D<HeLAXuQMfJw_j1!H#qa7IHf=U62$rKYJP7v{NuNc z_uuZ{PKuu>`6{*<Ziq3-@$pCiV7GheO~at3>vSuJ^3S8MWJB2Y;Yi~Yb@LFwh49&u z6?sbimy`AF#y*)vMe*A=&D2ntz66dd8(bumaxIsDHqN(fY_cs}niwS>x4~~YD0x<A z8n;CJ-F@{D6C@D#UVI>x$KabRE?cllU-Paq-*q*U`^|#AmXd=AVNKA5!i_7p4`m$* zL7QP?fk+t&!)oleMF3q_XN!1y&9_%khLYTJ52eZkdN=e`<cX272rl}~w+eq2V2>Rs zIDClpfhqzVQj{wPIi~$l!e$n2VZ985b(p^#I|zLtcpP~91+iuicRkn;!)U@m9B%#` z67vdTAWo4`nSW6nmo_jebKfbIShgXaw)gxT-w=Tx#L94Tr{?^_zFc+q<Nich<LR{G zqtURy;<zc<kU3f77@mkDV_z<lC}mB9Xu*zB{)9fENQ~wqkVbhLPq|6zS!<1?9PwpU zn++!C1{Qo{VMp{&i>g>~%v}1xaIWOIqr}>zxpfF>dy)ZT6{QC-?%T9~Zu64g$}PeR zgKWPfpuG^AC~b>u(_KrIr1-zcZ_daVsbED;eS1E<y@J!laYZimA6%MF!{98eW34oz zjFSjnYWjo_dwNp~X&ZzW$a?xX?&~ia%=lJ>ME!=7Y`Kfyu~PsSaPNo9edS#r)eD+^ zJToAHB8{K6WdQ^nI{dR1Yc*$|O^etjrpH!dJba7AZfl6-CKV>f**?dzCA-Fr#IEbD zM#>+whlvkdK~ThFdp)+>qXJPf%``!tNJ;)?_Si6w;4Qd<Q^=Vb9*6gHsDE0MDxTQ% zUc0so#|HK{I+C>>;tN4s&?@Ec@8i4Er|;~j*H$gHJ~C#^d9_wQuzEA_absYNvu4Dz z*vpG1cRycQGQUs;GP{-Q<aV4ERyI+V6L}BH%ov01?++&X{e7WsrG;q?q>HE@JaA@x zr9OV)5uu7#MrPY_Yy8G-7qIBJ9AOZe{{0~RZLzk!N~=Gt$hm0AHvejWLy?c`MlzPK zq-u?@5X{>$`!usm<?9@0&%TFTGpNR?v~VLiZz5XSgPr@M20(9VeGj8IFH0E3yo9-s zGsJIb#9Fz;`l$t4{3P6;kGcL#Fl0`M0{ZxDSapddH4y&tEY;uN6)cZdmoav_|9GLy z5Xo_2Uu572A@{|oWBdNexzf$@vPp;}h7lMwlDKE+HIjEblOOO37U*v!2K64&A0cKq zfw@?@6J-1hA5!G}?|(yaTnYD)&*2}hSm-rWGTE<_@JVa4_V2~J(E-TO4{p9}&_)K~ z^gcet|1n<s_OZewaJW9k6)7R#5l93R8J4Lr3xNSo1#3zLJ~Il_5Q1^vWpPoYKm3ej zB)xwB=t?Exx|JGCifcSQEPQ}tPeB*dt3Ln<9pOec2ZWYxdiDN9U{G@l@GEB<l<fT5 zTP0?rnJ5!k)jF;4KZh(6Jjm7)1QrG#s(|zJ%ASeekQrRMr$UuX*jWXV?%PBlcwGFy z4@0i9A<e4<-SEQE*%E8z=pcfb=dmjhDdF87xFZnjiX+^2DsJ>GHoKU4<$r{T7Qq>i zU^F5q6JIP@{%BN&G+-5AmtcBq*$lJjjh9p{TCmz?jT2xL6(`ye`z`+`srI`HAM^>a zc?1SFSZ@j>xu8V#hH2*j{og+jIVGo&DW09Y`bK3BR)#>@ud1<z5-5#}Hw+5@<Q1kF ziHXxe+QB-moA>!1sP={mCLs9Q@Rtc{dxdQoJiqbTIf7+~VttoDzvKFWuwqeUaU-H} z{=5w@2+X(@PZplx^3G^|LRui<=8gKZNu6<I{z+WS$u{F7?2wcb?@LWrGv1J{X999r z2F#sO_x01oM<?NTEiEO#w2o(spW3oO{64eEMCi&^iIk!Gcmc(AuU(DGu{^a2Jgb30 zRL4)7a;!$(_5nPXm2II_;)~+R2l6P%SG3G~dvU8`St;{VsP6oNaeAZ?65`U)^#<#2 zck+8EIQV>^xRnZ$N-rzleDurgR`k5AAs-T^EwirEv|89W|6fl;rub2(Kx?T}k8hLT zQ&q5gsyZh!i?=9=meCB>VXZevBbGt<WaRxgsP-w6ld{T;GwU`!u4Pdoggh}E6cZ1f zKs<1I8}>7U_s%Uzf1$PuCQr{M9OFf7BpL!zzC`7_(Q?R_Y7*Tt^P?ouN{P2ywex>> zJ_4&o4Bi<sk-Y;Fo?ww7#031p_IN#|y5KT@v0vTLKEL3`M}(eQkI{&ho_Ae=5iKHa zO~Qpg8jSed$`2a!p!`>N^pXDVM&KKtE1IbWy$r#ULuJegwymz<zVjhOYx@>`TQ2{i zOwq-Bqg3L444oGb+r@6L)xQ2y2O8M1jX@nBUYGnh>wkcXD$_LlZJGCPBTgxOT!3&N zeQhiO{I}R(r!5zAwEyznhvy*?`Z6xUEFi%<W%ge0xo@g;8{xVgVwyxTu}@YSr`;uJ zZjaL*QSV+JZTY*H7|V4=cqSkg7v$jZM)c(3Dogg{Ux{!&rt)U<o>keZs>NdQ-hw|` zaX0UY^y6OA$1U~?%%)4ueL2`(2%pRGjHr#mHS~9?Ouy#!;yv$Cln_hetkgcDZ!+f1 zXWVsgRdoC7OLo8XYnmB!F%p41TI=qVEL0JieOL<a-j&gpa}iF~=RO*F-ThqL$!<Jx zGWOx$zz@Gi-##BHU+LcYy_E52Y0Q1;6`nu3RH(R*pzkt{S6qCkDE*8jxISXkvE95N zrW8e!dm}vY&SXN8xTcz%4+l+iD*O{;M>=0qty=f0FzojhoTZ;XJz4c~|1(?Ce~Wd_ z7&F>uSJcm+BOXX+e<rjrc<F9f9G%hWbXjCj<Xz6K0=F$90aNwdPUfO;1^!A_A7A(d z^mgsf67ZW6VI)pZt*&Uav`j!);4!UK!20Ln%^ryd)(uT}O9deIUaPX(C#u4A+FE(B z9@r@nq?TA&i+|h}r$+&w!rIGImK({pK3YeZ8{}+DS{nfLOQ3_<;`2e}48W`2=2?A8 z7jH!~Ynsi>eb0Br3<~Id@f7B4o8978=~H%`*fMckT?w&%lxF255sUb$pLs`2QZ`** zu&&fpn@bu5?o|aQm~<W{z!CAmKn*DFWC{@<GB1Vcrl^z;r7Y;&{tM&W9!h*&SV<g` zz0exSU2E5HCiN9*Kw;n#ywef3t{N~J`F>^j=?4Qp!?XaFW9p)5YL}SiAcZ-;G4Xs~ z>X!VK+t?n^yE_AE$-)A;iWtFLHSl<S!JjL5{tu->4Y8t9pm_gb13`6VRg%la=Jh@j zvyfhDzT(@|%c^>}WS~G^s)ur(fZ5e;Q6L_uF@oq!ml>rCUnW7!W(HadfcVv6p3S<- z=7x}>(WA}TUQ-a{&jri;NI%^SfqLWAe2q;Yj_I29Qy&aj$j__deKT$|QR(@AXKQ!Q zgKDdq__vy~n+AJ=)iyE4@Ou*k-IfIgwBwdi<y$3ZavTrPu0T#UemrHA6e1`I2F?fL z;MualUEOV7=Lbn3fM3u`bC8=~7S!tr|8d>U_4838E?KT=7-{%xeKvzrs5#!wk52>C z>nHByECBH9#nJ=kg;4?E=6=+4AQ8pbizrQd1~a@0LXQ|fiUr$+u@7oKlz-}ZlpGKL z$AEU~&~6t3p6j-~H-6~>DT?T4b(xErY9pj6{k$v<xBBcUoo%dmS>5YCB1wI%loamB zdT}>whSg}#h?M&ueIK7_Ec`+Y%VT3k;$yqtjd6iapoL1Oyz*2+rc`4ieQ%D?1@JUZ zpa+T$jOsfFY+ud6mnI0^f@P*76f2=XeEV?N(+NFhj!W|X{&a2d4JNy*@htXdrU+|f zzfW*_iBytA_SB#p@KMTG%Cq}0asDCSYgv{kqYF<hwTeu|)0MPW7e5%}cRdg>oW+`a zjC+H4rVJ$B-c~L}80k*;zc$QHmz~PlvQ*=7AzjdbDz(A;pl3O=_P<_Vl1sLGRA84+ zh`KJ8*W~NCW6GivByVi0=eTVY#xDg;hhG5MwFA9}aF)+U*%|HjHdY#*|9p}&+0ykv zg9h1FdDDFCp2t&DLKl8b1-^;?qd>GXKJR-oJuA%210r+x44P0s-rZNGgY)?Q9Z8vs zh*@BKq_i2ynW9yMk$&9wX<ps4L<QeaRsp~Km&1gMkIBw#bN3;e2Fgn3Ea*Q;m-HX1 z^s-wlj{)}f9Q(s?ld*S{mfPzFKDkD`lG<axr;wMf%&7rfdZYti*PsfT=dEkpn2W%= z!}a4gE|2~iTt10J0b*W9*IR+GuW&xWbUR}zyib3-9r*hfF81~|vmjun=l{mI*Wf7W z`sHoz8W}jiL`zok^hcj&nj3?EQq>ipvi&l`k-NE~#VCWQDL8qH-d;A_x5Afa%ws@{ zp~X-(SsY$Fq(!kyjWQ&Xa^&(cFlTB?_k^^N3Vn?+Qt6h0q!pYr>=?@s@3L<tPCq^@ zqv!kdVNbI8dDZ#!=v9eSZGc3_3=a@j$>GaEAIx8n*YzxMNc}AE2?JVeD?t;fDcb%8 zc}RRbdGDCvkHUyMFpNA?jBYv;2(kdQ$j;yB0cgm!W592Bj+?VpjK7B>e|+=pDaz)$ zLpBgBvQ1RFGp$qD@XG(AKK8!c3<st(I_B|rN`-we>lZAEG;RAzstUoD(Fd^=@EvBo zrrNpqW81qpWMVWANlR@rBM=#9Ie$3kTUx4IW!m#LW}CjuH24K^1H!r73xAag4;4o* znP$vUCSuDd!F;k;Pk^cR%A+6_%z&v!{>=)#BSgmAH|50N*lu|_nX3-MNzR3o<Yks! z9+q*_&m#PNrnqgsh&LJbYyN#q3-w+nw<xOjz@pdk8O}nrk5Vv($I|<@bqIAw4o%_r z9AQ3Nz73>cri(6VSrz5{Ev6=Bf!Y@PIrjeb^=533^{Ey8*5YNi)6eBM{7ExAS5hIp zYIL*DQ@H0)79)W^_lzbpb-y5o+{|JA&8X{j*Biw_<La7Jj>c6Oa!a`0xIZ~p91;BZ zZ?`u>I0tqmuSyZ5D{cs{&6L!PmFS4`_mTO{yzW80Auy7p(w14In;RS5(@<pWW1pFq zEZtT(FlxyGZAp!j&gJh*(4<W>#rh2Ru{}*UH+iOWylyB)hi6~dweRR(VG}nc!RVeO zH^uf;m1zI*Gd>k4?dxC%e0juwi{KU$b^C&VGjt()*b$Y7DhBzG&)`0pvexY3qr3%) z|0VW~{6pWr>+PK}k>ip{UB$o@ewDP~s<{>Ou=!>_eTit0|3g)QDDmf0gM}4^IXCs4 zTcg~}N2@?=){b;HUjA$B<K$G$$DZqSxL86>%2==I8dhl<A&hadW2upJg0yClo607# zq|9%Z`Ij3;?=3w{84m48L^#BIZH%YL*o(I$Azh7eR$KFx7@*^WJuQyo`E3}}+iT~! z6W%rEC50Y;>kqu^=HiqiF&ME^(QufaL-T0Q?dRYZ(Qg!8%HQwF)ddfYi*$QInjGTI z@njVL$BPW$rk1dfNMji$AjLk1FOxO;jGFdwI^%RZdvD1_i`tTU<fCvImSn7sNeD?Q z=%C?!ubKFdb{a{JR%Ojt8x?*{jm;r=U-1lPHaqqu=tFA7DpG31z8O$h3Y3lR48OC^ z-Ofz?mE^)?;dxS|(1pEq?$Z5a+)E!n>>~lYY+K0k-u-=SHHY!%czxK6Wm%$FpR$jS zXweRVLuYq>;@Cjs{(zI<W^PcgpA;0w*przUxGnoU{*WrE>-$a@QYYd$Dm|OYY*#VB zH%t{aw7fiebzFJAzKY)$J3i`sBONDa*=Q1L&TO5tCD1mXZqaQJl6|W~aYFkzf{AW} zbhScrI^ngc*Hdo10qG^M#A3L6#@F^-PohYi<L9*IH@q0yYSp7!(5LGwh%-#u^@G26 z(d$4Ho!#dXzr%hTow9O-_J?Q?NECp%c01LvJ=26X=*a(CiqdN_^QSaO8JV*0A1V=0 zpqrpo;R}nZ2$PtMOHh-`xJCWno$n=T?X~X7(LlGOIBFun()UsS1ir~Oab_j18^jVF zNhi=CeQ;Bl08e&o^3l`O1h~(r0e(h&<0R9kX%;1zp#-NJ23<a<wR!rn#+WOiYo<eo z;%Pz4d*3EZnVsQa&eSc@rB7YIO0Org=5qjdGe32U&X8V3K34S;e=9(ktJkXWd@>sI zAL$v)lQ@6Xk(1Y9j*%hjO!4MLPSqHpK`6jhCG`ayMY<ZtbrsLoCoA(EexeE=wPkGt z*k*g<#tvEN^l@ubtXu1>TU5dt6(`f~cb+<w!Ln`H5@mK-mm*_I|A#AofRjCjFZ<lC zzInSPFFHBP{7o;bzyhn>F;3LLpaKGzwsYLUxDMxVw~IRsRtGUV#wNw0t<?i1qdBrl zV)-(8rz>?$H+hX(<uRM`@QrK0l=v4i&w308su?WQ%X~(4{=h&%MSG%ptp)MoL*VfL zqv*Wf+4}o1eiA{Dkl0&d?_IlX5<%3cy=lzGsG_v!$|PoE&#G0lr8Qe^X@k@%ilX+{ z=%CeBw@#1ey3RjvemI}cdEf8*zF*RL7ZK|`y|rhfO^=Gynh1fB>uza)KHqo|l6+Ux zq0=<jP3HVLBw|K1PnjaFLK!s?uKjF=nn~sghHbF+1)i|sBl_^!HTeB4IKYNI(ifm( zppp8#XMk+F{sCl+SQG~(lc8nRd>Q)CTozvm0(y2A$}Z)J+J)X=BQ~q4=4KiQ3LH02 zYq6p0CHdXFmx}HSF)xaib{Cw&`0Iqhrw|4vCH_U$jK|>&_H`uwED|U~>brZwn3DSi zsFUb(q|#H7p~^A_Cuh2tZy><gCl^sT+cj>$I03XI&Qw@X_&X_NvI~0mBm8gP#gpW- zp5K|G)DuoGPN(v?fYnV4P<-W3<ZQ7D{VRf}lmGS_KcV5A2R0x_%#72h3ZN(s8Z1P7 zq#Oe|v?efwl2d02-q(kVe#;s#+vlaQ4w914C{%H%Msdz0bV^?yXO`Pg0yml$xJN7w zN#PDD<Dnq<1||6)>BCoDXp1iJYU^AXEPaDOXM){zz9TK3z$#IKfc}-NkYjbqIQKn& zi$0H`?+CV9aw0PEE`YteMwW;tI={4(&O^ngBYp8&$ablVE*GVPO(f8^qGd>zNyuhh z1Omi$ux^wgE9ryt`%)zLc7=BIgS6Nc4t;_1NyymON>b}QaR}b$Wm0AFC!V?=6`~wP zV5Jkz70?Yx(rrE-Q@UB=*z5Cg4t$aJuCBtoY7)V)%6<)~0qr?k0B*wDuMTNI@y`*8 zM<!vL^YB#`e2%;iUz&t-mDBG2kTYUZHMVjzhvB`b;wwbnvk2&!N$7Jnb&*w!$b(D8 z=PFs0)}5o9&cYTa;r9Xf%5JFx($LL}Az`5KBu#RJqs=Q`_0G+xeC>h|+N$XW((#;D z+$S5U_|r-86%u_B30-;TK|+5~mF~wRT`dIHd4V2#E@A^Ri5q!#4-u*#n83q3EhSM# zF%ir_I&YW&`nvzP0ItCT%6CL2hwORXGG|tl^M?44U1;_IiT!Rrv<sWnr!8UxI$1p4 zteOlLzVJxyP7+)rleWl`YbZ_;6LDz$8X^#S#aIGf_X7UPMX+vBpk@*pU@kDurm9NR z((U(am5=4VYf_&f!k4P`@`U}QkPb5Fx}xwpi9WS*Dg0khdADm7PllM^Mx7}avb>uG zueGtyKmGB!Q$#^M{nMrMZN@@a@GH+t9-6lkKMBNz+bV-0spumTQ$geQ>C%ckXCOcf zrXeD;L3AT=|Aq3!mv-btT|XNMZe!tLmCV5(WFf+Z?Vq|8e0s;XWjv(d8iTNhWWF<T z+}^Fw;00(+oWKIHX~RWmjmW>jf|>C9Nd!k<)(}>I8dZC;c6nWYoLs#+FL0xrXKA=Z zjR(M)(N*5ID`}>_g$nD<!iLH5x7h}I7Dz_B0~|zq^wJk%kkZGG{JW)Hoe?L~wjU-n zRX4|jywrfabpttfuAXpA;ypidX;fmJ8&CigE}PwsuRs=JK=I)cyWU=wV4e`nacph= zly8IAS>EwFovL`~t%W-!W|G{UT>{3!`XXZ8?8b{xmLgqM1!rM*&ESh{*e!rx;(Rup z%opL?q~Qf0TN8Q8f>l%tj<8^e8aE}A=$k{glnipM2<qc3YOhPj0FzI19=W8SYIQ#M zs6eN5UrGT#P*)&q%-f;<I~w_^)3g)mA#iP!T=r2)5-TA&JlkDCNK0BrrAKT1%oJ<8 zFS_szEz}nw{SzU<?oH5o9N!uwgH}vuBG=}Wid;{Z#9#jASO3(#dv#-9`3Vh4{Ecw; z@ZnZ%?F^QA560R`i4{Cl-ED7upP?|S4<BO-+(u+e`19pe^W?Djdx;Mk&&RZg2(Dsa zlP;Z?))Dh<4kJ%fm(cV%HXK?`tzliev6gc$wc5&|r||_X>ZjYC2O(9PQQc5$-3Le= ze}n$P^Q9rZo=YMN0*Of=qs=npy18(YTD>GF@Oh(?PzExN{Al~#p(pLPhc=uM!L}J% zk3VM}_9I6i4mi0KW5sqPQ8WEt*5z;u;rRur6*u-TcL{zg;Uo9?`RkhnzMm7ex?lJZ z={^D*+vTr|<93`ZqOkaD5d4=l+M1$8hbGl<u5OI-;D=D)`}{sar}J0^t<**PDJ_0r zjz!I3@zCQ0Hml+NGIZQ>N2402+o9C@x7*uE{*ASgW50WZ(H@ucB@fq>;Y@__gN&Lo z<OwRFo^6R(zd#Jga9A&wTF=AaBr>4Da+1X9Y~+Ob&}U1beN4VKt5S%P{zUQeXULtf z-N$Vy$CF!;F~P&qNWMG(;Dy)6OE)G+lWu%gY1S{7pvYuL6c$tz+WYp6$B(pEk9bcO z$($GHje9Vr4=?r@1vZ0=P2s~V*!Cp<A22Xn?eC}+eL3TKuV$(gy65o4>Z9+Uv$frq zTH%xt_%iEeH!)PG4-Q~vjt9<IzH7(Hj=ePFw7%Xi9d{ABKj|(Zk}Dg0Wo11jG|;eg z!{5FuS;lqz#d4fa&A8t!F~3@s6Y+evrlifk+yV0j;!__<QNoGGv;)o{2?)sAz;ziE z_x`TnC&wWGrSq}acvcv)l!<(Qllw53=e$<Ke!yKR%2jDlU~H=RO-jME7a{v0@|*=L ztD%u_-?8r`tfX1sYFyjHY`z<70=>lPv0Z_B7~uBPO!AXnnW6d9R`+t2L*w_+XVD30 zS3ecg*#_R(<16$oLiVE`xMc+#Ki;u;btT5PI{Ih3Wlrji8Q4av+4aq_DS?N4Z3x~r zdC4h}(vU8nDH*b#<Y_s{ZK}%A)be0QiEDrNkDR-XUWYsrqTCf)pXm7sGTt?I9hl$D z6#5c(J){H~qw0*v3)~vu{`BO?kH-9EQFcMo)eCfF{F#EAXs6?6$-Ym-c<eCT)7?08 zREBC_{zDncra;pz0fiOrGi1JdY=H+k4|@L!h(U_V-Fiuf&7bWik7vQ2wR8w?9;+Nh z4)&-&cbaj2KeGTwLKg+-yHLBoH*rm`{yUYrOspn2rcMM3I`yn(8}>dBlXF0e`dGya zW+CTcuES9>_<N$fcBYw6kN)jA%AC|e;szPmq_GTSN`>*8L1T0)cr)%WQukg@D@go^ z@Lt8*cHNP`GU;(<!wY=K^jpY=PgmK`_od6L3&5hAaP6wJvtk+LmQ{S^;&K=IF&FA4 zxw~@sfH;ABaU;D~%f2MUBwrfkI2le%#%Iw4Rf5lW{R<IMs`WwE##F7CFZ=N=!j>`F zD{T0R&X`Bwhr151Gza0MV`I-+{2r@5k(oOG!a-DqTkS_L(#f3V?pn39exct;g@q|- ztU4))y&E3toY=IUI~D$sj#O?1bu+fz{rHliA14JL2|&EPn6<kUHYnL<CxhNiuvP){ zOa!(Sq>H5?C;>2=s`~|&mw3w`U?Rh(`5s?tYi<>|*Sbl*`9>-xm{ou*x!3c=CDinL ziBB7@S-e)yb7om?*57$%WKw{_+K2I_BA4Q3>{g)N`X3fgy*>hu##*gJ@zpl)x*K{5 z`>)K#3ziwY^)<pWNQW&y>u9pmKRO^2^)_AZB2{_rn|2_pLe1{|Wr$@78e=+6eGpO3 zQkPWBe|G#PQAFWhVr$Tk=C!x{mp_F$%RRaW=-Yh_-<9rD4yi!04myDWtE8(1Lh<K# zpL|Bt;B^n`<ucz14hnRxy)%2p{~%7_s6=Gn!82=()zdcwCA2IbWRyxbfCRH%QRRsD z(#Y>te`o$%<*p%r6GDH}<^OO)zuK^Cg)eo6?`@98FnmslzC1y*nMc+ZtbSJaa}aoV z{9SyO_kT%udi#zFe-c0d!2Vi$xWhrxz8wNi?wVY;W+Elr@|8cKQCZ+^D=RLfqb<b+ zP)C*?;NLPbFt@`Nre8Uf8iY^Kc>w`HT;SBanfc3_VTNxzFxeh1Afc-;RJh%Z5F|Is zfOay>pqLsQ7^#yW85yENDO1c(NPa7->2XW;5q0)%i*|Qs*i>y-R>^Ho%3i>IaOSK| z(Bov#eAn&^Js_RNhu?82wGKC|vk{qx`95%)?sRJK8ebfU0$X$K#f*QAd@kG(zBISk z6%8zhT~SI5mo))e&Ya6yX<2G92Oi{n>3v_SA2bwmb-Hu-&RXb7clf{{{2nIeMaMOs z>K0i8(vo`C1Yv*Nsw;9E)O2m3y^Yf^6_2*+Mu=OdN1^i%viD@w;%+~J3SL*Z=}P(* z)4IA*R?`{=Jo2&6Oi#nyI1DqIiL(|wRKKpmuVkUAK`HfP<}`|nZsi_sN*%t56P$`d zf<R<^ekKa+QhnU^lMvY*z;FY9ch5W#qpam~i~A?u;Fj=^y-&?Bhu+{eFJ1K~835Tx zbwehbPLfW)*`|FpB*dP#ECTWiRzL0H0Iz))L?cx!ci(@K>0iDM2i~@4v{c4-^D$Wd zK_hg8<=%!vj%`D*s+i;LI4m63E!8OfuIaqGWlZzbYvUw8WMg~LgtgvbFNp-(+HjwZ z&)4_+67#knrJ>xShnYv>3C%^~=-r#x=6)yu@$cax=ZMn>au^fpb=Nge790HxzpXg` z*oWWls+>(o80L`!pkO}0F=``&5ep_Z)v~|<%%C_G>L&&w#@8GL%)V<%ao6SzGL&oR z`K^W{5VkW!IvnjbhKm;K%EjlSeS9bm5`kg&IfCYU<xg(=Z79Xm^chZ1qxBvZ62`oB z${j1>%=m_+M;&Eyj3-~d)K$bLohNLq_H3)<=%#*hGTV3%$y4H?o55jd%@D3jp9*;w zUWvQ7`M&Z@Y9uE&C}H6Fa|Xtyr7STa?@2}WSssk1mp?b^b#Zp2Z?&(~Zxi%BKpZ(# zi>4)#L{G@9x}sXesr2iYxfiW98>_{d>I`0sF|(NUO<t&cz)TTJIU-630Dk>EpET!x zE>a%Aq1J2UAvo`9Rpn{LRmR(^;<Xok*nAhl{L4X-!F*@chfYX+7Ym_KW!po%gHjk` z-lRSoaWBOYT80+1Pg$SB4`$C5a37PZE%Xi=mNYQR^h6n=Gha&qqwC5&CtntmjIZ@> zTL>;3xI1kdPsP<q^b&EJ-Ge!P^<Ys-Q;sxlD%*v=A)B0^6B818bsnge=&*kx+Z_zA zfg^w=b0?!7*N#NvIwut0c*<L^$KQ8Oscwlth2%n5zo0LV=%JtN4=7KYy*9_I2)2#l z5cPSCrr`vDG}@#5l2wDR=c}PXVF&qh;cPD8P<)`&xQ}g60Fk@%JVB%!D6HOb79gxI z_Y^0j8MUG_1(B;F5{Ar8mD5CU-xQ7mZca1L*0wd4eZovcJRoi$0twc$!gX0cMZ?5- zKCR;%Rr8ACw+&LW2!F);<$FNY(i8JM=4R{gc;iqjZLHJT)&i5|WUk`^ZSJwKrW<F- zAH@p@1F|#KX(vfhW~s-ljk@#LLJ72!GuuSac>~^Pvc6(9e^DgIK+qjC5c!V=JtW?K z(`#1f^bN>J=)VYoU)p#yQe%33*o|{s*-$B$NuU7xlbm#ya9{99iS<or{<FjAa{xvH z5%q>87E>*~Zx(8!^R~q%08j(3+rQ6UW0_h&1QHIwQQRSVz?Q3`?&nQhJC)gj;ShzV z8ZntoTEHYjtR#6rdXJj%DJe!*HsQp70jiJPA7owvV|fgZ9m?^^7jd3jYp{kvD{8{i zWmeSfOmFt_J9e+R<wy#?=$XQ{1S^V7@7RJZyQI5sx3;`UYyh>@;kwEiq!yrdT0J#6 zQG{=mH8%!tPIkyAX(pi?0%9EI-ms3}%{`hCu>2X5FP8pQOOZRtUR-H<GTq`O7}G<F zbXt-(i6I79@%7uufeST=!SxBUd326T+Wvos=^eu%wHQIP(&afQU>~+@ot^9s9Q4!P z8kPsZdFi@9byN~|SnIV0GGLf<5j?eSE%`9tNNhm(RdNxrrOoJ?rzhhqznIDB+Z+!o zD&jPGMyJ#z3+LKsq3|`QO1{r4@@~W-vap}Y16N$EvWN?nN~k<y4L6<w$KLED5V^9P zzfTIC{=&sJe01J}Wo4pxHDDx3F2Nv3%GnNyoj(R1%wGYoo%4pU#i=340u0_?hPfPh z@y}*<w*U~doN+%uAa6bbD*)EGL35tTzjWvm;-4c2r37vs{hofbnh4dwv@xqbGsK$J z$MP22^LHZb6+c|?#aH$@rw{K>%1qDWVJFq+(<{>|s)dK6n;yV#pRJQ9O~#|9tJD0y z*2=!x;zl=DcOK=#n>>oNH3Wkq7v?j1H<Ka0EgkS~!}*)_ZMH_OpK#92+Y`u?0!@Qv zdBeW@0}4C^CE25B8pkLOiEWElaC6VtJ)`nB>W1~%EPu-6{2*8=^I>(hOR=`p@biYd zm|s&u(ic!__%y<nx-mofWPI*O8uOS@t?y+}C&uArrcxX}FI_(deQgion=6`O>Qf`& zxyaBBq9`lB8s*d%F<bE2hL6paC2IrtEW>-{Ju|IkD>1w#5zst#?3riX$fTrhY|{aA z7;&b_O)1tO_e|n|%>LhSqS7G9G?L#AwL-A1d#ZZ%<oATW3C97Q2AZ179hUP-OxhvN zI^3Bx5P9RR<DpolHKqQu=jdMR=u8Pxq2Xt`dCN0|LhZHwZ*Stj3$Citykv0!4)T!S zh9^YWTmo)9Xn2YB0kUx$QG{1(@P|s=`g`vAKbo8&8G8JeF5+y8?lRbbpCAnZ#NeGm ze+}j1ZaM1PS>>kii)5)<36Y)mqQvf)G34jibX_a3$QS#knndJo;0f;+0#gsvR1)GI zwH<UkP7E7E-@!?uG*kMik-_-q<L%Bg1f9TzmR?V|ouuR;P-c9>Lh{Vp=uE_ot&h>I z{OYj~ut<CGzEcw;b~d)ELFOfi;jN*a_eFfpYTH+g^Is1ud{<s^g+U07yKE?Y9-5rr z7#PjWLNZeo8446=M+G$9=OJh+6Q^HXl$<$KU;vO2(hu9RcQY6)kQ9+3wg)JXd1paZ zqE<>5_R{}fWap!lE6kirU~;l_vi6wFZnjt(bPNY6a*?N$((U((7~OOS;%x^Xh*m50 z^_gC8AI9A8drEympvqpPgF+Tm1)-&qLAIELYD>ALJ8k8X^cy$)(c;pD@!i~xsQYgm zc$}nopYNLOh~&nSAV-3=(sxmdY&xzF{;}W)_P(`<VotS8tAD$uIS3eIrSXMY!1n!b zdW=5)6Ridyc<MeM-7~vZCRxc)&qw*Pvk8^}!h}My9OG}gF^pyT+&vc$)gaep$6=+2 zyZ}30bj-%6{Azq2_JtcY$<<2ctM<fCuxx!Tqg0U@hfHTyD!j}jFm2H>2E-e52eW+Z z;d{CyE}WTghnaw4SwDjWy;CQIQZ!>SwZARset3Z2TYtQA2CAnmqTiG4#p1R+&$q1J zwZ5nIx`Jj)V6<qYi=`F>E?UR>+z;BKI-EBb@?*xVb-E-II#P0CSUFWsJ6%HcT_4`M zsNEHz&Py8Rwj3~`ls=Y8VA{tt>qkocd)QUd)SJ#01I*ZV!osMZNX|amQrtmt9SlfG zK`^cSA!qUqOR5iNF{L_~Q5iN_t)S=eed1>6m)SOfJ)@^7SM{U~bEiQHsH=GZnK))y z>%$DG<V*Y_!36p<OEvI*4CgJXiX+W|4FQ<k9tWZjA*&*h`J2p0)`XUYT`N-8q{ONH z+tgpJ7%C9Wi6HAok{B0aT6qS_{z#?!Cew`xG}}^w(<h#rR02<y@jpXp$1SQ$+^_|N z9M7iD^xS;GG{<((y7=|Kh=}4jD&~3JUM}e-1|w6+U9hYNg17L4hAO32O069l`}(!} zET(Kc#Qj2^e5mbc29vf}$(W>8?8!#QL;JbNhZI57ePyL)t7oUohtu~)6Om8bI{VV& zY@j2~a&%^A0Q9mjlrU*^tdvfuraMb=AKT+n#q_QLj2>C;UOabP05raHgwcwlNIJrT zJM_!=qFCrv7%$LmRuy?@s)^@6N#2N3+W7LL7Af9SE;Za-e8mFS(!ZjxQt2*425#Hv z<5F6DQ+|A0Lyl}~?$_ZfR(E2_X~B}bXADOQE?5li=oh!Tq$9H7QkdIZd_l;EC!QKo z$oGaQn9}OXUt<&LEECG^L^g@?Nfdeuf81mi5xoZlB|^U&^Qk0L)plipCh=!C4b&=% zX{lEA%2mI!q1(&P2&EA2aoY0^s;0RB_r51a!4<QOWtWdZ`Q)I(zaE#6htk;!Eb;?V zQ(F8mcZg)Vsu+{B*B!gYc>dDyntOvtd2Tu}r>N<XmLz)TOLc53!~1;)gQOJ;+(cN& z%*Ev_haEaRz+*tyG@?A7f@-TWnBG%Ihm)BvAsN7q_`Z)U5&MughVLluSd+dwY)lr= z*HEQF^L*6LP@v){3Ib7Qa`gplotvM`OppRA6Tn2+jbeRdST^$=1W0r@En-c$S<Se% zLbRH|7tccgmr2GAQ-x1?|6B}S-}K122z@Y#;1KOfvY}D$56kkyM-Tdx*U~0Q1yZ%y zEuVQJn&4zd<BhHAXKW|geK97giy2R%8}HqrSDFL6X>%8xYU1J2<D#cDy+B!7StPxz z=(JP>BcybUr{E~bY2^3Aij8`F#@b``6_!I%MrI&Xhr!&Ad6-Uci0@?|xb+S8pcC;= zw1o`;qC~OF@zj;260*GlKs~eWP3&<u3WR!hDrNZ~Mz?7p9sFyWHh--ou_T`~W85?U z(#dzoe=h9fqEM)qVy?|lDba2i@E6L;PS1jF6sU}m(-M-?YPrZB7tMnJhV=j>Ah3K# z-3z6HDrUhM##8=VdQv)m+ohhdL~fjm^o}J*Va0ccR1?AK_6QZ(JI^c((EKCgTkOiy z>Xdy;$&tA~>;>+0+bT1yf{=N%C5M77|MT<DA|XtPv<7vWf!QFlo3A|p+WOLxGEa7Y z<quMo{S?3y+6F01dS4osQ?EvxLqBH#Tz|%)R;0Xj3X{B$DHBgWs!mmGrP*ykoXnKR zuHQ?2sFt<+fH_$eOL3$4q=l0BPD)NNb`^|*WqeWg^GSN8a^~b6?xPE7&-ANrjhffq ze>B?(J*_W|i=!B?mB&QgVv1g?<Swjo;)=|?A9Zt>%k7zqbxt!#=#HD)R4L4;3YI0g zAbBLMI9^RcRRM;Dium)1ZRRPxJx*al2nZ7pmM-y>nbXQ9r7-p8F%|018LTH~dnxJr z^JH^*A|V&*G^xG_0(0{WK3qAG0dSoWgPO!~nGui?!N>^hdF)<`TOr-r?64}7j+vy7 zyGuTM8gOun6-)Z(qW>!<8U-iYN%3S%pmJmyR^z(iC%Wl3`vMmx(_CG16lRzFRy4P} zx!aD>Jhn8CBtBXyy$=at7`sT@fAPHf*EPfJi23?0FTi!utnoh5*=Icn*j+7R_x9~6 z2hOqHj4+2%m@27lm-)P@?N9?T4GI+569`4^f|y`3yn2#wi3AKcF-a}T!)-}ulIpFx z(E8(MOd3VShb0chXxi8%bLkPmT0Ri;!7E&)A8Ue4{I)s~KfyF_OWjXk+Eq;=vY3OY zKn|Umci2<L>pDr2Hw2Yt@^Y-bP4EVe^G0W`WET~Ax6pyYz}XMS6BvHU!%P^%c<qj( zB_V5hI3cKl)Rg{r#I67@R7gMcKHUBg7mzA{f*D6r>}N^$X=kJEGKjVm)q9B-C3+q% zF<rK7Z-+9SV@5$(>2As$D{AI#cfchK%EL$6-pZ-wim(zV3ybT;&2N3?w`1CN*3nDS zwkJ9^8TwhwR{1|J!2re%^%<Q6^M~g>;6KBh0F0w1x!rxJcFCUN7Z+WgcXH)3CB>NW zW~!pC(w07Hw`@hX*K%H7rL`jkmFE0Ill*cDRufriZu`vZ5vWHA<uYDawVj-7pHHn! z@-+t8O?S#eJ3!7g5$aY5#ZSItBD^UsgXG>?9oAj#)+O5iQ=&WRr4yXAtsEaEy{Mg` z+#SbD%)?G5sUt0gej1N?M)3gs+1$OqW1+xqroI0A=U$Q&lH{9gd5D#8SF8M8CUolX zwez`rKPI5ZbGjaWnn7I6j?~wWnPd>wvNE{R6D4b0Wj=iI*Z)F$O?sW<-vpN+s^Yd> z-+hP2ROhTg(Ml6=y%#wRIk#qsQ?cbo)=7*CP{bGgk6tM}^6A|V7Z%fZg(W5qmo|N> zTxE$bon%cmhj3*$-)<W%&XD)tB?OtwnD0vMkF{B<Jmr5Qo0`WQT4IJzHRCW4ERm{6 z#M!md|G+-28-6MYDt(j9v~4dfs&)%R=`7B9OdlRgPAh798h`tgBgc?)YL8*3ZhrC@ zFG-(~O5kz-U04L|immo6E$y5~K@JhAr#~<Pg&6y9@0cu?3vGma`}$~UdEx6)?zg9m z*wX7(x6mfn(tgp*^b&cJFMTZCJNhL9%BZ$yc25tCym7mC`nBusp9{>R&zKmY-D1hB z>67BX?rH1eJG%kQE1xZ$a+ymB&@=u}D>jWwqsq(&th!4zRcHN)x%byt(lvd1^yaG+ zg`qUm5UO_iY8Bs)f456Bq>kH!0?9n1`%OF;_cZUOdKVw9)02}4^Ypm2v|h!tOv%>w zJZJPy@@*7#s(aIPQS>ugzM2c=XHe$K6CdihAG}W^<TyNbbKtH1!Slt!{*0fP=^X{b zjINT$E<>ari)WcXnJ$yx@PE4_D>6-)WK(rZR%y4QE+UR))^01mMSHV^hy?X_9Q1rp z8R<{XW<Zxxp+%`Z89yYf;<$u9P)!LCyjeH}y*>62NlS_B;O=D}K9OF1j)E||ZE2Ug zUGw5z?|#8Yhd;s@$wt0s&NMHiMG_g9rt;AFn=!*u(S(LPWhYZtcn9TH=#L{MyVCZX zY32m(Lj<lr8)>#p<v~!o-F&(I{_|fSH?O~cJ&by#`q8;S((UADGZocvp{{do9}}`I zPVk-Q;WJM=_|N&xNS1sO$w&4ngaUmyh!A*-7Ka8*p+ovJIDLTuhMo8*5k$0pk}H3d z3e!kX9?4fdZWuO&<H5>7@&H0D9VM#4+eQf3<A&i(AnP28wf;oa(S%2$8j5yTP<X1K zBDj_CR?&`yvd_ocE8k!=As#78en+*??#9S*Y+NMz1A$~u`jV?8E>x@p6!$v2W;JTH zYFp7*%}FVG^{!1Q>7XXnX{l4Eb5P&^Zsx+>;0ai}ziI3W5Ti7o5}@Qrmp=UViH^%n zTiuz;cVjs+ePeeGX#0<xQqH{^g|+G2or96P<F0dbyaIBh&%AzKWqpkY^9$E2_Flez z$u-vI9&FZ2`+S@>*84Wl{MIa!*hniw#I~5}zpSzpSU0<%o~B0DK~-=#2nV1U0Bk-~ z7gkdR4Cjf|J$*bEoVO1`76!mX5v*BG;eS~E6bhF};x2mFod@JXP-KpI&wBdU<6KmD zBf%K8Yrv!!u2J@Dk=C7_etsZy1WZnrZ<`fAC-!#(d3GL6_YQ*Se1TzClLrJ;1IMNa znw!ZYPR6qUMin=1RgkMPS^wP8Xg(P)g)3Z%@VBdpKZ}S>`7S)HWXlF%ru45=d!<P7 z0Wa$6{>9>ot2MJD6_t;JxdP%ANk-1PPZEt}ts_i$1C5{I?IwdfGVA4VeHS=Sbyr)s zr}JP}(^u`Tb$V~wtDg;1AcXGNu`Vls4g_)u(3&t-r@6Jy5n&<O()rv?%kAig`CSm8 zlRU!_IUdH$cL65jhopnF`ylcc{=~bWY4ypIieDZiduH>FCr{?QODdEHx^z8WHjAlb zOy=_*^36LtuTclHcKeVtW<2Y2W=x4vUz4Ucl2|ux6q>KGfQxMq5mY<%h!3bNFz|SD zO72z4WX#fqIVtqb3w4>AQ3%|;8Es;{Y;qa%tNrQHt}W{{)KhvnWR?8<SZTPtsA1X6 zK7esb^ta2nS)eWl!}Q6)vt3&Loux<H6}kv3DZ^~O>7vADC4^gn3scwZTmW*g-SQ<C z{^(B+|L*m4J?68n1$kpMgE!cW8}QNQaO3_UU#7i|p9HZb6$jCF3Ku&qf1q}y>CmjN ze&6nT{hTH#<qCWvxTM~$&S9}3HJ;r!<?U0(j24p%V7ihgVGUsl6?|@oUd4f(>ol|K z%j&vQI8x(T(^gBhy;gM{6Gr;+4tkr3#mA&;s)c~57fZe}5&7Q-6R#J09ZS%dW^$1m z<$~Xv`<<UignpJyPr*wKx~zRfMC7+IcmbOb=HrBtI)Pl=DM-pQ?7S`Op4@&IDqhB3 zRx^QzNI{<-FhpRLdCghPYh2bYvKvvP0U1Mx!oC?V3<m&``WzqL8yPRv-yp|8WOyw5 ziUgfapL~x+Cu5*J&;%&Z92=CohXOV_u)xfgE$qfsyWvpfRdoHikWj)rz|!|h!c(9S zAZS<7%JI4);!LTvdMrq_*J@L0w%cz`od?K6*Gn&>cnvJL8;kPlWprs}c0KEl;!CYh z{-@qAJ8Dp|ki97$NwoPLVKPD^<X@7bxW_@Kvl9t*qUv7=K%@K3$Q>Jt)VACLX#(p+ zXPYv~RmsOOzt8z)CQShe72llAJB+HQ^M2yPeo$?uxj@kS(jiPZLfBfmbyH!oA8r2B zTt}{o#*HR|5JDR?AhLsrMsrCWoO$}tV7?$9>x&=spU`C?K{Ry^+M@(I*Q;*Zs>Hk< zaZibU;kuFtKGeJ<K0DNLNcwRyUG8;tTTrsK%qStdw3c$H*%O`@F1(;+x}N>-P-vv% z7s6D~_q<7F1ZkPfqZSayeW(c}a@4=@<lvOiar<`X)P9Y>s)wF?3FBop=IIu68lp&^ z9t~-pxZ#-J%8l&M7CBV$K9+$9*M-pC%B~n~^W+;PJHvQ=gH43m$FDS_Ao^zMX5-s0 z9&19c>g)zv@`34S=+teQ5auf=n5Sy*fKsl$-+yEqlP<i`=MC&xKLp||sO?+T?vX3K z;(j_Ix=e|<?7D&M;Ot1!rer$`FX0>tKed)16*wNHSTTgi7gG{fFWAPS%o}a`gw8`L z9(EDWbK>dXCT|p{I`)&)8*sHmPN}u#Xs~^4Bv0e#=$r9;AsUS<b23lJwx+B$#DCIp z(p>ZjY^CeaiXo@uaSS3#s=n_^Q<CQRAE>dAq7&8S3%zf82`?_A8;5>*l{eT6>c@T& z4>lQ){>~)67-6A3m}uKD!YTlGkMP&<2X$-9&H=!<E(CE+hvWfOBm!&_dNh$_qn(WK zA+XSY50B`136L3qUu$P4ZFTnb4N7g7!R}9+@{NQC5O1>~GOGw)HBOu1hTCc9gmU@u zQSFg!`*xF)x*caueqs6tfJBzNxsxJk%Wu*)_?zQCgp=mV7H86W4$AscrXIo*)kB`{ zE4{QorP1J47Ih3Ybw|duvKr_pQsxa}9+GhLrp`n9<wvy4en)M)*QKT(_OK^J8Qy2W zv`&ZaQ4w*~8&AC;gOI#Wm^R6x8y?q{>n5iNV+2=aIf$2|A2cxFysKlGDt!69&7o2d zkWIxuLL<u#-82vkX}u@4=yE%yqhxtm8)6z^(s6S6T$XuLgh^ARY2EUREZv$rhM(N; zX==G`tr>GkZIih7mp%58Eei?J4~wSjEkDoZk=6V-uU`;m_yOeIA~d%x;nG^Fd0N;R z4uJTEq{gv8Vg#O@E#5TO_n+OlrsCz=GKTN`<o0Wv7dZBHui+!{+SIAy7hKoddc-$u zt~94_ocNh}WdI!3POc}820`^6X=dNzLP<WI<S|M$;l(Liv&LKo4U)@F(W}2Itzgn; zIw`Xo?T(ikA;!*)c8JA*b1rXW><qj6>}-(Z_cym}o;7RP?>aa9C-CzJy22IiQ#H2c z5t<7Uk-xf9zM`~f&@NLUI`$E|pnL+YbWA%p9{kQCLkt^2vkYm@=VJ31W6XhLE1yd? z|E1mIWs|LNU%dAfUJ3*waGAH(&|C#ss8@?zU(5xdK_c~o^5zc=EwP{E(e>K^@Y(12 z=e!#-JL|yi6T^nStiD|X)&y~|P^dr7{)GAa8S=;Bpb@^v&d8$T^(wcIogWT8<w+co zQooLygu*pP{3RxBO*q*k^_+V8f@jT(knRkRc&Y_qH33CWbm6T>bAraEuteTD9e*lb z*1j6PjmDo(<n*pd;=;=9U7lkx9J`qSGP`Q0rn2LY^@pECbL>;PC?Pn5jywgD&;|*< zbeF2cO6t>%lbr7Zm@j|(zKlo$0eN3RY;ifdSGV0xG9DkPfK9wcApeK;2)wRAOYG?v z<1Fm!xD4oaDFAfhMNc|F;U}<QX2a9_+N=LmO1{<0kPi4%(@PIij-RCW1Fx^1OdhBl zrzjj&L@(N&-WmKWSrS(5T?WffMGlzx_$s1hL4opm@7)H9)_$Nle4i)svc=fhQ`|_- zHwJxM3_?koz>QUB%%X-VkoLsq^j1s<0<!*R&0x;u$R94@IEbY^!IS}c6$27C0|~BS zB%#+t6n(4#%rk=%qUQgJ3D1xhBqa>#hTHsv>|mCZ{enKkpM0W!7dP8-P3J%yug7XG z<GT0;418ve3eye4<S%*3V~Oy;DsCPr)>?Gh%D9IO@!1r!q)N1QtXn9-(|iBnI1joW zS2ZtHg?S;igF7k9;|?OLxbf87$i6O{{~Uoo)RSQmNA-XY9RP$DpGYK@UM=iVz+(6U z<AScI(ETgX*4;|l(}HbCNNys|LYFSESZgObFaL7G4uj9Affz^NI~@CtvbhYY;p;EC zto~RF$8m)0hd0L{PWl{C4j_ntcsYxhMlGAB)jeb>VN2^IE+MVEhQ1|nOZg()syI^M z0zF6T7uWj|%Z`V9ud|tQmHSpN7vziXeMv~<GJc6OWx`59A*jWfgsTga-OnnyaTOp8 zD5$<Fk*he)S}zf+ls(YR7z9rrzs_EPsHSV7tq*tNv<qoQ$)o$IKwk}EW$WzfgS+}1 zxr&uBq!pon&92hEUG09>h3XjY88M-I2|t_!(I1rs0x;sq;XdVWI$5toV%Yp72!R9@ zcj5SlV8!-^#yv%>*%TL_xzC6GyS@Gj2a&<<ssPoSCj^&LA+ND}rBn<8w+A*lSYifX zOQ6<<`dmhk0R!j&IFAz_vfw1|W>-2AS5H%9(#*oFjU1Itww7>Y-+ipIiY~|Y7t&U@ z_KdGvbgl6E`-RCJ+t{#yzjz*O%*L!S&6FcN%HqRmRwiM_!hY2sPgvDs{)ZzgXn_HP zq8jQkHDH(EEvqgGX5;R!<pj!#8{!|vRGu~A?CXA49G1!x@P%N9<*_6Vcj7DWsy9`J zP~QZs(VRRECE&CRzc9##Y4-^?BP0svD|G4MD}AQI_>+I%;C5b3O)({()Jkd+IPY<^ zf8d~Is>~6brsTjZNCoTShxyEHy{0_Ngv5c=iVrIj)MxR6iq?~ZW~GDAl5LIRtYsvt zNXgdYRvXpy{xUgw{o3neCh)x2+I_?ju9nNhY?a5vub?V3Xa?P3Ug=_Zk^qz94!*|! z)*+{dcc&8$T`4US>|aLV&z_|ZCB4B8->9D6#s!csZ)sfn6-^~T&i9iyfxb2$DAue` z)RBT1BMUp@o#ziS6xic`Aa8uc_l<3)>Vtv@7v{wu2sRjs9`r0(OD+*EXkxpcq%HQV z==X_jDH%bn3#v7N?zw(rXv@TZOG*CmDb|NN!93u13Tbrw^vw6kw5#FXSL4$TjtSYB zrJ|WY)35zX&=I>_3DpqAd-ucc`C5k*av8)lpgiF%(r@m*<}RGxd0oaSN(-`gJZV>b zYicFSTo?~a#e4EIWcKJo=9;)LY^4`uM+e`L{q(W)2m8Hr_TVb~D;sA85;dbBt1&Qu zEI#9TarBk(D>WCN<~w2909$M5*putEoZ(zM`&Nb@;=1lGZY*Ku_+RRPHs73-@4Z^c zL>i=$H1Hx#<`ju`Qa5`4!K_Cz_9Z^#MfKOFlVM!z1|e-X%T(?^iyTw^9-ydtyM7Kg zi-qx8B$k;Oa}6)AC+@g;%QX&|!LA>&FR~!`uxlTe#@hItw3%#q$bPz<Slp9PS&_-< zmFFP$Fq^_0FEAkcb!}aGm%uKCB|f(d<T#R_!Z^U8OXaKjZ*j@XuLmi{DYtR5oaJn# ztiny+`>5$DL7?X&E9RPZ%niRau-_JS=0>qD%vPeQkD*Kdbu8<`x-Nk|@;#xySO>nV z>GX6g@F@zidS9ld^Y!$1oV3pi<;=7P_Byi(Tqbm$(>@=M$>TfI)JIAW>W@cC3p4Cb zRqq|4CG9XSYH;l@YBtJTT$S!RWdlh4_Tumr(4TnX#ZHN1o40XWI=$ad*(`hR|NA)7 z)mSDUr+5zkMwIaAJ9$K^kAc~RK|#BLu>p!4sY;4)u>PAKNd+y)bqf*bl~{=?F-cFz z<1OYkn2!asmlBlH-2v<O;v{Cgl;(FYZGX<oTkG73BXrvzjsqJP(khy_2n6NZx)Rko z{H?<MBA2Jl>cQx2E)!zOp9?RlUA~CXY*`WUVcqrL9|`Nk;SOsL#EGlvUfsAsc#WO^ z0N>oDS_O6yaAX6{L-Ggtqc;`aowoaPN+3tpT2vcH;_$4sDJmsSfiUO6Y&e2rBS}Gy zv0<>!`&be-H2j0Ap6jKvO4f04M}A0)cMXd_s<ubSJkNm`)I8CC2385cN*wr3d}R8K z`DCATtdCu@W7+@fam)Yp%)tBE)N)37l92jg@S!E&=wB;3sQ5bK;Fz`^dU(NJu>9NT z45Z55sB-I>B27V;?wot4z>s69#Bq{%h5P!#ibi(>13HHI!v%>pYaM@8@d|G~S|@Xk zD$tu45Jj~_+!q1sA9_GF8zxB+*&TNZdu|ij{szHOJ!AMrn8Wk2ZF_f=-~sl_pg-<5 z#4*!#$V0w6)Z&+YV)cF6%eVseX6J4gA;z;f^5ciQV2e0wN2#`~N9x(-GC0DitAQE& zGvBFlUvXToc}`7^#Wg=O+vAx#;>N^9e|O6{A<EU*Edem?<I}#y=W?95*uIUf#lm#U zR7OcAWJh}jdmgXw^-}{HFSYCx`tv<p9v|{;{>0L`VMRK889>PP2{?X*g%Ltd4?{NL zSjT474v^YWcXcIBxDq5)4<eAZo=j(G-P)C+ob&A-RVw^0yGzyUwmC@g7b*`&S3o}D z$76Eo?m9&-Cy)P7@A5c*JW{$SCTbx2*|YEq`RXbI_KNU1O&%{bVN>#eqZh4|IG%K} z$l{9LA2h`GqoI#nM)HuNzr)kzv2nX}4(FHAt|#Q80$wR}`=UatZU7snMBjI)2KX_# z<a_cs;&s*2pN~Vi&(k<qIl9u=X&X|MUC-&0C-(5`V7)CIYTghH;R<YurOs>1fv*q{ zleegl28dB#igk)>eHQ;|<m2R%#sfN5xQck|Hj_3z<ALeL*WqCU!54nXz<yl!&NRLD z;*7QFX+hb2{6JTb@7bs8J~YU=^Y>2v5G=}qT$y!QHKYf4;++p{iC{pubb0MIo4d!L z?02+&0Q-Qgf?Z}Gn9&i<;Ue8BHgO;cGDT7!O?7v_s>d0;3K<@qu#0<ZH~d*^tWTyM zR6Fp5kH?b0O15kL#4{arjKSG_;$|+HkKipwrZ*5|-?<HqCB2&3KXk3W(&~^Y##`El z%hZEQ)r;plPda+`gaw8cm-J1}FvUj=dQQX<Zl7$2Nv6u4=ruV%{sRtk`hD{2tuC1l z-v4lSPg??eY)k?DvX9_{r#~wlRKzr(yem)*NlOB|-|8Jzhm4bsvsVJ#KV~~UJ}Gw$ z^2b|i(5|VlTPMschIUF%>;8xk^4)j4<Y#79IHe0|Dss`Lamw-g>eGn_S`|))EZV&J zI(GWklKE<eCe;GPWth#k(9k2B_V*q&n!q$mR-*fzqZi#7daA^Mel&k>M30b@JXg-~ z^Mb%gzq#2X6JL5BU%Gzi0>G!u5rlPa{|<Qt#@w&4oUSO{x5H~%({J044XXt7tE~;U z%F&6!5G}{UEH+qcn5x^_uOe%qim=eBv}smevg>h$!+Xxy2^)9f%(bKcRxi2Tzc?^( zc=en8sVk|9t2i0ri$8@&!z(S&2<mSiuB_CKGhFmT6fTgc@qDxIq0=qZN#`RF8^$Lm z0LR1zn34_fv>5w!?~`{QOToTaoAk6=8)yZ36f-iFHE3615mfb&FlXBN4~1a|+<B}4 z@Tiazav-$G@dP*f#G_?^WQ!YKU8!QxUM>DD{lD+M=i(FBKce{4jPbHq2k0gv-Cx5v z*MJSl9llRO-pmr+q+eh8$d0ro;_c7FQDQoQ)%%LR_dl!8>ISxxw&lzX8{4nQnZ|ZS zv`gb-<`HvC#!j;LnihOcFGVEy-+KWByto@!By%rzr5nlr1dcHUmU~j(<!Id7S!nh@ zd446!MKgA>RNxOu=j+M*XWiIn&s?c4l6<3mGs$(+YfLr8^EyKq^QuVa1lWu_uh5Zg zEU;)y;A^bp8QIo-@KRG<7htQ8Dt7|OxC|<b5Osq(tca$^|0_FoNAU0;1P5XNS+k-Q zKs{CJ;E&qi112pr1!!{{wJrAmLTf!3G%P^I@@S7B3u2}rNBelV*!ln>)TYhh>y{$i z(M^M(BJ|>UW=CdId0P1->hrYHJFBRDRXNhJ8wU>4fLl=}%ozU;r-J-<4JAR~k#Vz? z2aydW#<2^h#;JEBb?;id*eiH2)hR=$j*?ZmQ65q2+9-CClM>OBKiScQ%H^MiDF)-m z?2i;%C8(&m*@D(Y{sFspPymPw$w#4aFIm(}f1212fH*GleSR<(tROc5QOj4PN#K$6 zK~W&^Pf|sTQ7v8K*Dg;`(DXJG7_6vL4q*5-05g6-2UVLlFJpf*OAz=lKY)@yjN>Tz zgIIK7W|}cnUkPmpQ}rXIyo75_6B%NGFQ3|%Tv_D0QB6D|Ty!fE^QGN2zw<XiCf>}o zQEIJJK-9$aKYW?yYB%4$a#4I5m+rlIeYCP^%m!pFZ0$j0SZ-`{pK8UkZ293SJNr!4 z@<cpkPzEsk3q72xx;X5fuYXtkh~}F!BbuHdEhgbgm=56tO;DrW4gfwe8?TTLZDkwG z9U=rW$GA~A+6CZXh&<?RXCR0~-fNL}0xLfa-uX2oCv}8~jbnp$(M;+u-Qnc}zdcbv z`o7C#?75?v5<sfJ=)3n+esjowc=4a=m@CXg&o!#^{by^KxvdbvG<d_EV?f+gqy(V) zeQVT3!0@$u{&d!sQk1cmg|YtQ=GURLn^KLXK7%#4t7qryPrX`<b8o3|k(W}dSl+ES zI#|$RQzi?pKHqOBvGZ9^BSFli&vtvWKG?TNZLn;$rq{FSgwu*oF+!eqy$r5uf7C2; z&A0*E;P()NsLCT{08%ZV&#Nru?vSP1|0dI^9C(tlhV?eTp#_bjuC}I0SmXZ;Laiw& z<ce${GN9zhE~awXm*G`@VI>_BI??zSu5B#@5nM!1;tBTOY45-0D!DD%1aPa9)-z2K zLCGCNZtbwX%srqw+S6X1$3Dd14G2h;oErH$%tihzS}#4b<>rOR7j$MSMe#(APaFx6 zSvZgw@?g#}>QW=~V=!O@g*W~%RI#@ETKr1)HPe6&={GNr%bedxyVjtDhym6}%N-M- z7Ro*%o~bQ6j!Cmq4?*VoyjL6@E{`Y#9R@rQz}c|lpHadFSJpOyrR(_}6NWTtg)OL} ztrF~XG4w^t<SEP1k!6_SK+Oz7(d^)}V~2AIbdk^46uz;#bDaTiW&0n{q5nHV<(vVb z1dh*ua}M^^1`uw=IDG=_4A>GFo={$_$E*IaE;#=3q^F@TL)&(WTdRkHI2AS`-TPgC z5M7|`yP<?{Y7=`eS1;S9ZflMkkghVwS3Y%2!TGSES}YN4&e0f-J@&dHmSpYnGjxJP z9LaI1$CBz?MYY?M8m=VYkX}I@%#DM_w189Y$eGZuIEG_*F+EqMjbRUR>AAUo0ZF`V z=x;B+?!<(t>*+YI1co%ZFj0lr?SKut3zJ+|4t6=P>u*A&9u@_l&!!)&eGwiWh|3{p z0T5%u4;E5KZS8|!`c~8f+vrD3g^Aue_FglfhVROwb!2-oBUsY*+Lh)*xo_L}n^5`J zD?4YDdFjl!Tk%ixipI<X7Br5-4If7=D<XP<ndpG$IUdU+((0BAqz^+!am;DyMITX6 z(OFMBG(@f?`FiqRQyVljsu@5vU|phEoznC&pM~mE51B;^+Z;x`)-cJw9d#1}QnXiR z2E%dp1?pScki~J%Y}@<Pd2%2BcP35$H|Jrm3f9|k$IkJ*-mOa3K0VZ*TT?ceTMMFi zSIbry&-Oz6e0f%@ha~TP;Wtt@&{K``-qs+~KrnjV_`rzv^3>dm9J@b!7p=K5Mzvh* zSNgn9Cp3Je-Qs6_4f%_`xnt4(Xm~u{nsupp*htwB862YgsHY3%ck4;MwEOk)x<wi} zNs))k6be91m}w3Pb9@TYQ``#}`~3FWc!Rcq<1d?CZc1tcd$V`Ar;zx&%p#Fouvi@i zA`+C%=PlZRvZq3M;h*J&oW>^m5Jd)-U+oCn5J$)HG_+WM$7h2Q<*a}*XSz}4_i@lA z#K?1<9n?yluH8+yS3GL&Smt4aW5u>#g0N(*LqNTf`2BqXui@Dn*E2iKOXG@-<el0> znf0?}@@?F?w-j5E#r48G6uMnchF*T*yt22|NoQ6#Ycv&NZRl_?-&(cAABgM#`6M=x zeSEx)8Q@-utB3b9G^9mqJQu7L{LbB?{<)_t+Onmgj^<TOTo-PJe!GZcMoB-jTU9Wx z!YZCU5wvVt=DYprG>Fw(@)qy*3VOn#y{2KI)ltoLy{z?wdkk}DFpPWqgyFF{)mWcU z*()TvY0!vll}*KsKNZ$GkB(q&f!nv@uNfM0kb>6C0jY-<w)IMCV$Gv@LetLvczC1T z>q_e)>Lw3x=u8N1F^_Y5|58n^;d`{oSEmdsZNmP&iC}!%<x5pRw|K3T)#9JtH-c&| zR*D+u`X(jZ_2E6tvbX(^r(^p_c?p7vx;RAFLT!s)lYDaVNNw_!;YLHV)fDW8Q+~#w z<7J(XMvn=6-o$`^ykFvCYYBt|#2X)WvB*lWXIUj_^NzmlM^2cKH{q*RicMPY26bMy z=In^KphyQiAp3$$(}N~7mS*Ir))-K|RR0>?gO(WXlWuw@wU=A^((#wNZOSpll=9O* z{Z6$QL&Xt#vna6GXPTBQ=#^OuYW4Lg$LQz${qT9fE<sV?NP2*=8ctA9@d%q2ugAn( z;mz1mFyw9j%J(f70HAPwpVOPIsMGTyK7@U6C+QC7n6BD)IPmMbhy_}x2NR4zL&9;Y z%qy=QHzrn@tG73P-p0@6Zl|=?_QG(Xoz&m;5yP1~O5IoPv&I_Qcfzc2BmC6kuQ3m% z-!$TC!b;!nOx{N2gMim4QQ$@>Y|FvtCaN-6rW!4Ax26PEt0X`9aq!qLRRnMet$Zn0 z`LlzX3$=xyXpd9ZKdbl55dB{Ww<3Y1Jg-{0^F--w?dQ=9O<8&d{|2<Mi8np3tsz`T zJDZ0@)Syqb=eDj{IO|0TNr2e@5pcq)!NRw9;Wx<#&1bb1=q>_v@5t`%YikvkHdxEX z&m;Ylgpd^!^_P{RWz)v>VY-Ou{)W*3mcps_&)3Pqu{(d}^-M2>%I>t9AQT^X44`Ur zT#u;2Ti2ze-Ig*Z90XmWR2d?wu1aM4M;3X_i!CVfgs6Zb*YS|#MgBMcqv$-`l6>Dj z{D6okqTt2}h<lIR8sNwsj?9sYGgs!yOsxP>afYVms&G`U%Du93r#W(ER$6LiYF65` ze&6!t{TH6+IPT-Vuj}(U&pK{G*n8F61*+3PRg|)?J!yuY4*O9*z(>zu7AVy#$bB79 zdlSm7?s!vIop<;>Z+<g|Qj3A|;j(Yx6H!`&^_YhJ$DUtL=&m99*it?tieYrc;J_2! zu@w73uHyS;4S{<J>oQ$<N5%vmN!kv?%9IbhsKb%L);r&uQ=cB!Z>CAHKNeuX)K?!+ zi)WAcjTejP0Vx3jp#iVP98%hAa0oEE5G!L3lGMDlY;sH9q@XM8&}ok(#F4h+*S7G# z97L__FvDNVZL9t3SgLPAB~K!Wd^qKd!HiA{@8LF@=F*A*x1MTM%DJj`NeE}ciOphQ z!co?RbMg!0s<2&w&!lt9w~;1O6=GOhdaaOpfSPEAhzU(d6*S@*zdyDwk9_vrnT{_% z9>~9Lzw=RkW3p>qN9ZotG20>d(QzmH_2N=ht^1R5ZA}Fh<2pV0Mt(v1o<q(MoNB^m zn8--j4Yl58qEztqE$}#|7lAGzN(T}}<_5$~gd+)U8Y(Q2qx7=XZ}N`zVkX*Am_YS- zl2Gux>L04#y?Oad99x$V?(3$f?1p^87^ZR^JUU}^?Qp@~pkD<;;-OMo^Idswtnzw( z$w;1;_haD$nSQNx7->G>--M8AfRyNMVf_H1F{npG`w_c<^RS@<U^UIQ+8m4H@^ue{ z9+%MP5_#_+oSBdB-q?y;ztx{9F<K@0Zx#>HU*c=WH{=+SKq7HLWRd!9Z5px*TTsV0 z`SXhDCScsa(UcG2uwe9!s?SDPX~zW&`MZ3Y0Pa$ixxL$m=tlFE?8l+%=3MgUZ3a$I z_7y|9zXF((iMKG0InP1`anO8xMuIhLO1_*9vA{?fFznh+sQsyugD6030bCSCC1Vv< zxT^d_K}m6ncRZ`#m1p(UZA_mX=l38Q4haE{Fd;=+HGmO&AEEwD-r3T2f9Lzb=LO8y z?{vN?`F|p0Q%f~(KFxDD83P)+T2ZbePz%1GwG#aF1{RUL=8B;I<t&&9C8<B3xk)KV zwiBhcu1Mhu0R+<V&0b>(O-ig;G8H~;;<}PMUdjr`NB!`K*HnlL6n!#_Sr##X)A?Mc z@8$mx0}+n7J;B)IRGNWR%?IO8)v9aWA@K!rvu{cNBgVErkE#!po%<=b1X|}OL5D@- zGpP1DpAB0QeXGcog9!v7kkHn1zj=(XItQam^Y=^lhp+R&Ne6pFs_r<^M)1~Ri>1CL z`Qom7BMHMd?l`k?)SRJZc$kQ-cv_dAtIgAjVuW@}x>{DHeX3gvx_3pjazIjDN2+Ko z0ua?li{Y*2RGsHkDeD$-r=#M&*dVGQLkpNNw}|uKH52wvGD0#e0(rYivWf@;^jUdt z3bzFTy0j)YEtcAdliRD33!}vGb8dcjPKolrGb1^0eU4b$^i3H?303)thWhas3fY4z zJV%@!vj)juW3f=crd4%!tkhNCdjH!Zzi3H0ND7&C!j5aH+BxWp5Uw^l)OA4M(X`x$ zvjPz+0t$sG4IphV8ZsGl2!yjXoRh0TGDZQC-ajOi!PYr;=UYg}vDN&=-)&hQ+C^fx zPTphjqzm<8xL1ciRD<{An_tBBcfy8FX4eOL*K*j;RPNyZxKx7utrL;^Hj3LBcwNM~ z+F6Vc2=%!O{`I_L8iVhgAWnZk%aJa+!j+$~D9>Md!K_-QgHBUuQEhIJ>aP+V#Y(nf z1=>grfUe+CQW_7p2}bXMu8~{8J7j_4>*gBq!ZnhL+f*GGoj<^;tvX>&x{|yozZI|1 zI4H*E#U&isuM13S+dld;<Zak2-uu{nzpwIO2PK0$nAFwCmL#q>=d-UEXI&FU!>e<! zgE#-xt9<gv<>AL|hMeOEqmTpe?iRRo)g=%x7+g>?o^iCV`A8S;cav4X`3cKrEmmVy zxDipJ`cSc;i_~E8%jM;>i)N(;?LkroXe3DaoI;^#s=TGzyedI|c{o7G|M?fml1Hti zD^6e=H{Fu9bw<MdiiTDs>$&`ALd)$Q-iu|5jq57zr+Es{Wp4*OwJ@-7V5qje^+r!t zaIg(P;17P5&4-&$1`A#)7laTidR_|caiefoOtXqrSD#{lCA?7>)d8h8vu7FRp#-fb zyLGW@X~H`~^fp1Y8G!=CEZ!(w;9u|&s-@{D4TTm7$%!thvp0&ljlQIQ^wtO65s)-L zQ6?2jKFU3vi_JXQgHJptMhtQh$1KF8a6h>!0$ccg-SV`<Y2Ehl`?GW5+7hM~7??SH zj>#2?x(U`cvbuHU!uNk5aRY)nKR8-t0>j#}UhcxAqN~;i5$n|cJ%Yd<0SOs^m-O@X z0w@SgQjQN-*o%p{gAaX)8QhbHiQ%eEEVdn$7}zT|3R4i?K>5WK9Ctw+NV*e5H?O`C zKY085l_nWuDZX-K?ygq2yyzxXYIlx`FLa5<B5tf<+aFk-tCk-oqWY`IDV?S6#`ycB z<B0qCR3jxu60_Jx$v*lLc0Iz<*(TcdtOo=qnWy5pszL|(IJ|DZb4zj%2h-t?k77l3 zEy_y-D|ast$e9Ak5BR!!y4u>hV+AW$BnA=U=FeW@$qFqF>-xe5N?V6*i>D;i+S8=w zCU)LD=!*wGoT~U6O+#XI1-L}Cd8@=Q5{*#pa0u8$y9(Vr)Oart-At2U21w;sS-7Cb zg%_KzJd2EuwmEb9UMc6l5ii`2=f0&INqmAgdA+KfuQF)hJ?1g&Bn2#rts@<vl-_lK zFj9}35zf}!!3h9FWJD@&F90wfoQdPMZ3v9LoI3Dv88e5%DVBrvYVfW_TV_L&rHV3+ z1Cw?12jeME<wd2~Y2w`jjBkRLAh!6u$XBd}2Ry8h3R+qU$h2<?@vBY}_EK_rxkzVF zg71_B`Dwn#OOYQ7=grqeKlAr`#h3igu*a_YUUtQ>pKU+su-7Z(foil6uH6t4+%MC6 zZnofpci}1*#(eH<KM!YOIQc{M5nH*R%C9cn&f$9`wDXk!-JjlbC~AbCKau(3$JQh$ z_VfcX)^6JOWO&tBJ-yiu{Mrd;eh?O6cAF7t-uQ&!*xjqiOP7;R_}}ycts@?3)+K-M z!2!3D)1)6_e)aC3DuOEzpE2u`2%Kc)8d{kyZ{sEXUvJl?ZHath^JOu$qyX_Gkj2`! z4LHdrU_f*k#()L&%zqc+CskmoJ)EN*XO}#AXbTP><zu99>(%^Y1R`C(+^+iU<RDKR z5EI-#l+%NG)b+NYOyE>6H-!L=?uRD!^X$r$9z7&!g#Pb7o!fJXD)5=IepCkehfO%> zugQCz^kWL&SBDvNIiC<Xc6abOw)zTUy|-<!p&lF<dl%haB^_6V9ZmUP9qws|*{e6E z2|e;iWO`psl~nZYrPi7T$-=8JknxQw2hFZOt0*9KZP9REy!poI2Y&9o5Ao3BVS*)Z z%=XeY+igz&Hak}>i6wdcZotzAqrozmPCx<%z^N+04J3rcVCSW)X{vkMwp5SgNa#f@ zkG0f1xq>kq<YGq-@rh{%&j8IsPmuEb;y8R=I-3Ac08V{LTj08?Ly70hw9|qvW|#Gy z`#iHKx6^ML^~QDVJtuepVW`>=_(|(SU-)^@YI;GFO%O1Xn9v#HZJR#})V;$``*g4t zRRdp7Ts!NR^SnC%H+<L2`pnDZsqhlV*KZ#@#~teob@FK-EZ?x6-b%#k`fsz*_8&e< z5JM*N(LNeYKYVg1=7X)htep`T&d6^|pFBTLbJEhZ*Wa5V5X62h_i$02EAvmON>=tD z$B`IOyVMxduN}X>tPbV;%K!4V2Z;x2AryI@L_Ak9e^IM;&Qt|gd?A*LM}S<FzzG=2 zB&~u7a!(NYFd$u;4g-c!8!+nu(BA84m-imCD(?!cSeg$?J6yCyc)!i+LRv<|fa|D* zz#O;>SHHi+ku*n>k>Nt;L%k^qSK$#0*9CEZiIBD_jd=XGNrPAF8=hKMD0A|_bFz&> z$f9kilWKhMqFAoFW;+g;X4Jq;#!3^*b)VENmS^FUt;Dn*P!Gh^ff*?EOyjZ*@+_CH zEebD!${fR{_l=B_0@X!ih(A$Q{=#B+t;jI7%5Q=eGKo9eci7R4<45;6AyK$SomH9u zK)L2pD{>KJQxnyXDngzZu4<$vX`f$}g=y+DW09I0V+_f2g;<qZ^6;8<a^R18uh>T! z)z%bOE5woW8tx&*64tl#j4Bzz_$14~w2*=&LfKQo2ahyQ-7d%+{OXFI%FEy%Hp16( zG3X#CwV4?s)}by;>YHL#EcDw10q1A+fz)!L_5-04wa}DNyZV!tUG9$OB|0F2m8;=G zBI-a&jJ{2cKd`suqu)OR2IQ1y1@Bb--2L`!^}QZaO1zmWgwQwBCtE^PYF#Enx?4ts zy6?3>rGW!0@&pebyuVrTT9b<+R`5G-^wiGJs54@A4h0&LS+`If3If5ox&Wqfwp26J z$K?^^;)Ivs2)~|y?s|RB`*jbY;THx|-vhO-=DGdkEJbS9mxA7UygM5_Wj1K9>&1a` zmQFXP2OgQ(2+Z?NlHU!D99Vcn9+o*ViMoN!E5rhiLhwHcnTjT4S2e*UX=1c`f(`oj z$f>u7gn1PHEoYrNJh)Fd|K;y5@hQD$H?3>*XDsg-e1Z@cKo}N*!dT-LGZJZ02BNxA zJknsgKB`shx6_zrl};`j3^Z*Ce}SzVbUoY*z_`qJs27^h&4%QuKFk5-IPsy{G~qd9 zW`O2gcYbZ8mL%R*w_As2>PWp03pFX-TX6s41x-n>2%F91ma=TCA@nmKFk8R?5fc?C zIcenSz0@w5-UG!ayh>k&R+|F-XXKk>I5WblS$s}|o|44;W7EyZ?G=az4+s!Z9?=IN zAixka_S1lBy7zKFzv?N^ole>f(b@=%@g9g+NKiTATB``onig-Ta!IpLmvav3Y4>jE zu}otS@`7OM5@5?|ujXM+OO1@G&fUrO<UTI2%Us?WLkZt{ADuKY1{qI4Q4zsDoe)Rs zrh%FSYMQWVgblCGoOrgUidL?VI6&U2Ide);Podpa3s%5Cw>=U6_Njwz^+N7gsepXF zgG_en8vI-oNpelXHX^@;KmG1#qG-T-&)Wx8IWr_Reh6?wtefQurWA3_BE~eWc<pof zfqdlaasBniCND^`b{kAmsklJw{|8S-Pt1}sp5!O%n<f9p1B6lQ-N)JH7O+8--!1O{ z_1!P<*&9U5+M(>D&tUD)%zaGzIL)^Ds`ISXOCZLe9=Q?N1BV|D_tl7fIrxNIS@(dd z1eQi`fTh!QHnqj+q#S&FESHzKK|2kvP)sgej1k{%)vviYqHy=xw)OV<I!*@_j80NG zZ4!rq$HIohqk1ZY(?Q1p0{MnSJ?@wvv7$a|_&kJH)<z_vpmw7@WOCcz`YAc%8i<h0 zYJiD|&Dq=nQMuJ(YHW`_eYKc@m-|h9a<rXNSOJ>L)4`5~)f=+ZqiAqa|A0^fGD9zy z#y|7X_G_P8R+Y{B^IYMJpuZOi+%G{|;Ps0HM||#sTh{U|kbZT;ukJC#BT`#S4Bxup z0gmpq%>N;iQa7Hb*m558u<iwSTkud=s@mg3R^$=Jp%GGIA8~(TCQ`>9n;&$5I~%^O z8L)O?sg?S)<sYOjBXM4esKFo)aRHnsqD^jCC(dlZ&Uz-SAmad&5|?l{_jDg>Y0#q+ zZo+F#)rK5!GR4r@K`{mef>p=zbBaoZ6MKFC^R2BC^<u^1f>CS_D=#TOW`<sg(#7Np z*i-xVHd_}^FmH%P<C<;Kh*aT}<8z!r1JA%yojg>=hej!eqb~kMPD^W-&+Mv=q-zU8 z^#s>7S9AS`-}@~Avv+j$h*@=|B#qD*u*~=#_nVnkZN4kq51Q-8L^bG2=CQwVlF%D_ zVu8xgTa!4%$g9vNtiUYqjpRiT&<HDhbqFV18|^RAi2|{%od2)Jr%rO)o{EGVoD$@F zFhUZmq(G!$SQEoCQ6Mz?aUL*%6Rd7kGzTlMScwDkQ?M_!>Cf(aGA2c^Ic2<aE1wdz zuF+EB^@g$ePIYO=ATQZnpFf_EdNoseP2Nhm54%SQT1TyDfA74lgShOHie3!EK2mtd zI?|P8e;3FM-}`x+_l5HV30ha+-O}RJ#NabtvM{!K0*d4td<SUWRY=j*&(6gvu^-z0 z4_JLi^W=l7%}g5sGuJ7m4?CK#KRLQoaO2ZB1=9o`L{UgcCCo6dGZQ2bMM7#%W{<yy z628HzUzTWG!<2oujaPAX&mkXP!??dx0$hzFbUq5aktj2?DVkl#Q4g95UVm+^?1zfx zUDkf1Y@;dgOH6`8ppJgj_pUOWCyHRQN^|B8(3eMNS3Fu@fmx~UnOiMj{Q4SZZ8T5) zq9ormbEaSJvbhKAO3cYL)bqDZM|#&Ozb!H*U&@!N<aeor$jCc&`&quRWi?94$o@_0 z{kb3Z?(;i&Ir{@DU+4KpvSBO9y?I1_zCu*Ho}m21#UuO5U;^Oz`)RjMmvwiO(xuRl z1!+(cS3wGV&0eM@R8&M!szn2!IIwi&MQE0rBBVZuQ2Dj9&}&+YR7-#@(T8#5YT-nL z5%c=++IY)5AGD@fh(j7ift5&!j5`UlQGDEvTRxZ4X-T#JA-0%~k}iyp&Oq^`lLLj% zkI(8}3wEpMK*5MI-H99+DG1tf(LL$dilN}B4Uaegbf%wE34v&1<;d(yq*cgIl!^~k z4zh0>+@2^taKx?!^R)}9AkS-=gmS66JOz#yi?vTNL>}Nn;aH|=80s-Q?Orf09P0OG zfZ7d_V9h$r0FJ;fNhp^;h5K|H!Cy-sd0bawCBc#_AXelgqDq_R^(z0-1XQwo+J*P< z&_Vt+f-{7cmT^R^+ZN?&Wi5x*xYem77E4I2!(K<G+83b4V!ev3koLC7@nT^(P40Oc zvfBW1*lUAA5tToa)0dabS58J9_QMqmygvxr5|J6lwYikFxj4-SFKup5?R4EXBt;t< z)s1YmLA@;zQOH0637K#m_di`oo_3}4hR9|NoUaGj2~dMJWzM!*rGG&2)}d}cp^67c zydn!!5Cm2zry-}a_C@I_v+!|ko-Ts19^JC9i2qCsJpKe_elKjEjHo`1;4vWHH%!~W z3*4SLIj~3JkB{p*V9Dw-e<p}}w-8Qw*mKth+}zV?fJ#FG$OhNQ;sv_n2Wp}LZq6l% zGu?q-ZBdAV$R%5_R5SnKOv1`i$<4qZ0Aq1T7T6+Qvb}oFjt$Y%=F-vTa+|R@3^GQ} zqDsQA9hKNW1JTJ`w@DS#NtJLtFCH7=yBQ*|!Rk98ygY#m+fNoDh6h$BNem<{laTx{ z&Dmze7KaHqgV)E!$Q95e55$-EV2l}rG}H2YK}_B%Lgd)VhiJr+3ur0E$yR-&093LE z!?#Yz0Vr{q2ikqe>*w%dC#;y1lH>o*qmFhXyIpc60*bk4#au10*lWsvZIR@km!|84 zDSO<{GEpz|kY{W4Po8&C>lXm}U7~w#-Utl(yC-0|2NI>p=<R`(kzDowHy=@E&H#C& z0OkKOmy3om{&7SK#48_vxgb5HMw`VotHk4l+Jy>%OLMHt%6^6#9-;@zvUtk5ZBWrV z<+W(~6cUkgOMVO}d_&8kj2NfH!WjVY@4d0mHN+JFD4WIUdu0zA`^gfW*D#0-mUD+; zz%$<KP3<|dwBw%pIalpab<Nk8?cA@E4Sd~;3jtn6oVr4rNM<WWVUefw9FNkbnT(6M zvk|hVGZMgX#WNs7qc`cVutQ=#hXB<29Wo|?OPLBjWr%!mM7W@uTdysHD;Ao;3;gcR z{hw{17z&%y3_J8ByZ0cU&Q(dqvMwEDdJKz-Vws|PI#?pE(&MaZFY4X<>M9j^v=w5u z`Rpq;>`>A1>`&C?79;2ftqUN9nluD;w6Kf9GfoLR)D2HI_zinb#kCDr-><D^bntHV zS1SFgWQyVda<#}>3Oberyf<~-wo4Pbp>P#uV;ktBa;Mn+&WeqjY6(h@C?_^>hYN)= zHLQceT{G<Y#0mMk0bF?|TnjuvQLB&WKKol3s;n0|QE)@d1U8xmbNA3SIEDhdM@!M8 z<s$6ivuU7GR1-w$^>ay%=JEQ4lcH6P0f7!0ffq>Li1(Naoxhz%o}#=4{WCMd9%Wm; zB4~kbBVMg)-PA*nb>ZR*Xb~Q(2{J-3^Q!1T^_z2z&u92XsQjI7rW+<o-SUQN*NU1< z%1$YkiM!mEa=9!Xd*kW+QG<?Dky+*7Ow=LZgKBCO(x!Tgv*D2!nwe6v?{x&^2;j|c zU}!ejs_UF|RR%zg+}S2i&64*s<HdAZol#z)ZYU`?77%m(KKuNAY@-<JI+_+2)`>D| zq)M-eUE?t^jB{S!YwTL^C<M_iyIH!Vw_iz8ct$~#)gVN9ItoAvrEIiEg$a>?;Lw&A zwbNv)v?17(o;@^IKxbx{*g1Wj$p0D4fODg2LPW8}mPb<0OEkP&%K&D)BnASv43Wo> zEnEREcqCZz*3B%b{v(R|%|8S`V{A9)>$H)_)H;wK(@@1G$nhV=k}g%U`)>HxQi?tV zE*I9qh$p1rx_C>RcLPfKr03zi{SFyo<(ai=9Z5}@1^!31ux%t_42iz((l=r+KjP3Q z(Sv@2<SW&=OX90s=x=|x$A2B=JP!wa>A30DTA7p7ABy}>0D){WVscMgK={$k&}tD& zlxP|}xKH$Ctouhv-};|AA$snE`!Zl$)$2_!)T9p#)SPaG{FCC%MN|RQ`>Cf;G!x_j z#wVp2q)q@sCBb@ZE)`KZ`xyv%uj}D^_7$9YY0lA#9n`4H{ah~&qR-&*&*L(ErcDi^ zix*IVw0p|ED5rL@RR)n`D=aw4k2)Xr@P7}at1fi6YrWA$*sjCJSDpHe5%z`9Dt4bL z?x9x>Zxs-b`Q+{)_rX&#A8Brna#Hn?Ou<v!PKfOf)NTsO(zfe+HcB+vPRV8<5Ciom zKM~bYu_u=-DmSYkQP+n{XqC^zuofA;h`b!I92Kk;lV{b1yfEqWYu{_8bo{F+GJ)J| z9MWapfhwouN`SgxFFPd$rq~8b;w~DBxG4iuq$qFAeI3rXMr>~IANLs+uhVEc?*O!E z7)2%DoTs_qD2H*w3pu<?+K35hXRZQ1HQb1APAEq&`4}m1m(ANY2KQCJuA(G+Coy73 zqIlp#sgQ28qMI}XYa=$PD?xM{4~dj0fLI&4a?uk0nhIn#K8v}I`pXhDM9#?VfzR^- zi%E|UAv)>Jg=b{GMqnO1x8QzS?SLY5U-mD*hnGx3GUBG}Q2G<ui6IMev*@uH`KzS@ z#=Tm{(@}lN?RT!xEqhP@6biRDLo75a(E25aG9!yfSk)^3Q{>3qBvg*=*+>2GZ3<uY zjK<o>UWz)kJ{MlHjT%gfW`!(Cx0L=&c9V*|lIkE_Jb4LL#on*4``_y)ztJz=_@Z15 zg?wW`%2XG~nrzwvq_EPaiW@jmWouF}E>d;>VzX}i(sL0IOaIt;>E+`e{x?MpE2}^C zNDTB6AT<6IGo4G-X!~Dv-mwRefFTaq9Qz`x^rS=6v3Y;pSGmU&7m*4_&m>2ICKFfT zhYwfz2{O(SO0V1Vw7c$Fp#yM_`}w<@dDoEqeaK~|_3CD0>%(`ZaZ<fpv6nYap~eEb z9<57rwTy@OJ_*xL;L?GlEJu3(U3qi;;x}!9_~vv7P2aRX=-6tIvnA@Mnwo5Yog`76 zv}7l`9^hTFB=N9yrx(?N75kdNJd2$Z2bIfQGU1dU8?XDxE7xK@n<UWTOo1BdM}2xi zeBsoqcX)tFwnUBPoJ;P>F)6;u)pf0Zs6h<Ez=HZ1bA9mQy=xbgaxS9Aot}CbxJNr@ zHrb%4+L>cd;>+z(A=)ed_<$mQ0AYqa`Q$Nnb@3qTeav;i!x?y$wxC{&_vSa`p}96h z?L>k|BoZO1hQ``W=pnDUSN+nMmi%M)u<B7QL#NiJ>>wB(khm;|v&OpaU<Q1<vKx77 zKFG|XXPfySp5d#^GeStrBeqbvhOeHj`WsF0nJuijPVmLgz@uCEMT<HTsl3mrk{8-S zE9{aKgbJp%`2$llHj+)Tvn-hc9jrYnIu$z*OFqMQo`1bwlz698^Kpnw-g9&03v;&i zXe3vQ%4qcN7j41%8Q2GaM~aLxWxG1M*%n1TzIjXd+r<5frYrx2RY`(+0rGpcRj*3q z=jYr^EC}}{-xE*&!2M6==f9UC9E5;}ra=>mziy8rRCC#Rul_oJ+aBz2ygx}fdU60s z*@5gwRUyLn`qa%vF6g~1Fh|ZIJ4aUeJJ|1J5u*=2G+6u-TS0q8Un)McvmE>M(~*u1 z@%<ZyN4fW!?xfr`2Vy{yf4;r>E9iEO?<9tODZ%3IToCjjTfEAa5sr#WjgRm{F#_Yy zJbEM@d)_@(C*Ju(pw@HIfS)FwsGP7bKLyrOh7cP7{|Y-hVFc~b_%kOu`AH=o;d&B) znQY)$fY~IWU%*7atS8R9Lk}KK86Ot<8Qm^;S9{5{$q@<A;Qa)k6((!874f{E)1AjH zd?(`ut(Z`pi8~BnXTjDIAbL6zLrOeXrO~>q(S9*5%iNC=ZikzW<wwrE87^}>J$?Qg z(06s8#topk&K|%x6@G$(6Vw?5{8$yE`$O|p;xpJ4v{+yUopf4o;HVUcAIzQ&bhIlH z2n8c`GzVO2cLdD1``1X<!E%3O>KtC&^X=pRR*2rcty3|9H?c9wQ{+rZjYNgT5ih4p z=gltv<fptQL{3*C5)yaOSjR;`Jq=+@zPr#|yz=ObBl=xtwjlJID8IB)=p3;3CnO28 z?h7Q$4u^cK;<QyynfD1$&-&481)ip-G#C10i3&zoO|<Oxn^PXkZX}Z@r<9zEFuO$Z z=nTT?-`YEM0*D9SOyEMrePCB9_MXM4$j(*Q=pL?q3{$5YnQS4mq_K4xj6wM=Vc_#u z0czjR@~z?>s4laFR?F3Ye+ve7)E?wBjp|9egjSY#ixjev0FtDbV_XVXdC|ecyvI0# zYEvXIW0A6nK7G3<BtNK-_(?xfyR4?nuheU_-7mDIMm(gl1wmcO4xW?<Vieix_@$x+ z#KQ|MKR0jUg>w6M4|Mn0LPxhZH1_cY98-kiU>&l3&T@=&1t}TCW&x{oHVl=FtSU-q zrm;n<t&W^Hand{{y(C*wS%tx7HY}>!NY>4#H5ZPl{Zf>KXaE9Uk<~UT^$bk+1|JIe zVsFMR>h6JUmrsMyQO#N4hx^*^4~srJop|C{v)!KWI05CDKXhK4;v&XxmW5Z^ZK50t ziLUmMq_THte@c8tnV&Xqu;b|>FB`OBtQ2!PBL$vu&3kYSFBXoQM(Jd=n=^yNIORFT z2xF-$>|=u78`Zhfl8~XY^{ax|2H?P56(GsLveN9i*$P4ylp|qPnPPvg7rQT^sTjah zmG@56tM64;kV27ci>K?ho(xxutqoeC3~V^f7O(96$u)IsB;PRc-lu`ysibPT)9X$F zWt4fl))`o!-gS?_@m>A%#*r`dhu&YmEe`B<Tk9@uPR(7@iT|j8bmY%)nqJu`$~p$5 zLMVZ5>H;grfy4{Zil+`eGEqPWu_UaR$eHjB)2u{V<iFzAy)E;maXD;L&A+y4fMVr+ z`BO5r#o=@+C+sER{fF=&l{spW^6A`HKCEN{Ym3+WjNd;@BQo$E#y@f{#_~Q0@OeqY z*?+GR7HsfP^a=AaR~(4K=XU8U8iHjRwuv=%WnxftrBRUGnzoe*E1>-JF5aI9du>f1 zG&f=rBs{fR(Z5U130_vD6bFrHfID-8Vxpai<>OjO8*qRjFIEXVrqOq<W?^<qOOIZV zbMFX>WV|8LVQTw1;YA%SW{YzRT1XdY&0GVqQ@Cg^trE^5E3m;TLdMUzvpdXnOJ;NT z0IHq=fqv+QV4QX^WgbMNa|0C6NuScP+r#~hwB~>a{WV+cD;}y9TU{|w>b0dbiS^&M zmd(F-0U#El$w<;v6p)%@A;W|j=D{&~UN#2VvwVrS3KZF8S*!Zpxtu1Lz-<5PGtfk> zWg~gfvs>JVJWew{%2^_AaN}&M{19z{ByoSq$_O7SA&aZc6l}5n$fs+y>kb#Sl^#<D zX0ra6GtBam<*>ZEw)TIk1b2Unro(ixjF^B>ZwX%as6}>GJB9nGROa!??&Ft)?#dmo zK{I=4tlPG=sV6}FvbPjb4o<<Wbp5g<5o=_$YD-kI-I!A?Z=LNU4XSZ6Q{m_@DZ0_2 zqisbLKNs)UZg^radS{8DKirZ#)t-R4*^&iy5|$dvo1t*oLDl#=Zy#BSlYAUirFB^) zw`bN$a*hl!N_ENcUxuBNlwl$Rx~lUfP}o<yp~p%krunhMA&}qCMFj)R-lJ-BAhRzm z4}u<ET6})5VaHD@;5`>Tbw4z|>D|{(BV;<5pcXZ@PS~PUnOC~uBuNk})H*gx$Vxb1 zWc*zBPH)p!K_BYCNc=xT2|vfe!pec#g6LK|?($ao3cE~w367XOY7<k{qN40CEOo;q zh{7E-I#5)Q>pi(9W_2B^D7();{YlZbKRCh-gt3&(Dmu2l3el%m4Q-w}fjgYb4b>MU zO)X79nqXOSUtn~mj_gJg&~0g=<O<cXLSVhv?|cN~AV#vm+;<|r_;Q=AR<d34@SIdE z<s8>75aynfN|qT<9GOn7YWC^j%@6>+9FrZ+a{O=Rzs@qJ*C?IK<;5@!%7V#uQ*?Xb z_eCqH=N(y@;ea^TGmg<|NJQfH)qIx>!#JJXXl3~>-r?8w7km_l?4||kXV_YW`@!=u zGjZdb%ygQF?~EPZm<ziZTRNK^2upjwh*j(i`)<<iG~6gebXO`Z_OrL8H?5~K7h$9k zRUAVtN@gf^Hw9^8zhMz;K6dHzZ(1st*?%RY-EnhYu!eUb512XR%z3C`St2GU^?$!3 z{@H!g-elNXm}l2IXn8b8Hn@O4Jos2`+pGld#)#~Q%dt>(*TPZ!llq15YuaJmFZxAd znjyFB1q(M6o<IYhFriqO3*te&BJxVzsBUU(t}%lYptan3g%T#b0T3icR)=F@dZni= zt}0fH_**(A3};e{y<k{DFX4b22tf!kIrMmnfY6RFqF2$uju-fv#@Yd`CKqHR4a*5- z!Ylcp*F0XK@Lw@?OR<=w$>-vv!DDxk|EZnO`}p_>*vmcs4CcZAB$+rI?o7#f%u6g& zE#}{fT<^h1y76?bf-b@DSFe0!W7e5PtKAo1g7hkxVRBeh>-y%NK>%#XY4J=rkN<xY zPS3-Jr5j@T{g>AfT~xR3iwo~FVKS4C>(aH@#L9Cu7cf=l41u5GSFg)+aF2gf0pzW$ zl%vCun%9~#yfctbR7)@sNBq#>zbv!OYnUHZN&x#jQsTdpxk5Y-hu8K6Pp1L{;#Y1U z#O}4>MMSW&&x-FQ6xY+j6fESnZ=`~nW$7>>ASmItrD|0KV`h1(*@ijIE2L}i@nKNo zx8GrBt*-itH`fXhlbsWr<`a8(rG~=N4awQU86my_UFd85vLHT974;s*-bpRb*u+q6 zONl4!`B#@kHs1~7KhH2#!t2tvKh}x7Q>RPdl7bGIY5j_?Q7Gd!-r+W8E(h67XuOvM zBj|OPk-?9_z#~cKUx0dZJL58;X2x;=G?96}t{CZ_B?C|yQp`J8m<j!%#+;}Qr7@qK zrW#R4tLwig#avA>rehw_`qi^MYdx<X*-y6EdeAYj^|(U0_hXxmQ)|WUJN|Uzyjxs= zKUF0RnHfaLXsCdFlY)IyJNl+KuioUrJnWtiUq;YYx<eAfr;dXXhX#PJQ`njoFHxLk zVAe~<NfuP<cU8rf=|@&qpEBw+I^Bg()H4II%C5`Q7NpPU<%jkCYQ~-G&E6=3O-L~} zu}rM3(Tyy54!AVaVc=wwn*JOk+w>47Nw%i5l`3fuk8=Ty09WA<4(K;uYbmEG!|(1t zbo<tvMl}YI6@Th`@+l;MOn4Fg$XgiJm!cz6##?>$UM5Ir*HTnci05UYiKGea!ONEX zC7mOu*o=UxuswEIHzKq<-C&j5q+NOhT`xO(^k~yP6*E|slvP4qsU<(Z&;RZ{yvjW3 zX+=+J%d#zEQggoBYqgdWob+wr31({9X;(_i$13{1U4XgjkEFrCa?P}23`}SVcw$8K zEE>N!n0cAPBLSmj0>nHnD%5zqKba|=3M+L{0}hCJ(s)Y~Jj1rgR$Zs!Ba?-Nd6O&t zT^KwgG8WBm^--<fU-yth{pGk9s#>IBOGxM$;OJRx=&i=Ab5=u5Y7>mI40jkr69lBB za;<8c`gC)TZdv}7S45lK&6lvsZYh=JD=M35C}WPTOX-AwD!%V9Nf9^s@HSc0H1+EH zet0{2|NT4t=>Hv5-*T}NhfoD$_>NVKKUbI6$Eit<UHMl&P}r?SFGc(Q9?6ohIj(Pi z+4M>p@aR|gXhpZ&r>zIpePRs>kMd?m`;D$2t+J@8X~|+<b+qpc)f>`csGLM*UJh_b zbRYVvS0(fA)}II5rlsjREyqkL+?;)bzEOrhEQ3<6xig3AvSe=7ar?q}T<WksrRfj8 zm5R1;CUNMbiNpMp6-*w8;K2nL2aEi41LkZ7GdU1tH9e%U`u^;|TvK6IA3>7J*&Jju zqRwW~%4OG>2jT--Xd98W<r7ThBbnA|2#rugMvsehl-k-eVydr6O_%NEuQz3FxJ!Ab z)DHi5v%=`EDxTSq!t{TIpBm>4^%06+=){{2?J*n}WC=f4C~bhD&kLoYnSMzOV^65E z0&}NYbC}suHDBrroAF$NoYRIiG88+oT3KWmvrpOb0?eT@t7EGxvzc|!D*{l<5FPgi z%4c0`r)aBoSumO?h3C2BtkcL1SOAS14U?hDI$JXHD|i!oi<aAp;!V^hikLP9j-*?M z@B%vvE)8bdk{te=Gu_rPZs>S9Mo2?l2&4mzREAROpt{({d&4?heDhk4Y2>=2{y@4h zKs97}jIcCivvgQHOy8wvv=|{DiVOpJKeCDUe)8~ViS*{DjI|uzVW~TB1N!(z`pI1F ze|8+7rNZ1!@!f#PF}kUw(oD$OLK;F+tR2dpRdbv-<B7ka$ZVE0gV`dobO|R6wT)}c z>{owxU221k;|4L;Z(8X*dS_ZuCV>+tzVLnjT(;HJcf!7sEsX8a88w1Jy&W3dI`spu zK3#%1ATwVuCo;*FD=`zjSf+W=Rf;EqRGLAt&4@s78xu?~H|YclvAg#VZ(1%xVqoO> zA8><6F9r3YW8d?`+^e&9VHZuAc4gJg%`@etSH8W(@m-~F?yDKOT8qIzVq@-3)=LBC ztW*hejU|9{Z(M*cIlVTz^taorA!|A9e%@qxtT)^WLkhLhGKw#G_K=tR)Jw0|C5cxD zKQNpt4s4n}J#qZgVW@*Ke5rAKZYTtn8AE|2uyfO}%zYmT{Zpk_okC+{=(ov<d-LhW zrD>-6hT4(y@0YyGB<_06aM#f@yjM%TBE9M>v)nvSma$I!NPeBR`Vfw1*4xQxtQWnI z&-%*;#&~wqfD;#S%YU3iAB4*nCETEux=+t|{`k$el5)TFKpS8mGD1^FuUf<K<)isz z=L+h}(&8-t=UKg8$3l}9--JMKS;NBQd8|vJA?EC5rf}_ZY1Q|6lsScfZf;T?BX~8P zLt@t7I`$9Vd)HipSN87TR8{NlH(o&Qsl2D<Vf|4NN6t3zTCrd7Uaz+JmR*nSM%?u* zXAfjPrxjCaIq~E2ZErO<b1!4E^I65E{q*CY9zQdfJNK&pwx=zsF-y6RhDrazy#UOf zAb8Eqz2a5s$lBqbKRQYYHR`2pnLG~Xe)W}m>94(XP;doI$iF{b-!|Rf2&&i(J`Kn? z(C5!)`O&xTDdg2YFUZ&}=iVNBaHZ$O=RDrznxL#1$hh<&^J?sC8bOe1ddDRtkl*R; zy8_twbzU?c_OBEyoM5eGunB;q9tMtAV&AFAGQah>*c|Cu`%UC0!jmsDt&Px%bmMN% zj;LOE*};5;(cGCeWwygg>FT@T1Dh${4gS#<6>D!pUY=MoB#xc?=5MFaC2VcY@fc|j zztYxYtX2+KF=X{<*Sn2@R4)b5T>r52Q%l@RlMPu^ZclPSCbPrChJ>ooV^A4#519em zv*wM<`P4E!)_Nz2Y3IxLGHP7#fLq&QvwSo6QnwwAUQ7eP=u}BJ{pVNo<N)?Vi^9z; z3E3yDn*<!w3TAO^Y4d)T9O*A4UzVv5r3a}zeEQ%c)6L?&1P)mn8B7Om*XU)u!tvO! zGGew&h?hKKUh7KmDF*nO`XAhKA4}sLp19JqU>4St=67$ZU_tb5#$vkHDtCgOKz3(X z#AKLF1MdTt)%hQa_kX)!rSG&Esl`VG1#D#d-dG>_BVswxcc8!&Yz8H5Wd?R`FHUD= z<cTu5sj9bMSC3ZLd&wQNvKn=A-tuc7LvG*aZOLrj$t5v&sD=@)&Q}Wju6v%Yl=v8X zm1&IfYjw*EBtv2kI7fZJ)|~F2+{o?!(!T|B1Ko7}y^j|A9?{EH*UmZ54nFXz;|^Sc zgtG0u*d39^Gr}Q+eyIvu_v*pOQP%B4rcSa}{LU17_r?`l|GUUEsg>&4OR!fSS=VL5 zUyR075NcwP%H+TOH$K03ED1Yq8U!qfxI5iEw03Xw61?{NI_rmvZITGA*mfYthIpp` zQKLY8(NhZ<Rzhg;<r~b{cnQfs=ow5~=u&jILDydN%J3HI_b@}hn{JGO_!IICM*`@| z8nS#M^P;(1b=)I<&W!F7Q6jl5y-j|!D|7>i`!3V1kmC$lo#X(D1wXx7(E5Ai6YT(i zKieZ*;ROm}7@m?=SLG|imBv^4zpc24{c>9Ei=k5^0QUZuI>Y?weed^Q76YQofVeod z-sg9DJK;}aKbn*la(8w{O8hxI_E!5G^`|Z^l&&AfAQ(Z1X5#WtCXL|tN{mM{G^lmy zR_iUB-6dmE`1|sYw~a2r3T!&^jqYTCbLz)&#RjpbZ<l42x;qQI{6@fu;=jtaGAi|_ z1ak)}lw*r-Y_7a9Z-a?>d)Nc8&t=q6p`O@W-Op)tqu8(CuT$M-u3lY*@zn8UYPEZ5 z2F-ikg#E6(_sJfrw#Qa`%RS&IU{TgG7kGP?1ltOdIRzuv)o_PX(<8B38>0dhEUTQj zL?nD$?tS^s!1chWAk$~$SFc~Vithh&;>7?1X))sw0JT*5SG61rcxguW%(D1m$FW_q z`}l^yBgc4vH?nW-3=hp53@M%^@Gyukt~_fa<2L0n?^Z3P5_1kzCG3BY9?m`+S$Z7% z``BV$mfSw-_eQ!`H(d?GFlLr+53Zptulv-Xu4GyOx6;>`+%)!Wmdkr@Ujp|hf$Z!o zuFkf6Pezzw&M%XvpL-I=Yx-z)WxS_DZ)Fy{y#$Wy{dwM{?rmkxs9PvJ7*G7u&cdW+ zDcjT8-?A{IV@wE83XyM$HTHXflZAQ2q(3<p694>!+a;#ox#)WfyxWTGWB<6%g>k!3 zBIDEM+6C*Iu50=yK}cZ?^yt^Pp(K!M?uWg&*|<Z>m3%K2cU=y*FN<653lrj-{`hLv z02kAtT$A(ug{`g**un%&yqRHZBm(g7`!?4;r7{PY1_1fZoKbb27J%g{#0MzYBcb~N zL2G<MQVpP_JNt^$l_uxE?rwimnqiYNBX&RJk7lOp0^bSD4R)cD!i6}ZClq_kFgo!c z(I{+Yz%mo5*sEd}r04`U1xavI7o6My50rTr9N_fy8J`<+_O6XmE@|<7`;p^iWWAb? z7TENRnSO$lIduAwaiT%fH);P5cM|rr-vgU3b0L!b;lAA-ZP5>t7u6GT1Gl}EKd!1> zZ``Uj8M%7bn^_Flnxw=RJTp(xjtGw5n|z*j0-McX>b@Vu@Pw;dA7HZ{T>1^Ys&)3C z+2Nn>Mryv@b(VMRu44uO<)M9CWqQKrU9<1nVTu3*Mu@qYT8&b<a{w(+ySD*>le$1L z;u`1gLf!q}#~PF+KRTf2<L0!#O$4!4tk70B>S2H$d}@H9g(l%8!)wYC-{swF$zW-; zje(~X@2wVIQ}24Xjsa|O8+^VGs&L}YHK~JQqzFXUjMr&mwTqXZoj%IyKMfv&&2Q|+ zvdu3IeHjwoi8hZEAMXbPYUF+~vz_f8rJEObvYs8?9b<_&+YuB*fwPKygmdCF$b#&D zH1sSnT{?571R%H0#0-F9Fr=6@tCNM2Di@Fp<ogbm#`)iPd7$rr7sw|5K6K478BrE; z4x(S|yxOGqvlxmUga~JgO3^#X;YOQF<r?CjZ@nN|fU}<Z2|X(GsW;V-*de;QUSKJ5 zk??l60n7{JNx(DVYMErQ&gk(M#@qnX@L~+Z^xf1St$q+ZmF4m+HEw`Ut-pD}!9qQF zi|DGt2iQf*ey@|5Jp%#Ck+Za`R{pr}a+dI06ZKR$O?Af_UYI;n55(j|IE%kJvPXIx zv4M8(nDcJb0>bnh)#euh*Ru_`Q)f>1O$I*ExN)l$g6&$}P|v@+-67urn*zg)DvNN4 zuGWo3wv86o-Y25EoRKC?Mb2vc_LeR~y4Gmq0Wu*dby(3#^y4AK%8h3L7$VAzl`Bo> znf^N<A4sH&02<N@D-Z3gxTz22y;60YIj8}D8({amFea^5px+a~%qal7fmvcbYxGxc zlMZokxH>07-{5;M@u6@Nai5=h`l+m(d)A}T?2n2)jG-K@fz3Wn27CD{Q?`q_#1!?d z6>9u(@m9vGMU&4*&g}7w4`%BJI<)brbsZ@+wR%*5+xaIsaE8O~jnVC^hvQ1XR$~HR zGv8b71O-dV0LwEid8e%TfusdudkkyGaaSoJLS%!aJcxP&5tq`IUPl(*uSkf&`Yh2C z9uaQlG!qk2;xWMJf+$cYpk6|PfgBVG>tVxgH~9|5o!Ldgz1@MKM}pouMbw~FvPY9i zE{jf0N!67)dC9m}5MwijS@nN7(MU@A^CVQZ;Svo=EqESwySw9iPiX$&Rc?-rkT0g0 zE~-8BmT1c@?$VPUa;&Lv8Ck8s7!v@RBV`0Zm{w^p^{5di6{zGX$7r@oJ5%oY!7~mu zArmZxH&alxWC~6b8Bj+MHIYdl$YJIii@!{>PGqv=dY$DF#%Sl<C4;WrVWQ()x{ggj z!wPZieE+*Fk+VX_7$RCZ1AI<lN%X0-(k(63YFT3mEFyfEFGYOz<>^a0nZ^g}n$B%p zigN(f$T=QMcE33lMZ^OHm{>2;TIDcdjqhk8JT$@whJ71{<Qj02FH&~CE$KxlTnVO0 z{`S0t?`G+SIVzpa7PPt%$C8ctfT^tvQFUvWyL?U_l96WnD8HGdC=IDK*&mZw7;Z`H zrzOA(L`VrL1*HEnt4U_eSh5Y<x%oZeCMNV0ySCPCrdn>`fKi~?+Hk_FPV-Jx=#gjj z)$amalqTfgN?aa5cYLiDTbnsy1R(YMOTTI91*RY9w!<fC!8bZel_*2mNSTfu#lHD; z1*3r{7B{l(U@p}*wciZ@{RFIF$LkgSuX4?G(XKG`RSo&>`3gs#40Nrh)7dzNCn=a4 z>p5V&*)sQX&cpn|94W=N>`(?^ieP_6U;)P*WMyJ|23%!@L};9_m)XEJt6?5wx7AlB z3=(+gJJy(rT9>|c=?^hBN)*soI&eJ6O!vzkCa&f}C@h~I;yu@tHPspz-&Bd>*UIqF zzx{9rbMfM^rqTR0F9=Sww0Y=Yhj%2c`HSXVRrL!i=cU4#q!u<MT^L(!)!Bi-Iv%O+ z5i#btv9(b)=3{uyX~iZD8~-X3R}utU9#0nPHtzxO!LP5p`r7^E5<1i2BmfNe%<&Ka zx+97-Kb=);;!P2T9@&(ZvOr?hp;yPC0~0ywfvCso&d&N(ytgm$JqY(<Dkflak<FIq za^(HO%KGPghrY0fKPSgeV!!$wjEZAJxbvDe)xrS6agnvUky+OH#hmZf5?7Wc50YFe z+^qt|x{`+E+e=T&{uR(_KS=PiKu~cjp`wTF+8O@DhHK;LLqn&+J_!f~0`BWomS(m{ znH~oQ28q2WAsmJZR227lkJGdGMD(_GW8U3Ufb$aJOCairKi#huH?vF~U))IV{)*G* zrn(bUg^ouI(`7_Ek2~EdxR=VSem6z)UXW71qth>3poQ(ZqXp#jduKGY=OG%+C_t#) zxKH4fScB`W=R9{_OwZ&hwq0tSLWk(hq*>T%)K=v>A%oDDxubpxRKxueK*9rIViD?T za6csO5TX0(yR~%Fak77{El-tpgC0Nd2?uF_R!1!d=Urt&XNQfqv#m?wLmZ>6@0g*+ zE21hlJ`sYs`uhwP+b*$EH)`bQe}L;^b6l9PJ6$}#HCk`-7oY>vgM3~}9d~^)(b|7+ zqI7QIY{TnsB{C4vdov961{9Un^?ORsp_p-_=Q(fj9RuW1rr6)W{Vc7G`>iynUgG|K z+L*0PW&H>T)geE9KlVuIFhr9gfI68axzOHheDv7VgA+4@LMeUC4PJROIRsIok3B;2 zSnyeqJ4TL^I#+GZ#qCxsB`C>BfX)68&)ju8eDzOKfOk*;knH1uS(g5Jd8ZW__afwI z&|&h6T0FQUeZ%{Wz4cfV?UFD4rxcDV{@*IECjZcv>5JF@`8K*Uhb|P`{P$AyjN1m* z+lY{cW6Y{IpERF>DS8t9mTWb?TPruww$uGo>)z~up4}-Z|5D4xu;o1F>H6%!=q7M* zkN2~zoG$}6o%OB$mp&r+Lvrp1Lvam~M`YL$K-Eo<gDSFPDpk+1;<5WpA&-g|=PG`# z40lz@I9rvySr)R|WsMPp`tD8;2_)B-a^)IDWxm6z%WqfT%b7}8Ds7B*?&Ui(Urp^o zUJ%@zw?xVAr#K4Xaw3;}ooLlIgG0cSJRt4Zp`gjcogcQ6z|uRNH($(z>-Y1e4%eY- zY_O5?;1UbW$$7))<Zx?@y9lIJ<&yP(uZUKBR+zUoM2I~W0t;un^c{wBSf1L`LT_+a ze#3_Y1Reo|N@a940n)=OZdECD98!V5m~~m*YGp+dHJkrbdaf>*uI@R67LbKEb0ulG zIgg?5{2r$N5ciJt^DlZAc1n2T#3^=xjjYfs^*T$<?tv;_%7>8x4lB>^93`A79YG<9 zYs*e_fV9jwxYQeGa?5ugg4Hq7q-L=4sr64PE{zY<8}00hVZtQft=^mA%ghmkCPU?3 z>G7Ey=f3rGsZs#{8j-QWyH@S687Smu)ip3@%@DHcW7$;F=HEkf4<m+k1!PE3**2dU zSPh7(J89MT-Ri}D<Gn$pn4D>ArpNnXK)3XG)5+ug_IX9`oVUPw0GIYMpJ{nbnCGbc z<e+)<E6I-RaLS;RvNYp_Eu;U<8Qb;FWkH}B{Fj=B-5~i<2dDR!Kd<?Ol#Ph{L3Tw* zSn3GgOGH6q#d#9Bs?Mm0an>d=+V0|8AL37cm8ddXBW^gT-!570p0QrabnYSc8Y8)S z;P>t3PDYi<KgYOEIiW@nJ_#i3{_CI+u)1dufFuAjG@YhF<NqwRE5Yt>h8qs1i8Ip9 z?g}0@F7ld;HmWqFRldzp*c4Z85(8FZ45|Nj!gzg9^RQ`Ix)!AMe_Wk;I8^`N#?Nfb zSjX7cW`?mFyKL3W*!R82(pW>tmLioIBV%psd)apqLQ;)=iLyj0WJ{7tQc1q~dH#L= zKj*s6cAd|8-{-zxcS~Qic?y2MkMf`jk94No$N@xh-9w&d2sxZ^DaWRQGi#TrUFVO) zGHReBjhr9sG+&R%Zjd&oAD5PQA8Xl!VPYJJWh!6BN!rfx!o{2Z^1j6Dvg1)2<I3_b zri^z!V5ZRgFzMAaQ5%_3_MR9E^TLzV0|#v7H<up49819V_69($H4sNU!=SoNQo{oc z-|Ta3hZQE!B=1I}ZA~-Qn$F#}mD35708IO(IpUS|(dVp9m9pIe8jbIMp}M}HD&@2I zHG-t`S!e;YzLlYyxnmjHQraru<q}eZ)4D5iCVR*5$)5r4rhE5~jj8T5>w}4pz+lo5 z9$FGqq(rT)N}iN2F@SeDmN_TxV`wrfQk$<5ttAGs3(Sm1YQx0_9=D6;aokHkOFE1e znk3R(fjUKPi0EFwwp1KA)c`vQ!aDX5PmQ<*8lKacclu`t-IbgxWyuMt+L)yV(PV-` zmxxd>l^=^YWCu!*uQEw+6RaeKRj%w6+om>1NswOE-CVMXZ&@Kwz>p!5;^ZKe&)4;u zm$f6QDOk#|{XIrZKKa3x+}3cpfMn_wsI^A2ncD`@Ke69Ox`YOlT-&Vj+g|JH*Wc?! zOd&S3IWkr6DFhNL;IBEtUKJ1w>yv$KzzN$yNw%bcM%CFb+X`-}Z_XSQLqt;z1fT?L zszEj1XCtvC>#pSNo08G_-0gECe;hwr`G~2j^r@ix75T~wqbN!()WB_e!!{TL1s7qP z&h&v5=BW|W90p6cp4F=O7SfY$Ds^W=cH3sr>vh+7eQ*@Urk$(&Hp2gg<tHX6)nia- z(n6sdYtu6KVKS+NkU3=Byk^R!#{|mIG|o)|x3*<*qaoifs41P8vIP})n>OOR=d7|u z(k68mCs4PV(#ww@a*${jm0{1+N$u-getGS~Kn;RBW}?oT@FlxiuHyh2M03EK8Yq?e zs+3+*X=f`GkXnb4&_PQyXJg6}@XkJ$0p9GL$c(&Oe)CZeNwE~1i5+>$wM9a2{{7x0 zIazI+-)uaYA{5t~9FyKzww~nY$94liw)CGNH?9kWG8rU`a93->wpB=P<T%o7$?*BX zz<co2R`NV?$A4^n<7HWaw02+1zh0dYCR<CqiVrvwKzXbVkzUC~aNVA8u8DD%`Ck2! zqll%*90DO3sI<s=B#?GqO^v}w-Al%vKQjbN@6uG^Z#BZ+q4?xmsB%G6r2#M*CA%~o zM1A|VM-vsUZ{K^i#X38w4o|DV4(yf*7^;L?GnlNChE*ahVlT(!J$pMig-Jao=H;@a ze8WM1(4Vw=6aUm1s~sb<r_^^_Oe#!nS1JF9U;c^`?T#M_CuWM71fOm((A1wLHG<zR z42&Cou$p&q3LFqSZHGCJOFx8iz3#g^MAc}Vk_`QFJ?gVZi-dAz4Zb+|@fJy>w#JeA z&5Ef&a&yMZf|UlSQfrEGNC!`OenEDIpxyuzUwsfjqpi}cOCAIS(yW?j*0e?LFY{t~ zKb{ps*hA%KpCodt;I+REM23R+PqW%J-mBWljQBE;&L-|jwfKt%D;<Kw3DgFiIhFUc z2$WQ7u9|J5jraslJJ{&X2$f46tU*^$Hhdm$_U+p?70;WkNGo*xHI;Q!Ek4^kzHvE= z*(cpjRSb2eocC#B5x16dLh>+f9XYC330;tvpl$XDrJx4&o+p`sm@ILLK?QC0KM*=I zMtuOF{A<;JgT}(MMl@6*y+SQGP0Mx2a|Z~2*4U+*_Zbj(Z8P5-_6{!E_nkmfrTIQQ z-@_Yr?L^3Hc+3yh52#p2Hk@kWj<2(c$w4;Ae*X3fd?JP@oBi1XUh1~=5Dx`og1)%F z*HoA%qL+CjtgyUmRpt;tb^xrTLQ*XSlUps--_y>I%e#mU&*lsoqz*bej~!Ia=U@b- z%SQXmO-!@>euxh^uBievKocNzC_N1OY<72ho!Dc7G^}?lHN1S$_Me2IiJeQ1JIeo2 zpbddk&CqOG^vgz1-8otvU^~%nETv)1^z_7GZ5po<)ruua160*L+CDr%m4siQDn>T! z0Njf6VErqXGbX_b<USD^RpC{YH99FvA0Zdl;U5nsN6kM4!vrsnYFw3);=h+8{+hII zGQ6(!j%Q85_#|ncuwuFei!=&5(V22@SpLQ$?+dBR7#gZn%4P&fT0geJoXdIh>pAL# zmw@d~$+%1YPa_SdceR?AMSS0vXjmJ5$U3+%?rx~`8+y7bQK`jEaHkAs3JHo6Nmw^J zk+V?q;r6#;CDE0>jvz0Y;qk0JmV+TGP8O^Y*Ei8UIPnXb@2UMag9EGRmnP8IJ0we* zkFp6Kf2-MOd^9g*-43veUAfkyT~(8)hD;8rLy`#NR%Bv@<Ih?x*3@GF3M|@Ih!wZ3 zZYcXl_LUNqscDF8Qkmh%`Agerd3nQwhUA_j8_H3x_DU+EXSI|SBfr(;=twg?-G8Mk z>h}p(y;bPanfmwXUk_E5Hi8qQpSPJa+W%~%IBg{)9v?MlmERp~Kzl!Kdt3gi5h3XE zCsjuST?CD(acEHWUN8Fppy~Z5+yHi33CDaKXXQRIG^WdLqvn1s>|u%Y%H%NMYJ;Xa zd$$ODHf&g<Vd~P{o?AZd2(?|-6>BxmJ=t!(Om#hma`*Hp(z3iJzzWQj2akPQPu55Y zj8cwZ;PyLXZhJ#-=an>=6j|r*hvIN!kAX;{TE+?56o#}V!I1h7x~nq`T~zMBO|vGX zT7oDN$}kSgEs4Ya%C*PyCR|~xp!ws8J7b$vylq>oXNn&<XgV=-@^yr!VI+osTILVt zi;f{ZnfxN5QB=UN@=HX=$!G*RR^7wX$YOd3)37kE9C^G7?$)kQ^T7QV<Q6_ZAfbDR zvOOffHkD01sbahoX(XlrHzH@M4Kb&xUER6snlu&vhAMwU`N0cjvg&c3MA&;e<-;#4 zjWLr4sHj)_L~V{V6J0*0!RciK%k)!wM*|wMgkQe8J!fDwSGhuAyH*RsXRmfyAH``( zJ$Yf&!hZFeQVrBJG}WcaBi7oqvToB*_BV9g=EGSh`e)8N?q{&)9&!@^1}v_$iEvqE z1*^^A*S0RMobWPY2q>Msvr86%19J`MTAZVOj1;WUw;SNqj!A5Q1+~(&thI7vw$`Rp zx6ZPz&fcaZTM86cIg{}sJCUmj>f`v~uHMy6<Z;6`S8u)ib06P8zLY5$xvb;lWNYG> zfTAfw=vb>h+j)6qC`T_Z#QpKr?;Ep^U;CfFdbH^Vw3NdD5e;B(2Xpr0Il#d&%Ic9X z`;4mPqH|97Pwp9F{5ls-+Ywb|?y4UA-yVV~TTx@p6Zr;pU!mmwW=JLcs1!Sx{3LpY zjf*MpefinqTY3C(A+Z~+vBk?Nwp7u%HS&WO)O_`dOa8XL*X;M%f!*neGh2OZuN2<N zBFYU1QPOb^l|XFF!=$VR>wEtsO?g4A`kVj+k!h#_B*(DV9mmIf<fyvwm+BkT+7$7l z%OccLiAc2R?LMH3ka=t2Q{sJom!PRZLC;iG<=BHTRyud;beZB%B(<+ru^lZtlHIir z22=*RQcKl43gxTx9Jk_2tE3Mbk(Ha7QnKb7(^55u&Jh!`hufC|p1xUig`MtndtimT zvk~~B^S%EYQ|*#^-rD9Z!qzH}EBTQF+8OY#<u@+PFhyG~0fR^S+B#rFm6H&sPr2sv zSOlQvkc<;BP6mBIy=GacbIg$i$;(cOh57Jwa#2FZ5DGzTW7+tgz|rh6v?&LWx{z!D zRN9&$a;QKbt9a0407U6vROW<mUDMp#OAo4|&I8rG-<w)~vE|BXsre+QyCO2f72sKK zw`N()-mwuKK%14kMdu&i$+jDCL}=xxz)B~&7JAa;799hvSGEMKoo#3iRA=0ZeMWz} z?KR2GiqFm7RRaD(JOcvfJnXpnZ2iBR`tCbF_~LWMy}+?!KC=E>ma`vqBhvy7ML&GS z^~%hm3?6tT;~XMJGoykHWL3pB3nSk-RUVU))+Jx``N%mZ4zR-sz|XG~2aV$2ZMRKX z*AXkCpy<XX@#`GQ((l7jarK`9uLg9jR$XE$BUVrD6e7x9v`SvZURrJn{cI}Z+|%|| z_ml%FyW$DCw<=A;_-2*P%TY<bTqma7Z60z|K>`DR7J)dqfU-$Cb#|%6J176Vnm#Vy zRHrJ-qSS5xSrU!^d9l<%H`pmB-EXN)PR{b2OpoTwr$FkM(AqijqDTi`$iAGp+diuN z{_w~9G1hyxI?j&XMuK)!6hob;<JW=qWo(r)QyZo3o)+GGs<PqiBn0qp&PEvq!8~d+ zE$W`~NmuXSaX&n>+}VC<j|4N~MKzLH3;KGSjz-G$@3erWxAt^%9+~(yhw^D_^}_sX zO$5F~4^{?wi#isA`2w*6BF>Z~@xF}<@+*9@mM4>)eO6J0lZMi26f~ru8s$bEu$>#~ zG2G_lF%ur3E$s63=pYQvJ(gI6WAW4=Pg7uoWL^yv$Y^*f1kafHb|joW^)=&;&$~J8 zv*c{QKLGr@Bpp?V>^xCtcuUtT({2G^KCY6I-;^iQq$0Ds8kJ<vuVz|r3}(+(R$ic` zq<xLdBz9k`BrEKhvMT?^x=gO}cwB?BNhTC&eVNvhAR_R$A0%ncQ%-fg87q{BCExm) za>2`M0_R)?w^p1=vgHtQu&*jD5B5E}3{9E^l~iYe)DluJk9xQ*3FS$0c&fT0q=>uo zCebgl?nc}35FO2s1C{G=xiU#Hr%Y??m;1Nm%HGY6J>-x4L^F?aF>G*b#Z~M>qvb)x z*2Z=x`g{WwR9(dY$6o?>7?Tm0*?iUaKK2zfzHnpDLB&QDR@Zip%C9Rp<r{U?)2dXS zIx?*A6|L?M8H>Dx9^e|z&MX-u@s+-P!`p-~FYU6BNpdzk>4dU=G#{*Bxi$NXo~=pk zu~Qqwn(}57&T!}W-jj0y!9v&4V_xJmUn#K=fEplo!h#k2X3a!J>oTb%HGHQ?jrG$J zz6OyGWh4lpUfP_ITusxgJc?zn*`#JBRnmOw2I>@GS}kHjRaKpK!Uz}7L=Ez)Zd3n9 zJSGRVPX_ZA+tRS%cI>v}GUTGdm(Mri*j_WtDh}TYk7$E90k?A0_|MURYJa1Tbv^;k zzUB$K5zc_3qs+NScg>mdg3nHu-GCyfu6Xp>$IW?9KA&Pmkbt}gn*;YjC6<zpY^CBQ zG;qLx=+#9q2Ck%nGj%AkqlV`>JoIxADJgxn+-gA$5~xgxcPqkgSBq_AwUzM)o1ZnU z{f@lI<=!$PzufMLU{`G4hr*=0C+VIlB%Vn!H*nUo_l;}>KknZE&N{=+`bJ+@X;-kK z?$m<0;gk&gbjuMX%g^0KTqVXbj131O7;AS?I4?p8_YV{EcDr$m6LGyd|E6+(H5W`= zUzn5MW$U<HmSws>ix9alGkO>d6cakl5Ie3B&Cd%De0aSo<ogsCM;MZVUQd>2vLD zEVq(<Qb%*o@bn0&YL`iPRl^QjGojP^B%aopyH(#cnFNb4f!mm4n(QHmD(>;ALCM=m zNll8gNP1uhU)embXAN!AEMBdY-;^OIDDd2+!`!cXTmiQjW(xK-|9kL90Of`jf<C%f z)GHp+{t#CtM@;qVC?9F&Xi%g4%&}|E!<eCHFXcXQ2$lT02q;E%58x-fKMZE4aHUUG zEwB|T9%*~N!F@f|)Ua3QE+u}4+?ShA_Wf)-U0o{O+?hXVa4nQ0%_|5jl(_#%#@|@_ zrY99;%o+X!4lcDQUA471EO?pE;iBZ85p6ppj};JVco~EXoQe3=1`5@@@AvK8*P-Xm znS+WVBLo>idUD}l$(5!Hmu~EA_OjTwzP@p=+#~--#_g5p{7$u$`o9~QuJx5p70|a2 z5L`Gn;M^NORIFufsz%{7->Y2r!t+uA@sV>HEoq{@iNrw~KNd6KRLmjr0AP{S=uI9~ zkKoG#21S<$$;Dk8SM%sb_fx_U=1|vpC&wHulPn{cm(%-j;yK5$=#R>mz9|JCm-sM0 zV2&bcXoi5Z<(ZuaS3W3TFkT}QV-Y_Dy26h8{6?q`zidDApa_>;rcCEF6lcCfGtkiL zW;+(n&`u2(865;N!(CGPaQv2okz(-*z}=F@%0HZP(a!YzFxMQK&vxY$_|8#isvH{w z*#qzr%0hP`K<SFD2Pgmh8XrT^a^sllzk&h=JXBUtS`?m8zeiFE$@WH0&Hl1zP`Ss4 z`ADxfee}n*HS(yjhUy8Wx2AZuQI@xC!20(12IzDCeRvvD`E9w#s)g|}LzJ<8tJzDw z_9GYb{*pb_9bg_Vl*{^j%L2bpTCn+cTcOUr@81|Q$JX;GhCR%yrr*P&-&y)-?d<T6 z)AFF-$}96N17|%q#wxFtB1FPhcD2j+{4K29AiQ$~E(uRQTMX1Bl-K_9&&E$0_Mso0 zca$1GzwAS#E`?<3+u_vKAH%7?SyJR0)8zWRo}vuyrMK|AXDENIyO6AmduzszSVhDR zG|pMc6xz1jgr&jD7a~{X3j3CTQgxq%!^qWox|aqv8ExNUVc+LrtX!d$P~ib?yH<16 z|2FOgt#eLg6<W;(U*X?X-g&BeB<9PxLFPYf)|9<3be_m#ZGr?=P%33y68AaLL?oVD zh+fvpk!GQo@zIC-&A9R=oYbH_#dc~cgrtfuwq{>~tBDxk7-TqGz>#XTHO>?ba#-g# z3YYp@u2eg`5CkmVW(vG)e%kmg9Zq_77b*1k<#GOpnVdcblp=jp@B&Z(WodzgCYO&T z!AVnFA0SGfMUpH+qlQm^UE@gF<m=&Cal?v#D+fTpvGE(DjR!Sk;`}$nZ8kW;z2cHP zawmN+p2Y|xdkQT89OEk@Z&yUNcRS8ggmf{y(xBekez5zSXdX3|MXb!3DYGs%U=p6z zG5l$LbsO#lAHy5grf)I*AowIH%?PRQm=phq?96nP0X*(DVSm%a87gnuYW%FDFO~Ly zw?c}!Fxc&L*+0_+S3V}YJ($F2g$@Su9ee;KL{RC+(eUj%qVMhS^}C_YV1aJ(sThCU zbeQ~0TO0xOT3{-4s73Ruk){4ihvYILIz=L!$Rm#th>}Ld4k?4$V6KBsnYZP}xiz%y zV(!vn!tXD%V|zsE)ZY5DI`o<F$thBqtO6A-du(uJGRMC%^^-q{M)o%Vrg#vry+z8v zN@{}0nzNhF7gpu1)$nR&4}><Ax&{dJOj#bKDaNiWVioo4gERo}ZFyh#<=fQ}CR*2~ z`^B4{88O|l%Xw&MMTX$45%O0fsVW%mIl}8bqYqxzxSsW^`TiFrD9E>DP6;CFvb7A* zCYvs8dB=)fQ0)O$3dfNpCxu93j^7$EI(o7IW>e9SWPc@l%&a_1hC~7q|3IYw_V|C$ zVW*c%I<W6Dmz_7^Y;L=_1RsM>q@}_yAp(JMuY5@Wh;l6)4^_wY>|C=}(G(a@GWXTg zzib>q<@0IpB}1h5aVFjsr|GpE_f?f`SNI!C*=<)q0p3^dzUuY+$uTR5lt4PIyez1; zlPTOpZR1c9Wo+P;B(4FO<O$&wbxTlbblmaD_+vQfOO9AWqTMGBdECKA_Jgd0^`S<w zik`6->3thED>+i{`b0=%L>hG)K)?G+Rr6{!aH5)xe9-(1e&2$eB-`TVSWwbs$`0ig z75pb(I}ma|Uri6!BoH~;rjCpw_@>c~z1mR<5}~zorR*wYbdHNo5qnDHc+d%uaZ}io zo1;v4R+4NP?{q2qK1zhQ@v=x|bYEmZ9NraSd3NiE5M)GFMe0)r$!z>e+H$#btdGKr z=k5-Dt^oS(s^+D<%gd>&JwZIcF<Umd>gkec={`T;vzzhHDIl#c#Cn<yApiv4d7sZ( z4)^jb`>rMP{Ng+}U_NL;##8?pjD%?T)_w4??&ZI$el9D*Tjztg9R}IGtoz3Z?P={7 zHdBblXoAbw1j>|go}LeV&foau-yzG+Zy!=X<(-8wcOCeiSt|Vc=yt?gYQL&5X)Y62 zdMT1>h+p=8sCCUX<7g|g^!O$RBKojLZ1}f)Y4upu%l5^NUWVT%iZavW(yO&jnf;f` z@v+pxD=+2ZR#lRr+`qHl-(qu&y!z*4U$9Al_`OzIJHjk&b9${YoJ-5YUN6G0u4;)2 z_}j-LmzcE@7N}Qk{?0}z9kTx3M$B%fn2OHeJL$nr)ZeLnXFjcN50x_(ep-XbkY6m9 z60XvEgU<tefY0&`K1n#u2De)MRD}Q5DtLUe+HE6^>jmtqUxMp()b)&^5Iae)FfP0y z|Aukzf9d<NKSL@uy#8q?P~Cdj@|TA=Laxff&m8z>gJ1vXW^#En8>L}S`f6#)dh!(h z<gBg_5v`Q%kUip|cBDjQ%3!35+57`H(;k;zb&EFQ7|XdXHv6>4gsnU`{cTM`+G^8b z4vk-U;U7iZpGmT7y@ptYTk{45=b>-DR2u_?D0VUnQDw<osUmEYy)?_3OGLgX)a{Kd zMol^43f+i5^z#Rg81>Nl{F^0ecyh&!_b0U!I}6VLG%i7eVmF7Si5AZcV<n#}oeuEC zP*BsQZ1R|tB^X^$dsE~ZZyFCUtzo!^{@v1t;C+*}y4T3WzRQIrlo+utc*2dYWvmoD zdEp6b%-sT(ZwORu1En`!SVud62_<+lt!PzHsoOS7jCgoVZ!Nh_{<N@^C#7|s18P)N zEBoKvQBrn}$c%mHE?((<pY;B@j>>)hzRK42{N5mNC9Ktmb)9}<g_DnGV?YSs!$4y( zC~A4c&*eCt4(5nsdWmuNmmgo4ISu3R>o3f3)IrtHCLtYOinKc}sjCnlV1ll4_rcrd zLobQO704=k5K|^0?Xm*uq4QxuvD0eMm2xY@>apnacza&fcrPyI+WVGH|70(iq;4-d z1swy9E>$p6*3JD-%MT;#cjln-GFB^alr4R1SwqC~v`TB5*TwXFWPO~Ao+sg&U-hEb zMbL7!5(oejxqHw^G0*nbECH24hfn<tFX61hd^=vxmCkqbEh?E#2RJiM;(~aHcFspH zNXw8RPl?upuGf~$8WiwpdqZa)eEHnX?9R01SF$fkv+77xCor=k8V~1Sx#c|BJfiiV zu0PkrWT}6|sVfRhXZ+j8yl2bU8{=@{E+;P*h#*8=qN{ngOW7SS6ZDH5W|eU_!!>SW zQT1rfxO}-xuXOh!^A>jHj-aNO=(-hBXMq<ZjpWjSh2FeM%Fr8l7-NnveKh+<C9X*B zY2W>7bk<bVEqjugt_wLa%zhT9{?hU6NF)W!S&oW=nFu-o+UH%Ble2Z0y*uSAUVNbw z4?Y(WQd?VoTvsTjqwt=bOXRlK%Kqlw7uk!MKMpw69v8tI-E+U#UvMSmf{%tj^l?JZ znlTA(dnS!4`iqWUCHCN(aH=7R43RCfdG9g+yK!d+^GBP9WxIgIegR+mcThawoIN;d zu{<-foIAv=?5ceTcW?F=T@6zRsvUayzwTtN;8A;s(GBC+n&a(NWo*mX>j{p(<{Vk1 za*yU@Q!^tP$XumP^b=ado}RLVJ|1u{`y3i6G|>FO@Xf})C9X1kI3Q4fP4#ce5Quzz z{qWBBj|XZC#fa5QJbWx<AgDu$S0r+Bs^l)?<)j1Y#a_TvT6t&Q>i|f~t!DQ-SzKjU zGx=Si<}XU>c}>3<O-!zFo@>@JI~~e0lw?}4-<cfQ0`TY+br}`P5%<V<qeoFK!Q%B; z2}ku6o^@ueU(9?@yKrYY>`XJ;68Sv}WZ~ocX7dNP&(d^_baU@z_3a^+0&2)jqcrJh z*%t>dT<2MT2HrnCPuN{~H+|#Nl*y+~(iEbc(c^`GJE3|jp~=YZT<J;q_Dg|yce#!3 z=5GgOS>idEm1={>8ul%hE98wZH|a9w1?+mUnk#(WWCVVNN3D#Go6A`|oy=w>bGJ4E zLOeyOzJGGGO!%{VJ(JC&s`pc&y5G`tm2|TcxR^agVZIPA1yNhyQ|cK~go87y5<Xd7 zxC?kfEDt@ZZW>URWDj$sKUee0<P<HEzOF~SCnGI812l9IN3TxR-M@6OawHK!40t3D zs`x-gY{Y4nFHD|SJ}BD$Dsq;0o0$s+MI-OYUHeMT`yM%1%)O7kl4vbgUb(@#Dc9vH z<B?_7QN#DTHtJiAGg=+TCTG~UxNmdo=!0A_P!5ZuKtcO}y$Xg8a6oy17*)#xcsDpz zSk`Y@m>R^^4FY65`%YbF`vuzhSUEz(x`IvDQOt6qbTQ6Is9cSdnGVQQL_5HqXbz|e zpGtn^-)9NQ5zy4Ff1YV_=dM7Si(JFmCRJAZZl9`@YO^!(2SJF@jq&_TtkSyBnHPof zQEdFW8nVh3*^(BSJ&=6s*9?fBw4(QSi*Y*7<L;wZJP`)C;cNxhr>Qz^8xzHP*Z*<o zw)@2bfV<F0AC5#dV>1WsocHkt&ZFd|>Dn8^G%8|A&e=W!laWLo>yexGoA|&0HpS+9 zmZi#FKuFxkt1WwKA)vq7=3`y6jcpKY^ob1rIjSn>w5ygFFnJGgUE*8!W>pxKj{L6E zZYW6SD;ES5|5H6qcV<AD5?3du-Vu0E(BY8VoQ^}nbV`^g(G}S7JjbataGprm2jV!P zy>TMIalgVHf3+8;-f3D(bno<voT#^Kb^K6a04|<k%iDa#sVF%8N+ia&7e_}?W1HH~ zkp^9KY>#E&f_qj|I>vmsJ&-K|cl25(*UZrYw#pa%A-HNOdLtpgPwH|b55gtGa5d9P z)m?Z71BivgvG)9ZCLUPKW?npnDC;SP;9((Ti4Hp2k=isJkxAxsJ}97DYsw%%tpqC4 z>zl^{8=9Yrh@h*IU&RxZgw1S&xKF*Zr$esLi@dYD_gty=T#-QmP|lOKx10sm;d!op z1t);#f8<a$hytDJg1KnXjjK-MWl2TpIWE-&OEE@CF2H(0k`(2drwLl`NfELm=n;)> zN{3Gy^IzHo#i3iV>~ZE09XLSavXBq3$U{YbG7>vK^oef6u_s3~6fo>3s4!dl>L4pw z+>P@0$HSlFhhxrL9O**k?1x1K2jqO+BJ+6w-s_IG1K9t5`JA|M7#7sZ^3_)`EaVX` z_~z`{hHv5SSM(;IWI}P-QiYWd4AB`auV)MNl63rTK)*c768C`Gf3ebZXYp^N!_Olv z65xG_Vop6}iVwK8!~(=__p3HqJmP^W`klP>Rs;oU$}KmQa$~rUDPMjO{qgR7MFj*l zL0<<jF@5o!aB_HVR^VxJ_KGm?ksGp#1lbWKtBMyh${{OOjIcrelQTD=51o*+2hx$s zk-ize?h<QbGJL>~FSJv?PJf4vTE~8UlOvf!t7;0*|7lU+;lyQc#NYoPC2{KMe_9ye z_ONQBsFfF-xq6gsG|*5C0@zL}z>jGU@&F?po#)LRaGJFjZXQalz@!D3+NuF9bQX<L zVSoz`NS-Q-<D$Tc?WGBps$78Jr+XH<q<qiCboEv+6uozr@o%q2n=a%*sy2S87{C&H zdKAi=-%?|0inZ}8d-)_BY*Z5Z^7Mo#{9bq~{L~~YW$yga4G%D|=U#0N5r(3f9k=yM zq1@MmM&e@(So=ATBOVRNEO}h!-K2E`v*VvE>gu%Iky2P40<;0_5ZL6yGg6DurxmY( zPz<!Ds9`As{6-{$5sEG@<YaS#$CdCKa(K)3ui^)94{#c$L+kFD!FO4g{xqYnV))96 zkNA!A>2^|KdJ^Fb?|Tow%kf6lk_0!FPn~v=P9B#sJ-^*AV={h;lfoQTR*paE$3Jiz zK`d-tUru<2J2v2!UYOjVcSW{(-ogf~2olVSu65I{U@YMo)Hud@ewq=WQu#;(F&W3k zcXppXbpoq1N@WD14Yd1)#ro?K_w1y0w%=@PwH8IZy>qflbhI4aXC*2hh>UuWqV(sd z#xVJL;O_uyDdr5!Y`jTL({p1X_v8$Ib)C}*KA`C!GBn0`fHQ~0i80q;au4k)&`D+g z=H&F=>iCtn^}3vs60FZX9AVUo)Si3Bc2@Kh3dhGpkDLeh#WXk5c6&I!NN?Oex>L#P zC3YjzjPJIFocMU^Nk_i61DO85<>|zs@2lLGNr<{l3^I2g<=gyFOlh<-FTBme84coH z)3j(~&QxnbSS_;9X=w=8e$);+F&!o4^$E%}xjV-429{EeEszDSITg$ylfq$dwqWxW zk6PHSb`3lnmplT&*=S^RwfqQ?lruLGJ8~}VQj(``rd`>fom5n?ZD_WDMaGuV*%*ZY zvMcrZ^JO28wN~1_?0)+W%arqOQ~@Hmm$jQ&nOA6adFfZ59%Cto7~~cxSl^QH>YuTF zv*Ng}_hTN1gF6ZN2y~F6ATRn_i_vjQBa1&}Bo^A)C52ZF`!RKAZTg4`J>hRQviFBb zl?9y>^rKe?U3zCX1kGtSS_nKTUzUzi!my=ea^6YxdGCa{d{yr<7rT9DfjOARqJ?U! z@i{ZV$g0)dEJdPchegi~@qDx2m4XUad4e*;aReenEZ@P#^tJ0n)T;dc&1WVAsbNI% zBP?Xwv|9i$D2;C~OZdwS8!1IkSec?VbqK@PS`{iAEsb4W7+zCl&P=<}DaLId->?}1 zBtQgckG7{4pG)=b7@)jI(#P#PaF^bw?NZNm8u1PD1l0Cn_DVlfkz22-|J|>BJe~M; zwfW>Tv*5omkVIhtpD14;i1E$YhUY=s2;(gwK;jew)>`Xxgq!KrftHLIG+bXy+h*1O z7sfT3@y?N*Z<-)+{w0Mmf^!mwU%ApF6?vdNBKE`}RG^);;)ZSjT0GFg@>GxlCpUgt zzaKSCMqJo3Ia8=4F+5z16#v?)O#?^VWHWlM)-A<!sJ9Gt3xHv+d2%Ls%Y+P}SyCP% z&0xJvrm1|7?tG7$0??JIZ-|9FZP!0p){w=tR2nGrOco*=saDO55gZYYK7AFT-|#uJ z%ii>D&l?RgM|x;ZoZy7Kj3#BWVT;65ukA!8wcMD`9M`o-Jm878Jzi!GM-uS=J+fGW zT5dh(d-E7NtU;SwPQYF34Lztx6$<CNox%gX+g^8M^-L6-kT7`-Z6-vWJ=Zo_E(1OB z!@v9Ug%iCuWiLI#+VLdE0$;IT9)IlonR>(_`MR1bHU~>VlEr8{EG33F;gY75E;Hj? zZ82qf=oS7(#%%>1;i~H&uaklbw(Juh<cGJ!qYr+%OtieIP%W?(n^(z`U;ftJ($MkH zWk2C+$ldp@ondoESRI*Z)Zr@|Q378p>vcqJTu}vw%A^;982Kw(cd0|@o~maS2_y1B zWhhV2|Khp#AB48nVzE;iG34`S0mM?G@G|SoT#BHl5A5ksxJA71*bsW`mp2w8=hOoA zS%!tSoOu*>t03<dUvD&oLTa130#S`Qv1coLl!=^p2vSqwQ~?9<t~i(4g!)WwRW&Y+ zP!Mj$O^u*?zz3~?083giU`M3R9KRAxNYGiY&m{JC8%1o>z1SG3t&Oah(^DjRMEA0u z8h{$v-u!qDPG1g1*x6gn&~aA+^X=e6l~%0%;U?0kl-Gi)VR|J(tSeH{p9jtW<X~+R z&oUpH+m5cOKgoTHX1e1K)<zndnBpQpgitOBCBbzh<%zT8R{+@F!60C2%6<x(5a9aU zb^Lb>pB*yUQ?+vbOe;?Dv_Npw2pM6g_^AJ;jGd#Akp+E+#ljXAu%morAB5>rOv}HP zql%VxhDD>{{i=@Y+SY94X`Dyp!X(~c`Wh?<4RumUhIl4J%1C@Gx<U@f#oXK0LZ-I) zF^Djb8<Xp)e}<r$r0OnrSSYC7B#sRVJY0p8?W#J<knR(0x}2OE=J~@n$<4UXNGX%) zj<guKSj)OqdKmn=t#1MV|8Xraj_#8`kJ^%?rc;tW4m$)ms=z?$m*)I#*rBw{gsow& zPUr})P?q1UK#U`je??ceGFXiTD4<<t*j<Kpfx_BSgg)h7P7;>uXBS=<A|Rm#XdUSS zWRNM+$w_pgiv;rweuQyq=0Ep|mLEBb>Ynj)d}H;_CyCCChs<Pa(69L$d-(cf-|!cX z-(dy3U@U8>@uR$;SfQMBIYmf@onT*l=0$V8&Im*q%r%bG@sI|aQf<mG>%pOf+rd3? zrk_~y`pt^7r#MyZj;Wk^xLrA`eBt{)U`p9M9tFsYE!JVUs5xx|&fGihJYq5!ICc3X zsP*Ix|2w8S*%%|?br?LBeE#xI7Q8=p?G=CV?ZUc%h|@DUK4_>#D2peM_UD|dX+G`w zrqDgoab;{mTP^W~8S?8Scd$z_uX))8GvpZ(QiE`XCBrFtRMo2G_Mr^Vzh601Nj&j& zJf|h~xNo})`|9OuX~eG?7w3kuIiRiq@NhzUG?TS(Q)r2X*5nHu&b*uFZ&3Y^Wk;BN zddxll2op>T3z(7CJI=H^e@gvRBNX@MEHVRjZ4N17kn8)21~8l+qB4XIkT9pROJmhv zt9kgAy`XjqQUzwtc?#HG1r)9bjYXxYvsC$*M{22Zvt+sVmK10qD~+s!rQm1L(E+w9 z!2_W=8Rv2evvR|Zk4d8Jjj?55EuM#!2OE6fS6En;#nTq%Oh^aDYNX_C+zVmO=!UBz z0SjlbP`hgTPQufNtUo4W&W%*}nwQm)*f2YBBJKVd^($Cm(|u!Pg^3Mpsw&u2xZrAZ zrO(9~W8p?<g%Xh!*1=kdyPF|ccw;$#^jF1*S6wte?{>GJ{?C(Ca<c_LuS4`b!jV9z zs;Bv_m|GW+ES^l5$K<_#LnaOLRgbAK2NjroTxORXs=8AI(cS=g0KyR1=-Kjp^$!M; z66OdY140ytYE3n7wFx$0yz3T#EGb}RsdO}dm0w;fm2Ag`LJ*@anpjg?SV^|fT7I#; z7-4u`6#I-HTTLje*Z2k+ZqLJdsT39Lla*K)AK@tcCrRkm+nlejFcxSi!mLR3JCf~r z%Y7mNL8Ls&Lvpb}-h`?_F=e9coloJ%;YN}6ni#a1JOK!aO7_gyxb^Qh@;?C^j6Dxu z#;pPq&nl_3e~`AEK9>16sQO4fsRz(?xHh|2R`*&sso_rSCMul3x_$(QuduaegXH+s zVk2auvOR<IhDm~DLNBzDPGqP>91P(i%;DOBsf0eUh~Y>;vdgPMg}{6}&__a@qZVaU z7S<>|T}0UJlCUB(`>r}!b43frwCqKtn1Fs(6VB;E_tHlxb$5Q7w~u~&gve+&c7mx3 zo>^}ft~W$Jeo%=2t}YCEY_y4StAS}xK5P`??bahLY!tsYMvBh)duj_GF&>P4W`-0z zIE_?S%7~d5>pbd2#y(0to)vgkQjMM61$>`LV3HF8&mbYJMRSE`ccd0{HJ*3mUzF+Z zQtv<Mg5okbe;pYe-ojG&IUgT%X7?Sx{S``nUTgCfhNJ>1IZAYmMZlmMq{ZB#u_PoT ztQzvbt!Fxcdwg)vj1>c1!5Rpk@K%@1Mow*+1h^HoebVI(6LvEb)_A89xeWX7IdqZV zq<l;0z1}dF`f%X`7Tqlv!6FKac@}0=`_^1l)GnWrBz2<ip>+#%roIKsBPu!rebN9m zW0*Y>%ur$wMO(m?Xn*GXU`=X9tBJ@96)3NznGywgk*+%-M;bN7f-5s!T86v=gauc+ zdsj2}T;--ZSX|>EMk-nRZ}}5AOs>j4bmzHsDYTnPlq2aUre6|%6Ud_wNt4;rZPkU4 zki52TgeRgp>EAPM(_kM}xcidEzAdEu0aABDS*4E9W5-5)Z=sA4|53qQ^~d0b<JOtU ze59;yn%sFIi4~R$q2ubW&&w#vVR)vvCmb6i&!`L6H(Z&D<X0U!S#W8``?o`zk|*Yl zYe||SO}$USoCC0)yk&1oSR5KPi-VfP*~n%R&}PW89&pWa!&kJ|j^eBD+aawdxs0*8 zr^|`Z2QRB<M4q}LZ2;I_Ws3v4fuhjGJ3FBpb?ec}tb`ql_A*%gV!n`RY%WMu^hRHX zD2nfi-6bZAliyUlU0ZnSWLwVkj9H25_lHVlFbX?BT864GLvs!X9=~RA2}4iE&0sy{ z6@a173oi_;-Ut+^sZMiek{kD9I{`u@@u;<Qik}1-Z*g)TeK>o${n2a=k)_F<B_x!E zgk*T^@T4gW2aEI4>)tu(ghu+DiHytfQ4;cDt!nt2nOt!%+R$};^LCSeDG&!yZ)t(} zNOi3Sn;=bPrXlJTSe|+RitUE@vv1ZGQ@-YMAE|KJ?!=i-lw!*|l~lb)WoJ3qMPomi zO$5_!)GxT#<p?A~)}1loBO_v}&t_}i&0Q0|-Omz+WF(}T+@(CMgb(v|yfx+MfZC15 z2ScsNi%P1{w-bvP-qy%bxytVy>uIaaGG6Zc+()5ok)vR!X{7u##CG1cHVazFQGO$( zhG#Y}Kb)2ZVG(YHX1c*1@UsXVt!9Rw74k|f89Mb$*yx$VlH<y&r*y~%*c4A%LwT~L z@PUQhi}}|wdu#3>m^B%y+A@Gh)|FX>oKm@>MSx%|kb+Eb&E#rz@#^)vaYQArot==6 zrM+x8dCibK3Jt3M<?;7ZB>KdappoYYV%G(kQcqhJCl%Q6;XO|V4{h{AVQ+a^`b2J2 zehxcp+P2UGhsnPs$kyizPs^X*kn7U<F<`Yba7-&VCPT&J7po-Y!<z|egvdJ2lnZf@ z+<dQMo3|}HS1103K!|xb2qZ;ojqSkAATF<XTvdDqdU9>^*56|B?fb4OFjZUVkuGxc zrqJ8uExw9!YW=-0cae%mBGw=m4ENnFJ6vMSVhy>5r1)teH%uMR2|P;w%qo>qZjV$` zQ7h#D%KO3H%MClFI-^gw1)oJK-1Sl=b&B79DL)BT%xsiXQ%|+3uFlHib7nd&qFfeh zT;pKcaS)Fd*n>By!@x-)l&44;X7<n5lJ8w^pJ5)MLiV#GhX>s-$`kp=3#Qr|*j3cu zj<rVt&|~I2C$9Ar19Fnlp#qF4w17Q1fF=`vq07I7-)}4Y3pqk^Xd%rMfL%$+Z8422 zxD(Iw9kE@lYd2Gd&TuuzHo#QlAaLo@WY2y4N_UlW@;On(R57R1w}c-NS=^9}6FiA2 zik?c}pC2~uH66_iW&VoBW~iU+XLuzys4qiw7*0C2I)7;|8CD>zQjR}64Hqx}-Ok;f zc>4Wlnahm;x_sjIOnRqdCqyjyXL-rxv3XRRxhVI_kTVjZN=PqTAM*G(lHKv=zqK=O z>L>KM+a9g3^jhtm;az!sK7g(uGNEK+6*~mA>ktn)IN><s6ZliU@24FcI5VAr>-{^y zg#@5nQqGghL>hu0?=wHSVnFA?Sywtwts12YYX*+zU0&+BxdRllJNovspcEb3Rs0Q( zjXne_hoPEnk`=`Y(9bAGJ|`%;c4+gcK@u4_*W<FM5x%%dni~+B!M1EcQUUkUSL7L= zUpI3cz0Ah^fPE4MTtKOwdbYuR4O|WQakZ9af}#Wbm)Jg(z*_=@V8u{SIFe79?_DX8 zQN`rO9K+aub9+3C1$0B!7vB81I9X<NN7_AR)o-G};rHib3x-nE+E=bv4hX?J4~T_x zs11~6_Qt~w#AOqdm#P3icoM}siMPtdk2~_fF`&Ob>;ZLU=|818wTrpSldCw({6;T< zz<WhIF}+H&Up!vP^(^x&5o4K^-@!1pcR(B^f$FzxjJ~?_Nml)pWyB5<E}0!lViR`@ zB~nfw&_y*D{#-1+2bcyV2!MNnOGSaW0BL|hz#@uS*c#C?0OJKh(u?k?L)kj&TdhHI zCVzWEq3hSm*K3GKrq*~lQ#mNjnY-9psEGa3Ka82_(zSF4xbdO0qaCYA2sxE@L~2PR zP>S<$d{G;ej}<Hm?LVybf4qvYVLbyT-@Q5%P{|YZPjv{LOJ;!LjM%|motX4%52UGJ z$T*^;I^T;$+#5-Pe*z{g?o+GTt>ll}nOE7*x?ahd{gI0-?{Ug1Hpfb4Irw*=S+O~o zRlZ$LIyH#lX*W1|xC}#`o(JN{fKZL#RYJLg=IOTCDA$n39~=y#w1d{~-i$I^r6K`m z5Fj9-r+ShayTb_xc{_sHWTAz}Z?KY3FE+&<Xz6Q@>u$2IC6$koE!aOUN0`<=T5Ze3 zICL&pEI<8M_#Lh4N$s?Yn&kw+0NMP$qMII<pthGje*fj0@0}a%m+bucW5und6+hdn z2f{`yk+Ab+i-723P7lh4Q6If3?HV{)_}8KxTs9^~_r08o#Qr%^+%#!5f#G9XtK7Hm zm?F>D>SRhqTAOyi>9Uq}7G|x#iWy>Sop1;6&e&|?qfZIQsHG`}-vIBq*zb8Cdp}l$ z&iYH8xF=|JHQ@?Ok<OAANgq`)rTo2fL9+NJsYd27vpn#^!>HQT_@}vxUur9-y^@8J zh2EhR-{X&?YcRF1tKDDPE|*5bcEvEc$JAShOzxi_V!bOz8v4FNZLe=$|N6IB=3|K{ z<>NgY0t+F5V#!C303v}^x@gS)w*+Bx){qwAdlGo;qv+S=zY|q_qilHKf}wHoCwL}3 z+t<VmsjPtVPv`|5)se+ambilLYF6FJ-eG8Kr$Ebb$Im_!7LIJ<2-pl=^!8+T-|wUE z^@skTFRTL$1f{kPHmobaITi^)_YIu+QPlevK+92`LvMk5U+*NxBjZLnqfT`{cL(Um zGX0CkLoL~`9W7pM`TZ*5PfnP0SJn(dN*k&Jz6sr}RRsY7Cl-n(&HW*c%LeM-Mvy09 z)KjsWJh$Ved@zrHXB4FwaHd2OB}EA!K0-L`DEWLgcQ7+waPOnaoy;V{j)7dvijTL= z9>4I9aO4S$RO(R$y8xHAisJz{2BAMvJ7UU+{UYT(ED1-wr4zk4E8}I#K_g@!emr9b ztmSOv*K(0@QN+G*rc!!B;y2gTmU!_u`iUa8lX2{&X!js2JVZY){=+Bf{7mz{#q51S z_tjRkwT9^t+Fo4gaPyW?SRcwcDUTH;<#^hT&I~W;?nX!_eT5QsS-@E|F?An^%ZB_O z{fYlshYHaTwH=|=eZzl}kSDtcMDu~#pPJG};5WUZXRaEad^<s<l)bYKH`D)Tr^s%h z(r5S7na5Sj@RBXTUteMVdHi<u4Me~ZUy<5xMMrI3fV%DP)U>76up!3)|4Ce{lwn-t zq2p2lv!{Z{()^r;mIl|R>_m6lXD70-cBx(-saRNC@D~|7KBo(sRT*TSi^dh(RmzDB zeF0+R4c3(+g83MWCtOP1aU#&S=99_uuV$Jri=lwIZ26T_L$TmbZs)nFCvY7<LgK}J zw+_P{iglsvhml|<V!ZO}v-RkqOErs(i^vn#@Fj>|F~sykij2>y*wIK(M9E(_eHVjM zz%_vlq}N>47NPF3ClBg9Lab=V9@ElP<B`5bt6d>nLzaCck}W)#^FG<%BByvLF37<b z8CqK?VPZ8XZj5k_36TyBI3laUP}k177yKn#NOTvGJ$CYxbVu~q?H!^8K59Gc2(o$Y zG?cPkLGupmgihBEy%)P*Vj8sB6V-O&!w1ePPQOw3IR^Qkfb+24MwqcIJ7C@->wavo z_2!v|&{@=@GwPF2y{?RXE$D^)zU=fvC!SsW`pw4=Ly25^S#b8>hAee!#B2g$jKfgs zlwU;AVk&ZWxnC&6_C4V(uGCok(t~~_)622(hPMBVF~7d2Tqs0B__Db!ScQUv5Ee*- zlV!Cm(UGK>OBV)=^V{)Lm*brKI<xX+nU|%n)LB^}&zXXTA&916K20P;SgB4>(KOF4 z$djqj3%4uk-J(ezdC0O$k6k!GRe2>76ARC#r_72Hjh&Gw(-r>h$u&Ql8^J-m&YI)@ z4eM+Itv&)eH(Hw43HU##!EU~2O99gxg46Hz!GG29^=4LL$E;_jossBvsfEu3l1FWx z^=fJAz1CwI3b*qeM@<${pB4&xEV_4{uj$~Q)mz&BvdT^CxA)$aK(F4BUjGsz+r(NP zK-o@wDVTUA-e{y*G%pmQL66s*>)D`vbo-cV^~Q+jRjBYtY;k+WW-90Iw*`MejOcJ@ zzJ9=kcn#q?em`$f?uNN)(IFK!9`&}%k`R}ZfmVhr1UUM1gsyYHCgjie7mNR*(!4IA zzqSlvOH0SOk9K~)S<fbx+_@P>m%oChvRcg~C44&>c&LKV`Ax)!JQe6th!C6y*jsFq zf*VV|gno?us8h(Dp`Rt*TiVZK8u|+<r5*8*XT(3n4Ef*bcGlCSPl&e7MQ>$te$i~A z4K{?XQ#YfZLCkjAY_SQagyP@cf&wp29mQ_i@SeCdw5bzBWR-0RfYb?&JXfGDR!R7D zB^!nRnXtL}W6kOr`E}7BkMu{PMee=8emwp~1_|hbNCe-xdGsH5|EC#_4H0-?EmVm? zS<BRpM=D6_!C(K-ec|8pS)?tDmp=0O>6Ou9<cJ<m8AxfLc7L^geE!*y0+DyS_7*uY z#5qCjnE$+bT|g}U%x7#HivfLVD^;|S__m7)^KNO?LtHVVsyQcw?I7cqpYd9fa8SZ_ zU1}IJL5~TBRyMavQpTgTPKZ67`|<e2GD)abwdTAaSPtJ}-y$aj{rmUsneeB$AcK=q zQnPWaL1w)n=;KdtFtjHwQ~oh>gmgB7gFR9ZpG_YQ6%<vc@2?R~aezefsoLm-K%j*J zJgLike6q*TGO{cdDW#Rl=^aPY%cji4cV))hg|?CO*tJ<CYaI7ZCxpstc@9!S1y1QB zP@5E)WvbzF0(L+ifFmfj3`;R%FPcHIs3wJ+8176o1t5ycZ5KZk`Hy4#T{YvijgEMP z>6nPzr=NzFEx>a7;NzV`v=ak`>9^?87K+AEK_-HQPrb#Mk3`|VgakVPs=Z8=BY@G` z(z$ewmoXAt8gR-w6A7n`WKqye1$-QY5C?VNSKg4MM>?vbB27}qO%0|ciyx<^l7?fQ z^`eB5{x+}#wy=0#OQ2qZxwYI5yfzvjl=xS4bi=?np7HoU15(<8+1*CzAT=={%Ot*t zK32<-*IRwp(!A=G>Z5n{^icEB^X7HM=Jk!{4L#<K<K|5Z=FQvY_YcimI4mBBS+puz zwCP*4TUtDHv*-x2=!~`KO0{@YY|-6l@wmsLXWZh+g2mHqi)V)xOb*Lmy<(PqikAKQ zmIIcSgKm~XL6*a@mLsW_qs5kEjh4@QEXT(!Cl)MUY+JrOw4CIyni8{`R<xSYw|Zr1 zHS1<I7i9H1)@nZ0>P@lL+eWK*Jyr|jR*MT(OAEESpRAT6F@^^t%Zk=(m5h6liR+g1 z^~2Hl2+qy%Gp7r!0m9g3B<EJK^@N^vs}F>x4bcK@zVE%D3fcVNu-VhM`JqqW<9JE) zxB0FJ-;cD3&$nqu!~crW4;yWO9qS`Lcstzozik^Z3;^*@9yr?2=578sPC^r2!cM*X zR{S#F)@E1HhOKFmW6&0%31=^v{OM!E>TB~54hJxQpfEK602E;WD{vjGcC7v%0U)@T zX-jEuJe+d~M35`%Pee+Z7yrN7S%YLTv)0PdETJ$LL(NInu{;&;v0}5f>WL!lh^+;= zwxV8h7C|FJsZaoP*ECDseXPB1rpES+#Qc2!Y6A>a7MC>ku;KOnV~&k@1J6i52+U5D zQn|8xqBV4Fti+<Td9h9O9^b3$o%i4WkE62;YwCUD_+e}?MxD{A8{JaU;szUxZlznK zR76BnRARswHA-nIrIi*CbihEmI|LCC5ta0Zit^|BzdNs=^IXq4&wbzD&*yCfJ@bY@ z;kVUp5~r-|P}XWBJpyhJy3|ttX)sIWmM{naS4Z<N2AnZ#Yy2`<Zd2tt+}8AUw$^K~ z!0dJNx5buQU*8YEe)VI88qIvxyuD@jV_&+g+emxs{^zk0lc(k#ZHHgy8Uj{EI_^e) zKef)DoV9q<{%e18vdV3AABYy){x~RkL&F=W-rxWFvX$jIy?`Jc0c0_xTa8r|C~8`X zVwqVtz&!vPVS@DY%45<ny82WVC)LdlanJ`Jkizt=%Ah=FM<!?~bQ`{wpqSH0#>ny8 zKGlaHh-a}5gabT3yFAxN3N9HJDF<aO?3QHb&H`a{Bs7J@)T-o=YOl~DYEU+0Pm!Hx z$>^6HP-MdJxbU2s2H~k`pK@<pkLQ2|=Y)voDdiM?E(rhGDhWttDT2^25gMk5bX`@i zm`fO8m7i#E&yoSj#YOk*v2~^2v$X$PXJZAXizsCOt%~yJm0OUbx~;9M+TN3a%F4zW z|F1PI8<hdqnSimcFR04D18VDqe-B=yNeF(?9#AtWl~|_gQ?y4eRXr`4@u~XOyab6m z%M4A$fNsk(8{#g^sv%npYmdJwged~3XpB4y^g0}H1|oRg38{|01}+*#vp{-f!Io8q z>YdwaaMjv&`sn})8}sG7JQK!G8ZSF|?zB7GaWPNTVgv_ecM;GJ_bqjQg>464*F8`S zPKHh=1a$!vpl48L)L<8+&%W{)!<BLjj&K2mMx)A^0|%E4K`7A#P46B(ex7~|GC&`* zx;7~$T^o_^ek<mt9!7L3sQ+L=XN(azwpJssKx<>T?ptDhE}3SZJi~Ev9a>If_nT2l zSZz)s`wFixNJXEtbVW=ie&xcgf%pfO(}7Rr#uy;;BG*3g#DIWEXI^)6g}ST3FN`r) z29yI}LDI(TF0xo94O9*ye{lQNcS#vnQ<GU733Sx25Hl4{F$TIvl-RRq2V^XAT$hr2 zrgLpvQV@#i<hPPvK5(U{W5aAi>fFFFOctyjyDMM{&QODI3}f18Q#*_V)ai|OHTuyQ z8enNjHx#N>&!DcciAF-8O2t%?d(6H2s56G%SP`I*Ai|wUkYGzEN~4m`Sy-OME~#q| zvz9X2<@T)wp06@=@dnU1c*NFBJRO5O<7az1$cdW>Qv&rWDy|qb4F61F2wn#{<3XU5 zk3*6N>cq>$02pW>i&5(&cFoJ?8F5{QMl^B0lI*`MYY0!fZ_#|3f_MUkEC-EH!MHOr z#cm=slZni5KQDYWiQ~%!qO$-}4DkI4zQ1`+WP_f%I>PrvIx7ejZ}S0534#{Ro1=6| zMc5Vt%6JhuoW7_Sqg#m2+Wx?DAJZin&KChdu_@u(aG@i0aNlf9q`W#_=6pRPX$+kO z;rB7nBEb?=#Q=1K7l8=rdl8`|_Ed}{)x-c;^ORm`HqJ40d;%^Qp@B?3)K!0@=v&*! z1SnceuhOq1@d&EaO*?BKw0feOwscEzNU%?wE<*G0&;~^qa|Ok^&bQEEQlFRFu~~2c zX1;VllNbPFpu$4o$O2R=yMa4ZqODP(&>8E8ZP$3>!{J@%?TproXtvbcnnaPHpPOy( zfsD2x5%=2x?SaUoTee>G^sCZlJc{F+mJxXmtvpf`9Kk1SxVsve!q{RTo?JZ^&o~p3 zdDS!9sHtz9J%8d@Ak+jpWhx!&Sz&(8Z)95+Q!4#9#O}TrB@zLx0)W6j(BR>?3>F3r z&OR}=3HImHHQ-FGf%qk41X`{{(MDSKi(XpGONaF|%T?x8HpE%p-XXLHH@tqJIigK| z?JSy)s?jye%6EdYY{+G0y6_4!9d&T25Skk02Ad#C2sNS<vc<5M7$aCQQI1!t1bJr! z03DPF;Hc5_pf+l8$;aCs2(migwCWJ)9r@A@4;MMl1jL*oMZ{HvuzXC-bW`%sWs079 zZ)XI(9MJwglZkhe|9w=(9k&f(k{vxW@~7XAnEhc#J%K;<{ZnR~+fv;y4qz1+g;Lz+ zzVW;<c)zlBh<*aCb~VtZm<y;iG4Kaay)yxb2DR)IOCHBs9C7AP%eyn*MS(5=dGB8{ zYSSf%%ouf<=+EZ$+qp!aQSU<m+MQ1QO%gp=e<hN3C~6<V)%?a;5Jl)mITcy!g_(er z3P&f;*uIqgj3{(YqocZu0m4A#P-EI~LTibG7k0r8%*@2WAbz|>OvR9!=LLY2SV9TX z>`N4CVL~jdu|>JVml$+!;wjtta>M*D@y-Gh#T%-XqJO7r;7|gfv5%V@5(Q4<u{Zuz z>93}%U6fd7`lHYDG&+&L^SuM=XZKUKAr4}>-}TThHg23bED_Rt+Ot<H&)dxpEz&cW z>N7IzV&8xa3gF#7h~|H0INY;yErP&zpZ{Ld0ey7r-ptNmDu-44ki)CinP%O-Am-q) z7-MDcz<r52lM<E^@k`#o4qXFXVe3OZkE>Y?hg{W_u!GQC)S*NzrW6;O#tzL4Jb_Cn zFH`pznfy@9=+q%zjyN{mbvCe_UO12q;P|_@0UWhrLq~2!%^iP&pvMRA@W;7WZ?gP7 z)5q5f1}L=%0GH49MZBv*;?7(~-F`lckwVe?Ti*SUG(W&_2?OCFBwo{_7vNYefgbVk z2HlH{s$*KSK8XFV58b83M@7YU(MN1as*^aRX$*+Y$WI6~e1Z;DTD(Zy#HVzxvqIur zbo*G7&cZ*kLc}Tu@1gv4`|$U_`o!1rwkl3VvTi2)oS7?R)GrD1h?k}08`0HvA8M~Q znS)ht+gPl4;Zt<r@5t>v6!YCT7}aygJjsseIY}*i(8z-#ZRq~kkG>QB0ma+2cLIkD zBUN|~Nk^557wHU)n7-hHodsC~f|z|L!jZakrp3F+u<(N0>}4t}h~3J}UqZa^RXA)s z95Q}4?Z04E$w+qetyOjKJ|(gT2hMzcz*!V2kacV3Dkp}+bmJ8_RLzs8NT-)an=w-j zJ`Op&`iLB<5~L35qapx6V;dGOBpD9hg*p7^AAct}sSL;NiGtVNy>JKQ>ANM`7r8w9 zK%6cLQgrKb3-SDA(3AigLxKLwpr`vo8n5e7EVAej4?$i8d6C~0162t;DjB|jVl;i7 zrDDtd_=Y=hw5xA3w{>v@vo9$18O)b_F!`CNd?&_+FGTQ!#C3nig!kw{+JB%C{M2I- zfEEc}`RNp%84!iPX0>nRaYykcoNq=nR9qDGPZCtX-GNAg_CZDuu7XerqP`Sp%Xqu< zAch?dkd6|N9=9|lkv$oa&~e6rbsqRGqfA;N5Rr)d5ZPM_=DZ4FM8?L&osOXpoma0t zynGGT8E4J_?5cy0B%&cV>7qi(H<1vg1}#lRBX%`=WZgZGjzNzAdY|G1f*Afvfzs-r zQCNJu)ZLJXkT48mSOgfhLt&k#RH)*C)kNrSqV!rKp93eebn4{QyQ92`u3-#Z6Dg6t z;Qmk0c*EL0MpMB)8M{ia9Yp_~kMCaR`G6Cg+bu);ulx6c9$))X7R98*aK$pC?=skV za5q&QeEcpF%Nqlwi{fud6!b`i?ea{~BX3~wwhrI~A!$MVf$34q8#sV(P4eDMiogXx zcAXTjfH@gZ1zR#hCz}d1?)*IWuJSpxS~H%=Yggbmdenn)cac+1LYU|>A?VEeilzgN zsSdw5M)<NTN=;MjLD805@XlK<Swxod@I{hO)E6fPUoh&K-uAxt-epi3<#v~!CpiL) z*wFiVI{1Q2?tYcBL<)<MzQ+c?s~8tzdSt@C`JjiE$yk*72$Ri22Os&BH+mN-=m&O- zC8ZEzn2NHgz99Qv%z{1GI`^3I<b!p0=1nO2iJyv*V6;6W(&}Y4SH%-e9ckn+S2Fue zpN@)n*l8~#EDNp_)w3QcSf0pGl!{b>OK@<GI27I(FB~#T1(mSxXJa7a`AkLeUhZKG zAFi?8%rV|cgMJ8jt^qp4Kl#zh843sV_X9x>yPtjuB}U-WFEI>zsL{_)GoECTTeCR( z3n@kyBp`4mfl{%1g>Wq-lRv1xkO)WPpYSK?zl*UprWoG^f5$(}>w65JF>SC1wLhji zi$8kk0PX`WlKz}KwHgDK;5R<~!_%GEc;}q)4bUozF_M@`h<705TdSI0k_N|^fGPcK zBLv`&MaBVmfKqO7k^_#!7c%GMJu=R>;tvtqE1kV8t}0V<S)gPk^v2d5aQ$?h)KN>S z;E8wf)f`UIkMy7Ib4zlN`3nihOt+?alTtTNUt_+QRyliQp@cO&rttIu-b;qZ8&}iQ z;pGm&E=Mp<28;&FBXW>SaTOQJ@)wOL*<s)ZqZ~x2U7G|FGLfSw0amtEigvO=JbW1< zm9P}G*Ow#cp15;kZ|BQU@;-w-@MoC|Su6`x4%wOG{$L!2t5*gbzQ<|gSl)3jlM#u| zBIk3^<z@MTq&q&lzbXh439dQ1&`78v2`oLx-!kUV9y61<56Y6kcooZsF|OT=99#l* z^e6XDxs9Oz&C*z{>H#t`o&pEPs+j~E4ele!mF50L<vIZ%J0eMkTt!EYvB@d1btKZ$ z1=RCAT{W;fvX6LD$~(ni9Kz%wDa$GK(M%Oo_ECb$ZGjJAVR;&$b<|5`V-U^6$dUCx zd!Yo9+hFmvVF-cL(?;s0f(eus7a|z_x_r#BHp)1gT>x!MtTB*$JW@vdT^YVE39c+W z7Ls|v_`$u<8?2EA5qFx=Xs<zWWdqKa4tUFO#uuC(uL_O8Cxly?mH8pm2MkuGk1+U) z#vt`x`S`tBHe@60W=otCXUt&BfN?dO_JvfV*0+Ko?8vm7!PDcmwcyholM{*8oLH5$ z;&YXP9DgzLpD|#3Q?o`Gw2`SSXdv!q1x!T!mBe6-)8;KOBr)rEBGDL}+OLLomc#36 zM{~KzvLMqo=wHOcjHsR*EVEsI%@j#ukS<xL7kk0;G+^H8+`SxaIIz<h(6Vp$*@WXu zLLgh@eSLa^Fv+)!N@b`g5n$@;%&Q?9S6lh`vyCdzJ+I3d0zrdZxNB*<%Q%(Q6m*5+ zIdwX(Bio?@&p50ezX}Ksn5pZ8J)uX}FW73z(F4`5IprtWf4M(LP9{Gy?t<6dk!(K4 z%iXrfcl*kG2<b~kE8-b-uxjES_^zr}76yza(D**UW5fIEq>=F_+sOD@DlxFu@}NP_ zvE0EgwHwz2N2e8E2KlwcIhBH-v#yXj%PYBEBAt+cQhKh2-ge%E!?q%Zq9UL8ChlF* z1iXl?u5?hV5$D{(wA7BQ>*J=o0K*Q6(hao_(ID7r*kU8xqcx8|Z;9OWYvHzvcrM32 z9Xh)AxhWD|3yGh8;`O_(j_eNODe)=~@34;)ntR<p$4IR**461WxepS;8v#lSvko%W zl;f`s*y{{-<+Z0cQyFSX!NHe*@4Z`eEaKP6;-GueCIRDDj~KlDVwnZ0vMydBsEV{2 zfnnX7?}H2#{d0eAJ$3>O2O7F%Xv_(qUft+#79j3K4x|K4YVVFh#z*Oskj73Tu?z3m zt@6$8Qb26%($S4Cw~@uA$q*|x{%@cb9<gyBw4;O8-Ul}{krj+$zx{e_^FU;=NV--( z+x>Fp+}b~;Aah<{U*Hhk1rU!Lx;c!4pqaw*XT!dM8p6m2e@C?*fPK|N(7J|6a)VY| zS>DwNNygjxUt9gvJPm*P$Z2#jDAk{z9Jew9edOd*yr;oBl}3%A_s!fd)F!fr=H?a? zW%O$NQh9JDG`8`{$On@e!n460v#6rQp2S6l@mcNVNfw<sdMp=(8L-UDGWVTg!s-&f zfj5M%x-1#BUVic77v10e*xZh*OT)N|lcoX2BBR2g%c2_&yLTUx%UWFsj5dQM-q%vc zrOW$VK$<_zAQ3)bvh+)CjOoK79?Fpcu7+L%xAs=<Tx(%RbK%CROpEU<oGKi$CRm3% zcuk00<2TO)<c5!1DBzS5X^`)2%N$B0_t5r&W%qtE-0(LD<4o;#{qoXUwSC9|er|XM zQnW&koCC~;PL{zF7pBZrZF)8iIgwRHk5zy&%k*IeELus;6M5CX@OTsSV;U^#h<<lF zSu^;BSM>`myJ<HVO3RYG<+XO^zPDRRZe8pGx6JUU+$YF*VU1aKoEGh9n5tJbIurob zeStT#F5MqqJPlXtKSW~8!MGDwFrIBa{vSwZ4!)5eikDmZGrWqCU&*MJ;D`)K_z&DQ za$TG6RsPh2vjMNu10}WdE(%Bs#b!=A5`lGwMIL#}ydB#yq#scICh#MD-3+kvnFY&q zdh6=GzRo_r89gGB_+ooV0Ze$aJ@#gM#MK)5aQ4FYQ~Kc&(?gKiq}1~ovhY<a_xmKl z1kYyvdP8~uUC=e548QmMJcB+xYxjT?%Rom@QA}LeLiwwP@3)>*7~At_kIJ<4$oH9q ze`L49^_YXKyPJZM+t4DW)DTdd`x_T>9TvGx7+GOYrCt<lCH;L0E2`mM_~P&t$r}fj z>YxH>_{v=N?_WauPGY8cZhGH(z42>+p>=TVI2XL7ON9+pGcymxFMh83vdEIUjd9&% z`>@B9%4GiI0D0Dk<Af8Vq-S~V5NWk}GwI;xar@aH-?;k|8L>%=CLegQ-A>CK*Z9sc z-J)|=jobR&2#DOw$_HKiM<V<C8`}H1>i4t!V%R=Zb+!$ieY?VFHL1qRgg6JXT?8l0 zL1)_LS*t^1uU{g#UGUL%^uMocb?}VjBX(pblM9l^1iYMcTV&Sh5`H|_JGtz<vf@~> zq;}kq$UZ$%`Q;YUX?Kb3T9p~!QOQMW%nk7To5{DrV^PVQ6gO+jbKofZUtXnM7<zXm z<rnXd?fIt%Y9}s8#*+ojsxMjm!|>gFcZ@|9d&a>QsAZ|R)$;wSakZ4F@4<IaRcNr| z?rZjIAx{uZr+fqI*+>9jk|ToDqNsSNma}cpI4uf>cFBNZCVHbXWe^8aiZ*@Z9NmZ8 z8TB@uncPl1$F{qZLz(9-9;z~7CP(r#n0*F9Y<%&_`ogR=eLL%gSO}9y4IiU_r!wRn z{5aU!q*Kl&cWK)r+5pREGhBerz4Xno`P%ZE7{SZmmrh&#wnB^D?<gs5ah{Pmc7<6= zb{Fd_;D&`$Q6a!K^7oYcL}RiL_IH?7iI_2<^{ATbx7S!y4uRe53kP*DMaAVERMF;n zKxWm+wWp2!KN}r}vgw4l$-cf_{pLykNrxF0eoRliA;8o2$?I~t+o@Usf+Dd;dfiaS z6?8og+xs;9)R4Uij}_25U_ky}m*Cm*VdmAb0h4o6Mub-)11qCRuceFACF-ly0mTJU z$tVUPt(q31C-Z8_^}ZQu-dzwD!KO_#ZccZev{aiJTliMW6cYv2XoAaa78ZSPiEb_D z`^XN^5N*a%3PVxFsIS-e*kbEtawIQ^Kk=?Nl6<QAl>mh7L~3sXEh8^cF_k|IzW`u$ z@$vJ$9~UDjRh!ZnZz5R)V3FHYj^rC6sle%Wq()O^=(eg0v^r}G*}Vi|G%|xQ`Gm`w zC{kw`$&kd<%=v-iTW8{0o^eYQU(`*rkJpRqE=F?EN7xEiKnfF;XjJ3EbIc2sZ{7eq z%zzlQenJ~4CDvbddjwOP%iZHQjw2^i(`F<K=Jq5UZg@`1_2$`puTz;!yeWlK%`6ug z<eBnKGZM&KPc!jf*e^@FCu4*Pbr9VZ#nIU}7T)`6R%Q7BwmfV3*xB<ko-$z#I+wS| z!+WE|{**fw@hw`ED^Yz9pVvSk+to6+cgz_)E;49(r+(NnluBXVq61I>M(s5@Dx<hq zPT|GoG`Wz|*VN`&y%p+|wMH;_o|7{$yt0v(j?H(M#etD*t+u7yw-@?PT*`$W97u$x zo}R`vMU{?Hh0p(yI8w;uw#9TIy)fxwel{@T=@Z%8Q-6co@2;gZ*E%FzEpxm(K%Nn7 z4eDk$6pG-U%T>N|MEUDGm{kT6F6FG$pN8io$iArw3S@7NNRiHJPQ$giDCDi9__F*^ z-C%;)W37rd@j3Uj*>1Mi&Fb>+KR|8<JhDLCZ*0(NP^lrcd}<Uap3DeL5x5~TJ*70N zp+B7)s37$*%JW5&$WdYq=`yftr1Ri#_DRBAy18!r%k-QYLc-uRHWj<P`5^imZOr7{ zCS6#>XYSH#dP<g^V&l2^@Cq)rPN)=s>QuL*f&7t468;b=_GRyrur~Ulbe5Q=CF~XJ z>Uq|A9j}a%nr~vpMhU@z(7K`w4^vqGQwPsbjy@)Hsh3iO{yBA=2+ywQW>udH)RX=! zV*OI8%HWe0OkM5=L)1Td%qYNxiRF&-RSbtiEb5Ur?-I#5ikBs{IMYnCn1KQ*18lP; z+?G--`HGXPWAm`7NopV^oU2dT{DU^;3<4L{E_`NX4`tfADaII5;BZeZL$H8R*Nlt6 z{CzL-I^THuQ|J|ZA20FD!%wn`U(Z-S4B^P*7Gs;#ir<h~ljawOAl<nJtPng3`P47w z#YL1Ug<U2~X9zHR6eVrHTW)o1o`Q<nu!Ty4;jC#~lP5&PkAItn086lpsMrU|V!y`` znXFmN)?=qDrZyl(G~>o{I-24$&z#B$fFtY6-c9<BOzT=Ox~NP&P0Og~DM1OGB$mWX z<;a%pE0VkK&Fb~C^6ZpluJIESNt4aD9mVnsjB+s&SSGJ#6O^PQlhk7-79az{%|+vt zCJ=`83VL#*4mQkc=U?M)ehWCO<L5U6izqAyEd-DRf)o68ZcBQEdi-bG+N{d-^&i1! z<N1${?}{HCM0goNsf<~0Ae?Ke`l?IX@u{xnhz?t0^UDeQ+?QMMJ@MkmZVCo+lnQC9 zjaqh;^r4-PCu|#p;N%M|d?(_qXzN^uzb8(_{f%GdGwjJ%*$+xv);ZYr!QA3hr%E~Q za~OLQQw>#eEOU4pD=<E>mKEg6V%YNr%jBmpqb?BgY9<$sta%H2;S{bN%e>@WtzWca z+k)a#$|%YNsB2=MLTk!GkN~tx{Kh@~cmfxZ6DX$#6jI|WGc)|<{I(f)n?%_k3}^dc zdt}s@-9|!xN>ov+E%tkcrkAc;*Ne&%60B2`wZuY~MA&TVr)%TvXpeq5a92?&-HjRt zX=jzrIz+$rU@IxR^a_S?mSu>zSKwdCZDn3wdw%e%0u)$^Dpj}<TyaWBX~+0|Y&GuY zoYB~?lZ@=KWbku~9C{^xgb#igcjCDoh0@HO6%#9p_|3zAw(m)o5dp1r9#g7OhT6`Q z?+GR}T)n~#>?tvS0KnI5ujYsSTX)Pb;c0fUUu14ynC6xhS$>MdDL;6y>uCBl`&KCK zw31VDjqNW7hXP{2ffHsT4o66RY!ty6B%}?md5;#ra)i^SlH<}uA}zb7^2b^HXS3nB z+SVTPm;u)g=Tu?MC$#Z_l`7nje$kFUFJ$*yZp^hAcV=8XOzBcyIt)<B{lsiLG;eft zx$>?aUYUM@%QhL3XCnSmwB+uri8ZHAwwjGqw|-9sU4&a>OBXlyc%#F6`HbVX#rOLL zi02jaW~G|}Rw6lMqOEQG$!O`VCk#U5D8}IQ4u#&%yS?unUJQ)xpiNG@d+W95bpum6 zN8@2udPm-u8d5A%i`{gMnud$5h|D;RpkQw-<yBXat*2yDc7E($`D98+Xh35Y;&m>| zll$!W&94l=n<q<?VElfx<N#BJg>~&z{WYl{as=BlSuVMSHWVih>4^--co7SFL^9o) zo!oJ=nX~cZS<NVYSky){hEeIbLhV-N^iDG%xpDp?s{rS<V!~~T{IBU4%k96Zc2djo z-+AEc%+?_-v_GPm+~hVBJvEz2A)ADw$2gwO4dOwj*)DVpe={U~`w+gcPlv&!%Tm7O z;fAlh`|EHa)cIHc$%E~2=~m26B9B8T^0kL^!wos*TJ3x>9<9&rGnmcy{}qV6&jm0_ zfpiFzgv(yqjlutZ{Jp-H@@N;Ut~DFG_7cZ18CICRup+y*#Y4Z)_VV^feADH{C-PNH z!7tO&QFM_<Fd&HWzy1!W?O7ruqE7MgawWWt9vIL}=;Di3nos?Avn6FSTNlImHCXdG z2Yhfxd`L>ZPU##F5u4`u_WgK!1L-A=6MouGyh3j8yVYJ~sWl+0wX?4)#PxQNL-{bB zsfxdatRdet#$|7lF#U&g9Hvks1s|xZS-)4DLe+px=^Z*~XISx<7V6dOle>JyS=*U5 zd^OJd)un*RC%B-dL5-GNjj}Yom?=fE@|M#fgNx$Pu~FqQrT1el*LI?GQZTemeN*N^ zS@@s5=UY`Em03|~;&BQkwTx5-)FIzxHOW9C=G)3Hx5^-N;$_92%B$iV)2IzuvTYpj zp9|CrHf(RaYI1$ME1ce(*J7&pNVMmR$sjT5OPBUXkugNrC3t-l1$C(w+oaJOrHDf@ z)4p?(uG+Q>5fS()^+Csr`GcCpdWaMa`Cr;hd}x8{`z#Johz_)-;%NbbrU>v+Z88ig znrZ^>B4<(J=n6Oj%A%A}eB8;ep4F^!OxluxV<wx)RF)EDy+4i_XSA8FFUVbJd~>$g z;KZ*Qb_EL9N5K5o38hDUN$Y(+P{08srRwxjaQ#U-O#Y@c6Me1WJxvc=vGVTp3e8*% zF-2lD+9I;7B^AF}FH-rtEv2RMflfp2Dzofv%iR!TNoiS;x_9Ij?v-0Skz-MI0(Ht< z#z5A2Ey4u_eFS|jneJ<P$zE>(0eN#v8cRMGX^BhVf+s;mE&*{-SujgQqjcxf%yi6K zsA+m&0!rT~b9;~+)Zf%+P*l$Q)28%>3iI0lcu`+@?oo7kFkgkGrumW}(315V>?RW+ zVqsNLnDUpTfihdO-OVm>4xuZ5$~5&6WIFn;Q&sIpYK@b|({Pza_yvL2@h9Ul@Um>w zveGMZnA}qp_RFiVFlM8-&diQL8+p#;t(Z|~MogDbf9?*p=c{Jv*XKP;uST~(?eO?Q zjll}|h2J*J4huM2e)8xsd{F>@PLAZo2^Vu5{(GE>LiP+G5gRf}4U{t-IrvClM2tsj zqf}YClmwY*bfZf(07s^I_rFp!ay%ML<1%IYJNQM1>5ESM*3d|LxcSxg>Xs>iZf2R= zMx!^JP%+!(DJaUFJt{CC4dF&yUQew6yXQIKaPO)pc;wC1QBisJ``%J_yc5n=4AaFR zYKdiQg+08t^qs^IIfI<H`BNvt-el)UNYDej)t2w>k8t9x0E+nu2;)gR7}@(e(lVE? zPmVuvOck5ze_lLc-&UTo*=EPDRE<OYD%6hi93amDv3e8u3(U}CxImV1c*aw?NU2hI zdU`^0+s$WWsueJ%RaE$POcs8liZnTwl*boiQdqbgUxDvb{UxHzecM2#BOaA&?zh>U z(r4LZZ_~1Axd~PNj=SjR$@LVJDc?-Grq9gpk>2u)->hBaUrW(qwe63hvn#TAgXx(T z#j|L6xa~s0We0InSi~_OK{sDety7K9n8?p<$hlCM-2ydT6u3Oxt8uMAT@J1;Z{%WU zb15r^4A^&iPo~tyMAyKb2y@YP_Q*`;G@<^4JOtvr@(KI`SGpcqOqKZ=icRnkvs{hY z92-d0W|Af-R0$yrmuE7C^T@Sy?^^ZbHRH3hPZ`1EDZU!FUAmneb(5$pMyQrtoLuNQ zQ7e;G-wK*;o1y4piV#LT<TfhJin(%67g&Ww2qR*+;WaMyMPrVIU#H`yXURbex6`K^ zNN-N`x~$A*-nKC*ZpnhB1?ja?4TX8~za#<0*AZK6lPn^Cz2~X0h(%d=AJ$=&S$iW* zP2G~Ez(bKon*cL=Q&gT#&JsvhWSTp|-*b>Kr>c)c4W>vfR<xK;{B3$54}W21?_7v& zaGy)JTqfF0Hf)ZiWb~Ha?-yBomG5O$<U4j!0DHo3mi61IcD*Iu;q^S`Z%0v|Q>3MB zB&NI?aPEBeK5FwqDUetqL}m$T8HyLI5f$jqCufTm6mewS&wh31{&d4%xL-)W8#nx@ z244FtX08T4(-A+Dk8K)reDQ7NC7v9`IukGc_Q(3GL(Vb_%Tt?N{M+1dJzs>+1t#HT zTcy<U#+{4hiW~)%@Ba?PO%0W%gt<N-lB*lbB=N1y?wmx`1SVvXE|Z{JVtfuH#-4i_ zk>7h+V<-i5FNfQ2K>_Dl*x!7_vAm~90m2D%KUy|#wro50q!q!Nv>wE3A0~3*1m3oZ zL##C{$IX1N^#pV4O64c#Qk{0CNhcq-YS;{{k6ElsfjXB4a=M06xeQzNWClHlEBvm< z#8LV%zBg-AS5U%fXXtXnrUwA5o=m&_x?nG+wl*aXM?dzC#oIS1de#afehDx7v@esr znF;Z%+R)niyI{Vzin$+x$DH}|!o`2N7k>3$>dAf`Zt0-*_}yrb*LZsxndH^VL0()k zErqXa|0ZQISLo`V!yr>F^vCUi<s$8b?~5Z_LWshExw*rYv}67DV-M5!ZUTWWu`%nr z5i1L<_2W&wxynUWJeAx`thV&;;|N#y?wz@{q|zAHQ9<Z&vTE++CNbCAJ71!H`3wKA zob=T)%9fUu<M8a}VOtbc@T6x<B*d1a4~Sl-@36|$)Q$bX$I!BjH2}h3coJ-=QoUKj zz+8b8)v-SHZ3T7RB`8cc=*XwZeK~K&P0T#u$$Q5?Nh=F@m!+7OO&S(OSvk=Gf|u0Z zrzmE6#3JhHt%03L2LrXpmMc-_R3V2*o(Q@hd>(FZ25K857l+QopFwDC+Rh+Wn(Rdl z);KS+$>7_btXM&P0hoBzt8wA2ho3x5zB|svxS-h>0C%Drd@e7RJTv`8^irV6hTk99 zRv|;Z*Lpw^wVeaeVr5s^-yZ*YSLNxr*}2@x${m{W<E<JFc%O97^Qo=7ate`(Pf>hP z-T73o`&&v_vw3^U3B&2ot#6A$0r@>&V=_F6HzwX^j~CnaT!06T&uTxoa4{{E`Ni~# zp@iqO-8LB$XAJ;;Eh_}q1j5XhUY;M-ncjHUwWAtRN_(KiKG-bhHn7}Z<a;Ju*R{0p z()V8^y(aD^>yM)MzCmemk0M-&X_5Dx`R@cmVxKpV3;Fz$o^kEleieYqb9SyoaB^}9 zUQ}apV<}2$c|LLvW_5Jky6<Igbo-rzUcc>t&P&Vv1_;p^m<u(=aSZ0e7i*>%drAU6 zmcP;a-ml;^2>sNYbd6c5W9~gHNhvrXScg=2Fz`9-ibAJMq;FJvOkU-gs`|N4bniMQ zGrx%&XQM4;Pu?C~X)gCNhjkJol-6ajnyQx!7J1+Emqvak?CYCy9y;O`JTLMh_=ON5 zzNg{r-B$3%Zb6_xpgrcsmoLY5<(WQNLN*PSrRDl$4eti|0z|^dR2pYuDxTafKMXS5 zvSFcPs2;tNOFn1i?Ek=mJ|FkQYxMn`!eCF*-0HatTJd=tra^^;i#_V)pS)uZ-3-`0 zTgzd8&&Nhg!;~(@>oZ0Ol!am?Q_enF#w9a9sJeW&uD{jNvbARQvm*0WR@8~<V@X7S zcod_P?qO2;3yG~FmE0|*Knn+NkEH8p0^k@MXw|@{%qafFg2B^0-|hUB?WWq$a{HfA z6b2XS?g`E5C_N&Syb|O8<mcafEc)V){h#~4g~xf%`7h(i?~YwYIpJ=eqx6}Fw;E;b z<UXcj8rnZO3GDFk9qrv&(de39B=V3nCtVTgo41BP``5kr7~t;KmN6ojwe0Sb`dr$z zEM!P|S0Hb&SAUuH+4jN4y@Sn-D5-6i@~|SlKYs7R5_#c%qeo{MgOe<N2HpvY)CjgP zw<$u^OEKhn$>)|<-YAN2XX>3V0tw77;D{3b`umX6&yzTZRQ?T>gNnsE-{Xgnh<ooO z0q{_As=<Fh1k<vUf34}wyF=??onN7iFC0w8RftjUG2hdBy+Y=46@Tu5_lu71MIPz9 zYPg*Eeugc-e9%DYj4%7?cQGDiNH$1WX5;oRX842`v$51pp!C^Xx~2JS$B3Wq`hVL4 z>#&WYLTdIo5-QBK;LfpHF2g3bxJL4?!Ivs+m14yfY{Gx%_&hkTd#Lm~J58u}Rnzre zfRJneh8K?KcTjqMa1UW`(#{906DY|>i%D41cj06Iz5sLQ(W3}T?k)6v^)_-nbAD?g zY)o7)LHS&=5FtTCE)MQurfSa#RK({$JQD&{8pq<|02YWUoO+gYAJu!e&&NGG)e&&N zD+R-FlC>DRBCrQ?3yuD>_1C`sly@c{f%Or5&?1gn3m`ndC1wz-2p=^iM%Rt%pI}Vs zxU@)IR4;O-n!lcgj8udb#weA8uv3V=TxCyJYrDUJo4V*Xb5LHtPEF^$0GSgHTs=pu zoew1@?V$o6%hR#MIqVkqBvqfSeB5OD*}M^Z(QF9nu53^O=M~pe9s9FTd7kd#&>A<@ zm1qPkC4K#O;rM9p^V_nH;!}$Q;{&K>l;SqdiIoPsOCP@rdeHO#O!p+S+V)vrw^O4? za6&M`dReF0jab2PkpVrm3WHP}JQF@1R5Si~h7A5?Sh-HmKg(evC1ALQ6@`pB>j(M8 zQepsm^;9u-dA(F?q^{~T=8k*FwA~H5EZ+O46O}U<`BlTSPh9T(63;r}qPt0Ppg*L( z$33_ph5}$`R2lF=q<4ijCenAkopM4Zm|`ymt5L3s)~z8Fp3?yX7_B4%a|wO^rmumz zwU}Sx#r{}J#n;Da)`6M5c79|&Bja(iq>b{A*q7~)R9PKX+6Qbw(%wgXeO6U5y$pf~ zlNkLW+0vT}e+UY*_b7eV4}zfh@GiFx?c6+S;-0gqQDEH&0E3ixwS4c-H8XQat++Gn z;Z4g+jIB2*9(|srb2h7ym$?eA+Vy_M<iL6yu120&_phQ)RRcv=QKcpF;u6l2<@Dn` zGKPMCm6ZUcg|5T^*XAQ0g%n5-vJ$Sz2!vei&-o$wbPln8`=piUmn^WLDe(gxt@;!6 z<Z4Z@YXibRY+#(S4aXaSL_hf!BiRnsN%~(v#3TCisqgh&gmJ5wA@fEBKwC6pAH$~n z*tQm+Itv?2`SrbgD_EnY2#oc0k>#H2AyVI69dEwr{00C=Fca&&-=5X(Ch-I_rZma` zi4BJzrJh1H!B9qShbhNy2z4E2>G^4v;AWLX1HB52X0Qa+4y~^>Pw@&9T;I;aE<4xF zOXxB7#y_3|a3sP!WBvom?R0jWa82&D&1?&e&b@&?pjMe#fBXj=^WN{-=J<zzeATdP z?^rTSd+J*6NaJ4zEm(E?8)ZC50a_e6tAA~n45Xa&zMj<vG!y>VT!PvZ%A;sHjnRa0 zU`G|`TSd(akhGm8JDHS+1<(M-WdI7uT@aI7?CRrz_r=_zb7x^f@EQ~ZtMsvmg^6Zc z#sKbBgL5e=Wxk7;jaiL+YM0#@<-M7K&#P3qI8j;Yr)5hjEqrt@cse8CJxfs><`2F| zr069b3aF=TnBi1%QiUAv*_|T;QIG!8Q-%MPp%P1(S;XW}xG7a|+Nw4=G;sOy_kGIb zHJXFqxTB+nI>;@<B%PW%k5Tv!{P;j5m~oyL$YK-_W?<2(!@y+&m1sF)SJf0MS)YV` zcoj+M<~66WUZ>7JmfkYc%v(Yp&xwF1LY~h#c_vo$V`ue<s-IA75J4OdG?f#=fxgsD zm<p$2<(KQSM@mzaCiKn|m)OwmW5RkZ8!tRrz1c}ODTuc!6nvspSjHctr@q`7m`-v+ z4Z^-yBF)HgUH&njw2@&O<I^Qm)65o%fnpjwZ@JuBT`9-&1FBx>L4o-F%9~3TIv>wD zdcdE2KAzs`ZRx`5TtRg&M5EM$W0j?t<pF^{@Ov>mn}4k!WB)r9FBzNS7EynA{IW%? zS|OFio8=2RO_BZMV>i2G5x#*TeW>+YA!WOVTH!Fc)ll%Wj<E+Qy=K5CqhxDdS_puK z^5LBck`MRLt`FdPNQA@;@kB0xZyX)B@DuM;lPI6k%5O;LZa}o{3Gmh2z?OSY9(%_- z16hNnoK^OuRkGCLZ^XB@;>jvH%$*B@@L4dJk#c=q+5~H?`REye$i)q0V$b|zC`MnR zqe}jm@-P=+0Al7Kyyc!r2DQdQjWWBE$585Ou@c31TY}Hqj#+kcVBp|d^#j&t@Q)}h zq<zmJy5h>VzSJ(~ccIb}k6gI=A4J5EE;RQVKc`-wok*5KbI14L6jlwsxyZipP<r$# z_I(TTt+{s$MOspCWX7Jf8E|RfzFolCJ;wsfdC9s9eR3o#-E{)AYGhfGYkH5F`k|NC z^}=@tiRPuo<aO&4$7_SKz;pempgMhxc1ss_YfYD3<0r|x`A&VzKo|AP)r<2ps*-vy z(Cx4KMz#&(&uD-FMgO5~wF}K786pND5v*Fe1c6aF@?R1%mBLp;=?Vw8P@@mQ3b%dN z*ZPccP!SO<Gp!xEmJ}!>gy1L06Fr=@{+qO}NAF(X9^lC#ZcEBHf6p3)_++PYO2_S- z)6*Sj_1t|Wp~dY&iE|ex56$-#G?%cfCr~=VDI!PH=Ws7fGxUd;MY?6>^?c?CrMk*# z!oOK;JhW5QIm?>4#=l+v7(8>~?dSMgy4TCtIq<x{Ht?IWRe>tOcARE3%`pe17wNx2 zvR)~N%EJ@5hy%PpFYNLywAmq!hT^lmvCd>`?UH`D|K;xNO?81OEPGCSLAqWjN`Eq{ zl`S}ybMFwfw6tX5$eJpW85(TZ^j*uU&epiCvUBJciBRe>9p`>p*w$2PjO08E{@73p zyt{@SzGD%o94K~1wlSo^Y}HWW$E9pvx$4N<6vIDzui-0jp*|DqeTEu;M(IOLG6+S< zDVl&D=Q>J8<jY0Hri#xHC;_}r<W7W)u1bH4U{{uX&~aPxg*~^eky@%@6R}{BF0}C# zVu_q|`}<WT&8Iy|;1#I;C_w##BblXMVbAz9nmic1_dGr8hIdmXe$hZkskd)u>GN_P z;n~T%LTwJ?`F^;S%l-Aglt+Y)12ZpWfRuO`5AXm-->l~om36))uYX|Fh35>vk%`qg zau59&FQ+vV9M=)^=?1p>XhI|`QRu%NIY(q4+FFLBLEL5f*B`>>X{Bhf{-VRi^z2B7 z0RU|(E37hdO)k7Q+2H2qkAs8X^$dwZL89xCHc`cmFDirfS4{;T+awO-`U+kKxy`xs zeXO{26+<i9rOn&1zt<s(j76yqMd6&Y`j9c0zfm{E1;b1A6<CNXOAJhiXeKrs<8ze5 zGxykR;_lrEyQY+6_tb@Fe9giO%~l!T<b}iz$W{Pf^5GH|p4MV1@QW3f0rqYzpUe_a z!g|gwfAHw6S`0m11nUts>xePaml+2qz(4WgTOuoqtUQUVD2#v}aZz*GxVqnR_!<Kn zERlSk?PCT@X&yn=dBTk9!jMekxSi>Mgpu-5dVKn-7jP?IgaKRqmA^!Uu4jF|U6!0_ z5k4*oO_PzcgH#S-XmbSAMEg!&G>KIaHtAlCf1qi`j!I$>hI$&I<wo93mYa{4is0c4 zd=#t)3sn6B9k3dC?qB4_F)^u*1#s4*2xWfs;IKFV{oEHVbjXK%aldUpI?A0DnIWRt zXi6a^>St(ZbE48wlrlh-*zQt3URL`@L_^+V!%(=e!u?i~N#hCpY$bl*SHvL9bL0z0 z#NF9*SXw6<&cC^aX}3B*y@Hd==f312rz_@s(A^@0<4(q>(_vgu!Wl|vTn6@^U3OGh z5-L9FY7KsOil%H%({@<Vr%mK04KQ!Tq98zBq`k&J;Z-Jm)nze2D%wJXxB{?AMwBo? z-lKUwnH9J*PI!~98JoT!bQ6u&=4twKAH+q77&*~@EO?3#3g1Gxa{)R#4b80S_rCc7 zBQ|!5SOf@SxHsaC6aWvQeqrHpq>S-paQQH;gZH=qEmGI70jGAfL^4s>+|5LnNTBie z?Lv+M5snmY3my?*dtFPW+w6tcm7k?YjSwL0ME}ZTFKZrgG#gGM2gRI2b8=s`Ga@EC z3#y9XZaXkQ2F47=T>pbT2Ssovw^{KAEKD8mEvSMn6EV(R;=yd68CY=Kt{>z)iFy!# z`j_@^cLV%M2bklk?(%nEphXCC&(};^Xy5`{GcT~x<aA6OY2G?rUK)=}{Ky+VIX*tu zz0?KPq%IKA{t|dTeZM!NIx>rnjU<CGAwAWh3(tEJrk&?LEhz}o5Qig**N4NXr~m$v z#{9!FBDm%`&)|nrfHM`L1F~+u!y6AfW`P^K&(n`rh`KoMDHA16H)B28_a085#m+R4 zsKB>5usgE^lR^m0GPQ|@ThmhYPG}ZCz0)96C8;%R=|?5GZVNSOjqA^~6+RIn_&z)v zH5p>miR{I>Gx+fFt<y!k5Szd#E_g}x5SFlEbyipC(t-v?^c&+?NoN3|&$3Zcq?sQ5 zop<2SN(_WbXE&+H3iSZE&nfh~1>4%!TMhw0L6F;^DM_*bKg2ZNSmP3p>{*3M)qQYD z6(L#}Or||9$yBaL>$;k0V55|^p*-ZTrAw?*uDGI$tLTkOX|sm9T9C4qL+}&QavxL5 zSuXqQc|EHTp)0!1hLhHX&VoyA=b3Td3-P}zn)QfhkVzbQQ`l3>K!J%;hu;Z{mm!uA zT3#Wxx?yx?lpx2=cG~|C@1jYG`+0eiDaztZXNcx6w!Giq_r4J{req9uuAc7L{%?|q z>(T=i&X>@*gL&HB*b18(d*cxVACg_K-Bciy$AG0YEaT~haOu~W5q*le*}<t6L9CDs z%DOWi&I<iDmTdmugX37|NqaeP{avbW99_;OL5?1oYCe<TCF~fnbRE)bDi;{!Zq_2I z@%<`wz;G|J+fw0_oV#VPQ#z$A{<7B~k8be~DRJRh%q8o0^6?Ju9&SgA&|If+8Boi! zW;C9KjDne%qb9jOb%D&bVm#(VPRL9Je_!$yPW-mK9#jHc+Yn*JKV_*h&XIpVmi}xt z_IF{782Mvo@kynUoU~)acZ(xEl`NSm4t%-+C;Io*?g{TQ4^hX1%3xm(rz0qvruC~U zv-9QXrAoX{YDRxsoPJJ>)84h<-oT0BKqs8hnt9I&me%0&<h34+MYG^77g3v)_z}nM zpZ6I%r58w`KboOUzIo9l^5x3+{LKNzn%_xRdA2cpft&x<&HWRdcHnpY$KP^64Z@JO zy(_D-hvzK|J|TOe#7G;NUkx-qU=w2s1kSCnZRxXo$F2s>fcb(MZt5LRN6+_Oy%slQ zUl~)%vfdbT%XZB%@ug^&!rYdB_!*JeH!&6?wZH$Bc3zKyYw5Fi(O6bw9?6LB(^W9< zu?DOUOH7}*TcEON^8&czmx-*zP%AxgjqjnjbB<#0<rh8o#3pg7!q9hX9sI*hp0sc6 z$W9n{J!!?Y6%3t5SdW9>mE0?blxjI*OqO=BK~Y8SM43p7dU?6e<m>EJ=N!kjsT zcQ4sg=+%UvDuLe&;L5B|Wmvp?teb;S!FEox>>p;_95<l1uMm7Rb_oZo20~pWbn67$ z9y+JVaH)A-eed{(u0q)Yd}sQYu3UQUp8dF|rj)~IuolgN&JkMl4f)jPv<*>Eq$eE| zMf8?@Wy8HavyDBdWzF4U6Rbu{28-AbRZw4kUs7RxdcDi_xj5tdJZ@XlN*XRG81KB~ z*nTo+WtJQ&%`wzs35XEaB>YqA7WK!>XM~}w8s2izo0D_m{C5gQNS|zRvbd=PQ4){W zm9BNr$JsXX`b~=^J5%hTl8wR@QS0Yv2Ekq5cQD~9xR8AuUvL*B0u4k2J^NT4t6~-Y zBD@~|#2TvoHGQY!mUypEz?HQ?YX*E+wLtM6ftbNi28(5*xr8Y_Bm#20svX0=_ffbC z4_~U8gF=d1I;BYc%d{s8)Y?YIz)}hC1@)1dKJ-{rI&qA;uDYAOw0czcMnbUbA1+;n z-lQr<rBD?BLXWL0)SRVjAQ8s}FtZ!9g4F37*S^1NQZYy*CA(e;Fmhfj<pFF?%wHoU zYBQ3~-C*5!Ouwj4YX%4$86)_d9)vSsXDB?V>(RUyGya#x|HnuDCR@7>jtHO)+_#!D z^F21CdLFV^1&v-;?EbGf&r2&1U9X_wwf~;=r&>yglMcP-SsK;gi}LaL+bUmB>HD`V z{<DIdVP0I8@PZyIx+WCq`J_W6?|tTE<VzGGK8pG2ss|k}iup|!ITZUfAh&?QA>p{D zr}fBIp+rgGX7WZDZ<Q5P#Ofw5EC%oP^ooAmr)Fz!cA9Dyx3`Koi#~3eWAA-`qtUx_ zcN$`j%`4nz{cjuA8|5yEzWMmX9?B|$8yc?4?yRb@Wq6^XAhz?pJ;c^G<s{H2$u?!0 zxasb__aao5A#94Sk_BZ3R-ZM<6SufPi)vwJ)c>K+%$_BT@@V_-P}q@-MIm0}wF+q6 z%AvCbF{V`^ngcgH-@a31QS<z>u6Ap`@8%a3c1IklCg>tD`A5sO`VX9o_VW~{(#T=V zKcrs!`?1C|diI(bCN8_4pkAKQBMi>Q;;Nwt?J;|4ON5!tL2}ox=ATy3tH%T>{U-|! z7F`D+mxQfWvGkJF?$<MDaS36L<p)ke^>@k|kInVfd4IY+QpumaTb1)Y{HGXt%fa7s zFYY7fnkj7!Yr8*GB|4p1@55_FapI4^ZAJ-<Xg3UWyXWa*nN50+EI)Zx^pAGlj2|x~ zG>bN{#Z?mRdl%Z<V$u;mZL{9>5otW(63qH84WC1znHz4<R6~wD^pCOS`pPJM&l1(z zS?K0<FYUGU#zkT8WE$;_%D1jIaRJ)5*wlGbf9pVg+xFv6u*uXXl)Kj=BfPO+zxD8_ z)wW$Mg>vHazk5F0<#3QSQh3%=J-u)xLE3z3_nlaI%^zQL&J5S58c*P%P8!{+QX=XY zqDo7PX+w<9<HE)O>0pQZsw1f68#oDpX`F`dkgwsLmT)tnLF9E}X@IZ+=)lf$fSKwE z{@Lz%MT=e-$G!w>zc0lnvxC!!Pj{DW{gKCAVk2qWBEF^p)jH|u${<MA;FXB<+*sOd zFKnhn1E&)n_x7E-m%7avdS!Q7y~%%syvnzgD7}L=?DESiytjBeF0^==GsB*H;(E?* z-)j5Dg=;)RKdP3_{Ls^ZK3kFU@F?P03Uq8+-N4(SQ7@<RtzlrW%#DZ%gD?qToxfsl z=jGW@v%-g4aq(9by1#nSYCpDyos|nu)_tB~(e#!^1_Uvy#du~6HkuJB;0yz}BW&PC z+*282?&1JNN<hap2t;8R{}U^{H8$L-?1gyP?`w&Ocr44@9HE)+W0tFab7QJCUD8~G z{{cX-t~KJ!mEo*c;*(_S(!K*67lrwXni{KKOmdtDPpEq2mq4GRUxFOq!gc4H<FBum zv3~GqVJ-&u?^rJ&L%RD*_0<((IH!SZU%aylFv%uj-jb;FF>26fW10UI>ScaQP#2_- zzZ!d)v2`XdY-bA(B=cN3<sFLlq?$-SR)RBBxJB~@exB*by>p`gEd}A%Q%UHQSIdo( zo4YDroSnwzh?|T5{5ccKydXnjo^>EU_GrFxY0SYX>(=2<sHtw9=Zb9p1$s&~O7zAD zN`Dy>f06h5z-!jbI>dH*j5e93Rjxv8k20zn2Tp@g6NM#xt<gHl<tY@P<zrLys#Hax zijT@j;Tk~gLP-IN2(%!F!1oS*zv}Vc9QzZD6rA`!iq1P8>i>b`ALou+^f?Y^c6T^i z_EwyAX2@RIn~X?lICperXJpfvS;@{QS(z!DHlk=sQ}xZy@BjCo@5kf)c)!-OLV8=W zEZ-hkd4z4Sy4M&mn9oTjvU%syRGy^CIUTRg<(p|~G8gz9-)5x%JXDo#>4D1CD@=hZ zZ;Je)HqO)rubt(1q&?l7^C<b7YAx@X=ND5S{Q@qL1|EooJ+w_<z1xI0nKOnPR3Pt8 z^38ZREaDxUv?bMO#N6#%X_<6ruH;EMc#d&nds_AlZu>^G3cAr6m0suFW|kf-Ej=!L z{^Qch%Xn)z0>}^EK=AXHeD6u_Q9?*H#N<6<*&J_})S>a0?HD}dkyW}?oE*&yOudt( z;7lScKI1i4s)L1oKL3bP4t-ghT9Q14y^5jz+EZ;S{VONECbV?0XH$5r*JRru-FuQB zaBi7l<TE<cxd|3ZveN1_#m%&(;sTT4^y|s8lvKXU)~;LEeSUK~iyjJ^_-ZE1+aDXk zv&Y(G(D{>=f$ddN2ybJ;#wjs-Y2Wl#VM>2Q@B4U5VE%V|UGQa$X_5D=yuh*YUpy<t z@w^xANOc@Jg^r*v|40?_?kOgfgp|3K>b0}s`aR>mYzPBqBapGAX`({??gwBnyN(0( zRE_YC2u<3i*{Vt(j=M;2;@{|8Oh4q&)CD^M?Y7aIIh9eEByn`|6MVjFw&#y0T*%}& zTE(w9*4z<tDEbKie^F=X{j`ULl+%I7&^ptlcarZO#PqPBe5TT&kbC6~3a8sonZED) zguJ48cj43Y%S2RTT}gXT)sZCUQB3AV^4Br<=k!cF2hX$jI2Q0jsxeyWtI7D)O0jO_ zp5T~vq+|(m*-=S@cP7L}N{8Lc)GA1|P{Q8~U>UY}1G-PMnDl|1G{Xx_ru!{_)Qk!P z$4w?;0&0%f=cJo4g0x=~jCpF68FZvdy3LbKzWHfxg((Q|$>THL>9x5I|MmO#cT&z= zp3ZnBO&&Nmgd#0yy%IRTVM1?~67_gk6<HIks2p;Q1ZjRb%>C>5Ro5WCrr-&X=Aw{s zYcxT)2?<m82Z@54ejJ7fT<D&-Bn}FfJbSPyexA2E`4=na&Z%J}S5?*ZL8dW0#3F{3 z4Bm)F$7W2d(!Hw=^P!k)YI9a1N7_f}a7L)$`hz6&us+R&bmhP5i9vMC{mj)YsUPh# zzh|#9b%uhJhilTXmnQQRi&G2)32Wb4CGP3W=MWOgii}n45u1|!ehe*RZgp%flg?v| zFibmbAKWey;Vr$Nw5k6^JI^D)I8G2DXrtxNw1aqy-<)41##1ox9n7`I?vu%_bS-y@ za9u>l(>vTT({y@+-RVEidM}57@;bayUS%u$XLGGea0~dj3n+kTm$$F}75~rN&qj=I zFj8{UAYGR-;ypYVV#v+F&KDUT*wbpVD;Mw|Y8boRJSt_P&^!cn2=TSp@m63>j{17J zE>~5)poTi@co>&sa)CrCrQVIth+%}`X>)EdE`aYB@M0ihLw12er2wG5cax-X%lMeY z*2>@RB8`H7-|@1Z<|->!nGeKjgtj}JRSQCx6Y*`NY)r_7NFi&pVg#v&KDnU6W0$hH z$$RTXwc*7gOe{Y%xLU-Y{3vS3n79cSrP~=A!+~?**L&nUf(%o4sn^kxQe9N@nB`)S zRs4=sr!7e~?a%`<hi`GaP6l~l>~6T-Zs8b`GXaXgFdzx{(*nDeWS&>dZ=C7naMbd1 ziv2ibQ0Tv|wBN+A1J`^A{xpE+)bvfa`hFf$8z%myPe@#8fGtw7N`c}r-#=Yyi!H!@ zv8a=-n%c}sjp5u`HLY`JCPBO<QjFoaU>fr_$v<a=%s{7?zHa6)F*SCrOm9_kq~BFd z5Ud<Y4@;h<KQbQWHWae1xuY~1aWl<xSh^?Bx5&6*Jo6y*L(-DelmC9y2)$Q79IMVj zhbL9nChxSL0nGBU12-)>tKlZ&iOgDcc*`@<6fvp`Xp#99Pf>Afl-_VC!sn92n-ETM zB0KqMDNw8+`5MYzHC=7Gw;XG37&(ohdr&58$dd6~^P7&jRgX_AQz|&$)^-&IJ=#K= z85TunmL3r4o|3gI#cWAd)215jfh~4LT=VFlnrgll&`cfu)mbsSm*n!zGF2|tE7a}e zl+R9-v&)|{9)Zmm4mSUES9B;DGPnRFRi+_{{yvj%(?4pAHp%icuQu7mI1w$}$tukz z_QrWwpKlB&GUv_TR<VzEigHm9#I{v7@%h%GQO~f}eJn%Z>A+S}@Jv?^#V%?9*Bo>- zR)Zd{aVgXDbTMrvMyU9S&<sOEYO!tawD9Io`SsnwR;{1|u6tQebtdjO&rc=W2C1>C zChD0}$~0DD&@B~8Wb~f+n|LLHfKu1M&~b6fPy8CJS0Y11^z%TbL_T{hB{Wm&%PIHK zgPn(#j5?JTR@?KM*XslYj{#1=Q;cr?FRgWICgJw?fxBBJTT6jW>s;x!x>5=KRi0>j zMU>wkd}QZKqpVe?li4P(H78JSLCbkx(2sB0p*V0uu0JcN$#c0DYHIp}ei<^z*}|TL zPFBBm`D*zu)!zy>-Mc60!lPVK!4~yL_I}d_^*`}ki+JIa{FCl)*`>KYZ!>UHoz4(1 z+2AR){v<he{e()pt<~vH@jrpZB<S|CM(V7b5pP87vn7+~X(Y(U#i~eImEqXMtbLU# z*Zh;T`A>Ky1ycGk$ay1r3@lKG(W@by*Y54qIhcanSR1x5K2A3ZoxsOzgCd_;2lgYF z<|7t$0VJgsxt0e9ncJivpYd9c@uOD-v9x2zj1w0kNb%Wklez9oAIU8t)FpF~9H#Uq zI8|`3(-lv0?wkHi81A%@6VD7L(2;<SVgI}A4W41`qA3~HkwzZ!OEoSaHR*j+bDM+` zcO3f~ScRCip@HQ6G1iO57NZ&zpi_lz3Nwc*5T1r!=YjC`?OxLG`-~oMi6TceGZi7z z!^^dr%v+j&r!Ov>?Ex%dhC(qZqqqdIrBYS6P40}b)f}wixR-ItO9{C4Hh)0zHxH2& z*~HZ2lKF=S5{i;`;e=njM*MBaoz+HiN`k%I#TPZXEQ1sPubn$`<NyN+))||%f8A%R zutb*@$J)IHgD><%RCV9Nm%&jX!(me<p1U89g$`%>+q_Y-6N~V>2c?O{ZS003Ggy;6 zbI}FCkhIYpRpc<Ak<}6p<h)e`hKKqc2$8I5n?TD*I#sQ?`LBh`S6n^<xU50CS-5M; z5)s23sTlS+PSVSWeID|h_vfH`RKo^0K#CkiCRc)Oc%53p;2efaq9AaG<49H5n56jV z*0MdfREg64#U}jILwM-?F^!x7B$0m<&HeVX^dD32-=@dnZ#nl_e^&98`VU>kL+tL1 zzWPYvhYDFnPeC#Sf^3|^|3J(ew<~h_ialqaznJviP2${v(5%+KNrgYHc$b)W&}d2D zX;fIdZ(mb14leH?mn}W@^>3u~mapB^mLi9o{4n*z#i&e16iFj&HAY<ajIk)%?_M@Y zdJ02|j{F-Q$4$WwynPR(W2M#_-E@Y&d0Ub~Ho$ovH~-rt0}x0UC(0xri>t+t4Jnq# zO7?{YHp-&tXc=$H9i*?2W3y5a(eJ_ptT3{lCwWOJl7O!xb<(P4lS%Tgty1U1`sO#0 z!&qdp^+eD>QiOWto=gx_sL$t~m8$qyv-%N};dx`uu#Kb68ya^`O8pC$l!x#*JYGaA z+$x&-ScL&D4|C1ho<%~mxrhicrudBx<H8R7!R7aCujlc4t$16Au4+C}2^$M|UzJ$b zy&|nQerl&66~hZjTa1;ORaP8*jBDm1Xv9j@vmHH8JE5Aq%J>+HCX4I_ApRqUqXPv0 zvKQSAvU4IE&NNBEW4Z#Xl%*gJM2GJdTlH>dBzqPl#*!wKf+bBCjo<S~5O!(E;dn-h zq^YUN=EoG@`tp3gBM)U`8<Q88&t4k^i7r`Iw?_CpzQ{Ep0JYG<<BA7s!zzDn?&3$x z_fsNxHoU6TRt@4#93dLS8ewCSi+bRer&Z;?ND+c#Ngpz&JY+=9R4JpXK5@+82e{3_ zh}cN74dN009}mD}*<7Etxn|d!JdHnylp?5woYmQ7f06Y<dU(GCNlN`*AKHdzq`Hl% z5^$U<wUhQkoh12iJ-{2+LvVOvWbX5cl%Dk_nCuu)b-$urFq2DN^}PixEqzz&(O-!4 z%@37P<m&~Tf5sHVi_&Ag$rOf_6F5wayNxe!#A)Ulmpe*S$B_)M1ZW3|C26EW6h1A- z>#r;|TJ;AF5y-7Ki0mSTDyV#eD1jr`5VEoZa_`5|eHCSK4ZG9lAg`JULVZ+`-7SaP zJV27IrSq`2LbT*Nv=1*Qq22uPlo~;0$OrX>v>GDO87t}b%}90EZz<j>2FfAJ%%vww zWp?d*`^9p1f%di6es7c>@MBc^Pevy%%117R9_QA3+EM-6OmNl&i3!kO+loG#=}`Rb zrO*+_^Wt?{R3fPm`*lpcOKqSIeyH|^-uDxTRE-)^k-|g&@SIYQ@okRT5TvqxaudzG zog=<;jXN2T3Jxzp>=DfH1LFos%#wC1rjlavsqe?(%l&zfrvPd{)e{gZ|J~B+y}dYX z<=Y&dIV5nQRiDQXd-_p`oPbnj_pzc*>^$M==!Xm^UN1VLsD^S(wpj|NmKK>T_Zv;X z5d8+S38)SC5YG5))Vc2w!bz|3KSJP8Zoo;6;6XtrIlFg!#ba$)9(&N!xz@)ZW{F*& zeiahzQT(Ii=mVDN%{udu#qU=%x=yh8RUm<a9JlfLyMmkSN^8)QPpvv8G*4$`o!I9S z<|Z>Lc~1Z31KiemVT+e$I5N4D4XSr3$5cH-s-Af*lX6piM^7n7Ly`~{i^z>5MeLIa zRckgXgeWuzz?w&EeV{jTR>iI%H%>Z3awLk5sD4vd#1S|u(dH4b(<suw4nf31-lrff zYAMRTM@5luQ{_y0mIJa{>rA$xa-&ap#X2t6N3hJNqi+a5#RlB16xN&bg7Dik`{c8E zi;#Ooj=KuCSHAhhM@a9!&%g;YRyCKUuIH>;e7@CQ_Di+{dsg{ycS?&>Ks(1Tp44eh z_pz%yIJ-ffHP6)bKSE9mA4yM%I;O4tBko~a*7vLk44E^&M(`+(P?9p|PcvRMNNAYj z=Oox^|03oKNL5&A@}yo+mA$R_@QSge$}f(sPAU!ngncc9ksEpC>x%p&F77HW<OYw5 zRK>~9^<o5dB{txVH#dN<)_sESuCxewA{2A}4S=l!@B$t_m*Ny3LO#F`M}qY-iu7g0 zL)D*!LzZi9n#B$iSw_N3>8U_crs{?Sz|zY4iqBmd1Bw1a+T%zZu!sZB;#2C>7lJp! z6CvgQdK}!q66X!VU84PCUQezKgI&#>$G)D?N`zTI5@;kWaT^QjC~64-^LU;ED2{*@ zuSvlbqKLwv4j(s}tHq#N)mP*$K^XZI59kJruGd=Vyg`yr+|WAXRdga)Xqpje7&e?F z)P~m&mn^a39dPovL=i4$*BUBH2=f(S!}|v|<5jxxEx&)pn`Gb6dG)*?Ct=g~{79-P z7Xc_H3U&3nDNvh@`1`KeHz5jJ&yfr)oO-W@|F$^<DdXYm_)S0IyN1`>Dg}@CYO?{A z&X8BwXZW#7QT8GH!_qe4emv=!CeVL>qW@yXY`fvt6fQM!?8>k-?bZolDgKS~oi1|6 zsr62fdiEkBL&sE-$2|<9=y)|wZSPPtyCZ3xCD22?v}tC#>>4;+a&QnuQzv;GAp*jA za*q~N-yjLz3WjrGk{Szl6Zeqw-rP^0;mOo{X!71&ACZ?^f~GlM1!uoJdggG0@HE%y z-uU{!(ja$HF7eGXl2|{fxl(9ZK5f6rOFazhdP?foxXQ|e{jDD)4zfru|Am$Zm6>lI zJER3OgT5Cu+v+!DM{Hzr4Rb_gDyo<D4ANlV_V5mzqjvOj7daF3KJG8(Y6q%`>$$|p z>imf!NBiDQTdlukvZNq3gfEeB<RZRx>AL)l)Fz!cb*Y!sI<)#v=Z!{_NMt4cjd%YI zk2g`hQ}3hip+~U6K9@Q~7ByEy+jvN5Crw-@X;fvYa~eM!FL_}9uq3TUW^AhdT$tqL z_jC<|fB*hgNThurFA6Rc9KM!wLk7w2wGvZK<sza4Asd*WM~nzRvCI{9`s3HS=BVF_ z)yS2Hs9}Lm<8n13$Fa_W*+YWA#1VqinUBu>7g#lQMW4`~$Uq6TMvKZmDIAo(b17u= z{-55Ij7ZW&*(!8yXRnKt+D-NP!(`FV@`UJfzjp8!9>46?hgfo)tH8WOlF`sSE{hF6 zY&Mj4gAnErK)n$2Z6a8#>x}T1q%vV1v+0ND*Kz0!9w9@AEG&?1D5xb^H^u=RqU$%} z5Z80tLx-n%H>Mi?-Zn2L@(Tm)Yy&coPf{=2FjX5UV*Y`N4gvCE`eF;oKksaWI^Ivu zy$6)qxKtrrmOzY`e7+XXwuX8X-;GIb2wNEq8tCyh4vgX?6__-klHbbpxbOE2`9Q>L zYI*SfPwr2vCd_wq&7>W2Os7e01wPiS?$*|J&!;IF7kaLSY!q;9Aaz7Pzxwwf<5k-k zeJLx|)pNf3Xw)(PQ(4LOr&d($ld-BCH>}?NhZpPg$p`}OyW~s!&_An7kl5M#D&t)B zeb^m}v{A9eB$r>65I??AR(EFGwH04sJTF-lzy<*T2MDY^#!;zqI0bc%Z?kK+NENuP zqpat|bR}n^QO8TQFs{Qv=q6Xyw7r_C{3RXVX9qu2NDqruP9sOhti8LFLy(`IcW3$7 zmg`>P|Jb7>+Lk=S)N#Zq$O5^D!nn=g4-HPKJy8(~j9I=WN0=Q(??LM+DeFRHV55Xm z?%<&<(YFIn%{V1vUjcW3cryk?5Uv-K>^0jq9%KsZUT*$Af~2YiZ-WU?!23R|4cNWA zYdPK@rSs3urQVyEl6?qts42oWoPxqyh;pFMixxy2+wRP?^N<}nk8Ktw@3QPSmaov! zXe$Ub&BAneWoCWV{1@u@!h4rW)C*5O$QVymDE%G26OEkF=&Zf~e3)ZzeKjZaFYxt9 zSBaZ|`l9@%ry<P#=kwUi|A?S5bFS)uDc>tecP9r+eoHebQGyDD$13MPB_|$s_Ka%z z&YBAP0>IcQdwDe|c-)r5h`ei%>X)taX`<RdlYeyB`IrsCmLC#QS!f_9J38ihvfOEw zfKu3?gfS^(1aN)ux;d#N*f)pVUY_g}f!rAb6}lxxOAQ9JC1w?U_#LJd2CPQCm4>A` zlax+MPS{c)5fC6gy>b+%@w4{MOPdc3oLE}~hJ0G{7iLM?F5PR2Sq1Z{&LS&NSLTvV z^10Y1BZ*r<X6TI`5*;;^9Ox<d$QATJ&cOyl0m>m4c8ILK!9bKVoDJPXb_8>d@k3WJ zhFD{EKml${*4B@lK8U#UlBDKJ*2k;YoU$a1nwm)xQ{YCep2c9{X%)3MDd^rkB+z<x zvCbLzuz?3+AF&xIAnyrT86r>%9!@rPg|o(UR+}?dCU9<C4O!>Y7wsTyU8gjWY+Keg z0H`vq^(o?ggZf{Y#YN}3(Av;AQRTaDhfWXe=QkrhPOnP!Afbg4h%Y6!gdqrVL-ai) zYQu9!R-(ko8cQGTEW9)wx8n7Bg3Qd0$eHa$Kd@uA#o6sgwnQSzz-UO$hQmNeO9NQe z7w!Vi-WB1E8b+WN->qFi`gf3Dp6|c{a}S%_d@IDd@~XaSyE$mSR0}XueV)LcGzo*H zOez#Wzys{Wdl~=pb?7$EyaXGQ0Wd-JnA+Ug#>)Y}$hQ?!r%Mvp@s$RDmfb21ejtrK zQc(ft)#eefjKu{jqyvY&sVp704E$>CGFZQCeR=;4dn+5@EB?UM%wIr_qYqiBz<i1l zosT3^?vR)gro82d3)+(B<HcW+Q}3Xzuq7d2UmhqFRpulQrWxM<^@3bu)WL`|!{3ox zJlCmGVUreh+%05Ot5X^KT{>O(9$+90L=C5$HS$LkuUl_d^O;O?0|%8;9{__!?s%we znk8jK=rz7#-;~hJN_qTfGk=Q>Z$vgqzY5^*)!5xuJjHJCV_>7ONk4%7qs|S%$3@~7 z52R~M3)l=ml{{w9c@ESx1jvOFg*p(U<^bze-)}$?P_oAF`(+*KXp+EQL^{BH_MD%G z-+8Smsgs$~{IZkj`fY>%U><gCZ4~A87eYL*Qg-9QN>Pw4O!wAWidKnlZVFwAo)wb+ zp1<l=gaPt+l_d=5%gKudy!D3J00qh%KNWtn=$otOc^;k)pLrVx8$-v&^dc}otJx9x z?8&LrAS-tAyvAWP3wsk+XA+9I(6WA%a0QkGvL(4dDo4n_;3xQ%p=yvFFT<MaAkG7o z1y$JYhJMZ0iG<w%SR+T-wJA&To9ZY8i!6cw`pO%e5WNyc@jiwX3Zw(MLs&4m6_NBD z;V+abOHmt$o2H{{Q|=|CPR>_PM`jw`1QLu7%3@GAkj7jucR4148<=0D8wHiWrfR4Z zh=;WxY3YVrW(T!Q$@tAQ3IQeis2H@~4y{7URFk)N)Dn@K#-0zo{^|@r4w94zL%QBD z{G9GwQ&w#n&j%-Kb};3o^TQq42L*YCXH)rWj$}{;4t*IgEAXtw)?pFVE9Y3-U{#Vq zBFzw=Yv8`-E6|5ma4Pp*N)fd=m)2maT7}VmYMrO2<p8fqO6ICY)=1ruOIM1GLG?=b z3lTO`xA~J1RBW8x$q);DD??N?fG<HC%KFupSOeb91gC?DOlN;s<t08)ep79Mytq@e z0L?Xq`Mf7PIjo95_#&eMo;KXeS^4{t@94qd<_lEC7NFn8m*vPAZOAbdkDHr$^RVtk z(Lkrasf25@d5X(5gLn07`!A{NkXsw(li}O7e1Eo_oB!k&jylvKdQC7|+ArK&iM>>p z39Yf{=gBw$8IeEfY6B_u;<EHoNE_bXxMV$>G}bgd5`3rP%}Yf^8S|-k44zy7kg!D! z{{GlrC;)+`bY8n5iZK%8ZUX(a12UZM5<SkU->wXBzy}It$lr}g6FO&z@BG!~WYUx& zapHlYh}SK0S&nX)%}AXdG)bdQ`B^e6p=d88@PI6o;{Kn!aSuf1(=qpntm~3=;azQ{ z=7wL$Ej1H&SZ(9gdkvtWIE>#w{PrG_jFdY3r@E0h38>r$DP?uWp`H_q14Xz&tiLI$ zcd+nAgy}i^H;Ghp${%F=J$mOvMzGD-Q>*geX-Rq&x_AW}n-vy&9ENR<g42yr@B2E_ zCr%rFv(WAVqrp4Md66W<F?}l&#MfF%TV*za?e#2Tv`6GwYV=hy{Pp6ppPRDzeOQ$; zLFLVocJBA)9A{9*!ijL#=FETTSy<(5WrF_?DWEkId(9~EjYm_aK~mCew!crJJ7vCm zd^RG5B?A1AW9a3KHOUR!!pBso%6c6TP|4edgn6dzmw~D!u0zz6VIW0OC5OAt>u$k& z!Knrq*$7xQlwMvl)fB0XqS|UoiTpW7mU!fst-O?we>pvgqvlI~ynjFBy!uu40$kLi zMsbk<3LngV&yyM~_roFfxNa3p<($6<vKQzH;r=b!piKDA7e&tJ0%SnMGsu(SKW^Wa z{X$YgX!$pt&hi;#xEM#q#6DO$SL)$Ofxl~)u6UUE8kb#oY~H3V(U87>y(+h4v0e^d z%fF!$l#O00G<|H(w)?u~UH$uX!@tg{h3l_Q1Z-YgzwXN0{_;Y%CLxINA6ex{($baM z+m)ZMWbcNt14@FmZ?V4%!OwXI;6%3*tkNmbmUwB<1)>b^eyiv_Y{MKsTdjoLPIaZ? zIe{n`VjX#B9gD0<KoIOt+u5rbUAFR(rO#viq$~xTwUr#WC%u)zq>N&2f@=9(W3}4% zX3^?(+M+o+&%C*gZ}J|kw%jLx%>{m!3qk5l-KGufloXiq1}h~E7SvqkZRd;SIS*q) zeA>Kxl__Ld4Vv6J>@tDR#$ca2^f~H5pKf)?b+G#FmBe~+C0jvuj@Xmyv1sZ^u3-HI zBPwz|(A^%<D-iQgRpvec1r~ts##3Cku<#L_G@mb^q`GJj^-5W6S>0XNA?o2xUJ{29 zO2R6aM@O5W@_hCHUI_qwj-VP8do%V@{a0GtPb}0K$@+?2!sAhfDNh`aZ{Gn=7lB=D zP7-f5{G}u8a#P>Un~AQc{)Pe$KLl;q%-G;S0vzxeySlZFJGc%m?eRSs%ZiI;Btzl6 z@NmewP4*I|z7<)5_edN=?)#Gb+m3a13&+_R0!bEHBe-%ck9MeWebG5sr2@GN)S&8o z!K8Hcfa8*()ke{%aj|A`vM46KHYRhD6L6{LlbHYu6RuI#_4w^#nCgiL4E4izY#{Gd z<`=d%6L}fR+^_utP|9YgxonuS`nL`+6DCOm<?VAp$33Bc)pA)B!t^SI<qZ}{`urvy zFz=5$+W1^{pOdBk#Fqa`L)aYwK-6E;5FI{4sZ*YP{^wex!TiG#<hl6ZaZq>JPjjxY z;TLu%i8O(y{R%8X&n3?oYGw3-KIh#|e(}7%jeW!C8pEEKS*eEk&Z#bw=w_Esp+dE# zz`rYbwQ1OcDDHzU2-_RysG8U(B+#75VaN%fzpI58F@V7nt!(;Hm56E(h5HV7*+B{? z*t~WGAFva~50xN0`+36zT&E}U{22&_YX<MxyQXy%N<O)5nV1?sdnYPK1^fJFA%0ca zosbD#z`oq2T_4k_AbXZ`7^A<O6LH9us^z;(KEoB`=oX#4QOh@Nq}j)L0Qe<PECeLK zj0TqNt9`5XKEv<^TJ>4$F|Mh$8m#QP$;y+;N6dywitGe#^n#R0oa2VjKlZfbe9%P@ zB|s)2qg^4&UZ-V1`6oD6YA$SD1Vh6vGL;vT9OgEe%bXR6t6UK)g`&maFaxX00W>p_ z=l0VPbG(%!HNaae<+`$zo$jxlG$8?Bg;gmxAOEx!%tVNs^$PBix4g|MkmRO;u*-im z3|2j<Jm1InR}&f~VcM{gg&fNI66=B_-TYqdC7N>x-7*mfhAFCnH(L|O8X{4Zb?XiS zwJGBM=Y!pp@q+A*=gegn)VN<pp<JHGU|n<G6yt`s(;L<fif{;^GO3Zpe)L~KtxXYk z^2)ik@8^=FjQx;;L4CLcb}uazDV1K_mBG}Nda&~eCjLUiQXOc}aC7Bd__B_8%RY2r z3N-h<vdq9@d*EA0;j%FU07Oi7@rN3U#PC*kIE5jo)!Oqnu6=1(Ti2fI;*mBra_%dX zb;@DdU&{1}zX!Ft!>9$A9&N$yqQy;oKdT>Xr*Xu1y40uee6zM##!SZAeYnXt<OE_Q z&qkMcOG5y^)|hy;)4=Y{6=a7yTfWX3`z4`U$vQXVeB^H$>JxI|zrPar17Kk+nh=jc zHAupJ&vZIp{cxWTTZ5Z#L+k5^R_Lf&`yiLu4ve8@wR$d%8#!FRhiaM|aXI#_Xv13V zHb2ZCzWyoN(sj^8Ho<-xOi#lKqTIsU!JM=P_C?IhNSzHKQoav7d06oXb%9k1z+J$z z6X2Sb?IZpU(F-=3t?Uat41o*Y`=cB$;_DMw`8+Q0>OVG3>+rl*c!DiBT-zMic3sp5 zB~@?0f+}S_QFyGBOEEmec%Rew5$`iCeO@~>(<cg_z-<b%8rJ2GaL%zo0{2+j0#9&D zO59Jix&JKVj+yXSP|9ILnBrB;jZILtnDknLzX|UX2x(7Ww`q!o-*B#4VF%>oPWyI) zx<EEWtM`IzkVdOI73U&Th?}uEpq{$ZS2!r?K73Z77WZ(1WbV{|(#J5>?~X1JFZ8<m zn;pvKJZu13R8++m-VZ)P0kKi2ThdMU{XOof-$faAryY)P1IAyA!Q}vJm~x%JPB7E% zHk!)+{yqP#KZMvh#gDnAdq1)3C17hW=*9t*6@miHxIbap3vfU~NwI1lS|TiDL)Bnp z2wlZX=I&A<%42{MB46n`&`L0uBRM|7e6_gkZ9d?>u2hz;n=bCFezzQAht^jQ9mJ{@ zye`y(U_%o<;Fa2jgxZj|ckj)n`%l+cJ@vEpfv>F@&Try)+hldhaB*lr|1b8$2kf?b z<h-BLt{nJ2IUiknFq+Qx;J4+26*qC`56-YJ?U139=b*s(QHhBSGsqXt_k7oGwQ(Sn z5zhW<4h;kfLHH*RKeqB1Y{>CnuFt6tvPOaSE<I@E`H>)mSTzzTQ)&{kx|H%)r|^xH zryQ31T<9HSvf?a!GNoH%xqpwX&7Ht~DDv&#d8+HdeL>|%fHK9$Uc|H+Mx8<WRR7## zpzms&w#yqM-hA<6>N~2w)EU>I*UQF;eg67*X5z`T@7a6Oa5F!Ikse~Jd+=w1aE^re z{KGaF)yKwNfV=wQQjRX~x~Q;(uV^RNzbcOPK`gDT=1Ot;qo2bkFL)^Aw=hFJfcMG@ z^ul>}cf9sNPDL`8f*o?rdnp<PXnt70Q}Jbu*18*=G4jdRzMOEW5&F21Pw!9t>KvG* z3^fEEsCeHJd6CC%!Y-C|(<9tWLgxe`no}G?MYchKS=bLoRZi=?4TkjidFGuQJ$Q5j zWR3)QFSwn{O>r)8%aDEPBU=x_Pz{t6_~Om}lbLy|9N3S0#?l^Mg>&A?$eHjZ=;f3T zi|InSEHRI&d}Z(WS>vf%4BEIZ5@`Ef6h~l*EG0yL#YTKw{wyI`Tnx@U#mHLTj3eOA zTbEp%xhgjZxg31K2#+hCj(JvX3&FHpbO;}Vz@@kVlUDa^rJki3FlPnvXawZrSy1ac z$VIiyKC5D;bq8Ani}u+)({%(l1`#S3kMi2A|GMa&m6L(ebfAODXgh8?(3(yd&K(;E z@Z7hJN50GW)_hz@9-myyd7ka#=8l_kqk@57?ogW;h%c98KGp@DDn<ER$!t20W_!62 zQL<?*Sg5RU?4~~K%LSPx&?Y(m<N~Ku%tJlyaAKlYCUjKnkLsca_#ZJWu51=Y&4t@r zr}OweSmas&YLLp@IkZL7A-d&9tbZv-r~%5sLdN!8{BxD~uOaD`3JFfzxFE5xR(FB? zeTty(l)odWFJ`A6q96R41L?$J#67(v3w}-7d=u=f4?tTQVo_`ya`qfZ_<_3QJDAoW zbUYKD48UpmuP9X32Q#pcE7ddjcmi4)Nr;{sR1J;tGnB0%ETZGQ)^FW<6!eErQ1MxP zDx$Lpgo=X%=?cep>YI9=BMBo~9(+TO#C>{=tL}n)<YI&87z@r7@oAHKZs+|KOx+{! z1kXFx+ffLCeP0d)nn9~(2`_s1saRs7?bu-o<;#ScbsAh>QD0yJ>~jMB+mN}~7dlnj z!7b>)NKsxxo~MIW;0}7-3nUVdFILVWsEgv+*!J?fsJ0cml4o($w-SmWgv0FiD@=8k ztah^}?c8mXWpO9X8Or*0S|!V^jdP~ad-mzeZ!a+mx%YkZ4yN~y#|l3kMG#h>^?*%> zYp^DHw9!EOnD=u%d;#{Z-j}~^`Jt!&6L}%5jJ32Tx9zn=w7yXKc;QCt<7sfM_am|T zr`HJA=C0+*t=fFk%yhy}!)xQhkHshbys)<sIZ_DA`(UHT>f^>9uiId@JLquj`xfIg z$}s6i>71yY%jvTmo={H9Wcf<V_B6Yg@ZZ-2Pb|EcSDFhsBYRmTaT!jvDevHuMU8)O zw#K&U>md815`rExqraN-k(+;fJlwX2UV83ma=c4rAMzz3{4Th73zz!7xZ-hp20=r! z>T30gSb`Arj~B?Xyq_={0f}~rZsm9uPfTU?C8G|hvj-3tXvmr&wFFdzCWW%(=pg24 z)q~j$lZ;`gkZP)}VA3_zg2<vq1Zy&MiM!Ewf`_1y@kB9l#O0K?X5<S%tpkB~e4L_2 zg|x=E7EfnT!gP3h9?Fa`1!(^Xg<_nSsN9^{JiicrwIvMPCrrZILxV6FcA0H3fK@;{ z#ZSc4vnORz3A?^q&sIL49;9CF#;vj&fPIisc>eIL0?-Xi)u*rv8emc{r7HFnHQZcw z6z~ykmM*F^rJux9*%)o}1Lf1Xh_WB@lH@Q8n3LQEQ21er3Onj!_pO9zKrId#9(M@$ z1)f8*QB&3ztSdFBsLo}pvTkbMe~mv}4pfWQnl5%BH>bc4wrvp3?~Y;nU&y`bFcN={ zGu~$bf{ikOz}^pC#p6Q5EB~w#*#S*pcLU!6eM*y`;V3!7G6FZy04;nEDW0ZSRogju zx$+%;QD+05<ae=cqA#>A`b}|3{f<n5$5a{z5Kd>8?FX*#Y-6bQf^Yk_p%$+TqM5u= zx_GvzG~tTo=E<6ps>XMB2j@E)jH#4$6puNw`3!49e(Frye>@*f;`x#Pr_Lgpc?lz% z#=(a4Pr7h45M{vN20%V(qkaD0OcqVLw?1#ci_N=}D$BEA6OhTqo77}F4DHriSZ}yf znXekT^x7q0i9`;}%r-v&O!+2ssF~tS^9Tof#8OJ#dJJKYHN~r>+LS9{JS6L0f4sZf z1&*SxZGKh++`QM>g@Nt2E>R<V0)$~FtqCQVLQKXjC0w%jFl~2mm&J9=mme?>v-p8! zDe=KgN)y&m>ZxAO>VyIcLM(g+BgL<a>|Czq=^yaW=awcVvL!KH^4M4MOGc|Bo~N93 zWe|sQ@73o9aGs54sgAjzfRM2E?z$_K<@0ZKzr5>q8-q@L#@`vlpJl<Hfbi_XEtvPU z6C4o#dNqZrvshI}e(6pKtUK6*nvD5#*AEOGEqnq<JK^iXdG_%;S`Fru1xDv~7prf_ zv`+en(75n{TP!T;(?CL1Z7(fJG&G_VE(ZTlVr2>!NV;mlAC~d*{SK4-D_QfF@+hwU z4XxgUf}kb=23K#KkN+=D_llD!u*fN-gGxn<)@RnTB?u<zPC%0E0u+Ax8`Evp@7$aZ zSLWJlWt%lEp%sMuDQZ91h^V~NRy7$}TJR^Mht{&1S{gC`nET>@0}p4Cb(CMjA6l7@ z2mY8VG_<h7_KoFxD*oEBl={PR`c>xRL%GlwFzVz;?xz8b@g2Go-MM)1;-C#pxY@ki zf9)ue+ZcI=9r(1W!fw>CWoVIM8-R7JT%SXMFp-IB{wi$?SO4=G4bM*}457BWBJd4| z{4bUK%FK4<hsU@(CPtz2nGs-%!3Is(`>7JxA7GSzsgk<^c#ReRF&eG0eq$5rYnlN( zwAWZi0)q1@r4OY-*_Bb~oK(JrrO^}Y`}~~$O$?#M*4dx@_O?z9)TP3yRBw=mo7iPh zdu;LP#ER4pog*cz3I0d#r;ot)GEO3lxtekCqRd}85-*R4zj#)0u628~D7;O!IoD>b zWb@8fE@K_F5MzN*LXT_ln9y9Ssg~2cu&9q@rXXelM@=5fh~goHL6OeKb4J+al~My5 zCQG1@!g<(7yxA{5?V0nKSiX5h1N>W<VC)2~6F~^}VHeqm0!<=L;md`MucjVU_0kT9 zrV8A|2WzyM)}EUJUVa<^)4`&y>@5Rt_Y8AuMc{Xulx3?Pga7J6W6D`HVZ}8&?wbbF z1tWDSzQi>0U%OT6S>vEZkHb3rd_`E_I0-5;AtD%H_DT{2RD>C<fBu+$^r#0UdR)64 zsT&8u(-~zD{#KT5>TU~ZxJd%|9U?>x3<yJ2$^g<aw$$)Y0k00mifOWba&NHoh>CRq zG?^>R3N36WG5a9XH^(%IT)3@!w1vAW?=zQi#>EE~7B9y|tE6M`N}>~H<P9sOHb;X3 z;(|fA8;S1y6@Ps~01#;djn76B1fR0o63#MJKu3J?u&0<nF8*NI=Y2!}r5E;J+HL51 zK8AI?hc(XL6pau^d^jj;8n}Hj<N14{kLWfznCe6~h{ccpf)$qyW!e&r>ohP#Z&IM_ zgHLEFAQ*Zside2KZ7#jjk=??*!S!RmR(cIX(O^;={Z)(^-VOnSpGI9%FUHHUV<JxS zw4J;yR&(S;)@B%n*fD`qPrl>ndBvqQnQPZ+RQFlNk-)b$0EG>uYQW&{-u0z2A_?S_ zbvAYA3(h0PeFFQ?xIgO54qxMbfMp`tf@iwPvs?Mma!yYrG6DC=S_5-4^~=>Axr)$B z4rH54G#N1G$DRA_XG_o38)cRQJyPDy!LPygS$6gVR)?P_;~I5OdI{;D9T4&{(??i3 zssIG)*s<hXS(<*9%iQZKDz}v$ou+4qR~{U~wgWa%p+$uK4>II;d^ZMGpL86dQe5Sd zmz#>vSt>K^z?&#k@dX~hmp4`Q>Yjh<?2-1RZKB<e3tQ#qM=HDLCodfR9grs`fqjvb z#{W|mR}@ZOg;bj6E0fnMCKjVh0^kSm8t)%}w}x01j~7W+W+y&J2EOWK)L<acqavdo z!oi=aK62r7JiKA_N;WQg&JZjrV%B9}<mS~oZ}+jYsgU*tV{fX=+w!N)oR~bpL+3#5 zF!*gD54QBK<lTM4cln%xg+|iIz+dD<&B0qsQ<XPSd9IaboThhhn)D9)K|DLqJ9}td z4DtT%;(CUCfV^WZo>7t{3{=JM8tmzHMf?z?TJSQQ#5+<9#OGgdBFJ}P5L)8Z7dDA| zcO2M~eEE-DoOK<CFG-~_(S|RYX1PF;xhL_8N#ybizKQASuy3uf5!{oJ^l|rjUT=0F zIvwTQP9tJT0Y;Z-wZvSBV_2y`+7|&CPBmyUy4+cOaJfaS)G+rxHFKpn=>Rn!k&M** zEjbRXy*2oa*K0U!+<T@Cj^!p7wjA4p_)7gt3ZG>^L9kylicYLrQv`ec{KpNR5PGIV zG470p2`9>k(UnTn85H^gz&HpyUGY#-afh-3XB+439h%F2nU+3OQxz55HNSuJuIyyK zyXx8F?Ik#!Ox!Vuxik=^-;7HsdzWVBN`KO%&#sb@*v@$24u|(KHia4Ma>u!wk!(Wn z+ofvMRh{^Sd!0b~_Ip%HPXjcA@hBIzQkr57;iCdDeM;_WNRp>ZQ;K)f7hO1H^u|EF z#&5f_kkb3#km-GMrDZ*}BgjJp>wR}acm#u}(vkLQ?U+<E2JkPPms8qf2mEl=4|&>Y zI2EEU92#y2Fz#irpjyfKDXe~db}<?|P-}<k)Dl{7Y2^MpQn8y!lkO)Jv0-sTQh38m zfTmn;P|7&ocaS(jb1^Ip)?y?vt_pMEtVU=TX!gVDM?d67wQ)omaN4(}<_g1I=I?*O zFl=#U-;=XUao6t=d47bH%0ZF+d#OJwIr2b$y7VzN=x`v9kqQ>R><3pfW~ie<EfKhx zixzNLv#Me0mPr9?BQ$SagAZeRh5}C!W+r#xrp9=z2jhtxgUY1OLjVgaoeY+YYY~jP znqsY-YTJyM(7vXe-&8&%N2Of#*uMR8w|*#x=wx+$yY+UtR&z+{^+{cL<!sSf(uva6 zrg8?yyf{C^NZ)T8>t5PbqSQzDdXyS$nh|A`%FJ(!#&T;j>KjHXW=&u7Fi?7or-F={ zgFVxV4;cx%5Uj9ShV(dZvnHKlIFMkLxmKe6Y?L;k3$T!rPlf`T5!vub@8>5zt%|Xd zI4qU;idrXz%qJQRZbYu7W%Tor&YRe`aTj;={!BzTV0qd+7&Go73x0J}e9`VZ!-0Bu zzCZl>qD*Q1SVZ4g%3*M}^H%ip$%>0sbl~psUjEcWlzEPVUdSXJUVlg-ZcjFJoz4G# zIDy;OlDm`kB{8Q$`dFVuI@7%D!>VMT@<jI3g8^o?X#zbuL8D|a)$5dH_!@`3$RpaW zu|y~1dm_;rZICSvR;wCx$YzQ4!5{xM$ZV}N-UhFbrz-K-^Nq-Hy49D?w4{T6I9Kdw z26J*?0%{$6(mJ?Rqq)KIEX-*ze-Qmp6_Vutw`K_(0gUfeQf%lGDbd?ma=gf=dKBH_ z?!Z;auCrZRyBxG{^{ZvvIj^((t<uMN7)N~=%MQ4kT2*OC=6}YFoo}ex@V*caM!hm> z)EL!eYgKwE*Z9NRMIK}N$uU);TFQ@U!J{;#sli~gpBGOKeY2v^rYqtYo-Eh}bms0n z1CItpD^u?jtI#Q&0G#s-F!73&Cg)EXN}$l0x!LWtvOE1N@aeuzhP)uh8EJ$_Z?}&K zQfbmmv=fncm*H5{aVz*576v5sG4z_!UfH3({Y3#ocBa;iq6b}w>R~HX>0rj%qm)@I zDsHjX2yQ<pQ5$QLr!2i1Vv|vn8X7BH8_W?_f7KUE>9@EWO<3^4aaICl1?)gp+OTp5 zLvcGrIynt}X@<IOtD}Ao^8!9pKb7J#^1cJ{%b&5}%OF2s80o|3_HDKfIpZ&!N_VLQ zN~YK)e3c=?_>$mgGje8bF-0lwlmYDOY<j1M6H#?0jU5PZtOu0!PH`Q{nUn6JRz)yz z&*Z@stw*M<v}gv0+Q-`)I8F&cPU+B7saokY{PORHiWJOTeUbhBT@Btg_z6*@HE3*@ zHNxh~%Q5VfnvhJY7p1(XE*JAgejIFPPk**<nsJaMU;#TE1YZ0F1#EFMw5SSa_)O&` zQF{f))0rv`{*1bN4By?ZexX(22iYD^armL$Nc_UnhkOI`sfSmN{41?0Y3W6RTfZK> zH!bx*&dI(@eqnbtHpT#=Ei^ymO05^w-Y+&OcRfR=mcSsC=}9V!Uw+WteCY|TRXLSm zTxtuy@jyb?d(3hYJHUK4&W6mkb}O~LKjBvO_%IPI%5akL%+U5cc7fPKSm1yyj9YT2 zTczBBEqiw%GCq<4oKmWwT{fKDJPLm(>h_`WdC8!Jy?0;GDBL*e`OP+v)tLEadaOcP zjXJ1s<g3yBk7MnsnPz<OSI<l{n98LG_274pIhvNjP9yYtoY@Z;aNAb!Dg$;B3%7>= z_KmOZ>dw(thX#T%nZT@fi1kDtqkqw!TfrSKxC*Sh(N|No`QU%s$#iC#^n9AeT56Di zN#_HyTxFAxAb%fGX^Q9Ae*~tWl~H|-YNh^5|MO1NVDlYF7fnfXjE|9MQ8MuBC9SCO z18kJbyptw<GGi8EEewAHNh<ebG|Z8LGY`+3{WxnTK9e5E$GEE6b!Bp3p?Q4mKcN8z za)do;Yg3FZf<lFJ%CF0HzzV&#Q?y&T5tnY~q}Qs6GW;1ujox}bO<BwS$UVS&F}z7{ zM#5(Pbn2P_zZm?6$&lfJv?j`jA)(0r67#B&^-%27I;q~S#8q=rYlvd8k>Tw%?BGA^ z3s*UxB5Pw5weHfawDj#zPmZ(Je881<FRu*-Anxh;<Z;_?q{4r2;h)Hzp$Old^m7Pt z2PhmtN@?BE9DgRKOMZE>u@y151XtV`#`oaXmpd%q7<^FIJ!hXB5t#R4U9_|Qj!-1l z?vV&JYMnNleu~6JWs*E_FB>T{*}!J~ng^XF7rLrfXe*Kly%y;1r#qSL)kOX-lN}i4 z2k$1!<m!ck-5H6ga{cqSHp#wxS2<gbVg?x3)>a3M8HyD_+ZQcL4eWu0<@nA+aF@f| z4xex@_`DBX^njm1fDc8AofPAiqB9GKfs8fR{1eizDwz4-x6&;JX;dJ^Q41Cy!I-Uo zGx=oW0@}X`n>n|T<9*LkOor0|+KoqmyLLB7`DrfZrPteqiEJ9z+Bp=|iu1SM&B6fR z>!o>vF3s>sfBBs>*7KBYc}--Km8~;%Rk^KbSsN*agKXW8lA^FDE$_c6_v)-evVGt> zi3wF^1-Dcl*8+-4w)58Q{<%_nphLuzdVYB219-a9U?QJ5Pla5n*3#~F7V$ZvpZvPt z;x_bq#`iBp?oXZ;6_KU>e$@6ttb{-HuSz}Yx|-6^oRZ{z6oSN7!v0F|UT;YYqC?H1 zeA^COyx`EJ6SL^{;P6*NMywul(E*nDZeF`;q1fQni}fEc@5L#8RO5y4Xg7v|AIjW> zA@PY;l-Zi$LJ!WOpV)G+`Tme;?Gw#rdu%;usK;_FOhXrw`>k?fdo@6zYUT-RnyNJ0 zzd5B)$whEY&2|z7uSXmUWW0qU|N8IJf_;Xqct6K)a6*ye+);P$?JVYe&{h^8be}Qt zqmujJ@3!<~M3Im?64WS<M+~|-K7hKNJa^V8VT_Tkg;8jEN3EaY6WsB8LfQOg>xkxF zU`kGYC2n+UU+eSpZcKZbz#c{s&RAWexkM}fAS)TeRW!LmAXcupEC-E`voY5;559k* ztwv|mufLgobKQhdD9X@R*=uFrC~?_KVfnM2R>;_u>QlcJoJs#7!jN-Gv74n^+QM%K zi&J+Wo^%Yb#^}~gNY}3A{7OW~7TdxG7_Bp<n7176h&Qr3SvUE3?CsOC{L}oA>r@J- zzZOTHZIMzzWJb?I#ctRIQFx8+x1@G>?#!Zz86(<nqubJIx*lQjFeGDJ*6K<l-{M)x zI|yawCe60wRV8~%=yUF91Ly(Mib;zKQW9-MG`2WrFg_amd<;>J&9rs&{`3^#WShZ> zK2y}~HJGzswU)JyS^LH1Z^pN~oiZtjEJQl7{g_$=hjo4A?vE+n9A$hw5MxAN*=Q_2 z-hc^BRkFBVYe%2mNw}|>(8FNYW;_65<a^Ag!SWZ?eXppM7D9CLuX8|xl6fmVg#~>) zTlU&@Dg*eb`uy~ecR<%VN-pJ>>MO2t>C{M2o5ufQh!9pnfw?ummc_!YTDf;;V<$?u z$Ob&8wMm8ed)><P=Mm9`cNoflOL%S}cl0JRqTr7^>&!*YStOWB4P2m7KFogV%%HGV zees!0l*})$;X{^y$OV(>s~3~5UIDp3cwUm6@PEagU;Ft(Wvc_F=oOU#wE*g+#TY~A z@YL3~s~m-4H@k<92o_H8)U~$jD1PcQZ}#u03d*A>C1xppPpmpv;|f#a+2Xz?Yw|TB zIQyx7)^=|m?|vbb;=^z`0{k|xRtjH)0Q1YLkr#9`@Ult2Al|G3D#uNL=^I5b0+ax{ zi*gI$K|232--q?l;^Wz3+HX+3Q7MK(9M{wwf|V?ds7D3<u_<la5{wJ@<LB}xF@VK& zj=(83+dNW6jTg~6w7E(Jm=@A;*P8KF&stXWoh~^0e$ez~w~u?z$E_tZ_9mgu)MdPS zJ<xf{V=8V<F|(V09)b^J$)z``#9Lgb_jyP?%RlzT1q6l*|9eBumOrl&kZu6rUF&1K z`3r#V@b#i1-*s{lx8#O)t0l=iBY~W}Xj?yI$8P@QfWrXkXzFr7e|hV>9nPpXx5+U~ zclX_cE?~4az^iy;mFmL=h0LOX?oTfSG!i*}B#wkSm)5E@aVdV?#FgtO^0)AHgiKYL zJ_s&bzn#_p&MV*9Xu$E?3b|JSivvz@jjo;LqEZ*ZLVcIY6alxMA*8~fcP_Wcc~d(< zY?dhoufml-VPGXs$qDDyfe%Vmi*(s$ar_9d&GtZC%~!S#`Ic{bN?}vPG}tiDQgc~p z^12f)B+k?1WMJNm#?z>;6zLgn_7#))ds~vgqVyd*nc14xC>21fBa?}Pjl43@cZ1>; z`JcqBkZ%J3>W0Yr4|9|26o^43v)*YA4;+j-;DB>3qa60uYI963ai5}wx>8>#Cm^r3 zX=G#@E@5g?p-AThE`3vGR&yBoB8b4<Zg_Kw{bCx6Uyw3)<NhUMDWhR02>~XbP)LsY ziZXlBc_3+jK99>f!_Mi6hk(<u_^2RH(<hG8b}AfczO!vY4?=9O;4sfHRKcZ$X9oQm zJzxv_6AL>6`g_~|7&`BNs{bgCe_R(A_j29q+T-5q+IvgVo%Rk{$==Eim5fW*-ZRN6 zBMI3W#>FM+k|e3jLMo)Kudn~${PsTY^LV|UPYz0>3!P$QtyM!O^6P-*8@M&yFb2Sm zd48j*ko^{+QW&?3_bBVn6J;$nx!(NW4_g|V)tLp4P2c(JVoaH!p@9Zq@CN0{m#(}j z?zfzYDn*~q+9n9uuDL~gkbY`2yFfm9ws=Lu2UZI8^|jG_djwxaby|x0_-L7`@>^<g zOH0*bSCtB<+9xZY+77UHy@@1&ynH<F?}^lVP<}dUeKM9*)iN5t704$7D0!;qnX#)L z)DWue(2*mBXL9TfrSj=Ea8~IWGO}KQ3KysnZdC_-D~I5NtZ!?Y2@Y+L_8ozVZoYR9 zzxOv7M~H%}bH!k%Y<5MGZqCO5MK8F3w>ES2M(gU}Xp%SUGRp0hws>}tfT`&}iWm1q zru~hqz`PqFs`VDkA<**4swmCQH3}r5R+mx~617T^)+qX8&d-X5;KP>i8fW`hv29Yn z6UR@>5m`Z?>PP?(_ZF&UOA5yj`G1!+7)f1EiaqkgqyY3lo^Z$$VchvEcNwyqxAV`d zQw2`Gnd~pvmuXP)iA9}Qbm(=&0X7$frh_1b-Dia_xXHqoXp0dAdo)+-mI<pTMO7d1 zP+DL_bSmtHc@T~7rvpwke)8!67g_UR_HZh|AZIBgod$40Dv6gT{6vVX!ay|}+!QVO z*D3$XavfGim;uKI@I80S!$^tD;Pv$2Cn}+Ud1EpP8<<BVLsNy5Ub{^~0QI2t&`1%J z{tSvRHaa_<pTOf{#sXZlu@YTt9-Z$W!6}Mg3_4%o6*Iqfsy?h8V`+PyGB0fgh!tWq zLuiNb(POO7o}xR28KN+RaSAjIbChEz1Q=-=L$q<+>6#2bp|knC(AnH=`;Xp+zImch z97ImN!3gWqJoo!KEF^J6<c9|>$({vB{6)IUj!*}xjVS3ERDuj&UDiU&*}l6bRU-Qj zJU_3NxhqW*a|q?fBPc%)${|#fv|E7XK>PSb<7S_G;o;`W(|=duoAo&S1J_DLPo(Ly zd)@Nx{46vcR%o1GFmu#-5&dw)oD?w+w{J=I(;9)uDo0q-%4Hmmf*8X3cL+=mD6r;6 z8{!It8*~Hq?B(P7Zx)RO8eifJf#G94UX!f7kGdP%pfHY&<JhL;5E~}W$<`0IT+FNx zs1bapw>p=kRCpCwIBGOrOe<>UzleTjlSz;n7L!!*x#QY5ZRy#U*XHD%?&oafA~&0T zBKEe(3%LqP)UV1U>YBW+8%@2$ZZb(IQl&dlvJC)8DGMz+dmZOVa_z)4A0$O+MUrH( zfdDqYOT|YiUV0gb7o~A&0%~QWI+~7rH(Rk$yQQ97`tX0A;Il8mfb8e9bz`kwwXA#D zXReDnXC$_33_Qx4>n0h7Czf0`!Q^U}^%ykA`J?xSj2x~wWp9Ugcl*|w>?V(MhKr2| zZn?fsrQNMt<Duivyv#OQ(#yN+NA|qV@|rRj_BMywGob&W)igfOJ5B2Y)=OvvfA~}1 zAw06JwZr7`Q9$uRs=b4|VE(PcvOn+NNq@)I9x4M$Pm5uS+4bY3DytJ%7wjK3CG$C@ zgWd-M7sw>h%G8nv^BpAt)deHmafNynw{vO*#`WCN-cYVwvTYTj=}!2nQ?yv>Qt9mz z>`7mZvZfdrS=tN%Z-@ko$DnwM%b8Nv!Rv<N)<pqnQeGzKP}DXsFcquS`i3OwE`9Qe zb{t>VT|pa<JDeX>d}j7OA=}FpgeNN$<-0?9%BO2vLft6h&lo%3?3+BcLdMNMY!z4z zY=m^H`S8rgvj0l_2=y!L7D@ba&j)0|w_3uN_Q>VHc6K4%iX4X-=w{S<%qm>q@rgER z@-}#`aKtL$)0$M{-kU1n=L1CbW9yqc1uJ)h^yo<`>3yu@u+>K7=cgAH`fsJ&Y2y3$ z*wx?syYM-qI6fa%52ldtZpRSJFUu)KBxsLat7KeSDgigdKQY$JUXXp4pZCOU(`4GX zcBVW3^X}=k&#*@i;bkO0)hopIY<A*lk83`*nfiPLNw(mZ&%(*cbtW-_UhPv_^=!Cs z)sau`HP$1Mk<jv9r@uMp0LTuv_pf2E{fRW~C?wGOz(fa`ADn5RRUzoirU)!&Og21} z5@u7G*9L9=G+;H<wl?E^x}F`hi5M>GGmB=|5cqnI(hzVW(jg;<-(O7Xbg*-p26gg{ z*HHxht$3foMxVxc7t?rjN_yEn)WtkH0F4HK6n2*LdEK%;=!2!9+dE&bLVed*S>qsp z1Oq<SgbS~eq7k67>>7DPjK&Ieqd%Y5`HAn=gDRb$2@ri#;0$l)IpSf~ZX9^v8Kuf{ z#6B@QO6ev6pCTU%F03ps{|+Zv+_*XOnn;^~W1itXK)`|oWxf2&<~+VW1xsZGei3ak z)oO5KAF+yQHTuAyO%Co=hG`YWWLOlF5wva|<v^EUN|H<_@op~0%rn28$tSPAM`BZv z8ep(9eY5i>+<r*VZIO??k^s0_48F2JJCb%SrOPTWED0XLTwy`<b5qqvPo2ph!{>~% zBwXdjpJ~(mhEm~dH<`X<t*LU=tjwE%tS&Y)#rVw2SKjdESO0dS%GGlUHd#Y;$o&k@ zl9hByECM)WySTYboZ}@`V(J~}gqx7Jp5$${f~~gq6rZ$r+F<xW3O~_PStixx7_WLT z=sS3m!cSd+QkTP_=>c@K*c_veCZ|D{GvT4w3oAjEDGxoL`htBYMst1WiP7LLdCQ<A zR)=4hv(;6EE8`~0;L7&vX-UosdN-_!t0@PS1TofhZMt*<-Ft{w9PLG^w-qrxlVw8u zJm{3w{)!koIdbnU9#}IPT*Zf!Hh~M2&FYQC_(_LOBsBHNA3{(ARpDtY+Xil4{56E$ zSG80zjmHc43bBPI&*On$c66-^^lCm1>1j8fbZetdwsJYFMDle){YaVbBwI|~3DBSz z6(j}XGigWnJRGNJW$sQ%opKkS|4w63KvDEwn)A>#2`}(+4B>rCvEP;yom&LvP=MGv zvCQndGWm`(nYX^sW#bKb(U)S77109xK9|v0y@)qR;s*-@kRhlVb&za=@S~4U99Qi} zZI@xsAUD2*P&Ay$Y76y$Y;L~{P35JKT&b+GP_RZP$MjXx!e8*nED!CXazabFcx&os z2TC9888h~E!mniY1ssVXMsbn>mL`gw-yMlq**_8{pHmPJ`wp|@FEP6E!cmR|a5yHe z3>uKv&w2Tiz_Tav$RFy@z~@lL)HHMWYoZwDh{;mVzkXT%)?}|gMeKa?f|2Hr^OUf2 z?k!@ZL#XQE2P2O)O6=>CcGL)u5)KV;Xfdn0l65fRIeQF!8b%L}fw?Rd&1&7)4WP)` zvnBv|&iyJK7l_bAJtfTdRZ?vhvs6o%d}URVr1h~G7>u_oCDdER1yT9oQ}_d~pZSu} zejjrk$)~mQ((q!WG89Q~$V`ap-selIZitVs^i-x#?xKre6fJE5(z;bT4_I!GW<*DW zTxRl$Jj#VQkMV6>K_z$E5Jw~f)|=|-kqg6}uzY(Z4<`eVZkU{LH7^N%y{wsA%!Mwx zJxr^rBviXy*m+NE3&?N-D;P>r7LEmKbmVez6ljPd0yku0^WJTM%5R<&Ci8^wAZ(^S zE~5awAtSH%#1PN=+S|iSafUG1te}RnnZ1rXTO59qP_|&s<ecZ@@YnbH6-5WBc-%CC z*%r*D+Ed~WlKGM*ZirA9aGxqbiPRwSEfqSK<A-X6LgNEUf^r=}Nr3|OAyw8ATKtc8 zU)HMx8kxuf2S7gvFo<eySlk$af;pF0S!Z6J7XkA?>2X($NH~n39k?EAPcd2Cb0}_| zVyxSKNEn45h3U{I|H)h<j`e|a6CKH}YH#s0B~mP_nwpnhM5=a{xk$bJPCLS-H^hN{ z-Cl1*^(}J_75pdGS&!y)@i93;=VcMw4IYiUP;`UnsnW@6=3|>hVyEJ8$<VSInU;qn zi4jOVR2LT0$J=+6K?uNt+R&8<WhBDf%t#_1UP@S*_bM3G%Vw#(PA8YjY`IXfumJNT zv3lvtZcfc`b{Kd>`ajt-c=j^kY!{P&KKWo@`?4q{KEImO&-aW;Zg->CcQ&<0Kkmse z6J{KLv6ou;X<_`Wl|C~tL<*Mep$he7|68L<5^LP&S7tcF5FXRz8MOEiw~!1MPM#k> zbmZqV<dx{KEa$g6x{Ys<y{9ijX@Q4sW)OVjeId$@@vVfN59Wy>4|Kj%IA!0dmT{Y6 z(bXbNm@Vu@jcCy<weoKKOcd_=z(ISLXZeGs=Ju87A#Joi>JDd^=X{}9ys%y}FSKnU z3{eHE&MAn{v*owqLKpD>;Ze>liS+k7vnnwnO!Njosh2du-7zBHV^Jj+j^<mdF@&oW zkM`0O!vah9vy2XnHNMkM#R#{%lf`wY)+(zJVctw-u=R)64sMP4Zmk48Qu*@rX)kb3 zhEO<_q=s)dK4>6J!IgfE-8y_vS!Smg%*{S-AS_6d=py@uvM;?{*v^HCT%#UwLCN}$ zRNi|Id8iy;c0#uyORp))jB+MLDU{yLe7B$aUw;@y=_O@DRU=xW#}J||hn{e04UFEb zJYmk;6yhSZ;fyn$aib{sTsKj#RmP3j=iRV2Jy)u{r_Gh3N|v^>2&Xuy3j_zYY10KF z$@?%c*X#3y-`s=IH3SP~W6(Rw?oEPN6QKp*3`t}*hl|K2McrvOf*ymNd`X?3UKC)B z<sfKYf70RPeJ`rY9Gm0xE=4F4wq_G5{wY-j+$FJzO>pd-nq$?d)xYmNEste?EWg%m z+SOrdU#5BST?u5KXgd?8As^X}VjS+EuUaCdr(S8l-YysoXuLo<x~l>nCGTnkYu!-; z!_h2D!c%Ix^kdBkWjBH(CiP#jnoa$t(K77_M%KNqcnsQ*V<}C5f~y~oGYv*J<(ET} zL^agpLY2L4C`d=ZEz3h#W#Aw<%2eClR#b?51#W8Z#)ct}T;1LJI=ZZ7l0y4!Y!|Cp zD?*)#KPT6*j^C*W%5o!reeNzyrmCrpRld^XrRP$XjE)-lSI<2X&;$%v_`%Mry{&{Y zGekm`iO86#`4*=wd0$%rNPKI*LQB|SxDV!rA<)`h<d1C6PT%mbQ}U4ErT&x)xIVw- zk~b0LO4aw)_!%R|FylDPNq1f!H*^K(K~T`edaRcDQ6+ssPZyjBv=YD#_qR<*IFZvb z3>yQH7P*gtb@12ns-FfG0E3TXXf`wS)ck&h`}>WP^+gnD(x8jNZ56O!FIia4&QLn5 zmOt71WKiawx274tuArcWBiJsGd~KmlZS!C%Nsh;ru9@XL{jxmx8a=fmhEhgxu%L95 zupL9gPTm>~TFE=+)LsAqP!(_#omg#EQW6SQSte2_YvJERNlb2AEounENUSe<SS^Os zcHv=dIOXtrj4(Yqxks5D@uUg`Ea7>z*6*a|IC;KzGk;*@QNVDZXDX4`mA8*v$kU8G zpRf?hflL4|+1lSM<uW*>5S?#t`)Wz)$U*S=nONQn-sB%5WNT-leMrb(eqG?ObY5PU zvJ8{AxVRopujMx)ydBEQUVl@f#c`gxCbpEzx@E95LcB7_Ekp&g<{|2v<8J>XLcNXZ z8=jCuuRPDlSU0cTd2@+l%;%MVM(7sh@YPM(R7({$2Oe<VL(b!vroO0nRVbxHL2r74 zqYv{PpT%u0IpPv_!I+*-`)u)1Jc0x*HP@v3%$vxy+GbwS1uFXqQ<IM&e~5T9zUfWj zrC18QlHhZ&hHI#MwQ3;e#>xj`qiy3i6L~{&&Ph|nyy<%x;n}3DE8oIN<d#?J-e<=; z(5%-j&yy=#o;iXG`PSmQ5ba0SlwUt`CZ28W@;)L&)7*{ZNZLLeU*Zml&<d^HWGwp3 z<XN&JX`U%U58t3A9mGYRykFz=!qXSr=uZ|dk}b^5p!BK_yxBM{CkC|DkxD{;zdRW$ zVrRsEvEJt=g}Nj(HWOLX_D<liQ#MsuOv@O4!RlM!8G}QZH+7+Ubk`=BuP0{gnz;gw zWdCqWOV9YQBVEIdBDY+XCJG+Ncj`A`&HqJI2JXpa%PD7luWBfxWDP%RkJ2!@MAA~7 zn-n^mReVmAoU_rz<UPeNz03b+5T1CzDj4!NUkk_@x=r~<Y?~y~bq7fmK_Qn(3r60S zC<Uj!aLfUk7yX~%-y_<%o6!!(y&L-%OwWlAb7(+rpE*xmbfu2I3XHJ{-kkYuc{B4* zV!H3SHQ(051SynI^grV6eNAk$y)AWWJ(PkQ7V3~CRUSlY6u5%coNive&2g$b__1;a zibOAVn|Kk+0tNu<dWcpmyk<~?<L#iS-0n0153r*Yq98LQW8M>>&AB~$W8gkHV(#|S zWtHLqU{@hfZNc1I6{+HCRCq@-2)N^mWMqHr4AM)F$%<jV)=Zi(yTh`aB~0|?$bLo^ zQj)Pq(YzMzGqHbL8Sr9ZBILM%mg}w1RxaWF72}k01QFD>=YdU01@kDFa^S^seCfwu zcBGkY(yt?a-Izn62%m{U$^XnDq-q#|PeaGK3Hg(O%Q%5z`*iOHYYx+BpUZjmgw9T8 zhO{~V&eK-j2V9kbA<Yis(+EUEoJDnG6hrPwR?J+(VAJzEoFOs}f9wHWzUjGyHr?U# z1C)*^PP8uI#v59W%G3$nIotk*i#!@$MCb!;an;X-^Bp&v*WtjgcoVG@FsU(1eGE^_ zREAE1j)T<!wNgSZaFg^828VDuoU#*;ni8camtOl=&!Sor@K_ry_#<bEPZBt>**T{l z^cj8Don)e%6oA~<X`k0Ltv=AlepLXd$Q-#Z@Pb*if0op?eo`wmykc9gKTwufwRhxO z-t^deTiTP#;$fLo22C?4n!ape`W>Oauan~L8T>fsi&XRJZ2i?>Y>Ejhnvllh(%7a7 z*K8!=l7*t^X3CHFUyP;UH#t+<faNnOxOK=_Ef=bBFlPs}{Di7ML$1&J?{E+8WWr^~ z7~j^SP2?={o0K&_z8t7<<4#D+(+fbr=#7R(<jiCPc$*Ed0cd09Kw1auGf&=HgwuO~ zp<tkU32BV>`=Avty=1d3_q-EYi>mqiA2~o9(E1IT#|K{7v`;};HrfOD%QT`5i=3Q# zN`c-mT14Y!*=h!1heJXbklU-4NCXBorS<s(G77}B^)R}KT2d#8jqAv%TI8!sapRS5 zYXPWuWb*TpAFIVJuiQ`UJK}t4^LF*hFrwd6zp`lojm8uG(z))HO)87_F8Z4TuCz1k zCuB#&U2*5Z3aRG~x*bJpE+IQ$4U$J>w$^!*iLVYR9+oBr*TGW^bQ#62&t6bc#9<{x zf0T)q)ZZRoWk}z8h|6JNLK7`dA>~)7PFDh#AA?sFU#9GWsxQucm_1va>$tX8{nxSl zXAL@BIanzt$6)jAxwjSrb<Om*8FF<!ir)hA+jLCCR*zH0C&ufoOyvEG+SwD0?s$#~ zYq3D6(sC>&w*|k9s5JMSpQqd}VJvAflulhfP>%tYH8%YovFsj|HWIl0t?_d7v3dab z!4!Ta4DDNyiH<L;NI+HuUy%p6!9OoI)QZz`lYatWo&dry7+*Cpz}^oI>VRSzni+%( zIJhx03(*{TYzb#OnL_o60hr|vc|ejWhZeX`NX|+#(Czh9h#PyKDci|ftsIkQ!Y@5i z@i{A5zCs`Q#8xQ3JH1ifjp>%W!p{l)!`yy{n+6~E#En<4p9C00L%j#j{{e$_SH$a2 z7dMjcW*`QI3G31@vt_D8L=DyBLUOwOI$c8sE`Z-9XS3Ac4X?wmw}g1GEO9RbOrqed z&&A)GCc#$uq@=P4{|o#OmBe50p7eD=r<G!h<QGR}>&_GDoP@F88YtzYDNlh}Q`)bz z2*bK(>u1G>xZ);%opd)ill|}v^lDfMNmRn;A}AjN{GjRQ7qv>MoTQOFI^m=IWVAeD zf&&cdqdZ1dNftO6i?Ama#D&=_iI9Y+IDzAWXCeq`BB|9UnB+tDliquk0H7x)4yMop z-?-lBVLPvP$~zg^XITzLkA9}%grDL|v2#OWIqUo8WBmoHwhDQdggNebvgSAxnDU=D zsXJzkCcd68sd{T#B-LZi$aQSbxGcS%!x`xC9)U%Nap4lLp)JWoV`7TZIzem(luG=b zXE};&@eIu=(!u2+uV%@)3cZ}*pEU-KAUt856o_PBx+QhNCZ;nb`{5N@-karBllzBo zqn>@y6tQ+0-QPUMeIrg^4Az1`!bXbSFHWV%`I6sdPR_J_tnmj`3(Phyo4#XPILWuA z(~VRBEKUskWzL{YEg2H!@q#I_`_ijQ6P^oZNa;o-KnSZOOa{SYX{f#lZ4*N^_8}VQ zx;OkJME_K=8rv*Ak%r~E5RN1LH^Z!ncH<`gIvAsNwuf@Q9`#QZDsQGeSD#$o+yi?l zNo&jtZUKN+x3?YO@#Bd@P?L8VORK-wnvlUMb|ED8X@(5>Dum^!O4Q1W9!{Kfx2UOU zPJEuVT2wcv>2v4_L>tMW_(-OZo*pG7p9c#?AB()cWEGnyWpmQ|Dw~*~QvrD>VGAlK z$(9p|;7cZ=FqK+2k29dF|F*`Zv_dvXUmWbI53wd!|6$;4e~W(@t{ZG<KvKpl;dHax zPFbhqQ6m_bQT<5BSo=lqN!(PfLVhqL&PXkOh`T{8MHng&X*(|qD+Mi|>sPyH()rMn zT3sOZYTZOP&<^rMi#;i$9loYx>}`GR5BkMIVkVo$b83hhX8wCSaVmX~jk8m$?xY;B zo&o<FLGEt*3@Lf;^{$->dL+&AwA9>droxaOo7<P}Eoxr537|tvTkOMVNJxrDvXl?| z18*yYZFPb4LhsRH%~hV-Po>pqtttBOWSgbRe9n3f_8EBN7R*uj=}ArHFN{-^Xt?nS zhI+&5)7z$prWfanPq$=7_(ZYa`n9p8bKgE4AKN}QR`fJevLk(_Ma$nn(R*;bP^aSw zNzCm~7?`ASb-pU11PMzCJ^tn8?dD~h)R`+q84kM-s}%^U+D`+i>snQY!2ABYuYRb- z!1YzL5i`~yg{zRY?Q`Eb*_(U+2+-KgYrT@hlrZ;s0?0qq>eBf$mUR%ElD5c3k;mZK zQ(rM@u5p`1V)RuGjE)7pCA9sjT*$Hw-6~(bCI1a#U9l&nyH*2va%Wg@qIX8QHX;Pb zYFB??GkzqqV8>lqxBe#j<M-#z+y^GIxEt)wL8eMD8qsn+ck#2y9p2UNRQ`HSsT3iX zz0m0QQo8Ss1F~U~t5K7AH>Ei2_WKl9V&-jLAMBGL@u4Fd>9amxmse<lh35*sG%N+| zpQ_r^|9kJZncwsz{8r53Zl?BY&kV&^&%6zvY$|j7#awN+-eLm{94>|OJF?PevnL8d z@V~s4d5AsG)q*ATi?M38vM*@;1|J}CTS@Mh$>*OsVG&D1H{qbj$CKzPw0h%RDKQH4 z&jbZfsP<9CFjZ6!R-^cvqr+CMSFO+&D8*q7UvMqbhIiFNtQ7m#+NN6|BfOklBQn#n z0{<Q5JjO}IeL%abCAqxwaMP>RP282Poj@mVUFQMSP7W)HSYD6EUH9|f6ydrUmh2ah zT{sV$;L4DjYU*iK#2Cp?3_p-RH1+B+d1Ylki8W|;=YR$MK-ph0V;<DQbQYu+3tugM zJ;TqgLCWWo-)tLhkztZJi3VrZ?tj^ThqLU?4bIA2Z={tTezJ3_fywb=AS{cqBST@V zN<l-ROiWq-v-=^eN3&jClX*uHUi@j{D|XLMBfQvuf_PxqA9}+qg3@<GzM}iN03|wF zU%9}inwMqy-G59`MPF8>hHwDiuU|Xvc#i_D#qeMUz^gWZiSVtAi%x90{9g`eM?^!P zBxq<7G91J&$y%P~r;$Yw1=pg#LeckzU7Nj_z_I|i7K4)d>gOrI4}(ThaGM+2`brqF z?Ex-0fW`>>XKM)Tp?8>7>{v`107>IUuq^jJwv{2^WRPA}GSU=%pA-u?h99D3QScUC zTdhzFhfhWsA!I{nIbqD1cZ?ODWPx~_NAog&6Z}iaSSP9{vq1ikDtl<A-VWbEPx-AK zr)}PS!ep%obxH|KVBke#T&Zf<F34BJYO&MS)gTTb^VNj^cqh$jVb&acC13CHV1Fz= zi|kYgH-ZCXBb=F!sK1>C!G|q_J0JbwEl({7M&vI0@?PJI;C_^?HK`KD75Nr{sqqWD zVW{zNTl!D3*(I+RD&JKg;aHi+5ZzZkP7gOuK7KxZ5OQeI-j=b8rg{!FV^KSUg2&G_ zELpf8YtUR^1qFTV-^F?s%IG1k$%NhjOZ!1IJ^pwYu``5uSD~A`I5w}l{C=9eUT56w zSY^)`Qm9}j08pz_pUx)?^I&YIz8f_}1;G$<LlgbqkcS=GlA-s_k|i-D{ZWQadLHE2 z`bnznMrGJZs;8VzlHTJnT_%F_0qbEUlb9qe)QJE(Af4b^?s#tj)#vK-0cYdYIZk*< zg=5cedfl-1cUXiYUVOP%u}2k34x<rIQ;4E>eGE&F>^0CFr}>C*l9BX@%`L-CG~MG? z$7C}Papy2n7(-G)*yqI4XA;zn0<8?NS{SwMM~nQ*`Ii3yiAY+5+#G#B(bv+WRiM9G zx}XM<aNShxxnv<2qo7gi*mNr5`p4K!3>t=Vzl+$wB7a@)F3FnD@Z$Y}*Mc%&_G4jU zIFZ2Qetn-avAL$!-|bWie>LaJ9GIG)r!p)U$IDVw7`Hsk>jqxw+U6$v_&wYXFD9`I zDal`g9kI%FxMDUJkTWE7C8<FOqddw{_azE4;m4C<3F)yEJXwoMP7?St^NP0G=#k0q zlc{n@iO$HunQMObTjzt-dVsgWHn-6FM=;<Q)6mx8y!@K!N@Rb)>T$W1aV*+i#j8Oe zzoA}oH_ZHYhgEP%z{%N~Wf1a)9eT<h_ecHIe|sD+ie%<-GD15}nUR)<(~4{$aa!1i zMigeJC<KiFYKOVbByq~|7)gb2e?qu7BNZqh0gt4F11<pl9eqLOwBgkJcCyrkbr?4i z&}!l}LdvceAD1~XX@lqau#!KDgC$4i^lGa<Xdm0R_=3Pa5+%8t!$PBT=nK1(3$#;t zKKh&}*-oZ<ytj{WyJf6`AOK9K8T)+YS7a}Bn;ew}vAhZDmJZW7llaVkyb}l7MH)is zMe}H@>jQFF16XPzxQ<2ehz)Q@0X79^G`?YW3PBn@!DmaQOwgF*`(kXMmlj57a*x!P z#GQ)0dxyl|dA4YD&4eRI(;rog&!}PNnLk1(Xq|=z4P}Ix()m~*bD`Op=Goxns1fU# zQ3(R#Jr^o_q<~K*72ouctNxLB2VSx;%9fPzl(8#Ktwtf}L^2z!;nrYvk3_PkQ|UE% zDH&r+F$_tBP$=&F6>cZZXD=9gVs*eLGxp67ZR6yM<ofKyXQx`eO6$#+Gvr*;iSf@r z)wcDxh$_i6Zg3G-6f%b|Eg7{%5k%A+-Q5UBPEU(=HV$NZB%Ua$aa&D*jClBnJFVNF zDp(`C+hzU=rk_8;LcGpum`OXb)ry}WN=SO)2fm@*jL{d^V@ym5=0s(MU$4+#(1R~S zwS-~~N;KRYFX<4(r(|T@wKU>WtY1rK&&yyGz9^azkMr<el+}-74!DI92ebgjzErJl zTU{YNs<15In96QN-tM-dgkdv~!`H}O>}OM3yEz^0*Dxl8S+nE{W@g;TuGOISWemSY zV{urDryNi%?8Ql5rVC!EgN1ZUC58=$f!Y{7IG+XU0Ivwevp2|7cHVyTJf6qr4&JC9 zwp1k}aJTw#5NGEb2wE#D+IQ`fCPrq|{k+#b=qh2sgF(Z3RGG1hJEE~Q5|Y^SKAA<! ztJY3OL&ti*jH#a(u}fKJC#>8|zs?6gV#fZbB3=H0EEYQ?Xk|~0OZhrXqRdFSvbgAf z?J%~9YuqeH`HeR&C41dc?bctB(jXuYQ*#$ys|a|qf3L+utO^s#Jm5qq7b*Xy6?bF4 z18=R^MLbT4bmQ_Lcb4U2k;%21a+uSuG&rZwU@Pj6%-d-c#^6NeDG`l7T(yi^N#%Hr zoq2^*V8vK7^ipgMsl9yawsg*CuI2hiGFJZSM5QmzU($jerp+hNKPBB?Xf0|6@(b{Y zJSm;%N`tO@%sn)mPZn+(d{sYv3!A7d)vu4WhrIdGrsW%kO_W(RcV={leMd)VPtuOs zZO<p;V&oE*QjE?Mt-kPRBpZ?4Kw@B`NC#1<!@-7cwS0I@fPW{h2R37M0{MpB(8CFR zB|7$Yhzck*_e$q7fObfnvtejf3#_LLOP`VrQ<o%eV>#KY_}lqTYCMYjRgoCZ+&a@} zJF380aZ3opL%F0HnxXmk(#@$RHm~!C2#tg<@+<yII_(6_GMzJV)siEE!vr*szR$~| zvtudYXIr@qX4Li6-Ssd6Q^b*gVdYI1oX})1XPA_MsVeZXgY#G7EZ>eh=%z)F6gh0b z`BE?}`G$H5d&r=7GBD~~EPGEUN-(*yXRgt_77Hp$wfQ6c!wA_i@!(TxPR!A!wn?sk z0(+ws=&mgLl@qa6B}39)po-SRCug-#wV>2{**WswmsXAW$b`5JlipKrq`p(qY)I#B zJIQfOivRv5%x7}vdb|iMxgtd|`2IfYnab#!cjqod{DQ86I9$<lT$m|Q+O5|%{6Bmh z8JlXC*^i{&X6@nAK@&-@A4h+j@JE(%DreVL*4!sfEgA=O_Tv<W7GqL4Thw|eUalj< z>d69e4N%MvBjb<FIN&-SN}pjFEJx9AnbCgy`8++4AzO2Iu2M1apWBVUZ5&rT#v1JJ zVlQ{FVQI#!9#D`J_EcYPdsDCt+ObZ1OGap|_2I0bl;s;mH*9qvPes&`)L*Ns4Ua>* zJ<|>5>$$JcP;bzgK|@)QR!WOBRC3_dZBNv+pzLO&Hn}OnSI#T^X<__7bV4l4gL9Q^ z!_!Fi*Wbi|4xRHiZ|0vp91DXs>aIZ^_f?Hu?uUV(xWAYfH?621n=4`u@&|DEiY4Qf z3jHj{E8xvD@*mx6U&!Y;*}hc|xp4JEy~6Xl@)&|p%RSxB4<BMq&cD{T9)kl*E+QB5 zD$vg=j3$ouM}%%%lpxJsbZ4r0!rq*(@W9xhWjLiz-}Ygqhfmsah%xe4-PbAaI67id z77Im;Q@IzKZwZ_lc!z=?t|r2W6VoLUZ=6?XeWA~;#%#yACmIHX9}O2tcUV>YH@S9G z&PM#Hpde;$=v#7<pwQW#`_|}|XWYnVw}lS%zwM))hM3@Cmrf=BAF8waQov`v6?pA4 zUQneBDCoS`xN&1o*7Fnv=9=|c^jK2EgTAlAC*H-Xa;oI@hg9rZ`*}oiPkUSTssD|b zd3RdwGbXD&cBA5G)A(D`e;>m}uN&Ry!H}evPL+~Q->u<9Cvbv+YLOvdAc4<~(S{+o zbFn;R2{RWYWWp}73~s^`m0iU-lilPp(MnD&dMZ~?5h#K^V3k^FibNz*U`Rf)Jq?Xc zz6Kn4_BLQD^ZX~34rkT51psS*_AN#-`t~(oe`aa2>+Y+g`yL}1;^y5U&In91sG0@O z0Z5(^He^AkdfF$ub}OxS>`pDzaI^eViVC<RWvuf|qbQwAW-7H6Yn}sLF5WoXW)jnx znu%_m_R-c~?<y`0e35}P%F?UQ3YxFGrY_|aT+(_@#Gh@LvRKploF{4Rk6wYNX(8Zb z%IYC^!YBE7bGmZH%x~NZrX5{B$FwyeYq7A({Xs!VkGUU2ogyOH6BC-&p5C&4^7v}U zC6UQCz6ce5;0$1rCm>#<n??#z;x~@fM9qr>@1$ioFBK~lrIRYI5Semya59(WU8-KW z4?sREOc)oJoi(XepIarW&en4WLDOT-8*}X;vW_&tmL#U?qi|`Fz%F>Fxg1Z@!5hcH z86r~Yep^R|*)+j_)f~98>1n*k7v*VO5OTYabUM0oT;jL(`msnS`TN|N=x3vF1oZWw z0BNZ&a;@shkFAfletC?}bMgEJ2Kh{t=D_E;DYqru<F%vEH?(GEY;C}>*%!p+mCn3N zt`3`dY25j<7*cMk+$s%M1xd_+UR_`JSC1h}Tk3#3Tv`(p=(b8L{DJkY(3|XoDm^x{ zV?>=h9X4{vXAv{^s;)XN5j*vMD*)xnxC~NJjmR02ctS)_DRAZYZ3ox5ekLXr3c{E3 z<Z~q6)|B6X$7iS2gGnTS$x8a7UjOpw7DTpXci45PR0U9kPv+HdON$i5=j!;pBmPn8 z^fL}z9LRfk<BL6VKr8UNILW1;_I7l0>uSbS3xba5c{>SG1UeJ#gG~mbwY~Gkf26-5 zF2lh*s>8E-6&D4iOVd;YD2PuMXjH>D;#<cUyE&MteCtz8cCBY=dCMD{GLP@LuMf{( z-6=gQtlKGPsnOX6C+@24{CuDIvz*rv12aI~1P%vm&RM^F#`Xl9tv<HI-DL`Y{QGtv zD%RJbR>!H4{&3qzG4*?-$y^#excw2|y@k91u`@f{Qy{oScCRZ7pwd#0<&ZJg;g2Gn zjC_`7o)!kedylK$x=pI<wNN-BZR^m*-(a#$Z6>^&zxa`&)qVCHe}OOj_j~inyL=vf zp~-i|2%VzvdT6M{3Cl~>rZ$qRzWt9<^uu3S^pf(-Xc-tq*1;yHA2nyRjH0v^`67C? z3q$fZqHHt~fng(x+0Z7X`WZI;j2c>6Z)?D4G9Q7slIk2~Bo(*`3Fv&8KefR0<MtdS zRu6I6Z0@RqPo$OzK@zQTyPn5LXfLtaQ@}3Hu;kN%yGVp!GL_dud`6VelK)sGelJs8 z{=7-Zpd<iRGPDCH{uC<cOFg&<zsQ=Ha$y+G0zzAWLl~twy)_t>di`w9o6UYk`kV=& zt_#~Vwo|KE=p8E~`=d{1lw&a2j&QPzsCoe<A~o||SiR#2=ctHZepeb(&2>>9H+{ho z>o`b7mgKR^JM#61v$f}PEin%s7PUU-!>PY(m-+~|75eh|KIRvf>5Y0uQ7T!%o26sb zVhJ=B<npb8X9i1vj^_=Wz;S~sR*7_co>qk~JaWzyN$7%e+2)o)e^b*0dWG<YHV#0w zbMNpd+^NVXpQnA<n0iTB@H0<}N6pQ=Fb*KfXWhv@vp(M~fG=k=85KInCKC+->=svx z<dPlsT5$vb&kD3xOUngtk}Je!N@31eapBri9KwZY>^C!E88#qch8Kwb1X=aNwm<g# z)@bs*@JNVrOdx2C625mPYeQfz?{LN^$7+4aqV1<uD|E*92Y)^7U;>Vez8h>%ham*$ zG4C_EYW8gdjQKP2Z*?&QZuzWp1tw*NTqXOvM$&u(_RB1$vSbo=AQr`Xh2(%}OsX9C z5v}$_onAfEOx;>@q_($r%10vJtU16q_*QscB6`t{vC?g)tGpZRZNN78?_qM&=ZU@c zXfWO@B>9xB123?!MOP6v$!N>4@=KNuG-<!>n43lS$0qT)J;BZd=1bQK4Xs<$Yx8AB z`RQ@MriorAnb#g~>jn5i6ftWE0B7m8zR$dFa+}k##R92@Dnw#F<t?V+%8fl4|8$PH z6K}oq<vI#y2)~-m<Lw>ytj}(vPJnoamFqo1kHNSC21upELYel@86OUx=H2*Ef^qw7 zcHMCaQ;K@k`}vuF)~z+TleQpkQ6Zop3aWG8hI7D&Z=UF*s|3^&uGju%xC+{FJA2gY zHLeS@{Vji2PS+EddNBQMb3(ep20MB}e(%oe!jt<`*_EQ7Oi(8^9;XEqM#8JwDnD8v zx$6YjwLCI;6Y+(L2|{#`A0xRj<4h|fGcw(YDqa|i$F*{w^K-4v9140452y5vnFo`6 zqO~P7<qd`6aN7`UMwrP{fqUGGnXS=5RTz1kwDUzL3u?w{46c1pnieCHy?T__n;9ux zD471$#<_K8&LFTv(q5pzBdu+mgEf-DZeac~$n~;f5DQ*-2r-?LSExw+FlpV^JdOM$ z0L1y2q-xZN|4s9mE#mP}_T51_N;LFMZ**RLr*Ba4P_B0Pq`0b&I=4kjv1S)&LJUAF ziFkRz?B*@Dx;56^<Z3D1evFLFMq@yT8P6NUz=jPp-C}a9T{4j&tcLOTU8QhGbK5)+ zMT7=M?k(y)KVhQ_00M(}cJ3_}xL%81GFYwx8vdC$CB;5ry64S>H4)7f78(ju!0k|} z7NV=Jo4)e#Vt?Sb#Tf>haGx<>2h|LrVMnn~#fo&>sRB{#cB=hRk5sA6O6Huxde_fi z4(AKINJ=-YuRHm#aTWO+8}jVuv=ySgBW%Pht-crOQkyTB*d))E?OgcDy#-rQBX|HQ zC?8P?ju(B~8<mS`(0^Bf-Zv-`qDd7u5K;O>Q1nr9K$_T{S6lBU4I)jK1mASD1X!Qs z835S~et+}j(pk)W0P5|wDqWys@UgMPOzK*j-L80`s)f~%ZBa?H)JW<U%O!4wm~CpA zE1$K7GU|GmF8O@VCC0hcb<1S@07fY<^sa6qq9h)`gB+4P!GzG=5xIW|#P4yqB=UlS zu}mUf!|A(I?klUz>*P&4ay>St&`;du2kNYb6Adg7epcY<#l}UBmsr9#zQyRP1K-?U z=^_U5ufA$f&bLXBO-_FHf={gmJKBZkE=pkKKZE4}zH$IE?EI7@nQuK2Kwg|!AwLj? z2A4z;UcxEki7-#N5hc+_$P>hn)b4?sF|TRn3xdNhKcJ*)&T#yv4M~~di|I_ltegm{ zi+zDS_56YKOZC`ueB!t+%~2AvvL?BzTUft48O4uCxa}Pea9zFaIKIbT21vIorz{s- z0RS$U+mJr^d5VvY$gpt`i8Je!6Rcf+Zx((HeT_Rw^@lOsNlx-B$+8h8<oheLRyz$~ zf)+bN34;<x5xUO=(C19xZg`JCeh(JMByNJ&QCL*;xg_Iz4ESb;1}A@vn~Y?$k3e>; zp*k3Nzv>o@LZEA~No+vUGEP5ASa%H(Am}~1!IjUHxl<53KsV-@32^O!r!&b`kYg?q zM;Xzp3j(m*F@jIPT^Ok9SA1t?SYtZiN=%TXn*HFf{CR$V$R<3{Dau+clBY&6j}@>K z%=RXzRuC^}4!OGTC4E5TWF|>Z>LQoV`nu(N&vpe}LuhUEhyi%$#7xfp<cspX%1WML zH4Dn0Zo5%0nYW@LGHhJcgBUSgH}P?mEk9(8eIA%aHGlNf={=4UzRu$LnZPca;sol* zE{bPG0`UMI&R!6oZWy-(|2zUeGON~;D=)}Tmf+iD=j8-?dQV4ho~9D=%o%X4@(ZZ_ zr1y+)j5<v`DX=N&;%JgLeaL%5NV3wC@0>?i8}kyP2cElpi66)P4FZIEXzR>r+ovZ? zd2+gXsZi!PIqMTH(H-I&17tM)pz6+cXOpPx(cFAqr`QB29AN$t_#I=G)qLKoeWi=S zdbJ<nZN{ajK9r~wC1kMjyt*?rDIl}k_1vEHIjkFPy!aYFd49%D+TkK>r7&H{#>-ah zxiQje-?l#@r%jE!ts3zF&244p+d7D72}Af%;7EcUj*X1#m7Z-6zgex}9)Y<vBJSCj zq^B;^n_3yv2Oqstb_DjUimY>nt;9i-qV`_+iSM!4cHPvgFf;%OSi&8GyHVcNs=>JH ztBzh;()jpTW1f5+t#AcNqIE@+@5Fd{&_`L_u^1L<oAmlXrw2J@_FT9XYZ?s!=i)A6 z;lAj>VG$Thte3t8aJ^qeG}7?mTr!XSE=V7%3z};~%TrY<qImeKR!MODU?w=c^h8DD z<_q1?Zb@o<7EgE`4@;eEep!FR<;#CEawn*oUGU7j`l7rGg8NCpZWR!hFdZ4wBtq5V z6F(Oz?AV`EH=!wAQ!P=$eXp;Gr=9!GAiO0}m^+D6dPezP2ONGDtI!2+v=JxLTU?0N zbz$Tu>ExqLBe=(W6L>E;0;l?F(<p?@(H#)ty&KB+3nkGP%1vOY^-9cGY=vr~UVmtO zA>3pcE&-c~D$cNYH<{Pnb>5=4irW)8#9_@7PF9}hbCJ2dOuX$-af?Si=V#i*U<F?* zjdoO&7&Vdm>q1dyzF7GTo5mhjD>GeZty)?de-|G!Hv`Xj1?TM4uxQqK_`}?S-sH;( zgxjl5G*v2^$ph7@UWp;k=z<3?Qjfyx#A0Njp8j7JJI~FrdNAM*#^I;gfIxwIP0yx( zZ2X2Rr?q?^RB>Tk!!eq!&ETOMbU~VsS-AU<wG2ywSB)b|G~9#0{UDDciD~_%O!$Ef z^vFsM);MT;YmlqetR?j$!cZ?^?G;}GBB$Q0jYmE2e5UK;1^BvW9C`6UhlAD0t|&oP zf$*BndmlUNZ>asNmMys9d3O}9`LoVJG2dD?pwtZMn_Ri9E|YmjXn~+0vR_Z*5V#<U zzztiMv$SZox8I#;_at!lw}rJeRo_Q*-xraF&0MPXxPv$jQ>`G{&>Z&*I@aux>AGCC zG|bP9a9`0r(FH0j=@>83R58$Z`eduTvjAbxpPMD>_P~>bkyaNnt1q}I9f_EN*vHPm zE%rit&!$F{S&Xs^aiu?iVhZzLC*^%IZ;I^>Jc(R=1Fv?%jtmqc$pYz{g?FOFjvSbf zcMWD`D_s83gVZ+mn{vX`yUiF7vUL}7vAWpBNQYT?sh=H)8?S#vkFJTo_gcz$eCx6A zSjkns>*9P?+j}yzV77wAn~9T8T(Z;}M&WTKp4VqlIp6xlM&KLeedLvUoD=YhRceuF zpJ~05-vGQ}+lzb1SKKWY8zS9er)h7Ns~e$t&O@_9%?Y*$Z=Hk>GTD#>!jQRn1KylG zm&+t^DL&x*9L*VkL=>Pon?w=2c73oJy0~XmFQee1yku(sXv>t^Yg2emKV0I3;Mpj_ zw*sZ>^@ID|98<y<esq**?Tzty-OKpy8dN84bZ|Y`)!Ipe=6fkd(>w6!>eBdAjvmdG z!cVEm&02^DVT>VH$NU-+6V6Tbz4dyLEq58O*EFP=|2Rv!TRRg{iJY{S<4+w!{ah0) zTs`yFsA=~FIBE;Evp5M>mNa+;zXVDvFuPoJ68Y{ynX9_c#X>8;q5AKX2A-r~vC8pT zPwb>a3(Wv4?)gj+6O7xxo4iptbb|rS&vE#T@HJM5fz!l5IhW<=zq%aU2$hSGX9_8k zw|C%w#009x(|9nfpaovmb4-h8vbJyfxmV&2yf3f)M*Xfit+|H`r#kQuDtTD^0!J>e zT_%rwL}dp1Qa{cFJ+g)lpc1cWO28Pqy~;Ag*}G^RXr^ha8tq79r3HV$sUmet9P8#l zytifkAlo<ZunR>mvH0Pi`ZE&Uzk}lZVA)oh#?1$+dox#gN}%DBA2)&ZbIKDiA2UWB zooCmzPIbPTfBA|+bf5-5{_TA&Pvcu+52_x(1wY?FH{wM<j(ihd(tnL$L<fe#rk5>* zv2UuC+TEr3gt5WC&(_j`Fc?kENo@vy?ErJpCVlYH5ZD%4+IB(WI+^vaJZcHP?-dQ5 zIsJQO0nF!-2OHH~d7c3Rv@%}P%;4s4U;lSXz@=02f_fBx;GnH|smI_VOx@w@NeTP$ zF-Lz3Z(_-&ayfVY<4^kmQA*bPU|P`AAqgdMY-_XMrCUee!ZmeS6<6F=OS|E5iJX#H zSP1~l^59g6h@ByERflo9??Q~rf@>Pz6c1*w7rm*CcxQSg`cr7Fdw$%Vtie_4;<;Yt zn|fAZVZ{Bz_byff0Va!Dgi$xl2?!$kzGe2yP2_={klR~6*X!$)CEv32a!*~Ph_bk( z!Ri&Pv~D4LTiBzC@K;{mzPX;a>hTK9HqOCBr2ZVI8+&m>-caTx&K9``az7>(<ov`} z-hCj+3QnLF`ZlWF1-Ldtep$lb;TmmK@;fN+74%bi3?<-V{9jHQR~8O<<e$H@jWWy% z7JJ*AS}$Zr6pjagvcy?$&p^jrOg4e55#VZE?m2?76qlki8uEG;Y|nppcpO`xBKb4? z6;hzG@Igl}JUH;0%Vj@Udx0}NGSL(+5x5~3Q@SzOS>yioeEa+Qg!h`)x0|!OxOt+D z!!y@0Z-SS)I$?2|@|c%qNHxm*I(DHzClGCQ(JOq3$9AN(8f&u!S4MgN*y2iRJKpNJ zygnLim_u(2!fPSOy1cvGHJ`V~V&k+pz4yj=ScE7w5eh%^iVFD&Hzqj_Q6=|0JzAc? zl2FbUzM7q8zMi)SW8yP4x*9)Qd><*m+=+uOE!R!Kui@i3`aUfDG1nM%c*DpRN-n>) zS^rOH&#<LD0V%FAViw>(y&G*1sGne@r*ee9QrSg;05%-aOn5yW|0x3RAyez|SLJ)i zbJ**={kMyipDN#jKe+e8cV@PDk{bWrJE&A00OyDLQlEqxJ@sy1{ILEz(rMR7#CTg+ zpk^_E@?SXl;hVvi9m<LeUyXF4-+l7sGs!>PJL@(5{E9iOoqelPI(=hgI-%&E2PAv~ z0;oYLxUDx5&4nIY=T=@czvr9NtIvPH?@OrTuj@pdkuiP$d-J{|m|%1fGq}8#=$&sg zCA{l^(tyTYm+{s}|8Tkc-vnUWgh;diph5aH=CUks6Pg233*whg0p#4XAnmmjJAPde zG79n1xIo$xq!-Oqtd!Dbct@*j|Hz(_p{ctl#t5&Yr;2FHyHO%ujF|%LcC}hI1w*%G z6;(iqjjJ_8QI7n>Z+p{5`jRU`2CP4(%GJFqMW&KBLPjy{mw{@G_Zk=A1q_b#IDU11 zeD&XdY+_Ek9>b|@KmVFsx`zO=xNk^reef20l-Ocb9Hgdc+6bUSLl)<%@w3HTehOu~ zAIGh3q0K6L^XJI9myO3N17F<#k}GAq*L~^*PonWjVMCv1VO<1G_V?gfEoRj1dYt$P zjo6#tYM%kkptdW;>s4Jvunv~Q$E!jE>_d7EuC`ngxCA~aoyzk^3IF~3cl7gqD%`Mk z2sd7p=w&!K81Pl<yN<^F+IvR_{o8qsI@{Cw4b8}ax+J^5CN=Z8h-cbW5*5nWOv7f& zhSLA~pH-{0c=%G@s_AdlTH~GbWoWVBWxWP|k&Pl_?4B1-N*>6gpjHbE4CEqyGlq$D z<i)o8h6*W<9(4d78QIkfjfS|ifXsRUe%3Zi-S<>Ys}s+MFV+bdZnHoN#0tMYx!>Om zVP^bbOxAxjsg01@sXsJ9n94Po^jDfql55gbKGQL29(C!s?1Laa-DMx{tvX}J-!PLD zeNYRxi83NW%A8YSv%y?NT|rh6O>8cxm2uvF(1p;ZDF7Wyj1EJ_n*bsNwune<gKl@U z{<H!;z_IBPL7c$R!Q4<i%ST*~TjX;}sj7hC{)#J*6QJat!ca2hPU+SQUd+X@q8D?^ z*s6ISD;Z?krl9#8JKan(`Mcn}i<`)_oVB^GEcd_mryW_^K!BqPi?4lym79r!s+#ln zl?VEVdENlFNe)59%<v>m>-0NornHKI;ZMy#PO1}QAZ~!sdXJWwI~&o=S+Mvo;BD@< zMNiP(`}2ybEzb)?08t?JY4snWlX+?ku_9=WvJ`)mR1(XtI-A{?9~X{U=vqRa0J*Sp z#3V98DDh><UAZ&qg3Yw`EZ{}<xV4=dD?qei1B$YYKbT6TpRD<xuk(Iq^8x?;LxM!m zh^<Dby{gn6jnt-!s$D|u^`TXxv`xfF%-DPHz142)S=Ab~Yqb<@Q5{t4_?~lqIlr7g zA=mZfdhX|S-|zRUB4&we{HA{tsz&56jwf*dX>gGhs)WdFv=MO4zJ(6QIPJ*muD_&M zDE<PWf3&6HaqEn7dB~9VC2HxVOK<Q_{>}uA8U=e7e>qLFfxY{Til?~iMxE~0=-vtA zfTVD>plb{U+5Xq3Z_qatS)TS=4#kUb68VMr8BC9w)&GXycAA0Ox}&izoN*r@n}s== zoA;9+fhWD@IVuJjfWf5bFQG0;s~jcXf{Z-CIHsi&SXa~EpI{o-R15Of48Cf@X?IMa z#yLM7xtlbh9l0*4PJy*ExCW(F=r6bt+rYo;FtB8_SyM13X%NM~aIfZ?AYM((6zY^= z(qdU{1^p^~O9@lP`ABin+e?y9)JW_27yM#L;Oiq{kJlSq{2Cy;@t6nx(aE+tP+JZG zM3OJKALH7mxe_N3B?BdgQDZ+)km>vOVZCCG*L#CJAt=Z)OxzI^aDLlU0qiV7BYWG# z984{ZNzdDBW@PaZP}cxs1;o*VGVF;Vf5XfR+WXU&DUi`28u<e1w~3|5kN08X+@H}W zTGE`Fv5i?7gQL5Z6MC`Cb<(3FBFCZtkI!=r{w<2!Yt>en4AQs;@aqyc`0cafYgPze zy<Uq%NsT0dwpoL=-!eUHMM(l?;?5|lr%Ay;OEC2V+$~rMzQLrPUrk_4oW7qbI&Dy* zjSlvT4#C&<tmF!}|K>_nm@Yo!;#;VYyZ)a?t&GlD+c8rD#N9#BR}qs}m=c>uy<Nm+ zqPTTpzsc$%SryH!bE!*N{FwW*WVo`QxiBt>I+@9sDd10<@SPH47Cgj3xX(5Wog%0= zsF}3iGlBd<o34TJ6~=o3z=iJ!>Z9`eB=*@z0RVf;8G~=3?h~l3A!sJEP9(2?SLGaX z*8Ak1l+OY)IcSO3(?}i?Z%S#Rt~ArL+he;S@5EfO%Pw-3!P_6ap^MaylUWw#)amf~ zuRb+Vz(>2Z^0^a!)n>x{)+6cxWv%>YI8IynFbft6Y>K~@kLZUR)98&KDJ**X+U)n{ zdCj+9vOxE(7qFHuf=L1wNXc1b9X}83@1tCyN-M1sYCxAo7AN4&p*Q*YUF77+wPHn# zpY=Ud-`^pJiZM;2NZCq5uH+t?Nam91UyScf8cSlNom?OR75PJVd@SVjS_JTe(Xqba zx+*ak1yghU@3{zp4y=B1mt)Q97Vi@(l%2Ygv3ziC{S|t{0Q$>q;8W+~u9XR7)uU82 zbAPv>9MK6cnq}wiS88!`6&pvJ;qoZ<6)sbT@`{9#ZflBONC=An*N;T1`j2qJZhR1D z%yJFof7h1wVHuiUNvv7ncf?%$@|MFBwkSXGeuuc_8z3Gq-M%S3)Ww>!JgFPpDT#?h zT)+P%Agx@xQb1quq73)pkJHbMOkbnV;X=q`f-1(`w|H)%oNc~WA+}7w-p;_4uB=dG zi6PLFdWrv!sU%a~$4=LyG>!fra=>T-m6u>u!H;e)m-LtvA3>=7dvuxionwKaWp5|0 zj<j#jP6QJFO(lvxYd(3ZJxTkp9`|?tbB+k9v_zJhz@q^TAGDb}o{M2Skp3ol?a6hs z9JzZ<_Xs!lofBgsZeL>z`SQwaSzvHVoUU`;E82qVK}k1RZw;}+XyH^N%*YR*)w`p2 z#jQR5K)5@L_LDT1R4l4=BbQE7a&CCId=-S&Sgd|dShqr!>pi@E^M<`7jW(Zo&^wc1 zy5+b~7ZW2rO{xpVM8d|p#ufkX9LV*Kw6<r{8dpERTO_5eN}NBv{+~%+qneXn8(Sog zw>?bNSHZ6*Wp0DIa9i`VsOM|j>yQr*%~g|2*~YAwLiZmW>m>DmeRmQ%!`(zQeh}x} z<HV1+tDpY_9Grx1YtBWt(be_6>{4my=8wBMw%G8j{x51JU%*6u#rYfabF)F7Um4G| z==6UjlU}>e(K7+$l)%!6&>t>u(+}q(p8^#t`$B%fiQHWrH?J+8H4Z!{&x!j^udf{4 zwNnA460>H1{Cef-_e*bun?PN}CiedAzvCinl_c6Cezk!I=E^}d%9AsylOJjum_TqQ zrAsQvy-e`fzbI5T;K57FJ5BUJR$>AcAgE;2C2H$vPEH`n;~{N(i-ZKG-UKom7>wuV zq*KPQ&d4_3uIydREJ)U^|Lw`_U(Jv!PSl4Npw<;;$<1VuXdEPb78+jaoAgS$q~aY% zXC^HG2WNEEu5d6PTh{O{xAk+PdPcjHstNbQ(m#tr*P5$g0s}H9Fn7@HD6#By8yFvF zN00QCSNqZL9=AkWHcR+*+*WLw#5VLB)MwrxzOj_ndE3IZLU`*Tdb>uV%$NBsA^fD8 zU{%})<4>E4>3CR~U45AjSqEt}(5VC9|6p0Q3;1ury-DmbjA60$kD|NxnM48gEB<VF z<c0jhVionPw`IFgp$%l2S(J*22qAgseij?v7%l<VKnOs)u(50Cga~os73&feP1d7| z=t=T0`+3X{Wn#FADpw6900{>MRQ+u<g{~1xt0AD7t5C7-@8hInerUQ4<;v-m`&>nl z-wTtF+Q2l$)#;MMnIYUc;iJs$!HgStH;NZ$S-Ubs%N2tCZE}nZ@ylkq;%<e;4T#H8 zTf2Klbpu^ebjRz4f?ny2-&@-FAcSsW0SF(SrV1NWd70v*`93-`yYgmv1ybJ&J<|Uw z@C<)@m%aU{4ciA=6NP@l562xM0Lz~9T^;<iKqmx8FQOSXs2|3BlhqB!)pSAOpc;lr zPEXR+K3EEC;727br@I+;3?X>ms-!JzG>bgdpna!DD>f#AyH)NhX&{Qe<=FZ4TC<F- zf{eJrZ%}*EZfrnOL#{?iEmOFZG-38s1ZO3oQ5Y+U!<Vkym<zdWp$bFDLa0;53B|B( zPJ;d9_?+!)cma%kv@q_ln){6KAx4BO9n;)VDn42IDMbAN6K_YK+-Gr_M8lNK$I*}W zwQtBmuJ2~(H-IN6u4LWFn4`en$r%hh(EI$jBbYh-4j2%keY3J;m^96{x*gLb0X0Ch zy_-~;4}VjW)5wBh;)Lif9ki<xbzh<0eAi8=lYuIqh#V?GYp=<Cetb~_6D3wmOeB+P zP>3|W-wgVs%mYQeL2!GI;Zy=CNedDl(BGSk%z)mW{(3HTMeJ7b3T$jWou*N64$s%$ zB;WT)@wNezoJs!g*|&4uSiefb!elaEMRNj{QpV)2WV;mD>k7|=wDy1)z8(Ln8oivQ z<GDhR%@z~mV}&(MB%vk~D#FZ@5zr#Ne%<=A-RY5{T(<646YEG(34LgvVe+)dmyOnc zD};veE~oGzmZ#}ghu%I}d8;9L8+!)C$r6R!O1nTEl(Q<oq>1jA`&Zi{<(AsvGmhHF z(MzT?^s5AUU70T@F+-~1rXis3#1TgBe8gW!0$slH3b)t(MRXm2GP}vy)y`^u(%O5- zs;1GE+z`=4Mxh1g7bl_?wop;qF&6r!^M44Qe%kAAtDc+if69Jm&eAObO~@6!E*~eC zWs{Vl6t15=cur<0v<3-^s%oN)KjSCPVZ47QT0h(fcU9syn@zWUVwT*H?v*K9E?O<X zPRSGkd!Mc7Spjj9oR4spcbXIbJE{U+Ay7A#!rvLD6vrxh^~R||JN)h|IHT>G5XtLi z`?p`tX&CkHc4uyxR=UX*>W42Sjo2Zs+s2?*JE}}qEdLqg3a;PM)^CpkjIYSXw9wHJ z&S&nNnOx41TaF9m5nZ7Kalj4M?TCvKgf?;|C$C?i6(njDlFh$5mRRS$TNfY(N)mnl zln$pLu8W9PF6i|S^iuZ>CI|H`eU87)IM!bB&OEjMh5OByYCXMf`uHGyP|5-v3{bfX z4(n3Z3PRa2Oyv|Uw&6<?-fgkhh=0I9BY2?|xYLipyPikCYqcm4h0=)=4Sz7)c~%70 zlC4BF=kT$&muk|P8q*!k_Zav82eM*fQH`6WjTeM|hm6RHJeYDCZ-s~}$wK-}`N&m- zYwZFpw4>1rSVg2@#L&vu2l8%LTV7`5J+~bobBZ@FTMYb#Y=ih>RtR6KW_@G{3Ay(8 z(N5h7<(Ay&l#dBXa`g%r3q#unHSE)`Rxd`61lE!*@rt1WI$^S3+)2qK0gDoo5-Kb* zgU8vMdG-4mgU~<(!rrQd2Y|ocq2lk}hkfB#y@s$Uhck;wU}}OU{<Mw^chdfe8BE`r zU5I-yfSQ(X9jMt_?!(`&mDWl!?pRw9dHH0yRDkokXr6)qRC<h+v4rh&DGzEDrv80h zDzArltt|i=#$A<AG5bc|B*8V*{x_A3>4^vqy0%W0uzZ#&!AN-+d(-Ldz_sNqHFemL zjLBEqFoo$4aioVODdn|6>KYmyzg8iGrY&|8GkU$R69{%mztOyI6_mksN$YmkshvBs zmZGX5NH>_QI`jsIdXnzS4>(_W(1rGM=u({Zb{r;6Y*2dQaN!RVSgbPa=?VwvqaaG? zlied)&8MI+(3OY7xeViraVsFP?n$}l+tk!pK}*V;3p~k+wxvqszpBu6@h#Ij$mLp6 zkMpCkxoh-RPh`#zM)oG&_%3L$uGKAp=TB$E!|Z$hTg}D~+KIxdaLUUg9CZ=!pMfMt z`M3SR_QO*Kr63Sj-G?N_ZI?{b4>)HUd4e<&Z_UqFT<T;&yYr(4a_8qrf*S>EhT_D7 zoiv_`Q&re2&UXpzDvbVGL_yT(G*6LVwDpeyr5t$LpPdA)l5eBYXd#z=x83LpO22*G zgmYJsA9b6#v8~`j8DAS=(gka?Tf)GQ)bw`$kQ`B#Z=t?pEg^$1E#Px2j|gIYyc<!M zFumEDv6Db@w2;E<{(O^+d05^)uXAl$tWgJ6y?d^>cT1#IY?tzGtcA^|80!F9RyCsR zA?0<zMQ_bQZz*g#b>}z6tdZk2%xHjDO+E=5b=PHo)<s_W=0ld~q0acX(T5(YtDl+) zte*@v+1i}3Z*y-c>Km1O=oz&ijz;(Y!*2%kkEP&i;JmEi@1UPwwPGH&QW)cRcN>uS z=)<thnJ#l7;_2>;kT0FAws<-4!QcGLiAz_&Tc&dXB0r0G`SgKn?tvF5uk^&d4q#R$ zgH#DFI!w0cuXyy^i&qt2uN)nPX~5Z4rF|>aV-$ZQW9edLkoW_6g5dOCy`z@sCog$0 zAd%)tSxI;&51lpt#&o6P{W1i3Snb0{G+3JpDJ&Uu9_HWt9KC(V?eo6o**Bhgf|TXq zhrE93!0hpxk8TScjDz!o-f@%FiEG5Ko3H=t1KgRHy!NBNNsAhkTa}KeiCeEgTE&Us znnyC};)sH~$&k9Mar(di5gN1|LU{6cn0Tz}_8y?s3K;HkEm#4+zr6anqZl{iCgi_k z2U1cT|DfLf%0~eD(&OV?45`bLDb2N<{o9l`AM%hQ{@!SG#f@?~DJF&QCayf|AwAM* zJd9FMa;M5k>V>70?nF%IQAjOB!Of{^zO;=oycSL=ZV6Idi2m^NKeW#JSK>P$?wylG zz%91R4PyDj7l$*gdn{!?lI|IFrFm}^`j-Po7}*;yZth3jycFAcnkxLN9izeDguM1% zie`VvN57Nx4>H}7-h5J39=qQC3D%0U7j!I9t9TzBboE;z3HsSpDH#7xMc-`)26(-t zdAlDC$3vuun=@fz892dR-~M&~c6kT_uxC*Jl}J;1xzVfB5d6q@^S-b{)=yZ-hL@&| zy$A7k$erwZvTh1&3Hu^VK%RJynJ(;ZfJUOB_t)G?BPD%r)1+OoA`U*=C(+So5H69f z4@nhHbQhLs|J}W3U7es96^wkG#1?`JBPacX)Ov>@%<sCaLiC>wY#!}dNOAs|uiadY z7Grly?eZ4>5v;UG3!%Y^!FiP{?(5v$NIKjt{}9t9ABIzp*^72<zA})I5fx01X&ec? zn#E^Aa}_wm1%5*ZcjR^5*4BSjM-U`hUhl}V*rF~2o%m9CtcuL2!3r*}#6L1!x=z&D zOpnNZ5+hc~mvv&f<fSL3qCZZ_815bSSoa3+_sOV#oTdxJ=DVB?6hGHs*W`%57lM*? z4O~>A@(|e3hu4CZpcvcnW%<zl-H?7)fnT>UBT*pK*d%xQUwY88ZUpA9h)N<g1fZlq z;Vxtjk^MMj@HqQI*pP-P<;D*Kw<G@HSWbmU2fIhtMoIiSNfPeI0^=!S+>~y*Ao2tb z6$a6yL=uOD*~;Bk9!>A`T?fcq0%AfA9Dpl0$*S1DfK7pNwH*f{@0r!GZ`np{&3Rtd z!wo%ByWD@UC_^T!!?z;oflAODiH{lnlg34$4#<xTDpcAl%3R0|elV7K5XeCe5>2Aw zaMBnQ7=>PMe?ci;cW`hjyE|Q^lPo2<w2DGpm3~K90ij5Itf?Yz^^7r_cuP2~b~}|w ze=iVzWl+3f(o_aW;z^+m6tk6o^U*`{vOexf%zH-jR2b?^qmwN$y(7do_F^sXYM_m( z#83g#a-2#((6G6F>ostg`SshyEi47C;<{@N_aGW3d4qXT<0gf#rrv>jBHWj3m9l06 zN<3OY`4FPuL0kbr#sT8EkIaAvPJmzgp|r4ZWZ#dQ8(KYlgUO5l<S0BeUXEaLn{rhL znW)7XERduZ85xZdK&7l}+>qQJFl?gV-a;8~mn}0N{LtP)VLZY&P-w1C+8o2&7He7( zVI?e<lnyNA=3eyRHLWLcfm~?E-%u?3XQ<}NUDhP01v)_W?Vy$hz&DL%)liyN{Z1|x zD9iNd6fFm>y$_@NVYQ7%!G#7ZP}EPHiczfpBH?VdkP;!lK;(jonqBX+mB9UXej=-N zK`t%K*{mB8)v^4}d}XKu(EvDe3~h-fLLChOS8`}@^lO|Rz87uZh*pv60QEd%gcWIb zOnZX39rjQaJSod*fZ~4Q-KKHQNUifQMiI0}F9Gp@*F!TErD&<acJ+x?6e*}{Dr+{M z@~?`UeUo*`4Zxb+!z7*N$jrF=Sm-GeaC`8l2%xk=HrDx&rXu@VZkY~w7gSr|gZ}bV z^O4@<aFrGv1iIuJ`&g^HdQddiB=?b%$b0|B9gaY=cOWQ>c*L#X*u>^v^Pbs8`dr(V zUK*E!C_|zUm=VhBg<*N|d;78MTJU~Ppng6j`Mbtq*@f3k3y@LEv<bRnQt#tnH~2*R z8Mhj9EXdhX;(?d>9n%MPvuCp$PT{?_LBp(qB85T`x$v!HR=ay>6$$3#+sU*}ld7Tn zy(-^&U?=f+s~4k?=o>x5O{o^W>hLXo;hTl5FHUE#vf79C9c4hB)u?~9yvs74f$BXo zX1Pn`ljHc9`d+O7>+<Z(SBR?2<U1&{Cv^NK#f<@&k|uHbSvwV=N(bhpKIW!msv!H- zlK<my;1~yQUei7zAgjg~QC~~*%(=lK&_+8u`FA~x@o+%Ol$Z7%1ds{Rc<3c^n>}_@ z`0E`hk*2B*y@mpfosD5+TZjEaCs4RfA}tkL<;5gra>bya53SrUYYpcxFcXgJN|<X5 zTZ_ERE1Y7VxjN$vYp=OT9M;!3FPN9TokltqULGsrz^c7hS`|MUsZUq9iX-hJ0rE9o z8Yg}vNK`j<cZVl1WLbj~kts?61nVHV;NNzXSEOB}feZ=;a8nJwLCnzMCUk`GZa98@ z4`xlq!G|$w8hqj+9F_2GE>}kBC#Khq#|Q~rRN$9yzfu7~INHdYqYjAX48gGxJ`-8q zT*kY|pwKw(d(?a*E8m{0MziXmso9Ns5%EaBEnl+xO%3NJTC`s=jlyPMeXuNF>%pi% zBXfKBGy^q-7p5vaQ3YrK0Z})FP!}N1>1WTY8PCsYt^)*kIzaZ86=gv{qDVHZUz~t- zy`Gju3Hsje$!mtfdJw^I=@Vxdl6$n;_>2kH()<vz=zuQ6YJ?lg@Rc<=9)bItuUKl{ zqWmjrOhcS}HdUPO0gx{bc%k7a%?BEea9~M`Y0+$7=uUen<7Gdwq?)I&CAom%N>M~w z+xSDL`>Xo59L>`monkn;*$iFx7zM}%eC(B1)ISC!29HWqJpb#7*r&!m<~Xr6;D*2u zo{6LF!!#wd{aq3=_+Kc``1ZtV)Xgfrt8q`R@iIY2(%=&u6lCFiEy&3M)jiS}iyLR+ zE{{D^W;(c1J%s{56c$|2g_lqQp?`%jcyZg+4G^!UT-7al0rH=l_cTBqxC_!W-iza{ z*`0#2?mT07-LW)Z*G5I$%B5JYjwSy7p^L}eKiyu>S)7y@M<rD@LHSmiX8i{^X)vWN za9&(L@b^0QKXcm;$G>c88pChTYJs%0^=TA)G>(x1Z+~$L6tn%P>yfFsnh~F>?K-C` zq}Nol8&?Lkcnv|+l*lBn(DSAvM%BAoKL9iB!yElkF8>ta%*N!)%6?PBu=B91B(W^H zOlf#yM(I_(!r%{I5H17C6M;sjNp@&&?F<(74E<C7ANq!&6zj^t3?=a-PF<%G5mFSL zlic;A>u49REv1VY4%=Zl-&-_E0Bz_xRr=|&<JD-=g05`Q&*ppq;Y^cEyKuE?s>yRj zWfEEUTk!O<lbh4{uIuZg!Fui!eSg~>ljN*>qpI5~Yl&TfwtI}Sa2}ucbh~NNv)*`~ zu!jO!PJ-ppT?%KTfhuVBn12!DDr1MmvYSic0!m|+MPod&j?0$UoLE-H<l6pT+wlq% z2pr|oy){*OBTpu99_m11XwoX>Lsis8Jr6`nT;&saG53~|c<C8kvTJZR7noputi$!N zijU3&83qFIhe0-Flt}iK=k4x}bbfD)H<7<gG&(1_op9X;L2;_1*BH^+x;z4t0@b|V z6`QWc*ack(oS=iN5D1r#Z(Wc~Qy);fF^8fq+mx!cgM)Y}e_!Gfe;*hXHX91Rx>7)+ z9LNUv@MzdsOiviJ={lAmEzBHO1x`$7H9yXTKd=D{i)up{)xrjGCl0$lFG9-KYZ8r> zn!hF%edCEDf31?~a(ejwGNU?`G00x%_6>K}LaC{=%4TqorczW}h%0>I-N+`;jzuA8 zf4zRpbMHFOs6dh{uZR60wQ;L%3$NMFMbd*wl1^+lyH?-Ow7S7Dk8Z}D$soJ@+D{Po zmtFMF4`*yNGjeaKAIr@-{-p&mv@yNYI#hfU(-5-9|DLd~`pk{T@71<aWvBP{+(B=B zUY+O#6Ct%Bg4A}@-5aeoN@KmwjT==v{rTz^cDpAaH!mcb?s)OG62S}nL4(9~N*~VX zmXA2+{&_=xpSS|jCuxmpw{WkZ={3DYXHjIz_Rnnpo*^OBqug|wkn_cV4&Y9W@xD8D z;d(QSX0S|+f<;Y?-ZbXEmN|Nzc{#`GNF=u=ZY}=-06*w+VSWJN;X_c4k_>6-rnx6) zAKdPs)}9>X(PN(-DsUYvI3?y4A23dwU~AnqnJzEeIrCAP+HxZI5OsW4<0J2WWCO@q zB#8~J3XU%;54u_=ij6lC7ML~pH102IYC<=WtVMT5?>+dOyVf_%!yi8LB>YO973d-t z3HT1}wDJkLY`S4?XY-lD2(%)ONOZ>9S)&13k=3iD2!*oQ^V4iGS=X>kT<@m-^O_r7 z5mO-mf!Pkz9A=`-xU^63j2`?qSg&c%emI4K?{3T|uQ;Md0iF#L$xkcS_`|8>P5Z0{ z;m!}W&58@&CZC)l*HJ_cT1{S&0j1w5G@RE|+8*lZa!H|hwN>+(JiteZn^Q`gGk%)O zhSxmJcnlz5K}rC*uJfYf8d_*uzhS@!8hI#@&Y{e*K20{z{c!PHM+?2BMbLLn+0uwb zqt`(mK@&H=MxpZr^o78xx+|%4V>0~jP)i$H0n}eCot_m=phC$sw%EgqSe&?5xO7>G zF@v*?Z4qjrUwcKT11iA5GsvE0qYq4J`wMs$aLFJ9&0PeIeFmv9Yc#gQ`HNA~&>5)u z2fdti)K6X@CrmE9#JpF~wr<de4}8~-2M7mV201zQ*qa(TYj<yJgga<Mwxowk9e9M$ zwx!obqo*9!w9l<9g$DD3x3$>^`H(^`E<!ko0nyNYq;3Q=ia<wK!u9WC%_%nY9OqIe z<e3&};t{@b2P9{PzkJXnS3Y_7he?@%<St(~l^a?o1NYm6{8(MJw{@Na5PNPCj&T8n z6n-IC?q?+Y#Jv28op69ld4P{_U_g1`bK#)K@}PL(;I#7Ki#*|{W#v!nghSfOLwbcn zhs#5!grCiqKU))i{;B-=SK${w%U}Ex#x6~&H8^2e-BgOSmA$fYQX*HU20Gww4l)(t zoA#xK6%j6uexkb(KD#tkTN-eYsK^RJ{AEp*rZK;!$|znH0#+8dPwW+0d5cGp27LP~ z;*vOT0jQWYk%XztNLJ$nYSCOqJc+e3?*1+cC{L6UZCk`g$%v+~&KN%!yrt=uV&{(F zOO`fwi*u|@e=eF4S(y<pnweIanJ1c6R+&{Nn%!2Jy*EYdt;|W9sQkN|vnHDNJY1!F zAn&L9WB%}@u)z+xJ<MrkzO`n7V|d~5=lp+DMM7f54xD0W_?||=a2^9|Szb&jCAsWU zQ0!Ax`c$keOsrhqBahQ%MstMYrs04p6`@9~rftu3^0KhgL#Lfs9Z6GtIgk#D)u+YR ztJBrK+Z(75+f~(Sd_K~^zaMy0ye`WX1ps`fU@92^03<Gt_W>*=@^W8r0Z>4g+c5=w zcnFi&Wx}s;APRm>KS#H*XefqV)?;O~v3Mi_c{`d*uW7p<422^V$)?DObbw(n_Oz*N zGF#Srelqi(t3i(Xi(@)kf495&+C*B(@tc)1WybmXar#g8W=n;dJy!oG;a87Q6Eg;| z8hC18s_IU4o22zi-}jx)SJS^*bp`GWzg}kjw$|+qnxHy2m;TU4xFY_1+2X&g5h91q zu)*Sy(}ef^c>0Ns=AAbMx1)Tp4q*{96?bfmUn~FkJYQ{JoW|WH@4eV?|NYdnZ2A9Y zn8IMZM%{{j%dO%C=3hHIs6I8j-;Rp6efemw)BE<Dy1zFAcHX<XUcCIe+D`^&YgOC7 z>FxRRt2*v~C;a~Y`Tgx7(D&-q#RYI|krm3qY`Gpv&8cf2#)2Hh;K4HN8+az6-GVSC z=3R0KSHSK@6w)UJi>g+0+a!vVRcuB}v;`I5SpAXH5MbKvVVvSx(8IXCj@_*U6t!qc z0#mr#cA~D(sYB?g+~@6NW7a4K8sS*X$5cxfqF_8=8|9FKi4^^mp~j<2N^&c!{FEi2 zrm&su+q;0wDI0V97%S&dS)M8gAaP*lVbR@!@VX2KDh77sG{H-LZ?~AlGmFiRFn{Wp zz@&@ZD3qEHMr+-qB%!%o&H=Z`9P6sRDm3RdfJhv^5ZkZemQfZBclz|y9*4jp!^(_} zL`hJVMm!ym=kH!vHz{B383wSE$v}&_=a<&})$zSHRwrb?5~nW8opdAbP*iL1>~yE? zpl$zQ%Z#J=x9*d8|LW%7w1Mm3wM|*0_K7873E;D}lQ#KOs7CrZ740CZ2d*P=L+h7R z?0-~<^M)AK1I+nKAtkS6omT$S{sBRk9FL=MiG9z40m@uTfSu{R*W*E|`ztb;RN9BP zWhlb^7$8}j)*r|~j(B1!6{O^N%6JFnZAIDl==+?dy-LxP3BEE1%<s#D0_?G{-5hO$ zj`~=RJH~inj@{)SE2^&~yyt^<xGQUUXD<G3_i~)81^{*$J>SCk?^PxWmz{lS&$zcQ zdAjX>{H3l+>mPP<UE^xq`c5U<O<4ODocru!g}u?~UQJX6YHF)Yy~LLlD=EL@)&P>O z5_|geZTX8%i9d(SZ9eBmdxcI)N6j!c#pxWHX-$RJd>=<&nKaDTpDTeM{-VTWulE+< z%(3UEyN}z>e{aw8$nWUqG*YP?5HQcec=IFs{+<8&c5!hoZhWwyL+0}qc?L0D*Oea- ziT(Q-2ahcP3+wjLS|5g8Ia!pYEC?3`7a+b729f+n_;!cGa1p~oT8q(s)=ue&%(IzH zX59f!56xg`5c?d%aRZOkV3fKU1bz{iLE@uqjH0mAkajz~;t5`-oMY#r&^5i3<t7qT zOR^YZDzqeA{0Qg+NA|woS~vbR#Mp!{QnF)#tDQ%2tQtgp)&?N8BAhRv<r>eAc9QDa z5uYa=3i8P>o@I9vLa`pfN=XKkA2~~q!b^CU7j$lkIVHW&92NMLF=Aldl#~lD<u;)l zG0j5oI}uC7?q%lPr!7gX4&N4chGH$>y-TCTpa5Mm0|Jbp?ScUG&oyeTHjgt#{Xe4k z_2A0NkJF~XSlN6l18bw1#JSi{a@CLt7o(XBr^HWk#hH2DNwPVgz<}u8v8jMC!5sS2 zGC0(i!al9^DjNn+af4rA#ate%9r~A}Xq1g#=xgRdL?ILqX)G7@I^B-q$W3!N5N3T+ z#D4#-h7%&uz05Thv_KYglLq2lPD(`XRO-=HC5p-8kdUBN%3*3OtQ}pd`1%s^$qq$; znE|!cO5-T~*@PM_r74D>M^hAAr2M1OI0Ay?l9{Wp{!wN5y2||J_<ej%7{x8EOVPak zeA6d?IJMQFw$G9Xm05p{Z(OwwyWsoIrMX=Ho@%>a<L`UVe$->>YcMnh3;mpJCK75j zj%*VP!^%HP9G=xU2~XrvZ6`Hly!LY2WjEDP#1<#c)wt>WVbo?=2i5zc-1H`v=3O)? z_#RME*%~Y_T{xB?bRlGF(|tgp`(|7leVy->ekw{Y3^UtwKdVIc!iI8s8w|5c9fXU% z&xN8$dsY{K-^YV&F;`Q5<LRj}R!udJyLMkoaJTzf+e)v4B9QLEZ?f0U)PF)5*s&n5 zhC(<Q+x@Vx{uxd80!RWSl;d0?2A#wV$s@WjLq5T5E9<l{`Apu{hRDCs8`eI*2SSE? zBQ*>++oKl-1dSSriItnI>8;VrgJm(UhQ{XOO&$EhAGN$P;XJ<-({7o6(g=-(^UwSq zEposn;lw+{WXKeTJi72i!;d5~25HgzDD~y!N2!q02@FGX#)#o3ne5X^H>2jP_miLG zyG}1&`^Gn4Cj54kmrtjHrkeA9P41}wIemj=Xepq%vx~lZHcc>UDPnu=R%^}zM4&v2 zg}FIVs+{jqrdrArUVk<UIh!e9Xsyt><1x~IjknaOwaVi4o^mw{P_MowY<*|nx||&W zBDU7j$3QeKXBpjBpEx}GVq|O3k0euLulY-Qk%fvDr_Dv{{J6h(*eoxlw70dreEr2I z<j?Xt!^`#&wP_=EP3G-9e+d9Z^x_p@0(J)l!H!@3WiQ3PL7wQFh0qY!GsM}?mld)U z|KS3anZC;hmB;u&^=;8iU<<`^@x;R*gPa-Y&aWZ4TB6ZO7t@cm_E8<9<D~5KZIO$+ z9pe^L$7u@NWlg@pMYTfT(Kd0cH|mx0UHM2)Kv=d*t?_jI5>0OL^-oRHR6P`^@74b{ zu4wDzPcw$Ws_m5bh9`ojUeZ3PDNfk2V>_9pq5RqKVUZQUL}*}r0#vuqY%L2^H<=s1 zW?1xm36hHBFED`tE8O26_x`yKM$q9zxDN?;yEob1{2o^McSK6)-d1Xgd0_bOIO9$C zCxthsQz8Gp7hLJt)%oCN(d~$|5&oO`*66c0r28`<qW$6i-9Jkcp8E|isrJ2JY&U(+ z8~3>Qo928YWP>;OVEAtDar&F{PbwFu(+RyN<#+$?*<740yy^Y<^3C6`As2tvue`eW zJ#zQoarVXe?%h{s@8A6U*>&;vFyYnt&fSZ%dJf*7Z*G0V`I6GnxPnb%TA+Y|@~v5a z!3&$WAW8~x;Lub=E{KMJ%{c<Ivf#4e3^YO5VI=NBAz1haY;KwsSf>Ly&|MwH3H4zC z6po#R9w5QykaQCmxGW*;T49*jefrCFf;a$3qRe_5@DYM^j3VKeE>+!(aQ*gh!-a68 z-{HpW5vGa}X1{~yjOka5BdjZYU%ZU4cBV(OxNnxzzqt?DW`iV1+q&#Vcx9+#79ySJ z=;qeL-cHkjHZH5V8GIr4|0BSkwMSVb)BUGNKLZd{SbV8X2qV69cbo~gFYeP%uG0zc z5{ygf;&h1_8E#SOM3YqNz7gW>AzCjQ;FWYxsbx?B;a;(Bbmgc~m(CNKMwpjHbd9Bc zg)Xs4`boATywf)ZXo#r|(!clei6H>AVS*tPv3;XPq0;aSU%I}-!0d|H2}}L|Fz{C2 z!1n2gIYr|PER?1&WR+mr;`?+fD1J91ey=_LU?KkN@A$*tmJC6z^M_F;BiQfk317Bx zcS#9nzZ3k2!+=F2N+nWxiW&8o5hRmD*Wq&Uo&@JeL?|UPTP3mvCrW91vv(xQmEgHf z6OkNA{7Olmhh7MbDGTX=g!PovFd*@<B&pM+q+)EOOR$z39DngLnwkcD6AH*o<3sL~ zEWX3K8)zXng80+H067_SlpH_>zH}hzMNnB{6-F%|2?e{Qjlen!lKD<aaC{2QMk;@0 z3MEAvO(T_!@%63(n1yK4Ln=Uj9V{;!y&{sNgGr-@q}@Zpt&wm~C2`&0beUk;UK)!9 zEPc#-@Lg;gV4ON918YOYMJU119S*Cc2<i=b%8jR~r`oIkGdt4H7i8pT3MEX_=eaYk z70?F+Wt4O9*NxEkOf!yQq8fu`7uGW$BjIJApI4L3ome0})AXyPY`Nr!m)IPu@7XLH zISB=sKP#S>Oy6HcMRFuw>Vk7t7IW85bJscYHZPR&wyp9$1?TN%=0&GI-GhoYk@LQA z<R2^LpIGJp49;r+LVk7RpD*VBJIx0?LgpK?D6)ijh>TNK1^hR1IT#@Ti7ul3kvNco zWi14z=>#eYzA@5EDZ=Th3J*-^3w;X(G76DPJUs67a=O=>1B!T$p?o_<-zXl*SQpDb zEmq7bR_-iTT`I0h%Rl^F{J<f;0bYWxVkrwO$>Yn>_jr6~iR1LN#8kP|%(~S4X{lva zsdZ<m?NX`TSt-UkUtGB~jlGPYNC4fZqt*!DA(VYJ3t9-4a8WM*hGS?xCVo_+_n?jJ zUyl)PjjR+&OGLn;qC&6T@MIBYB>F-kE`W*x%b>{yXkr-cJL3{w8Hj~NNIgL^;3>Rs zy_~11GJBjaekpqBmq@;Jm7ZJ0{Bh;xSe0`rqzGW}D9`s-W{gB)-2<!Hj-uPftI3@# z;T$!L4)KFeYc?xkDa4w|rJDT0Dht_~sVew?G_^BX@J>wa`_6!G>6OVp@|HSlsU1o- zqu~utOQ((NV7P#WN(H=e6<2Vb!ea;?>CP`&%lO?3KzRWe_r}FK?hRVQah|B@deBCF zp?sl~P(2by3t&>XHp*CVl?n4tIHPIHk+M7+K5V!KN{2>aVtIuHf^&l7YzeN#mOUUM zF6;^a8J#oXA(>9yGzx84xJYW66s2tg8c)KSSM|~snrJ57n>D&<0!i5(BeZTWp`O#( z0H$XCQOhcn!6OUKATF-GpX>F5I*Ar&CevC}*HvSo1pp9^qT8#2Cte0y;IMb3HV7l+ zJ>)XjLf?29qA`Y;-=>|*Y^yeI1K=<+8A4T_fCy2?F25|6rv0qk4oEl5WHr+GwUP@G zB0Tkr$!(N<(0dSw8&$nUY6oRsv(dtnwXFM+Srw%!2rk&mx<8!_u={^myY}2V^9;J$ z_igW{cTsLMcmL^nJnlt?b?#Nw$DMU$RMnk}!AJHxsY2i{Rp2*OYO#A%m(iOr05DeQ z*}T*)ka~PC_AAO^09vK?r$?lF0XzukcJHEj)X-~=goGIP`o_?lh`0D7Tm9BM|7!r> zyxkSpKux(p6@+YU=<2<XqWJ>@V0147F;wJzDqx+;AC>f198Uh(EeE0jkYsUD@B?Xh zR6(D+4fqiTK6sUL<?;vEW?qMJK5%Um56ur<@3>CK$>Ry{&1UhEP8#!cS2*D4y2@z) z0L}p5c=(D5TEUt<kb7gWfR7rDgg*qjoPDWvCVQWaQQ4EJ8uy2~|4?<qhSBTb`-kZb zT~s7dFfMcWh0;(0u?vj>1K8mPn^Z;kNV~yEcNf@58sx7;b+H3BUQclEA|32^nuep& zJC+lO=c6R9u_V>86x*@1(6Nl1v8?W~oRu*Vxhw5|81hudOKiu>LdPp|#;dx=YgWeV z&c_?LCYn?yT5KoULMPgDCOW$(x>qK8&nL)Sll`ibgSL~yp_8LIljGf!lPi-`=abW1 zuivS@p0#~FANqQMj`0-h(V}wY`}CE+aQOcNCV)#YA^*R@L?R<&Vd4J=Ol)a|X-ZLG zb{Mc@$s+fvRIOy3CsL(Ndd-w%%U-9-{nt5IDeGdCd@E#$Zt1(QNv^g<lZsMY!AQAr zv3{<8Yt>w}rChXS>VIphh5x5{sAjR*ZKg`{&lU2kK%-*EjB1Cv)viGL%~G4d`VXB? zzw@8OIPh(RhoADO){u@i2MHJQY3B=m>ph8*Y=*W$(jO=C6{4sm+mGEQN-3@~Cl1Uk zhc-N%$h*_k_GKCH*<bTkQTX<OjQ{>qvOCCYb2wRChj;}*!={UE4m}+x{kw~lV4rM# zJAc0UFc5RWd$+gy^!x72|A2{SX9pSdS*Ntk)fV-qd&S}0Oh2F1D|5e0dU5fw-1L?( zRB`>qclL@TeD9pj`ZJ1Sg@R|yYXUaU=qORV`jD?Q8_((DGYSakC&FRE5?ODHgyk%e zS=9XJhaipUN@{CNT(A%&MCMb)L;K7Q*Z%<%mD@>%@<hAKDkm)Fu^PoC-r$b@@j=fj z(pfN_?zyGlGy4FgGCgOXO6N$6CTLnJ5Gh(_<m*^jW|Zr&4pp)1*}AWQ`Wc}?HHsYA zys~-+vuZnYKQO&$%?e53ALD5Jpp-S}7!PJzpmKM}TPp1<%~f{atE?!y1QTCb1kg&r z`i1O{b<4cRer@}wDsjsKYt*3Px9+Ve6~Nd;%wF2%5HI{>&T`;NZZy)Hp5L&%@5&q2 zaLJ-K*24YG{LJzcF>)CWUz%?j()73Rn;E}vlOvDpb)U?8e(SmWZg=w5>mN)-cm7dx z9a>SsBvM|{u*OPT)0USW_A6_Iz8kn$6KK?9Ryp^zO2|4gQg3>?DOKU`ZcT1NN$nFk zva@iLBH|V>G<Vd$asJnNx}MsSHxl;r6vWxKi-gl>krbSx8GLjTh*=bEOa&16ZPv`f zyS1v$=&}+<{#l2()f2?Z-39yfk3WVyi<I`Q?CPJS$1dh<GuwsNb<6nkXW&{ms4_16 zrmnDLnAB3c(MeLuu%BaN!7jUMMq67Y*`n)p0W*p*RI_A;b;I}YmOzUrsk7aZ<ee&6 zfZQCgSo8Ah*?vPpL^_q(Z>SzAjN?oRA{BqExaHz6R!o)G6+0RIA$sNam7R<u+KG90 z>kKOX*e$5YSkVUY$$VT@&pJzr)W6@`F?Ijhm<`wcJ3Dy!YTu3}=uv#Zg1d4hH9{gr z<3p%|kxbz&5pr~zAmtaU0>3<Q;0Pkq@!1Tcg@hNpRaKxkvnuyH7R#qr80{0xm3mVB zI3J>;+mFZtKVKLJApa<@L2F#xUOi5Pb!{oJKH2i+te}vgbfxC+Cg5(%;;Ao!Mv9!q z;L?MhiE!D4J|X2J;#M$n&(XPG%=#$0alpuRH$D9-)h8Rbb&8e}xnfVrD_}y^+t#I2 zg`0GB%C|6!6^}$lXv!v}SP2ig^gu)EXGaNE#r&)^dZXx0N%g2k=C8`d75b^#rpZmr z#Z|JZM#1G$Oavzl0dnPMZdh_o5-|2pcidFn#2#sw&u1|<ZeF#0y*O4d5%nZ<#Mdvy zu;c@&J!s-!<y{Jyu58Y>l@8u{2_|ey{nHjjT$E*%qq`Y+SU6s5-$7(ebbor%HYRde zLX^2qSFSjsH}xp%d(N(5x$^r<Fwyxv_e%}HNOCB0TKb;Hf1cR#v*V)f`QA+a{#iK+ zRCU+=2NM`_#|?c-oW^}k&c84dL2>WBiQ-Htq8t*@;8T7Z?>Jk;_QOp}i`F#GWwuyQ z@U!kM50g~ZloCm~N`rf1GbH7kWl|BMy5eG#_7Frqir(Wu5j9)H`J+PfHOeG4dbZ>d zs?yMV?_RptT$Qz4l}T%rdAa^vtq)7J-474*fvUNh_|zI5Dsk&lkNMW7)@q+S)h2H^ zEn0_Dsq@HDd*PR0;%oFJTdu)?R4mE;B@LJ5<rLJOOoN=}f-!dv9`cDV4%P`Y#i~g- zUbk5sGYx1aQPo;WdoE5Wn>VMbdAXWoFHYCZw^V+taWg?%zqu$YX{*Zp;%$G`nvxv@ zdVUEe{u=@S=3ni@ccdQOF}3}uY#}%r_f;>;lj*ayLdT4AT|g!5!HyJL*P@yaWoO9h z!SHtHt`;#UKilqe7F*YZ_qWHb`wtG20(;lJ>q2J??Efw)2%i7_&wm8Ae)cH6>(^f? z{pTi)8_K`?;PDON!iF2PHoyDXry3$pJF)a3zXy;EjfBKXEMxZX3|d`3;+;oWrY`mX zNYD){=4l6x<=?}KKc#VxLz6d;!$wf%_Hh)(6v>9<(M#0+Bqe8Ckhen_z&54ihdK%B zWR6?NKceCc-j)in8jGfE&JZ@n2`O-l85(_0x|8IztJ!f0CZ0FvtR8%ls6L%EHh-+2 z<K=YoyV9FbZM}lVnjO{rlJO|{=2WV<9Te}<)O~G#(tqz9>{^`PWvtCb>#?g7pPtPi zTA8ie4fjm5I}>m4J*m3i<6$;1I9nUgs&Djn&veB4U1pnJ>Gj-wyITt&AzckxZRrC? zraueAQf&<eSPI+yl2M^bY)ko_OEB?gsaG4?(j1rc;PIbj&&9SgF(i&5r2u?Q_hsk% z*IxtP10Z3>mv?NR?LAGmUSbt_lu=6W;}g>L0l4eZVSou^iY2c@ZngI_#UC=26oAwD zCt8Ko{bXECCyp5u%h;ry;zGJf4pItN7@mjyA24yfqw_=0e~rfHAK#hJrimMa0KjKS zb4spgBm`{#m<vez*FIgZ_yw1&`ce0KFf@(+sBwCE?MI%{YoH;T(+O*~(&k;)QkO>I z)%i?=w{xLd(Kne*^|P>a-(oNs1f-Bb-0MzO7>39DmTHs}N#vK@0G0{}h<1L6rJt4w zN@>9WLJoMDss1PW7a<3vK;Dkm-T^J;J?qy*D6TB@#Urq%qa5~QGlkE;6~zF+Pn(u0 z2b!q7a|%Ig-vK>0KZI$?_77L9NY=@wtp=TczZ%4qKT0N?lnOtj1+c%0a@F>wlY39* zgmO3lIPNm^`0X|W1>5|isAOPMpb0Rz;Ppy^wtD58bJO&m*$AH_%y_=I-qN5qCC51m zzIs#m;c>>Ti%=;G8^P1`hxgN-cWu%N`O)UgG09*N_O1v^Bs0dBTH)<ev<7xR5Z5IW z{8cAZv^;nfgRt{O=(Rad2D<%u|Dr_Rn?`_=1B;k{@429(%Z9-UGXiP_P=&XS@*4mc zpce9bF5O4XT7gK2!f9KIe;L7vD!kxzLpT5c5@4-}44c-W%EQtD<gn}QPcNKV=@nTk zu(V=Fv<tq7RB77bX{b;kl|xVnVEp_B4%;RZu45VHVG^M4_UOt8$nP=2z5%gp?sTjj zcwNWkUBFXL@_!V86tKex^u-3D^AQD!Ag=5dmA0VF_ntzP6m_KVVwr?+D)3g*AVi3G zKh<%H4k8L_MpZ3DD>uH#Ab4oM_i1VO;i*6vNi!q_FqJICRPIJQ4@7^XiXF7nvVkaX zn^4@ErW5mfZZaBEu^Yq8=H2@<Y)CM6C?hV-(zzlTEOY}ZWI_{zL6ld-iI~KH%7`B* zb>s?++rMYmsr{heI7k>5bm>~B5Mrj2w)>-NKhp{f$=Ol5+d|2}A2-suB?&Ml(O8ja zGf5Og5<LeA%#ld<nZz7SVp2+kStW836S+?l`A<nK9VGh2L>Mt{uRUoj9Dp1?ZYXvX z`$+&Rf<+Sn#f!}3O9H2~n5=%9jN(W^E2U^!rDzAI=w_x!bfoOD(@_{dRMrcZqfUOw zpDgOaWDX@-5mU{_Qe~h_HXKY2(6k3*DK4V^_M)s}!D(KLX~=+7hr~3oMn}nczby>C zXk*#|DBWjF|8P3}He0Gt<3qKh<QpcJ4G<KUpK}zbjL7W_EJtRN6<Yi!crw*-);U2a z@i|bLp8VM%?=<rXAwx3*ktLedA@9_Ec>M)2t9F!<4WP2DL{tn=izI@ruZ7f|I)bTf zg^q|KZ?n3B!|?@7?NJB<oaV(eNT?7zPo@r$&XGxbeiNDNBN{1`2qCd#&FeWxU=eH$ zltLGN3@3a!tBe1YKmlG9Edwb}lo5=+0mS`QK3)vm3Dz1KqLc)H4^Ut;7;y&^^2<H^ zLm(nvI`Uy7?ekV3MY;gfm=6Gj>!<k)XWn2eCRmS^%DQk-sF3T-ub-XHd@z?+49#O* zB$8EBs|h-(D5_E<N}V~N06+o$f5C(hMX~ZyvHDptin9c*T%u`RqW!c4MGakzEV(9> ztxqmVZlh=bN`>W%Yrj*NMc=jL1kA>ZS<P(^GfN`{pq_;V&Tk*{qVR1{)>%NsDGTw4 zooPr<{GJ%=LM78$5TY0*Uf;l4>`MV!2Rik1eRq{#3sO1i>prri7rwy3>h9%UJ&Xd7 z1zr8X*ADR}c<xJnDt`=Xx^nj8Xqu8~u)79ql?K?bz&YXYhyd`Fj0!;~lG;XTdTBZ= zDB(+Si6ahdpj_c<0#!Szbh%NkR#=(kA>QAa>B@KckF7%cL2mR_D{J8EuGR88l{IuC zPBN;T`*I#Slr8`@kM*h*HflThE5&fN7{9D~rgAlnDtBD1<WnZU&T_O#g)*GgJj=79 zK;N*lOvo=sh>`Nvyt2PBwTJ^u$Rvki+BP(p6~9*@L=ly%&kE^MABkq&3S<iOZ4~Bf zaP_OQl4f;M26zh^+KX~+8uYn;mfXWqji%R{`%|=_>wt^t$3hO4beJa5qXyx`8Zlg5 z*L_y9k^=_}n9F3P1L`|XTV$4_QGeu2JjLxSSS6<mo>OJY+vu_{F-?zq3mmq1G`3<i ziVg+<m#e{S(?O0CNlsnr?#oPO9pZi=d4|hvL7v5TkS)Q>FBz;~KEK)?rqUiBlNS-v zPB36?5pL%m_KSxB@w@E_U5F&{jue}Y$03M}?2hb?4(Y}YR!C=hOh^8H2Qj3xXwjB| z4204!g}(2sQ=+a=>1wg*Y76OV&+h8%>grzZ>S%-YUhS^ZE$p}H9uDaq&F&uW>YiNg zp8C^04P&~>*)wa?Gau5kklnM?)w80a+dbd2esQ&zOeo#7>HQSayPMs+*VTK_rS7oY zdl+IU%=zlXQ}?CytNj>h`p8%3%dZyODb&ae|Mp&iZOPPJj^c;;og#uXD`bXqGW#cn zKd?S#+dkINzQd3Lpr9|=rJnt~4_VX2HQC2k;{b|vh&pUdEUy;Q=ohpt6jSwg8t(@R zs$<ssud5aiNCT=laZYDtYFvY8)xn2+b(*1rx(68HoI%5t!7j&agM-0KKl*wIg}`C1 zGzRfqY{=Hjk>3wdD%~}>JY*S;O~nif<M3HPR6c5$W~Cq^3z1t8>2pBNgpWKq@5@@R z2{!EWTp3}bqfa)5W=%sw=tgm{aHk8uDuEQ})c6P?r&in(@j`^UX}=MXf$$@%(~H#w z#Ug5yM-oGe@ibt0D^^tdGxZDv!Y#YAV@$-PQOF;9sgcQ_9xh(VWy(REJ{<=ROWgRV zg*F<+C?*=YR04A*w8wKC^jV{A#~z|4g*9;ZPsYY$i+(sEPM0Rh2a^hY)U!2+rqI_z zp0&<=EzYE|%!6uqzZQG^u)X1wQdWIgEQ0Kn>CiYX-bd{NpAzdEy=o&L;qkvHIuC!U z{y&bN%XQsrUe|SvjC-%W_a5Cv_AXmivO_ANGOp{IUz=o)P<BYAGA<z`qY$#Pq9m21 z?$7TZIFH9UkMsDP&v|`b@8@&uAf^lw|3+!$wN=VQpyxg0)*BhF34P@ZY5ZH|xIw1I zN=V<(X%?{*1-{7wSa{rR<L8!TB~QqW4MZW<eleq;AyA8b68L_A9@`-m_6n?T%;H?j z&mM~LK>YRRu6CZJvT&!wAl?=a%dWh+5z1UN&n*9UQsP_3JU@3fK=Z=CN~AUF{|)=S z!-$W4Bx5sew3j4VF*$YeCVJwQJUgIp3qf;!D-~8Q*ifAtI;a$vP#J@WIAPM3C)|=@ zP5m(QSAx++4*9GAkzzgy1R@$GU$5=H)5i};wnEqH9y*pFj7DEYG|Zd^d0*xY>RH$& zPLFfSTU<-hzns2$DziZ7OBv8;wduQ4x!Wc9STZy4SCBh8wEY$T`&_pf>E6C<9PBPT zz_-{S8TZ;g2_d{-(Ef_$kq4sn^w*&$+uE&9V}FK-ez!<>MNM{p0D!l$anT9z_exw- zs(<g_NJr#lj!IR`M4Q$-s4dEPew>$@ffo-bhrJO`M~Frvr1lc>*#KVIxYc09;O?}B zP4NJKKTy7;9)q}^zTgXO2y38}21i%LHbSW^htCaCUr(87Kj#~*)Ng6FI$i`yXO(Q0 znZL{e!0SPCW<hrDtEO}M`1^StQ<7OLrNP{_IF=hasOhIDDYMzTzNIJ0h!5=VmKM2P zl!hfehYQVR6LACc^-F4QQwAX`G3>zOg;V}`ZLJau<~C~DbTu&UqeRxc=@+lxpi%nW zcAaHL4X#I$E2|#(B>+CxEIE^in~{m@R{}M}(9>SOVFzmWVX1c?><FL&Ic~SF*158G zhyC+{Ff_m#5KAKu7lZCbaR5%stM<21gDl*M0Prvafyh8S4Vc<5*^-Fcs79Ap$HsQ@ z-W~v0-Z!E`Gf<tetZmk;>pf72)}l%2w&>5PfBp!Heq>|_Vrdq9BN_qvmyk31*o&(K z(THetpHuGb8-9)$4MyZX_zd6@8d?gombh>2=(P4gm&<oYL%h=e&d;*}c#p>Y<Bv-C zPsc&ajX{W~u(z5DbD_5oGABEqgAsh`D^lNJ0bN^?T=Np&K0A`zuq?n!4+J9mt4Qar zQtv~I{0^`m%Q>`pc4*J+7789B>qpN(JT|D8jbnMZ&+@g2TTf^gOOM900~#JpFJri4 zZttAtluBIVB_qqStvd<u?|Bw|nV}0FrHIYajWiD6zouILi>Ri*-;E+)evo?y^h|(6 zxF>fvrN8Y-arLhmzZDDmA<H$gb^Di$&AKFrr8#t6rguXY&+4i8)9V)q&&j=S`Yx(; zR^j$-kMcuF%o6kpBIM1!Ofi&$6S(61rTp}sIcg=tYCY*+)cC&YD<6@+h82x4I0em0 zDDN3^qG}CL7G<bH3s_h4+!ensvNqq-ntmy-`~rX@S^Po$%iCjelge3pcK;Fp^k~EA zn;`nM48Fnn%Z`fv%Fx(v3A)Wt32x)LBC5&b_!Pn#{~w}BfA<wV%*-|NkH8-Z<sG2s z=$sH)$>vWkC&09`Y}34Ux@%j;onvGd)~hpFuC;+OWiy1DqGjwkI8SxdtQB(P&LH;o z#Mi6F+2SS#tCws)ndZy8y&&`3ZI~CS2QSg?+HG2v$_BU7Dh<m~3N9QeT#kccCAttg zT28HQ0!M=I-W|=AzE1*pOrn_fM{11YM50R#?_Jn)?hIahk$C1;kO5!}wEKCsoQB`f zG8|qiqTB|!2%wpie3$tX!Z=ifj*u(mMEhoUaVfa%Yb%B`8Szrq*!NjJ?0tyWZ!70A z!`)s|gj{|G&3Dj)|MLMc#<B?kF#tbS31+SY$>Z=5ooK}mF_&>5po^7N@r;@x)6OQJ zdn`-OaGWRztUSmn2kP?0Q!ku*1hx1`5xMv;=J?0nuiZsn%yPc>h#>C}I{=PJtHzh# zW62^RZ1!vRICkXJ5{xmy=rr(CYqSm6%Md*?%MC5~1)O54xUERahCB|V{)~X5(w1cQ zedCA!4MQHV#gaIjX<45IN2(D?I;rs3eHohn^B)&<>qw|FvWls6ExGw|Latw5g`Av9 zgH}Q|Baopa-}Vi?&0z|DG^&<E8j4%ct9!Q3CSW0+rY7KrO3ha@CZ!fvt61Zi#oH(H zJoJp|FB5<q20-Ak8dWK-2RDjlc;z}?t^&$r18`CgP0{L{*<ip#O1TcP*Tq==EQv!$ z{6dO(R1L8eT$IRTaB-5!ns|pv!_m`fl(k}+BOpRdp$iAaWfujEU~mA)L*^m$X_I}b zuqzY;lXp(kO9=TffpK<pF)8qTf9bK?jkUg4Xp%pCi20rj54E+>fJf?_Fy?od3sgVa zZ#-EJ>40u^?^Ug0V-Mi;N{z7j<(8^AsI^ucVLdHo3__<lrOv{w%@e-N_G1IyApOoI ziOsRiWVs4KEB9aU{94H;EvS>y?{s#ZDNk}A9=Io_e(Hl(WI|8**)1L7;u<Wb=;b>X zCaZJC0}P;8G5N`x)o#NFJQZ$KBi-PR#E#eHl8`<xbT6B!^LEx2x<0c$oa8ed|KJ&i zCD3kLcfKh71my}uNbu$#DuLf_N`UGjgI_DYa-CQKh7iC%$T6Q!+zTm=i-SFSQqHN4 zrQ_&eruawu{ZFn#8$uOXKJ&B+{DX@j=%ad(D@nCuB{w-H$I89gk6p{<Hc*S`feZ7Z zmn_-iEuW6K3U57#7rXh_g1ipy@huFoX#6#teEH?AUwa>luL9X_CTZL9eP@7~bCVxF zX1N#eo4okm*euV1;m7itMEPcpJbx3%Nk&_wT*^d)&%qe|k?E`V5tsQ%bo1Y$u$Sd) zFTY^O2#}y4flVWmK}ReO;*>3asFn#)X`$pk^8{b(A_{kkMR4@;nrwMIw=leXDRH0o zmmfnGEqybV<%8Rk5r+PchH^>zG%r*lZ*w+y1qx6_{ubYWXK9m_LzMW<>hjP@X*>1+ z+?C+x`=UUPP2Wz9_mg?Jh7^p*=M45izh6yQrdgRmq}O<ND4A+H)tuSeNE6gs(fo;B z)rbI-HE>@o6GwFru<V^evth&MPv&a-;}3wAf;c_|=BygE0L*aTNPrfVbutYVTBX{s zi^Yb4ahGwbwJgc9o{V#D{ne2<)<wnwOMF9$!2T<{3sXgM^wwVXSkX*YgB3+RPz6yc zK?1O^MT59M;@UJSvdiOn);$wtJwU8CGf3(sK_;fQ@s-|!{d|lzgX)Ym262O%A`HJ{ ziM#5V5|Q7phJ8Q-<(CETp_T0ep9<_6RVFuTS0^(&@%2x%S#kfELa)M&wK8lbq<<vT z$nLy80QNfzB0|yWLF4JiGe&tx%S1#x)Y15WU~o&!YflBD8t<9z$+upnm>7UsE9gFn z%@TLXM4A^J7$;bpWj7Hkbc811u#Wv?;Z>+X94fW0lP7ft3#x>)O^mr&qt(KV`K6;Y z<H|>Idd@lZeL4tAgAx`3b8*af%CGVY;(q}>N7vHAWad4cY2!TUVOf{Sd?DDI*Bk_! z3X;ymMm=zbJn{QaMJ5vnPpztg-zUoCV$#YLMQsm_17j{LU(#CR8|w;6xd3;aC*#l$ z)P{KXQZlL8VPYLf<9|P`of9&x?IGHj;#I$49#c}?n(c0|=#6PB#QW~e^f4A^G-CoS zw}Q`S_|ApN-0hv*T2U^<V?XAH34&8%W_^a<um8wiEJr?P9$X0JY_kUB9MXVTap3S+ z{ABM6TJBNPfAC7Tgszbmw{MDHz?GwM#h-H=*ih<R-K)!>+F*;V1#@Fc=0<M*HI65i z%ai_G{leb~PgTo})NJjCg}?)HM&a4l=#?Hxkz7vSuOi83CE8S$zMhU$Q!hG5W<GGW zSG}mf!y>Y77k}zd!d!<Yzvou|Z^C-`3gwY&3z)AP>(gh_noI1H&a92RChocP4X5M$ zuK#$J@I!ED%~bHRk*0t`sUb9dM-QHrHICKlFc#xleQbYsy<cn?{&n)&fT-^Lbgc%} zO@Yt5^XRS&GiZUL8^qN#ijug0)9RCHdVu?{r@^n)jZs)VI30cNjq}E%+WX=>52W5+ zgT8Ifdb$Bu`*`72z|0!ndNMHNhKsnJ1Z>Bz`=x<M_3MQ*Gal@f@J7rRV>fM8U?Q!y zJ)h|VYQ<2hrWY1|!~jelYM><rLg{(t6Bwt;dSctt_s{A>?3#XloMC{Bw&q)fK|$e9 zyds+>`R<CnKGHOS864D2#=4_^FH~(@-%Nnl<-dF69$^`nz5j$v_;{@XKYh7qFv@kE zL7E9D#)nrDXO_iohWasQO9MR%?Lel$Oa#&~9Wq~4xnkPE<GW{36zQd=*Y>j3DWa_m zaptsRY|`Qbr``@)fpXor|9}~2dK$IS(wSkFft0=JQYZG~rw&1&P9X(WeHQ{Vn&Y`M zw*dlJ`zg=-oK`PA#Jj{==rN7U_hoU0ozNJbc&_p`53r^gNL&jE83Ko&#b_)_TR)CY z0Jk}(JeCO*y0j^cplnDH=xJ8B1%_8FE}CA*c`hJp(q*_bJ~T*r|3e~6A3!OG<-v0< zFy7s~x!;xTb`m32Y<*5X2DHCYP!^e8n>=(<r5HzrJ#DJ}VyqUFZP~^0i?N>i?ws6G zHc%EPQ=b@`2?3x<x#+Xsi9MqxQiV_!Q&lQj0G`^Slp5M;dQAS)FJ|3uuqVsfW&>N% zh2F`bTmWJ(!JmUky(?K<Nyho?0SaU-Min4dH9%nVYDSh8`2k<v7!@2>NCvQ~Y~X?$ z;fay+xDv+L(yLV8oflb9h(ALUGM6B9d_QYQ=AHN1`%}mqYwoY0*fD6C@>G%8gS-C` z8m7=HR^gAbW;^N95&bI_sc{}E*~VR+valMDmvKX7y0Z_kPh0C<atisOjT0&TPhL*c zX@uL9Y5WnIknK*GO?-rheI<5lwv*bEW%K;>@`s2jS;;LaogOk}6H5Iey6j1OS?AQK z#$a)voMzfha}+GCzKY{3uBmyg;*;<+n~$d#HqfYC=(PPT%US|ZO&$T^6SR6F3L7He z)H_i!PPu~~zhMv})Y%?(A5>9zI<yq06ZoWQ?seU}6z=%n9A6PeOD<}FwX9?oEk=ME z3V-Hbea<5*uFOL`hfhmYAQ`r6l>bd-{t<O<uKC1F_0@I>A2xZ!B-tkd>bcL<dar@o zzBQ`dm@bti8|B&Z#yMHV<E&brAuuGJ1f1I@LW6BI<F+{1%+IAxKn-(}9ong9kE{G= z$q7pJsnaHZLZ#!N3{}cdS^i{RLD;=Eya7^DZM*Lws0{D=*#A-2zmX>euCKgfl2gDy z;AzLA5CYW6#X;*zkgugp3^w_-oSf5cr=@+qsRImgjh1KZl#?~RV7B{30cLX7T}6zm z`I5w7XAefW!N5i8V5^$>A6!#jq#oLo?OuSG&s2NKgQB@;jlzlNk&Ml0aOwC1El2=C zqu3;%Z=_#r?08o0MIj8Diwhw^U$hEDghQ`?XdXQ?*i9l7?7z;2k4~;z{GJs=c{J1G zwo=EW4en0#ZC<4c*5l&J&En947x2)p0)xfR#*9wR8s{dTRiXH$G1>7wTLN3nX<5V_ zRo)HF|MmUcUD;&23N4i!jc-cEBGDKQIh9iQ^F2XmDD=(WYEF+p*ez|*9BoU%cIsFx zxrqDW-xTP)AoQ;;=gig<kau#59wk=i1;Ulmy#9tgF*Qbz+SZ<||3@Z4>2zy~JrW%B z-qC-)%l-NAWwDewN8Z~m>zc$UW%zj=t)ue1eO^mOM4nu6-$>6k35xN4`x7vrf9S}k zzU9AW`&di+@4nTmd+qtgqTLnE`Be2?E$Uak#2c#6#z4M^;g0j|Fh8&v`>jd3`eHII zSNcexs>0(*%#(V#wK5Haahx@@3?V^KHQuq8h_LAwFNS$4QCj5i8t3irg(f|dg$b5O zDb(Gw6wEm_o|8S`5iat5PoFA{jsDez8Wk66jE)<spMO6~GPZdhGfX@@Lp_qkq?Us( z?%JvbSr?=wo9NBB-AYf;p+*bB{?$!7$|QsK7#(M_6i)gsslzCIwmS<i4PA}h#Y>G0 zJ6JoYoyxEV8Md4uB$p6OUAxwoi8J6#^6y<LUWmF-{jLlKLhvzPRPV4p>Ff?j&Wd4e zhAJaIRDU$FC8N&=wo&}xMbhm?s8w~7thi+`An5{=F*7^CLw%S?^gL?k7lwOTN7REI zgS$cR|GUI0d(*D-(Ia0F-1&f%x^=H08CDThX#E+QC1n?z{vevsN!}U1k}1-aocv2Q zd04JC4rdL7zB#zdJ*EqN5cKxgwZEY6!ebqBw(C?*V9i|wG^jyM@7cgl-Mb0psAmsn zv&$W>Bb0}3T3ebD#AA{rk<`U@c0U#K5pO$A9;$=~GPO(9^v9f~Q&s7HQC3%G)Edm+ zwA({z;dcw8IiK0*BAckzxP(i|)%=X6jni>dlts?`m$<QSp2=j8$^%zK#`pL4FTvc= z3-=5cOQ7-Dv3ffC&@%CfmH~x?^7k}p37=!vaXHxa^!tA%DD>&YH=7vPEfbEz?&&jj zl@{qR`lJxWW?qc!es6Z{ZF_n^3*|Bp>r17?ZBfGcn3wbVW<E*CJ3Yz52`M{q-0!l_ z$4#Jf8?&jE(Y7B7w0gL;b(12U_YHBu9nNvH=-%ZEKsi!QFvt0+Yn_MdCpXxOgvXME z_dl{GE@~~tX;FOmbaEmotc?^_%d8MS=75QdS3a`_%Ue3`Al|LbXGNxLDn0(xuD6wD zs`_2Gb*^!I6n0J5;F2{&-6G3cDk<b>5gyVmz;iJHUL~TEVi>i^@I?GagnfRETOQ8Y zhd}+2X??Gd;_m^;Ohp7um}0(Yr0YSiu%s3CFfx8CqYG7V09(B#TGV+_7wjho3Cv=N z5=7XDD`*xHv`h&GVuO^ZniGj(U8ijr<u!ri6_1W{{A_(VGcup`Q`H=Y1h1l&v4}<3 z4i6Id)BCIeG<X?;)9?Y?H77()C53kzmFAxNiB76hba=gxT}Q4=G);|M-WvF{Or*Nh zCA#xbJ>U?JcRn&)pW>D&afJ!zfLL$gPdxX~8FQSai7g3R*_$e`v)-;7K8>}=_IYiG zyuyn<7hDsJVUNXggW#7Uu2VxieB=BeRw2IMi-@u-7xS#WydSzINol%0&<i%AR(72C z$}PN>JM256$tZUAYCZyIv`Gos3Xa{fboZqLeqeoRUvjA5wT#U`9qp$)P(dDOmUPJ` z!+W25MI)IX<{EXfTV|5t65Zx_+zT(lgsEkAeqQ5SX^>dz&vhwqY{)((D0b`Y_;%&e zR={y`1{c(`#5WGQTv+ZnYyFTvoN5v?aF2qZC<It8`TK@!dS`3}ZLKxF^N;JH5Da$Y z!e{?ImzBN>JDe%gpB1?hvswTr<ii&co`j`KyluC)E^R={Hz-CuWCM<XmlB`PS_a}| zR!j7uL#n2;d8sWn>69l7r#<+xsYK)TKu>&-<;HgKGR1e9g8Tn?B82*Hm*&1JC-X)- zwJrNr@?mbe9v}4_urZ>{et~p`-o~*<{j&D;yl>+IWkzG?-FRhGNZ?%nbBDG;uQw~$ zVmRX^_lS!cdw%f6&%KYRU|=6|rHd(U%X{X!-+*uM`U{DbnvFOm)BE>u&By&C3oz@g zOap$U|AbI4H@;N-^S5eByu|UDA`E?L^fe&9F7DZ7<4#u-2^g;dYvBnl?RU_ZrEO~I zmRHE-$`^hE@AeNA_HliKamM?ZuKOy<=76#PGf1M#eb~!}kAHB1NlGCROIJz_e6MJ2 zOe(<AzwEdD3zcID%Xj2>IiJ9D;Z2Z6Ua)&|i_>IL<hNt3&k5A<xWaD&k3%C-Meb;D zoRnh%JhV!|SD60ob@sFO-X(NoZL*u^Hz;SW^jRu@?KjK&`w3eI=Zq7}44`L?f+~f- z3(wPvmIpUIIxQZ-9J)%5E$=C6P#;mg>(Td02L0mv$PMJn{O`Bfzg~q_N*~)?DbTWf zp)Wu3SsYpUDbFKO{R(fR-skhLC^UsD|1_YoyiiAx<O+o^YvU1eMeVm-VQ?Aj?W_;( z;pq|=xh`D3w$=%it-Y4Byj{Gp@0z6Al0Fme!`g=aDOtc7*aGoBd;PM=smb8*TyyBZ zLGu3f!z+?k{N7if(Vp3bQ+ZN3&Em-q!@QrMuOGFzlP9hRZ(cWg`9q2KYIfbX1U_b$ zu0(~hYc8CjlncL@S3jN=Nu%G(y#BBd>`)*7p^4f$z!x%fBVl6X*5<F<SFV9JzneP1 z-f{#5;UYOW6ZJ%XO$djYYr-_IoX#8`Z6(8AltiWz$f;!^dDC_sFr9=J_e|!SS)4~s zmy=t*P~?P@R#9Ks{=0Um`8U*d-M%qdRin|hO<^_$oH%iM1<2PRitp@=tdDE$@4XEM zVSX%35@>Q5A9JAAMhNb+0VF77;*a3_KM!72ZeUF7Zg<@Yd#%awr*k&wJ+P9{Wo^it zRNhbVm5Qp`yz%J%Z=V}5s}0I)4lp2<luX%ta_6`9uRlTorSD1<pFYZJE@9b<9W$=` zB~qOJhRg~tg#-+Jyv0kUy8^LcbriqClT3$e9s86pzu(xxac@f|*P(B3AMa28`tD(O zsi4cgSqAL+A6ZzisN%C}Tpc6;SQ&1HJaS07uzd8W8J5EvnfvQ>O-a<{rQ(bsakK8; z!dJqQZcm+sy4RMT0YiZd050ZN?}0ag@~Q-F?PF+Egru#jak_Iyn!r7EGiJaU9|Ud$ zq35i92B;r8G3y#%OtakCUj?rX28)ju%h?_5Zhx1YC?_N#<O2?+CaX<v5}fK1m-FTI zf5{2bCJ<skG9ZWOvfpZI2J-c*Aszy;sR0k20t3@U@isp))rs0FmpaQoJPrH&PJWsv zX#tp?eqtxLN~fjps)p<yDX%A<Lz!Z<PN_ukHe4xLk*`*=6|MkiY@wgWdh)YK@$*JM zSK4R&YU>BK-Z^)~FTu0L{2jd9E7U<pdo$43qVP|s<GqKf>W5pCwRX)RLSC1E0#(ty z?Ai!C$)#CznkiP@_7azOS-P7`l@Y-IjBD37d-)2vH+@oZR!;!%pH|_xvNoH@eG?|r zg-&4CDRd*+g7%sCaIp9xkrnNuyeP1?-9%7ZvSYflc<(v53;5<$5#TphyNGSfkAe4E z0c3(Pz5-l0qIH|=F(wnwqAiw13S;KMBmapFp<|I=Jj9Ih3qDptx1p6(>^ol+sTD1T z(4Z^yMNYeux!zkSSOP6D;A&R{D?Z__iFnDi`J0;&R=6;JB0?boVr`vGskI)D*)q>} z&UUm8>E;o$ki~Qy@m&NWr^YlNAg8Hme?hn$%_J@znfjU{XB#^XlOaQ!3qmSe^$2;@ zhZPiw2Q^i4DkMwIF;eGykGb3_OT49?t>s0gF)rChV>*E{WgIrM{5DCkk3AgC#-5rt zQd4Gyon1#H%bHj}*;+qI27Mm$ID}7+3&yb-mDRqPk5+uawo~s$W=*$gOqe@BvJpr4 zf|P)!x6Xn2mrJg_C8Vo>c_k+!6D*#ljy>eiY2Bi(b^lOrw|yagFGj`7!jRSGGCc^I zIMl(yQjF*Ypa~Pb+Gj@P`~BF@o6Bt<6{V-{T-UKw^am3r<O`0^S)Z}0>aHNzxww^# zWTbEMl&Z6OvjKx!-QQK3W_DVv#eVDg4|=I@7HB??sPL9yN{&)LMGwhmA;5ccUkO^! zIJjU4fMdp&{ZJFXrs}ZXp`7(!qY{C_F>^gYbp(b})Ul2D<?!N*zRvd4k6?bl(R#hj z+Kr3WRnj*k{AAW!a#w&5cxL8<x9;#Z@2z{>mvi=O&fMu<;!&`N*fd>Duid>UYxitV zNaj2zVJvNU);;FOW_|4d<Ah<`(7ihbrS(QMJs{Tk?`uUSE<v`xZ&T$p@N{NgpIg_; zKhLn6jnHz`%9~>$VhALf1edRCLSKY30z<Knj|Mn_!)G3cFC?CDVA3$n7?zMW2QK<w zA4L!t{oF`G=9^GUqC$7ZF<+kytw%w9Lwbmvzfa)k?`k|>yU6Upt6ok7nM#^VUqmzF z`pQEi&HvbFP=EEkW%5k1Pw~Vn^grMi9=NHVX3haBXMM#(=G8m&{97r>_0O$d%3DUj zJ62Luwz4?|XaNcBtxFEtTj0Bos`yuK;8`z_<xYtAY&+lcX&*y@%4p-713wj!EnGIf zsBhT|h?Vy-Vs$04V2hLBrmjiqv0yPynDp5>lTD>i<ZDZT?JD~6a6P+PtIv{D@@w`V z@(`=uQQ`j%9yCh(r9IRZM}sm=e=~_vJ<XE8WI%!N&?^29k)IsQsf28HNb<AMPnw!y ziFp`GA<Se%*4+l~tOw@(q%5IAuQQLIX2XuVzWD+u@mb;|W6jqkZbiLiW1w(f!tdkp z9zF5#mbI`6u1k1hn2?(_vb5I6SRcciMNCO7%V6XFl^;m}4=3Y}Jhz@_0<j4a5fxIm z%;6GtnSAyeDt217-VkiEfdPb<r)EnbL)z+asJV_Qa0pZN1ZgN^bWhtRtB%yySCBoD zVP9j3K;%@!3s%C}xGsr{IU^kb9119B(gk_2y0*}HfS^mCt<t5lq7dt)f^O?dJ$N{x z&$e2-b-1`mX0}(w=i<d-IJ)b2MiFIL;%g|2_gfi%{Gy{$%^R*o;hJ6A`=QN#SH_bV zIPgLp4+{vON+z|<B+_<o8iggwLK#@wO7l>inGG(|fx;;%S=fl@bMFr%ON{fX6f%`7 zJTHXjB<-JXA2%#DFIl#3MQe!X;YNbqC%@~kMJ09r9p07jqSY7^k*htFpHa*`>+xSC z#G<)?w%+N@N!}}XYiWGxJ~>`3Q@4!G)Jq!sZZP{is%^H(=h+|brwFlbSOS#mLnJbo zDk?_$>=y1q$h1x)o(a!Zq`I`HFRJx%(0}MFr|@#S0M*<mU;UQg;NHbfVezgT*UYQ1 zHS9+k6dwv^)N_8q;?1B#!13KHDLLjc;%c5Rp}qB9=qR^%^Et_uVC6K<m=BMQ$aOC| z?!v#qgu<wzXSVmkC`sP+iQT_K=IRQv*V3A|EhS}HhshGq$>fxtpCgV2O86if_>G^m z*IZoR31Y6OWcGog49~C8+f!-oqae$Bd8+r7<zdOb3~zv0RgyI*_I&2kH@B}Vr_IQ0 zCBmbyTU^yd_!t}}n}_CurD$DW7}@MDKo>fq3<tkat+aJ6J{(tTt6&UBDrexSc2BH# z`<60S^rJyqIf7p{ev4B^0OMOhhXe~;LK$%;56NJSYYczFgGpS#H8YKF){&{?%y?w2 z-_J)?jpJ=9>$C9QpEm`=AH@&NOY#kmHAcse8R}e1J}U#&YyoXj4jJ0Nz0g`Zj?JV+ zoyRiz4oLy<aA5Y&(r=9)FL+n4klW|=4!Y$EMO56W)Ie9gZ!_W65w6BxI~<_fknG1? z#dUe$H6sxrH26o3{+;-BvF2aWU-ov-!>iwLJP9T`-xiJ)CEw<h)*|?h!^2vcuCiwp zPF&~k52=h^J$L7shpJ7c{(oM`A1|V(zq!F@QPuNIToDh22!o2Emlia>ny8x#loSK- z;m|uLntR1Otx?Y0B}b$o`d5x0c4+cW^yRR3GXjxhpVZGUJ=hb1H#{n*ix-eL*HdhB zxZz)4ePfNYK_8#WvcA9YxemdJH>F;-aD4HlNRe8n|Mhnw;M}+;XJwth(0Rs+yqmT& z>~dW`;&&721^la-s1lb6CGrl&b65YkIiIJL<KsbDkDfFXL64U!!^++WOrIhC#afDq zs&5Y8s&@P8!MMlcp+Q5?_S}!<(MwwKCDOEOOc%x3K7R5PCX8O(R3^p!1;5v)^<*V| z);4nIL+>%c&DcJuDwVTf-{5czVnNQ1CLVv>mWGtc2N==_7pY@W1W$guY(ZnT<TRXi zo?kv!2tM~%9ReGq^Ts!nb7QR>w3aPRJobm(N^ccSr3*p~NF#gY-{l9!mj5GC-AE@N zN!4cB_Qcj?576NI+r|srgDcO2X3)@)j;;(w0)sfsgJ)xoM}>ycAaN+1f-9E@Cmy7U znSZBzs7oIUq?T>c(6IPi!3&i$Vgzi&0Cv5C)ifT=fcx~xX-fGXngIy5AT5`CTr;O( zHAr3TOv-7Du`LxKOBO=ptSGrpz!|Hk@)~=xitSovjl%A8fxnFjp%rK;Jhb+^*q0?d zoC4U2uBDrAvD7&G+a5$kF(P`1tfA(hNb!z8><wUYe3i_s1gTOA5!ko5yRdzCQ69W$ zLWBIIgRzq~h3i$RJr!C%y-UOv(a89Y@-;<M6Up%p1UVNy2HdpUIsFbVZzv~hZpo^L zYGAvXT6gzsh)<@y1CB#X=fyZ<$h__gQB+E?UU+GpG7bID&Dn&+Yzv-67XJ{#c&$_1 z3QKHUeGDwwBs>^29T^S7#cU)XLNSo@a4=f#5)Q>M>Vd@vVFS=Uh7Ic~1Td%Y0MTfi z4@I_+NHmEZyS3$GvoEGGZx||PW{nbeA-oc@X43xGE28x2T)vUS3l5SircS>4M0wqc zuTlmz;Ks$pFJoA(HJOOV+7ye6Z}_+v+>hw~Bux8cD<K4Qn+BHHk*3k78d>}_UF3p{ z5#RMoc%+1FWdD;ETB0(=DTUmWDef~UVY?9LW9#e1B-Vf?Gcxpi<ss#PfQ>L;VrCJ^ zL&$K!n;5gKs!w7D^*9J8nzYBSYC{Ui$u4T-t<lP$kXoyg*Tjiln|JqJoAM{+Nmnk+ zfo;Kl2$Gp8S&bzTZb`c;W2ipA>g6#SoJPClCwk*&t(6of9$*pd!3)wrk&_@{F)3l| zjY}GS{(fFW>v+e%E5y;Nx>knv)_5zv)qrXmGsl8*;e9Uce$~t^uW6<r4nz0-YA(wW z4N`)-T>72yI+7IUA0#+VKq}JI*VfngW;he6OLT~-l6@78Y2yB;PX~uzcWX#4@b*j4 zgcAc6jBXpT5y<Ft-|d&VaerFk&a6wV3W@`}c-xR-(xHTu0!<1*8@jncoL<vu<RRsj zT1l;j3!nF2^1(;id$%(^wfE15?2uwXd=ZfE#h^2h{u#pKHrf7nQKVORG9jke<R3}( z=RKm|;%h?^lQIb&w@4`TwXJ4U(SzhM?6@h7ShEDU2+LH;$OsB@RLNuzp*|t2mq-|z zuDd&tR(4N;#ET_e&>@){kj7#kgnrt#2q1=#6TH4yUU9uVSm<cIYLwFU;4Er~uNd@L zMuso}x~l;WnU~4bAv^x{RVnQ|Y4jl-m2~LS*yW}15%e9(mVi(3&Nb9xm!D)OM5ZDI z#E+KAK=~Egl6(*DUqO&fZ2c~`Jv?Y7T-T?y{3PwDlc@#}E(wTtCzDGxHO9mL<*_$g zSQ07-!h7<$lYyn2j{{G`lR{nbg;O_Cq?#|Em{8KHKiz!x<cQsy#EC#_>I2(Y#<Hc) z$)`)DhBaP~i8r*jJ@WD&H2F0Gyedcjk0I9KdCG;tz`XM^ct^A;Vw<S<?)zIu{DSC& zgd}OzQN7&P$A|W6ka?0Ik)wUrE;ne(7Rr~_o6c}rC<`E|B@2b@5q6P8`<)^J*w20E znQzS-9nvXI^`Cj!=n5ZD-v2`z@?z)n0*WqPQp17wi9_Y?qSWLo7=UTS_+u<d8w(!Q zB3&q#B#1Sw3e<B5Z(CP4)-I(*#V*bZ7}guT+Heotbax%pAzk+Xp{QTB^1qM)phHlG z6k{afw=m;u=r1VOS1H?%BHd%a9XyxL*7>-_bf2^pGOEx0$&&e{vqDUd{1B>HOCs~S zl%i#r&E<W0LW>+>BH(;W{&!q%(*ysD2DI~(`y@GkCX<i^F4v`Q#f1??7t8lr^%;{4 zz{424Y4;}rm=EA3=e}*Q?F!6>FdZw9RsS|QR-+@<2mkB{T00hls~kCjUN{n*BW}$k z`*rdk@AOm7(-9B6*rzH44J}BIf4Ad{??OKvZ#rSByc{p_5kvlH5maGF3QZrcFB-Cv zOI2<E%666))@6@J=bDPgA+~t`9t>y2AUf1&(+adIf=TtxMu;tG(S)YrE)MH|=<!=R zuTKfz5=!!`Rfh)iC85}nG%hiafaYC}@54-rWWJz>MEgBBFPWK_;mN8DVc(wHiY(hu zOY9aS7GA;QL-C<7OmxEM)}(5&w(MR2KO4(AtAr>ITg>2o>0yLF;UxgAa7C~-LoD-} zueID6X%*V}Qm+8C?2BcJ5sr<9q{&6u5v_@ff+_&KO|G_(<ERI&rUEGO1Jx|r!AAJ* zFno)pAae*Jm7ZiJ^*uDBNJWLzF)%BAhe>Vib$+g~X7pA5%AuIs-_JMVSdk>HS4f~- z8JOKeI_~cr$rD4Bh-@L&;LGT?hx)qU;^S7^!>f<%zn>+h(YD5uVq5XA_z9<_s@Yh1 z=3aJDFv>!Oc-XkowX4fbQl9b@;{IYqmH#WG^nJj|q}K2YlB801Xe#N%2?w+G0PGX7 z?1!;hmw5oK>Dx2*JGeQWQ_<A!Ass<Nu!a&(B=mogRUgfJN!2a|!AMHi?4}$Hx)|}U z06^+sv+m#k@OYoR9BDXkl06*XVcTOVCHp880e&Xj(ms6QjlclIJ*!}~QG#B--27+P zGP<L|IwR1N@S+J|+x>xUMiT2dwbjAXZR1LIjlC%FZj39@M;Oxdd2_K-)rjKak{%SB z8q_5$LHp`E#Y@1nv%yJPjB(~XwA*e*cjVzpB8fjO1FUAx5a8<3zRs1gXXH3<+`p#b zXE(so(i6sr(-KAEPh~p{mJ!@wI*M#~jwE$AhZxyNJd!!OAawog+EJ-vC6bJb*1UY< z=VdyhMhpP79}4k+Z}Wiv62QDQO(ef!tMbz}N9)wsMYPWK>mQqJi<P!p&h-m6$Lczq zEsi|9PCVPgNN5H49Xc+G3=|yD9<rT2c$D);x$*2a@0BlCe_Zc(g(Vjpc~sD~^iKMP zmOF?(JQu3Q#pnnkpltY3wF^ZHz>pAU!P3Lm@oI}+cO;~FY3J^E+Qc3$QM)cZW(LRu z@@&7o%9&-jf7iwSI$KEgQ>4L*mGNp$hQ?h5I$+lj!Cb#RHx=-Cgc7mN=bZO1XJ!Fg z_zW!d@DX(=4{h3uRP&}iDdsl4+^j{&eaxYEji~zg*l}MGuN~W`OccBH14TZ6QkO3o zM2u}Dl7GL*Y7ALpuQ`*V`G>&L#t^H;h*e~=@jt%L&Els^t}_GYGEebE*8XYN048<> ziLgjAB1n;TD)<D}`KQ!L$oC)7t5Mn4SXr;8#;En3B6?f7-)U*mwE*Z(5BdSoSlcji zpA;L8KUpbIq(wcLk}hhqLI&aspUeoFKJKQ}@Y0m42S@p$pRFZdK1(uJzlq0D9lVvK zxM&fYq+cl7$zK^jP^pLb(;9x#{a|t_BDEsO46l?>g8{3OPLlI9@uypxq3B0fjSP>P zZ3zKHtvBl!l9VpFl1OXhW*X_Y+O|LL)cczN!pWN_b>|;|{zjbb<dPR94Sap#iJ^^) zlFPn-own5_MxL);!US}q3(nErPKlUBX?Y)7Z|mt#^MWPV?nT(&BJ%N#O_>nhhl_)H z!p%rZ>a^(o$9Z(U7gzNNU{TWS4O0!5&9KPm15y%-E<5D{XDmxwd}Dfb)!c{7G(x|% zWE?>PzLh=RB?_v(3-5L+Q?Jw&!b=?=Bx-vH1#E7<Za{KvZJOh!<C6{b>B^9g_g*}* zw^`vPcXR$^(+<vMZY4@_Br1ZRbmk|fDxFT-KL7D&XzjL5?(IeTi#@T9G5rL^I;Dd% za04k_Lh-n^B6;f{Z5qpQ9;sX%5FEIjOD>hg*)u4GdemA0MqJ=fQ%_<NC&ma|9{64X zK#BWKcV&5>`%eTT!z~>?r*etCo}V!^s9fbD*eO0&JIB}Jo@Us_^pl*+R%L>Up)o3< zEU}f2$Z-C;h-JQvXvj|+E$IJ)R29>3sZe^k1i;Llef-3R7jWl$b^rW_FtOoFj3S_x zjo0rRH3PqG%seZ&a`EMzGq)qRh!qIH0v&+qs;QWYyR7#Qgu6C@YoH41U{Bj^4oOwU z;wLUYu^v;JA3EKxo6o5MWN4f1mf5WThsR-?@1CE*b{849N<q+qJ-kW)4Uk$>;vm%n zVw{3Ld1&7Z2Gwg!6ENJ?7a0G>VofUc%6Cpf20o{7^;61x0#`RvEPw0~K%OypS$5|R zoz5K23^YUHJ<(@`RYoi1aPj>Wy3ie>%5WXSvdm{}B{<ep?{!Ac9t6>dp;&)|@g^EG zPIOP_YEx>CN1t-Wx*yuT9Xu08ALUXKih-^|0VEigLg5pm)+<888>%)T3^W4JVCI9C zRv!`LX5bVsmg8b(v3jMbZEB(KJruzO<n1nt-;c9rIE_D7((EeO1t&qVXbM`&I5ATt z9KBZL%mHWsp=%f&Y|zj!LBLro%Mh3dLK{OS;gtz(xpq_OB<v$|&$PGy<^2XC{ip0~ zEM{H`#{y`WL!RF%OiG}y(iq?qHD*%=3sKpLAioSzBi3GPQxow;s_yx_;zM>;|A9Iz zx{4a#%?JJpn5n3s2-dx!08Acf?stTY9plmV(98#=<m_^9kR#X@kjf(?%(O={$}gQV z*X{lBJQDZaA@pM=AmOit<4U3?ArmbIC74&bip%`M)B&?Z8Oahc=tHB;8s19Ivs2kC zXYfK&XXA!lx7G_hGx#eVm<0~%D4jz**2=kLs7+#_Se*)BP-=@Yg|$VX-#`SV?CxH% z_x}_N()!ksu$SQcxpC3elL_$g+j>Ryzed%fqQB2rGlPz_y@A5&P`?}XY4)nspyi<T zc=%4nXF56g$|sLVekpb`-O@Ge-#^fw3So%AA0<q(SjMS&b=he`6{>&8kp@c%(YXPt z)16E|9BBJG@P>8phsOcy50u?U@5P@V{+?m*iZ9>lta2BxWIU`#_L+}773z)lPdr?7 zz_f<aYwJIixF`MPZ68f>|Fic#pcsu3o_FhQ1L0&?Ul&BxT?LjytsNg%FqV7&<`0f2 zf5zPAu>A>!y&JvgS|H*+T?u7+?Y{D_0LL^!!g0Xvkz$w&&vA)4-F!`@qolH2rF^2M zqf6?itwq4TnPl-@V^(1;cpq-vcQbk@O!zypcx#L-ax+;IGMU!i^@X?o6jQzt$_D<& z5T>qH2}@uwcxC7#rI~{!?GChyZfx-OdO#!?zCmZrvr^sECUEG2S_-Kp=JE&XAGC^I zh8%-`_Qc4)r(Imv4o@T3^+d(pSXd&`M!tnAir@csPO~u+tr9wmyUrZz6zAj0rA_C> ztL1aC4Vd}lWP_)QB#q<k6Zn7$%x+X$s#Et0>c1mT`J+0M^YdQ<H9b>K5x=qRhDO-T zY=<F0Dfzsw4>>~ZbqvGX)GnYLHD{M9+aST(9V(ggEMmjLmJgh0oR$TSV{7rXRZGO} zgp9ZpAzw}o6p)Er5xHDINLGsGZe{566BD@zJnLD5oYH@oI3iSZP@k(>%BhQ|X`D|k zu{sd__U=dAj%F`qdC#2#lj%^Jk8+k{6Xf7BlF^?uySUt!)V;rDC6Q7Ym63b)qCFPy zQ-TMBOtLtC*Ag<TUr_YI(E;{D=S?r4HJSU20q>CUSZAW$r}ZkD7*&xTbp*L_UmS%I z-?qEC)*+7YfoA7W`QK_xG0)iFX0PBNWg8OX)wmT$%=x(Ptfo4ZbH};$F#RkSa0seF z0+PW{+E0_}IH`^BGZoScY%)SgXoiBW-8BDEXQJuJL{-H;K|W<}yfw5EIqAp*AY>iJ zmMG_NnfHxeoED07d~UI0>d4(Y$}JkC28P~c-!r!M4IrEbvz??uL>Q_=ihyLiD;X5` zEFXucW@0pvUI);F{cMJqzqGqXI=>w5v2?m|)uVxBzJ>IC2G18#sfJ59uGF;mlG2rp z*WW%w^|q8VT?FI!Fj%IKzo#%O$Hq^mwKNmO`XaW)1Biombgs$5_b-_s@RHpfxcF|p z6kL1KPdENzykPs&GZmyHHa0HvX~N@nahi)Xp|lLH)i3_S1d7b=OF~m(_>=3y8|vZP z;dzlcH+hYRoLBA3#d&z^nQj^v=gb!s4xPn^c*6VT<7am;$`<2tXZkd##*{wB-n4HJ z6~!xFzgi51sR}9eslp!^9^)jaGu_1-Q{=HGJppRC$fU<==t>@Vn<rPqXX<xrs-O0G z=)dWc%(iMOPjJfsX(%C;TUuu#{U@tdFLfvl&Gc}<#&{lW=bYGcrH}os?;UoRdM#xE z7rs_wsdv_?DzZg08P~75Q$Dw>>a0W6s_xt5H)Iym)y1@LDC9l?&v&NB{21io3M?PH z=V$w}Xf6_uK3aG!vlv`$oOhdA(Q-<`gd?$OIy5m=RcThj{L4^%)k>%I4d3Qy#p|m> zXFIGfCjzGm?GWfz<yAXb-ai<ZcUe#Goi9E8J}v@UYWSeA(CdoD5_4P7gfRBlJ3FIV z`d6t53qPMs_=CBYHFjH{$5d)h#E)(pWXTtsX6C9Ee-Z(ev9bMjN3&t9)T)vPL>XRg z8;~lT3<N@lUvsIgd7-u~Bm0;MtTl>@kKY7cdcB5p4xQu2s?{WXxc(xG#aDBz3-`3w z#^7z{Nc^_7X0$~{Lsr4@_9SQ40S=znYOJ$Phkxu;!5#;Ca7B}O{M?^To-cKB>|WhX zd}GWKjVly+Zi@HuIq*U<cwU?X*Uo(F5^XY@^wI%Wan4n$NDBOHWArG!tA4UAq!Jh} zCM@=D3D)|H{ljx^G1NW2Avt7emK)d$%fkDYlm}y7(IoHJoz+LhGXOJ;vFFOtsncir zaz~{}Q|!slNQZ&#*s}zbWD?W}+7RJ1)c0SnNX)nM(g~{ui${;0UJwx42G0Ykv)Xp4 z0-Vn68G-Nra8xk$@buMBFdPp4cS8R9c%d5J*8I0?GnK;x6Et4)F5|r(A+oX$gWAUs z<oyd@5uZ}0hvLvr{}W9~MvXoI*x>-(-IK|!g2`>ghy?@T-~SI$?;FZ~d_QC<{&KmW z-0dJaM)`))(GeIGV-Vhq8MFdhd<7iffb)b=LzN#A4!x`tMlr)WGkN(L4P*O$$n0~V zt2yKEV`MmAi^bO($$+^mMQz6$E`;v8Dsfzd0~c1>juLESszx4UUOT{JjM2S7Y^JLr zX2_3$c~vW;ifunl)Y{BVuKIT8a1R9p`1T$OGaQ}x?Jrw%lqq2q9+JYbuW(q%rV;0_ z%)o;RPH~3t*q#SPW*D|_1EH2!H2K4{A?JUaY$m3tcMpm+yegrJM@5<3y5BH6aOAc4 z1s$&l%T_Y*7UPqM9vYgbXNqZyt?mh9KT3GJ1+gK7;_nF)_@50SKpvkM_L&?q_qE=_ zR2ld|j0^W0_&Z*mS~deK<-@U|qQ^S}v6roP8%1>}EO#;#7q|l8p^e7P7{>}2Y?Wuj znxiC?V~kPwnW=C|7J5tO2~Z9J0W49HScP-aMuAr~u%8*)A{)%)jpLA(7(Esh-=S8~ zQYDVhnH)A1B<E~&H_c3JQt>d5?bjLuZX63r_={bA7x3u`_KkojTQ-t#Cb;2E`+sN@ z=6j5n_>&|Ib05!yB38GRBe0DW5{}_xkS%+q*A}9A94GaspZS6*X5@bFC<JhancTM$ z{r5mrVz_1hvK0MVpIOj3UZ~Z7f|cBEy&S#aJhaJ6CmX6pm^w>Q`ML1GgI-OwJ|6MP zd3TfJLR;*34N8bX=0_^lGnJ<tB;ZBF$Z^Rr6O^wYc)DqFL~xWbNaadD>c$!aJX8g= z#=;7&f%GljmlwI3K8gMh?O}XXWz}`Tm+j%`8IeAjZ5Rp_E)miu?h-D3$qv&+*6hig zituKAm#rDrF9jpOnXwm+lC2^dC67Ix%6R*=Z=acp*Wh9Pn+XGAds);7a-QFj?cXu& z+))NA9U+W*!#OJASW(gVnDv7T*X0jrpXOsNW|ukG)V)C8GbGq@(YXHW?s$z9P601G z#vqG>ZWDnHMc|ktbh#L0f7f7i)D*t}cy8nk;VqCZ1L5=JI4TRhbne3vBn0iHvy-Ie zPeA@*x<Lsl)#~L91R*W$C0lb08FSI)=hRB?^K|VRy&qc?=u;|8l@g3sUbk>Xwu&}| z7>oCPFlIJAdWgxsEUE<thD@(rV7}oR$8%W6mG<o>L%ZR3dyE$nkXu1?=MLH1V0K3! z3+AH5vd4mbt7`0L0!_ahvQ_MGi1%CQoT(%lQ*;e5W>2pMQi9M7E9}r-9_t(~Q#@|i zR_;PL((i{dY}J1Rrmlz=<W}#uOo70``Zpz4k$tSXQ<!%WqUEdFS`soH{&cDB+w{;N zv|i?w&NXh+A6FJyNj;tk5W?M{tK#Rb+3UuCj+%M74>B*1syW!k3=Q=PV7apLP~wly zJoGlrL`t$;i!M(R^}FW!n<)XFcW1m~=)y9iV^0%buBc0ZK%(g7i2Io1tXu6P+7i3v z3)7Ao6PVF!4Y~Hw<;+NY9GVZr2lNQV1=v3kHG*B0WqJ3u)TW5<x-oXE=2*tW=K(>K zL55`4v0*2=bLnPVszcQ|4enKYk=5GVPF?4pm)wH&{+!2fNLw`oNIA2K!TJ>PzAH~s zf`zv)QzSp0p8BSXi)&veA_*x5KkpcOdI&MVcK|@CmrV)84afMk&G=7^2Ggyf*Z{b+ z_^L67GR2R<;Ne3y%|pzRl&EczHSdt_PAYmH1dMv3HT;l8$;6?tkB1kU26NC0W*EOO z=h%q)ZX=@m4edq!!K)nJg<|NnDPzq%nSKk*LR~3|$gKlHDpZg_<vBn(AGP<!E0$pO zb$6+_tGb$9a#N!2pWZF0i)Q2<3lcWbUbhb)9-PR9@tR_~#u+c?Mt83wASmP^^@cVr zILGKpI|E|j{iXocQr`RKTiLzN0Z3|x=xuwaGK9?VglPBhz3F`CXLZ~P81CB-5DjA7 zY7S_rid+6re>OAIgS^`}On4ryL@P~NF0^5Q0ttx=gYm)WAR9Kivb9d=$QqW*c1iP2 zlXnWL%hJ2cvegW+aN~88Sw+|T__F#qVFtY86;WmzF9TbJ%}GpQo5-Tat%Gbb25g{v zpRE=l=68g7mml3Gsw>cikn%)G^ip7ziOPz%*&oK=bhJeA;P~t(OK+H8-4mURI8YcT zysg2|F8I}%$*jD;?HCwFzkE@(GOi$rnE9Tvc*?}P_R_2Q%l>}a+f@9cP`FSZRku&s zxBlwCx0s!dhcZ=PQYbGqE;wsenLTmL5qLmhziX?;=!9k<wp3<SO=fuprU$S3-ju+q z{9Y1_cdDr(Y(N&)e~DW1-#~S_ejP{;Im+A{Y(X<QFMi6S-}71Xak7lDGdxCVF%x{n z=R`+y88Cfbq^=AeFQ=*}AC{1omnyx@jAb+Lx}!ng1@Z2Jl`jn-MNi%`*E-qRemkpD z*d^?j{%z;CFoTz9<z;A1yBv?3*e(VYYM?Bdd&9)v*)eZzE<Z+LI^{l+mBsJiZqc8$ zt2~v@tyA(ZSKgDiaPZC2esBYMUbZXS$w%pHK7nG|b;E5#;^Sawj&79ZMz7I>xxl42 zqM=F-;9v0C0(8&KYd5X2U$j%W0&aJFE|K2OSLr+R<8$fNsM<G-BDf;7z@`vTUi)&L zALLO({hrReS~GsAz^h!p5>mg{Wqc|0x@T(MBlG*xe5Q0IZ-Wvr^qTX-8LY_DW6}MJ zqQBl<TVkS=<%Z_#qT}}WV{4K>`c_zVsg&C_4R*DxC%)8adh|ci?lY>%c2O7gOBzW? zAXMpuUd4cPK?4YeA_PS#0@9m`fJjlngc^G29YgO`q@$r1K>-D+N)y2fHo(Tt_szN1 zT=Sf@_Bng(zl_0;jKO%r{oc=WU#skJNpVjcSK|d)5#()b>M^nWr=nNgb<;V-?j&Nn zzt;_h<ge#;D*mk6G$`cOWY_L0WD{+>#~}tsTIA|C8=Z&%A>i{5YDJt)Lp>@b#mX)$ z7>aMO{d!UE!dLwod2X%cK3_*xh0D{g7*vsSOT-5|4y_I^J>hnD=m@{qP<kq}mh{6w zww=5Za%wQ7xlrS0n;R}UuhgX!6!0Bu?|WRVI=M%;uZOu<xO@2WbhcSSbBDlMh@{?I z-gSS&X3?;Kp4*M(ANQ{v{#?wtvzTGzrxm?fSmJ^@CH-hQ3G1KJ>k%%(CDzA1)N)*p z`F&QIRGoN|?U1frk*e8%(C)~(cPb9dc0rr1gI!JurgAM{#A_*XT0`vl1@jdSF<(r% zFzD$LUDrK-$k;l!ZHg;M7TE-nuk0&dykjpVVL=Ff(tnV5vvKVDnvn0W>m**#r?w7K ziD)-bN&~HO%(wm6#rrgyu-URHCZ;a+CxfDTV<@*?ZZS;<)Ki_lM$XMKQL)GOF7c15 zhzaL;3`s^VdSFXyCvWCdT^Y{-<xjc&o_e74XzKPe%N|jM9uEogXNNJ*t`|RkCM|wa zkdPQki#{XwT_71z9CoOdAyx({F1c~#ZN*d`q^s!?YWKt=r|!3|OS#|GuY?xFhc8Gy z*Agd5U+cRgUZ^4dF@#?8em<UAzf|Xzmek^_8;eZzZcR|$bh%Za<jAm2L_TEjoWh*w zn!BXla^B~c635xvE~R?QXtn;P?}eT{zV^Z0D{}ydrmr+H|GBH(BPwWU{j3<3xt{tu z+xZK}`utbTUshVR%c8u{g<VB*vyKaGjXu$3xccN8^)@zBpQz=q#H_cf??6U96eV2{ zqwq>Y!ag@{e^_C**cVE@D%bTUnvZ+U<Dl;45ySbLVT-+uhIJ=uHYe7Ub+)alwk7+# zce5Uz0zI8Bw=2CmbEuBi&5`hwF@4l*-u~cvj5#b|Ojw`s^qKkjp|PqZT38d7^`XME zQ7F9hb=P2IT)zW^w2jilKo*ZWFMd{b(+<V<3mfCc7qE9WhCp$OTh0h6MqZYiXR zqa#1xJ8?_$qj>pKSz7Ilu-6}`CqDY<2)pUs=B#+Xr*rV2?n}-o)=E3gF}iHhw+uDG z?=FXTIlB6|`wooT%GMP2G}knW9nL=Ue5HHXniJ~jyrbFX-r{%OI{($dA~UO8=xc6g zRNSA^3D|bS;a#9ughU1uG1_p_P%jps3SJHOMfSyVA;NX7-PdxCgO@FT!B?L2>WDLc z&w;~V(=sAtTD1>VnoKgtu>cknd%WUFfwu1S6hc}?F!?IL^;>30EGy3TmR2ZIwfcFL zWsPl5oNCQ%o%xp!Ek$4w8x}|sv;?gn3}S&s)1|(&b=?jjreHzdH;xYZ5{SZI+5XOt z$z*18JLf3JqC7hRkLBCAN&)q&b5~CXmzxfi0*Ybt+p|quQ>7+(Clj@9uA{lQL0e3u z_v|sAY}GfBZDJmkRN1&+?J=(RR_`MIjCy6$sOrpVHDRoP|EHw%qnBY=_4R?L;4F@- zNS*He-Hpe2r#|J<*rHhxdbJvZb&CpIH_W+?!|;ZkA`u*sY0rctzNuo!p}+kE^@f>J z9UV0^gAZSN2H;_51fTJ_E#I6IYFRw8WB_-jh$RukVkK&E7PlZdQE6OUZn`4C$~AS1 zupdr_llCI7RhP|+w|mcshNo-rlejFRmko`*&rJHjL(aISpEEOZ%dk#Sh3FaqL;-+^ z+E~LE?G6ma+&CNX+(PU7hKsK?0znsvz<Wws{xOK=J7esgX~E~>8#tx=a)LlixXOfa zFNjkd^DMFawmzdPPlJ<C+)5kIvn{<~(*=hHZRdS`HdU5R<JjHp!jpW;a_-&LlHJ1F z&c$GOt_uCIxLxyc>`FuT0!`Sa)91j!AlD2cT(_rGm0~Z<7dsgRU)KF_9r9;WK4hT> zd1%<Sq-%t!i_|K6hj(&|_vw6_8=Y+S21JrI@YZ2>FCM-)sGxU7_fkrW=x-^81B2+U zcX9DuJjyGqSM?sRWR@<YYcIyd5K(y&{D%0g2KjX}$AI@;;3f*@^ktCmRuA(;=lOFk zzPBbVZtligwfq5*&OFfq6YcUL*G*>(UWWBT+egf}a=DzUFI>Gw$X12eG%}sNIdk#N z0EpmvLFJew`VvG9P&+puV$Sn}fLVZ#>M{#knM36P1N~9|B0#&AQF8XgT;wq4R8cjX z>pmO2+GVJXL4jpm^;g_1T$Od(#lGSQ!u}e>hngL_U+{%*zusTf$wAP0%GIHVFWb4J zY~G)?c^KHV)%^5jB_8;iW;M(?`0%Dawg7eRwFsY3#+fT(&o%YJf0e3zXwNuV!?S|8 z*ERtE{o8`&$@Ql_#Wt5ZgV%TBU|G!ri`gRMN>%|c-u(U%d}HtWs9eq0AQp4Xns?EK z#Z2rdP3HjNOWKU(>S*0KRXKOeP6J_?HUQ(unU6wGY6-K#r}H-1cd#uBptmi6xWY(` z82jzy!?Bx~9VP&l&Oaif2Jh#ME4M!pVl^1dAreWVMu><m8w5U+jwAS<8HpD`otLh` zTzqPx!3WZJ<m`%YMFX7?F{lQLL2diGw8-SB^;}xj=qj7EyFXTUOl?5n&^hX)Sioa0 zUucx{lDilYY-hgYgjap*my8`1*DJTKirsg_%0LpcPZn#1D?|lg2G~Vvn(3{y_lX=9 zwzeA@7|PdVtSiEVi<yHS4y*`%2`-g2kL5Iuq{Wl$>@HwpY6#N}Vgo-%!lo(4m8QK0 zmvh(g9F@XN)~3>5vSUsFE5mkj=aW;6pCg;gHR>BB4RKnzOAp;ujw_y*j@712mtxNJ z*j#tjjFkdxW5=&mAJ3{-8RH~LcigV}c;%hoS;5zHky54!`FP%q4$GFl+M>!Rfaavb z<~=5x%PH^Fe8F=_!^A+$QZ5aA{>9f($#5<XKnuu3vP}<0(EASqIgiTnTqaPtJ+Bvu zFu5D9a<YeOKQFb5<(2A4kId&7h=oj%N8~uh0;U5hZ%Ht*gxjXP=x8xeu9LB-SbNR@ zZ?7x7mFALHCdN^}R@q6?;>!0eUg)s;w=oH?dB1L~|2R;^%(Tg#Klk*7;6{yi-8<nd zXX*`aDAK)-yFSzNMJ(6jI(^?_wmU0E$v-x*qo`V!u3=DsnFL&2kZ|ogf}`~$k3ZLe zfcfQT7W|XgT1W?-nYUy9dE7@K4P9?si1P6L>OeVE>^q#n&nYAH2H25z7@wrMxWd6I z0uqfpVVrZ0o8&Jo0mg$~-4M8ZP6BrS`THPOOY`xh3korZjA}(u3d~0bU<%kR&dA;5 zyMo6>61nSdA0J``Dw%-2tzjjpX;9|(mixA;N3;>j;P=9xWtT0>>q`x(U#;W1WyF|( zlPkqv`@q5ujKiD9OjW;$xgNP2a82*zL3<hNhDlvol>obHiq~7JZ29}tdQ{itWOj)w zua|+y#NFiZbJ;!GLygJm?vq5|h$!SN1<U-oGlJJCNeQn@>P^o)Hrjerv*l6|)_d$l z3ba>fFgCG_w0?KPWmwziQ}WaNx{wX)heeHRr!BQ!MEp`2h3AmjrNr#h`Q8zYwF#<i znuJgM2iOJiN+n>2?G7C*;%0ciM0IE(tZ`Ou0_}U4dgZ(VCH;bQ2&bsr?Y(qI)afa= z)}0b_`^J!#D>VS+6Q0mW<O9B*i##39{;Oh{ykUbh>*1zVZ1TULwkE?=j#noy%iNI> z0Lt>2)n)XUxU_kpKMY2mgLGygimFdvKEGkQe*SfADz<b)ac?mlEql>i0wOKvk2UzI zI7i|~X#IYzAE@k>dv2v-^W)xPT+X_)S?-AA&DXe~;tz2fH(Ea^w?0ze+KJ`Kn=cE1 z1zATt@s5Wf4-6|iMTGS?v=(|5h#xHl&(+`Z_}ugnCo^){tUdV=AN5DU1M9q+9mNcd zEETxW_+7<QHUJjVkn~>D3VD*c3V}D|C4Q1RRBp1%Q(j}--GWK}WWOqYa7(PU^Ti`p zu`EuBT+wW?*{Aov)JU?uzxv2IgxUW&nVRXxJf(HFNjc*1V&dCtpMHKni6aJ`DhtYZ z9sB%u(*D5t!T0C<1kH){`y(a}@*an9N>ml6mh`-W?9-|@r`Uds#tXj>IoTB)Bb0Hp ztG;oodSL5v!*~*+P=$7~ma)Sdv=r~jHslyH=frmBBu9a?ljMijF50SLRz?@N*dBf{ z&xxIWXnQU^hUx9myT7LHjLY2%ez<qf*yk6B-Y;v4^Qt%B`c(61iKNgRR(CzLPNG2U zK<I9fhe+7F`n!jcGn=|*mh5%ueoUo0(0#6{jYHdX<=dOgKq>t$+m?fXBc^tjiFMP_ z_lzsc{uxVlP^Zfo3_Luk{LYCclFd!B*_5AXW%!7D5S%@XyO+PeE&MqA_7fsn!wIdf z!TyGEu*fjt6r8;Mz#UJBr0?A}phOx~Mw*O7p52Nxheuh+M4cx@UGR*uqC_!n?_3&* zvfqlj43Bn_iFP4GyLm=?P@=smqpyraU)yp>*o^k07&Dff)_f!VDKWU`Y-Q=Dcd}yc z%A9x%qeSrPzn8obNuex>--yYkByLfXvxCEfF`IO@uQ<#GokFdQ<r8NElUW1WV~adh z3ka-1GI15{GC3NUFiKpVhGhRrT+<vuzFZ9hmX2?uDD64MwU5NJhqF~*WT#HY_gjmN zxhH%8#SJi2m63#rt%RrW#3`A?XN1HV&%_s$#QALQ-?X@etwb{mcP6HPsecFn1_Xg{ ze~;@k!37D8jB$NH1^d5O|4RQJ*S8yOE_<AXa~aDwx?et#r*Y%$(&+t)r}v~%$bfN6 z<x~kFP0rr?oanQEj_bcQtho43^{+%MjIeLq`q#LAm$QsU5f;XB?b%p?Nn8DLq4lS? z%a7X{E>n0QFky}0omc%7PWf_q5Pp4-DsEEvD_tK(76k0d$Ny6Q<PlgdbZ5)<vr2hI zM;uiZn5{qm&vE_s8}D9DbhZ68uK$<%*S@<xk|uxoNq5JWH+SUm_sn{<F1?$(FW!K) z@7nt`7?N<v>lfaA@OkTL+ABUQ$EEKp>yOPxLmgu|xpoipae?872LQ}7HH<ySS1$y5 z(<3zi$v;4Y@Kdl%L1?7sYLv8)43)ewL+ZUNe<7F(Ih_yIyUQa?ng)20m8%F?Ar%BL zUXi~de7Kg04Z=LUkp$y_NQni6Vp^aA%tgvXz9Zb4lRQTa5p?qUjN|%k$%DPiiIABy zV#=1;8lq9(pw_YJp5CXiF|z4E*4^o4-qdiO=X3T@o;#WV&ncLVd#>mp(^imW(uyuK zhbN-gl$(InQ)hzUp(pTvG(Ar{Cos{EpgM}^Wpfredg$wB#NJ|wQN~m1mSG&UOc!*B zEA_7-dCL=+g|qvLVso`>OfK_ds!E+-{+Oy5Qf^~>hsgbS(;)DhaWjg_DnRFH^v`+U zdNfJBFfXppYuor42YDQrg*gsr;9H~Q+IF7A^mgCWGI7^e<@wIQKVEy)H>QaBMf1FA z{9<j7)B^CJU9~&ukiXQwyX=oubeY5wI01|;1UGUjLxF?B8&vgnXY^EED;)&qrIQ}Z zAIIL;Z+hT9IR>oUnFMJzyg&W~LZv34e&dbFYRss`FW!ii@h?xcevSkE#A7|a<Cgk5 zs!z|>pj2l;N<A&l&t5+I{l%r2iQ@nq8~=Inge<mg2_b>oTMl;lD*N)z-r-RU7<_ew z^@RM$=hHw-0y}-2rz4TNj@ErhT>=OW)Yr-Vb($8TK_~Zg16~~M#207zXl<8QIP8I# z?$B9LOfsUTz)>0Tg@wE~AD71Ned(bu!)AoE`$dl8=}>tH{fn9ihR%u^d#4zB1N`gd z0l;j1s(T0Qclj67%yHijn(Nl!+Y`?!t_w2R#XrP@npRmk!P?-kUP)_8!=FDBqvHS* z7YPbjZfLl&vq^q7u@xlHPyW&L)hwMFt(e@S|E2!%j??}c*Jr)86M;oJ+1e>_L-URP zrT*<i;S!2a9t`zwVJBK+yofbuq+j^QP7EGZj5&-U42bbtNXTh9yUO&kOWHsXyg5V0 zSSO6MA_PMaH8=xlPcgrW1-LXK%vFj`=XtUNv%D0=)-@8m7{U`oM{Ej)8<6klA^20E zLJ+-p%6L=4ttlJ*jUy>czoxL!39%9~sgUqSn30K%tG?xigmmaYBD~1a+#5>B-Ezc+ zc2n5oI3Q$K7g;+z96@#-jL~)yuYmw)G3UYKf&Ryw1u2ry&t%6^S2pL3=SC~EAu^R6 z@T(;#cId^pAzib0=f#0WJma)47E;vx`m)Sqio{6>qEC<luAdK&ahw*d(x#}(PNSRg z&tL+6fbfH=JpJ5(LTs#qfurxCURCY!t6w*GM5jJ?k@&y5pXz;MAQLnht@X7ClUR9L z+ITANFZFMt(olVDD(TkO5-hrkaK?B#HTQ4z&)8~gI<xa@87{HP)Wi5$?!wpdztq2= zv1f%pzE<GT)qkmfe~s%C&Q_nx8hc*OQ2$hZkyxMXvi+t08M`vEK+ds}H^4QH=y#aa z-3v{O>o1;XYno0L&9-)at1CDS5nCCX>X?2|65Iao>K}`sIsgbqo~@0NX$<EE@GwwL znX~kX6f?|euJjMCQov-a34EYA2U;qX#J4b=`@N;|Y@N3iL;dUg{-80j?yARM>fgfm z*7k`ypP<K!FBx(iI!emdem~|E>PYlWZADaK&C=$}0G=l|MUNHd^<71t=6QZoRI&MS zpQ`^}*9y8Jc-Z9S=iI&St+NfcUOayJy|b<5c5uU;Hzu!sEMy(44<6KW7iGD$6m;v4 z&bHbglNHd@^mx#GJvlAP5t!5Cd0_3^&9C4zF$L=4KACg#`1mU8KgadS=Vut>`U5iM z<FMA;HJ+~hL0nQ(g2$3r>-7FmkR%geov<E1)I5x5ZKlSUZiopSjLd~drZzo`l)Q3g z)GW!Ir}%xoG~Njb(3OF5Q@1ys9gn+vV+@;VP+VS4#dGa{sDEeD5Bb5G(Rs;W54Z9E zN&RcCGE{9RZy5?$_9hvg<rhE8b&c4mMh+e*Qx_UAx}l}Y_}fqcFp2J{0fF_cw-wUs z+u<#@W^{~(N-IPSti{XkK~mO~lAJs)9V_P__l;J%v&`rAHFs{rthG67;=Ma3^EAMi z>)|e8`NX)m&i?TG<uF~$6)=5qp`N9s|LjNqyq`;=e7MdRbzMG{dCNP|d0p#gKiyKF z;csYdd$>38DeULZSHSQt1__GdDimLF^OC;FQuz945EYY%`IMzu=>-5TtLNZF>d4O& zKb5@<>p~5<coI6ilxg+Cp;3e^q%YA2_k*YB8Ytb0f=Ct#+LV!q#Gg}23i`?OMr;5A z_^`t>f3_mdJ_$zh^`v>{U)Yr2fT<7leqGhmc`LJbpX+qtw`v*tA^et>RiC0slSdiz zj!M^s$@=dP+Ir;hTfKPKmAOyj`R}BCT$kQB1ib^8;^4h{xtC180~239oc988k&=Q- zRn8&I9JPT~pls-;>k2^Xex2nXX^1?%3!d`Nk$!Yg?p(4Fk)heoth~=Jr`?)*tmj-8 z`>u~Q_*?U_IQ14M@2$;~vZJ_fpHjlnH=pWa+eH}aA6whTsqpOs_dlj)*QtIc|Nqs$ zyCqVO{)oulQuYp=9m?b^`Sk+zgmhPs9bKY^nL0z_Wr$_~0D=SHN)rESfM*MeBbdya zP3CVW3(k>+_Zi(;xR^$`gmt)}p_5cQrjZmbI~T6FAAUq8U;^ub3&w!qH&m@LeOQ!c zJI3He1T=-Yiq4`9j|8!!9y&&XQ&3Cgk-&<H8E+Io^fR7=K9oS6m5H)#kFuMKa@db@ ztmKX%g$hJ-QmF74T=aB|(@6_>1pN||n*Md(=#~r7c+Z%C?3i2aF?Z%-PC13@z$sxG zl+Q1qe!P@gY*Z1IxfRC}a|n-2ZWq)xbbI(F@^^+)-%P}=s>mb_eh$uh1O&!4x+o1r z8+x*^!GK9jRM7yu1Go{s#T^2@UZa7@fJY86wt7i1r^r{lnOWF};Kbh3lq?F&Db7YI z{%2r(Q6%HgVZzU$aARwvLp!n&A9bu9xk5y>YG7)2TqL)UG~al9<z;Xa!hQ#4Hj-$; zi;Tu%I`Bz~a3oj>Wz5U?IlOuD%nK5H#X3A+0%I$IE(TC}R5(ZlsTzz_b2rr_AdU5q z9uQRDe)2IwvPC7;*3-nWG6h(%xeQM=3`UfwBGE<^8OF7>8IH+p@&JK7WG0nY#z@vC zO)Vr%<6};mR!5rle>bjg+>vfNpKf-LPUOotr<q}ClW{R5!#XF!wj;xCKEvT4!;vr3 zSu@ksCevM0C~Yg!R#L|+B-1*IZJ)~K_8N0|#D>Zpe))nkyDm7$3!JJN{*i>aa-eo& z)ZxnxD~LUtwf`(+ij7~DZAgiY(Ul)gvhDAn+@rI7I&$*oa~R9|G``$o&0OC!JI$?> z(wyAtj@;V$-1>vuM!vje&Ab+yyw;Gs_8i92bzb*;-ot}DI$wUDX8wRp{!mE%NKXD( zNB;PH{*#0J)1q0%GC98|+5SHx0Pg=T0_ep4mk8i5^REcN@*feP^wep~|A+wIGL#Hj z6yl!|z`hXq&j=73@&$?d)z-M$Px%lIG-@=h4^zcYP0)26VL*oDm6zikU&g?2-P^)v z84(~3#e=d$<5k~1`%ho%e~JK_uMi%?TKCKfs=mIRyDxGN=(!s8Zh_%z4cqh$#InD6 zR&u%F4}`?7)oao)8QT5(r$PtY2GeEvJtPNLsYn=vN9NpJu8uRrP)Xfk8VUHdR{#<7 z#FC+}_$pVU)pR^lV_>0HWGIxT^aOGwyi$lsrfFm~9#sXOzRAQtP!P#O*y%qp!Whw` z@Tu)F>)N*aVPwIHep6Ji7t?wgG-OgYaU~Wa0bF1$eFYKA+=`8rK?b}I&B1$>6I5F) zFH=D`gVuv2idT(*_ykTzJC9qCGllyF#J)?;fx#~MH(<nJjg!rz9{P?HCg2FFX?LM` zzE?Us;rP%NHs1lZvR%aFUg_yqN%ZzMy6cRTp$YXwc~J7l4!5@}q|1Z74U3nJm*MAT z+fx(x{56ZSfN_36g5q5Lt{GOoLUvSz3e-r0_~K#890VNp{*pI^33knGl$gou?53!< zCJga_@&>%!2CO65hfb`M9Iv$PukFzqj=SYugF+*fq>r3{tUT6CdG3c`KTu0}1%kK0 z05GT{b77FhPTOyYQyQ-{%ys_GWGQEs;O7C+V^lxjY;EemsRjTKK6bx(#BUJl^{Z)& zId;5hOyY{d?xd#2uj5Z4h)|W$x(-8s5bK%WmLQ@!T4fS!p~DWc3rbYcWqe3wko>b9 zb9D(*PCa083j=^rkw=Mh_TrfD%l^;o+m=IK9rgsh2m+J#UIjlr+761`s|#9=0N0bA zQ>6{QZKNHKY+H(PNt%3}|8qipP(S~ME)YQA0C-Bf?GL=Ij|F^t0quFBqT77j^5;my zvzNCvx=l`otiilqTFhA<!{Ol~5MMfU9koL~A%eo){`6d)`P+u+k(1P&{#QK!6Bvi5 zH@(TfZ}Rn-RYRCRu_8HjR=7s64<r%LtOratG#vUj19$*@;Zov?<>&SfvLr5r><hr& zFn$e1lCIXI;s3m#BgNjJpnlP3d6)nN>z#-JO^DzR8n_^!4{gd=W!M7xc#Pe-!Mdl- zs1g`nkRuo0b_7dMwh)qs8iRkID1XTFS)+WODygD9h^Nz1phPhWvHLOBzc`-Ec(I(N zL69!w9aQAsJfgwQr*{#j!W+Ds5O0g+f8oii+Ps_Sn@}S7hA^zPu$vS-ULw3VGW?gX zMM9NgnY}di0u4C?HN^~)NbKIVkQAten0|RMm!Q9dy8z!H6t)70e=9YOUW%2dQNq|= zjbiH1i&gkeO0zVMOa-t8oGN<pC*Y-bF@Be24nb`(zldUxNjF^(c03gyE=HgU0oqmR zE^3hmwGh0@skN~bJ~v9&^H?-2+$8=hO$?8Lt7U$MM#?lxr$&w_sQM3F(~~I394~j8 z!&AAC5|D1ju))~Qp-ejN8AEQBWRdTCTEA3812;(<UPX`;h>(;g_oK8$Z;)3FHsDm_ z+%Mx>RByG?d}cojgI3*4FJvT4z=^IUy&#ZWJy0gWM?WSx4N^27Og!!;+va~O^ZC}- z3a(XIv$zoUIi`P$0K~*<O9rY{{h#pnO#Q8Ij0jL;J<Nc={}BOfUyS`70T}SN-5X;D z{Qa#yc;eq9z+dq9_eRRuTIZjgWZ_1zNPJ?gYgs2q83b4WTf?sEkLSxf_3sy;>pahx z*s=`W|2qOS+@k2$s@2wq)>*sB{68Xq+U2j2@2|%^u3(`uQs+wLiP*<>Nv?j_GS83a zRGEOYq|cnw_TJK3Da#*k{r3@IuV*LmpAlg1;eHv#=*yMilUvkBftE6)Z8(KVfVXj3 zyHPNx$WcRz7r5`~D<moBqzP*I+t*V6R|Gg?y2kN$1c2+GAOA-L*c_L4Y{Fce3+GXq zeHHb1AyM$>{_vf%xG3^?E##Rq54)8AL*ZK2m-AwyXOkAFC8n?CE**?nKWWY!1}_}_ z3;vFtU{(<L7yOOtc-G8-zq`>)fGyxr@7(-f;qS-cAlmSkNZmz`vS=wPGv^0E8HS7{ z#5GdP_d$?wenI_U63!!dYuk)D^I75F@b}vWGZ*ZTjH*8&$NNIpkD11#2elpy_<Qlk zZ2OZ3^+6Nw9DXjC&Qc7M@1DI{xz;|{EGpTYyq4&;IK-Om+u9;so#^$foPRbL2IR6Q zk^@Qvvmdm&4~1ad;=5#?5(8CLf<F$-rDIDiqm`4UK8~2W@Q+&?_UO2vZhc}z0Je5I zvzhNtJRfjDq1`30*D>ly`6{b=0uJ8nLOFBi*!hR;L+Vd<llmhCgxNH~!%pawygQ-m zhuFPQ2K+tctj|!XI>tTBzT__c+H7{0&{g;_=)WR(bhW;*Oh?1(NVO=Jh~f{{8=};+ zuKS4aq_sxoX-bud^(6J87MBPUKxK1fJ@sNt5F|?V@husyS~>Q7eFWKX`FEl#GyQ0{ z)6GAIp@{@@s3=75+#k83$)G*wW5Lr2&*hk=9NtH-MVwsef7JBRsqI0D_+bXUK@*;S zh}>jqTpITnWS0E;>mvTxkEtvNdENG6yd!C87i;^@&CLBRbKk8G5ZyP-IiSj?-63Gf z)vvZ8eGBAc+>BjQgt0G3uZ3!{1~zzOhVTB8#u4d?JiQOLQK`r~6*}rJE-<Zg=dcLT z{PV>3<(}zJf82+Azxk=G|9X2WPOX{gbIb5O*&g4Yztfu0J75|bWa0l)odg-d|B=R! zaaVCxB#qrrSc)%-m&~C-=CUU9{0|X8DmYvwJ6x_kT!9e*Mx1}_g^Mu-KAF5$ebY|x z<^?r4FiX3xyv4p}h+)}}5Yk0^y@&v4*G^kUf|`6x{uBPTj=C5eWu5)c2yj2}ssk^3 zGu_q6I@&!r+F|78><WwL9A-f+_!<Q>j6wNrVFWE>;7-i7zKrR@7|1G1z*Y=YDJI++ z<7i2t1Y>SzQ2;8;@sJBe9-*Xa#HL%vW(LP*dmf1*l3hJH|3Z-)V>t;fr<CB(=*y1Q zXNt39KhMO5ZN=5{#y4xkw^+xUruaos;#=F}&9|T@He)(T0jVR%8+ex1o%rxz-!WbH zg7WyV5#$KL6(mJDj1p;D2}p&b1;xMtLkXUn2{$P$?If2CY;5}mWB?ztGRNKW!2h)d z<{c%vA8=~iH(HivVK0XhEf9Obn5t~<4}=?~G8iK@>IHVHidAyh95Q<!S&O+AJc690 zC4zd9U?wCoHmZ@142q`kXkzG&P{%Av6D~HJjsS@wA7CjW2w;FpA@9H<SC9)M@UqDi z_d{zru!Y<Tl_d{AMNOWXyAV?fAfZggHz`O02$?wmrvrf2XlfckKW)oBTqAvEFwQWC zQs9foX|(U=&BTt_AM=a3IFiiWs|(kR`XrU<bCBuFm*uaS6=0JU7?Ks7lXa^j>&|>u z*g+PFFFRZ_JJKdQIwYHtlO5NQoiLxBbdXJD_*$Ad={7l;AvxJOIl2E40Tf;*#<qh3 zW>1tMa;q}f4oGZ$uQ8f%K$&#T4sP=W$KDiju3$LoJ<hOV9%rBFd`Qd#c39EpEg&gg zHc|O~MY$j)Hb&fdzv<N%oBQ0RU^b*+E~j9jqhP5+|Jhu$^?bpa!GD3j-*yzfpD+A) zP`L9i`1{^|&b=T134im`Kw312Ee&>y2A323y^|MKnOn{G?{Y7UA@}}!xd4ZH6Gj?~ z`eQKS#`%P%;=y>{<K9anO(nz0Sp7Ibqvrp8xq#;s1GE1}xiI#8qp$p*a_@yC^9Jwb zu?ICT8jK8nQGvh9g=gV|L|;8!6wgxi-{nFV{{Gru<-)5+oJZkY+Eknqol!10Bv?U! z;RHsxU>YJ9g92#+bi2RG1=?i}yoT0a<-&OnJG!Ie6`<~N%|GPce@hk*gP6jj%VJB; zGJfq#Ckqc(DR!q9{}$AA<>?b4df=z!NAZVj=EB_vyKf#dk_AKV-Fv^<m27_ZVd%kr z({UVt?fr6iLuaLz1mW>qA;YCASHe+hTPqP5Lz&e`u8W>Uk!U!u6748T!rwSzC$mP8 z$n-2`mZViW$0^irImgQu%7{k;1Zkld4Ijw@((!X}d@>%k-3yoH^7>2e^(v*B3eVB; ze_qR!S&qxDh(OP}SGi>x2X4C|FR2~4f{><OQkEAk9@)&j61Y;H$HQ^(I^SSuWHZ6M zu*$>I>gBd{ns&CRCsN3g@TTbQlP!8-f^r545S5bKjx7XM5Xyy?bG=0YnZ&J9@slAg zC8a-}=jYPO<(!KOOLxFgLivYuFXTG5q_nywNs|tHyb}NzgVXtKZ-lOS*G3BMkjA6# zmotpuI<f8TCayT|^CFOIy+gW{D9a&(Io6h_#%i50@dq4#_NDU+cZmHJBWm#|w#57h ziB8TyoRse6UzUgt%|b1F=|0a@$L4jr_U+m)QobfFH~X&ag#Y-?yfdgF*+>Gc&9wcP zRa@lzx=~*k(=#J;wxz>tn>m@hF2Lk<J)iVgKWF&qH?KMrN?4SYKk;ZNN3h&L27n;& zNs|_F)bepM_ZiJ+a_THUSMiWjiS-p``Z6_Bs@TwG>GcHM%A~zK{8NRO$eh}u_ow*m zi3`%L_h*sSU5feRnTMtfUqidIWs!I<w2?VV%1mi3A*fDcDN_GqZ!yToe($xkC_ZR7 zSfn!OjmO>4t*N_UAChz-UG`uhLAo+{wO&05`>yWHN9E1-djWEQcErcq;o9lM2t@CZ z%i+61rPHt#CY2Qf?rZp;C&;s#KEDZFE(e?6mx4b1-dl+|#*llnuKzjMy8a2YCRF=r z6H@pK4~Pgr=w|8#b{uzq{Mx(zr#Q2#5YTBRL3l|_bxuj3BO`Q})(#nyK!ZpVbeX?b zFv<liSTI|3GXTegCIF(d^yrXAQNWo1`SJ_gi{^lY^V}{1+iOrkCmT;GCO9%3)1V87 z4d}x(Y+!$v3x-wXj66q<#E}7*FrI9370cAU!)Db;69D_-HPw9ah?DFQ%#G6xg8K$I zsTC_vZ9E@%t6$B3L!X!s2ihbIYdV)E-AtzlF_DI$D^teAa7Qo*8{_?Jg2x(8m*~Tg z(0WuKB!yM)&j`lYp^<!Xp#=XK4zPJmC(<lY%XZVlgdgn5+!6o_KaK?K(|MVweVRy5 zeOUD8Om%^>vzxpHOoA)vA$C|$)Tkin*XM*W-eFCZRUq*wCTlXG{A2bPCg#)UTuuZ` zu)BZ(QDh_&6QNJ+?VgDjL++K@o(0q@O@wU~k`TVG>R=qnqUcNE{>F$5<lLcoMEWL5 z*>nV0$axyhuOgPTKdXCWjF@q!m{Bfx8WTkSQ7&AolrJwP-F5pvD;G!y+{7FDh@^nW zVg&k#%0&<&LQs|Qus|AUf>@I76o+vEp5`h_mX)S6{NSm<i-J_abov^rhUk`lu^iQ0 zMpwL<#yH@{&i){9MkO_Xq9d+MjQz?jl?ni82}Whp;(o~laaBKzyWTgnv=*L%CRPSo zl`|@vfS!L=HeeYa4fqjEvjt82o2dC5!3!#oQepO>xqPY`FDOrCJA{Z!-UhbDO+hh@ ztdTVU{)&MsOA5E;j7$Jl5%7#>XRP9~aLIZDdQ_XaYS;+@_P6@f#!F-k$Ihd{a91Ja zg$U0qv1Nee#<fOv=I)u!^Ud<c8}g~ZdsQ*qPNn4&dFszTtKvVZ@gj#NE9sDZsjm|w z(k$aEuoM3;x%a<G7G_OxR{u;Ef0YZS>k)s7hBTfuB?XPI3p0|%e<>FTX3eQt<F2f1 z&e#aYD`^?p6lwjCzmtXe4<@1fb&*T%RT=%JukSaKpdi^8{Ab-wwJy!WksZe`d2dYL zXe}P}v-R9B+_O_XvtwgT!4KRERoK!!)L@S`Ybic5v1NGT#}qZGrF2oyHrVvXv~&g; z4~yS6dsfN`VUMcN6l4L2#g))e2=G}NLrk{qPXkC{EX9bGhq?V(+286+@(~w4*$(8i z4>X*yOE4j>apZ1&Yt*+xIJMoH-?5K0%(uVd*&oP0Jw%bx>YXubUs%w|XuStrqxeO1 z^(T40?Ksg5zfp60nNLx@TN4!<1jaXgsrT(f=*1duX}#j~k$afeY+(av=YBVQV3~A# zhsg8o`GqREqo|iVYQ}x9EOMgo#%RC+Al1)gaNLj=UasP`<8eN;R|R-|%1<q2Zv-O_ z@V-t`vi;p+$iolkWXyIAdwy*mIe76Xqu7sj$$Ha3{TBHe6L1kTux{*uQw-3Jx5w+V zm#Jw?lss8+mI3iU0O+$FKFf87de}B7er)u~_tvi8AAFO$mfo1{b-oKY($(1Ya_`CB z!=JxDDKCRpn9cY51pe#@1P;n`D6`n$gm%?J?<BM_9gJOi`AI?K=WCNO|4Soc@AIr= zAL}1`7Mu2`O!<^fT0~0VOqPmJ2kv}^{ar41iVL<)btu~1{3ngK|40u9VMo)F^77|t zzA-F815(U-83O&347+cfau;>AB^*2Y3UN%kFlhbN>CZvrp+j?;BK6~K5vdkJk8P44 z%8$^G0r`cQx4!cG-0yl%`6ZC63-;f6>c%(bh;roS`g-Q>$<-@wq%A6Zk?0fzZx+d( zjCyRv$FhZi!^w7{cQbZvc^Tyb!6oE7S!|0e0RTVM!;M>QW&V*Y_QP?!5y~17xD;Cz zPvTkM2o|@9qZXc8mC`m;j+6Tlhr19W4hoPW0ZgQW(yh~!BgXrY*%54v>edz;Wz8Ej zX&|uX8wwRgy(tY-n7aj)WYJ-caFxLfVNsn~QIjo}-gD8D64A;sF@5SW+h-#Cd{KL+ zt;|Nk`M09OM*;`2-ee7mj|7@RG3jRpo*eq3=G!Q(Oe`KUu|AfunOpkV*|Ff3*!=xi z8gE>&MqKHLzzh++M2xG}@Xl>x%-oWmSioH}-5MH$Zx^Al7w)*a$KPg$CsQptE8Xg8 zjKhnu^}PJ^-vt_j69iM>qwO34o;(vo^b|t}oJ4_F(d#t#@h#4&V4lYW%<5dC3KPq) zTY^Fg3ao+lB_t(~lf;w)Oa{YJwvyb>p~qKHft6hAp2_y)JEl$OIXXK1O>&tt`nM-l zrzsHO7kIG=4MhOkWmLlyn3)HLb(DJ!#~MjOtdr0HCWUL1^C1@1yTiiAxB%RSUdA8| zR#+zRRA7fO$C0YxMDjS)4OyN<_u%0dCs|HtQdJq110TnqGnibDFc}13V#6apn$|;v zc;i^xHPRTUuaGE9&LEY!h{aCx2nGQx(HWlyW<Y0IBB2>$zE-gryeT$1!w|rcWs{i~ zV-)go1>Hu4T?f*aX=%<maXvZhcW{_&UsNwH5Ot7ovnll@9bGjEjoe9Lgbw~)7{r3* zQVdI-XV&5hdT|mpfn&CsWT|RTgDRzDBG|J@2&fawnGRmeJbHZ+egnsh-$pMJb83v( zTj=rkl=2oP(;{)q>-4-HBf*zc^b!UcNrQD#9g=0U6>{>sm{MHk(ev2c8yI9DE|WZp z5j*rMXi>_1Z~$+$VeMw5j2waa9CQyARz-!i`Q|!%VeZZswx$$x@gWm^S*~N!o>kqW z_o9`I;1iSZ$i}?z(YymA+Rst+@?=U6j`^Dxrk0Atye*s~LQE%FdM05Vh{9zmvWt{2 zpe5io3bCRhpUk7@DsyGYR9Radmz*qaxeRX{b1yY+aWeCoO-V(HLm~-e<(Owb$pTU; z)a6foFI$>Wl&c5;-Xw-AmoZOFE23ta=jIam`A+3JcmsgqB;1<_jr7gEPetC<EY#Jc za&%^1=I0Bqg2}9aBB?M%Dy#>`3iivY(qs**M$KSLl(i~uG8LL33zrU8K#Gke3c0Y> zs><WCDZ?SCW*WkZ20Ig%D-%~4+?3~RlV|E%=1r_tSg5#Xkhg?I)lgw)I?GD7v(ou* z>Ju?U;<=b=*hK(HBtjH@p;lVxx1%hB9aXL!iHX>Ip;|OrC+~zW6d>N~LjqRV94p__ zHec2-E!LhL_%&aabvi8|tH!83QksDrVKEjq)k((ir3ExtHqd?&j=EJDa3o5stg;ve zw!8)H^)5HXF;{I>c#-mcZP)rSL(esy^OwU+SHryV@TWGAJN(G&7-Xnc<`>(bs;I~x zTIbm0F?y45ZhmCy0*fi8HdHQC>7eSV9N!B7C<lP5LtIWG5jsBxDZ<sO<~ZOU2cD%z z$VMdsJMorCz-=DtMT6a`hH20%IC3*}7Xwe<K3A!UNnfeR#@2@3Vp--xD$*fU)(^&< zu4~+UAUT-ob^_D0@}P=@sN%i%?rl*Ok(KRn>P$ze-3y53T%)XHk?{%EQEEjZjV3sM zUt6<j_ARK2SR-kH&Qfbp$cPIzfgfFHey_z0?oElrm&wpzZ)j*}Y=gy_4)SC4Ya(kl z6&5+!Tz#9xc^*#27Ik&hf>uGv)B+B^`(aLnuU85hZs&t~(O2f-$vD;<RAkr>lweM2 z53Y4jGw2+qnGf1M_N?FywV-N08|=q&`|zOo3LnzQxZFsK)t^7}8go0JYKpf}d)8z@ zxYh%-EoNdnw?F_{Hi|YNLc#@7(NM^(ih^*X_7vaJFDH7yewFn`@HXlLwZ|2fw$NMw zdY)m>f>GWq9hv&0`C1;Pig53XY&A5#YaLtrtE1Fj?yL^o;l`fLx)w`nE@~Lj!p4*X zSxl+u$nR;aHLix4VC%2sWS;dlJE|SDFo$lRY>E2uXk!7xdC>8-BW<Os+hqX_#G^iI zVGIP%>Ja_jcA?Q)nJ!nW9<6kSjSiap$hunFwl9}mg=5}U&8s57ADEQsVe6M2(bycc zyr40DXAmR`mZzRLeWeF#kk@<YoA=FVkhyp0%CAy%b-$lCZLF)_`aNh4+n{<de9h9D ztc{7ZQ^!*+;biC~iiy)G%_RrjvW-eGeYAurE&n;PZ2;$w%d<2c+RX{H!VGNvv^f=L z270gmDau@Lw8_;7-FDFKdbO2Px3LHVPxtCt!rV(f!Ah4)!B!REUO<SnR-fmYda{@> zWB4^%)3DKy2pN$`M=yKbo9D{``$6w4pxG7&CoftXuRzvNz$Kg_EfNj+osv9R5Ng{` z&0{ats_SuN7B{AXw+n7uf=uT+%mb-FPz^BobPJMlr#o%%;NELmLA_w1U{Nl=7Hbi; zJ4`SYhJ2d1Qt{|e?!f}>X@4LjN)of8jWG_60+#i`vDEcA#EljDy7#orSpLiR?0Hx3 zbIWzjkqTUFie`N$s_4Zc+g+zp(5H1+lUF*&Pq11|<STj2KImr8k8kQ2&7TWld2k}L zI}Xt?It(eeu79N-oHC~DN3PzT$)1FzYCZCrZ!*z&EUJ_;Y63569PGP8JASmH;II4b zQwQIls;<5$BBN)CmFtt8skd0Wj3z;`bJD$OOY{ovA1H{@gB}cg6q`Li#&Wwm{7?CO z`fj6=7Hbs-9wGEB$c9?D#Ln4KKfwoAl5K!=<c)#TUr)lVc3^C^=*(sA0$EDB4rWG( z<u#7g_pkt_Bk;`22=g|cW0{7Ypu#|+Rb5pNCvZhNC(xt5lU9v+Dq}NJDa%kY3Lqle zF|)^ik1K_6IzDcax0zwwotWEd@v^NFw??%8KJw!z=93QV@Cwufi%yptfBk`@`(WPx z_6*o4WN8OpOGi7p<#FXX1pOvs%=otK(e<boshTKY2PJcIO{0zjYSXnl&)|G>2lG&! zC}3_szr`LslStNQ=5@S){xp%6><jf8OMK9|F1wopVn;sAg}F|Y8NNhkQ@hh+5}z%x zED$p|U*4|dSq*bSPtnjXsVLe?r_1O9Xcx7H%?`cFY3$AHY&1H%lg^!sI(ECI=x`FY zM0&Gt&;A^n1WH*>J@KY)5#Ce~XUGB!IwqQ!ae@%Dp9JrfZ=>M|#y8w%T<()d-!;FN zTU@&6=R|Z9YrJC_di%l~xK^g&6|~_M_*-JPR&QQQ{94u4u!~pGgQNXzlh7ml=$Wmz z+@c*7p6_Ppy$v<*0NSgkikN~z&KIWla#-I;3L{?<Gd}YnAvH;pKI~5%(2GQL<7CT- zBW;3&u8{cvN}+1_P57|TN?0!{<RD+=pqy)qc4gZZA8x)2!_45&8b0XVde{@v+7C0# zAckd|x~-v`?poDvg$BHYXC{al0Ig~K<Pz~M>In{$@bClFg7FUvy7my8)0BvQmi>X< zVpr8~=638lNO$=a|JuFRcP6T~5+3fr+0jpl=mp}3?@R9i;9{~FxBnulY6sran14QW zqCE#K!3J>0Ax7!*?;d_uIE9gaI^XUK<>618-9bHVOwcmNl-6^mSCo=Fx-<9|+sEfq z<+~h{^KKj~O>9R!-a$RaeOthwTYVeb9CM#%?;snvu63Y6ch^H+<|j9zlNCE6X)J<9 zjR|3KH1B<g(~rkEwC~G(o&}aqAKxFD`k>SMZV5k{QHS;|K#fv2AyX{ZS6KW+wjZ9j z6LSi^;E3*A*{^S4+)&`QiQ98D-#CIy<sM`CmK1NyznG1IKR#spS;iI%_Cq}-p}TO* zU*}ooiRg*DU+vg)AycWvY^kG@x!+D=?k%Do-eoEHT^s!f1^A%=z+<NRLvEUs<*_R> znL6=2*H%u)aUXRU$hKHFOcIiO!e?FgBLC7vt&>UM6|-Z&oLr!|O3dPMZ=wH?dv!wp zK=>`Uh{Xnp!UnlqZ<^h}SwiR4>T>HfZ}52MeV@!ZSFhV)VLB^MY$h-Husd&0^A9?B z1xp_HY`kJ+d*j2)!91%^4i7_r!yb=t(ObMMxxY^jUB#}}h5hU-oqNyMhEE>yis0S4 z*cyF>S?yhvEb-XYE0S7&jA|6UXY2kU_u`#652J+o3x3Y4*m<!^`)CJ$x4*{S#?+o6 zmHWVTsrJ^hi`TAIH_sB(5;W|727X-bxy#H3?BHEC5@nCOo4!?i#ZsZfsW3Nxe`Phw z{Wc6JRl8O+b#Xl!WBO3b3wy$6YABBg+Aik@0`rDWBBV<j^;nLTR;mF$oQ647cTCE% zasdp5_5%m0&LhI~Vg;hQccr-X+Kpg&YaoeI0U#BzaWuABUx^?ZBhgGK3~nN1FNBlh zdsOsX4Vx;ARX$5!^WkFwt~4Xul6)GCB&j)4%~D)?-BnUKxK;n17P(iE$IUeR1<d;| z-<gWeQmLnxGO%Dz<Rt#hcvU<37FqF-PtR59agu9c(@?IL_80eI_m>3d33bHlmh<MP zE_ip7lXBd%6zhXGGCd-9qpEauCm5TUtyASWmtJm_9ntfN9hxMAVkx;-g+n$puucYQ zHf~vEa3dg0^g`BorH(Rwk4Pn$dT;gv*>vN3y_+dah>)71_!h(<>(ydSC2bqmRW*l@ zH-lS8BtlMnOR=nW8p`^bz8mF`KkIEWbZIvCtC(=8QFNonXHE_0Sn18jHVMJ(<&BD+ zbKiO#lXjzwb=%7Ji9p=#=nPFbLh2N=ycjR1X)fQ^YU=eNO^^C;r)V9^^RbO;=$lU{ zwL%>hB`hWS#Ur_Y`rZ%r2F8|m9(va>ueoK}!>T2DT`Jc!xIMD{0=H^<7lyn7vbLa# zfWt$#Ca=OODXQtyp%b6-Q<k(`?Kq~@$843K-xhm|@nK2Nad7u4R$-z?Qm-N_y8YcA zyyPd@hqG^fQh_6)_`Cvj&pk&^ly_&HS-`({i>sVRlPm@87jmkO4(kMog*Xl2CQHWc zg5sV3EX|!g1HsqYjN}dluHK6Y)3XQY245Vn=0vPd-p!%h-i3WWx%a^Lz21cv(#p2q z&hY!Z|GxDq=I$}ut9+C{<be65Otlt|&8%(tHDSjvC#^Bb5{+u{)8dBDFdmG)cEs0E zC3Q7keW^IaEabv36?h?cE$tA>nHF_)(}RU$LGQ>Tnt@(e)`LSgS5oJC@{fSQxCRv| z%!Dt@DQPM})3J{~adZV1r7=LGUlH5k7wrz#jsHzf3dqeP?DR1|Bx7*bleY}-!gt|5 zk!$FuxP>^lvfLF+IObHq1x#$ap_=ywH{<0~cLE%ckh9?NTH%$7Y<ge=xh~$#OXF_1 zm}qD!p;8MsVH^FdoIB-#+x9k$CCnNcUu+g@Xe8LX7O^-iDJARNhbp!Nrd@_8^PaEG zJuR3XqYv#n;#do<f2l_G)OO{I?1(C{H4sZdcyVPy$|G?hr-8;ko-SXgFqj?buoWKp z{IQX2uk=XGjDck5Az`RwoRY|XLHyKLKSRaPrpHD<K6Cb-_6Ty=HPjHZI8w6}&YfAs zGBXYWzAqx=b~m+rN}XBfm(I#fH}*f3iIBa-hY(ZpEH%$RUcffPDrnPW6l~io*GYS$ zqk8Mnor@ONU7NtbbjF0Yskll>4y7i)2-SpbmVF)RX<D^8nb7UbJ?J_p=h(zzY2Awi zE%0;5hFc_@`)qNI0F{SNB}89X=N;YBlXHa`;zhYQlO1D^J60e0QD<0wxeg;oWFqCI z-sIMLFerPcb1>lvd+mU8_4#V{G(9tYzDr)l%HB>fwLaX(#4OR)(8YqwfBeNNc(2%4 zC{0=Kt6;L}(8HtFN^@CLGgcG*=lJ>AMcruE8xs4`-rZW()8504VBPoD@ka3$)?@^z zFG|6hDSmpaUap9Ma>{)XZ>hipJfD24l)D!1FsFNU9DeOuhJ1rr{td2DUbswY7t;3Y z^Wq|FX<&|TczSIroL!kgPV8#tb{K0v4X%wy?Xvss&(e7hfC6Ts@n-F<$|Yq-fwk;c z4L(p#FY9sp95JdQPPZpK<TcOC;^XgX!Gu&^f~2xCvOjE%t9~-l{5FBbwElS4b%?RW zQCN>{fGFMeW;DKjGU}w}Yu+JWnA9IWT(Rqu<P&`55jX9)&YBJs@i;&wRer&Pk6!E& z=0RF89a0}`Ew8a(v}Qj}??SmTG9P!#^7*iLgXuCuGU~HNNkQ7~d3a}RTJ`{5xoI=j z4g_QYgR&B<3u@YZ+-}!=eXWftijl>o1!rab;Y_tl+Mm%6R|eysl}Ox!u#KPYJ)Sdq zbu+HkhBJ2yQf}mjBxvw(Rxj^fbgtmgOF&LK%tpL_Nso7siRN3)2P^VRd)Z#1aBw^s zkW^+OnI-hGCxs4Jqi-XX-{2UEnSPk^K4nA4S><)eO}UrEcn8`?0#}HNg_$36YxdS~ zQuat)Pyxd97-+6(Us6U!;j*$wiO)EUt`RZE675udKZsjK(P!0d$G2<orB8!69Ss~B z5kV6<yirmdtLIN>7jptzN`P67%i_FZ9zkei7SKr{M%MBtXZIfuFG9Hy1dco;o*S!6 zOyhYQ`ABG2oqqE@oN!u<BYpC;Bx~=^nS^4_4OsACni5MYYG8toE5o=_sLV3J>BvtW zTgq+FnY^n%UnvJQN+|0hP68*MWm4LcB^};xu!FdIh~h^Rdr_Hj<ul_r&F9}@IVB$C z%MWDk4>YlkpR(TgU!?tcI8=Y&|Batn%`iAK_I>R88nQQI-;yoaw<ueMgru4oGaUPn z?AZxPh?1nShE%9TsSrXErPB6x&*%HQzt{J7UBBP`*Zu#wu5+F1oY!?;%k%Mgf@})J zk|>>S`<IIK7#);loyIy`cyk^Zgf4uy#H9vXc*$RqnkwAD3^Ts?{#kyH|8Cz;`yUcO ziqa4Xz4OyTZD1mHJ6sZ;hjnnL5$Xc0k2mCTnp*CEC5!wj(kh329U8j0QfG6?<@aP7 zb@w93XNUv{i;%@K6?-(%f~XdhZVM2fTzD_o#P5sWc3Kv`YluFO6_cqS_&oFXR;A6A zL;JM=9DJr}DGkC-oA|!xp)!&7DO$f}^Fp;++pD24gH(Uv@(kNtpFqY`;zOT3hP*V3 z3(2`Eh9NB=NJ>bXy%aqq_~!GzbqA!aaPP8lqeMSrD)4?rTg@9*=~6JG`<qV0084xs z!(EQCTtMJM;D(b38(XAhF(&%9;kKLdiAjMLSM;UYY&pZ!K#cH7h~>NnzxcdgeG_ZK zLhvr998jXkuu`OPz2c6w9<RlLS%dv2SYfYf=qo_^%F4GP(iN8mOg1r^Ln)>J(hwY! z0SC-MBnj#}fTUOvNxv{CLpEw?keeAO|M)&8AdvBltgDi*U^>x%pb9dmf=u@ihQt(^ zK$?!+(8mjXR09hu<Xx&o-|^^FQgKR{L7&SQba#!W>sfkuc}P7DVE_QmNQ&`VirzL{ zJP>ZgOflaz)(Al>xL}ZKqS;z#b6Z3}F$z|CKj1~baUenyge!nnCfn8-P`-a4gEPq- z{RtBknCk3Fb2g}U-55D5XQ~eX2O)$J#wHXAoW<E{>OOe>Vc<HH@4IoOD|4W1LHtA* zT_Z8Yc@L%e&1yfn;GR|^6u1jlXHjL?DGFhX*=CCAw)K2s*M1UPlqww6&u-tn_bmNk z)SxXz451&LqT)%*^+g2NLB;@Z#pF?;9m0{A>9Yw13U@-dRPXLbrE&)}gdz4Ww@NfE zmyQVLAISjh&p7g)b4>B^G?uS6SDJ@hn^6H_-99jsINjb(EJdfyz9lXteZi)6S3mzl z`fg^gNmZfJ9J8qNk>57Mkkx$7k#V?g>~70VbzzLw9!<V`TxQY+Xq=!Dt@G5Zt9v1` zr`5DWu8OFczllTzQ(+U!xN>C-pCU8j-l{f9qt3!Lm=n3U6rC#QF^>1xWJ&NSST_&t zhuEfk|CRnctJx1swejrQh&kLQ3J08N8BAI_i$-lcERIRhVmEyYr&N(l`yky67|w#6 zTH#CxVA1ufNR`_aK6}Uy`RKWJgtKt@aMaVl3@3m>TQ7$Lqi|_0xHt$0W}PxvhpTKK zJit6#>lX~_7Ko^}e7;;^)Qg(#M~OHvTINLm^ggqXfM<X-5f)6m_(=wU*s{dG8!Fku zaV*qvzi>&lSs0#x;qD@dTX_w0{m7PfRQMoL;c@!dhO_i<XP_8{7l6-Bz_Se|IbEj8 zO3?4)h&_ByZ46R@CF^TS@|vX#w69JSE_GuL<*U>zo!%#X6(klz`*M4eA`ttQRQb=( z<WYcnv?IVAmo`1(*hrLXw+T<O&zxnrE<N|QMVUnP90TPyf}FA;#=gkSIs?Un&#{)a z^oJJD=k_=<_NvlHsZ;|R6@u{>Q(?ojf8`jXddTF#k)S;Whu<^NE|=^*6!Qbad)9dl zi@e`2RYpREFSKqc(VtDcnDeA&5nswO;7W;bC1Gfz#VNgC(TU8Fi9z2DL5rB8r%PVm zc0XJ==X^8o=E1!woh~T+t<o3bOmH^0NH-)wqK2R-3Zu_5onNYVKNsJfE=$Z@bVQSq z1TVb6`Y)g^-bR@3F<eA3z6%V)HGJF?=m^C#zP@z-QlbH2k0@M4O}t1IBGGbJFh*T& zr_<dH?|HcP%=iEdvtgIXKUm{H6!A&7AB(Qh$T(T!xmc2R9-t(TrX?8AKq6HLdL@tu zBMQUyBry6fkK_a%4OR9!ZCH=JiokrYAiahB8X1JzoU9LxTIqE6D%Abk7%LDJUEEUi zc&==nBYBS_9;9)Rs9cFuwhmCN8wOzDW!<lmhiyqWM>ls+zH2jwrc1pSo;%N$t_S)0 z1v1Wspw13sER+~jaJs9$_?iSJc`eOaiDn%QyC+YjGO1#F?iGozOC3FZ+i32it}Rb6 z6R<a4O3j6zrgbsMKjj`>!}IyS()Q09q$TWSWVBJAzr?EB`kg8FUQSGLhds!Aft~0_ znRnBDgx?g_O8G4uNGkRGqBZdDTK1*cx%1H+6%PPGARq@buPW?Y)RpdqLHa>u{@1+T z9Z(qi=WUpX^k6ZzPQ938z1Y2)eeEI#%p(BMdSUh^eSeB!bra)Hq=$d<PYOnv9Y)=) z!Dt^?;MOP~Szx$(rr5AhYb(%%^qUK>QN}E~AEy4S1jcic@vK^wr(tnz4i!3D;Zy7} zGlB8bx>sF_@l+a*8-~^|rp(GTh<XIiu>!tmxjT-D%Pj`wgt^N*Fsv~2vd{iT8ETH0 z#dMm`JHI9E5fM3Qj^)Ys`#uYG%6HNW2OGVBAV<(A+nL+DSi<o<%A1MOR`_7nP_$6O zhz0;fkl|B|>Vr}E-a#7M&6{r-S1<Zz6npX@P#&HL$Hb!GuOAM-%TzDS_Ib-#527D7 zNWJ(3>)Y*{QN{2JOOY&rSUpgJc7raYcMJ+~8VNm*4Q;Vws8CW5YoWq=q<HEf=TU@D z+x6ciC@<ox{yav=$U=O+y7$8EV~M^VqpiL(C!G7sxlOC}Z4u$!sK7>y)hgysOoNy6 zQ?3z4=p9Bv9_nxnl&I0LIk?L6d^sJ^D<{7{6@QqqBI`)e(UHJd0DyNRV}Ce3q_x7G znc_fM4Xp^;Pt>oOqX|tBk0qXGD1QH#a|es7VBSps;7)AbLl!8>te$U>^6j2HnCMHO zeU#-q{`i`@XX3oZ?0af=)5RZaD@*+<SPxE-=K<T<PQmW06R0a&So}1D)Rr=#Eh9^- zZ9)S%{wS~F6#Z?LimmXKr3sbv*W1MvrRsIH{{_s}9}kzNhd)^s>Z=RtShrb&%OWUy z8yoi(2!D4L!8?j4IqNs7wJRGdI2De)EDpab2}Su|f8=+)G#lwS+U_w+FQ>Bohm=br zk&SX2x{VAkCFwup6O~~k<JFXZdQr@$m?(_~o9<;}S;pTa#;M1fbE`a?=Nhzj;7NZg z37l&C7ig*1+8F7y@_T*0FZ${-8kZ}V!h$`WU&n9F1%|uGAXNiV&l)~Z1L?ky7^4B> zSyfq-it<fF8e&d=7=hgV)r{K^#}*>)lZG+?`p3dAk_yt!f!Z=N(EAD~WCk<2MI$j= z0-v17j7H_4DMK<yO{NIYhMY<4JES!Ft8m*gejaS#IXi+0_Pm+R4E1P(I~L!}o=I=- zIbg<3-y@(Zm~GgTJGE6P|5+=4XugcX=ntaj7OGz#SvGZA$swVFeHfl>jt~tPfT&{z zilrOS8`+G#(=oqtTD%fd3_%~<Lr78z!$fO+UUG}cL&*(dd-+uNem7CWqW9$wW&C{l zQ1Q&puRN6SLz+{K)R7U)e`afHm5{CT;stvMc%%$IPM5mdrXQAqezlN}F|JBH0|<NQ zSDu+f1Ly9*@eQ>Jmrk0_9M4(!K-D@?S`k-vBI@x=tSi8f;-%|NuBVT7K7h7OyHi@@ z;&LnAIrIe@>6|HR^v!T~SzB@wXizUZy;UxZa%8f5B2oTgkdx=R2Mhhja=%wxny-A# zFtN@!7I?>r!dNd<|4hg@{W#^n<*u|(T-<*no+QWndSp9$B5rh_t@cDkZ$HV1M)|D4 zjc0#YaB!+=p&Zxf4plGu_BNO%3BC>LKE<&<iHt=5>ppj}#{fo1q5b{|AEv_zln+mQ zx$VK@Hg_~2#=$>7`=WoOLx@W8MEOfa$AHC}a@lMi&YX8hO@LzU35WG3R93z4u-&#{ zwppIcZc+Q1FZBT|MW|x7o8En>5{?F-pL7bt%@g%9;!Gv;lSTAxzc*Z-Qkb(GNum`S ze}fqgto6C2wbCzGNAJAD#Z+HgRJ)F9Erza7jJ<I;saGo@kIkvSPlEYJy{=){IB(nD z32&CYP!8z^->0c|$GAvg?)=0$7e@iJUAEhB^S}e63ET#ak9z}rct89-TCAQ~%ILJ} zsN=|hComiX;R+Z=&O@{%6D4r<bA{GgVlLgL5pKNJ{^p9-zCuFQ#H-}^qfxvUgv>rm zd$ygBt~aWUP6U)_x`8NXW-5QeryI}HgD8JJyY=k5>AGz+C)?WsKe-G*>$iXZm3JvS zdZT6zBmQXr*Z(v9x@NSwC+$@RBgZDgt}*FwTZ#%m*+O9K3)otLz-{6Ho%4U1dmH{g z&AlyQJ2E3#q6cF)*LGw_nKCx{YF_y-Re)Ps=hkWKFI7{NT}0!CH;&pfTP2T{q>L>z zxdFE6y+~GLgJW**S~{{Se=Otld>hPJPi3aX`)=&#jqj?nZNcPLZ>z@{0=_NabjXc- z+2-y>rw8`WL)Dd>Yv~!~bge6Oq%$)hO-?!g`F=b4mdgKX?j6lnbX(oXSP^q<)kiF3 zX(^6&10<~7?F@e92XdNZQ_pnQDix}nUDCv!<H~$b!ndu@e|}oItK5vMMv=P7%b~}H z{e}}{U7Ta2>b-Ox3B<M_RPDSi#~ezjIhdRTU$nvR-Hlhb&pd12tko!iQD!(d_R3ZK zFsRQe;jZ$2iTE)Yr>oaz&u=OJujbyy;^^3$!B(Oz^BgYm(s={+LXIK&oRF}{IeajB zMTp&nEWSs~RPWi7$-0kcj63;v?$~<Os_**R*4A043mg-NQ*wp;YSI;IlY{ZpuHg}z z4755y_UcjZ^YVq_*J1;F`8)Do$Lvo_$a&k5)%DT@4pD6jJRkvnNZcQ}G+N;G`n+Pr z`GLf76}tP*i0pOZD=C1Cx1UzJ(c4}rQ04n|Ov&@AEhu*tU1K8<--sc}BqjY;Zmf3w zVdrl(e{PW+C1~{87l?BimKCWUIRO>8lSjqQs9_5;(uRJZuczUZRoaI|FGSg1@6NB3 z$gMITS8S#U%edru$4s^gf99;Iq?&xS7DKDgr7MVX7v#zLd$y0Zal&Y7y*uNP1R3DP zFR{)>YKJZUY|A;k^mngaJ4GA6=`rOnDoqAJA*$^9Z3`n^P6?^!kIKA+X@y9qB;r^^ zjt9n?WAbIb_>qTJ_RA{!XVu7~M=V2C^9Dr?ld%esE%->u<La?7*H5`ir%8Sn-PHyt zS;;!j4;yFu*Hwwfe(Kaa()ns!Kp;v_C7xx(6pA;&dB~*WZafk#5p>0jN^8F504|uA z9(;SwINtse-6Vh6LodN~TRziMn*&;eYmE&Blw8Be#E<SM%1DTH?n=c-#ihM1iQKB0 z{`Bu+x@5|?y|y7auWMuP>1sh7(j_6+u$EUlJ*K6<f9+2bils+6uK@0S9P>b6pW)81 zYUA$KL%(2tm2j5P($|1+S3AWaYODruw!rw0`E1z>ZJDEqF_;1j>dfT!$c=}WLRddz z`e-X=12#u0LtMw8eLsmN_t$ijtQw(_c<_tWaM+a(7Sdo4Lxsr;esLR>TpsDex;mdN zAr9Y=#HZVb(eyBOzV14(_Jgc(Wz?0!#5+QQcO-6tw?vUrl6!p%c5O8M-s*PDUXdd> zz%^s&`d=^H*nT^Nr-X8i+*{RePjn$3$0M<?h#VY!M@|pc4wBoTLG@U?Lsy=}Puz66 zqgFp>ZX!}X|EoYF>**0=1nZwK0#FpK3l0=P5^FGO-HX+!;CWjigt9FMcG(vmBY}lo z#X2<ZsM<so3&a-+8}MvL=fH-fmUb0^?H!(V3tMrt^0<pm7~u*;58%0t{uD<eIO1xL zNlK^f7uhXA@s^`<wYviK|HvngdRj>Rpm3NlJBml5Ko$I;rGi!vA-9drb1&F_&QKGi zw#gIZzonh}5v28SvsO@%R(3r9c6ly2OI~NOR|8o?DBR0cen2<^5Ea~x7g&-{moP6} zWRw9+gk)hL!z^*S9BmqQn!uOt)esa9k#VOwgYBV#5w0^Bx;&=FC3X9o>K8Eu#T(A3 z;0(TM1=Dal{T0lhnilBP#4jf)nhu>{=y%0fDi%AV?9~ReQ0cZd{j__=o<Z14NRpCE z^Nae@<!f@{<#IYkV*)Y5ghI-5!hoByjV-PD-n|rFZbDj}PFKr`&$j2kw$U|6`!#N= zzeSFztSH#IKPpwGMV^7|(mKxvaofs&@<OP3R>fY$T1{FI3ECB3qasvQVlCx}+7-4f zFEz34QK8$Qy;>`o>!GEJH~@_H=f}65@S)50&hXu8fVz}JTV#V}Irt^Q@YF_MF|C=V z`NV#%r4)p?wa@EC&UpM~&rbzBQ%%bM)Ea$bEEU-0=7v{41_xhAnT<CtX&(vV_Gi%o z7!LD0HM<}-&eG+iSWCA25XI-$Tw<@PzSFtpC=or|UrGl&rYeHC&G+QRge~5|%Fdp` z$^{8bvkU}f*yh?P4Ug1ij068mp7_zVVICbh!%o$M6yHz*q~iiUcl!8#iq;uvo*fQx ztwr!Y-wfHan8|aYE-Lg-N!$2pSBrN|AFjHc{fnW?Yo+4k%yfi|g+5sFpW}|V4g4zi zHC0|X#Dp}$wm98~<h6qENrAp8(u9>!$6*zZCK?EYhsfP7$)u6kpZmB0S&lcH8*eV8 zn;e?0I~(a=Y>^UFE=l6-=CpJg6?)yWhK193qd+)ci0?h6vP5YsCc->qK2KV&o72N! zXxe}ffrM3YIvF5@0Wj6-c4^{ZvJ~-$GhL=-k((wwcVFe;29z}?%YbSmkS>s)4f2%? zUnT_8LR*~e=L+)dA`{+jgd3kKrh!9D^`uh(^M&6KdLNJif=&k9X7a)h)2I91GEZsL zB?R|B5qav2)-<T*^u<^-*B}0Tv8*MRrqy|=)pX+h*k>wNjHcujh0{!a8NAyaybLm? zlie!0kS{VQJPx8QF8tt{eg}VOA$iMSmkjo;bPzESpqb22?pDqYdH&{dHipI<$)XDA zs&^C}99m-H*<CRJI_qo@mMuA+UhGOW-tE87<WbnBV_k=%zVV*91Lujjc*?&6^S(jf z2<T?+wtvL7#m(Ljigrfsey*;{woCXJ)i+aeTWKoz)&PH&Mm+P%gD(jg2#I+jU4Hlb zrYCaKv-$LQbKPIuI$8L4pSXd(KM%fYmX2HOFGT;4Utn?hVdO;>+zit{oW6MgSMls^ z?Uyz&@2}`7xS*Qm1r9&dwu5l5z$7KH&VKd10~673NVLCE>ZR$0M+1a%Eyk;7eZRPa z5#q^v?+xhs(tlR|Z9SOgm|rZp;wDt_#)qD)=qw`rIH7Oz7>hREA}Jk092A+|_Up0; z=tRRbfNjm0&6A<UiB%S3Z{G#FyGZ?-+83xyilPdNBLxGgpaEG>c<5Jk<w_o4F-qY! zNS&2Nj)ayAMUioF{(zSi#me&gDTZSGf@IwjZvpqa_aL~8<>nI#=)AD`Acd@EVcy9K zkt=;9VmWe=%06)Im9V6R%rM8O0T=hDGo9a&!>HhkD(>HJO(qcLy%yrhB#ePIP6sJW zhY2l^a1ieZj5K+TnkV9QG|SDroM=bq6C7UjSEpX0PoD^~+Z3VWZKVN67(c+0a*}>{ zw3@t|V!W^*Ho-y*5B<(&2pUv3pMnX}0|iJmB4|I64(VgQQszU_z+a(ghFisC6~AK@ zQ9(lb$Dr|F#6ddTMJ@O^MSL^{CTIZTSs)2m`qWU#%_4N+g6a+!MIp&5L0Uip@CE#& z_K#w@&8hsrlCpP&@%(@RK;bh%kIKJShm&f^HIKe8$^Wh)<BlJTD-vuImH-MR-i`53 zF7R2(3V1J?^bVSU`vZpE7T`sOAgcnLV5!H#gw%-ES!7S(l_*4gon0tK7h1hKch!K( zH^IV@`i=F;1eWad(IA1PL6c|;*-2TzM3(K>@NgtcI+1boDlocV(6Wl`S!3z@!NWjK ze5fD%QTU%SJ@F`(pG37p%UI`2NdK2&TyCLMo+9uRXAwfQ2ISddH_L|Qg;1&koI;Yc z6w<fGmWu3Fi!2_t>R7ZpB1*+iQ1H4`0y1>v$p@2NbJ;9}v8S}<B*j`6Mzp8$Gehmo z<phhDf2~wo&--|^l!#5dCv-1fCz1I~`uPe%y&CGhe@mD}FPr?eP|<}S6sBw0BK>46 zLAiZ8UL1McjLc^nVsF2|4=uZu23to}*|n4$t-A)cz@i9T;r1b3aF&(ziT9_L4^1G9 z>E^QK2w)<m^VFi{9)%a#kC&qo*kUSS80QelYlLNK-*0SQd#1Nim<barC-Z0IYUTIi zQ#rkj8hGXU@!PB3PZ2g9DK_tD0#0x-CJ@^S*h$iH;z$ta$BV-_djZZW5@`D|P84>$ zA(U@c-n{WdC<GH8dh>ZIs24^$m70OCtG9eg;z9O<ZP!=ALj)8o*zL{&>^{OO0F?}I zbpkjR1vd(CYpqcFSlqZZ$|~R`YU%AS=M4u^evAkuF7Pj~2x0ThuzkNt5eLEqi`yU^ z1Yp220JW|d@1{t1SjhVJtM9@OwvjPR7DwY6B}W;kVinf_z^)>gtN`F(1YsD#mhNVh z`snkL;Czix=lgcnI=+{3rH@kZj&#-IT}X#Kz#l3LunzqlRG%Orn98Us5~i0@FG|mP z2UN=p;U}6bk?Y4;atAr3c>>7-bZY00a(nXHmDg+BTA|fO@7Y@m|6>oGA2hBTz_lpV z_mM7%TAq}l7t}lw<o_f@@Bhp#*<9#&`8TEByO|pq*<$qm&;k+Ag|i2;LN6;rM}}7g zg2z`28jx`qYV*@fZqJPdryIl{7UmO(X02dZjeSV&T}@-5BV~X^o>0C2<HngVGO{P+ zkOq0vE4bTCW<at9-m`kG7r=R{Jp6rQ^Y96?WebaLgn6=R+t$a^mVt<^<A<!P$;eGB z-_Q!r4bCb6yZx!hzGc&E^N=r+J36Y<b;QhCUTUObEO-chf=coT%|xnVog*-vtXn-T z-oY(N&Y_1!C|tII=0Jm$8Z0sxTiOT2t^%s8L9(aXw9}%ADDozp#Sz7R4eS=r#y%N( zXY4R?#2@FV$it*RI*~rb^BL9Bi2s{;pRn|5E7dnA-+F0KML&W#LE<G2^^Sxc`&(^m zCd-ct<JXY#pW)_eBVm$RB}r86zx(RZo;M7+R}6J&>dP=e;zx2=i$}<HN&D+u!Z6Dp zA=iw!?M?%z1wh)p_TyItX^*JT|5AK@46sj2I`x-cTMy^j%W-zI*n=||Uc*OG8594q zWNj|GOY@~|Z4J~y@waOA&2`EL)ogEW(CFnS*2uUu+z=3Mc9Pk#HLpw6niw>o!;LAe z?@w#~<k_nBSPjh?G%QCbb%)!<MNpf+;FPF-TMg!<6VEN-t^*dbx^Uy}lnbl3{-fRW zjsIfpdcx-&T<<ADue<+lK5NR`a_Pr)@-hq8cm~{TxGqU2$icV|wDr<is3?G|je3Cp zqlvGA>v*m8iD>7Huo%&O%g{cAY5X!W7ZH5|BMT>SHEz8|M|N%iU<k2_XN@~q2}oW| z(tonj8n8MJ2x$$PcB^jFZlT;(L!1=wM<N9@b`E7}oEQ&XDL7Spr!li{?NY275Z6HA z45R3Taz^Ih7EY_gH5H`}xb!HRE?J1neim2N{^z81aACpl1zfn3g#uWpswSmc7JKA# zPc$mml9Xxz^h}ib9`IHUVT`#Ysym>rt8HriRqjHoHEntA>wxwoT$6nm7S&XjzmD3A zknLdAxAOADMu(nWCc9U^+R~Btkv7$D)<38MOhjl-P{9xll=u+#8<BW}S59?@fB*{b z+`jMq?S00ZHL*d287oEp*`V=znz%45HsZ9oWz<gZj@aM<vL;eo47oNEWdU^dHu{hc z>3WEN=?!^e<r$@Cp=*7z)B23AO+u&5WnJ5}PTO2vyP{6JN?rTwo%XkM9qx8IJk)i3 z)am$4_wcLE!|!#SK6W~N(LM6B^T@ugGe?&*ubzugmy491t74a{rk>luF1JH^?lxWS zNA!*!>pB{s=W(*j<BZ<1gsx+k^*qzMJahHDin`d`g7@_<?^}94ce{KZ>iItE@_nY~ z_o~b9y`KNaF8?p*ZX8t$P(3FQ98LoMk4%(3z54&d`v(8N<9(9||6jbX+|>W!eFa<p zZ{FA8GSv9LdEb}LTB>9&zW>ep9uoS$d0&C=8%J%0|HmZ6_XP!`v@fwuLJk$B)D#vD zP&>jl3Elo!!~v%M=lDM|Q4tX};cijZ#!Tb!|6iHtm!nlxi(!jlc%o8Huc6-(N(@tA zc9Hn~(@R+3tBQ;Fe{L<@%iP~LGc)=1ZS{FkKyJl@-#@nBKTbGu`F<=gaqZKQH-H6- zD;g$zjDq9|tD;~8ix;Sz`lAaeT-Iw<bkHd*h#|~r(4Q(EzqXhr{$GMLLoO#QIF-|b z2*CezVFY71TV?=X;!N0wY=hOt4>=}3);{D2Q;5q<OF=g3D?GXPA>VPslZ@g4n7}0s zkFl2p2b{K-3w`6)SBe5tl~;>H3d2`R!ZHl09EfayQWo8(e6svBr#k{I*3k5^BHW1u zM0%i&1Y)qGVPw={h32)ItfW1uqC+wpRIIFf#Cm=42_ti?z0B*i>xQwvKEmBNBO=`B zP6<ktEq69HZUjW^8&Z)d+rY?*i%v-ct%_NbpKkU2?ul$Gs91nicn>s3RUWZEzj50| zq-V49g~y*2UZBclke5K*xLFbjcZT0uF1%olRoE<TElWrZ`+VR3H}-R{qk14KtAf`2 zrLWRV<d_5i;7DlQ)y&$u^-`Z!tUM5CKJWm}mY?29di-U$+w9lJ%H8<Cd~wYKs$WMh zOgB?S^uY4Xl11~DZ7lA>(pcG`eU{pooXtG|CS)+k2UCK5Za+C`m$@@#`=vY7myezK zLBACh-zWv|JD$d#?vp)TuLw+@p0<_kX+L}!tYe6A<mpTb3tcs33R={j(CiC*b?Rpt z0SZKms;2F8DwloeGil+dC=MDiC=_*QM|Qk>qEuwWH#B^tWayOq=ugRwy;b2qK2+o( z;@R7|m~Rn!x6UNF4#N6+*H_!6V_VmzYrRh!JJp@g=-TYn{B7uR$mCu`ZhnU9-U3jJ zr@$(Rr_XLa(8T`oWm}$D%h-0<o6l^wPTcN-;%`H|h1KEShdq+-zhf%?YO%-YL~r=@ zMF&mIM+d40{!J1i@2WfnaKt(-twIlmYBWs@Rt9KMeqy=fFZz^rgmks^$=`@iHGKLX zPF5Y31fJ~35WT^JInZCv!@Yf+2ryxQ{7sy{NUh+1UvKw|R>;BXzgAv1W6MNosuxRp z_!svJip&K{sWB2X_YN~;tI)gA0L`pdgaGJ}nD>s{zd^Q)Z**AGi-ZUqq6j~-wbr(0 z@wp3ANa8G%%36>l5GY#opO8W~=9Xg|@`}W>-G?gvJGnArOCO`GM$JXPG9kx08KJRJ zYoo7u%&a;&K0_+p7tXlcO(B)y(~W#-n7c{KE#`)H_NlQ2S+epfT<K&|4?#}Ln-v+t z){i!?7Isa@Ys8c|cyGnRn%C>qsdkP*gl|P7mJQmuUXDTk=@j>bDCid19S($3U@&2% z*!*_x0f2%_6NX?Th7<mTp`zC6&}vSdC%yz^>2vX`YAE<KZyk!&zYFzdhO~W)6(yU( zacUkZX!*!xp13NMX(NeC)R{p@tA6aFWGR;946(hUxO0tGnnqJOPW)vd&{K9wLsw8< zE)7L>AxA687w`<#BkncY3s5Wyx4t#ViG-aAQv$O^-C>ts50YCH!Q3SdqhGqV>Y3xt zsRnTs>md>3NKUtM@2i?{(`Ngi0XN#HZec_niSw#9h~~GcK6dyM`gX*Xx(3}sF5yNs z4xqC&HT7o1lTZJ7xV<bX7;n%##obgl#6pk+0Q<=s!2xqGTRWEdDXz_v!JRMf8^yO5 zcg?HN;BI<w$|>!aRjvmdUUMr50#S`)!VOw^$4Kx_6y7`hq}W}#{lG!)i;Y;ZSXI1t zTn+IesB$Xp!hM9VzI?4Pq)LFlNy8L%Ps(RUadc2~kt9785msc)W54Ovh8tz4upzK2 zeJUs*%T;BW@TyFB@DfT0vEEO*6v;f|PJ6I7{N)GE96kUip?`6=Q50of!^HMj7^gOx z(El^<TO1~Z&XF@9yvq=W$-eL$gSd3w(Q$C)v6WF(1Dy;m919lq$!^6w`Rb0xapLw% zP6Vef!OP^Xg5{;rOq6+sLKs~z0ff|KIszo$r@}5-j>d?XQ&bMf0sbCXx&Ku0a^-x0 zp~rZ!7+iNz^4`9zo!MEJ!pP7Yvw=jnJ}6lkj-&=6l%fqrg+SNf%FaD$ry1MyFStCx zN8L|5?LL#{^_k$djC`EZ;CJWzRU#trQCu6;Aa71H5nAD?t<bfp!LdD5Aw!5giaPP8 z*x}fa$0$Sik8#mRVH3Hh7?E9agK^#|%E}YnSqy@3_)`w-kK8k!F(CRHQ?M~XMXNrZ z?S?<q8kq2AVZ`q4al(llasBx<r@K9`o@~Y6|MPY`=Wg#uwoLTRpLcst|Bp=cf0=}~ zX<~mDFh{xvgic>E+b&!LZ;h47I_(TP_bdr>j1L}o8gtFJ_XF`2mT2x2o0{b-@31e4 zAp$!)`3cFO;*s<A9$T>&j+kg)097Q+PcaRMa!=qpC!VBz+Rj$32N{WD67iS7N?FTk z3wF@@&*ay7ahY=Yn6fDt(YM0pBJ1eEi7`cqcxvLmPkZWrLSDRMl4||hFYg&VDanT{ znU<^AxxpEUrQN$9&us#%3jy02-<m&`6Vnc2p8eVS+1X&So=WW{1H6=Wj)Oa>dx#sT zfxVIUr@u7jB`=7<e=D8oTd(*zJFFZ~mUp{?cv<P+`qhsA<<M$+wf$25(2u;!y(@+f z&u^Vl+?x%2@Refw>l3x?d_zkh3NE4y{MJt9l7-_JleL#Qs*_X2{Ts`^B=3KBxRjg* z^hNcCe%~CH;!kkC{Fk?{kIW;TM9nhYnh+Y5)YW9p4IcV%t_ZX}mJE-Hu{sDQ0GCd^ z0^7c$27X-rcOn6ScUpOLv9{>)K>hhMf*d9s92e8{PZHx$+USqNgj_V$u|4^rG!+?h z4jn{oRsenO#{Ku`JdZXybkbKzSY*tGa<3hOgV7OG3=o|>pFn4Y#%;U;NjBg~W{UBs z$jV1C^EC__MrWhsmJn!W3%bO|qhK7TIRF_Yut|`ybAkZ`GIFX?k<wHjPdc(aWd2|R zj$O#P5Jz1-d)yNYg;I0185n7LSNjQEKMh+=LsXx=em60BA3D)!1)jt}>3Ixwa|l6Y ze7hdo`U*_+1d}ivL<8`$ZF+t?CUY_s9R%5t1K>N@$~HbW6AVxwzC`NNt~li4Iclo@ z;jj!SDB+G0NLoupk+H94_-mtSTKyTy{g*kUQ!iq&((x2bbq2gYLp7fN@u*O5{n<vF z?6T_AJZ846J~j`)Zd}C{ftf{2>{ugzomTF-_RD~C%960i?M4sYqO+65X{LGJ-9@>2 z<eUrrS>B7$kYX}&4(vk%SssEBVOdXSnb{|^0OuTFo6?>L7LmaE1-{*|JTNuyi~*SD z0hY2kqPF7_%J^Ile+BK_>&$$(%a!H*6#+9$lH7TrsIYtv7wk?Lcx@qrFV9z}gurBQ z{<Z+s3kyu`d}c?%SAv-((N{yMoO<b3Tnv2#&gY<Aa2rRls^<y%c7z+u!m{B4bbq1W znBQ?MP%xRttoJY4&Qrqz)+PAsz*RP{3!f@DGv+6I=Qu}Du~a{MWei*=7SqlXTEUVO z<v`i^fJ$rZl|T?`!fIj(xxWZ`_k1aaB_;CM0<GXr5csMAt9q|Uw4XEaM~SX<DZ{!n zqAOdU%yq{uGExECpj^aC=VOaSJyy#$tgt`z3Un63WwnnFi3ApggP~Zy1ugLQcDYn) zDVAES(a+fklp(5%f&FdHh4c7Z?6n}}+SIvnoc6VY+FZBWI9Jl~9f1)W>28Cw;MBe2 zTWmF}9X`$)&x)@6w32eCJGb8sEQt>IHwP+Wy!6HjBbAHuu|QWk2s5g9I#%2Rl&z=Z z2kolnQxakl8E)awpRsF5Y7r8~xjz^D`${40d^G{a<)&YW2&xsr*NE*@%lsDmo&YvB zW~V8Gp<`?iB(qHkyf2t(d%iHD$roJY6jK3@dRLl7fF`1RKYrDA=f$P9F@BX~%o&^* zHw3v$>&Av_+5^FCJFpB@EMi{^C)cBPIK?6=-R^izlK48?>Qnof{^NLg`>aS?P*w06 z4>=%n-wxC{U&zNk=!pQ=&Vy}QTo+$Ae5+xmWDts>(s3`t@bM6Km#*#kE30;3qCNQC ztCBmf;vy%|MdW&=tQ7UC>7QaFTpJUZl#Oc7&PW17y$T{;7a@1*uzA(O&CNWpMkI`@ ziv+f4MQW072B+N+$%|tw(Bf?%()scXZ|uBbi-gE=UQWRKUO`?@wV6?<mr5uvwRX1o zh{h;*+93GqTt$*yKzpOU>|7y7bql(^`pWBiV4>MN1N4h%`_@Aa^3G&LfZfX1kk#0S zFH7pYuT#@o$1*@<SuL`<4CesOc!S%amG_z89p?@>EI=(%)N=G9`E?sIC@yZ_6TB0~ zcx_N{b@H~#dWNF#@l3<x?Zj%=aqtRf2e5seBNLo4itJ{UBZ9cPiR>rg$!ha`^{azL zzI?#pc2CA_WKb5LPkW^YNb&)7*30ErIpfA#;5)7G#TKBggGagxiRa1!czo_l1vuPR zId&e6Z+CAhId2ErXMk*Lm-F165BFL;IPt!3I$R%jy%5F0cevEKx}Qy7$QMfcmEM?X z1g?$;>x?uzMS}77?<r*Bdsz2qH5VU5fH~Vufb$*96t*(Dx&Ak}(!~k)sm4w<qpHh# z3?nt~_e5xSkjdR`kMR%fKr`cjTf)cp?b*z4aSO9E+NT%Q-*IK13+M*>c9(inI8!<L zZ~S0Sq3uDTKb4O9xpQI_h#Pnf)xM=0z0V$-#%=rF8&0~+RiNe7le1BXh4tn+G^se; zT)sfK&+L%h=}El*Fr1o;qMoC_DFb)<3`_KRrW$V;;b)Bcxyb{Duzvo(LQ+5PB3$yU zRKV7``yc9C1--*&nh)Jt;Jlgy%HAlOm}4ny;)@#a%71#4vxEf=?*CfPnwq=a-+brv zc)QAl>&G%qa!vH$f`)8%Sn&Q~8%Lp}G_dAimS|M>$ucmvS^wK(u!DHl?Jwv(!QZ>h zQu;d_Ukzbg?kqLeB&E0OgtPEFoTugqF;S2Hq*QThH{ahE8%DbXAC15gsJ#-f{&P{I z=Ysm3sbxz^V7Tg)OLlllM(_6bLB60Ne-na5)Y$LpYl!|wn%IZD+Q+}z-)(ur@=^nv z#0gm-&s6jHlf{8!hSyZ*@-oZ8!^&+jWfi!`wayMh-8kUhU;G#m9ChY;2tMiS71M~S z3v=jkYi{w%m~h|<5vt}|E$>(>CrFn(c_7Vxwnx_3$H=_u$LA_MlEJ~Ta&i{PzyZpc zPo!bE$!Of>yx5zTd{qDaEG(ZwFIVsO<bN%M-UY6OHf#?O*IRWDGs7)%H+bs8ox$d! zN8`bisA`V>2OL3Moq>=4m4m=F!XopY=o5kU{q$*+AK_JM7DoFTXLfU?aw!U5_3>A= zT_%@L#AA+_@T)C^1OITo{T*9L&sFiwC%A@{u-C`yTQ<GHA9E8fd5`<Hxr%QH{J?S< z{_S>sLYSJvmN(t0oCg=wLOY#rz^N~;=bt=(;(7RI{HP&#q`Zz0Q|<G%KF;qIw*8sG zBG++s@Hrru`1ZjCZbIR`Dh`(kc+i7cRZvLf1+ZP+fUb1o0vOrD)UVfPj5?OY=j0b} zjg*52QY*$=dXPIkonTjVFaH2ZVDWKp^MiDD2!Pk6;8Ire(1VequUj1+ce$m`TH$d6 z3kQ&k^Y{D&u5;hI_IV`yVyxobo1%FQ#rsc+&os|*_rK{-Cun997M*b=7X;!R9zS@( zxcv$I<Mk4eSFmy}tUvR*w8>rbzhDz?^1vy=fYw`Jauy&hxWEFo{=HM5W#FjAYOniw z+r6YXxnRFrA4R^x<~;@5XEkDQNN!*RTta9sc~mdrG}8F-Ef>bJm{zss58lgtngDmW zV14fn;GY8|4;Pn?i3cfPUh!=h(}i3LD_O6PaW}bc%*{M`f2bADdu>YR-=g$8BR~r` z!@|k@_W}WH)OpIcSd^6Li@&b&O!8B?<GYo;OaiFRhdhNtRbv9EOJ>x*Y{eu9>;c=e zRs@cJ=o$gqd}AHng$Jz!wl8S!_tSP?fj^+rQouz&>3L-N9Kxk6PVmjUGCs*mqH1Cx zajgV`5|r6^Ss#i&?u6g{KBoN|JaD3I#NjoX-BnPvA{_JqPhHR^FPY$11Q%N{7YN;U z5QGEnZqN}h#_W3eQSsOAk+U)}AK=;xjXTrZFQ-**vhxEEfIz6RJDu#k86q6V4w!=< z7YI``*s0>Up5|G<yS#ZFlV<oyr-d>NFxrXlP^ws;9r!1Vjw%K-*+L->z!`%!?jC)` z^~ycsSz0zY;q}PjAGo6de(zf`apGHw{$i{B$SkJxZw_ebiE%)09ri?rlD1wZwC{+G zJ`sIgkvjYFCO&$<6*peBqYHa`*yXbUwfs*-wxS(qm#~474nJZ`<3F+LmbW3W^O^_W zhd%^%IqwKcvoHGwCx3I>SyqZU)%}=;e;of@I8HH_wlWSD=JXuCaF@H1;CY6xJW#Om zDSk}3Zap(|(Evnf;#~s+r2%%LToC&O?9HB4zbRNw<UyYLPR<)Ya;Ps=;wN6a`Lhqm z$_BHJrJ{53X3Q8nY_;p(JK{0pV$@IFm%bb3aU)`Ou<r=M4&dn84p9@7IfB0kZDOfx zMb4iK0pJNiWSLY<Eh#tRY+;k>*rfQ)i8ky))jd}!y#ATrVD)cRJkRrT{@JKEIy*zD zVOjF~5nF&V7<2~o(E?jn!M=c)OW39)i4LsG9%gFRwE`a!ikp59n)Kl`sQX?=_%e*z zfkh09L`%a+S{7?L4d`GwB4QHT#z=Bxng7lEnqESRxGvk~%OB1#xjHFe>w}C5oktNB z`n{1wCGLW*a~<WFGZlZ=HWi&~qyu8>j`CMG*dvu);KXpETviG@h<IQd2WaD^Pa}1h zsjeNNPb#d+JZ_F2;c=1nEdghS3wd%S%S*IoSq~!dKe7y7v>X7&{<f}M{n<9sfK;`6 z>1kUhmg@zYi!>rxdD7%$HME5HZrHSyoqV!`mPY?EVD(aOW&-gRG_Y?E--0ew1x}6T z<259FmECgF4c`44Wh@BN3fsXU6FiVFJ#aJNQH8{=3NR1r&Uhob_$lu|IPc&3Yj@Xz zUz4|tG+k%B8}ULSLRb!p*g+rI-XYt2X@q=uwJds?y@5M_ysdv&>+E)olZFxM>I<3q zQQ<2yZ`5_e8)DD~xUteNEsi|-^k({&TSQi?ZYhoU1hkK~6gwlno{o_|8#Zvn8n&QI zqdO|syu{dZ%K7mRHeQWRY#P3kMc1~r;C{@x({?<1`D>jyn%u~n3;1f(2;<F{*qQo} z+lSLTeB`QsV~kw*4x>dG{6t>+^#NISx3G+F&h)T+ZgL)aUmSSR)TEi+I=|NN-GKjd z3DrC1fLj)5xcnIULDHx_APQgLS}7jH49Mw*cD+og5Np4J<um$hp5~9|rI4Q3=ZZK1 z(F&$H#D9?Mr%@M6aqt>!>Zk_?%&ksmMA(*;7HsmZ>gZtel-HTA6!Q#t5aXzUy{JQ& z2c5oo+Qc)^i@T6?#j(+uUOcf@^q@v0sxkCZ>}m;xW9gVd2zuI5oT{$A=aZ)SdLyfq z1q{B1hAx^L0nLcOw6sHaT3Mgmk%3P17u@;JWUya(s(nM}UTUDTO>HfiXX3wcWm`Ut zGAh5Up)7T!t!=Z-K-OF+2-qr*E-?8eK01@KWCiWNO9{46>PsFgjT0&3_$|6N96a!| z?$FfI?&BNaYXo3KTx|@aRZQl|w0{}#scK3@Ryozb89)0B>Wx%4No#pJ>Yqc;hCFlP z?kjD6x-;bR=>ms}nB2DY0j1YW+u>2eH6DAuGtXb;i|N|9(=7>cWkxaU=QvbiuO8KZ z6n4yKBfq3-LL!!*5_jon8c{`>cQYWn!O&0r@sojzy3h6j%5SRqIi(xa@iqICxgMv? z{(5*JNyL1=1htyyvnZnc)>BE_chul`+ZbBK`^E<95WaBSR)SOP+t9Jn_u(77!J?yY z2<9az>_WxZ$1{NZn!?`#UO;XTQb<PDnO>vqU&QwdoaZs;Y8kUuP~08$uiF*Mv*nR{ zQ5=Xfp4RXF#~~X)hDJiVEyUJ8(-3y07DyZLXHbazEwb+e3IX>9St}a&4RhL8iM0X) zQh`JnUcG_t3j)rvGRp)69~}Lqo>N-<d9bL6<yGQ{hO~txBcX<aa;$sFuLll1NK6C& zRD+lCSV=*SSgUM|b?o!1U`tH+aEiNZX2f4e=z#g5pMhV9xCzcRQb)6_Co;cM{BU{W zbkEuF5a?o$ZRF?`%Ph6^OH$ZW&SMyWTLN(&YZziDh_#<wwl|1;1N}fRk+Qb4iXP$Q z$y&2_uLM~}@Z?FU-ikN$`-_)t-^VSJbI1pP=mWA7DT}fqhE5@Ugp>JWqvq%Vsn0Md z3uqJMk%jlg&U{ldQ=21iAt~Gqn=<Og5a#9`n>5>4`=hatCW$s`DH&3<993t^7krqu z>mpka!i3|^MS@~catHFmY%^)kM&v&89jbXr@{X6=lea3BM*>#2ut3nnSK_;t5}Ss0 zhX|7?QDCph_INXY@jYuj?v6Sm*yI$IQtd6$Bu1uei_ls~jmKV&PSwez8y*d=G!u38 ze8VW9g1R!R*z|%3QDHv?WH}zM=%H7`mAU$~ks-@%#AiO3qNFGNHbs%Vyv~#p$4IL& zBZH68nZJ?k>VUA!zA|0zQLO@9a91TrDzp?IEOOi-eQ4cE)QEZQgmyU%7q0&}zu?!z zaMA0<Nb}KU0RVa`{eq0a@!$8!-aJbb<DU<AYM;&=nqaSXDj(<@%RkH#>>|JY9D8Wm z+sJ5*r_lF0H;kP<<$;JYnGx$rET6Bza(sVYERbgp&V88`umdRTUJk)-o!k69G3uIj zo{{eVdFV+0#>?7tpimN12kxo^EOh5~?qB^xBIQby`MZ<Hig=Kb=T@wOt%J)dgi{WV zRh8Q`PC2hG{;Y1whT;z9553}il+^w}&b+a{fY%`LZV4nYKJ&&*7GKv`^rV*Y%fLmz zcu4p^G0bxQzH}4R4N7Yzukr0f9{<-@boh6Py1DaFADShT7}lb4_4B=n+!v>bmpf`( zmC`dm1fLc{4?`aa5rmH!=euCsIb;BEq_cz6(cp(h^wI<M>sxma)y>z=fAXQ>v?GXF zQj!O0T?YrxYl*F|U*UlJ<vV&!4NR$49+X+5NBw%fA^?&0W*kS&vSn?CFlCzX%7ZsT zMIVjUH}K_$n<xE#q1fLT0K$L=1muWtI7S=hy!OR>?G;Z2v&U?2?T4g5R{9O4)feWt zDEgkP;?qvO<crKoqv`9<Bp3g-xkWLd{w5Cc%Rr84B(uh+&d)S2M_P3;m#w2eRcKeO zc35=Z#)x0;gJ8B^%~Uqlo=-P0KkGYB&HtGAr4KkkCdc`YUT`S5Ay)F^0LOHxARlt! zr&wYb>mS}JVZLLgiP(OyM#><L|AXM!Urok4p7a(qX}R3dhiT=^f>%P)aJ4-Hyc4tV z!02M|g`NOT>5?1Uzj&&~p-iKt&GJ{zLlk2_wD?}j%jcC-?!A#|m8n6nx=62no|szi z{HD1+1sCb^4D*a*X(YEz3^;Y)Xqb0;D&f#~=~O37@qG<_5+o`e5|6R>Q8&orv-CfU zb@$WA65>A7uDPpTr^6W^oRu{wCSmw*X=>@)#q08SE<Lank&tN}QuO{#`sQm+lsa#7 zcmJ7rfkduLis`59O?gv2l&Q7cv7gLY7~fr?u`Wi+1BT~c;`5}u&3iaXEcr4m$qZvg z&MD2NXe(<P-jn-|0yHw@#P0=4p2Fm%QcZ$o|Bk2rB)k2ZshyC+{54L)Xx)^>M3PPD zwzQ2l(|>=8Erj*6JoVBr_nMkoGD#1^$MsWO)tR;_hV0KM1`|1Yh$c+VokXLv`Zipf zUM6N<#S^>?xrA?<0WSKv&LsX`kuegTBMWoIrShGdGG~FAv;{<PJw%^nWrrbwFy1Hw z3>!lk2rH&0qE}_1h&HrCcxvi;YOFAaI8H}4yhP9vatX`yS~RZ02pF}Q?PoLZLRxBC zamDkGF;XT_`x~gpg^*)Az_jH6v`~IG&=HW1T7*$nw0T;axnUNDXu?%$45=MpWi}qP zp5O-xvdGaay63gLKp{$Sb_W8uZQnXEruD-Z6X2O@WC5v&LlHz=r~!H~G1Y^_K?AF% zGa5U?&|k`O7bA;K#tzxE7|<6q%KvDH7(#7rmS@hhYGD*B@KB9&eGa6V-)2E}MSHR1 zSNt5olvIBtuuATsdk!&`$f;)`!e2eDuRPBDSli-}pjsmuKmu5;`r-<JQtzrQrq!Yo zg6^G&V~)sTB+EzWT1}8rP35Os1jBnBB)Jn9^%(I-`(zo@Nmi<*3FN<L4$P(wHQzYq z(3H1bZJEdluC2IWiJ7&4+;(izm^^Zj1ucqi`wzzYEOfP9U~m0e*LF)DDK)Ivd@9;J z2R9aOWcf9=TUs0nzYp1wFjNCkOBQb!8Dm1k^gn;(dY~(X0zW#J1<eA-JH|di>PA`j ztO6zaVq~ukL4{4VwyFd7h3)9JeH~Thp4;e?O5>BG=+j}T%=y$hcN@CxxZAh-+tl&Q zL{7;mu@AzwX_R&brY&5gb4wK3LX1uuV%{1#pw|)UXL}zRLx%m@If*uras%l)W_BAE z`FjG2KDcv^jw<&@eDGG6H!xSI)?sp({YMr&%bu9WSr~JRs|a!E=nk8Ah0*s$CntE) zpJSSp<WKxoH<=qtq1a@PK1pFA8Rq7lU|K-C?WeZXQ-L;Y+c!Pz+27#$R~cMi!X`3j zRkGIjX`W-B(xH}F&cn2^IWb7l8NTgevM!E?5P;;12T>-N2OruqJ+lM99ptY;?SDW8 zbfZq}G2Dh4h7D|PccV@(jN+4@Q70?kPMh35K9%Q2{=S3hn=^fQ7BUF4u(N~?*4<sP zbjHC*fv+ur;t6W^(>}6hs;-O_*B!s^Ox3nFA55w$zVL@dW=em~i{muvcIw~3)Tq&i zgS(`>nj4;j(A$<He_lY-z0khcwRWA1gBH)LB||~c8fiTVSB4z4`x`P&()5Zp@abmY zo|obra^1wUPZXzu0_g+unA4+Z>(Fi=uvuFV`zF2AZM*8gXN+Kwa~i8P^G1Jh7PMOM ze99A(9Z_Z)Xa}(D9ywMTzi`iDsc~6WqsMG-Z@UhNW5m}ORHcdUy@zR-8MoU^M-=DZ zu$T0zzD*enTpZ)(AaPsm=%RD;5ftb9*wUcnsmCzDl#N|pWytVJY05)<$pfbs&;yS4 zg8*P>3I)~cY$<v0%B0gfIrUyDJr*Y=9Jm^qIi|ebp;_k9>CSZ>k5#;uEu$;_a{;aT z1Y`9Qqu6`+w1MgV=|F?j$Rp>5ka0(!ofNZh%s!gu{Jc-+={}O}bizn94N*hEXY1}c zzzq++^sB`TI*V~XF4yOx)ossLbk8Ga3?`@;Z;lH$wUOAyS<`Hww@+u}V)9HD<W_j@ z|03y5{F(kAIDmgPGjnh5yB&_1`#w@_Gt515=bZb#C8?NU?m3fGt_o3zP%37QE+NTP zxe}7lrM{J)$K&@W?D6<K_Br0K*Ym|}(&4_zJxgb1$s3(8*i~le<s@X<{jgyiUey-N zsqgZ0L-MeH7+x*+xt7woXi0ZoqSPY}8D>qU5NJ4M4qEulIoojJYhUx1Ee(2&{mIV^ z%lvsntz8FP=vqU+W($RhFzAFmi6UF+Rc0VKf#(X0sk2a`uWK*bGuw^(j6z;O0qmj- zCYv&r-uPt5E8l;f;h>%O3+NEzSB~R+@`KOw03aWuFJ@_q&JU=m-?ZVi@8#JnHVpS_ z&P#LIE`7Td<GnQcR&!O2D8X2_VJJAYEXc549pnAbdUfxuRd+AU5!IQI{B|SJ=cn&f zKH17ff-Br`0y=-{Zq49X5tD-br$0pt{}sT6<``Xrmlt2Z(}&OPA7lL2)sEV-t82?m z@5yz3i_O>U+UD?`Z1mpR>8@amGQ(aPHTw7+W5n*v|EW`-&>T%StobU-xIM-A@z$5j zvy`%&WzqIHuOD){t6k_4@96hDaREH7%}{@|L%V6|8aEyGgYl<JDavr-=W5m|*vaQ_ zq0x))?1h)R);S=o`x5_PQr=X9Sz(xH&Vl}*d$AN(Z-#5<4B6FvMZQ&4NuT?*EJIU$ z_%9xIS_SXGnU<!uGT7!@Y*<{1&Xt~K%$UgjmWEkuL!)8u9v{0=S?SNs$#0@g1$@2e z<B|cX0tC6$l5sf$rXMhF^*P3H$lV`TP-|%pi>`5Ft19hd%dE2$A8W#-GM5-g4(<IF zHS*X6nZR8{t$tp?``8b<VRST*7Ppf{ihv}To%&%i5y_<Pb*vnPrfm=y0`JtbncZo6 zZB%uhxz?o!a~N@Sa!fYcsgYCJCD`x9<H#O23fglu@Knj-hfUk%{7>5PVj<)BHyPs# z(Osiw#9A%S`%@-^x8RD~)b|Hzav^HCw+y$n2g){Q?zz#)9C`qt2!uv+dRrZb9h80m z3AvhN@P6?<R)f9A<HE2z?yiP`@!t;d_9!W@sHuGjrklaCq_d+W=F-Vf;*KBpX5W1_ zY$JYSRyj{22?pqx=byTF(7HZT?o#v1&Lf_Y?}GUv3kyD97uCppG=`zhbgFaNtXmYY zRvYA6xmi*vr#XD}q`Dq{Y~$5zxscV`_2aO%irOEll}-|$(tBulGGj3@KyrEG0uS-s zluHTI@K_f6_`OgddGMjwrH}og!R=Lq2^fdi5%a{w^pKC~@bK6ccYtA+8Flr2Z%9d+ z_2cp5FBDhO|3z@)E+35ilT6_E`0wl(^Ed-1!T9l~X&CyXZcR;lYOJ$I9n^RHe8R~u zbCL1q!D)Xa&BSnLqwHh%VamfZSrxa+k%Q>;r#7&<y7i}7$u}82+tlIw*xB&wuxSNY zrnxib{Wjy9cXZLB&ZEtMpTjWKna$t-Bx`j<6j;r#qPC0-xrlAF3@jJ(+v`^@p&h`G zVDsk;vd3Q;nC2tc4IWiU5o4<m<*9!2M?}^S`RtDvM!X?x`J8Lp>&FL=7`<;{)$?1q z)7uZ0t{lG~U|v!4Ujbc4k<p;Y(2yalotGH+k@v)#PkVVc9Ud6}FSdOt3J<<sDCZIU z?w$AbUC!e$)ug?HYYw}`%)N9*e_hO%^945<ZnIJ@VA&^opI!Xl;ljS?ZK){^=(zF> zBo^rk=IFhLc|*Ak-#mxSO;BBEje4<l5@EFd7+`%!_B;z=V}pMq65erb_6I}HzBq4D zgjO>MLBpoc#SgxUP`UHPLh#y!dD(nTr?bY-i$ucT=x@>2UuRGv=H+2_rzQTW=Lx=i z$sjkUuQwXF78-I{)36`O7bM(I^m>RZb9#r@M!x*B2L1ebAp*L2TJ*>qg^%LHms0IJ z^2{}xxo%eUEoR^{&z0|YJCgMOv3>@8qK821wiEkX6RJ@^)S=w|775=9+Be1`avyyq zcqi|s7x`N~J&0H*0{sbxfB$ts+p+tnb8_>}Z4Wp+X83noJQ6Z7K*r8VF~Ad1_9aQ} zmO&+&S*PMESbR@jorOxcTD*_+RkLNpwtck!nw(t&VRDVp3>oDOwMW<Am)gVTjbrRP z(kl$ER3eiA<{4Y=X?37^Jt59bAZ&^M2Yc1a78Tb4OQ}QtqWd=IOfZi8Ophu~X|GN3 zUe5YO$%x4M%;<-%-3!JCJMFDqzx$XWC@4&$q;wrHbYjo;6#XZS*w?@Hv#95{P5Z~# zwu=!GVG(w&FJ<SI@)_5@K%;Li3%9Ppic309@D7~F={&)xif5e9hjmB)QQx4tt2B;s z<vbBDJZQJKf+`Z|WN5*~<gt;3<?fFwTu+{LB>?NE!v&tK*>h-e0ZOXp^wan1D1VFb zzr7V<@=<T|-F}fWK<p}S+1zLY#J)oxqxrO0l04lz@+H$LWcAC!^7q$uV_*Jz{Jv;w zNC*Op0H8vuA^-3D%83leEZxo)QgUpW$wtZou{fcrlIx45G%^6$CBUJ)g*exah>bmk z=NW`TZ1tX&;@HL8a&uIP_UrA{MA4vUP+#fED9)Q8ifP;B$;h`oq6<IZ%0M)*CNY&V zg#&yRqCi;Uc=JSU*qe?>-bK6NdxV9_*6^R|Y4XWG?@c-HD8288-u2_e&-mUwh}Ggf z$vGab0yNL}f!B#izKAHN_Uoc1TI*Kc0Pw)m4DLKn<oUT^v<?L>rw78$7tgSDwioX6 zA3p;QG}y^#$ate?)uolDYtKm=%Be<nN514wLSf;D64Zb!&BdrXnMi5|@fnX+Ep5>a z_}@Xl{5xl(090XPODMeJ`@aQo^B3UCF6N2)Oved5@ss|MKn$-dkig**Tm<ST1pscP zSI)j|{dVO7kncKfW@PI?IV)S0yo}ccEs}Du_cNdQsNbhMIn2c92m}IH#VZb(9~zvn z(9mI9eJiz9{w!@GB+Um~=qg7z%Qsa;QNx}25Jkw>r9?ygw8m`@e)&BS%7>UuHCPFN zYEY?q0&e92!0+{H!XudvFD}29X|N?s=PS#UhS%P3K{XRDQ9L1621?2=82`pL0A)rL zl8hDm$^~;j4Ab#7LgHq1{O$7GIF87#is`}v4bCM++pIjF3devseCKWFMuNDdWuRSw z`R`k&taK5MgioNOOx1S}18gp^1G|+8o}9C84!)Vq6$WL;xWwWJd+zQo?|*ZvRtYIw z9=8Kp;+~Sqoe~(?9DkQeD*1k;s6KLD3xA^_#Q8eHcU&moDgH{i>3C;xY{m<HzWEQ% zI{e_8j}C7n&+q|H;3Cf-h0kujtK<04Jw)&kBKeFc-%5ScaDe-M6g~n|=4gvrW^mw* z!Apir_W8L{_kmPSBc|-j#1&he?y_dLI7q>*xM#=s%PkeJp3~AM7@RX&PTdo2;NaH= zfWfDMmmfMl<97e8ZLRwz^F>c@H3wde2tDWJaQ4jI0y?B1{z`(VKGpC2tG~^8ErpMg zD3Q>>-4D}_SdkyI<){8p=0w{gDbIV{O?UC*Vb#x6)5)Hi#aUkxeF@cpUp<j8_~ifF zT1Y*+e+>mbeDli_mxmJM&-RX2T$H}>rVmoi_2v8rw7?WG>f^UF>xXrz0;Y?Dvq*FL zG5>K)@x!Qc=SttY7=n}g*Uno!U8(A^Pm~}d1b=LRw&{Vf%;OVYUj@L7oN6VN3BWi0 z&l!eJC0gXzuTW_lYag8+zk-vW%}?<fU&$El=AY$6tGru3^>{iMj_?jObS!lu1b}$o z0^qd06mmqsN%)ci-3_Y6eGu1Zno$;xeOAK&t56F<l1;T_oiYq7^$U63EetZBAb>0v zO;$)y%uKB;p<`D!H+|bdDb;C|$5A75hJsR=K}lgaA8RN!SXL}&f|NV*kK7v~10n36 zXfiyy?T+)U@G&UAkbJgZwte*a(9f;PtSHi8Q4y_JEoQ*n19m;kXsMjQs+7wq(?SK? zV6Z=z)vK%XN`!J?AeBiYfE<k?$c(BW_BszjD10Ke?Ya8<A_bS1R4w1C*m>-k*O*re z0?{#)^}g7npGo0j!e@iTQLjs%4`l1*)LkR?kN0H66j;~(33{}6+NvU<(48ApsRJci zWKc5D6TW6A`z8v$M>b1_F3}C8Du)(BZb+ZA77f1rijOD(HGMie{IM-r^;BwX=I>rb z(=Z+LKk0Yt`rGAG9iQ|*%>N{6Yx(haGvT4iappM!N1=lh=w)+AE{f-VwW&KS?ZkQ% zQgT4iv<GjRK`ulow__=>+E%sl&kld7uMGDx)8$da6^Q$W)}jkP)ZG8vr|>MI=rZ|H zs)lw`va(K7oJ|n=M#RTl<z!7G_<Q~X_Icr7F9<P)_rxGww@0izLBeQ0edT~FupDz; z9>;={tqGFTreyI~h&<0SOjX8ievwo<KgRaD^TfIhj;G`KImy>LM^c_hh%f6slv%x* zbWF`6YqNq}7>}~NGAhGeV&|s58v3yECRr_kxu8ENRW{o!%sn}fo{%nmSV#nNxq(Q? zG*arBxb*3GY?T1X3NkxN7z6rlwUaJDwA8`|AHXds%jzwO+%kG8_!)4`EiS*OJv~AL zYK{#OidN=YO_Kv3O~j*MOXj|<OH=+=oYg**)2+fhm<5Yd$az(m*;yXo4nO+=MnoeE zLCo3X8LEfXu334XDmGGIIeV}nqj@a_2J~+xAq!<0mX`>{5x{BeO3HSi&G**ZSuB;g z(XA7<o753w|9eV8A1O}Z#TmY*Tlr=~v+7k5YhAoR6@XU)XS~U5=|G!#??yb>UkGLz zwK+#}e@YYXF{c;dLTAkNAd?HI{|?(=i{|@sFd&RC*+$9aqQ$Y65|vZE$ZcX9238V6 zL$XZO%V07yJb-4S#nXx?Zh1H{WPvXRdFSmdVo(q>L2+<&LkGrj3e9wRU8xTKJ)NLv zsD2dN;M5p2TKyL@mf*Z9%z@H1=ccXaj^0s^?@dTP(Fx-}67b5@=nfIr^&x|8BVpq_ z>Qw(J-*bd*Zy$c}eg1YvFwLYsgI`)46}HRQ7P58Cqk7Zn=by%a0cs}g#;8(9HFGa0 zWr7E^SpU9*sc9#L8b*_qiqFmM$vj2ojehes{*M`|!mbu{Fpqkrnf+Xh{ZON~Fu#=} z%9r}_+UW#}?!G(<(9n^3DXUGGn|(c7<ze|VXcP;riw;uxjoiTr0w2xZ-s{Zn<mnFY zmwm+aoxdK4(}#f`^eH|XbC}{%c1^m`9vStRE?irG^Xwne_y=%J#>>&`OErdY54lyz zSK}!JCPHBA`k?se%o}X#!|1GjUO4}e6e1OtHp?JfM$gm40Oo$?y4h`xU#k-YBgV_+ zThGFzMzs#KAM@S9u&05>UzDd4JORJOO~kF9nTW4e=IGTwds7R|qHiVj=v-$n?O5q* zuF1*YA${Q{w2`C)08VN4>A;!QzhcY#qZ#pgyu00m%59;}IMPGT_Tzxdna{@u_p;3j z73`{x@*U0kdnuuwCotGz`~|vVv@>!!?oNU9yT|e~WxykX(8M|o(kI9+;`T()b2X1p zKopb=xKEx)Pz8UBl>o>`EPB9q&bfs<)3p*tIB^`ZMy7iEW*L;{(080i1|*XEp0N1X zIswjki84R~O+W1#Y4m**<(h};JbwKeLEbCTnVrE;w-6x#C1P+m68n9iuV)-daeoOq z0KS3xDO$41GVGelVO;+!2%4^JB&!F4{@5tjOho|!as-pN_|#b)!;Fz$&Y8~^@d*@{ z@^=?BIelZj4jFTK6Z(z<BuVm!B$h20XM3pI*?t2Mw30vjZ-bSQFZtON#GKNqjG3n& zf%FD%lPld$-<Hg1;(Vg3Y5E$3kC-*nD>GG3VCW&U^}Z2xl5+_=mU`GBj7|2{zPI)4 zGWkif`lc*_F+n25BSdzAAYxBQb46V(@KAnf3cSbm@<PCP5#trpWDySsszM>^x+a~G zzWgd?86V;+AqH8Wl^{gWE->J&e%Zxj%C&V%4`dnr8%@uK<LBQeDt!kmwP6T5maQcR z+51Z+kjJ7a5=6YW*5)|U@ERKDQTJg5Pd*|~TqZ3@|825u>6tbUJTe@^fKE<mi(InU zGcy`rirRVdjGygKej&3@#5|eDQ_Q5YF7ku%M07pDSLjPWl+g3qlwA1+=1<T+0w9U# z=K;b(BpoTp1HRl|K04cdMejbTR76<EO(y4;sQ0K8(3rsk<`R}AX|#X{Q#8mB=H<Sn zZp^cZV^0V>JhHlyc8Y8XS<gI~0r<bwf8ztkODxXl&i&&jIY@mVt}f`{=(>AyYLpd1 z!ji@}-g!udzir@!h^u_LRHHiIYx1W4CRrL03V_XEPr$*TwKq5aHs|g2nnW*GqR3Su zuo9w1YM=e^v@d8-A)wBTNHDCq%g^>T#yl{g`?+9%HU#b=4`GKE3r>s89eyU0p+owh zM#|7)=WDIY5$PDO=l(NINPQ-!yNS78o0o<OP2{0J<*gsVkmw-BBCPS4ZwUb7MGdkL zeg`Llglt3wzjWJcTX279374rZl9)>SqQyR@tw6v_lm4)&+H2IH_Yq!%{pS^$G8tF+ zAR#f{20T#R!?je{EWXcEo3B8_ZSd#5r4C(?AaA<=e8Iq(^;fNiuyy1Ef-OtomeqA5 ztOuB_XWENFxEDU&fnBw=<z@i*$<IDEVh0d;rZ{nZ-c&#_Z2aj+3q&%-BcrhP<^oLz zW_oe=b(C9%e!`$;4OwH6o8UH(t3cA#;#@dpmEKIx(}tk2wSDVj=LP7C1)%HSk(yE@ zq4Dd)RSqU}10MlN`hK%mYU2RTw$Y}C6%gO?uPJ|1B#;-0WkL!iOR?yW8uSJH0!<q> z_^j-e_xJ3JL0AhAU}#uyA;wfMgkwlE{YpOXf9(05zRDMGt0|fdgg-LGYOb*54ZLb@ znAKFx`BLfeqFNzkqUt99Sb)v44-vnLx4{u?HVFA^um76ily7S9n~CSk-V~r$m4#FO zSo`d92Gh8PzRln}UrA%%WJ?{ewV%5iXRhTyswh3Y>|GoI>o<woH1Eq|s<TtbZr*S< ze6GL!Mt+APTTbTisp*jAqjQMO-Pw@sl4GkqB|78?OQ%c3NpbYtLjsx^J_+ucEiI1i zlT{F|B<M&_vM1b+D7C<PWyqlq0UNjss>!_apStRt#CRl-*{MiRQDh%CpEJcv64!^| zaLAzk)+6~(XBFAu0uUde>jdm20$(Gkk7g<=+93g<{-ag3Eq_-g86nsKv=aQ`-4Q*a zn`WlhCuA~!%w6BKPX27g9<udnB>*o^)#kInX{U4eUvH29i~WobsN!&8IS8?%<mfZt zv=OOwVn1w|aWLEvAf`it%m-jXJl{3#4ZZCpYr`O)J<~NzF6u~dD(VjY#KH;gN~sd% zw>_G@Qb)sCL(FFOGH5Aslq>XmTBe$MLxaTtntj0efgrD3sz@(&BpuuPjIXB5earh; zFdT!u`M9suY@lG+Z9>PEgUinp{IH}c=Z>%LhZla~Y1-_G-wXJ%?D0(44w}S=kOQXj zUdhpST`Ko@pxkZ1Y$sc69DZHYCsmyu_Iw?!SwnOyd6XVW7`;QV@h9|;Hl&Hhq(ocy zXc#6UUhY}K9XOl#Nf;*%okjIWtCvr$UatfCCE)77`1p<x2@oPpf%~V#G%FZSB#_r8 z(Fe`m+Eq3Jq!I!4klcr1$IY@mDG%8--C1JkjK||~a8<&m>muyltT*v`;J{H8*;pB= z&(-fAv9I7D)BC<eN@cG69ry#rt1O!c-RSVnVL6j8DBWfPh4wzm<3k5s*;3}E5L4ac zB|ZUV>L~}{JG|UEa)WFXuGNo-UOL+adgMKp)ytLxRKj>dB^%f5QeNR_ZW1EWaBter zE@l(i%r6lT&+(mLz1>KtqOKI(vH2OP!4@l_B<{LuZ3sC{j`RAJBb!{k74z}d{Yu3P zm*gsK-yMS}?1!5HDqmntc3Ccjd>Bj0%j<qe2_wfqn%!ZSqoyOMel(T<nddxm08ysk zfGv8qm*2yI(Ge0voa<@GBKxTnhxRowbrVyK1`z1QrK{C11%HWZd}Hz6%um~vA+~5) z?2PqG(F?C?6Y|;Z6M&H^&%hA0@T$cTr7&XWS7N{{MxCVb=BwJHP9MslHx+D6zT&kJ z33py+w+Qncd8Xr-(B`gdhTJ7hSzj9)!6OIYWhC-P>+|=NOeu0m=_*13*xEIo*!NAP zjrM4pRl`sz{dV`%VuIJPVK)$7=bP<*zI$UUA5@z3_Yov@tvzB<lNiCD16w_L(Y91F zkucswGQ51JfEDGU{-w|_dM_e)gEm!WX{$lUU{2v6taw|~OsFN+@PH%n_Qm{}T&NP{ z_39p_=Q`i4J;xpP-uJ|(<2$Qb_GtOg<8qOTa1W(*uMd-7@hxTQczMM|R<t^)yxB1; zCm_#{6?D|pVyr^lcRcu}b;zfMqes}D;@?RUT8@H{a~(;K7QfSMA;3TqF`z2!^^Z5( z9Z_~TTw9*n1~J--??+tsD>B0H9~|YB&1>-O<oT;5JuDo)J4%JFXmgtcX(27N5vp~7 zd@_rl1b^0D5|Pj*N3!jO4?R8HC(<RrrE0kq9bIk__*{?qtJ6=?Ev7x;vK+E62-x+{ z);9V!TaYySa6$+xO^NM;CiQ0?lF`8giP#)zLFS#nGLZwwpjQuZ>Wh@1qB02;wyz&^ z7p&^30fea7_4ky;Rzvmk@FqmvKk#8y4*MeR*1m7V8AC#9hn2i+dCvz9UNbOPZ%%_g zL099hlo48tH7&&M2$W)bMHEOwlws>5Ga$to@I&so4|Zr%Lh`jMwQ)bQwS5Og-56S` zromibMH3G0v(O)Pv`fPDFSSPLpZq;_XP0&F7-^6MF{J8eM!69}(u?b-8eb#q-sNj+ z5mc2;VOT&SiJ(c~dcv}ELaC1KKXf;;@$F4ED(xGZUJEsq@*J>gIvMP7BlD`d86zu% z&%iD%1r?o4WN%oBNSi-aI+Yl25x`H#C*QI@P-{`ikyw`>kfbNNyY3;;^$GztCEY}d zE`XE}uC5OyHC=xvQ=<35TK5K#FF`8N`TauVT|*9?wrktzg&MGo{LueM4JF+pke<7l zzTzbB<;GLrYnCn9?Y5t9aR4Ul2WM;g+9rP=mqLP<_wi&}r#JYe4^b(ErNpE;#to_1 zEaCSJfGK}M3w#!wrmXkdt5OfEWm=d>HTHY1)wduMGH5O)ITF}6c#G8ipN?5&36JuB zp?vp*g&+=J-lHUPiQ_wM0>1>lX4&-j<uh_5_<BPzo8c_|$Ms4?if#50_I;pVIqg35 zW}d0mxgW-Vb$6M2+CxU@Z0+aMM&}PgE>Kbl356fUN%~QrzRj)>NvF-MAp*FU>do|} zCN?}@=iReWrhT%29LeW6Nx_Mwu$2NmiEFH<ZPdT+CG%68Uy#TT&Geq>z8r{;^d{u@ zYKJW28wN%&2R`Ka5e>+XZBp6o(`k8UU&HkvkLh$*_9qRt3H$tWCHm{CACLLz$r@}d z$OLFPtt9coM3B@dPCs^04G%Cm)5L&NJ%GFu4F86h{XoXtNrJCmBS%~-XsV~!-=awR zvXRY=t>tzjpt9Iz|Ax!3ugHnbInLdBqMMw<72__g(m|^-q;f(-j6)qG0|1&YwLPz- z`&6h;A$G}5w_MwUUf(Z22!B%))gotA8REd|;8Ad}no(ZH0#_ETNTRXjrmoyvJWe6c zd~K_w&J27ruGBm<d+pS9q4-NyKzF5bOOlPBID_Vc>y!`<_hyxg(d;D3>K$)U)x#_e z16QUP44#pSW0#XYS2c>?Pv<}i0LDW90s9=lMvW=;MUp(EKT^>))?m7ecTqI$GDKL+ zMB?a7(ER(*pH>X+eron3nU_|E{Qc5&?#$50<iy4A4^FA%6v9Fqi8H`IYpdF&usB>- zW<wi~+>S)V_y8AXj#aBYwvX+hLkT>Gc8g{hij2#Fq~Sy+A!#-#R_mqq3urTxqi2~N zN>aFa`#$5|!3tRs_;(+BH@7c?LcVp?0o##z)o55NTeURguFv@;&c090uSU%P-#&7w z$OJe|x4=d?s!1FD9LAGf2xDdE749otLoMZ>9BZwKWAFnBEBy7mvO>?Wg8!{#kdE3t zKYSuocW1ORZdY%kUj}73-ZfI@^t}|QYD?~;m&|5Tf}i>erpYVhK0kKIhKC(5M7GA6 zXD2y^l$jg-j;pN$Y#N!2{ckXXe76-wmQ{}0^h_ZRvS`<4h}IljiAy920Xx26fGAuQ zP(oLqV6*AEzv#X6khh`gfJ^V4dfK~B*7b5l1qLX}$A|h=gC$xW4QNnfP`hrzu0rMh z;oeJ#^X)OO(bgGOUt{-M_1~{?$P@}Ji?Op|@vgw=JoEWc(aq1@nLCuxPSbpA*geut z8!OiYpjelXu@hfN+3XkCrK<hq@OrQ0V#lY2D~ZG6VE~dY^;9G`OWQ_L<z?lt5G!*d z?E(bp{Fw2B(eGVfvQv*jQ$cBh%yGAs+p|#*RJ28(-ZjYFKHLPju5Gi<EPfC43t5}z zxnu6dy(7OZh^Xbfn5094g>--Hb3z9eLTV&^QhUuXK8{*@7hBtnCH4l`|F8^tmaNzJ z*X^`Zvzf@GkfLK~D|*piu~^dSNPicV`b_aU=h{KNx*@S^Ms=Yf(<mp)hmFDqJPOPJ zfd`|NzF3T4n*04%_t9&?(q}L^0~+uDu&S-Zl5%!xWCuwA=vNZ(TN;P8KrX%g$$)V^ zQh6lOjkvT$O!ycMKXW69?`yIKdiTr|?a^1gA46M@67E|Sc4%L`G87t>%pzZ@BkFS$ zGU*aISE9Ai*#f9#!{9>(_Xihn8B`M!M|fkwLz6viw(7fsL-{pAft1iqGUU`%Q<x$j zO@U-pb6NQCd&t$LKPbb*QrO*)SKv&(-E6NG5plFO^vx1Cwf$}#aTEZ;L5=VSPo1-c zw9EdHNhf05r_Acsi`gH>^U6|8wcEOx`hV(DgdC_uCYP``X#>X@aNy}ABzCLt`3}z6 zlN@cFjL@8FN|4)44;P`{qpLO+U2hN(-z3%27q|mr(o7XM7CAGY+oMJa5VT1rOdLlq z!BNLrgq9z>2CgbHi4Dq2t9c=+BR+s{mFZ+#S&g1LiqmNnQ{04jO)`UWBR&*#NRC0% zwJ@y<1^c;e5TidJI89>gwyt~y@OclDDg2IKV~=M!N7&99ZHW>Vf@PY-#}$#uYGT}# z^sPFDB@=%O!%M}GGo-RVo!AUY6a2dxT_C}YLp*m;`uJA5z0_0b?2?Sf^v3H!8H1D7 z_299*Nkv9ps0}K!HeW$b5nkoLNK^%vnrnhYjvrgLIXFr)i^M^AfsioTSOS8AV;7LS zaDM&!oSGzgcg#EyksFhJzud;~Tu9}GxJ0qHi8&>n_cw>7gx}CLBQ3diGr=P(%%|L@ zj+asPy5ia|x;-+huauFU6iSS9`a;_Z{*uK^w7Z#;O9HahZ_S#+#JVOma4b(o!jBEN z*~Ql;){s>#F>+goRGDOI`4n;a6|5gevN|3>_J0d>Tn7Uk*2M&~!z0?RoQfXFjnC$7 zi(sHXT|mi`@gJIM4V0N(tac__cTI7>q{@2@74UnD#*NZV(3YAYFV1ukw@e7t=zS@p zEFre-X9O7F*9+wO(&<p3o2bWqhUNHM>%jAifT5eLLzK)qAXa?L00qe<qbR?NqdD)I z&3iFa?mvLL@+WK7gbb3PH`u;A)RS@(azG)^`+4=%!_eW4sEgp&`3a?idedaFdrifL z{V4a_35<Ph7E1g+Q&$Tj-V-L#XE>Xb2<fs){awKv@`VBl_mH_4PxBu2UDou%w_C(4 zkqYTaWU2eP=fz7_=sV)T!Ryf>A#{+mU{alp?WjJXk{RF(%WE_7kCAC9?sy*SA++Q; zw#}^+eoxKE-Dp*7x&GnH^fB?G)Dq5X-OUQ>2@~qWHRk%M<=oL`rhZ^)zs)TK=w)xa zJ$|c7XIVruKUO)&n~{A(8i6@@|NP>vhpu)x)*J9;Jt+mJi9R|VsQMpGG_7^vVxZ|- zRqC@=&)7CM4WmlMkN{4g2cPElce+`gfC{Gaha(?wD!~Y-GdH@-f5Sug&U`3b+J@<{ z)7eF^vuK&nPSd&ogilD3_yx&1n+lf2ac{RdYb^(j-j3|-sO$ZQP-*pNwYf+R<ZFRn zU?X8|C`TZt@}=t^iIX%0>#z2T#L`dad((OQeJ<gbXFE#E4!8RjDk%8>^z<<$rvCTq zmR?mXC3a2T%F%(X@VF;F<BFJ}Gc{1Y=`#y05??a03U`Gz>?u4iib*=_Zz6>?9*%=3 z`G2s-S;_hoSu`cXoOIB}bA|&e^}EmF4>4iy1w*Tq1E|ZMQ-S;NBs@M@&d`+w_I*{S zG@1_q=%vSZ)bpopZ`3wVmX6aNj6VJ7lyvutjLN%MbIv;vc_Gy0L7Oanz_`25Xoq;L zPARA$%Rs_b;ylL7ezfVku7p8!00&UX1;`2h8dV8c(Sox?ka;U~@;S^U2yjj62FjCF zd_KN!TfXhqpT^Z{3_(gF(y!wZdB4np+x810aX`F^&N9ARX>Tf)jc^72qT84ojx$v2 zsGv7t!6?V!01;Y?2za!U$a8g(yDDvgS%WFG|6{ejA+ih=sl!o_P{0@3=F8Jivn)cZ zt^w;gZ6qFOvd-Ck4(R`kmPc)gQKv-A^_e$6?DLQ%HXc^0K4S)pdp`dmgceKiTUulP zXTts|LbI>1YvM6&SB<$Lp#ihw;&kz^8!PCRp;h18#ISD)_Q!l;f<5jDVgi^K-l2IO zP;XB1&aFPbm$fDjgQ2BpqQ==4^2<<hA}n}tlnK{|6Sy&~TscLIz9ohyVqa((Hfqil zf#=uA-3{o6PRpZG@Z3Vwc~wE+o+YtooNkCiVL$!UT!sS(6~%lrRX(8;%M#|#F`o9} zLE#o+RDn?qG<5*BM8DeqVj2y;&ohw$Al<8|tGdKtu{xYxwyoPl9u5xR!cZk?3kQFm zp=MfykFt7&mOF0S+lZm>dheKO(yX`0o}K}sml2C1Xi@yf#xP<HEJRQm&A<0DvhNEP zLLUHpH<CE042M-A@Txo-Axn!$JDd>4p-VJmU6qc!gB-aU%UN|>2$Z%^mbNF-j%nN; z5n8V8Uu)?RROz(#94|)IH=NBcPzgfuuNMi(5(S%sG}LLrRs^X{@Q&2#YGbaU40vA? z{K5*3VNPJC@=-5FP@sO<L%3=T%1KTeP61#fEZW!(jaTQqwM}2k0?D#;AqdR3!B!hc zat9mB@u~6lqJ-44r7=~pkZctN5@`+<Z`)x1rimpW01<+S(DK27)T-Pa*6*xhtO6Qy zGY(a!g`z!Ebq|(X^Fx7<5br}}ACD5)gN>?jm-((3jy0L+Ooz1QyR@nJWMEi(=&c;B zrQ2eT1H9{BM18(^QHAGVnSW#aoFn`~l0h0p%14_+QEn)2fq|c^pV9p^iOb8%U`H$n z*{rFB4oMrHv(>wRl_dId$_ph%`P$Na!Q$v<+-)pq5hshbR|oGJ5|u#65871KCgE)~ z3oWrB_7lFIKsbh5(g)#B+zN93ht_y-quHk3(4dab^Cqt>(L`$*DO)!WEXu5*{E=Ue z%|f;FG*CEU6v)?BTNqOq{=0&hI(`xrp~hkmF$c)o@2ZN0X9i`}%*5Aq&~AQ4A&A4A zi70qLEC__!+^rHr$EqLttb_k0Jt?qK!$9IuB`2v6M_%`Ooba;d&lO4K&LZ75&7(Sm zFD;7I*30KL##!tFmo*m|)@ZW5-noIl0o)3H#jiBMzMW{pJhNlcHmDlj`KKqF7NL4@ z5uouU>S{dd_!HD|yz#9By2uWvudka>iPYs+sD>|NqdC>2F^Rj8_I(bn-`3D^N|@%) zYEDz&3$+%cKn1y#M(QqR%}!7jEdD#oImaB%5xGp8K$#2R{&n{2BY+AAlm|X<S{NX2 zQ20aKTx#kfYN+bq_We&i_xjr?%&CK<>u@_QM4U1%gu=fx^k_=m`OLcST88L-qzE_! zGuc11%K3&}2hYWzY*y@K(Uzu#sq(A#M??X`ujsULx8hKT$VG%Wnu1w29g3d@fT)TO z=*^(z)z2!e&y)nd$FfkU(Iv5}f`4L9&0Cj`ZR@}l{bHAkoC61vh3a@ULBhUWjzTCI zaq1z?m{h%U*v7Q)(nV|Up>fT(_rIq)DoJ^nTHSR*9ZxXf5W=aJmkSZ4Yd;ZTB;~?E zdqWy<*O~vK(sMDeuw(7L+qBpil-$o443Qw{dt-f(jRmtw(tP`AHcdEoB3^x@(>LUF zA|@*_*s^gxgwGd*-#gHZb&YSaG}yDFa(xO3-l$WNmpz33N52X!pOownn_5DNuufrE zyi*w#w{lGOsmJ$=kgH`#*h{w>GYp?W==TT|J1qz$YK<Yfg8-=JZK<s!x}pfc*M-)q zYnpj(Kcx5)`ZaOJ*I-StR8jpuU{M8BT6maKe}9+V0`|X9hMG)+C)8T#fyM1uV%`G> z#M5?caG>_GK%XvpVbM@;IZ~F2RbWADVv-()NSoAgYdfCS0`tXS+&z?0nxUXpM#JWm zmjZa9@1;v}j+>F+S;cO11DfboTEI_MaLNs&`7|nkAofR4Y>z1B2@>0;Mfh`QZdj_O zPN1w@B@QmJRw_=0AV_E#(crh;WiEhQcIHtKzzuOhS37Tdat#yL(6DcMF_EqJSC2`v z!iAT`8qyz$Q5CVL``U(r=Q988l!%#&Y3R)8;0#e{kZ{OAMsUW}m`GEGKb^N5ukRQk zqKod+!TbXOnmd^<l(g!F+??D{SHGh}UTju>%0EAYa&tjb*KG#X9*MCYC4k~Ui)q0F z|Bf$f2-Kl?sQia2dGg8ZmKDW&r%`h%C{Kc2tsj|~tcyVlXj|HgFT=aOnO^VTJKWv< zHto7pc}++g%{qxrb*)z~kNUCuyV3>C9Q1f7u(4I~4On~+o5cjBi|$7w#l{XA>opF< ziR#~}m07D10|rL|M=&Mv#<6ag>133zE6RU1&E+$-;Uq5o-s5pw0;0@jm@J*xE6ttY zO1DA7DgntjasAU`QdT006*(mqsN)7GySn3I;8Gt{ZD3hVCOu8i6<-FH*Ftx*U;t&M zLcFfu@pIPA=K14kgc0}Z)J1JsYLo#O%M~kf#vKh!zdAz2h+Whwjzk45LA`V_ZD!g3 zz!?}~ErxbBn#Jn|64~Yuv+)xK$~1oudK_ClF{gJqoMtn6)AE%oTBHd5P`P372|)+# zBP{Qhm1I1G&;MbA?$PGMfaQH+#)YUJV@#C8y{f3Ys4$R>%(9Rh=-@z|8nUH=nnsFr zxS@oMON}m-=5Vz!qSWIE2qAP)z{-h#99N<8Cy&(;hXDgkV^krp)nj+eJGWcT*<~bU zsUxwr^7iKysHe54+3n!yLRVDFch!U(JGGt4+DP%el-PIvVtaeZn&?2k5}Fa(@X1!Z zf4aWR(ki%E>C!2*m3RPtxT9PrQ;TJ!K*c#)<c&i+ABL#6-Q~P**^d8hblF$f`4n2U zJi&UV3&nSDut!pI#CK}&ndZ;*$bm|kWDFckezO?Qg>KV9cZSHL@P1o8U`=<}WpS3$ zheU~=A^=<@f9o|$Mzlft8;4c-g9nUTAb{tT5el9M(V^KK=;!jcY>Qjy*8Rsm@oru< z(J!QL27}v&Yl6gaZsM@o=-emffA&~->#F%0E6;R9?$XhuoXp&nmfyaljF%_|LS;`B znCuPI`;)yXCMAkaOkLD8`05}`KmU0KW3$jZbn%Jk0xCpWD41}TRCM4d_9MU&wKhmo z+b=omiPp~V7iPh!1BarAYLcZY3j(+Cf1&^`U4vfz)fx1v5~nYM@|i`2bw7Q<bu>~O z6E!1sVzka|`>i^7^iQ|S$T*5+_(F|xv~KwYqUln2!&yC|xmdc1)c{VWTTz=m{b+4m zk9t|BZlb$2Q@m)hH4K-AgxxTCJ$5v6$hYNdrNKec7RFox-)xO_Lx}g8#u|$QL_$e- zFpZTi8U#|hl~qKnHHJP=r1*)}GzR?a8&cZ9xVQuYl~1+M6QbzHl%I8jeTs@Z31wZu zna3`td`BCfLXme&tt}F{?!Gj1L|0#5W$&X)#5WxYnRVh8Gk=c-@QCeoM0=x}G^qX3 zr%-l;Dsi;fs`isUu)g7HllY&&-Q-PVb+b`>vjP?N=WV$-l~Y}JQDZas)UP0gx>Awj zDhA+vX!@t|g}1V#)q!B~WZ~6%E=TC^Gym+x5>QVkKP<fT!X$u!F|(@oi#=SPA9|@? zXC|LR6Qngnsns!?Vh<rlEu(f5QHpTbLEGHNVBAqoJ(RH%s%8q6@+L$Xa^aQ$#>p6S z<NI{u-=hiCx4YbNjczr<bqMU4T&4Z0ior|b=<GPZ8Id}g){?v%!90L)?c0Xpc80l2 ztvd3^4I#8kpUsX8>lD?rgD`o{D!F&;jcKI5PbtzChw#-Bxc2=#eN<6u{_q_CRf867 zR`8z5_wJ=vQl?VSj?C3hFK(i?3q`S#jtPj>Q%f~p(JrcwXh#iy29eCC|9*P>ZdDxZ z5Hjd@?N+@ytGD4lWr+4jQg=U4$DNiA;gyov|5C%s<dZf|g=y8Xb3{};`WRX(W(pkF zOk#UD@uTU!07FuzEuUo=yQsT$paUQ8Cvfmek|4<9;rxcA-`|wOk?I}<*{72GVJH=# z3pN+W$t#>@ZwHcBSkFb_fMfQ`TTRSO`y6f1ALZnmC}|*^H&^-BkP`d|5Rv~d&*09x zhpGRW(`z-kfdQZ@wK|TH$LdiOy(hcgaTs?!dsrnmWCWouL&bmn<(u=v(JcK2QVhdI z2VM!B=JXm23$3~Cc2~%$bzFtuSPv}(^ZHuePQRj?xOucOf^7&?ikp08J|n8aH^c(8 znBdm&g$HL31iY7W#ee|5EdoVzgvQ_xLSg?dR%(xf@E2qxKVR)UiyPq+M4l!rO_~up zWMFs)E_akDaN}XzfvBSkf+V1ni=e_)@3au-38(lIa-)2{%TGs@^EEs%Wx_j`iHya= zHq0eSNa=-tw!`E82xa}l5Gr?>9Kl$%!Hfu!%Lyp4!jV|Sbv=1AGn|&lrFfu0Z(Q!8 zS|}wNNPeO~YJ=;IOV{=htwTH7hR2gAYGtn-Z$)tROC7#+voSzGpfv6X7)iYdDIkVK zHvn8|R{;vRKUSz~eH<n5>omOZ*K9D{3Mga46GbO9$9en;t-_j8zOTR=0SKrc!3pBV zmvQcr5$CzyPQ1sTO1YS0+IMLVuFCb4I*-3ig87-=lTVDGLwkjkfKx+`l<di6v1L3% zoqcdBT0t&>dIx7mdPUTiVlP~eT6Y_khz9jb0G|1f{<B<9?t2pwW)sIlcL3g)e(=%N z4bx8pbCgsOXG@BQn`79tjn-Z{+Vs6Zgy>zf4NHdVoyy^-q4yGJ7BPgtOzG;w*lM|x zm&62*%Z2SEtf@DRQ_*x;fQ>aTv7!gY6Q!Mw0Jw)L4rPb@CdU~L(Hy~HM|;~u0-g^F zSbzyjOfjBQ0Uu-u8l;oGrvoR$hd7Nk*N1@1!$AbsfjHI9n2`dJ&LQIlsYn-~^m5d! z3p*DLO++vhMX$lq<N^F9gLFcrGdz&$3UM_%f}pdT0lqV`z>)rbyD8^ug$F5{9DZ76 z13>bzVril8u`VG;IbzP{Ug_j-c{fCKc5*-sMs|<J3F`KRa$PqW$BhX(kqFuHoKKZ? z-gqK(OZgIV#3N-~xfSw_1vc<kjp(JeL6^@elyhvXs}puTrhXA;_`f|fIjjVy9Q?a5 zqJeB{J`eddItk!q&qku;ze&NYa`oW`{Y#Gg(xWp19mgL!Et8bz+=q@&aCa+kdkn{M zs&tf;)ys$2cM-1A$#-uGzYB_n7N5+x9itTE2A0TY&{bVPx%uoC>Lp)Kakg2GWyBX` zaVcXq%(eapC{4hvLkI{Mf!iS((r+Dwy%FiSv&Xl3p7Y7b!5G85@4(~<^3U>N+Ia>; zn+ZpHif{nB&Tv`fRoX>|LLZ5n@GeeOW$nHfD*FvgQ=taaNA)Pv%I*#*f*yNuW}0Lt za=a_@j!+2&EzDadd<83?0gtu25392{ilgTNJH>=OXZZO`ACWh#>(!z!6^k-9kuAnx z5Epoa7BJwQn`58Kjw$(Q2(iAXL;f7bf;$+qV+BC+uichf(*H2^<spEIV^DUOSAeJl z52U8Aqx@1UpGeE7q#4Tq9$ytNG^I-x<^|VhmT~5a_Dyo4IJi`W0<5a3eBxb;_c>ew zWd2(@qJD&DBAdR5Y^IVmn^x{;$i$<-{6#A%!`N_v)q^CCcyE_nYF@ctU{>=$fhes9 zPHt8t&33%Qx5V5$DHC=RB56lx06)p1EDIf*uesVc-a~5{Mg08p<b<rY0)sMA4oUw& zdcHo+2y?!*9Ro|D#Xwkm5WnqqhMY<w)9dd|^oRO2i?bERPKI%&D!gG|J^eB*W)xLU z`MrA%RkGs}WmB$6aAJL>?&dJTr6$7H<k4D2z~P9pHRpBHvO)U{-BRROEt0U~26uUs z-JIz#`nuAI*%Fo5)uP8Zld#Bfzo!{_`6R4W!jO6A#YbeY-spK4xSdw^30}<E|LZX1 zvC`2P`<?XmtDEp;+P)}22)ODcNqd+9r>bNfyl{t~jmt?F!F2N*jma<a0LfM^_R(Y< zP{Ny|xG8@vn>j(a`iuEz)UIfIdFl;c$pp>qyGf)cL-JIfFGH>pX@?;TLSO*6qzlPS zf7vGomQAm6yla1KG${A7aH!O2<WJQjrX(J@s!1o*ZLGU>^ee~LHQ*aO11>eNI_a%i z*7b}@m!uP*)fG?LFa(uFz&emh!1$c0PS(Ep^QjD*+n!HBbQ|19W}+IYobOUS5kB3E zdOoBs`d1a$X<vlgGAiie6P0k+gS$cFk=}|LmOR8G8DzLuh%(H^*YUxs390u>7o%iw z<tFKU4>B)GuEr@$$@2Jp^fkB41JM{BbTtA($A*<H$5=3pRq5^db8_-X6t^{9Cr&L4 z2L<7UPi#Bna^~a*%VHmAC12`<8buNS9r*d$GcVYWJ{Y;|fV6p@6nLAAYVxu&52_#v z4h4&?l6BLWBp0^4VtY<eM6>BH%j*!y?(afZ*3<tq;in#wqs?P;tu+0Rj<Lb>jc78> zlY07M4;wl(qLZv|AOujlM8i(oM-^#PyFD29XG)6cc90p!gipIhq50|cFC4bi73QMN zDIntZu|9o<7#Em8^L*e(7>p+9>u9B}v9G>8PL8)W<GGU@_-^W$*>~WwnswAriO{cc zsmYj3R301{jum;ue?Ys3&N^KJDJI3++cNbM{9e~RS0ea&Gf(vNoimh@A{cuhJP;7A zcy-vQ=pKmHD7KQ2y*__;nwf7tziLE$5Ogy{vg6!eMa*$nZPSgLx-xW;mEm@~bIWSh zxmY^?FWpzK6>neRPDS3lsv75~_96YxbH&U`#Gt5Sl1k!_bBNHzvzs!Aaas12#5)hw zf_vc#Ha)9*=+P%1b*}&3I)ik9sFMQt0f{qL)}Zc)6pKtAjixo>*DKS?eF2<&pXtA? z0~pJX4!#xFwW6@MBUWK{@zv`j$7;eqqVZNqT8G?8PNQCei11?O^LxmiBcq%mQD;F| zy?8F*sXqKTa1h5KCW{7XM1fMjems3n%#+VgUw<hvj|l_z4d1UBVxh=w5wsUbX1;^R z#+TEyTX+f#EOjP&*K(h<fLB;JPInU0NZjA2(0NQxo(WFpwDZrpk9R<YpC=H0XC?*5 zKtEG2jNM4$oJb;TLSk-kL<Xb*%pfo$^W;fi4lV2O26$Jd5y$ml5m1P_l5j(SJ5Oww zVpgKiQu<K>)<+v|tqHHepG_f%E}5M<!s1zX)w+l$T{1Y&19E*ia%MO&xvmWM`GaIN z%9BGY>2CvkSLwpjDfOgpoRf-(Hj&Kf_Dsl<fNN!Dy_=pU5RtT$DL8P}ldW8niAaOy zaQYntLSkXhy5Tm7$?sikwR+CQ8N!{J*s6OcNfz)V34{?Q;9`F$e=K+RT>|fJfR#eQ zgcE#e72YMB6FB0~aq@^+z49fpyy$My-6`LOkividxdX#+VMUv}lV?TJ&4ygzy>;+F z2eEd2xc9|$sZoVzJun+ht{Na9^EK8-DEmZlG*>$Jx;X5-VWQrs8|Q?M!Ot^#H{piq zu$(m58VP<+BJW(A!ecY|91IX9!OdQ&3oj}E3U<EvJ?A5=^kjVIeNwDOQ<}i8UX@!U zS8Vv7T6-ue+?xxN?HY0)CPn<A(0Dk@35Qk2L|brYK>Z5H=7}5S2$E%ph7cx|asa2{ zjR0n(V0sb`aYAr{E<nIHNtA{wmqH2Pr$0(!&EeK7m`)Z3Q>*ED13oz7UJ_dX^-Jk$ zEQb`s+$52OM1S96Can$;_9~iZ32XE<--*k$(6soAs8N<>vX%in9H3r|Rd))2$Mg%~ zy5ZRL9HU>xf&+TKFu+t3-Z4^fcjJT_J{G8{;G2+3Ose2&FLf<D(ycFfAX1^TtHS`O zo^?m>J8&1Z9j)NHl-GplUP)lra$BvXU$lgini$$68QTU$X$B?rO@Z(cI8Qu<Z>b8g zX2jnP$|7IhZIb6o0`atGK6a9@uhAVdhqqx)D7i+$1Hw6K3kEM8DDc<Hd{}014HVVv zRsu2HX8?e{b8hk%t+0+*KF;kB8Ul@#NuerTiaCT24HbB<W!;3o<pxfi^l5WRNy7`1 zoz<xpk|D8N@*5IggO9w1LchlQ@wMx2CCdSnpnz{#dpQkD6M|g&FzFfu&vm%ZU3y=l z8IzDIQ0wBXs5M?z{U_Ped_(v?g1ZQwNcjkt2}8VS<er`hg~W#N4}_I>!LKeAU)I9> zgym3w+WadPYYMJvOn@r~!zT$EokS0!)a7P0$A`*>0xMkFVgpxtE}Rg@yQ}wg@YKUD z3wzEIUW4Rcjc}5CNF5KtB1~pYH~NjF`uhnLnM>ZwlLwr|aM&fy;<=nlYyODQjk+{$ zAP~iM<vv$3rG6b<#8*t`OmEtrfnPS2*q6Lm$kS>)8Km0Z*s}ruFBEZd6D~jNCkRU7 z(yH|KK;)y3zx<h6OyM?zgz2AzM_VB<o1D>1!=hK0mI4#2gUcM&!sacTRg8rXCDpVT zNpg9lp+^Z%ah!#J@V!j@#AX|}epB@6QZEQ%cR6=HMJ3g#x)PL9*L^9*197F3REl)W zdBt72k##h^!=e*gaF?`hafiPh)-YF7_p`Nwk@|qz7IeBKSs$MA1fHwq;bZ7G9Sc`& zvp#B?Citu~6_v{g1N45ya-}!^-GGaQ>!wv5AdtNZ`<(UTA{b;vF-LK_zZQ2fp1Zui zI8>9TGo>La3?8k5=(K{zGtqOi=d?b-|8Bw?oQ~p1k{5TKZr$v{p0>bW)|Ey1!W~-w zd(~OQi+pO%@n<iI<|n~fOKBTPOUmluM^zgVmCGHD-epKivg@>Oo<E*`{^(%wC5pYC zTlpffP6Bm2<dwHP?(mF(`vuosajnWHH|@{M(-Wz1)?BN4yU(c#1f|W$`4jvA+&l41 zHc}t1Iewu-*{{D7?mm9`d$+PO;R2sS3&gnP!!!8P|MB%+QB6GHyY3_;kdOo>)X+3^ zP{e?M6v2dMXbMU%3JB8ufg)W^AoLb`6QmdEMS2NEItT~~f(j~96a)(*q8!dT|8vgT z`(oeC?aZ1r<@w(4eH=Ik%n)`#yuJwcN2wk9rZomH8(^f!M0@16H8!>m=J!WA^`3|Z z4w1fmbX*<dj9W=^U3am!;_G9L3nsGkS%c=Goz$SJcYhMNASGWm?0fujD#W{l5BaA4 zcr+@sG5Pra2ebbvf*tvhbDGrs^^z#q%g2)$aZVB|ZmzL-^PV{i(!jSi(G0YWR!b*( zOR5_EoVA^uHBX@2V?G4Gr(Nm!112E=4nt`%Hyub?=dum6v>tX#`1I8&KdCBkWBnms zrq5$Z$kp~1uTOfF6L{9P#GJqXgC6#QHs^>H7~-Lkx5DTB6tVlv)JOs8r3?moXmsUZ zlL2Jvtn%q^UgvC*WI2K!E!4BuiwEF)-Av$S#N@nZvQ{WBe!)A~`f|^z(YK^Np~#~_ z5E9YwUccoj@zyG{&??6_spNBlv9-6rNA+GaO^J_9z2Oc>I-wE9i+o^vFU}U5vN}vK zxRP{tJU1|^?VzIcJl65W$s<}(%cpqU7w~I+vXAND*QU{pB_XFDgRFA(TR5y=lZ|zy zsJW9)ii667QuCXa^h1t4e$Bbe_2Xzr=}nX2gt`v6&y_I2D^b8R?v<$0OYPWQn+aM` zS?WnI(hvrB;!fq{$u8b4ba8#(3Ex{8?7PHZt09&}L37&a-;c!8rYl%>pLVHYm3K>E z!Ud2mAxf3)G*jc6D3T$C%&V`h2oC9D&13I1^d+)<8y5Urcu6`k`cxqJS?>s}s{lto zP2;!bEZ~4xC#ZzaF$?!+79QJ?;lTWW-|)UOl6omT7?i!Af3EX%gZT^OLH$SuB0Zl4 z=73CKc%_C^hLGmr4w6Qzh)8@vWkeJ=$(fXi9jA(V0CAc{6}$b;+52<3c8aqekDbq$ ze_hha7C3o3SNaszEZf~rcEWH4na;g(3B?L%cZyi^=|g5j%s@nVpl$5(6ZVzo9y*|T z2zL1b_Kqi*W=&)_F^T`YFkOwkl7ltrTXJx{M8=sx56UcpKu&TZmkAXPiHpSRf4bj4 ze#kkb$kL(KI5P{sZXeGlC7q(RNQ@3q;E&~$>VC@e&`&ec!{kW8DIZjC*SY8eGg-Hu znOH8UH#lQ|LVl;})RO*+EBGV1>W1NH1nN=iI9RJrU5I#fBzJtC2vs=_oJwYYytEyF zR5ZXw<E4K(y><R0;{1oX%_w%y?%6~7yM9)=%U+<fOY%*!g40gl$djDANWgf9RwK^~ z7oNdfUiCM544Z!V@*tb^o;DV5BC`bQC)EADKh(|rV$k18ekCfSfQ3Q~>Nkr8As^6k znP-!e#@6`c-zGgYYW}Cn(+ij575nJdIisyLnqi5}Ui?@ho>80C2P66X{LQX=bv2Fc zB^M;eG2H)TucDh#J-hHH=HAy27C`Xai^<}5kxan#iX*VtA5=%geSga7H~FfN3o*dm z%<8~WBO5#L1|0kgGRNw8dYcdFr++(lvG6HqT0-%a3uoT#WrDEJdTq=-0PjW$If<>n zAPzr8&FlJtjfNNQ%51t^TGx8(O~5R&QxT!wjl@9Ez#g6uhWM3>RhqtTZqE`5IFk0a zySqV`B(J}{@9vLSO(u1&x~=;UfTKnZnSV~XU{<YVbxl0LN&79n$5@MQ&==woTCfp& zqKOYeO2kr&6U<RQd@jA4-?l%5;t}%ov&_P<EuA14HteRrUB)oW&oj<uQ}A&7_u6u> zZKitd^7H3%;@2tJJM|!2ZJ!hOH_J(Trurj@Zso4kLu|)Dc-N=NiE59q(FJ?_bH_mG zlE9sJ)!*7QldEcGISP{GFMfAgS)0<<|NLPOO^wH56|67x>Rc|#=I5|qzHy@w?ozRi zHn})?otIs1%bNW+Cl)$yk^ukYVOa!T^?oxu-SzhLq@e7pl&J0dO5meI8y8_1oXS$x z4F<9UK@66fTC8|?esbZ&V^#2u{a04V7Yj}4w{btrU-NX8tiV>_K9Gc*O1Q1l+26nP zZ~g^S*#HB9-$@UT>m-X=<m~VAY{xo0e3E;ksO`=_u_~LsyZO>DZtb!N{JD4iH%sUq zXB6Z1pX)*ON<VJ10p@_{gW|GwC<p*YKZK>GmPvp=$Xa}taQRW#ZGd4FwKJY2@5tr| zVZa&bVR-DFDg>Z^Y~W$rlxhR7cc;raPZnFf_+<1*<=*zkg%@jA@=1Zs^bromajM|7 zhFey6*<iA#h`u(tUMyGbK8&Y+#wD@0_6D3sp`3d~IE)g&<~YW~z&{0Ofbx&EEm8*n zY^X?)OBXURwW?L_X8E&WF0f=3oGyMO5!&J^tx_WXB1S6&Uo1TP-DRpkCsD%g^$)jf zVyKv6IgH{#z3M2?gl0&u(xK|jg6C2&@54bM)*6wW)8^s912O8jW`+D#Xn3dG{@N8^ z>Vpn|f_o+NJv$W3%8NKkdO|$E@q$U2$u{2+a1IiHU3;-HE@_mFH*K#w2jGl3y@^ni z!VVF3v9TAAw|@P+xHL5MIevMPbC?kJk$@0URUOd6U(hgIXA4IUumL^Hn!{C`_fBDj zRZplQ*wAuuZrw56plh`B6F?7@v|YJDn#ai?nRz%&@90V7_<qyN(jb(F18(b{y<v1> zIXSGDj-kBP&#o$b!?sx+7b~MmK83m&qgBVt2PLZPkWWkL0N?hRo@c?Z)1}I*vm@$z zV5t73FyC26BtTIhlV8K0U}91TYEsBEVe{isfKwDwLQ0GKp6OMC>S!2XPF5UAHdj0D ze>lzBD0Z}TM*;Cf-ujr|DnC#wk5N?RswrT@UPZ9)#4sR$%I2Y7Whc6ilf9M^`?6KV z|CFCDZK*D1DqLc=TqEmICTb?^miq8j8r@x*k$xa|?|RVZr>__(jx!GD!kR8fy$tKF zDnI4`n^7oj2%eWB=UrS^!aMRIq3&B9JfC$l^V;o!Jk8lrR_e>T&srQw7$0HM=F*-- zwCEF8&9E6KO9yJVrSf?oV7#p~<g~sf-s1kUsf0iA+1mBu6!RdrNB??_=aTo+My^tM zMfUUM-A12^NTweLVxLsS^b=w{6=0nj*FB>K^7p3d#8p?eD^_oNCD)$6^LdQlh2|b! zC3Zwfx$|rI3d#Avdw}zj;2d{UC@%$W<z6Qu+c6#;+jXzg3SDkLSUvFr9Tp|RcY0G) zm-Nu_&y_mxH4aeS86HL5;&hMRMtS)LmfGIkns5L(2HQo1j}lCm84#kTbOn1TWF&w) z<3Z4-p1LZGYKb4kpXT%Zi8$j>8KRWqeNNd#Yh-RXy#J0F`qm9e`SOVvjOLp%wwvdp zOjK^N&pyCdIj|pnhz@cz=Xj<N=fL<pthuMefj9wUP3OO%_m7FfQ}-lD;G;du<B#Y^ z=-a}X8(D_OeLUk{B(cmQs}KNW7DSN5zG|ghaVl1OTqk=^yw~os>yI-uiUHn+6LDmk z&v9WzFG6Avg}VmqH727c@W!0O%Kv;6*l(G{+HhemNQsmr&l6eH0g5{v`s|)njr%pi z+c}Z`oHGLqxMew1VAT84v*jdpnj=%l@UsZTolQ-F&6O=BF45ijL?Tb<g66jJxr6+# zRAxTTUH$hZPo9b)i0f1?gF7(~51CGUd+#W16gb+)2Rp&-W@{+n50m<bwpZuG@wkV{ z>dT5b$j(EzuH%^D{Kft}Doku|8c+OQpy_fhPW?-tqSsHulneVEbS6d9bh{-r-1wQ+ zZr^G=`{j(sS}c<77Ff!0XXFO6uqYrK0Ag4NyvvJS)IaO#)5y^=(A`u+`=g@AA1h*` znIXwMt@Z?7Z_<Aqdbqaj`3}!bR`nnKNWl}y!?MSDOCF<7uJ3te_dd#5JW?w(^!p%{ zMH@kWv>D!)kfi%N?%>6g!_~clt_A-q5__Ez?Vf6pV)YbzUTQA>CYx$!xPqrfh<3iQ zz9jv<X-Uy)lBMvyZ)9Fa?*9}VgsYvdKGpxJAZa<^W;HST%%A=qZ<-yAxbeL<v-~v5 zA-RCK6aZ=~rba~yGu>q6PRo^fVH0Q7$N!Sv5q;>LRa|LvMWmg`9J+D~p(3p!@G~<T zQ5Bj4BeK`gz`_Ae;r$C9Zbq>RA;mnvcYvWh3+fXfK(PG1)hpg@;YV-E>&)%$<r8tO zxM%x{QoFHX;qNKTKVT*jnoZH;w;a!jU47{eo73ENl<!SrEeItBS721XU*-{WYc3Q2 zFOc(mqCbG=hGt!oyl}0J<AhU5M#)!Fl&T&LVIkF{ckN`a#9ZF~T#xeaH~;OPlF+|i zZT^eTRqqyse$QO2^izp<IJ;!+!zE4phR!f+{$A_z+k-4M-+1{Q&h@6xCyV`RtL)wJ z$o7=)#f(=Y_!!|vxkNZxJQw+&OQ=B(P8g|A48?*o7s3Kgbpk|g%};I)QkSyyz7Ml_ z!e=l!_7%B+C5B_lmA<d9Kb{<ljve`-3&HN9JK7ND|H<=KtRL};s%ObK-|)OK3bfh& z2WN!Yg{2C&vI_rAy;FcOI@_<<hyOav&rL#81aMA@H+T@NXbz^*kEc@r<K3d|6!;m? z(+VSIM8L?qKZ_#uoFAEca`zkD@|}}>dY8u)Xm#>j=WH%&A<qDIN1@?_^?bj^l(+=# ziFp5PZj#b4O6ClmMZoEzkvHaAUY*;xxsxpOf}h)F2soKULhE~N^R**y1K!(2`qd0Z zpC_o_$UGvC?9Gk7|6d5Z6y_S&mXTo`==W?7PmfWe=F7j!3SU{&Z}8Xq5t2`<mVd`t z*6Nxt$Oe@6;=A$};W9$`C`2(y)qBp}K6>!1B)jmDZbC0Q{pZf}PGxigBy1<y6&zas zIQgMT#&}9k8Yo}F*U_4a4Q4#3o&f7$dBBTY4Su%B(5KJ>3dxuV;Zoo$RT?I-H;1JD zYl5w#R4jCqXO?q1Gi?o~H1FTm;AHxs9nRcf%4p--<3)Ugf4>cxdHm0x5q4{n8>xci z|D}9o!JecBFrw}syeI+i%gNcAUbBk);Sy2d>d#B=-+Eu7!0+@8N-D~~5yZp~2F0*o zb(igq4)VtPg_zrhF8p~@5w?{7+4h8L=gsg?9L@?a8R+jygeJd<YybY}`80>O@#&?v z#rfkc(PvIW&8J&_;PtI0N@Hq%N%vkq{IGVUSLgCBN_V_lg#1+!lQ~g4*J>7O7(<fv zIFoWlSvW#f+Vz@!9;dW-q2w_8-}0zcY+KsA;&suB%$~$Y_SJz5<*<N;oT$1^PK{Ul zeEY2Nn@?oL8_v?e=na8hE6!+KIX6dKoK<D?pAXR?3yE8*2yC(l->@1-0Hn~8x_Fm( z!j};Oq&=`dlY1%}By$8LQ72m=w<@FffXBkh&_dC!86t0(Rp?@C)zJrm&^s|QuwGps zQJLXT*@47EB0^y%xh_YrXkP{(b8sObIHIc37n177-jmu<KIKuBOqBEE9j`^&@PGm} zs&2ZqliG;U=8BSo0fKdC_Nud-NAd`nOl|d>ML7X2mKBeL={=d{B<c=<W?2$q+@mU^ z!+c1}L?{7tV%R=V-lqP{20WRmV`soBhSz?Mk9Jk-mD$fBe2lst7u~bL?^_UOY(Qth zsw#Y}v5t%8##7IGHV9aT+ZPe9b?Uy#iR{&iS`dW+^OP%w+}Zo>GQXv5VaiXapcOXi zU`&Zd(9U)xWmAU2=M_8`qeoVFube`%wo)+OP-8IaVL+tXz~G4{-D?A7ft*o81<^!7 z?X3AkifBPNgZjI0D6bC9eN!}HiTru2Y6cN%`&ouMKNN0BWj|IO+aPEP<oQM24BIHv z<*={-ogOWOQfl`8QA(f1Lh|nq*@_(J;$$#EsqxcHG0bjx+tJACyVOgW#LzgsisJsz z)QrG&7EDSCJ*+H!ze;eK*G?@|ct<`pDjFiz9YTdJ7?1g?(CbAtXrOAYCHX-N2Q{A- z=FJkFqu>35WO_(KFDe65;n_|QvxO6L9UQ}01one`5?7R@LW5YQA)^98fhr$A;3THU zUn1gF9&uo1+QW<$_6i%)zZlFOcJydR1rF=`4fiu6RWR)%$KUhADhSfe_;lq<)F^Jr z<W8(+{MZ-0$I&e>7zO}d2Vg`78duMTOfpUn_t;K^k;AVmv#{MPNjC0!7IrZyhbmqy zICBm9?TD6^&x!a(s}zqWt*%Vu&P&n)SaMmzF$QNsrYc_0F8>{GnWG`EUe!5nIu$l- zH{Goh597tHOU|i92`+0DEe;gieJ<RA6s3>-%0~X0jlLfCJb4}Nhp&7<eD+t+<b+{u z;BY^88=gH3!mW(B;zri+Z4LvVgEz<JXP!!$#-PR3^&5?+TA!KAAu1LcRBVlN5U>L= z6Y*68U@KgBHvBA^!&@8SYS`HhyC}5JF5@;;>p>q%?G+3s40|Mp6dPpGsmkb>P}{3Y z;ulXZ*7bge1M}gY^KhCgC5vLRZ51UaBKjcfnLzkBak2Zs^aQC>N889$2P2#x9bJ1A zTj3uhs6H3%pWjgVg=NP5ni2QKmrrIh5ww^o{1%eFrZ*llMJ?EX5Ob#oKd6ghN0tuJ z*0UKgM9nO+Qu*#sI=R+=`0|hBvW+EEhb~>tF0-jV^=wQ1MH#)6CKF}|)HUARF2y{D zXqHdO5K=%m)1x=WpF8|DXA!($))f8)QZ#oi>bSxb*_e#fLKNYLAoX)u!!JFsQC%>L zkO_;WoU4E_gd0)o6lQ``oC(_>e}SJb8q3Svr=>Gk{+qLidNYf`o$b?W@HOKI#Z-qQ zsF?ZV<%P<0%NJ2XRv|`WkMfgqWatXwR_R_=^Boo$@m5(Sl1aH%IbBwdYA396-&o~s zSv~%1m5;G55V9^jV_l?fU2J4sVrO0IWnFgPx;);xBG>v!wRL5eb=8D*^&9J&E$iC9 z)^!-0dLf&JGd7LtHcdu0Pwi})y=+?U+qA~pwB_2gSKD-S*>q0WbiJ|Z-m>ZWYs0|U z_6phdow4m#w;eFDeP(An=w&-}-*!0Ob|lw!wAyy8%XWOicH)ig<d*I8zqV5tyJ;c2 znKN&8`%PaM*)jbdJ5HDj|AxVjE4P4Su^Kbr4<$eW#1Q~N2$Jjad&2+)yzOvZ0UTf# z(0@d(FMJk@JLkSMTwgSlh}Vh{)N3dnNs+qtWL(+3WGsVlbM%p3W9dYW^4-njq%4K+ z96&Uj*J~=DE+VI#vK#dkmj^}9xCXc~r!k_88vn;(Y>zs{rSdYAR_FS{Pq4DNda*@q z;YpP-2s3XDn6sv5x75DtIjeK1{MkfSn-SGwzVC3p{=*O*?kJ_4if2Zpsa;N|t2C?? za*W5R9kw;O^+f2olkd0R8<|6DHEKy1uei@Ywfp?m>)d<0cPGzYX(s%Z|N22(&R)u% z8Jq3%jHN;Ma##Ckp1M{HQ2(agKVb<HbyU8rXAGQMBN|Tr>*@+l5|l@L1c?9s{E>IK zK)fqWq^Pbr;qkza6_;fy8cU&vB9xS8AOHvgys7)V43SZgK!HMqfR#vu5RnokCcnNM zU3!MWAfATSImSv2lBc0SIgW@+f)OYWQxw7g2pVrJ%B0Y+UKo2yLhoa;ywb+Ulx;ae zff&z0nVu3FK&~D;j2H4#ZxFARJoKJ&WB@ur6`!&_+nH~L|2spxBpiJhhJmxl(1|%A zdmAn{u7=i=0XhRDo}cujKI0Y3|Gid3*B#}~OlsY|A^{PD#D+7?HkB3UN1QrEx~j3u zeumfgE(!R68wKKu29HjCu9DEp(otlAQHD=KLRQFt_ROg-bp!6&3>L0+oaTAR@eB|y z!E<`630JZVF+FQWeB~ktB@pvaFe0nknljWYd$zPv77)dyLW@rW`4s5YW?+aJ0#dfy z4|#(7kO^{hnu%b01C_`sQzu&YSLw^wo+GGzD2Wq2$7ekTa>1^$pn=MM{1B_$0Oz$s z^FdvqPz(Up%(@K|KAitHyp_C%6FU2oG{xg7=#)lu_ALHRv>EVh8b5dGP?njS$y?4g z7$FwTu5EVb#~fY43(5dyiBm5E^{!eAT4ublp24DKNf36Ux--@%Tl?skfM_{p;0EEN zZp*D-M}KjzCFAU?eJ=OJn@b}8cFvr7aGveS%cIier^K`_FJ%iZ!qhjP5VdWU>y*d# zTd%Q-_mi6+m(>IriZ*QreGap@4Q>Li9>MTZ8{a?Mi!<E^Ul})xmv#ousdH^&%_s|I zX=lzFf934jI{a~aacOFi4cKwpS;{!m`)fJ!=r8OMglKtd{iHTdm*?8;?iViASLP4j zy!!eZy1!O?^iO+xj8R57IH|d(C`RoZ*3p!=PYQKrY$0I}FI}BZ`f{naQg}HO*SXxu zL8k-;PKA9t$VaRx(y_^)1B;w6NqM-BN3|}L5Vz1NPu7BE8bi*>hRNMIsZZhoW%> z;8A2iKl`Xh6xmQjpBSJeuDTnIUr0e&A)cMGP7<xPCa%>CKa=J7$b~>sc#j>%mX>1H zPKGzp&bvs(_T6~zxFW$d@{q*H#2MB)YoTAmLmCIWi4=4(o<;Bfa~KOnChGi;!&p*< zeBJn4a^`rk#Q71uG|!q8Od*WS6^Rw|cH)<#(n#b$kQfloB`o*hk_PoG>m#akHelHK z4`BdU-o&@>$1+Wob674>?fHF5h#Cd3#9^olkgucDj5vjxO^U<_FKa6~VQ;_I_T=Tu zObX)R@s@{aY6-k1N4e3DC7wPHlBoE51kmj^%^kOZ0~)YLJhJ$Y2}TaiT6sHI%1pjU z%xC8+OMAK*qbRmTFiI8vjcVWN#NIN#sJ{%1Q$KP5L*ry^h*o40t5cyMRf2~gG78Wb zc@G;PZxB$Xh?hxF;onYL^!#b6GNa^7CPIzx{qwN(S&=sZXnmL0SQZ7&)S|*$hQ-;* zfa_fm!c>t>LeQMtwtSM^{WzWieUAHk_IQ>qCrf`#Gx{TXl`s+tF6&#IU1_Wd=z4zb z`{=9ggP*k&OqD&0!F(V8UR{(?l_T%i{GjSyJw3k4Nz!0p)OxQWbE4|j`LTt`puNU? zOttGJgV!_Jdrjp=)$SH!uV1$BJ*|tc_H;2=e0}tKueo)i`nLaPA)?d^#gkLLD*t+I zWO*FHFez;xvr1b4t$ALi&P@fDoVcpF3r5z}xYwhS%X{G`=H_YwhAIax9#T8Y6l?w8 z&FKDU|JAh<|23UQ_}!FjX!p;bRifX<-u*lH)dR5AQCJL@p_fK6KtMT_w@RC}3V;0@ zjA+eg=#YiKjV~;(b36y3Ts~GS@V+ECD(;$KbM^<MF4xCcjKAmU*ndVysE>0o{J_7s zKd3xepWr|K;l!(7+!|~RbZ4<K>ToDGL2HBFD}u7Z4e*d9E=B%vek<M*&O_iHmZ1xx zs5_zDt@$titB&J!o6+Ryz$0XCk*dEZFC3j|u6vgAee{#cwV7nU2Ttjb<&PJx$&Wus zcOozut!oM#OhsL8D&(D5*Ht^1rYAHNOB!v=RkzG!PBxXEpKz;cgAVI%`wGSyzV@Q? z&KCNKo+0OM%I@(2#mv5ywNeun&$Hvm-S_yNO;C1;KF_<^n(HEszBmf}nNJmyZOEAT za%;$wN$Fm5Q<>40yUm~1^AVoGjT2r%DF86N-P}54w0$S%&;R2veuEEfSoAasXnD7E z=Ie9kg13ZVC|4-}JYZUWyC0F&!=zEE>nDb?#_zj_3!}qRoJvBjM#upKpUB8@9HvEi znC5_XmeTsbHl{p$soT~Aq4i$uh-E=uBkx;!$Kfg=v2EPt^7rh;!%xa(epl{J-hG~o zhplBs)>WEdZliarm`z-tXRz^Eo%?Ij6QX*(N%)=#{5{s}d5}|4%}=so5&twmRLGVC z|BJiXZug7h6{=ycsYRU6<T3N9H*dwNIbdl+%FJUM|BBrS{e0YO9oZLT_xl9iHh;Qs zA%mlKe^V+;gifbP34G1fXw8zS9lr47w~UKQ8K3aeefVmkV_=R`H@@K*ef9>>Ns0e7 z+6hHM00RaDbiWe1|M$N8S?~tH_*rw*wf#<XVtLGp_wq@N2Op~rKV6!6d0b7FQj}P@ zaqZ|}{(1La%k%p@Hbq-+*n5ulhpznlmUDEtZZQh7Lc@P_JdWM^`m5(%PY(4(kAgA1 z@9#Y=;|GfmkAPuyBjSG$OMaLoCC`U~SjQQG{~fqk&F$P^YNb4uqjCjM8KUr`NGfHQ zvZ-VtxR1jtI|%RdsxwT*T|=cZL+?|4E7DCl9Ne{FFj*<48><9ZD^+s<qkD;SiHM*P z*wojxnY6-~9KtY6uu>Xm3HT%rVBX@vt|?5HH#lD>Pk@D5Hd<VPg~`=pt}BBT_TW4J z@WYReMgW{OlN^7XKcF+;48Sf&Ix-c(F4si>b#R??<ik|vV_m5(Zv-3?wn&H+X?_6M zN7^dTB(ae!N4-%@Cc!Oq(+Eq4OZdwGJ%VZFKV(K^PguCB4~o+S1{DsIDd+C;M*W8e z^_*j1a{SO<Oq#1B6Ye3?3N7_xOgzO8@P^ArL`FOLnkj=0lAwz+$a$Vt=pRGw4dcc} z(1+s;rZJ{NU=0GmO2yxX#J}F>eKjAyj7xYQU_DQW{ou;=W*JksA2UtI<Od`e?Z!XF z$HG@4cFMU%=xCT6ONnLZ^gj0xj+M5P$UBT#&5U>Jy<+J~|7sD(Nu_(s#W9f(z)n0D zBq{zp=J^yTfaJ9#`*B5M4+0XEso}IK1h*Tu1q^4>!@OThelQ)jY6%VvgLd9%rz1&_ zpqEUTM&F)C9VoMKjDVsGiL=Y}3vC<=`H55_*mxc*l$ENOlma6mDk!O8%AmSb)YU-F zxmNJmK6A?s8n=+9S}*^SLXX=|yT!*jZyaxF1s34J=R~@f9;b;k_?md{U>@Zhn4z!| z`38*WG0k9-^QTyG`nCC)WM-;Bt_{&M67;w#5y0JL)bpK$6g@6=sjQr6&X-dtyQyHu zUm1_}I88S)d;+soO)zRB*>!H|b@sZKZ+VRK<`8z>pro9T2<PU=9JyV$s=+{pG-nN9 z{8Re@JCA8UN5C^_P98;2<kuqwZ0>B}@v+Z~z+CxW@5PZ^x!v65Bfh*zmAp?Ix}|}6 z(ktlAg}m+Gc{_ZM+xH;fqB)e(?0yE?4C{f6y}Tl0N73oWYthOl2eCO8V9W13Ap0@; zbw1qznc}ars^alyHJ>M_0GD0B-(DcN>G^V@0JmF!55o2u7m5ZImigqbtYx*!JxYjn z(Jm-_FNulYz_lRnLw$lioi9k7cBv{YTIXfEQ_41W{9VoLl-2Thbq&>Hj2Qrc34G!G zl_DnLqE9Y`9V@JDx;831x|kt!&XgN5KU^vsYx=^FVOh#djdp)sdIAeopqu-zma;&Y z2;RnOgfd^&W0^4&N-7OL1@Zy_N&L!rBBw8S)%gXh)bS1j!QJ(p1o(gzP+ATp6qG;c zM_r9^J#BB~JAg_Y&C_}9n!-x{f&^NYeF+DFR9&VYrkoi(=a!FejVXA=PPuX~tFpdp zCab*LAZmyRCVHbf7*EcdWJRTyPx&g`i{Kcsz-HFPbZokeZJwWSuM(i5ns)--cwCMh z&h3;c^X$i-5-b4TqXD1KQqQU%lrYcA*#w4gVG&h3Zd<1w-;rR+n5x=1<$04wt2YwW zZG~-158Uw;kq2)l-V4-oVrlfh^`afDvuE+5=i_2f&CI9|s^Ab(d_3^(e-tD%2m9-F zeh41q3C2?GYgkTmMtfU}<=5rIuE~yqRYw3Tyr4#kiue$PBAYj2rW=^Bs2Dm5dXM9R z4Q0X_yT?_}SAY;d%@Iv+LX|hlCOPmq_;Zt<uDKzBDULHHSnTV9$|+rk&zYBlIbGDU z8mC;2UrEXW<##HvM70*b;FbW77XF-;kj0h<e_AL4t)XhI^!NJDby}lxT4Mx4?eHu< zi!GI{%@2c-!p*I|?ktupfS@1Ok$ZY3h@{xGk$daXg9|3i+Hc1oBJ*vB(pqfQ5Z!4l z!|;w=kCu9y4r+`ooYd}*Y=;&+B~Uxc7dz(t!YWc&;8-Mm`RR*2uUys6DS@sTwXRv4 zE;SQ`ZBEPnM#~7iwcVp@`ADGqy;}FjKeu){D$>kSRy(@$O6(tccz?;!Q{?XXVbil0 z+_Rt4bI{RqxY+aWPY)o-fOc}D#Ty$-q2^AVz2@Z<1BevmTGA;dHyx(a0fpN{ke31# zrnh|EVPldjXL4ZhOZqm*vrC`>W|nf%wcb8x57S{EL9k!`LcfA-zfws5n0ROKsW#=M zevQL^qTqn$g#m5b0o{-R@}mL$&H=-vfy;*j#uu!A5&Hszdp8(;{%Y(e44*v+?z<n$ zz7Jl1Sn0{!`^+SS`ge+*d7AATo*hbM`!#h;Yr&7peF0<a05C-L81g+RrU|fb0l*J? zcK@-Vefz;Xm7Yg@JM8Wug9(SjbitA23nNiE?2eCGBpwYyApbut0FG$^<$t3E2)HA8 zxK6l_72r|*KhOeOX*$>cN(+`$c3CL=d4Ovjqw)Wx1x*$DS44C#*X2Wi?0f*P`eyWL z<*Qoz{uo7^S+O>nbMT2>rHRO5i}wc+@zLaMBF1cW(=N8)>)Rd*(~Co4O^-_*(C@6* z$D3+z4AMmnl*%pfjsQ>TgDO>0-^b^=LYH7h?Y>Se5+`%6-=C@dFoe3nu07G-?Dfb6 z`DxD;!esI;)9u}f$;Hs!587MTB_=ynj6fhi5+)ql{{1t5<)zxmTvgwV`Tp3WOIg$~ z1{xSoyuqFl_UD)2XvguoP1oN)JnZ<{#GZ#_C?H6rP*}KJ?Ws^KupElOtmCQwbjX5C zD72|Cz<ph6C4x;30K)OI#1*JWGWmU^2uG@Lgm81Ya3o<+>O%nQtm}vP^ONNt5-!}1 z`jDuyC-u>U7424RM3k`lkYxB$+Yt(g;hj^jUPi8_ncWI>PPKK<a?Y>|a&yjf42^cq zvdP;h$#N{!`;_h0yil5DTBui+6Y#deB`;)q<WstlG}0-B)+gp1enOr>VTyUsT3#3@ zaZp~IqPtmM5@Y^asyOG4>PAVPZp=nmR?O>-^5W7b6~*P*qwZxV2agWcBje;xeXg$k z#QLNrZ+p|DmQkwuq#BJ_W)O`<#LLpdmHu39z-k}Uf?0Eqt*7(1Dz}=K{625BENbpB zT0f?HY`1;T1R$+nnm@}jG0!TOn1nKKeCd)9|4ivP-242s2Z%gPg2Q+{cX|;P_9SM= z`K8)OgE<e;Zmta9f_|J!mE0gZm<k0>MxwtBi#)tw3=t^v+-kpUQcj5`Jht2&7pw66 zKB0VVQH~v&w*37$k>&4qB1ctD<KSmaym7-NyZwfIg-e*3X;TZKtu|ec%9<vj4EsK! zBmnNsJ7x$qBOQ)t4RieGC={ZO$TLj}N=*9a8^Nuyy|)6jM+VQ>O^r#~FW+rn=+iyH zWu*M>?<sXU(<NNVW0{i()0QZM_tkAWKA$J{*MQnsT}c4;lktAZZ^8uQ5%%vafN(8G zlZbd7B5?M0%^&T&j_r<)_jin0u<X7aKj(l{`ra#?^gp%Mp$>KWxl7#17yzhA{kyHZ z9eeP7+2s#_&2uuo&=G-3ZPpq`(Z2m!@$hKV^6&h?Lb7i4p&LNs>!<%RO+$Yn<~sKI zrmWeC?A-fvPk)-w0wwL=KziViC?t&gB)~-4WTEK&ph#xn@)1~Q$=iz0G%3RZR*Pd= z(7qE+h$}$bDOc}8@KCFqm3GrIjX1IG09AA$cytqYhKpx_8%c$^E))82X5|#lM|haL zJ@YBX*?U69Z*^Wv_DcB~1OfAa3{I1&jY2{L%TTR(dWXc@vb)#gJ}|kvXfQ)5ERl`m z<9+r{Wydie-UFDX`7VcP>n@#(T6D4mcaqK4#|AS_K4H@`>=7S%F)HL{QoiNLTJ+~6 zy5Wh16J)xEU$S+Up>w|cTGzF9j$|vDUPMR)78yDdn{cf}Hl=Xb;y~U8jk*P+>5V(^ zr#NuzJ3p0a9lQ0(NuT$iSmBDKtZzkZ_PYM7jb^I}&+FfFEc-txc8yFN523T)C|D@= z>P=qBev$n`a80dI?|ESQi`@OrGL7#eN6+scG(MKR@Mh+b-c&AEMf`UgtfqPKR2YFv z3mLesDg4?vjI2<|^=w_oEY*a@L(AeJ5uv!_f^3qhA#bu(Zf4p{O8SP5d$xrEuW?D} zYc9!e`iw+e!wcH{XS})&*%;+`KL34G*(JrzD;SabQVGSo-r2mQPujC0a$a~JEuO}@ zY|}9Ove$V`rO~O`QqC+_H=DGDlu=qiV~v7=dx^CE%?R_e&z{yOdR4A|bhl{leyZ>P z_j7|hi(<*Gr^2*c93VfGG|;zI5y@TY^z+VKYSqT+8@W}t?q$7lsWz3dU#fCtS${b? zIM8&XV$s#&wB{_oy9@%5*0%b;X#vl`aabjcwC}R`_Q3CK@>Dg6phAZn?zIl9kK$6s zmOh<;$4|!B_?8*G*_@%#|FZ(btH$1J2mR_;#?%H38NB_L{i}1`s5a=;*xNl0$&=gh zwIOQ;?+#x7>i%^AfAH&nXo24?Cnj4dJqoOYFM3J09LveX`;iO7H(;TQO}3yoaq;3P zOg~yuLFld9N8tqEi5zGPL_h}YqGk5*D)Ho2aibl?8D**1n1Cj$GmQU=1m%~b!R0}g z-Zw_60mrN<wckNlUJDp-1QY_rr2Ski==;1laGsf|VpmrqD(N)@5ODn6hi?&aj2W00 zMGVU8j2f<#ukIf;?~~68AfOB?jlz4jAnf*BD~DK)CH_Qdm@Z8qQw_An-`hs8G*Ylk z?8{8euIX%}WI9jh?`~d%ULy7mOoN>UNo;P=DqI5PPC5nS7MPv#WI%m?8pK7y`<xzz z)4IqB$nhhino+zjKB;z!(VrSyXbC&K7#P#QMP<jUC*Al88$Mwo-FQQuhBy54y5ggJ zbBj@<nD?K>Www_8g%(U~`*r+zvy;%$xn}e=Xz|b6{mGW@uj1?X|JcZezCE4*YwSb} zth_^<*FVWK=^Y{ZaYRsoJirHyjFCKi&-%4rXPv^5z)oXh8EPH&NnWSTCN9H|%Cvge zIU?yNVI!i6ftMxzC8>-ZeiDGtbQErb=2wbWmDvx-K*4vKSoRuxC4V%0(l?n)UHHl+ z#0>n-oor604Ws7=I?Tc=<pQ*IZArxQUw}__j*!^d6Np!BY(TBSef+hH9ZM=#qcn+c z@ZygVvDF&Cx=#*l1LeVQtQzk0JpKzpAt9RcHA$hO1FI1kfg-2m_Zbg!MKsoeKZa@i zju3qRooW#xEcR%x&PIDV``uxWkPltQ5{6B;2q7&!_(8L``}zA;myYebK!DMW?>Tw6 z4*%xc!VaTc`=zqIyLAxvqg$ldrPEDmipg&v@b`;*G|}vL^vRAB*q)P!qkR@f|BfEz zExWVilc|aK@1HjL#k9~(22TcTFfsmlpG5q5))2~#a1w-0vv2X*Rh8X`72J<y+(-1@ ze}3s<wEsh|A@DxkpUL&V<Yjw3Ckj&%1qyixtw(gd3SQ=YfZ1i?BHz2S!UnaZHt8T` zEkT?scw(K(A{Q9F69QYIz>@sfOaf$FZ>Jd}5xb#K2vRoy<VOGsuHeL_P`Gd~2hP9Z zSJ)?A8ZLm!gbiaVa1ufQtjgedDRAY|!`1VkiA$(=i?={AkC$%vacb_DFtU>w;4Rm- zEvKE_4~J319Hl^2DX?Vi9{>69+m^>Yae>7q$gE`toZK-j@S*LtP=j2-%gVv_7QQ-> z5q~VA_8tB6S@^T_k+I4kNs1P?4knNzt%qsoV~$a9H;fX!ITY>xJ+ia_3DiZMP>SK% z4Nawl`;tL@rReMAXjnnO75~sCvfPSAbdnTbXH;w(j@GG+t%#z*>uL7`;wa=0x3ajg zc^QXR{sJ;~t`$pn1^p2bgY)rwF2@6lbFVWJtdw~|6~J7gDj!yJ#ue1e1djsZh05cB zositJFhAaVJ5iy#t)eyOqpMmHppZECUF0t^c#xTRAO-$a#vUot2vTACWcpUr10>Zq zXP*AImx@SAkdvYtkyty;z#`)mxG?$G(LPe34O@l)7N2=6>Lgyuq@k&Z<Chth3|8qz zooY+ABS)s>$0UPk8B@p%Li|ZS9wn8O^KPK>NRpZx*fF2N3`qfY9w4WKn-Nq!B)}h; zY$PozHp1^E1$yDqG1S;BdfGoJkPw~DvJ&U+5;U@&&eWT#Bj@spH{$}y$;3_Iu>az{ zz{G$NP-q0y+>g}=#EK|me{uT91!8%L(7U4UV@iCstue{MDOGx`N(<Okglm0Z0+U?i zo%tXG<!I;fyA(=l!HBT`ekQ*dXb}iLlLku|TxG_$@WLtRq(n|qdhvQnG9$eGQe4l7 z*!*uQ97|)S#uiF}yhjyWV;he;o~0prvpI#y0)bhpIL#R(khT;1Bs#Jh0Ytex@QQr6 zoS8czmjT_)+(qWvI*`Y*K<7^!>u%T^NI*3UyopRk7et1X2h_LH|81N+3P>CJ&DW{} zqDDa_l{~gluqhC{CzX5`8T@-BeITQN0L9z`fDAga{x?qqjrAleP)V`JU<)s*f?}*d z#sXH`DsD0=itwbsOV^=rIJWp&aS+vBEe2$9$0{w{3iU1G#isi0#|0}#sLkgXoD!ZQ zAk*@Zxr~zkri(O2vE$Jo7f;qXw<IVjpL;ivIfBX|4Mr0~*>JJW{K877;#;H2=+i~$ zf+FM*HP1#mODVcMzBP-jJ~!-1f%cQ6WD+@MlQnM>G&`_oTgmp@%uibYZ>c0J?3aD~ zMahUcnPHs9rdph|QVJtE^Fxa7wP8sCRN3-ynUP4?bdG9dM6JHPvtLPvS)m|_*1L}V z8(5_jUMWGU=1j^*?q&<@rc{iA9@5pj&ehDj1##_<j;&uIf!KGfHOX*Pt-ZquNG(pd zW&>G#qTY_#FA`|4`NFSQg|8KapvFqDfDH&=1Yf=`Qeg!^zZ$WEtiSx`Ou?LAgX$hz zWB+?nJ~~>*=7E(|eSB9csgJ)tn-g{60Bc>!!7>J#ekv-bS4mHorRz6@i_~!*d4SS6 zSe4J%hPp;Es*S39?Flt3px>xa<opZ|wgR;p2Anr%oA^o9aqgTt9!;9^x;!r%p#{#3 z#^6%`NMe2}J>A&k4LYjTGVhiO7Gy{rRNW5>GLJp^)f!Z?0h<VQ5@W1J-<mlKB7A~R zo<{-Jl}`cVX6EUq?)42!KJ`KciGQU^9t5UO9kg%@dsnSA(hNXF9yc`-D$m9NQ_zev z$=c=P!0EU3%jrhMf{#(n&Gsl46le8V8v@$_5b9!LIl^Pwf63R4&9$ScD2ZFBs2pd- zT^Cq=`$%P{LO}_WNkV~Td#9QxQ*d(=qpc~p6;_Wz3U@MN-G+}Av9+hcq=+tNNGDrT zhd{3l?4Wf+wM%;CZdnIU<yhxOHE=H$>;N$PC}2g6^O0Hy#-Wwd!(p?d8z8WLkxt(k z<H(oB{YEv13-mH2b-{akxF2yIsrB-BHZ%J$_zD;uuNewH7rXWNj~08yCBOqX@YER9 zT-U3(+y2%A%PG)$viD+>exHnqi)1IxS*`P7de<qz?v*K4gm6Ehw@vX8_AaWAdnFs$ z*?(c2!&nMeYtU<C3%2Js!KR-PAcOJ}AeSeoJdWKQsWOuh>#OWjcr<|AeX1Zlh;!&Z zAydb+Qo}!858#`=wGHBWQ^Ogx-br0r=x*;XVCzvnYLLPuJw5<W>Z;CZ<DuGxEFJH1 zfHSCJ30|LHDgLxh-cw6h-@|7mwj6dLqcFK{qyx%XZB&42U$#61uOE4|beD5CSX7Pg zNgP+#mmYqs+qg#udZpq1qrCm{k(Mg#^<Vw+eW(BlaA^#?^k<Bv{#jBSSYtcLO{$I0 z9vNH0I!HS7NM?pQOz734UdRl-Kyx&WjS8$xtX$yWi~?1a8%w4qRi`IAfC;98=XzBG z?*tg%$GImB1%Ya=e=-wX)CmZN<30ZqxRKQKICntl<e~@Xk5lbKOVg*KGbhrf#7(BT zPJ^e%TJfsW?Zt?hsXlq(nbY;Q->PQdNB7XsB=ppmnbW-}LKnvl>oc^$i+0+80%_(f zY1~v|T2q~;mQa6Aou`_})@{tG+citm9KW%P>ZP#7P*5`<+Uzffn9xhS$xTJSK}5l9 z^EBpf%$%bz8?+bIyTf~19TfDMa~DPt|8jE+VN~T_A`4LKOQ5CA`24+B0TbMF9iu)4 zFM5_ys$QHp4A3Pr^~TfT$H8p$7Pq2#=Y-}=SUlF%>s5{rZ=MiuFJbP*O^zfl?19X@ zsL4E#zfhvi)9C&B^UA!T-0P?6Jasa-yFwhYZ(b{qTF-a93cv((gq-aI(MsxIFNUM{ zFRDKt%Z*vQ8PdT-UE;(L&mQ?9J{g|#7J9`ajP4^~r`16xBkcUdvo0@=urI+KoamW+ zcTwG?lhdz1|9z_>hbWLye0~OO6h+5>0Y7=Y6(qeu6f7fqQSDPN4*z0T?w|jl4#MAp zYZzdVzOs=E4s^YP)lZdogc^`azYMDng6NlcaGt)h>V<~CT|uz{2XlQQZ^2FUd+wD+ zDX%$}Ggh*fLHX-gRgDGgWsVD(i2V!al!Vxru*+;dD=gTLC$59%j|cQ|)4I1gn`G{s zTz>dN96e!=C1|Jt_Meb)AMy38mlCiS^Yq6U;3(x2;lU>aX;ma?^}Iu#SB<{w2~Mz^ zBP5~ydyd}e8tlWP2jEpUAmAT&#?l&%gUzQKd++vIJln>1#SKA|Wq87xd-tGd$c^Yp zv~eCb-t*JF?e`f88>>3A!g6aolk1v7P{7;mpEF`*`BnDi4Sw0x*lv!3iOsBHO#L=C z?J`&?`(;g>?TOcyZrRTcRbR5rHW5kdJdn>lvRkW9(X)-{j>}-326m`sYfTXY>})Yn zx0f$(EL`4RNkb2VYoFeNFSoaU>7bdhYqRIR3hu6LotQM9y3vbg8=|21G_Y3~H%7d7 za9EFDtFHhC65WHfw7;>;K)eOnhIi1DjIW#*L1R4pDgba_`Sw$BBX=1ywuAok4}J1K zQ1s~A_apcXAu2qsIWU0di~Luvqi$YQ56^VfcTC`S^<*~a^mqTTclh2#wJRJG$CoMM z$L-<|Na~Q$bB+piaG9VMZ@6sn{6;U~)%QvJ_z?7LjhfT_RkeRV<$TszOuk;L#iow$ z$;f?DI`gy8?3M3h?An|4fX6?Adw5(f67`RsQ=fB%Jy#EZxNijcH8Johu7@+>%DIsf zzyCemPk;Pda}BjAtC*4SJNr53nEi`c&V!$6`=yT$KCHNfZKB`S9DG+qFYWw@;Dw42 z*p7fdI0wu$<K;w}C-d%l`^7`Z;KaZY2f4VL9>O_85EN?`?qF@ple{x&`;?F5+_Tuj zfgYnCv2jd#qrd+<lvu&!n3dRVgPafkvp|<hncQ459Qr%Xv3dE6xC2XOzQGcP<LLf> zX{{dt2yvMh3P*MGOQC=>)MjQ?Usvx8QVjQ*>s(PasY=H+N8?$d1P)#51mG!}b#+xg z{fu2VjqjQS#f;}7a#rEm+T}d;`~P74rmj=kT6XVa5JcYI=*~DE)9=ibikJywwt-K{ zAFkEdb&YDTyXRMCL$5&air%S=E9ZN<!v!q1ZQHrokunF|1*8bB3}~j*)W$1gAPQ2a z>%G+E29)!Kj5lOIbpf(<1m>%kTHABgZ<<>Aq**q)qLQsYE3LV_thVckuo-@;Wy^fz z!Hz~-2mvPWT%?n2b)n+Q>Bg%vY&O5|<c#NDj65O4cub`L!`(LCNurOPuf4r&O*lX0 z@~rZ&Qt1~Q#W}|h6=&#W?X>Z;<Qy#=%S~x4+d5()5L=lcc(qVLs<u@9o`_UunG}f) zaGn)K@VPwNEzNXn#gbe1VX!0>X1Ivg#auxvZShUAqo_9TjSvqI3YRD7B+K)ar^FhH zRTp-@cZ|z&Hr3xg58%S&^oni=k91HE!bS#Tt87g4PS<{M*X4)MzljK*)sMxSyE}%9 zNB-j<&HQN}#GEx)M|&Z~g4|3Jk<xpjtrm;sDo<2Cf;EX>tQ1`bwb=y8M;!X!xS~t| zU&D&afNltaqN3+0A)e^V|INgwkR)Mj6944I$c*_D?PM5y^Ny*-4Kuey5@hO|aagOs zut|D=?MS+T&v!Vbm-WeNx;^|r9On=!H&|u_Ah^xl{yHLg^ib{R#Pz`Hau8b0WN#j} zoY}m@+sj=J+DN}n=RiP)Ifv$!M5M;+Sx5gXqq_^Q^8$xLqdDgJiY@lBvJ=NaOvCYX zF@#0eunkadyMYcno51!aw)vTBbUYyP75iu1KZc&KxRO@PX+`G-i3h|>pz2=2}Z z7%PTySR-D(68qNqUa2zrlop=gs+(P-zK1Ix)!bKzx*6kpA@C@lFt(XA!~76VIsQ%B zUFEqY|EwBM3CmV-Bl`0_$JaoXf9qx7o5^FTO911&{GJjSMQvbcdi4gk-^5?6Y_cgi zd-AUnSFqe2@!Qt8JAwIDL2Yn?UBHM}U8BQ^3%+slZ>8^0%}MaIYa!{<9RqO3cKjWd z_X3o&QmnSVZ?1{>yHZ)tB5W6S1YLbH3?-uqdJMntQeOMI1^aKP+raP5^;l;Y@|^u< zlfP8P@;HA1l3(QZ7_SqXI&^I`F#j|lmGZqIjkV`N+rSfzdoRu0747&=L*EjY>(r^K z4(MYY=@#oZ^*@RPik8VcgKq@-C8=1vp}ReE&y48jt^bZBYCHOwAOsDnC7Q~wU7)Y9 z$6++(abJ2vll1RSMGrkeB+bBqO`1c#b);H6FxlFoHD61F?c+mLl92(iH^wd>8O9rZ z9b3}cfA#myY2inDze-&%ey;Ms|2_TI9oCS}o2)I&`Wve|)ubcTZG^YxMDz!Uh?ghP zXj}_@#HQiFsb~-Uy&qRE%R11XIMA+=g-7@?p;{UdlktTR#)Av<$(>cjA!i-zMbAoT zrg=+70d!tKp+385>a@6Zu$V5cLhq?hJkQn#eQ|c-od3c<`)70(8$i#)&9BS&og0BA z$QMMD{(Ve}`QrTdEwe$m&K;@7;<*7&J?uLNrzobQ5hwYlZAQ1ZX^}Vh@_t+1VNkst z65r6w6#Y32sWO+@?|@`7cvUxf|CD&8whPnB`gj4^Q}xB~68!<=%b`xfkLyND?0^Lh z!(kdvb2*0jae(o$GvKkUipUq)(DN}@6?iUG7->tmV?+E>Z`~&i>#QalQ(LJN=C)G3 zdt}6?tU+<N;$gCLwpQ9;cnKHZ`sFf&^beIL5moLd26aAyygDZ0qSlrdUF0M3q4-3o zip$jxrsBCDow#&zkyow0sZ>jhNMBZW_PqXWhRU}41h(RAb#zlxxjY5`;1GR|rBAGh zRkw!neo6ZvD5(`vB8B2coG`zmcGvM|?Q74IN0(U&ht1M|)RRwtxy;5r$(=kvg9m<g zP8-mJj9h7g2N&y0@}<0TGsVl?uh2mUS-*a%<n|;Uwe#S3G4-lgWwW#MsnZS8%gnBI zywk5;-{ZJ6e7J#jIK__Ts@c%L>Q<pQ;m)-Jg%Vc>@_48>qgk&G=N$^?GbPCa<@)r& z+ZIxnq@uV=S9RCTv^%z)Cw;6$(r5X^3{^Qq4Hf*}rn}1J?0ebsuh9(uh|ITYV9!3R z8q9uc?%&MD91{WoTbcUH@4qV{+aK?{t}kC}m6v;KlVA=qk}UtP0PGYK>nI(bmWU}r zRu@mJCd{KJPY7%gi-}>y0O;Oq<62{xJOK)@l5B&C|D3d%+}Nh%6=jNrvb`Sv*dRk* z@=J~^Ul>a(yCcr>a`ZbBC~HE>EOBl@s!3%4Q1{AM4zuWNp<t56SwLgn)p!d6)?1OJ zvn)}dopoYlj6HEFU>3CCfR>Wh0-D8%*0Q;nBvy;i7}7%_Ze4O5wWs(v(AM4XrB!m| za#5NjmKL>K@Ens(6NGL+sq*dKdf|dJA=Ly?!V>^MYH8uZ)TuU!b5{M5R<8uHElHqN z2Qpg*KEc+v7Kjp_4eisS8ZZQ5FcMQjiBA@avlI#79ZT5e70=px)TW5E%LP$iqZ>fO z=1R8-;!lbMRNQ$Zx2%^P-+?H>-Rt)Cum9be|B0+I+n%}0AOJz2G;{K$pEU@x2W}83 zXn0f)b)LW{?iqL=<R|hT2))6L5r|h8n*y=;z<Is#RF}n6DyamwBbGR>l2#=b=4HwS z5(Ji)>)<`V(#um4bB^JvAmNl|m3FKWzX`b_JO_XcfIjs`TH7c>7fQ`Za==elMCStW zfexrXt)GuQKv-Xi(Mh6oo3kW$Uk5<g%^skhI<F#Z>-gLS(kuYPtS)E=N}5yBb&BZP zAU@Fhe|iehia^hX`Me57vSHS@0KO*_8%Wy=LU@B1o*+R$yg*>U0y|GT)K{vz-S3`v zC2b?}aT&)P8o>?DfQaueDZ6vDzFU&C|9BuPM*;vqKakNcISBBr$P{SpqPlDRpsp8) zFSwC8gJfg!wcSJEc&`(vi#iF3AIR&!!VL};g!%+os`Z%)8^61x;H7J(P!M|uTvp_> zF};ZA(ftHMgWoHdXoQa_jFwnG*JzgZYY9X{xa{aG`g<+=vxwi)zgzRSCQt$=s0b~< zKmVHv4rv2|=!TOJ!HOuqrBV)MkO>7uxRlsFl4v$`Lp~=kJ@6C1pcp`k2tk7=0s!a* z4k<twIjj0$K#HipotVH&3xePi2>v@c0GO=}gq5XWz5lpA);Jc7@EQQviYp01pjfS! zID}f_iX-H}QOUhV;)Ya61A*`c{{W~$5FChJXhSX}oiik?fvBmU2t$h~!a*B2X`8_1 zE5ojM!%(O_0EnSKnL>hCm^`$IGqVU<5{N&0K#br#0KhUbytNq|M4<@5VCxX9D2Vk) zhJnbm-El<LD4L^TER1lrPK3pkfIgL&LxIS_`Fe^`3X1e12ryVNC`7p>oWUNj0U7{+ z7Kp`UEC_F?!Gb8ifk=!%=`I-I#a<MMnA#&LSh<2IMrHKImUu?Q5S2w_jl!u$aw7;W zGN=wizHc-Laj_1hb4O<c6gz|syut`Ka|x-NM}n}9h3iLiQ6%RZ5H0Z&%_E2k1IFK@ zh#m+?C3(Du+zEp8j20XS|5hZ4ZKMd&lgQHQNS&Y!yGyd2&=sAq$T1j$WCMVh5=4zO z2#)+nO-hb|*uo^Sh9B%TODTwv?2J1IC|<0v&^ot);KY~=5qo?MLh!)=;f8MLg@WjY zn|#B9VTh#AE6)(2p~0JyLm;;*s11`ZxHHORiVSNg696bh7nw=`xCN^yh(|c7)}W3) zV4AGFh-BLWbtDLvEC^&A%OWbvd_h5hNQ`PQOaQ=1=jesX7>Ex9fLcTvp2SK=bH#=n z2pNFMzpM`x<cg@Ih-d_n$OFK{)T%}^h-%cwi+DCAEQl4*OdY}uf*=mibP<%e3Tp_* zxO5G4q04b12%$^~|A!n1*L=<0c@u*ujy2?lV4I99Ny~u<1OUj*l}H;H`H|FPiIRK? z0^_I>GN9Ddf^{^A?;8l=EQqx%&VqnMo;WeNkPnLJK~MyM*o2X2EXC+_iKi5m>y(a{ zG9cMHz4XKgdBg}|5~ZYx&Dfkt7`ci@fXnH;2wvcjIT#1VOp+hzi=CMZyO|Y)6o}Lm zP@j;u^}HD2SWqR|isdYbW;BR2@C6G!Q4mQZ?Boi3jIN3R(Ubs!5G{~_s3d~uHWIxw zZg|kA421K$2>ld@$veyo1prw<h;OQk>`4jmq==#{&UmZ{M^L+|!-l5}iGc`HlAzB~ z$t<I&B^y1*|4{<~e**y4Oi$D7(t-#ubfZmyI8qBWh+51+2<4;R1c2;QiE`UFOf=Mj z2)-R9h|KIrfRxBPg$#j6171i5NR`p$*s(Rm9Yck)fl$;eHBA6`wOkoQj%d!3KtCms z%qi8rmk2Tj(m6OSP68PObpZe`LJ)#*6z!ZiZa5A-HHcIY2yOsY)KiWkyf-T=s19?} z?u$u0I2;;z9UFNyps7<+I+gtx6ZjD|`9#dbc*<L-NtwF0its&#Y*PRjg1FPnSy4E< z0V4niqQ!v}$6>h`@&?E>)mx0w7YPk1wGVw$3Gy7vrK3bw6Nq;SC5rHvFI=))L{5TW z(If#_|JW$kfe5X)TS5T9QUNW5r@2+_NRUs`PPZtwOG^r0DAQMQ1sYur;6&GFYeycv zjsighFN#-Q^)Csdwlxq4LZ}69u+%^~)9A?9z0|)UaMq5bQiJ%|9{tgHg%>d4*?-ed zZ~c?2Op<I`O#$^IK9Q0Xp&Lh$GE+K*RJ=57xP>+3K>(<RmEEbKx!8<6GB<t5Gk7WK zf=7%P+o|C*NP@KI^aaYWt)j6A2I4h;n^|`(Ip0Yr>Ts^?_|ZgJ6pEM^fk>j#;1y_# zhJO7Mm#qsE>amq9h^*2-Bv4w3<S25vBoU&HcO3{XDo}!Gi%~e42x3IbqgkJ@7693s z|Ml9y?&;LAWCOfm-AXhFN4-^C9f(ma2yDe&ezFLy-QAbaP~R1ZOB{%}(lxt9JYx(< z<E@B3h*p89Re_M*g3uLug_KRRyvezs>TQYZ^<6jnEsAJI@a@Oqy-|w5$Gb=boGpk& zBP0NTGM1=H)sx?qC|czx8m?Q&f_TM&;5mMT0r|}i0TzgDA=^5&6OwoZSjZPN3W`(w z#+>=4>WPjsFkFfdL;&zSCG-J){6^6wiKVL}wSxqm1pt$s3F=+ogfIw6X<*j~w5B5o zB{WY_BLNn;;F#con9@f!m|KG&kQ~m{idc=D@ZkyLC$f+WUf|3iR*q(MM+Fjt{|c)J zI^ZNgK$p9)l{pO}UC9X@iQXahxUTRVj2KKZt_!Clh-q6_f`EZ1=0GSkT#M<>fhZrQ z=>x%A-i;w(f%w~=>5OFg1*`Mpx;Q6ZimPdp;bhzbm>stfVr261$vq*6$<@`1xQPS4 zmsoxZG0x;<*<=7w+~HHktI}S9I9}LUI-A9dikM@T$d)4J2{9H7O}^#27_yZkSb>m% zfNWs^z#F?t<wyRfieTl7D5@OOU85M|X6A~lf@T2tRHJl*@zK=8ky-#CU|sBl#tD-` z3TJUf7IJQl@Z8>A(=~$KQL!t|Ttdk7y^&C=*Mg|2do~JYF2f!{+y9`o|0A2gbPmz& zdm39ogda6J0<MHF(F7f79EC23F*(ab8`>lRW9fB~A=AW<RAT{B3E9wSVuok+TnW^X zFpAu+PJxrrXhav;B><4GBkNcg@Jn|D(Q*x_88H-A$%{F~X@;eUh}LJ4XtFr6Y8Y8s ziHvE3$fdo_XudUw6dP#+wg@J`&#PwO)4>w4jJl50$3-Rx0$aF@24E@S4o_;7ilCZ$ zA%&WXPM!|pxLE~<WsYnjLxG;=j{Gb)plk9uFYBn)Ls%%ao8$rx6H1|llmZIUA;(T! z9mH0S?~$*?Hp($*;n*Sw;29KfscawB>j9n#GWiL-1B`Kw#nEo*|CG?*g1`r5RMvsG zW`o!<TD4V*aNe0fX110jII&xF4n2a{fO%9Pl%$9|5}_5+=q`bTRmp6tk!rS{iLG{# z?}INNSYqPz>WkpLGy^0X0lA83*kdMdjL2#eIav_tYJ&I&cU(yRtzsiW-va+4APsM| zh>3k_&-65J0a09Zj_VL*?U_d3s4j?+pyd7$(wJy)%~T!Iwhz?p@6;{`0q@^}ppJjM zj;A$nF2R*;DJFtg3lDCI!dlf3)t^xj=#Sh$)kd@G5T4jI2uhd)0I&i8u!Bc|mkz)0 z!5IRJPU?Pm$l(?U{=JA5Ke`@mUV-=nuhD}81%M-ea-XQF|NRb;#xBlkRv~b?3y~{` z38DygqU1_0bCy7J7g6(pfCr<r7_PJ{aT$a?g!6*1gh?Rt;+Z=H#4u#6Zh^>$m;~}G z7vEEkiSNF1P3q={>@ADg9=menOc!+>5`$`9XNw3ZK``i1XLaeR@ZU*w0C@FQr}c6H zPB+8yYV-mCC<4X0)ljW<uSjqKA<ljXZq1x@uDl36SoL5hqNJ8cEh1%>@RNge_G=H6 zQNBpp!S=Gc3wQWSF6d?XWpoUq@@_9fho-FyAc#nR$ot*oT1GHKev^D~cXY@1e9w1d z;CFrZ_oRuIQ9-1yuyZSU;vRR$=!O-BMw(n8h<^VH|8)ltNU?DxAw3G%^nVYE2Tz(S zw2Zx*A_EnbbJzH%;CPz3JysI=sZ|p8hV+MY0=^6shA$V0S3Qrvl8O~}D@p3d=<{zJ z0`hEvj-C1N35HCQc<G_@KVkR(1^|**#^8(Y8Nh)q+c;m)ZTkRXpBSd8<>3Pd5V(!S z8yE;#wVxcvl3)o3MF13?my0g3m1DDXboYU!m4Z&SdW=DPECC0D5Qd}|olokLMK~<E zN8Zk;_-}MbTO<0h!+BQf(jO(z)@F@IH};M+`|#O%EXm|;dgsZ<D^2B!tS|Yx*nDps z?;f3e<#^#_Bmo)VM~g0f0D0$>fUeG%JbZxq|72`|7ntT8kp0<Dl0vWR)BKFxFT>}Q zX0Q`}D{&oh;zQ!D3wX!}<R8T9CcPJ!@Z1V!2jhg}%;yH`l1f?^aDm(%D<9D>^AI3D zfw+O`ev9sRF{~$|jF+Z@XjR!kcNWloi3EsWy8sXbFbx2&f(jQhZ0PVI#E23nQmokU zki$L}H*)Og@gvBPB1e)e`4NW6lqy%UZ0Yi$GJ?KrDI7>J;me#X7ZpSV;7}m|fC&B} zs8J`<q)L}EZ3@7K4W|U}NUcf{7cQ$7!zpByCX`LB1ToPR`*2Yrh(nJ8ph~r19D;Dz z0HAC3F5bL)_wL#2*Ka~x!4zUj#S5p_|2%&S@=QxGXv02z8ODuk72o2_nm4z+v*#`6 z&`A;3%BjmEt2F><aYhsrvct&@-H5Jj`}SYZxLaneU0UI90H;OTqBZ<9F4hrQ;hIy> z)vJYuipg4q%K9p)J`2Ha_?gbaxNt7-E^q!k`t%PGC#CrYK-tx@D!PKj%GJVAuCnKZ zB(cyS5P3#fLA0rNAc6@hxS&VF6_iF&vM6U!Bml5N5G)JLrxPTOJmeZk<JHB~JPew6 zB8n-hw970P0uWqEtgZ3LgtTnP5r5zmgi3!C1vQjJbbv>Yfd!p`6iS$>xFnMz6=mXt z=y}l)F~^Y98$q_na-%~o5(El{{{Y~pm17EZ*N|J`HFU<2EWv;hK^OthPm^`pIT2eX zN_d`w?5z}ta}s7~ku1(-#a}_O0I&)vsF32<9<nV2N09}Uk<$i2+_@>IoN{?yDDh#b zk}ZQ0B#WsHz48hyreac%m#3Tpz^pCt1i-BuefAJ-cAZhi7%j2TDY3;GTiY#DrlK5j zDy<R9mK3eZP#~<VvI>|A)tXyHz$%r`vEhn4u8DdO6y-!?67+~__?@C|Qat(85ReeX zVHuH?>NG65{id|S3jPXQ(6aF9bmONEAqt9@rvgxnquaWa>q>3rL_!DyYrHYX7P+WP zd@Pj;K*A7>3GZ`^6q9Yo|3bC=GR!e=6f#8{rm8Ta5gDQ=q`Jv<my$9IJ+#m?yJQ{8 z0F>fUCPX{^G}KWSbnQcFeFDJM6;&cN*Ij!pbSz+Ieb<oqetkCDX`jm!Dm+Rwwp4iz zsW#npd%Y(Bxd8BLxP1*dx7~pYK6r|{fhQv2i7W1J!{NSV_TrICK6z+}Q+_$-nO9}G z=AC=~`AC(4K04{8Qv@F5rmMcXM6Q%fxW25*Zer65X`;#Ox$7P|?z{W`d*HPL&^z$O z8-G0V$t!<eCBiTNJoNrLA3gQeTYo+F*=xT&_qh4jy+Z-k3qJXHd00OB>2J0O#p=8N zzE+Ez4?q3&+kZd)|K*k0^&4-%oj(9Ol?e8AtqZgYAOeY%mi9?a6PHLJ1S2TH3En9{ zKlxf9Dl|O5Jc)uH<Vb*mA}6Umf)XD*VS-+Bh!sX{6q?Bs3S;<?5JF~zGQ45>xMM-x z*${_5{KyVx*TaGg0uX2VArc+ZK_QB85Zob%_!ja9NhPt0y9-Jbi&&7NEYXTy1Rjva z2Y{l$@QY?F-uTLR#x;^ojBI>k%yKn7r38^6Vmyi(;i$(w^0AL1kwj+l=*PwJt9o)+ zh$AfVy+PtHV=QO^BO@uvNm8<sckv7rEvZShMXDe^+axF}GOvyKEtICz$&}Kth*6%h zl>-~1L|Dlw|IWFxmS&oW6?y_oTk?`)9^#HHdnrs}0m6+75d;*6smzTbLJ);8<}#xh zu0kMFn%2A~HYNCnE@rcv-uxyw!zs>j`jG?x2pBmTf{k>tvz_jIrxk++&w1VkT=cvr zKF!hsNanMj{`@CE11ivg611QOJt#sGs?dcpw4n}tC`2PF(TP&Dq87a<Ml-6>jdHZ3 z9vvJc(fLu0iIjeY9O=e}1t*k76a^GO0RS=v02;`EAU2=@O9{#jg;3xFCCw>9=i!cm zY(ODD1?uJOIXQg1;~xNUDgb<d)XtSCb4r~mR<o+rt#Y-iUi~Uq!z$LXlC`X6Ju6z% zs@ApY!i1Y_9q0evD%ZKvwXSx(D_--e*S+$!uYUb2U;``I!4kHxhCM7|6RX(8GPbdf zeJo@nE7{3Xwz8JJEM|9ykE>>ukM{t8ION$`IQFANoE>c+@gZ8&!Z9EDpc88c30sED zHnz6Ct!-4x5OeT@9t0srZE<Txc@P90pA{|}iA#>vBG-(kZSD<+0bM?}BOU-CM?I#S w#HuRf9?aFQ3}M@kemobv<~=WZ)2rU~vbVkNeJ_0D3(oP%_k*r=Z9o73J6Yjnb^rhX literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_sphere_product01.gif b/images/demo_Riemannian_sphere_product01.gif new file mode 100644 index 0000000000000000000000000000000000000000..6bb394dce79098321681159f05b90ade4d8ec679 GIT binary patch literal 647037 zcmWhzcQhPM7u~+Auija`i{8oVy+n(M2q8Kl1PNm8>OD%L+vqiVmt^%4Wd#X>tQrJC z5|Kpg_xt9&IWy<XA2Vm>yt(h*a}A9RR8(CtAWP6MfGmIvfIuJueEdQJLLx#UVj^Oa z;*zr0WL1<@)Km@BR9&uXUPo&^)VZ#!gVxc}*3r|^Gt@UUF)}eXHMca6v$U|XwD7dD zcx-KDZD(V5)As&NyPG%d9d6m*a&&OK<Cu5n_8n)ZyUtE=ckiURIJ>yq&2)2hyYF`2 z!`;)%!^``>@bvca%JTL0_4BUu^Xc*P&G+~95AZt;@DB)l;2ZcL=wV=Ra8O9d!$%>( zxJSXSLfza$LqfwI&4h=BhldqB34ikBac1O`$jB#^Q4vq0qoSjuW1^!|W1hyuM90Kn zuviQh7ZVwajg5<qi#M}Kj89BTOiD^hNlt7`@%KwfN=ZpdO-brbO`1+kDNIXAOLx4J zo|ur4mXVR3nVFuInVI=4<5`xMPgcgW>}T0I9^N^D4|B3|p1Zm|&&hp}ne`&~MgHR_ z`7iPd@(G3c1%>(V3yWHd3W|!0ii=AtON&eJCHR-6FUwz+m%pqiFDtL~_Ny$bs4TCn zDtlR7SzYravZlJGHou^*rmnuOzM-b7p{}u^ZthjXtER@L=EUTdrk0kb?bepowzA5$ z*0%Pxj*j-uj`qpUsOZiY`CT1d-Cg}XT|K=X-o5pWz1_WiJ$-$B{jd98zwZApM&9)F zzj;0Q_VrsrcNgI;fiN&QNEjR(*c}=e8cxd?uBsmXZ!$<29vU7Vn;0IS9hrPLT2M4P zG&(vwIyy2sR#rAPIyNyj@lHqY-Nd`8cT-dEcBf0rXQpOmrsrm6h_lqRv(uBa)5O{N zMdA!`Ze(<BX5oE%$9v-Y_w$?cbMp)D7ZzU>EKbiX&M$tnuv%VP`BYZ<Y3BW>_wUy# ztJmuqJ`atM9!HSYK5uVc?QU-GwRavr%Q>E&`6e#)ZEpU=$mH}h>Ga#_cQecH!y`XV zzyCP<`TOeX&&8iVfB*fty!w0Z{@*|UF3l}3fB(JwdwKcq-#<F!KPA<FXx*#i)T?#U z)#c^Y<<-?C`Rd=ltE(&W;|TK4bMn6{@;~x_jgL%ap>J!Wt8Jw(CoKa80ssKM-w>$# zf1~7o9q|7&0U*eLs2!bz+0p?Vf>GRQy!qu&0#d-F$f%`kB!x}hXLY=#d@KW{o6Ke0 zS}~CgoqH`8`T+GN4EAlJ$hfU)x=<zfV0EIcdbSjeqvSSeubC@1$`-#f*<L$eZB=ek zoIG13>9%_{tufJ2|FOwsD4E-|vthZ-YyQvBuUVhBkv3bC#im`a*80M~AFRFWYWiGo z@#FU-{AShLw~34r&QskjTVt65A|p4gZcjz{$osBO^|XDN#p|YA8Qm&XnW(X;cb@L; z`1&zX?5{k$uk+|rcktKswVO)*>jWGXuSI{i&!AjXhVx8+&-X9Ha?_8gzq?MqF17i7 zo+;itJSGjLka;cNoFDG*&DY<Zee?Qn`{L(!rIv5s{QEm!|KjuP+qY!0O%$Ajfv|YF z#DI8eNLXqmQ70^|f#^molN`)7j?JTHBi{VZ_(lRMUUbubm*lybBwAIonasxSv6d(^ zD(Z&&(&Dw1rm|a89`a{;Zz}_R{KYj>kHuT?f#Pw^c9xma{<e`ckJwI*ZLgAhu7gKy zrSr{z{hb#sa*Ox#+@E{zTDX<e?iRRLP3#s1TJL)lg?!lGDhl1L6-hAG+W%6Df&FpM zh+y#%O$_I$+baVLPwtgxCV%m&$g%fXt$6NH=N*t2aIjxp|A_LSro!>!UM=iR`9WPn z-N8)#aWk3Hx4xmwWUIC_Swy1#>T>IA69Fc1*i87)USHSqT*RlfX|C6&X{fh+x_win zJXL-?QHN5jO7h+~e~g~1KGOq1xpDrg#4;*{8OicAl@%msL)*Aq#9HgQfv|+faDf1= zY_F~L7@KS!Y5<HBOeG8=*a8Vd5NcEqkjYR30Hl*o#egYpl1?e4rbxpKZcY!W6jt`+ z8?HBX7F^5fesj1|*8=-Wr?!F?pzby%AqOE0s6YS^s#4T4N_DLn05VZ0{g}77eu4p; z$fx}na^S>20)n}kF<?$ivmRT@_GYTeCiP#7hM$v{9B%@??ue^>gZR=a)sSNJ5S)@^ zf54n0??1%_Yu01*Mxw|o6-d0Hl;VPA^y_xw?cgXhgbk0uaYZ6<<|}Xiw1s{ODu;#b z2dB{<HJxP1#nZ5(tlH;{m7^}U5=4puA^pFO|9&IDzx_R?H$rKD8~$E$vXIT|f}UgI z#b{IBal)G0zs$IzJ;*4Yd2Le%mza@DtDx5<-sWvSo$nSXiTpM?c8z@b18n~Ga>P<5 z<};Y7@oET$L<9RfTM&Yh5AA}T=a85fmVRx<B{aNQkG1}r&}amU!lbJ`vs%zz8J&gK z0Enj(UA30(){8@*99O?(=_SVTq`ai|bO8QaYzDDq5`dRo0I=`_A0!*!4|4xG0IZY# zIOjVrOsOj={C-9Vdp{MdoGr)mp9yDy3K-7SteYxy6nJC4_}j5a46B7pJeyHD$H(ze zrQRSgvzG&%d?rwFGcewB*cHNs!6b5%fTQxL!77+R9YvZi3=M!kCnm&PCf~HJc<1*+ zd&0!=EGuuSLRfiX!s5wUHlDgt)X;d+y5KAaf0>|l_EJ3e_W?Jr(*WqIN(;i29%L<# zx=e*Du#F<YDj@=}1EaBf0Vwd8nXsHPVah}8dmc|B=A#lJhNh+^eGpPL*3KRi&kO+4 z131ni^SUdKtN`##0Fvcdt09BI{hHKjjW5QtPgcH{Tx`4F=4U4}+sDyzrl547p?Tv2 zsurpJg{3sn`O~f}!TGbPHS((HxnxHLKY>*Yyoh4XgJnMLlbHa-J*<aol<qOSqTqc_ z=MYE|1Mw#6tMV)>ZLi{Fly<&YRn^Q#bW=KPHba?oFc_f9RH&=1tIpP!cP^c$FS#o{ z^wmi*v<^S(Y=2_xyCxT3g`yy)R09T0K6A+?Ir+SI+_;U!fz<6M726uCARbhYE{6-~ z20BjVY(wJtV!Mpyn)ejw_DJt<pU7Z`0Z3xin*qMVC^LUoqbBdEq=H<q!;v^b>D}_o zlk+wd0*Ejpnlpym*P}>vcJ)4swf6JnA!Y*bdtp6l<k6GHv8_9s{MBegJBE(F!dpvJ zjIn4JC#Rq-?dm-^PyGhWO_YO+CE|zn_!J+X`HJ6{cxRRz3TUfeZ1B`Yub&nC>fe)U zqL9G=7%E=$<IVkVcC0womMMZc{g)tWnFj2eonbo-jz5%05Nnrjyx%Yh;uK&y=mR?5 z(P=T)!W1=H{%+Pgff!)#XnT*AdF_ZqxqGqNl&j;1zKykm@Xw}LmIVBWOnOVIs~?DA z;R3*}GLU-baQ)ZwuC}@nNquFPMGC?9U@ounu|xRHHJX_sy=*jn2%k3O0iFC+;Jt<q z*o+;yux97=WJ{XAbbh25i29F$Bc8qm`s@qx%eBf~JG<3eyl)*wg~!`Uenn!n{w~i( zC}~rnNEmD}ikR4Wn*Pnt8TH_2A7}9n1dTDf2eK(tbbp8vIKjZe3o0SqUs3oCi3q#^ zZ^9l>V5OEeg2`Y|tupY<2bfe4dJwE{*QT8`W*cAitZ#Z7ZFi&Z7VoSIG1}t1^akP3 zLpfquScO1Qr0IWOgmX^um2B#4gd<%h+KZjU>DZVwedW>nqDPTra_f&d4?>qqTwPBo zbO52^f@?YyHOjkREaCoplB@l{ZQ48E48-KUcx)@dZCPYT7x<xnZ1;QX4Wg&#?aR$6 z3*hJt88GvV%hp1P(ujV*k>*%lzb2Wbu}j?rgUBQG*&Y#O-F(M_<@3YD8w-X6k%*u? zFfExdCfy8x`}c2ikJ3oKz5XaumOROBF^;+MdQ{6fW$7c;H|g*m$3tS7#^@8RkXG&E zL#DichZ078E4PW*_O_@aQ56E^%B%DC(tn5UZ&mPgjbE};o<n%7cuBnf?ks({TrKqA zTCCaahX8=EKFpY7Xb{w(Uzhj7W$d;~@jxZc#O}>|7!Nx0Ywm8qi!8hFurFqZ3DK`d zTzS>Uzd8TvY5RBHJ^T9DH#3G}0sV{6^m_D0U|6bzI#JeO;JpQ5+3;=X?#^-3RYB4B zcri54COocw8JNIR#Ls)~0w=pXP<wj(*xAOnFQF;%1{hm#;tOXzWnbj*o9bNu+SC<v zs2>p2=GlKtV8uuw!M&_tm<k5&0Hy_i-g;snq8Ox6Sg3L&OIV~#Jc$0pTCDn^<Il)x z+hB5~22Ha9Wgy^AHYg57`|TuHEs&DzLif!InV_xz<)#?^7u^+_TDe)5`&<z*@1fLw z=bd{rZ9?>pzT0Erh+)Hs0K+iQ9>$6-&RPX*i->#M1yDlAIf};JNW{=zgi7FpnAjc) z6T(_!0cyMV(hTm(josK)iW13{`RECtJkdY|!gld=%S3QsCe3dG-AVJ~8@9O2hqz5N z0)-B&`i1Kc(XAsZ+u80s34=u#?|HI%hMFT{;B0Y@OG)xpU_4tg{vt^com?3X7C`}( zP|0N%NhRHJPJ0-jR~S3%!zf`LDkA7<S3I|h`<Q!xsmJvq7U0Jh04jOFo1c_qnUH`? z=F33ZdfTT#x``>RN(pvwdV;I?h%EZT1KIItL@DXd%_Qcr=yq0&%|)`~c=914S?MJG z_#*wA3K)$7auUFbfna4+M*UKHxmWVRQe2y8{DKk~fdWbq!+a7SZtI6H>IGjh8&Tr{ z6q$gKMHz?-sLzGA4**Xk+{9ea75$Qn;ulrfv^fq;V~|1nR_P#=qu-vV-C|C^YnXod zF<Ol564Ap7mM3H%7{wipXPnh!=sgCj;4@SRV1p#EnKxJk0FnLzwwTD#SIzk&nsK_6 z(TK>g6OHSs4!trAf;R)D0A7zf{jb69*8aTH#C%(BSe>yJKy9UB@?DvMn2?Hrmf}sS zcj<n+WJ&6Xt_I_lh){`T+-lx+D(36~rR<Hw*!vDaD)~w3zmqGyk`Ko-j3#o5ymL$^ zz#3?%dNVjjDT*5avLpf20T3-h4t^rPc|Tu&KVN4#!;w9+^&&So3<N`iB&_^BYQ4lh zMmj#a+xbYBB``{hNl#J;fFQwsd;mL!I#ueXh4QP#-=|WsvK1CoG+9jK>j=C}z8QOw z5X<<{Pt`czYA;E<C*zw@PBTRzUbVC-39Ll`OOb$<7%IyX>c)v2TQsyAK>f!XghoMr z7?+;*;0+(=6i#FuT_i&;F#cl^a3YBPm#6TU+jZf)x(2~$`DaORAPq?YfdWtgiUR@g zO&2=E2ReD9ESKjJOxqG&L{RiR4&IfQY8<N{9=qk0w3lC^HWB)@C%w!ox3DLNY7%Tr zQJ{saw5Eih(NJy-RUSIS09C1lu2jtgQxG7w&81v{c&7q9rDG}e3jQX=%iBG1n#LFv zq@I#hq`*f{%B1Ioiz!}Evx!;&OQ1%Nei;=JAkqtP$b6BCqCFvJK7PPgUYVUm##5>M zF;5vwJo{p+%a-)Yvm`4&$R8eQNSX6eC5L9E!po%8X{EA33}TB0Sz;)Z33axP^^H$J zTrLna0ir=D6}5tNI@Ws@)KT<S=_TbJE+xsjfDr(Yyi0_uS4!kfH*Yb=vpDy*I3SA) zkirGH7q21Is{ld*0|0Q|W-9)q$0I^%<@btx7#NR<5-Uik#*)J4eGgh8&tX^v!_81v z2Mlbyr1DRR*`EsUx;iJ0hR#WdI<g+_Sg(U@VKA*UAOI!s^|r|nw?7axpuv`-<-g*- zo}<#M7k_iP%27303F-efA;M+CPjD>kX;<}90g#I<^DNL-cVR4iYXz(cD89Bw`{%jj zah<TD8*Nl(8uw`0Gv<<a!?kE1Hxr}CgMEw<M@E}ish3)7dtEaFXNz7l)Y1j!L8!YM z(TT=G7%?CNREw$$#1GYJi-ve`Ht3wR@JY0e98^#zx0a8CnUO#hq}<)*P`7bEPM^jI zwcAX1fWjC1O+5=%ZvevyNHY)tp?`WOl<vQxNdAwQvJoZciTOFly_;d?Q|*o!#!1h- z(^Y%2wU(0{KINbGblh3#aE|C?FopP?Kw5e$`%EE&>ivTf5UUe_STjTi-LK;U`48Ki zTsl$peY}4=_)S}dO#51vGgJZr!kKZm$rrgJp3hf=9l2_NA4Nd4%&9>}Hw8ifj3=OL zn4Ujq<-*(I`d@`!@YT))f+hEH6dhIrv1aQ(%N6runG#C$lQFG@6@|C@5WZbu5%{qB zK2M2$eH6s98S00D7@#4%W)OXJzaTY~AroY71rcu;3^VQIZ0Kh<gXm-qu%vc|b2eBP zyr%N`FWW&#Ova1l?A~9kVNafGblwt1f!6BG9^{3K?`S*}D;D3P&6CY~Zk>hc;c@VA z*aSf7Y<l@%*}v<W>LogKl9Tj(I`V4sZTAZ()GCp;2NbD0hwBGXeh^Ia0On*MvSHBZ zWDJuE(MOG2Wdiwe5MwKdG1&!T&^#XA4^=0?Qu_x5ohIa*hA8{$Mpp8506<O>_`yo9 zw0ivZSLgLmASEE2XK{F}JUsphfO!HS7x;jTq0Pw|IpoVLU?|6X(#AFeo)_eie*4x} z--C1IQ}z>De3K!!`(W?D-M3#W`b`Yg4;lc*O-~?R1gJh?Jhccy;+ol{o-sl~Ijz7J zGBc#9aWevx^AM6PIWD0w8)`O~SJbssk5`caQw8RTaSr!9j+irv2{!@N+JP|Q_C`v< z??qC(-7P-;0tUL!LN{n-OxTJ|#eSy<E$vHGSpk!n6#ZFBMpkRJebOhnnvH$H(A%XC zRy*eZb}X39o{_1?Q>hU&>J)1Y5L4p3*1vglG33U7j0ONj|C?8)naJ{knBXDXT;tJZ zvkPXg^CL^YCxLZ{_GrTUn?1Q2k1?RMFo9}+{>&l){EZ(YL;@tiz}*N&0Px~{I;Uv! z26}$g&k14Q9R$&3QPQAEGW^`5GCj4hNY9pE(cWBrm6W9csm+0A158}~i)QmyQZt(V z5JL>ik^nQ+l+#>;;Q!6zHCIfLP!tAi5Ve3`TW})wc>!iMq87GN$BmJTKmBHvB41lO zf)OXBw)-V7YZ{m)L+?d-2@?FM(LhXBwf{wmFLzJus5P7bkj|{3t$Io((#h0)oPPQ4 zIT^%AM$sCh468r-`Uu)tMa1UT5V~2LZ~iSQ+OPP|UisK}K(K!>+H7WvdchnIF(5$Q zCSewV5DP0(`5lr)APEsby3q_m1EA&H8~9?90SS^#XaT)~m^VXSMlERlTR4mSG-bNj zF$va}0dk@t!hIPJIEe97ZOk9Lh4DaGR3jZlDpBgD^LHRaG0mO}ovojZeS-*Rlpy{K zZ3YGiaWVCKUOO!5M;qqc?3t7o9&!A7RFY=ED!FgoY3!-lC(`P?F=>PT7-Et+rjfZp z^=8*Eon-C;6()gi5O;l_LNG2cO8~;qYJ*~CgY$TUmv-|^W3fjH(w~OENv0_r|C6C3 zNp$T7iDr7r5CGID5bVhLY%zZ4x%X(c425lv1B#-P8u#?K&tZXx!_-=N5bhZU2;Npu z?=|1dUyn~C*cOf&^(H%|)e-&b85{bXwZ_|N_R6F-7+*neH$(3<?^+QLXRZ#3&Ln37 zP{jpm0XUj{LvlpHZsVaLB_!_SFRe72-~A>&6hfHMpb+21$iJVCmou98;`~2)@}oeM z1kj80eV$3;n3x5HJeEct9Ed#Fw|aMuxnD=iapNBD4VK2hN&zOaG+;Y*<0+x^Pp`d2 zog%uKuAwf7`tVoU=MCyT2HImkT9Ty<#YY~f<mW?4@|g_XcPlayYDI$b5WtQy-(|^X zGtQ)BG{_bYGqoaFog4*RebJWMwUpYNGKDCj?svUAK03xr@~l>hrbysH;>{rW%vEuh zVV_$?KHRDN4lgKBprqti4Hd7p!$kG31YUDNquRCfEAm>?*O|%p68=TAH=S11?fl?g zmg7FeaP8JLl0L5=f?pvl3I9O`)Vle5*0tYONSN|xXcpaXyOT3(moKmXURa>N&pkcz zw^-qkp23(+3`szYQNXv!Lx()2{(my8yt>6?K-4ndC?{@B(>#-M*DLv8$d3o}Ot6Fq zFb*%C*Ie~{?9n94P|?W%gooR!Q-DI;jwO@p27lJ|$?TuMAAS8#SI)k3A@FUUGyMYL z{6jC}XnGxb8w2wpKr`unXWu1DUWaiLz<Jky7hER;=%LgFB0hM%B#{1wPCQkyM(kdN zakdb%l(SQoAO%CZelju$bZ?LWrDFyHZt4orJ(mpX9}X&yPvemHn@OZEAE9Jcm2{{H z(y5_f6g0x14`Of$G@Nqo1k6hvC<Oz*MtHMJ3=pE(?4<g0mZvxJ*Hnpqq5Y9#r~lfU zIL@2LPQ8zgN`87CA3MK^`ga9A{J8cu+LMxtcmU9eMKB1P)gTpzV6>*s;t|@|8j6>q z8r2SSIw7fr@*XSQ&p13xpKDn?S70wh&}ZnARru#>=-oz=%=xwax@GuuVy(LaAIljh z=ZM-pzb3+SM{Q8t4quUP<!1JuLR)XtG!yxrQ7Jjys8&m}d+0M$*thk>Z2<;~Hp|hc z#qSeL^JM*r4HP0AUS6*8EKH)>af}+AlQqaJ>pHQTiYHTb^(^Bi7{scJV7lLM?^tQ1 zfuw{Cqotm#KI8YZYJJwbv9bp2o)s+yoDYU&4Y|X%TgF&FKmJmBUq=)GY~*p6k{uT; z_Y<Q-6Q)FG)c#7g&l$-##^>AKZWQ`>mSUc`?A4Ygu(tm7sOu+f0j=g2yp=m#cFIjU z`AY+FkW%y4cH69I^Zcu1EqDjNh8PpDf(+hyz6I*tFT36JdVPI<Jdq#2hk=L;3-V88 zIe%)Zyb1&~x3l?-Z(ymstoY)Xtk~*A8Dzi%I9l;w@j6QJQ~;=fMTGzmWE;RT4zAA` zmeNPLci!?WjZ<>u(p@ms_iY+cy4?x;`-KKVZFCqj%2h~-n-Kj<G8U~AOrB(J@Z+m4 z^jJBIf8k&wc6~`jXkK77iy%6k^fZ{i+i)P*f)ZV#VnHQ#wjghrNU>u>B~@oM1V)V# z=I>>Qq%Tp5>G8NxDG&nZ`@YdSGg4wj;%1ZB#T^FAWz|P4KU+P<?8lSa8^lEDneg7w zo38%E0Y~+2#hbOE9Y_$oodHD#>#{x5=4?5nzj3?iE$q{){z2hBzqa`^_;~cN_semC zY^SUVn)gw1lcAdR*6rafQw)j=z1th_J`Qd#D6IkBh?-+#-1bO&Z*=J_#b!joG>YAs z7hBTpdu741*Wqi)3OYzEHPQ0(rCSPcnV)jeF24AFJj;vm*GXBJdqDo@GCEp<qk@+e zISyah2^=u$O%T;XE57!d>>Aqkj+*#4IH&3Yyf_8Qix2~&Mv{{Kp18zvN30HrEYr_= zyp3WS3%&mIH}HGHCkr0HFQd`%+(NlWM=X<Aba_{Ju7N3egW(OqJ*#kT)U0oRn!qB$ zH5OE@9(6FtmMKq>Q2B}+T%>ykq1gqSsnCw)YtQ4aK|>WIQ}0EX%uX)I_q{N8r?_!~ zMwDR+KSgePsDhcJFLkqlb9z8Yd`xaCOtVa7Pup~h5F47SS#M-60Vbf8*yeD4dpO>c zyt`~8qO2EbbE%$Y@6?H>bipSC06Y-Qwb5A-{F~0?#(U~qYkXJHN#ld_-kZL#u4_-9 z?cYtjjU^yDOK^9Z@71X@G4BdOui2gj=MK9IE9OtgRJ=rRJLs}1shV61d6ngpI4{_b zHeRT;uv~j=`%aKKj@=ARnP`TkfAZ^D282#XVk6_Vl?|Ay<^Tp+rC2ZfIDAVp@d?8d z4rX@w4k(ig@DX_&#zo4cyLJHP{i^GxvNgu<ojYIjMbA_9^F~HA$_)e|QpTUNc2(o+ z0{~7)N*G%cXa(X$-p@d>Iv7Q72)i((CJu0jiE8Vo2D5;RSzBdFWZMICTnSzVioG|| zO86)_5kiLg95Ay`3z`VDuBblZM#kyBx?B+-4R0$%)Ci5RFml&_xTVg!Ic4)_<5sjE z8q6X}@RUMjT0Bow@X(@%m}m1Z)YatvNBm)ZD*ANoFKNS;1b8ouJRL^VK7?4C7I_wb zc3BTfa4|QR-7536DGD*1HZv}@&tiRkMKLZ-L90ab<6}O<3#&M-$!Fn%^AzgJs`822 zG(HG0nax1$*0Xdz8jDOcXD|9zdb%rhuGt7nHy(BaJJ9YTdY|=uAWR~1=ALvepBX&^ zSCRt|tc1bRTq~ph{bQk8m5P}*JiedG3k3%cCapi`s4p|4tLv@Hv}<j}08uWi%LEWt zR)<A2ezDJ0K;+hly7SqYkv|a;13)4TgA|2d1();O`C2d=bv{>G4HWbRDXT2Aon^x9 z7@@2y#PpbxkOB>Vj?fc_ar+N#ZYZ4Rgp4cY&G12Qf-C2si!0@Iwn5jE2Jg2dsD9o6 zHI_KYN|1r2+RM=l7VG-l`DDFhPrUD#2ZZ%z8m%3KRKNYYZyB?n#kGwFsy4^e{vd}c zIQScQFXDvb%Bq<E6Y!}HTw-abPU%{Il=t6-1wXE3_K<sVtAX#ynC6u$0=)gL@mT7k zyJRqX=p3u_*+C(VfzWDXRNY(JDH{IATbzTf6U~c{1rPd(_sp_#DxAH*oSpc@Ymt0| z$XyxsnPzW`u$6gFnGJ|-{k~;z!H^qZh?Pg(djZQg$R>mX|3`tSz0N|UBZb25-GcJl z67D1STlB*}-TsTnS5yXI5uzmU{Axvp`eWyYA~sNEAi>-E$PUc%pT=GR;Jx)I-eL80 z@oD(-)E9$a=~I91g!)SO#~R~4$w0csWxQX7w$*D<jCX+#*aN}bHrh~sdUC81#Fb?= zdzZg=Pyd1KU@prr?PPHLHNS#|N(<dl#Wz9e+1j)s$U#o@^l93QCxbpn2=i2P{Cr6a zb+Oq%13WWUL7~5*>!}p={Cv@Jyemkf23xTz;J5zgyn4uuf=bc_#|4-cR=p9>{$hE` zart1SKN$^fr+Ibra*NWTIYDbFhOV{i)1gG&hvh|{ygw~1P>4*HMm;Ehd_n%r*Me*7 z=i!xquf9AOT)Re~^07iN^tz-K&bVq;?HPD33^BjD5R|NrUkoVNelZp~aTEyRo#Ojm z+SJeAiH0e5uPy|8f#`Qn9;UDN=c-;?n8eG(Q<KnCa*b<5c?RBcDl*-^Hjx0u%AoQ! ziZSoZ3xXSIm=DdDfp8Tx-;bbVF?SsIF=B3|Bl?A0z~{e@*i%)M0G5qYE$d$n2>0dY zrPaUx%ZU8RV1iICl%ohG#(S>5<n9UA53?U+fho#(;WS0T+W7uwfBO|3a0*rgSO@`T zhEtaT@||eFBGCxJ9%x7p(Fde`f=vnTQ6x4~d~Z(6l4UQHEl$Bo6Ji|I5vwUE*RP4| zjM%$pF{l#?77~zy1k6WdZex{TuHu!C>vnLj4tppYw>p`L@WT~oq)I8n?>A!ZDaYl5 z5>6?o0T^|le787jaLl#ddvE*M)BYAD-Jlo!?S}gEmz9j&lD*W`IPgl>im3r_2_nHQ z<icia-5%rH1n5FH+z$uy!)f=UwNnY8S}?ujutA6(R6!5E+OAB(%Hd;W(1cWZ&6KY) zvxB;ZZVJT5qKUOwX%v<M1=h{3H4e&fZDTK`<mc<g&?B+<Gxmb+q^$^M@50==woV!% zb6ri@acvc~5iHszRzl_ZQ^KH!ld`AZXgdXi1%Tz>jjZo&BC-`(eVgTP{;FU5oh3uj z4L9MsbmP)3rv=%l%zA62J!z)gQkY_de0Uivf1#@rG90-u79}~XT!W>_0~>6Q#l-4q z8>K5Y8$#RBaSa+4u`-r^ugy%fr4q3eMj&!>4()k3LPwyNT~cX-9>nSb5I_i*&M_3C ztGs;cD#E43+^8GD&q1QG(M!<NTHXkZfq461(GM-}OSlG!(l?UYuV1+wfj^f(zFx^f zTPFoxw*A>k)0R+(3+K{HVN>^0Nr)KJoYG65M{Az|m5>l4rtugBQ^QD{QaDaw9HXjY z`czO)TL!0z7}xa!r+-zTDwj+;EE0FX(GX&e0=d!-TU@g<GR%_rx&ibTK)$n#Y{;Pd zy-eY<T>kb>mj=q?TL3s319HGdvz6Mg(KijkOBUXom~<`JPP59Upnk(uRWRM<$`dLt z$P)r#F)u)B_)C+aYU+lE3S(rIiuBleU7Na!XM^pU3+?Z~dT>ARoUUpF*SIo%=AeD% z>#&8Y5ssz?+%ar%AUJN217`LCYpdW4n2h3wO>OFB65SQz|Kb()FdQhHXrkt_34(*N zb2WT~1A-M82g2Au|FB7=L7g?6gOlydUtP6a`zd`GFceF21{mDKX1Kdp*Wv<EF2Z15 zV;ZFm7Y!`z+T@j?){WFPnag9vfcgnGLl&;Og90il6_dlJ-P5jy@!zjgri@XC%oyf? zCm3TD*oOHR$G+*k|5gNMz+jKf-v4(_2V`T5*{q?hWtQ74!tM2kuUL5imf8rH{#Yo_ zCoyqpHjN|%Q^S&}M1jH=m06O^HH>LH{FGCHRkxG)_v-i&1mr7pY$RSQq=xswnN{1T z37z|0os0>LsOuwESv4|qA#<Zlc9RdNivlm}gK}>0NGJ?Ftcg>%7#nKeKAcSbdqY4< z4_bkf1H>vL$J-;{J9Jp6X5y6haO?!2)``U}sAY$Oo;C?2TVrS|^uY)+{4=EIJa&9* zHJ!o;j4WVtz%s?j*sQ%n+&QS^CjwzsAbukX6tb+8BGa?nX1}%<;i@H$1xVD@se0*f z8^uRr5+3l=>uJ{OcHC^|p!O#Xo_*JeFumTtMJ*>ebp4)5wUaK~XNX;Mj6=WsK-6Mu z!Nj^lgUl=SZa)Vnl?UlM922Qr%z!Ru(kv@q;8*}yt#I%&yJg4MGdc}+3Py2HBj3TN zG%N(QS#XM?0Gk^R8)c(vm){#D5fBPeplqutmWvn^rErkq8`a{e-6#CFd(6b@%W5|| zl>z45F0s)U{Lx0wBWXkyR*5alZ4n3tuW+sCVs)eG(W!CufI|bkF=~K*jIHB31;fn0 z>^xJS?lIh$^_}q)MN{oWMiVcvqxr1^+htXk)zL?*V^L13Bpkm3P$LsOUW|L^znYs1 z?g)X{SK<`CmfI?Bxj!<p)Bsb9f*5tQIX<aw5-r!>(Fh~40xm${bVgOXezt~jah?r1 zH?p-FTUA?=>^zY?Q-o`FgD8)~BTmGF1wQTRSJOg2HQN;$paBAWbH9?WG5t%8dY4rR z(Rh2%^oOw>8@v?Kf8))F=-V9=!pK-#`;1Nn1dRuo1iqW9wEH)*diC@3Xd{@e8K-vf z88qXh-h5Xh4>vqw5!LSiAJ!=RiB(nsa(aQ^T;jcQ8<$=q1YAG@Dj8H5pfD+Bl{t6p z@Xlv{U~cS6r7N+9#4K?zr6x+HLI4F5|I3=b17?Ai+;v{9>PLSP6iLY{E4&n_NemQ) zU7UX6IteYiKE$rlZ+`b!ROZdJ336*LxnrqoY9_}YY?!BDvgZW$SXD!BkrnK>6rHzJ z2^e)3H^mY#=<2R29&EA%(niKU^C#tN+Pl+$RZ&2$aNJhN>xIXSAE7HgYf^$<p#OX! zLIidz3TY-<4pqeh0M^l`O-)QkM`DFi@ubQI$@^*%jxyNseCf=?BM`8U<u_nZNlC8C zwAE;>fBjVi$9?x|^94aiaD-mw=TTnbllJqGcAlRmMme9qL6%kVkQN0eK&X>i`j*eD z-T$7N#R038=jLnSHeR`<nh2FAfeejqjqYsCMGZ#|6S4$ws%Rk9jLGfqMMc>kE-OBy zrJ4x4VEOPEE)~$_$*hS*no90Gi&a%s8IRN4{85V|Xb&4rNFe(Wf&N5zNOQtdQFD8q z>h>)!S<1I;%~epNEC&BiKj+H>rv8JKB~11`OcE*)Df9aN-7pOgX(hY+N~RtGyQ3pG zmESleJb3g!-^clGdHR+r0>WDpqrK-*VR4`u2tmt$gG;u?|2YW$+;Y>zDU)KT!*THW z8eI!+=Ge8!s>CGH7cmzg4I5}BPQOBe$7z_tti(*DuB0}OV>BF7D~6FChezYRR4x+2 zF2n=>c(o0D9M&p~I>G>#rbaUFQ=gRfK4S>$VR*kZ{buu;Ih1Yq<qh5PeXgShDU03v zGc*5=?y9+f(L}JKl8<jEZn^4crPKe@D_mtj47vtKRzErVeD1$$uvOiO3mC;o8O5pM zaT}vf!}piJ#hOwn*j-z~C>eb)<@7CS^t2YVId6WM<S@^RUvoZtUHq70JxcBKotWxM zwfer2*Co<m6etMM$KwEbM1sF}_ZvCi`{z-rI2ey;7KS5VbU=qxgFnUmTYtJDF|+<6 zsQs-Fs-cdF3CvijJ~i}9^JstDd%Ae{K?&}9UiOa1)~6DG5-dOieaigH9}0_6wF=V6 z3}W^?RYxAHvAJAFgVCg2rTEo%(+64}UqWfY6v&=MpV^jB&EuKz$ma-Q6*`t~fV2zf zPl|8PQwp5@w>uS6>cx)KBxWCe0HY{8U=Tz$IN=Y!fRlv_M?Aj!olZCtO2@Bms<usQ z@DG{9y*0HP8oaesB-fuGP?Jcrs6VgkKC@q3vY7Gnt^$wCPA6CuX<z>4h~#|AKK8@x zV+i|OoE9R+eC!7Y-SLWatnm_#XY90Q)Mq#@K!RCYjsW=jVc4DdYieu75zoB$KboiZ zX8bDHm5cEhmfQu58ME_)Dj#W4kb&kAbE7DRQS^JX3Pc&HEEXB8^6i^%m~z`if)++g zEqVd`wz{ja>CLC$v!CDZ8r+>L(bai7v@O_yUfBQ72SW#UQGM=KYY!F=gcx=GV1oa| zuwJ0OfFcM;%*POxYOtCSRF>$bmgi6QJ-=&z^Gl=#7)hMTD*x#i-F{TUW;pQWt{YYi z38Wdv@?W^{s`Z*ES>+VX|NOA++@Mswk$V9Hrd+`}XA)i=Nc)emDF1rQM87G{1{e;+ z2$W!M?P46A-^Q$oz{q_p{@zNLJAm?&;Vg%Q`M{=aL&5t$BEIb|jRvjo_!zo?l>#A& z4}xM#gR}zwb|w7nPKeNufe4~w^a<deu!znVr*UBraU{gVA)K@6$d}eL<ip*@06p40 zY@gl-3+fRjTldJP2r&m6?m&>R6-cm|iA2wXmChZ{>2-gxQlBl|C<CA-!UC{3J|aAV z1lOVY!vy@ZOinqbWGMT%PR_D;GWm-7-P2F%^E-Erzq3h=#WU}^Dp_z(pM-x_p=WY( zcs<h;y}IGN#W;4QcJWs^5TcI9vC)NVjYsr+!<~J@bzP6{x=#LH{a2_vMvnmgel7Yn zYqZrzuv$%An`MLrJYWTus0M;l7P+0^wN)uU%eXJ?zAU0P-EFAt7N!|Z^&Ai6k{32( zyXM@RdRV5P!YpA|)|@lQK*=Ox)tczC5o^pSWSq$)rn6m*<U?aFNCRMaI;WD)LY}OE zK`M)cH69(b8B4+N-`WYmRToChCT^CA1P<b$aB;7{)pQma(dX+M?_PZ4S?_=H>+I<3 zuWKX%7S1Rwxm2o3j!tHk4>-J#-5$>pv3ce9TW)vc*ZRLU0l)wVj^sDWv(om9r{UJX z{3oTxQZR~GRXEITcFwaa`mLgqhiWojqOn(k))3<?LDK@6uuU#urstCNw#K!URH4sM zT@l;iyAh)b%)D75pEF<T#35)ts2Vk=bE}7KZ}qs9rWZS^i{3cUHO$}%M<l{|p&Uza zEQNSC3P%Og(cz9!Si;9d0z~mVAq!;)=JX|266QRKt(5y4efv7szT%HeZdpLk7zf?0 z5PE~pQ6J|*onvE*jYS#-*Gy+rPjRqYkf3Y^)5C2>dTk2*oEt`BBepbFYac*%_O6w7 z2%d20a|g0}K6C&?!-k1bI`3B;Q9nP)w)6;^R23<H<Qz(OFMhvAq%`W!?=Q|*-QVeW zAsAr}@2Zzo9KL+r!k_#))>v>hW~aNHbOSW{PC;WrUBeG`bl~nxi?_zgjnv|0VeAc0 zUfj^%%)Pn(_(4U&CKtFx1ewH7oA{C^TC_DmAl-e*Fb-<bE!jqK7GnhWH(HX6i`)j{ zd87TbCwNi!MDbBSpRtuDL0{I~<BVJ-fO%vmRoudrHrcF=HOeX&GNo0O;}EJ`FCi8t z(i0WgRy?^mG^RT&i<CBYj|P3yLx0*ixaB^wcZ4<Xd=R^qSe~IC22_)q5GtIySt3&3 zFZYfdS@u0c1k9!8=w0pF420KroEP}n8JpAw^sNy;J;<m0vTZrW2S0dduEENkSyd8S z7m9jh2n%oSRsX8nQJ3J`vlahWf(LLgkieIH_zZzTh?`2SzT<yr%O5%Xx`8J)@#Q!Q z=6q3~_&x3RtDdhDr}4d7s{@LUSt^4@w>Uc}t?Pc?OL(7QZ8Q+aXdov8WmHk*ld&9O zrq;``mR?+-zWL!i(2pTvM0@03$qvTR>)`vWwC?!*49$yn4UJRDYA21eiNec=*AQHP z&}G$?@xkR9vj&C!QUEE1IfDOWZIHUy#~<@D#)id@KHjgcTU^(E_47m96REK${m)g1 z-Q=@1?Q_iJ?tmfRxeSF4af2?p`!<$(90itZj-gbDWpN}Tw78HlRGUL6CRdo=g|;?q z^DgNu>^dXgHchmbHq9R*EFqA_Suu-?{h=TOPrjhg#gimfQ4&^EW`JS}xJWP)DJtXg zGim6{8hX`Q*%*!ob1tFtq+!6-;##TxKCBw%ChIe?rWEJPcc*VeM`h3NTP>jpKrT#8 zfh!8kK7OlQ2U+;_KAm#!#xybYUi$`S*2at~*9;%3#aTzEp0kzy*F{KTwD^ntvFtNM zlzu0r*dAS+sIK@AA{;t89aC~C2nL@fpr;1F;m94~>&8-G4juaY=vd*lodz=Kv`Opy z*(}K*oL?2P36Zkec+4hJ9`5S@@JFi?O$WMI6um(ujR&yBDyUUS87J!Ul^x`r<<uC( ziJPQ4+*Cu$rljoy>15Ebl`=X5cWvHtME=RRsO3&vP|3Mj3H~Z34Z(#{Ai8b+2-)RW zA_iH1>SMC*9~-myO>euy=w4e<^~N@6%<dLrhCbW!_#f@on_1hXtvMqE^MIEu1>4)P zv`gq4Fr6F;e=##R%6Tn?O^CmYo~hx!HTXCrhUQRLss@EH^vlxbZ4m0#GtyC|20^6| zv5i=<DJ7!lL+;<>vfklM_YF2ESygmcigtB<>={M1*^_y)<%FsO$&99U+S>Nr3&TMx z0m-yAo7b;^teHD*DZei3Cy{Q|0}P$b@oA~-zk4vy%V5wwZvn0_rLj79I`P~(;9T;# zCSM38g(*09-hjE|$IFAv`c|*-(V>ptK|eHkXg*${59Y6LzeM^VamIFagxoWQYPo+> zfiZoFFD3cAWfp5i7>(d|hz=I0<N-9>&eUo5n;y<cn;N8jo!R)2eaj@m&@s;L$?{i0 zM-qs&3IL{e-w>8%mq0$&X%=CZEHrP)8fsurH=Jfp-X2~8DO9CJ?mePJwZV&M>q$`g z3)yfvxQjr)+(;fh=%2gakCh9(7_B<|in^D_uWn*R6iX(#tT<h-wzGKt-ci}9yrsa~ zPKnDTsm=}!D;!e|+zx=HsoTTxgicy-G4zbfn(J}s0Ftg#501b6S1Z6Y05c4s%6(Ud zv_8czsEx-UmlgwbSX%jApZ+rVURGp3%NZx>{?f>T<YZQ5tTyY&X!7RPSEUDSprw4m zjXMk?c?Sh8lrC;zftaD|7eKn`CH=wlT^mhaDR0dkMot!IKex&R`4~sKh?~8V9<r5U z6+egDw&YuW8~Coj_o-HwetJsjX7<)_Mnx;8Pd44g2dxIdj`@x2@jBGm2+)-+jcO^i zX8Zf;o&cd?GO?|Nhuh#f9i;6zq{%SpJ;hwsbN4>-PWLVv!8GiG{G#U6$i^!1m_56H z=MDv%gAC}}_^|5riYm{D_kw@!$&0PTQVz9-<Z3+-DzXwxVPf^gK+FW10#)?1R%1xv z7QLG;W@b3~S3$5~1I{nQcdABOHxB3*=2!Y8b)w~cX0C?YO8sZ%4I=7(HnMd%-u6$u zvF&&}!#}IX*$NuLnYdG+O;g9F6j;ff=*C#KZxOAwP=5U5y6qsu&0!c-R^rD`9-#k_ zK0*xc^$#%p^{J}}$7d}A*4aK--Q)S*uqmXPVKwvc7Y7KM?gHI2`ktY!ap!H?xV@&Y zcaqtq3DcO~2*QD$DwPOVW9UDfuvwR*>r~k#!-v>|-0^_!@_cU#oILGt%XXI9V`BVs zD;}=2oelL42QbBr1G6+iJGY<|o0Q-mD(^K9PeorHeVF(>T1K5S9&1*}<=<%f`nThQ zSjO;^#0KT-D<%)T`Q%y>Y!#xAD_7oalUGM-6;ZI=fWJNSM{9Mhg~!LopeMgauwwoB z`QPH2vP`-jJmsZ^*K_vUp5)ty=rhJlKm?sIkI|~ACFaAy>-eGJW&QH|&Lb4|J9khp zlTnY=q3huUfC~qtd2ZSd^CBEmp67i3j(s9K&3m>4&wn=#D>;&<xr}XX!(+zuYgkfG zOJ<H%4S&wg0`Gw07|iB?d<$4McdS4=nTgNp?uQ$^3+z}X3qEH1m(0$t{7VBA=s}dz zOFrAr9~1}A6*qn!Eg0R&U*lTDENTDF{}e%@40}EBXJT!2vDl~xQg{o^VgxrsP(%tD z-YRBxWTr0(vSDzID>a`Q$c?*IF#@8-(CvY>_J)|<b+z=?ue;-g?bmm1;6*m$u9Kji zwgd2Z14R7#wB85wPio2vmxD*MJV7S9G4{Xp%pWZ{(*z{^?WZ$1DoJe_OC3nKT4F=K zF;9oCnReJ_(_>N1Kz>QSR{afDhCziVFBP53`S1iT$w5Um-UYtFW`)7`?4Pn@csY2O zIX?jC@(QJyXS9c3a=l5}(zD=xPo`oE0kRnZ*;5I0UfN9EvHz9}i*`yai!7pkmkw$` zH}+Wv{;?l9OhEukAS8jaTVH7pqe23otb#|PHp_33gyRKwk~Xh5Xagmmdl{j<@v!}8 zPP0YM0S=T^!~E~2`KO8<Y8`;m2Z?pvlppp=E)|Ba^*)zbUuj}1e<kF0Mx(<g2}0Fq z^E2t7G`N-QEA1@!`22LJQQCq|m5K~H{4!t;^q_5)TVVc{>W2ir3jjSe=uwAT1S&SK zB{OVdE&mk3wueDP0?{jXc{h2r3vvT17Kwrtd}sNk%q|Y7A_#s2gu(z729Mo`{*z(~ z_i#oYRanhDkI-H026^J06Lu;V=G{;cALKYOH(G(`l6=LLR9wJ287p<Lt+!TEf4a#( zmuxk|A@iPXmR=wRB}9y}e$RXx#WW~{$W&3{wtrF?{KQqD0*J8HVb$_vX3&w$12Xa7 zR#mgQI0f>s4F)0y6Enw?hVSP+y15mbU^iD>=Q74@g+{u^nA*meo)o_xd2z*T_Lh(O zYhboAO_39DCHg=5qX6LG18dX_iMb4@)8}~_)D&U(V;>7bX_J*|;=~L9;#IJON)O5g zkAvw7-(J*V5~bcwg@wl$-yQQ0?l}Qxq|_tI*~PINlwbTP)*i^-nb#cT5yh(TgZQns zf+=gC@rY#!lf|+)uoRct{A?h8hiWFJHCd)&akKLIAkQ#+Vk>C?bpl|b)=5OrI&sW= z8WFJTv5M&ZtT_s#N+dAjU+ne|-@S5G1Ues};#{Q#?U7C@nu0KyO{UrrNFw;8J4TQM zhMecdsc{&Yh*sQ#m0akKxf0@HN~)eY`-bGrCe~DjWYDELdKP<0&5$e{)AV1{r3Op~ z@aruR;YQF6B*R8JOX0$O5dWdJq{3RJfw!HwSTpSFGp&806Ew3EC<o+g$Do692XTrH z%9;s1(^+dN7J6ZUpvcrl0n)p3jMOK0^6Lr>Ruc_VfovFUmXmi#43IUDxtLNA3Ed2& zCf}p?&erM8eHxTBU^g{V5tkp1Dcb<E6oIr(z#azTg9flTrMi*Vx}r}A#?pYQ<f1Aq z%8DA{1KAPE&XOQ5_`FPlLq6Stl_4_|!`}+=1}~;33$p@0O&a7<!0ay?)$Rm)V0rVj z6_D6xI^N7MU;ax;BCL@}dqm_P6lfTr)&TJ%{hJ;6_}sBMwV)<iF?(xY_T=I){&8NC zc4#FZ33EID&DN*JyLOHHJx{ec2>_~!n8*JR#iRK}Q2waOT=H^#35Aor%(HvRaZDSu zz*V%?R2;24_-+vW&<f+dJ=~_W^p?`AEiLJ7gIC)Y(mVFAcATZR9vU#^Yz|kE<6mGf zKlMx~t&Oc~RwpU6E!kq|Q!S|t(wH(OolCy<bg~6ZCO&Q;UfWHUVcAK@OIxP)oMI7S zGT>XJ+-LRB;qwD3nn`8R9`OqfemA)GLmKqc`q~fYrXTiA=K<F!G_XJIubn$zn>P^S zcLxO<H_mX>&b+$D<}CFAHpuNqXctWUb}+!bHy|?ukK8kP^1kwDMTmX;n8^vimiIz# zStN7yvw~R60gE6nJ(T_wP|{&BRDq`SoA4FgymwwdI1P+(9b#_QCGoTEK5wQdm7%N- z+`7_@<9SscWWdV?@QQU3@7?|xyXWI0nUu~(pU3evnX(q2!Ax}ed$~P5Lau2%*%dfF zP8*PXFSRoz_l1dPpOs&SuUT6`uzr@|=sdKAHM-@e4wj~3K*+4=oI#3c-NGlz$Bb_} zeR}^_zEEIX7Pk?A55e0S{wc5EOH!iLsv_;*2~*&h_FFR`>yN}fnBdjKQMOAqse`t3 zbg}f$iz5;(hbDHj1XMPVO(hUO6?Ufid+42>4sa^4OohdLIk3WsqSDLnf#^bDs<>C& z;o;h*-r{P#%R<Ud(YJl+liyrCe{CCSAI$za;8b1{4UGBkW)+38&(yB58MZ0-J`fND ziP*-_`3)*u|2F&Z`z)=uusfE0SVsU;Df{<;*{AqyA_sV?4gZmLBZiFZ{@KF&_gh~- zF|5d!^Ab>0_EB>k$@}IbozU1*%6m7KUf7_XJ>QnPsX{MQU*T3ZC#A9~ktm0akz?2A zFo=G3&#&a3D%yKxiZge8Wb<TVKX5LmCTZqjEoI9@Ndvtbq~Y}81IqHN{zF-<7C8=1 zJLe5f&TD+OLp=QhqI-TsgC+%KthK~X0gXZH>x#C9inanEN=dAZ?jr@(BO$<`px0oQ z<NfCxUmnowa4ukeX}^H)w@B?@)10mBolESG)Mg>ZARyYDOo22#M}5+*kw>2tx!a?! zJe3D5?lIJiu<hOBMne*HwSMRdIrEnXw6l7*yN5j+O4dcN5$@%ZtIEQUs~B?jc25GP zwttPwp`h=7SL7Xa%<Av#(yk=eGYntj-DxF?o1KPO+H7!|zRY~u#>X{e!vl7>_l;E< z^wZ>#fYT!zkzWr*lx>v5Yz%+#2ZE4#+9HxzThs498FT~zI^udd9QCKI@sG@;K=e~+ zelP!yZD2$Kg165t`SMg|f}5>k0GWv9bk}}d8~f>M=e6vaBJ&)Xy^OH`bv<2QK)i@z zY3RE95Hm^lItdpW=6;`!?*2`c(~uw6kud;CdjyE-XTzqQ)$?k8Ci8-G^D0pq`)M|k zaO$Ynx8E+a6o_<MJ|@$0%j|E>YTqA#vH$&-)`h1*ZpyZX<gRD(UC%^%vLt@<d+Big z52HX_zu>?nAo*1zw{dT8B0z#700Jb4?>CFL7cys9HyI?<02C}jDpAX~j0ioaNPOFK znrg(ky1`dv!5ElCUhB1gPZJ{xMd}z4z}*Jy82C5^YJxu^806I{EP|ri1%+eygnhE3 zCl6;Vf@YH@i0cf`K#B$128bn;N;g!Br#5Yt7OJ}VOv~sJyR6UUw2qD=&Hn0+3#}>; z3y@>?aZB}*=en-%dUQ8JC7eJa>^hYjH&aK07<ez2hxg8cb<+hxB&<LYJc3T;7<A>q z*9y*>x4Avj$VHrM90Y*~#KA=M2tX@x+!pkc^m#%;@}A|Z-qQaS2SX+)`~yC?K{lX+ zJ4E;dMtWdDI={CJrTzmn9KfMuSPe_oh__<)sGz5BR?C$bEz2AYv3TzFA`&O@67vdh z(s(e>s*d8eRmOTZgYP3a0vn7%CJ=j(J2kJjyvz4`Csem5NV%{_^&&(=8B{_d829uR zt(SjgAT)vybU|?)7fNv{ZCOiuuk{F_-#f~8RjGj*WI-Ezz!ktB8GOOzU`_%HG``JO zfFDf42=-uOFcSru?KHq+E&w#>LpBTnI&9It|9i<?INg&>z@vi)^wS!3cE!R*NtZaN zI{Z(33i+URMA@?K!89+%$S$M0?$Q`=QWEe&an`~5Gavu8l|w=-paIGg`OAmC=tnmv zw1Ek90?oVpQZIrkm_f?(yp;#-SAV4;{6Pva>-FsxvsgR0U_1Y&NVo!Wc+52mu)rID z!51VykJwPx_g!EDMcC`<o(7=1H#FLp1q7(Q0g!;fp28K}!=g6&-TR5%k3XPr#tfWf z-)E``aw^8Q0K==?(R3CJ#$2i7<V)*_&B-)X=_WwPku!(joH_>)+PQ;=Awxb7`$Uu| z@z0+?7cUMPM2Mpyj~)?y1c``bB9kW<rBvCdQ6fmZ${fq|sL>;vH*x0Fxszv4oQ*im z=u^q3PnO5nC_0viWh0eOPnskdQe;&_iR^@U6o~(jMvNCLR-7pDVM9E3(Aq&*knJ0{ zZ`#CNGdIneG-{??IFm&U7{6V*Xc25BO5rF_pg3{Tq{)&cNstsFLPUrVAV7TZ;DG~& zjT$v(#Aq>kMG6!rNRS8t!h;7688Bd|Fd+hj1`Y@?fp_o9DSZ6&;k!4ScyZ&$ktbKa zoOyHS&yD*t2c3F#>({X__vh|kqXGyPJcuA+LIn&PHgxa+A_NH&DB!0U-6F<}&o(&o z@Nv1akjX`mNWwA36ho}ADiE|nFu=SB!@)7gAmfZP(x_{$HR6ivt%2A==pcp6a)^(y zDEexUj5Z>~s;Z_c38kk}Vrh|<AfW`1QD*<Dsi+-!^a&D39_hphBt%)H$DCRkMGZiz zY062bREkQf7FSH<jt(A4v8%7Z5{tw>_z3Y1JJedMt+(LHu#LI;f<uHH;^+d5F}m;q zu)z>CEHT9xa||-cD6<SR%{cQ6wE9R(;e-=RP>r<?Hh^t532Iva0RueACmS8m!RH-& z^2turQAxc{x>8Y1Rn_FS`{$Me5O6>|^32PCgVxw{?>!V&7%hhS?z;g8&GrMLvj2(@ zaKHkgFsup%7p&8Z2FHMK!V2qBvyBZoWQ!n$Ky2ut5yuLPON}(*NW~QmX%UgAV1$t+ zn-<Yzk{gLSGN&K;?bqLb0p>T7O9uam;SwPAMHrG})KF?hC*zG$N_Rct=n*Jt$kLFm zw&XI9u)YM-tTD;-upoinki#uCF|3e|BSg5uFEGLY1F$=_u%Ze*5#!U($R_J=(9Lcz zG&Ip#Fl|xQLTHVHNM)0N(gz$s0D)%mIpvCf+yPa%RlyFsx>Ln2+id9mc?SanWF4<O z3^GV>z4lBn;RF=qqi=@2Yq&vJVvRj^G9&_A)(Ha-d{&E_8+<TA3M;%&%?&%O!=Mk* zG7BOS%{>?0b**w2-iRO8(WaV40fdrDfJC^cfCY|3_StE#-FDg^A%%oBIC%u%o_?fh z6dRi~{d9<7lroX2HYTK!8KD1oWL=KX<ua^4LLRrFwCX6++d1CSwvD>z5MhWkxJbjn zX>ZOs&%%0Mtg**{4)n6jI4k<Iz2{T9QAb^~f!Itc0uER}0YK0xEbM}7`S{w|Ab2*i zMUa9Ke1|`7V1NZI00QHw)dp_G9=hEvZ+g2AXNI+({t%%E04m%P2y{5ZL_u+kYaE0m zgsp60NJA;>7C}5jriEyZT;-~W=hVfncDd+9@@mSAegcV1uwoCfh(se?w=dYm?si@D zBJCj2i8c6u6px5Rz<ig*AF(78$Do2LAc4g!(gb<Qi^^1-mx41qqFo~CO7$>uz3hpJ zOeM42$yBzoHPPh_LlFM~9U|nH_1P&fI@=li6tft|JO(mB6BPb%pufE#Z3U-cRBD<A zDM?L$QV=lU0Dz#6Y`Ebc@X&`ohLev_RgjmYnqV)1iK<o^LI4YB8+l>_LiOazJ@A>& zuV!EaVGT<^fjbs}lm){~B94X%Vw{7*fJ4YdPFs{Kh~*LzE)jvrh!!zXx>N)@7QJh9 z@+#fDZqm9omLV0r3*Hug^u<V2f}jMwL_ranP=!`vc9&RzAv8hI+QBXoG<ifDx3H9& z@JlB$BHbMkv4}vBpbv@Y<Hjn+u@im8OC$<Ym>7Z<k^%9M1W6=ZcvvAfP#_CaNCOzi zK(jEg4^Njw%%1<|=O;i_<}!o|rJ<0PH29oyH6G}|YogZ54GN$T`8WhE(E+M^=rWhP z4CYyxBOQONm91@c>s#R(SGmrWu64ERUE#_dU0BVSZZnTE=a!ng@yb_xlV*OZDL8B@ zs|nj|)`6fUEozAqTawF=InVhag$z+dMWo0P-?<SbE|H#zh}e_xiId<pq7tkCL@X@P zh%*9ApaWg#ZE?F$NRWatq<{oNyZA4gL;^=_-~~thWzpk#)Q-z*#2iRKFeR$gV<2<s z$hc=Ro2pD@8M=!bU?74x_~i^_04F6YdC9}<Nt2sI!es21nazZ9f1znXX--o&075D@ z6JTYf4sic~Wc))1*~kY!Z26CW;FZA*cJPB6Je*&mmBP^R$2<OkjtFSb0T7T{tvIku zy6q}&(5!(C@Iy`h2=0a2EYJ+Au(+G8FPst@=UgU-Sr2t@v*PmXXFaARdCrrbi!g1x zoV24K;pnxN2q+|Ko7+oFnaWkR@|CeX<wc+%p|S(6?VzmBQLup$PIg_tcEa4`A>t8W zut6kFx*~OTjHTIwX-o~N-8pb~Wp79W9oirQpQa%~W0)i*bEY%+vA0k3lZ?>ho4?Q0 zfRz42C2O#X0ai)?0uNY#0XFcDY{20k?9c~1$Xa1lvuZl4c6D?7A%p^Ka8?t58wlq% zLcISy(>^CgVKoEyA0%uthTN>7WF0q73zaiv-b$xB@vu1~hE_{ToQg?E7b70^3rA&$ zMr;RqyWCbH%jGsVmLp*bA*4YRwq2+fD*=jBC;}9$QzM#@1SJ?D;u1Az10P8;+CO@Q zrPy=nozFtD9kV5o8CnA!Snz{4fPv6tF!cJ`XURopveADE+WnkrwEj)CQ6X53DrNIu z+bm!JUC752UV)FUrTW#co^Z`;?hkbQqZ0xEj|2RAo)EUjJtXXviBCLDU@JD8E`BUz zt?<pp*|@Tn<yL0rP{_>rm~-w#5yv{ht`=eYv`TK>>>x1;M*!j&P<HpY&mDKUSGoTa zeTV@m23F-ROVr(v;DjOo!HP`S`=7s4E=`gbi4@e~5frmZJgG<UK-zhGg)CD|_Z&VP zU*Q6Ap-_1(K2$_oLDB0)>L%&uNs!OiGe;v0$xWV0s8v8}06suA%mD*^*u!hOq&d#d zdUN2f8pGOHzybQ|!CT`>*Mw~W-+Y~)Vk!28#eQspWLzh3T1$sG&apsfn$E39`^ORK zTp&IdPivR<$T2G2wz(JyP&k4O+kk{6-d@nT@1Oruu0$(lfDBB5+_Fre4k{8jAr&TJ z0MYJ@1}cq=;)x<b4s4(jN{e}>OI;-IV+`)PVoKrk3{A!d4BS8jejpCiKn?#YF7$@# zPDt;4;wPydW2rugP(*14Ms895r)i!BHa4w*J`Dr(fe{$t!hUb~&`PZ!YzdjL2_Nhp z{NWxjED4IK!`$Z9LMT`4X4gz8=@3hW{DXy(KtLFyu@2|@Vl4X_C!EIM#(3zm+yeXz z;&OOw{G#nkKnq1uWVDzF$(o`^`~~giuMF%@b}qrT_D>TOaS<7@5gqXnAMp}U!3%Cc z76|a%5GoQZAr{zR6uwM$+-|n;?I)h766&A^Ho*`i1_R|x1FdI}DzA|AOdt{|4dNgR z9tm5@3qlMHy%J5mdZy8oO7#Xs(m=z$N=XMV%{5>{)3oY<+Q1*Cz#RY1L6>gH39&I7 zu~EWW4GCQh!<GS7j_GZ14Ft5%=tiU04vU(=5WcF<42{j3803biZrO6ohk%F<dyMO* z?VXZH?3k$iR^ld%M<@QpcGPYU><|CuZV{)f5jP<sC2}GuvLY=qA~oR>NTCG+p%X4a z5$8^Js$ma^i|@cF%s8r}=tUERKn^0oj;MrPB5$R-<V(t8dqD6Y5NT!7U=Bv$3f3eI zCZy0rFXP_lFgR|0#&D@F0|;!;XpqJ<@{4Ie0ObhCfG#B)PT>&Xfgila8<Vgb!Lq{q z;U6*p`D*QhL`+xWqp(hh9j$3_7z-W^BthhHT9U2m-f&yuuyX(Ekci5!5AqQGL<=CV zjqKcSUJBA6`=xdysuI+W4UWMQETP;WaS<;vGc_|aHNh0pfCnrQBR7E&vrH3@!3;8C z6y6TZMsX(=p#ug15@rM{rX=8GlFla217q>>Ft6e4KnGaB4#sIHd(ju&XVFg2y&kOw ziKg}JOR5;9<Q^qbDqvDv>40*;9j5UdcyBC&Pb|GNm@rHZILyN&KrM5v=(rGAq7QI_ zjR>mGv7CkUWDGBB>{=pcFENV_yN9!0s_VS&>(;Lik?inx;vi{9q0~+hwm}oE>@qcB zGbMCFDKaBBk`P2;6F@-`F%lw2QxouS8}=X*KtU4~>LmYDQYSW{4NgE4j6~lgW_fH= z&H$+<uj|gzLM`%fyWV1_vVabBh&VCsW;70y+UsYCG1C0z7!$>mq%(l}YihR25_SO& z;DH^?Dm*Jl__S1lr0^e%4?H>unS^dV&JjM2&ajk@2Ud)Q2*+^Fa6Y3&`)VwQ$mt$` z=yLXPo!aSK!fr(l6EW|}Kp8Xs-p>Cb;TRM_DJb(JA(28MHBvDW6+TlIE&&uIGD1c3 zLnE>>j{y+Ut}@B(MA5D_ZK4yD00}(dMV}}}W0FQC&$=c8;qZ(%w`&f@#|?4-2I3%c zDnv+&GQD_)Pn5ELn5q~H<xpNPzn*mV{_6oA-~j(5z#Oh18+I=r)~ZV*NC~yETfG&+ zxI+mDps#3U`2uSToe%of6b$_%Ss3dK<53MA$4>3Bhng+3`jfNnu<L@XFaeeQNT((i z(<Ttq%M$7#DN|7eVKOa&6E1-hI8;(Ak`pMlVlDP!DRwg<b|Vcz6f^-8Fm+-lGDOLY zVXdsoP&9aGq7z8q4=Rcv)hs1ybGmAj0}l@26z+QxDGuV`0^EQ?f>J1nGFY|XC}VJw zJkEZQRg|KV<N&A#osrWTfaQiD8NdouzBOyL7OtQWJhfGVFzgY;(Zk;6Jl2u~7G*uv z@eAJ*KHn8yoh1z!WL|HK+3@k4gviH6<j4O8lQ8!%bOO>3fu}JOlmIXBAuj>{6g4#| z_F*FyQZY7iC3kWocN0*d4Q#+tGm{fGfpaO=5?H}TtO3d#_R2=pBtbEFHen7@;9%wm zMrHOSSg|VpsNgzqR&Vkwbd(MWVrA?g;^u%Zba7}$PrcU5XE+IHj#Wu<V1Gmdzm&16 zo+jm_^!Oyf4Ghd4`XLIx)@-=6d&6eI)@B@IBW~1#=twLb4GXc@)L7svSqz7py6G;5 zDhwVcKlRgxx+Nj>RoW&Z57Tczo9HP9mS6*Mb_|fpI21%JVH?;WH5=AZC6sb0wi7s^ z6EHY~HF$$Fm~uN;6J#L+?7$Q>Rb>A)6cjl37zzOpM%NNJ6w5O4Bp-njnne^0I49y| zVyNQrsHe_cN@R931n1xiD8LRbM0h9U;#yExhqb+y^5Z}*e^88nM#Iufjy0T>(>(0} zFn|$AO&xqMOTjl)zITjM1;YqIgE**M&G%df>*&~XO`9?d;TMJ)OMah49=l-sBBbiz z@NV&TAN}`#2lI3Ol|TvDN8)dx6xdNUl`^+M3><+K64zoUmU1~blQnshGnsQ+VGT%t z7Bs<vH?v`jK@b$OVH>dkW4NL=!2|+<b$FsxX;Vgb_#-+3H(LsKM<&nCqy&$kSJPmT zew76=?l_ycSede^=8I{Um8$=E&{-?xfOG&0%;6tEC5+9OjJ<Z7&-fpp0an68`Ie8F z(zaKguh;wrE?3BH2jq@n?AYj(vg{&%<&Z!3bX?jgK>rqSi>yEmGM@qpffM*4BQzr) zxq<g!k~M*IAD4nFn3E-XqBD6DZh-{epcOWu6FN6zE7B5L%Mld88W7NtGqT(=5fU~5 z529cbAaIsr*2rq}mQ$)mWtA*?dB-frEpAZ++@M0_VtAFfcxMQy8Ur$nwJAfc^^j(& z80CslE@~<T0Tck{*kR`I;RwAMJIZ*gvx7T?fWv~WjnNk!>%%?{%RR5D#o!Uf^cXKG zt6ur?o`Y!o0`vR?R3!hX0$>4}Cl(o@uq-1XHX=CzWFc7$rl_MSSfV|lu^s!d9UFro zd$K9p6FQg_5FrIjp%WTgaywNMj$!SpffE{*b2}8J4GI!ap#{1?6igLKX0w)MbVX8x zCT(^sa5g7(at`Pq4g{?ZhB>&gg?NiMPmVTum(wzo^ahUcdEo;EO0KFR#Rq9)gATv~ z+#sy7S*yKzY|LS6!8^P$j1>6Ful{N+(G{JcFU6M59kZ#e<@B2z<bL<Ehv=Gri3mXb zbjV2S$OJM*3OJ2I(O?bgK|l0yHFOgo84wa-6hvWiGr6)Qe8MSwvN3oQY{3bt;1)L8 z6DW8TPII&ywnG0w5+qNy5>`3{H~~eALd`(x@tViBZ(3wvDo4!(eDq)lVBiiGiI|0Q z7mL#cfiXFgc6mciS?>!zb`aCD*wYdK0T^JwE-1XITpPQ#yM+k~(P0A6G6MWdEzgmJ z=0hF-#s}KbO^J<J66e_L^M11hPiaa|q3y2u`5%ewzX4p4L-Alo)u1O5Wd9t6Ex{T9 zVTw>Vq8Yow6@AeuJ3}*|5=eowEn9;xb`**M5LAJ*2fHFyxysTl3c>*ISllQgMs`19 zhh5Q!aTiB<Q!U&A4k(}v<X}x4?pJqlNSXL}od9W*dT1nVZ*UMgpV}Nf06ipyQl^%w zbwD4~!5{y856iQITdRE9n~*yQVb<38ZQ^F=?8dCw6F-2>ecklE)trXdd=2R}e*qbt z@|7P6*&q44zXdYM2Dfna?-CI_B0C{uBN9_9(}Aa`Vk0|)C!NtLToe#K;U62}6}=N| zVGLq`!!^0HIl<D+K*T-TA`jZc4{8%qfDklcU`$eF(~OQ{J9ceZ&aCHlBO-TYDj{~- z4Spa8++ciY9f{At(0Y+bi<HO-2a0{YGY*B6rs`=0sK2IK0TLh^(gAC!{pll2+M#~x z>*`Cf!BYCFY|D{uo*RzWHih^@*yi%Z%>CTKsUFqcFaMHH%}+23Ib9A}P@(8`_Wa)U z&(Hrgo+3$GQ6cleIatv}!4ndG@Cm>04gc^9U+_I#7fyf-Zh;dTTe2yg6ON%6(0~_8 zp<z9IGZFfrNWltbpcO>Eph|T|Vs>U9Zv%H(A_z$>bo32++o#hYO?+HvLyvugeB<QD zF^shajnVZ=X)03*YM*rh5<md1Kp(;iTdBVJ<Lb(xeN-?ktjX2ZZmk2(6iwYSt*4KU zhs}=5y_@89zU%gn?|bbXf?whNUz^A&1lF&)2(S<8K{?cO`yEp$*0MEyBtbm?0Ya1~ zfu0H)JSZxm!i5YQI(!IG;lNEEAdxzVkrSs;#Q^atWl5vPO(aX2+@wj<rAwkf4C?>1 z@=~Rll_J@Mg!7Tkoje~k`q^la&_sz488w77sUbpy1_g2&DA1ojeX3UFgC{GVJ9g~U z`TCVkoFG5^q<PaO?V2@d+MXdZCQKMFUb=MAV#P|8C{dt5apI&&lO;)z6d^)H2$01* zc;LWsqehJxF<P`(fdYjI5+p!?=&&IJh6)oTJXnw*fdX^+?AgPYFW<e{v}@bGjXSsQ z-MoAIrtQz%@8QIY8$bT;AF%@n96*pTp#laB8#;Ih!TChy6e}#xm{G&VjmJI~0}+C_ z2$CdAmIww6g>RH9d9~Q}A~(z!GH2SRS(8>;Z@eLg9CI8v$5&n5afeoX^zr|oRZ~Sp z;UI$$qEu2wAwrZ;9{$u*PdGthQzSISgrZ6*nZ(ISn~20oC!T0j%^sq#G9y744HOY6 zKK=+~kU|bgWJ9Eg!pSXK0HF&fI~Jr7M}VkOijz*xIFgGcU4lv!HndU+iZabqVk9Gm z$Wu@r4n@?488+1vg;7mq)m2z!#g$iI9azT{BH$rMfNJ^o));ZoWtSFsRk2rJe>u?} zVTL6pgknB82AK_$#ZXxbnW1n32_b;s0SBRBP+9~Kq^1BP|Dcl(KF7^UYpuTpXKSvy z?s`vhD;VH_0}((cT?W>HfSm~^XxCi}F@RUYcsTG--g)V**PdWaIN|@-e2iLQUl;i0 z$6s4(1vnsq1}2!Gf_5~R6(14S`G=eqGL<1x8xobsnvI~j(}-oBnBq#Bu-KxDFm_^P zDVb2h$|w!-7*Rq*UW{?ZKQhFLE-iF%OD8%Sl#rCEw4#wG3};D_N-d)#${-uSbcsqR z(o~a~BSHeOPiwMS)KN+?#S~N&QdQ@jc;ewzR|mo&LKbwO72sNg!WGwCb={?xe0~Ks zn52g#280inJ{H+zlwFots3C;lK?kOeHo*iDoR$Cu`uO9TY`p#r_-?`ZLwMnaAC7q9 ziZ9N1<BmU$_&x6YgGT`iI7ci78C2&1vLq;rLJF2W3!V*+QM>;bdPJy)t$ToR%NKp% z-iM!|WAyhQfC3I!AfI4$^{#{SRyCo$7h<T?h8*_$;lDi#Tq40SrF1aD2*Vhoj5C&^ ziXyg1?9h=4iLY__=4WhiCny*qi}nbGB1$o-C{he42EnK$Ntf6%!x^&FoDwm~WK20b zQ_q5;CJzM-5&0^bg^q?atH?_$dFskn{*VO`xPfX_^G_NIb*QZ=N-vFilwjIpn8PTB zF__ZSrYw_!%xq><aXS@hOoIRh48RTcaECqm;g5g(19C(xq7jeSxO?C#a7=9CZ2XZN zb41_(&KZ_;G{=F?B}+RfXx6jBGoHqnM|DL=0(;s6pZNd8Zg%3T-G0u1JKeP*T?9f< zyMPBTJjkm~#H-M~ke9rDF;6JY1K7@@Cq0AJ%z7oko=8>(rBc)a5XBh9MZ~v|^8v{e zob040KMBfEauQ>ru!SKyFbjdG(qaNB1up<`i&2C^Wh-+eNjRYiQv4wVq_{-OY$hh0 z-Nb+)`WH~v)FuYz3n_7eARm>sm3K8Q4sj4c9Nuu2K(%2lZ22G=;G#7Vc8xDz3ru?o zGqx3;4Kk9UOl2?wsu_}MZa0j;0u-Q{Y_tZ5PV6VImgvub+6s#QAcN&F7ah%QpmQML z4CqAXENGc-T0A%p8Icev*KtdY^O+r8ykMwunG642=~`F2>ad_Z?vY;gsu0ltsV}4O z%U^{Q5%g?=Gci%`mnUhFBRc_9pbo?nlBAy{!)HEGDs`z$9g-<Taf>d@z!st)UsXxL z2}x4&7@^>VKx$dbk>oN2fgr`fsz<$G(xgPhMAJ`xmP}>7shLutlLVp3AmG)Z5JP~$ zALNiOL3Q&jWXO*Q@#3{|hHX-aQD+O))+u<Nzyxpmj1BGffYb~C3+mv<-eM!r&=zNK zNGz>sPy4v!ID<J=l)x3MgRCuPrdi(sBSlk(9`&3NjT==XeZn=a{fIPoyHgi}e)lew z^05!ad&<3*xx5Y$5<~&h$<9cG$eE;Qr&|B|sYZfIvKhIe7Dn}vC(p;!^r|<MKkB3? zbRmQrAY&6jVg)B$5sN)ka+W#@YFPKz0x10NB-8`uN^q95oAgX4$6N%z+%#7U8BHqB zyi;Bolpr@yKrDf+8e8CqwL{sZ3*&SYV8T|INmZ(BjmZ>b*%nVx&2s~Evs(ldfMaav z10SgEv5!xyMB#{b$ipG%3JTzW2Mo)#Skz*&X6vjkM(cFtsnqJqn9(%K=ePHfi*Vz( zO_KJ`cXLRo@c39f3F9kYGW{8KtNVyUW>=>G%%3B(2VVCj<i4>euX#r)r1c7V(CIyr zFi4;UVsye3?G1%ii@^#}%<>@q)rkKlWPt}1prU#%D)7w^JWQSe?5%2gu+SnbC%fL2 zf?OHUAy^QEYYs?I+jPq}4W+e2k&v7wJZBQpX{pDm%`%dmp$AGOntG~603!H@J^V)G zXzK=`(yn%G{4qIF925e>nt(!&C0mHLptj<<twmRd(MWA;qg!TUaED9lIhypOC}og? zmfPH?yfi~H9pob3j3%69H%!}I(TcA3T|9#qAy~yP{UTioP?CbtpPV?MFOG3kctQeT zQ1qWm;R;?D)fDg>*+DeX3Osn=MJ&%BN(@ZE1m|SbK0{{Emf4gE*Y%mK_R1WnsX@RN zh}MHGlw7vPwMO;j#3)vAupR$%15JIWQ!$*Zj7xRdyWw~Mr+5dfU;}MyN1NJWuXb|8 zkpW;SIddDxqUS)@Mazs^GGRoWmC>#4ZFS3A?ylW%&n2ig*zu&vy*HX$8kOTgcX`dL zX~1r3BJFN>kvt^{C_wQ@|GEz$7IQRtE6M2gV*Hb+D81=X(Mi*<7xn5TMJgvihGkTh zla5x!Bp@v^iSVc(o$wI{2+@icu}n*8jR~lAHgmVy{N@eJd8#9L6;>-K5H1*kAJoOc zZ5BOibI~=U_VTrDHC=^^S*Hu#31hd7%2dh5ECUq4?7rOtv}GT=kn2BoZ2w~o0$9KT zp2K7rzya3rHlL#%5GDU*6J>W+rd!#vZXCsB;^JlB1ZII(N5`cg3<591Lp+G5Z_8u| z{nmH^cT+i~QwMhvmj_fa!h1r+c~|8ll7?SwU=6H53K2(fqsK|7$AdlSgFnc6h1LqW z5Cc4L3#}jurces4Pz`3l5uOkV8#6wf&<d?k0d{Z;o1ii=f<2uUK%Yh?Y?XXH@m31N zd<`UFM^j-ImM3&@1tRbV2r_FO)E007PTiMuCG;2Da!yWHevkDXGXO&|))_UFY!Uzg zIA#C|U<v>54*r0D(nfZX7+Pny00(e6-Bv7a_cjmJ9h_1+b%$Gs(K@c<7rw=1?<P`! zw>x7-Z}w(*^y2?Vil-sU<8S{4aMmSoIF(2#ViK3P37v3x-=%p7F%X#aBYd_8(l83G zPzpgfXh0~9(@2d=HF38f1U_I2w;&3oPzu|y2OQA}QD{}3unD#R2@|jcwx9``_ed?m zX}<(>!i0RHMuv~@Z)UhaXgFc21|bu~2YPS^c`yfWa0nuB1ctCK*;i{HWOTW97fN@E zC)S6J^>mLRb!$^>SH}VECjk+l8VY~`_&}2MM~MP8i6_}l`p18l!)?%^P{;Om2k0H4 zNM#n4TdnhesOWBTL4p1uM{`tC7-(jC#DUCZJTMhgGu1pKxQmfTa0SO{ov;bO2uZY* z5S(`;G1&iJH;7+=P=iVcjiN-2rB{VziI&m`N~K2%!mtJtU<brd3ZGyNfRG8rKvY5E z32oU16@UjJBO{u(g2QJLUub;vh<u|4S7$ghbhUFy6OaOV2X*iUZr~?wPzQ5RAlYX% zb$Ey3B#|bBV(G*}XwyzqCqtY8Hy#igH#7k_27jX95A2|lqLq@h$wUN20&1s;)B$b= z7&@P5lhaZy42Wg!p?472llt+K#6?mU2p09G6?$}dNeNv{iHnXWY9*LRY4tKB5mdyu za4(oiK@tkEzzloP46LApoaBvbDUDSqpYutd^=Y5?DW7U-3PJc@kZ=NBPzta>4vLTo z?79DyqR<Jb&<mRY1t#zax8PNjCYXd-5{7x0Vc1q=m_Vk6a}P8p(03JjAfkFu2Yz4& zdN2Z4pa%sqbb>Wl-*j{%wkW)|hmlek7Fn86_hK7KL-dp?I3@rl;E4aA54h=1w`rt* zlN`OkS}(bYP6nI^2p-bX7*)oA>9z!~vv(aeV((Ug&pBquwSmjUT!{Bv{1#mw@^3a3 zXV?XmQE4zL!fDlmJ>yB9L_&M85DQ?*p3mq>Xo;VJDyV~cmaPDUoK#Ar&;=pj1l^Mf z({Ky0a0|I`3%YO#PA~&jP=&oWGVW7p6xuQZM2|ZIF!=~H3?x^~R5Yo!T+_J~dGP-S zL%;%kfFOXynOB2rpeY|q2R0}KY%GR08JT{YAu5Jg0i<zb3UB}i01b|qq$_!U&&ou} z(E<k*0TGZ;ZRcd3=pEtl7{ob>M4*#e#&`DdQOpTPBL$`yh*H55FZkwx7s6&~>MuSK zBHRh51s0Fj<6kehF?ebUtPl$LrJl#|o~tm8gDMLP%diaF3JnXf5eu<_YL<rTgQhTq zk>CV--~enO2zSs2B1#65Aq1MB3kRxu7~zfy<AoMFs`i*B33RFrv=sdaqVgi5O!F0P zzyfj*2L*W`9K=ny3XwC)YZNIqWb=onSp$*PHu8jQ)A5lEU;tE`1OLDdvLgSjfrF%5 zTPw*y3<l5~PTFLifgQ^dI-^rMr-M4@rXCK+Zfg`S5*P-}$xULmF40+d)QNBQLNv+4 zFN1_YhV+!($z46QFm`GrPPK!m0CIcU45Q$<tAMbkN2paOv6-v6n>(@hS+P903QG72 z<gf=+zyn2~1WVupMNn44@KmA4mAj|1gUPZj3x;9{vpZ3Sr+R8j;d~!TrU981e&7d& zFa$Xe2X=5EwklXxQ&@ONVtWC8iX}EhP$?IwqZ%1QnxUGOB^pzUV+nu&+VBrv%eB#J zzPgeeL|_1!$acTUt#da~;Oe&H3On+_Ms)i|>bkD<wzo&wTxZH}*g5~WPB~}W)m@3} zf&{@zj2lXiyNt)+3eQ-%sGzV6I}4nv!Ll$59qhp$thp3hdI(zzp+LH$Fb%z+3%Vc- zy<iJlX>mc4Nm<!nwM2XtdSGjnp}M=FaTQ@k<BwL62YJ9CaX<$YfSJp?na%5&A(SZJ zceLh|w3Gq_EtV<YL2OkAwd_|n7oY$Jpa2Ds2Kqpo>ANdkYsSQJb`XF7|JQAr18yN; z0w%B>YU{1^d%df3MmyPVz%_xm<D5bXonjg<9GGvk7)a7JU2Iyok~cjl*i(bqud8G+ zfku`jhn|42o{meXo9n^00Lq~Z%AYLCqWr<9tigi13eH#x<N*H&j!+DeCO+o{Xh6ac zM^X@9MZ2|Im<9%FJIr7`%$Ta`p^sT7tY!!<-~xqUN6hPCwicsyv1^X<C^q`5>x2VR zhnkZmPoR+j6(9i?0GkK!0ODW|?~um1g2w6W8<WEa*2;DZRe*3OoM042#Ysl$My^p% zA8qu<BPB<?lec%YfdK5cN*RKT*OUg#ivom#`<ifyJ3gC~UXH7$eCmv{K%X1Du&3<N z9}UtW4Z@p?pWbK<lW>=gJC+hBBn)8?pXyV#d!b|k%r$3*shSiH1ia5Q#6;`|ZZHCL zKnKlytF{(Gbz!t7)~o15#lV`)r+FD#%o*NGHxi%#46y$I13(7<;129uE9>mlx{(~^ zAOTdQWC^u79S~ceQ^#{RW#kdAZ>v#z$0&+o7x|$dfPA-toVUNDTr8E8N-2WV<#;^N z$WeK?3X^#*$RhyDUi*m(B&?^)$O;-gpPt;&9zDt(YzrY>%AXC|9-YebY0?B*4BoiX z?A6jS_|l(Bl{YM^1(dryVXAC`)6A5HK`bxwk_TV$YC(|1%S#|k3}Q!z)J8jzQq0sV z=G4O40$OZrteI@dD!vUM4)Bl<kQmmZWez{)-QOKK`j-gsjMfV^lWE(nHlTpTc`bWP zt`SHV`mw*c6VS$`x3I{!9cZ0wrpUPXJiBPPcDDc6dUnecO_ru7+03BH65I-?46&aq z(jVN}5l-PCJ>i@?3-alWuFMgrt$Ix*!ztT>D<gcJRx_U#YP0PVyPHh>2*e=T2YH|e ze(-Z~FamCHeVM75oM|<LWmsHOV!eh!7I~59_fAiHbv9H1IOcx@u+@(U-cjz|LAKq< z@ee)#EZkP!Sv1eg5@j~owiksheEfZVhpy%ll)S^P3sT4|6|V@L(2AUkhV7=(Q(!3Z zoeE6g6D@k3WN|wP*&}Sx<h7nvDB77l;j@tF5)Rsp?&y!M*&ZCR9h})4t_X-w49<9Z zv`l(KvJkVof((P_^60V{I@`v?;=^3C#jO8oe}J=ofCqG72rw`OdT?B}N;SIkVc--O z-j`TXyabH3Lcp56+f1x*GdCC@&I;gvZ7dG@V3Jkd8(=N%w4quE&>X#))-&nlQbwf} zmB(_;$K^^p_+htzC(vvD*Af!1@`|SYy{061zyL&foTlfSS5=k#XG_I{8V(C0*9^sA z!4FQ#k8bb>kMN(Z=%GB)4co!aXbp;>2+e@8J!p+Zg3A&bR<JFqp>~flYic<CyT)uM z0eJ_0a0Me^>+G_bJl@1|A)`UgbV<wH#NJNC1}auJDxk3e$I1YykpK@s0EWQT)qX4J zYxKE6P(0ASYga7V+EB_uljAm}Y-|6e=rQKW*~fl-=51kt#&t(*Zj^vMi-JwBbN+bP zW#@@~O9QSw1>WbO)Pwc;?-MWZ4~xMfo$!0l_ogh;dG89SU=5U@2;|_64Q{a?u2h~b z;^B!u1Xk)EKWe46k3*A&J1s$3L81rQ1#u{N!d=vGWGIM|hf!?JMDEm)A&7&h^Q2NL zqv6F&ZU7$OtVz!s)L!k$0S(xWP*1Pc;a1OYy@2WA-f=r0c1^c=9Y^SXfrN+OhTKwW zX7)^3z%~Woj$CJm%Z2?)GWuQ$6SwJqI`{M$pa7rgw1EET|IvJZ3%Ahs@4wjvpXgQS z3a(%c$3O|z0CG!smWmG$rUd^EBxs7%!God{dSb}1(?d=XIc=g?ag!#Dmo#3g)G-ny zkdH);9NB2m$wY||Au`m`<sg`WWCr@v$L39&e&!gOBEn6bIY8wMebdIM(KTt(oFOwN zjF&D^wOFYV#VQmiPMj=Rk_1T+B1D7;0Rn^v4jeaZ)R+;Y#R?QCPM9DO0)z(+7%Ese zpkTrR1P5&Wd*|=oVZ@0QFJ|1>@ngu58T&IQ+45z~nIZdg_pghA1r8!es89jJ1`ZxT zgfL;^1d0?bTEv)9!v<O&Jb;W95*7*9CR&|9u^Od{6)jq#dhrrw44E@Z(;RK{=FQMK z+3VD?W9JSY@O=2-{PX`u<{(1pU9Ml5^5mjMjYy6J2`SS3j+HiE!f3Ig#D@ZG$P<MS zLP#J~P$?+E1Y2pa6$m4gr4(3rQKXq-Af#m$4m-5vLl8q0F~nO+H1Wg}KSXiG6h{oP zLl`@xg%(+4u>}-LtSP0G2q9#U!GeM`$Uub_YA8U7BJ%H|jP}d#qmbr%#H9C9T4_B) z2!Sakn##k84?X;-BMw7Em_p2;fSN;&qK-;xDKeURDylB5pz5luoM@t}ufiIuEFaFo zVXd}gg9`<^>;i#<3@W%l0Z1QMz<?MC)9g}AGi{7AO*{28v%=89-~b08kYEDSGT5L4 z4?-ZpHP~dMt+xLgaLCPv-FhRUh$Mj13M;FsI8M1Pm}~C2=+ao@DC@4vE=}&f3lAro z%sUSzEL&>Ny_4jVkEHtSizL7O`dbn}0UIiilpPO35XgakM5RZ1XMqqFRZ<BiLsw>* z(Uw_U6qrSV3pN-<fnN+bMh;~uMwA>&ab;e5<yBBff`}A_6j265Qlcf9Y*HhSpp;T1 zDp6ADN|(~(vP)|9z#|Vk0=eRYK%NbXP3x$8lPRa>>|&~_@YIT{uD}wDtU%FHi!Iq& zkgK)2?rPKmNG(_Zum{Ak^i#0IUW_t-$~OCKw9{65ZMNHX`)#%F=`4@}wjRy2(^3QB z)e~M@LDv7;Y^aq7TyxzOiC&ioZn)xxRgSqZoP$oOHI_BXI_%O6$~*Az7_Zts%9{x$ zLb5ev+xNbmFWmda)o&wB`123lP8jOg_H_?@*Ww@PmC#>%VL679Tln=iVG(b!<zVKU zCm8t`KkTrWQ54a!-&tg-SYC`t8AxLz9r{>F|6<>dqe@z@@8tNZTp3H3XQGK(@xZhL z4iU1TLrtN2c2g;!MUFXAxl<Idax|`Z#ZQ0AO<Hci7Pqt@1yid_2t2TX3}`?B38;Xi z7EpjU5C(1|Bw-0nxVFP^N^C1!;Xhh%fCWI{ZWvHi2Uf#3*!*o)w!saqc(bd-H6b{_ zs>=VcmJ>PWBuiP$x{e&4wVh~n?sL@=-RRVVCDe6Gb>IR?>pD^{*;#~kwNqD-bVrZ` z#Y<kkYekJ}#GzKWq8fl$MKNUI3h0r@d3)p|!t(ebT2K!V-H=!-vZp=YaSvkx(HO@( z1`&`gNh9V%pGVdwrT9=OCGT5L{AN;<n%G1<Vp_xxSa68ysEKE7LJ9!mBtSY%r8o!N z6Q97s8?y-Nfe?HP1?zIb4QK#s7VzK!D&P(lCi7D&RAw_Z^NxQg0|5vS&8bqg0oAak zZ?T$9ZE7$$-HatHMEH%bhC>|VAZIy{Ll)&KR~^jhY&)EjB6+G92=tT=i-_P>w@&|7 zA1{7!l41N0?FNL9jU7mlrr;gLB;-a}_=^@4s>U9QQ4Ck$(M2U%ULQUBQI6&@kkunc zA?@YHME+=zj6~?hZYMrSh72Q=tmJ(zIiL2ajAfl1g#5gOlQ7*O4sj4c9H5w;p|Htk zt|S8zp)xe86fI9kQ{d8o&@{9VY6h~I;9N*Rg1c})m<eD&1Rfx%1I*%U&Sa}(nAuji zZVH-3sM`Z(s45QJ&;)To!QZ;cLtFV!SL8(65YZ_tbry>`V`%5HEY~b2LaRH{@*K79 zna^x(D-o&NB7MZ=y7QS!6BJ2Ox(HOD+>s)UrdY))-sK>N_Q;Kgw9)c1x()wDTr{H_ z1!-@6%iD}nPZ1@>BW+Q-J(VufKnby(Cj!)oBrR!V`AHv?Ai=)(EW%1G>7<r?8p@mK zLA-$&0t^Pxo$aiWm2LQ0Q=IZtqRlcZwe-p@$#PXeY1L41nTuUK;DHQaKmiPpfLSMH zgSEz0!HIe6f*t%1XiRefqnQ8(@@7L<Z8J81{idySW4Iz9&YZw9P8En%EXhr7iI<C~ zcIHXh%96*5S7Z-AH>*V{0Te$1<qt+CvWba|v5aQ)o+&nl#*0}@wh*0dhcapnN{j-d z%2QECeS78KCeIbZCGNtEi%8_IR!EI}sdL9izKTq@WY)!G%Cx)F?)LvwCglMyAM&7w zI~+m;ZP=e3o<$T^z6nn6g>L~3sFhmw$*N{?8lfWCRl0x`FB}+f1tb6gz#Kpq33hN? z8{BEQc4iQuvFoWUysB)%Dg`>EjcvebIC2Kju;{eYiI1gX%dyy5lBK73ENd-%(%2<g z#4#5?%i|tvf_$ZY$be3pP<O4gcfMnCL}TQNR*(Y_peV*I@Q7t_gS*PMz+*E;F-VDV z2w>F)bA%RJkmVN1+0TuxMMg%l)|sr$?o&y&JlUl><3SH~Fhmee`G%tc8YzMf-~b6Y zOW`E2Pq=K_(`Ha8xOi34|E+X^9pHcggyA2^1hs-cU2<po;~oDSAe9VFUBg!4aKkOQ zc!vWEVi9xYSBFh3JKL$OT(?*|ldY#^XPj9ZbM~Ld=J8BtXV4)Zq!a^jEkiG6bq2Aq z+5rO?*RgF4MU0{uRt|UB!R?Abf?~M4?Rvwiol<zg8+>JcE_8ovZ#7p}-%`r%cKz+$ zIn&P%dLUC#fwCQ>@@(PKiBr%DE!Fu-Txs{ks#dppD6iTjH43<Zr6Yi8W18b1DED+_ zNZ(dyE@A+op|ELClj_&>6>zS;IfxUdxSgjnIY*RSvT_a2$hx>Yox=mQLMOj`>T}ph zFE$qgdOm^{^tl6aseuI2+IJZQ>sfzj8)4LS6?xkg+UEZ@Ec!@xv!~xgt}yp-B_<-b zLzIp0{$3;J?GQBE`+RG@DM@nrW;n}|^!TKovI+6h1M*^lLFhA8QmR&RrJxA|I<bP{ zFrciUDkNB-vS^@Px;VGUxYqD54;Zivn1Bd~fUOyTKp45xW2=*E!4>ic4}hUktFRi< ztJsU0R=bT`fwi0yqH_wCp1U<A3Ob?N9C`u|;{!I#+NXYkkIw3%9V-`e5u=DOt!G1s z9bqW!GleZ&qa|aq7!eUyD1~m=1F_2}^;<)bvV~$$yKcxRT2Pn{VY2y)yNrpq@PVmF zO0&FEpD6J^H}kvoKo2<sI4bG`F>wPCkb^v!CsqGiul91h$1@r|u_ZqNl>B0gLg}Uc zx(g6s00zK-2`DfKaDW0puy=sLW_m$Z^b}~qhG{C52tbw7z$P4wl^AHX4$F<Q5T_6e zqF-s8p6fl|W1?LP3M8bgDGD9)FpuPOLT-tV9Fsz1o1~DrLer|g<w}sM8wekH5D3{i zhS4Kf7(X;@hFNfh^vi`@U_*~$KayfQ5c$3@YqxL|vmj}yGBYzIkuLt&h$peB>%yeI z<D`}`L;|E1Kk$P@_<<ZagfvJv#e2X(gQcO-f}*iNM8m{C$)&WY0bcUNNCSaTQ~(aB z024gLz;Fgmd&OlkJ(v_5Xj*~+_&5rqAyog%MIEZS+o-+X2*$z+LaP|U-jfa^%$zhK zx@obe(LoQSd&16o1ZzY#r+d2Ti@I(^g)ZDadV#3yDaYiog>xi_beskAyE1oNOSWuF zw|vXDyfS%QJ9eZpI&?eQ3bQfOLud2HyVE~PTC=??iG%Dn_yN4Y!wEmQgU}IyEARt^ zi$wonF9<}USSp|c+6t~vG|D>*i`y#M;4c#h0lUDO4NyssTYv#r0v4RfuyIA#e5QZE zh66x=7`iK5bQM*bJ)8S5U@RxxV;tfzA{1jRT%!)5gCg&c7GHD9U{k*3lges*KG+$p zbJ0dJdNyb~h}BxHaQw<9Q#Y;~5flF@%djhkT&T;Bf=l*nPxpMs-fBN`P{WXNk@!0< zcf-Rx<i~llyZjRwfz-SHLz#nI3GQkc#H6!O60bZMgdxa*oI$)bsmNAh3ONy)___)N z@<^uPK#|0_6i9)&Sd9>Pln&4fQ*?j>hyZcOhgFPCPk~Jsy$ond0|5vP8A27j$|jkc zy`LnUUknRg8A`?xLOLPBW7M_aQ%+|5wWo~AC!7-JyAO__LhF1wPG~lD;h5!G5CxgG zhkB#78_(n^&+!YpvGb_+TvIlU%k$$h`mE1-6wfcy%YB@?<{BUAqAC6>NSx9nLM+5X zoF9g)13k+EqtY1)rOZKlugm|GuS>*4vCzb<;zUCc(L^DENAUo?D8&eHfCV4`Qh3Q3 z%?z?RAyiFORW*#m=m5~DCL7#I9MVN^8XO-e99{WA;XtP-D8?izLS&3A?wBm*Y({51 z4`DkU8@n-+n98aIqbs$-EX~d=T&^?PK8F&+F(uRRJCSqj1~i?8=4n%1C|7emS9DER zbj<}_VAu9^p1GV)^_0^&g%LZ<Pkpr3geVfat2aLk%syowKn*|v<Pz`-9Yr+MArOH@ za3VVZitCt6%Ct~IBOqbn$Vja(tHP=W^1!!%w6EIKPAxD=DF7%Kxm8VBm2I1QkkL|w z3}|wO+N4EOd%axTFrWXl)m#b6ast94O{XI=&NE0-7F*Kp=rv=#tn`3RVxz{@=^}C& zsOTfDY1L8!;nHjMQgLh}u-sPiToLmW1Zf~k_#~J$Radl4TeWRh_AHpSjMq4A5%}Y} z`|OeAy3>7iq$7c(zr2Y3E1CZDmXrxp1U*E-yMsFjgb%oaJD7uqMJkD%#EK;vsp?2c z?aZ`rG_IN&)_4>UXcSL9MFYS9bYRt&y%d){-Nt~XMz~Q}bv;(OSq`g}n-eD>Qk=yh zG2<YXWBIvvf~O{WqN8n68ADbmO`W9^7pttof~wjf+fIxDQ?7lZ?;98v$*69i1VxC$ zv_z5jY}d67U-AE4SGT+cwp@{SgwuJI+q=9^FuU9R+}D1LsXYx)zzswKEzko^NI5G& zMf8I{7z7<)ft*ps>}Zz%S&9I{P|Tbv$=g_6vQ!D0AgXzk5C|}pJV6IQfCAXG7gb%% zNL>(C3}~tW18{&E)XD$S&ApPn9i&|#wOtYO*~2;x-ut-~174$D&Z4`CDk7cCic)7) z-q)EV=A~NawH=Ou-ss(0G4znHEtrf729kmWSa?UaZO`%DVlF0MxHR9gg$4PH+Z7QQ zdz~$Oy_h1aKZIIhJ_NGzxwrfE(<#X$_c2iT8B{L;uP`|T7C=-9olr>xpoX(ph>O%E zn7I3jU|#=PffeYR*0=x$_}q~-umXsJ)*NBW5MfQe2WS!p6{Xo!(Hq@-4V(>}SKAFC z?b+Prxphh+r2M@j99H7>;irU7WxcWHo6_aI&Lq}O>kE=KLZq$*80$3{c5FZHEmtiT z-(GlTXpZJ*F4ta2*J|$Kb8S!a3x-vo1ah$AvSpEkp<DS&W4z7Vm(o+b1K8@q-;x+u zg4L2kJlH<i4mXGc6!-}!QaI|6j)sG;jie>|%D_JfluhhJ5j}xdc@z@BAk_Rk6+I@? z?c~ichn2l(j8?gSAca>o71B5jR&f;^@~fJIVZk~aVI)c;f}AkGHCcXxCmOn1rlO;Z zPG<jwkEPqOB0gfO#X=&BHm#kP8kt@(1wY<m9%;w~K=@`@$l|sfUulkNsh(=8-eR~E z<3z}jD`p=1RJV1*PuSAO_zfR=>stT~P=Yi_e%s%c@FY3|s=*5c7Z`#FmCU8ONCpmQ z%dINR4av4}ix7omNp5HiE=34<fWSZo5z1)BM%9*;Ns4|9Xo3O)K;fKJ6&`hs6WFjF z#0}r%St8}tmG%OmjgH@Cu_u}*q;*bwf=c#~&T1s$(8|WF#2skUKCK1M@Z?tKaYyq@ z>ZQ(wD`rb<o@Q)5?zMGGEA9qC*j_8<qxLl}bKXn&y`8cypMXSbHv7{%W@~v~$e91p z12~`nI-mmsUX#h3L;(WmL)Oehz9mYnR1lqu6tI8_2mub*fJ!deIUv=@W-!S9@5%6o z4rsZYwAoUYy}!Bvo&BL9)j5?$j>mD1#;TmhN=7D?qGnWDY0NICoziik!t0#Ah4^V9 zkzS%6Lp>T-ca+CT=mz0NZW*8P@NLWG)?V&)N9P%l7%AtlzB;+f+r72BJ>}DOrsI*w zF6~0dwl>&M0;N9ivqSg*7?4Oc5#%<h9HnTy^@b`)&DhDquY>-;sYw9_xPTDo07gMk zh(3T25b%nI^VNm0X>vJRd_B_Sn^pTO!Ra9od+=T5Ibw+%WFcDMOKql%F`EBIR$OL2 ze~Q9qHR5RP>21uNCU#=5gklgGR}*>1T#!#Irtx#FYEkFnwY+gk;NJ6V-+TS>?%_{9 z{Lh)v?g5<={neHxpJ&i9K*Eay3V?&7g50}a;7Zg`L{?-m&)kc<)Du_%1`vU}xS&qe zVB5q7{}ymg9^ttu0Ly+kR3pvZq`AQHb06%LRu)3uHAc!oPU}E)9`>9mqBAS%a4mv# z*{)7s-bSol<Dd>hYt!^@0KPy$zhxeGWadw=9vFv(Yo2kcUigGB^>p>^>}3UO0OxS# z>aNa9yA^9T=F)WL+jR!mw8p7hk2CNNuRh2FL(l;ifXswTZ}l$rLpyf+N_HIo_|Qv5 zffi5z3Lt_1!XQ$-w2v!*M#yA2M~rL-VQ7kh6Si}m#ITW;4OI4X2Ty4dBTgbjN_G#v zr9|AOJl0!wLM0#Kdk@G-2QqEkQcD+R?i<HU_v%eQ7#%+m;r{eu*aLESg;MVYVc2`V z?|Z-ZdxkG{SO8bCn|qI%+d2g6u%_-M*4yh|XMyC1koUil=ig5<zMx{nHZUs5ED8&+ zOox-Ds>n>L3iD*|*bkhb7GMAhFoC=9`3W$=2T;)#7`>ubjH5r@Po70nxpQpFb6A-@ z2KTVCFdX2_U33px=<vPYg)HsZ`tXQ%CQR1Tfo)@>&Sb+%t3|C~MlwwQr(U;zdp<h# zTquTSn1pS31%yZLXWn~;fB*J(|GqbFb!~WceFefF+u=TZ9<N(~XeAI8L4u|ZA|$1d zlqiOt9(Ib@i4&(y7B^|isOb{NN|ho-f&}Ri$&!y2p<I+G5u%ocUK%1qXi%V<fBy8z znUjy7I*W!}IP_*tojG#eAZ^oT&6+e$&x{%4Woj2KR;onF3dM<&CQFtiK~jW>5FtQ( z@Zf<1hm9FATC_-U0tEvRAwYQGumMAb2@)VUK(IjDzk7xcBTlS%G2_OLA3yeI4l?D+ zmM<@U_fOV=1r8!en1CU}h7KS?kT7v#F5DP1YTUSigNF|wW`z*{A%f&<6RuF8WUXRF zOP4NQ!i*tv=8RLOO4}fnGiQ38>UQqn$<9aT%|A5<4U!2H=E{_f8ksC95@aNg94}?O zc#$Hfhz}o%%HL2SLWHPV5hRd6vJfcCEC(KFi-HQ?(x8J6LfBv~6H=H<G1Dk=3^BTJ z*rA6Xa@dQA!jM>^i6^3%qKYPp*y4x1faoDCuymuyDAL>l3xyH#7~z5o&SJ|f1<E2I zfCcrJ&_WG~a-T#L$!F0<8+G)NNF$~9$ayHO<kEOE(PWcOIqBhtA8{-q!VrE;H{DTh zJh#+SWQ-9;7+w@-RaQ~_#+6rLjaAlJX{~ib4Q{ot!U`n+C?Em}Ab`-p1{w4vK?Dvg zP(UC5xPzIepMq+bWTBE;>SLNMVZZ_pgjT_58+Z@`YO0}-0$ek^CfjVa-9|(ayDib% zZ@@(%9C5}WHwJUf#TgxS)?KIFn0<Knop|FJf=GGhW%<Z@?YYNMeDYBw5q_TRw-A5* z1^AzU1tOT>kGAw!Z-o=;Sj;zUL^BL5x	wh%mNT@QNfB+{?iWpXlO?A;w6fjX3H! zVZ9g6E98Mh7Aasss3duix=cD55tQ;}^j?)AiPUW)DY1kIwqVv22u|GT!3R%%U_k*L zbhIhQn@Ta&R2oo46-J&{Y1QXfONf=5S%VgO=nO6YsK9~+bv=sLq!{=W!2=Ey;KV=g zn3}fQ_l&x>+n{P@P6Y=z070u5Y`{URsI7*=3b)o^Lu|X+R+g_x1nV2I#uhhKRLU{? zTy)YAMU)-cNy}Ze;1Pmtw%R6w(#zdm2~xQ5X%gio<=TfIL+XZXN<l^v8E?iHM|dxV z|6VvrHU9PzOpGBaoUri*H!RHYEh4<U^8ydg;f&t^l8H3ARJ<eZKK>Xlkw$(Da>z?I zRPsb8U!>7{AA!_zmRqV6^UUDcbThSl<dH{DhrqzXA!$@@XhbvG8R%4};#9>7d+L){ zz=8y+nFTFsG1Q@2Z~_)wKmj@M0Hi>$fxT4!3IYp200!RSkGG)^Gi^&D3s3crUK{`c zp9#&YI<Pkq%moFld5z%KLYu<n1__AkjT4Aftl=~+S&&P^8k*%SqSV0-m&4q&Zep#@ zVGDHTK~I*x<&jE=Yh3fGkGb%ZAK0;LcJHbkf^N4x3F$5u9lB74hCw`s5szUCGZ8WR z=tmL}qeOvZ*un(nJYCF)9MzKshjjNw2+hlT1p*(E#z(#;LBwR}OP|Wvccu5GL?vE= z3C-#^CO+VyCvk`a1>8`Sq6iI6&mkb4>_io-V1-XxX&|7;0)#<L&`>j=!3lD30Sm;S zYkB#aUqrZo0}$hEEu1D}R!Gfj8pa*}|B!>KJ~IJVk%oh^qSfD8;F`e6CN00jjcyQ^ zxZeavI0!sWa+bwJ$xRN5Qp8T?a$?0RW-(i#ONo}!^DS_xOpF#`T_?<V#)X7TjjiCA zEHsuedc84@6Y|i7QV|Q_K~ERYGaeuPXws9SG^HnPUc!_oqTz|?U({2@G&<zSM>?o` zK@t*yhD1q&Bxz*%G2i)AN2Qgq43sdFU$$a0lbYFVTB$^3A%-x5Km-jbvXs-D>U5_B zRw0*L>B?7<Fcx1@4F@-93o*5J0Ty&HQeW%Kr50d-HgF1?dbOrrsp$_CsLF2N9F5*i zlbX4d6IZbDVQp;VD<Sfxh>Ju2BC?RP#3nkiP1T7aKXo>yY6Sv3;Tca$w77`#kPZ^2 z17kv?#L$L16pj7~&>DLRBsXSMcOVLeGh(5LX*8pygcM{Sg`v{pA{V8F6sbrHCOlY> zV-h!lm@e*x(*{K{NE;)Nk&Yz3ppx%Co_NwGF>+Lou*ZERInT@DH_DgDBuqB5Umx_4 zzx{pS2yuXAEaOB=uPUu7VQm^&9T=zxs%0%Ur~wUVz=B4#;8BnAzz6v<0kPTj2GZ=S zUnj%iX=+9rBU}Jz2Aj7V&LstZJ7*8m!YkYq!JSKx?4B5htj8@2v(S0sX7|}of7Xn1 zSv0Na40_PhX(UP#Y3NY@^#eOnq>*-Pl-G}Ns!<TZ;uqWaZ7~cv(h(&$%wkTdOGnyV z>G|Rtsko6GZED@?W_P>X^;jkQBUDT_iM$m-*?B#QC6mC<y`zk8&2BO+RMz1RtE2!N z<}ehaBxQg{BSS3%j7tJL;b{*f%hU+PmSN6d1Pnld2uwhN3G2nee;Khj-hs9cvyiW_ zcAI8e(M`~RvowaKm95OlL&mN%H!+TE5#xER%GT2<_~fy5_=$(@XfDX3C9SqX$wiZt z4qU8F@)*eoTXek+qG_b<M5nydDnBxg(Hq7w05J_~{Gz$bL(!P)UGEZ&=y)9x(JORO zqv?Jqj&RngoI5uE5TJsWA^I^NeWH{yq$V{z@axih2`#2m>Ol{8u)`p9@BysCGSXa~ zbe-^294j!bPnrHo)X<6+wYCK|7q~zRRAXvLeJ}%ju@t5Z;E4^-`fZZ&2hode^rIs^ z=}KQZ)0@6@ZEC>)4tPKW2AhGx&Z<_4{WakXryJe~3pin=>~ZXL*=17>iiyS?w7C;x znP3qnEg9%(udN<0vKDpZV(5LGEbiITwn*m2?e^3?JXj248)o=MF?^wmU$AIIfV4N| zDX+&C{lXWDEC#&)<spGfXnWb^=_Kila3v{ZsF~EH!{O7(_Wc>q?d{Uco_cYepfV44 zsLmns`v>X&^mmqXs-?*<%_l#V^{j$=Ia_KFI1OBYm?<#zqa>wsx;lVtUC67`yYKz) zgP-VZGe`K#Z~pVM4ILbyn_$6-b=4qthc@ux4-NM#V#D)@^R!d4@2Ql0ZWd>CR@?nk zXoW}Iea^NNnL)7!k}1^cl#v;!3zQ|v><Avbw9&j+nc=+%jIi5p1=lYik02RW<(Z(p zmDvaqLoa06Htaz$Fj9<w-W$c)kbKX<ou0@ni9_U>Chb}JJlrL)Ps9OQC@~d$+1~B- zfzIRs9#qGoVL=^4hsepvau6S$7#{;^TA=(A^9fT8C;$t{1qz_R%~_v?iH!ps00@{6 z+nnG38^WQ|jbG5AkY->50?1H_VF2C~)?w8OT(kh!sgq+pR<ICJ{>fA0(9>mMRzB%d zwES2B3K_N09cp14-sK&9?47su-9u4e1(I924T*N08-t{qZow1_{(?0Cf;2S49hKk- z%Hj#)TfvAR3$hy}G=uOA&rLnj=-J?$dDnN@S?a0Yc==%Kt<MmClEf`l#nF!`ostvY z!5jpF$Nj-{Xw?Aymo0%6rag^WaT+l3fDO<<4$uV)tbkmcz|Aew9yU{8AOJS#!>iGu z+6-MB>f=88gJuLm0jvtHy^1*bVL7oFuz4M1%@~c1ofZ(sR9Mz>DBJ%%(Ia+N6}=t* z0wy5cEkYOJT|%YK-n9<6rOPLZjO>JBPnDtuo+5=r5Ah(9BC$d@z=AJG-YnvzET$ml zeIRhXWOY>tPG!ta1*5@zj3pT(Ch3_`omYCP*Lt;=D9Oy1$d{qv9x7#rqaDHs<iH?A zhkyN7$t{goA)f<DO&6j?gZ;qF<v<F!Wjm6<T}TQ%@|;~gf;91CUWT8jc-TFvjb_w9 zVBJkP?HU=b*g+1W{Q=86Elw32+al%|+G*B4UF2uIo#)J*wRz-f<=q4FU2LsOM3EZ? zw$Ux1TjAYHD!vpVso9PAf(Q;*Y|7?rrpO>6Od#n3yQKnfy;MkjUQqsGoN<i*=@Fw2 z8e_@O#}7)$Q3;__DixO;VN670RM`(7=s|WoAuD0Q8~{+9D8*A0kXU}BE^$R!MU9{g zN`tw;sIh<woPb=Inq1CRT^0Zj<dt8hjjZA4r<jmAOaS{0=KJN)it$ivBxVq~(;?Ov z*&PR^<(P9+WEA<>v$Y+yY|gY%;udWtLWzqeh9rHAq~HA=;MJCaWZ;5q;6}xWAra3n zz`{2u0!_gP<k4o0+GuPROm0>KAYg+v_<~Imj10b+=mCi&m0tKHoWfxeG8UCGBGpqu zC3IF?5?bX>WXHx;BOY7<1q=cmY~xb20eE^<@i7f~7T9@4kPrC44V<I@1?0e6tRsBJ zrKIcy*kITJM1VNd<9?Qke)8#MXa+HK#texDA99c%`i-xl6X5`nLLTB|9ScMzhf|~h znC=+mK#Q|^R<woIwa8s&F5o3LAV|6v8HtyOnk0!1h)N0xOXikK{$#=U!Yh2kBxJ%g z5Ci1p<gVi6<Ozc>48x8x-fOOAFAgd0)Zh)`AW|+I!zrhEEu(WfBXmZm#YNRsUZ)gk zWeJGD|4<>NLWP}tl~pK^F6|P_Dc>)p#SI9-%<;fm#03h#WeB_@*!)Fc7{Dz6-Jg1j zpYkhZXhs_hK=$b&-k8R$q}Z(p;)^|2g3?%USb-u&WaLn!W=W|3rhe8x9pI2vqTP{% zYOU6LcqS*hPD#d&M8S)KtRzOECagwJOU2ta!~#tT!!P^-ui|X40_%?U=;IZuu>vQu zUKHsWoOdCm!Vy)&@mZDlnae!mR3c$CR_PL6>F&)z92mj~xIiJOfyjmBSB<9@f<+N< zAvrRD3%teEq=3A}rw7dC&ec@`tiitit7YV)UgB-{-GgSFfT~a(4PD*AriNiE>|)Kv zI>A_ih8@I4tZ~qjMEc*QPUdw~rax&chQ7qy4U{D^V9171shTRfh-mDfq`Q=xfmqaO zwrrbqV8Z;U!o*uQsDdJNgU#M-&f=~K{(^2!LowKFnZ2a{FJeq2sjM(AYmzoAGSWv# zF6TykQPaxa?8OY!N@rDa2Ucoabr1y{P=FTXK^n-C(M%fgjipwUWiJT|58S{JK;IAC zN(+!-8OEhtU7w|ljRAN7Ugquo%Avp3ZDZIW9xea`RGs^Y6RjkwYs^3o9WEg%<U%4M zgZ7_uRP3{G7TZ<Pg=(bca*L69F6uDvLWQmbj;N}hF6v%XORDIKj$kkRs5BJABy>Z~ z=59_R!z^Z=GgJd5@Fw#FDbVgnE(q;VQq++E$k94PCMhitQpp#=Ubh%wwN58}VecJm zoTJ6T6kLECyg}DW8p+*>$)OxsHbDcSDG=}g4Xh>q3giF{0Aie;!2IUL^<5ZX;Hfy| zgFXH)W%%zND~2{{f&c_$tB{7?pau>R?m@0aW3kh)eTCv=1!djX5=AajSgaIH5ruMU zr($Nci4Ny_3&?)a=ay;&j;?5qrfsckin8v$c}R-@Ddxd28;}Ds+-?oya&p;hGeAQs zqyjeR+fNE_y<8N6e9uuL?=e0JQ!*{=#U6V_B};ft5>jVQV9xHn(j54~mi7UhRB9C( zkT;U6SV2J<qw87n027G71>`^u3=_PPVI0fKJBARZ2!JWvryoN`AM5jBXoeFE?B9w8 zY1k0L{-L7kO8vo@qe8NcN$S~AB&KGnc2ubUByO-Lhbp#x@W?J%C(72iNg3*v;&oNX zz`Tg^tRUw70t`<AIT*t&t5huJG79SQFYvM=Y=bfcQZNg%_6#raj^dmlGwLa6(mGt9 zSxM}bgy?X|dpT8AS|wKEffYxQqrm|ShyWZ+WK&q-n3nJH6<Ap0#xI?P1+YMa9SXdz z?YzpBs$tjwEJ8l_b7S!HT;Ib#;DFT4kgMd4;PRTU<%$m>ZXrfi1n(b?O=Lt{@Puxv zg?fi*Az*2BY!`867-<6ffatfODk_^UX^ylCxAH49PxIWaaWz9R&~C2cEHbcmYu|7m zz4lD^(JsU2HVlK!wiF%#u@Dcj%8sJ{4gORzE3?TQbrYi(5kjT(QZIa2?^RZ<9TdeJ z*g+hyfD7D#@I8f8fNd6@>sJ`TSeym>UceBbbq&Dl3b5^|wKd$1O#y6Q8`^a>^<{il z69&-D-}1E$fxxMeQ{g5w5Vh0O_y)vAD*q`9bLbd!q+O3`YDGUb=5C~hiYkZdT`7mC zC!TCds^m(l@J}`uOZCER+w?T}jx&g$Z4#Hgx%P^?wjaGVYwIM6lL&3Ifo;D+A1%)- z3#r8rsc#$U@fKrJI_ptKD{?P2wK{bvRjJNAcXT_N8?ZnQ#6fd_CmDz<7M7{XY1((2 z#Skz+I|q){z%yJ<*j&}I0~kR63(zfnA4Xm4vt~d;4AsruoY-l=Ujo0zVktC&3V5*v zM}bdlCBK2tEVi>{@MTisWNY+Bhwx>y&Z(vg>7p!Ys_w<4=1Ye73J#LOh&V6D0xy_2 zOshDHlX|I}`isZ5z0tNA*tX5)YUKGQ5Yr&R1*7RPYx1(*(iS<CYKd}BGnHN?Dp@gf zLw8Zo0d>Q`9o&;sP?}c@*aDp|mp1_elz<RS(1Kk}qOhY0%=28<^8r)<e6x9CxVax| z1`K(IVAasBrP$vnR*Nz0uQ+V6VMXIkG8s^+jz#FjVlbyp;-@O0$9fB+s}A2a35I95 z>7MS1nj-F8dMc`jAH8P(Ghjn1FatEaLaK||sdIeCyS6eYgT{*)ZR7N9`@(BCOss=Q z(Dt^*)Vi$)c~SS^5=%)ZL2nVlOp;IWG+t@3S2a>Vxs;1<c!u#;Gti$ffe;))3{b!j zu&G)&AEK<|YP9VchRp*A24U#&xX&TiBZf9r0zeXK1za6L{<Wg^5F;lp*gb3%Ad#d_ zFg`7Kvr%-$0#t^6vd4;YXNK_VJUVEGCP=TUNPjku@HQN+FbnS_r~A<^PeUrG0yMZf zjE9-WTmI!!o(MKWGbjSQxq1nvpz?S)%M&xfl^zbJs!*LvG6G?d8@ZO`{BldDG~!;* z2VhaW!Owia2fP9QxKbJzNQKe+NdpN16Rc+t1OcI}Ra(Qvw$HEC+wU{!>(-BZx$iNm z3@o7<D!c!o0tXJGHZrg%=n*w8M1}z)%6*{^;3h*j2WRxh?tN=*;)O>#Du*;FR(g*- zJavUg@&JS|Vgm>M`qd0tG)2>d8AL`9Vnk#UDOR+25o1P;4<kb4Sn!v$Vt~lKG8j=< zN|n8IwbaGZrORA1bKSCe6Q@mEJ9p0VIZIa1Rzq8%LS+hRQd6XuG8N?sYNt+|sBW^l zNz)~*S}R5J3JKC9v11!8GMgw7B1DGRvL!SqP~1O%`qb^i2T$HRcIwozGiT15Hf`X1 zpn&BKm^5eqz>o>^<%<_BTB<~e0tJebCQX(UkrIS~3nn~#@W6rNMvWOWTC`Y!;)Dqj zAwYQ8kfFi^2@xPTC~)bYyL-cl7dL(!d2;2;nHTqGu6cCn)2R>tH^YDf2oWSyz_6i% z2M{4hm^gtVMe7+gYTUp<8VC>}M2H|svSdjUCr+SPj#9-6ExPc+i!jC@<BT-YSYwUB z-grX}IRNX+FFWqYix0c{m@BS92qB~`w$w_*EVCLJYb>xLsf5L?G|}WLtEl3n6R4mP z1;?h8TFMloP$4R)pnl@XmYj^ViKdxiim8_-RT8EbfjSzf8DD&{29Rl_ap<FtHu@6G zFejS-l1zi78AXw9PBI1}D4&GMB{*YB^2nTs?8zsgi1KmArJTaiMo*-w>Z%vFx`f5A z!b0(pvd&5?M7Q3Oi!QtH(#sCM>HsXT2lMFR10Lo`gA6jj7~?T7x}YoyDK6Wu2_~5M zfdLV+xWNY@O2feh)mU>4HrZ(NfP)M$s9?9=2*4w_>YRO+y660vmfC8qy%yVSwcVE6 zYVYyq9S{!Cj=Ksn08c#f%tK*?7GhY>hSPZ9A-?(QyDz`}FtaQ`0SWYCj06>I&_M_} zrO-kQGqj7t4nb^dL=sIrkx@vzYEi2fW87p$8UrOol%`1O)5jl&3UWvy>%>XPT$XJA zsYxfFOo>c_3?he(Zmbz*7&68D8R(2^hRC3AGEwB4UViCl=9FTN`DI<`T=}Lue+p8T zJ&oE?WTtGCYAQ}PHk7MG!CI88646pC(zoD}OT$a?*h^DR=a3@}HR70pfft-u4AoRu zt;{ma@XJC326Rv&zW8=cO|{lmNFlb_Lhzu24KUD6g5C^R;-7cE?UwY?O(*?Zb538K z_15qC$D9Qa&`yF0%mr_}^3Fp+z4hFC&j<PJwGTi2_WduwE(Q$4K!MX3tl$VItS~P; z7H0SlhaVOZ5wuEdgyIw}Ua=AvVT^G`scZ~6WF3_%8Au^*@kwQ>Z%Hz0n4)a|TFNqS z&Us5cn^Mpwq6}paP)tL!*)OJ%iAj7z7bii<%$gLZs7Z|`_R|SZ=m!)%6=iE&6WLRu z61K6CjYVCF1Xvi=s7FC6L?3!vASz`kz3ingoRY(X=CB4iV8I0!_<<VKkOnXiXjNK} zf~zpY1tu8g2S*SB6XXMgUGYjaF>np#DtEce9cu!-alipc5W3N|4vlHF)^MH!EjPXq zIq&#~G7x}(2XJQs7{~wz(xp4}xNAM_kyr5KLxds_FJH$4kbstVpfd;zdTn@+gyw*- zgjw%;8;VOHJQS(!No*0|YvK6FXTFW4Pko-iQTs-=BOei^6(~ztk?cqR6REw7CAoB3 zloYtYZUCYf(jZ39x<m{D8W5SuMBqkhHW7nNV-%@?;L?f-rKeT!CE1MH)Tl<JpLkGD zeCktE098U0#)xc)QXvZ&1-?hIErv6kOWdl5Lkit3LV{^S8tQNb3Y5SFT*w<2jyM@E z9Fz$qV891-00kxp0ir^Pk7=+t11+{71;Glzu!@zN-8cXN5l|f*Neag{mK3Ga@yEC1 zScwBHzyWyFBOi0OuJpW%J@J}Xz2;K{eCdZj{Xw3;3gpOvMRJnU^UH-WsiB4qqLU%| zq=`Z~O0SgCMW>`uDplDvSHALOLYn1HYKg!6$;_Hk>fe-p0gG?{q{0#3aELJpg1}_n z6|c*r$k34Si(YiY5tK-p1PS7_rseX27|fvkym_@CY3(Q?B<I)8S*SxLYK3S+k)sxo zmbJullQg6!rYN+j2+1LmXK2G5fcQ@qOd$&VVL}#yFaiotpa)!Vf)RL21c*A$G?2R} z7ll=uVr}lD2v`6#%$QQ=M(3o@m9BE!@sBkOzyUF>-Awzqu6E(n2JYFZ@C^A=eOYFa z%VS=t610W|K`*J5?8_ys=hW<R@<X2V-uEgtz7(1geOs+jS6N9iu*OoB^((8A61zXO z_HrP@_{BG35m$r!;vss)>xMZDv;&UGOMRWNB5E<srA>+dg4j$fH@nHfJUw<O;#5l4 zKxR%tS>;7pDVw5N$XU;}ZBjI>As^&Mw;Tdyhk{`cgG{9cEc8GJ6p#Q0Ku`e-h~Nde zl~ogzpadfn;kQ<t7vz5Rnl9F+1IE%#1RSt{1Bjxz)0MMxRHsHe+xZ@H1VRDGWxMat zR9)w34S2;%uR<Quyg}ucznEv#qekyw^JOZL?dvf8?zgJ_y;%7&cD?{}m3{7e-+^U0 z3k6fntQXv0FCYw&VZ4IE7Ut41k+}?8-x}A;;P7387Gi^RLlMXLhLujtGzU8^u`OZo z%B(g&7=tjfl4T!dZ;WFdtCPp=R2vN2BEwD2(=PS@%+!(Z_8{oFS3!9rViCarhAu<_ zp}N(~5|V&~BKQ`#r|FeNfmONLU`}(n5u*W^C7e4SoOP+2^TLVa4|jxMT-)(8x;9FJ z^Q5N*tEoYFfhWBAAkuh3O>ZOF`(F4OOsRILUM4lk$*4jMEua*o`25T1jA?bN>tkgr zM{P0$i`CR*)nKagXH6#&gMUv#`h~x7jD^fKXuFpB)Oj5ykBIn}w-9mC1!8n3$!VL5 zWvq+AnY9>4d&Ykvp`gMhHp^}Wv+N{`kGU-=sKU*LH`LUo%B|1AxR)`eYPa&L;41&@ z#|ima0ut!++bix{i)KCn3I6>>fkWT{1*k&*oEbjd=yv|O;QEI+WVZka)XqD&3-li| z?z=(Oi#~|dm&lVxAOn@0V33yYQdeGSmv7GypOjemG`*rjY3$RfT&2jq>hqtEwMaa< z1ubtv^s_##>k3TCFNPtFW{`yY#Q1QSs9yf5>)Psd6)`!0xus&G_?l2kwqk37ljuu- z`eX;E*81cpwcFV3tPSqgNwdU)vpNf&y6x_SY_#TP?@Y_w&P_qiK=2+TiToqB_5(la zt?_`%G$5}vVB^fb2)TOW09s(BKu^v-PX$v-j-cTHW=E#JBRp0w1=>a9eg{4ZsXmHF z(a<Y-x}ebzWMFbHzUJ$aD2-t@395kqFJerjg&sjgu&UDnOu%kr=aQn8i~^QQE$FCk zWs<~YmPAgzj+a`EAeuoM_JACg;TOh_{LD`d%a56isjr5C92B7#rh%}?#ORDJ*_N$N z8tcW(4uty8|E7)YDoX%&Y=wHvQDW}1x-G~=EAJezwD2hc+W_4t5Db_{c?QQnG9&Tu z!`|>s%z}$O_${Nl2;eXPx!CLgHsBpnumzn<S`bbbQAhMH!2n>YT=Yow{HR?rZsT;2 zrwj=Re2_o<BM1xR_Sy@nj<7-|O+#AFL-Gq^x`)3;iIi*(`L2R0z-GXfk14dUN4W50 zfWp-12mesb`d*@fj%}@mMj$f(tQnj^5y(LqhT&)C5Fn|p4xMQjwqX*Qp&5|D7kcTi zuIXjOuEku;7M@MU(hg+GX%Pd^+H@?1z5){83CI?(hVG)C?1}G^?A!p448{OeRAq3O zh!i<v@$N0mDC!14uoZ;`;M6R+96%i2p%!;hD78i5Zqd1_D-8+&7$=ScI-sV`<GbLc z(2^14esJWVF<>4|_v9;6tPy)U<mE&J(}+)eHVweU@d^oy`H+GX;3uqP;hWwu4C68W zVuohW5Fe)@6`}ze#3Ug9a_Ta|fb8%Wpg|Q>!5I>=nEWtG%uvPV1R|LYPYTfxE0QhA zY3;zK+OXo<;;zTGEddSx!P_Y15{>N0P!f95Z6#Y$c_@Q$VsZm%QlhTtCbOvDiYs%B z1zFfkc6x#HjMAi_12|C%9sZ#Su<MTe>|8vc;?~7oa7qUW38L-=KV}aI83`+iF!vlp zdbo1ZGU=(baT{eW3a1cbF2U2#5^Qu%)Rw|6OYKe;%$AtM7hr;a@G`@Q0UCHA6`%pb zz63A>w8J!lFrgt96d@d%!59Qc`%-Mh1kp$c5o=&6ge)>gNJuj^GRFom+vZMfLQ^zF za>(Rn+)i^7_enukG7OMtRjlAOVTCi2KsNKOq9QL?W}`N4<5+g%0T#dj7NJ>&lcZQs zNZsfkS|B^{$UBz*bM<%!kOb*H=w&*oa|x^y2$ct5SW;k?Y%3*AVVsHy2O&~|j~hdY zET!-p!Es|aCg*I#t9tG&;nE%DvQAP>f2`ysybkH`)0mn88)6|9u;D)iQ$PzfuQcL- z3X?yvp&8H+>98-C9#h$7LWA;eGWYN7(C#vwqQ**SGt(*V3ecTO1Vr72G)r^ukSqe1 zYyuqv6bI)uGeagh5EW_DHqA^nNWi!PPB$LFH{{?S(4k0!b6DR<j?7^L#)Uh&gS$Y0 z7zYhrUT;c?2dIQ<sIW8|wNjE$ZbFjq8t<zK#gj~j?@ZCuEN?FP227O-tog!<9p_Z& z=5junWFDXY#!-ppAQGZKdj<|GVh(Xl8E(x`l?hRmp)g}17PJJzTFp(qE)XMg5Xp`r zEi(~2mF+&YGtEX+>24C;VumcSE{cpVDoIuS4n-HkRl}e)s~}eAjowaCqQvYpQe!nj z@B}Ic&3IJ;e6;|Y;5UmkT7(m5okfnsVFC`|j!^H<nA49i4yR6|;|`5l&+9q|q^KUL z2&0FRDC7>jatVKLOs5J8t%?fMlTFidUE4DqeGWcPtxm1)nvRXt27>GEG9tLo8WbTI z0>~l&($<_I*8q25t1crDLJ_KA8ukk5>h?`m;z1!cLM0Y1&8}p|>Hj=cBRO*b32?JQ z2_)nHNuC-I4^kB{9>niD(J@%F3tY5tWHm-PFlKGlHgoddI6!Aja0RAiXrF~hcegp@ zNE_-%yYlE<oYDrNwFaQp&<-uptknu?ZwR;42vH7UzVvIgN2<g&(@?}bIV~JzWE|Bs zN7R<ofG$3dr2g(_UgHF68na0tOdyQmB8r9$tf3ot1{n@0Aajj>``3VU4KOnzB%~n~ z$YB_K;UnI!X1osUmIOlWL~<*WVlgu_8L<(u?Gd%@ojP_jL6#(|r$kTkL|Zj*T#|J! zgB0<D-e%N_W_A^A)D>+P7S~L6B)}a0!FQ{pcXL=d<VYBPad>aXDJjpUdWYlQqj7rw zs(H~1K(MuWvQ}%ShrYlwOo4A)L8&}zt_stYJ<qXS-!d-g6n)nhX4=>2T1|c}f*80D z*z6a7|JQGq0dV`5f9H6P`Pcj|f@iux8pObWi3!B)@loxvfo0->?Jt5MOH)Uvf;Urh z9kBo##m7ojL>thabjV~;S4CY?3#?!iVI?+wD`su-g)!<zX~Xi?45SbM8-A9DlVgWp z`8eb#5PmUfiMJ_p=VnpBNpmntlhLPqP?7pYy^Lx*sgd{U3rxY%ibrH(ywShTQXIL; z6KL#<W9ePtRX)d%UhQ&b6bKp8cpxf*XTE_FEX*I{_-~zoo!i-+-x;3WSzrbK(js_9 z8h+`I>1r_-*g?aNQpaw7z6mZVv_iE|WT*{eIW)6c$aBvk0cGfIz%69OjoeU^6I*qY zTa$G$LsmmMqJV&uZ}pTxAU8dVHxGamTv?WlBbHa1IONC<Y&jT<*IC!)k8nzmc4|t4 zIgzZj3b1oUjd>ckwlBICL%tPUvoU+g)f=x09L+X-*9T<CR~^B4tmJe4<hJX$PM^nl zA{KNQnht4rCSc`oo#mL0(^{<oHZUnd!oFb?0O1=XY)n3aaTj+b3Yq@WS26>-5D8jS zD;7fsC38WQbK7Z>ClR7gb)rejL{C>G9fL(Xxn*aS@xttJdS$pq+BRVSaW{L^0OlY_ zT^g2!mb8(hx|TpGlXFQoAYE+wrUGdyBdWZF*{6Z}_Oun5lMp<Ux|z##dui@sj?W6k zHw&*BYoHISlWo<`5S%lNBMhjVc|j25Y8Y(I{BDh%*P6SzyRDJofQ=>=z5%=`Vqy2x z9<fgt9+$5p_EIM{u*s=YGxUTw@~}G>G(nfKKX`8LV7^LL0vCe<nMY+?lyF|96lpbf zgG;j|hjNOGSag#|7k~gZPgqYIIa->ut1AXpI|7sw&}=#?H}3VM7GJFNDvL@xhdSlF zwl2UGzdQ-JXD&sYT1`2VO+jsZc`hl+S5Dy-42?t#nS0gjwq_Fl^6I497`mYt6hRum z8-UNRyQiGWrLH0-Oc2JqysL>J<@SQa5TN}UQ=!drr@E2FCdW9_zB|+aM->4%xDrQ_ z$Q)aQGr3g>TvaCHz+qFtX%qxadGa_)!XtoZZ$PC_Tf<jcj>-W8BJRUe&$VlMcaS$; zkQnw3DL<;!KT<qfr?)$~*2P;6znoBPX<RJ2SDJHN$JesQs~VfbI9{tJC*qM_l}>>a zQzDW{KPO=u`ZCHnY@Op-*oU3i<N4Q<Dazm45qRMn`q6;6+#VZNQVkh$A$T(3yUZ^V zp$oe+uS)J3#f3WS$0$)Guklh$vSjs%LGGM+^8ADmJVx#R4YL{CHd}y~C$DySRg4ax z1JD6nF#I?YU6zYB0%k|zU~vOzs%eoI8OaON^TjHkQN^`#w~e}~u2-q0YAlQIJij-5 z#rI9&)Lq-rZO53wh+Jm)N^#XMf0cn4uz}a1f$FH7=4n1K`*9isLD=wjpS#>)zx<G^ z=Gs4q%q7cfFn3K+C{#bwp*uE2BU;Y&?w*oN-BGuM4g8Z`7G`IYqW0}qT9NWD=eRry z0%QjPwBgWQTHs$<j<7*^Pmd{?wuqmU<94v8mNC<t@jrf=s3v|v2xhmvRYO86<6&<2 zntHgm7<||BMnb;T*;anOFxE|;n^kQkdZ{9kTz`@O0UDTr8TxY9YF_khe%G%1m)zJN zR~`-D<YE6gB6;H3irylf0_oAourn)?6FVgLn?&mdz&R0h@f_=0*JWi?lqc!~>s<tK zQ#W;^HxR%8T3K`ep3bP>IOIqf24DdeKuMSOc<KI^c@PQkUeos;di~xAKV8yX{Heln zT)UBbqdBX%7z^1|<e%?Of?UXHoqg>RAczSZNRSw^g9QyDQ^ru)GHBHlVf)pP;j)X% zoMGI^v7^V2AU{^DcyZV=a(kdPJIFGj%Y?#u$(*UHX0MtxbLq@=tEbPOJ#7gcI!l(( zR!C7PHN})Esi&kwN%iEZlT}WfHfhzWNz<kOuazoAiUbMLqqArmHCnVN5u&$-;u<1E zXi%U)fBy8@yBCjNJ9g>_o-;?zn>TF|uSt{U44E-r!g%ST#Y&YZn4v&%(qze!Bt?h_ z5dy>q4<0yf)R+;YMT-<DP?#VQ0)&SR7%)tb0KowQ1K9q(yGOjZ@#DyoD__pMxj%Ew zqf4Joo%p+d$_6ZO071e83>h|b01<+Oi4!PNxQ;QS#tj^&eT*hTqzDqvO`JG^f;oy6 zEnRdGSr}uG!PpvWB-X|oau7C$V0GAW#~pt0!Pj1Q1u_U-a>eylB5W<97FuVOHC82G zebv=gn_y*CCscVN6;z}&)s#}GAk~WhQL+d%%TTreCFCtT<$@DVGU+0dFiiF$%u55c zRM0^UEu#!H+el>0NFjaX%$Hz>31*jMUNn+L%M9ZTIg>ckj4~`C1m#Ol#>8YyNgi3` zkU#-B%bz^zh@*|B&?uECF<zAwi(RD{)>vhcc-C5MCE`|xa}8qGU3&4whhKOA1|eaF zA*L8(j*St9WRzLfpJtqS2AXK30fAa-tF`tT3Mb4~TL-vRup0ymEKopj!&Rs3veP}s z?6c4&ciklgY!`ud;E6|`dFZLv0(&;R$Ab?*%vWC$`02+VX8#2^AQ@*IsNi98H29!k zfKiBtg?#0e;f5W)g$RgjH6rQ%BPK=?R*IUi*rJOtQZ*w~HrA+=jyuZo=bu0Z$!AYH z9VxPsO*(n!$#=RGCzWu*ISe_96f=!7COK3lM`GqI=FK3T$q+ISDKd>TD<cCX%1Gmx z=g39!^zkiz0vc#iOEqQaR8%SIaHC*}MV48TQrebVh{#2krWtm+*Qb8n5!hgb9j0I# zs6MvpWLju(S!SDc_E~7OmWIRNxw^IjuP4w30<ahe%bNqn+9F)Eltb%m<(MmbT_n{y zaP4>Dd9dwyD6Ftv4dKGa0}$oXR|L9E<fj>CRkSPMss+lM7`+Zc2pFjR?&YtB0L%4Z zh$2dw@WKo`j1?zV#W?Z*Q-qpwF;YDC_#=={6B+W6H`#P@FLMeMXOt{cndUFwD00j< z!wlolmpo^r^ZoSK&k;#hD)S3Av519A;B>z7(aB^nv5Cm`)V+?`q9{`vRK=izwW@Ri zD_iqQ*B}Kp5{a!XaOqH8(srRfu+43wikqnt!<aOXfefn(LxA-5s?B)jZ}h3vt#DAd z796fuiesGPA^^Dppki{FOJZ~`r^F^I=Q@ihfCC=zxonB9JSK>Z>Ar=!!HtV`La5K{ z(zPGj*=|5%h*ugCv^(D2D__97&>#NAp@0#rV9JBUSQN&vhOr1@G4e!IC|14eWlUon z8%p=Qr<0K(=}sp9o0F8#$C4_=FC1!kU;Olk5&YqglN<4w|FDq?W?*9_1eB8jVPdlI zIg)`Niy8!{){3fGje?{|)CCu{m9A*;5?+f`*g|Bf5XR+fB)rfG-&O}w$xT5mJcFuM zHN(9{0akvS)o56^!yf+7SBu*~28IYZ0~|3~PE2QUn5a&5UZ)LGq$0L5z=11rt90LL zPwKvCE+n9939?&P?ErK;0-YgVY+Mk7dKV!HRj7n>Bpx9!b-aQZj6};rk&67d6+lW) z6oj-9j&#JMA8k*OPb-qhT!}y@m2YK~T*yI6GK_B=LlE#Y2`D{zKTu-CXBUA+Dyjhu zVx&@)t1L+WE5qkXoWPP#4xFVd1ceGhT}_v}WE9tc$-%Ixg_y=X=BDsc!V{vfna*qj z8|yYr8MbO~*t{VUXhj;+;EFYd;}tl8l>yyIfQSn)faK8GPA9UnuuXiY0j7AZ3SdAy z_B;W4OvfJ7iHltQ{AWPTNKiB$bdB?JBfcEEuiy<&Lv{4fzzB9xj4rQ_&hzM@Xe82+ zV$Uch<zDx`=g1{F$)!n+(oriJzi(KB4dM8ONi?EAp7zuu%niwz;@1sp0Kyv17=}zI z8C-$bDS?j6$xa#=wd@J171g64qO!J2UUKD^!R%mK#6~tujgV7i1=Sr=SgN_PHHI^E z)iwM7CfCqx)2^z)>#l%Uo7?ntH-I(3Ban#LCLXrJnY+#$3}7t@ICcZ|9Gw>P=^ig) zHjMUx-DaaO&;a2MUb<6gy$CZ}eeof9eTXP(DLSwawYEeVh3y}q7cm)4uaJf;X(ENP zTi%XrCQW)$cd1k~hEUhK-$2H4Iq6)T`Lur(DXullkkjpQx4XU#uXuH`$nqZLyy<<) zp>&BstvV{c!zAXVL^#&GC{w?0bLKPE`rpa4s)n)h3=#~iLtL#Uud-2`2RP8z3jDR4 zeV{OgGk4)lQ|>xmSgbrh+yQ%LF$I)u&wJo=;`-btUF%}8?OuGKgo?Jt6~eKOHH9hv zL-ZJruGOQ$G<t~@4LN#<nl1GRW!ppM7Nsd|WO#oI<$^Rr%228@Mzkx9X-r}p+4X6c zbM|F0)3myZfFDJQ)?I?wsi{mG@6#OkKw3)BDe7JCi|X7<_~O}v$g3}(GelNT0UB;` zo7-X<^B6A}x-xLxj1vkRI9m<Q29Ne(Y{2PYzY@^_1~7!CJx#ezll)ok_=gZg-Pp&5 z7>nsibr)G(E)>5Spk?H&iwOkdgvywqaP*5DBdV#12JF|#3-*bKZS0N``J*6Rc5QQX zTSRuO$<pqv(h%rwCMo26MPnI8{-+3{j(cZkCwJPz)RAFKV-$`kGrM7uG^EY{gsJgn z^SouLv8ht6suPR~*7oh*O>Fg1U(0i)_G~t^;g>I<3KcU2t)PXcidAprn|}PZ=!)M8 z<1=v0YZz=B4g~A34*>Zc{^5?3W6tER*W5pr!14)@+SKV;kE%^vb60CN=Pd5*i`8gr z-ucd<H^wm?jcz<k`S`~P8@7<04n2ttGNd=UUiOyE<UajGr7OJ&$_Qc%Vw9gCVNd@; z8Ui$42oM=NT|3)BIg;WELX+B^d%M32UL`H?sY4Pq_4a191b7oPXY9pq@6|Q`HYtxl zDaBMa1D8x|b8v%EFDpc73^z>==PIxgD@o9KwPIIyr7I~wdXp9`6A%Iasb>IIz<RM) za?lZj(UNj8z;Yh;SfwUn-cngMz<cvyA2%dB{ZR$N$8*FNT5mvOxVA44br(g~Ye+XD zXc2wPQ*0ci6&@u>Q73iTM^d=OeID~MPKG2)f+tT>erh-+>KAq+u_lTD4e%FTWTFxB z$98mBhZ=z<!|)5?pa`l^54w<lFx76vpfvrLcX|g^d}nV4cuR7IRSI}`Vj)Z(L|=?I z7x(pe71%bDr$UwYUzkTj1GagJ#%SC$I0<HgC}?_(vx2>009^osH25sASBue+awdR- zAGQIJm3v$?bNpm;H>55_c!UL#gl#lq4>AWqhhu&4FU8{_zII3dKZY>ECVkCAebGY| z*XM;ykz}~_KvzeGWe7gww}xvNQwXs#KeK)f0f+h1Tz5DooK%0qAPs_04APJ$VP}Zm z1xZNqfAYqNMDZi$MKy5-6_V&MhIeOOrFa6@cm$_5CIl*?;vg8fLY8MYqv(MW$9bq| zaV6*)u)%SzXlW4;i?c{rxJVt(;SVx7lQdbAHhGgcnUgxXlm3u$D6m)%5COL5a*=fc zJ-B-`7lb!wjI@J{Fa}y}v``QdAvX4esKtD~wptdIM|*UIP4_TQcPJB6J=Q~Y&PI;V z#wXyXb>C%vZn=)X@OA3<j$!r--QYes#WQwTkMxs=A+d-5XmTan00`J%5&sAiM{|h3 zm52nnhz9vUCgq5aSSWIqY!>u9TLY1aCy`-=OcZ!y7&&<x8Hx-i8LR?vnwMxISXZ~Q ziYD2Lr?-+IH;eATleT%AxVe+}5R<vto4$FQ_i!B{0F>VGVJ}Al-QpTEfRw}NYGf2^ zM(8fMlSVOi7)y9B4ONx>LUdS}mCh$3*Jy=Imxa&MjYfuj;V6!XbW&remQHpP@Yzz> zmTfTQjs(Pq!|;cJ=nHDXm;QNnU`8`oG6~S&5W|I3!Nq?`vNUVvm_pJq8#7B(wUC0x zURl*|nrVq?p=T1<cw?1co|r-jcPblrH`SDyBI$Yms<;}Vw<{(v8>Od$vRME;z<R%V zqc~cVyJ-$N+M_tSqZx1j3(y@y31Yu^lqHsw#ON7J8GO<iL&~U7Qt3O|DLiz<W8X=I zRTyL&6<gh?Y&F7cwxwk3iFHOYZHPE0Pr`2YDR%4g4XTg|d09XI>6c|v5kSKXseldZ zcbNMJW$>ma1sO{RDOD3{Rh6l4TJv69gLoP`DG->6nbK!}7NQr}UnF{Ym?vN#*cl-> zlBZFUqxYf>mXa%&dIf+3HtM6Sikmz7lFZ@{=&%7oN~Ff=0U=Nx$;leb*=i}qr28RI z$Vi<~DPs+Cd{vrbS9)|=8lKtcmE^gFM<%BKW=W>HWsX_*WaGC=ZAh05QC!l%26K8d zbvl1HgQwU~cG$2b2Wm8ih%zkIm`+2eKC&^6xR3})c$w)a5qXJ~5>}J?nQS9@qf#%1 zp>QR-sS#(2pQ@sSqhKdUsxkVCGg_nQ0ISNvo2|OBJ9!=A009TU9mT1GxT>qU7Xv;B zgiD$qz!#kbH3r05eAkJr57jSFIE|_`g<QFG(+8Gc`i)3dtr`QF*Xo|xx>9L6pYFzv z>Src2GYr)Q2;C4r09vm3Gj3MWKS1+s1!^UJS`bP*5Os2Qf$CIEvv>7ss0xXwf~Tk# zilJc9uaL^29hxZ>S*Zkjfg?(y9*H;qoEnm+=&-IiswR-D9w0=+0&+C~gB;tqH~Fd< zOC9f^5842-o-?wLm8-~kvX!-J%_)Sy3Z26mrMH%yHEX3%*qs#xp3bU`UCNCS1ExrZ zG2@7q?P;`UI*{U1Z7)@yapJAtiVWC53AMnd8F9Q_Vzu^|y#1qH(+~_&izZ*2pn$4o zXN$IwDWQKCX9#FPZ@YkTyO{vDcy+6ZlxlEz;5LCqd70X`Ct8XixSFYWaS*FlhHI*i zV*n%&xfwfy{2LwDQMn;&t0b$r$%(T1q_WN#y2tpWFiW}%g`E<Tth=VVZ}EHwV<ONR zTTdr3T{yd7$e!I7ZAS|}WE-~sY}l=-R3*#sKa>y)*dPtcD}VOGQ`=Tk#{dZRz@H8= zy-BroW!s>O1T{V~fPPnilS!EsYM}~fc<{AHk4j$vOBZ*GzHW0?g>kT?=|UVBAb-oS z@=Jn)3md(1zbcr&Cg2bM+bsUO#>?Tc6Ck9YbE{Z%z$vSw3%mqP>asEPz|}dW_%b1< ztE>`*m8+|zTk5)4IAk3xNVFxUU^ukpNWyAn6L*Kg0`UuR*@k_}GT-V9SuzdNK&LZI zu2zP_IHg=Y?862G#MTRd4@wk9OjSvYOOjZ4lqk0k7^&r37w6lF>dRk)){$M@1y*1M zC>pp2)|x#;#)TUKDfo*2XspI=>>O=e&B-CFv^u1iTWWO-jGe2%pv$tNyK_kR$M!;{ zxh6-;YCIQgQLTH0D#FM=`^dEw$vra3*jmE7TWu)3rkre_-?|Ll00^UOGi5TvcIqW> zDhQd7Q>(0ht0ZOB8(!D@m?ovYNQ|#h!Nj<nB3vc6U-hq@xrr8ORw9b28mOs;_Qk3R zsw-N*Wem;u8;fa-&CH>(j=R$``3|xgq?cQy-h59;`h$2pMmX29R^Y%-S$ydn$m=XT zM2EB9iNRbc&tF-du}dRide2pt&qa&7YDTs$Rd<IdmsIA4EG$2FISS*Nyb3*!UDAi& zzy{VZweqtJ>31~$Nu!u|r@Ll5sIi>38hvm0MkBYJK^ZDvyG*|J<#+`L%=;zG94U$& zn9NHM#-G>B_Dj=e9E&7C%{;x+#Bqz&?9=EFq}(jjB}+O*EzYmDVooZZ$%xKOSO<da zgxlH9s%4GWh>foMl|Bn~=vkJLygetiNNf3ICu~3g{kweVhmJrA^`Kl`R>N`qNz4^L z<Y3njt=AGwy?<@du-qqvEtzb)#NIoJxh%euLboDB2vscEQ<=rXY}sDCu<?tEV$9hy z9nF@OzoCuO%VFAX?9=7|)N@?GM6H~?+IvVX+b-*H=Ul9A^hWxk+ftpnhCGFc4BS{9 ztsN}8kX&{D$eosAji!)<$>=B0Rfdn>Fbax**9(m^ab1U58#Lk24D$1ih4`lesX&4% z*yerS1Zdbwtls+CZyFR94Y<p^T(_PX*`S%ep9qTWTg;V_%niFuBzXfiAk)tb;EAih z)J)*Wq0^(?xV!ld93aQtjH?aa0_`D;zWRHbAyDl?;k9ky5v<OGJUkoH;oq5buBFIX z?IIs#&tDkH^k$~H%iO$6Cupt0VU~~IAhp?b-PwKJ3;_+)kP32WpgvweV0+f5?#kp% z<Ui4fM~owr$<^z%-tI+-Pd?Hh)XR{4(rq)@aHG=1EEz4W-zmDxsR4Q>*x6)$X$BAi zGP#@oYtH5d?#4d3SPO2X-|Q`Q?zz4i+k3p!FWc0i_0&`u)f+BRNB3)L(Yk!JjZRl& zM)tuaUUfx`;zF|ANV~0)^xU3oWyl~6>ADS6TjQOS-G8}<K$8m5FzW2b%H;#E;4|b7 zI@sixkQ*I%-K!|I?r*yMfbdO`0^95Ly|*jvzQ#=K%FLP<=ig(FxcTes!HMR_q2|%P zu_<=~#F>NGKIbt|19lGK|D?xC&D0P~?h_p7Q?0s%Zs<UU=+XKj9xU%(ZQ|Sq>0{m8 zy(=e{&VJCKr`pgAX#&><Unar}2-^S+JznajF5bWO$`fDY*-J|o4~ZH7y<D-_2Q$+D z5%|~?c#&2<@`G0L#Vlag1jhWm*<x<S(o8JP{_Hi+v5+hC#&I1uFS12iPuZ?}KOcla z|Lp`de6}sYf_!5`ce6@=M@$dm<N5SOM&j9Lmd;l75Bhy&$W#bqCrS0(T#_cxa10VL z%GllMe5nio&OkB0&d>{rKn~iKwO$+E6WvnqsfhC$fQ4GvwshEa&)yvG-tSGmQf>&p z?DrD__#7GRZe`5KoEfH=*@wUK3Kkpx?edHt0+OHRJo@;JtBb@rl=M`x$cY{R(V|6+ z88vR;z`?@@5FtW{6iKpVNfRedphUq~#fp|LUBY+?Gv-X1G;K__dGkijoH=z|+PQNF z{|_EMeQfsm^CwWCL4*hy0tysSqC|^~Hfr=psZvOgB2}t%N$Mp{nl@eC#EDa<PM$=0 zB^5TTDY9fyoo$u2l`OWi+}eT*_tspxb?4^7n@iVTzI%HK>lOGfF~Wrn8%CB`@nXfx zls#6qY}v43-vBk6CRy|5&CWc31|3@T=+K-^Pp+&=(6?X1AU|fD`0#AnfCB^Wn>#OF zyLRK+ayyGHTeW9Vl_e`y6sfOYxpvZubraR8P$NZZx^yX0qeKxQ3Tnvbpq+vK-0Z_= zW=uOS>&%gp@?@JeB+rl;<3)c*Emo>TfdYz(nve*IB8X@R2p@Pr=!P0*h(Vwf|4=x= zgb+gTpo0xCs9=H!AaK9{5d87y9uiMPF+~+uWU)mTT{O|0duF7uMjLO$F-IMD<nbPN z{vpAD1t5@Mf(bClfCCRMB*6p}P*`E0f^0xYA%+|(0ttzhsOX}MHtGnZkVZ;ljgwMZ zsil`<nyIFnaw@N<@C^B`D5DlhO1q|>f@&(Nq|=HkPX=91EK-m&%Q&@$d+WE}?AlGQ z-24)z(n@K=G&W6Ni)=DvzDXq$Y>?^nG|5OqHPz8fUB)xYzKMmBa9VpzGG#QyG*`kb z#ck5PB7JnO-{6|Xmf_TD#W+NjV{TASo{J8vs;aBxy6m)jq>(!l`EE`^{{|s%r}J)7 z505+Aa}PfGPO2}B`^E_4qb~ZZ;=cd~Ebzbt7evU02P14@!U`|UaKjEGcpyX%dStj^ zha2`s#)l`S*x?^}Fu;KaimU)hC7C?o1SqAffy#syYUm*?C8Eg7C^X`z3o%6^$xM^b zWJyh!WTFW@ICtvlr=aSz6De#TajMU$sseN?LBT5YP(+PGWzn{Zbu`$!cJo!2zXThs zuwTahr7&b>)09+BC3EeYQ531CHP2XWRaLuDJ=N4#)v#t7Wn6m=S6wl+tyf=x)%v&K zjxFx2Wy4zTt3kPnR$5J{wH6X=x$Cam@Wv}|T${>07v1;fSeL$b|KE+*3;zBCP(UXL zT*5#Eg;0<|9Q>U@pny>@!9ol<$bdr+6D}Zzf843KdFOA8_<8A{f9D?|GIk(>2|7-4 z$q<?pIm#9aI_TspRo=2?j9vy)=6Go?b3UBatb@&--_(gGIm7#Is5|pqic|QsG^Sm} zDqDG$vqTX!M45tWR+B}e;-a;!<)v$X;gv83N1L>9s#C8j#w5DojA6{pRChz+s^~_U zZm^*n-JndZ93!|5&c;%`;0q4>g1BG}t60JzPFj?O9OW#~S(M|%Caj{wX-UO8*wLJJ zwACGMf#-AJ3LSb#cL(>pM-K6s&+72gx_QwncKE8DzHrAc{~S1|cfYHU@H{{~;~~re z1(?C|rnkq5MURhvWY~|8fIaPT?_=LHLHGnRr7EEeODmg*MZ5&FFujjVHbaR@a^@cU z;lXG5<B8CQHWWMI30r$o8da8v6|Fd}D}-Voavqo#MoG{X6ud>Ga)U#`*d}Z>G~1>e z0~yT>LmJ@##5SNY47$}Vh0k<GGnE02V^9Jb&0wYsZxtJ08m3aW;icDfvl|L3ZgD|O zmg9&BIU`OEI!TmH6EE?^Yi;LFi>RWv!X+*(uE%s<1S7lbLxy;Tfj|Di$h~HluiNFW zjl7c(g@Q*gI#xge5pcjAlb}aHb~HzR^k_(HRJ}C_|0#PCFr)`SfXF9_k9>_h9}yr) z5sQ2&W?~}4CC{WumaK_qd~lOZKnbon^{<ph3t-ZsB9#KNQY+7T<pN_VOSI6kEx;KT zF1dC=Uv@K?9n|LEj0vi0EVEUtg67?tsTpT90~?fx1vY-MwrwuPtA+XI*Se+)9zM#P zK$HcthFF#&N)B4^v>fK3xVd}g^NQs$54lKZI+n!e4eSylyyRuZGcGiZ4dvGjAliZz zNYp|gm}BuQiqQoWU=IIyhe%}`quI)~dVw%$1d8M_l_FA+<0~0VQzp}ha7mIjt>l<$ zw$m^6)Ft){s!;Q{zflt9f2S1SQdKFPs|4zm|6Ylj)TmlDt445Gx74ZyC&f!&UdpR! zQ=11R1C4Dc0vnlO=4sNZs<m=v8qk<TSpjD&*eK>!cO^z%1+&+@<g%RS9Zq0{cpUMX zqOk6KCwJvZ&nViHik=I~x56d5(XEGzE~#ulO|m-8Zq^FxQ>a9efCM6dmO-L@kU&Zc zywj!@0~5HY0~TO_KESrNAqDA?0a-mr<aW2+TWKO&x=4dmi3jJ)QgK^0$@bw?r#G9Q zdtfq?`w2Bp)TNXE@C3l5W|x56_3n2UD3%5)s=Ttm>I5mc)xLxigO<wG*@$6R_{P_R zEL21>ra{7JHWQltWmTu9u?KRHaF_*N|I9WKBj{XZaKSp<VS{lAVaBENaqM&!R4d0s z#ny8>Q}m7%fdV>y_S0PFN|$BBNRlziYhDOFBkgKeW849O2R9yVX)8p65TKThKxVB0 z9${o912SSS!gjW`y=@Xzj}%Tm5|n*AGJ*uxd<>~E6103=_T4mIIbAN8n@hhjmsz?% zLvx*ug4Cp5CzVxMWmcS~z&X=-yb%0hR`;yl90tZ~H`L%^#%2t{FlNy3^<b@r@r!yW zVicpwo1;+(=}0SM8l#BCHzsrGx~8q-8w3omcnNC0kn_PlM5n3OiE0e5dc)PS*3meJ zPg&1e#I+`uiMv?Y%bsMQ1obs%|L-Mi8Yjr1IDVtDO~7nt7Z2J(Hh?T(%WblkUE8#+ z_LBeMi~=m+q}xkU2UZHc6Qn>&1%WBLv&=GfQ__7QAw#?~$x|`&%-%l(mnel&N>l17 zyGjFi)1F2sLsd9Y2oFxyw8rQ4W)M>pCq^>{{nbrn{BOVb#xWG}4a$(*nV+ef>zhfL za8SY#qp~!n39XoJ%ADro6m<{(3fRV-nmNsaYK9Z*M4-D`DO1EJx4iYOEGFHbl-0FB z&u|9Kx~>br1`ryTa3BN$!Pp4F!Gp3cQLcMn0~zR0kcSKnYNvgVNw&ZAs)r2(Aix1c z3bzgDE$~4ByCa!{I5zWh|A>buE-nd>_31K861+@G6EU*`GK((6%QrPU3heSX?Yf+R zYb6ANrKu{5s#*(1$uqe~FG=y0uepuSBMi~ww2K3)*I*lyYlcavwEU7i*pofFd5n$g z21PgqY#@gGg0GjmxEd;)-vd70xH+tHi&9f3!YZO8LZW!O9OlcM&4E7en7$E1kMtn3 z(m^qGX*$*6weIT(@RJ?dNdodKHr;Wf^;@=Pb3d<>01#P#1JH*0%fIKrzd>xC{aXP4 z13(PGfDMp4->N%-AP5^kK!q4Cnc}+#%m{ZI12PD__+c*Rs)Ks7H=F<(pWq*TTQd(F zAf{?6fpaB-Gq^)J{}ek*LG!{I7F;;I;3}}mAV4b&V=xBUsJI*C6xWajY)FM_NQM#$ z!jOALRw*HC00eBXhSqC2yRt!2L58vUML<(9D6Bb~OB}@k4l6thL$R<d>^a0@H7{H& zDGEdB`yA>+I-4LfJD@Bz6exG;HP_JsEr6Y1TY?!=BlGhC^iw|x37M_K5Dno&5J3P4 z5Qle&Ekh(kiNQ$csUB^R07cxbMtnrNGr)4IL<OudOpK(O+C+}<vI$IyH`t_6{Hf?N z#ZXc_qxv5<+Y>$k!GMFs$t$?AIJol4JU!b*7xWAEg1EsU#!WLu$QTB<iiKJ*t452) ztURm0!3JKi|F35Fn?ftbryQJ^^Q8p~H7T6J;1G^k5UeXq4t7jFpX<VTYQ7G8zHM== z5W}K-?1M90I`~kr)!{xelDar#D631zHd@FQppZNS0f_vuK6C&Cr~q*g#EtADjnqtv zsh)DcfCKoyklX+z0Rg&00ZGKWgs>95gQPB5A4-~;?E^(HlS${=84Sc9d{ewMD;hRq zipP61$rH-(ni>?WrCda>q}(g8`K8*(6!;>r*Psk?s77g6Ijq#m9~>rTO2$-(256Y8 zY}`FzOpJ&l9KvwUz2d9jD@S5Er?)(gonsEkQ8l`3HN4CgSli24+ozncHC#(Weq1s8 zD9rsh|ICWmk~wTB1!<7Re3F3~9)md^2RHx@Fo(?SOo-vk4SkprApz0cm?IHMl|oI` ztN|-q2-jRUmx(~Y`!WigNt$ev4CKwCQZs(*w^mdo5sby5B+8<^Mdj4RV9}-Z`m>lr zu(2#XTVb1FD8gg-21eV??G!6%kOm%%A+byh^Xxqg631~=%lD+hQcI`##6m+cqQl}s z%xMb!<eXU3r|Pr5m<Y`5qmO}d!vuAL1wF{~W6T-oofQxmIpP2cwW9+dfp_qSi}X;3 zDa1$Z5fD9q1$Y4MVMKA0veZ04;d-PN<uaFipHIZ3!P}&ks5hYUnK(g3{;{qObi5B7 z|4yeGxIwABIz!In)I1|)I3)GO1cS~%E40XvO4Q>8M_@f4JgX{&H0m_DQJ4gk8-_wV z8;e6v=se3XZBO^~tGHlGGlk2zR1Ph~Pv*Nz#`>_LqqWGgK6CjeHC)5YikE|eofs=f z+u0Z0;T?d9(DvH^L`@h2$RkIURECMvg4K~9nSlcMKTJiE4j4d@;Z%Z{0UMwaA8@2} zYth&Q6a5GY_`#%@oYDFrvrl5xIWYvH_)Y9ms#)zW?;<!8ygZ{k%H`a=Ufrd$bg$aD zR;cVC0%N9WC<aC7hRN8kqlLX=9EN&;t0@H>#;7Z^`BJc9PjVDKZ>>UfY@l_l|4;ke z!sUZU=bJ|m6Ayc2*U_1*0maii^+(O3*Mt%fIi#`jbEw_<7lC*ZheWM^ts@X203zTh zgq_q56<i%b2kT+jlS-+%OQez{A1Z0h1yr|84AtZkiIFJPFk6!vT~+;Q)x~?&#*5W| zd&O2NPMLL}T*XC&<5isPGnwmI8xmGyB$Z`=hGm3?PAL^;m8N4fhHemqBizPJOHY{l zGi}}0To|>#0@rX=Q?Gp|cl^2Qh{xv(L$Vc*|0FRpytQ0gTaswod7YPffm_d-F=9hV zeZAX4^;gxBKLUt?z%5)IIoSEFkss-TwtG9?Vq8Tkw<=3ObYnouMXtZ=|3vVWAD+?~ z!?V#-L|Ib0uA>o7>hRH6q&$NYQeEBEN8vobXt-|z#=GLiv>B$!kOpX=hFDl8VkIWt zJq;WzreUbBX^;ktt3j{wG_OHRF;(8XxLV+Ni{?dBaTN<KR6ZuEOL{t*Y|+c2%ia+q zu`Sxi@6}WBg~Pa&F*;1&epz4k)5D6AzXEsz`L$o@A>1;)-+%A|0&qLsGNh4|vXU&B z^0_iBTbV5@;F*E9kWGo4p&#fn*;5oHqKV*G<<VCRN;yN_)Wtj^Z9!ga&KnwxZwz6y z8P-}+24`p?8fLjt(avWyA<ZzoVZer1U<Pbxh9x8%N(RT{WiWE=|KZ*kK6D&nB5tSq z<iaFAS9B#hCpO!&<z4|ru`f!UHUMANF{tkwNW}asx(%&=i4gW}HpyHqAu9kw&`>m< zk!v%%ZuaICsh&R2UpMxck0C(uiGdoZvV<@{*W41=Y&Xk=w~}D43fx?p2&$h6rJ@Sm zMUY@r`bjv0*$WQR6GXujtl1)MU8QWehvStcH5=W_v?u)rN>GJl&A3z9ugx$$8JbFL zNTy{FONdS|NfsxE<KbBTVIT%93Ddb#iyU&5-s!Dg59{T6Bm~IPqO?sz%UVNYwvQHj z9T-#4#9Sjggl5u`s0)eA_nS;VGyqK)yKkoIZbmz8zLDyA|Ae+%0Nn~V4&Z?PB{xA` z=Q`FqP>s!iG~jvWW5Rn0-F%ZX>rGNBnkDW@(iQ0EkVVT&-Kwgk^WxPCg5(!;&e-jy z#2`<^j*M5K20#c0UjUqpjy<$m)=utd)R=~200bDCE0+saU1=|EjTDvcR&%1|T4omL zJz^w=$C}Q|&QVvhjp8$WSJX)z!W3#{Ch9&lYJ_}HL5&ctW43~c$jUSTV#sD~u3t2+ z9%3*6klda|H0L-T2$QUmcE*w<h=?t#T=(h37>!AL9!0pmH_ye<SJlye!)xMHWDGWF z@)}ZG+C0H#=-2f{!#?a`l?-Y421T$266$Cf>aPGF|7B(P21iIaWSG{LgAJ0-)>r0M zS)OHdq8gZPr{`F0n#K;HYvS1c&z<(Cbb;4?WS#x^z84EN+QHXiTg*EQZVDlR;noo2 zp-co=0CC6%tj3Y$F5`|A7r>GmG#?$mSpREdD+c>X)Ku4hpM<lQvyoP=O)`RA5( z#ip@f@KVPNz8Xh<<of>LyoxwhW<m}ED`!9kXyAoZkSk)k>=!0*0^hj)meOhUY#X9v zyaHj{fbcObZTKX<#;Ikly=4q9SG%NMv29{~+NUy<Vi70irdtCRE2y_6$lhk7JB+9k zV77;(P|7@j3_yo`AXpv0YEz$)>OqGM5KRau|D+PVkWF2rDLKjEn%qco8NbtGGD+YH zL{$uI;C(*tLN;W`1IjqtYreL{2xCiyUT83HxZ7|q{B}x-R_s=xuSswQX^3+eR_t!? z=wYBHMR0~&N$e%nAW1fy!-;SS2lPNc(*}B8BlbD!2wVMRV%VNjzbqGbJsqZ#^htLY z?sMB;t5?K4--bFiE*8{HZ$B`mOaoYf5<&GE;qe~-hZ<m5SAQ}AoI8m{(G+D(lq9Z9 z<XCru(VDRt&8111P*o@w_UhWnf0os$$m`;C??i#``1W$<WX~jhP7%K3IS*cp2KS?n zb8$}vUO?r#!ZZiZVR4$2c6WD{hWEir|I_-E>6!MEC)#jc?$7L{(-I5uf7dlL5%}#J zgMv>`Iiy3}S$MmJ5QqO__qC$|r~)!J^^3RP9|;3C=6LS$`0ojsi7kk-Ciz>ZDHlcg z?^bzv6Gf73lR!>9DGy!XeAAl$lbeq!)U`#PS592Yr4G(n&m(Cjjg43F%D9Paq<4Ml zG^S}_gBpem1t%3^7{(j!J>S#eskhoc|5nDS@ST$?=v_4>@)JaN?R=NhD<VT%!vlR( zTlqkH1BDmw8($a`5I?0`2W8A0V@SQ-!^!-R*7^gz*Kxj|-|D#pA-PnJ$$-H>=UF#5 zD_KB@cxRT3f){oCNe75EZQ8sk|0riporHGm;AzN*PoIc={sgKxh!7z|8Z{zHlxWeS zMvWekBnjzcq)3%2U23UG)25g)IdSS_(~~DrqDb-NY3k=sR6<)3m1R`ctfaP<F1_XS zDO9JqrcTvm^(xk0!nSfH#`Wu0Vq(XVC5G%Q+O)%lb^E5s+OlEF=F+We_b%SN%a+X@ z_Ul_FMctIiU3PY^*tBH9GHxuamsPD;tx}C@*(p<7Ns}HW+Da%Ypg?<)(uvcP%}z9B zZhEPyWy?w_PeLk5QY1)^h!AbmNN7;SKYt`fY>4O1orHDf%#l;@&A>Km(ojD$CX5#^ zUAkzg66HG-C{C7;Pf~=4{}3TSeDJ`5!$yr7Gg`D*f#QS-5+Oiz*nk1U1QJB>zyb%5 z^3OZ>D7YYl4LbNBgb_+Op@ROHLm`G4YN+8m|6qdv0uV$X!2}gxut5hPgg}A`C!ml5 zeKXWx!wv57-~$js5J5x{NRZcr6XAUqMHN<P(S;XbC^-fhXQUy}K+hedTpf1Y;Sg~X zRTRiYy>ZkLNFmu~5+o_91lvojZ9>ycIPJ8PPokLunrBBLl^Ii)T~^g(lWC>ZV_J#j z*jUJvMOIpg66Omuyu<=cUXe;VDP4YrqlhZsq(xVvhdS2PR)F?0YM+!*m5ZKHWwx1} zo`EK(DWsKlT57Aw|Ku8ME6rA$ZMfx@$Zm%4<{NN<2uIvQ4c%dfa?CkbP;}F!aRwPm zVz-?Y-hn3`c}pO1UV7`bhr<o>#SlY%_vHtI2mN7CL4X4yaDXrfZg?-g_gd%=zy13A zFTeo{JTSop_j}Jj=172m10$ArVh0|C5JHPD#wcTrINX?{jy-nkM36&Pp~aC&E_sHN zX+-xNb5vT1C2_)8bWuhd?e<YfBaKO0N-Vhq6KibRBuY-DktQddbsn`@W~oATYM+or z_UEXA9(t&uS0|R}rpu56$X=9+JvL#(Yy*fi(hzo-GF)r@_MoGNTB@n1I*l1qtae7! ztD?y|D{3~`|9b07xyp9Zn74(go0q>8d#pr!D7$R4%t1Slw9{6r<aS+TJ7joHG(q0C z=&8q^d+^P0ZVM@>yI;Hh!7HExAe!^fJqGK(JMX&Zeqp}B3ooHRC>-Db1SFb>qQonn z;39o7$Vj8cIOfPB5=oE;G898bVdQq%g~6ngP!ePiLJGYMvqUm;S#xh4;Ve?(D5>Og znnBmpW==Zw1Z&b-VW-W^0#A3l1=Q#^wW?VSZVueqrWWOvT6|+IWV;|<egTbCFasOS zK*lhT(KbV6?SWbgl&BPVDpcJKPkNJuXFekozsZVdIH?sU)Ks|G$YwT)^VK4NHLQ&| zE;z%9|J>x5wH#+%PCC@loVB*o9c@KHJmXnH5|FSX^@xjHszX-`?t>rwcz^@4n?M90 z;D7^g;2r)L9vtInp*Ye}cpX|o0UYpv5t%3h9PogONZ=wAte^$bn^BE6c0G^%h<hSC z5|WZcz9&WJd{a`+`q-x>i@?uj@(YugN@Bk=p-D|bJB?1@L<#@~aDYl_+5r<tH>y?5 zfx<8$*Uqw*ZyZAr6_g7GgDID^si7OcK+9Z^am*5yWh-yv3IqS7!pa<QRh-$I3_~NQ zo}@A-ful(dS+m1S=qeJ3>s2EbC&b46#)!yL)<O`%#3rs`I@G$(wYXCSZH4ZN=0Oh- z{{o7-8`xlV^s&zv$;g2Wyh}h2aDV}LV6Qq-R6}#DC`Kvdj(_wak0K%w2K)#}=eekm zEs)WS++)3tW$$A_>fZMt*@Y!Fi8|&(U&|D7B|JPNW?Oonmu`kLkmyX5J@eTm@+T9a zb;3>l`ybMVQk12=vMC2dpe&;n%?6rKYY|MQ2(dwlYCr=SVGAbN{PGP|`0^Kp86h*f zIu;aeb(&MDrZs2LD!yrRn>^_z(F8ZRn7oFEJv`@afXKMsV5C^aLYCwjqQoUW3p$vq z4jJ&-x$b}tWTV64c>v0uamB}=D@Z{?*|h<NRzN@yc)$SK@DF!nw6+kssBLq*|DX=t z0s#wX7)V7L$cmYC2Gg@qK-1GB?QQR+L>gJitW{H+M(GU)$!V2#%2S_isY~(uWSEL- zlA|IOX!>gtoK(3=(SQaON<&Ijt$Mc=DzIvdk*fn0r3_<0<7{OWAzCSg7PYeB7~gO! zfU|ZM{Lb|&kdda;u(HAyy6~DtaaCVOQ$t#*X0YQV=V5;c%Ec0~oyIz%M2thZgv_&& z(z++-xbr#ih^||u3m59#Q`&>7OFtp-z-nhVpamG<5wq1Tl5vaV-2Oux3qZggl?Som zmei1k%oq<iwxc32cL_ie5|O|+)A5mk3^s)lPScm&okFC26q#8kh2@d(|BCk!_FD;T zl4{ERHMM{0Wu<$kY80ly(rNVdQ-lE(s$0r6u83kAT72;hL1fB;0j^6f4K)mCL}L=z zkVb+R%;3d5#=#6MmEG{Vlo!H~uNnRcX}bAM59b-gyZT`|a}zAaI`*+hglFX{8=WV@ zSUWPNqIf>*EpVNV2kj}Bap~i_6OceZ{5d1-K-7zgF1fZ!?si7=@eU3g;G+*i5ePuQ zqADBmxYg4#5nAeH=YB`bOPVAlqa=sxViGwHX>&y0%*jrIH<Y%yGyar1lT$iXm4FVk z00&KI`5HQ_x**k6z{1sM;*xECnMN@H@k<c`m~5HO<um}Xjk0n||J0)%6j;0x;XX~6 z!g;fB4EsjI(wOFk9oAuCd1y|=mL%6f1eTW!Vd4|N^EfM}EIo;x*?ekY#-aOc7Mb0} z_sC~Ht?TiA+y$>R*3JRq;5N7`y06}`z3pwkM~8rLyyQt>c@Z0~#m+UoMB*qtJCZk$ zLRN1`nhf77!zm^+3Ghw6uV%w4IQ<S@ru(7Eyi4V?n`8y6IY~9*5-(t$VtMFNDLO2l z>dFH%-3)9ff~>xPD>5Z@^4P1Dt(poUGK^siTb|x4jY%}kscCb~Sh&^Me08k;%JaZ= zIGltH`brMVtHc_8os3;NiX)ON<S5Zu&x#giuag~YAv@XS|GBYxoSiyzNqdYFyY{;R z1c3szz+P^@KmG;wyR_RD9URSLlr7I6Q5gzE&)&V;^<a;e1s+Tl3E|OH%1FogSQmD! znI^dpP{of&%+Di;7tciB&sg4?FkC7*TvT-)RaMnhVHKZbMOKuaGre3{M34ymf-`J` zB0vME;oj`^U@j4ufvp8G7=zo4TB$kMRm@!7+?A>kpI%)Uh9Ms}0nV&B-}4#H;ow@X z>BbN#9rk5kA4Jx&bYF8k2j;xk)EQgV@ss(TAGie6xDXWkAyj_A&O!l*LlK!1pdJ6! z(YN&>9d(E&9Kdh!QAllo#8g|0q(C7_55{OrmZb+v|7lMXFyMDMAd*1fnN`<yF$Y2{ z1e-0Mz<HM^%^6Yc%;Ztt&+J)hpwd&V7kjnWdrh1zT$RPm(tXKbq5R-qP=X_joDT+L zqHvn0eNgTZAzH}bqRov0E#V5Tie_L_Hu=?G^;{L|P@a_&(RJX6AzkAP!sBE~vK+@` zwHWxJOd58M)mf2^X_4swK^%6Sw1FMF++n;pzycJ2ktGNqQq&*z<M4C{Har<{O~4_J z6vem*j5uNqU|HWyVj~IOK3PHdD9Lo?Tbd=Fb^#m)X5g2YqQQyM<l$MKSspmGqEkUt zEOwsf5m2Gc7ghL)pEww!nNUsU7YHds+5iGM|EvYc31cu412m}IG?0+)x!g_Kq}&8b zGwQ+$vC#0bTF%XohE<~tG2dXd2K4pN(2Ys;2~ig+9XJL@mh^#&m17xJk`qzO=BT07 zdDi)D5f{Z{w0)iXU0Vjsjv9f8Gw>lm3eP|OW$;)?1suQwB#%L603s3~jGWW~Zj9gY z2y-zYOo>_HO&6M3S0}2Ec4djcHC`zWRpg1JnUG{sDcni+nV-dp-vm%g(&7r<V${%8 z4B8TYDbwmjLn=VSGQl2Da*bML0wB~wE*z6tC<cDfRn<hs)C6CuIZcH<q47=Q&Kb>B z3YHaWWv-aXHg@0^S|1TP7UU2|5(S%O|3wQril4Drf%jMu)}i0lsgBpVPJUQhf8?e7 zJsAXugSZK%908Ai!cm8`z}!h0^Qaq(yhtNH=1O(UWI9s4QDi2PS<2LtKuC$2fg+p5 z%qYg$&4AKqlF3n3o=GxXO0wok#!w0xkS)e!GcILV=pxoE*e}4sHvqyhOoK7-pfJuL zTKvK<bOR+Am@f>2Ssdxh(d1*uq=ePn@HydL$<XE{AJ1K<U;*8B-rAUS<F1A0mVjYo zks}$VCHSR5nTek|wkOE6;}*doY0V)$#!mc^-2r%jKJa6J0w#dwY4CJN8vvjo3YYVs z03kVMN+F=%$=kfaR7`b_Bwb`?|59L1fueDUVt08c<kcC^kWwj~7yrD;(X1rIxf1A6 zoMo`kQ#R#R2})ARs4o4*F_b|!>?lxPjbdO!D)0g}_yUl+oDters3@UxLS+*YP?WY8 zHCiW!fs;5v-z9M8^eK)yg=G<uW#nw%ig_ZLUKU%TDfxAlKm8Lx!Q-=)7P?GZ9oD1l z&<>G7fnV~eMeQlP-pfX9f&mm_-G$Tut_X3p+YC^T#w6F4CBcJ&nPp1S7^F<TSyBbA zPfxYar3O`|*3U?mmk6fjY4lI10);HjVtg6eQ;c2`E+?=ap^Rz`kgi@T>?SP0)yt8P zGu*-+ki(89hKwE|GoIRH|2XNBN~NnzDK}Z;H>rts3f<5}t9SlNmlBJ3LKZxs<@c3o zW_jxxZcB|}5qypoxyWO>+@-rTR0QB-0W8A1&MSokrrAzNhY*8rEkK~68^0=~0Uj!3 z>PWmjsNfOF1C9ZcJkd=RgeUe}rE-@?mLi=|EO~|Cp6!n-ZY;;P(uy`kEsCCt&eFxv z5}=&y5F+DQ0O>bO!ZBcjE*NK50cVin=r{O+FPuefc9q5jtFZ3ubN1{DO{EkDZN}CL z(T<a@bZ62Y-O`HXPi0@2j$yOxTN63awBVCl@)KNQt=8q(7tN#B`UlvGtuD;g8>MZ$ za__x#h&C*Y+k(`I|8RhcB&3428{KBvBDGW{a!&(F=w()DB_UpwSjmQR7dT=nNQS70 zs^V#uDC0Jq<8mHLE{$g3iK*^M<*I5lweHL5-ccfhFBn5NgdEKtQ!^kb+;mDWY)~qA z(8;c<62|URUR8xfBNVzCti+l%;t-Y^ZFee`H}cw-isM-ZThuCVu}RT7u4#FM7LGmJ z^xDULSeu;cW!Ygv*?RATpsf=>@js9o@)+o1Cgce;rg0$>B*GgK_{b7~480XeMN;S{ za^fXrSEX7iCnep75|#gsl4+tQQ=yX4py=bO=%6{_OQwp*)|YZ_+^97JG8#k5P6IRS z!8Cl(kviHg|4uLk1I8qfgEII6F*L(37-1l5)vz)lR7|dAKqJmYVX`VK^Zi`28qTgn zt4LH|@G9N#Hl1XRDe_uY=2(Yj9h=pT$LN&KxT>EVnpT{e(VWiT0c-&7L~({du`(}+ zKXix>-0L1ajAEup+!pE~QIE4F7ep><{6?1<KS@2IF?K1QXAYdi_HW|YS;dwl(PAC} z|Ig7t?&lTIEiAAfH!zc4?pEDWtIE|@sID&Q!Z$Dj8ywg&k&usaja!k!9#}&+jBX~s z90|v+?DDLhM5kVHhV8<dPq?s^HlH}vnl>UW4R>i{4KMMYC9`O2)LLkD;8Pg*FdJTN z*1aRS|8A{(P;a^d8Ec^tJ{kZJG;uRKv%D7dgKShF5CFdR5!|j@p&AkwzguK-StEfN zCKg`8R_IObTLo?;hr(Gpi)Nj%^N1=gYox}fzT(5Z7krf}C{r#1)fcJ2=%VRjGgvaO ziiKNQ12#-TG(f{E7)CPsDhZuMFDQdB00K2kLoZCUGD6ebSo9KlGVR*JpiL*TR%ey^ z+?5heHcB7Ta--6IV=P~54lhx2>@XTKuM{C0TxQ)H#wXXJD-tghya07R$`+m?^%Ebp zZ!<`T*g^r|>$&|=+-C9IYV%6{9VLEQ{K~H;QkTAMW<r3q{?g1?gD5JR38yODCUn@R z|K2ek8?al`Vq8;hQ)We=#GLP)UM{vSEd0eJ2tox_u%iJfF<7!P4TD1)m_!o;4EEl8 z2P+D#_X(r$&2h#PM&a#R<+5fa?{eh~yK)y+E7Sd&)6p_LwYHL|AsccF7K!Uzj*EP@ zAAU?s635E|EWiMm!jT2{Z_7A@fbWwn0AlvhzE(_Bqm)Bx8Q{ThnAux6FRVfE+jS2v z;gVu#a<}BAqQ$;5Cj^cwnqX9&H+rw2RLCaj5sK#acQ;tWB&0$!3_~vv1CZ)BnrE^x zJccva0wz!cH29t-GX};X`0Uc|6LPexy&6b!7%Hc-43G9Bgv8=3ZAx3KhCkhM|I~7s z!Wh;4uuVs=`oRaBqJRmQfQsKC9`5A=Xai9rH8ThI6yNJdIrT^h61yEBqAFl>VYOvi zBxcsHR|l>+yBVAj+#BZ%;sWq#vLgRztV%vE#Jy&G;WGns`E0^Bvo}VX1F58?0w7q! zF!;h_7r0pT!Z0MmHk5&ZrMZAJdxP2alJ0Yp<~elcm2?{4W>@D6!!Y4YxR!3|v|hO5 z00;4k;X;^a)M-vz(zMl9BJ{pvjzOC+-=$B_sRKaN2DrmB)3}3-I#O?x4HS2jCFWC` z0HJCzg9_|&MdUX>V3~3C;nn&l`rCHlIy!$>|CTkvRi2a&u&|eR#|qk8|FdXp%BHXm zxPkj~v&Y;o2tzY`a5b1gCQQRx=z@R?c$p`IHE;nYY{NG!qqswpqEXFyS2nSxdvqSF z&Q)b+dp5JiyDA^8R~lUqAv!odPQC*hi>-Et$Fyt97`VQtT+;UHpbH&t`f6S80uTTZ zgu1AkgFY0#;U7NYC%)n@KI1pO<10Rb`~x8jzye(SL8e=RrtcP$3!)Z55g36H%$p-g z!9GC}7@U5SC~W;|>q2O#9_WFabtpy%3n2*AP%T0Sk_p0DEGK9JIMGDLu4Ye^0x6V2 zdlh>OwE`_Hzb!DomjCfAZPl|sHue9)W2?Cg{=zFv!!%67BxC}$|F6ZS4Z|@w0w!?7 zH%x<mW3maQdG%j^MbDf?qr0l$4J|bP@-Kh#_c<yUKR}QoRZ1W!Q3pLGRLF@T!%dnV zUb<B2Qlv_eB0<uq@lnS{ixwqXgeVarlZXhV92AIUpg%AB^wBf(&K)~9?aa|B=S>@* zZPElKLk3JyFI}`~sUjsx6ev)fIBBv(iIE~guma(+m4}TQHDa`Au_DC@6C^-@@UQ^` zh6xfPJXlbm)xUiI^ySsNmv3Lce*p&;-1nckdxsGxR=k*TW5<snH-7g|8v+ClAV`={ z0mB9k9zujLapDAu6)j@SsA1y<4jfy7U?oxnNs=W^qCRa}|HX=yE?vBY2{VSwnV@Ud z{Cx99j?OxB>eR%8hYz2aF<<^+IcQKyL*EUV6bW)sqmJhvX~bxeqC`!XAa0W1uu~_6 zo(>iyg$k7^|EBokuayB?k!2PGZLwvR1Q|^5mIon>P{Ld&%te<AG0afIUO4PUm=8bn z5JX{!Dbd6eQ9RKYWRUsgmu|M<1`{>>I3|`Z)VPKoYrcVHm|s#1vcwQa1kuA@G)xl1 z3YnD9$p{-%P(fL!l!d@n0_^X<|MWvBq53*;NWL-OlSrbAFyaWkM;iGEq(n+W1Uy3s zS*fKzu8WC}>F~Izjz6DUt|y<63+fCq#t`l(q^zi-|EZ^<nrew8iXb8@A9!%>h8kv= zA*>ZpFpGo`)Z!om3@VU70tg&9-~n;;c_*@2X|2^(#QZVGpIv$F)z@Ev4OZA;i4FFi zcl<HI00$n3KmyJ(_zZ*)NEppDu~J*DHP~dM&9)_SgQBS@c>66l;f6XcIiHqmPABMY zx`R*au6t>_ln9wKJUGcK&ph<hW6w-Y2p)42hQPe<AW;h1^1lGDtkS>*7mV`Bi<zuY z$&E!cl0#uc6jEejjPd0cUwr9hm|<Qahnjup;bxnae+2SG7ljP5!<~;ra$^lMrtsp6 z8=QsWDzD5^%PqSUMIkW5<iue42sV?VG$C1&|IL2kG-*zi?!@!D>ZY^Fjz8ZO^rtm~ zO5@N(y;xKWE5?OX(j<_m^wLam*tAozQV8`dQr9~5t+*U0fQNr%y{Fj6A&*>ge;n6! z^2;&L+?{`-C}4qRHNzl-4LX>%+R{?MRy7-JaE%8bVk2U<Z*g-%H*$OXO}H?IGA@mE z+i2Hac<qpPI(o6wE)eeW)mOZJ&HJ~bfGeqf;P}R*&%T5fZrEV}As$d-DvhqV!J(hD zFk>ZoMzVbo;U76jV@Sr?#TK1`W*BH#{3RF@=_fK0f$V)oy3o#k7PMTTPeM^DpV5#u zpe%jQ6isv5m+B)XGQFp26G4-j&eJA0|Aiz@U#rud^3;bt?a3z3dCnYovYfRU3Q>wW zN>Uv4D5%^G39=Ic5HOXg8+he!EeM=hLgN7ru*EH_a==_J!8pogj*3+@R<3T9MJ;ae zSpUd{=P(nx&U64Yr$a#sPLr+Hxej*SLc$Vm6RzFl4miRgj_-gcJm>tWc=O7Wz3$~5 z@SJ2kAd%kmsMj9%VDDfEtB*n$#xU<a415A2P?d}pB?d7tLh57E&)BDnp6zTz@=FoU zZU&@Y*sMh+YK8zk_CB9wXqG?=8Ydy7$p=b|Kmq!mehP9yPe4tBR4bF!KA1K1w23@j z^BQ<g*pd{gkWVc{8w}M(D7L-L|Avgpp;ICSM@m`hhe7PyS3Ctc!Hr6ZOgx+e5U>Do z<fCz1wC6n+lPfFklb^hrj5#LYDhN0WTAv9G2}pCTY}H^}Jn%tmgfN>o#?f}-A{TFb z(*-*g=Qzq?j=KO=JmVoRc`ad{^AG{OLn3lL)>|Ya50)@UN^+80%F-n<nIQ9R5|_77 zpoNmeAyIDVV?`>ZDNodl6_qG}C3+=`kl{)a1<9x*5-KfgnWT(OXn{l1q=FzwrC#!f zf)xxVLYxMshD@!49!%z%J~G0t=?iSq%oEx0V76<{A)9Sr8x7$mH@fLiDw4_@Ie{od zBF;daq%lDfO@*onL;wO0|1dxeV&%AgZuWAA!6H6E8`{k|p#aPxsOUD}0n=IQG%e`V zYFzhF*$`o(6tyVsGHS;=c9dPrc^4o1NF9>)L3zs)<RD2h9uaD7BLchL)U>Ct{M6Jx zHx*w_!K%rg`c#4JlVyjhYE-16sHrMCQB+R^vhZ3}l<iAkleVkNqeW1HWToI)g*nWI zNNs~{tsd5t>5;g;sf2Xp4ok!~wrcw6g)#hzUjZA~-!#fmkdlfxduS=xVd|Wm`qUAT zsFn>F4lWLGfB_8g4|jx?#rFJci(!1L$(X_b3kc(8I-^=@u{MpX+tx#4Cs8=Y@pc$B z*Kl_GJLCk<x6Xmr|46IzN9COqrG+dHb0L9|>M0UF&~@bY@H1WgILx}&Jy6AV>Y$$f z6qG@2?{|wj)v1aM8Ra!molR6#S%Pe+S<R{~;R~Uz63u}+HIS9Yx-_QY_dXdc=0lFT z<+s9>YbDVaoeqrP6z-{PXS=3@3Dq`kE($4CFtt;5IOK6=MJqx?=ciDxPEvJ%EfsjD zWuU>h81I@^FXr{HB}17A#B-oH_Kc2Az*^M2wxMl|sJGyVo7>^;$YZcJ9{tK>Ie-*8 zbqFqXQdrzTG;dDNBhN|^nPr!{XKIb)giOOsQ&Lbcd^nw0nt8hBp#4mi2aNN2KST@= zAyv)*4{wJs|K#3{{WQMv9bcjqz37EC+R^;oATs~E5v`3dByzfRrd^U?6>{2|Xxp|7 zLk-w4kXk8qOZB7<yEjd7DxIJ*%i!86S<1G`1C9gs&l%%upbvdAJ}|%onl*t5pjO9b zOr2|e{2FJ=t_ZY~BW|nB(ce8-kIsqLyhvJH=8^k5$vro^1Lj=#6wF}Jo#~j%TJP)L z8{gY~(7xOJXC&zi&ILr}hg?L!zPC^CZPuzT6lnKb6m6IEo#1^1GI0z>&Egk7)1=|* zCOBEzz;<%UrWXvTouJ&We|;O=els_hzZ`FRD<|KG7#1VSTEwSHRRm0IfHUZN=)D(u z?}5F!|3TE)0nS=_j#caQ9&770vW=)jZBx4<(@~?t(K_(7y~lWsbeiJsPL-{^(k!=> z%WThHbe$GSVA9)?_I@C~ZL!_%8h%4>Hn^TU#<Tky72%-#GvX7k;T&kb#Hzj`PU6rC zgVxGm+UoMKX5%XDnV_joJWu4PDX*;QT|lk$R4#5N?9@;#Dpaiq^k%~pi&MmcENG9` z+Tw8J;sBh1_ki!`es2bMZ89q3GK!5ej?HvR<BY_jQ&{6QUI(I}FWM?<H;n9Dk_`LW z<+r@;Cj2Pe0tuze?#i%C%hrv9yzJc`iF*uU{k});#)o3+&hF-q{)p<|_OA^O4uRBg z|4A<7mK5)+%ID#*#Fu{QtSByO+U=Mw?;=2GnKW;%IuC_F4+8<^IZkd+Qf??v?*j>| zuwc&hV25w~hOx#XR8C-2LLldCjj|x%06+j)Y!K*b@DyY0A5h=`J|_Z<O<H!WG+HZL zT0`pEi0Z7a$c(Ixl5FdGYj|8pq^7W>#?A`)#b30hBgpT$9-{5M@C)-p-q;TnuB1RD zrhL9i@zRjr5bmn%&ke;<@W9dE!14b8FaQOR@oWJP^U%H=rb|eHdxojv{?JT3Xgvmz zO_+(mJnn0_qXJWiPx8vsUI?2U@vqXLhCGl_TrQkoj+}l-EBeN7WbcRur&MeY|1Mai z0MbAPRdLr+F(gInANruQKxgSjr*x*pTAoggVhf_4tu}5$`o^USlA?}=!*`Udx0=j_ zyv=xo>yJ!o5H3wT3aL%9Q0>-^YM>F`;*Gi<rv1d{K*%SPw2K=*DGvGV&AzKhzDo_! zap8b!tL#p`!m0q@v8>E0^72cq9&HowF&{G`z(R=Q3hX=bC7MDm5exEcpaX_BP$5Sx z^;&KcM-Z_Rt8a)X1vxPzX^q5iZvhT~7(kLFTWlmT^PVOH8WunYHKPJXhXc}rS`w<Y zgwS=0aJFcpCUZjx>1d;{&7+#E+rDln>qYFyuI#Q53(upu{%Z?i%H5!{|9hmelB{v= zu2LKGO)J+&EV&Y^`Y++4lm75-(CUyK7sMSOZ_yYnt?ZGl@Nvr?kPzi6FZGfF5lrOp zswMza1GA}6+@>(SsluRw67j}|UeDEv$mTLK=bDIB5C8+*fpRu8#x(OlxyT>T0Rvod zpq`~OQfswnQFVrJE1Yj8qfOdwl8(+r>v}R6p^%TbPs&VcH<9w(mQoAx(frOY8fQw( z=8ephMmgVarxq{%(6Ae;vqueYEJ5j~ghuglbO6&5(G0MxfXPeh(b4`e(*CP1?b0J6 z@E`Ru(_rGRLeGUpkMu;XhE{IE8f6mircyL4u`(t0#sVWprS^30{{c>H38Y9tGt)5W zw8bW)3Tg~Op@non!!%=U`PRsxrj7)y&I!f^>zMHR@~AdL>f44(H;*ekdQ&L@hI;0* zDZ3DAz);MpvHdXVMzhj6@y<t0HI$;0;fOSs81G1t^c@e-KbBOODz5UVW<1eEO3kyG zI1eBz&;qNeh2BLlQBFP&g$#D*hUO-R?$Zeplhw9@F+FTeWz7R3vxz3t07T(3@6^TY zv|B-IGH&4j5FjPnq6cSDp;D8LjPMAXfJ5gfx6tJbW>ZA94^pXcJB$+i&Tc8UtVLav zIN{AWXH-@NqPnQE3^VBriBw2W^<h(0NLLj~bP23@3F6xF|6pge4;PRDp){EWallBZ zSFhCbK5uOLU`vM;Aydw67&1(kl}s_rhfI(^HPPlm3>4o&Kpj9ExD{NrC_#a?R&qrG z9`v+4gN)MkB~{}V36(Wz@?CAGLo@0_8P%hNkwl@4C{L8^kTNOJEj`8$Bd#Z4wZ}d# zh+x^046_le7<Nb53}WT>y;OB#i&Q(u2T8j#9-D?9;j;1wrh~{+S2K@SC9q`IlRY`D zAQ!Pq*T(daHB3`)OhZsoB9hfO3<uP-1!7H92q&^`4^9nWaq4Mk7u0e%D|IpFFeYOO zz{vPeOKAa>X_=2ujS$+1%%V&!Cz+65)rISRGNhyf|J>@OC6?#XC^Z@V#ZrHBY!xYR zhx2S9$spvdU}-dBLiK^p$8LqREaz5kyLU+K_HNzw4lfo~l{A<N;%RD?ts-qA01N{C z(Ml1QC8lX{^~&2EcZP(5Atx6E?^D%cZa<|pojCXA*y&o|X#ou25u`|UAy{%MCxR(B zayADQ2w(vgATwey`OGMdV&E$-)cL4xqHHo=t8EPE)i{>SCqW8OhBs0r)p<6rUztnG z)DC(#^$VjC?r1b&$%pRVc2&a{sJ^#4!<T_{)T`{!D$myd`@?z-R(-wXZ=bYG23O<c zmxK-%(*$xL%O(SNVlW}s+9Wq-9|a-@*aTf;|FIm?b4#Vxb{3u>KpfrySt>Y>ujpG% z*IPHh6(1lpW0yjKFf5|ZcApP-UlWCWk#~F-7=7}$o~#(LLtl5Z>}uGM#BcmAVhc6Z zDZfm*s8I|n=^ERXIW1;<@2-1~m@MZ|VpW-Z8N>{on7+_AW9MyF-_l8+6q(|88F>{w zy*O;Nw9`bdOB3=-BQYr`w^<EKKQHkFYmQB4ZHeCW#9|<``q*2y*~KP<v~0}yMAJ{H z1)&N#HD=&KpZ58p_JpxcC!5d--(W<8@_6!fdAj40&5b<PWFwrn{65*;yf8*-YHg_! z8?j4DQdx=NwuraV@F?V!9a?<7s;AJB{{Ub0mLZSP*tcVisR2QDO8L=nFO4tzvY7Mt zAp6Q#5oMX1`92LR!(^_2VJ%eJ)LKUjTc4-^@Ib}7`E>O-sDouPbb(xpPmnhtwaQu9 zmaPU{g9vlcT^HHZtRQz5_4<JKg|*h6i`SA-G(|NT%l^4+yAVdXM@A2J3=djiwRcow znY$*MmD4e<&GM~fS$oa*8kJ_zrg&kh*oxg35OY<Fm#NZ7_DYRcakum!V<?$j7EA@} zn^^C#G|ZfaXj(TBj+MyvZVdrq5RZjAv@7SQxo9%VA)r1-kXMqBTg$Z=>Zw<gop(`O z9AydP#tVpp41O1Do8wXCCCW_H|B{a~lMQJZG4*+e)7^$iVZzXdf7q0>k(R$|iQjtA z==!?5*RH3VVsz?AlSU6WIt+K2@@y4)aWzeraci2Xi!m*+6&nLRO#{g|!p@k&()hwE z5wSA&vZr|k<(MN+ECdXcw1bw93EWmT=MG*MsSV2MRHtcUGRUe938xk|%_VMlN4I$^ z7+?4{fjfD0^C*)GY{gm&+aqw>t&s+{ded61*P5;2uQ}~n(6BqMXPjay)_iRlR%5lV zC9g^Mi%dTHyfGrZ@shpUdp#4;J&ze72Sq*?60-l7u--MlF&FmG$uUu2a6U1qC9A~d zVhsKP9S%H;gtp8VV=|V(|1uUpoJB_#t0mUNqN!gSkxQ7ur>$I47^``EkLsDLb5mcx zuiU`8xL0)D)()n=49xu6xoxV<lv9XfT+MDgeQLbYon*SZTgRRFyZ4q$IJ!yO*JA}c zN=3RO`laLOS0#S6nBjY`8u4*ePI9||aw~T#TJKEF2?t)SvHmlsZEaOP^8j+;XVKg- z&ivRF;~zj^PhoepXYmA{uBk`3U1`#`bQdQt9LX3pIl9g^V_1f}R>YGru8e!E-9sYU zO?o>On54LZkTW^4H+!*ix-tFUD}B4)&mEzdOCWC=`_K=IiGw0-J;ZhyMQFY0_d8lW zPYAN)hBZD3Q_8)m|8CS+rfc?`I;EyNF@ba11u3%v3bb^U{V|fg<h$q%7X0|4rHn?S zLh0OTqk6(!lNWOmp3_Ci)<saXdU&TJ+`LbpE0uYhmy?Ba-Pt|fSo~Av-QMo4eC<7# z@O|o)*g>owEe(y|d7LdRDB$DrRsm5TPhGtYch&h)aY+v1i8Ucj?@(5b<p6lH&2%Dt zKvOoCn&bG(CvyO-z^73@GETnaagba$SXERK&Rz1sYnOy+>rkhUcZ0*)G#rw%@3(G~ zcmus9E;)I_5A71E{8IdEx2Mrb`G?syy1QG`)r`8SzV&hZqIFy?A+E=#n0m+C4+DEH z2m93VQkd}t|4Z5P;o}=Vi*@29%polvzw?vTDDnpQ`yy8`vJM9VJ`(}viRAx2=nOpj z9fK8X%v{IF<xf*}V5|Aswd!VDcRf@#H(c8~{M#_Ul225`ds7+vIg!X3>CHOKsMp;A z!j!;)rcfC?*eYQ{SqvG@nq|w@!-o+oTD*lZqsEOKJ9_*GG9*ZgBqL6g_^_cYg$WNH zBnVR=shKl9*|gayC#Rh|H~I9bNz<jFL@!l}6bTZfM@*YGdb%iTqN#`w8M=CvkRd{Y z0(t$@Cu~?gc*@?fQ>V@xwR7aidGn@?+%;+Ho;fpSOc*a+x@fUtC5qrEP@FhfvLp$T zB1D7;{{aGo2M-)LY}A-BqeY7qC{Ua*5dwsV4jV9Fm>?m70|y42=zDiBw(QxoYumn! zJGbuLwEdam4LrE;;kW>vKw-b%{j+6YfddE<CRD(XVS@({AxM}wfg;6<7BMi}pe)&k zV<AL}AW4F_iD4*E23yh6*Nc}hdC8oqyGE{DxN_#KO<RW@ca(((AAE?_#~%uM704i1 zJ!l9bQza5rR8KY4lu}4VQb{F51*OSPKk<}PPB(cXN{Tem6w^R18N`xG4NY`XNhFDc zV~#rRh>?vb(Kw4k4YAb9i>S0{%8I0<nBs|^l-Nm6BmPvBQ5_<s6oyVM(uh=4RrMet zVlo(rg8v8_NZ?rj`sWs0bJ1lN8G41WS6^CGQH5aa8P)`1iZSLG5I#tT!wofD7K3If zcxD0#p?SbTX%$Ey0R#>#V1O|Hz(!oBo_;!;Z=jA!>Tv#maDW33M9>^`8*o6Kb=PI5 z8D=$nhXW5j0O1%B<)MezdhH2T#e4D5H->%q>DLB-{r#8L9Rm`0pjZnsC?<pvN=TuF zjXd&gh8k|z;fElKxXDgXc5)(<DzX?8DFwYqWGgZP36YNx@yKt#JL>!6L^7_#(u+vS zw4x|WI;j&+oS+L7Q5{~HRF)Wi+hv7cYAa?}Ux9UIns)%m)?042u?C!J;6-PhegQVv zp8rntnM4wdH3k`>m0dPNqMUu!XlSHmPyuQYJiwX<{%~4q(@ux_+tX4z?an`S46quj z&Oz6K2h~}JT?(3YcPMx~K-Q~yh%KR>6YLRdY!~y<ne2UO<fk8h{y{6?v;`uV;2#VQ zk}ZT)O;zEAS~3L*xgMGuVu&NETVlIPu85?O_1=qbzCQX3dgvMXNFz!E2T7z$2Pc`Z z!VBL7rIaFqSk%N=TC8QpQh~{F#|)Y&7Mf<EwHBKu$2C`+dC|$&%Xt!3*vx(+;cK9S zPIiN3F(lf;qMtb`S_c_mP;{l27C_2B?)Wox`=E;Ie*B#prws%MEC2zk&t<^DbpIh# zcLMBerv<j6Os;mtD_@-_J;H)p+~!udW#vt8d=n70sudOm3C=5o(~9A^mAG(eX<Qt7 z+)&PiE{B<jT{cnCyWo{Mmk?=SGb$ax_9eO;e&mMuq9H>HX0R4rZb>r{#ff4Ev7lT+ zC=#QXQkJqfsCbEY5aNo*G<YVm43BsvgA4LdR+lu8K~Bu;i}Umpy*?%8W{(lnWOjxb z&8)zCBmkcWHZVS;A?*Mm*p&SKC>;0!a*(<)P8tl5wdPbHI$ev^ti;Bh8Qkgy2jo@S z7Ra^+Mxj{nk=uOgV>gsd@D0x*nY1p5pldZ~5DwB7x4P9O5i;(HNGVrQg#RKr5vj0p zEp(Ub<h8na!6-&P1kw#}q(jjivm!w9Vd_+OFeUktVI_jtCYV?y+f{6qThiUes%XWJ z0Zw?*LQ7iqW-|SxOnGHIBO3WMJwUaQP=?~!X1o`)@JR|amcrB<{7A@v+Qv8jD5yaX ziqM2AbfFAws6!vB(0dq190)+ba`XqC{y7pmC>WrvC>b70DiBz0a~rWZ=}BZM>u${Q z;v4)!vc8qYK!8&vD+`B}!*$C-i=$;NZF#~=STkLeW1$gI#3UsJlU_4C9WyDiOdKW? zN4DtEGHa9)8P%&uFNtRB+;tNpA`xBKteq2~7)6aO;+t6UojAv7mjAPu6P;dECtc1k z#yK_bFVBOX^rlz6c~ZtQaokL2zV|3Rl5YY>bHM$yu_^XJbh4DKtYs4#8$k+mv$A=I zK2U(j<tP#ZukxC#!ZtQZ;z}}TBhPtAs>w}u5`qzA>3+PpH@^ApZ>ij1gK(Nt5PGYp zJ}u!baS1UJ@v@gMoXJvO^h08*q;sBI=2S;gRnl3chcv8L5WQMNUmg`FQF>SsX(urb zRSb$~Ws2_Bnuw}UF)JQ>Yw)yK&Na0qo$6GcUgXmkEA&-nYW!1U=7~MRW~O_La#RQ) zg~#%##sLM0g8Dd%;d^K{!vQr8DUyS~(MHFAU^{_!Y9&dt?f<G*M8ISwO$xW!(rpZO zv+Zr&0@JkE!GhH4?cfNft!?d;OR^MK<9>SFT<TJ}EDY-}F}FGyZncIEp>9-d1iC9f zmAXOdE)c(qBx#QKh&r(*h?Gc_4LvbKPI&~Eyp)I_Z-pyl0@+x|sV4pM7iDn5D;b;T zPMQ7HX4Qktpa#n`pB*-z5MFGh7VubrayXzHo-`r<ae`E>s#PPVP6%d2D*{TAl9d!` zi-EO-*jAyFa#N|@@OE2L=2*w4oM}ycds7bv7jYq6+#{aYxQQiss6}luQj@CGgK5rQ zKlGt2DAGACOMBW|#;U-yx>aa`mnKZ2X2Z;k-t?~5*Z=RGBF6|<U*H9gKzPXWIond# zH~DujeBo=%(g@fC=j@Gy<sLrmNE*{jYQn8iANwp#$VwwTe*UQ1B?_P%=1jm<jjRr+ zw?j4?fb?vpE&{6CHmpq=OFpia;3#nnAeqh-gMlMc2VE)Lrzj3X#T7Q>h|LKoF;`(v zhGC10gbHRim2=glw$YCX5vXq2+1>@S5XIai6p{DaWDWPk&gyG$c{9FN0cX0wVrSvC z+ueJMHyFc+*X8Y1!0#NiVgmb^H`cRfhGo?MM8kpcoyL5a>V%{h{zruazJ2tA^a3`$ zKk1nEIs%NOYBvs<1gdRq>UkTnX8Xx8z8cnE#Q(8wr)40PCunfMy^2nEdZ8lE63N51 zCX<cr%VbAc%A0#O(M@ua8XaBBx;M#>YS?9hDFo<8iYDv6>g|S^_a|q@riaej-Ysd2 zty!V-?*P{aEslN1dN%tyS2o6W{v|MNFYsdY?M6fw_TMDX=lBMGsRMAJpo1TzZ}frx z{Of=J{O`a2{||rxD1ZRCDgV#~1)wSt=PDX?S{>zhHE;uvhc-n(fkvPNO;A$9A_c2v zMquE9_Hh?B)-0riasjeq0-^^gn1UIkO23sY@+Dssf_gItY~yluMsY%%pb0wYFg@rb zu{T7eAcUwOgrz`yTSX+apoB}vgtTA_P5-!rMt2K0q=XT{gii>CSx5^=h=fKmghV(K zr7%R(<RqTZgUc5&L*XInrDkj96yCH55(0yWASPCnZrGQCcc2FX!hP@d7R@pjZLl(8 zL<SxR2K9y~Qc!+Npae!hf#cyuk}-D+mI5j8J?+<Mdv`RL!U+X9fS(A8p(u(1_zzK2 ze}6<j4{$%LvNeq4X(SLp4j4%gsA6a{Qk1tI4g??aF&~;2MzFRY&r(6PMpLQeaxeEF zI#nUVMO;T#LMF6CLE(DE27B%zd&;(KwRbu-RBc@5jo-Lk*XC@(_hm*BOi<Ttu(K{a zab8Q5O>Kxf?j=Q2G+%c3J79Nb+W%Khb46Eng?8cRGWG^N_?8&dqi@%ve%$jjLGxfk zLq4goM-zY!`EZJWBzP71G*yEG5GPvC;VK@mc&Igt8V4Q-bV<1AHp7BatwuL11&kvo zjA~(mej|D<2xKtFYs}b;<WeOkq-2v*RAtC>%>_))g%C(Mj?>k9yN7#Om6Xxdh30sU zVzwk>wvMthJJHBQ+O%HL2QF_0UvubncNjA4CRgtUZzpqhbpen7<`)B27#J8&=yzy^ zawv2+M-3)4d1o5@bSVZf2Y-i=Q*)7nSt`cya0`Gx5zvYoP;rdsfMjzkwa8+x#XvA7 za=S=!wIzbil3O~)W4vW8KmT@<AC!|smUTXLgU2<E#rA{Nc#SXtOh-6nPf2B`<BiW2 ze730)T*y@hQ<Pzbj$`&Dv4fSfQ&v{8AzhhP(<hc;!b<lDS7~BSez<3AnRfJMCwFph zgN6hK*+vKnM+^2dpYcDVp;$$;i4}znf@zpeQ<(1wD(_HGAdnoJHgOq6VvGk#l1Xa1 zVvE0$7%vub#bO2V@kw>_YAq#edjpy@S(7fOYsvUZiNhtn25gS=AwKz&L`9A50-Le< zbF|5YylJ8*3YA<)e8m?`2*YhvNu0)coXdx1RswxqsddX3hcE~sghM7}GM(E;GIaGt zXLlEJG6rrLXnV3Yg#SjD^we*PqL+B5cY3q{1+WC}DW9bhpIhoF#<2+yx0sEoQJ*#| z80Vk40-)n@YOsZwD@j`}35=e}7PQ80ET=)(QhKI0Ar`87tEZto*`XeqbCok@uG4eD z*`mTkd%lUHCptsEIeb93sItjz>8Oq}I#e}!bw_bKS@)I8$aQjNePv>2V_}wkSTe`M zEPaNg+UXbE=~sp^mpEf+{C1ae<QXU6VCX4u`~+zT(4I`=rA^bN#Y!CYd7oPI9Hq5U zq1GLvR+6n%9+(7jDj7E^l`JmFpfQ<pJXVax$U!%Slc$NAJNZ-4h(al}OUBkqM3ktN z%BV~wsYCau<o{T&D{2t(dVH5!mC2`kn_8nb3Xh;Vk834gV|kCKntjw+ow>DVDdVck zQz!P8Cj{mv6o`I0V;P82cZfx$eVH1ofu#nAtng`yCrc^~_YayNrV^KU{qsMtXkut8 zNwgSJEH-(WWO;b<K&{4^DU&yD;jKGXYof`5$5?tW$ZN5bnl|`+RdQy@^?KD9UWuxx z*tnwg%C%i9sro9fLj<o2W0jf;ZUg&#p1MusrlVomb<kN~rW&N~#ujXHGWqd+ex_Fe z#&&uFPX)<Fk5QM|<FO2Oi4PVj@5fjW5Uj(hvc{USkGrxSkQ@%ctfVC!&w66fN{ebr zt*4eAmH#&wnRzTFCxS3pf-^ZFp@)4oRhou#nlm>-BxG|OI;e!Ib08X`P{yzNdX!!Z zyw3!-VJo&UT83A7oIr7AW~H`k8$|~@A-xlw(pi?nb5334eJYbzuqu%3L6C2Ekb|46 z_cW!DqId9jrA}b7k~=EL%D%gSm<3=_tRex4*GP2~i;!e1oeQ7|RIRXOc_J4#Ewin^ z$e<0HV@BI!x2Cjmb~wu@yR*BTwR>~y>Y7rwb6A_TmFm0n8g#+i!K$;bm0G;w6;@MM zUdfw=Wp#B0OK#9h73UVW>Xv=l*KU0Xv1Vta*$HS`(7oS#ezuB`bElAu5;VT*XpD;h z2mjy<TKc|$6uD1qDjMbw9FQFOGg=$qn2yvL{b?(!wWj0&x@=Q<1^OPlIAbf-nIs5P z|FL5i6rn#hp%iMafBI`A^o&v~jjg#ZLb<yl%E2Kl$b+nH{MxUV<3drFsVR(x$Qf<~ z>%tc!a~UIp30p<1^mW*0!(?YXYAF~0NCqv_JOT!n@KiJ4DOl>aV1~<Rks`9HfhjHE z4pQ8{QB2FiVH~q?02YPC_UkpD#!+6ZT4ocV=HaFxN4hCRA8I_O2<*n88Lp!#$5~;T zLq=q(m!Yg@E<@!LJ=n*(tHC~J$OJ*igFMbpH-;umW-_Y6*W`{(L^0#`ygE7|mj4W$ zr3$3j=deTSA3B`3c*Q&}L&|M;7=T-7>1UUPyO5yKkfpI$5un5f&<aj`%e&#e6<r%k z^A9$FfcV+0WePT(;Zeh^rY3od3>3goaK?Q>z#wRHBgn=v6`FW}eWNGGbIhmK?6l43 zj1(M=+)Sv2Y9dYoqsUgg=Zw@zJ(a~<)R?-+J;=?=3(sonhFM3?T=%wZWsmlCXK|&f zL|UY-N=Dop7#ABogBG|5O}K@Xmmq7tjt0vHFah+3(aCDdbq&A&unZuUKU+gu_Y0XQ zkXkc<E1oM-mic0D`alUPrw3fLDpw#i>07H*haV(dI*G2&sIGgAb4>Pw@BdnrOzm7s zP1;E<+VA4jD9p%>%zTe*qf{M_Z}=@&JzrYg6<5TteZX!fs9$N>s(qH7;>UIu%O~c? zM*CJML@cE!U;;<%$`1+Aj&%T=5LtK)#nv5267>%=(9xIMX%@#(1C(+9xnjNIV%K_7 zD@}4?;ESj0nX?AjNZWFxiPJgVw%~%HPzzKQ+}T3CT$XdSqP@YTP2eti+K5V=#mUYp z+<e&-&s9CoqKegTTZiF9z4x`xXvwPm#g=&SUw}5yep}EPd(d@h15x_1t*p4I!MFv$ z1AcUH*lp2wE#tRg9M}M97u71HC9~k29UgTkB*|JLWz3hU*gjmkp#SvJFfEL3EG;z2 zz@%5-LN;VF_p~HrB~rUYK;6yM=&qm*qXJ&w1uo#>Rn%pu;AVTaXv>ulF3D|M&sjZZ z9h1pfw9o(1$zdHvd9}A)02qDiS87y{2Ns?QW>4hn)~+mJmcpJCUE{q$<Bu*I2Uj&w zz>&;RzZADoBAKS8c1dn}<Yu&)?cK}>98*Wjy3#zZ$mmLa>MeE*sGWLTKi%K{J=7R{ zYzb55fIQ{|;ap`7n~JQ+S4nkA<de(`+p#T=FwCQ2Lg#fpooA_M*ZF;fNU?ST7^VDI zOK^UHqSh$BD0+#W??)+&>i`2F1nVp5xpC2tPCt&dm|5I4U;lG)sWnL@UCc;;lHMC* zqTZ5ZV8AEmpym|cl8tNRTCO?@>v!yon%$GM-h4pm<zIemf4u9xzUyBlUJ1S~%15Ku zG__Ja)scM17bD?cBIoq=qgXT+VIeYKZMSM!?P>Snv5F_%IWq+&PpOOpcUi>c%a;<i zM;IUu`9Q4eejDxn=<M(he^9x-oKYR{iouL=H~XI)SDDAm@5wwj?9HtLKWnPHz&^I> zQyw9)yYP%N!9LC3OLm4GkLF0#)I^!_yk7U|oK&g3$R5v*oBHsty`0Ma<`Q1pJ=!1_ zUcEQWk7@ZuGw<PaA~(+SJl?zQH6u^AN*RWN89wuGq5lB_4moiBQ~;5n59pv_NYCz( zj{33j4)kdPns&LRHM5|mza(8rY+B@(*|Tu^@0-`Hp7+ee7|ruNu2ZgzA++$t<?yq9 zyAp5fw+_x5Z}E3e{liIyXx{Ow&DvR+oSho@f{)+j=C)O|71N9OHLQ;?zh5%1GBhuK z0!bLfU8~k3ci_HgcJ$m<Dt|G)`nUlQ{><GYSkT}>gb5WcWZ2N*Lxu1Di88QY0fYz= zDqzUKp#z8zAxM}wfdWN~7BObbsBr@a4jw#!01+aD2$3R4k}Tor#0eCjQKD3_Vx>zL zFJZ<kB}3*+nlx+LOr84XjT||1wASHj$IhKQc>l!m=~LG1pFe@rswG6o&|A2M5Y0`L zXwlt8jq)~n)Yq?HNP!~_j#SC;;Y*1VYhtWv(__eyIZdA2iBl)cm_2Rg%vsdu&!j|? z0u6ffY1FAzuO3}GwCK{FMRoR+*|ufMoFebu)VQ(Y!-fe54*b`6BfWR))}0$SE}=ou z*P{Jn)+`@BV)5MZ%GJA8Iac3LT>};BnWbUEc=2*ni<K%uqX6~Ugl7^YMQ+xd>4OK3 z8*HdyC6rb$>4XzVAOQpqI^ZA!3@VTy0thTJfRumSfoMYxJM_>)fj$&*L=ruesD+9g zfIxx?Hrjv#4?t3oBotOaNhOwUaES*WX8)?`rkr+KqKPJc3Th}Tv^Xj$rIvaMDygVy z!>X*b+NvwCv?I&9KG0e#km%fUPA<Ca!V53Hj021~!UhXYF*qCJO|slByG=9NI&*E$ zJz4XUPe4J-leRlE%Wad%=6uXIP2dc!%}9uYM9sdC%L^~&=0aplLk5BFOSHJ`13T@u zv!jkvxw0}mtEO7x)$`6EV+{4!bFYf{grd(0`<6%|i6Zpl4~Upvx}k;vV?Zed1Wh0z zBoI32V1o!JkN^S)95BF%f8HtaTX4g@M<9R7HTPU}(^Yp}cH4FLU3l4*2pa?taNvQA zCcpp#k75*wq>^k*i6t9$<k3f)g8$@cNS}-xiYO(KVsZ?p%!{%r@v5A|JFl|D1G_EH zN^31o#T--9y3W)qO-dh;6p}U(gY%L`X;u`nIw>o3&_M(B`RAW`9<)&04!yaz-)c@Q zxJue2j#A{JJ~Puz$877<>8ca8RIs}9t`4ol8_!i(&oG;eT94}DJuBqfmDl_7+poX> z02GkG77T0_S`RpQ5Cdx?cwm8gwdr=;coSEAamE!NcOY>imz+a){z;>N1yp3w#TWe@ zsic!qQmF<TUgELGnrtFMC!UCO_~9g%oS5P#qmnXXjW@<JtdFs?j=C?S^ORGRQ$~~J zmf4K?5}6gNnX#i0t&?b>d;b>2PuTc8&9%*DtG=^NYBMzFM2}`{X5fT_G}7V#`^(a) zHEqsnPX_^2YwNPpuIp4c29H%Kl_yqBsa1Q{hAX$#r&mjm8xe+8EF9cTS<6Df37iG3 zX+fw06QGbq4lssp`D1b;Bq2h`)i@NUP=$<>h&CL6fXwBKBb@_D2uwhu6riL91k({r zWI_|wDXeurkq@q7cNFy~r75+$*p#SbrLUoicVh`zS-eEDt8t1<%Q4ekqSmrC38pZG zF%0?`6}`tyk7(ihUK>3DDAIV(jhtCy(To;7Mky_QO&iY3CIz*rQB8|&k<N5PHLCq_ zCsknkpV$I8!1UNk3;&bM)qJ2(pSU4mZgex21PfF_3qFfM9H7<)Cp5SNOh6omTVX3* z`O3$YP?oavheY}?0E=KmBQu0iNIqv0fsL+UrbFG2aPq637zqkOF=E7+q{NCvrHL7X zBFDa>B|M1gieM_4$(&Or<9RVJV04+JV%9w8$w@cSBVQdeGe>y3(Vcdr3>p`8KJ+o~ zFiv|K7^Q}(<y6gTgv?rX@P|nK;lXRFT9qTIVxF_jYCQ&gPbGKNEBxrkfkNP<-3By+ zPg?MT49XzjCRCvX7@!k}n`KKScfwc3RHlq0hzLn=fEco9UoZNINPd~afg!7hG3gNy zal$%=DN{a0asTEsmk6b4KCzlooFd4$v`ucd#Sq?v3pl&zMdba(kAz`bKF{YEdrFUd zcG_7yc_zo9-N{aCU8g;hhR>O)kDugB&Y2bwP=P)NI)zkAsJN6J{qgT>jcgTp1Q=0T zt!Hf&b=xI*WuIR)kfT8G&r1OGQDv<l1r;1=gZ^g92smH?1@OQ>YC2Qc#+F@=lWlEn zdoGFG!T>PT<wh{Dfem<$MkoO4N=WAt9~KixNG;OqkaWa}HH8coiz-&8+Oeuuu}fGL zo|w2wCPakuQeRBo%gBn(bV4t!bhXSp-B~^NVur41g^X|Vsn19C@sBM_4*dR_DJ_=F zepx#tssF^H$i*^NN^KBe8e}C=$*!#^7Ht?tHM>~|9xGWC45cXhwgCtQZgBO|MF?+u zVwu(yaxP`DxFmuC%w1%2GYqaTaVRjB9M^O|G-gg(*W4o^DPl-b4^zwrr3Fj%O1tBo zRev`!FlF_-T@9~zS4Pe-LJGZc@(q3ITABEUd3;~aS!B9gU;E<KQTv3{%dp&6fNDyM zTP18D44Xd#o5~KlW8@rIH8uuM1)}Il;(8|e9{E`Evc0-+M<e*rPm<QdB{e0s7C?Y7 z`~w{#Y;mVa6e3TDT0|0o#sOf6uNh}x13mp$Nq~wY9mAxkJr)v>kA$m9s*OELG~1J! z=>Np4XpCbX6U!liN3!}&d5hxROIRsoPB*>DjCrK5TFI=lFkhQ|)kd>@(Z@7C>bIY2 z`ez{L$0>pqv`cs{)pnxT(8juo!RKiTt&(EE30D@AzG|QYXOiK&&0vC~4P^)z)Hev3 zG_{07fH=G*YKU_P)Dfq+LnM+00^~9RE#jQ#NPr;X4lKu|OD@80!d#yOC07uW-FhhI z6kjKqO2Y2SHK}N9D08!9S}fjI!HQ+&MO)f4%OhI3okndZ{n|%IRMGXg=5UL9zy9>= zf9o=5LSoI%2Q^E(!NMJ|G1Sk0cI;zkWp7(a*rJvtQrtAkpU%D{-~$Jx2|{98YX4PB zaD+2}CiL;}iU&R+6Bm5p3nCG5EC8nt$X5ki1S1&@7sn$v*sPaZ>y$6Eh|rxK%%v&w zt4vjjrE>C<zoeG#63?quclNWD2k!gQ?2JsunbOxv`#Cv1_Df^)Uf=9rfF|PHV-ntg z3o9y+B@*mbf;XTU+~BiCHtm$vm1W_^@3(W*KXubE-db>=(vnhx*0Qt#P{2yVryr&$ zW`9iYArVgOHm5D(r3Y;6>KhrCbR`F3!dT}zrDCQdA~I<5wWyM+ufeV<`WT!$y)c=x zW%IdaLk>0ZBf$u_En5tyGdkSsK-w$1*khXYakJlpGpmy`2-Lc*<GMWC4*&i+73TXh z=YtgoJG&$@paWXFeaoo**sQqgK7r#fXL*(nOE?i@IA}1j_FKXgily{Zzk8^hG{7az zp}*e>uE+x&f!QG*;y;>Lt{=-h&BL`JOCqMAt^>>+-T4Y)^PNLFJt<Q*a8j9O13Kk_ z8KJ9$-IKiy^gut%J>A<q5p1(@<F867w-X#b!4jT=;yOf1B(Lb7{{bM!8Z_yPFiJw8 z`KU0r>%oo+5YURWf@2Wi+81lN7S$R6I|!jCRKFE##lm|Be?W%~Fo0}nJQ}mVRx^oL z8@U}bxuX)2qzW=4(ls+2gCj#Sst_CIOF)~`k_HT(o#VMVq{G&$K>zc~!we+4KK#R@ zV-!AAvwQ-#sAHe0d$YZ$I^jb>bYnzyyN*%GGewfbu@jF4gFab_Bpj@$T)C))!H=8p zH_n0}0oky;0l!JhJJeDw1MmQIU@2G>Ji?2}z^fc$Ff|pyMOEtnUHqjQ$v<Qnrh_r6 zU|g7nxizAIu49a*&%>BtYsQ*uL+!F6?s`CKtTJYcnrjrRpwq@}oVE>=6F&?}5Zps> z8$n6IGQR-6IAcfWxEd8yi$jXXc8f%@^D}#VBnNx2^oX!7n6Q5IN9^0EnIM+`07Zio zElCq4N(&s68h{eh5Q>z@SDed=s~j?*LX4OIeYwJ(nh{sC5&u{lCRqc<B0#2OaxRE* zrX*UTm;=4su_j{cooEamw~)g!sX8=ygq`e*v05M4+r#uyGoma_aRf)v<h?=Ur$RJD zL{yG|>Z*1$zWXUKuIZZZXuf+KGzd$(9MreV>O`^}$WAiIgKQQeEGdOUDFJAM4B<4p zq_~NU&WQ7ef2e^1xW!cKocjZ&{39688cAAPnC4Q<0o*ksGeF3M$w*{FEpfxE$~iF6 zs++_~l_4*sET^74Cvr?ppft@u^iQbkJ)~@({N&8n<RV3+pE_GX<Vz^Au*$2%ig<Gs z-jqIyqCQ<|n15_E;*>i`6UFdT$dgj71E_$91U%}5xc})~(NJrl2(TAaqrZ(5F3>41 z<03htBFSJuxd0S0wIM*-dCVvgo5+;R?3zjHkk3G%Pt~(e)}z1!ofK$0FES#>G7?ZN z-O>SFO{p_brPN7v6r@4A8robzN2E&akkCHE%B-|dNGc%rU>geCH-7WPfjrB(qaaDU zJMpWQQzD!JP=*X~QR%EpL-n*-{D()#xCNNeor1hp3rvvIv6$#TAQ2(}Bu1u^nCOb8 zU&9@kjL8LrPt$WiCw)>V^(!fzQVU$4^Xku~;nFR|(xWU;5`42m^eZ!=8mAPj!8$$a zup&H5C<H^534POf+sb?_G_?WC_y7vFv#_`O#Q%Z}!h-}QQHmB215^rO$TdK}L=CkT z9oH6<2qH+472(VJ0|Ah@AxaIZmLMj>L;@d`*3HYcU2Br2u$Tn{HtV{sjv>9$+pc4a zLkN@~2|S+8#KtOx)ho5tpR84h)hk%Fz;pB`sWCy=l%GMOvj#ORM}*J_U8FXp&<dr& z=#xIR(a^VPyRjt8?E}%YB)A*$us?OnY#D$X=oS?<*A^>Rpq-^!>J|^csTtjf8kLcc z3mC!7(eRwLAhK7J6vKRNIi~PDB&)8-TtoMKPn=5&>F6$H123GEK%L~w0}UfFf>@tK z42e}uTkTQ;B}BnU%C$vMj)l#2T+q0vpZ_x*)(1VXuk#xJVXTzBP?nvne6yrWvJYy- z(+oov?;EYP41ose)`fI{1Bd`@FtMTSwDn^`(tRa~aE5xh7hD9ckH|t^{LXo$S0A~& zs&%d?U@9fq*8+UZWmK}mCDp15+ngiYvXvjY&`h0dSTK53x7D(WeO@nZUUO{CwS7&# z_1F{~EZP*@gGxTaU8rPzQySdL-o!z$tUk8u(Co9;P;3E$D>#E|%Rohd0}zJie67;W z-^QUW{q0{BsvJYWoQ%{dj)0Mll)R@U9Ub)nsioZ^QcRY^+9CB<nZt@BMHMzo(y3(9 z2Tav(>N(96C;W6(=9OL(K4G`TL;v#v(*w0$<*>TG&0cqG!~%oRd3-m--OV_isFsC~ zu(ZC&9nP6WOKjDfoAt16T}}(>0wwfcCyo~<3|&z}S6j?T8eKJiv7zDWMWHenU@XZ8 z4l*P$Ml*!Dn0u9~aH6iQxo7+s2GpjSoW}Y*+l5VD<y~Hk&0`dn-aPiByj{xv(o6-# z-ZE{_t(!{k{a%xeL9(kvdV?@b<VW<iQyvuJVj<!QQp*lAxXcZ)5?!qnfJiA8U2}M1 zQ%;=s`v-C0T<xSk*0oVB6rC>QzaC>QTid+zOp2^!A~f#ZV7p-KB3L+PQk^T?w=mwb zjncIJW7q3rXMW~qW@d8RTmKj~-V_8`VHMnB<r;-b6&Q>`hjQfTD>QtAk3<v8m>rgx zeKg~=*=OP8KV3+|aeyS0#Z$iL*%I1Oo+Wh92U5VPN0p%&;z$sf5gG|5VM4A;B}p*e zRLy&?A-gwzO-9=ZG?xs$X4Hy-1zTf-!!QXG5B^}UT3Cja=DdYwXEte#rDnSTEJ8*% zGljz?J**ad!30Cx8N|o(r6_X-&IPJubq2T)J<d_g+`KzN`n82Z-DgEbRHi1{DEx;v z5MW)>mke0iT?{!KndOD%QK}8&hi)ca>pYf}iZo<C-I;?(T);OTW@7Fp2sB$dM&6ZK zW|h8cye>fz9#dZptpDfOs;wfVz`e8lX*WFsUz~P6IITe&^h%d~n@n2YJS|RxwA@hy z0a7X@x3my$k;SJb<<IuCheH8%ow48Q7uWqrdDYR=!PJrjz}LZ*D#*2#+g%F2otYE8 zwQjeW6d4W%>9{^-g<Xyi1}nSHYvfkx<SlM4^3~vmj$qAZ!Y&JvE!-$NS@9*C^5`{4 z-p8KaP)hE%2jaeK&E&d!XHx7|on0*xa4pXcZI{w#_<pGtdZGDKS}Z=`cpaVn^Pz(= zrq!|K%){k~UXO`pqJLFmnv+b!CX3!aSkwdQkXF@}E^gyK?&Qw!l@`+w9^{uUQ|*=R z2PN49Gg+}iS^vd;mB->rIdu;o_UV5F$c@rI2>PtbMo3OBLT^<q7^>&_W-<BxadGhn zcKC;Xwuq!{*O0g&lTdB_W9<fZ;9(4F+$G}zM8k`r5{%}vVPor2nM#_3vf_iv;5OUl zCh7ac&k@$}Fnu38rshEE+Yg6n?X5FyrfD0#;j47hcvErctGCE<Y}r2N$Bl8hNgYSK zR**u814$5r8zs#}>H=tm`xSDcb!tl=A&CG2T#~WvB<QT}MPH=lTCTMsk=A9B?Iell zPo?Nz16Z_n#;@b;-Zoe`EaohV>)~$h;(l`kW%Im!a|;hXIrrPAe2Y4lY3^mW+XUYe zZ)B}}Wd97!P%WsWP29m>$vz*P+@ZGY5gosivWNn}0oNLrOs6GGKljLyMRPEL(k9@I zbl0p#Xo4X*QpX7)S^}#rq6qd>+g3*0e#s?c<H_uuTDPKGm+%QcnO$eL5PoxKyJK?W zFFU@JVTa+qE^}lzQ#-%&>mZdpXH!Ooc8fNT8th8nq*FqtWFAEH4}A&BU3B-wam<|- z%_cw9Du7THp>k1o5(;vkFOkYAH5g(%3D_l7!@|@KrW{2sSyL_tc4#W+ye=rR32sSW z_T4CI&jvsE?MnD=%5`1uxii0b3x{~LXG*i@>od1zjSuW(m+mxGQ%L;gumcZ1|JMd1 z-~X<3Y)P&@1-cJl5f-=;>Y+A}wIr!hjF6+ZGz2gJWT^C@pPbRfXUlJw%He}fH+n0? z>ZT<wrmuH{`R`H>!vPn-TrOi*2fbe&Rf1=0Q@yHNk8lAK`;!rFvM+lyfB61Nd$qs# z3O{q<EB3dCd%+%TkN<c#CR{yl(|S}^I9=Hr#K9b_)8O=#mLG4=Qgj{i_IJiR4LbV0 zqhC*W&dWdlb&2B1Cn1Tb0RhlB)9xG_1%24H)P+u+lk?FZP01l6K!6A{h76fAX%41Y z(`MnqHxA#(kuzuFoH`ThV6<cB&K*1+J@VnxXC%pzB>x0Tsd5lYLM{!#j45-bA^$`+ zZ{AF#bLY-QK7RrYDs(8(qKOvq)QNK`&89M45^Bj(CDlJxO_mJF=c7lC8ZBbPNO4X? zISv^vT%$J4nYLucj0qFQi<d5TwP>+YB?@1@P@p&o++@j;BuI)7AtGck5Fb8x@W64y zMvWRXX2fXGVg(8mCrpqa5dwq<4jV9Fs4zi71PBWj2$=KF-M!kjZ{yCbdpGaizJCJ` zF1)rsbN-GaPp*79^XAU|<+CS!`t*GM{{4HdeLMH=$lv`l*MY!m2oWSqsDL5E1`ZxP zga~co1d0?ZG{?AH*#?gOJbVBF#9~4aQ3Mi65Vk}UO$7GWUwl<jg%wt4VgFYbUdScT z7;PbR5Lyj6R2D^Hg{9F(9etz~Rwn(?hgDPsGDwV2z2p>4h`_XzO-UtHl#f3G#UoET zGG!x8G)5((j4-Bj)rup9gvVA~eMO>06h-vV8y~K9kXvxcRo7j4MHr!9e+A~mV1*f$ z*nj~-7MWy~U8dP)ot^NRXr!5zK?SO@_P}ccwD1pc-XWT(qKh)>-95z(7b$P~<b%&W z=lpYyrkiT|4?O+!^Bbl9+(W57wAF@>KKe-7>OJ6z(}4jCIA9)n>aph@2qA=E!hD_G zhu;j9-QeGU0WOx9fk_}p7=unY2t{8JQfMJvat&0FK?y1JVH;XXH2)S@C2qu(lqx>y zqKhcO*b<V45MrcLL@p(yz4zifB)vDudnAo40n8*yPOhlclpk?)haFa4iKSU*dAo*} z1ih6ZT^5pQ=9z%0xu#)<DJDdKjX@?EWtL&4*$OFmrsrs-ZEzZ(t-V&j3FiFsj;lNK z+_TTXLHe_#nDWz&HP(=W^wH#q^AA4wfSMbqpgs+cKIdGG={fMILn);~_vVi~|CED) z0S?qE!L94H=fSQd%ts#z!N!o^e#QbQV6p`sn4p3UN;|EDc-eKWTm*4=kXmYe2(GwR zYLu|K=cc<ZyG+J72$J#kJMX@qBO)Z|`*tqxzf)lzh*bm^eE%@Q3Y#dFSPpB+5aSXf zbOu3jg^6)qdi50rnriy}F=B6$+}~t$)~#6zEPDpp%N=ZxL29eD=D-36U{FrZq=Fs3 z_~Y+ZT%(QR1CKx9?DNbx?SKQ$`{1-Q$v6I-Gir1F=!4H}-)!R;0jvi+{sF3d^y7Sp z8k;sGZ~(ML;5_MJTL(b!HebmtSS`rUuxwB)$mDH6%IaH!p7kIIMPYCiDqM!LRS<4< zt6L0l+=w7|B95deB$Zp;<){KMchRVHHo{R&MrTAK39(;D`eEu+x4Oz{Wpc2qQdq{4 zrH62-OA`arT*P!2y=Y8$X<AT%3{wQeC}w1jiOlj)X8)&^MNfL9p`P^sB>@O%?*Il^ z#%vVm$3Ft{kHj$t`6iVQP4R;n^JvF980pAHK4TyJu*cU*<+a)%P*e4oL_B~Ik50ye z66LUmI-*uc+=%TT*f_ugYjvJKQP6_%!C+@nU?;oPfIr4U7J)|CECreHgb<?83Ndso zxFAk(GL+%B9ukqqjVp4J<BASf#KRY1?uRaE3A{L$#3Ul|o8Md_6H~{-b)_qcTuIo% zNK}!rOypq@Lra%*r#s$t(RX0%%kYS|rX?Kacp?kX8kI+<l-((gd-4Dsug97QXb%Af zXvFtUY0-=JENB?T<RQ;dk86NqAM_Y0Jw#ekaR02M9{J$f0rOFt1SSwu`|#u^YYGf* zT&<KFB@R0NA&LVafL0NlzyxDfL0-Y_S97z|WoF>P{@~zPdh6w~ez_oM2{VO*vsMc! zmN*!;L55m_2s{}kO&q4EawEBB50{j=9|8<2FnO0a>uT3-p01pjV{41j86_!og`MrJ zq7}<B&nzN@Vj0Tk7lFsm;r+8PAafHz9|P6pT_!UL&6D&(z|iWUrUGh%=mI24QJw8H zwW{TfMmI_+O-^DSA~oqq_py(0tRo!%PzOA`=C!BcgB|(chdh8Gk9F8~9mO5T)qI=U zu`Qwiv~qw1i>j-)!7YRMvD;IlDpe8k4gU##`x{n+N39iJsD;RUp)$QSR)~bFA`Gj; z4b6qF9bU7EDbZ$)?&{ypc@wYO)azcKsMbFG)m(xdY{MM(FmHtwcN2RHKE2q5j6IfP zWF(9k6O%^9l&n7|tJ7wnr>8xEpaUGJ<IEo50Es>#XOCJfjceRmjP|3W9}Ou<X-f~> z)&o029x{>3;f;7agB#?y#*cw94}AFJX*32;A7&*~^h^LXZIfkE^R(0ra<^Fi$(!DM z>9?zv*Sy3m9EPyv)ebGLagK}ce9t<$`=*Pn`h_c8H|J*o)3tO#1T<9mEEUu>@tg-v z@H)Lh#o0Mno)MF<TXwfteL7Zn{r~h>hut(#lF7*il*z2~@B|vsysS?SrP%@uAcu;A zug0?8sQCiPoviKH$FsfdI<UbHZHNQd+88#mv4M?nkmJaa%m+Dc>*V98%GTVe4R``E zD+fG4g1Fj12i%5TrP575{1G!`Mz%L19O#$i&FXorWjGCKYg=GN3%H(HLmQ&izIev( z>h^4CApW_o@sevy{2Y}52TZ?CWE~U@reMLk6P{$b;+7`ep|;$UcNZH|nI4-a;&FJg z$V;9<-B{wzcqTN{Q+1061%=r>O4>4?In9;xC_=i{YnloNCdM(_lH#@<?U08&=)sMn zBb^)DF#6J!PLEIGVjbqt2LCy5;pBS&x00#_Pa3S8?X~6VJ>RB}eT3D)?v|UE9$wa& z0T;MoR*TJx&DK}r%*?Uc`y%+BCN=k+=lu3Cn@lvc!3*za&E+*oQ%QKDuX*6CsI$?q zi#R+fe%J_yHFuS+u!Sy6rVMio<dQ`r@(L=M8yr-#CO-9O_ypRPFQ5Q3c!xh|AM07; z-lDaxxpH!>NsyX!AM5bBZ5LUOdhjFp%3uC)lV4n1&;uF<s0TNI(GEk!ocGRo2Y8l1 z0PWdog6!comudNB4(5{FX;*uJ3{=8kzCDE#BAnbYwBEWi6GYC;`+VtZBEI*XNIah9 z1fIgJ#Nz#%;pG)vz5kT~!ieJyAfriM>@ZkiQ5=Lt*u`a>#aP(y?8U|iMr3tb>4jJu zk=SOj9%;Z#9bu1aw3-L>l<j4o_R(MsBFfF}lyChWkB!titV3<#mN?i0rx4+$phG^a z128z5I0V4-+16}W$EwsAc%Z`xNS7<E4F+u4*a3^#5eroP2brB)5vUvd1y2;rU+1Nl zdT9%s<zF-HUs;)zouNno3gCh96*f7bzx^A5?coEm)c_)x!#&&-RS~4oPVLZB271Yt za9{_19_V#U@rWE_fSU4*7(&6(XUNfeG*pXej{$%{)6ib-nIcBr*hTrCM*&}tJp&M? zls>>iZz0gswEvW*bVECQ5)%f%0h9wjj1ndNgG;RzsZb#aNY?_`3M`FZw~Zayd0{R= zRa7|!`=J}Nlu(*Dh~TIYSGC#wbqKeF6}{CPG}T#sP0qRa9lrtIAG+f^E*u03;vl+C zqnXH~y^{rE5rk<GTj&l!EEZje30_1Z2#OxFAORA1m?f@}oS0zBz>z{tPt33&Yv56< zjbb02;zpiQDi)Fso`X1~!XgQu58{^ah14Xe1J>w+E#6}Ol*2Y~11~nAIGjT{B#?6z zBLiiCm4zQ_Xd$<`O?+fmE!{`m3`_cfp;VO_-&mD43e#RlNZeV-+<BF}EzaH5TYTx= zIo?nm+W+Al&f`h&5ImY?JO<)e(qlco&J<CR-c{aMEn<XG+CNrIm~7mIO-QC`+8C8l zLJAZ^h8PZrTI!Wr%cz_MQP1mPkDy>ADc&AON~X~4UJddOB9TKo%)>l@!#v1?H*DrS zJi|8F!>U+^cI3}FOkDu5W=-aUIV8{w+F)|PN(CGMt%RR?1f??)rBd0Fu<XYTs9!aL z7uz|@$894Db)(#MRU0bP8@`u_$RWAhBLIe_Sk7aM<l%O5XTNo)fvF`SrlX_9j+ICp zS;*z2Nf=uc#9iVgrgdDj_$7yppkO*AW+BvOodBw-VD(fas~JEAK&EWYW`P>$atxAz z%KxH1Tn9ODLy!HS(IH<t<WB-=M~;<)IAB9-vZeuu13VDYfi8zT=z};wz-?lo_!-qu zc3Caml71-Vn1v95oKd<t3z{V-giIy<T}Ye38^*aI2I3u8b|rQGpLOQYIu77>GHG|J zCFDh(6fGEo5msR-qV3qudSV=fbx~e=-h_PMnT*kf8BfT3nq{3{CTiB5<jH>W${d*n zP`2P}96$tU!}o}2p6cmw;9zR`mO2nwKLF4qQPMl)m`<`*hHfZ__M$lG1J30hI_Lv5 zIKXWxquNZ+Zn9|HkX^VXCEBH3aVBILLS_8PA653KkJ6pIi6i68(2z>pe92dJ=KtGu ziUf8(X|C$3Nf?X-PGEU5OywEYK8|BrtS5U~T0nLlUVv%vILMg(<r#UJ$T&s`s_7e< z8h<hr%gt$N8GtSP13E<JWRk1Tc;rP<$}CEUrrg6fR0BW2!#PODEDndFGAe5d05rUV zIao)e{(~+QKu|5fd4S!D?#e9vO4%Xhr-~Uhnj2MBRW?H98Md3d%^lsb1wy#0d+nce zPG=1rDUzlmNGR#9nryH3>d5};qfuU@T`4^st6jP$V}0p9W!QYONhLByL!RD2Y2xbf zXNpnes<|Kn96%>%WVtHs&z$S{_}0AA;w-v@yYj<I&Z3lAl5hBfy|$(RRR4l0L;^O1 zD>}>=?)B6n7=Xa$rg|9c1tqKo;gSapCofSI2}vwgnd)*fr<*ya#$q5GmgC3X+ga7> zouMo}nryBb%v$>Dc#<c}R;kOrEIozemd1s~<t4M)tfuwTK>}uA5>%X+OzLS?M4s5o zctFgARtrYd01yJqEp6;(lyU4S{^U<RP(#(81EYvTur(nmuqGcF8?d1RZPe~Pj7=R3 zfZAdzGq%T3$;aDnm$(Th7>-O+M(q2QD#flDS6OA>wikp&r^nvgxMakUo`}lYYBeQp z>xifNuIxSb-+7jWJP|9*YU$=J)?6%WvpVahDM+-E-kDmfVX6$uo&W9}z23}Rq(t=r z%++oLi)f$98mMTBJ%mH<#;Yj_$JUAiG#tR4nm_=606LHYF+hVhkgcSU3ZH@vc&vc{ z2y6u1%C>C)i)L4+POpA6ti!Tjjbh{7<|y3p=)1WY#<6NvLg)CNXaAiqt%|J5qU;n? zaTP}?{Nh2vXz@KlZp+4#<=rp-YGB62MVmpQ|K98*QX(3Kj2aa%%B(48v}tE4u=T7O zY3Y$C$XMCRZXZWV({7Xn%Pa2k1BG&Ma1@6&n1hBwgDtS8u$cooi0imc;XV8V9uxqI zhF_MkjjkY7+_<P0irP~0z{9THs9F{L#ott-sz83D3$ZE;ZT~DeZY7aAvHx+g!f0{f zVsS6~vdZo<?2xDbWrVB>tNl){vGyafQdos`Aee@!L2ej*PF5Q?hUuB$nzjJTa8@UN z)@cweof?218?PUm^B>dho@z=z)I&5B^6oCm)cu1tpu#P<g98LW6#RoYa9_+3=mdj@ zCTtIGYTLGX@+Zqp*=<l$rQZiJ<y83+sk)tc?I?QLMVMd<EXVS^acsvDY5CR}E`Mb( z^YSnEGD(wk7dtWig7KDA90tbh<~j2jcbvyTD>Z}6fD9DRPR5AEu^e+Eim90D+EMmw zj{zX9&Pec5A1DRam>}N+?&9P*9CC1=L$E1>HaLSh^#4Hs2te<yunU{waWGH?oDH@W zbSDobuV7F@zi0<FEC|hLFFB<|<1II)Vdoh!yn(MQrv)t!=|>moEgR`bqx4}T_AVQ? z{1SGsN?iTE*Gp&7;#96(a*;r)q2@-je1>2db()#FamhSn>6+N-de#a$RG^@Z0Yrc< z!0tK2b_YXhjlI@6L^U-`wblv8RRdeF4O<4_!8??Lag?h+^prMKz!lm`!CqHydRcwE zb#UU%^@?gjp4qdcnc&QyMH|yAuWC5Ta-0FSM+<gi&mkA1cY3S$dZ)K}JN7Xna~RVl zWmop@zy;=Jwg;YJUv~CiCgikUujvt{0dKRZvH#vg{$~WZSgS$6ow@@h$99D01|Z{D zKWIumNcE*uHE_HGIz;lmLPOJ_12(8IYLTlyu){u^z!iR778>j)`=+PDwXr-jcwM7i z=crU}w?(I_dSPr5i?{ejcKx0wNW1ruBYBcH*khYTOaJX!EVDoUBR;+7vU=cVKdWGP z_GgcrfTNxPo35`U=6l3xYD1Lv6aWX@=?Y7Do3qwz(^zd|I5pIRK6DK+wu;WUgEnA; zGu%Rmv$@iOhd*dR+M>0#X_-)RSq_Kt!V*hdf7ciq=W%YYn&mZ{^>}lBmBz-<8|q(R z7kR8I`KUMch=jW2zE>9Euf*i<mryy)j{gZXpJA4(an4q=PG9q2etBlCDV~^i9VfVB z4nRf*x|<vOZBV!>TKMf&Lpj`oI+*J{EHa5lG9L^2b?||qr>JhWt#c>zQKH`{)A(G| zH4r-sdExCUQ_FViwU25DIEEvu|Lv<rHhkHeU^g+TC;6#I+OVejyr%_tH==!WQJ0=E z7-4zni5{CsD}aaY8<W~$a+b=i95^#D+DMcT^wfhNd&eU?oUfK3muNK9c`1d8tMI8i zNOC_zxMbEIm8ETYAi5TEfP3Ju`TeFS_b>>Vva)3Ff?#*FP;5n`mq5Pz<s#0eKPSM` zdtm1sze9c0OMR$Ac8JKOWIwsUGyn6<UQ6Z@Bs3@dP3LUGcX^yR<h4q?%Tzpzv2JM{ z03KwA40^oBC%Z)nvOUy8HI%$=XH;^SGk9#m_JChnH{;F6_zpMpQi|aiT6f!(s=BW` zkFpRK-FMP&^zAVHw*YRv*}Fs#`P73x)z>d%$G1yoK7H4>eLrGd9Q@`Q<iaE5t$*4j zD$i)E%<9qcwu08GEjTMBLe7}@+|zwJ>#3$}EuHTcQ|sxgs8R-4YPKPI;loF7g4->{ z?ani0b=xg4J^s+|B|#RGyJs}Tu$RCGIn&p>Gu86wvw!=$|NB2o=|}eIqrT?J?0r{x zerHS=aV`J@#1er?kRT~ig#QQ;Aq#;t^uYrn4jeaZ*r;)FMvNFOTC7Nc0>z0FBuIn^ z0m4HE4jVFHs8B(Iga{56EI8nx)jxOsc=q)96KGJOLx~nOdK76=rAhDkGj|VaRH;*` zR<(NdUcY|o)Y+?7t=>O%Sjm<(dlqflss8S{`zOvrftn5?M36ASC58+eICua7A_Pej zCQg7{!I5K(88a?cyde<>L>~=-EKEq`V3H&PIX7wI1hf+<qoG7GT_sADDppu)>GHaZ z7cXIG&!#<Q3>n>Lc&G9G+xHsbYuXeyejIt5H_Mqfcivo1bm`NnSFipY`|{-5j}He9 zoVRY=xM|n+0vml7E&r^os5Why^ytt|ns6Ry@UlW7lpjW%Xz`*N7Tbs;k3u@Z1d>il zX{8KWs$c?{B6y%C13b{?pLd#4i^C2*{1C(t$#P0W5cA20tAF?bOP{eyd=W+u(Rs^+ z0p^0ht_do@Krg;J@XI6;2rCSQ6b@@aqs0QW0kX&-qO39@5;~{|Bs8<nv-wDS?=;m~ za}7PK+--FEBkyWoW5j?Lt<dlSw$n`@I!@772&jquJOBeyZiD^Irc)LV}=_qdD? ziupXVk0AW?V+aTz`h)C-8!%cdqXIt)X*`{WQ&VlU^-p@}p-3;GcMQE_=%I%y{S8&5 zC<rJZY7%-6RS?wBQ9!CRQA0<hib@j%K?D^95d}qa`Mx`IXU-pRX3n1H?7g0~*AJ8T z&zB-8ESkvxzQfInhDS!F=e}|Ay5TIx;iG6J|LE&l${l(fzN~Q0<!{8x`xsU%0fa!O zT8s$&T3j7@4i?D7ab=ru%nl1DoUUjIxR0ugKYTa-OtKZKXrT1O-!3D{C!b{+Gc12# ztu`x|t);W0XgeAIzU!Cw+N&;An-wVc)YLhUK3hi=Lm1m*V~f(9XTP;(zfw=oSzKbm z5)Zj(pj-u%gzXv6<^&d_8?yaKOD})~&O4Ge?uffvvU#WSO7MfS9J0C4HJ64F;piyg zJ6jdeH%IQ@LMapHVd1@2Bf=$z0Ish>U8O}rpl!`vT6(F&<8mXkvu(;q{<hWG=hm04 z6E44;uqI8>94FR}o(g>H&8qzMU(bPH@hX|l#koeG<5GH!KSIHF+D!Qrk>%#UB5~_d zx<6eVDJGW95(Q3-Z>o_2WU3UD`AFQjYC+}B;ajg;e-CT!wZ=Z=4Ewtv9J5z`_ZsW_ zh>%<eYuz^J$?jr{IqMykD>yMnthM-1Lzs%kSXbedF}V@eYo1rkRW%>KdFy>UJmLM0 z>ZRE2nz>6)mpgCYcz!GY`V?)MRUB_P8_={iyOM8be=oN<kdd62h)eUp$BhnaU4393 zu#06-VX)L|<`7P@HR5Vz0Be+UvK+D|igM*Pn8fHd&-+~yb1HY9|DJtoydMPbvd{Le zxc&6Ukef^7N;_9&6+ec-W8t@ZL9?`me3F%?JN>utQGbe(;p3f~pRDfFHbxBOy<5D$ zg+REUil6)aX6hzc*L97#^IWpBvH{57sZ#DLEkj+xPvFTrh;AO)MifWB{{fp|BH2^o zBm*9FEgW}o#TmDTUzKz+H*opE(jv%_hmR=Nz@l&a>hHwp^@zR!4jM#B&=B0`^2c(L z?4q`taXz}E>@BbL+p9PAgWJgc^DYL;cblxYD(|1%95DUwU*6?jDBIt0|C(#dcGlbW z^ZicwT{37ndvL)#hng{Mv^(NT!NJrmB~x^Es2rK`yJv#1+QXh{C<v-W(sDUtam^?% zQB-YB^Q2`ozPF9?^$4MZLj%5i^-3d--1PsnUi5B~IN~Z#eCAX%OvE-X6uueE<LHDM zxJ^2Ek>j$${v}#<*|canac$x(ehbNsH5SY2*DU2dc%F2IF^kQwY#rV|9AY^s`uBmL zCd_1nn;01>E+D-nMNug%oCL7p<+^(dug?r~Chiea^xw6xTsdt|@!GkLhDY@`;?@8a zXi#>=)q#(EP7>6OayFjev1Ha<57b}o1?Y#d^TVwrAO3I@_YXe$)BVM3=%nJE<(Sps zabR<T`sOj*ysN0<Q+QG^8|VEJv*Dx+BD{O^@F>6Ku10h1iW&vC=bD#KO)M+7S{Mtx zLNq-Y5W%f~4vj@PFW$vHJPtQke@35Sizy4LZ?E<W&97lVj_&0RTe;-igjUgzX&5SV zKpyWb?`MnQ@`s)ue~y{Wq`Ny6@!hBhqaJn8K1fyj<G#i%c$_P!(F~UlxcE=)4(4ZB z%Po3aXb{xZvD7=cZSkE{kh0{W?$xn&<FK?~^9yo(V`9;XT)T-E0z69Bes=zBmUAI7 zc{0u_bX+n-urd+>gcdbMO>j&2?w@yd{8Hrx3IQm)i%-P@*%)wK=s}dJ+u3dB-pBsu zV_$688}#wKu;6Bk|0^;4JUcg&U;kZj*~LdGl5)gZPb1LMmKkg~*WnDqG*RONJN0TX zxeg{Y=Bpwa#YnjOoA5bhn^~S-)@OU+_vl{oS~=T|RlaG`q?<?H)wH4+C>8JcR_gAd zr)c$KoOy+k?32x^&kIMxk<}qLdOkh<_M5Hg`p1y}g#P$DmQGbZ5T1Il|7p$zAvZ?J z3iXz)*D9Grr2Xo?NL22aNOKJyFIJ^&qVx>$iZM==*8v;maH6t8bTql>XZr&d-GxT{ z!=KZ8&bp@(?wmr0QsOWpoZx%PlZ*`v<0eFH_41zY6!WZ9W}|YQ@4nJm7|6+@W(Dzn z>KpZ%Kl&?8dn`ENT*+#7<K=#_j4nA{YXjG8UYoyPWI|nP+WxKa661P!2bp#2?*4iG zi4ykOL7NsOfRc!KzI?@Hnclr<GINlo@vflweea?T$c3MqK;)F}smst<=$YYf#i!>r zW_Lg8pmA%oSQK3Uy`rfW(x_pi7`X<{vFYz#IeauC^@aJph$>6rfAZgcwc;9T0>wu{ z!Zgyv1kdh`eB*ts=BW6XcTXIurloN9owzZ+?|7BrznJ@;9!a#F6z7FkKDU<?-qF#? z48>P{t<4l;1@^31%LNoK2H2E`dBt7b*-_l_l6{Xlh<bjb?0l4>>Zp(O{ke;F|1F$7 zc*bm;wIF))ONoQ$oL7;jMl|EKM{ZC@KGA7LGY|J%wnOr!(?Xif2*{uIGa+a0W*XsA z%)Rk<BAK1tzh1oWxjw!nLifYcY?RU(T9xY0I?tB7m)|~-jL0fizZ7>f6M5Jg9e3#3 zba+Shmp9u_R?MpZx1Xpz;5g-Nu+4K0(+@Z8Ue?LBCEA^%R?Qh$jgxJ}QI+CG!^fE{ z-`+OV@n=dUO0#%w2|3lCc%$HcBmKeffv=(`qviX(VSms~Fgl1&4%@(SYUF!iuF<q* zlzhCRh`othQOMf9WBa5%r7(&asJ)biMiuo-HzDz_c~L(-$Cw26o^?=u1+(lN)q_JG z64jV!99u8rv&4!}ktj$V%A`)O*56iYp(ZDQnFuKZ{ke)qnakuFA-gV3i|mPZ!Dj;B z^$WHWfcdjS$@pM;!3Yv2-jlwuMVU+y6sIR5XUiVZx8x3E8b+WfriqUu9nHYEFV)@; z&$vY}Ikx<gLa~t8Jo$${G|QGkzqW-FvU_DCarN`Kz#Qx8I&0IIMVg{Jh5deuaUdm7 zXB<8>wNGt1-}_la$p;)-<(iIg3m!F0enj<TeuetHyxJ(X$--5>H=K!l|Ih9ayvKO4 z<?|>?<RF)MN4e%G3@jkcqME^S{LNks@4%f3Nw9CnPVV9`Y=_f1MU8Cw1U`b)pJsOP zm;JJPByrtW;^#Odj2$G*Rg#EbL>eB7aLp{?@+3W8N&d$n<>w$}!6En0P@sUiz)t}2 z1Lo<B2lS$9NGdC5<;(1J6(Nfkjm;T99!X!Xt3p$4?^HM(N>JWA*fT!jkZ*I4@63~b zaz$P?<GqQoLOJ$*McxN!p5@}?4y%JhtEpcMVO<Xsr#6%=mKtfB5o|qdXabYMnM!+n zVVO1*nO_qQe1&1-ROWP4=E+w+*ZQZ|PQ-RY;)STl$(o5TN;RWKkx;`fM}3znO(pM= zRcIWVO%gg&2YHx~he-?<#$PqpuM~e*>5vz$w3Yib!&sjua&4A5gq^slEH@-M_x2Jx zc0X(JRhvd~t&S~kNz-n6uD@mAS-u7(wYmT-mQO)tQ6*pZN#t}@E?hESuwzZ+s}H+s zULgJEC&h4VOrVV5?1cFwBd5j7t(qiv9d`O7CJn!~AK?u|{Mos|q}hklPfl8dW7}Gp z)fAkk6d<p`VT_RFNuE-F?GjFCicRF#>2_Ny$)nUh{stpfDofy?kP?T!-48ihB>#co zQiJ7^9*60LVG-zo2y=PB9k}2?gxWDUMdyX!)c#h5^tN2}tFmy}KeIoors;w|G$Put zXSghRMl9N_?+E@d6iwMdIvC|f)}qB%$P=}gsL0({qWT3BDs@qC0GbHu*i<lk-!3OS zyC*g){Le@4kEqCApYAUw**ix1E#>e<)$VB)1I7KbI%yKZJHau??V@Q;*&mI9>8bQG zB}F<Xwz2)uxWng~0!Q8G4{GWxkOD213azDSmPk2m*(BV@>~RBI>$_+BWMm%WhwCI- zKe4Vd<D5E<3eI1TmO-&4_9%)Bx9RDB*IWDH>=`5=jRlgWyM29;w@nW+rzP|laL)Oh z`}sI|MTcWYuF^b>kxd8XGfpqxcuuK18awYGaXg}*YOD{l#7t{x<5nLr$K2n?sgWDj zaK5F?$0!1zgXL+SGRb{IaE=PJ9n|~AmE<r=xKM+b@L}~GeV2$=s}6L35N#l;h^wqk zc^x4ndf2FjDdZxfORuohr*SD426$*_xw!<)O?xSaAANB4)~~mcS8F#2Kc@3u!Hja9 zJ$GTED(BnugTY?H1IC{|xz4ssXI1R{^&-AZ#TN!=7`aXKAsB&fyaH8*{okFJ=9+J} zH0*H;57iGHWhK=M)3=0XU&-FT65!!-$;Sm9@HXs$iB*anBr@1LQiHWGO3AQUDXo$B zTvG7&=8col3AsU_3^2ZFy7$oKO1;Zf!rsN5C;?3970qALE1<toqA+GOQhFvNR_$NE zi~aU&_SZ=D372hy2>++iVei>JtEU~Dxvxc@zZQMobHpsLTS3u|+uP2W)b)Dq=FVlI zEr{2dGOeUY4X2zV^@zW3T-d097M21&dqw;9^=`*KMrGF_)yM<GhecPr=(~n)mqnve zM!qYt#bPvM)VX`S6<)b&dI&vcm~o;1d@J<)v9H|WHHa$_F@NcsOH7t(;n8iy{MpO- zo$CePj3yL}eGYfCSr&da2W5N&;ApTMXwUL>ys?%Gt@Bz3W8_3zyeaSCqLCX*IV2G= zvjtu@I|z9>GqiOr+O0FRJ|x7GGi)L6mbCh#pkKrb2bXeq)Al=3LtKn9crHX1kv^~- z=Us+lDN3f{)|`jCiEj<ZE`Cer{s><MZ4mGJS|v^K`dowy|0@^hAc>6r>WtdUjFtR8 z4r0fwsy<g%Q=Uq;9>xoV`RPyLzTWPM=~B=5p(tP}`>QDC!d&k2=rlUpQEq9><t$BS zXLY5W$IjbI{;bd(;@j|?2%W=S=ojCBeqQkCyx6Bx!1_`D_r9s`q^xD$?3}{F3jxwA zAD9KHgMq0H!KujFzymyw`((?_#x4p=Y+Qk(f5cC;#nrq@w>z~9xd}(;`$sW_s;t_( zr>{x-yq9mj*}gYz{HJcBW-3UWz&ZvB#2yuyYGuX3I{&Q+yqgzpx6FROFsX5%_=<SD zbl5i^W{`4e85Mog;!E)8)s)zIu@5`$=|9xPqg5mda~~{J%xR>4JiK$3Z&yod*Y(i* z_WAI>;|q_w$QHX~J4}M@xD+E6{FQiDA9vqb>)!Q%tmozYM<6@;L2ON|ss5j1P+Tm2 znXP!F1t~BwbCbJ#<gG!{4?n(y@@n3S1@_W~yb4wR`Zo8<M*h<Bd8_AK)`gc@wYzuw z-O6|p4abg+ZQR5L(xJbJr(u}2YYT#y$gD3U{v#jVC%2nOzQ*r9D8427-dOls^s>(G z7e2vXW?S=B1MiQz`OsU)Q&Gz(zqS6!;zL!BHq}3^5gIBoKa^b_Lk1T8lJ?W3i^;PJ z1&1otXRa+cOan%%9KdDD@5K(;&YIYdo#F0HVX=>{f2<wyVYu|e43oz3r%R3P4HcqY zuF3u*Px~QHut#lAt9Vaa)04LPCq1Uu+ts_<g`S8PH|39TP0$}6;@Nm2c)l8+=kGA2 za(Hf?FZkIhqS5Ig*|n?Fv=;L$)?ELup<qll0Q?4pZ`?laN=}LG&N#*v^Lym-_1q2* z*~<}=3+s8j)PGiRx1$tC_wx|dYj|N@<#oom#nt%nQ7_vy$sc)Vf8hfjb^>~Y4m#+@ zuhPOV0xqlNB75$&j>W@aHL%0-`*uTaikEZFcI2e6w$!UXD6h`vE2HSY{ik>GuWG*h z7R!Kod{6bAv2M4qCwzl_PqN{+2N~95{R+u)L6YNKMwTUwg)>Ha#f0ne*<roT!IC2f zIzgT$lQ#ta4z4jL3WB_^)1JH?eKMc3p5uN-H#%+bpsK!)E+Wuc={eRH*CYS*RcG1Q zld=@?zc2gVX_vmspKvdm(v!ryKb<=%>nmRH)*BuOoBH&w@G_I>55tjzcb)$Uxsd-b z%QW4-l}$_geM9+b4vjmS^KtQZTmCuUXv6SWeU}36JF|t|FKfN>E4_~IEVnn#kKf@b zf1zt%J{O*#GGt!jB3U)mm=7RN`Pra7G|!yRjU?L*!GGm%V^5Yth9gNQBK~V|F*HZU z$3eJPH}p>OG1;7{$Nl*YncU^rE4<@<r599<KHOhilz&FETv{+bS-YFR#NJbNW~Fz) zE68v}(wjWQqX~n&W6%IS`}k*NTla13g_SR&{70hKT0eiJU#x`{It#84z$U-$FV4kq z?cB)fL25HRICJx6Y3+>A-Q%xweL{lkwf8<N|63FKv)%bL*52dw6#rSP8}Hsc*|5L+ zG^FB_B{L(Y$|myJu-~)5_79IjR)k_U-!2%;HNE8u2EgrCl~UtZ84QXU?#$nKJ;PmU zz%)>--XhZ`{JCjmU*sHlz_Zuz>C!FkzTTT<58z*q56Qy@3lbX}>DARN08~fx(Q=>7 z&b^xDmB0`8L^fCMIsNx3@>mfpiZ7iQ1g~`6;3&TKI;WIrn^Sk~`QP~`Pq$0s!x1I> zx9=a9-rvu-@}=A0^^=>%BMafP?s0Z^UC!`iTGaxqSa1)(PY+t+3lLdhnOWL<BDiUg zJ#qheq4W1q0>nM}M)a+%^1yD!oAadq4g^@x*hHjZ1=Wxf$$rmuw0X^lOGenJ4A)XI zl))=*6xD@aOG|_^u?jL&RHfug>xQn<d=g$V^ZNSMVI#?jr5s`=#622m3Wj854xctE z=)OhY?Y@4k>A`F*zS8op<>QBM>RsD{m&YF0&o#OJErD2Z2S1Dd^y5wC@YG$M=nF5$ z?pk#|TCV@M`_v<yYgt8xlaUwOOsj<;b;MT-Fh1Z3Mio{6@b0{T6jm9#A}*~w!e|16 zP1FXir+s^t#aR4AuvPWN_-)<h&|{9k@sX^smDew3F?2ix#@&vtV%dIPeJx-9zscV2 zgBstz7WZwR_8fkhZ?pS0cXnqnj{drD*7jNN@xj(?{eM%>{{FcB>agb^#mQ4#kcpXD z=__Z%hoP()2~K#vy$c`W_9<mP<ZjE)lHfYi`P|@g?NMroRJDYF75ox<fvEbi!_`*r zu$^`pc4`uk91=a8%!uulUe8o}8?>IKwTXQ1I^|QH?f#}<omKDikD!fQTwLK?#_&bQ z7Ys<`)e1<GK0vyq^>LFoHP0fD8o&_T;by_ZYC<k)D8cpzvvzC;mhfb!IfS;^zpV~a zc~iA?N!M#z01Ovw22hk#zp`_f&BBd}OpVV$u6lHXvE`gYC&-FNPT<4s$g|I8{m~M@ z1zLfD+xC55&5u8MQ<cx)_{c3jMI{LIw2o9V%f0Q*lJNd+YFV==uJo=K>yaxgOR=c< z{yCU40A`mcPt*F{b@ZWTKCpi0im#8=gX-Ueo}I3ZE05>&amVY{{KBc0#XkCO$Nv?9 zgmnqG&o(+OB)7@A);IbqX-yaVtKjyY|D9wAu@dCSsBKYKPM&R*bU5~)iZ+NcKUV5- z+#Nxu=s9<m{u^aeKirC()E4Xf`n?;sTsbZ%tANFV$a(IcAN&aJmb>kJQ+sK;c~~x_ zA1A#-ni06_>e15hK}zg?@8RYW=(i}!h<}<+U21trNNH4jk#`kgSA9rpyW;8F*|_8V zL$rEA(Vq}b1V|iL#cqB7tX5H!%`hrQI{NVCN4-hH#i+X}A~!z`pu{s8ia39{?cYbB z!m&`z6H?aPKWb#-Qq}EC5)0W^I#tfSN%WgqJT6xHQ+Yjh@wRF*S4$t5EJW4pz47O7 z=fe?311(ac!K3(fyK^^B!YD#aT{b<E!yb0Y>esQLQ{ud#KwEej*Oj*0mv4IcZdd;M z{k8Mkzdw5;&;Pl}-}aN$ZGPEA|9A518=Vd?Qvn1H`}1Rh#qcpgLx~;61q1-Gy19kI zD7`gMsxpz2vWku@{S>>GAeiaBZ({P4&TgMc=JF(_k&TG<VN~QjqS@ny!|Zsjy=1NN za@K331H!+jZ_!hoYF_pCTt4y(_+;f<sWVgn4Nl-r#DI~+E2{5v<-BWj3SlXlPiYp9 zVhGHBJWsSL#++HMbIXsXm8k>oW3fyMmT1mG+=z~xMQWCVke(|~_Vv1T!O*r!^j$~Y zrfMs}Hr_-|qh_GN5OZMxvQpUIWvW!PpT{%k&v!dOTg~?3WhCGP3Qs07qkLHFP$@fk z4x@%W-wPemY_k_5S);l3Q$MXvDqMT<();)K+pkHJ8ATkLRb2yuJzEeicY>z9oBf5{ zC@goA|I^?K%Y4q4Y3lVF7WJm|E0?kC)i+rI5C^cv(lMR9^EySw*9cL(mszX#$zqCs z2j}=h7jdp*KWlfRRiv3YC@1**_^nhJe~y+hqZUB2&sMqoJfp^>TGoc^dsS(E8THLH zuTA))eZX}#hd?z2i?)|@PU8c>OWHc5p4ZiNFDuXeT40H%?N)0AOk!qya8<>|0`ozG zf_DgH20Z`-<)s-zK0d+kPWWDQs&uNfl*>t0kwLR;%Pgf58NyegMs)*{QRP|OjX#7c zLN40QeI6@Tv5fw$XQp{_WY@8%u6<W55d5W*C1``pb%6+GwQVMyqMl^XXJ|mdXZ&BS zpDh&Fq{|s5hyHg^2pwHVLTzA?_6p+FyYnIA?^?JXuN<~tjS8uB>CEc>m#bTs73Nip zTbxdRtF?(js8P!^JUop!Q-h3!DzH!qUQGrIS1^0{bmE4R55tQa1A;4isaBq1Je^p$ z#-M06dH3<%YW2p@k$RIiQVfsOo{lU6mMcFelhXDY*O)I`z5l(a8Mw#Nbp4ku?m&#; zX=A{M$hSW4fBeNt`;B4or+oRR6pd$y>^=DaH@hzl<3dZ#a3%TiHP-7#18CNkRCDVO z963k#O33obPe|vA&bantvRg7QoSb326%+7nv^j3d=Y#N{qY*4?D<#ExL!|P^{&>9Q z6rD3VKXdc~pH2Us|Mz-T{K^3T26n`zdi<l(b+-<uo0D#<!E8cJzg`B}w%w7=9O?Ys zCh~S3uEfy0sk3xES=FYTvbM-}#Wg`hel{Q%VY6i<@OwJdRxRb4gs;RfpUAD(DHYN- z+m;@`UlntI&lL&?xDq-bM7pVb&)nv-Lx|kCKKYAoPYa9U+?&_U*^e9UCVc)>SN!Ht z@{T@O`-}IV-*c3HY4=GVHWvs#r2^j3di&{DcioinVQ;tiVw;`dUyBPb`%=#B`8fLC z@)I~YTEE_4vwP(|-%_NHz%}S!?(6YS1pg8<@+WM*#a-iDzUua?XU%8&^1*<}dKz2P zj?EtV;QZ8&4O;{HzX;Zd*8}|Hbtzh}Ugh*QtIqOHbq#Ay?q?$+XX$SO45s_CLK^%8 zr(8!QMkCm6lzseopwTsc;pX}HIm!FHmqzrWlyYK;l|pNy2)$Lqg9?GWjT*I91~2<E zV;lTLz66aJEGlQ)-9O%Po$5j7-`n+>6F;*$kI?_Q&m7kP5qzU{)gZ6&u;a;cnCERP zgD*2tE#LeE@#ea9r6)h1{m~DNIQ#Nl-!s;@%;m2^=QQ*}>vEp!{@Y(-)N}j(A}1uX zaxdk-5k1<|)*<762h>{y8-3)1u&*cI*Mml;p7(7$PWgA({B36I`IVy1t^^VM<&@o} z7S`}3$Yu-Mv%MV^`t?W6Il5o>5a&J{W^d+K3ZG0PX08bxta;FXyUQAQF{c0By?$RF z`CpVl*F@M+%*n}?-SgjbmwnCd&&z(zd4BTAj{dt1p%eD+*}q>RDmw?Kr*I6<+J#$C zS0X%yh@7`V^AMTmi5VYmvGS5QT+bM)k+@?>WS&Sm+Thn4lJF4;%}W;3B1^cErDDi3 z#bmiIvcf!B>4=QsO;FKFP;*U?++sU!4x>|9QpqHPqlAUqJV(<^<`LZ1&`4YimZ>Pw ztSixaK5_prk;TQ>QYMMzXQJ!T73QKOkI_WOpd|a$B(LH`zpW%&T=My#WS`XJ0AyrX zUGjz0#Q$XIDSL%UcwEvot)#fFl(^BP=%5tBQA#Lp3h^lU5-!!fI5{CE(Kj_Uc3$>o zS8`NPDq@4}1B$Vm$a)ZvP&S`-?<kGRn_i)neyVNO#H827kT=7brl%RpsVv=+tRFEM zt*#j#(HWgu89lg+?x2jWu8iKTj9z4B-+V?lE^|02vp+R+q%L!^E0ZRZ*>#jLbCh|? zLfM?od?J(8fy;bVm$kH&x$2rZy_Gdqob|dc<9%`V=b)_7uIv{<+0Rn5=jJoFkFo}i zvS&uUPDW3IyfXf7<<MPoUXEr@;c{RPa*paKZ(Xz3iYd(7lpU>{^?3?ZHv4;VCY&MX z+k8k?PaR7c!1RFtmBoT(@el(v)ChpeFXSm4=PB{!W3=;C-1608^EFEHwYu|l7V`Cu z^9}e4u-XMiZUrW>1!g4$xb6bWg#zp20$aX9ymq03TcJ~Ip-V~Oc?PJ#DnuQhr$~UB zp-=!IdJKj60|1~P1;_!eU`a55qyr$NAg-C(mw@Dy^Biq1A4oxoTmElb&H2se-DpeY zNDkUKUC^Sn>P5bc<3mr`{bk)EjNe$9MO)28saE7?2{^4l)&b0U#>50CL-d#gBw%Qz z|4gpw{9juwQgQtOo|lLNdz2Ng0<?rg7?gvzxM-CGgHC~qQ5_a}O3d_t<(HjJ@1GMP z0vp;v3~U?-7PKc306a%n*!48(=2ywg!a(N5D68gAQ&i&&VXwWrx>?A4qyiIFkvJAH z0S?D5g}Nb8tZ#?!{!!RP(9Y;k<o9SHL&z(TE>Q|^`xUmo$Kp2szpJ)lGYO+G8@~l^ zo}=THD4nt2d1B316;HiJNLn9fXnjl)HViStS9b5|X)-YI-E<BFlj)$5Acc}Vmk<`% z+yq8#nZ86WGs0RDuUR;E*muRKG{dvoJgcb^MM1u%Ctgs&h%HeQ9%Ifyne_~~GadwJ zPHL@Xp5|q(C-Oa#7B*z1sq+~|mep<KS!>9moR$rxD5Mq!E|B4QqePN9Z`AfjxPa4i zWj4Fkd_X2gftycJYok;(7R>d!!~h=gY2$9p=7ZUDQ7TTv5QriUe<$)-hLWJn7*%P= z2TTW53IM1FRp0>Bb`>LuK?*J$Lj?IDP(j!_D0esjt~2VYF4lKI0*U8a>Dz&)6V(hd z74o<8_PySppF?o73)*-wBMFnT3^msFtqMrMbRCw!KL|p=Y;<>w?!*CPD6;pE2EBV_ zdK)enMIk|%w1~7ir1i8+PMX}0;`opxG({U~IP^xpZvW-CCIF!jZfr{=P(0VW>l&~g z+#3pp#o$xP_jMq*eeK;mOrHmPkN_FM&M9#zP|&1#7sTqCUYVu9R`9iOZzga93lRj? zjOeTl2a~onIEo5Tg`xNgvFc1uq-$7Bw@uqx?hL~Cm~)?sI<a8ipq*IyK%5jTxsRLa zwXC5~fuhD~frrb1&lG==gpUi~s4GN`p45cg5Zq|OY9G+Q{(Aq{P#fPeENtTUj#*Q& zWt43pBzI1<7@&Db;gk;FfVGuS$g+I>uv$I^Jg_9}Pb6)7Nv#lKyCYl$LxEHk%DLU% zS<Th1PqufJE<YOPkHD=Ls}1BZLZcDB;yKeFp`uch12*mdv>7y*yeJ3W#^>;#5J}U0 zU^sdjG)i#q0nPT$7KVD7vc1mO-5U`pUIp(*pgaeXq%{r4<7BTO=G?sxIK;GpG6Gs! z3k}Gf?<Py^k)$z(OlS<~4;oK`<a$C%FFYpuGXw0dSSXgLXH$4Kf~7PA8w73Z5v^0M z$pb{2XQXe^#6=DA@3UTW&Hvem5_|37Z9<noJVkOqVK{3s4$cY_$RyfESqsewOq(R= z?Zq)=-a&|Uk{lxdsDO+IAo;O@OYD(3<l-`x-?8MEHZ0|6wOsI1YA#oVDcTf+jG0c5 zNy)s7=6+JP2?sv~GfI#+OFkIlr^zg68rj-Of`k1Sm5>zxuwy|;OmfS`qy}_q!UAOR zS4!g6dKNJ1W`MUCaq0Pf6>*V?d?iv6d1!x;^#%U{)E8$gHcf(9kT5L1Pe~0l@`&0d zqkA|J)s96E=+&qtxL6Z}ITCm!Mj5a~xj`pI=sVSwD*nQLu4i(hS)!w|SECsf0GhCE zA41;CVk(Y1k<F*n#w|XT-W6=f0{BFh{fN6bVG0KFd>-JKf>FYo3RSQvu2IHhzVTpT z6B2{x`Hx0e@@3ZV_j6S$i%}|LB;E_?<LQ)}k7&rJRAV71sapTS=T1Q}V?~I?`O=#* zy<N&XIRMLs5=+`ds6*}@L&rcPUz$@5nEJp*2*(Tn_76J%kW4Yjsa7ucf|=TbMFkua zW_p~HLW3?c)uQA-DqPvk!9gsrWdIflG(&*Q@IEZHb<FwIkEWgj%S5O7S+ccd?2~w5 zQI?oNk_^Wk=!0ORXN*KX*PpFLk~k-MD`&w_ELblFdA@s$k|tJ&<`^V`^qRq(Ce6g` z^><QPzwBn|l1k<-!FFINbBc26`Xj`)`8mMKlf-Zdg(P81Jl{@Pr72PoxhpWy>-dLq ziS^!%4K7R$3A<v6<p6LwCWM%POau_{5<`}bQtw9Zt7v!0Fn>0=cG;R$sNx<Gq%sYj zQ<+A?OB)wthT4;7hKgP)j<zs!jC{~JI&Z;&B(JDy_PiT4v&!cM9-C5Fb*AcaoHtb1 zIc9cr3en4Fnv8mNQQS+baCKLraoDsk|1F-OZAHZ!eA?Q~sW8}i6Qovvylv9*S<%{< zG~MsH0|?!Pb1E>RkbktqKlZ^gz$Fx3YenIb;4HVj`#I2l+#8r*9a{66WD&GPr95(@ zPlODEB6aW}bTi*mu$yXRke;7FX~`4t!le?)rH|ayRX_q0#nDnXZz$|<C0m9!jFO{( zkp4X2SeWkBq#UVp$Fo)YKYlY_QB^q03XHY6n-9c|l4bH*_wJJ7wKFKHpZE|lO31kV z%r63?+LO;VL9B^r&>&T_y<2MZQNGs~H71jxJ;hPRz;H063=Q|T?c<2GFlqPQMFUk_ zRWM%=3?PDBbY8mgw-JC1h)~pb`MOU+{JP6x?I97?f3|!-qrp)`x2OiOBsc3Zm&fDn z!l^951V4@EZgXA3kFhb>{f~Pz1TTU-Ork)t=FniS=SM?q4iSk*`~W+B>Yy}CC~U$Y zx?C7z%UtF5KFqO|SPz$YC|j+-{QQkF84Pf<mS^4SebV%oqWSc;5-<4J_EKL$5x^&= z_J^h;roe-2W8hd!OYuY-P_<C0!~~(QMCkefjo~U5BK!^uHtW(FR%RtON&A245l%IB zYw&7`;|8e`gP8JSU-t{_5tE~SO!DMa!)16)z7<Q)O52^WbClI<<+x|~uegL&&U;bZ z3>SDm%Wt!I1>NhCIt**w7Xv^ryBM-&cuSK09uYo8OWKu|fQlpg5LmzfCD-~T@5}Od z&_7i}|A~atDH)-dN?NUFa*^$De_5Kt^;;s!_9NbX3zoJ{m#efs{yt#h3WS4=x~4FW z5Mu0nTVMzKojq>jClip|BW%w<if`630=)<AqTy|5P;21y0dPd90T$ZAb6uSPHEE78 z!jlr)Py?N}PExMPbPA5uh9YSoEt(S&VZZ3|pV4N}I;XNAA$SiI^)(swYxUyh`2@KL z^O$L|ZuMZ6NX6qS?c^V>kbUQ>r0`o;Assch+($xBI#E1GU|<BQizXV;ps`%>1Gkg< zQlO}2NGKZK!s9N0fN~>~xLrvAG5G=x6*-saejXK9bV2wCr%7~c(}>}Yj+vh`bU*-N zLpR%6fD1F+t^ndIMyOU4RiDVl5}1%pPvzhvTx1|=WvM7ne+(Op!Y4>OAASmDE{uP% znH-G(42US6t~l7t_43ECP#W9>jSA30nPM`GP#`TV)b!NOwg>efKriB;G~SGhL8zdv zIKI(1L`3MZIZ6W{p6cqd!`{A9VPIubqb-~F8Ypf6;KwLGfXFL5aw7p5nU8Fizf!ll z*y$fQUIw9vLBS>L8m1er)N6j=eP7m*XoP(_gp|(zE0IAIYDt9KVPTJCpiM}itJoZ% zn77qIwJ;zHEEL%dz1|G-4uWFQBvT->37IL_m-847<sgEv6km9RFN5igQ~p3|E+0P? zv}vY-&sTW5X8er~WxH`DdwV{ACf5?6iP&RN&StKee#!|OR&1sr$WI{;=19L|G81NV z5c`Qu^SLH8m}3{hmIARPK$%jZ2oltE8Y;pAGo?ZQy9l+yQk-Z|93iPKwU8M^aXL<{ zzYs6O<8D9%q*oyqHZQRH*qbEsdi&v)k?PtU(NAE&wi;^REWtp#B-$6Xg+ey5%jl$9 zE%}|@NBGKyM@!WvR*v2hTeyYHHRlL|nxdiR%^8g{C`&5Tsu{|-2EE`0wVH-n(e4nN z5q8Z88v@jV0)6HR^_49`<WiuZyaz$IPh|3%Isq&-k<8#N6=?mV7|W8F*4wT{k3yBw zWl?*3Y}*93p8zl*SyHf&-~S4eV`!!4tVlPDmZ7AS1tgBuWL6bN@NL~1kU>peL_zMD z`)X%^`(R)agCzi%twLGGP`0ZO0TgU(0m?fDwE>WJ1V|{RY{;#Qsg4NmqqKIFIa{Cx z&ZnE;K_zPiF=l>bH@8>6oVj1;fuvD903b#KZHOrwjGe<lKui>%+z7R~$My}d+gYgU z0$()|yN}$rfT<@UtM9A2qfWXa9%!K;Iz>`)sIiNskQNvKAc1fwK!u{lN*`OG9`n`W z_pI%)HN5HNmec8Wc(?<t=#pg(jJ+1vs{yF|V|+E>-(_;{ciHGf$W=rTYdH?#Z?Y7r z{o#X5y&v}%Db(3;7%-jsN>s@9b5$%<W-J;dC$8}g0eBBQG<%F%Ej-o7Z{z37pna4v z?TWEj)Kd#o{{Ne@%0DB3YdWZF>E%`g7@7#iPeX0@8a{u5;=`e~v~njJtnIkA!=jF{ zoL?f{+-ossz+4NrDjWT)j*%zqm$W^cJ@LOb?b_rA9^b_@BPGtR+HP-ON-t*H(0rKx zi#3a;a11fRB^Z>7tEaLjBKED@hEcT)8L<6a2A?{xeHqfQj?EnoP>9>o>@Fy<2>^S= z2;lLp5~Ve9J*QzoH6vrC35<12YmE}=RH)BwB%KeWx_6!Jdi-P!YN{P9M+Nh?XEpRZ z9IjO336x}Cjk&0X`Z`VcOHuv%xycqTS-7VVo{N$DA+{^6ekT%~$91Qy?$L{pz)+dO zi!mhOH1pAmD3$9i@HMC>4c6D)Dy>@}^b+Mo0b%hlsSK0@tsF-?eJ2<*sr;-}L%4fO zQcr!ldz};pWJQhekxrMn9kMFv?S0tRUsbTAiW*aug>%cWVfdIoKDai-cB*kXh1`7T zBS;QXvpn5-_pw(-2UT?@vhP>3JRtV`MosE8Kq8>TW{58hE+*eA;n8|41Z5AvyqZBq z1Q?#!2@`EKry>KIA;fT~1FbiiUf&C|Zx~#Jl7d?#@1*01ZI3RTR(s}FQsPaikVBdO zE|{W9*e{iQ=7#1n|E4-Ldfc35=h-NiyE!j|O}YUi-6vkX!asli-+bA)MVs%%7K|?H zT{=oqx50q`2dHpx1k{;IMS)=6=%?<4rw+~i4rr7jGt83+52C@|2*9R7y5{6t5y}ml zAt;`cMsN#M2HowCOJ>WhW{|w`QUZK7CGz~bmN50Xi`2#J77rK}1kY{yuJQPk5n{vr zL?|L!&djfh;pzyI!jMMIF74udH;`_1dMhw6`33s!Nk4#sIa5Xe!s!?dmkE6eP)3}a z`!xh%w$uzKD%_Ti9R=Hu5*5lXf9*(cuLIwKa)d(~-7@)7JMghNOrJul4y_fM17I_T zzWyk+R{}d`(z_T>uM__jb^(+FXp_qflE}L-NK-7zghbq_8+`(48P<(|%HP|2z3izj z5uT17Nop8j_8IV@flQ`hlc6Z*<`D-fJai9Ar1fif4ov<T1<&+u&$Wg#!K9i&wiHSe zk}B783tsNq`WCF#oTfmu2i3-`#j0)W7pDNgCXwyhkFmkWT&(P}?e&I9p8{TALopAL z*5XiI?sb=$Mqr}P)&(bx`MT_Au;t#7*ie`Y0EjQ6?6L4yUtwZTQT8;LA5iAqJgWF^ z`~!U)b*1d)lqKp?XsHG2^j86mj72$gw+YJ>zv6*})`S@qYacCvieK4brBQ+*4A4IR zuNKof5(rpJiN|*}p{q7big%`d`u-jv1=Uf!<!T_LXK7!Cp%JqX!%0%+g#0)xm^R^# z9d)L{;=^F>01z)UPga~KmBEFZp+2-Z#=bfE2BZgNR6Z0o7e6AkgVM7`;qWj57$(k7 zf%$Y#nmt#=jHzRs<q28U@#>{q_j0-QOgyCZ(%$G5TyEQsY?m}iwqWO|y{-PG`l~gR zsTj(0QgbPc-I*{DZ3FY5p6)%sZz-a@h&(YfD0d1R4L~nomKkSY@(mMqbPR(x8s^^o zO3Z5ovNo!2vj8T|q%M_lu0nAX=v|?jaqZVExsc)4V7Wc3d-5pTtg)y_w6r=3bEY73 zbg1>NZUehsZ9?#9zMY$Y7PEfG5n=`ux8~zMbIy94FAFsnIv{al!o7LUfr_-7hK{q$ z1JkfujmvB^aPKy_*D6fSd)*t4Qey?K-pD1OVcw|a8J78UeH8g*?eoOimm4kic#t9h z>sM?`U0lMa#{~*NwrcLqX`=4<DKBd3k-*X!A8a+bV(F!;UF&RHbGp^=9^m6+ChHr` zaBtRkFGqp~kuCK^%Xhpxy$Iz6xcw{e8tgwB+=B}D3}4rxE3t=#FNUnbeD<~||F$3? zH~|G$eFRHyh6JLKE~_wi+6O56JVf->q~~l>1ImT~lfr|X(eJEK6->Cc@fUHW@hCMj zh{klZ8WzH`6uh|p9`9$%K|@2z-xwp<Y$J@3mo{TwomDeNl^$2#|8wf-`64{Zz8O+` zc^PHq4ZA7yS>7Av7d}T^edi6pVeIhK>@B7>*o9T7)HFPM5>=ptN~ghfsmQggT?Wxt zQ#PnM!9CK~PeazNyjbX{&WpZG^R|DJ)$`F_*C1gCfEyj?c<4No7-Q{qzc{!6+}Eym zhZz#V+BWc2S9Ll$!75-Dl=ji}?LhNe)+riYvyex)jwyF`iFHqeb@b-W2YAGKIsyLD zX8nW}Fg?qDu^B472lqn3Sq*;#<Kcl6xHkswN83GTuzUga62iV*Vf*<_8OoLblOcfJ zo1wPNYr$a^hfgcM3AmqJ0O^k5zdKv!6h=b!Em*;-EYyTgduA<R-(&MOnXq49ftx&j zK78vOC|49B_Mjt;|0CG`owUFl6KIPuV!gn2TTKb6ON0Gph5xq)d#Voi5C6Rq@teWt zFpLQ0#2|cVhe*-wLtA)H9XuEd&)xlT@C-gKicn?UmB>0avE7RZgK1Gf$;^${Z`MCN zk5a>4QousuQ$D)=>#oQUe^GG>Ob5ZY0mOL<%Qt_v^NL4tVm!%LXrbBK*$IYL6JE?C zffYEdw(K(B2R~6hPsN@sYqD+wAj0YR{vVh9@%JQVUf{wgN)Sgu^QE7W^oC+LZ8#XB zhs(4R>?QgrglBl80TW8mS@1ybk5}QO!BnrF)ZVn2^fP2<j8Th<4+EDpPewMEEVR-A zFi`s4g(f3d0Civxn67|1WTJtnc?xJ9N@f#8aiNSw%x==Vo+SyK-}UT?-dPzcJ^#)7 z*^R&6ndn>vBD26VFu-mk#z2+<s(@xPA(M}{afP-uu)Qp00|@>dS7#*3Ra#i}mN-`3 z#)$p*%sK%+A)wAk7fCi@bkLmBu+<wE&6l$A!lZYF+W&xM4k%9y3`SXpTj0(rgX*3Y zJ7#c`btTP6A3i3gDcMr7%8UdCU`i})e3=<QY`$=7c|=s0860I5M5Yf>!D;B2RZ!a1 z76eiL-|?rr*Z+|*Mhwzb%|=XT$C<!Y8mm+YnF~UA&M9Ge8n+14jmwcQb%9bcVp4O^ zVk_61kZF0eQPt^HITqmFYWj9{>WYIg%Z5yUnAWq!RB(dETbv(@Y;8P~ggR7qfLVJq zyiQbQ_$Uu8y5TyZ1B_>ev@6BTQ!@^fjB@n17dc;;i58DB6U9wh4TpG}(_hL1dR<6J zE`Jb~F4l?hZ?`uWNm6_DbdcWyOJ-iDL5xm6F_Hc3Vmg(J;bC8LCvlaLA@}W)@}$=F z?+<jzUB(Z4R3%$?MRN-{6SIV5K<njd;hbrfz}pzBE)7ih2Nt=)%rBYhQVSI<>d8Xf zl^T<R92FV&+6v`&%`(L5BpXuu+jGn2bJ2p%g-E-!7}N^{PraDTYwkS=T8ERDsjuFq zJAIW@0!0?0Zvi-zh=oY9mT#K$=9o|}_cUJ2nCXD6(su1(=um7v{{v)9wd1$iZ%XO? zwXUF5R$cORC<_tOBWWR_!nFWG5z_R3R!A?Q@1QGk%zkgF?V&+w+HdE%mHZ|7i|BbO z^QaBxHR_>*n3pm?hv%2+@w8f*$+}gz=9{E^YDF0}QeTjvbzdJSHY!B3f32|_YLMtZ zt7CVrcXWVR21dXD%upgQAkk_ra$UHp>&nZsBk@hwWxiEC8q|^uI!7~xy}mrYl`nId zZ>Q!<uhznF>f0|$Mx2$mp<`}Zxm6$CQ0mls{KUFL%Y+=}#5&05o*J%1CS@5>$k=N6 zyB^UdX)x!5JLawAOg;<_!Z@F+^H9GVgnzsn!$4jGzfu0eIrIWhZ+UO04YRLk#*k?s z1cxNffD1;9S5SyVm=M5c&9#BOHL(kQ$PcIkQO?wCw4~*Hoiz*??@Fb6$2tlvn;D(f zrlJ=|?y^U}3p-U5<`z;sAUuXoQ8NjPiFdohP=rYln1s2JQG?uoC_<LcCI+axXF`N? zkko2D)*dd{w4;(G2~;NC2S(htzRRU?4aHj(moB?%a>PYoZsJ}{;nZN<toU>Vb|iC! ze>*qq?M(Ky!~zfqgLs5QLIgh-`+n!S%N3fWQebbNfxOaGqhM;bRVrYHJ&+>T$!DCa zC>%HYVDip>B2JuPg>R!d$zrrTsMo?>&bb?|M<u|o1q}#fUR6sQ<q&s>dnE|8z;sO> zq&lj)?A2)qdaYTDH7U=wrefgVPH+<I2NlNvLA+-{5y?X@@B4#U*TnWo-V)s6g>$9U z!6g9T3>Kk>sW8{;n7#WgkxBQx@@;FyWc05AoTjOiNZKI6*@z&dZmMGOs5jK5enHse z+0|Tbv3)Ve-=b48?A78w!;7w!7@sjBASxEVD_-8)YI#dZS8P~g!R3$UXAY_7VU)$K z<B`&Bv+x#*kFJ57&(a4myyz)W<?kSpl{c+|50G>E<(El?OK}e=vI43gtmxJ#YmCdA zhv$cojBs==4K?TheIRXUAf?qEgGuz|@bUDPW>0wbwWcEh*J;#0*xerx6EX^x9492F zF)CK^<{A@Vy7PTtqIKk6KXeae<;Ky`%##bD<L<wfe>U8jGRCy17@a(r{8oY4OACV1 zYKAM;Z8l2#^Eqr4B>vztl(h~A8D7Csj`oNM&Arl-jyy~Y7)=0u0bC`JfEM?b*rzU} zb4!osruU@C*8=3a)SmM|6cLYZUBwv<pF#DQQ}g0C$8dg0T$9YY6D7FGu8JzLD*-G8 z^CU5ceTf&AiPpc=70jMYgACe9*4N97i7>&_EfJMwvwR4u6Z76xc)zH>w;WSA|0;ud zgV|~nE8v@Kly*{Qe%VdYFq1Nc4%!qm{%FbgYJMr>tDVF!?DX~wJF@w9ei-Ffn>^Xy zm61AR%mJFIb%`(BSxiE{_nO1u=^2ittBg`S$NZdbmZ+e|zZ4_!gWOQV8pq9FP4vev z1#~FMIz&G4_yQz}L5u((`<e5p5Wk79{bKGv#Cl#LcfDW1ShYyZYh$ct-ovJyFD%3? zc_Z$5OR$$)R;id4ruyw|d!SGc{Q#771P|g3m<a_$Q1`P;^@Gg}3l(gh{xG#&E#|O* z;!R!Jdx3EOd=NS>YTqI@?Dn)>;FofamR8(nD~cwegs~aA?Zc9>+54J=zH*enK$%9U zuMe^2pQ?;2==tu@FG>B(KZ7@EAmIj*dhb1<#u(peQtODS<tn42uSBjuDE?;TKCN0F z4`L`tihwr{XbYMJ)5$!7Mz9z;K&7T@#EU12*P_?}M7T^Ya~8X*>y|g7xzf$s=4xib zh%@G&4|~4G>I6WA{9k-Uz969_fPN8IC5{Wa0<uv!82@7PN9~NkNhpKxOy)=R^l?$B zW)MWh{FT33ivW-)h3vgeNYn=bD`K+iVqa_?jwLdx_)8*@P|4gTrAaI@ysq!fv!C7L z2QE-;tLL2Nyv@EQQ8T&BE)w2nyT`-yy(EyY159<v@07%ZpSLA+fBy(+>Si64Rc$+V zMU4FlU`=o}9RGwr?!vDeL>DIr3i`k`v?^FaSJplF71XF9-2JAb%{*ehLQ&5H)^{#W zacLFnh*IgnD_JY6%pEV!X3Ci1l{Ozbg7AQ1B0s==pte+f?uM{cq61`>ZPl8q)jmrh znwM`qt_bsQ&*hbQ&s*VL?#~w8C-D<gHHo=0qJ*i-{}iv%ZvESzD%5^QVpgOjOtfiN zHAAY9%}1OGuG9peUb|{bTbD^wQcRIKCIRDmuJj^HE2$(Gt#;Ld58x#Wb`cfA8G9dS zk!326iCv9o1G^S<(<-r<TEJKgFicZE4<Mt8p9u-73kh<8Wtad8&^li{a8&k{lVMG~ zlCvTIVqWTV)%Ix=!#(V|Tx{=KPT3Vy+C2zyEFWSCK;^;{0ePBI@42e31l`qi-IxSA z1Eu@#?DLZ+si5|5fD>wtf|$Bub?Z8Ek@^F{y<IVR1)s?*yhXmPCAM*_nY8Szm+Vqn z<O(9FeT<oRO}c8Y=j5m$XNH$XLrNqF3Uis(yYptuz`Gr_$U$<CFeHmewT6&%RI31q z+%HprG#ZeYtJ9YoNL@RU?AbC_RiJ58A?8%DDK$}l@m$(!Z-(n|27aKE2GO2BZBih5 z01)al5LAHtTWahJ1<uVwuw4n-F=qcD80?18TgM`OF_Q9H9^;oPzt7}iYN2a{PURkr z10c?zz;k!hfl&dGQJq|pdM0n~t&7S%OPyOE(r+~*t`i^GSK;(@nCM6cQ|tUxk(c*T zeC%97>W@ZyZt<sOwheixJ@1Oie!Io}2vqX~(>5iZs#673gq+fU20&0Ec*E>zR{|D8 zl0qilgA&yWka{#TGR^FyzFVg&K_L=q*qopvgS~5Qo=ecc7|Z6m-r-y&X|LX)P*Y>$ zTV?fF4%Wq{ios09isA&a$)9IO;p|)q?M#e!b7RVKG13q;lHVgEwPBQIjqVgjLTI?I z)j^9867Q%Ymw*2ghEeyn$I=_Lf-0uLNDH5~vosym3%v;{1rQy4qRJlRT=9#$Utd%e zFc}ag-bSI{_9mFrfkZKhAq`A#1|d4lr^N_Xr$Uz%2I!HQ871}A6w3tNQ9XmxGu^YU zCGBoo0eK6mCxxf5qgvRl)SmF+;<|4?>rTJ)y9d>mDsu3!X{<N}0+?-qlG6<OqNc{m z1^L8NlR`%OyHaiWa-Er8WMGA;a(wwtCAG5*X7ReQug~}%n`R!#V}BS2ww)%DkDr=6 z)Oew_y=HF`nG9(7>J3Ic476MYsz<P?3a55bAv$$14H^B_6YEUMfSQ&5q)B>REJPX$ zYG&5Zn;kNhNNoiXx7xw7=yv^M+0SZVaRC2*-8Sxt=FU3f*L9Ir2=Q9b)UWpcq3B%v zng0Gb{@DfF7~9PKwwt-%DR<ipBjkRIa=(<^E0t=SVJ^9aD9W8Axkssnky}ENu3v<t z8>Q0K&+k7tkI#8L&ij1M>-BoRX1GDPoP6zlZToTJnfMni|NO5q`wFrfZE_e=S_$<# z&!Uhe6CLT`D+NAxAJXkAG_525q*|0hEn6WkUQP)fekgdGYY6}}qz7BomAaB@l?)Nv zhFGpap31w5J{-2XI~t6I8oE$SryxfDV-e<dg3-g-k<GzyP{hw(N$^Fz<lORnf>Nf$ zW1N&4j*D3UU%wznYL%<oxNGyplRJ(O2bmSLV%v2~b7nJadS}9lOK&t4X-mMpi@3wJ zH}ssY7s=dL##Lo+z|}<z-$&-QiNF<X2-#q@5kG?^EX7QjYpLZ>hjlfqgdUlNSmbl* zTC<i@-uE}e7|I^K+uqcNsnuJlZ{I;IMj*9)kkiMeV;l{H&UEwEt@BMGJMaa3tX!s= zS$%11Zu>Q`-(6V#T^L!~N}k$|qUlv<dG*^j?QAq<n=soUKuV)qc$Y7{N?zoKC1^1p zzEtG(L8_<cBD=_F)IaYi(!ASroN}l5a;Du4nfh4b6M^&7lOJf;{jIH9Ax;7F=A|B) zu=)Ei4vLXVnfLCS^0t(Q?g5~*N{F=p^OTdr(G>3tr>BpX5he_X=t5P#x@-$e((4#J zj*9%$%GR7A<lhCeN5FDutK^en;!tpdD#QDQ)*b8p@9#+GY-a@EV8?J1mnB}^)2*Cb z%v$`SRjE)QF@Gbbdaf@hOV+jcz*ovv9N*|}=Erz<)5jAL8m&8j^eIA5Mz4g<o5ex3 zRV~sbW?RprEPbFa{GjLV3R^aMTd8vF=OG;rQ&YRVQ--)#G_5V!KBnh2H!?L{mWI@_ zxi79&eC#15$sna$fdgN23~Uf%LolBsROdxLl46;&un*W4N;VeAjLW#B@CsTloZSn{ zk;(KBf7E|c*!I%i915Gn95^m>6-n$nxjZ&x?cI!}+;Ot5?&D%Cru_gY*(L3k#fzTp zROx>Zc7Bk|YS!-Za6FdnTB@`lAop+aR%wvZT&mAJ*eZ^5%Em*8=1>s1RBbqR{O;o) zceq{{@KJa3z>xb0;mdD5ZYdS8OL$yALwoUML`|W{&Vv!{hYFd4eD0Lzf^m1Yz(S`a z@zKN?5%KtdpMkZX3Sllq1GN&FGXuo~UnTRWrWY$!uWC%1U^C6Mf*cew±dE~Htw zr217t0Nocd>B35r!q&J{6bvf&J+z=PC`UTj)J4DmU`qa5w9=iW|MhcF9=o=jWyM5W zZZyJ9+vf!4hKx}}2Vn)put$+%b6^|aJ9Jl*f-~^vf7cj;y4aizrSpBT43MMA>T1D= z8#`_x@szNzTU$ym?EW?Xp0yk@u5rA%EdEt+&jKwxb*hFBODTSx`Z3jSO5bk#siJL| z()V45E!3F|W81Fn-vh<0rE>PH$!M?P>VtN0WUj+%TIvWVwRpun1{aNW{jAJAY8X@i z<4E^_R*zZ1A#y!a;42g{L=U+K4~x3(RZu$q=loo@v1LmseBX2p^xbMDnJctO&5UDy z{UhesCVaZ)BH|vG5gbt=J0&W(s^<P~u`D8@d`bOY1YIICRm)ay>#ZW$gINO0{g=v} z%(h~1Bw?v^Tx1V7GQ)O_630oM3ibULwEEDSb|yGd{+${bie1oJq9Y=Ms#y%xCp^*h zKOkbNqb-qZaC`6TQ$26Y<O`TM>uDj#FQK!j^_a;SUeBttJRF02+rxNkwVHLjccP6> z_&!FPyQ6RTVm<n$FndnJjuE`mAsXzGn{SoOQ7&aM81H+!v)S5_G}Tm}sUz(r!uvcO zVwwjjJ)l!mgC+kdf?FZ)ZdsX3rh0w_eu4cp`SPTTn65hebMR_r2jaRhqs^hoVSL|_ zd$3!9P{1WaM);_S_Bv=W&jaF@_^E!Z(zsTd*xLxc;`6v*N}{AtH#@j@G_kws<*0)M zJYNy+JNI-~RHgucoho!;b*(^}L!HW|_;6IYEL-E4uHkI@Jj4da=~P^zoyo>L*}UmF ze?<f;j{-{{Qp_0W(C8EW3^46OVH-F^*+H!Ug~!SjADZU1Bb`SwIt<ycd?9cIz|8o2 zMX&PHXT1~8sJ+}BFX)|ZL1t1of+878eL<P!abIj3-Q5_z-R1F4@C8mV(rN^1q0C9w z=G-!l#|i;79Q3X<hoZ|tZA^*pPs*fhGA?e>bduPr9J&j~Vj(DXb(t;r$zF6G`Ehg? ziAVszG^1!+!S1S>Oqy+$Mj+s)a5eN^&n@GM0@x!dj$2M+NKRm&{vj`m0RU2(Su-a+ zYx8kh27WrR;GyyLXBMlorzBq9g+EWMnvjJzRoG7r`eB~LdFHN2YjbF-5SvJj8ySZ6 zj@f@PDF+9&&i`?;;m4_~C!EtcsM1tA_r&RoCu%84bgOva|8jLIH95X3_dRB3z2ixo z*&1Z$KiIr$-Q&EDM&WW9z1L{%$cyCGLv{p4j&WS($o^VgEa;s&Ta{@hnfY*9=&kto zcLz$-f_^GOn7Nx-VJfh>W2>Xxpb1q*_GQOfrs?jVo`DR;CcUty)Zo-`n7yLMP03lR zK=AUvAoPEbaPE5>Atp-+>Tn;{`Y4;4%pvnw3~A0eCAc*TZf&(iSAiZ(R`jGq-r7lG zCohT*|88~iF!}>g4UD`rIQCz$yO7F0T^J<2$CF(Oerjn?qUfJ2NXXnUeZb8v`HSHD z4guAA$FffL|5@!p#bKyf5UF4C@qa`$w1&GSCT5Qh>;xE$e=2Zs`n>Yq;$mb*33rD! zG8>7DY_p5U?uF8YfNt;8cX3e01{*uY>5MqtV*Kye?%u|%c;{}>r4sHKzv%6<#d3pt z*H((ME`6Hph{eOw7vSj93RRSE<DISmi?&x^<s=<z(C>=c1`R<4%px782?Un>`3p!j zasxNOK}hLGuWjJ@T#SlabL6g(<D9??>6E}$u(h~~?w%yKspWok!8`I>nEKtp5urXt zHGUhe031t@<R|8f@hwG!K+<$9g=`g`j6QsL3T2<k6}+)<VFWds%>rL@<J(G9v4gU; zMM5|7tgC?Sg($gdEt=VJ%@$t>uVsRBurK8&d$-i9$oUf1vDyU&>?m0R3%WivfjN?Z zSFLU`8wyX8rhvH%m4Pf9D5wX>j}4riZSwAj`S|NtT`G#;xZs~ZNEH|IZax@{8nZ4D z3IQ`hP@ntv3LYUhCnioh11C=XgHG8UrFX#cE<LPe6f{vdt(Iph^7F~!v9duAP0{G; z`ZCqB(dDzz&u&O;ZsDir-X;mXg7W0SVBSmGF+J??L4fHxg%-50LInwE1xeE=s-da0 zzAAtTF9QK=nm7YsLWJdO^Qdb8Gw-C{m@)CZ5xI7ndKH9YLB&bSAb_+Mj*7)ZG4Ox{ z!6VH9h@8d%K{>8dMMDyy^43NYK2ywT8AB;x#}dy8u%XK+d-?dcRoRlAj8+bwPp4o6 z#EPZCN(5lp9*r-<y4h;F7YhMr#s0G9Xek@hN{SR2Y$f%8X{|hP)F;ao>%{=Qq}`Kn zMWK<eDqX?^&XWj$e6$NH0!^QyKm?*fWPyyFaAHgE`fUwsWAc`79uf(sAZ#SJq%%bD zUebW{Kd;@KePgHq;023tDTW6{N!bA|>o=SbPC`*sN`T#}@0>*KtK-26P*2>05B=fP z69c_dR{&BW%sy`f|Ez-h!AzI-lZ-utyZE7CjF8SLmMBkCEJjslkok=@L6U|FrLav8 z92<`JmX`^|(uemwbx1}v?5HSk_zi;as>NWKvM@7r7#v6A3NDtQph(R)0JhfnRqUp{ z#@)`Deti-FF+@&Eq#6-9oQ``{p{T&ehw<f70m&drHzDuOQ7Znuhus5&TGJ;gmr#3% zW^3Z9Qx(+&=Hk8=2=VUzkmSc6MxKs)K!nP5sw~2&T@fjHfc_})4Swde`#Eum5x(G2 zo4r8BzxY>5w|^G3l^*irqf1VXauTS4od=IfOoMsX?8)d=%|;<#B(E`F!Q(KM#Gx!b zf?xCDg$S*Lh;2FUv$FVxaZ1k56H<<y$`BmdJ@59s+^yY3o@t_6yD_R}p6<7VP0PNz zH!b*FaK%vS#m<TRecHF5D)2wiOi#3Ku3eK1j^n6rgy)}82t^~K<N<lrewf=v;1wT` zj5dpFvoX#>$@}l-kx^&S1azCOH4zcto4O27kofts3LFHskmop_>Pb~x)tCBfgTNbA z{bxP7ajzKGV6SP-Efm!^K!U1LazVV1V5Y%nN+d}L<VMvEM8TN0CYoTL*$3+N^@6sX zCl}<tN2j7RoCWn4AixvE03FcO2)_pc9GDP!vW#n(XxS_4K4`syLxaDJJ4{w$pv9p7 zUF@$c0i6Cc*>3$v;4bCjFa{0RpQVV)`Ey`s@R*BsTp&2xMn?Ta1Dp2%zm2YZi%4kM z5#Iv2u2nlTpATQ)%znlhsL23-1_U^f{oF?mu+Jh1wW$k%9<fD)HWY@94$_0bHW{$R zpy8tl?x*s7U=dy``JeSJ=s7fV^==yNX)lW=8`wi|`1WyHeT)BGZ`j%tm{%Pc5qtt7 z&;OKEZ0iC>*2K|MzVLa1>l(KCFpdyT&w<NquY$P>$o-ORozPo87{m&r+GeEEpMS-D zgYx`Ib@>O$9Ahf3-XUkcJ@q9TF62uF#-2{3QabcsX)s_+j@%J2&kk+O)w;(;NgwOD zwyV-w$m+A6V?!Ydx+AURnhrMiQMq#{0|P<{yinsPhsZ%>!rA!+YC9a0$+F#)R&ArT zGu<rB4|ei9ooibjhy893Q<I{N*%}TIG8gE=lX00gs6F^JiD*@LyvQEaCF!N!Q0ol? zNuPiHr~qA%$3`zo0n><6GIMcyJvF|k^&8dbC#a;8qNOo1i?6z^W)O?A8<i&+kia}a zeaftOJo@tU?Tnk-RkIEHw|X&DKU#Z4zG(8otvkMq4a`?F01G-IhCf1IYN+HkCYgTo zD2fb`;ido4I&_i%CG{;m^&}Ho^Ueo`puceK)}G>i3-HbfV-{@U*f9GkK0&eIQ2HKD zDpy)Siubs6Rz58F9A$TIp#0KcD^_wEwd<>8@&z*V8#{tBpo5(oq{EqAID-nV^RWZ@ zd%FX#qo&cjVYR%|8^%qOfA#W_OK(b}(i?H5WG;eco|fVn{_^OY!o}9E7ie+3PMMqE zlf&gP_MFZW8>1%|y-IqO>2YNS(u){ZIHi^l|Lv|0O;&H3&GY3+sYT-~ixx~jU%X#U zTDj-pD!khbi2`58g>NE?n-^42+^GQ(6dqeRDWM&-R4UrPTnEwPYi~jU0riy!Y{RH} zcW3ZK+>x%~iR5H4S7H{TTI_tNO-_BUXMW<}SzCDkB)YIf?cDB&Dhwnk`LRNi<<Ot~ zMusMBM;hBwP%(H;UA@gnkG8Ge4hUd^`*yC={s~g)p~2YbN+@aDGs1D^<f~?1K0*+b z3Fz=2Ar`&K9{6;c%2JzzR${-1Z6mu>4RxLY#!9;G%YNb#5Np6K{S<fqNCT2Etf$v` zaVt7i75;?2XXJPlj4911xTP8x;wkY(MxsnG>JCM=<(Ssjqqhg~^rPI+%28A~t(OpT z!R=W~5lUMll#)k~3OLeOViUZa`scZK?|439U!xhj%723$@EGO_t3s4V(yuBNeq%3R zMszU@gl^pHVfPlgu$UZF{sy-$1FJQ^d9~X4RQ|~^d}vce_mnVZU5ynqJ8aJIc?9PS z8MmDrfbjN%n9J8&9I`7|yoeo9m;97cYoQO@c3a`vzt(rVZ3R^sP-hR2R+f09%RW|n z)w|^M`K??`&}i{A0=S@%v4&a1*UArlOwY*0FB~r~Ll5v=TTL)I0vq%3$1?ZM28stZ z?4>Wu(^fUu>%i1Knx7gv*|S>EoC!UyzS`}e1U+~9?TkEX>xaXuFuXqwB0cwx<aRx@ zK2rx4tSL-0xBa>`n^#-DqEMV$3Yg~DPMlYST0ZeKf{ucCax1eYTG>v@j}Li(vL*PB z?Cq)LAY9uM8g`_F2^W*$Z>(Gp{v>`{kF)LR0#Rm@%BY$YaFCkxV~+tiiFWnb0a}VU zKw+cLUbr6*zU;X(AUad_Wigv~cO2)>{z)BB`XDYMOP`V8Xm1AmH~k;A)l0UK`o5WU zNS@y%f8}V<)3ynUKt1J0sHYIuU7(Z;O-|1OsFtdp5Zg*6{qtGCW$Me9R3FzL`Hy8S z`Pm?*uWRO~f`tYuA9toyGV7UdW!lS90S1+h)h{ZypHcL%zRwCcjKW*X<JB>Xb8xD7 z{=hf*B0Z8#a0H8k=g&QS)(?9rGAE4p0Ha4<z14*ddJ+PHWQXG6iQ5O`MO>*O;?jNm z`Bwe~dbXl+HMR9pNKaK^6=m6kzIuKj;ct~O895$S@Tj?<Py!lz7rh6(ppR!cY0<|G zGsjRnLc?uOZp}V&re`RG9-!yX-bum=Yvo&`=2W*qIC<+3g(~aXYBfnZDUeT$8<3p^ zRLt3E$wg~RDEbRq#$(`Ie>Dy2)zf81ET>3m4)DwEZ*#D;zK8e~w--ev@~zmCk^XPx zjz!D=&9_P?EA!K8pC2{i3j`NaeJ-xpON|Q*TIsUoUZ!T})Og%Wx9Wocv+{r@kc)>N zlX!GYO-|m()=ZXuLYa!$PA@FwJ1SiHC-BNv8v4BP{JJscW#f>p;?QO0W$lu}5E*(9 zdXA98#ufGN*?M6s%du9ZlQhX8wxRdqzz7^onGUuV4YJjSl3WHAb@AUprPTbL<@+p` zyZ)0ErA&EEc6dSBzV2GuT7`4b9Cf5_D*l-qliIyK?Q>NA!LEbv>`P-O+hqkYU;^)2 z1_NLOpf%M^?WxC}hQmH#xw`aY%ACnQ*W(XeKX1v$#vmJ#7cSs9|J3Mzu+X}-8VA=U zYi91@FTvY46sWn&KTJvjG2w)X187O8x;i~XyPoDji*|vMlEIirkXm49m?-|N<?>n2 zLB;&b5d%wFmRD8Jqcr;MaOJ>hX}(YG=uRk}uf?x7;nyW)*OpG0roHW0aHge<x$Kd- zMmb1b8;(8tC^u9Yz*1<Gi;17s=#lhyNQxKXEp2U>5$%ag@(fwn@o3zIENW7hPO8is zLoL0^A7Ej4YF24JygIqj2PT@bA$$oWS-u&F{^CuPFOtEohA5DM4{xd4D&@c4Dr5P| z6Hyhf)vhdE3yuNfn|aEP;UNTQh<Z4E@&M7X1jldC8dwVHJ+KXT#0By=ph?~hVaeNp zG$5^J8~Tr)Q9HYQKyg=YVZyNdM$reUIhU+qVK$+jO`TVgj3{7$sl*}Xy<WGbd%hbT zc9nqQhu0?QkAd)!tS_rE+VJe3uF`$b;WYIgdB&e-c|AFB+S-L%z5D94=|Y|}R~0yn znaf0gr<Wp5+K9L;s!royJ15Jjm{hZcMk1vLt`6*63t4aIb*mR`XUjUWX_9k&0#y-` zC08w!%FnwIQr;<50`~0@?$N;)l{tUZYN+Mw^iIb#>GW7<C+kXwCV&@b!MU;2G$KiV zSHazN2#whv#1E|H80|lv_OgLbjJ1rSrl@4CACw+gNsxv~>GLJ$oG3K<86ysZ%wa27 zS1Vf6=Z>5kP@^qhJ4^?w<$y#x!KB%Dmxt3ItA}4+U(jo$hMf@)L-@>Vaqh5Y`e|&5 zPRjJZkXLPiv^bGRV^mhkcpaZbWwQKw>&&lkKFUBZJa?p(%eOjvzgOmek9<6$9g}Ox zhbCwuu%iNkdD)V5Uq${LJzLh+zPo5ACv&<!VHV2fO83qdzcF7IM|jcc%S3s|e>vCD zb4SX_(Aj%}DqB%kZXbF4FM?eiWi;_3_+U7y`{QjEh7bo9HKvkCSKW<sbS*hY&Z<A> zU2t&KgsIazfnh?utU?=}HZPqSIDM0!OZ5n&>Poz+{~Q5}YVwdO{OI_j6WGRvT~M$; zVL`tzuNlucK#d!(<BY%F<U9HWpA{MKAsxb6R)m<SKU3s9ZKnplZs?u)R51r5jey1a zSSoApsB7B5pSR~^tJLKO?-|j0Mc4QKl;NGKKeQ?pA_G>LWs1*_(l`Pj8Qmf5p(BcP zCf6tWRQBf^R9TS%SW^z#bti<%@toL@-{{2u*z(E@eH4M?QP(1W9gJ^|D@cmxK_&AT zu<MgXdLLypteH<ui_iPvg$|~SmoOY2^n|}`&VIWk4(e*S(t7#O%)<KFjlSL%Vh)Y8 z@kyCZnj@cA?E|4kXr#DSTJlD3E*S1U7}l+(+!6EQ`Ll?GDdh#8G<~4zRhu=h&{w3! z;x3X|=^<7%Cv{1k;}8F=S3^yCyI+wL6nB#rNHly_8h5Z*vR^h=mTwifB4PG6_vaX} z#$8vY!{Valx-L<T(T_$y{HI8Nno>ywyHB<km-MY_KVh8=;taCeX`umIG9NF$e!Hir zU+Ixrxum{zB-s4O4*O*E0Qtkj=0UKzSpse2Q!uSvW|pmNPU=O(K09^&DkyxZ6i_m! zsqEpX+Ch6GWgA=((~BQJRfznj&k+}~4I0rLG4gGv5ATuX|5l9I9o4@?J4Vz~t^J?; z9{5act@&B5{Liodgf0A;3#YdAynm?r5J2h=(s<#tMm1Cy-cOI7IAFTdrtC4$r%g8> zPo(k^sZ)s-H;0wy!J?5M^@T+9{aqf`--NOUPH@=n@86yYZa<5bJa8Zg7Kys2%1<Zr zz4E^tc4QUv+&fJ9*+J0@|3pRk=rA1T80b8WUgxm)ZA<k*ntWN9D&2Jq4Q!Nubdm|2 z(0{g|Nn`AM_+8a*l|H(0P05CI$ki(HFnwUp>;u)5IO@hHZxxQ`p>Ibb*(x|1GJimM zD$xT%@%j3lR>UR%Y)yb^snU2ZK!3}35xEi5W0K?wL%Cd@MI?;U93Kd6_Xi})epZ7X z4eF+nsAy<R%#bS;)v}v25Da9x$<j?nE=AQQ1?OG4iQ~K4OJT24mTkI!lHz3=#EWYs z76fK4Zim!Fzo?awRD7$arVmXJU*AKYQS|{I*>4nmplfRsj2L05MY7WlB*&&2(MxFR zssrjd1Gfp0=hXOT(WNK~HU2b8L*^<0R9o*RwAW0?+8+RXwya0KpyQJ|lDD+1`1?9` z99$Jt0GGBqOOW6Pw~T`!bj^<Ii;gr8Z2$!-Fj4z{s*;*>{$E+?uCY$tj;~cVO82ig zr(k5uAD*Z6c)vHWP<g0aNt2tWXe=L(mg7W!{hpBsRt9+Ls9Wx4U7z%C+>-rB)MTqw z@}%Ryk<R>pcXosdVVfLv;l9~;O-_@gu)}U0gg<Vx(m`t6)+FX2bu0D4P7nsm^THf2 z7<@gFCbs9_<WYMAMd~=4G(wv?N)yqwmhYi1Y*-s^{b0RfU;awd{aAi@04D{N^B7P~ z?uz~VlOD(JN(9^Z-{}syquL1&lEE1d_H=n0(c;+QxdW<^;6(Ag;e|I4KX#re1N{pA z?E7^sV51W*d+EZba>R(7c$l7bwCU<6XPW$|_xY7j4_hx5Me6Ay6-JT#K+CN=1*L^q z|2bTEtVRI5|M(~xg-eh9cc@D@_+p~=0$%8Ov_1FinqSUw>kpY{Oz?KHyZxG{gpTYU z1Z=yOZu7y!a%+CqIF~%ZmNM?w<otf5LATJk%ZY`^6}=$qo+jSBLp5IAow!Qnyr)jk zsB^PrjN9E72&tC7c{%72fd?0&V`$u4CIWkCOl2DP!V2DGXy3~2s{*LVlo1UGIjV4d zrV$&q0wouozybr!`7&Y^la?Ao*Kjs**XV{p9?2UOa|SAO2(Ec&Pg>p`D%66OL{lO0 zyYnpH>Cjau;LOO=Geo{;EV%ms&9uf$Wg^NV<J&pOy}`1J#K-};PNs(BvAN7CZLt5n zo8--6i)R^*&WsPoA(Ygq+~*hCF5u|~HU-!ll)Y@GP>yMc+{st_l*b&zclY@u@xqq- zGwRE&gDEF>V)mR&c&>NJgB7yAmh|Fe^1IXDSJX`7p2(R}08}!Zr_8=&2wL#iH{IlV z$r%5#GgDlJC8Y;mo3$rC$N^iVVND7{?F%nOZ*qgPgNL#%Tb}LgM7oe&D*XnaOx=*W zQh*?EhCVhdQz5Nn0iJ4{esnb*K*<*Ap_o=mzeD+nZ+CKeCRQDQPsi#T8T}9-d2>b} zM4};faTp4!guK)Me+}q6p%ZiH{yC74q<Lvv(5~ynv8RUxu@xsn>rv8gs*yPqOLG4j z9f!^F(me$iH*mVVClu6&-d;T~f75vr7*XF?A8G;%p%b!HL#lI}Lew9^-UYif2qGo> zLfbqvDMPjj(8|Y4kIu`TOE=6Z5LcsVImSO<YhM~#2cPsa6=Y1cam&e)FUwjZhAV0I zRgKm=A#RIc@l7NJ5Miy?Tm$#s=)StmTN5?w`?X$U{Cs3BCwtN%TT2VtKA;7d--(0+ zB~v0Ta)(D4`dDpnKSa!U9#<m-by&!9|FF{^dGllPhv^4OEY5XiHg-I+<*Hwg>QE_n zyD@W;f?XTT?gMZ+dM$mr<R{t*NB|x(P}AR2pEZi2C%@4m*Oz2v8?y-gBMo`UG=_K< z5b2Ees@|t+`B8g7+w49d5G{Uy85tt!Y~J6}mrc&PN!XWFMMoc5Di^ib+RnaKxL+eP zRNT_7^s!o<B*?ka<~4!;ggQ2{mM0(}E6$vMT@7Jstm4L>W@}IA)~i-;NAYuX$4B%f zK*m)zV(VZa6#?WgR6~ysWhmX<M$Ej3?MF%xPXM|r1epF<W!o)P2rpd@SilqUfGVLy z%|O=rzw8-l;jV0tuL-#<ft~i6>sKQKboYXfK`2fTG<>6Br~K5{$G5cKVTtA@ZAB7J z)YVVsEOU%hjk61tl<sAYuAAPp{kMkkf`S6&zJ|_i6WEj+wc=)RI2%va>pxu21)pQ3 zyar1|ZQe8O^;9wccmZHQTVMtR1ZZGYks<=JM?2MZ2KLsV3tE5Z193f|*QL(Jp!TaI zE)c-doVTew>-g!#=leUi-zu=0?=sj3T_9SJ6-U`a6t8G!4`$n13j_Ln|Mu43Tt_t~ z=0w*W^#WqV8y6c$dp<mLJW=wQVAf!E*wk4wN)%XY8hm_>271evByC65UASn1@u(_L zyHQr|81~<m@iJ~lZ$(hwRPFX!-lfCK=mj@#cN}E@#cvHwI_+-`vzCDixkk6={t(;8 z|79P<rEssk%3;7j&xbMIB5Wa4enH;{Se$_20!RSE%A*Sdq*6Jcu!zK(uZ-Vpx{4|+ zE+89&5H2`L;3Zf#$3rwRbgIy2K|kZsw-xm|gI6<_;9|NaAxfrdJ}wvoU+!_XY!zpu z;D*Y5UdCW???y&{5fI8?N@lIglK9nav?>Cc<q8GV!LE=4x(+1e-|#wB5X{lH_T<eM znG^XP@?t2OO6+Y#Hz2>rcGd+K`AgB(zfSJj{II%DKli7$TZTzo<{=4FByf+6(l1vQ z@od^Dlq7pMmlmxN=#^4{{%$;y;i8`~$OzB}m<X&WtIkk)K^}*a4In|PCb%8i1S+fV zBVnsr3O!3kO>)*$qCw1i!<2OTunkSU^Lc-;o1D}=ly=g@>jSS#3k*&7N8sHVAKltA z{8ga<;a$DTSwdDe*S%a1KV&jp=6tNhz2epEh-S)^kZ%#6s|;yS_9@7;@E9aqVLm#5 z!MHf#8Zgy85ELUwK8G%@D>xA1u{47_V4<3SWt<_~Gi#I+IO=d!??Cvfgiem8FdJ1Q zVw;=fP~5V`oE>Ap7;yzylA53aV;ZS0U5mLAw@;$$xlR7Fi`UkMtE{SshC4FqDo=l+ z$WDKQ+;`Ki-W;^)3RJ~-&>qpydf|FN*jpQOe70?KP8MD*!nO!D8PW^}o^10^j+LS- z=IzCcb<<Flfmz0F+S*R&N!K&(v)Nb}kP4$WTe@{s(qN8OOyT`zvf_{8R^u6sb(Gz7 zpkE0VsK7E{08o=Nj|31rnAKLl+mn`V9bufjt!!egkh381{2P#%{%>)W5A8brhU005 zc8r{qmc+N&vPXm4Tk|$-)90<#%d?32+3|-}D1R31E_vU<?+L+16fb#o{o1>KnFdQ} zO;af^ouh(yvf&E?fadf=yP<E#lJ0U;Xj5Dcif<WT@FoH7vExCLrm3H%YtI6@M*hbH z%1{K7LXz^!(l`&?Jt(D(tdXx0R%>4t`l3*~o$Wl?4SApN4kF7eIFXdyrFFbbU8m3( z7*Qo^7XD{vOZR1^=n_LaUfLMm?p;cMN9-g7Y`;#J&HBdom{}ej&K<bA9S6M*aEBBx zfiRSldx;;R<*I(0TvR@d6t$wjp!L7j->AlZn&nbPApH6n31AmahNMr2=BQ!;`&WvW zCyLMze0QEwn}lMHM!vNR1@{p`$q!lDho)t=KgfckmcJGJHhRy}&hlDnUU?1y7L+zd z#<N||^G<Kqc!A?@xXUMlC2!!gFQy3V)NHu6?gT`Z=KbSxT8;~SDNs{qrv*9Ye!uX< z-uqEPvBnwu?*$qWKQH@OG#F3&zTNo8_m|ciy49}`6Q5`HQf8B*9aov=A6K3A@wg0- z1>=Trs!gA=%Jx;tU(@&kAZ`R!T*F?vRy(|z4n8$DP*PUVY{;!X7PpN91*V~s&*x`M zaOcw{l+hp_-3bibO*maJ1Y+uU-edd&T3d4ZOhwnF%PD{Q*F7G+j9u$_p{}wpb9KUy zh`ZNJ$q)2JzSlo1-4^HQ^4Lhn7Yk_gjkMZ5c#w_jZL||G6n+0y>b;-A^LccGM!l1b zYxJGTv*;7~Bce>NNCHIn=en=;BHRlL*+I3b3e=bf$Lb7gyNUO5RQ-U=!_PBr{>==D zUHH;8fH5Uj{eH(=1G?raQ8Q9it#;?C%Sg2!iDd`pL?oYrM@w<_;7l*UdI9DRC~y{F ze6-l0CO*r^9+Gm!MOz62Bb7J-@{aw84%kHDqEmuIZnL}kp?hr5LSS24aY4Mnu^fsB zU?lGsxGg9CYs#caFRF~j%MHut?0w;Ea{52U=22j|8euafaO&;^oty>64l&XQp>3J@ zE<a5b)Sl5lEMr_2k;y!4e#k}^(OG)zrt0wCz6Ymu343M9i&xUcq($@PTk`w?;=eHD zDP(Dmvjf>4x98EpXe2SxzGTPv#+EsbOyG4wm*k;fC0OM5=#2w$qJaM>#7$j4QbRiq z4tES4JTAf^BZ1qM4z{Tfr<!T6!G_?0&01|@esgY<PE^Z&9Oq4X?e$}|qiSOe7v8n< zu~8F%Dbaf4k0tx1!>*8mLxnD0*B!`oVM$>@0Hr^3c<N#9TJo;C<<t*dWn$YuYprsO z1x2I0!hQvF%OWBD(BS!rjD5B^&2ksq$kGuEJh5bhU`&4sWfuk$8qT(M1Xl|P1Q%%s z&vt@<`9;B?HoH$Of6@qOs*Vxqhzmv%J@RWU32W)P<Xm0&4XBpx12t0fyLHOEZty&z zH7N(F+p}?MCs~lFKYVh6aXd$;IhY^;fPmG9;to{gxXoXWY-|iw)R`$w@5e5;zVKVT z+k+-H<q$_8mWC|sdZl0}>wb3(E@4E?BP>@EO~h>wNE=$e0{fv$qNG|VjBm*P;0-Vv zOg9N6I8oDS4LUFw$CJ{b#kj<1ORwp=MFSfINza)g)xo#r;Dq2M>s(P{XQ(DXHY)kF zuShKEb+Eeh{-~5Ujom6_+~WCvTI9+sGku!*THDz2{_;Q&(5flcb>qX>iu&Cfx-%`h zbgC4WBAi6MKKG8`gMV0m^!3ZAOz?{72GY{6UwDIwHLbf;2mvSp+UXcx(JC<s;<Y0x zqRn16@=1mKTv-}fh3yS_W8TsoJ}O9=_@Q4-3L)45fjWm{mGum?6@h@5M_a*5wTBP0 zrB%MBe<JD^Ca~XCyR5-ic>BslY5DdDVk_cCTrm3$A#2#U{(8ow>T&jn&Man<_epL# zP811|aM^_c8JGwJn^b%?Dd>1{TSUUN3PQk(-oH^XY2TE*DEDOFhnG3Yri-rHRRRP& zK|i>13U-?b-utxHDR>}Px=jbyrjaBdsJnz@JJ#H@^>H*HRxu4UZ@@Iw$T7^?!sXhe z&xAmdR0Ug5$G|{2Nk_2Zsi`|Ixs|00);|X}Fc&4C+y|{#;`|yqlm0$$CuW5ZDvlS{ zu+*Wc#(q^n=xL8w<GZKtbi4nnO%$tLly<;lCr1^8Q%%nC<?m=pZQ!7<_iGMn{q1bR zdQj0>AmpRNW_GmCri+*a7OaFP`Kk6~QuyAFGb+swdiB|!^7%Rqab@l7!y<yfmp}yL zErGX8aCsv#x$t0j>E)I1EBqN<!sD0W`g@Q>8qcP7s7~7hcTi8s*@=e#rs5T)w+`-f z5Cfu{1#CYN7@LFyH8Rmzc%ChN4o<|3(zVt#0DGHk5n`ntnKZo6nJ?VYqW%88bLE8C zVvgdp!$1A%hroh~PrrZdR~;@kuH*u?Pal~8y36(aJJBY)GZA>>N>X_#m(&^}-d7{= zX&=7a;dgU^g+!BTTSjms3?QxIY6f_#*k3UM-sRe&IBg?+u&0?Thk^z)-@6+`b`ZFa zEk~&a1K=-<-w1|o-tDx2k3{222nDDQe=l?dAf2S||F}h*iAWg`5RMneL>4=*4c-o1 zavrPMxi?zQerz7dl4+f=`%2Qz*&_H=N$7%2DuTn~_e30%jQDQ=>&L>H^H9<Fzw@ow zn0jtc^M{!uBrI5h!$i$#hwCnlCPex_B?(LEQD(brcEDo6HQ`?p51s?J>(idvhJJ+( z%q3(83xG=~+1j->MOo11e;^=OENJsP!A*_0<MBz0{QYR$KAd?jF)wWU>=L1Z5OSaH z`FCJMI`&BMhmGoSZ4gH7rtqYCu-tFL$J-A@ZnVok-O!5m^3VN7aO{^<?1%E*aFg2D z<{(Ur9d_9DMazvW-Zk;?Dp42SzU!$uJPGZTCCiZ~8wasYVG?;5?Y7_=jdh9`6fFE_ z0ZAgsumrRggoxRw2fqk51P1l-Q1NQF?}y_$@<y@Bvw&nEi2RLEz2bH*xI-5XNV*Sl zHw+r-IL+=uy0jYOh@YixPjsu(6cN>z)QlBbRnf-|-w^)q&m*p7^;luI$-aJx+IAWL zZl7!;a`;?P=>;qYj|i`nn#nuXe*?SY&@X$hO`1`KeHmX-&%npvq1#N;459K7*z+a! zBVDjDEWvYXYyJ~=GiL()t&)3dmGCFfsL?xd0EjnWU(_9-JLkLWu=VL;?pDH3Hv}Y$ z0|IyecqC<W4sd%HGyh{*oBe|^sph=l{{9Cs98(ZX_&FS5^B>I#=Y6_W8}mt@^|!z@ zxjOWty;j>;)`S>P?UrL%Z*nUn;$%t08BX~7W+_cIP32zs&$;pwJakq+X9!s__O9HR zDpkl63h%%2EBHRf=h^EuD=a!7?;`K)7eY=mSBNaCPf$67^m#pCZRmXQbq^&3ycK$w z6**Cd#g)MUn42&#=AE<St$!wQ$|YnB8tsU){d6>8y@Z{&mOLI!uko-?x~Ny}>|Lw^ z*`~n85l@Oe-ByS#4H#H(vCh+Hzg*1Ry44@TiL{`w9}6N6!;&t$R}O_q?otxOZtJ-8 z?|x>1YKjb<DydB{VHt^gl%`$wK-%<6de~Oqjr_c(;n+6m_z3Itw2b-N4c9af@N+?Q ztupZ?PS}Ts5){|fbQCsUHdL}ZYnGE`=E*K!VfncXBi;hoz}ZVOmpl`)-t1Yi9Po`? zCkRUD(nuV#&^s@2ZIR(4zEA94|J*f;UeS=UK)6=M&8t0d)=dt=w2SzZbx1f!0VKbc zx0k}-KGzM!-`x3j>gKtn!d;$B5(x4EkYV)Sw8Hynok|<M;p2+OPy*2|RbwqpVirrT zt(z)@pyUf5Y=ri;R<corQb}1pVt<&TOAFuyUg<sdDUBIjGd?28j~G&YR{y9y;v3=h zTrr6U27m)F3KHNcggRd%8cBty#{kT^!|Sm+gvZcZFy^L;<@zZ-JtFRgb1I_$<+0xG z;~6>xHPXcd;p%4-#Bc}6=GVyb1gtK(6n|J!`_nICc)#S@Z<VzdlF-4*|7g|9za$kw z;9r0Y9dA<hSQd*H{{pSiD?MgYC8b^|oKz*=eO^Q^%)5ep`0kW3LPxvwx~}a3u@4JL zJ#^6>lBT%E7wH?E=s4NaI!oux_ILaNOZ4{G>JGRn75BIv?Kwva04jw-2sWlq+|%Or zQ(*wzDEjOuCq47b6<uP^J15A65>V>i+#fpO9wBQ-J}(5{{ck|xL#y<^=PkQM?BP{* zpMFogmm`k7{F8*o;1)z-rzHx%ijRO$Db)}4eWEPpg$5S>_I=j+ckSM=Dabd&>uMC` zETJxz*lBlQ&+F<X$0S3|iHkbmESom_dg-%m(zm`f#Kww&V8DYQSNX|0zjAPi;b;JK zse4_;_k)dr|DORuuGZ|*MYqIr?~+xfeQ`KF^>7(5@z$eI!{6J&gJw2~3dUDKgA&q& z@tt{flPH$tcR65Ap15&m;@zF+D{@ue<g_>B?mu|>B8G}}sf2NZB(gkF&5K%-nbOP! z!5Dmb-?*Aq%Hiv3$!Qk<A@_SqR^34#snc7ETEGH-C^Y%(gRx(T82kNqDur7vJ$TJN zSbit#5FDUr)HS9R0fC^-MI|rC*#O4}R)l!z)PP!3a;e{gtQBk2*Mwzh&qLOp=f}b5 z=BL8ro+A3X=G_*o0k7+7;hirZcI!V{WIy|yFG0F3@#*#pf#8;|zgk!R5hnX|X8sW7 z%-3(ONhaaflJHV96SA6Nub#Aw6a1u-D}`e~670_LW~1j<v@A|{2up0-vA@)DuG(>@ zL~T9ULTsHU_7VW-Oy|4R$R4PXrHgg`Mw7<h_zz)vza;?LBO#gZ#DUUi>gyrhH%|;- z2jxMZw4E%8qZ|bPc(Z)*4e&&b4vBxJ^0fGKVC~c@+(-8%_wC&{wdu$0|4p!-y-r$O z@_8c*)SgNG=7$TXR=@rIJeBnN?q8j7NtsJL2qs86vPxQi(QTqmVtzeq(q3A7H)Dj; zoE~M=T^P4oy1EA+TGM<#Tq&1l_Vyuk)a#TN^d7ZP8t~zbS}hrxPj&rQy&tqImXa7y zFp9v(0rCjBE4pYf6c7XSfySw+g*&HZ%ufA*>DP`FkoH|NkBXxXBIQ-p={p70Lv~64 zQ`M0WXMZ8r6Ppe<5ag8^0&|@vO&d<OX5i1jf<d8+EuD;~jwO#)l351?VlX52K|ZW2 zB3T4w1fZ67#H#w&T9a&LFf!s<aaddl<&Ns_^zyKMq^5(}6zsI&(OFVLxkG`zP1dYt zz^&W)t=7#qDDHwL5XSXqfei%#M#ltP)Z9pbx0&VPEm;Z?$d+^!2vn`{NM!+kMoU%l zu2_Qq!pb4QNxNzq^3>)`YXe0Uad9DfEj4362Co**t3<KKUY#AkY?WtevFjZ$W5UpE z4xFVS`&@Tzu-=IPWG!RY=(b)kXa&_;qAT5QOl`S{%4gAcuGnRBXP+Mie0<<Q!x?2s zpa!H{q7ruPqN`f`N9sk&4S**Fu)?+onfj|n!s@r?tJC0)ji8ae_j%R(bVk;|_Oh0m zi=$fAeZ>V4;b~hzjD};Oo{X-=k^^>k&&=8>oqXAk1q3Et?Gymjx+&QS5XwUu8HIP* z?<(DSfg%8ha-0yageW397NIUeaw)Zsa?%yE8gsObNaBoB&!aF&A^AZrY(^EFDUV2t zLMiRS1y}5D!42_8TUnt&w(jcuAZy~;64wLu6YI<2U8k1EcClk%K+EtsxcN~3sib|o zXwU5EHav2?n%X@@%hqiFGn0igGjB^1w~J!!xCqnz2@_fPw0al6v&V`T({8kp7o$66 z4AlY7#J&+6`0w`zu{ebRe}%D8Rumgtpl2(6P+HTiLQt86a(e#E1#$w9Y|00VHI_yW z%SNO;GLvxvfMiJ!>MHG<QIho_Qo<GLY<gxkjbbHGyebP8=3JwcBcM+jkOIN6b{@*X z2fb7>=L>p~51-dk9QB{MXw><n`rYhYQ+CPmdDQrUp?8YkOr4q}>{GkJFmRCRo0?`2 zQs<{Lv<K#^WoC&5FI<Wgx(>UfH<fuDwoRW9K5Ul^OjS}t)8ValMUo=S%K#6~D=*#~ zs(|@-EXf)Pez*{U0LtUo)NEPO4$DFA=A>z+e6K;f9p=pP&od%w{Eb}_u?RB>`LMiz zcT~FeTA9f4ru=*0Z<0ZFEa5FK)!XJ=70vbtjHi74_*N4o@|uL~jjp*Yho3zqG*MiQ z&&TTr4@GdI-`~=dBX$BKwDGL651UTftuL#E1C|G{E{TP&0HA9ml#acEvhmxJEZoOv zjeT;!+xn%loSW+q%2yq(w4I-E8eS`Qtkt?~RaeLfc@rOjlfG>0*6?0>*;Opt=PKZ$ zge_{pOZQN0aR8In6~m>=XFfRo24FFp34)oAQbd+iSjjPX^U6%>_G9!qKZ*iy%j~>h zfbM!T(ItK=mZoe7?1+2}km2KwXsYHX8HJt}lo9q7nXyP6aY(sETL5j&XnGe_%Vqgo zrKAWH{saY{&C;x<$inyBF&~$FIIm>#dM3-O^pTcAyql6M?SXN-FfePde+odsRzM5x z!;gL81vT<@FCB4O(HCeb4XCuEE#y6I1YkQf|AI{Dac~<Cq>0PVmf=|BM%NqEB<~`q zM3sNHT@aDLq^bL`5}?82G9z*6)uGGCF}=rZ^CbfSdLtF=TSJxIG{5d)k54e<e%}@Z zQjXu$Jfi0vYB<>WFemf~fFha9w_36><35w-a6$lH8}M((GnZ=_ltIdLKHu=EfnSru zvwV$y;hnuQCUw+*`IEU5K@r9VBbNq#k~Ov`6BHKr>j)&I{*G&KRhwE&;l3M$>f*p+ zE@a@(^i-{S7x4>x^dqzowd3D`e__a&AldB$n(cGIn-{5=A4ONc4V{;<_p~$Y$D1Lb zY_RJk$XzKJzhlE*(!aTyt?Bog?moh0ahBco)9e99TJ$u*{^uSUOx;QPjX5IP4C!{W z@|$fjcsiA~Ytc`<(t(dM9+Zv@_cWgFB;IMxlyILz1r<8ti0%|y!mp?EV_b_r_5`3- zE#Ky2exjn9785&Qlllh=6k!;$IbRBNUoFOggJKq;Gv;sAIH$h$W%<5MzT4OK<aEW( zmLsJ?@O2}+w)ztU`1QT@UW6K_svVhmC}7L-2))xL{Tm}v-k7kTp4p~k?|t0<9lHHE zC$-=&Bksz05%zFahXU0{s^{m6yk%{ot04@|s6=I}R)Q&phfiDODCU6{05E9D21?Uo znd=dGol7<5w8tQ-@pXdU6$Ku2PXAXpj|5VazrKnVUHqDRO5~x{#kmKL>d@}ftee!^ zAXsWo@LimwS77p!{2zKUEF`sA@frAf{z9UL!chiE5#$E%>cAJ+yiqrpaR5s5-5q>` z*x{oWUV|vv2qKJ8zgB?S4GRdi0VC%AEA*=m_$pqobOAP))kz5!c9q%j_?^nRc2M+U z@PN8;m%6T@mJdGO(qBgH#YMMCchcp^F7KJ!b1FlKScRV<b^~OTO|-J^XU`-8{vG1B zDq9{gEqul<fx<d#LOkgq;jPLjwCT}^+jQgFyB2onz80ysQgeyBX07o03{<G`JhcWu zy~}e1z})X$clPUpazqS>-!{c7H@DF77od;I^he+ilR}oO8uo<#)${6HD)!k+Z(A_a z2k!lTmE+Ml`Y>y{2$Y{0_;P9Kv*qY;>aHQ&MQi+_UpsBAVR_>$XYSbY%_wNF;eC5C zo(#IxPVr7i{=_2EY`jd`;yrl{yOux~n_{@Fnv``?x{y^oXvuE>P(o75IwD>O;0gjY zS(-ym60hFsS66TX^&TUtCL?#>36=&7iNc3h6fi&f)7OqvDA1t<47HPo_Qwm}Y@pG6 zwL7JM>b?F;0tg63A0vBd($pL;fIsiW8z9|nY1fEGi@0#h-wYowpqaIY>2?UjhCRFK zXH-z^a?l%37&5h|E`=Z2%fGIL98Ii*sQ3#q{!?6ZPt*DnNzD)eFihsrYq=?D(hJ*2 z69vG{B{s9}!!<#*j~E8HXuoi1NrGxbxkUAw@&?!Q-Vq@TP1OfGC3J(GqW6RF$b?kK zavOwaWUGN*wDrmov3KqM&hM*wQV$RpT9FqTjBt88=LC}WGTbrShSak{c8_XopO8`V zwa(*-ZeqdY43urr6XVDPgNhZ};1e5Mfr)awK6xWj>B6zmw`?SSmqZ8Re8(6=fw!yZ zKLt@wBT#;|5e6k^9)d98m<VU|S=AM}NKT@ltGf7-_Vqc`*#-+_{~=ZbDrGiobkzs} z((I(z*XTyK=$`!b<6M|eIw)Cq$VKF|3o~yv*{R;;YXk;?m0A6w?%9YB+ml#h7;ru? z5fQ{Pnxh_V_3ct|mRSr0aPGv-U@*v00iUA80!B92_ri}ESD6Ze6eag4y*r+I|Dvu8 zYu`ab-6JZ*_qC|w4>-zgr)<9_c=S*f5_i&kM#2>I;uCtjS@9=}p|Dp>#tMjuL{kPC zIYZKv$i{T$RJu%j^g}{M*LIxprk6rL+;jU-@xlq>;wixbxo-n<V-Sh6D4LSq;fzMl zu30A;JwI@~f;btqd-<v92p)I<x*UlDyJUV6L?ZD{hVv*@UXm6W<+F@-$#+ujk9~lT z5SH;GZ2DkJsknmkiJfOVe3G4O(hzOQ-GDS+FKnjO>Q$>Zaq--}Jz<AO(nGe<Dg6c5 zt^}vAVUhiDN&|ZX(23QdsHpI>FSdPNsrsrsK^N7@AFn6BRYg^Xp|Xt?R@#!@*@F3< zs(PiFw4%IwlBt7FK_r&nMZq04K{U>?(TTE+_Aizf8C4bx(%~4mDd@?WK9iLx)MoCL zL?uZ^#HTR?jSkG6TrtAjDTQY*BIH#t{mF_CxR~GGm=;~DAprJdL)afi?D0C1C~yI} zX%SXnm-9{HrnH^@E$y>Da^mb`w?G9-RXS;<z6yH#w3gB3;ix%1jKpdt36-hf3Z#1% zpIZSw4ud`y_+1@Q=oUXNeq6;O(&XOmEA3<Xkvi0?6Y^n%h=~>dwA8F4?_?E&0vZ<& zJra~eP%l={y({+~9P&!Y{F#<Dg=E12t}iBC4fV;l^n<-7zU^FAX5lykLwqJB(%`Dp zkH7A=--_%8rW!VF?-(4woJPjO9D>Zvo}$2yefbh59?Gba4)I_0N`j!gweKhm7{Di? z?CC%+Joxv#)LDH9vtB_aUf~ej|AIBnz}=s?d4`1ME?-1r8d2Bd1D+cwKN*QWDzS^t zJoS)m#HzZAY|E|zV9RmwU#_8C4x`eq31`wu74UU=Ny0l9a&FTwKB-0$60QhiZFYkX z<rn&9<5?ut!ZfR<U8qQb3L`GWz9~WzR1LtJf&E<(zyj1P{)|9@nZ|7eW5de`7U*(v zF^P;K*j77uI^@)&lm}JyQ00wv3V8`C<}gf5;qFC)romC8OJf=ZF)eR1$W><>Ht`Py zT`s8Y#FK)B158iusGxii0KfD)-J=f4Dh&|NX>C1sgnRYC8rsIM{%ZeKTw(n)BI^3I ztZ63og=&M;8v5iEHI~wpP)QS<7KFc((kXG5sj>#9JY?dFg(<+mM&qYp(5E1jSyIgZ z7&;HXq}n)&Ul0(S;L6<<_bPYJ0!74`nwEQI=E{|o^)>)e!3pk64QKA$sVy}$SLUj$ ztkl%ZEJs#mmal)oeLnYd@AKUIJLi0l>JFW!$<}tZG}4(WtVZL(=T@VHYO>j7)EZd~ z>ifc_dTP>QsaQ5D$gVVRE2o^{!Z!f`>7Arb$IB<WTsp4Q_D$UAEl7PaR(sDN(^I~3 z-n_CywftE>%A&t$jCg)5J_z%<@@3HB>@zik{^swyq-9IsHbz2^rZ6h#5ZN7zuWx*K z$pG(uI5jipu>_ZBdx=C(H9;92WxkjE<^Yj@u8_aUOCZx!4&PWijdpFmGW{L%woOdq zQ{#oc)Fl?LC@=7oohb{s4LVgQs;92q#9R#%I#q!AcmB3(S5wLq#!syh!D7v!jt++k zjY;}FKT+_$Lvg#*^tu*zq841Iq;s$d1mnE^8kfA!#SrhHVIgSGn;11Dz^7#*4n|`9 z(97&r{t7|9B+rBXkp|u9{UE#IoTZ+yL)b*&b9Zwri+wP<<z+(Js156SPqSJxc3|az zvJpRk=FhlUK@Jmo|K-4}Nk@nAz0_)TYNw;SnD{d{mh5==X9~W;ydJ8JM7}{gmT<>1 zrB3*{gOG-ROw3UvpxwG>^i9Q57Zg@Uha4{llx8!a7>EE{XthiB-WQUSBOr@uL(DM{ zkl>?!mays&sI=~>MdzGM@O3{piIU@YDv)S8^!%20a7DXJbJWa__Oa=XgW643D@dZX zNbxVVO5?oud4PwG94k`-^?q^J7$4_Nt?U;KUoMTq%^gv<!sCBEl7+;{X`fsC)eCNb z(ZET0N_O%xMq7`G+E6L7Xej3b!~p0hHz2^=&jh%L*%3tiT{d$Ac;+r3=I--2*>}Qp zd9=$26p_#VhvU)S@~om9Exfjg5I^n7XnB*T@x2K)@@e-&=Q>&I@QOzskA{%E%e-#$ z3?Ux9@_*KQgCMI0>)$C}Wy)b0;>iy*;Y5Oe@|94u>uiCnzp(3Ds45exJj;;9X@lo; z5EPfobx$o~wOeb^AW$l^FI`3*q}5c%2K<*u4SglnfAv?L>&Ijiw~+k&@d#F)Y?Hp( z3?^;r)C7~Kx{<F382b9Uwy%SO7{BrB_n;!gI@5?3qhHxHL1r}LWmz`cn<D+u?%ppV z&o*BxQ>UKOiM^uK{eT;IgO6~|#!yUyn@(IEpK(NtVKgD78&&AKu)6?T_^`0dWBC$L zJG5}#>$bV{@bH6!`_Z@5sBMnhibmY<#TW#o?(n95(pz*tHNSD4_bD4W;mFq&b?=)0 zUcN}`y{;N<hY_Ca#^P%mKK?wl2hIp-eL1i(pA}S&zQ(pmVC$-u_bO}Xj&1ny<7I9P zrOWi7KVGqr9*ULIy${6$N5Uo&d+iXINa(nb+&Q!=4^a1(Uhgj3#}(z^AA0WVOK{Es zTOyfhI_TANB)CA2-!trMVaMXQ{+G@h5SYSStrxKn-cmb`WhzIW!s(O|YJGR06V2Dt z&6Cb7?ksq2&wul>+>O-Q8Cm~B5*2!J`B$_~nf+IV-tfHM<zN4(#Afc2ZnS}E07sfR ziT*P1U+4F6p6G~%9L#1eLFL-CO<Rvrqs5PLmG}|#BLd9%2gd)kWu{J<|JGfhXL}+> zU%}f@y%RmjwUjjBDbWUm7_aBlQ2R_$-V77<T(Rkf<261q$p2F7@&iqwhwK*~-m+bq zLkj=y$w7FZb@MDUhM@MvisM$3!*%?WmkU?%wT6!~^xfO|0JJ7F!q4=dbGmnJq40{O zu2Q#*_6X}8h9Zr@&Q-0M$)DsFiq)7{Q$gQUgYA}lke~aYx8n*uVvhKRd9hTv%>6J{ zFOTQ!n+V>t=s$^{=iWSS<d^p01K(rrX`-*bH@>X?Xzeq{k0g+FDb<co=)n5}A1s7! z;jBW!+S{Di;Rv<gR8v1!<eN~3#C*(Y=J=JDn8IYsb6$55+R%+ThzP5Sr)Te~OR<VQ zvnSIy_~6d18$}r0*dpLqSY@Kz;0}6yX}dKcGW&Gw)z8XL+~*oPD)k$VOjd<QZiq*} z4}4xFD<S(LYmD#Zx;#INbJez|*KfY-9lDo1uRQmOM{bBxTstu~pHN)u>XG@V^5iXR zys2@go#AI5?ZbD<Z8+NL<rmG5zCveHwXEGsG-`~z7$+Xx@zB88>A6Afe_4^rVqhoH z>Oo&}P70rLf%O?pKK@=^##<xux6p1JoKrrTK4Uti<|hgbygO4g^Caqm{9HSI=K6S; zD-UlYPT;?8o{6Z`2bx1zhi?Gx+v=4qtK)n#4V;6~-wu|%xcn9and0-C-s5+Z^xW<A zwlH9=afqdi^BE6pyeA%8`=ihQHMuQ2@*)qz2eI47Vk>L_?PnH+kI63<W5ks{7*wGj z-#W-u{ly)&qNiDMX{l|f2~@s~L58k=<P#bmHPdMr`Ud|fJHAiP<F96--T^PV*7F~# z%@Yp_ad0~okGBv`TcwB5y-_>Y=016yLqEj*_!_ZXzU%L4H|V|ggP*m=gsUB$<esy- zvq*DSvlBVgdRHmVGW@}!VYjj-`qzL0bjjw6#2kQR?_4}AU!{t6x=;173c1JC%lFaq zV^Q1X75llsZSS|&8exq~(U&M6la3OPkENKE$^35JPoW_yyP@co{rQJ<T*@q-29K1m zBca9WB9f);Co6bycT@NiFd{FV#I>2A6n3j4dV!S1tu3(nLgyncMXVwXI`!4Rfo6F8 z8_X}|({om-DgOd&YT4R?i(7H`yrW<b-k1Ppb4}Uiu^bDe3C;_kAmDdyN<0_}aAEXG zO!4KpWzUZ2#nB305Dsvoj-d6T17^Je?MI1lFc4%FIn}t0>x`x3Q36N#ye!uF$u(S` zfW|E5@h3O{sc4yx?8X9VM04Y6>&eO@i?jksda|E7wHY?rtf<xCKr=iAjoa3ARl4<9 zqtedMR6#q7v+_^6xKRN}(YOK0@4O=wO?}P11pT*nUJmd1@Y;l^e&gRQN*(Ixm23}v zV3Lj$k`&)5mo-}fRge~kZk=wqEh{yU%xVusB6}l1UO*ICkgQ47F+@VS1;8(|+vXzC z1oq}otsI)9#S4fC^+M#35D?0UFPv3Pjei*&&z8}hOa)CPLzBThAszlUie&W~Tk-M) z4RlC0Cbbul<ObR)QDFo3(0wMz+(?x{LV=fG^=MZH0lT4`WxP|3O;ua@CN+O@Q;57d zViNrDJ-Imse3MH3s`7hDSE!^snXsJk9O!r=NNq$j!GoBB5$$4WyWZOPt4P~kO0alv zf+zwCk>gVnU*_n0UT`HGg5>*A_jt5|!^*{oI^m$CAeG8i0sK<IftZD8wvCZVwW_6+ zNj9js#zk)1!5S@RQX1cJ+7hc~2HSCh6FMbsY1j<8RkhHDJYO(|z>0`{?a)Or*hG>) zEnmB!e8t2#tHMy7dS=vA-T9Jf*~=7OQ4QgpmJ$bI?@zW(oOuj5DdZ8#mc#HgKc*m? zxbU<$RjcLw2%d|ez2KV*>;uBa{(YWDy!?C%&tFf$10XK=Fm=})qSXU*l$3a9i4PF{ zq^RM1Izn%nN=At*;$&Pd_8j<Es8gJ*glRT-ODR_1kyE7vOlL<yf-Q671Ksa>oquR5 zemqAlv{Kx1;P+zQo)10xv(MEFM{Rubh&pbPCza%$macpwiUYBh()VnD_hmW(wDzLy zs=HEe!~<zZhq+4deA3I!iTwb3I=-fAyvOHwfj`I}ag0)r2BN~s1O94XjVpTh*^kYA z{b(^;408WrV%c%$t`ff!{judT?#H59OxCxz*|klw!C_Q$!T&tAAmV?(>Ez^0P|fnP z_!wpB@w0Q^MTmzxsEUHe4_y3OuO#|9{Z_fW&^3&pN(7XA>m(JEO8O|iPMv+c<lMQ% zr*Jar$p_N($z#uCXy;9;-L6VvHK_{JtJZUZ+d?s2@g4rUw^&c65SfVs9TA`#eqbp7 zVm<|lN1~y;d*(J{RI!_6*u(Dt_s@XZVpYfF6EJcO(3tmL`>u<nt|Z>nHJ_q#4#n-n z2h_aE*P5*gG=KqLV0zq;YjsZ2!UvB(=vSZ>3Iey)Z@os(Ytp6#fphW$8iv!%p|1+Z zr{}C~VcSKQuhEjvvm9n|%`9%jX~{bBshdIvWV`&(z=Js<ZqH~V8f@r#vxJ=aF1=nz zKp|X(z$2F|Qcw#~A;p5EgYVs%<ChzgP$ATKF9hu{aSc@7Ct9>10e=03gIVQEUN{(8 zu89X|_jr#7&S#3taq@#)_@2jA5vhf#X+XY<%(p0}k&mWc*`(m_)hx8x#nB8)hB&CZ zXT?0`uIlx1epYTcXP}U&d_3hUs_=?j_ft_v`xjSjt%}bdwrYU-Xh3)@Fbw9=A0c4n zl#tqz6=|ElTo_|3h2M7T{jrES)Um2ameyD0k;dzukK_9C5(UKa*j|MF7R7g&GxPew zK`~@6YBz@YA!HyKCUNUngSAuLH;xR71&CngU8t?I7rj$o5BDO;O1tae6Jv(4wgnnu zzw+Pgi7C(n3H((cSZ`1Wz9=EvvTb2@yy$}5uc@pu6%n~hP{jq{Rcc5%^}s0ElGMDD zYbyk!4E;`2Q^6bt3WimXFZ?VVJG0OYTgswb8b?DI=zlY!VW+-4Is4wadGE!bocobf zkAT@tE`SblD_1$18<Lp|-X}Yw8Qpj?0^my!1$04Pfoz_B>{e(hN<t0jBFn#;ivrJW zs{*sj+B8@|@jsSkf8Z6SdD~B+AgL)Q$193}_(fx5xvv36P_myMmt<4^>VsU911Ulu z58Op&VIM(w7rQyGJGx&(WDGKM+MR{3+L20}b(v!uv`VgOO<;Z90l?W@b-no}-2nmU zAaySWDGZ3;xx|c;CBXCydw2>YplCfz0c=A8zZvbPuy+ZxlqKoqp~zl~$z28{WPm_3 zj2m8iABN(ZA~Q6o(j?qP+=f?Er3!69|8#AMIN+g<b(!5G+V0fb-ncZudW<p@ZHqzx z?OA~%6Sh5mr8Kqj@sxb&zEPxmtk=ISSxi^v6BsKaNh<RdEwKLB4RPm#$jl^@#&r18 z02#nX`eS@-iFPw@Zd&*Z`uH4RZc+)UJ_(3}T(fZwM>W`xhvWqV3E-&=>c9=1QA+sD zB<0SL2usuFWwd8^g=|TG1hB`-MqZzTj`IfyPVC$EE;bE!k^p%r-eCIMS2&5SBO*P? z7Q^tF?66i1JNH{^j8d~=KgG7!yTY6N0q7O)Av#8<nZlU^&u@oFj*h)$)vYQYU7z9( z#>IQRlLU_QZ!(pm&``d>+Aojl+}+OfeTvvUyvL;~nUg|CE6j)k25M?R-5nzRwnBsK zt+G3p1CCFzqu$_H&d0cZ*K2$}bwpy9Uqv|P-Xij2WN$D-x2A+10(<gYA!%6aI{uCm z=RXss)F9Su=Unl$=OJd0uX&?>Q~njh+lkX}ypM<>9k|$nNB6{~f6VR+77)NdPXezb zJVo0bLJc5rsc~o+b;|f7*X5cu`rqh=yMG8m;-n$f8|WT8I=8O^^3K>Bw5EpC1AhOa z7AHP(9CVRnz0$ao+It*`D>d6mOnGxjcZfFP*_#?Jpi=!l(--+I@*Tj@6Zm^%(S}<h z8wSKfFhA?h!p0*pM>`{Q54oT>{U03P`+9skSkv~g81OS&^Sy}~GsB)|9fny;vC7n8 zJm0P3m*~Y4T-C%NKtX3IW%j{{Nh3ZQKn5RDSpm=h1?|R))M>|Fx%oy;exKDlO=+S9 z8|=dfOybOLTNGuv>2`FB9fJZh!)Cua8d+oQ`-Ez0F#QLR-Xf1Qp=8AajK@s~91{_? z-gV5RJ8QP*E*H&iI}v$;aj&C?HJi3OBxF=}uox)M4W(OWJ)|`%hi`TgjkHJO%<5S2 z`i;kuhK<&mWvNlruQpU(JGz$~J<^=c*O;?}?d6)RY&XnF6jxXK!}waNUDo(m%YuHX zKt0GQnWe=qT=&r6t$gd=?=mrw^7!EVnK6*{=AdPPbQ!XKj+7-E{s@%rrIFK@KcblH zaKtUz>3oDQGY?^Npcu^P0u?(bQZ8M0Rq;{|Rd?e__#+mNS=*BTVbjLPO=_CrttIFf zaiqSA{zh^EKY?CwUSi)ScZ@(+G)DS7u}Hp>lr=!+-<HYAYUrV-^sD5uv7D^!Vhl_| zPwKXaF~giu&3Fy-g^^EQ5wx*Gim$dQ%`l{Cg>$&0pM&!v{rb4S8}E1F(8ls$^Qgf5 zqc+ZscWvQL%*54?Rkx$e*|P?;Mnc(ap-;G~uj%6~T&5)sX3?!ThP)kL8*j{xKe`Qw z=a<oN`~5F&rhua)r-NA5M3KmcoR*@Woj{L#zsZ!M*KQKkdLQ`f4yA=*axLgs9_2|B zGr!l(lrig??d}@?WMgAS1Ei^}gLc&m|9bXmkBte_{C@gXUg`oeWwYgOE&SLv!WWRn zrwrU?lNg00Ab)^?MfU8XPS}CVZbxm%M~<Ba`vw{Jm_4?u?Av}O*G#2EO&PZ0QvOr5 zlijsHZVBAXmZag@UcD{}6y{838BItbW!V&zyOMBR<->e{D|RT<9H4eQp|};diFX^0 z5NQKL0p`f!*C=yNeWNt8(3F1qDzD(MIknsB#l*vrrp)V{dmYxup&8D-W%z%C^hbNr z2rUNOYCG|iIATdFxmSesB%4=O8WEFE3t%Fu%kqxfNb?G@{xd;tgxN-Rn&(0LDcd87 zNbM>R`39OvSx#l$6cKmKH9+5eVvAIt9m?{9fcpq$N41`ToFFVRfQvjcqx3Et+wYw7 z5o`51*#hWj5O301k)UVyunuvNZB-9<(x3Wg=ayI?MeLBH<7TU-^slQ9_6qcGCX6}9 zdory9k+X2T<ME%S(nWG39d0B3h6tPd#2}_|+WLX?I$oaBU2Z)>-gedU=PG<-RcmYx zTJ(tLnIbKM562nPYgpDZQ1XuOVK$Tih|41}4+S4W=0%*Ahe|)%<S6b<J`pKWxZ5m4 zjbn}P!|Ldr_{E0!?s4gx1<ocNuXJ0Q?C8x`?}jwBhFRlZ%rgK{OzZ{;C49W=Dk%kK zjsv-U#SxFC89r%8;pY=ky@^4NTA$g*N;GyBS};STBGGZO-Mxac4$GB9`qKDYD2m0* zT%z<ra}`6&x%dpDrlqS~uxLt<DcyF%hK3|ifd)zkMA}hliBdy}no>-eQpJ+Fkp{sl zmGLS$Vk!m8mpk(?WzlM7QgA>*>H#ZXPWb%Od&?((oNr+T_N>Cl3j87(bL<Z%#G}*& z55IntMH2S3e-wmE^nwFEa68|M(qC5xRQ@LTS0QlQi9vhQq`<zOyzcaW(wb%HK{iMa z?X&thm-|?UM?tkeQc>oU0#aM!**=dHccFg}<kCXA)R9KjZJ|n05(j~lJl@nqzZ8Ms zsdzU4s^xgCPvS<}5Dn<2G*a><-d?nPcs|rE$-9Gwep3905n+jZNv9=u(ioS8d^Nhl zY7YvAinGe4*fK|p&y<e^9AT1Pd&wX;<toXsuM_i+-|9nzZA&>Xy#C0Wp$kb@f<IEJ zBdCSj(qE5+!GZR_D7cJ0Kp$nf^~VQu`9Oi=)u~CRU->$j{*|K3lbMI-A!meAjb?~c zvd!&~(e`II7k(Rh8a13XrW=-@Vh=n%&%>p&$4rggVbsXE?v1@Gj~ZmhAFe5Nz=SG( zEfg3qL&bOCFT{^HD<lR*C0b7-fOYtD86?XwF;r*P*X(tHJ^WMrBNO>Y#fu!YYV|9b zH}__>%(^mi!jXq&7#E=}94Y!?^n>oQeu^LUuD698^u2i6_%RJh5gg<(y&*oh;a<Iu zP{<H#7PuFu)J+~|4cPcfpkxYCbxcv2m?uSUC5dsg<OISSGsZOqc=&g4x7qHpJko>j z-t8Z*0mw#(Ej)ZZp+_2ZM$4~^{#;*T)_JSt(BFwd#lD}ZmQ(LgQCWBko<Sa2k0TdM znqM=B9o|%}{?6&tBUK($oJH{fbie<rlqFsZNTayyiXogiefPw~X<o7=T|6H$&xZ|o zgF1|?+3_qosD1ZnPKxp0BPtE=Mi%bfn3y(`Rrt2RSPOKfy$(PP3;Zj0Wuvu%9BJAP zM{k-n!VsuHN3CE0FuXWR+<ZNBO_Wy(r5=)TQ~(1{tG}<yL+5`HpFigOg?dJc?zA6q zWINTamP(QXsq_YA8+uH>l5Jwfe`r~%*1nhKE&p^NfS&F&D>(2Q8~dJdJ{0*UEB;v( zSEi9KEzaugwE)8kZ$B5?U+e&?+li9DRh)p{SZmaP-7IAr4oOLLAt!d<JZkWsp?maW znOle+0?7L}%wm&RiHN~Hk09nF_TZM)H?I>TdOYVW9pC7_I0H%M(!Oh86M76z{!ov> zk5GgFF?mNSMT>e~VP8`pD(aZKEP#nMq%Sz<@K2vDuA+orefB2$l&++jY-W>QTvO0# z2TaRkyxSSJp;uW#=13qu+;$=hP4|qTZ+7(b-28}j(Fz2)alweR?3DaU-n{Fd6WJuD zY+}$h0*5sBCWU0q9!<tNPLq9UZZHLZ!npK8yranR{~XG5B{u`yXxji1H&ir}jBO01 z#bMOcZD=avS92B{lrSyE<B2Mw7afr7@B$YT<mQiA?xL{fUB*tMUb}Zsa>Km7rQ!!< z_@F7zhRE?Jd;h#t&v1p26`tuQ=OD;u+#-wJB7gNS&`4{aJHmCR5qF0_>%fy=)cck- zE_aZ9CzL{`j-rlk_g-4zdvC_5gOlNBqYgPnXmA0Oy6R_=b%tu~j}mM~Kd#JH@<z>| zKFHF=7!ax=vXRWB5Rv@)52ON~#-A4{>z*8wM(yP1_A1gDFRjWxK1^~yvG%<^ee>HM z&zjsP{1^4LAGDC1>#NsT;T!4BxjBeSEo=VB!m?@i9$5?zf}9#Ov)4YI{|1#8D2Fwo z3+Xm}`gY=FiN`V5`1moX7L)34UaKuMAHV({@WLF`=)QUp;F^6SkjE<%B+9o;ba-?= zPXal)XX3y%<RbhGvY<V*dn*XxZX%MGkJ!&V6w~l%NIP`a`)?=wwj0vZ&0BG@u6Hhv zx!$E!LW}ex6*D6Xqhp3;ko^t`;LL!5665v@)ZWJEy>M@y2zUv9-tW1sX1QC*sPn;c z$omd=Svc(#{YBb<N1bcip(?1+?at8bsPdYrLj?_w$3kiOH8p&(r>X(vx8Esrixy&p zr4_QkGh#Y=Yh!+#LR#Mk=}g-Uj!Af>n0av?_F^x%Cd#pfRP*QMH*dBNk2-THPI-Bp z4axUGcsy5QZ6}1NB#tD&N0nxOY77{kMkY{Zj=ypX8-4ie^+@2Ir!+_Fv&VRnD&G(9 zfu>KMyn(->idq%)KOshQ2LRLW)ppLs-r@bPeVVln98g3aYIYGLB5!h$eP92sxER5m z!#gP(YSZ%2ri%6i4%mONoPM~R^=a*M6+5MSEzOYqS@(G)8)1n|@-d90G1pQa*QM?y z+C^QMu<YBXIH<U`5(?lgk01V$b8KQw1_{dCKa^Rk8f8|Iy)lpB{ZSuUSbUrIjFOLL z9}%TCmSR1DbK6P(jm?!N@!ojBthmRkGW<23wDA$nLqO;zJlg3T$OkU@hIMYJ2>f^I zVQ|N6L~)1IdP9{?#2?>fMEV+{K>u{|oyzQDQul6`T|Vs!xpCsJS525OF_bZ|w-FBh zO4Izr*mv6(je9?gzbd}R$dd43Q;T-rPQ5ya3~YXzV}X?8`f^2%UUuvn833ce9x7Ch z1P(v|q!8f17p^_l&mT|VG0-*~OX;UZ!bTyE+_(WsoG}!shg7sB0a!>CY&H{Tk1&EP zD~x5~oB&dYUV?LOw>#`y(}O<e11Bh5SDFH?Q^kRR$BFQGMDVQ^f0-QB6t#=tE`bAX z#iH9`9+lP~u0zODIcj+Sz^7`Wbdhe2GMLi^5#xOfFOaatbCsrp8OFi(kgJnP8QmuE zMWEX*Dy>^L5TK!S8*N15ZDCl|m?l3<swy%Q3GplGMj<}P?Tyy|cVw+fTR?18Yiy43 z3U-cf3j)x4Qem|&O{JE8!NBe3eBl;96>QDn!rDseS(VRj8Sy4>syb@nOURxw`W=_T z58ZLN{WH{f>{~>@03Ba8U@*3SPPuVW6kqB<H7D8eygz@wpdc#RUhWHnT;x+B)_n&7 zM|{O_5}bj=9r~fDKj!nDALi=_tA2GW0QOA9F%EY5l;c5}=p<*UH_^EW;B+bkumap5 zIML2`WG}o*p&t}zE^%?DoeH>l2LBHLXP{`nPYUnC6F7sbmvA8n-NC>ttt>r~WNa^_ z!f+Y;+$OpWAinACa>&woFb<e*MFED<)JZ?HJxHI>e^5-Drw_D*<ak1nM<F%olKtXA zoiUCOzaGa<#gXcSN6N)}h{dWU4Dfv)K9W6^IhPn<ukU!cz+Atyg3C2I-xpyvq-F<9 z<>wRW=s={LIzQ|+E^gl6y-23M=O&IIYg9lC=TU&+?V*lOBGt>uy}0J+{q4}9QS$DC zhel+fo9YC`Z@5{Wg(aM~$d>y>nS?-Yn~6$TH)zDesdGCd;UZg_e252^s?tevEPt|( zlqA~thpL{~LBVn=Z%GpJ@IzO-o+*@xapY>M#ad_M1xM8#>)xrvjOaxd{rKPoM@`n^ z<+%SeC0~J{Re}1z5odqn3xUCxp?f_G&dnKm%_O{lAg2+BJZ>;1gAi0m3VIE{j3{&} zYA1xwiP2{Gv`K+zWG{q_$7{}Hwamt+xKci}zT@qVltDE~+SrCdwD2)J<ubrQeiy4A z!0n<?@o8b0CjN-Q1gV)z#w3f#;34P-I9Yg1HOlhpeJ;1o@G2d@SmJfSwWxnLL_f=q z>(p46QM_9`P?elNf>aY$HzJGZK0Exl(9(77Pe|a_csEi1v(I%)o;DnrvA9!mx)T;1 zk#1??_&Ntdz8IuZG57i{JV%Lno`mE?n}P%HHcv7iio&2jB#{xwPq@qDXCN{qnO*B` z9g?%45ipjAXOA6Iu-|(MPGg*{^e!FPW}E|kxNx6&pjG)*5f>g(yeEzOv2QR62NZc; zUn6kTf#76~qEcSh5o)UMx}DfD6Wi*brPKvh#brqr7GGtEZsF`}R#op^U6gXt<JL}X zl+Jmp{M7n|3QRDN<n6T~p+_KW{&QajGWDo1KrE09)AqB{a@@x-hJZV9pqx9r9uA$& zkV4Zf_Fs=aeua1m1rlbR#1!Nq#2~EW+mR>HL#<B!{!+-6h=n#{Fic6OdeB~_^3l&- zOK_c);8Ylt@^B`=SrT<};0gu{UO~n=W0cmrV;)9stx7!+@81-Gk(G^~BoF*I@7Ap& z*Qk*ty_W?h>ZPl+zF%iL-|z8H;bh8EA2=VW@SICSOxzJ^-#CA1&^O|nA$keGWjLq_ z+w79iTq3nhs3l(>!JLVrqX1dIg%4O1*;>a6nWIPAD?Nc8=c8pgH5~+SC}6;l7<)|; z8OLcEdU3M}Op_e2(O=RlorwXvGzJ*o;xoNpSDbnvC5fqqin$G{-5d^AvXR{4EL!WD z+iMJCN}TvD?JOit{$BdY*KBf`bt3oE7o=)HZ2k<pDQuO1+SS88Pw#dDx1_m<a3OP( z{W%R(V}K7vy*mqZdvjHvf*@92y$|F-kf;-QN%zA0Jb|}|`~@&dL&qp?*<h69p1-nw z?>Lp5t*9uPqQ+gysI6Z!b@^zWD*3|sz<4wG@$?|Wk)Tt%)T-7Q!0?XI_muAq760Iv zfXz1I3slItT!USC;Ppe4lD~LhY}QhvaXj_Q;7O2ErS_}J1Z}5ie}oW?+2Nabk&IHP z(4OL-9@sQ85nuH{peEW=2}}h@x9_O`pu(CG`hul3DC4Gp7o!h8hPr875UnGc`?=}9 zJM(ByhU95&$ZXBz)NKe46hA@$6LMi7+CpA^xCOP*ywD2!JUqd1p8Qg}5I9lvRSTsf z+Tu599=iVZJJgO@@qXH6AAWn-d2U8sAh64W=T2@{t@G_T{Rg+)VlM9mmm1$Jj{xte zN8(RHC7RRVy<Do92lR~4zc*7NK4OuNK&&EV{fHe3L*fr#4a&~vQsk8rCZO%mi&2hX z_+}pd0lGl@YJX3p2z_ZO>h;rXS5RJazm_N*EifFl-%Y}}gvxB1%FPe4+Xv%2&6tT= z<+b-JAS3dA^M?VYQp0r{xT@bvQWo?xL-m##Y&rhD?WcXG=ZY?z7q1g#S&GeQl9~?X zI;0iGhE>_g=lmwjp}zFTc#Z~g|I$Zey%e4s;wEvRj-uWdQ6LO~EATxRL6IhdH@r^a z(Y!$4xBln;fZn2MOrE1843p|4AHdfq<kXrCs_TEi?e^|9rI##l05E1SIk(y=ERZhK zb5577%?QOkQGaUoYY2u-+n=nf_t&SmQ9Ek2E-KvL@MlZ{eu44gCasdu&Dp#Y`p%iI zz0jU`8Dc;Zb3a89#=M9JUcxoI^Pb<arsCI8<d+=3XedhvIX1FUD;&t|V(nP`=;*oh zgBRGV7m#Q?;ZAwre=cW3I;f(p@#-CnqQ0@JJ22{Mb4>H1!RmC+2_MzO8!Ge?S*4V_ zai)PtE~#oZLXVnqA)e1da>5Y?xLrFSSY*10!QRIEG&sk~CI|d8AZ4G|r4w#AYaEp8 zdOO2QE_-qcTo1@nL}lXj{wjHMK`7jYjuF5fX?-Jd$r1cMB-C(B&mKN^J_M_bJ~rvO zEci$|L+ejCrF;w=4nn=dzeQPl+JO*d`0q1DwxuK3%BxNoqsu6wAgXK~llOQoZ9wO& zi@fMq#|B0E#(`6xMzmrrj^sm(G=zcKX*at*htC4DO|Y-iRHqU1-{CKCjaFsboKqCH zNR0v<Jsn^8qC^z-AEloq{q7!{h}TL|;HOPpmRj3*)`hy=>HdD>8SWMahBowWOG8|> zP7j`vvSIVTHS5Q@xVelVlg7PWMEd)JVQNTA^?_ay8<6q4&rX8#L6r7u{b@to`0h1- zk6E$reDS)>cr1=9Nx{#_eLNl~ycdZZAENbX*;(k8d(@>$-&sx`Hw1I}Zo!*f@MvNj zzl-U31~Ove``=;DL0SCNdp8^dx8>vWn}0to#RZZfBYxx%=>F%4i`y7~029YICIB6~ zYQ_y{1#DUSN>gBX@e!H0(e&6PlRg<<4DC;BZWcvsnUyQdQ>coQE4M4bd&!AGQ^G70 z4uAC+ietIE6zhl&XchYFPTR>odM&K!8Xq{Wvh~t6dnO|8_(7uOhk9-e#zC8KKYaFk zw+C52>{D>!d{`b@I}>dsUWD%+#+e2jZK8FNN^yZWMIzbm+`Mm*0De7<IQ7Dfc5^y} z@OqHZj(&&Z%tyrf?L}<O<CY1+MEDNS-_JKJnh9qmj5o{<RgJ^-PRi<Vrt7Mxkw(lt zR$p~~fxI8G&QB&qT3UjY;E>OHfrLFf^DIEc!v(ZMHWS+IZvCenAU~R?xae*<g|m2{ zcTd&jzRNr=cpeX(hH8v;MR%JYCD62d3D9oB$<dsvAfV@|hT;gNCkP{?NiWg9pd~EG z!-aX8iIMe~_TA#MFhrWy?>|AKy!K1|I{sV^Lkp5isY4;0(2$(reb5k~h)<O@fdb_c z1fnGDk$WI51a?9UW@V}ftjZs&>3=0ka1|mb*vy-UFLJq5p5n=dkSlNlvu<{oxK+Oh zq}`rbfHmpN2VD5=#D_4xjnXMT+Hu$nF7^~@GXWOlYDFg*QU)romgw?ijnGT<&x~tt zz4Y(*59m*!<iqWT6l!Dr#WLZ?3(CBI_6O}>i2#*+MvA#eTc!tP1jCqBqWD<eX$Uac zR!MZJm>R6ajrHTEl_LJRLROXh&vYX+7H&##BE<+^`q&5SH}QOTq&E<n0tC-c*o}ZR zw%%E**z#`3yzom$&5GL*hJNE)9`2+8oeNwwgA12SKZ$%s7^ptkayjmWQwj)tpJSKo z#1vK&caNpY21MlttSe8O@|wPf(@-810m9zuX(25ce4KaZ^eb020^St&u$#7LLR#hu zargOKOk5R?5}+j|!>w9f%}$;iix$A=FGpzHda3b=jZQxA!RJV-J`*9jWAypL67!Dc zY1h@nMSo!#hj?<}%&iqS0|-@D&tfqIm0mitBuW^@s|IZ%lG+?y*i~-Z)%aD_Kol&W zhm#+}j1hso@~<G)sooJ2>UOEZjjHmH_Tlsdf%l*Di3!EM3})dw^@)t##^iujd11-K zD;g`YqbiMG7420&He8eY%X(AWQLayc8*reye(`$2(sRIPZ?CL4<M`nz|DpB%i<0)$ zLJqheM3b0jKNX?D$rDznIZ`%F`YLRxj>2|LBJLh&2_2i9n~iMk-V58RSyRl!?ZcU6 zlpB}$uoAb4>*M?`G(oMT$?8FGz5Ea{+LgYtUA9kzTi6TfP^;iDs|V7Wto)~eIb!cc zeg*PW)#r2Uy+kbq^|UO`TgM0ZphS!`qqPU_Y)xl~5-w%Jhkl%iXq65KW}n5t-a#~O z{ItHTof;gJ-b(DN^T}*ugy5Ie@LIulWko<r9am>Hr&9Ii>iA8STHNgCJXPye`_Z7- zOld%-<R%P&g+}g6ed0q+MW;0u-_hj?@nSHY#1ki0Ym@(uz7W844*46{Q}sCNHCu=P zY><^+hPJBDc}3NymVU32`$|h;&n|F&UbZ*6?3XK97yMIt51&ma45f)OiFng;^n!a) za$iUF{5vscbF*cOv3gvTCw{s9G5Q;B>eg`0yPRdI7)gRT5&mMCCd`Alb`h2W%6|(c zTudB~z1EPD(6B7PiQmmNxK@~m77|eu)GIm^U&Yg<c1n$&d><jMb9Br&rt)k}6&^R7 z<Nh)y{BE&KFdm7Y(TT(l^qU(W-XgByn2Xm?1YSLbd)47T1saI4k$4)1G&b1NNRxX| zfiwN)T_va`M*AcxU7p<ch$vk#8aZw*9n<8orSaql$J|afXit(O^-=+_d!oRHteCI# zNw>5$Dv1k$e#0Wx#KJM5v?Wed9Wh~}pr5j`&wp<raJSHIQKLo)Rmfu~T>5J>%`cm( z*0(DbgV3<~X3nQpCr_bp{K&gFMxX!G;u*;@!L`IEu9mx~=*oeU%ZTI8qRMox#>+dJ zn|WCRr!cv@hw%^OROH!yKUJhmgK`&wX(JI4K!SiUhe%B57UPhvv0L>Tcry}El}dny zjBR)$K6M?p8zbFfgP(}DBE9=jfKVff;j@e4FCPvVsncxd$o&`X0>}%t*!a#bd%0~Y zT0F0~ZlP^weq=q8th%&`WM|0w<=W*rc)v0vBEQC*A2nU?VQY@4t>(aVZ43wJXHSJM zAJEy$(UDKoJz|A-Sr>1OdXwK2A)>RF#z!j|LR*D$N_Wb0wN8IZZW+%k7$L)t5M=>? z3dt=|Z5di2T2|*vMqb{$@55lGAs<JaqfIvux8EAH*c{_MY{TsN*T}KBE+Y^)hOn@f z4<T&GwLTEXJyeO!)1u*{WGp<j+_Q@ga{nOQ7PWDSeTJbOKmNJAN2QFIAb*Qq9w9f> zx@jo&ei<9D2jJBFr0oyTYAv&JHMndq5$e#D{___i<1h-x62vzUM^8!G1}dq0x4LQc zHdC62%gxFO1P}f22yuO&F*^Lv51nHd<m}sUE;6=$ZEXp`@W=~`E-!!eu6onjnmLNt zFpm0bZ{uXk(CW58AsBtxW^eb0q}QdwYViRbJ}y1Scx<r6Wb?PEzpi@LWzoaQlG0C( zESGm&r0quVJQmuwOu3ytSd%qa;l?p=6y!+ne#Zs26XPWC8t){J6J&0aEnMDhsh#(Q z;J6Yl=Hj}8Pql?)Skf;N2;ZCWkl={c6XrhZxnp-GxB4Q=X!NUFkx8+bd*wvZ=~IrU zKmQx?J2ttub0MN5_8CZzJ|Pdf#n<q287w8*AFjST{nTw1{mJ#)r@115NIyld-nftR zM~9>EF2knp`hpH}3y8hE(L%s~J(5cx-^gp<Pc??zW4Q61RTqo<8};;%?`?ee%d&^e zR|RdOC;iIVAH0FDf7)aAm@n3JEBhW4#F{xi*E2k4Yx`BWtX3yq4)n9o0@=CKdcM@> zT<PLsCuRezEYsHvZKs>vnEYp4Y}b_z{SYOf#V%L@6hXc*EiT}iFz4i<%cCOYcjC#E zAN3#hZ*z;*DQ^9e*FBU=upWn>*XA4jX`QL1ZHr5YS?#j1pkHhBSg&73d;DD5S1r^W zsgZrPKEuQGtZh~KcwNW%f4^NCtp;u%wv0sYn+krM584`W-^!W2RoenHGg^QP)6j-8 z-=PX8ZtQUVzK3I8vC`U-=jm`GsE54FaP#_}kih-;!ct!CivNI4*&{FCe0kqTFC(SW z&cUPqmU0G4z8s;O@2QP!>6Q@a@`#pKcGmLo^BYh-Y0~OwpF_{~A7YIg0Zb9;N{c^$ zuRC3u0YA-YCl+$fl-wgCC1>*g;OM-Sk8j}$RV~`?-`da&8@VqlNQ-skZlC!R{07DD zeg5dKlNE4vXUw>1RZITVrwD}y4djS5tp|#){EWhoGNlDJw{-dsoQmCp8mK_~6$Mk| z5mCR|PfVX@tEW|-`7dqH^PUvU{TH$0(;v5ms}+wmpX*xPl!V<E{QE#7lS`!h`$?IP zEkrBQYG|?2TORM$T-cSb(rh8x)UW%zuGfCQ+*z<uwvnE>&?WYy@9;}%LzFGjKr>#C z_T*&vipUEi-xk<j?B0|P%)&-FgR*^D{Znk^`1Zll>l%NqO+)|Het>Jf+*NmoJ<Ei% z{*+Z7naC1;i3<+?c+8P+mYppKTYCEbN&0Nz*y++9W1H-wr^^UUao>093zsydE8_%h zYA)L(9<qhP016jMO}E2N(!eLXQBHn)>}E@nu<FS|m2oWj%n-mQ^|M}_9XXVUTFA#N z;sScFpaNALUp>iJJ@`h_(3Y)1saGkGB=L|{k_***x(He95(Y)(rv#mwEK?rBgt}q1 ztotQJtX+QWh=#j0i5wA+0v&sC0%E869^f&97Ro>=vbD4#rOzNt=OxR7r3zHq^bl*_ z43-|JR_)2Iz_fUqUwHztu9efZi#UId8V^_ZO}F52i9FGn<#2Jmu;fS97L4e+z6n*c z>n6m{QqBIue)5aE=+;l!y6~maknh?K?#7-Qg;j3ZD$eHILU6yLd8cxQhQJX0>F5VW zq->>xFap>~Jp~D@pnufFi$L!?*zw9;y#Du3NTujBMf09o%w4ReN+}Q7z;V+StkS^J zw5T2O%Pa<;37={|GKNp5u%;ljIr$1^RDIlzFa(~--JnZbCjai2|F`X#cu(}kZzAio zpGHU-<GMPFod+x@bfCF)1gZyQW4_7tAxgi=ttxeuXHr0GRdWhbf^$EqFjPw|`8~Lo z0oF`eFdnAPO9dYVR=E7?lf<G<^c#PLsY3xJaU?D!2$)UWjssN=Q3}|qsoKbSUPbQ5 z<w)~v$?AQNR^e5Wg#g@KVBhS%*-E17Os+m<&`ieVlKBdP<ug{S`&g0K<SOTsE4B3U z44|p<miSq&hL=f9JI3TwX<Jkk1D)lZ#i*%Mvo%NVZ~>tQdq1WpEuiTmI!@F8cI`xY z@Ux`%d}8lnb%(OpN8tr`?WwT(Wk+faTIKLzn7QEopSGU}*+?a3t0!BjE$XrDfnjS< z(C9}tNcYD^OgX_No2HUTyWx5T&R*mB5$TX}+0!=8N9z0wUndHMl#lPFmARmXIwl-- z)m}bn%9RNgPA;}ovjxgU=^kOI7{?LD4jku8`F4$N231zeV;}jbu&g1pi@*70cT^@g z{^)b>xsuD=SZsq*Zq<Pq%H|LAhZQHxjgQ%&y3kKPsZFd`+H-eV&NG;;;n)<&^vJ#R z6FcH<A>~fA!mRsZ%O_7B>8&hqY5cu-Dml18FRCDhD5h$EDC8phcF2&9ZP{HoJH32Z zc=-XPj;*p%^QP4}p0djY(gqU_e9-_DssM81XRcXT%rh}Mk}7ba^c;0ojGjvQi6zY@ zt%CXN?ykDvUTdk#$jGmuFG9p_$qE!<do>LnaK>r^W+YxYJMF=x2Je5{mD77e*J)(& z1mRADwVUJXvh%8n`m1g#)?)Tk%IFu@`p_1&CoLOYSrPm+wLnLaM=<9D)P)AD%iAK4 zD@kI=5fqFs+n@Lz0vzO1fIb#}OYi_efKN?+>ej#yfccQJ8wS2hDZ)KcW?Gq*+u}ct zVi5sHC|=cS&OAdfZGDWrCEs-&xfu%&^J6(GhfeEQpgtyQ^M@1U#m0bHT(GFd*%4OE zP%y&aXCr@bAqRWgg2DV2$m{S7OZ9v0PCT^D{4Upb!D={nmATm(<qD&dg-D)=80wL8 zvvS)v=Tvls%mCBwI4ERsv%u;QC9oN5eieyHQ`ti+@DK!`o&j;)+^U;Ko5?+<smd^@ zVtG`RTao#Y_|s<X#&VLSx(C7tm@}MWW@0BB5&P1Q6nw=>e6%i0(^Rjk5ljTl&gWXn z-o%7lR?a+LQvMj{W<quA$;`7Gy!~c^D#Gs0^7}3WtXlx#vMvrPA&XN!MwsenXXq={ zie}2q!%9%HpzqB9QB@=`g@F}uQU!p_ibjfI(lr5L<ZMlVF1C-8TA9rMFVuqJv>F@} zr$9Pa(^HVnCNNbP)z_mc?>#6fXF)G><dt1mhx%IZS%e|v&7k`XwwC-kIVs#RBc@r2 z5RhQ5qMFyPoUG9r&M!m4^cJwL?(x%V{z0du+S@o)IK{FI>WYOB3#q2|BH407#S$&= zOv!Fd0dOHP1HT`g2@0(G<K(C3^qrM3>*9Su!Tub;M2&1FVnes=1676k@8)M?IduZg z5I=DZwVY}_)dJz$Sl9bO3wFRVRV;$LttLtc@Phkn%5DPO;(m49X$qV4x7MGWX!T;+ zC8uHs3BcGna4KMEdz**+Sk^B8wZtmHw8Z1IM-4XR>)Q|g6PY*NG^%vW({w%LGjAgt z@A#HDxniAfS(D06JpmRh2w$Y0@s+2F4km=40!At8&#b)^=%HU;Iy44~*l~4!#hl1| zF03Ti1z8C^MZIUUMAhHxL~6<c`S)$IIiC{G$|DKfLJ9v#40wtRDz26WBw24#1h4R? z<|<80J%-NO-2K6${md3UbrPm5SVlh$VW#+pjC4!4__~F*VuH)(#mAUli{0i+*@SXE zwX&ci<#?gAEjl<b-HcoEVi})EB$c-f$o*Q%u{>!x2*eTm9#ZGNY))gtn4VW;=l$!* zZlF0DDFEO;H<`wSsmi{;eDe>w^(WfV#WRdp6P5ScwfsN3>=lbv6DG-(mMm%$V>9K> z`d)fUL&&!BPJ`Fu5BW$vzY<ommoWdc-x=7Tpcif{9acWU4H8^Gy`Ik7o;4S0>q)~P zKlE;nr@}nUp?i3Ovra(psx!^Wc39IU8Es~LYDca+EwA#kCiC?OqfZ=7=T@6|A_=pp z2hdQAxdyYd^=m&&?n!C1D%0CWf8g~sIzk=lqmYt!R)~PQCu)nfXnysvZ~j8~^}iB1 z%%JpxAMI1T5Wtxe->{Ob@Z@p`e~_caNUfSyk?1ecTl@>3DxT5L8y2%X|GR~4P$bEx z7aj~hw=MTsiGC$6Y;dJb`B3KdU%2o_(FTCcb*lCk9@9aFFH}!T{GPN3FlAlgFXurW z9O!*&fvK+ZnCFtvG5Ly!pcXc~<oZldF0h+8%7wES4LJyuOUD!}OSmcBZMRm+!~#`S zl{M4jd&4Mfw+V|NF*+M$Er9)cb7NP1UV${0q01`0LsK!cFvi!E$5Qp)RbTlK#w{bO zRpDN~!qs`j^TXtiR9X?ZD*1;Gqs0<)riDW{c5q}c3LxC`(Q6-`f;0wiuI7Um(+tOd zUip(c(A5USy>x;e^JnoSq~IV!UyihG=e)80k;MBc=!y>}P$XYoYfU~KkJhSH+x()= zu9mNah`2r3v|CHHgGC!#C}~iCcx3o*o&FgZxQ6T<YhFAYa8{sw@s}+2@B-E=6FfBY zHEF&c8-N71>O1xcQ@I(Gb$if*{(*_@SE!#=DZLky3O>q!l?VV^Ll-*2z^LcRV|#*; zYE%`(-3L_YKg7KA^6}-BKq!}Ln$SA<CRp+(`<6@4$;2e$zIjYqPWn1T!shwtj-ZBl zg5i~O*x9p2oc%oE$1*jfYE@M=6FPvvnqE2lV(4^fYzkNz2D(In3jDbMu2#bw!95RX zbxVgw#c<?)$Dmi0u<+6hP~%yNZ0VJ#@NYV$NI2G0I&k;jEJG<^=HI&do5<d(v31z| zpu>vx?$W=_(*%;@p55qqjZ%K~wbP9hiMSFum89=#eV}Qnlr!a20F9TTDK5CGzO1Dv zEzjyT|A{a+$>ezn;KZDIXRh##E1BaP&tmPIz{KNq;Yhj$e+ObdY;4b*t;M2%WbZ3h ztJE*T%H|?xQq4e~xqVvO;4EKN0RKxCxMK5yxg@HI6+0a-2JaOn^av|xDCU<_HsxK~ z#~e<=3;22^Tuux93y#}wy*z(L3Xqd7pF04nlUy5dXpIIltFK9GXaqce+ZzoQGqJl` zim8c$>tGohx;Etmil_S^0^snNEC86&={?5R4TH_gZfSdeo0Fj?ffMPV0|;mKX7e@3 z)N=!)vwRv*tONn;o`xOPe(=u$G;joYYV)b{%9*qSIn`nF>QzuJigTbi6Jq7Vkw<H} z1t6pX@aMhaH!II=1}#Za(!r=0Y-WgmfA3qzBthjp=&!(Gt}G!LcmPb8hOMdzDUR`S z#=^&V9ApFfI-0{OkAwMNLYtip_R=QERXa+(AUE{zPk6)|XHZ%w57bfnMiy-uR`s%q zM^lU+@+ux8m^hyOITms_a{Px9Raru?P;6inI*9d{P$;c7aDg1D(ry7r5~1lry{iWR zT&we<)%69PWATK<Pyt<N08?IPgz>K`zE{><_$bd|)p-`N1)I8L+q@`HUMi4FhwTH} zJ%j-&TC;wB2dgPRuml@hIT$u+Fxe-g)LU1;3)rzQJMNbUb|Vm(pt;>2CG*m*yNA{0 zMLqceYS2u?^WFx6ihAkUjx5kH##(l7e~B83OHXyFP6{72<O3@eOPnN$8A=jWX>OET z4I$Wnk>bB5b-^_fkc~Ahm%3GM!cEQZ(8Zs?HWs9tP_w}<nriB%oRY{z9@dlKvtYr} z#bV;025gsf6E;9kestbvY>u$MIAwO<4#yHzs>VH^_`ZHNq7^GLk&Bp*SJSgY^p0(Q z%afk6VPe-uY_0S36ro8c^mLy$ZYZi{b+3LmojgCC=%3*%Cy6G>n;-WUStqK<iLT%e zFzvyMquo03iUHJ{spUhdPpsiC_7CS@BCz<w&LCE9Od}jz%~rC}hpAH!zu7c>zz(6_ z#d3I@N-{KLFU0B8^YZL<*KV@*fmI@ByT8P-zmDoCHk{=%ZNoZi+pX7_fC}c+e(c1j zLz?D??^U^C)+}_)bqDE$Ue&5_9mwJ1me~-=0XfApM69^3{7O|i=m;j3NW}z7&S=<O zN<U3;a#0INt>e>r9AN)P=x1D_r$p<06=?Cis_Jh&h7xqYV1d?)^VW~W%{RfhOA$e{ z&gub{5TJ8G-_1Gpu0i)cLlxn~){w&hFTW*SiNc^tuYAM$j>$J%Y&H5AgGJ1}K$c=5 zfY*I}A+;VA+1y5^i*a)s_M*XARp?nun9_AjPk*l*r*+fxCm75TUxA<_LbcD9N&L^y zdH+-O$8r4J#dVGDw8y>I-ZLxXUM{Y^WrysLSyam9;u>+y5VAKRq@<9Y%3h_cN>b6c zq`vj__0#zWK96(W=lyxTo=@qjsKW~@3NJ-_j>#yWND0FX7m=6ZDx3Z@SRKp-qASic zjd*zd60yh%zhfso`r#BlA0Hy?r7&OkVu3Lq^RI9f+wO?2MdNRkpkSC!$VXpR4ciMQ z(jny<o~{+bszK{ERrAQ4OA=;UAg?iDE4*1jVBqHXKmm2(?!^;Ax2E?#;DxB&;&xjQ zl?7jS-u2<Rtly#BRp{tAYp;88o7efN?$1wI-(;g4lQpgs@KjXtF**jEs$|e|*VDIs z3_rNWbP(&RWxBSchEW%f(-m03mszV$DRH<BS8ss133t$W`L|?16>$rjg#3#)s(;F= zZ~}WcApa%N3p?*Wz@oJ98%h-ZP^DmY+^V_Z?{#9(#SMGuP7}cd<W5gtR*2f%EeV53 zZnx71K2J^0X6roJJU09J4S!1v3FgNRW^2~}V^R3*3WdK86lq4hIn^tplk~&xr+r0> zsvCjlg7Vg0?x9@_{#&71kZe;8apBre0y9q&g#WSwmi9U#bgHCmQdr`Tgo5Fz7e+wW zj(&}%;8Tk5Jz2zoccZJ^z~*k+Q)^_L!`G(XFxlMn26#?JG|{O$qjf(!C~>e&ZpW2) zzWO`o$IO9A-m^fFF%!g}$th4mF4=qjkD7+QpaJd#vVD#AeP~|xQ1QB4yU(D#7W^mS zBzMzqAo!}WaX5xZl$OpJwO%^5)p|*?rSp7Y+}FLX6j$3L?1lwYR)|v@B0b;oKG!4* zlfZvOA&bP6-SZ)|XS1tc3^{9MxO1yye9{UdrCT)JCr~x8Dil)djK8(n_AO$5*LB?& zvd$N;m;Q)4jQU_zCFU}0R7X?B+31HsfjV24+Y?USn-)1$4O4te<xtU^SjAB5ngjKk zj9iDDQ8J}K`gSM7f|+Yi)P(t1Y6iX8cl_mlR3Qs%8Aez5Y5rav$`5T|+}Ibg1y>8$ zk@Xl!g;jsbOZ2T=^&=&UM64rHea%c}mGl#JpLiQJIT-ur3LXwbq-^l`uw+Xfbu>-M zYR)xC63cQN@YlItFCS}(t_LO6Xu1^!K7HdQ)JUW+w#xMI+l1#4f#DJOF5wS3b<9;C z>o?*w@6l<O!a5WpGSk{THp6?9@M`_){o1Pz%jQrYBsj_YmV$cCHmUKv&pmlba#*M0 z`SVlQL{)G}MTbC_!+U;vzU$sMiwPwoT@l@x`W2@gzFmG9<`eD2&vUAo_}|pUg_lfu zup`W8eBA|S+Sk;&su?==bhp-qvA!0&j*=aMynZ+A-`5lR%F1`zWAkR-o2tPMF!1I} zxp3mS+^Dt)Q!j*VlSJgT&f&7#u8yzHGH>plX%)z{F(|rl=rhEo8K&vq+{JmPgYU6L zlpQRqfAe+<XaG1)5aicz6#Pk9HP2N2hr0gnLjeiM$A24Uv>MM|xF=F&wz%@grV0Yd zNt?t4kxOSd-0w&yc0W@WzcSVWOYD(;WMz|?B0_Bag%j`Gl+nbU`|jtZd_`!24*fe% zZ1FP}-VAH@`O5^?UiEqPsKKz^ZIFvcJldP$#Xly!=`c{0d9~E&u!6U)(l=E{4yk(k z>?N1uQ_E@+k9*v*Lodleqj^B<oi~VO(whMVRujly51NPIlAEE)_n!J?{_eHHPZi<^ z?C=sZlr8rcew2LpW~Jojox!U64+mb}ljP*jb#p43w)F`lip@k6cjFf=;|?1>-S#<G zFdBhYWr&K&9;-Iw{o+gAaFnVPzOqsOY1??2WFls=aMnYvt<@=<s8iNLbYOpSRYJ|< z!cy64SbcBXpbx#Y$BK%NUEKU7H&k&)SME>cmNYoT6fgUvglH2-<ci$=&pj;PK1~NH zJ#qJxw$kPkorm_?%EJ9y!9<@xK~?#oaPaL+_LjM4M?5tf0>EJQVZT+CH@a)%+v1t! z!>zTizR_)thLN^XVeuQXK8x4c#3#SLwyW9<9iumW_{@b9|IZYk|M!<zf=Bt%imsl% zFn%>psDh^{SO9fp)i4x9D$v5}VskfG`lURSMMHiu|7~M_wZnj|Gji2FY~7xeOPo~< zr&3`JT*vi&rc3zM=|`-*0yTrWest06?jOrG#D=k4)?bQL3#p0k*5!#VYIdR^pp2;h zQ6a1P(Po>;nKVHclLZx28qeS>OSp|NQ1|i<kbYmp=Y$hy{L#~+{Ox@<ADjFe%Y!3y zxrvuN@2;M<SQz~YXWLAZ`a*bdi`Z2p!S%g#u69&Wlp5|n_Dpp_=;v|y0gr1TE}S2q z0^+5%R}3bx=1A)_a3mP`0t}QP^#HHzJtQMM<;biyruX=BhMYz&m?V|MFKIV?6dN?j zw&Dkq0;k8$0DFP%dH!A{s*wIzLSQX|EX9(8g>If-=M;draZqSJUhpIgTpPLG*}Qao z*X!veU0|K&oK8uXf=xq#St(#0yrXh?y+|3l)HM^x`hlbuk6^j<08SEp3MYUV(Dm7Y z!jmYgb1^zW@+8V?tELrM(Q>kq=bCrSi5~PskumPh`x{TaM;{B>e-AAh@M}ULplZk} z!!!sj6~_f^ExA{ndh?r#20kR!A$`8M1}T$AfcCypQ>7Cx73>$V-+XVgB#{Jym%SP> zBTHGW5~1J()&v1~GZ%Em8_$vi+m={QfL`Awk@+~bX=G{O#F`8t8zJKjc<1RD$b_Tq z6<{w0eR6{(u}pr=NgpRA6S(b-vUIsud?AkNOn->cQUMjR0UtPyZ2D;6s@NcuZ+jLK zKU`wib~@>~*c3?=Nq)A@Qli3%^L?%~h!?fZ2{2XLCY>u`DUm<7BIS_@Fmh+jJc2IU zq(j8P18Gn`JA0$eUq(5p7fMZRc*&eK$ydWTv3HC$kq%GE61`&nG^R14P#;>1qmhN_ z;W$9DqCJs(1R{yV16VTi8jLSynlIpc%@XNiAas)ypKzIJ3FK2H$*D05KIGgOgB8-; zOyGO+^LVHAYT$_1m-)18TOhYhw~IsTs<SGmigh`q*7)fkqNTDwbB<YvL`g1ErmypH z7vnxsnVnFfW`19<+TKs3OPjkw2KYq~cSXWt4DvXoDKwY~h05bUK1E)3+#sQRjgWA} z<%fw5*qn5v9ktPQn%B1rk#I+7^7oP#bj1uwcwjbZ+8$_i_AB|NP)+qCFJ(8T!Zccp z;}-To#&j3U1AjM-h3Ug*N{$kLnO%>QtEuw9pIrWjR5UzPQSWm8?at>b=I8yDS4&@| zvwl7^R|Y^gzme{(5|jY&OJ!y%<X5rh;K}Z=vocg31fU>s*UmZL5<U@MF-`QCXCNp5 zfWloz@J2dnMo6?N;MGg!N7HXjeCR&dB}D=im&y3_pD2RTKUaOy!yo%j-(@vrIZrO( zyD%L!5e!ufoO&prMq_tuo>rW;$W1@agX(!a7ha=QcN-3(J{Lp)a*7WEM9Rt}0yF&r zkguQ<51I*oSHCM7Xs^ZpG=ZKnI%^w&vSKzuii_d_8wi}UhRpi$6d+SkaG-^Z3{hbR z<X958P9O?WBs_?76Y?9+1(+(mMk~?tlcK$)#6_tB4kk>Et~Rcp5YnE1Ofzjh>zrg- z+HFK9o7dkql@lJIY&t8Dv%DD#kgA*$7c&$qN3VWLtonx~vDL>y)V(Q)YN*t~833); za9z!HrqlS}#ffWSZL7#TFm83u22_7KhIk34S~T&}Z?n<O$R|eS4)Y{rioufA=uNd) zia}H5YX}dU^b{Y3#(JDHS*53<O?M`<i^`72*|7pV!rNSGzI@MsgyzKj27JUHhQz)j zQsa^Vwn+JoGqb@s37?9e0=tqk4{=fw!x}p!tBStoQ^Nji^4PMQ_dc#nak!Sm`-FOn zmkiO{M^Uc9HfC<B4Hcg+9<r#xC$GXc&(Qa|fIU^JH=0nNI1qCEEdeg#o61~_QBl;> zf_SDRGNthEY|N>NjVFkzmnbn7NSr%aX8^?UhZVR59st)2kEbKxATEX!S+l(&TWl8} zOn?vl4nUG}rhMbg`9uzkkv5Za_#S@fl$k@-rT1U(3k10D6;0&Z2M5;z*=5M(d8*%p zY6^S4BaVYtYunO~>_m5nEcd(Uoc<PI0qf6`b3GtN81FreHCeQxbR_CR%BhfQHaB(a zDoc7his1irDtg)BMUp$Q-Xr2|>vjM$uH3iwgQ=l43%Hlu&kCf<z{zEi)9G^Km7Mbp zMv}7JbRr!BOk?Y{9dkg!Uql^w1%Z7ZCax|Mf43PTb$+b#!Aea&zo{g7f6`Dm%*S~c zEu+Ccq}t9fZtbI&^5Qzh!#JbR`6sN`hekQ?Yd;muRg4IaD|0w=7&h6#IB$)v%7MBI z@Y+N-+4NxM`b2j<u-@ow=ORhZj|^*n`by9<;AH{Yx19x5n#_WJm?X9<%@U0SY>vah z7$(UZP80Lvk>h4_4uP<0fdGErl@U~p0fSxIh;o&=aPT<~`qA(LTVk`o=pMean=2Gl z!S;iT(oe$HckKBoGO^IcGY0T`MLY9g)8W&0H|x}D2E_u8Hr=4b5(Zf-oFu_&fu1y~ z{mV{=w^cKvtZ|>HRJ*N2hC!iXTPWE{ko!zdryt=9gb_Gy2aFS(u6>`gmKu6ukMos> z9+0al(CgM8SqUz212kTXz`O0ac;tUnP6<<#n8PgIv3J`YyrOYxWhn+CeQM3v9a;Ql zKVQZGe!gk0s<78tys-F%X3$>2yY-{K>R<4n$N4!e!DpLJv3*k-S57;&xVFXfm{ek1 z#itt}9CfwFDVP$=R&$32OY1M=0Y<MPm9jBFOt&nVH*Yg>r`t+GeO&6*YXj$21QRD+ zwv(F>knV7V7v3QyN{|K(UiHcHCTkdh-BCbTk<E@UyxHo|TSK5m=ZZm8eNX`N((V_0 zwJ`i^>_amL$PC^?Z{i?aPTf72uBNX-?eyrZ&E5JP2k>?heP}nmz3yFw#I0%omFeL- zn-9H9znLV=h2V<|h}jRnnGE$AyQr~hv+xD<h%4-VkKcavCsE+qzs!2tYs-sKy=vAh z1}vn5f6n6$iURojkX%z&@m$Xi&U}gZ+H-+U<J%cXq>>UF6OLtG@<{AdpQfAM8lEhN zrV#++k1DZF+e#nl6fvSLn_Zt&|F+<`HCv>*)7=Bn`w87y1w!shYY(?y%$>g5hq!rG zE!%Yv#iHg*OLOq5<{4+a@2C#!sz|=+VxZw!$QJn>+>tvaQe1s@G?cmID8}JQy52;c zEPQDTWv!H<(l|5MQ_a5r4tx0@>Ceoau2W*<B6+wYHh6;;y?^7cQGq*f{mUHp@KNz- zTCC>h7fG5Y`8eCD2B9aDmJLhwfsuOWoJ7wN*o}uHNIVxrW+=~8)gE|9>O09}W;mw3 z9B%@gFWPm-#8A(tIi4~(mZCV`A~|N%P}=vS{9^ch>E_3JNmnN-<Fu0!c+a9#5|O&m zfv3)*Y)mjo39|b*B7}xfp4YzRg!JH%s<D@{^wQj80dOkHkONyB&8r|1|M!4v^;W#_ zQ>FjBk!W>qn6hcwrj`iS;CU)Cx>7iS;ws~CjU^|XuA$$)pa(FCd#91<W3dI{Y)@u= zJPA5O5P(ku>1)Rrn~7jO5Z#36iQYFq=acBYts@j`(FuY#da?C@IBiupt#UcWywbJ- z&WG(Z$yl`ZQb;Yx9XsQ+k4AS^_$40UPVe~KPDt9_LZ^}J59V;-D2<CwNZ3!4;NEMy zhk;gsNOgb!H@YqmgG^!pzL2C{oCBTV=Z;;x<KZZXsuJXM0yQlvfYsIjnv;@1%skpQ zZK&0_l)!pjIqV-y7%nF^V=49~8F_2{M)nL^6_Y^5W~d(FREiwVa*N$#(KCOS;Ng>K zWWX_sM~w}io}S}ORAO7QVJo&lv?19F2RN3L*yaJw)h+gABfO!3G3lSv`k3ekw=CbD zW+#F&{)<(8;D{{fh{ldZUw((<;)$t+TFZ&jomgcLlTRd(Ebpn<%8_eT_n_2$vH>0{ zjFBlE$;3gud2K-Mfyi0So1q`#-(E)E7`=$C<o0Jc|MJro@<$%lX2sKx$*G3W2x6p9 zsuCyyn2x<F<&QH_H9d<=8s|IiPxX_`Vb|%*g@D9ZgVehH6FqD#c?le@Q6W#-#l_&9 z7NT%>5?hE8s|OSDYM*m%n*E8ATK2Cf-vZw(My`knviPUM`VS}C$6F%gvvPz8t;Rgo z!ElIotixI4A%y=AgooEo6PONz86oY`$PnAh`2F~0H~_8Sa~?1Fd6)^0z{Q+J;!duH zI-P6IV~J0#y-6xK<#RA^*3dYleym}%$}I@UM7rk&<|lE;hwq&usuWbD(IdxxRK$7^ z`4mKRQ&GbxpPcsM#RSf`Opc9CS`BZ-#uh_X>H^lgsMVBVx}Dpu<#0VnR88fiu$9ek zE0n>?c4i)~;de6s;q76dbKk$?^vNtWBi2Q}*xg0C(R$g>jhnE+QrIAA-n0y<9{9r_ zd81B>6_otf5&4M~*wb+JB*YT!kY8hcKIg%uU6H>p-}-SBtL=ztzJ#8v5)H;OSGPsk zmno=pWbF~E_E%kPT+tJJ$-)nIG0pn$NslsCiK&$IwE~6@ILX8hIX35JV&a+4>Tuc_ zd40K-Wsvs_oma{ZMMuI@G-8tmvm|LMQSZ^BKTtLYVcF40B=eH<_$BhBm$Ng31pty* zYEUdd_IVc#e6p7}EIQ|!&6RVk2P};RL17Psq9TzIzEv`#sS1(702R4(=?=d#dpDMu z)*E-6s#RHUYs}S9&+jc5w|i%rUO$GdAKAe9#5e^9GlAdr5JCeB=z`{@1_PKCcEk8+ z=u8&53T}G~np1Tt((q9na+LK3YYvOagKH2%7R;8Aj)@1?k*9t+V;qnWCFBmXiKFfm z))v%$1t|alx`LZwwotQaYXzFh4W3xCGx7?lb`9hf-KiKJoeIgZzn>ObVskbl9a&?8 zXs|)l4pg#|*%KR4DM3hv3-XCly5l9J>s(!(RD}&Y&F&Bv<=Ra~7gxvf3-j<pHc-U@ zm7hu|3d$6dv3s@Q>LTfAmWbecenRjF-cP<}(co-C3No?Y6daHb0kNDL^FEeD$xLc` z-*CEIQ~(k%NB-XD;=Rz}QiOjNbeUx^a4ZOEZbOwEBz*aBTdp=J#9#I+Tt9*hI3s<p z>HCe`pQyL_5nBK75kRe<C)+A*yS!{K*b7wHUhTWtTi=)8#!{L7bu(9y4Y-549bk}G ze>=2$xyL8M?5_%P{UAyDHl~Or_UNA&k4jAx@c~N&E{(fm=>s*>JTT-|8H9Wh(g8vo z2CVL2Mf_}_-kOE%fbq=b;8^X@!2A6Tl8O&+i}}|+bxnPgXys~#I<s)5p8c#Qr0Y?E zC^fp$n^qU}u<N?3pw+XwUiNO{PX`yr+(!b^$-8`;Mvs*Ftnj~yJ`xefUEPM+NRx;Q zW~v*Cn}?|RtJj$R$TUCdxF)hH9Z5nwhISNe+>RHjMQJ36oYz2(789W4Cx#I`fRZ!p zLvw826UAiz<4qx5XJn-G!+%%dYopO}{sT``<MJiV-#Vb(76s3Ua^L^%rUy~Svko4| z72)I}?dq8KGfH&d#~Hth+Fc!l`6PS;-<4FhlI@6YiMIL#8IVeZKL|u70oDqW{w&H* zv9?M<vF+!z2<4*5g+^Z4Ze(D+7b#B8JCWH54&!Pq`C-?eOJBF8mHw!7{uAR2tArKn zxF#6pHyDM994JNw5+lI;b?SJ&G2?D%pT{#)n9dlEhI)2B^4M#}VSpew>|LVZ%?u#) zd4IwgZVMjpp9S&8vDikqBN~6XA~V{pD*R3QK2~`SVvc@DLUNwLGln4@&LZz_$^w(c zKPFkdC!1bh;_~9g&i4b;QqURjCxPTDAEY_|lP@{XptJ`vM*3<L>vfQI4EABw1^Xo$ za^QncZb!5NS;yFsLLl_CG)}cNwngquE#*H)?>a2HBV*;%;I!upB?5|44JWi|;%l7N zvmT-)N;VT2_B2WUAJ(2Bm5}!t?+fk3aa2=jyY4^NI4&UdT#+s=*CCcJxU0w?DPEFH z@SV=5_<~`GvgW4~wPCNe2YKQKFr|p$Ufzg4XEuAxI@K~Ln%Ains!T<iZO`gL8txg- z^$*u+3ULR%>wCf7=i$8^*m6(7_RfV1^N`9V$iax@#{7o&{gx<eesU21#zn}6%bRg! zHp|B#`KcY|r1x`b0LGS=iARh|^KIik{%j15N7p%qZ>L~l6IiQ#8!ua;{{4n3U271T z$v!>n_cp|VW%=Rc;B1k}$|humg@&4_iyF2aGlxa?XCTK<s!E~AdtT9Z;V-Zt|IPU& zNm|RV59nu>m|ebA5nDP8#Zt5<TpJ~2dE}BOK)4;HY-oYh(|JXg;95*W#{5j?9}cu* z^oMM`N~FAezl^y`c&(ftjxaHcHb?ChEFE`i-Tk8}ns5_YI`ih=M#0&V^EsBSsxRgY z?E20GY`wZtgt=C9YA#o6GdJ;X_KPb>-xk#PZglzQnI9U&m{)csDM3dN>an~luN4YC zwEC=3DeK>bhClB(^jv;>i6lvYQqLgIEjynm2sFcokFKR`!pk4HE0L66_MeDYMQ<eW zY!13h{?vV&J+}13P_6^2qgj1t*6D<>ADzOdu3P?`kI?qIsa0WSYk7EW6tgv_PVr#z zSMYvu*c*D^85shR{AqdL`frtOSopPJjidtos7jcrbSdirdAV=F0|Wxgzw*}8bB=AS zb|>@Hl(K+2$25_nRMf?rcC4V-D-gqD+s97^rotsyg2VH9q1Upd%F(w7=V|e1O?0UI z8ZPttGMrWf{676G$#SPWp_#4W^Da)aPIRvSBaSRu{>2a$!B(NbedY)kTY+h|qI-Bd zs|N>+n65X*Bkx>8ZY+HYOKtM>Kq4q$2`?~Oy%{?H7#Bf+)1JX|gegH2ah|A{R+MT- zo=a1x+~`+hOFo`@w|7Q}Z6ig62eT#R=?G`kBlC~Paa}rJmr44q&(YDjDr@fQjQpjR z<<SOjx!@I4V+L?P;=yZCEBzhmcR|wOA=K(Y7bz>|-uqiOCxg5oIj{V3Twbvru=@k( z?RTs+(x3M(*3PJlwsz1QgJZX!sF;c%#fLL7Lh$%E5~F5rOxvlQ5s7lV=$ouNi8mY4 z%S8|V!`(;DWo>S$>b4=Pw{)_cw7J#qtF4rnd^I_%{sQ#t!N_Ncz3;dU3E5fM-<#?U z!akj%`yR^S=aJOT>-&MU%NJf$yWhlN2S0`A>+O$_1d!JW>#N)M7lgk*PO*~;)t#v` zWRdRDfNkszXbW2lTPw`X@OONZGeGK`RxOej?V$H~9Pph-c*=crQ?bHt%ZvTj*tay< zSM&xIIQ(4kvl9R!dCAfMIGE(vj+eGW2yt(JZ?BNBM9b@er>Wj2TpuKxnnO5qfOP8L zeH5eKt4xdgRSSw*ckIQh2t0J|u&YgfDgn-ci`g;9o}RGbYDnI;1SkN%0t)|N{n4Sx zvDI^=#If0k1AHddhQFF6K>!E`_AA@r31UDYoDRl^VQC(~JT_M1`BM$>yB4`v6TC<P zm${6XLrl(SA}@%Pj%`FIm?Jc_GM5|kNY*eTkeBmx{_qSK!+$N%yxYJH>~=A^mHmR^ zYM0ProxH%I!x}8=-NSCTk8;VZ_3GcJ_(%aXl%(F>2BloP%nZTEXkPSyHxMt!-D6+B zUiu^yT9V2}l1NZi3zez)wBKq#Kxc4MA`E<B017G$tP5?hh_#a-;*$Wt3N5L?b2T*$ zvfMisM5MPSmL_~6JQ|H1*8zU#R*R?Z^;Wm1f~A9)WVC(ei9QJv*f}X@&&ZonceAQ^ z$!qYUYL?{+m3z^-Ph7JlQp={YK36VqqUDNx1GUvNilIrPmm&)0xb1dSlZ%q1s&>Rm zvSfHzDUJ9ufLCM1H-y<mU9QW`))n^zgS}xH>fwQ)<S*VTHe^_VStYCB<^Ti<;0K{J zyVwRfASH4~5-1t4QAqCE8Ol%^EwaZK>3nZ)Qe*%9R3@thGyYIj2opH^L4h3uJl8y* zg|#)XpUf9w*QRpI$*ZWyiiym^CYwVr^Ak<i^BR_=8+F=EY#(9aCW1lnSu)PY0*zlP zvju%R@Lv&|qL!EuOhfIH7ZAKI%>Xx!NZs6RY`W)fBPE?o0-h0-SjBtSAw16Q6;Pqs zyA|9(LuE>5irKSDvG>pB34Q9=K*hK<Y>o#26|ksu5RtiG;V7hi4^PFGv{YF3!q!jd z+pjuI6kxLtdgoi@sFST(1#s6SP6sDKHD~F&ZtsHC+<>&U7`O=_g>E3ah+ly^(fGX` zE3!vn(j7Ts+NK`B;<X(Qz;idYu64KhUd0*q#4bD<J6X|Oeas@L4iX7&#~aC)c+0Wj zz(Z9QTb&HgSlpGZwZdhmj}CeDh_t<CnMU7FVHYkn+<Osu*cmW)jL`lZ)KoKqxKw*X zR6D#m_(ot5I3Q@1xYaqNKK34373V*h_1>!S%$}D3aKHIvOp)2Nmpa!ZHgeUP1>}WD z7!76B|6{<3V?0R}gbkd#E>!is>1fX`uzx~7pYbann0BwogSj3wwaJ6ac7%PZL!?=O zzSRPQYwwWqM)K68+_H;Idfz^uxn?t4F0=gbOw%9gS=h?dfE<yO94jv>8O`_r&F%av z?Ps}1JoR@y|JLC=R1sWRPHOqd{A#&FFkKOV1BVp|?imIcHBClK<RGcOEPoyju05*9 zj^pU|mr+#S`Mi|=N0#{bh&P6dzEzlmQ$T<$1EGpmKTdvRfzQ<{_X}h(fXEod4CFFC zi5axE!k-f#LPTIm+~g`FB{RoP^w)1k%yU}4CRICAt<-=VOZP-NSedZgl&ezP5E^<i zcpFj+QdEHfT@5)Zjy)GD)&c`!Fz~~=p?cB9lYWpa9QtPqU)!~=rxzk3r&yrqh!{?} zlm3dI3aesvG{&J<&f(EdO_SSah>A(oJDHOArgX$&5CkL9ZfMO$?|VW@SFKa-4>?kB zE%iDyLB2)I`i=`FMt>CrkJuLckoiUCCJ^`xs3^mM6Y@S7Ed2%SWs(Oh!<?ZcE3BOb z(A$Z}U8R-_Z_+sBPOLIg<G*LMW+4xb4ehxG6W&76V2maLCL3Es8da$jc5)!_Hf>tH zi8B0kkX#u|EH-l0w6T%^pP3(|7R%Y8!hYDht?$hU;Wh_Sk*V1SkD8nUm#i{cFo5YN z8K74iw<--QbFk$sNT?fYc5fzlb(T=x!xJVf>MTw=Yyu0t25PQQaTyd}U-^fTtTGyh z>#!MGt_f-Oe4em_furu%*8w-PYi=zdDq6sa5;8`1ngb2i3O$B`i0yQwBZ7BKlzDn( zkW#;E$j<4_$WQk5Q!Gi(L>LS`82yoefIfGK*T7Z4f?FP;sGa$@-B%KRxUfEyVNqq6 z%tFr+r)Zz{Bh8o4dfTXDd3(`}7lloK3Ev5o4rbCTTg;DsaKH*5N=~p*mJUAoBOX!A zi)Nc`+-{XpbuOiFe_~4QQP@>~<y*{uLLxyG;zT>R@IF(2*am}I_Qv(vNFk}cIeiGe zJUjLC-KVtaXI)Hvb*f_)Maj)A8|NeT4tcGc^^nxoK$xRQRWn-F*G)9jcFO&bsVcM( zMc-*AO=Z~Zw>NqSMKb;b&n81YOcNks?*C%Z_NfWA7yp1h#)G_8{uKU_N!H3A0;WMg zc#o}Qth6It%QkhHJ;R&yK5?r6r^3ChWXdf7D7{{5nqtsrR_IaJ1av-WZ<}cUx00UM zwXnr4HOfjnw)zSHYFzxONoOE8U$o=S*2(x9S3pR`+HyG~AvL1gos;Lvei_)lxai4{ zhyM}G?MQSOCulgk+u|3L&~oX|<7LO=y94c1HD1X~0@LWmD#_&KipLI6(zWQ|DLK9E z^FF=;6B3y+`F!6A_t(M&yt&7kQP#x2uaz~MpFK?M&1#)d`7$eG>14)kr@1d^M{ZGT z@!sH-)u}3xq%>e%Mnbd|{|P5UuQ)Un@!UYvb|+QtA#Fm<s=ig)#0T@QH&UJOeb9m0 zvd?=5wZ&;C0x}XhAW4b~29I%LA5}BbJ#*Pj_lh)CVCuZ^LV8PF@l|S*aaC1*ysux0 z8X@zzE-5%Q&?n1j=?h3dX<+@w6qeZ*9C1$uS#b9?>6*iK!F(7pG4mfykv-c>ch%3D zkM2B0orRxwP8LdR+ppj<<+-pVfgD`?O~|eO$KicuJyxwHEh7?s15{ym@9Z1G)OE%$ zXlH}5%kXNRnfaQWIMQ?JlkTY*)yAQnZR@NMr4rSP#|;xIpNf#TbJJGD{hYLyDL0ea z?4Rq5ec^X2b$sYwZ+CDpXJJXIv-gx1_0`~)@!QG)s{1Sljg9|>6Yu}lM)Og=O$ux* z%0P$AK)5!`8+Jlgeo~j+M7o<J-$LBp{C7$@A(6KxPTg(z)}<|wNMPw#>BJs<e;EWQ z+dT&N4X7qh-&2faXnWnNFc8S$O<Ot77oPS|W3%mHbGj9P*+VE8=P|<V5L?tUZ?yDM zktLl`jQFRD!4G75h>W|p^~ygMCtqc>R%$m-pE+s3C!+PEChla;X$}!_PgQEg9pGi@ z89uHV6%D6;cY?<35LtHc2@E{G_sPEkr71Z*H`r(|?jgWf#{B`TU==$=RpN&%L+wc2 zzC$w^P&=Eanc3d&kR*D^K3yOUj+&HQuS$O#SHgd<31^{|@M$QjB)!?Sd2?UwN}k5c zUhXEBEb40JgUJ$QkWg)6P9yyGV^NuwfuwiddH>kMi;jw(ZmI*CN|GV^h&b_N=5g)6 z<G1@G;LjlmFev~yN;QHS(~zp3xp0MyqE1bAe1mjyEW6_@o2;gihbW}tUtT4!C@M~( zmMUzpZhX9=uqJ@t`-E-|$8UuT8Sy_R+YKuSo}oY!u5RIlE{LV=%cu5oqz{xhn|7-Y z^_{k3WEZvWX;wGx+zWA#S2R0iM}!Q2(t6l%@<_)qw32rkCJ>`uf_J>tO4Tupl**oS zxwWIHL?Um$c_o77yE+R-bilB|VS@{&tkD#XyQ@qf<W=(raebH`H10zrHQzUAX~IR3 zTf)ake0^Qb_sLj=#;V6J2T&F*W6h0>oqZD5ABx2!!q!4K!%M({<M^R&Mq1Xh)AGye z{toHWk#Oq7skDkm`VYqceP)~-i+oXnD8axp5ePA*ful+FIXi|jGfe^fEXe^rCC%p$ zVXE3>*s{~E!X}i~3vGGTUxFIjMpBHM>aWPQc}q_w+<SB><mU8iwbWjXxn8o#H)vBw z$w}cObzN^aJjX~$CL1}Pj;U5}L?pW_X0&%EI=A>ift)K02^Fnf2=M%h`M*&KhSGvS zg}8A<W8#rG8=C~Jy`dc63ci<qQJ`gCiS6&fJsQ+N6_n7B#4#qwq&=vQQ+qyj%_JlC zafXG7B}OytsLWcF^N=p)HkfIeTWnc0c`cuD{d<WK^EsvB*wR@v?W+SkchIu6fldBM zvo=sXgPG4OmCo&KKHiB?F@K?8A-&wLmE6mlC&v)n)sjafmD@?c|FGY6fahzn?Thhn zgcO{KX4HJ6+|IOkkjO~g;n?<?Y)tIBiaA4LSaS<bl1)v-gr0*yedmH0_rIY{iTE^l z$EmB97KsI4J0&ud=#OR6^fmdO2dUf@vjCPelGSRZ^K8m?EnCKIl9fQ{9l127`l-J* zs&gsgxe4#P7+8jMN4vnUPAmVAQA`0`18Sb!UMlK<P+8;pZ=<Gv63)4$l)7WmxHkj3 z!f4pbfhF?)6sxy@l!%SoeRshwm1?4^l0|2l*y<iDmmbjLeV$*+;7YaENIM#AN|;cF zB~*d|HcV!(g;9&tv!A<c46Ig{6x>CIks{6DQqp4EDNpQW-F`ji-<NuWx#%&J0QFYY zXhw)AEu|J^i;v%uVr2OK&>H+Rxo}kloo4%wnZ*H?$7zedxocu^&+yD{F(H|9#{ofb zarEgZyVUYBF_5!HhrA5Gd4INkZQAj5C&LD7q`F!Px0gyyP*VEc^JAb}L%uZ;FMrOS zQT)3$6`=ih8=<@A6u@o>NWJ)8Jl>Juq^h>UQQ45#kXBwL7#E|2Vw2I^Nh&Ozr<K;# zVbs2&8;%c@Tqf*FOA(6RYKQs53$(|UnB&6k^9xPRW35!#j?Wg!RJ%X(2;*0h#}0_; z2shn7l(FgdWvsyI*{sJhiV{~P9H62L_ID3$^wX-!C5ld+sD)joI-7d!Q}?rrZ@S#e zORpjEo&>p5nNC3OsoYPeZ?C!pblv*h$1V@nF8J;|D6sgHQlKSB&lFc_Vq~_iOKPXz zZ{oER6lGW&j`7{=x~zSM!mp>BUh?sR*fyTrG(G%qb!=>)?<-m=gQRk;fI*xZy=-b< zi(h$+RRZ=;XO>8BI53a^FR(8KQ16w;zn;Y0Lj;-^K@uKqsGNyd^rKS`n-j~EM2v4f zMSAn}C_6=U3=Dg%34|6L6EJ=D$LVtYv*s<2=YGj!o~FMNAFgmv-j9>qy1=g&te1*+ zw!?X1MBfOenO)TpZtAL8iV=MTX}H$S(56Uzt!NLZdcy|>o^B#b5=5?|+%0K}ccj1> zC3j8Pq*EsZj4P?Yv=JZ$xE`<;>7IMGmB5wos6XvN>fp-BB-1a~|NHsr)`XcM8@8)! zX2stXEJq|BmON}>is50W1&0w$L+FZVyY5b*H(Cq7bsRT$R_`q!4zbG<f2=2&1$+k- z&mWJ~_#5_su1d4pbAJ5?ymF`inx{=~wp3sPN3s*0-M@hn5`s1rzGIHpv)eQUiD7RE z!WsMnv`)<>Em?P|Y4z!XW4I=^;M4(AE4F>0V&IFjw?M5X*2i;6XUjRxVsaX4CFPHD z(mZp8VJ8JkDSFJA!s)8H+#G1PPyutbIk`+mga|Y3knoF6Wt+9>vI}(kKDw|&I?;{J zZcpeWKo2euzD_5dnNIrah;VeUF9wpF<lvh9%yJvB=(MMyJY2x}4(~MP22D;;_0EOQ z+ZoY2<5hD-8MGe+t(<&@T8&g6$@I!#0Neq=mQ=@WQ2jXS;iJhu&`96)zvr8mC-k@# zntL@|#?>T8nmX4wwG|W`#3jjE9gV#UYcg<$^B*6HuHO)R*;!equX(Hb-Lmm$y4K8T z+H#tvu0x_kMk?>|<}cOFRL^0MrdE2Xd2)hk@p+Lnd?L8!p5|w4GSVXMfpKyXNkzNh zYVsQrhT*vg&kQWKH2M%ZnvQ&t&JtNMSBmgPai<C)IjXkS!uy`-^g<>F_hu<u2Llgf zgRARaRij6ku^)0Yi@6ax4<sI4irY?<66Y#bIh)zgNl%<@mdgJu4)nfGjD7K+v(#PB zVb*B_3ki^lpwHJbVs|^%XEz|Qg<ZlzJ`I_DS{hYp$52xDjecsTa>-H-mhd2VsyQKu z9$3*rdZjajF5`aO#s7+87qXF{X1^2GSUG%q!gRBEb&tiyzPfqJ3Gr#Y@3HKyk=N<F zj*J0IQd9V`xObD0wzv<nVdcUC%UYXG=)#k>7l2-b%VEru#0E^i!`Yu^11~MZtmB@} zU*X9?Wma^a)s~Z@3G#3}ofm}R<LCL!?6yoT(18+`E%>j3O9!KM>22b(;9o%sG}*yA z6zB(cVGg_+%=Vw2Xc5O^lakRHWX>E{#M5BX+^$x+O$Mzk`{&80u7H}>8%lFVf|2m4 zsFM^3kP+^JmbyR-1ZBLhr0G2!76?xr$OsCNN{dxu6D<B9oT+7jDynJ4Ug;KG8z8vd zPb>PmS7%Zh#30dSB5Ru7UM-nbLk?dzN%WE(;^q?8>hSorewjTuKC{4lb^fkxvE}cD zM&xm(Uef$|qtKk^r)3$ZQhi5%l?|DxU+|8C6VUMNbl?_-an);6?c9Sl-gC7!f?bPm zK(Z@8o>gh_c`W?H{LpcyVpmmV&6xed>f#z{%(<J)(jm7%Azr*V^?FtI;NT7=MC86l zYwXWi3&y^l=0aMu&@Z%zpJp>PCjZ5!i+3$qx)Fn&#`iD5<-dWm+Vq>%-4jQp_BL)+ zBct?YjPyUUxf@(kO$t}%fxA;cH#Rym3K>0A!=`=g@Ku4{wm0sNHNEBG7kRo~{kAi@ zr7hRm_aIp2$jKizw8|O=vrt@)lf2TZw6`Xu?6G3n)IDalT5|I4xD`jgak;zSHQ2-W z*kdUpvLS_Zineq}l6O`x{91XJDTDZRJN?a@Sg&ZUCj_GVFoy9f(gj^Nb5*eE#kV8c zc4NEW<U<kX8{hOZOmUYOB})#KJzrZ6=9`><pHAU-7HW$PxLg_VQ$^I%94p-19ui*j zJDe>xyWK6g<mrHthe>(5s<V>u$p&Yq5_02hP;D(jO3>%r)qk5AFy{nDoeL0HwUci} zn||$5gK%upcPR00!AD^DG-{nu22$T|JZh)FZ}&U>@QA6N@|UsfD(FQJ%9nl$eG0R_ zWAaM;m^z>S?G*O!d@*v{dZpGvE;PDDbN8YNJ@ZG%@s}*Mi4&Q7i!Ow58aR<G9+Ox| zyo#PcG{|OzkRSyEX%=hR!huX!1kmn%-iITDs0EDUBR4zqWX^VmeEcRpRiqLyTl#T* z@EHbn76?>6NHM~5XJ9*=XEvWEa<XS>Nw>c%)#m<+9fnlAoY3cH<3p$I$R<!SDC$1H z0^f;elmvr!h6}N;iyM4;nlAiQc;lpG*-=KF6qmLIbmBU9E^T@PrB;!v+nsiUW;srJ zO&nf(?<n49`HA0iU(Od>vzLRWqrJ)UPM+NIQuD;=JSnS7%U+#Blv2#!AD=(}tFgbX z8rly%Nex-$oDLagSr@IIl)zO26<@-;N0jO&N(q_=A8+T`fvDYceV>jgl-o;gI(?Cy zM&qz0PuIR#WlP)NusfNu7+eDAg?OnE<oA!Ib5DM0pl-l$>N7r=jnqXmCRt@BndrC( zPlb8c6`Pd}LRTr5Gg$`&F%uDX0^CCLSim#7GMO7@ik+cY_72;UMY^G2K&;q-3FSV3 z0T-b%55)2;W$w>1C2QAnZTQo~%BYSybdOA!kQ&omy3Tnz4U^L_i%$a9S4_QH9h_Xg zmWhb~hbv>e=4rTjygOUxc7O#Kf$*XwA>fz_x#Gxevo!Fums^U<uqj=}BiG6I00%vn z;u|A{W=K|km@O7Bl(x%Ike_D;bD4^vVl3q<XD<Nz#{iJ66xvQU|Ec*)wtcX()`HB{ zj!mRW?>pFV5_L7OXzq`JLX<{ajZhHggvuHVv`{6A>mTO7F9CQH%dhOZKz&>?yd>;W z_Fd?W5|`gd+tm_da+i}%ePeB;W`F~{$WfdKVDPb4@XQn7&yRJpg0RGMj}^SNZN>QR zV?S8XInZ$P+Bf8aIGGrBQU<v8z>lor+O>LfUPwH*;N_vzY^Nj>31$lALkFN3d3^5O zA^!NT86(KF956atH=8fBw#yGt02@jdu;W}tU5@EM_9$`Zj|M8(`Z-zz7k(<Zo!{uY zQm44kZ1)&<N6ajd6Ra~+mAN?oA(5(jyc15o@sTHD1mk)of}9Ddh^Uv8A3C7mv#x}Z z%NtwKB2GCBb>MxP?5ur2`xLX=-L5YN?Q$pjLKOGOTl1yl$DZ4>iJu;y2{#?3B(h1K ztjNjAQ|&Vp^?Q_7BlDQz&&$;@vSUTt$(}Y7{@gXVk|gAi|CNfw9ffz82a<}{3Z`8o zfgg?Ci>|2M2f1Ff&+&F|>HoCl4kQqE*8iRyT+8KFe3og()+S5Bc>ibAyQ@nLh*?}D zZHoB%HeC3KM9ekyvxw5<0~Xs;)bqo{)nur45}Qz=?lwH7y@VP*UApBWrUlz5FiKbJ zg6!Q*)$@I(`)8xC?nF;Ux_u01)v3t!>xZTQMK~kGkWPUYJ5c+J%VH|8Kh0|-kq8ob zCDF+^z|~xX(T0=PMHO>u-g)jN*_i(kH_2K5EN(J+uKkZ8;>qcza2e@LulHw>W*yM$ zCB5^Hl*C1jdQA*5zZ}RXmGUW<ZTC0!6Cw)m1l7vW45<?8{mHsq$At!08Pg$3i+^q7 zAe72oOo9@<<Uj*T4E;yq3g=YRfY)3Q7=aC7CJQpBZN!}nz%t$Hs)8L*<FkU^MU(cp z&)pQuw_BP1Z(s?RP5`4{$f5#o14tPb3?>7`=KY^@-s1yX%{@9>4fkU1LtHo}^$~V! zr)yNT<Ze#(_vzH*sTj0+XjTSGH(Z#+ssJSHi=8cn_wf6`WNW60_kz6_06g~HFX~xh z#DD^*BHKN;t42n8fFg$M5=a+|<qo19SbdXg?ykd|FPGeG6U|L#l0#r9Z?c_Vj`E7P z4kE@B=90(=(TkK@)7eT^5fh=5Q!rVB+40<}%JG%=#1A-LYyX?74~E%Dq+`-_Kd9&Y zXuU}Dr`=8+%4PI~j+{63Fl}tpD96NSh}Ro(0<H!21-)%f5724Wa-FKDq#}s2@^BEa zf9mp)=w*riz5l*=ucRGC65AY1eJ&u+-1Pr$_N;U~m>=vMYDsCR_*3(v<yL<+H&m7f zx*~qI>bTs-!~gchm`~=rQBK_h6ejW><IeAG!-2KW;n^|_{6F1}8EY9$vfdTElJ^xd z8lH)lU?*&?qpQMVo^>n4QH>m{%x3uy#bk@h%)+a42|hiK#p6TB`S3?+Qq7VWZ!U8t zn^Ebelyq&TEv|1aH|0>m64ttHrnL2P%mR7`WBV!kyvmdKwbt;ssJ7JPk=G`)qTwX1 zHvEkC>%!&Krk$rq^EdC>sNjS);saT8tXXGTX4>HU(^UJW*j#~`Z5DMeSL<~F3;c$S zcw$^?e6@w0Xb&Y8NVs?}B-}X%?wpJve6#A0epv9R@-F7Um;5dGRoXi5(CNZvqw?M7 z7mrg^X%{Ax%EfSbf1%AS<3Fs^Sb3D$K)_462tn}D{g-(bz4vqFsF$C?MiaZV?gl*e z{NeolJVQI%d`b>ZD|2QB@VST&3z+7o!xLZ?4wG%~*K}WlfIyB=5VD=hQWBE0B2^sZ z7RH8ch!T|z9E@8Hnl!wzdt0GXd{#0IBlZpo{5Wk@8ti8ZvVXmyd*BjI+Ys79!xfFk zwEFOoJtXVd_m*wLT;c+Gf>W6)IoBrG4cct&yx!erGPX4_D*($jdxBdA{qbGB-aHPg zcZt6Ev_XqSO5n1flYf_#4ZX^Uam{Ovmo5>*YdwLT3{kh<9(;|<depGCh<Gw{ES?pS zabBjtiUBJj{{}T%ls3DgZ~XfpVm`0O<Hh3(cLhhoVF~(@EyX7F0+ylwg_RgZR$07! zMXZj?p$2!Ae19QVEXViRj5NKRr}-J*sjfLRXN9l*n6fTMpcQ0{U3CBJDh6p|U|K|T zWV}oWuR4ep+wr>l<-Xfthv`(Mr<K)rprzRv^xya=i|l=<SNToOAl5Bk{jV<neD6D_ z?TB8R8mrm))?`ura;|`c{oYsTX`24HK&E1-=7j(Lk4?G(RQ4~=1dOKmGJI{Npu*$x z=qau<cymg@EEjO+?_blf_IIuzyen_^ruk?%(|3+8LzFIX%H?O6eo}AqJAUoI`@A0A z!`=B!iJ&W_bu92fSVLm}?r!%7hrI9gvXtF6FA;Yek!Y*5*R(!)toihto_5L=+A5|y z>kHY0Y{5A<<$<V3;4GsL;3&;PcUb>J<afX@G0?W*VM}ijgf6|Kn58r5S)I#p+Mcs{ z%L>VeX*RX2Un}Bn`ev(r`PzKizh%Se-9{txcP`GqeJsf0P4}!}zWIw<J@1a_9%R4t z+@&iB^RO&~5%S_;C_1!^vKL_vFL(|fr5b8x7hYS%w0i&WfCgDUH&M&57F%q5#{=xF zQg{a_^mW$5jf;U!WTXi-jq=%o&bBw42Te9}7eQE2IvR)h#9n0|D;I^(mOgRLQ<lBn zeRq05C^K)cJ(&QJL&Hep^owEy8Hq}Z2A_+s&Hp>iRp*=e+hOBXIGiieXD;4$qLFjl zclPqf<@Fps?*8G-iY1B#3h>G|(qSC|k(5CIi*OZ-aLybD5eO+1@jq`#xe1XIL~Fe@ zJsN&(IovAsk|H+uW5d&{W4MQ5NB-_uSIoMzJ_xu%Ih~jRfyA2DRP`W?x#k=G8Pl2W z?B3^j=I+9IH9pgWIUvi-&Gq7#=g+p~ZTQ(z^{j?}GBc=fJWz4-=SU&-nt9wzdC@P2 z`qOxUAxc!{mMM@&l}ni0Gd>6swLCNq(0WbrU8fv*svdJwEOm3T9ENXF>GgzRiXfES zyJbW0GI1Ri2LoAg9KSwS^Y-5~kDlcBPVaTORq0Z0xcc^8vR{w9n3iRxRx$26W!t=B zrpo1=>Aurx98@vv<+%4qG1KCZ!47XF^I1WIOOZw{^cdu_wRUPNmeSY_?VL9zhg48W zD;A42zAq>_*Q%*gqwr268?HjC9IPkW#4e2gN6q-y-;~qus?8eM-Ct1Zz5K!>{E+YM zq#wQpITrP@ZIkNW>eI}wRNRK9G29LO@FWjiC)iFYVgZILa-X?Hr!gz1iRJVHn>#tD z**W`{D1xcWE>pgj>M!n8QoRyPk1~}G&K?~9x%D09Y}rtFEAwV#IlWk1lEoYC;7T{P zsttA$zo6}T%FNf?nKxX=+dTT6)a-D`3sZ5Mh2Oq#`KCMi<pPe^XHNSiQ@_(Z_&-pt zxd&BIA1UV>^)41!(kbr*mXN%y;q$WqiR$%XjzQP(6wNfQyL=@eSBzzFVu@wF=1B*= zuocQ74#Kvc0NFp#Ku)|z*h!`sug@uixU=z1!wz9pX5k!LaaCqDFI_DwLz{+aEavnn z&W{VvWYIhV9+`!QlKS100yAlI-<mO-2J*Xt9qP#ZgfO?f7lUPyV#I2BMCA}Gq{8h9 z+V3;DcP)+(BApZhcpxj0lHNu)KK8n~lm^X-D|vh1AeMqOFIq`S$%Of#^PAH2e%Gbi zWR<#5jCMs_uh*)-&!di;C%HEI9f?|0q`tRtg~gwZxGokqMRvf_uj!2}{Fpb59xO-H zEgtPq=FLndUYNm6$u0Bvhe`5$P2J`6uf78y=Pe;H>GP4mft<NA&7+m!D*AY8RGxl# zlaFn%-mHSJuMx@#9(eEWdwsL&V&GKW&IMnN?ILb|nmXH`2eu(xHAW<>mcu-=7JqXK zKMzkMdobW=1B-MWo{;j3(z7NzgNiu)RXm@Y0yM2rXqRX6#3H3C@&Yp!U<#VN2JKpJ zPewVI3cRO|aymVX6uf-Qao%F!6OZ~{!yDPhCvGLRK)2t`MWZKioR++X+NR*i!66xo zQll;!{HgGp+t-6PMm~)*$2|M1?=v=ddp`C2S$M{v7>%c!XSVp9bo6?+P4OhqwgGv3 zXX1raei_-fHs5Gn4Cr+r5A1zH7Cz_tNZBu=X3{pblSg_ewjQVM)>($Nvhg;i5|q|1 zTJYW&<pg^q4!%frJ#jCh$6sT`%t<U@vixX8a7%geRUPEz6=#niF~B!Bd9t~52){f@ z83iwv*CACN59i>9Rm+DjsY_IT*;rG!`wdKr>RqGA?V4MZLapeZY-H>h!#PefJ@5qq z8=sUmx+AaW=VLwT{-)<f2<&^;;l6>1c^^2xc*|THWp-4;RrAG@$ok#KGWBA6`JIZd zm`&!)ugTn$rEklzw7X`|Vn$eq(a7YY++a=9Feknk);Y{v=K;J(T1t0W??AsdLE-ry zzWPb{6t0^(b26)1`CXsY<{I;NonLsst)mjOO~i$jUHqS;v+!#AZR7BF!8U4)8V%d% z?iBfLFuJ=8x+JAbH@c-Il?D-&5-E|AuxLa?rKAJ|L<yC>p7&39&bgm+p8LL^&voUu zie}1|_{%x0`|h{%lx**0og2+Pyhj`<yJyr-zxx>ez$AN|{ARCXc+AZAv=y=4=^3VQ zu)@1$c)<Jkl-KY$!w{qO=~gr6j2PfsAp<hy8L^^Mg`@JnjYbtWV_)(sC1i^hi98>m zWn$gLH_d-8I3YghMjY@fg6GcX4JoHHO#EJsp;E7@X*F1bn3O;BUy>8>X5Od^*k~xd zoOLr*uj!h*!}Tuohpb$FPX8<k5WnWAm_6|j4L#g_Bh5N|U_1=+rB!Ndfpg{b&zT?; ze0V+^1vIR2gi&`$IDH_Q{Unu{v+}n61+`gck5e_bJrWWq7c=HQEG`t4pcxf(eAOQ7 z|KH!hXrOt$pTiLF49vaaSMbEr-|YQHtwFDoQMSm_VYxXo&*7FDlbs`j(=lmC+xX}B zf82MYUwcD;B^9o5R4CCdlv}La^k7jZW;PTC<F-v}U!5E+XzI`ClVE4LS1`*(&keRE z?|tEaApht5`$gJ6+S8A7o}k|py_-|GPbGb+w~jo7ET-|F8b$6OCpsirk2(3emuR#N zThyR(sJ9m#h}?}{^u`G?UF%Sm@kjKTA3-?H<e&OQ2~0UMIGr!fHmU5_+gW1mX;e)| z$wCv2DG_>kCx4p=kGM*qd)+B7+a3iQJJ~uarS=_(8~29@-`mN!>UVWYyw;xhnCVDe zc{{7Xs2FiiFTe6%>f5Qi6{3N8+XUs9NoZlmO9O!0;v>5+lK#5}aCN@h0}>oFO+W7? zq^|1abQq0xK?VIA+;w*ee(U;nGbM<p4V`U<`P!z}-~V@x65;%0B=XEq_*z4Q;rV`Z zp#Q{tVe84jjk>E%+FoIIDZbpEOpm$Jd<}_j@!{WKYH!Ir$3D@4?)RY7yI!|biFY{b zxaNHgYgW`cGP+xhE_DzZ+X)eYjlRb6utU(<HPo!TNj~R^DTSHqd%fee2SyKxe>@_t zE3}4LBZmx5ZF->%tE{jBI*n%uuk40dQ{Ohy6`P~jnOKCP?hng9ex|*ggj6MgxPxQT zf9}bY8R)srw&P_(XWN{hbXTAJr%QzVl0`GB7-s0#BjrE=6Y;JmrDPR+D9-89O(#du z5s5>$2FBw1UCyIWm$u>hvc>?lkBa7#24x|$)-OShrUlCT1~Jqboo{Ye*I1bnop-{u zO9PKPh}o0~JAMF6Q6YVNsssltBaa-GTcIBvW<wgFk^Dr<U0;i=Y&_}sl7(sK<b%kA z9ZQ$9aGusKk{p9=XMkk*b>B`@oA#p<?J_Hsrt8Xkt;1uoDvE+X>C+WF#2uqGS$4SX zqQ;G&zummOS>(f@9InDNMfhr%zTr|_6@SRnRw(R%W(mn`nt(PG>C%q)Bxg?BB1yI2 z3lCS%$Kx#xL(I1F>ojvxV2_|#Em2Y(<6)s)hD}|EvNt&t!A(D8Jc|tHOTMQhjDXhK zp1dQMdxUl5>u8>Sy$$!E{q~QO!<VUh=?+U?WisFzMAF}tV;|b;cqm)dy+y3yG#opm z4u&!;$lj(5wHlymwHH3-_<S*H()&ql6CF*6|5)!?;bGYR_PlR+fS)@#@Xf%B^xY0` z!@wFtQdZCNk7lXs(cQuX?t~8>0k4E_5bza7#tC$a--xH3&rFC%Rli=1Dh~)oNezY7 zj^+;+R2&h-XyMY4A4|>mJL=MidXR5Dg-0h-^=H4-jLSYw%lfweeVTuH&T?gWT3JHp zT|y$#sqgwCn(Fe(Gn)uUDCGC2k;lXe#{}j%6*<RYghBPE(dWBEu>=gM3Y{QcPBN*% zyR-<XIt)9AGru1rT84BBq^W7;sNJD%1(l}O2AQU&e+lXt_SbIc(PMIbc>g#0&wj7} z^@LZ`l(z|w)E@MX+z?G?Gt7U#n`!LrRPG<pRBvv$Q$M{tf_x#HLv7bn@lJzsi58Cn zWMl>t$Z$qpb=iMy5n2}Y86fdHYbThXbU+nTull7R&jCbmARQp*jqGSa;7tbA#F>xC zsRwtoH4~7WC8-D!wj4lFUGDVqc&P)qgEMx>_qGJ?@Csh(mYc#=0ZgiIsR3b=`dFq_ z>gY-2pelS~(6<e?!jb1j%sNK&rxl1HD(OO|q5VvN9+K&S-eFQ^8a=2?h5&Yk1MIxE zGIodMHm~o>dd~M22YXH+{(?GB7<gO(T7bxI2kK8E^D;>p$u_^F1LS>{vQ;RPa1@{k zATFYtsjma<p!LgM+OG$)5r$wqHOX&K+2idy{b;jYe6cp=4|RUvWJM_?_M%;4cBj9| zB3-G3lT|+URHs-d>Q3Mbn<w!|PH8;o#&n}ZI}nj7S^zkibw3+n=g*M2_pM45*l+Zb zPERn@QyxObHB_Mhz!`&-i=YFjEwtz>!}rgOMmW5irbf63@!oONVkEkMF=|6ErA5pj z{V+MA8IdX=)heQupb_;Bm*2=WHc;67a4Soa8GNG_OskIQPl$0ztB;Q}ke5GWYJK%q zc_m?{?U&e&X+zb!HVLDI-Yer-YS$Y1AMH6gRCg;(2hx%d+KtT=k#!_k0*i_1&maQo z%K-MD9b%6JNf|JoHP@G%vjWbS@}I`zJ7*K(lVZFomPD!=p7p~Vrlp_5Ec`3zq}BBv zlSfG3DijtP-wk|2MWvc0>;rhA;&ZwH%#9Nk%YHIKpFybn9Z~+uy~T$+a%yWvZ1Po) z8<`(IYCnIVUe>|Wa82fHcdduq&3^+!1&>myRIJn5rjr{>@fQ%aJz~Y`$3yy`#pgnu zo+Y4MedORsrmwSi2uORk2?xQIIkH)bH8H_gyFp7x-Zf&1%wilSBmq*PT_(RuQxYl~ zWPVZ=)s^<l=wg<;SS;wvQ<0^*S%}jcS;<$wDl{xIJ1AfNlgwR{@L*K4Qj1>^^VUpy z+WbvFA>*4kwLn@*L`5p28q++MjRpi|;BHHCtp%~2-M?M318<8#=`ID<(%MnW{hQ+~ zy8&i+udkoP!Z@%+r5T#lJ!&*c0-}sCy!lQe6!4vEdt?7P?Uyma5lAUq6hB_2dbNFt zd3xgHLgDvwoFbXB?Nwh@7mI0RXywFeoF24(k*t0?6jkJKGq7ToFCoyJ26QU2m(`xu zqm`a@C34JGpYA4x4<3gh0%Ga12fqV`;rA!g1~>0TAG6^>$OB%Pol(l^<{b*Ti5qg} zXwKf2%}hrPh(k#90-8B*tlez=E~V(mSh4+^f7A$!M4?V>Y;#l*G{E~dz3_jNJN%n$ z_1A`Dd#Iy!?jz)F@k6vx$O3c1`hzfX|6T2VT;T$CI11jXN5kOK5GVLbAVcjVVY-g> z9X(Wqx>C;^ZJEQulc0@Wxy~@Pz%hI_#J7V-s5S+mZiZ+n?3j%Lhbaue=^8gMIjXu` z$q+$@<h@|#xN)VXB;nW(Q&)^JlIzUHZTVnclC89hnETR*!dMaSc!S0~%`(5y#P>gn z!;!7SHxwC!p8c-0oMj<Cs!1&@Sy^!p6sarleH{rI;5<g*3MD~}67PJ<wSB{~XXw|{ zRzK=#AFU?PcllZ9f$_P0DyWY#ZWK(KEPbkiHA_%UPMQ3)u4X?dD-5XMS;nWVES$c3 zxySg=c0H<8MWB!MujY<R80Gk{P7fIS9xFV^qKO6rG-(Ym39XcXgf@YWtJBWwzY)~l zbt1&dcWUqf`~I<2;;jJ_2Ucp!y?kMzMnP%$XEiy7-ow4t(=~S+a&2}G`fH2JzE;Zz zy&hnS>&PNC+fF6uv%&LFw7kO#tcN-Hf3ycr?%`Ws+r_e$&a!SFSM&X3d3%{9JUakz z;&u1awYN0C6I?d*@LXlHVKN8>?QF=<n9l#rlvl*!W>gvm!Pg?eWu1O4IN~F4aCe|N zF!m;7w8})ge?w8T*4=Z7qA&Q=ZSyrdu13AR8cR9~>E)_TZm)3>we&)e_(z}&k9cU~ zLPm-+nO^&vaq8*Ht*eR<+o*e7n1*jz=6v#PqiS~9sbyN_r$&Wfh(Ws6PdGnSMT80+ z1N|C+3=&8g;ys%jrCcPd9DE+iJdV)0G@tW1w0(`^qfD9Y197o%OoA&an*@!5l30TJ z|0S!w@o(D3C;7PB_BM_=KSfDwC6M!G^m*cOA1&XXrC<6B26#!^`B8p1)US4p8&~Np z&eTm6Sj@blv+S|gsBFFTm<s<B+%f3dh)knajdx@h%zf!{Xv?=d7o>iAw=>Ax#iX*r z+X%|_UQg&2aLPrA1;nn3-hlN0&HMPB90p)%Dic`V!S8M{gzT<y{H_=+-fqeA3|!;; z^ZUM|G3)yV;!hA{K-x`inX}g*JMLNP7?D@(8QHgm`mT|l5J9e~L*ZA#QjdkE-iKk! zEGmgct4B{!H>DpGjH>eq4HtFawASjh5SEjqk-l->o7NdN{W4}1@AJmIq!@}_*3!G$ z7|4dw2`({=_?VpvaDM^jT?|6UXguP<FS&{1k3s!zn1lW><Ko5A7XJdc1u|OUCC@Q1 zs?l$JC$^#Z?bW%X(RX&tP?d^z;*I@{Vw!P@HFVgIy~{7t!18_UQL5-qhk7ax3Urml zYifHBe)LjmRyXE`4HcG{>y6*Ca)Y<LYFUH4Gi`#V(2sEOD6`>*Bl!lGzTz*<AT1jd zI^qTB1hUlh9^WtKUOlD)Uht+kWk;b>>DaMj`y1oGI&!`KLje<yeoaZoUk!46U;YIF z2bw`Y1N5r7<`<IYp0#B9v=4Eu;lHa*_io%?U*k2GvhHRG<dj1nKSuEA(VRE^NU##y z1d7&)hew2}`6zSH_s?G#n7*Z{v>@~PcIWztc}9*2Gs^2WQUQp_x~=u($i}hyOOIX` z9~@1~50s?!@K4_cy{c9~#%Q-cyP3NcfqDDDP*Y)5hG9@rMTPQEk=8N?eR@SUkG4Ba zXl<R6U<KQL8Iab=yqcNd3jyo{E|kU?|86~jaDM}y6^}okQ+{FXmWGRR70WeyG+91| z77a0Hd2?RON;PQ4V)xGEg0;?R@!A?;`^b%EF*SZk^x3y2dc}!hCh4{!+|U(?BFx)R zvGmZ{)fT2I-}#Ao|A(VWF7KUO#=v_eu)!zn-~bd@i5mi0Ha=B>;YMDcnxTXq(_!a9 z!07;PcYt?kfX79K?~VBLUn`u`51;R1dEV^1R=gfxl*BF~0nLgB=NXkUh)Gn{zJL#g zX1Bizqs8*joV_UzHAv_bKIn)yyW)k385uOw7vK7RVN-Po9AMNlMK7d}tQtkPzEd15 z=t0h!H9N~uLf`Bw8q_)_?R*Rk0>$}D1h9x3f`Q8}g^i^dC~TP|HYpJEPE_ZX3{@t> zM<yIM0xq=c^=QnQX9EQES2k^|aQ0#O&Qo^#cb4!;x9OZPyyh=pU_BVPi^T_1=tKR; zTQJ*6ACdk=#!aw>IMtCXX)*Cvqmh>4KIbtw?PZYkrdb4&MS&$8*5niz?QlwK(TTf& zo@ybR-9qQ9^2U<#&>I+*Z~FK#w$eZ$BqPzKqSIw4NX!MK0(&BI$a{Yu)9EZU--x@Y z=R01>nq1+Uq<gzFz`G3MZTBT>*6oVLeS+am0Zf_4A;u!<$%PRll0@-Gx#S86j!6uD zDT6Gt?1eNEqhV5)iW*X{`PN)R9BxRfTlpgYgVnA!ixe@^g<2%uOghFJ9M}vxrD)s9 zq=H>dq%(%3i=dGBbPK0do;&o|l2;WpJD4l$n3V6lPnodIugj4xJRS7BvxHs?^PtXG zeCL&KPn{*tuzVLF-p({Ehn$<3);~E9jvoA3<R)Y0!%m+yj1NG}UAKvQs8w`RC`Ih= zy){(>m*R_k0mfCe&(hewW)UZ^^?rUY9~|<2j*gkcQ}n)E^TzVE`a}_Vj<qME?CW_b zO_7Hw#g9c|+A;5UaoGIo_cR%Z1T6$9ej!bgxZHw84?>0D6eR_!TdT>g)BczYfAO4m zyYt)3jGDXvi5tLUH^*_y<AKXqp7|Z_&PKik5e1<ZE0<xO&HziK%L}n1Q9svGUrec3 zB0n{w(69YwQjiGG4UES_(R=Qm#0fc_;EN{n6{YX;jP3HqJ3{}mEa@(Cm&C9ZrfMWH z=Rf{ZG=^IEqYXJ!DKLZn;vWlCJm9Wo)I|YE%&Ch2qTKS;LFFAL7e3nq%(<SrtxMoi zS|*cj&`6suL|A9lfa}#3M&KrnG47xAkUw-kT`WlhzPev=paN|f9rF~df=Dg9s5QB1 zifayv{D?xEt;3Gx*k^SVnB_GB=!$VhEy4%=LX@A4L__ZznqhQW473~f#+}0iX+nP} zXVa7}G6I}FFrvT*0pScLoVJMqcH^P;ck??)9N!L^lT+{YLSy!k-fbqAUX=pN@4^c0 zI~Z=#CmNT_na7x{18XTJUfU{{7)zCFb-CGEs&usfNmg-JYnd+%nsp>AUS30%Zz08) zQ)9;KL>SwwB(Zc8IFZ-Y?Q8TlaEBp}XkXu-_$m{{ZOzHU(VBMAtvno^tC_QlSg8v- z&4lUojQRMu#JBCG-AY~n{|GkNv#1#4QDu3^+S`=Yg>sQ*t-9%xW9=8ec}1}^P!Ov= z=G<^>!xxAdTc%sjH>_41xuQw1NjV0$Q-Dh0p~pT(+u5RW^GHTbWDTnbmjE{#J+{}$ z{fVOEb*X1gRsC-^E5&MU0x?&Z<E+I8RYpayyeZ7HbEhNXedlAmugIJ`D}4J1KB&I< zk>Yjj>axCx$7VmTXTF_)X~u8p1miZSLCb&Kq_AFXI5(l?^$?+oF~b#U0zhTgl_dD| z(A8Y~`m~jshUs-FS9?+45g|Hmc#>@-E4F#oP7~Mih7q_T%`XwS(Xj2bnX~}5zT&N= z&rlT*RfxG#1B8HirWL*Jm`LoA`5G&E&nsWcRO^~6hpy@SSgv8RXLwBkCx%sN9s|hr zpBwuoU%CryZc~{m>bu8VXg)ol95-n>MEjU!jN{sM#P>V=1BP8yZNwXrQ|EtS#0>pp zA>d#MEQ_xnI$XLcP-Q+x8Hu|Y;QC<r$#pmml5M$X^Wc{H2`{5C_G(}V<20Yul;}P5 zb$M59dn@@r<kR+9&?)OJ5hi`<X{-hdHa7ttlcyyP_O%7uG2sl@nQ0${8uEw4Gf(2; ztm}ty{<npql&d43CnVTv29&ykUgH!Qhux%I1zzQ}WE_dyaV_D6EzlLZ2;oiyPWIgH zA`<s8NGImiXWEp}teq3C&rEzr&qRN*`Hbsh#8y8Q;bOn-DKo5+b9~0syih}E?DP{_ zp@ad0v5;Ghik5MrIu9uJ7BfgTvqWuoSLF^7x+k7Sd7j7Ycw3xgvvS%z$<Q-Xq~+;P zCr#(4nhU)RpNUXeG2u!*5}MT-$2aEsYb&LkIb;uXo{uJ3+lIocg2^aA3ERlzq9-}% z#$rxpjN5G8{uS0KlHqC-Kp*7Z_O;0SFD%kYp}Jlo?BG{NV$xhI@hcEnmuhEGl-w1M z&8*khp@$Ybxjn)erL;^-f6s;FcxMHx5f?CQSDsR1>8$@Odd8-My*?50W$j;G2xEUZ z=Z&xM?K(@9E2Zrv-}}CKo7w;@R1s_FMjU6Ab#Zc{vX*hSXR8hoYX4B^SSa8l9?>RK zg-u_NXhq&Vqa-?rS1T?S{R0MQ|B_p<3hm8_Hy<UuLksCt(Ztu%)Mbn2PQUkh^6v~D z#b#!VE+@!UYZ4Os$Ntvi+*|XJ;vYG9d+E;qINv^he~)rvX<PM<g<91;NDvxTx|>Pn zvy(}ZpdMr^x%N1&+_h!PYSbv@Z%k;WE?V+JzQ$Irxb|+;()pvW5rTy7s&Y+VOv!vv zm4RQINQ|H8*SdW<i&D-=A+`SNwr&+y)<IQBo<g;TJ5s&vO?(-Pw>i0l^1EAax0{P= zRyehYhRoNcSEVPc$-F>kz^iKS6I<-iYM(WWP0r<Xx}&b*2=4|HB^RrME<FqVSS?%a z*Oem(tD@9fq}UR?*&jrjqmsCbUHnjJY>aqa_>Z9ADVavKKVnr7&O?mV8fdFU5vf_u z<JgV)$omI$?#lwKzV?36Xqg@W+RC}^oC6t5CF;3-W-)N`Ta+m}uCR@pZ2q8+dasF8 z7T8i)=9Z7AuWd?H#tP7C>Y6?x)cJjw7q;G7cey0@MWN)Yl_6wb(>bn7b<6qIH<?)1 z1*SomZv{+ZY!mopJ!Y+q!YztbnYYRHCMvP+t?*S%@RXgVN)O#OMYR<#3fj74{9@`7 z^L(<LQvr8TzScD+HhAN%la|(W2j_VwLvM6Pv#86Z3+^(%sq<SFGZ7T_V(vf#ugt)? zJCvlJs3-JI8y8@i5S7BqP|s+oeTmhZo>e1$>Qvz@L1P2Y-$*|H$u`EOH}=HGiki#% zI#s$~&Ul-5e2DqO69sH`wN0i)i<FQ1b0^KTT8FvQH@2D%J^2IATi*P)G1vo}*Xzd7 zxxYTkOFKAcpnuQr6D#=Z@iT+cjp36gwOsIP#gIIO&#={#*3v!+@YHYhZVcDtGxFr6 zA<LY{%zYD~469?TvX#r`o)BiXavZfvvUD1MhI0V;iE4}udYQXJ)amb>(dEtwhf96j zZa%weB)LFS2is4$uD3c;UY*gN;N$`(NKc9~GcMRdU4HklneijvK=g;&jLc#A$&ad( z%h=C2x{5yBO(^{(S(j(%wxSBz%_l;zX4|TM^kS0Vr+L*_5o3|p^<AGnwTnDnn+-Sk z9Hg-sdTW#Lii_%d9_g0QwafE_=gz<PeZ4yQ8(D^Xp5`iT`uRTj16xb?Aa#;do(OGL z^!|<wbL(LQvu^2rkiPd}!0=(8GuJ5yOY6P+faV|X`2N)(?W5_(YW=cX(FH3~u8pPC z@ELu6s!k->A||onmsEdc4Xqt|`CY`PiLlr18nmo2bEZ5=x*l8Qg9$f%ohLU+o+-wC zvmC3r)~z_{ViqH4QStKQj}s^E59#HqA3m#YzUS+!<UDnr+$-3t_WiWGi?JJ0%!;L8 zT0i4_A@K)$73BvQnv7STt4nA89+-m>rJeqV0)bCxwm#mOrFtwHQqb{d{|n<_H0|vr z<z!K#-WX{_dnJ>QCZMnE_}JmF=Q@QK>&SEAY;m^2%fuwPM(JeKtN_3e0N{XeLQ!$U z{mgKN5w8dcz`)DI1;&6Y#s&oRIn`RcT4=_k=$}V`P$NzTfSW`eh+4kxO}yXYn_lYW zw_IiD_owQeF#KeaG*<_=d|i!pt~v-$mTRUa3DW0a##PMpY|>eR=-QnFbu!TO9E0ml zs3B-JtfV`ZR{8N#SIFl1k9w)=mwo>1ex0#ZZeAXMGxGrU&X}Y)FV{MX9RZDZi&tE~ zws&e%Ly(j+eW&i)>@}fK13%|BPzfC>Q39pt_%R;$%ZTPF?GCa4o`8*u4(LpF2cHE| zRDw=tR}FAEiT}slxr(8Q$D(+boSFw6iY{QEzdcs#Jw06K`rLC@`hNGV=(8@v>l%GA z@hF)8rt0OFgjRVBvZjF>7(1Lzuo}2bmFEH33q$#1G6`IUl24%|U%9`;60aZRkVS9$ zNQ9*~WL!rlwSxnS1@8HIXa@i(HOm1AwNSG_D~?%nMowpiNfK~+@P+UOWLE43tChKG z#6xHGFA&{-{4Si!MBlwY=I6|WDy4lBsd2FE>RzP&$u(Po0-p=d#zTUd*9k&&`2xT> z$1yjcw1hI(zN|D{O&D<&DkGSYtrGQKqz-e$!ymb2>jMJTE~zkcl^HWm&S8f-#l(~8 zT6z8Mt?G=`^{Rk4&f^>_dO<SrKKcw0KwbkaTL+_`HV=k)i2gI9aVZop;2A4aC-Y!A zq8_cU(voY{&Sx!+FH;&I6Rq>_*2#_-pm|SIZq8fyQ520x#T|8@5LSRxB{mZP>AIB7 zic}i2V!!sU7W9}$1YIKj8_?da?$F+9NE3gI=<kJiqp5m%W7mm+jZ%c5ZZ&X)^%WPw zv$$Ix_W6%oevz&Ep9<aQwriWP;m^9fvtGdPiXu|_!$WHXTv4Y@b6B!o=KK~~L*U>` zcuY_RSBUj|=Y_5fb|1p>^o6lkWK2C%yqt^d9TTi9&Ia>Kwds_2W-1`6ISMboIVfOm z5*YF~30y<99?i<}(0gy9zWYr@zAMx+z8vu&nD>iN^3`2D>v{%{9$);i+3oOmQA;+m zwdu^gbeER$XT>;Kw^KZ!OOqURp7e|JazD9B>ht1gwtcH_@i1HV{PakSlhOChS#086 z_qh`QN1)3wl@&LPxYm8mpbYHD*kgG4-Os8~e#}{yqz!NH3Cj50m3R0Uc4I0ePcdZk z;X2Jg-`B?$5|)96m-a%^%kQ(S;Ps3bCsQeqM3cLPMf(_t`q%}hT%&d^(FbuO1+BuL zyY##PTPCl^EE2|l8niApLVb_qBq$ZXP@xCmNO#oqkS}_(iiupiM>|A(9#gi){ik6> z`Ml*az_OocrKzihZYCACdpq{ZA+%!9s<>DxAczZ*O(K>3a(-h9bY^sCgrT5R_0H-a zGOJ*#RKs7t2e%qJS-exZ`!{rtbjQba)@Hb&QS|^*dz6{6p4?7eO5rbBanh<mBveo} zVE=wF4e52y#(^s!+^2J6015=4USrN8;0)3aBqZK8Cw<9YQEg7p7dsou1sW0v+yH5F zz)fF-d#uz4M$+Qk#wY@`U-KzHl#1Bl!8-D0=#TEGx5NX?^>#fl{YDq8Dkan3zFM1G zaYQ9ID64cz^8pRjUGSq<VlTHbAEDHFnkCH=%HCz#W~wM?HdMxfruLGu)n!iqYOdX) z75ws#cc+*e7!9p@!hV|&gYQE%SfpjH8#U>I<pC_BYKd^uyNiqhQS+#l1mcp!)WH>T zT(#GGKa1#QFQk*#2HwkVTIl*-SePBncv+{pqIjtXbpNBN)Z&rj5Kvq<7Ql#@#34vv z1&{k@5<Zdpt>dmCTG97+lg+>8DO(guB>D^@;STnNqkrH02ct$AC&Db#R<|(v5TVLA z??kwek#l)azMQMeG^O)ih(LhoMtaCy?Y4m$y!+)v>j)yWnA0sH<Uuh`lBp@a;s+oe zG<xX|VYc4DMy5nP`QHvWE94Ez@U*Nc0>{Nn0t1q~2(oGB*u+@blk6}boM~FvOD<yx zGnry@qbtYw-&0h|y?c)WHh(&PUL`&%rQVoUIhR@o_t)yU7Vv#gQb@6=lN0bwG2vRZ zWRS_#$CwL-!&mJl(!yo*E+=1Za;6Vo2=283iwSVWfgVadaIE(m!#biMfue_)SCwP7 zgt!Ep(?}J)s5q5-Rgc<EQl}HMR6)pZ^Ls_~G;eD6tdiEQtm)<Zp$Et};DZh~l@en5 ze3;&e1u7SjD22}@cxNt)eM17i5I%V$Q%^?;UU&B4=Q%9)FwSIa;9$p91JaV?7g*1= z6q4Ql&C;o*RVm$T*7wSAs=?Y^75ehz<3>@|yO-4n*;{iRp08cCVwAHte|dY!a7^2P z0I3At1Y7Kl4E(GDnHSQ3|1}Um8${<-X7!6_egOt3eVfH6Z}MoU3qvh@QA*~U7&>Rf z5$_uMiYB7~?|Q9vyQl|^CZUU7H2*=OceVtx&YW}DYs+H?XIkEMuVL!IJpPi`_S$X< z3A55=%{Lf>#j-S_ZQ5JbT8B73S95(_9*w&5s3g_~*OHqc{SN1sV+-z=I45|e6tFAX z^SI$D@}aL65!~#(jh7VbZA7mHFmY$-Q2D*7HQ@8ay?ksiEY5gn5Slq^8b7=(0qv64 zGqVR!TkMN;cc?WEKx+XCTvL~PBYgZ53=qU4k5qdjepi>mcwV{G-}LYC{tjL7UbQo9 z^Za_bb+)pjS7;RKy9#O!&?$#fLPe=^dJFZeCFcOX^{6?Ai>X-krT#;hx24uR6X-Gn z5s7}H7XGKwH}x*Rp^dF^HCyGvx%#%hP*{{^LWYAXt7;|0zQO3;7&Fex?&=Nk8^h~< zIYpc02KzYq-v2&b^0#0V(u%JN$@IUO%<Z;Ew<7wCvsFDEuLd1cnZMtI-1{NI<?tth zqH7tDan>0!n!I@WogmcTOMm4jMnkcIu<o0~Ih&gbV+_}hLx)^_Ofw{1pGGeF?L$2z zcq&7F|LLpW$DY@VxRVQ>`T@2571^!`xotap?*FoVRe7Yuk$+pnqwhSQ)#5Y$+2^#s zl68AnAom8NB+$z0mW_uA2$cPGI&Xhnbnx@*)6ldp@E<<I!tSqMGDll!%VX{S)COqY zgivfW=c$;J-5Grbm}}f_S=(M)v8DgIELRai4hf0`CegAj?Ek@lL7VF+J2zPw$lpUh zER?Af7AwC+2qZW~u<?!7$DrMuFwP`vg>aP>rQ~PaFD(VII_P;g)6cKsvWEhBlyy$o z4Ib<%S*6f-p8wViILg|NtuBPw#{%USrzwCT{{}J7xf?#4W$_g<S06O&on_QuW4(MT zqvn--so}PM+ieViduYILBuG}CU0Z&|tVf3ffRj@cP})|W(3V@Df8LrIO1yd^chS!< zg^`qzPmRMSJ`iA@RdV2Q3iHxU15m<6LL7e%{j^sdjFJK@i3(?)s3QL45O#KUqHLo} zx+R%_CaV%o-NfoyIph<BJsJIB%#H48FGfN>usNj4qxK7A%JmXU5ng)QDtC)g=k?gD zlOfP%SEP)7gD%QO(M9G^_J=2GGdLqIM|NOMEH0V<rU)PVux_juYcFM;Fd(0@rX+<L z;6{#xp<BSovl;X)SLHw;vk253D*L6ez=a5g#fDobdp5VYTaX;uRw!}qA3-%d4$>0) z7zzkEnL(1x`Z~B7E8U)+n8~s;D=rAPFC@#7)0I>6&{QJ&%a=}4SX(-id{ektuvc-! zSV?wfeLFWkEwhhRv6(^4NRj~*;|rK&qN%;4<#Wi)@^&2TCr)IpE>~J0747VDSf3Ku z8Wtd=`MQ!s9!O#bIex0)5A9++Nx7@&&8U`phsc~q24Rd3{Uk}^H(k<#j)X+LPz%m3 zgG^cU&g5&}LAUZUm5v#dgo;C*$?-q|&<xN~Gx3nDlPRpiXN)F(?@=OfrpGGrx1ns> zC_9sR7IyRa7>iQh1r$br`45^AynSP;GQ@u{>d-TgPgH_o8QA{{1ehV!6i~Ls#k*8| z2iXjNWK1cj;we$K-&V-f$s%4=--=GXrn`QaDZdcSo3do#r=xD&_LgfM-uO-QQ);#r zj?(|$Yn*Kmje{&_>m#7WV1v8rsk7oAZIx3&-uq9Pm)#2{AC%{@Y8?O!f1MbLLW@sk z3m6>O?j5Oz52;rRdh?>>+&V4MErsX-hnIP7GF!RvtP0l?xy{_7g!!wR!RC**Sb05C z8n#hu0vuf~j2`4z`oo|s1TX+L%Z^aatgA#*?(%+duFTJ`G~Pjff-{@q95O%!b=qm} zUPY76NeRQ%;txu?if_suURMyT_LZ;xii=myF=Uq2TOG;mndfc|PdI{?;XLfnhd~?p z@*i8W;j(d7JF(kS3>1?6r<TMdHMSeerUBRzxU5-vryqFK6rzmEsmx6tBf3Z3RCcfa zZZG9BSmNG&&u}(O*G|tR=lZV#0exIex(L|>F7b)=0TzXr7_Z4%3_Q<fI5}Wg$0PRx z8BPKAKCvhuyF5*h`DK?t6Vx}q1LXmVE;T@(CngEimoPK3?Vr`DuRKy2fG8*4r08fi zC0<{)C<5<DrmA`yKP&Ri(fo<c%%(hOvSyRtB-@WHHk_4kMuqXECh|0HX3UdObLR4j zGx9AVk4n|DTWkd`s2i`oED3Rb{71BCjx7+^A@5!!S$>AT3pj*>n#mnn=M@ZJ2*{7i z47X%!g}K<C(*TfWSBxwu)jjUW;6ZSbLy4O3`<=M<5R@KF`RQosUz?Csf@(zTy$+&y zQi_|UVf#%;i=JnZMliU|LH>#Zk4OUA>#)2^FcjA*`BtorKAcy2zV(7s>}|+v;8Tbl z7s5p~7dqtT&u0jqb4#+jNOuxj;mVP6Pq$}SB<({|(<9pJ8)eD$+vlVx2Mt<~AtL(O zkDU~7j-6<dfgcEbm(&qRiT1rgTX-?q`YW)>3D<p-U@&fgg-zy|Oruh#1R6($sutR6 z?Q#{{p5lA5=*@-8#X3DjIxke2bzT!qeml2pJ`mY?R{qM=!SGS!jjlV&_cF~3C?P`h z&Hy)x`twTJ!`Feb`3ytd^xqEyS4%mW><W+1uU5M=Lam8H+bX(D!kbz}FK9h=m6?aQ z*e{|>a%ep#9kZ`T70Ff><rF?IjYdtZnNpbnhMESI5Bo^yO3FVX|8j?{<A8BcWLw2Q zC9hnTU2~O4738bs6)~5hsQv&#QS9ruNkcZR(zM?<hE$wOUKfQe+B}C(rBLO7sK}o5 z=6n;(M1)ft&`(`XSs1Vh=RIf^oa<*e!&DlVaXy+txkvIn5M~xF>(3$!h@3Usa`B!S zvVj~P4eBQqe5<XVQ^`0BL6e0nQUTn8`SOjICO)o_Q@p=0m8bm!kxMK_z9>I3kRvuo zKP6DZDn|%&V2S{XIC;~{25KvfteN-Ukrf8LiU_QFKu@TGfWXFGdfa9;gxx+&WE*^d z8og2xCsF=yaTPNqc%5miIfnVkZZUk|*5bpq1)(QlT+GKkJq4wOGUSofoHuGl<73q+ z!%gxFaXrOcqk)8hPG4W8I$lR66$++uG2?9zxg*njv^Rr&$fHKst7nG$MK>*zkbT!X z37)S(*;JH&t*Iz8VdR}$<ty}|dW{pRoBQ2vC~rx-+}DcBB`T9+Fs64hs6;i?-i<QM zz)K8yFz`_5XH3!9&=k+!6yM&IV59XUH!}vW;g3aq%yDrSXD$qROZ&+s-2B>Niq;%> z=H_8Ggt0h15R$_=#TzMqV=8DV5hSRBq7rXSsGL#;O)%OeRjRvSNSc1F6L4pj)$O7o zIn>20TD^iAJ}_((HKS6ee*j4S1Q=8m=2s4%!_413u;P>8x#x{TWkFwjsJ}X2+OxN0 zS?>-OXl_1`Scv~LD@UmE%gFxt478E|TsJC;zS5J)k9Qw4dE@dms&YXE7M0VA`9dDv zc*=p$^69*Cj$OrR`3*T{;YaW1zCEq`y7+{L?Xh2%fXyq+dEdO!RO|0+xqc{CY9L|v zgLS?BPCvtJ_T?1x(i%b3GSnbGP3W?agZAG_EJrTvlEdJYX<=gxp+}2LgP)fC7{5F> zz<tomyxgOAo})a}HKvM!_b&|t0ITTy_}jpOm-;6a$W8p0LvuJJXE=EYrIBeja8y|z zJDV=)`w@OSfoyH)@+#ZY<V)&j*@5g6F=nBjFD4nha>S({Aq->XD_<+sUM3kZWRDrQ zw0-Sd@XVRL;qpp43(bGFEYq_3Y_BhsJeNg%k6zYV1%;SA@chBEI)c`cb}ctd^rBGI z)<1qgC6J(Apsei#1AKzXFz)@G8ul4_W(R*1?B2UHqc}bX(5w<@1P97SXUaL#%92+M z{X@mLOz*nW^If~;ufbP93I>)x)9<GK1SQ&LtqruQ>__`GR(7$=Y{AK&_ui`$d*}Z1 zLkZ@AbWqIWKAXv$O(C}!Bul@9-r8Pabj=Y(HaH>lQF3p}UtaP@c|Cqr%fse+Z*3Cs zVMD#4o`u=#a1ISxy3ZRWTjRSPNT;x|-D|@8-D&&83EA5G5RP4}=3)1|rOb@kn~~ZR zRbX}(fB!0y`4Q=f+FxX$)rVnTuZ0wbH#Vl{lKbl*Ubmy^R_MRFOHJhteNVZ#=B4pH zhId&R3%wagyGlZiBK!OvYq8$lw@&_0;I)srcJO|hiQk(M@3zt@R)BO`eQ*r0Ju#T5 zKHQBx3<W`(Wl>_k(JOritJdo~B!(|$^hO1|xa&vrt6Gx>2&fkdg8B*%Vh5IYX_rk2 z0?Tm59@)eFw0Iu86I{9Fn{+_tqPo^a_Q2U5+2Fe1hwYE(AlfP!W_|9jTK_RCGcYTW z7?YgdT0AK)_{y+?dHIv&r(1xeG!Jv?vT)3Buq`1JR!Q9r0JNjOY<9nGgwC%g3rf8> z*|=N&J^MKROHIwgg0lDI)TGlp3}+(2Y~JMzq_)hQJ7>kxLTOKs`;@@>nbuz=(&yFx z@#Z~2Qp}d_nw~$LINyA>l7Ig^xo-WD>F=iuOu_*S55CKtD*W#F{=3?=+mw#s*D`YU zfZpM><HeIdeG_NH0a|~ZW?oDG?USCls9<1rs9Zl__;tWw{omg&FV4e*{+?z3y&L&@ z`Od{1zRKBR1~g6Ea@ob<f2TF#l}n~g`^%$K(v;s5ziMbv=f@wu>H2eNL?0}JoDi7n zeMyXhCN=-^_1YO6ivH^hQ){}}SnVtU`{{N4d{OJiZXc$<jzyn9?^&KaUhatgwW}C& zI=yLHK}bXjI?QgF*XS4Aj7ed*-+i0%ha=<MwEVyN(<rI0i*w&>o1G~yvjl%DZfM0G zTp0HxQFBWfEwv8>JIwE2?T!4o|MlaEt5K5d#KxuYEN&^MLl*H{nkHXV!)^(h)?N8< z<o<@6>dR~R_p;|fsb9x`Y)JAphbA7LeJuI#^TtAp`^2^Fi7%=V7pIYs`K-@<p}*IE z-a0|y{MN?{q&-a{16QJdCjGv4;`>D-;3%Zg^8J%9^Yd?C-Vwh3IcB`*GwnB}%ljvN zH<re(u8rR5Ib7TP`F-=ti$6btmvWGbQ8XFf??(*>jmjqu{`gKn@aJbg8Q|RY<aO$` zhm&?X4+Us$50mTVW4X%?h%A;?<_&MpyY{#NCP%ubdf?8r`!~^6qr<Gxl;cBPjN;;M z<>2Xur1pr2wWK@%oV~^uG)>mMe><-I$Ux%ul7vwA?s)S3D5j=*Zp{)pCnWcWNMS>z zk0E(4B$cB#%WkuzwHnEP>u2Oi`V;xX6c0(1e3#t&TDLxCm;h&#FKy>H{sS!tu`qa@ zCjai%{^2IC-yi*&DWTt|quk*c509;^EER9Gq1dRN>Wj|GCYxH{c>2@kzVFPOlF6ZL zjX5O3YXuf`L>T3{l4l)epA+JaFbF|YFOxXHb{Mg+VaDXy{-U4190SFtH~7@SBD!Tl z;sYDG*D5~DPXw+NDBJ(1rQpfo)lL{q0@P07Tz(ze@XwL7O6=A_BNSFRlW&wa6KBX9 z^B?!(#XD3cQOp-qobF4h7!qs6mAvJ2LnT$c;9-!Rd+-Hfna)dJBhsTp@R+&$riZpJ zcgou{VW*J!rbw@<*E7jjG9WV58UAK!!`p62TeqS*z2kgmW9O-#r*Fl8j(KGZI@-7A zAZLrGeI^U>LXRp+*d_SQcHv&kq=(2}GmqR)->0I3TmjvD=fA)Af8*`#9Hi&#Js3*# z_;WDIb*JoLSdd}qXdLvSH)!-j7UKKU%K?ax=Z81ck00$8HXNke)r$nb;-^{;sh069 z4IbX^xEemD%vXk8m_lmotuWiF??u0P%p_Pm9(Hlo`U-?U51yd->2U+i@B5<m+9s|! z`aM6<__OzN<s$lE{C(l?A3f5yV@^MfYTP>i5`Mq(_xp+aw+_EQ;iFK-8AzXgUkCm0 z?ECw5BI@Gfb>Q23jpMU`C<Hg(saVAGi<bene$HGwuR9^^)S4zNRDXu^i)g}WvTwuP z_^3?T`_eKd<7BTm)4WjbXOTkP;+}N|^LXL82D8bEA@`3F>@0jlC_=-|g}K;{QAlSh zl{LtPRnkIRRFg5?u%?QoO^;F9BnRgh<HGi=;iZgFP=+@Y%-P~KBGWyUj&`o*6xJM3 zip$9eY_H;-(Hp(|_%P#EOf_arZ%mc5^-kKKRpQRrsE)yU4pWBjD(eRkUD?mFX_|m0 zF9#C}z@9;=+yDTO5CX&iJMh08B!U8f5ZwP)(jl0|u8cKT4ke@b4a)Rds<acn%Q1y) zzH`#ag#3qI-`cMpPrQ(7yfWTe`}(eo>#H*Twz{{aD#2nb9~k?4qE9ZU3q;$uUStC* zX|v<)4`%Akstw8wo;JP>*QY)gcbL4d;x}3Lc6Hs`3?p~7ajBDBEt&N+@O_87qc-h5 zLV|iw>sPvBrJ!@Vn?F-$8&`%>n8mNX={(eK0)L{qY%p1-bhQojJXMZA9tuaIFe+yK zBme}V$ye&{e){b_%!&d3_MEgu#UNH8!t`}Q&}y<dmAUL`^V-^2p7`~5>Rmcn1lqLV zjR(j(>>NTWDo!Q%ZOF1Vgkp!krw&YRQWajme(mzs$+~trY~p$UE*OE<TR;uzS6o@h zcQrG(tmwH+MhG=5$FaLVox@)v@TYPAbAp4s8|T8fB9YCT{Sj-DfuA7^y}GDWAp5i* zFVY9+jQ*CW@&yDm==6ix%a)0J&k@P*@cCFMOFR+ny`H1jIBOmPejfi;&};#(30>j< zfXuU0#A+mW-PTt;V}j@gp2>^_L_jr(WT*0Uuw5^(!I=?Y`hP%g35HA|rnxb{wm0v; zu7z?CR<|tROjr!c(R-EAjn@l>VDTX2bt@1wnerpeY9Of%f&>MylRMo_U);M2D3WHY zv8iK6%vdXml3>j5wt#o{?FjY85j<(~y$N@jtO!(KM#tS|m~q8!>l<W(1n`P8|3Tf0 zxJZv0k*pKv>W<=UB7b*7<IcnN!W;WtysRQ-{3bxf768LEZ&c@^YeWeHyyCmfBi+N& zz#m+XMEl*s$bctcLPek^jJp|xyp7;D(I9B1?7w99^mTF~WL?TG*kK(O9XvsXc)wuh z&X<EpxMqU@=^=?pnDl#zwzn!nMn7Ilo@5ZHBq5Uj{x=0gp~9h<e**-+1vy#Gb7<Y+ ztd;E^i<up3M82>YyBjY+bBDVB`N_2sxqhH5(+uXz);<6O0x`;P<XgX!j}b54{`#!= zo5FqE1}|vBrB!hN(oo?hY|UJT^8Tq|d`Y|!pNIr-RFZ#gP)8X4RjNb?>@hZj10i^| zZPv(&Zg}0ZtZqWYP#O7)L}^*T_&-^3RcfWCAyjnH>d)!HFx&OXdsKg`=|v5#`mc^{ z#-^Axk6cKY?a_4gsSzGNG%-UgC-Z3lSavIovz2%NK<qx0&fex7rjPm@)fTJN;;Bo! zS0`8}98e~L7%s1w7g*ysAaQE(0%bwTuUbYhDEz_(O;rbZ*cWnBoM*>sRD&FXip8E{ zwEN+MhvlXi0RgP0m8V+Q)OU|}ayHFlg_oKi=wm4I0IUj6gTWpo<F8ngDf`Ye;#V3J zgdK9AhoP4j=+{F(r{9OatRIZaf0D+CC8I$V+Dvw`iFQP1f(H8w<U*!DP{HvFZBd6f zHZ{a?lJL2cG{GpS0O3tFZ$U7FI*kCmkO+V@X6ZmI?_+$U9k-!_WMssXcqeWI^}A=< zalTVfh%89Rv|ryuswS^O9Rw(NXG`7so&XWO{u}7moc`eFA*Yp67xKOeNj(fOH-qJ} zH2dR^Z{F#r6S8bRLcYRRGkj$h0N0$5^dy6Bvsel6Z*Pp9l9$sE#We!@qA2E+*3!!3 z8bY5vilyjB83g1`P#8BMN95#RQ~#>?aa8kPLKYL4{$X>{hVqD6UpfnJ2jXkSzWKM} z^vR*l#oCZapkpa#MfIA^X%*uc#`X9H;{8jqXZnR@%v21F^_r{tefnun;`e7N6eJN6 zZzZAs37;k?A<1{*mLa^m0O|5k(B!>y7TlPYuEB5+Ery6O;WO}Qom9%sPu!1f`hz>` z^wR$aXRo$l9izsJp@JLTsGP2n@%>`iEJcb`SG5s(s^fG1E{gXYSnk7hN5_h%GBT-B z?=*<vK|l==W6PeRF?%>O$XSTp*oucPTW52Lt-G80VRx3oH4PpImr<#Hqp`r)0PT1| zNyMHf$MlC5&YDN?l{)I~1#RnA(=<+^E9cK*ISxt`eH4Hqi|@*!Bv3@3v*m5)WG<ui zzt(If|5TDhfy*Wj=tAUg)SSsV=r{Qklu>Orc`@S_r`|cis8h)iqvD_AvY%mVCHK6a zs~Lpl9@XsU;b`4UJ7}1EeIuVw156|^5g^qEPJ)8qF_U1%p?_CUWCO=;9#>;@Ka>^W z%NVEc4+eVttiKan0MgOOa@!X{>13*-PfVrkfY5~$!Gi8uLPk*!bm}0HV83Eeck^+2 zO~4y<+vZ&I8-NLb013j`B}}JdFMof-@AQ+C)$qm>ZlW6EgP(Vmh`m^yAc6sR4rfFc z3<mmfmkPYW8hrY)Qu{ESI?krK>L;aI<X~M{(x@-LFz6Kuozfb`3WA~5b$lk1a&nBe z_~t8h_H*w&|Mg5qdyxK?Wo@7hD9{FIa%$%qQAl%CN12EZ!zy6-;@9dZvr^6hSD~K- zAK)4**YMm|$rLZ;-yR`#Gr0mhh;LgTXBTnnNeTuqH+Jk5fUbLTEUe%^iz+wrQl-%m zCnCPwI-4#5nfc_>efQU@s5T$lnGzvcf{q^w%72RS1Cbo(%l*UFNSJ+CKRpzDmmKi{ zyL`0`ula3*rJc2>T0P}_^}XKgWoth}Uk`|m{Hv>OTA2H%$+IQpyJ;uXk(Z}NDy2`{ z?n)(u@S5=n1p9sR5B@a`r5pw}4PEh%YSWgYk9_7hYy2aWR^St@x3Z?y^A(QXqM=WM z4`0x(j?ZP857y2E(MbXTmEN)uqgOweDUbwmTSmR0rwfpL7pmdjdn1lJ1wv<EmxmqB z2%ZbGF~5{;m>fNPjtsuy|9C%Ke0U$S0s<oXPx^kBe~<ifsr%4BJN$jLB)DauXz%$~ za)|AWm+?cJ7n=lBe$IRE(thlORTb6bmL-6Kt6v;u-8$vBxoR34%z^;?@YqF()~ipc zq;xv3u>*d7ZENn&x0BwK9>AueKhaKylMnjgW2SvacfUj8B`6ru^|4-1;C^u4hu+ms z`+bte-tqa|1$Xb?q%6O(!X48IG=p<EcdRFFjUF?~EvA6MgMG6JzN8S*P|yCJSHA+k zU%YIziJe!DpdE+-CS&l~B$`eVT_*_upwu~}=;RngWw<&i7$VCy6CP0B;Vruye9s+K z`_<Zy)s#aKRTM6I9xvk)2k>E>;;8;TDQ_v*vBp^#fe)jgsLM{P62G*~%|q?;bWtMx z_5tssS8aTblwu>`!PM9olo!gplcZ^uXk(WM1SUE(Btri!gSKME*<y!Jyf;V467$X< zzIxcZU+ofd=0g3)HmiCz7zr`wWH|tB>9W_`#>c3zeqToB6JX8tUa%RfR)}G3zKP)b z*jAWJ5M|RHp%m~_C}wmsQKcdxfDFOop+r3DtuT~9CDE}cvBE3SUN6nDD6K*SWoL(? zXHR_lEPU{8a4OvAWW=Wo9iFS~TGgKNO$*if^~U)SPCOTYWdnSZkYp#M?f_B;#v;Fv zJk8F0JA!3{1ZTqE&Z_m42=#*#z@;H5os?Md!iXvlNXp&t2sl)Q1b&!E+qq1CkV0#E z02MHUs5(K3W{E^pVtGp19|TaQk`0y3hI(hiR8eIjC`u8^ZXpevLt^oYL69Sq%^+!a z6TFH%vQ9k8iKrr?g>VhfMWryP0(#CQiUac&$f8aUa%b4{<gpx;$(h37(BG6i>BtTZ zpYR*cbiG|(=3p1RC4aeBD8)LRlGL5R$DNQ%W-t#YSTw3YVG`_k06owHpLszc=1|0k zRQl}#fCSYB0C(>~?d(FIu0r1r*)&}!6e7(W5gUGjuAC>YZrs*7$zcsM|E+88H>28n z1Xu{86f{AB*>t)qvT`4a&{MivFkqr1Ufm8wVpe;iWnY{S4H>X5N^*agl(W^D;Isu% z2huJbKpinKkACR?C_3+Ws{TKYpF7>l#kH?}?{#s_t}PjNk(m)f#wE!tt3v8~7w$#6 zgoNsnB%_c@8C};%qKt-684a4+TKxR}JAa-(&g1<#pZELqem*^!*;}zJ7X~y@1ov-+ z#I8a+4WL&Ipoy2t;l)rW3px;7J(O9!hYt-iC|B^!Nn7EM-`MYp+%xwYjV0S04v0`9 z<-v*p{3<v|Sh2AoG%X4~i(ZfoN>MyBzuEK&bqKOt+~+8nl4@YH|Hq+HS3YYzuG~^s z=`Vsiu2zTMExU*ST#}*JPFHy|;gAuiOLDmzx<+iU=@Y8~d}=(fHEOqN)GDi8Ni}<r za#CB-DJ%JC+k)(i=W1O_yPqT_zBwgY2DM$?^L^1pTL(SAvJ2L?^G?iJ$6IpS+fWwR z?dMYUbeFbzze0ce^`B7)dg>-RJXW~N4dw|z9ajY|Kt9B-D)g<;WghC&D)F5McPCYO z2%%o{XiR*K%B}kSzw12!0GnSfky0M!iq=)ju77%1bogk9H9Fz-e>e7l-}a~Lv^p3K z9%oSTQX8cIHm%rT9M*9{)+yu?d_rz98PYbPrS-&rOFyW!Y?EQ0`saG;L;VBa4y9$- z6daDf;3=qNt}=sXszO7W_69e(_|&@qFkdDTXodJ=Vc-d9iXGZ3xp_FNIccQ+p5(=p zkY<Ej%^kPum=%FEE4#Up^~IVAt%-}WO2_U^$CFD4Xs3l!b;n_NOKM42<fU>+9)L#5 zk$^AlfcImgU-BMb(!8c0hD(`+Xatsiamg^(FHqoLq>i6(NiIudLPO%4poZ0$5VZR| z)Jq6eGJ@T_2}xuKJ;qJJ3sC&FcActbfYE+8zd2zBtyzgabSodymcNr&Ea6%V-Dp#8 z2rR023@+Xmn35azIelM+zQJ^DEEpsKtm*)(9-I0JcRd-$ankEP19`!f^nfE32hkO; z<L$R+i&YBHYt^!Ajo#=cx=)j*4-}eJgKVq!nuqQkfh97Lx9-Ax1ocvsc3|98r|ZU% z-R%boZVct$7?G44i9_%Im5;_0z&<P6Fyc3-@l^q-wYOYl;3hv8gMPAQ6rOZU4QK6L zG=Tc*ks%&63QqdAd&t2dHC9nCa~VyIhe0!qX~?VHNQ5^7o+!GY+z3VDI-!(yycDn< zKpbJhJCmV)^H5(=H`W8~gYKEALW{R`_s^o)QZ1<=&2GZ#yo8IejfLu+71`ERtd+Hk z*yRkPc{eo?pd;`j4BGkWnTLx@04A(lsC3qY!<NsYGIZVdnh&K?%Dd1+awGV2lyl}O zYjt7NYz`@*JoqiN5!vp7ttQ^Pjyr-T%vx=pl{>I7KN9jL5^>L{S=+d0LLFv2Cq~wY z4gaDa%wC7oRL`sT-VYY`?LybUV@!U8#XSZa3c+3@&Mt49aRcrO_4{%vOalEN=2&zo zCHhZQ;?Hrp4F*Ei2hdmq?(d~MR<^-P+`gD2GGR1AKG(hSs5O(is$*BRWBgoOJTzw; zIwj-|0@OcwPt14=Wsq-d6T$(k7(O93_C)8t7w2xwSxtKM6lt`8Q#v0t3jVAK{-|ca z`dEwbbcipQ792pt*olb-){T1jWLR&&;D<b=MJD)zs>qRu7UZNC=c1d{TfrXatFe`Z ze{$^X1#vffuJXJ5MVo&KT}fH(qI)+a<Y3*E!{C%*a33tR6&5=V6NkWZ-ivvO!;s?P zxoYv$ZuHRvwCD(W@^=sN=}=-dTIJ^6Uoo2>d}O?ZFMjgumT`z*^T?$qNICL<krqb| z?)B1-4wL9kL-lpS7lzJYMsaEvuNuI;u{X9eNBg$*zi1xjhr)aTK(l2`+eG|CP?b0j z^JBmQvEl&H#60T0)`tn>(aE{FiOdbu)XPHjs2y59zg$PH_raxcq;HG`8AALKtV<rK zb_+;3NL`-UA_ssb6}Bu(V1BGBfaQ+={kwCK3_W#nTPGyaug(!i_Iu&arLM%GvgP)< zwTOf3J$=TGkh>uZeNWWKw7SRCTgCt%l@K9}V+`{Z!lOoDd$7&NT42O8)6&J$#GXmB zo+n#c(1#t+m^1a|XX?ids|Qp^9W<|cH*lk0_iL0xRunT~3(jRn9DbDP<!<!_7+Jwb zg9Hmm-$UpFkks<%uv>Rh`%bldXhuIYyoi0<mAd=-_T<g*0s28GT2ph%=-=FfvFShn z;J1w7n-Phv5aue(ZyW~Rn0PXO2E8B+@RDG!l3-aTXzagf<&^u1l{L@)lz$0BOH>VA zfdh1}qgISStbyAuk0gg6e7-y=n1MdRe$=K(Z~l4PGWE({8_=m0R~z__(wLdq!$;@b zGw$5Umqk_YdD{Nz8B}QucH<I4UE`_b=ZOI9v-#uG5VPkmO<)WxESlNnDTIg2!|a~J z!i2Er&(QYwmrT~5P4zr63VZqBpZKuDQ{1-hJNY$oGi9*06B!{_k$o+I5CjOp(PdsR zxk7^}7x08rYKK(s=DHFinsj<zOrMQqZyAsu@-3TrLD(ZxGcFs79#MUDD75*YJ<?kQ z4@HYDpN;yqP9E8Cct-SkZu0zzy$s;A18ukCx!&<--mMZzLKuStr+j>NM(ZW)^YXd% zWl}ggU-~J+cUe2}{z&&`3X64XuJdbdybTHR{&#T2P{51QgxDJ(qdnImz5o|}&_Bp2 zi86Et5cJ#=KVw+q?S}v84Uspi9}n3S%Qd6ZMy_Xc-|!Q`6~<r&Uc)c!(JNlh!DesI zJEG6Z0Fh`oWBeln{b?VtoQOpP0`Q3WkJS35zxO{uCO$>BE}fHEfr8$?c=n{AXj$5< zU%9DW@%LK<=qlMO%~F`rwzmJgb3#d;TO+~Q>!?BcvMD$j3c-aA9(s>>DPurEDKWJL zQLcd25N_ilRpWc@$GMAWvx_tLR-ZI=$F#!YMR0ucWLC@AF)#G?D<ADYehO!xK@UCx z^RUm3aNkd`@*-ps`um6HA5k?+yR}zOe*A=(SaS7#Ua&qnY5x&6VU@KTJ#Ki{4^zy# zp{(TnP?GtzI+#7Da|~hg`r~AJ7n(!dplL41hGDOLr&1svUYv<T*Sw0m^fp`L>>Il< zbotRK7;b4d1MYBka^HcEk`v$lu73}e{l2->__^p4gY-$E1rfdqtI~qY;{Jqt{|3wb zaMxa`zx;e6aoJL{hfwfzIlKRy*WrO9pb*oW{IypGu7$E9wM>NUZ^2H4<C+>ob$UFP zBx|y^andDS$2n;^3d(vVnessb_qVSAjUR=@`&`G*J(2PKQ+MDGr0x5j<c&4&@0+&b zedtdBjyHDFZC|$l2VtOqTxnH2!NO&6z%0@@Bz>5KqHWRK7V~}*#w;%kz_{>B+Hi{H zKIV3DliUUQGOHx;e4h_RplZ24h5*7sX|jMFX;jn-rXf+9#sHQKvvaW<1ts6{c@cQj zspl9>J@9={``)p$&Q*aQLawXY;E3ZSYX1d*ln5|y5c`FICt&M))!9Yen$@8A#Yzv* zmkE2^jCXEVGmQoI7B4>X=s%$j3hj1HsS)#Kw%d62w~p26he9*Ars*xvc-J=6^|-{} z-`+e>aRRS>xR&n*7--f;Be6GWr)A<|2-Jav$ZE%IKv=v67N|<^LluF9gZYZm-cZfA z0!VnC7l@nzFhC%g8S`75!yhAd0UPVrU?eg~;{QrIS^t%@&1!a{OSyywDGthZUI>vT z1K5V!o40mYUI^j=PJKVX9H^A%$T0C3ck$LTtv_z&28wb~QqFbLg>{wojczxd#$T1j z<@u$>9^XO)4GdX{T$fNl6vy2CDRb1TBUewdU#g&^o2PT7nGtIX@Ms44<(SPpSjE|U z4Ll`_+K;#1Wgw`mckzsd+>cS1=A6$MDz3Gc3uas?Bvb$!%$q{6khyC;1p@pBxaK)Q zw+veD^s;%S*nFfrVHlMAy8RyR$FVO0oKye1%X%8-^7ytO)sl~1KuEM}{m^)Kob8fl zWnsRFUoon1%vSR9jpOb#;z({CA>p{ibKoV?>ba|lbkdD~akF|g*^?c-^n_sxfbQoe zrP)XLSZD6rc$Xg*<}U}V)Hd-YG}u^_w}Vq?UyXF0nk22NGK;~IKm+r~vo)v^S{~aj zbVe0y8S2#g?|G&KkZ8!00(?)qD;l(cl}`jzg&#yXA5l*|>HON<{cC4#a|75j?;(jJ z>D;~wMv*e6VsYnnZ%L0F*aKm@mUX|nUO!D#<!zMcRoz#PznC|t9I6juA`)@l{lgx) z<4LaD^E}lqOJ+p)^SuB;!_SNFFe5bs>Yj;K^v|P90tSEzyz78)xi7$}R{z?v=Z<!s zeJaSQg&Qg11`}RJS<hq7OYd~9>CXKd6HCtxI(r{yQ!L!A8}`U=mz47%22C&uU@CRe zlqA)yTF%^8V_I>wj~!n)V17(``wudwX7Oa+dIm5fQcE~+?t9iq<t^i%i5=>1*#x8H zL$jTgS{x)`{i^)(Ud3G+6vRV|O5A|cw)BQAC<FV0;GY<FKFAy^lkIw+DM4p|HQU=Z z=4ya)^`{%=skl67J<fov+Mvef`~uBy>_?>p%Pl{~hk}G#t<28R((A7lH_+vF&$HEr zR$(<b6O>e3`BhA9i&e5mmRKjeBVQudU&xXyC20kfEZZ-CSj|H5k6#yNsJCWs$qvCp z%<fOsQy6*4bxl_2-CU9FE?W+;A)?L#tC|6z`&+npNk0<6EV;Q4Bt;T|)FNd8Pl}%; zG#U%zWB==1(q3Gxf-FJ+Wa>xauLNEmHLo4h&<xj$=T(y%O5~oqA5C3)<mNB71`55C zUYVDx_)Vx;HAKeRcn&}5EiX>ey(0baycTo+FE~XAQb<ppR2QduL@7^Yif1c7?dMcI zwXI9U-dvO{fGD4~*GD#Q?BTWSr*dR#Q;yrTF?_yBFz@SLz^y~bV)|aDo#kbmlv=d? ztE~^NcuHyl<1R2bpfoTs5$$qU8@V3Um&@egTFf=8_fOtBeR|c1s4An}S7*8!hCJNZ zQLYxPdbu*%!z!uuLj1rNcuD!gI>MRf>f~GQRtR>MZj!61X6n5aC5uy??_*s=2i4WH zbO~)b$dnl+_soMS$n9QKzc=uv!ek5mD~njYC$^Z}I&6Tnsv^x=bXL+|7>(}K2@Mn# zf$gHBzR?pxK)(!NnTcRHLs3W7&%BI@bx;?dbN_pxq}p;|uQY{<RBz`h+;7seo0|CP z-;Um60G4j~mcOC6FJ$MQb?AjX#r^6p$KjNQK9{u4S22B2JKz5Esk733E_<WiAt#og z6OM38eDVYTRrNZKeL<-uS`1EFtfO1|=$!o<6Hq3=I&AN|r}0iKfZJk05E0W_EwAWm z<D*+oa^@Tya|&UW#5108!>@rEL6>}bdP{1VgesVO+m3*I5L`%8RTx?18At|V-CQ+l zr;l?fv9z5KrI6F3m45{tmd7u7TBJ@^4YP2m%vO!^U2r=Ry+XPxnX8Ec5Kk2AZH~wB z;<gTII$k<`9#^&f+pO3x7ioOFErwP|h9+s%9F<wX0+L^Gxy|#9$9{Pr$eX2*!7w-! zjez1e%*-+vPwskO#@qqOJV?+-imr#dgq@9T@0u=2t2X*<qL?GwNatF_@l;gJue|b9 z@MQSCk15J2R(FJ=l3XX%AC3!jwWjpCEHCA#<2}bxr}fgv>9tB@3kV2S*(IGDD|LKQ z8p4o4I~sUy*|rn*r$`j>?u^BabmL*(7rjT_$b%uP5G+tLDqY;@PRIm*HRt|^I;|6? znhJpDKqI%|*Xy5uzGP{SHbhq>?9yyk5j)ERwL9G+eYU@T=cBLF0(tdIZPDmtb?Olm zWd>833AevWd4Tn5-D@GelXgRWLU!Fv^Q{P-X#t%`pKr!qC-EIE>z-T1(YRif!5fq# z8RJNJoGcRMtY2KSu+-@KRB>CcS(!ojO}`i3#v+0Fsmud$P~cpnB(W-k0daH7-&F<H z{_kfV?g#47=-#vCZc2ZAPDAdUs*zTH8?;Twg#9VI?CVLJSwgT2XIQoRG2FVfM&?q@ zrMNv=ky0o9`^&F?(`Y@W+yW8G@UKIFkAi#?1Qm^HqiKrQ8QbPSvPb73+N<;5$CPhH zT0c$q%+sIBaq>u%&(uqvbop%Nb+R|t;Vn`%m0P*?H{GzN(F^|FHLo<$v;f-QAJdz8 z|HLaN6zo8Tezc-weIAWCJZ}@}aJy^F(D=C9j;aIY5oOW*hyLknQ?JLrU4(2*7zOU@ zsO^#|KP<bUmnOI|^MRbVbs$Q1JH12my<pi9RV%$OmMWDk3OCP)lwpbbHJ-OFd)!d( z&vg1=rdyz<?}dyTk^k#Tw39zsmpt~3ePFCU?M82{Opnb<LG5(AUmPNO4-Z6QrDkB7 zmb>BU<o`PLQvepY^L$}Y{#LauoE53B`S$it+wK@i4IV-LF|se4-;#%xuQw>Ef9hai z+r?=@epBczziN|JWpl)$_lm1y=59wyGS?j7+E;K^syOz`5PesW>@rhf6~u1<p(~gu zEJ$C#aqQ$sH+4wdqc-m3Po~z^N8X;!aN2v*LHVlcs|MA<S%T(QqYc0nb;n2!@Hub& zn~zh!QU$?+d8UU`MUK@skBD<`j3C0UTIG(D^VZDdZn9*e3@boAf7I=UNqoNFCf>~K z_D=qi8%OyYXQ{?APk2jOp*OROa^<Tez3E2Q$=-lc$BsSD*Qy|Pyqxy0kgXLQr*Saa zmZg`$p{#8_b8fujI4*<nwk#Pk%Sy1VE3I{5Nxah6sx+$Wm0o+GPx^jFOGjMW7ydwD z5XuV5?9Wh8%(Oa?iui_?%_Xr?zzxzQbG!I_=S%=n0VFL;sxY|e%NVDZ+ux5!#_|A& zKz6{_diPZ{%B)9962tjIR#-9mp4#tqtF2PNf9YDYLBz=9f4zP#wqD-DNf`>YSmpQ_ z+q(4kHP80__ch;dlo#mF&pg??t&`Kb$8q~S+e8SpTjO8=kO7A4h^4k1u>nLJr)AF8 z3YIDfL_|Qp-s8E`ZtqySDqo=HlVH+{X*`uIr*8|ET4UiEV6`e&-Y7rl9uK94`QBiU z47wS{0iuT`GR9f73{3iX_pyO{8E-LRWG0;7G<s7s)`p%^FID8(%U$A|CtMM^TjaI7 z{;3-HCmwqIyBOSbN!$GFR)9Mbhu9t6A=6K3`D6Fe!>v5stt@CTH>j&h;C5QEtK(~* z!!*ZvnyHB3p8s~Oyz~aWi9?>}7`n1Hq+L0bPR`{$ckegb`D72R@U<Ei8V+z;(jpOO z%(TD7c@FJ7^P^a)3NYPjOw40iFU2EdF=P~3Kd-@j2n5&y%(QuljQRfVQg6s_MPQx- zv1M)xAyg;uB+V4Nv#gzdRTW~3W!U|la&{Ouq}kn(t9+-Rd|i@;{J{i>T?X!I7ip=A zqVCz-v2(B-)isqkHuqQ3o;0DLw9QTki6L{4(;#ZHSI1YY)2N964KK%Kh>-|TjOCmk zrIfAt9$M<y?PpuXv&|#Y&Zrt<G7C3-<hh+d9>$}Jv^^KS^)p$OV%F2+y7iWO#pXz4 z9{^-9xVCGuhdb~6^53~}=Vo5f0tZ9}{?$oUxt`bpVWRR`b^gfmI0u6;x$y+>Y*v+7 zWX(V7DfJoY3$v9Er@PJ}I^D<+N`;NYwjEg>+hhWIE3&=vV!c{zC%kn>yq$d=#v$9t zT+JXLpc7(;4QQi{1y;MQ{IPRv;HVA*`tzKX*;_A<xJ%p<pHQ28`BV*e)BWx@tque2 zf_ppzG{_?1N^&~FGhV6DZgfB{ANNlC=5JE~u@e}UuoZzbk|i8Nrc!$<taaUO%TD|w zhzdK6{sx0q$)55nO?jg&=c<s&1WNAe^%v+HyjHD;ok-{rQdup;wah<{I5@?10~pTo zN(DD9eDmfx8&$lnf>#i~76_fe)&#f?SZJVbfWu~ZMAJ9oDufoxk&b2AA)Ly-*;O1J zVYL|N@s4ws4We)I534?`^a1N)&RaM0Wj#-W0=DOg&?8bk&La=vrt=S*KWTVX>K4h% zHzBuSiSBQUdZOsDIj3jUq};1LlaEvu#`-V5vvVgx!X+n~Ep}+74_1`ky=nB6AHdH) zzO7XhluLBqI?uG?<+i6m9WX8qtuuw_fRk3vw9O#OGMGm0%^kOs9lKQ}yd~8Xe1^T_ zs@yqwZdGn<;p+@~uXyH`-weGN`-=$&Y>gVrW}fH@jt~j8f04+PUHiUDD)h1P((TE| zw`?dHc2f_U=$6<$RO{$YYYieoD61TemyaGQZo5$x<a;4(W{}epP!Rdv#@-dG0D$R2 zu1X`!Vf=2cZKy)a^uUGPS9G|Rt4!5po2+}h|I|n55HBBks};G``5N&&PHp}gUrNB% zN%k}7L26|*8cN^Px@VM2>X8|KoEr<gPMyic?wTHCfLLT8hzshR!9$p13(OvpgH*|` z$%(KRUuJF_;wochW>c>g`xw`LMm?>#po<S$Iuoo`?R-DPnYWjRk$&{9tgHJV?^yqC zVB-0)tB$DH5h|AJ06=Njr<I~vBbNxpLCCh{8>m%)in#sg?~T?!w_0fT*}4WB)qc`T z!M1Zi_X)DPrrTr1FFLs-@GtjbPqEomsMJfbD3>t<W9C|p%~N9ve!qv^i+oauA=9(1 zjbL)$vdXertohjr*1@Q0j-1~lxTE-LRfTTDNq3)a{<Fkhlh{ip;a+9vM|i!(eiMQ2 zIs|a#DiGQ9SVTA(;*`t{hBG7V7b6FzJI{yzp>x%T0eb`&m$+?b;>}ET_q&5sTo?su z<u^~H8LP?M9p-6QATfGUR_)rYYfFW;fJ6f$uaiNG*>^QoaLimu;$u5p>x?}v<avN* z{@l}*=AO#s;r7;TY8{rrh5k+r{&^MCk-6L2gBEj(BC3{eL}(0ckXs?L7-;S?#K8w< zO@ah45E1)%$JAYb*x2`Hw(YzILSP{IhY-t0pVRs~q>c<NI`=ir74pA^<_?2%=fPFW zEuO!z8uLrrWiEarRqRYbG}tmFf}R~Z6yGik2}_pD_~@M($VcVdtCKX#SDFU1uUJCv zTp`k0Gk56uA*t^?Bc#WEId=r1AzN2D*CC4v0kImIamDNTUA=tr{JY-Q3AytL=RLWb zXQcBoryk0r4nr+{xPqjSyrI~VL$MzQmp@o>&3H^hEccqu#I=)8PtrS@Ahuf)mma_6 zDXH6&ZfahoSSUvlgSYw&cTFj}vJ|G#@@Vf=$;dLF_zjAqk>%01^Y?j2xx%zY{<q=A zE6X8y49~pS!Z5RQiqxw1OBQXXb$d=~eM@s++UfQ>Ex|OI`)X<S^YsS>N^v84E8o`h zBccy5WD0uWOqW=YISKkB20<g%dIG?}egyw);@!Xlg}o4J1q3+`rU8qU4G$+eBK)kS z(tM2%8ayOg)r8%(&hfj_i=RQ?oosWh$VE#WnLm-&Ch<gR|Dm&r8IAl`)cD+1Y^;LM zkwXacuQQ2i#(9%Uv#C|h8VT*kN_>j??m1XCH$8mSlvBSGrlcFtl=JFq_~QEd-YOtQ z0FP^1emAz>M(K>TYk*rYASa4a^I{L=!IK9xxf?cQmIZmW)n~9{)`zXo=BaTuSRA|s zckQ5@U18Vf*{lz0KU<uQ3msHZ+6tJaa9LDyf$RZZcC5zHVaX%JCWSi;g?)(5cG0@A z<jbM3^WS&0#_q3bP+cUS8k;_208VXN3-B!SjnIkM?!z&khZXnmbN7D={_(E&@|Sa+ zvB3D3@J|Qxmftxu*$PbV+OvZ|GBjYC9U}M=eCW{6p?6)HQ2S{nk(?a#`r+w^V=oKl zoc{2CEH&ge@P(;7sbR1_53J8*zxZC~_<+~jIBE3k=H4muDn{vYNxIu7OiBX)Nd_9V zyu0EN-65=uFvjFRzPul8*s@=u<zqXnb3=1~+^+zyoA<r^uHALu9dyX}p(FF!2?5=G zVC42Xvg8JmT47$gJu?pj?L7unbY;8Df4{8<r4qT$K3oUEuRT}zKV;IX<{{v7fRQVd zuetdB;G;+1#;<H!E)-lMe4!RKeogmPH)nuWxNOCEa02-JfPZB9uiM*y2)?2<E{ySx zJjs>PdzpPA<U>j6e<YT`jO?OS&GqNI`}Lfw7`~EA-}#5{Z5nv_7ynPd^o84$pa5jx z!S7r2BL?6r#p`>2<Q`bxk1%=hsj&6$h;~7xEZ2RWX&nSDeUM!$%Z*K@1kArH%lq`N z_xpP8p|3e}H8xOuFaP`TM;8vihCv>0+->LoSG4C>8fs|V$)|F1DpRSp2iu%Aue=LM z-IN_i9l7-A@{zSXg)G3&O%YXxt-&ZhJb&)+&#wcmWm4L=j#^cXO-s*zwkSh8=UCm( zSBd&ElwpPDga|qH=|6_|^LA@zir@%<1DD4`0Vahbp@KIaUd7RA@_#z!_bf9gd0g<` z+74PkADIi6fue__g{Atk>%aE2>)vxxe&b(3L&(w`B~ly*(%uwlZaerEsIYibQ_VS` zd_A)>#!HPS+XE~|eP<|MLY=XU!<P+Hu&7Lp?iwW^pF^M;zZWgka5*wES+@T-(sgJ3 z{PN-5&n@#J_Jv-^>X1mhsmam@M6GD(Zh)X%8wA1*z2aCYFEWVGs1jX?9>-Bhp(M>j zwjW@4!9}VU(X*CT#$^o?HHVa+vv}M0opS`f*{1sIm224<<v^I3K6~9+9H?XU{nf?6 zK9#P~PQs%F;r1hX4k61vx4uy(&e80jmdN6_$k$rjD0s8(Ed&l}@2&9P;pchx`cN2S zv%wyKPH96cqWN$@o?${LmvscjRp}KVhAN<6L3$dkmEPJ%!T4{!u)<plOo7R*HGHAj zNXC;$1hC4CN{JNoQ8Y=Gsu9ZI)ze{NX99ARLK+SUR3f=%aKNWm`4I(bN@pa6NLxLm zbbXK@AK2K&M^0!LMdRVRhHX#6v4rC2vo46!PsTHu4(3CW&(Ao!;ztvUhiR%xFJD(Z zZbJgv1;9cd*3@AjZ-?Kr!)TxI*Lnd=bjw6(8H#eZE+8zU#yJsa&>N)guuU1~NZ>$B zZlostG1X?eRghbHbXXaol}yG1N~A+R`2cFw$NG0CgzRWx_s6(n!ad<hyWLX+GfKfT z84swhb)u1a8l{gZ6-jVrFbaf&79XuS<WnMbux~s;!uMCHf3WGJbAgn&!JT#J&nYpL zM6-1HbiyW&<j|C(e2&5i<54u8hb={_=STZpq~;<j(FgV1UioPk_(xLvL(EhRc5L+I z7%2Km3}&NmyPMHxsTWGjhAv8k4Wbnrz%2oCZD6c2&=HOhwE&~cU@4=zWH7L(1qA~K zGzp2JHd@hSyb+iLwVSFuYCRM8>7XpF3JVv3<<gI$`7a#l2PGx0C6~*(Zt>?fxfRB| zjMyXaZA=8uWbf9b{OeHnJ^}9*oChjy=HYW4J4&ixZl%_^6LX9^c!MqeZInh^yo(7e zV6>Iqrm*;#qH9w3i+a>j-ilx!aNj3c@I`Lxfr$NEul`q%ptQT^a8J`C&L&~u8&~!- zIq=rL%;E7X_U6z&NW^UI2|I~bSDR;6nr^RmjB9iN*X2mBgC6gq{qT9d@k;Aq$E|a6 zNLyMtR_#jjTU=m<tIDQqfTL05p3fQfGe4+&%586|EXxi1n~ZR7#VHiUPq~llG)y18 zzol)d;10eGWM3*HM@Yor5iFj&Cs?6afCG%L3slN|c7RV;yq5Q6=~>n~8Y&d+$Y7r= z|Gb&yCqJi{m+7{2*JlO<%hT$xImC(>OMr;wYOyVE*W81@i9+N}f(b32WbiyEV(rU< ztgUM;>3x@u*4NJK9AgiSe3m+$31bceD^TL_3rdVndGOu07HwINsO4l4$8s6x9wMEP z6?nnOY;XQ)cCDtE-tD?Fz?P6J@&NntoDy46r<1u^z5V?g4^GSAmA5UtTaQ90J&%;T z*^D7=Cbrr1JyNC9K{AJjX~4Ht<F}EzTGnJZ4UxCCuh?DN6A3I%pn!u7PyH+(UE);N zROjx*(&}4<lhw}2F1vYxABQhv$j5Pu`J=Q>U6oCVGi0$fPxCu*oF%UatS8@b>hNXV zScu(k->&XBK{d^-_KkbbeniP<Li<2MWJ&kElGg_Xp5S>a-jZT(J)(FWz1PNRLb8sj zqR@h&%Ee^7a=}Cif~}3W*^MrE8`N*w5rxrwK#`t(*OR6JLB}-Yz6(WkshEG=CIwm0 zR-S;%1C6@(k@u}YK;X{no*q(L^Px6K=8ml!BzII~AGHIU^G0(3Sq3FH0k(ve>3Ezs zg#1u1OZliN7x+ax*Ip4YK4^X@<kwoBt)UMy$CV7`9vzO}EG<g!lW<jTDzd|!XdQr@ z>;>om!g1^rqs<U~No5i91zu+Ul6dRaB;^~adhR%C%M_A}i}HnA<gDVZGzH<AzjoG{ z6XXh#P1DaAJ<9_cZ;9*n>#Vne>8_`4x?bClH!tR!4AjagT&+kwaYR$wU3U|z3`U?A z<Y}3Yd>MOr`ya?F))*6Fwj=fRXPH-W>iY5}%ml95es{Y}Dag8`u3hniP8TEfj_aXS z9)GzjxY;cY+y#JHHKRqjZAP#SF!Mze``UReO|HqJxN5Imf&+js5TniHF*gx_(ZIcZ z_m*DL>Vqtf4ZfE-x%fJ`;%nE8bd*lxGzV*rlmB6Q@KT#pJ?V5)nX~1SEqo?jJsIFT z3r^n)3Fn>O;@j^IC^ak}#F@CQoteQA&;_=X0gZqct@+m;@Jie(y7^V-SDRw|;*7q^ zP@kA4Q=}x`*M^Ja7w&&MXrUIu+H2V*xK+Ard_2RLHsG@8donBOUgLw%>n=_}woxsr z_;br>ZAad68SZ2=Awgv^2U_Is4#YMke)uxbHSmxpd-HY4f0z=A1`U-eFsHKB_R$)C zj!JBOOKtvliXJMKa+}|P9==(9Djs8@Fm%v@<lT8{l`E9u2c7V64fNUrxn<LZlk9!K zw!qF7u=cHpK_4a!frr1b)LP38(=puU`W}Q(8xiVfsRCs{@MDrGmn<%S&SNYAM89kP zdV8)Z4rlylyNqfvCX_#T7{b)P_AboZq73H9N97$6ekqAktQ>2;uxAl@E;!Y_X7&}H zWt*$|P=I{*w={3~QG4fC>g(IaRE01!SYLjE*J2ZOPaNIo)r1T9RBv<Y8ke`}B<5K% z0H4969cdxdPdo9&e(1h2Di}I%lq6|*yGRmKslu%v^{`5Rb#EV+Ze(F7fBdjn@pYL= zU@b|g@q76WW#g~!_2X&bOY6gxcQgT()8*gBylg~nw6n|cnct87POAir2m9sLMOI(u z*Vgph)IKLMV;ZjeyH6{%n4La=x`V#Eqs6%RqV}~>x4pcts^agQ^nbWVdA)jKGIWPA z``zwSlBd+=p8Eo|-726@zEdam<}T=>i-W`{t+ul{b#=XmCiG}RMBlZuuxUpHgD{F( zJY^F-1{0r|puRkwm+hLH64FXP8znj+%TxnI{Z8``_#*915@V0aJyEe15Y5DzaB(Zr z&Sub&!6_=X&&329=L#!Xo?%(Km0~a~RFEx<S2I?4do3qzJYslFKr?1zd3~P)9<2a7 ze{bDTIc2p#6FmK9!u`20_`T+-UOEV!A;#NNb?m_^e&>E3eUU~1>sIs;Lr;;)p2{D4 z^81-{Ml(}s_#By@m(@UTmp&5+of&<3_6tDX8O?`;i9#|#nDoAqAXd?4R(;`-q@OHp zjX7E8vGid~Qc#fBTpU<83`UbR|Mok*XRH5((B>dRDMEwx2X8>kv&(}y$E7X<0N8zS zgFG3Cng@LkVvl3D4!ZbHhd=*NJxb=DnuFa9MWe6t{WW&!tx;50#ZPp1nOa4hwu)SH zJNNzQ3x*|I-<Bd(Ay&?c%#4LS(G0M9&(bag3q8-<#XL>JmC0BsynpF~Ws<cq8&o&X zJ7ls%Tap5;+fzZwxiv0_`S~1+1dUg$bJdLsL<yU0YXdEh<E_p<Oy@n~0*|MqY4+sC zHuiM(w861DEu~yrV-ct>B!6q}jhBNlo*3B%hRZcZct`pBGdWw{&IPZ8pL*%s{VX!Q zkWM2kQFu?Z2B<59scRsnon6Gw030R@SIA>43;>4NI=0UTD~^M80jd@K8HMob;px+d z!}3<_*-AoyVEOceVBqf=`ncIZ-Fv9k``il;AFIC)OA11=8u}>FeTYtFRczhpGuU>y z(C_5M$$1g?!*MWMDy%!_=fI$L*uDHv*48zeqotH<O#O_8zhs66P`GjSdNmJm%%jt1 zNIWKTFUlFwgx<R*+-^{TKjh2KluR5b-}1c9|C?~P7S|xsC#B_1x+iLI*#}oB)~W*& zq9xKY_kKSZX6r6xK)+zaKEE>_M({b8VWk74*X-OM=I0nu{^73PLy>$aH93YGGWjBv zOb<FeNdgmqVM^E``Hd9!vH?~Yv>N|$A8>SVf=rM27x1tSkWBP005Pv{u|P*Lln&&_ zsqy0KxwT{M7&h=8_Q+>U9Op7sH~-(dS2(?|Ruj=PP_F&u#fJ}J|CtRO*}v2C)%`h8 z%|XP)RTH|NKNw2{6R_g%xJQ02IKci*M>_ilpPd%CFPyo-#sh4<<h__c9Y4o~;5C1& zCm>}oC7hOdHTR_LJLof3)z3I5e{x8=gcbgAZx2xrzpNiv_gEz^XCs?<3tK-`F;BrP zW517FA<>~^;BU9|&}UAA7qLb>?4X!S!~$UMgWygzp!)fGw718PvGA>kZMuv8mi*Gv zsj&t{rais)+Vc6<H<e_1vU1qSYOJvjMK>CZXH+R>MFh0FW|G-0&kZk|59p+WRk0ug zK-6--F_2CrOvhUZSvrN{@4oxejzv5Ph<q4#nvND9xdsr@3*VsJ(PGUYRk?c=N`Au^ z!>U&(<1FRTdn%oeE8+EVmIzw=>+oXVeWM%Xr6kvo(AsGF(Amo~5MvP-MaI44Z0%-l z{mXGsG!)+&uF>*`a-UOzl%J8g$XMmP_g=<3T)Q65#NAvu7Dx%yKr0&v68?tVz7+6$ z@S;#ob^rIXVSi(U)q^H(&N>5ZRXg_D!84t{`vN4J0+*Ww;CJEg-(t`p1AFl0nYT0z zlQt?<N28yR+-DZ5P4Ia`Db0HnrIVqiOAVz;R<i~?16*PUQ!!O-PpgDSPuAp2DN5IA z$MnGlKmlYVTebGQ=JTrFm^d%lZYuq47+hEKG3z()r!l=z6EFfq2B9pXp79bKZqVEB zgkbF}I!gmdMSH&Qd?_8n$dzVp1b#;$<yy6xd?w>zdM9$4cR$l$!Ge>X)vdQB);+u< zk>isxwu5f@BsKME(-$z-M@)p4J$T#fZ>w9PMZXMA8vhb6uV@0Go4$tcBaonN?h#EN zL0jktY$dORk@jY2aivVeni(STXo>ga$E@+$)#NFX%<NrLZvK~u2*0~3gkg&D-LJ;c z1pX#|J!mr4S*lcn)|zuA5jasjtPK)@jLFt7IqKEaCCAo?*ym2^;y=a%f73lA=48XG zrGh&Nv}DD&(#!ZEM#4>{M0@(~iO2cJkoQcv*8haVK6xKppr{(vkJe>s8W5pz!fK$& zm$QQt;revXD`8}|e%%HL&7)@8Zc(uL{LSTnz)?&jiV4Zo?@t?7*PE@}VQH#ty=n4U z6ubHZnmS)JUi0Z?xBojw?u-`qsGf6#DgD9ULVv|^DVfl&jAXpoz>nq}XS>ZMsMYi0 zeriL%kV?XzsHG_7niCsyH3xRjpNx5RqVN&0(X7XFnH<Vrjr%s8SaLG#p$nAtmdbm3 z4kT-sbpM{D_O&p&Y1keek`lI|kLZ7X!lms;h<>Z&XR2)qp;a~9pQ=k2>#c&2%Y2f4 z+BeCs!KgG{e~xM(wFPeUz>%wbShX^fe7Ep(R$R`}<8Q666&{;E^YLio^A#97+nmlU zE=I_FAGj3wcS9-9N1E3Pb1|jg7R#zIV(>q|(z4GwX}opnAcJhlv@vOV>FcIf?r%nF zo9qV~d9A#U74Zbj1C7cpy_AqwFR65y9YH?HqGVz9vlSt3*ZzGvmbk!5mZ7lY^4s?Z z@g|D0MsgO=DzmHM$y9A0X>)xGk~Y_S3$*HK{7$4;)#X6jjwI9FUzN{w;QXnW407uA znoExt!h^<pp4Dmm-KBjN#%6*rJ~`(fr4XLx#8RL@LQZS8-g(D?zTXz1Qt9lwW9&dt zW2E%%=vc|>*Wt`ny|njtMx_3gO!YLB^-kv$rzrGH%+4<4$i(g5wc`bzN3lu_^NhHt zvcqI@W+T4sOOCgGT0{m_I%ss?e?Ni=--!)iC5?Xh7lv{wTWG7P0+%>?EEvh9=wiT@ za3$3PMyq_K-)#QpSm%%nEXW`TQ+?^A@pxj^`@jsjh(wp3TT#6~MtB(yLbT~?DATK= zeq6uRlBtxL1_0(gr%oT-oB@YLV?ykqw0*Lhw>ZyDkfbsGea)0A#%AMSK5+?F@p^D} zA{I%xt|%F&Gq>#HvPD_yGu!49ZPb#^v@Y-m8%zWEL@_m#olE299$2HG&4}+o7C~Ub z-!GHl)-j(3-6U3a+*sQ0G3Z=M-}55k^XlNv#Bc9S#u>6>jTt%Xxy51A<f&L!N%BUc zLjo*6rEhVO_B7ij!+W^~%(S&--dRA<qm$_uoY!CG2hRaA0}92%KN(bL{9KfCL4Fu& zn(rdF|FP|X-&(Z!^Qwm})DFE;_Hfo~6%&YTCG{(xO-=kf);eOTx)toTRBG<wHA9y* zN+|W)A*x9$OCSA?WbxTl=L1z_{hjh+B^E4;?bF=^^|`BC{Car+7Gc=68ul{WZ~6^w zHLA3bbrN;`SfC%s`N6mDDGCFTeL&gS(dA#_*qu0M1IMj3T8)lm3P>aymf(zFe9R>c zq@NrNhTN|>=iEJac<%mCWx<z=VtwBZlJ&nIg|7z>yTz&KeP{uTh@Mm>?~OFi-F5(A zv17YbO%)Y^0oUqh<;}t@POh1?vJ5pK-zqb_B-+9~pB+*IBOA_dt9>>wsy+8B*t;|! zkT#xO{+`MNl|8&yWHb}@@;9|Z>cX!8hd3B$H)*#M6C@NZ{-%*t|8U{o+UNV)E&i~t z4^lg4o_CNhkFNaZQn74a8#q^cdFx&0Q|=#<B-PIwlMcBREWS89UGlK!n^o5#%Zf-n z<D?6RkM_LDsXek55y~b`lXa5WXJgrV0CT44AEo0ccQ=)w0nsIY$lI0WwXO5=7ub!h zebR~G!(r;e)$8VGa$J{k{@W^71Yw3NSM1IK1rUb2g}KibKZuT+-iqEhc4h|V67!RS z65&OVr==%G^^L8khrtyD8j$+B7jGORd%+Rv8NN<6#`6t*zOHFkaSTs&zd4HW4bt6x zr+P4z{YE83e+o>#s>v}Fbn;LA=q~t2<Nm8n$e8VSn66?=cYq8+#ov$Ip7p*xy^F0o z++$#=qd$DqNA{{e<5L(WLx*?ZJ4^S^1PQ&KW6*VgZ0ej?4I&FbB$8*vrjZVx2xcH@ zfUCUTfLsbTpQl9x$BxgFq3Mtp(jBLYquoyG`_}v4EZOUEitw-J>l@jAvIIZ~h03K2 zij>V{W&o1eo)VTvr7=AS2262bcK~c!%&ThFL13CcoVW3y&v6R~YgZ9FU(1bA2f0?s z$=7j?7a7P~HYO2(GSgRsRfp#<uqtJK!>|~pUjKixHy%beddLTJZJdix80Jf_qYznw zl|ev*Yt~o!BFx>(Bijosb1wDqje)B`NWlfy*l`h=74rOUKKdPbE8?2CwNg(SXq1rF zdJh)m@62(PrPkSg9ulb`j>L?TTB-LDGFm7^$(99&);ALucilewkNh9xn&Kwe?oD4M zf(DRMz_@W$NRy5vfCI2m*p+hTM=TNED3;`QV`EV)8N<uRInRZ$GEG1O&FEzBZwN3a z-zeSu#FPC}4seA4C7qqN^@CkMB#&Pa6F1C_&A7y!o(g^+(NW41#s$WAxTY(0Y8LRW zx*>Ii#<~(#OnO1xcCEOVC2Fh07UTA43j&^sxJyLKS%@JgSm`?aerwY@0I)O9H!MWR z#_z|%CH&&C=gn((G_aWQxNQpZGmNgv)GQGTCQ06l&6r-f*yCX~=D+jQCNShY9m;E9 zbL>_D?q3;d4Gdtm?-%m3F(f=0w0d<DG7@51*r4Ybd)x{>vMPL$F*{c0G)_m{Ft;da zu{!x!ZP-1(KJgvKeVUQutd{ic-W4sQuJ^9rO)0MmmG<M>T}xzU2TEL<<@$^F*tQLj zdb`WM2n}Svq|R_#L!(bx25ubL+)^7DjYTVf7`9_pPt&hbfmCMXBDWR{Jm6I4<7;zw zG=3CP<*4bKPQP17Alo|W>8n!_$KGfs5p0>gJllEEL$1&AivByeCIWF%ITZ{z8qC-( zv5W^uL0fq({f5mQ@oB=#^76&>S&gFMr|p+L?|K++mpiXES^xfr{0N}%<N|)7=t$dE zZtJU(gHNnhp6!W`T*3gx3(*SdZfbvo*NNixVpks#C!!=;{bX=yCmRDa$-Xtwu>xWt z(>!af<vy<9&@vW`Ec}iw2CZGe18dt5I>5)TA6cu57@mDa=BH;r%jQ5LI7qoum5DTL zK)zy8v5~iVmp7z-r{hqbi0Jd)l4s&dZR^x(tp2RM6-LXxy+z<CJcu1U_Eg(-#CMc8 zRMJbGY9r|cj8t71_Uwa5_!D(Z`+{E+s^<rY^D5Fi=01hjQskY{hXqQJNRR4Ov9x^~ z&xL-^3c|0>S`*f@cmn)@p|Z1iy+esD#bB}qAq%7n0-T`%Ku|ax&16RZEy{EFhI3s9 zNkgzq{OpQ|QhjH$-7bV#bncL@({Exa_T^mjb6<hCYXHlVxI3!DZ*p@4A2XLzb)dlG zp<N|+ee0}<RD=X5(3a~TrP%Dl#k)qHy0$V*f)d>3;8A3*F-f-==PZq)<nu5BfrQ*f zw9DIye79D-n{a+lq$LG&d->kcx0~_oUFk^0)rFK~uJn;ks@%40BEF}sKgX1dHm^%A z2+`o($@d$q0Rg$BZp!$&ML(;83B^s{m6ia55SHYOi$SW}j$ypwqDHiTl1`5h+Z9eC zoHxscs}hLW!^ucYSN$Ai48k_QNG7HY<-4xICndgUa;+0IT*c_cA(=+qly?Qg;je>` zfpuW?1>OMoAapnxH*kU-{gMWIisbJotyOw7VB#|_;YTh#f4mvxX7794yb!Edg~4hc zA*da@)?k^GVn8%XgKMSZO%f=+i62jES+>WO?fPs$EoyZ*mANyc#ljHS@DqUZu@?Gj zstAo%lGmjjO2+Gma2*uG9*LC&RHp$TMq*pRHv;_fRgesnD|ma8L{XgpbE&&DHqlgP zdW&g4nI}tHjt^%OCiFx6%v<gpY(II21ktqV+n!@uikBVZ(ZB91P$rn;l|BsUIAsa$ zMSqch3_x}BefgmMKf>*2o-qEsn!MiJAa|w$r2V(O&t-Xv!y`i-@07}Y)`dphn#d2d zJcYIy{$3Ebx_HL&`XId6wA#d&&Dw-f)XEGTMB-x1u4M|4gfy&VGKa8E3HV%egJ4eE z4wV6z5)bw97u|;&nesgyXHD%~Zfa4Jk++b(2q12Cj{G)%;|ZsAl5hkDoF=koPpv87 z!c(z~A2INNaiio)OiQ%Jif>+4I`#}ec6O?k-!aWbBviokjjN(cm|}%$-hi1uB_}Be zpM3sNqTAXlmC0%6YwxD$D#_#gC&P!XOGp(2DJCLxb=J;wIUpXVFU@jBDM2@@sG9aa zBMNag`1_}o<j+>gNBRvwhBbyi$cWgqihixX;}Z9V)%ShQt&@d{UI&`Z2fW@}7l6RI zHy;X?cXY<xz6&E$>PrN-!1I@%y^B-zO|6ob!$(TiyLzc+muSlB=^Rc|(O<;#_KbcK zpSp?4(+>$ob1o=c6+mS7_eBC3?8hDJt$Eu}Pgxth1jRdy%_Nwd?Y|tUP*4&nE>sPp z2#rcqx90`RgY-(~%OmlXZyup1^}ze~B23qO%ANMj(Go_b!di8KT9M+3NI4)<%k^zI zjQNfp%|~oqBwxSx3<?DS>&(1r(2hr^O_)5i=w}1myzBMp#ON<O5U9S?{oG-tLWJ1@ z^GN(ws}Gj=YbyysMaJc^xA$V31NaN*MY5W9zg!|QH_WBrDeQhVzA4b#2<*!V+FAGb z+Uv{*4j^Dx9aXLgGniw*cG@A~?_M_jxln5XsXt9tB&PnrTe{8`5>M-vb1aiVqWe72 zO4{GCD5~VMi|5B}@V5y_v#$`aY_`${fH(m_l?CAd*Jl3c&zekb3;@`Q=Dh}G&uQ+E z!=ib3FVc)~LFe=4n8P;RYuN6Jd?=7{R5zjYco16d!@kI8gm(oDLZxGnhUNh2yWKqT z*oWW4B=aYPzJo5=TIs&cbmgNWimBSl*Wd!`8l=sN8k;1F2iSG+fn=A`k7PBsI2U;W z3x~SV*Q}m7gH(s|1!Z!Usg8JK9;emr;;W0q!#5F;0^5tW!my!yyRVL}hgMHM<G5nM z62469hkc)*t%vP&Gs<yIKMr(}m>*qho1=(0@bP>_e0350+58gLIu|9MblERTW_Vc! zoBKCWN7oTy?c%N59PP5<FB=L#NYEAekVx5#8pX{KM)d&}(QqL76E>>|PhXH=kq|k_ zKd(o-bJ4&d@6Gtg+Mx#odLQ#T2o1$`#O!!1&o+nBPWoM0ao?dR5G#1P{h31?#Zx^U zO>wut$4Pe#Ut?vK3A#g!IAFfTxRoG!kIfybN))Zb!5e6Nvn%@(JQ*EUzjGZ@B_DOD zTH+9Ku~~*KQ7?rAVA1o*SmFtM)XHV~TA3^w^y+IY>V5XvB&-^4$`R?|a(=3^j&O{- z?A}*r%X;jOsw>)p&lM1gS{2g!Bvu*9MakIx#S*fM5)i&ZJ_QX#s$&e6^NW?Pj=T7M zG6nCE+n_R1@U``=AM1CpJzWWkJ>Z1LbzWJVGr8D*GK*AZPA9x}j(*W#zk#Hn9#=ju zqisqoY<wUC_Wg2x6tg-i&%ll^XugjmAlk6AIvI!>piuusAyL~KduYZ~2Xi8@1dq4R zmC=bZd?+UhWG@|(^6I^EW%UxY&*iA+fe@b}k}03y%2N3uQZhDHc3{<3nBn3ll{sy? z_7s)mdD(0;oGYdHSTgcdE3z1kDfUsM;uN#S4xnQ74z{Rzi+59LY8T|>=`0DcNYc&s zk01D4?-hbrzl`2sW4YzModnMC<9LaVcX`6I_#Al!_U8;F5R}LF!@t1JYaf)*+&FXx z3;JpwE!MyTpu&qEcj)QDVT=CYQyO$B!hUMe9+L%v&TC;jn!N;w?yA)j<Xv8Vxm)V~ zF*#_!!<K)HWPrC^co<_^_k%1Xg9hzt*5c(<yv2(CQTjRa(usXUmN`-B5|Q;;r3|gC z7%88+u*@y4nakZOp>tA=xUw#U*s<8AN!MMkpzcIRIu=`;c`qaSN_z|ZOU=`<s5RLl zFnIU@JAVStGmITV?UMm7XaOKaGH8IJNyU?XP3bx=${-k6yl?})=m=n;@rX<4MZ1sk zKyEIXCq$HxO%L!1B^;{Z3H<n#Gx%HrHG0z61UEc>GIYSC@ss7o?Y-OOYm2e><eOR2 z@e3GtoHGBxW1gA8ZfbF|0&vJuhpAwj1d@%%s+6K_|NFX~<7e?dj?TlM%Kv}k_nFSZ zeK?0>pK~0WI`)V<=Qw86v3DIKD+*a@oq>*(V-zWM%#cJy(lSeu?4*TMnjcA}zLlTH z?|---@7Hy|Uf1=!N++kSst6lKYyVKfh`kd^$~^57Vwo$it*hDUrQ#xR`{cs5n#iAA zl<6?Svb+6!Sv&QwC7&XrzkpplvM<Rin_!ljucwLI0fBQ-|0wCe<!u|TrB(=l^V(A! zMgDE<^QW~To7JW2?b{UfS-+LFc@(>;bY(GCb0UXE-$21Hk~?K6TSd65G%Dxo%#Syi zC)qSx{a?YWCz>e<tRDGtP!B?O@uIq<oYZm-RZy=&Bs2Yp@1677X%<6r9ig%&p~SdL zYrcf5>t+UR68Yd2sGKuJ`Y?~6y|i17YQ$lGbcR~?PkL>3Qq^3Len~#1FHgZNe6rI1 zEK^PCZq7hOM2mX=`R+k*fSvLuzI@t8{+FoO`*E|>cdjXPK>>iGygmMlC#x54`!kAE zUS(oyQ6|0NlO=yq0_yY?uPwB1LxUevvFBQ(0mmsJQefyP+sgS~61;d`J^DMT38_i_ z#dy>jc~aiF$5+_uS44Cf6A~gQa&Z#k2_hwRlHfM)B){NzAVsgx10QKl5Q~-euN0wN zf`3PwxEj!J)gh2Qo16QCUI~PfN3`hh%T`wnrs1;P2ZoSPWa`D1>6H-Kg-aF|ch}?I zkhO`F%mtf3heolkCT$L~wt`shQNt;O;uV&YDHroEK;?*gHtyEmSvkMssPO(UBJ1qR z!-sStu-JN+SGTZf6O~2R?A=cWhsXPAtFwb2!h8k()icOOnpID1z{WYLipUDpEl~)t z%pxT5QOk1**_M>@Q!!<Vl+t2(e~NsuF=5w~<rc&Db8k0$%E$#)q0%Kp^`5w$VQjo0 zpjQrPjyD)~-Z$|*Z|*1AHBIJWqYNIp1Ivz9H>N~#eS8OY+eu(n+$|@L-zIE0Y6cUD zYvdmXw!#S%i@8vWFY~KO_J?GKXl}nLD|zgj)i_sr6kX{SZSRYQub;<xJF&g>7QQ*k z#Kr2LsIH~`skYwc+9%#G-WMtt##G4lOfTth3Uwr8GEr~IisyckE3O|rXr_5;g_H{c zV|$1dgxG@r$kj<tRxdbRBjE$N@`3ts(>j6Ab=gl8D6<w6-x&M7n)W9BE4ji>94kwC zCslp{`8GabGZgrp2&MA2!g&awTMd=OM-Z1=W4BIYjb#fTHyLPBSIMfEq2{NougzVe z(ppBo9$;HVn7{M7?;Rjxc;Q5IN8pTk{}jP%U$E;!Zq-kzAc_J|MPl^C<b4-S!9?eM z6;Cm+`7^ZQ@|c5!GIJpz4gvrWh0L_+eOI(=#($mL|75+h%+(o!8fOs5p%a6CMsA6C z*VE^a)fP0PteqW4WEZ5T(0@nYTNMk{zE7(a-P;+Bkp1YHzP5bq&4G1Q5&*94ME~Nx zf@vzuY2$Vl>Om2uAEKzxZ0Kjo%vHPFacZ|E$xN$EQ>dxY{VmtE!A?^ORm#l$>C;^n zu1SW}+RInmlqt>>f^(?K5SQp&b+E)N=dpc`UoRmp6d%~FuuHjIZ=vj9#RVy-<@PGV zzeqxEXj=SA_TJ0L_+jgyb~)!N=}2-Rhj_BDllGrWPq{<QBP&zu7Rw=1|F;a8QQ7<v z?kN+2yHs!VZ;NB^R|HXjZpH#!gchK!sN6Y?^{v(CrM@d*00_82;Cah9FV(1gGKEy~ zwYKKc=Q0`12*2Ohqv0|3JE7<9O{F|cSlj{DdW9jjS6lD@FQDiOdhgU#)hd#072$A3 z&Ov7di%>*<dHtc;3;c@qvSL-B2cJF@>oKc)Xt_^4H@nKZ;(ItgIlt}`)dvqfd9{Mt z{gf@POL^RIeRVF=(lp<~yTvTw`EsVrRK_k9>N#0figuXn#fu(2A4Fe%lQ9fPDFk>4 z8CmNhhc9S^F}AkqJzkB|i4`UM?-NoRnq8k)wHJ|$4@=&pWG4&F#6$nqYe($tRe7Sj z=jZ!4(`qx<*Jd%kd3$A^#2%QI>&>_@t-S8}zq)`kTA50Q2?vl0Jqn(-4KX)6WCciw zgw&eVznx-LNQ{mDKD}wXSZ@0vStwB?!8-RCSv_zqy}9VNfkG>#Zv936!j*x~XO3U# zymp9OEvP(QgBjn%EZvY7f(C!57UQ3AXGZG21`lL4ki^h<S(W(i*?+)JQns_?My|xY z?jT(eP@cl$siWH8bC<EnWEHLIw-;o3<#!5b+o?Y8@}?%Qtu?Eyg`2f1{E5R{6;}$u zl~0VgNuy~|IH8mHY9hyO%1aG!y*(9FNf3piM<j~QRg?17M6h~tPX#qvyz$i#e()v| zP5h20{*-uDE9(uO_6oM?0oT)c;<Y`loG*k|(T3i>S}pFG^@r^*El3~LylGUFJO=Cf zV3j)>^aa_;)9RiB$dGFg;0uNG?(9h8b_$;Qcn7N-I7~jwEhBpmV{dut^`2U!+cT%1 znLd`uc<pt4>|E#SSfj)5Kyyld=8q;)20!WEwij2MLK}_;-jiZ^#=W2gznI)xL8>6* zGDDq$>@)+9Jkb;oPE;uY6op{Oz1`2(B8;a{IR*xra*;joPu=p%)n-Ai4&`Ug`~H}% zR3S{Iom<_25%$V%UBs9Xx<z@c<x}CVtXo;U;Tl~{dUYy+OGeJ&R{3fx%#nAu{{zmv zkX^V)r*7N9ZI)wYtlR!118=^5vh=gDpmvL{Si*Z>E6CoGr>I8K5+5EeJLK@s;XCa` z5ejwHcG$8iHQnb-xfg}V<rAHm?TJqp^}-gPzE(go-?6tnIq+g?_bsCTyaM+IDRt+) z<BChCx|H&yk(E5D+>RwYRlxOsU-oiLP2K%ofMshK24H-6ihf?ldcIS@oXzc)j)+$1 zV!rz=t5^L=mJI2KsL$N_3>kT;N!D4m6F|CeBdLf#Pi&Nv$v8IjX$dpIW!D?au^m4T zn9x$>tK9*?P7MH#Me18MNO}c1C=2hkXbMjRkR7^El5v(h+*<B=e~vuQ9d57iY4L$P z;86{Tsp}44eXnPO8$|bw{wZo;v)f6NJ@O6xRoFdv1lgd`v*uET&5>FCEF*9CLb<ps z{fpDhK%88}K$CZ4{GJm;`JkaaeqNgcS_mgiw0Jv`x97qW(yA^nwQXE(vBBagrvkt* zFd9|Fw$B7;v~&(tU64k|mDneYs9FOrK`qnlXrjOaV-avAq6)kSgsFb-=97^E91gG& zzuBlW{OSL{f6}&{%k%wt@;*p_4@1dmdy_l)LMf0!Xz`C0ZY(JnhwUL7=F(Am_#hz| z2K?Q>r35V#Ou9j?x`&Vsh-ar$269Q}a+cO*yY1WArGB-UR|=GBR@o&SZ2QXkGp~D) z<w*?9r%vo47urtrW1PN{yR%9R6KO`(If#Xrw*KN^h%21SJR59+l}Srqc%{W7W)`vW z9^ND%hb9n(VUz@m;h5Wgpa!s1CB;lpU9krfH*m+Sb1o4tNmU0!Ps#&lk==66y4NaL zmZ~XGG=(?Elma4vZa6|u+zkc(2p?x2{fCa02ox3{rvbJSu+qMY*UPa2C)Jp2+*Ciy zBR|qd8MqdDG7|pOLy7rWDQeN4sZK=G6dYDmT+WDVpX4GQ(2D%9Ck5P`0WnKnALG$J z?*mdDsw55IYq(PX8m8OOJ|>-*r3RhbE2=vjCao3wDR+ILdGo-kXD85U^@IiO#dK@c zCl|2|niXpC7wujuF4{NiSratUpL+ys#GjdbmDGp_fyz+?LN>cxZZ#wppm}gA5O(^{ zk%$n07muhddb~w=6qhte)x<F1a=IIsXmtRDq5(5k4i*^Z*r&pO0WnO6QWs8LuUfO- z1$g|gGbIS)7-F$~WtT?Nzm#jE7co`a!5aod9be;8UDgiWI<AA!RePp$s>k*RCfjH2 z>mL1h+MrwGKpd1*PqIc7yi>ir6Mc;I!`hOD)t`y7hV<pKo}CJMUC*9#N%=d~t9j;= z^XNo#rLyXsFGh<Id;ZKyb!)&CX=WZ(5b=5|3;Xla^63*$p1m~u5o0t(_pC&G7O-^^ zLm%MbkL}hLO9}_?X%zn9+=h&*KR^W7dSgtsUkj-P++4+d_93xZ3P3VM`(VUbh*?5P ztK|olvrg>|_Hq2`KaTre@0>UGiHk)cI>g%Iz~dSx+rxpdgfJzAY#O}k=ANavQOt<v zzBbWkI$h6+pZoH#k9=D*Rk4JNG-OdaT0~%CE!Sh}x8J55$w#>>K(C4$)B5$T%M=G2 z*KlN!c$;&ktOw>K>k|MREBazv;W_xen=PJ#Fx+gn3qJaW-=5=1$V#mf4^UT(1%%B9 zgFh{NrAojp#D3TWMTAaBQ>$KIlWd8pm^{sSZJLvQ84E`X*JK<CBZh1d9FH1LZm`b+ zp~*ift`l%C>;DyG#<o%)gm5~kfd{u2>wUlk`iDwesMheV(9e4L_jO0U_`I)!lxwsj z$5qhauF&PogigI}_V*nXxPNug^Y_42b_%q!4F->Iy(Yd_u=kkOQ<UC^ZkU%hHCyiV zlW~Fx?N$Hr1Ds+x4O994d7cZ_mm{hggab4J9~A?Ij_7LNJnhoI$14~`!ma>`@W*+p z%{mgsyIb!ffQ-8V6D;kl+vkXjTNWVQsvk+p5=4A7Acpn)@j1S?ekX-rDoY`T(Q>#a z$b}$|YU+7cKtHff!#=>$e5h^-Y6HFicL1qZR2}-_(mrf07l!q8oo;pKD-AhF%N1d- zeKoUxT)oG)!ZSC#wTiT<?m^(u_vF*9BF3Vp%dQo<9EAjdrVTaM^e<Z@XLa80@SMH+ z+T8KIu8mdu(}kn1Iz@DHBIOmnr0=ZAj+`8|rSM9?UVv=+oLFlE%w1q%xax=WQ`@?4 z9N!k107wzo`G9x_(~VL3iDQ@xXF~f=flkYW)kC`&3-8BUk>8WEb^k%B-vkH7YWgpe z2|1!BLiM0SF<ai-^nnYO>X!H*)0d?*t&e+`8w*sEqN+}Lq+^WQA><3z#Jc1xuaE#R z9LHJrcQi=NDE&y?qsQsVF(=@$dkM=roC5tzgedc@#W!*d2^9TJ^F=Kd@|qe`x_{J* z$7=qBHe<*7*z0qFS>4}txgVgGC!MuL5N?!sr6(1b+nLhx&HW05hae;Y>>m5Ppor$2 zorie{!*`VjW_d%i)}=~o=3!4hHfN%H*~@_B3>>1t9D-e&+|*yS_tD$EI&hnT@*y$d z*V4r5_I8J%GBQ-TOqWY_J2jnKm-TH*XRz(K2O*DTW+a+zde&?v8>=uV?vp!}=p~RG z?0QVyZxBIINaC=->E%G**^6M{ZNEg{&?;iZXs+6O=eyX0Pmajg*Ul}0F-I2r*43)L z1!Tw4OJ|fZ>RPP(e0}zzNue4LX-g>cIYlmY2R3kyGx85J+Wv6{ll-N5PXS3jU<JX{ zI)P8Po#bbD0jTW*e=^oi#$wHx_oM)K^g&$~A?(mH_nOQ02vDe+TTHy-aRM1h;f1bp zS}J-&p_ZctAtK+508ElD3qMX$FcQ^8-jw!<FeMKdoiKS<VbV$rc-WuhH+Jz-!(dQf z&j*a{e9@l*0@Yp9IW*FWMn#kxJ4}>;m6w#Pmx_{`+?&-@g2m$`S1RGo(=5|l;Pawx z_k`Z|i|FF8_&<H&SHD=><rFOx>(OlPR8_KRjv(4k|2};FYp~b4lb9-3n;g*egVkzO z#89U-e{b8#Gr9xzn4Kn{&>rl+aJWqWrfz31n!<GTzzIuWI(<XePv;%TyY=y}Lc^z< zucDaw3f>2;Vrs}hG&8TZwt(0(V{aau$h_q5P@LH@r0pE4>ACp$Q`C9q0m!JRZ`cCw z`YbhqD!gX97&?LJ8IPR(;46?^5JdsflXrFS#+7f)<j$3T*G2M@1GOw}8$5+7ka@Z{ z`rZvYy<Dl{08->8YoqCqhleYnIg`NJx><oGaoi3VPSH(Jvu0~yfEsBn&}z{JxTQY# zlojzD;7(0gY}<2l4N?42#!SnhVNcHjW_SQO1z^Q#>-%Fn_TRxL^o3&k#YkTXF42*2 zp%%Ql92_%&5v4`-h%qHR-0nWg-Gx+rM6jNZXGH?m1Aupo9`qgCy$o~jHFh7C*J?hg z#nwE8NTi2QkG^_sS8bu~8yboTH8m!i76_o_K44ckq@^C9l^l8GltuX_vrd+g=K&c| z$FPV1Y?0&D1B4kNyjEMALl0b#N_nlB!m>B3F(t^GgTyzaFMi-F<hFTVP!w^D>OeTy zwr$@$+Aq~y+ll~jwuCd8S4RoWWN9@x77XJz&!<T*>2yeN>16omC}Ta6IBt%uTQs~j zN2pE5j?vNATQNQmiq_KhI}k;E$hu247e%9|BlySc@j{7C1}ki{D3o|iV()Qfa~7a< zU@qgVquE}G9x`0L(ex<J3*5ocYpmKRb<4B@4osM;BA2o2t%rSdPw=W`+uFBeO+n}# z;PVYsAuqW`A<+E-B6$(92m#u%)jy2+&Xl^ps{xZpHpn(o+L9*1ny?c|I&*vz^{Z7+ zvekMSwWF8Fo-({LifNSuk9T7_<}kj@kYsI>4hgnw4u&mH1D5xnTPm9HNxvB(&EqQE zVquyY7Afy?H+?lS9y^xThd#r_=(eJ+mv8d*NVTUNyGzM;3o|Pz;vNBxd)?QI@6N{- z*`QzB*=lDZs^TtstY^Y0hk;h8YbU5gS4oEgSe`DlTW{X#M7)dYKc39v#J!V#0ejf~ zoBIlOyM*6O)bnlxJuM?Lyi*YK_8+8xBOD<xcXZbUaOEeeFd)$(CbdGGm(JXC-I=WG zY(UDSgqjxRHi%s3F)ho*HKVwzqeaB%9EvG+WE5H^!TMIE5p`WV#1<Fe2j9IxP0wLk zTX8)M!xSg5rM$%Ishn0aE1iP%;Ucbr_7%&5J5|RwIOT+ta`sn`4<1rytDMdj2Wq9+ zT$cjM!*t#JV%bGdx)<nG3Q=Z&3Uju2vW(W-Q{UgKJbWUBNH{EqS4le^fDN^SXes*# z6k;js@$s$PZES)YE9UOkJj~ecn@h*l$D9Xf2Eqn~Vge75=&ee%sBCl<UElsfg1Tv4 zq3Z(b2dJKm<~PC<2It_Z4BW-j)jCSMV(hW1Xkc1`i5rzJn1id+A!T&p@y-MrYlDA% z+a9eTZAUR{ey5i`ot*+I#dxLJ4iIgDILZN^H43pFhjQK^s_wa$h7lDN4)-8WefVYD z?*#h60R*_`hs%Yb*RncbGQc=;wdlmgER3oJ9iw8KiVgv-Nw1YM5ktapZ9H3BivicK z^7P#<06z;oSkQf{QywB(Riu<TQCZVZ=xGlrQc-4+bG<qkxzltEk0DbNvtFb9gO}Y6 zJG-WH>`BqI#Cw{IfXrPCVc<HbXPsh+`yjj36VR1pbI$9=&J^oBaGPuwm`O+RL5<Q# zE~W@<{#p9IDiC8_kDPMHdigz_I3(9r0Emz1@B;od?j?1HJ@>ottqbhu0f?S3rR6LH z#lP3l6wZg)@=W6=lN!IO9nU?KtB-%x1j-`x-}gx{Jx6=_*5`k!sN(m;rk%}7CxE}m zDHj-Rgxu>K96)DCHB{$o6>mf?>)17NMOTvErd?v-cns<0xr-10`mh@8b8TMtVj1?L zuae=Ly{l9xb)kwvMN8p-I{09x<6q`!!TR`AdQwoY9#3!Gud^%(+mr0T2tBKX57on~ zbNx4VWTGp;0^@T0c2M0OjsSpSE&L?Yzq8~>uOmo*q6T#(l$jL9Hh@vx4PKV2JH{pb zJ!bzKYaG_cvvOE^h@uO>+j<*a8$Vz=IJid=R68BlXubC;AZ;N=nP%h|x?+1kY~vh` zNZxpY;dN|2UP(1~0^Ko+v=U=0B+dDRJt02m>+NQ@MUDSCIR{(1N1QzBYn+7ndZ|sJ zB~hqXN70^aIB5+7qGL@RueS(&0`}=cbglwOI%xZ@<Hy0Q(F7o9$u^vZzv~MMGEAR` zs-jEinJV#tR|02heVu$kUTx=EmB#9m^=7p;O%J5V=W5AG8os;NQyE(QIOWDfitF_` z%x!Ve0MMlqi5+Q$he~jpAMzT^&UA6456$6huHbIdz3jG}y>=7C>i8TO!yMtlY7?$$ zeAPcA-d)Ds)*A#){JJ*Tw6#<pKUmJq#@1ts=*ba?#ScfOJIkKl1Y4LLf6xF<44L0< zBEKxto_c5L%x!qWDeQchvDDpTC+jhI2N$ujJNMjk`AqI?KJM8qL{a|}7eXrP*Z?*I z>J|hKw#M*x(@q}47>k%6RqB_k2mu7LUKAk?dp&`-IRJO-Mvt~Ot_XmSkb8j(X-6$9 zo&hDdewky;ZW^>F7*gcVa@VojwB)zgn%mkYGUAA03&M{oYv*vYoTqo4=Cu}n9kF)? zx5#s>U|W>5O}(7Ksjpd4hk(J*JE4Xr{B&hNaai#iRm|9qW4T9odotM+Ndiu_tphx} zf=n}H7YFvUAvXDXmtev8?>}`;|58!GsFvtPWu)<FA5f1ZHOJ(xBHGdpSrWQN(QNR{ zQMn<SZN&=-vYjh^X%6!<J3ajXp@qbQFAQ0YA}@iORb4?skHoA*eS6OgLBu6^RXl7= z>L5pHA04{B5O~IzUFit6r?Hc35sCJMtrJNzTjH>7EpEE_gx~Z@w+m$q;D6T1fMg3i z5vn7GhNj12`0K+Li{hM$vKIo_A3SW%&g<2fDuF8PJsza?@0zctH9FT+{@RP;{KzEf z3dK&)x~{seG_9ubVoSw?2c~D_#(K;_)Sxlph8TONsQ94e0|mE=pm6DHoH0=uFZpk8 zKSc2gU5b%_RZUc+KI+>=L>I=C-W?<PxpEPBtzc!iAr}?kIdO(BalHkG4^8;A+Puxt zcIvr}sfxuUI?SAfEJ<Wt?M|p`!jmq7w@m#v39pBBUY|`Q%xbD1aRCt-cNeb*K6)02 z;HUT+YlPef@Ae#5;^*<&nopf({n5E`e9cg<jc4yM+RDN8&>3CJPjYY1Aow$XKfhWp zn9*%o2i4q=G29usqM6)+V#K2-u2a%=%NP|=dbShg)I(*6Gv*u*lgWXR3lynEF9F^* z+9Tyr*UE{&OMW(7Czw{U7~BUO*Zk>=f!wzJ+rQA3^wmo5zXq_SC=;L`0D$mYFbF&p z_+k9$-lM|{%YYP}@F%%!I2fcmficB!%jx!zBQ_T_51|7i08n4P{eJh-))mvof4@c$ zTnPz(kF9;`tvblBLa8D`Tqnes#^oE35oM&2NiP{=G>2P1HP_cRbExdbFrq}^Q%-fd zm%_i?JM-u(2~a){11;{>2vx0(Cv^tfugsGSZ!bLgrT(J_TEx$n*1~(fFFRGep0u4k zEdTa;Phy!`_ZIvzAj1XBTMs;}SscEAPP(YG@gERFYaj^g<vYNyR_Er^UH}~R<{qWy zv=pp|M^U23TV3IbA*p$x&t6HlZm5dAhu}!bb*idHRHpSaq;p4cT3eRrA9G-8su?>7 zT?tsDR&=kV`oBBxup{p-(Q!*D73+>qe@31;Wf$4~RjyKuwW3RrKP#r;7n-Z|D_R<v zVGFW}9;sG@w9&hF^C#SzLD^H;h<Ub;jOvR+WuIvfJZBNb14c(b4!@K2D}SzE4<7C^ zVaPP}{J4DhqN&Rx)A3Gl<VT#x{nqz?-uz(^qTJtpmC6WpO7*(TLd>r__d?|3n1qyf zOR$z#horE;=teL=dK$on{-?4k1N^i54|w_NIw0-Alj5J4`@3t2ztP|#3BJSNk3fwY znwIGl?0z0>Bkd~fqI&)bDo-P$Gwy^HTs5y-sYNSEu1YVx{|yF@xb)@2wABuOwGm_3 z$n|jOztej+RP+m*Z#vpCGGKD@jh%87e}spr|BLJM{iYJF%$m^E$6sz?+q8V&y?AKQ z=JL&L#`-%dXVc}R_b$Ix!t8JC(s*!}|K)EpN-!#Y`^FEE(SI4|W@5Lg0!OhA$x=QN z+{&gocH+-A4E9+!@^<Uo&w56O^-YU|C3blzJuw#di<*rC0r<KM&3}|z<A_j%IK#U~ z87u(lpgMD3q7Lx4a!-eIxGMa;$a54^Z5*%}+V0;dH!vp$xB!H&x~<vWBp|SsL=teb z`FM2{++*VZE9o}vnVr<*xg!BX`XE#Cm~Vi5Nn3*PK)#t&uc7}yE|I^>Q^8GhMUR=c zA7X2xjAqoi!Zs71M|hVyd8)hP*;=hW7b~vXzHB=9FtH`*2GIE-HNU{zzjfdHg<$%V zcaH(uL!S(TER%aqUfAT}*{>g`OF{y?N*hlb_#=qeQmwt@u)?gO*ru<#blwj5|7_|G zCC@Y1a7~#ZUHTVB{^WL`d}8cow<YXFJwAP1j-dz`KspU)*yLg=`&7%Eo;dS93Ixcy zjM?>L0F3P_`lkvuKn1qsB{*;`7Q$1G>+B)_3Zp)>(?N#qmz3Tk32`ed6K5IV1E;C* zV{FD?&0CBB&U60MwOw-CY>X{=b4o?mx*n;51LkosiRCN!Y=LA-Szh|e<9$_olo(CF z925mMK_+I9B5J+Jp;Sq_afT~zYVH^J-m$>Ht4A8R=egyIgbD#<oV^8RqLN+d<$Vh3 zh=u;0bzy`Chg#((Ju#z6hy}L6hnN!U4|I<cCwespjQ}?&Ilr`v8`CEc1Cri~NTAzW z;MOS%$XWogWEiA@x_v!xZ~K(yF{CmEK+(z>5}XC6m3&U!Y|ua;c4pPrPRoh%P1yv! zTb9m-V{HBxlBlpoSATFL$gD5o)c;;s+_{MS{qZvYgsJ|ZHKcq%;ovKRXx9`KcF83o zEEIW~ruFRS_QHn6PjkZaU5E;cah~=AEfp0nH$L~Yk-P)_;Un_EQl*2!p_5cC`pzUh zDsJn#>z82FqFIB@O1o)G_(TNMQjcKtJDhBZ?46e3H~)>c71$7?eff+6^qtGRjp8JY z1bWj}d4R+95vWTr!Zi5Mci+~&qaW4z|Gv_6`E+nlpWmcC=nrVGIvdtaV_x@d$2N7a zFEq$UJFLG2c<fQvAD%KC!RY4+Ns;t#ytCjf{NQ!*_HeIPqZv<;8{Q~M@mvkKwey>R zZTWXKSTqJlg~dYM7jg`;>qvWtTamni_?|S0<{?v@ali-FrLU<6RcaAIwxMa{<T3Ll zM+Ir>H43}BWTc_;f6INc`2dLuZvXyoP<OQ}S}#U$N{r6IRB8`qd*$o_0c7qhkBm}a zbOZX3wZJ$4$<h0g=Q9g8F|6s{Nw!VU@Go^xsEO{;9HZ`3VaS;k&M<?HQ$?>Za+PN& z5s{B5s?1G^HSW)s97ndhzD9-R-tW0c?kahLE9))Sc6h6B`h7OlG4W=B)`07|kGt2` z|CC@O<|M@0Z>UoWrrH)apun^)l6;~n@A>Bu=iD~GTLQLiuQwE-r!x4|9|<VPz%#~7 z2dN6hBDVKqkoRrcgFbF&Ga5=x0%sYU%8|u5xE+i+%cziSjXdH&9#j@J&iS5)r2>Ew z=NY4c$^^vjyfcf7>!Wzc#`yQUo8jZRXaTlbE$g~In<Sye6_yFLGHQ_74%^~}50hVY z7pdO6vcoqCbY%g4s3Hlmpy@T^lC<tpP@dGIq~65BzZlHFlwV#t@&>9LYSq`5ztAsm zGqmU+A+<b>aff2scHPSHI*alW->VWx@uRcoc1iaHq!VP5lBW`2onu-<VwEAD2K;md zV0>;K`BbdX8F)Yuwq7A~l~A%`sEbVNC8)fp+ZzW6S`s~LHRA^$z#MOvG+b951wp$d zKnaug{pGs&lW>-YCj<~Aq0c)llfivHwX&V6s5wcWm~U8(&&+^_?21s_t-K>^FI%;6 z1j&12Et7q}l(IivimZARS#h~F+kDfvJo45(qNMi@o0I1Aw;A>*ZHK&gb8l7252vY+ zTb}I{?F<gAZOGXz+Dyl{=uk6?^bM<LKBtd&c6BzKheDz~3XAQ4S`qnbur5>C^&F!j zifoXWvt2?4%W0IY1TB<I97m|Mm`T<Jx)Hu9+t!7uk`~Q3@t6LLnd^XaweX&9Bn=HT zOS3xwv9gTehoVXgEw-ca7;<k?Wscz<%1L4{8qM-)SQ?b~B_i}rMY)k=98bd_r|+Yx zN5(T#xLxT6<mxuuMt3>)NwBNjfu8<aZVb1r$Su+$DlcqqUv}W9a--)r2p&sRbO_hb z_wrDU*;_9%{bS2qtqw~-O0j{V`$sUv)s9b@o(JY$!)xB)uU&H@yMRQdq=U#OVT)l8 zbhT0(PM*)ccHO@I<hEf7e<QfakRze?VXKK}Q2q5zIW5~U0qXo)o!V;iC!9PZ7C;qv zrt?8K4JqX#@9E>jvv$ouu>7st)}QDuKY9}W!(lg7xkfoR;oiQV1~!0v?IomjNYv8D z{7uh8Tino(x|7yU4~vD;&CB0*Ke49uD8Q|P;>!$`6NTyMetE@RXO%Zs?NpM^EQ9fD zRHa#J)sd+|+Xki)H-*e?C*Tj^W4$NsQzkADGYtYlL74a=xdXy`@JmG`&iNAuJnaRr z;G3Pzo`kaTAIyh#TCGm)t^sv>ymZhWLG(S~rXWRtNko+whS?46ON)%$YPt(Z=#|%x zvNqJbe6V1pCgNW<nS7CAYNsRK^0Su<kfq4EV>mv%%eCfX79Akt@-`!0lPsOzCC}$G z7!YMZY~`tHq;%xXJ>~UMNv2sG#X;yl>kLRtJvsAe!k{1|K&#zp$B{Bu6volrxXGiX z&nW9&@xyZ|5A$~RHhv>*gkus48M9J=;~k5m(ykDpE*A=tIq`TA-~$5j*Q5r~2wn0< zs~<S4T>I?huDSrE9CGZfGGJ#uxbu}<rSb8-!O-^?Hcz1%j^t&$`_klsLu{oDJ_}Pg zc{4P239CHj^GT(Y<6yaqnKVv`BMW8DY!Wdsl%?uRTI+8gIF+1<u?nl$8;enVgS*iy z11HupAUa6R+`Cq(PLC)0AAhB;Rse((=3mJGeY@CEX-F2+K8<)nf3dRoLi2e319sbq z*ZgbU{#5ch)1%pQgPHIMSadz~zmqGn2i&@AWtO5#3jgQH|Kv|Tpo6+fhw~<`m<YPJ z09LS1d3Bq-8n$!`&o3xEG7;J6cOCQ8uW>e4_NeO96I~3urMLlz;g?bI&B?L3Gh|Ve zjhcT0&SLr2ZW3yQT$%gYD(|%wf5xiN-!7-bDs)tvDuV9;ZjT-4sp!1LFH+k}LNLfu zvw1fvUaJ|&$?Q<64`v7kpm$aR%aR{3_`u~O6?v>*XF!!qrpR2-joSBhi-6m<HK_q= zi2ht+({!kC%^A}P0am=k*UtcGG4R)4_UHfX>%|sLGbgoGP=5?WN)3FyZ<wEylUfZn ztLtqyza=Pqjc)L-F3ns}F|##(Cyxr&w@HTq2hS+=s@U9K7MVZnt(4E-V6V<w<v%m% zJoHPpZOE3Np0$A%W6WfS^0E~2JC%d&M*Dgg&#c1D9P8FPJA1Q(x~<0Lt1~I(8}l*b zd3J1tX?NG{?s0uG9uXD|)m_TE`U~p`-kJYji;A(Tj7rx76VwN^13&uCj!*rzgF>Ud z#vLR^iG(eE+Qxafu|mTCRRk!IP;h0`U%DPY!GaOzyuNWnP7pvO9b0LlYJg`yY%H9E zIKr`A2ibzwD<pZ;ttv9mDOm=UU6e%bnR(lQtDji8?--aqdj~T)(ZGCn+WLF_!814b z(Y*sC)<h4}pM>1yjEF)Z$%d%$1CB~GRG7%MvDCG0>Fh3l<c?_mbPh8#-BEk|^6>wP zV<sK+9!PJivA(f}_Z-dIlpqN9cK{L$)m=`Q3(uKf$y1DJ>iHk}xUT5!f$J%zxnH`S z@DHxIK`i-e_XW!s)lNu@1j6qGDgj<KgS=rFuL4ogOH#)_4fEHGnn9GdfoL%n1jLv2 z!32((_R@M4QN|46+!pypEy)7ATUEDKPITJaT);3@HWu|iWWD)n$w%SB1y_AhJ(qvG zNLKUp_0%%?Okgc*H~F|rG_vlN)%bhY;+vh}lX6YAxffPdqt``z$8rN@LhoMv>IuCK zm?H8H%j$yUmVkuw6lXd4^U0L^CN}r~voT+4d{8GkQLPDQEt3g)D7$V{@QS3)6jeOq zRLaTWTN&vLf<JkMXT#j?6Hr7B1Zd@9xe&0^S!cq2*H`xA)#0=?sYHLEB!l-mNTtTV z<?Zh~e2Ge3=NYJ*5M;UtyA@JO+IQS~L>FGqk}y2uFb95>c!uXvi_RWAU3OiU`8~Nu zk>>c=rDwJr8M2neT^s1Q(lZT_?BbSd^RlB<?XqC49ddRC@6U3V9b(HfW1Q*!zy$=% zFr&!!a;!sNF@iAqpr&E_kuW?9PqCCkLE8;;*6Aqu*TM`{(PtEVQ;G0g*B$6Ep+V&m z#sPC7)D38bs4z}0Yv!`NE%@mGtW`HVc<jf7RFE!^dv@&HvPfYtM|tjU>(W+%)ur#t z=6)H*{<(F_Ii+zo3~N!g9*ZrW1di$$p39Os6qeh&T(Bp02i;iI1-)imxdT{3I+bVc z@2=iWMz*-+=07an17;B!k5>t1e0ueiyj}4`mUULvBR!<;)Wpwf(`O$aC@L#?mqY%o zq7F1aOg6(L#bmxH)wId*CSF4EyHQyJp{0M<a_Gk6+*jXVENE@eGZ1weJSw1W;g1#` z=J_0d&PF!?xb%~G1XQ^RCND|3aNSUZgZP#)3QIdxqOH5lo*UMDgr(&@r~w)jV(uH+ zR=GP5;Qn`Az%#Y}=#`a|&tJaE`naR;p@YMm!-r<8deM`05E;VDR`!RRYavyF{kUiS zg5dXd%~2R6L`-+()d*>o+3I7OS-}Z{fpM3G!_8fAVA-`j`>(|D_PLzO_ASN!+Xoc( z;?eE}oX`Iw0IR6_qMLl42DSl0u;TlC1zbGO?0zr|o7;RU{;tYWVHL?8aJI-lt5G-D zxMWkYD(WiXDbzQ>W^ryG)6Mtu?;q3ORj7OGRh&{oL(avarf|>Aj4THonsoD{*>}l3 zmOi(q`m8?0Wp6-IcJZ>g>s&h_IS67sVFupVRX(&*U=_C7`H!NeUXke$o&AAWz-Xon z<;c(bKeXgQLlSnq`!2tOJ}Kb&3K*i}<|sZ3W9#3&Nd*Fkgf5L}qi3Ze8zZh3s$xTr z<y@JC0<%df$_T)2aU-|LV+Ovsw$~%E(+#zx+x`@gAt{uFfx0D^RI*wsmd$ZUo(6&! zgC3Xr6;kzqoI`40&paCXQ1>q2<%Jh;9j(pH`s%Wi*Zha?ozEm$824ziat&W}8f#@o zu4RSJsK)R*cYiX<^Fn$tAW;ogjfCt=hl8j?x7rtQF{G>*LDu7*SJtn?&gYvx*UZ|5 zg6V+B)OkkgI{r@Y?dyx?12rPeg@XGI=;8CR56lh=mwUECo6+2?{?lt6Dk=edF25yQ zJbIP}H1O=)w!uXFV@t~JVe>yGWXln`uQBd_RV)O+;BI2Ki>gRM4125``0BQh(k@e@ zWn4oi9CyIHQWahB*>(2QWBpAdq2qRi>8-cjF(Qu;ZvGDA6Ft*aBl{$;V!&*3^(&^g zA#BbBUo_MbJaH)gu^<{rqa7b!e)3DzP<ArQA^{p=CF6MSZH3k3%T@ZzU~b{E<Xw>E z)^6CAR$<-$gs!1Bqg0qoK<Mr*wDJbyUp(a^A96UvW43O1{Pys0CXhHP6?C-YGCvbS z7va{$A)P8<VR@Hy8`Nz@a7(k$ypx<PFUq~sa?mX-m)`Vl=22b3te`w>K+`+^4$&a% znc#hA5|U?9H?n^a?yBpzJ38v+IATMiScs!G_-CK{d$`_K8Rnu$t8ACKsBJ%@gkXeW zy}VZ|!d}EDCzf^7FV9V|`t0KB6Q+;vv!sStBH_THe0Mp@2g7eO?P3Y(*&JWe#!t{t zPj49<hB#9p=R2KoGrH0bYu9sPiasc>CICv6yoZat>!y&|@onffU5x~d8g8NPa?E*i z*%?A1-)fpqU&u{=An=bZ<c!ykKa{c0ean=&*o5|6F7mU*92)z`p9@Qrv7@dxb$<Rk z@+Cf-ruy-~5sQd&guLjr$v~%x){XFF#~;^T?<&vM{hC$K^RWgP>ZNA|mqXl9?Sklt z18&iE{@m_^qPuaQHeiK!KPo+dFIb~wuSa*ed0;s^+&sQu1dN71TOi=T;E<|lH!~Dg zZZrMm(xK=vkj{J3z76o-1I(dAe8?xvQ0qctk%=3nJ}%g_sMb^zsjXkrw5Y9)!kPtV zZ4!MLd7El|qNVzA{hAzKk3@=_Fivq*IXkjjH+z41=JIz$$Bx`a+ixaO22ng{yVfhC z%~4rfI=>J^VLYS*2NAIxE*D(z!dh;wLEf`9OJOu~vx#AIY=oKqoX&a+x<1LbM!!pR zba@LsO!h+~_;p4!^xSH)u>yz}a3DxZDAzjP#~hSjK7Od-4N*}qo(I51p(o`Oip?LX zyqo&LN!->?!`(TfxaIooZ%Py$RO((!c`W>3aPHf5ePMLcy6tk~!0mpq!!<MOe-^nT zr}x{O_-}V`c030j&9jQ$^2}xl+P-Ob+y!Rh$bi3dmd3T07g}fU-9%`R5<Y6z8`_q6 zuZmKFbDjLg%G@|}2%gJ@Nqhoq$5xl{mN<6`>J%vAyo{^i8dW;;TW(HWyD`jX@QQ-I zzx;s6vK8~wZ$dJ1DiU(ex8xjnrgGlJw@^1VTnY&3QhJ}LU%1}geSe(MiIaK0eaEY+ zaXgN`Sz!ZK?D|6swL3j)e?w4=WXF|F8$j-$1INF$1YhhBAa*mt3w{-Df}UuH3(N-* zX^B^Rw%*_NAZ;mTB|Bt}L(ujA*e^v$k2{D`TNawlZOJ;;hZ#r#fPm@WaYAQ4eiO=5 z2L&6<^Lw+_nkWUd3ZXn+u9>sFTa1?)%2651pLwdQd&%JS{hH49fx8h=Ei$zTAl(gB zukUaneFf5jo_k9DnS>Ga>@|3=p)~x%R09=C%HF+}?T^}9f2_ka1<KM*E42EV{yFRG zcZcT7^%u`Qw)%A-q#Oo}=(p)8&AH`P#Ni$6a;>Rw_Il!-ZNQqO3uf0T45)xvl_z8> zqN?mLxZ5Gq8HBSEh}V3MJeVTffXFUm2AmG_0CEDkM}U;2-un4P1B8L_9gOG%M`;x+ z_{uURkz305#biSmksEtcE%b;|bQD=#a0GzsJ2#N28*a(1P{3tDJG0UTvb^XbX()gP zp-Z(!PZ<f_3!sBUB5zZ}?FN}oDL$mOmR&b7gdZRMOo80NUm00A{bwD}9Q-GQG@cOE zn~!;TG38@Oh)+B6(Dz(biN|<SPtulU1y<cvWX1RtQmU<5>>jFJcd%hWu;qYE+_gbT zm7q@Q-!Isl7O)li9caBeE>SMgc?_=O&=M?9A6kVAhB7)CR8-V8(HIoSmDk2Z0-(nn z^!?jEFFrOO+4A#?%74EOSVDSW0um6nOcrM{2+*kEjp78dSh(R5QY6*o5{+)kwlL*@ z{eu*aEA)}JcrS7Q-tFdS2UTWnaR{5#wnI<4c$`htd1zQ@XEEx9cri{0NBa11eDt6R zKFr$*->3Xw1yeYSl78qT|Ce8_#3okH_muh_iXr;t-Tni8XqjteA{|CM*XdCT@EQn! zGX#99>VgVaikOX|dSt;qn~g?WP>LhnVR+Uc8QOSnRseh9ah!SJS`jkHmpz70*a0NG zVmRPx@yxIIWGJA$-YNwJl(-vmRSswcpi<4>cNCsUnvG$Ok~x)3)$|QsIQ){NQlk3x zoyLBtN;3{0sEv5XIMCwA5h5??aWth|{5j>Jn9O+w1A*X`!HdR8-kR$D<=(J1=Sz8$ z%J7=}U3l-;CePfU?xtHZW>3>cy*;GNo~Tcrq_Y*!uYCfwrrq^Vt459*c~P(Z$DpVq z0R67jw#-eB<RV;|4mnqvTgw2zm>I6VYT%CgJX9e-K0WA+hSlK>_QBpGf%9r;cr?=i z^f(V9rs(Gxjhlwf9fUH;O|ccHo?U$$e*?zTMu28&KrLof6==Li7fY|kXPPi?9rWNR zL)O)kC6}P{#ux6reB&J%bQbJC-G{28f~No&4!9QYlSgD8RVq~ko+WMP1a3dEB5l|Q zw4P#{BuPy(M@fRdE|r6IenqIi)JMiqTKB%(`O~$hj?pj!b-|!?;=todNny>Sjydrh zswE|9ma+d1x?5xSbv8%sKrKNE2Rx^cfhaNa9tq(?F_*Z5Qb5&rBD+r-&`slPU}8C9 z7?zMQ_W0R>W1}n&&<Lz6gpT$wv~^v@!%!tm_d|f(=5g$%kDaYj#xD0!6_{GX3|SUa zYi6nBuBnVSG=WH1Cqa?6ax{2Ftu_=1QDd<tE$SJF1Dj2TUau_l$j+`y1OF*MwDhKk zV#s}pd-1Bw<y6aCj~YS}tVO}aWXv9TBRLIH^?F9@dL%(8y(ktTT^5@S(1wazMeJvo z>eCVUMIFUrXDtOQF)VOcJMhy<#=m!R4Yf31z`sv<mf^_Xi1~MYl?DFLz(r{tG!z2; z1`iXe%m5zSw<{moF~DEKEkdRey?<gJ+&=XDwT7xyH`5~Fj=Y47c*xI96x3YdU&}oj zcbfPmZt7;irw`<)p#@?J6*Q2`^oPyE;l~%y+0vN;RFB+Acv25e|K8>mxhg3sXrEGc zo#O-m56lkD?`{((urlU1hp*|`MnhD##?5!I%I*0})k^DE0k&m*%E@52hr4spMQ^Xv zVl@~G@d3TVjA0}pLWzCy9E8z&G^PFwz{`U|xIv$iH;A}^EJW`0GFYr3yd?{0fl%3N zI^s9Y-FA=L0>&C(Je26QM)vcD$E~4yLaXsDnPJ-%n<5ENrD&NTdC@&@`Jucw-`oH? zSI@nXQPX-Qj-9iIIqu60GV`dM{e`vAu(Tp6L^zF#98Mg?TSe}}>JM=onH2}YD6s(L z?J&66URQiO;;K@k<Q_fAgO;!<+sLbF+%RGc;|U7kd0<nof_CoMjW?!ne8K7E7%{Vd zhk5+zzJD^s*+njkJK;sIA696C%4W%A@Z`EKpuFdfaAVc0`oi#nSqj!sj_s+^`H88z z9VDY5?LY&Kxk<0RSY{Eo)>lD-w6?>)R@F((M{Tu~Yd+)Xb`F?<!!>oqI;?vat`R)s zU!2-rvt;7z(53AimFyltey!L?mQtyuNCQ?=W!<YMd|nF*6bzxtPL+7$RY5h^O(@rv zfHVw-@3^+>OF+jTvC-uSOsGVHPgWazN~5;rP}pX9B<YW-TSQ3oH2FMxP-?5VxTt{E zhV+0k1$0oIlo=@nsb#1FJZN{xRsEMcMgyt(0`JSFXd}^(j4N280N<-}qc76~CVv_g z;ci}}XNPCCdCS%6MA%OotZR)Mdh3=MvCOHg<av9IjP|Ul`2W(MnBcVB7f3Hi59xCz zFO#efkVSd*n=)J;HRRGqpo#j2y*#kLkAA;1Z%Ac25~}giI8<453-e2^AJBTGv-gEa zASKv&qzm1PYOG|=a)S7^6kOl8-iyd;e}O7RYQsve1_2fXwLJ0#Rw09i0OV!KTDC#P zm!4HO{!r>aOk<os1Yej@w!KW=Y{2?MGr3!QD&I)&y;@yBNk!R8>}3?6O{01^@ELCB z?k$L)8p3P>Hl^u}5Q_p40^hx%UdN4wl6*o$!|mdPq*tRYxzbW)duF-`BXjzmuU0nU zV;z*nIQ?b<%KG&NH!Sd{mwR3|Ov`(fg^C|^2*G-OEg<|%-Zy`dp>9-SiJ<Oy_5kJx zaEgm~5FGUDV<%3ki#7;<qS)4RSi3Qn)nP+@V%q&MGUVg={rwsjj}EROp@I;5&*IUm z;jPasKZU6vIuPGOn15oV)b|hHf76xPZ??;j9rb4v5ZBGpRyy=l*!t+lu6fPRmC_U= zND-%zDjoB<?!?rrna>D|3bIr*=ciG^v8uVhtnx^I;Xas4r&XEY$3L5T;_U<$A!DpL zPctG}$!QQ;sH!~m`N#b${|nrEC6b)ez{hD#2#8x*Vjp6Y(TH(RlawbP%^8A7adxKi zz8n&+N4u(^8YUeON#_cze#Bfb8gZ6_Hk@#FCvWtfWq<ce+38t9-lT=vk56I<g8wJ? z^eFc!n~B-1m;cF`COY2H7p3rP;4>^V?It=cayLt;)YzT9x!(0-yP>@S2$@sr-|XR) zm+VmNZ=V*>XOLNTqf&(>QG3Q2Ad~s@hTT<6{LW}qeda*)Qi%}7c4PZbQ`mfhuaZ*c zxx+n*WcV<;A5`Uow}$i8*auMkO#|i0i|SA-hU4E|V4$j|b+<i=jjWYouFf7ByuWg? zf<fE4ie|eM@aysYE~S~O!>(%FR}8CX8fGFz3VbX6G^17q@Gn|B7{aVAzoJ^U&Rm;x zv^{r+Te7fcz-MOOug7^V=gAyJKKM_siC9R5_odB;Fu97@U$|5V&lK#@`V@p6K%LF; z6XzpBRX0%6P{V%d!1vJeMM1~3Ht6k8InW*{mkGZy&WTe`dp^M|y(jEJzelqRALP2= zGBt4hvNI%7>lowH2?l8+@f^+^-hjD`G0S(>65!B=vd3u3r9Dogs}RVo3TA^-4CVE2 z0Qh!mXPXh^lXT`q?*iiQ9id8t(~~kSw$D&hxZ=qwy&QLC^_eG3j><hbgimm1zynnl zx&w%K7OIp_KY@MoC<y4L-|DsG2=s@8PNUgWSDLq51Y4ULgo3SG4D;o=_PM1`&ZxN* zC&RQjf>*Y43yHZK>=Gm^>(>h+^IA1C`JCR7^EJ|$A64N-D<?jq`kTw2la%_U{vd&1 z&%M&eSIo{cq90F`PdCJMe?2(^B?0|#ceCH;>Sq{hj7$c(fKgk>w0-PQs@$gZj8PhX z<!`M=bIrbZcFbhv?s#|t!mpST`0K{JN{54WyTj{vwoh=$8FUU)xqqWi)zTkEwxt2O zFiq-&NwjYey_&6G%_a*?7NIh$f;qE^zZ=CedM<`2fs1<o?E5n2HNmDiCQcWow?=qN zR6gFnSna}wFtg4?SF$JhYR%q(#U9Gu=NTLxoT0VO!fEdP#fXq*oBU8dBtCV~jt3*~ zD!uD`{+-<>>7yDk4m!hWknSWiEg<^wLz0uH+~b1AvB>}p)^p~M_Za3J4d~p%6c@W| zfy${blre0#3>AHa%w77yNQVcrAy4mKIuq1A8Zq*eK7%5A3r{qQ!*)#hy09~UYfyL5 zyg`_S|3;B;R=yiG3ZrgpHD}q+Dggk)v$Z$W&ZZ6v7Uz2~&5^1*K#w@*?9MEyp?8Os z;oEYaGilE2wR@P}yW<lwnO6J+hMHq^;jq~w%mzA@jyZ5|=JS9mz|c%-n%O22;;HZv z2xG%3j3wtfv=;u4kwwVPtoM24BB@zttjYh^`i}8w$nDm<AXhkzBZAh2GIgI8*HL%A zsY^9ek8x!e@ftRNuks_qg2@dGILyr3ULQ~oKegQ<>7;3SFYs1;{OBn27S=f5!BQ2b zm<$8fSSRaFdaMO_uJ-1&L@v?uc3vBBJ6FXtWT8ef4ePT#W^yj6q7+&n`*@I|FZVVp z>k+iyGv>zZ(d;JUp+=4@*`eQFwHq!GZsY2WqIcJ^85gB9GbVR6(T=NGPo^d_E2wM* zh5oqyn3h{7VpbKDl>3#wG<HmB@y#Dz5BWce?)xFB{%-^L0ReFX;$DCYx43d;fM_^# zr)K8fJ2N#aWEgIoxhmWvEmvt;cQ|vFnr$;RGuyVz%5OeCf5bUIyg%3Vy0W6xSi#ar z*qwY+n}C~s;-qh@yU@v-E}HAfBPvhHDk+7`n?fd-Oe|t$uUw&_`5)Qa32b(ot|u)) z6m1_SIb`oTus6vVU`Rt0qS>!DY?S8$@Qy5LNjwVg(1bDHg*Yr`XYMpeU&@RTph!qw zm86PHE!{(@fYM|sCEtpOln=yYEr2PA2#fA$WVd(#9#!`Je`IZdYRZJG>HEX+Kkn&0 ze=xE6^xp)jL!L5N5b$xS0sFM|I)d_4g>yrPBO68U!dHsFY#i%ymk-K5AH`pLuB<3P zg?w&|ViHCEH+&$3j$34;9Nc)|rweE^M#EYZv@?xZc-4J-#>m<bQKC!JR<s|TFduWb zwAEUtW3@qqt>|{m=`7)~BbeNGE2F=Bg#9F$drS94Nh>+A^MV}FQJK}Ot(Ile=ltXd z$}MwAQ7_4(l9WCi&2W39%>UDu)tWO6vOio#6|x&iDo38hLE_fMNWC4*ms2Fjeg_Nj z^0@}+rOw&MTE`!MBvpVnJ4<)~?N}PyZAZDR_5ZJ#gYw#SYEehMHA!&Mz!d8P6(BRj zhOKE+vuPM>IbZobJ<Q~D-OY=x($<D}K7t5CkJj#rx#mv1Y+r@jnA{{KWPLt&oV2Ly z+{=pXMw3=Ria+k#-+o71mu`|kHw#dvSNUC0jixEVe=VI1Bq=6AysxLUwr^)!1VsNz z^1?{-h*a7<=P^-#)&xxKtZXIf>+F%asxE>M^C*!^xAhnw#hnt03PeYXLaQ|csaj#& zXvu3_)F{vD{s~9%EX|L6f7wLS4Lxm7od9dY5M5=9CPPz3aF~9fON(A0Uvr@Kh3#s} zBHX9}Y`CvvK|)BKairV%y3%CST->u*(PMKTMGQHlRK>!Gyy(UIg<zU|?>p&tcBBN^ z4{6Vd?ShMUW?H*!_?e4DQyQNzZwun|CGo56rTBS~(N?_347^&lZ|qhSztrb-+lfyk z4pz~feKzINon_@?cwwFS;xa%O|4-c>2O%lits)p9Chxt>HuOzLFy;&u!*9fZB(i$) zX_poziecDG7m0X$n0$Xv&(cWG1#Cne!(NXNx)7vu%RqZ@Ls;3dCsn{@bp7l?o9k#j z986o<9@6bm|13<YzBUxN&kT6v6aJ37;6|q{u`;h}3>jaqlHSUmF#HuEcwkr>sF)&h zX>0*XXXq#wazT8r&Mto_9!Av{>!QFVd*8VK?|x~;)8^6s@3s@g8WRz#bm~Dl=oJY8 z*X+4k*->8_tMa#Du(PL{5OYaql8`Y1jh6KMRIRF<5)|C67Vnuw&K!dk{O{$gZ63={ ze?%pKFK6MWZTn04ETd2FRqbAUo*7;zPHe=;jzt<#CtB6_cDqSSM$T7VrO`bf?64lC z(Wk+*lN=(PM%y#wD~3>bKjn$A3WlxfDQqaexoJ)|a@6qXm!k#mE}VM({ibVtMYwcD zFbQJVv50#TL;3ZyocQz$DQ|Mw+~tU)>+xat%>9vvJ~HOXLdvK}uAf65F%0zI3!Ckq zD(dU{86$z`Mht`*20I5x_#fnx_cq!p)wDCyvpYj_4Sa}vdeo>Oy#JDX&0#sFc7};2 zlbXTTN$Edr|KO_YBE&gG=~Kopd(3sY=Al3VX37~RO3p^Xc=0<XXBNb3JJ^$O)P6gM zVU-Y{^efNIv^WLD{4K9=riQp<E^<mw(%@q3)evJK=Ek2jHTuVpCsauM9d)2LSvR~o z{d!+MxNVPw7cOnh&k$!GR7$AbaPfb7%DXprSrz9Qo3w;w<U5iXUK=U+<nRQ20?`^7 z12&@cGnFWz)+0PKYyDlaUPP+q)%SNZOg$!wLn9Q66CdbSFH6w#E(3)r)uoc?LekO& zc{_+A!I<Py*ynbykvMV)eXA(Gl)uzI+4{G~y=4;T6H1OL<*1Y{N%<>#J&2ZeUEAB? z3d-X9J9K4gxpxhZBBRyZ_CWqU{6MG8MjA5?VnEakbKo=BXIV9~P7JcFt@*GkJoO6( zp?kxDzScf2(8DMDDXINfBM@OGp{j5jHeM1ROL5?ntm%(_=XvS0cw&2i$QD8;o@>50 z^;G&tRh7ac8v6W)Qc=n&d1B-1^alYWwjr<M&PS3g#n@%OyLmdUUbjiR8<+Yu=ozS` zap#KYqF-;m+ENFPVT7x%zdCp4R;gp|;b|rE!Yfywh|BwhVbG2Wdc;Vjf%}(g-NRz8 zA;c`(17vMlG|2?-5pP<?^BZH@KggIZngKp<_0LRrKvBx3iv8}lf2NkL4|Ys_No{v; zf1@(Looyz$Xq=KJs$fn}#6M8gFD|}vI4{wV+;E%7ZYF*DpXohV&rki~FF7AZn=5;5 zM8z&9+EI>^D%tMbe!EG`1CfDQrNR}nhbOm4!h8l9BZSfhB6lz)z@Xon6}D=;XYzDN zCgWQjS>l+=<bjGzW9Gped#1w1-@9-=#a^HZmJng#V^Ox9vOb!zwhJHsG0xLLDnUjs zFh_rl#~!;uP-J>o$L2X*C8CM;j?Js5?Y}_55l&M?{eN}%9QN4ZDL$qcKn4&XAYgKc z;mnoKt8=N9VvB2#Z}S0SiojVD@D3k_Lnb3cuwV|HhXeBQw&0cSwIQc!Oo|)czP6RI ze=Vgzxt?0A9srTwsxL)5<^Wo^mvujSoiU6-DW@1UJ-Ry4pX7NnrqUqP`+`P^nh4@n z;7Cp2DGS$j@4jg@K|Zphj6ny`uKCg8>w7)#mw?X)*oP<A>j(Cdv1iXDl<QmR)VwQI z{XhU*8-kMPRCn=FdqE{q#v(g(ijjrx&XP{5vt^&$kk2^TnLlg<+~>%Mk2^>KzU|&= zPv-=@G6m!1^FSD=jhKAU^8E~jGbx{5fG7m63z@}O1TiszU_da(6eCE0V<stCq8eFd z{b!s$_eq5+eSG*<8L+LJXy^-|Zx%aP)lV7%F?AEAS5nP4)wv-ALEu<kw@qtKlF$2c zMvZT~RGU47rrCb24lctUAgf*L??gGs#-!Ro<wBmXiC&X_wU(n7GtS|Y>&RnLD<stI zKg!w2|Av(ZCJWeV0&VME_`of0p1Kb+J+CJx!fg+3^cj`tq{0edwA^Jx_2k#RM0dy6 zUBK91JIG2k-OSp!%!sQ)6v$%CPIp?O=P43oen3t%9RLK>z#!W9h3b}Dmg>HB*$mmX zAe_0Fc|Fby-NvXh+4~!T00q0X)-Cvh1B_VcB^4v5@fd{q5qvSCPEco5*nmxLXKUQ! z4t%5Zxz)7T1o{7%x+hcSlPgcGDjKg0L_;y-T?JqiEi`Erq^Eq{?HhjRzg89sfBs$L z#qs5I&8A@G5A|80YL=VR^$B3!6NaKCRs6WR?5rvkZ|{UHoom3W6cnV3<No(JVcPV! zCU{uqCmL0Ho2qOYL1Rk)ul!B<%YnVOiszky01#CbieWJD2anv53<6iyIagD!)m98k zGy2?Kwlg9vfR#cq7GT-p+2=uyt)q%s=8zsJ{y4RAIYm&iZaT{i@6%{%38#c=1hr40 zuFU4du?7T>F6FF)13Kc}YE|TeZ+oKK6STlrwE{a6*Ya^c*MyQ-%*wyq(E&4Ck+ior ze#PFmpj5}Q!{*00Dx6k?VJ$cd@5mCgY9ZyI+b059vPD0+6c>5~ugxM|IJjM9xXryi zE}<9qWBdiN7LG9nE}UP!b??pljw=yhc3jqkB`f1{<^#)D46)iZE!1Z&VFF{EpD$q` z0pwk}HW5@zHHiGhz*y}~H2U6x(Zv0gy`QQXU_IbMK-g<URspL$B)<jcTAQO^b>q_A zr?Ux%pUE9-n$PP^o|dr)dbW%wU%Y0@Kx@%#2Xwt9a(34wUadeeM*P4y@s0UC+;J)P z*TzLqXw2cXOZ!Ay(Q^_c=yyH)3&!mbTVDj&8gV)+ibLvnfIP$ruPEgwZ!>y%;XuVR z62ue9FO7jM)Gz;hI?;VT!rD!UOXbIV+5+t>7{eCOw*r)sGYR71RWTvWNy##rh&1_X z0dL#kqqY3z$8}VBj~0NlJN~Da!k3rroB{4+__1*!!l8U$f8OkO6}8Z@gy*$As=uw# zVB5L^HF-L`*NxC*GUwI=3EVCwrQPLtd{>Po+I2+EcJ8FN55}OF%TiQ)a{?`ct9<T# z!&sx?(5V)Yw)Fso|7~Uo^Vf<ec6%EE$(mMzpl3<4Z|)EU+W63kJP;MpV|){Ng*`kD zLIAW95Wpu501E2#!vIYTsH}sd(8C&*AWW_=;w=U7dp5@pqU_q^O>2P_fi)mrK+C0( zKm4?35=b2AhwpWhNZu95n-V#4H9p_QK8MO8XtV{?d21*i-S~!?O0d1zM97Z|gla#J z6mm(dl=6=v!{?qhY6b`03WnEZ{WNELVT&F6X6VwcD-2y-L!ls&O4R`~_I1&51J%8z zcbF&b@HTXi!Uz1ia08fUs!=STOol`VuGT-G*pAoB2k>o7ybVIy2!ZDuv1=e2Kc0S1 zaumqOkf%Ck!DvSWx^v!H%L0f<xt-YWnEZ@&3XFhZt;FM6HAL(*P*u+w7fI2L)DP+3 z#62L55*21w$&XXe)hRa!N6GU^H%6{`ZZ9^IW>-k$r+wa*lg9$)b&sR#j(^sF6gT0r zgp%wc-*Gu*mt8bY0OmzbY_3U_^c0Jv^%4VBhQ#}L!dZ$VZv3a#NWoM0{~3Hos^84M z_9fRYo?;{aIl|<ix@o4sN4N`%xPn0-4qHjTSp9Un7T_FYhiF{o43jB)wI40nN_#CF z?K&~ss<sZW9H2R1@(Gjb9qZR>3%BM9oR2>^5mT5XP^w9xU9M2`JtIVWHEfhAL#HMx z;OpF+RVwdyIM}oZs@%?w9zd)H5OOLPlVYW2mmZ0xe(!dOAf94nkn||1dZ9>1KEw-- zTUmkKiN0Gb>u!v#2(Cz|2h?>JV)!&%@g#+<P3PU_qkR$1n7`M5{Qy<`5oN~izgckX z5ro$Rri7cpq!j=XMclKnTzdbZ|44zjMwhhEUv*aJ;W6I~yd>!=;^)h7oH2}-|FT<6 z=}a%K$SOz8K!CTT`3K*ylKr0P<|WdRKQ+;vbW{RW);c#$_uXrHeDP~aX=H%1#3Pz* z%EP=c?K=xLelqcCh0L<iU7Yls3-fX#nKYjI;_8zkmVqOX?N?!J0m*Rb0R_BZ>^unU zSJrR0(!|*B>E3%W`NLlfH=&&_i51isZa#UCamePvV#z1qJAiq{kSEGrEB}2=TaYHe zF;%Nz!9}+r$gJhbG0)9Yf2bB?zo23k_byY%BJbV(kP&NW7WlF^)9us$!sN8>(F5Lc z7X5Vi0+!ZcUntzJe7gW^*=cFp!M?wrE7&%A_g5$$jmB@Q$;uBVxKB2~iuQf*=K>eu z^9e%UMYF;&t2d0_jYyypKl$B0CsRwMs|UHhO1LdFmPy@f2Dw0R2nhUROu=OAr6jTT zj8XnX9*Ijh`Q%>6__IOhrc~})5#J@8KUaKVz2QpLT~>XEo4FUpcD-0vF%S*vj1!m$ zIpTY1tMHbM+s(L<7M@d*ztrj6QN@?_KXfGOcgB6yio^Ow8vSCu{E)&R$CRS0NjV_m zf4@5OLqFc}_xtqsZJvXmVg-FFZ>@d7-cXaiD!O)4Rt%L8t}2Raz|#>hEP`COAR2Vz zbHKTRIuZR(-%NBOD4)LrKuG#ES4UBto35JIb-aHe)L6B9JovHm%BULsEyV?U?sE-M zSFnxe3=n^@MGs|s$?mk?QL~!}TH8S-;2_lbs=XucFY8U^s9vb5`!g`>U#e9$;5ab) zneb;rIww2c`wQmzZ0K|C&y-Aq^_k`M>rz~-#7)u{dx~a%4sMIpq&6&>T#Kw((YXKK zL6ZqwA6bofgNeETl5<i079Qj$RIKfS)z{}Uw8fgbJj4t;=Zt4qe!+l0U@(q(rEh<D zi{jR)c<&DAiTM4K|294-FNl6n4b0C9|7EaI-ELj28FVkex)@K+z6Jvl-m;@?1k{6m zm$n01L1Yj0%&92Jo$3DG&r<`jSJftb0BfN>{Tam(nfp2~AAd?%ie=6u{O>a$SG@jV zE&ggv;HxZB+<L+u@hzU$CR)XlLBQD|`}-$8;TBnhHPJ*QIp^IXB}!KlrP_tlbj9j^ z#pHwwSjJ~yhQ&bu+BF`x9#QP<x}jK%)BIQf@E#X{1yE${1|w%ty~aQpb=ncjjDM#% z&ejZ)mRO7C*<w?*WWE%6?|cvqk9vWjKlqbxu}!x*_g<@;p?i~r><pAG0Lx3L>J9|S z#O-UX!#b$ot3NtqYd}jb%&VITxRfM3dq|YVRjelbp>JYRg>dCFI+#FEu!FIG?hRrP z#!T}Dz>D1PMI<R7TDq`lIp;3<4MQ<dGm3^TTBpIH_>y2aFR^#}3y*BCg?W6%n9$Nb zQeh(RF;Od+sQ4aHoQm0=&M)?TjQScu;Vb52F;YXI0XI93!5Kjut0KM;=+iM(^WL4h z$>|H~9eRfA)3Rea@pCaBgX(l1*D0b`rN_kp-$D%uGIJScj;%{r6q6ec5S=0{uRYLw z`#{7UBztq=K-Z`wGf?z7O`6T}Zu=zgFbOBv)B$lciJ#U{+5mxgDsv$Sl>`hH7o{In zR5!7S2V-r-apf3E*LJSUK15zXP=&eyz&OTzW1CWNlOLdb#TYzPKJZ;aDhH<+#NR=z z3%D+FuJBrot+K~A^OUzrK459X5yPN+($NNLnxhvQT&8jy4zwotw5`eatjSi}YtLvK zwna<-2hzB^hZQcG8XRz#?Ns*j9ra6~>C$^GUT|c1;`n#0liNp1Q;o#<zDS0VtREZp z*Eq&Rb)TYutR&u8snZd-1gHIG|CKD<K%`#&28LNrd1tL}Q;dnxS91%1DfHsfIppK{ z5S}$wx@XvhXt@7=P)OGYd2ase#W^qPc%dBvSUi7mErV9umnWShz=sdD;`J#9BBwO! zzW#Aur_f8MdpS$Rn)a0j=JOr0out{C9%jPNnY<rn*dY6#V7dD|!QSt;&}+*#qon`S zw|w?SL8;#I2n{{u;dxcmkY=M~JmMskUsbS1l-4(1D-CKG&;Hkgi+lY`P17`M1a%-3 z2i|k26<yOmgan9ys|46hkao~3%r#ULtY2zAg(q12z*wOr^=?=UD7zQpM3&1;wouCQ zk+`M}^M8pGvR}+)N7XEc1hjCT^>Z@$LK>IX9Pa4+?dH4VJL>(qPU9^ZJN5Zv`8Pt+ zDep?R*>Rlh09~&J1fd3+zsnQ31k$L*O1s!$OLI?>AtzFeq<k^QvccBe8AWySDvHGe zC*l6_oF(YTCF)Fm{5Y;rN3lV#n?p$-j59QY^6-rzYB+Pp!~lz!JV8mEt~=KED}j8{ zUx`k+I>DzdspWwVu7+D=B;q2b&o9+=#QgB67M@Qk?l(}D6{CkX<B|ZzEx)}9-}NAw zn!qrPI-NK>Y!=qcvsMw!=Y4%-FsV$JdXaji+lF&WG=}Cg$&$YO$iAjlRt;<UmZkOU zOJwl=z#Isfz$LUx;{G9YKp00#?NLjt)yuWSBD`)F*o5~u`*ZQPnQel6o|P;;R-FvD z-ST&uiGRC|S;s?~-d_G(p1-?_nHve)zG?aSms<p)6OFqBtkh!4i6yWD_f2kiEoK{~ zEO?#7N&k`(O7v1ZEiO8DN;D{-AwMLT?x|E?`d{*YolLLbl;rr<h`}wn_ROruYo`hq zb*LA0Cq%-2gJo%4l&|#1{n9rJlnTOHYOs?`o_rCdPsIevEb|0v_CTd^y||{+9k6k6 zZE2kDyUh7hxPb#P3P{v}M>@N`PtvzCwCMbgrCe0H7v+Cqgt?b@1JAwtmA<^H<j4cO z#H>XeaG?pf7+RoNqKf+3>!5Zctzps6Jolryna6~*+Mm9|SIh?mg>(%kWlNtddS`zB z>j!_kuxFoH%_n6#Gf{OzN3XwT2Cv!Ojmf&A340EXxFv4RkdjT#r1$4r#DHYlX~Ly} z*#~xXo_=#L3?g=>9>3CriHtd-UUxu^>|UtMuW-{){5>8eng8l>{@3hBOISY96^wpq z{Fj|vNOU1c+QQZWyX>ha-goGXb`kcIYL65!1(}rW2&mHQ=-!h&@M^6;UHtEE-K`&4 zxc`QCsXntglCs@U*@PXu^Xby*_`!);y-uv)7FRyJ-zKI1LRooaxQ|pq0J7>Lj=4rt z>%%oo8iu%Apl^8wygu}w)R7~qoI-LP`X_Pk=-DR+%x5Y>>U^-mp;a#?l;%j>Z@==8 zDS5s?EwEC3RQQ+ZTH(XDD*PTCg1xE^%tXFl>iBnjRmU?bHU^xC%cI{-FWsx67psOJ zN4(McX6r|$cDO!CKF#ddhbQn@N#E1b!s)o>^b%{l_ApNFV7Ej~=IJl9nwK(V^+9qg z(~*f(3g@Vl+E0A9q?TY<!=!OhmvW;9nE2}LwLF<vjlJOvB#!i`?-IJM$%*T#4z_+a zqVVx_^Y!ND^X6_pj<(!wX_1k{fxT(3>RNNn)N0gv8f}d~y`7isOq3{Whz8?qO{$WT zJym5w3+w#jHtP%-tt+v@vq!=o#FYMRlA9swzz&zb!lis2XUe9F1_5$tzObTNi}RpJ z36Sgt%jdmAS~l0W_8kEdgHU>Hb;s*C)GXtG9PWo8ZsJ$qp}%f?(Ro)YA*KsgM8N@j zq~>FT=|M1sqz#b1<4r8id^jS|t`pOX@52Tq7$b0y-AH|VPx_#-VnzS?qKQuBqyv#S z@OauKixdAoHi?c63^n4Yr#rq@nZG2<bYdml_OKhB))OxVQtpw%)3W*DwLjx7-g)!j zPNS!&;cJC(kZdncs5I3AoXGwm_Zu_()o&N$NPkxWf4#$X!jLmw;VSoy-?%RrCXauc znI{20sM!uyS-B!e<5#H}KK?>JX&hwa*M0LhKIWKmAGKA3JU)I4w;aOp+>L&RDms?Y z-;s_BD#2AC7?Hba!S>c6ZHKSa33ha*SLA%UTx#yH^EWF~UaeLp!Q}Q^T<cV9S=+FT zfw|sCHHTMcQo9n$S%Ct7h|(tOArDXudZ~VLqQ5n3y(kj15;i&bwF)8mx~bEZ8f1)Q zP287Xz3R9*7Hv-GW$22x9EN+vXgBZo-V+J+Va&%2>@uB~R$ZaKCVKA0Auv<**zGmN zEo9K{!@^^WH>wsTaEFc8lM2a?44)iuXUb|-Ub$N&+;e6Ui<9>tA%+99E*TBpEqbEF zug_f-;bAO?u1zJrlja%T>Xldg+6lcqwJI_EOr3J|@OHmM-E-v~Pw%E`mnGV*<3=N? zxF3GlAl`^-_mUWyd;j3eM|VP(CtgYc%UTb0<QriUb<17kO>(sRd9mO>2VbMt#OQ@c zbpg7vw+HF0z?E3sVt2jgjmwR~YiZ)smf-_>e>7J_ZrfJ~=l9@fKbN*+Uw)Le&z9iI z$o`us;MWDow$#08y(+shD8>FoDA+qamAs1N@SfIlEXH^7=l&rs{3Uq!MoJ3Dc3^T# zD`SHRKN>1=j%RRn{@4Lxx_9;ayJPQ>zz5|3i37B5`Q66@ijrM*qrr4{r`%Trg?@{u zPa5P)7iLzJM$#|lebyK)srwjm<;)}Fi(l@JJ^E=rk?-EowYGE<WEm-Gen3X<{7sxM zgtaqq`nvqa*h8J|!s$x@W?Y+(*vTDY0FE*$o-SzM2m~v+WHi6hXb-`HQkk7Abp;rq zZ|}VMX*CCc=gBH3U2=!;02hb=2iO%An8q=UNOOEc!qNZ*FTHVPkV7reJU-PMxp4kD z2IIXI5HTbIu}-c50sNwSiq0U9uC)arY8lj3w)f;cQIaL>?=FG5pBQB*i6t$jx`+cg z{APBP{f|kL-T|Ki>tB7RL%)?Iu^8%d@tQy6jDXN|+B4z<E<gRpM{Skfz>)u)WPip! z-JH8zChB23Xaa-+9ISQApp=nCZ0G-E|K)P^!|$O<gTeuZH2+e=3msh==HUPfWGWwn z*gC-|(+AH@AVd6_3|OL-z&ByCj#nFksZp|lQsF-f0MUFZM;Jr_PmYxB@$i*QxaLn$ z4>3n52_lYZkRbcL+>#(4U>TJ=U^+4-N%0f=5+bDQ)V*Vgvrt<4DT!n$|9s5oMbf#n zaE|&VG$m)x`e|nJzGDjNln!>ZfzgT-e8$m)`&f$O;VErKHOUpcGE?TQCL!ncO6AvV zq(XL>OQiiHuj=rDPbqUH4+2jz<mUkWn#B7t^-G}@W~Ziu%SZ+cgPyI(IS%Pxs!O2o z*Bu04c8=dowJ5L8mHPIXjSD8Q>*4|_oI}VW$;)~uk#?}7BO?EkDJ4^-9Rnl)h+^4F zd#_?Y*90jK@EAzcD9P*CDHb2KF~=9-1HZ-3lf@LlY1w$m#S0`xFLmxXJGGaZ$3N@M zIe}T-Tr4E%hB>%XaT*Fh`5QY#b+2>UTzF@!nXlVJW{JIV^O%pz9qwe<1}_rVIJ2jN z-Rz#JnZ;hrF}#C5ib#g|T$sBIn_Uw|$6|tWxj;>Bg?6sY0D{CyeA1H7Px5t1Q}DFc z0V;5B%1JoX4=m~PSznhH{&^<4jlV<C&BfXbAj;albpP<sMe9`Iq0Nv49vC72Lkkd3 z2^r}GHjla>8+Eb0`z4Y&C@HwpWA1*GnZsN*kf)+^<8jt#tedgg*zpudrEo(~uCXm= z0&548p-O5&uagQdMym3*Wj)dkx18dGn=H&Y+^WE=nk2*ysHzGZv3CHc(PYK%TY8@d zs?ie?LPObOSqDtkISv|vfVzWCTj>n6^|S`?FeTZLbpP|r_cMA(mE=9QR#fjW2?NY! zlI)a-Y}bDjoqszp*I47n{DEV}fO>KWmJ}rAvHffxtED+a^KG?uYn+wtBdHHFUc!ql z>C$2vFN%>=Z!eDR|3p+sno^{&K+|KGYsxw97f;Ea=1w3f{`{`6a$BkzUu~0OR|3R@ z7=h7v8I}xvoli>7%-5xW<Q`Yr8h=Jxq^PP&VS1p14H_d<I*!h86Q)aha~%B0sdiZZ z<D%?V@U_r17-{;#PV>#br$W-l$kd-e!a+tz{26H16bSaU@HFR3{@Tgc=OM{u?OXe} zZUjlVpN!}n+n+KrkfUx%!Ss5ad}hqq>~$D0pfH-lzekx`7F^Sz|IqOhA<4LBQHDm2 zBd|FZsMnWEFk<Hr_O3~`5u9%O2FGC8GZ=or&zkcf^E0Ngc2;P%RLxj|DZO6-G;(&~ zm$$kn^9UGC`lceB!y1#ENElXTezjBiEE-kS&m?gtWXLWAl@wl`-E(V%Ud33hCoTJb zRhV9V#gIHLeOXdBKk(CT#WO1+cxPqef$t?Q0LgSA-IS#7?T@zUU?!fdgmZ*vnHZPO zE2M944e6;9m_04{OBmZyf)IL4f0}yOXozBKGm8E11C;|0&sFwCXw(Wfj+HVoK@|on zy&!LDz-#*$in7F<ONmZN-SqMI-4~<jZhLyZ9QGRsU**)IO-YT}Afo~&aD`Iyxipnq zj8Z`@X-}wFug%gI9n;o??H&wsZqnP`&tWs)w*BLye|lyZ3G7^M|1)`%Pr(Kbd-n(i zPrt{Ig~ae<!Q{CVL=JBB{0tw4WEy4DlqaEbQCNV2hMKZ4Fcpb*HP|ChnJJ@eLz7Qb zed`K$PyhQ#putemS~8i~QfEBU`6e7u>@Z)MjiIvq4i^LqimngK9O)QWDK{gCrchjD zqle`zVZf&1*Q#|st+XI74n;mBClO@lE4FsK+`IPN=2<*-jsM8@yaXW6n}VniIZ){U zmAH>r&xJp_n*JOKq*B;QpgjOW$8TfuF5zEHe7I{9m0Z92#xafj90>zo7dI>39|yXC z_L*6u`#=RE?Iv}fVOe$xgf~$>4%fZXulZLv%o2dF`96<}lVEZ$U4wTV+~0#`bJ>}O zoGxJto#x&W0f8$qwL(WKh`ngEOp5p#dSxDt4fr&na%k;1XR*CInlvSO@DcKq{Sl3p zHWKODY5K2mDd2xMz8wEH_{v-h?gdTY@d<Z>eu7pCOy9ACE(T~b*S~a`^AT-}+;~)b zlu8lm2<!Y|j&QtJNtO&+{b2SrhUozfd`fZD(cK~Zsx-FwGux=MNH8pbQQj(gsi17$ z;RG0SBabmI8-!5Zdt$~glNikFB+<J#8hrfW3AVwysiO?I=tJnLXk$rnsLoqfD$Go) zLQdxXL{q3L)T}pSL1>)Qatm`c$`GKs9A(T&0Yav{TbnU&(=RlLrY(OT{CnH#a_<oy z968Jt%J<ias1=Hdt$y*RPs5BujXMorQO>=1w9#+-D!?%!$CL)rWBPkC|7uUlzFu%H z>}K>^!COz@Row@rZ<?Pa>}zANXvbigTdYKC`qkII*1B)t^H7rsA|ythftr{V|7aD< zQPpCwr>x}3zVG)hQw8V+HTF>u=gp^_pU)LEqWySF<<({ml&HkZ4<5s=B;NJZc&kPo zc$YKI7~LCuwtasv4@ken`g{+=Z`I=_dD+Is!n<CfD`@%0b~l4UevMg$WJ%pnE)7+; zc%Vy-5E+%vxn!bk@^fYCWYxo`|JlC%ZXT!&K^C0oZ(=$`nhBp>e$9y)KX9^>tX+|r z=iez{INa2R7r?dnbGfKH2p!a+t7yg0JIc>zOrNOQtl9<)VswT}4<i>OHwXrwVA$^@ z70n%${)d=EJ@x=-E{^`gK9Zj|xcv6YSFkpKJ$CE>RWiLc%RW9m;-vqDrbB+E5m*Bp z;DS29C&i~C1xwbkn}_G~kZ5U1DM_T_6J=OYS`I0xCIvySBb9*^R3Z>pntcz#l6j%g zd(c3&7WHEQEuA1OH-!;-1;BR=gc}o8yRm2ZO5}!q>K-_S`0p$1$o^)?zMAA7G_viN z2NJPCz+BZ&K@)Xv_qb89g7PT}k4`6Iy3WG8Ec1StWG`x1opk;_kNg#=32?<BNIuLw z=v)|rKOofE`uulw;f#w`r!K_7Tn}2V@X?^&Z{K=_beY8bv|JBO<tO-0h)cdO$SmoW zdf1$}LPwOBXF9m*DtRS2okrBIM^=JjW|Qe$$#l(o^uZ7h(1^WxpS>x+$P1dlQ+*My zVe~NreLf_UJb^w0gJARp@1~ro0A+B!5q<hXb8}E4@wmd*Kr$JBrv!cM@Yy}Xq(nV3 zBDC==93-{mg;1%}*l+Vqebb0wqwN47^DrX76_L<#4u-v;kO<VWFQoH}z~+#QPz0U^ zj&E@pp?hPo;_p>xFaiwPuaSGx5}bU%kU>OI5fUxPB3s1s<ZNhSpu%Yd*6ZvExWUf~ zl{+iCO%e2HdJb$T7`{sH0x|TPPaZW8zUv}ZN)+g4<?8G(w3_MERk;$5pdujf6i{$% z*6m&q&f@4}-C4e#h}#b>EWk*gqxt^oMGgeGF<;hENP*c&L?p2QAcnogyE-Qz4j@yl z<_e7U`3PGDFap*aiH2qZ{9KW3_JyaN0K7BY*ZSbu5X2shg?0_#K<7=^8|brh5hLP7 zC3p>q-#RZzktNN6kX0Z1)j$fFrF07|*C5k(v>5s|tyaoRbJDl*SJIOrvsVGI7l2yl zX}!Kck6y1TOBvLEAovS?5kmy@D9T>VB;zI^lC=VA;AFtQx`{8k^>j*i&{*YZh!^un z-fPbyw=%h*3Tjc=i*4;wF8p!Gf^|x2?BQ}_f(aB^5s=6i{j3~IxB$rn0Gh~YyYtTz z&WnKo34Ir<M1%m8<5(0hk;D;bMe)N?B6dWFA{|H<Tp$F2eoT>mr%;j>iLXaACDdZ) zvmGOoE{FLx7%|5ai!nL&+VA!+*|H;m$lerG<l$CTi<)dbAJakrRcnhFK?*<Q!e6Wi z-<sQxg9^+g=wkzgn%$vVbAsb(H8Ky~ScayDf@%ed6y_t{N^c76r}xhx&q{-A(Bnvd z@5F)>1mEJN8D;*p2t>Gxt3%*9(J>d;P<hCDA*{>zw+zTD5cp<xC0$(<xdvQc(>j-? zaA87&-6RQfMa9q4&L((aYPmu=mr5JZ=-MJNQmw3aCAKRPTc08A;mbQ*%(bh(VdtTm zQ{{v#nc&K{&87D;qX?VAJ+^YUQ==UT^852XF+|aU6``kF{5k;SA|P^fLFi1k`Y=)W zK2gvPfb9R2zx9<?YN*U^H|${ujUIm#(5q6?lj!9)EzeUefi3<Ql{8fX|H*)+co+Z3 z=O_pv4xR~#9grZ*fweHrd^U*R8tC+FAVmQ9+tB>?jo3!#K_7QS(xmZmhRb<2nrU)y zI~e-b)A`Rs^veyZsKB-IVx8qNuGCSxax|(EFDO@z&K<I=KB{83R;&C>o*I}_Z{MbS zIvBnt`)c2x+t=$7^=`EU8`;-iIUxU%Bfq{PRE}-W*bfVD!HN(yb9227TX0twzLQ+x zTP{u$G96G?d_|jbr3x~ijCh#c81zD?1dMw5=Q!Mz2t_9fuxb0+dA3m(gh2ZS5)ZW# zkFiHUy#fS1jrO2LoiNu<35+NZ9q(?9$jH9JF9#NQapmlb0sv7VGwe(VL@?6|u!OAq zQJH7`Twt!tDKYReMzH<^dhm5-bq*R++09K?(5nt^<Tt(xi0l)~Pv?YnWf_LvQTnAp zP6YW^T*0U<kxsy34kR*~AmBjb`-S8quRtsV_)g9V^&^Ytrb?%MPI-*q5Frh~hXiP~ z9fA#L_S`L<Bx2Mwe?lUTEnAQk<!V{q1X)FW&cPN<_d$y^GdygmMaKLb(8ioC>sYu@ zF&MT5AhzQEjTx)BAn?4qfWGa&C!KMpv|&SDaV4<CGl=_csN|E}FbP!FN(aD^65puU zTSK1ZC$#1TMLzplBR7#zm43(GwJ?qBUYXc_wlVj5D7lp&a04Ma@xILiReuW`b>o-H zAt9kxJfR%o?Ews-xK`LHSCGBMpVbMUV$0Q}?>oq)%s|9)w42ukUeXS6Oj84%=yPch z2PH_AL8ap6FKtAjz6=^chEOqYpnTFskfMSQ(%LY>;m<HYtP_B8G=G@z{>KzOzAuAt zc_$;l|L{kU8HnOzmqjh&kV0C40To-huFD&jlwuCN7R-dqhboY=3r~-S?J9Ulc4Jn3 z*4?@l=EufNf`&}2YuiS9>Vkd9S}m?Ux2k%AaccjaQlr-9^yVOV)q(|cB6|Z{f~XR8 zqKfb|*M5R4r1Tp7L{-JEi&bV4dwx~H*Zi#F8N~6&<NT0&5s&`Efcv2H8o+)D&h@Tg zX5ae=#HY=DjIp2Thxl<LoR6loxph5n>F9QSJT~w;boD`4HiX%P4#VD^rXy5v&X_#K zTz+6#R{6}xREIF2SyQy0muU$eIfOI4{kq868}ays?s%q*wfDpBaq{gmY6oM;nr-kt z3x`Hmvz{zp?Pvt?D*PTsWVB0HUqPn#HJV+2!|UFi*M8&G0gc#NWSNoOvxRZk>V3E` zE`@lnYEb)xO!-e?Ek3-fQSAeMuYmLGeUN$H)|+$Cz!UhcqXI9F>?Jpa7cHHD&hxha z6rAIigu=Y-^yeRnqppx)pTCwxC%CRq5$qhC{7>4WBm{e<MT+0hC0XEE2*N8RGZ%%@ zx>W0#N|=a1)ILpvBiq!&>~Fe`cFP=7dyXD)6zF5g-g<HJ#+uOeEs>Z2kp)ZnOTVfG zz~j)bHEY_>pGGyR#v&9yG?uJC%99OD)xWo#f{5NKi(E0;mREwULSjWKAlnz;M<R3r zCZG2h(_#VXu8A{FR=-wkQ#pnEry!b0;eM=+mWrTq3ZSm#k*0lNUnhm6o>h|(7s3(C zsa=^aI=L6%Wd>e_JSk;`m-jyranmw}dDF0A6;**3T4pcyu%kK8+6UqElOuB?W;smr z%{s!=O!Lmk|K`?c`wphQ@R*j>@!NM4YFQ46*_;aqwC!-($(Q(rvoB_!ioZc!+PxOr zro<jAPk;{{%-pYKvA)k9iAxsR`E>60bC4oe;?wK7i!%jSk~qZwkSFaBzi2rm@v)%U zRCV>uu(D^++OD_rTs`Ze)zvAj8G+DUgvJd!?CS-o?~8WZ^1N+b*Wfj?*5Eqi;u8W{ zV?gB0mi>LA!%e~&XVU8=1L1oZ_`;m9gEs;8?e)yF8au+c`|qv@`BvM{$PkI9K+|XO z#}MJ43<G&7TZsrr+&Kuc!sFazg1zn2o-4oqT;}IA?;T%0`jo2$a|I>Y9Z{dN`lrKj zL_&9VCt+Pfc~6J-2h)U8yRfxg*r6%TJp-n5V`KF~HDvsdZjK!}Xckmwa(vBH;c7og zw)}IBrj?oYKasA0lAhk4JJT}bbI4ghq$@$adMMed7mdC7#;*W#QTpuTv`d!<(JvlL zZq=YA6*Ti~BEWHod&^3GtL0%#+gbk;%rh6}onJw)qQ5R!9jZOZKX3IvA3h=IEr-=l z$QMw51Z=x~NU#8vd-K*?XQF7uXMj6(;{8;mO(e^?Qh_wx(otzo`g((2+%);cwr0(F z$lW}GQNm#~mOt!~Mg7MV7CC}ASvWX@5E*gF+tWIeG}4S_pLDvWYdWhS4bLok<a5)@ z=V!J$O4j&stlWb)jfb-PO@3P|K?ooJ`XM5pWocjUQ~-TXrh-4Oh#8&u{@VT3ZyNab z4(6}Pk=>o|q(XFVzW+qf5BQLF;)@?Jk`Kyc{kq>K)}nh_!E}At(|)RU+ltT|l`}lI ztC8Yv<2l;(98G9myH6CQxd@Zqyo2<})m`==v!h4mg%@bm6DvYH=f1#k`3&)Knavv+ zJx+^nxi<@@o=Tyj|7sUrkJvpw4}gd(75d;oI9eK7%TomxA$&IZfC4#_uu*R|hXMx_ z3~+v{UzQISt2$k#RJy&HD*m<nzY$kp4`9ND4ghcxU6oVfg7BI&%@VFO1Qr1A5?4{0 znbOygkKYfkV8}q5pb;|xNwWnM5BkCd0#$*F``6aaNOAikb^GlE4Tlx&V?fNK&}{vq z*NO)W1eIYJeY>DxH{4(LPQAf+ep#iTq|djh{o|+t-(rUWEi}LA>_2S|fv}(^a(=h$ z&(Z6lv<cAG3x{p{|M1~DrMaDDL=QDPosYeo68o+Iq%41@G189AfWQQqokx_cz+Zq) z!{*4z`tS(^WW|On0T88hBU=n?g#ay}Mjy*jrU`@9sj2%%;o|dOzWw9ZCxV=k_-Q79 zH&82JZw`WPyU{oA*6!ty1zY)`zEKvLm;d0~HW33;D(m(J4w&AjQ=5GyNyp%NgDwN1 zwa*dnZ7|1oWw#EEA(CdgN>q+zHHKCVWmVes%FGzfk;U1)L;oCNt6b4VY8C!L%8`0^ zAXW1XFAScG(DdEEQMfDAh4o@__x%Lqn+j{Z`Tk1joTx>`f(utj>qne$<|rTScHsga zAOJ8;ld*EzzGB#&m^QK6-8|Ih<)WlfBX=h$-%%P=UVoA)4oNz~m6co*z~XX<I00sj zcZ;A_FTfT0y4#@NXzuoBuA!s&Zv>_EF?n;w37X{EsB5^;Xv=h#+nOvU@^SBtx4ks# z4m|f8#_`_!?{{cLX!(+>ek5r3P1$}}b6xIuK;^6tGhxZCQ4hqiDL=z6U*KJWGy8mZ zqurp@IkQ)MGr#!u-|rZm_7-yOcObzNLqQIMYGn}iAQp@09YJCW6B`yB3T@0n%Q$8L zz>mS(d1Sf)T$YTp>boFo!*8vE+z1=^(fVQo{rck_^*sZ5=^{lBS+?kHmGdCehvIHa zD5}kJ@-*9qSqw$o(|QLb`j>KNTZ~H4J==tslX;HZKwvXWme`ir<QqzUF+W+%B>hzm zO1I0GC$<-DjHgygY%MR1J5F{OwE9Ox6$6s+_sH|dBUTV+pfu~u0;^OF=JrQJ%gnuq zeAD_LDFq3&a*$y-Q00V@!M5vo-a7s25Q;y{1v<>NDul?MYRpAOfw5Nr&Qq1T7p5+& ztdISofYp}EALX|OQ-Vb&<W@6ksS|DM#VFS{^Rc{iad$2ue(*!Ibnv>t8y??o`@Q== z?n?&kC$|oEW=ZFf@`84^4*(y<unoVV+5<&0(Ub%erP?RmR%>-WOVN^r?%BsE1he4K z5GMd5M9z6#HUpYg;X5M=Y(QvMr6Cqge<w~GfO|{OAOKm+CWfgawwFY)7;!2TQH+6@ z=AORG2%1`66-!QD0ZLHRv!*K`#0)?2TGVCY<qO3|j`2sHO#5#R^!4r)GR3gRvt<GO zW~-8zAXA}8A)vGA2Jq;CN+0jUznDdBe0j9*go|xBB2CB9DNN@6)5izuiYlkHTkYPG zpXhOsxgNxNnUHBD|6sXPd+2(BkQvqo@TzGk69asZRL?545mx(GWm6->JOEtw1<@{C zCsW7V7U*sYNUZb@l`gqfh&MUuuD6;A`sObF2MEYDHM1KBczpX{1J2?v6+Oe?=<f(% z2X4D$bux@TKjLKd<~3f2EU-<ljV6IL+%<l~fgO^r^53akSUr2vT6Z$G3U}0yi_Et( z9pP>adqh<cMC@CJWo8YkX}m1C-(!VW@OAQlb2g&4W^XI<+b&!f1Pl}|X{ZjUFo=Rd z#rlFO<kl%_z1Io>*o0)mi--^mhbxSR14oj>-1t4Xd}f$K;=~OnV9UMmU`xt#G~8JT zN>k%$V&_UcT>zI-gUk2Rl_nLHmdq~6fN7d4tA0nl>YDaz$5+xR6IQW&v@^fIs$`<^ zO@i(yx-K(*{rwdhV*j102@Jg28e3ZOdioG8iES-{Y56@A@)p*0NPE^o>wGME1QOn$ z;j=1d2cAw9#hK41hC6r`mm0Z5G`;p=AC*E47RKax;AszR&uJnA0L&qN_~c~ifFD38 z(YoASh>B0LEFN9)=y}~FwvYH=+clN<1{B0PM3Y|BzAV-dN}F<jY-;_sQxZ@;cHiF3 zd*8)RPHJRMpZ_zUAz$khYu2p|AcU&!5Z<W>$aiLnJr$01#7R8eVg;0vgsn~V_3q9= zZ9Kn<crR`C2nmGPZ9O4nu1Bl>oq1j9e5}~BI{}+yL!C5mlXz0Ba<ksu-Znt<VIHMW z)ud&}ChC`Bsc8TR);Z)_IT!*G2}@o0G(oluqhRC20n||Bm@N3}W$62hf$Vo?KOwXO zD@oR>zpalMf=_hphMxudOedJTl1tWq)dvZ>$8AgamQQFUWP$bv4jhUh?zwX;|MrMd z*GhpnQ{yw@?9AF9IRbQCqA7UqP2Mh;T9UA3qPC5HveZ0iP<Hd0+AcLJ|Fyl0UI@at z=}mtAILZJW(j+FQPF^U1Bm@ZqcH14FmV1yTraTbXRIsE>1miN4mkM6xdED`CdoJ>I z>Sb@_Re;z+(4|<ecOb}9ew{z*apg)rl!N!^oCD2`|7|~dt?0gx^RjcoCIgnp{$4yE zA!1Ho!%T09-suaJu9tgNK{4Wf6$&w`AKsgX8l@5hV$gghssb_gn{+)_Wyra-SuG8< z@b?n&K~CSH-tvLF{??s0&E}BoD%WE5OqDa(KvOC=X_iw8oS6X6Pm*!QB~a}E;27b3 zcUc_DAq^5X))Cgb*XrAo7vYYR%6*CA{Vj^WQ0W$Ir8O(H=4||6;ZCKSkovlO&EK$D zmH$!LPriY@Md)rs(TspdL9H#C(2@!q;uJd3#c#jJCn<cs-#%kCH;lR;^2NZ)4eC^x zo5x-STouY4{*lNjPiTnNn9sOVm$Y^2{tcx+jP|1KBFlFMM}@FQegr&XRyD1^B_6P& zi_(5I{_>xk&-g>W2{&-{yzw5qy74VT+PO0fvZRLmd${3SEwT64p<&e7H)}C!#hjok zDUvsqipq)+;kQ-p05i{=*HpIm2ESw<+A3xfgij>b%S8l?4_|?760ht@(S|zX6PR{8 zS$>=CT9vnT=lA+V$ZWm&+p|L0g(>!#DYm40A1mSd#gdXmYxprT+tTc+3DxBKhb~fW z1&dgU!3m&&YnQ<wu@zda)-@=R21Q)R*b;m7kd(PqXoLsCt>LY>|JD-=C3*0gNjN1? zq6Ds$1P1Ex*A1T+G$pheT4$H%cI~)z<mrpj>}pdSazEAA-0YX_I|g^3(CgRgawHrg zr%V3$aOkJ9@V0w3FF+Xdeb7-xME!SOf{djNhX0SaetAMM{5{OXG%GHZ1s^n(X}t}d zf!|Fcy1u?$QX!w&uUsOIIN$@P@P@q?h^g;+&HW4`^Xm^~46o&uu{KSreJ|$`hxuj7 zxVd{K076EY4-lWbps;QO;5qjCw2QwB102W~0A=P@*C84B^<xZU(|X1{=VPQglXJ^h zoc$FmaOxq`*lzF!A8=%%+07o=uMagY6+%^8?AG2+^MN1e)#t4qBsW;!P0NE!BSR|g z@hT3T;AEY;l{Gsd6b#Q}pVW`&EcQpV$gK93AXNWLmxn_D_c<*~lxT^*Mk!wDNJvM! z=|P#Cj(6S%OZz#7sdpYB(N9QlrF5IPKkT4lu@Y&3H8JGBIOI>H6-!$ccgipWCSRJ9 zfE5E4Aov|9y^XLCs}ZEXqm%(cT|D_rZvB9pMF#kut2Nx>>L?3n`8%H*nz(nkXZ3Cw z`|!!Ha@$(HYSo8_*hV2c&=Wf_&j1E718Qd>aDr<zgSl{&CiM&>_gyPHf8ln=JF5;P z3)x0JZLL%4ElP<n-tV@UrKxA`F9Yb0ZJs=My}DKRsoAx3h1^xUOlo&A9K?A?t9GeV z#nD!&=2ad87ZDdALv?~|%}8tb<#a>|Tj4n$jWBg1UYzY`ru>0a!P#Z|Cl>fb&0O=o z)l^!~0<42>Dc_t{=M37ne{3;^a99x9sSr#iM<mrTyUP!LN7=#B$fzvhP`8mohP-fA zH9m^Rq)f=2n}%m8XZcBI1rr%TEydlx^~<-ElZ9t2_znRp^~2hG;t~wQk``w3ZK5!9 zt_)=}>363-Qqb_KSuurOr!5wuBEUv~JBC3j$><$vCo$8@4=Hd6FYA23tilYxm}z#a zG7fku-ENP*V47VbET*qD$>P<1;$0SbcUkT)=OiDXvo0v<E^y;D(`@kSu+fNNo>0N- zt5jyuwI9=k#6xAjuctX;N+Rxd&)gddI5N5g4cy5J1DJO3ES7T3iJjcE%B--bjHn8j zmWEu<Gq>Uhs@6}u2ayH-X_YD60Xci16tEtPnYp?t@u+_0V=Lc+Yejg*a3SwTh^2ti zN)ys%I0$u3+n3Ex<p@^PNxdY=>(eUPz`oKW!qpYu+N;1Bl|5L`KDyr4A&wCC)N3f6 z`;tvyvaj1jFyBCcW(wBBympmin1Ny$7`c>5iyw42eCi`=@U<J!x{?5W_??n%@Ker# z4EL7Kife(Iuvvi#E&c(cYMJ>7W-t>jEXmt)ujY1!^4&7TB1z%K@U94|O>f#~5fmx< zmNxTrjj!>RsL(812sy;X>gjCBuu>J(TQti2;Bjqi7H4b+!4{P^&!loLQyw*b7y=_~ zk2Q$3PQj}J3j?NgAE4p--!z>(FF71+Zs=UBmmhp2=w<RkFv#h~#_n*BY3(P*Li{e< zUfZQ$z%Ao1o3)f1ttxjK4G-L0C|!MQaC}c7!MOd8a8|;ztY`odmdXmG!G0UUA~>+a zJZ5YK?8KJ-(@lrD1^bL>DCuCfb))P<`)t@juP&GDBQ=5nZ+N19aQ9J;M+5o`hLjm` z>1Bvwjt2eBF}S>{EzX+l>){GW1M?a_jsHi{nfNpPKXCjrw%MH9%ze$8`v|#7+ZyJ+ zg^*+JTdq#SFh`mDF85tIi%MUF5QQW}xkCt*bo%-I3!lg1^Le~KulMWqe99rn(twxs zY)0-xMyJ^}5f(C{Ff0K-y%!%3Yin&4|F(sQ@u+tbnf6#C)_x<}#-EAxv#%a#d?Y>Y zx7K)e#aMCwrD9@U(|7Ao7mV_Er<W?wx4ubU{AISCNdaZd4l$5!TB1FF!WTQJ-=6ue z?KiwK@E5&pO{$jG)U=6ZJ<T)q**4<6X7IiaR)^p89eAlMnCjAdY)O-5y`0KZ%tOc0 z5u{DqfS2@DBz;OB1_OAQE!jV@E_l66%rkO~n*r+CKpAGB{Il>6Sa?}MuG7+ZM$F(+ zlf>p_xkp6ndzk4p8kkI{Eh?n7E*dBYirx4{U%jRC*v<8z&0aCcu(hiU_?^*S<$A-` z;zo&wG?aRBlnwSxGA&CE0FomelA}7I-VPAox=glTFbIuwdUixPPV8s(5W}g3+wrdG zKdwHz`hsHjxXx_d%miZvc>G>`!cf=7KAhO=u*zLAj;pw>1@bsw!GPq##*;YJXJcWa zG+#TQz-+#_uqY)?Ae6E*LU(;hziVYcYu0kXp79+$hJDYv4VQqI@i_5&zN-DR6hwk` zAnKR9`(<3_Znv>TP~i1%F>U)w`=dGSP0Nsm^IIGU_wmHgmUH1f-r<^^?lBNG*Om0~ zSLOlu8wzkF(+t&aTFkz>nco?q?2tE(;0SYYQK=>FN|@acdHG!p^S<C#mzn2DhCmfy z-g7W@eQ2UwVei5qx45CpRII&MZ6^v->t`QeGfHgSjKkK#bo7~AE9>au)vF5u=(%*f z{X}JBhC|EB-&=pIGmYnOS)5<qmOqzW@P4D)$@|rllHju5@h5W7tv=~=O=o!j2`G8o zBv=&c;O4LO-CMwFNPW69n|inAFTJXR9OrQC<MJvkZgwFHv#8ZGzB?|SRW_53sA<Zg zr-M|0IuY43DMsQM(Uyt{t}0sm)C`zoT!G45eQT5UTKhlQFjNkoUMaI*LYrWzP8T!h z&kfa!^(*~DxnEO723LMAuPu$inp|PsS(jp25%mu<Rg*Yo>oVUQy$b5a$#MG2@U~CE zpi&cW&IXY_-5^aoyleFfMsM%`?K0j5?5a-qqnEetzk&@#v2MdYSBK6dN`Ed%;NOT_ zDAZ?qxo{sdH<L&W0Gb!)PrPqOcOF0dyfz78##0eD->&RqX?5zt`T;~oSlGb{%msGA zm0oFdYPZnq5KBXZow~Q@lATw%tapsO#Otv&nx<QvHXi&@XrHY~t+)rUD3xUIA;0!f zd;@1;eEa<0TVIR0I=);gY5yXuTYt}8tD{AF_bFAvjb}jZ*UDFw(z9BXSEC9xB;l@a zeDuYwPE4S2F@$9+D;7MJd8l~b{^7Mfmdia<X8t=EaQMzEn2?(b&5{`OSy`+tH*qNU zmU?LoMnrAy3&Q~B;L)}!?Fahd&Ry6OUD@{P6}@Jx?G`t}%mkjktP!ij3vmkao4%aa z<J5k|KYIg}ICWYM5~SL0jQ--a_|H9VX6eBYJ?r*^wo2s~J^ewE;V(m`^V$Kgz8Up+ ze-?e`Oe<52t4m=n0K#VUaX!Z?$3q2>AuhNB1L;bSj|vcSL1*_IC|wmz0SP|mrB_+< z54hG=3Fr*nf97NWR)~<`)%N?<NBVf%-kle=cRsNIszzn?AsWKHT-X0A-@CssSDs|Z zcGvr9!uc;0`0k&|*wiQP&!VyshPg^Itz?B-B;ELj=<^-VEC<$g@A)ZE&Lt<hBnHi6 zK!3PikkRb69A0?1!FA!%LjnU1iF@d@dP4Kc@%U3N@&kUC5wfom=o7KVyz9xxVf_>u z7N_}j1<$#Hm^YT5ODl=WvyAw#_|$$ppAV#rc$BHbCnR_U!}h!MGM5R^cA@geYeA62 zul6A1yODcSKO57Bx^s`C%tiwh|Il+yz!DM#c@GRm+7n!q-S`a_Il9BX?!gx(_r*r6 zfZ2c(elxS9S?Z<xUYY<nRK3oLUZxYr%?tZz+<J$ECMh$WLIlP!n4FZ4KBCXil-hJA zm<MvpwXQT~IndUQay9!(zQv80Xx^*WO|ix#TGx@ZcwtUGZ1a-vz|#CKmyfD>Z{F7Z z-5U5UZ@yBi9yA!||1rfAQ2J|ql(8gT-%1u6UHWKbG5KSwq|x_E_K+x(c|j33y&OnL zBEV$$(Gp7W8J2`weq2BH92l8a?D(1=VH5K{in9LUZ+P4@Hn1p0p<tq8HZ_D2*jFq; z_zk6N0PBGCvG1N+uigy=CpKan0gzbu#G4%8JrW7|DuVOv^;j~ahW%lK=F2<<hV*&S zrvnEPfXfMTl*uxiU)jCi?O=N|TcV|i#gFxG%6PREt&O5Ak-}=%n<;N3zHQ6kre;9Z z!oZ;u7#xt1#e^aGT25;7obUnOc$?{;c9AuZnW4a`I5In{@(?rimLTLJK#oIz0Zxb% zS&8lz_b`?sWph99XZ5-0<2^;`8U7w9rzqzgY4$Sx^muhwNf4FK-9^rcHAzNu&`mJ! zGHfpHXRRCNZrY$I?tY8gg}ghgsYEhQxlBFA3q;oXyf|{F3laRO{<99?PK;!g>-?&6 zd^N9c`c##Gjih5$UOk^Yd{M@B6MDC;zvz3JWD$TVy8shl!JoQiX={l^ibqTn{uAkE zAz!ZJK{?AiTIsv6EI<I%34GJ?63fY)m{s20vKI_F+uQ>ZDO<6)sx}vMiueUU*po%} z+MNh`7+WyelAoflPXR&=2m*q*WMO6`7#{*z3L7V)cq#V!C<Xdr9Og!@Gr{TSkF1*z zLZYROlt2#ZHp{Rrx78OOTh}W~YdJn8*=rF}*OquxYb_V!z$cZsF~dvxeoTuS;Vh-Y z))Kj-)=CGMT6`HH1s6{zUF4<lnp_a17>d}K!>t8Pd2uJ?0?ZW#H%sENCKixb26{L! z<tLMVag03z%A&Q{19TpC$+sE#C7d8p?JS!z#H*oHH~Aee%X=)tN#j9~wRId2Lh5P= z=>buBNstb<p8Q)h$MNb*-4sdkA5ht8;-N^yf;`9~Dy;%o4Ob%4dDU{tVh&qH`^T85 z+~l>=7qw;G)LNwqc(iG#S7;XHga(_ryg?WfU%hLuCsMGOe@A-=Q4jbQGU{tvzu71G zNS|0~+U&l$2gvVeKlg(OKm+x8(BNJsHgr!41$FU82jR#33KuI>7wGjV`>81p{3l3L zb%Vl<ut;+Iq0=LPWToG<$i%oPxSA&<L5${aw<M}(9B(nizo@`M2*tdrU&5IGMI)XW zm8UZl-nr*z4V?~pSK3?h(oeedV<bDu>T{{jDRYG3Xx7GM-m3i#mMfgCUZE-{IhXFf z4-b$XoH!Ad>C8G=b15le8q@oiLsP8gR}kVcO9zPh;Y81DnH;s$L7KpT95dmkwVHc8 zm;Y3rn%>m-Z0>4ts)~QsOX`N@11Ko7k+8r=p&U*NsU|fZcr!K&*{&*WJ|6=tH4|v8 zVP{+TsF>*7_`O%$vhOYQr`sigqnF_TVy3v^4fos?sVLpB3^UtWVkOvESFV4?(k;2~ z2Y;##Ob*t|>Mal}LP^NLLjL3Q;4ycr_JSaf5rwQM-a!E_9H$mJw19;wclI@PA|NgM zCR8qg@|yf`89vA9$?y=MT!$b=b;fI-sT~fZS?~aueYw3q<|IVJobUu0@n|IUBBZzX z64@5<Xto;Lwv~csm6k{-NaaGSkeQxDXx_!|(ZRBBz#OQ0wp}@#MB{6gk2ziOWu#>B zeP@EDA7h5c*it@>%gVR)acW)YS+2|O@;(lkf^#^%8unr7voPRSdweq1C|eqvn`7)f zf?-`A=4LxcJ||DR5>w`pJ3jCz{wW0KDor0p9Ei6TC^(3dP4z46sV&VJw|4t8)wNfs zFxowg-eb=rpvMrv1gXU$tuGzZ%9<opK|sd=miWvO8Q$WBfej1faax~&+EZ-YJ)FT3 zbRG*^h8F*-k@AVy2jTHas^RHUxvOLC9sIUCwBD<1sNyA|;}xv|CvIYyRf^!umic$! zt{?A!%<HbQR<dF&mpJ6X?5eH+oe3hAb_}`jZ09BGjlh$EfBaz;G`=g3UxUivJ1eQ; ze_hH+;c`YSVm$!mn@MQkiNAiwOig3v?HqNS58G9P2}?861R?IvTZT}tohOH2ShMip zcmx~8txj+iUy!~@N1?HRZi}#$^SIT7RW|v20K#2TKe?f4sLxkA+wmEtx+{In#D3;w z!MLisI?1o%I_h{dL20Y@Zr~K9eUj&zf|ZSt0-baMHi(>M4`mC(se>2|393_=vo=|L z@!k-*DM&eV)}Bm78zhu)18<oCXR$@<8QxV<zZ)T5Ge44;Gyz-%2!F*af$;?dz<zid zCAT{XF*NJT`HZ(eVsYYY0>R#Z?>M$-W;7vP2A_Xj*uE)ibUpO2@(w!4=0wYsw>X8V zO@znL<E8mUX=fkh?0k0JT6R9L)?s<F6n%3xo9cL5rfR@~eDvH1*i*z6<2?w9Do^j? z-eD$eMb)HMbvIp4(9fHaCijyOr^7q0N&GqmL?tq+m)_lh6rKWa1yGyYxt|5Ar`{%q zQR|NFNXkbNAQOA$p$@xMwHfA~M~}-a!{VwQLkP_lg7TSAUJCMsKDnFWIa`kE8WL5b z->f)Qs`fLW3L+kKT|3`+eonokfyYJh?Q<umXPi-LBBhN%S3Ps`jwE#cMr0UW6{`c@ zQqG;6@fF#rCJLD;T<Sxf`9->ZOs_EJH(W&;oE2%NuQBJoij}QNz8cAqbf6;}34-VK zzy;sO)(?ku{<+_V=|aT?sKXtBp%;KXN5}TbC};L?=u@rwx%akdBD;(>Zy}r}M?E<~ z>Y{K0`xmTGp{nFxPd_V$$Iy810>xmIdp=9so$bv4yWiyFcYRgn4-ywl-F|9u-+p|I z)!I%m*OzQY{IE6C`xE%Afk-fQ3ZE2+Thtekc7%wort}titFcY$%JP!t!aKvWW5UU& zuJ8fZ?~(r=6&9g0-#uNtvvS1l#(%H$$+l8h2nTyJ^;bo-)1o^0Xw;h_ICYu<oA`M5 zvq5nvvZ(k?@Z)wKA<eaW0SI{h(6~ElGd<6bn>2rgplcPD_HJYPlxjgrNcx=%v7c6@ zSFhiad$TXRbrh}xaSyq6B>g&`<n?r=6v+(MHTsW4U=zIBDuNm-)|#xh$i07F*_Lsp zlhya~L_DwN)PG_2wAVNPq`aAAr!wJJMRwJ64(0mvwAjneAT=+yY^VD?=A}T-9M|>! z*!^({F}wDFrEu(fpAu9>NhTz~;e3bCNO1z}+3aw!G?6@G;vC=Y9KRh&TQL$QhGtoY z72TNUys<a4mUHK&9qEM&bR$gkwy*2e5>Xii{jD7*ThrUa8!tcSrbzN5P2JE$rJ~(( zh!e^B75+Uzcj2R5KR=DYA3@+7GA8)iJz89dO%ZrF+S9>sY!)W9T!*&fpZ}zYp#^E@ zs)W>^TKUk%o|NVj7>?vWe3?`}K06ZMltIw=-AJo<>LNuUf1sWq%!G(}yqm4VlnF@G z&Hj4-3es^E1o&8ql8@N9lvD3Jikd#14>E(kbTrs#>2I=g8~mHbvT%Fr_*R(}T44Ju zrv<-|z7{_XA=<03VDmkxore_J3+bZu@`8YcKNznv4nEQTC*u8}K<YW?ODB%k**Ky1 zy>Forc#(xn!Z##Y^Ah1m0KgNHZ9!SSz0MnpgsQl|jwh{u9zYibAWEJ{&$av{;rMyN z`7x`D?w{@E39z>j5p(}JoBL(DuDf79<2=0NvE&kdNNRyKX_>(PW(#7cwOd~Gr*fs4 z6eiMNsl{(WvX(Y~oBgy`$oAq#5pdHtOme8nzYPd^n>Ds{P|i55g&i;W0ZW!7f`A^T zek5SZ<||AR4O?R0d-uzZG#|tF=f)fA*{a<Au?E{=wEk4W@rhm8$ew0L3xio?-KZ3~ z3P%2X<sIoDWj44IV>x=y^DI&P?6lzMj(rc=<Jkt=E0-egd+bb{WE6*xDa=jZG>6^1 z(8+f8jT&W&LkwVdkmVeUMh?^KE)^^QjQ*bKVGC5zyTW0t3Ki$h)N@YPq#dAwuN&|> znXso{h+VSycjWk1BIl37iI%h^*Az-pDgua1VdG002f~ux(*$`5Q*!bRv`wu`a%5fQ zX|w7si3)MafqRaxjO6w8et{9n$s>VT1cyXTr%8t-65$zG93hHRwk8~LG}H~`;7dO` z)_gx&?EaqX>g;j}oaOq9Broet5C))S&(D_FxgUFr-QV^g%m}=ZHX~4T=P>>B9u6{C zFbL>*jbHiOF`&vMb{q#LVv7?12{Ki(J7%DO0@lo`u{KE6GDx%u6%2t_oZxwah~hz$ zoGj*0nAcixJn6xANil0@mBO0pE8r7BeKk%$LDivepQdi~iJ&yx;pb=#gBy685JFx2 zas+(QFNNzbfJXI;OKWErn17!jMbZ5~x@q&}gC^e~{DNrW5cJISYF3GO>|yN*kxkU0 zQnfzK^KAbpzTk|4aE83-p0k4}be4Wd8n!ef^MJ?V1jPmY$jv3Uhu2F}?f(lzjBLDw z+>ltU$6Pp}1CzK-@fRCNQYH*S=kZihp5I%>j8OD$^|k5QXhCo~?EKqBnM0S4(bI3B z>4O%CQ^fu;F4<FO2CEy3%7LGy|BxgR+X=LzXI}b<Q1G&P5;$yBJl?oS#K1Y>nM}!{ ziLc`ejQ{+tK;OHX0g#cJd&-T$zi77CdH>6)^GjL*VUdPP*_PHcN7jv2xVgTmz_-0y z5g#rEAF+S*6Nv7nwFXKdZwpwE@WLW^=qRl2g9i!$5J!<L80ekv8*Z5Xb0YopZODxS zE=~7hH}~~yeum%y?I3-VKsA04ZmhpIbb%URXiHPs7az_mvjA7HYzoSBgCS1U>wzq~ zyOXU-a;7lTHTE|Yy06V~60O><-{Am8PH)WK2Pax0ZMD#ZnX*W&VS)6xH`sns5}5zK zn8CptUZx)Sx4Pz|p;W3Aph*SIC+W<1{8uERLNYOWmXUElTM!^2J8vo5ySR1J&SPm# zGyeL`?ikhnrJz8<KUv4Co)+?kRq0L1alQ{G>g|IUQ@+!52T3b^q*bS+`-w9pH8m%2 z`Zlt|a#z}89KQ*LyQBLAtQ*H!fz=$4(^t8qzlZOBR(n$%+?i=rq(B9k2G7>mUHO*) z=f~erGf1Ni`u203EbJe&-+Rw%eS?=)HX!lQF1IO()B`amgI_F(yH*aT#R>OkO?+sE ze!9?*F6M2ydz_xWZ2e-)o^;o^y8Zs-paZnsI>~N*J#vT%cD8IRvy9+Svh<Ji1A32e zJ!OeMzT%$&Q@Py5n>ey&<uUG3vaL5^M(FmTF$ZmewX6qDv$#@vA&qo$dEWyvrE2NA z?|#6(2LS^0t8iVvr+;Y;4cLQO>6^Tl7Gx=VR`3tdSMf6b>i&VtB2tbG(nMh|$)L~P zx!V?j485CzV{@?0uE49Em0mdo=HF*(6%>6_Xd%`mk^;Mibr?sq#o%tkrvvbt6s(#( zX+J2FIql8i#_RljV>iq#rKkn|v59wmUT{Nkbz1*>0g_)JWnq6HS^`86LCZ~#@h6cu z#Au1f!U(i7A2DKmFup&IzP=q-{VGV#rYO+D`TnnXF#4i&Z~tkT%3P&=ge+CX<lE9i z4|~6Z{$t78l^u)wn10avpgoyTGCTi45UiT_6p&6%*>jxkCb2v%1ux1O@dCTM%1+f6 z4Ftj0vVc3oT!1s%ud!mTCNU(MFo8y6|Lgzrog{bxeDX2_Ty@MK<z_6&z`?<g;*jZQ zf85$nmRBzRL*l-OxvJ_h+iPUpJ}lo<GZu!h2<1gAe6^#7SpY$R34f)GWx}xA<s|Uw zQzWwy;}h$~g^t(yHDd&4C15<a{thl%G!0bNbB-aR>iIFu8-JRYbmi~JB);bF@uJ0h z+L_#|$i`*2o4k3d(2vrx(_`BT0^A~p(+6R%#I5YJnvI;3{7_y%uJZp!^;8p5^~;VB zd@|V9`~^;Om%@%Dqoo}15tYhAwZ4J+drIn2esA8EmA~ET5P>VLyeEWaV8r`5PAVcF z8ovqj96kGXtt(%X{@$W$$Wt(+K>UlwwFrxsW@u8}IQyK74VUv&sCjF@Dvz*<Wq9S= z0~5D!ym2ZM@s1VP3iE5Tc2@9e`hh|guUrDJEM?b3X>BNqSoLk&zASQQK{Wg<N!85O zSqvOuzWuRqc|mD7h<z@p%Ks9FwfTQwBOx#>hRVxCWzoUIiq9(uM$H~CFl%ola3gx) zV&H4>U~@4VekVd)D~`|Zuu1i_DT1MB@#P-Y$MN<<Jm-6T*zSrmN;Ev)E`n(2*Ajm$ z9+HT#zhHQ7W%Jj8?br<m-g6@ZaWs|4zQWLWR@Mtv-dLjQ5GgHHC<$zP%j4TrQ1H_L z0x7!TW;>>P^)oLRnk~i>*kHuj^ELI+>~NpZSoZcIjbl4?VIc$WQmXlB!6f}<gm-)X zGjKhwIAMUzfFq;m!;;@I_(Brtf`>3Mfu`i%VZIZ_ojsj!Nt1SP$^_F%XqO>UW9T6v z0MW)V=W~dvP{GL}AZwXm``Uy=n17nood|Ys@0oONi+b>g<v2TonSNgHDCV&6yl}OK z+6teZmp}j8Bc=ZoK8RFmz^7ff^F9vu@@(QvRcW5x8x)YTX@6U@9j#i%#;1IkkWIpP zD6i#c-5xshGSwu1M>ytJGQuX~PHEcrTyePBm?e`L_KyTIblf0*l2$(;xNQdZbQ)fM zn-foSLl~s`DgZH555SL*&egq{aK-p>@g`ZQP6Q~R5dO4S%(z^-{`I|**4JmL&nA>K z-tI`NSc~aShIz^Zms5pBedDTpznFG}hy|m5TguIZB>Z>CQvGwpVCh%Gwy*p5vCWWk z2jYf2j>#6OC2ae9qimxTd90-tdSFq_Kjn)Z^4@Jl^6@-$i>Pq5$47r$=cjN_WRuR5 zCj#naJ0`0al=LnYtVLw8ePz35lac)^Z|>gB3*Zyx<AJmkxuCv}=fx>}pU#;#68e$V z;w=wK|0<hdrFZxTuXPlIOq;XW%i{n1!}bqp{3-s;X%I-d@aMsZ7_F9?`qD&YLsrB? zfYfu`)rl7C-+J<%SKD-`v=FlXZZ3G5{l@HDkE4hrVJibyo`Z-luYU{lYb*>tvjc-< zlo}Ft!+ulr)8%I5u3I})7&^`;WR>Z?s}D%ZqKByonMwGaU7KtCnXh9wlGCIjv1WI~ znQBk^(OPDqNzy)5O8nzPtQkp^4(fQTup%~0h<Rst{QC3F+)Mg@syzZ_jYI)Ew9NVw zf#34PA6LY#4)BmeOMj-Q5@EK4b^~tRvv>djD@*H9ro3V|J+o&f1ca}%qkRoe{<&{J z4|_G0#xX<`2MDhkYBdm-0oJn?fCE*j`HG;<DkGZ#GiI&ADLB>kb*ZG)-y8^jdfc%s za8^+Bv(G>k(_Qu4hOd5;b!Hi&W<|Mm_!_)bB9HF~n%b&;gB5LOl~Ze8vdB7*j$V{} zq7wNSOr6Ay7}%VM2G|$5fOMgs>`yPhFfY|ceH_Z%2z4)_ovYk-R$;&ZaU#{W3FMa4 zgO)Z8=9d=lV~*qOU%U3{^+((HkHS7pcOMu3Fpu592|Hj~n4o|#K&$KQTjc<B0or;x z#f@8vshpy|3F+xQlMiZAmJy(?q;v;;y>~>f?m1)*7<?+DT-#&rYgEpHK>x6;2L3TG zHr{QLwfv6>*}fwUu*fz@r#Sgl%f<Bz%4t}U9Rn18g%`b+<dR6GNpycx**qPG`nh=u zV9F#{mhuZpS0sNx43(eISI%Qjv!d!)cVy>GvEtAJ0_Fq_;G4t`xCLWSz#gELos>Yl z8@)SW@lv5{`#?RKT?n8q$<CEAXIuNamrdTpR=|KPz%Au-)d4oWMz}#4`(mq%jMd!> z%~Z-}hu2qR{!)RX@*Nt$$ABRu)lUj>*~Fx_jV5T!dmnrdQV)T%TVfkciR1VWt%A*O zSR}F}`f7&yg3hOCcX0vc+ZAZ4GfO-iKwb<tI-6~rm5Lxj-L1;{)KT;dyjfA^)4M~6 z4f9>-uP}_XEU|+As)D(PEDUst8%cWliYH33SO=+{Ub=O`HRj__!(s>`=27R$9n~eN zPj}A9z{MdIHdr~<K6^tN6vagqlDKMGp#zRruk4f6epo?7^3=_6^K{&kETO2${FnNw z@0%3-qS{s?V5k4Z_Aee{DZ}E(BTdXZeJfJR1cdN9Zvkz!Q*;6GJ5Cxd1Z-BNn(HbL z+$Jn<sHcvmk&jyi--iw@rS9U$7&+YXbXCY%?je?q5i=AZSv<9A8Yfvdw0LFz)x|HR z?U<7)E0!UhAj6_fz;+t4&EU4w+wNCLH}KO>Ks|L2W$56m+sfx6`w9kb>tb!INY?Uj zN{Xe^w|Dcpt5x>EZt?e3M;7f_+}+}<9cyL*>k*GG))YBPRmqNw5MYsc((?aC`xYqg z6L<vy3wn~vYT<RBIu!Z4wO_Y8w?Mrm@xmXO7Q8?}ldd02d?)th^B#M)?E3-4A<f=g zP9S_ibjT=sU7gVbuhRQ5H2DEh(9`{vgSlZJ9}X-&NX@B<H478|*aV>}ZEUEcieUo) zgFpK?=Kd)_`YxWRl7+rvDw~!HuEIzli)?XH-(}|TzR@}kcC;(nZ$vJH+Mh|ON~J$5 zHb&m+M1$0%>84@1yZw{T*VQ1t6K7H;mgCzqjjB*R)}=p8ZRO+W7E)qH(*wA0J)obA zxjbGZ+$ov)V1JA?Gk~>oYC7lmFXe=7OJzQ)#uGTROul9hfn^zSE4rZ=X?*YTOayZ{ zoJJ-*F6*swGgLaUEW!Pr3(oT?zk-8lW_}X_5Nkai#fk_fKiZF}N^Q5bnk313*Kt!Q z)q1-XZ7obc9a-_Dbeu^RRX(7cSvX4BA{CD5dWS@*=dRgR<-5xyS{P@V#96*R#;G^4 zRm+CK$sLA~*6v<M4N*kfA`;hChZRA?`i^8ZaE@flyd*^BoD4h7{E(T7ly<C&n<;~) zFyq+@5(K4<z|4b%Jpf$5D&;WAlqnOx07l^f{$LlD#EV@AzP&H(2y9=A=kfB77?wr- z7HJd121?Tvw)SR;a@Pg7JbpI*AX6kSZm*jM%XH5XxV*IM$MI2vZP3U8LIcWfuTCYm ze4AAN-_z2s?J3WN`#96ScfAZEebZN}sY2GCM*{4*#%GGE9K~(fJ#~-xwM<{)e42$% z{9(l!aGa{auai#Bqinr@NMNvV!yWmXTLHbu-~p&uv-tSiH``_OkMT^sTi^8d(qG_i z$a?835s5$yMc+?kh}G;-{+qZKl4P%Ih;E#C#Q{Z%Vl{jEhQQeSPI)_%Z##%g`k4}= z>V{wS72i~BGv6&VBz-{BCEZ#FcE(gBo`+ZS*Qz5LI4Fn&Mm>JcA88%_>K0Sn%JWr+ zOl6u`VAN`@5gku6mgNM3(+Ga{i$keO)>uRgm6??~+t110@?(S#jK##IQt=p6dT~*N z2kx)9yIZ&le09hh^@S$Iae01tT~ChqoZT2(-bg+|5VW%jB2UY<+z-h1MpZe6U<hMN zfyF+o*7JEp+l5=9Y1Sl+Sct2GewvZ*3$y!kEK*K1#bZ8wG`vN7=dqLlxZ<H)=9h<d z{a<n>(j~d?JebW*xWWTt++U$dI`9WAp>E+9r>y{aG$1Gf!<=l7n7;gM{=UWJ$<o)O z{WV%DaMH+UPg4qTPQJ)srt+9J5K;mkVo$7#1%@ffiplnvk1kRIj+zMGT1w<ozXgr} z-Nt*%4%mlwA5;@$Mr+s$r|~sgjT8<lOr+zj?kic&xA8B7CO`Qq=NX&UJ;^6+lCEF) zkYeh!rS*uZhqL6&>uR%Qca;sgq0aE=0)Q`V-weU1o%H=yn}kn%C~CL6FN4y*aq7Lk z$mjs|bl+SCA!t;vq!Pi+OvOm!GiB^O6To0UmdW&Y8GNo&A0?xvP-o88-;Xg82W;7a zwue!&SqGazb%v_t@JP(FXR;2MDqFaITj#iG!~N_>wl0t6i5ti*h1&efDVC{{7n_C; zi|iNp0<I%ZE)D8f!iioy26M3uQT?J7+3NBXjF%$W2(;*$(xhdM5`Tm@$W~O_LB{L! zp6Q;rkB@y?>8k6tJ<IJ^^Bx%eOloa1AFU}R2ke=%bAPosZ11}3yUL}kumsn7xL{Qb zc2M57bMdA7m$C@u;~tdWl&!j0C7J6(ddTtV@-5wpap3|f9}}n04|Z7s7iD#VTFeE- z4R$K*uyRg~t$}AoQk$mkYfli9KyD9@+c+rCm?g~E3vw=%h61fjarn9NbL1;>D*#OM zi8&EN(8@1%Ud?L8%U^T{nhGaaUTasK8TzpB-WL<GlfB#fJ3F!>G~Jz|%>Qxa=+o}G z1JlFf=ES78q0fgHsTz2$ZxPI(E6-PBh`!cbQcqb)-t_OCb!m0%sHFQcrfG+=75cih zT%=KtDMKfJaQ6wDaNgu-&_aq%2`XEGj_#CAQGP?0P1)1boKO9VK*Vi9`tCo#PTj*6 z^p6vbv8iRB^U4<Ezbs-|j%1m1r+c1bD{qaQ_t0ZIA>u5{nqvcHH3Sp=T$xT&*!|MI zXQ)A-m+?RXG1XH1n}-6(@BZ<N-~=GVeAw5NqNiwWyi-$VaA=;!%+iNoc+pIWG<okE zqmAHtFT+)-=PC&odldR`Sff13w&i)u)UEMdQ_KnM<Lrb<o@A(!G3Hy)$6rBG?6S_p z$|KFN3E2wP63eB@09oBenK{-7nD{-$eKxh-(<+v-2J0)T<$4>-QlY_(qaK_tWBGZt z0)@%%iuwfHccd)ifLNx+EH;f1ODWyk`_R7cW$UNSs~pB<JPkfSiNJz&8nI|A3~$8` zO<&B-FQa*um>k9#=q`l27UFG*F{grw0GMBX94J$R5?|{ni!Ti@(>#BwA^}UFPr4BX zVaiw~!G+93;eE&ErXJ#guhg--QsDEOKqeo^4e8KSVoE$-B}xSjb&W85!Oa@Ruj{J9 z1Z$NA!%Q^zn?W)U2I)cHw}{-j6sE4asigZ&s+{`9Oq<5+IQ_sJU0<nZ-tSdlfaUli zuMb(4xVY#InI7n^AW7}Xv;ON9*)|h@o2Ai1;%29sDvscY)Q>p&c7z8H2ylkhz!mAD za`EARZvQn^+QRj5@-owa>X&%~{tx%mc{4^jl?M+jO&aPn0vn~e`UN~8XD;4K#W8)# zNjv}4FG=z;Mm|(Fb+?Jcgvbv5H(IOomm=GCYfIY?GxY##8;UtOPtHIAk8#v&VmVNj z!NhXRz~Y6!fdEclg+gwP-8gkTUh|Fxc3z@&YPHh8M+^K4CbNxoQ9dPC!Pe>NUe+wr zlRjrG^OV=7=J88fgSXlRvdmvgjOMNs&WoG2PXuGnF_2!GZ_b@Qga5%S*o&3YxhyOD zRmz)9HK-4_{Ji%1z=emk*KT^~wFTBlnq&1WpF)>6oA3Pv@W@Xv-TRO)&S4O<c=EU8 z-Q{f*C>&Gp;J+ap>L205WUE$KyUd?*1rP^-J5jRrp+(sHdT#GNdu4{hjzv^p`m?_* zTVaIP4baFpDq}gFjs6k)I0>T6@4m-aaY>AqpQ8I<(K7$Fz9>}0xi=9&+K7+(nd3NW zjnuENoSX5c;t^6?U%$sZe*!~3J;KPoOlZRx=+*_dEhp;?4c-p7!6G<#B$(tijN{`G z!2FIHXAkqgUa`D0hFW%pU*g2&jIo;3|9*{yme627YO!?O#30u^*%<S<%n)ZLI~Qgk z-B%qI|0a~{{N@*_PFpLd#<LD87ltBa4elQ#ZTYm5@Dj!k)k$xYYJAhzB}-naw|)|G zw-EMvAoKb3rgZRyS>s#e6xQCr`&CRg4~##X5_=rNq%0S~ri=P7tg%>X^Io5bdWX&T z4r~vFo7D{@JJM2QLDph@Wtr<tJg+UU0*~zL?p!hNqq6V%-?lgQXhJw0EgtI|H1)sQ zIAzLa<s_qKb&yMqln{G>rH6kCW+IimREY3UXtg4IeJ&{BFWJHBod8vR)Ix||9yZP1 zAF3yIDLqk)*fV9atm6nc1e4BxbJz2eGH<|OS;+BKpJn5NM!hgoH1YsSOQok7+XE6_ z1k~|1Un4I~OjA{J!5^%p)ZJ_$%V?0>Z_8Xc2orqR0$UdqK5DAOa#>bI{b_I}jyaR< zoPkD<vUOgKg!mV!bc6E^$>(CN2|u!>Ua5vC>Ay(--l=!_AcA<o_^TDw9D9I{)UCk< zj?9|&r9+?V7wJ0_$m+BEAri|@l((lNJ+rKpgBR^w&H6G1`+@cI$2JoWW6YSukG(Nq zdo`#vMsdFkO3adFI{jS1od2PQ_Vy_jVpOR<?rykL$vw8T+mx?N7k4g8J=|!dcq!n& zI>fGr%jKKAiZF}yu;1QOf0inp#>3v>Gy5=SYA7txV40Y`_M|8nLmI8d)jU<arE5GM z0IqNvDkHt9VQpViU;hm0y&oJ_3HjGcP1m5YFqyXFO^J3`{>_izKBL{nXR`F8n|*cz zk_pR5U7{bWzD$2`La5coNT9zSxBgk$Tf&bJ%DU&^(_yc;tpoWCjrAWXOVJv%5o^+J zYE6Yxx01$9yC)@C7hJyj8u=;f`Wp0X$2~vK>)v6wH5AOLa9rkWiOHfwuhn4D>;PgB zhyVf2B$|GwYrlBtNqi~Vh~3z>UDDKlQ*#F9J=SyP?)s-Fos>ygGwjGqr7wV|S`>yg z;cT`9Uu-;|Re00L51-<ST1oD6zb(2RDzD-^%!}XNcqFshkn9^}uOWFk;>Wo9s4?{# zPa<?ey~s;B;(>ED(a<<Yhc!Ns+8?O&*-X0<!VHDx_Tx58F-2b%My)>_InZLyiv_+= zQ*6+jA3&RVU}YwE`*%cH;{5}nF}N;2c$?BkxMwYsNaXUeO0Z0E{Ao%`j*DEx_fxB( z>Zz4Jt3@;G>~m#08hHW{QmIJ(Sf-7rhHIkb5xtL&^8+4eG$)B{Hr!{AkKb2BMaKs* za8RkqOOm;mV<-rL7XmLEJkp{W0pm4qisbq}0>P*d>h3GaQl0<|C094H0=)15yP@?| z-I48zgDgpl5`itDYx<>U`6PzRcBbS8oht9R+89#F*=Trm+M}yzx%|qCYJ$G(;67Jr z&~?^FmuF-PW;f<W*;FF>WTRK5M!m<>E4c>}tIRwymUGefW}97^fkU{dM^SNy)+GSL zBJxrbW+*$K#BzO+9NA~*X*J2an=Za?P@^BkWu<IKvt(Z*T3OEqdgckAzQ+6G@&j1f zm*>90MtMR`uD(xX{JngJi@I)NV{3^Ln>NS3UHp|}R@u?S_Qt*QOLZb)RXXXjY|@5> zEzfzrgguyhi~FS<FI&NkhBM24XW`aqdEFDjTUG-h?gm!Iqtt_BD^AN{pQ8-^qKMbd z<-}#E<9ZvpSWllfI`B;KlC?I>^WJp&`JhLtI;l=g%2n!7K=nhvi+S&{57Ad|p0g<v zyPo%&(HJho)M$4@WJ<a%Swd>6;t`sj_7H2C;@H{b@d5s?;&#`96?U4f4&I0S9QFqW z4YIX$j#!?LVgjqS+y<2al<$GhpV;h}2@k4YfmCR!lxeel>cz$H{@FVDOdf3yF|JY) zWNY2+Q(4ccT6VL?t%bDD+eFxNub4+4r_~ZkecznmC8jBFpTo(y16Qy53)Lz9xfzr~ z&~R4OxgL9M%_*!4OIzdf43RQzJ+#NosUKRbI!5Kc#|7iWn^Xb|zD=O*j=<Z6zgYun zXJaweQqQJw2z>7WK`WyqV}c;2TmB17L{~3gxn*JZ6$PZaJs7ko&Hv`kCplW<Q7K1M zhG)>U5AQ@X(Ic_7t`!{vh}cbG#i-(|{C{5UROUq{%-t(}ZkPAUDyjj#u#bwyY<)$V zC-Z5Hr`^)|_xKT(RtgSUHGtV+6g>wc<4Z3p!=DbkiE|6G?ucc-HSONsEbE4b^Z^Kh z7~<O7pPjCjJ%Fso6^O^jKWoRRln5xh@uK~A^}VwXB%}Vy_SuI-T09A;4=|o`-c%mG zLI3N>WyO28i0y5|jrEqlsr=4PAva}X)~=$X!{Y9zWd-Hf=&4!Zo;bXr>3JYHVx;7u zHwI(wj~yAXey_Ah#nj}LLblDKt~=vXRX<1utILvg+?elQ(Plf@V)YLR+_8C+#qaRA zWpi)=tFz7Z;&ae*|Cj4-?auDItj5(??48{<)qD4*zUBzpNcHD$#P$t@cf~q}OGYI) z=$~n+5;=>>>CxBNcuJqT{+7!wkox5N=$P;i+dq*~Npt<zqmHAto_HEw#Vv_iVPS(8 zq04WMZ(yY5n&TPULL-JCw_|MqA=5jTcOLzG`EJKF9-$^W>~^E=cf_(;|5zU{2W#{7 zq&0~0dGcAE=IrR@WjBkv(S6qjyJJ&g^nhQ*V3#>LvGupHf6qmKGRc;_E)n5bcQ*c+ z%*a;zap+-c@iKt5!~kHnLzy8K3jz?cJLTB9$I+_}eg}}-LQM;lfTt0g6%cB!tR03o z&?8(tBVNOQ6hKt!k0c5x0R<RwCV&Ni#>m8c`7l~eN)tSrs#-r;ZCYG}{;>$Wj^_aa zXPU>s0GiF~nY=N0*i>5o1wz*bQ8|zk4tpi;%hDr4zkY<*J@RocBhZorv2<T6EIo}? z!$Yth)oYxZ;(vU#X?UZ?4A2bopOd*<o0z9_>bt4dn&(7jhAR`I-p!v3h<4pnZL?ac zru{k;p&Tp{pRleKm3+0o-Je2IL;WF-vr=WPc(uhl!97_xfDRy-kSqitHQ0zVD3e6s zlo3HI?Vo@R%FW+DiRC)?>`!3^Cpt&TJ>Coufu%~tFaa{aIFTK=u5XKE)4zalgyd4J z`Mnj|c}XGdke-WS18NrtF^g6gjIV%B0_M&!%Frc<LaXJe<PHaP09ZfE$*LL@x^jzb zrapTepxKXmmAV)pDB8SWf!k!!VSa0snpKZ$9U!G4JTpjXIT+3p@j^tX2qzpSSsj-d zcI+Ah#*@Knj}XQ(jx1n6ueo1@0A(HGA&4WU#0Wf#?Fgnve^zd1B#EZ_R_rW%eRb}% znHTB`2A|^-cV?iA5f4#_o4m}))FVkaH<n|Nh*UuH0rl%qe0f(Ds<2H|p6?#U_Z4ub zZUL$_4%sHR4=XcG_sQ}t1{_8>!r836Dl5a?IR}rO;lX9o1P~&C@Tk<mGA}|IcOk#g z`-m6lGa^|LYVNp80xk$NiUwSlU8oMf-(G5Rrk`Ya2eLB^x)RHT0D-}9JW~4~qW?|> z=Q(!eitd?5<6y8?j~Ia2?n1=mF<G8i<$X1{QBz^YjM{+Is*)#&@@hr>W8P{LM3O<= zOv9t=$ebM_9oV~U+;$dKZPeUrKc20|8zD$~Ei0f*A|*|qVn_-Epqlj+g1%Xvo_@UC zgy*yKA~1h17a}|*sOF2T6zP;amMKhGPY9fRiAg|=Ia-#A{C<MCBB`}V1xXgHSUk5n z{VHa~=$?BI@#q#yCLF{`UW{YQWY3J0d{?YOvTJ8Y8v40|srCOMt1ah%vK?8HPNl<C zz%7g!I?$rxVfzC~mvE;yecFn%t)>CpYNRJ(JQ6by7oF^&PM0prxyT@RFd=Gcf4rWp zI!zl;Vnz(s`SDH(JHFN`*N6nW8zMdebm#GCX9x^<VgHt7X?_eA4?TIZxUhb?GLV2& zPHe$>CLLw?AZ|eUPjx?(EmJH?RUe^IU4`>U<<d-Bp+(i7iELL)eq29~NSyH!j~!zB z4x8lrkIrG77V4TF^+^W+LL_xY=iZ>aI>ZFHux2JkNV^0%vixi5DdXXetKO*j&;V&U z)A9!1@V+lRRUAQ<3;d%$6cwadh@4l=yDJjF?1NmF&ImBTY?HN#{G%YI0_Jkws2<%d zq(_o;57SBhpB+eL79A1;<P8yf{QyC|OpHs(4xz?`PvFdYNBq#i*aMZNc{Df@OvwX< zPc1LX7)`L38#4R_*6hJn%ftvT!9|gY<e`<(=9uHv0w+{ho@AH=Av79o$8^#tDKVOb zP4>Mjqy*JneSa}2Td}YjqQL#jh#&4TTuvX*o>>y&3Jqmu72PnWo`S)aI}vw;0q{D| zql13*B4*@_o~JYb{DWn(2bM95&di9jEw|`I8p`B2!#3w5CEvt_rk%fX(aK4aA)o8( zQzK6oN5oBhDn|jAbXb+#;rCn#ax!Og)-0Qn)F#m~Dw1#4h~_paCaT_&PduyNS<9%> zZB->~aLBx;)#}?E5@|9^6a&R8&(@S!YyqXp57x`f>fyWQay=#Re=BjEp@5u*I2i-7 z1bj{eRC^`0j<1VyVxKZIvm8~LvwCnJ8~tR-l!i&$f&efX)qf*95TTx3S)&-Ul;C6a z&Z)B#!G0E}$hA3s{)s*!t|wIb+;4$2+LeOYcJEw7Ir1I;G5_Fbgmmlb+85K*N}=z~ zj^x5>-)oKtw{_0iFI{7eR8}hO8&vV`XvG-sRb)JaP+pNR^y{z)+)_Yl`1Vrxj(HhR z6}sp47gA&7gMb_&;kh0g6;1kOR3Fb@r!%HNE?H!uzE+^gQ^bwJZzmWn-L}XkX}OCC zv+4|C&$Qy^OswL0Re`|vq~sQN<ET%LxNr_^<(MZ|boKLidQ|%}a1Scw0P7JP5jb&b z2puLgwN0pUUTYN?v)0Hyt$19OU|P*bN~IFIUs;rhoJskIVFE=410uib6r*C<DM|X% zcK{`RvqQ%rSnvSu7H-HGlj4fg?Wq5%;%g20-I|t@S`JPTBJjTKu8uLmob8Y%p~4hA zT8DZ_Rz)Z|-AXVwE=KG6Ov0&j^tdb}T2PTpJ=1_je99|y_|s}NjlTpidga$YyVbES zgE_W1%x95~(a$ECH2f1i6IcE1fUc7$2M`3LZ5b9EtHhsF0MX*${CmZsg1sGcU^B8| zEk9pg_4!e7;qx2M6B#*Gx2|5$p2(3es<?x^Tp&*rEWXvM`&zM}H&uD(+SXHk_>ZiB z5Ch|T?CIWRkOG-w{97}+URC!_?s&HAeX`^*Uhj6nYiaM*0K#K9Qt%~75}cwa45GHg zAt@lJrg8(<ZI>`51mk?6E#U(h0q%waS;DMFO>T)t#=h(ne3~Rj@O_3)9p{>V;NkZ2 z<G)y&in-Ks^S|s8LcI6J9$2{=H@oCaq6X#=yG?hvMsq^$3Sg<cZDp6!g5zUSS^&(I z6rT!hz_;qUoWV!agS-!GMXM5jpj;%$HBc{yJQLR<9J)t0q&42SqpJwhGwZWR<^x}b z)PruVB)=o`R%=OgMP85f$lJFXA~ps*PDW&fQw|B^lG+cOV5d~aUg^rTb|?i1mY}rG zBr2a1J7z7ByQFiQ7c!=wFAn@t89|;jhwZ@XZ$2^!M@3IAEX%<vT?|5?5`0*dJMfqh zBgVa7DHsDipg!^G;p*oWcM5;cSrJY2<I`1Lx&_=g_jyTKE(zQhtRk#(m)BN6G|^vf zMEY!c@m%M;PcFw^lHc!b=JyeILZ0ner#=jv`z3$XlH%@q@C0F0d)Dj+qWJ<M1Te!y z^X}OrroqUJD3nFDK^V&JOB{&l0-_*-%dhsjNDN+RDCBRp7=XBNyc}|+mHeJ?qr)JK z#|JeQW?7)>z-@i4*G@dlMo}Vy7&R`j_U@`=*iA2Q)QSN*DKj=lBlh0vmAnhFCNn|h z$3Fy(hICtdt!z87ecx`fP4NAV=DUA6m}y4b9g6%<g2)yIrSwp15`-b{5JUk1<txI| zZ@?BNbrEzOz>EI2LTpjEz1HGlXEgoz{1+n8QkF7NeJIF2`G*05e+n!}K|6SBv->7| z4Lj>nXZpYc+vbUK*5n_*?D%a-^rcN~llZA>dg`H}SXn;0qr#C5bhfSv>&$<iSa+!_ zGG<xBLycR5z7||(Be}|qls7<pn*`hNCd>9}L0V4#wMJaf*E$~ui~#hvF?c^dE%s>2 z1{grCMjFPsmNBQWAt8?p(uI4&{4%v!H@vibV}!GavfmOOOood-yjcyt3_eB%XY$3G zTU|CqCW3}jjgb-$d{Mup-3*cEA3~4~(R_C87lSK<-NF^yYQ21<^#&)9LVoBMofp8p zX6=V&i?---2vUfuEZG9UJZ~u&>4It35LO_rDGOt$CKMaiK1i3`r`rwMntDOvIx>X} zQ+gvkcGh{_qb}*rB-r<}0Az%3Tg)kyv;PKCjy8M<3En~vy#uBN|Hk+$S~J?L6bxrl zNbW+m%kGBzIfx0N^hlxvuOy-c8tI7e?erClGb&I;nXF}pkP#kM;NeaK%`%ajHt2AT z>#q6;2ykw5DJxSzZF7lhS(%6J5kk#~X+nY^b_V_FExqi`1)<|A;rV<^Awoie4{FE2 zc5g%c>yh^3eWLx9+-kI3wIL&$FK;x-ar!`aC@Ifh>+G30J}xa=l9%G;D<1SDqz^2_ zv&=)ZH{U4JK)jwlhcs7PM6qQuO&TH`bCa3dLKE9S|Ms}H#0y1cxc)A3{R6m;fV)2# zTvp5+A^E7V_QIr2o{umU8F5d2H<hbzWMr(0Ubv&aCVDup8!h?xHuNQc9B#f%P)A81 zI(ij;XmUHj(<H6<UrOdNcNvbI=ZDr?rBJQ(UnFMhOGqx;Fd#Y~!c*L4%G{Q{Hm&n1 ztyF8N^l324lj1C(TIBal58D+9NZdGXLGZx<cH8T)V=71WVBBU`)W7CCJ3qPp0)PXn za^mvIH^$Jw9+B|v^l_$CDj12a6zR@)y`HGz-Hw=@q6&jTd>Fpm%EWN0__M=+wCafc zBXPSbp`W>?t=TvE8*KO@83}|6wuy3)w}OV;${sTHkIq!289NHwn@YNu%g<f<1<CdQ zD$X=?@v}NNG`X@Pzi6^h(i1H^wl6H|csk*Vh^(?o2P@L<dnhi{6XLFnhy%J7&8@fM zevWe;?{RI0at`}90f_3<c$s`Zv~yVULv3#U2o>gE`4I6OHsx9+&wLqir25M3%B?)? zBm>dHSK?piom3A?VdVPPp9tFAHqqI#dFjXgc}ov7R`M#GIx9+zOU~>k+|JdP>JRWl zi67W&c(e;gSKer5MJ{P38}=$YK|+B&DfVx6Obiy!#5;XgLl2A)!@oGDdN}409P@4* ze;8a}Qn;`I(n1BIYYdQeFE^VHx6Gzk&T{06KBA=Z!d|6}Q8QTD6NMmZ?@L@N%qioY zy=XivA<}xWb4WHp&~ekL?(@~Ul!gb4eB*up2ic!=RW$0gyz=0~H>(Y4G6a|`5oVWl z^*BEU)^hRo+XyH*#?tW8co)*A;@+wK>@DW1aq+6Q#|Gz~q)Wz~Bg<arH$gzo@L<21 zE5Tc9CGT#PaUQyHd<HldmAH14xLzOkaLBW@r7R~K*n_m#fW#9cAvyZAd-U2G^D(@v zSmn0ddGrTEaUK<-k#dJ7ce9MR<5ojQ&lT^w_FMz^dga>UFD<!3krmC84|KBwYm={j z63n$R;<M3dfL!z4lGfwzLLMX;c~Fevb&Rf7I=>}Uoij;J0b~9RN=X|bG(lZ}8=!`1 zyXnw1({X3miSwNj*JpeWc%E}-kK>rpWMv};TLdm8wy2BOG`$b`HGCIvV>UBD__LNB z@@m^lp~#Vv=d5zzPDv?tzLIgltmQ-~vaYd~VQAI;I~jI2M&Zj`s(ZkLofh|<{9L0J zMhCsy%BUY!e$hExA52z+9yjWL^pxE*h!k>sHu67;&cmOo|BvJ6F8AVcFRqz!?Y;ND z*S)w_*`s93E<zF2<&taf5VB<!l9{?jcCwRHR%KOWMD@+j?=Luy$9bI3Ip_0vy<g8K z3yhi3Z>l*;ZsWy^uf>cp?3})eFakQLim7+;B|^Mp<Ra=V!2Ab?x@LZM^O!#@Gml7> zR253Z;JlPsj0MS+Vu}F-!Paf<2j_BF@6-oaAOVsSS#rg(2UIA7F$}0JH_4O@_)|DA zQ}$bfEC0ETVj#w;yk`tr1}zj^|7ijb$edMq!R=cb<oN0pg2gcf8h;5BQ$&(LV=tD~ z!^)n*SV#ymP`=#k6K((6zhV0w>UZg2{v`8N<WP|r^RJAC?GuGx%gm?2bQ6zK2`fXO z>zd;W>b?(drjVctZ7-00F6+J~rem!PT_*4aj#Yo(;ZyGPf?+9wqSc}A$O72VDI$KT z8#7k;+&AF4X-K+VC&rg;B-rHoqaEFEMl357jvWtPE8gs8BuhGJEY2BkTsHQB1YQj} zue@hRH>vX4fBY5{g=G8xFx0<{!LLn&YnHUDGDGW@Ltk+XES?WlmyM4!F@=5!jG5V5 zeiM91z6`Ok(kzSb&W>Rt-QqWzP??4|q&*0Vxi~}JBL7>($0I|GlRpRI#jgu}6)(GJ z;fwCo{jiqy{9aB#2ptza%l^F5RRrIbbbVYR=AY0@$vt}j3lM{i|8`HOc`~g7XMjW0 zF1BP|2ltgW{sqVUW|`?5j&@DvwYCL1B1K~JG=>>dR7s2hR|U<Qmd%PcpS5b|);&2y z1N)4vu8XU1E}g6CyP~FZ_G#XZFw6|h55&BYUh40`bR=S`4>%R$<{J%0ZM)HYSyJcK z?=YI?Vamu!_7?j`4%ng>UF{aylKMiz=fm^Ck>JZw<@w6)fCO11f$zfdBs1d*YAXYE zM6UYk*04oGeQIKwqcLq`QE#G|=u&92(aguC(<My6Dgbto%7!YEZm$kqEGt<}=~d6@ z(01y6_bZkc$`YIVz;Leh&<^dfVL4tr-wcWS=bvn**z?`WN}ORyY3Iq`_{Xvr2RcE8 zK{f_!iyV_s7KUN+m0p&{Zw`z<GfAg-{SPd$PBECXof6yR`JBy<KM#-q4Rr*de$zf5 zVVOS!BbS<(-tRIU;+RV>q4xpi16oUJDhlVmuov^1Q4WM*18Ggw_re3%TxM^8y9EjL z#o6J7tJQaFdGV4t=Q0Bl$2kI-rXY@wJ9=D0rJV><@0o?y28$)O->!cAS!)%UsH~W& zteCeaqb^TK{CTu8fPlp&vu0?-{IW(TXj+DEye0A6=;s_nn<G7Q&!QXLvL$+mhk3e* z$>Tipp(XQCDe9{UbMW86_m-%Uq-91Hj1?jEjj_Us6}$5@G%;xL&I`UgAx{rHUwiil z*?x~Jih}GGXs(sy`U2LYQ}a=2%*b)WYKw5u76V}m?zQc6j@|-8@qgCwx<^^?9??CR zBSy=&*|%?jB|xM2&S&ToE$^1D-WV704w=SNFA~QkHqT$cU7{icx)ZfN2xDPhU;gwy zW9M%$YJg$puz38J+o#h~)M!JM9FyWdTGf&&dr#d3-bn#o&$G6C<BdnG9GJB4q20Ny zys#v1sNkbz#yiPNYy0PagiYP=RBV4@y;-;rQR&sQKil@-!~2hJVjiByT)MvdLQ(ER z{{YGAQMt7`s*iV*O^a8TZ2=!sNJtQ@8Jj#DdeKk`g@72Fvik9z;@5Bo0PttB^MJhb zmxh8)p#~OF_)LwTr|%v*zliyEG97YNBC$Uv>6+IWtK0Ab2B8!n-D~tY4fCBn=eyD& zlqI6hPw<-rT!bSk=!0&kdwbc|66A*s+Aw`k#Sm1owDt9Gp35ath&gHRusd_k{-9L! z;Xq<M*)qZ7HNEm=qOD2puUk)Um)G9B^9kcnrO$_Z$!Mi;*A@`5yj=a`n64EC)nWdr zfLaI8f4?7Y=b`wYNB#SK;<>Q<u|ENJP6=u`wQ88ct$KAGQOXQTVUxMCFu77r&&J{4 z)!+_+1N=a=uS{&S$)E&hy=`-Ol}BEZOP{SsC>`!Wa)45spN-YTIUrPSBGZ(e%-3)O zSn8w>1sLi@pQ;>zcE6&?dS22GUvmx14&vG2uVA=e<$}-o4(&yVzSk~y--Wp%wYfZt zlWac^H!slDy;3!m<q?IrA;}7a9=BO*QPUhL_OcCG11K3S2#{@4PLw>6fV6dKO+;** zA&O7UtH!Z+m6AlKL;drMnWo!6k}L1?acP&(yFH(J$>GPR&d`&en=|mKKf2%H|E*|m z^azE09ZiJ*XDKc;g$u}mqRTx-lUk+QnjF{eZ717@rirJh)k~y|{_~KkcqNlHTA_vR zHmz?|_-%S-FYX#{Xj$-=MyG!1s(Eq%{MnZ6*O3X3Ve0Rj6nZRYAY+iO;2$hJk})lz z3_L&GE!QoP88uM>ih_kIM6&>zO3D>5fJ?p7{X{QWYZ)LT*PkL@zyPkt8h1@Gq2@|s zO93TG8z47cV4&HUFPv-js*u)p<;?i{NBU40gd^fY1rq@D>am(@;48T0Vy8_~GDseY zNe?<|%Y_r5Kx@*ivodZupfFmKG@XGYSCgJ?)Sgq$niOLAL7fuPLD~e!KD7<JD(4(J zXE%^a3}bwi>JQs1Z@u!F)X=A}n$*W57|2mEWd4CPq&!@+)53py2P`2Q%^+JLEc?LL zMC4yrFCD;YCkaco>}nK}22EZcOJeZd7XbPOLS66tVNZE@d(s&WsDf(XKsazJLDK%g zb#K`H8?O;c_pUs{zCcLpU*!sB9j=@>15^+7W%57a*HgxVsTlH<%4+SU)IqL_meG`H z#g=5#9;#vrf6A6ngVg%)LTZv|mwj8{w+)Bt!mAe_qqOV770N*od-ciAJ$2=F+ohvl z={Td-6pJ;>8)!kYEqx4cWP%E&jm$2!l+Q&|M}*G#*SPB^S3-f8QjpiwvE-%N<KO|a zl!bDNtaUd3rrh;?q5ZT!-+zv={U8-0k--3f5TQ{iX>eGnW%7aNV?>U0Y?yTsaI7|L z(foSjO4=YDcCMteI;5}BMHESP%>Gv6SS7o<ySx6VZFr+jy-TZti*owqRv)70&aR~I zqn?ex_s@c!lo!iA^KBItO)WI(^6u&`e?HSgYRi^tNr&`;c9|-`IyJ+=uVI$ts4_>x z#~|j-9Zx<6VyWSACMui;5jdME{UW2GxQ^TvS|rmzdT@a$yEyf8yN-sIc_q03p!V}= zFO$?yR(^#o6~OIsXHHnQN&I$@|Jd-AKDTbm&nc4Lp6E9UeGMtC48kK)<_8L3-Bzx# z$Ug==)6^=#UTiX|d5e_NlE78__p$I)pOaBtc%!247h}Ke`9(cX$qtYky_A^&tG{*T zYz-X(7a;(w=1F8V;=(yQT}vZES(X8u2FFw$9p4ElrK959DUhFF_(c$P&2n03bJ&4S zwOn3X6`GaOFsxq`0ze&!V8K>WDJ~<EP}KyJZWv~A9_Hzl!QVFY;5K>@p1Jq#yN!wD zTn!b$E-W@EHNlhOko2`2she&;QtP4m_9xLZ(@^$&4u3-jLb#Fsn-i~l3JYf(OVvh= zP-zzTl{;V&Sw}o67~{ZZ+ZK1-NhF;;BrD+GaC<INN!Y25N|IUy;4&>j<-FbmNDW_d zAjQq^;<A|JLVBvXSJ}<$5|SVG(v30LT!2cGQd~7P=-Ia1v3586k1E%bKWL>^mcv#$ z+4AP^_2{+GuU=W!MkyOI7j=_Id0W~uudxnF%iTI<nJe{C`J!`J>lC=f(OfNKZ#TeP zzg3)i-(Vm~#jx1tDfP-ig<9n3cV*(mf>FTIxbt;zItOS{-;-8?N!q#GC{kmD1i&GH zn=YTI%<7IiD&lyp=@)HC|DQYRdLTt$2LN<-ta?Y;?~^&EpkVZ5RaQ%j(1~`j;dwIn zKG^L(cTAT56;i+UMPi=1qP2WD7+4G%6;iH8T2Ge>H^tfs>uvKnJQI5UScYBZ0bfdT zl0)VbkwYrSN}chGHsz0*b&^%n1ztEiEabAt!$4&LqdxC9NoTYSl3PiDHv-`NE^8%S zS>p1=E|bV0-gK*lH}t<tV$tT4LZHF4mD3t4)DG{u4*KNB_0nblbw>`&E%?olc)#!8 zF^ll+0mQZ!Bbj&bdmg@-6d}7NnL_oq<>|D#!RC1;&@z>Fn4^Ztdgvs$ye_b?yFZ_? zpz6(f^XACTFwfvEmcTt<;j&2K%n37N?fds`hdw)JuH>BAZBH~6s@SFbekoIq4+~!O z4K8>+z(=)K5CBaiXt&|h?$Rh&_LZ~(rV9B$^JRcraU)voy2M;&;5D8XROG&6+(MV! z0GCs}VeBlwK*3%&d*XPKy3%Zl%#2gxs;NfiEkQ4*)S(+L^XU%Zm(Q_u3gz>cJIcml zDq3fX3l;Z_ZXi4~U#QZPGFl9wwrBj)arKN=P0(`i(@bJg!8p(w`gCYEgKBuhAMhnj zujuyIq~Hl4`lEmm!uw3Is21NEI3las@+N8B#yMm_k~frbla0-L8mI|#Jol8vZfxV0 zs?y{7zpq(*RzVN`cx=@er`mFFUrM=bSMAQ><=1k3bYKZg)-mQaUbrms_}ly8(v#}X z!Fls~|CAFAe+RNaQn-QdrNhrIKQ2np7#BFLfvb+XqjqdXJWe7ajSs4rkb&AFcUibc z6u>sg$2eR>D`I=8ZtP{{vw?yY%%g_*Rm+v{@}F(l`)}v<G}sQ$AjEBYAy?OU-XGh| z7mjLNQ1$A?gvvkDt8eu4XE{6_R8=**D;O=S<eCb6&lUYa8XYNmvUcFSM@b~<H}$9c zNB8f2&EH==Tt%$`mp3Syf=2e;?Hn#5_a3ci|CuceFq)Z}5}n{kmkSLKpFUUY8Evi< z@BD%50wS?@`|Z1_hf56~+<);+J?y6}(wVuQWq#pb&qpq19$b!lYd-4vL1ES4Y<LxR zsCp#*#Fhma_D6_SBN`-o_umDzb>7`zW3P9ap$9ib1as!vqRjPT<QePqev~sYctwVB z#tMQ~w398>lP3jTvx<{ua&E3tKX)T4(Q;`xRd^!9QZ{;NySzW7I%&84?o9g%;Tcj! z%DlgIkR<Nki@=T|)RKx%d-C;CnqFjqfb>g(|J)=!$Eds7ok<#iZxiA|lD;6cFDCza zR84|^4g9u7g5Wy!1OkLAfWW(KaB}*`49<@mTz`70vlnH<J4LysAEl65bKUEI_93J< zVvQ;4_5EG%Gw)Z?<W^_e`-i1cB~*KMak_tLA`j#mSyNWF3pAGtq63iMg@js0sS4EA zlA4aBbBgVW6$gvYl5tGGT3RmlA;LkL7>%5s>0Sm6O}GXbvJjUGsS?8&d|PHtiG_y; z!-wnP1LevAX0J$KAPij~*KF`#Ca3;W>a`iA`xj-Cg9StD2SiPnW}@mLUeabG^pQX5 z^Cjy)uvUL2C!Mw=a@escr5y`>9%cwe8n?Yq#*Mc=>FxP;rqs&PHoesBKP4;hGjsPR zM@mFt;c8VfmQ%^R>sNEt&RSpaT1(PyN%BH(N(OKV-EjZuE5T?gz^D+lk)R$5k8)Ff z=sBD`nSHkjoUvdCEcbq17<gfZifW)f>*`3hR4Vz&-;;ss7;9bS>FsyaP|O@jE2Xus zQNxLP-$u2R>kv+39BFPXf{}&6^m!;s@7v$cx+4>hN2uQdI8%>b>^-H*3F@S@8vZ~u zMIFPh*U-giP*uiEjef&RapX53V2VdJR;BD^K}jk?w^xF*U5ZfYrPAh9$cJw!0FmL* z&!WbPPg$cWuYwifQ!1~^86L=(KUC}ujYXO=j;D5XL7J&wLy6fb#Aq3U=4kiPgR+8U zg`NUXW(pH9S&wc)_2f4tVSzbf!ajCPEKn!>IN`d6LY!5?Xtu?=0`oJVF$PS|VjP@7 zYNqa{&$IUTMDUr|rjh#ZKUhJG<WH=3w=PPL_cSFbw3vK3exR_(DD02^(5cQA-JeQT zRU%b51<;_+bIJn;Nh2D`$L8Q@`km}2CwqmGQ~Cf+AZ>#+N|E<Uw#C6dv;9HB;aWma z6CFTH`!H^Lo8I8h3?i$B>TrE5Rl?$ul6qA?BFxjM`)Q-H7i~#O`aEc~A-M;;$awnw zH{(E@NWGi6FwdJO(}<Da5#?d4(ZEL}WohGpieg`-`<=#>;~me(5Y;+eQ-3>tk0Sm| zGRf?{O5SBN6q;-p!0t39Tm#JDm${@xk!O<9RvC#s>9Xlj)S_cdh_nSSqCc%e7-Cx> zj5pQbQLL3#6sQ}|ouw|+PpnbyH^(rTdzu^b%s#ngo~rR^eI~P>(KIDOuSdjm%C|u1 zHA2L)T{4@#E4JjNjbKGRQ%Z-WL{A@meiN~dYF2|-^R1LmeW~D%aA<{#v@%Bw!&Ch2 zJXj<FlG&7|rtI^{cA1GZ%9D8>-M0@4drBKc8B>2wA=qp#7{8vvY|kjt&z}AaW8i*m zA2eql03!!nes+yrXt>C{G)I-ctlL~r;8*koljn(D&QG*QXHz?3diFY!XiX_xIxJbJ zPmW_bGx51*I?h4ELS9erMm)VU$rj&XC;dw2lZauQbyem98Mh~J=1@tmsJf_Slppcr zc2~trw(yAx0fu?PI@kDvyZVQ<V)#W!-Yiu;!U=CE_BjF>z~n&q%UC6m`w3hZzDi}A zqqb)9nW#S5H_$~_m7N4;S%fqFT}Q+mur{ny!OK9%Fnob`;kcVOp_V#)9X{9xkF9ws z-veJG)1f2)snm3d&p<3R<~=rsz*68ISbNKmGwtwMGB$QWtLNrt#Hm@Q%~)JJgqz{P zo|)3I>^`r<mo58m2DZg^&g^!24@_DFre_k(dTymu1lNvTPpp44OFf=OyyL38*=c#& zV4A{3&YetXn7b(WyhyX6(^mq1lbj6?T0pYG*%sOqtD1fUjPaT`Cgp?DDYfeuf{+_4 zWJ&Z`M<Cnw?VRTYwpaIW+%i@-R~+88`Rw~l(BI@o{8C4NG2-vY`NZ~8Z#}oZMyyp2 zBt<U;;q=?9F}dk&_*C-jw^z?Z1nlEKh&5yn)!#FT)ju_a2W&$i)FvC%8p6-EKY+?< zH<f6T!*QL7nPB7<UVQA#+!L*?>)mtxaBL*M9SfG)^L}jlNA}c8()B{7eYxX{8>XN5 zPm*01%l5B3kgVh(18!6CwbM}YY|_PlDbukGWj4BG!zQlN)DJ(f)S+aVu#IU^4jG^$ zPVSwZ%YTfsAe9;0G7F+h_2Fca?~_N$@-$HaaBpMsunp@aqR0$_^PzoXb`R*c3&Pg@ zRlFx>wfUGMeq13V(snJmRQwmLS=01M*n2AKHmlK*@ZZ^mo?S9SJz~C<3R#ZJje^q` zufBSU)ySM%eAT)1YR-r?felTjbW!Oy+Du+B1$Vzq3r);S5hPq%OmkFWVPuLlt<Uxz zfOI0c<y;-tW_0uzmZyt&H>p2jS3X#q_!PVF``f2#Ts#$*@QnCi?3$d&cwZnj$U2Sm z;ZL1c7Au|g>Uv|)>K!s1Xo3$@l*840?kezxNPumB7ZJ5O|LzIQ5&2@K2h4Z6&mQcz z3?E4D=Xt)Q_(4}LnpLp<HwG7RKleG$Bh7q2wV)+wrS6<__AB#boXJLR<ITnjMKvZd zC#@JUmE>V1SsT8;mKG5OsE-};(mPo>HHM*Ljz6%7*e3XsrF(ZfhONZBQybzS3vI9r zg=DwSKa`8%6R4C)$0#O(ctO45EcK?WiJ&IIcov*==@V)YnY+HW&*zSz`09*UwaU3R z^9K~rm-Ot?*Y5kK;snIG-ie$nr3?#qZwlWv^*imz8BM_s(|x3Z@?$Js_=z1c!^RRG zL}8b_7ewzQq<6tmYYpa|KPPvvD(e>KAX?9VLv;q)%;#^VHkFC2AS#~^DgWhgsdizN zUJ_tf6ksq7&=l@D#^f3XJe~j6>$qLt&7o5@XtbV^cEx^;19>8nm*(j82ican_obtX zbp<0B$)b-SnL&Li=>|Ktt=MlQE)gWWs6uD>=u?71(M>7{gd6Lb>`S9L<i!f4-4>{u z?=V?HEW9ggj}cDx{M4(USa*(L+X9U>*nVlwJgO0#;<&AMWBy`A_tM2eSDxl6x3@wj z---6?DGOhc$zC(R&*gnVWbguLN4fzv$J6g}mg6C-p~1=l5o|wSZ0?^&LU*xtbT0DE z>FBqJe`Kc2ff!GuZ%<QMC5*GspL=c|(fi^47?dFb5`1<b1>-~poCJ+7S?SYl2eKro za$GDWNrN-LBwK!KZw~kzA&-5jG{>6K)=J&2M@&VMrNsboT*6&kLa%9v!!tIHmkF|; z;o;N}T{z%mDI)dRQ2hy_E?RU>CuRn`iae|c?X1#c%`lv&W_&)IYaC79cXPX?XLOJW zoNl#E{OsjAv<Uf<gZzHsCH3-ze@};*Ve+Sw$`>j5^x}S|FQc|nHhhwYU9&5^{zwDx z4(QP6KHg#PULx1h=LFxHglP1^DMp<)a5?)~4`Q$IDhiv^Uip5uOIqO3@=o_TfsIM^ zLxs#2-RUm&4xCR?-F}u?m?Sdpx~Z|*-u-qHo|WpW;^@k(^gK*Dszl|-?(rAI+&I(e zx&tL?-&91|;{1(ENYUF(GEouA6w=X0DEaPg4CuH47C|2S{wk7tLiu$%2K!O<B|>44 zsMzK`QzOVUSmrlDy+jEII~6`N@$I4h>ah&}N_?Ao^_O|3*00aMQpm+!<K1`F^Dh5- zzRoolxv31_$WmZ}Mw>kU7k_;IMQOtF=I|=~t_A`$6MDaXRjzZ@jZ^=3$7Ii~uv}UT zhb8BqXNZf{{$>Nzyie|x|Ghs=TM&F>=>YZ<zIl^5QYJcb;8z+sSOv2rh#x7u75(>N zPR0w{s%PQ1d1#DuKkvq+UI^dH8e+=E)?8)dLzG%ah0yihifFv>%CZg-QQ8SP3!SEa zCk)Y@LrccRl1)FBAT>l{!!~nB^f=*<6XGiBx%6PKE~BX^rmGXL&94{L%(${Tr)s=A z*tnnlDzZp^ivGu+<cx4$ql=q`dRtG4VcLGjKi#JdPh@%ddTYs+DmC<ksAP#KjO%~< zYrhi^%hzyRWR15^1jw;;C?WHjV8Q--%mM~s8$bBTcL9<i7NEu8>FJe$4FEVho<!OJ zzE%o@y*z;Pq6U>vhCT&wz^sa6B?1sJ;Zk$j7{FpA&=o|y<LA;`D&iR~wQiDOt{P|s zYR({x^N$h9LSae=Zj+*j>{7$nO6&z8Sg6pM-T~g1kFWzfW_mm^$QHoc=L0n1I5;CS zYIwO}S^H6%03l5#Qt9(3>WBM8L+5g5=-*+!wYS^=eysXJ1>G_V=NWWfg(Dg*Xh1;0 zEwU6s(4u|Z%sw1B0lQx=#RZ`L>G;mOSyDU`!N8x4ZG(E|MjtyzZ|z@Ih)k`Ve{(C> zDZWuc?>3JbGl~Wnr{k|p%Jp$Y>{sJ@Gem&*^x_d-lVBLTB~%OO$bJyZsI*W@fd$<! z(EA;H<1|h8(9-6OKKL;Ef*vZCYZcFiIcp^|>Hue86?4m8Ja3#W+C(rTBjXPGT`+}! zn>~1VK2S0*!^r||QW^S&-8RRH(aHfG{@&tVPL7TBrU=0_EkOi051m_bg6|E?;B^;? zMb3MmgnlM1xiA6XcX2Qn5Sy);q=R=lqJz*tFc*NrT3g1}B|6rWB}h@z%afHZW@v3K z^j}c@^tWOHS19<P)@!H9CIbUMct?grGk+1H1H77gi(!$=oPg@qjkkE2XHZ<47PuXa z{?REac3tm3uX)zbqAIhF7nSHAIv}lKIBP2sOHh{CS$y$qLbY`%#7(L-z`*yh-zkMj zZcc$>hG=xNEDD{D%z$I5>uBRMp$QGS=t!)o{`2#_JmDX}t3ZRl+ec}>2bKln|0yA- z{9*2Eco0mMHkBmzg`P&Iz~Plu5BpGqZVdmN1PR{bhB_D!kL&F5BkUqOO@=&94UXnU z37;vZE{s;MVXBHdPQJZJ+N}@s>y&8;$W2OzYSH^EUD!7#QU)R+$g?tmR<IBNUv{7D zXUe{Oqbwg(>U0J2ZU%Ml?*Rm*b7iK{((}iGI}I<nS`dQYlZuNif>kY78)$+{tMPjy zhP>&)d_gLgboj(oCh1t-SG_jAH}v#t$vM%_xiF{q`>)4keKZZO@U@@Lw|Vwm%|Mx} z^V!TkHTnV?iufLct`XnpTh#V^d-?fZwqebYE~Gabr9T_zdBF$5=lW|Gz!CZYShz)< zF?&bN;UL4Su1gFykD%mhFW50`w?BcgMHc(=7|lonb@BPlS66Fa#t!|K7c}xu+rnf) zpYcADJ*qcJk7&(sj^Dmb=kAKXNPZDJTpP_e^&lB44AKjM0#GU-BBfNbRi+Sso`s81 zpgJvV*Yn(b@Q|-9seQ0?4Fxg41tNvG0NZ6-#NHdcN4PMiVOj59g&Tgp6@9`!aOtqn z`GQMzMhQE;ph^WdwS%hZAq%}?vM{o3J&zWUjnmtCiUN#ooMvROSDt?yJ5?7~^C(UO zi(GX}#Y<$VodZwb8?|wX|GU=~R@6_35h>KRuSh*dHWk!YvBPU%S+mA#sPqLqW(zm9 zfu=-3>y+~JMG9ImG0|5MLT>u*KpTdhy^9`*a=mmkJJX6FjBN@=i&#hRaWPZq6zT7B zt*Rr!m;gEjGP>2h&(J_QgEDT8&sSH!L#*IGI<wht9-*w_f`y|!hmX;#oNUOe!NGyT z+Kk|A-hvcC%RuUXeTb)*T7LTEyz|I#^rNk#Epp*gpYzS%$;J)9y<r6=9kUJ@+_*5W z%~cC6fwgwZS@%rP*YHKxrq#K&U^jTLxqcg-IqGylSb*`5?@J!Gmx&=Lurw?37$Ac( z8vOI=r(UzXNzlG90T=4Nm5yhbHgo>XplK+5v26VM!`O};V{28Zok@wjNFkBf!*?RC zmTaIGf@FYoInL0zPX2!RT%e#RzaQOog*%mDRerj&{(o1jFV{eAKU~Vh@AzggFVLy0 z3gJ`fd@>ld2I%}Am>EzPA6oHLKEyqcxiyNIbFw#*z0kPhxub4d1QpkKdPxGvKQf~X zkVUUP*hodz7i#rLJYv>N0dZKuLjQ&c1r|$RQ_a=!=kdaB9mDUb9MpVNLO#jdd5B`W zE}q8zRD^B{3q(A%qYz(<KC(kxp3HBlFl9a!gc?@mqY(`y3Wp`gcP7>$^aT~S%*qnS z?EY|MT@2g&YynVh8tBH*8OPxYbedD(`|qI9ctj_|6|O}(Cp0Qt?B0jrp##&WZWbR5 zaOXfkEmuqThJRM@HB%2lzHdEMAx#(QMT(-m|ETcIt4>;acuM5bWVsyld6g>SHh!}; z1TQQ2%Yt<0;w9BS)0-j<T2%Btrj%KJ8KB!Bi^(WS=(}i)`4ox;!<8Of4J4@WPPbGC zzmG}L!xp{%b|#nd%-HC=QM_p_MA%`?=AX%f-}=()<7Y6MurWQD=@*jR{aJRHpXj%1 zM*TJcvvPXp`*M34tN3RPgbKs8!A?)g6y-zCmQ?C^`5km#_fq<VvjpL{<xtJ9_%uBk zw<x+5wjiBpp}67u`hv$?TI!v1+#Q*TR`0*JAMh?xo<Dk1V12{jO1n?NK}Vwgoe_d0 zseaC$lcK(LElZZEBX%Kk2J+Yuk8X<7{n*dvcvZEV^WajF?;s&P$yRlEFTGQAhw$x= zrRQK9u)rJl<W4`W`1<e1X|-m>#wv(n2QbSk&GmPCY>g6s#?5%28atpeOPV8jgT&j? zozw29X#Y@F&1smysxGP`l1_psUNUFO8UTd?pn(S=pR{}|YuU0;lptXN$+=$>e62iB zt5>jsI|_x2Su?0Lu>r&i)2WBmdo<q%a+$=uGA8$)-E72dIljBd=EmZSe_Cn5^QsM+ z(mm@`jM!@(BAG4tAL=QG?vHAxdJ<DCDxyP{=WlSr(!uxAa88lUChkc{ej0iYM9b0& zLNMI&cRlP>6x2$hA2w5C>mq7TVJ;lJ<u=Hh&Yt%wyH-+cHXa-(Um4xx&CbGDt{Oin zW+*5##Tq<e+z)xFR91bZMxf{{QmWw3zNlJHc~ct0C$Z=M&n6)#$R^J5=jV{3o>a@p zIj33?IvW2w@mkr(V&wv5jCTKR6<=?O=rextV5kc}%FMl8SMMKUu4JM`i-{exhx0*8 zki(yb&lC!FdzzoXE~j+QCDRjd*m%(_)j-NY3O7WF6uX`bq0QdoBa)p<zI7%Sep?(8 zAr=kO^TKTW3%EvlptI0|#v=PavWP!1S?SG*GaWX_y7a^{`!7`kBQZ$cIr^+z;@E$w zg9^|`nWh?%I8hAI$$c4PaE}6eTkAyqnM*l{Kpa}S`*#pt6oKH^-`vx58C;ke9AISq z?s`s($jZ&^f_#VXz}{dgL|*yufaXdZAJ{4w|DtKdL`{a;og+FG5~52CywFwgz}+xl z8CW3fpaBdSPK?DDO>+8|6KX6L8w!K*qx-&WI+e3HiD@wg0fQnC)GH?u1D%<gJuDuj z^JRiNpDrq#ywaq%`DYkcIKBc^C2kjgA~YnjF|GbV3-SG4eph_C&@tnVl?6T@XjdKh zP82eTAd)MG-Dk(Z=olH^;j3k<8b>U7d~vGmDJEsMs^N&K%nGk2JLv{;j%3^+`+(tp z>~4|;k87QaE%WdZ0;aab{moMqi6yA6nb_H~VTGk_$v790@=8%?;0f&R!eIO5wOZ=A z1WlI`A}Cf6@v&!3`-s;dVptpCa~@&R>sTY1-V=y-$KwcmIy9xd4E!t);g~&z8W+@5 zcJALAfn$IH>Gg$)yAfFNYl1ccmlmr&5Sr{&>arD190<oHbq8~`2rPemHV8ulN1s+= z9_E^Lt*eNh*-i86*!i8b5aKv%5OI1QOSE`5`>odff>gn%X58{~tMC=q->oLMvFl}} z7d{(SsF-@5<Y2`ziQl*fRQrm^hv!S8ElmFQ^2du@%JQytXV5mvM;`W96qR3jFsO|j z)kpX9l5p^&$?+f_gUYh?%ddmX9fH1>7d3rwzig?Xi}+p1XjT5k^~Fe6Q?bXz)D)S5 zpoY<JAJ(YjizN}IA9IM}I^)`89>1$%KK#(QVv2ScL6zzR_3)8Wx`$VZbv7R-o0oWj ztq`jh*GI(8{eCstSr!CdHz0Zu&kwpRyN<eB79BsjEfz=r+jU)&uTJGMo_xA2eP2-b z9&Q>>?MnShx?atG{cF4}CB$&q_xy$#7<YySP$~k^A<1DJ*o0by!QTutEFX_%xr@oB z=l^==+v;6=mtkm)AJ@AsUMR!QJQq2rVzc}6zn=`;$o4G=1I!>k2SHZ}Qb~EOjde-L zs=Of-w-iC@3CHA?4^HvL2`&R*Bn?y~L8+FAQu7HCfl|ZI5oA1;Cw;wlCFHZ-sPIF7 z35tJn=dtJUdl)DJmD$8|k)f5nvd&Ji=8}17>lbAQ^fw5-yyn`Yx#iY_3q@!ZVlN#p z;Cz(ftR-IP4V-`WPFSltrOA)5;1^WA<$3ITwZ*K#GLK~o<N5Ja2u`CmCY46X4J45# z6FC5oIe^ZH)rh8E{%^|BT1xZ&I^G<yUn#0j9jp|qk1eIhHGmk1?>=hKGz^I~{1OJs z-nCM34Wo5)%bNzs`}&W!>L(wi$PHAz8*Kc3o)9Qv5Lki7kU#FygfRng9h7kX?ba)g zoTTFNBI#74Df+hgG&#hcP9IW({BfWPE>)AnFqp{?4Yg-oURo`T$sgi19ZQr!(4<*j z1*9~Xo<FgBxGemn`ki|b0>ur00nke&nJW7YCyy1MK#2D2<ZC&q(|;6=uvqqBpk};b zx|Y-kLm;LxdSB{h+(jQht}WCh4SlI-^p}m+tF~x7-FYCp@$fIbafAivjyI!7?2rHW zC(qYVB$qWk%5>u(s=Jgow*=qQ1z}zg<cshKB=sYbTB7nWphf)AlxPQiX8VgXT+KVz z__!ndfUxP~M)1VE)QYFn<0$^CQKkSwPU4l&0Lb=i-ZW<M=hXYvZ?qThZ+xMsuJrF) zCTRuxZdKp&(@W9!B?#}*z!)6-;YM5eMuAwZLEz)J9x`>l4Ke;H)tb-?AEip9h+pK0 zgXX}a+gFo*GC4}Jb%1CB8U)P^S%F01Z}+|99~UNI9_rT!1LlYmwPD@-YJvYKYD=-~ zZZy#FgXzqmqzIIn(U;R|$?V90pK|gCFCKZ@p2`!(c}urkO0Yl;k_I*>qgB9)`Ggma z+%=+gf4bJ=B6i_Xy9T&r{b)$Upv8Wx2)tr2A%9L=qn{TO1IN-V)Sxq$e*{d3(veYv zDsl7Z-ESf2z;Z!CnB4bouho89z7V3(Y4l=o6p~&(gU#lyrknT!5$Homh_{5!-v-S7 z(k4GtZ5=ECfaoW8$ss7?U8WVSuS_WUWZP>!dPEshYl9B4+Fc8!+)H>QF3}6eDgst1 zvh4b=p7X+XHz;r7PPMAz@(#~WO4#h*wmz&3UNK}Vkz*O6!e2Y?%<^`xn*JVde+ZZm z2OS@52={u6=6Y@S<%s0NDFaq1Jte$oFcM_@By1y9p%mA<*njgUgcCKOA1EnTL1$=A z^z<sn=k&|&;zc>RM3n|KO!fh_fk4N7)e@!iQj(>sArIow?bAz;?NpFg4#bPhq|wWZ z8Gt#&HM@Kz!H|mWjk&*<_G<gLugu&#=sz9}rQkyFr4$WBKOd%--W=zg7ApNSga4+K zL9}w1e@l-Nlz__T|5O<^T?C0BGsX3uD+Q}jA=&~1xtERf(;uBYl!r<&00U^v14`?I zuxb@n11g2<92j_xXKAI;+v1=)p?H#y$On;kSL37-ES0#!t?QM%TdsRcv4K=1;R`s< zgBVFSirRP!-kf?_^fc5QB5Ru5^rCZ4t%IPg)#8whFprfmKs?p(g{U3G%0Oc|Q}En3 z$xs<w590qWUE<#@06{zQngtWdP+J_sGL8prAdMqvmWmhzA1+>1xTqXBp#{~eth(1A z;{7SZ?_a24tE!p?Mba58^t_h`0~%MsBa3LM_7kkw7|w-W-sinS09kC^Ku!WOkx0?t zsrL$P6Qn%D6HCj93zd$goDai;g&DS#=xFzb^|2qdmD^3!xdbKS5&(0bj{e@#{yuwk z2GQ$&3=9U*HzI~w<@AX@ON5Zke$CRG(PQenvh@ZMNxr5GRlvje*EjF}X}@3FPS~I% z0GIWaPAR7U-Heq!c6K@<s9d1mhX7}8Px*-WOUHYTYFkEb9MZ13%M@Sh<M`xbs=7Ia zQ--69f}EO!Wkn=+YrI775O$T~>LJN5k5kt)sJndnuI@e>7u5J%(-==O^j*o?P#s*7 zZhlUJxmu?7NwzxFwBmal(d~T(LA8UT3j}H#MCL_x8qD4#L=@=dKt7l*_v{_#)kmiJ z9Ov8`PB?|A1w+K#`cx$hRM7QH`5x3KktMDjP8=nn?RGvH5V?W=GGQ&AS%{EodWrU} zWV258a{|yUf;IptAL}oJ^y`Ju=>?xuP=3c6-y)2k(~p2Cv_f<n`c-%Ob%1`2gVX-< zxZe%Z5tZUn5=Ket1N~Z)5cP(By%dPTIK@z6^!m*2W}CLg^!DfRtF@=MG&2bGjDPe8 zw9I~Lws=PAqsG&oP8wiO;x~Rj37}|X^eZExFg{UT;@W$X+S(qq+QSfqWdrSe2wgs= z?(ACBM_v1Wgr&7_2oU#o`l}!WT^Srec7icqeyOY@ciPQ<?O1abqP}rUmxu$PG?inD z#&b%u`ro0uhyC*1&|4(kxOcst(ei%@nh`p~-Op)B(WcT!&VYVREHLQ#ToL&#@@4d! zwT9uRSE1DuwT=GQYtaC@e^lN2!Jp_E&#y1F<FuEPr`DbWOMUwJ{f8Q-|IG`u<cQ}R zkp9!R{BO$DV?Ol1cQ<{<rAre^AumdG290}#Hb9bpDcYrwHx;)(N^c9K-g*I2nG(PO z%V(`)9MAYQi-gws?f+H-s^3Zz-=Fq_TYL4#@c@#nvCt=@(cf`XbuH?j#`UQ7bWE(9 zs!BdVo=O3rfZ+4~j>7&Ackk>_Uiin|(b;A+Z0*tQ=$9pfwa|EgM4SBBlQVi}ufpTg z8RmdW(a?aX;3#SukiqOe?dAJ>mrgPEd%@|gmjVcyR0{SHjh;$4BeowFzMPo5^NDXj zyR?7%eUI95vK~!;Nd4sG{b^0iAswV4d|pKj7-)1|oa})Fqfgxp;u*Qs!j91%#6&hp z`_>2+Povaxnl}!PS-eP@!Y21s5_erpbEO@$4!)uQ^RU%3=e^JO58C<Skw*t7Y`&Id zghUS2TPhp6fJ{MM(J}Mo*;qRF@5Ec|0rriTI&U2Qp8NWeaypQu8pYB0F5x%x7tcQ& zz@?_p&G~0hoY!1>Saa2aG^e&)dMWgrYSCQR+<+4<_4D~`O6#vuCBG_jY5Ke$g)6?S zckT?Gc#}ei;<wN`*qkmm&eMCX8NR(x=R<L^=vMx|m~*+L?Rj^I-|LbnwwJQn?LSuA zvbWQAc$LHEr!CH1OViOh+I}9Re6L40;@9r7mHZ=K<x0na-`nrnZ=Uk&S%m;!lBInF z+%<vUC+~;e2+*z{zyDDRIy{qfLfCZ9tWJDkmUswvTt?p?A(=^hs7%9dFFkxcqaUFw zf*xR$oZWqi{$;jDV3WtN^m9ncDE2eCnr9fYUbbbSafKJ{8PVTHDh;t55)_AF3C`2Q z=)&mcVbRQWD?^@aOt6V`Nc65amX#HZP<VxWTBh)t_i35pTo~!K@>n3-xXPQb>@v+M zFT{DJ&vE+}+C2j^7X*I?hF;Ky7tfU8PMsw#;J3%0PO1tVDqE32pF^z;<W*H{i0Ziq zHd>t4D%Mu)LaMfk?~n(R+T5ya2!Uvl1QrlHfx^510FaRbqyQ9H1PmZf0T6<h)KuC_ zL9j_V4>y(dC!mE*i%8AohLrCNA0fd{Du&Ye<r$VFS}I4fC2Z=PM_Q`J@)SHrp&6OW z-38$Pm>LqFK6+DvqcHH9w)&3Uh2+uih$x(m1FHot<=<LcwvD+6rBfPxR{!>iTYr-1 zEjD*~C*X^1Z8L~QDPR_>#DdR6;`h9VwmyutKl${M-b79WMjJxLoNezccY;9xJe`m9 z(A=qo21{cR0^D#|&;%3(>40^#ZqC%$yd(}iEq$a8=%9C^m$6<HMj2y%$IhGHaTyf- z^BMpS284$*&8k~AZGD}rFoPF5l(w0|I8oy=yGP&OC&CR*5v~dbhWo1mI=g8FD?YIk z)ng?WUj7?NZKR)&RNCzc`f*M0N(K~e;kF!u5UW{+0tySucvd0_9SLaMFEn6pZDPYu zy!*P6fPGk<ZJ<hwdx-nOqLBe*X7DOa9%8ZWO;MTm^`yv7IJzZEgKri>IOgZM0TGED zS1L)Y*2{8^9%={&``vt(L(P1&ij!B01JOx^L|Uf6_7JpOaiswWFe*5^k`>stSxq>_ zR%P6SAv=q4*F<kr;T4Y(LHTfR+UHW%XWqVa5WxpEI2Z6_O$hoZ9}O;Kw=6^flPwuV z*KTZWK7u5&#s_8Ux{2O*A3WY51{u!w)`Op&nr4)zT<xq2A<JR#&^5jTeukg}>q!fX zSpS`7{%YLhl~s`C6$6)#T^l%Fz)}{lWVLOCx8x4=wl|MnL^pC7B?&!2*QjTJe$Z#K zwd@WCxCXJWc5dfK)or-Jrop(!xVJYhp%GBFA~b>{L_4F8-zz}2V}^D8b4Vvct9bl> zlC9Oxd2jxm(G~^+7JLxDujE@GwVZ%U+}N((u{o{r#$JdZ5{D3!AofiVIT9x)^!AG^ zCsg03e8Zi?rC7d{U|s)UAQ&ZcIIGNZ!;-x6O>#2C9FlP`<;IC5PchO5WzhRRYHXut z0)5-ZUHfF7(Z{Hc+-^|1r-{C`sdqY9oNQL=F*#_<d9{P+li}ubMN+%_0O#DcbJ&-Y zZlSiM$0mz@PhUXpBNml3W%V(;CZkJP(8B>Y;dY9adPfTsOT9ROtJ*DAsDlI?glqES zM-KSuazmDD)XmqP=UShBK_-5j{K_7G=LTNG<^sA8JA9>mGmRM|O!3hAuk{|V(9dgd zyng4;??HQGDh_PE>9{6mz|-6Y3m<!qyTW<4&6wyPp$8)X4DMPeWQ8~LsQqP37~m}b zhZR50_V5t-75LE{hnuxR7h{rdW5d|2#}&`bONyBN^FSQQ8E3RhW?(0^m+@W_xUVct z@l2cd14{>VN5Y@z+`P4jJ6&&0{=7`#`wvmZnwrb~13ipif#g4H5><$4+QrK2fSBM} zvFyl!WS1QJlNVe@5HQY(>7?XPMm&S>NI?+uml?0J%W!v@fOWtkbiOZSivCvA;^!sF zKLE(9m;qbZW;RX<`<NM#5*R`l20@NB<;xXQkclxkk5UswFfEyfL6`^5N(1$!k|4D% zKPw#{$7c8_)1#^T--i*LJF97T$GyYqY}jKp20>isKB8V7W{{F9VZ%#a;xM5H_pzZV z!16lYAkrv4fB9aGa}~2T&fJKFXt-g817j>nu}y1Oli4b*3&PTZT4{ocW}<i=655nO z1Xdw3tW-8~YF?64QvfN55%US=^7Fr50LF`naZl?P3Z^935N%s`I0ao&*?{qjNbVNF z?#~VT6&~~=c)gj2j6E|^$pZrLu5iN=Nrij4e?<(?rjxO=r9^aM()o(=jAErqqJ|;K zq9PJ)zWP+~&o+lTXJ4rsgBOW6r&nGBHeE+2DgrO#d^i|aN4+fVRxbkD$B;}g>ox_& zyi)jBE%Zay$~;&t1GD|Aeax&KR-K8-sv>bRuFVZ5t>F(U^D(7xeY4~B%|$g=J{y)H zUj~Ma@EUg7^%svsq2+ld+YV@XyX{M9IZRU<PPCZ7sVBE{#a!q;AVBL4sZjP|=M@Hr zyi-dU;Lyq7^20x)e^!M~7FT2NMq~6%$oKf59eWR_YIVwU7>SPh$qSa1K6a5)qWTtx zfyOfFGdHvl>{KI0sh=l<!yY|Jl_dnzJ{~=YgZo&M0_*!O_3&3dnUnc;a9*-qO$#ab z#pDCdnggp&0|8&VAII7$)qVF83pi3HslyCZ+5~@vj;@Nk!WdZUA|kMRFd&+f)#H8* zr(kH1tib{UIaX@Dp&ar<N<7aXUgQc0bREfou>Ju1vmg|{nWoM3^T|Tovxk6$ObDkI zdhW5~D<D{&Xu#`n76p$=^<vNpcKLD3r32tjQ`@V-Z%eN)U_E(7L7G11iJL*E7w$p; zMrQ?d)S1Gg<8Sjr_)s?8+xn0{LZnOP4u(R_uOqLRlf?Hfq1)&03ts%LL?Gk*D2@fw z`4g?xiXYGd!6#VpJKGf?+Nz&@_Pq(h<4n(f-3h(*=-dzc-o>H!2&{2<a*~^lPl^{s zp>w3X7O(88jXpAp90(8%XIkEpivfBs8~CaLm9p8U!d_#S|Fz<1NER|H(P`9F<y1na zo%n?*V#R$PHyJYYd|g=Jc=%}pUMl~(&RpCVInsFPI;ev0W)oOb_5?_pVKosQg(W`8 z4Yfo&M|ff{P10~nhJH!i$q24D$EH+;ARzefVu2jB?Hp^awfy2+pHuS#)u(=j59o=I zx8+<fcpu4~!6z(_gNH0W>i*bX?8eg8rDCqjq7yoou<!vNuHxs5Z3ddNF!u=j0G1BO z$G6QghOm_DW(e&*!V;I?ycJiv5$pAL4H~J|`iS>!JdiiF@=<=O^d^Y=gTK!AfmpTt z(8`BjmAwAZAf61@t0XQqzZ{Hn;bbf?^S<A;5UOhvNGO7cq2ril=nR-6Xu;ApQCM$< zK9)GQ$QbO(!6R`JYZd^^+dvOV0QoI@`Cig4ZJ|Rn6b~>s$3pKnEql8lbecd${Bg0j zqjvC<E5GV)l^4C%Qpa~Czv6z#{-A$QHmBVJ9nV>P02#rbKGl5_=Sz5xFi<eqYzKfN z#(^`A>C0_cOWbdP%74diUjEyAd29ZSz|m!g8&G@@#s@9zbEbIoj+{d)se%6rpIiED z@d*l?H}nB;c0dMkYbH8j4T*<wug3)F$4RhI6)Ir_pScS`36N)o-ah3)C3Mih42Tf` zC1RmmU&D!RP+y-L7BpzS0=nEM(%kK??9|=nUw3QZH|WYj{BNS?@1qaq!VK+h*Vx`v zQ8Sc06i2ceZyTURZ1r>pW7_tay%ik@XOw97=+p36*j~U$wTGoK8Xn<orVwJj5$@>& z-Bm}M1}6Z^Q0HK@`6SeA5*inG7s$BFiYGCgW<n3&-ra`-wc=40)Eib*k85-GwvO?! zFd*>h*+FH%V)iwQr~HMANj&&_rci!o(U{MJu5~vqm~%kNL%5{W{FlVgQ%8X_Um(T` z=s;SCE-A74(Je>}HD(yP`_<=;FEtqfq)DVwHBy;ZpmV;dqmJm`4(R5$;b5z%=Nds@ z#QpZdJ@%j7jyg1~iU*t0CH?2E!a}sNQ1(*6Uv7xdZpZ8Y&C;)*cV&vP419K5@QYu3 zjJJbWkOm1I<p#C>b!T}9t-k?1PlKK>g+lSL7;2^jJ~QSx6WW|g52C{M!ok!VpEc0J z4jx-}!4O5G`;}lRESe)CV$oW*@zh$8X_-&9kGUh~{7Hn&x!!1rRe`K52@&6H+`d6l z-i0xhK(Bc-+bbCp^C5Ir(A&Ofqf+SBQ06<*T@m^$2na@5NcjF$#1icVUV)-B?_ZV7 zoaajY_4QWs*YM_{5Lbtk*(=_*ZHZUygo>aR!4bN@ugHB_;ZjR5&cdO8a^zfF<wZCN zUW?&pUUfRn$C=opFJp}41}}ERqr<6a&!J39TEcV<)HFCVkURBAJj*kYH@x{lRV3O^ z5<RhTzoVe=SuL7Bkr$zun&gPyAG($6ctheOlD<7rF42Ak2KZfZG)%}=>Jw&~1R#Q7 zZ8h`{g?nk6l4s(#47`5RsiX3PP~T5&5rwucjC+2QH$vco<TIpGc2jPBZOURts-H=w zzaKhWQ7XI{4q4FxurSfG`x6>y%qFy(JL^4HUUEdj>D#!sV(7BksN#(%<_ProKF&qh zs)m)n843uOLg0h=4=0j~li+*n9Nt1=-D(7=qEXvI*j9~;&N2is5*~p_3)f84qtW$B zpdXK*;il;J0yMOX)ylH+JUB1JFAl1BLzk;yVes~Ob+pDab05{@7_g+oI!Aid)y2*j z@!x_EgGI9=MV<Ri#TEjbXKmok$<99BuY7O)cQXag061qr2@lX6k?4s9HxsE6{4mU^ z7iO1H1J0~TIbE!=pR7soF9eUGyE{u6SneaN^1zO)YpQ4&td?Ykzd9S(BO7h;nZv3D zu)(6g1RHM>E-yJ%?<*!^j%CubWHr~6%Y_LP6My#`Xbr89Foqkt9k+~XplK3x))~2h zwWWVLOBl*(puIKFi!kR&7-R}|=L(D=lbx~m?5`BKBi4wVY8V+#rQb_+O(=SBTn`dO zt5~8X(2k6Iu9t)*abO<!AO>89q8F>5wqh$MqjMv(kCJfRUEuY8Uv-5`h`bx{sX$Nl zD2RJpTwG?AcwxN>dh!8!`8Ni&2Mxs00j017e-;5oAp0V^qNRlq)EG!#Mc-WOz)=u< zx>XMr1#?V-HOcNgU8adu>PR6_!X_6x1kmaY1(JER@T|P;+?{y-zta+p^R9|wS2qg+ zOA^B|N#1#bai4rsV9lw4^ayP%9T^QfKk3G&-T3%vC2XZ}X{!-h2D|Ydb~%IHO@SU7 z(|&mw<`Ue3a&HI6G%h`8!EU32|2&|}q>6CgzxfXR^?wwddpuMBAIHxwW@FfxJK1KK z`!ykIH_ZKhNysgPBuTn&Gt4bB5|Z4KTyjYzp<(Wqkc1*h5?yrn?dIqA-}(2P$K&(< zoX_j?dOcrjSA>E=Pfcu0s?1&Sdd5bro+0_*SK_Kuwhqw>ZmQK1Q#sSDx*CjKr63Y! zcpAyP(y#}WN2epSP_|`oAn3F!zY4T&;cd`?VBQy<6bj;Y4DCe~Ho>4Guuv3iO1qPB zuyaPVZ6F$z@URBEVWAg|64~}c)yWrpwQb&OpT?VsBtNwaHOVVN<P1tFW~6AhxzS%u zLg26+1X=!#4cSkm{IcdfIu)v{#3q>^)xwjGaZj&!6;-;46d>CRghBAe2W^napc4*l z{SQ$y4?6+@7|_%KY<5G+VSxY;jOu*yut!Iy6LP#q)e)WO(DBmY>hjfF;BJ-3v~&oQ z`}JwM*DLGKzXBk=_EKv)D1)#~?A}u|kIuf5`01+iH5qlZ`<P9y@zU<fE(?@sJ@0L1 zN$~SFrH5A)M_Ry!9g&Xr75!06?KY=ZJw!{?le!LAt`PnOD$WvpA-dy0u5_=%ZBe&= zwn=u~&D+Ge-oVkjm$&x@t~{yJ5!TKCt7}aG2vh_RC+=LYke;jBTxdKBsdc#7XQn2d z>w^lct6WS%UGnYk8fsxh3qkGgFU}9ZK)p_eJ+o&!4c=p5XjmAjrH2Uj19~1g!b0Ol z2TMjnNvJ2!QTNWFX6@US);mpi9wM^^|7EM(taKrUWFP^u0m@_o{8`H>Am1fMYR|T` z>RCK(>$k*zO(&X*hXTq;6sUSD7%aAONA#daPQ<XJ#SYq}Um_~IKnvw=Py=S3KAG7N zJBk_^MQQKk_#G#~Zj(S04C^>~R|Y-Mf$DHXJw^ga4s8)H3Wg#%Ioc=zA_e0Y5_cK0 zjd4=gUJV#}5@k8HXR}xw$`s#$t^7kxhuJ@-q7!K0Pl|3O{W$D%eU4SGS#tMabJ}2= zXtxmZZwDb@L}LSU`aK3M1{`ui_4!XmxXvh_p9}*Op`V2!#endmGqBuI;m?zB^b|a| zMNrqm{KL^vzO=#_)DH;3^C8>N!p<x4i2U*9S%0V-AO$=2m+MS+nl?ilMK7sv2#(G1 zMRTpz6{G1I-iI%%H;3%K7jk-jBC0zo?j$6*1wS^LC^mx@8<lfH#RbfW9ET}dp$=eC zcMD)UXqL#oGeVz7LUafGt$LcTp`J&hcI$L&Di@rp8M`Ppff)wN1VJP;6%5jCDz-B$ zB?x*_D4aA@L6wF1go@5rmLf|>)Q(is-sh(oa@`MH_DSvi=F_Yc-7mWn*pIsJ$8Yet z34iz()vr5q_vrJsF;u&i@HvN;2q$#t(H9XxqcYh&Q;IWS!>Ln$F^m_(6S~>|HM|rm z=L!u%PAe#MNmoXNqxR;b(m^0ZkjCEQ64cH`EpodU1%Q{OiX3nH<%RP5gEAdC4$Us} z)V;0qyamQ=P>}Bl;=elXk3yfHiQvKj><bk7MUV0eFu6On69!DcFx_t;=vT5%s06Dw z;tTiH&Q3)lYv>nl<L&CyF1#!i0ZjOib$A~1^Zw&cbo-up%^X4b#yNc5&U&pIoJ#r$ ztaal9-TRt@jc;pvjGr!_(LE~Q9Iq`wSzBoRJ3n>c^L=o$P`z$XyzX-uXO!<aDjK^A z1#L9$+h`Tvh*}ap3;+bx7e^;Hx)wKt$Q$s<^@fi#abh!sx>v#2H@@VNQfE~CXtrJ4 z8F1v$k9aVCrfGdP#ILxhWM_ZzN)Yc&IcTjrXMj(?y{26*mAF&9gO$hhVC^2*$F7wu z%G@;l%~#dCa^e!|pKckauG6)2K={Hdzg-)R<LhADYM3~hUpfg6hOrD*#XfHw41Djo zt5X=%E3q&yJ9>4}`QnpHP!sKV#0yhVw5rAwAlxJ$x+MYBe>B|Am3tg=Ze=F?N-V0w zE9Ad_CylhxOY83;&67gnu&||(R;O2yU7HZlh9+)R>eB_}r*FE!Z-km(v~{4ofDT+> zzeCfR0yC7#l~1K}VP`M9Xz)!-k*11qr^JGWPO5*U;0%sKtm23YJ3kqqNYoG6FR|Jk zCwAy{;=LO6@Ph^%yG9g3;&a#dH*t{Sqh0?=xU4qezQZOrQLny9T-=1Xy>DxHg&%vR ze5@P0_({tt{pn(i>?UMiT&2Hd)cG6M{(g5M&3QYXUR~5z^W2Z|D(HzIlm=Mcb*j3v zfOT|t6ysX&qdDjWiRJRZ`*Rr$v%h;_<d!2%-?CiL$I503w;!Y80mTzoRI(ZBRpX3s z^WW7&sD=Hgy#4R*={}d+^-KBj%UA8FQ*h47qTX)bo%_;Cpc}#`0cOCgoLOj4CQ}<$ zVE|(6SdF2&fl6CT-C#go?-w=AZH3NLb1J13xxcY5&<(i#?Wc1UWG6_pGi6$=kvy<2 zSf0+t@-iLZ7V>cGuzaHIU0^N5uvWGf=mF%6xmo!7BS6V#djqH0-M~EH>+xgd>K=XD zdqNBtzr-}&pyjYApubpf^iPGdoT))kqi<vC1B;0fevNDcP~$H7j<4>N1#UuOhxm9I zebf+nVt{mA81cowaHrLiC51S%6x0l6Amp}HNbQ5;A7U3f&u_!VfA6v>#+xUghR&3& zryyKJ<R26T<uUX0O_k-$TL$|98L83YlV$UtnL?F+q9ygZzXR{*`^;>+&H<zFnaf}I zU0h^tI+R+yt8b-=Y-AZX;faQy+SkMxH+L!4-1<QGt7u{BJ>)PISaNXUlukPc$MemE zSBk|JAH~9fB{%?DhwItMM^rW2T!v$7%;pWS#CuFFUX3921s>dvw|H1%q@nH+MfkAm zY(|-0jlE;HAzU>%%XrY$fonQ0I)UGwef`+Vd{sMrA8S46j`(ijDF}bhZ^cOc%=x;n zV!&9>U}I}P{;_2POj5tOPvM-_w*6pjA!;vBoB*cg#s>j_gsst_d8SeeeUNFf6a)bb zYRXKrkUOO|=XF{JY<v!-?Doz~)joz*MzkYtX0lf>K&t(6unCWgjUsFmw?<N|g(;&I zb+?t)NG$P{o=(4?v?GquhobHrl=~2wC!V|Br0Nwt^d=N*2{gSHx0svyfwvrss?-4n z6w(c#(tmC@)9##&p@iPL!$F9Hf|yl~2uU<BUGNY-SPbU{^~r!31Nd`cZ`wk0E*di` zGj-=lo)RRk97D25^&Jeb-!QnLu6}2HQj5Trto&3cMzz!xRczGRp2l)Iz6sbP{`Z4S z(vR@g%0k6Wg_l*gQ2-x<==wQd?9-SFqlvzc6z+_S_#_vNq~w;7X7FnHz!GQOk}VDd ziz=+8qChpl*y%HB^ks4G-bp+{2Om`7wLiS$_<(i1t(uBv#h;2p2=|&}taI(t_?`37 zbbFP(dqQ(<p_*%zv0$P1$i9cpc2RNxhw^@0Ud5bRKY5i@4v}zN!Wl}yGKfztwlaU} z@%~BvuF(0eR&z)b<oX<64UhUw0Se`aCM?G0ghnBH>Q69+CW6xtr;J^$>QhPE|F2(} zfo1jTuVXc^PC?msF>)E8C=**=J9_1Woz_rdyt*_MO>j_0yOu$593J7All#G;=^gNg zSgh-I^5Xmw$sL!v2M)IJRxEV`Pp0jwk0u;h>m`lu?){gQu6yBt%bA%aX#+b4Kbi93 za)nk*CTE-hY38HaeD;)Ot;U{K<g8xk<9;nCnaid-!IDh4a8wvbsEH%Kw3)*le4G`5 z9B+s;MqSNk@74y&C`KB1CApP!IWk4^3%zI^;Bx>DtEJ4y>W<S!noRdI>){@lsVmni zfmc3tCUh_BMK@2T8A5)~9eTit#x@rwKLzAD``a8+Wz)-F0!8Y(-`EBwwLE(YKDj%W z7|C^(l(W%Oy)PQ$0=FgxjY30EN+zShGInI?#;xMaDx#|Vk<@+vCU;~&d-c|BN~r1G z1H6O2v}|Sc<=dQ_N|?APjlwf?bhbNtj6Oi5ADF77``pvQ4U&AdA5V@i4`pseI2XTP za(HpsPPUeP9YUtXz`BLy7C;i!N`vaUQ$4w(mk75_(*2qaqtBD|&jiZh$#T-=)h6i{ z(qIOh#>hVe1}v^Aa>(Ci3{osdac>nl(K<bqB4#J7CE#-gUnaGHn$WAZ)>>MfM|dUl zu-(vC)4lK(gFK};i}S6Eq*@=IVOU?Kwf4LY!YIuyW>YLNH|zsZo{|_K;9cpcvfkWu zy|P7?NX?9V2s4^+?D~$s9Xdyvu~!$J5iuBh$VtK^?`Q;c5qA!FyCvVK2<OY7@=d@7 zhG65`K(@!*y-b9E<vtcS3M>75a0i7U0Vwr|L7Ii#@+_Xm)J_&b%;m{!wg(FtcS4r= zj>L;AQY)Lr4-UU+DY+pH35GVSHj64_nuP%Pve+&Ajbej2?<`WQ&Byj$B@r?N2%|K9 z)QVJlIc&#T3KriDznM62CifzYP6{z!i5IoA`se+s*`2?OeB0FkKy~x+^4Tsi6Zg9` zp=!z69~6Xn3?_Dm54$x$`WBpXDkkfm%8x=vfU9?~fs?K2CU#TF(yL?c1A%8Tyawmp z;rbzf{T^X<?cujA;62yn<aN$=UgbTInM<*;iO>CSo1cb*EZyF)KXz){FO6K^t$G66 zOrNSXu{_%99nxu7F3HZ-Gw~Mj=2Ctbgs?|<Ayi59P3vDW{6j*fajLhR`hZOa(@a%G z9(KG;=zK25Y^6km%o(9c`a?sc)x=uf_<U03oxbKJo>Ux6dQca5vb<_gBlwkF%emdZ zkyR3>0sbwgFWzbGK7^$f;**xT*LpAa7=%7N?u`mHg;@=XJnG`C)e7wal!j{YZYD1c zdX#V}SZMFp+#_DCZ}&mYOgy`tyB}_}o*DBQZ_&r`4E=>$Y(2`%baH*H^Mz`#zvcSB zR#AlV&?3j1r}hqiyoQ+^#WD-Qb`18a{Nf95TfI2>{2V9#9PngMTyu2Povx7sS8OF! z)}xU=bB*5j6>wQZCXsG-&pNC<=<x3-^V$daHixs%Wj@d0-*a{E9qv+$DX2Pc-p45i zVQpE2=fW<S;n;t7eHA0#aRZybUt9U^V`mXxR-C^UXxQ^Xu39_wR(>wd;)}4=RyhhF zYAb`gKX`^-iwb+G4ddSFZnHTb73-dK?ZwgDs>a{=vH3=6_15EA^a!kew*2CcRP*C$ zKWs5aYHeeqwOJj<R&!2e-UDH?c$>s7=kN86Ax$BQZS|KDA@&QbSV{HcB?Rl2V;AoA zsoU*)C3c|@qFmTNq<&0MHN4Rci3S0x*lm`?#YlZE=Ecohl^#t;BkHV!Og4;8{}+j$ zlnuEJhGj;QAC%7RN)0-PRzXSuLxG>UrSruZjP+H>0mcYU`1FrDnrxQJ&~aeG)1^ph zP6G#aYt2Eg#J)%fy|?#!(v3$JYI`}wxiwY*!^p#7_fk-~Fq`i=bzf{a-E(;lt4(`J zvFkFnnTF+%;a&GDln-oZ(3hp!r83XWUAYsC<ZX$+j{~nq-VFJ#bZjWUTM@AsFBZ80 z&y_3s0qMyrlOC=#t*(Gy-kY8F08}ekFpkc!n%c#ZPcJ`+obJ8*yXMLbZG;m9xZsz= ze%J{+hj{Ujv)`cC*rb<9rvkH9+qLrhE<zZdD7D3j&ip~b&7!-WuO###iUJGnnrQNq zqUKxxq6xib-3#y3L`;a3RBI`zKpD%M2D2Ftux!hVoD$JYTJGjOXLE!i3O(M;32N8+ zC#Ct(Ou13v>K{MIdB1jZIjLvN-K-iR=UxsAPt8jr<@r(z%m{UJow{^3rLDc?D(NyG z((qdUB}sdGt(f$={9!0LpF_^8QCvgG6ty!!BKv`*1{Dx!7KM=7QRgO7FLFD)hSKa> zX+?Dp^0<%k|FiK@;EaE@oH%jok+#7H5JQclaqqz;Ee5YYGV7CT{Xq{zL%OUutG$NV z>xW5KgWS!7v(2HvcINx+M##P>5<+I(IuFY>brqw?H6vSyr!{qY=gV{3GPv#gHVkOv zL{nCc;wSBDBEFSh%&Au3Ts4r6CvYyv!AT>+<uL=~N@+BN5$_L3Ng+^6cB~-zTSnDx zt#CXMtYE44<e(ah!{bt_n(E8`<LPTc00$#8<HDLtB_xv<d}9-YTkYV35(l0ElfIQq zmSa-@GVc!om?iO*x-u~7IjtP?ZzSln(GFEJnt9Fc;qGp1R<eLYYKPxT*N}Ts3DGJW zAAXR_8P0Uw&*FAewhDx{x_5yXuW;~q3$cU{6J8|mUiYPjVoB%_F)wIzMM~#EPco|# zvVAHTV$4a^Yb_3iI%ZDrGh+~0t#H(|!w%9bv(WjeFZ-PiwB2!(8RyI@bI7EPGXXN9 z225>($bfrs8)f~iW!dw2O`93}3Ccj_KA^^hNXjTgii|tnEbSeVeyuBoYWPodpwwgx zA_QEVFumb8<`%4;>8t)W$Y5!BKtvf%JeMwD$gp*C4uH8v&2VIf#r+;WOS_R-V|~82 zlke!v!;ZeI8h`g~<O&^%8XYG$6_c>gz$Q2ar6%WvFo6O*OC_F;O<s_GderFs8uVaK z?SAkB5w*TEqvT9E-QykRSF{;@R9Es@;iAH<gGJd_H?Nh{K1xCDnQVh^m&<kHhqVUc zP!VqTFAX=wASNHs>(rk>SWotliOIekoR!&BOX#@FUs5M~axH({S{gxh?Z3R0EXTo7 z3MX-QJy{0qwJJ~h%g$IU$DWcJ8T^p0(L?`y3#Tt--FT@%sN%VJQRL^nS#n~JTleRC z6oIbopRs%d`!Gd1YpZ;q<Ar?@#x?uIyg5z4srSFSAtz`Qa3VVt&ap&WEA%B=?&rfD zJ)}o-Q8%2FIrg2Nao@9@)a-1np;W#Yz<_41Ov~vy$_O!NbY#-yy4)o~rn`b2D@U(V zt?ZTuZwXu#huPnr^~#>bg@Bn1c~*_FOFbtpOog`zn!&@jGd_5sw8cG|;rZS0MWY#> z$Lu7KVcN$jMyId;pJrcr(Tcp_*>y%aU1ua&`a|+Z%;TME@OUrJtO*O-lb-h{EDqxB zXpz*4-E3=4=ECm-S*T}J<#f6BO4qv<=`XZBD)!9O&3yOG@z%-Q65Q3w-4%Y>aI_7+ zC-3Pk{Daj<kh3{+0(?L6gt~4g{5T`+R8!ii4&N<AI;&m!>MS5GSDOC-UOL-xCPALL zWiD~xCa-La86cA!rbl+$Wmwd5Y)Ct|u#P8y+cJ7H!`x`rp1f}k*Z<B`XXo0q!D%}y zngHi{3IVRk&(2TJNh5fz3N$On#;l2(Hx%wDO>Rrl$eFXaU6ROyV2Oq}_dR_`yL9)Z z48K%0IEJt3lCJMQIm;w6tjm05`OiC!mP`rYQdb$6&$$_J&@;2^HInHmYH(h5bLQ;c zrUY!+B#}33SW{;uTib4=1m7>mu`_@k{p;;`)aTL>sA3yLf-o=C1*Z(M{fH1??Eo)n z8fF@>=H%?5W@w4sduH#Ap_7j<^cDYtGNN`m`an$^$6GTe>~TQH@x2IKuv0DvxG5<7 zsj2#DthyQsAmXaGYT?f~uEKRp*91c>L)`Rf7Vok~=EPnm6i@DGUZrHVdst)@XG*Nz z#vPPxseH!tWjDTd#x_igEQ;L-nBOkI`jt9CDI92~0sF*Z>Wo!7tuw%&pD_e~oXNlM zmZ=>*7Se)2+$EyQj>!DZKXfVi<^=*arbAJQZb~^Q2D;0+EBX=!Fr=H)&h5lyn|zgj z$X#3u%s4*rH8U`?P3cLJarwg=SyCef*1LYO%y>)5f7LiSCF7o?bWziEv+$tB8mN$E zI*r7pEz!*^eJo%@Z_hcq4NJTK3K<jXU3@>*YF~O5ovuBUvGH(cLb-&c;L!(~rGw-N zm~<F_g~<>eIB4tovG6Ra*;$Dr!i~t<R59s;`>AnW@y5cMSs#gn&t^GylJ=1=5pv^X zYt^O=I_Oy)OD6je4F^NF5i;pQrID9O^Y*SLhf7~Ccmz;tU}mPTFVD^?S&L#pUODV% zVtNRPnI5I}`6CYu?UI>|Yv9h;`-uw!{D<)KFb3aV1!xLe1{h$zCR(vJDn4Ss?UC*< zLq2t4HL0+chS2;|`GI@Ln?{~3vU<4{QU~&>lRuKV6lsb{r};u#y*FB&qgk7zDr-N3 z#OO~QN)oLbNow$l?+zw(Av$-BNoRjhN`I;r^He&0&n2I{)$w-BsQxY^j=TH$&Q{aN zOr3KxDn_r26fIbh8T;|3c|k8%>7W^d2;uMe%q`&<fHCN{e&e59u~~^T)PIzE_)Lsp zGODj)sZx%5d%MLAsZU4t1RZF^agyw$uZVl`w*2M3y8%l=rjh9)|K8-n->+ZVC|E0Q zyZ!M4jU5DI(20Io#Ep5i02ilcsrMAxRzleyO%ji^t(?tyU@S_x^jNpqC3A^I>wc$h zikCYZoTAI=KG7sohR=krk33X~G6uZ5gJ*`*ToOMlaXTVmj7Q%YuQZPyS5?m<VlUhl zpETUV!U*cjPzB$O2!|2h7fDKoJypC?jLNX~${P!9u{oOIEV&f3(v8f*&-2O)ee-;C zlhMq=aO^{m2fgrf%i$ZZAG-T{h<@nmKu4r*T|TU}Uq$osd`<B8<W2A30r+(^bP3OD zYsf<{Z+E}3<iRZ(JbA<ZHVFrj!|YM!Y~DS&yaR#9ZYX@|-sSEEK=oXOo_>!!T)MXK zeEgwvx^>Ox{5EK&>o?o9Z?=!4&BS9K^lxPBI_BurZ#>Ab=F?^VE{}c>h!PLmIgXwO zL5}<fYMfxz4BlY&afu(0<$#Dpu4YLV(^Cd<obU!t6wleZ!yFX80Gv=9Vh9NXzwI`e zg-Tgl(!zDaLCvnftm?Zh+X7UMihVLm@1yF=vaVV*#kK$0;biW|wM&7a-M7Ed4t?V# zv2!<fhWzV|Sm?AGe61f&e|fy6Yc011${KQT{XYI0`Tbjb`F@+6Y4a-6E!O%S7W3Mr z?NPamGE%xpr*U}~95G?cnq6Ve779N~bJI(_JYl-IKr=d&9$T*^kz@Bh2-79{ap#pR zn_r+<+A+$G>m8mM;Z)_fKi3nZPrl7QBMh7!;GEizsJh6$p^|P(TJUXyx2nU>>!*J% zozx-)$UJkv9a_s{7}Z&ST#{a7VuOJ)M&{Zj|B9>+ze{E@i13GZ%J(&(0xo;_vU6k; z;VS=KF1s9L<CJCaM#}8^_HnsL6-42exP9(-%sTg)tBfR---jxtn|QuAj6Ghhw(;~R zwR`|xdF<DzpXaVb{>-iUc_!ja<tesfB-<MM>zq%*E#Vj;^>3L$PLHZQna9?Se*d+7 z(opR=)B1*}!mjma%s7Z1kc^xE#N&85;O>9A!!bE|FmnQ*6`AV}FtUeWiLS$)r$lGe z;Wu@@s!VFG7DiohGg09<AwkD^g_27b4iCoUw8krcW6c><ZK}8|fMjrV-+*oy8~_W8 z`%iPQ-L^R>qnNe0B{HDvXcaTNh6l)SS&)HTa|o3NM~I!naDvP7pxZ#u5LaT?zH{)! z2dWd}d<)1MvzXU+#26+)GsqP%%u$x<2l#?eeXk?|HxTw#Qm>6z>W;Jm#DPh0wj9hJ z*yJ-w5!)?JpiK$Vqq9FrQw`BS^%gtM2vt0fG6e$&>HgRy0|RLKHd9k!k^h+s@3{rO zW>C+X5M>yEA4ApP(>NEV#W6|2leks>{`1gwf*A+(J`FF17=`9?=|K9f_?5P}#zmV_ zhOJTxjNiS2GPHQ1Yp@5PwqBP22SG>#=98bpP{u$j$#OSh`NiDki3s+Q|3|GoHGvUu zxuqkx3=ZJLo5f3T$CrE{Osp#`)XM<nCtMhmV+DQ#QDUR*&B_BJtw>i8{<<@Vyl0r6 zmq|`0Zj<g;j=+EjNJDd}3%K0YRk?D^a6<W|n7~%0&T6`t)QEP!7LbbNrQ-+Xd7Kl_ z<Ln7r%uFAGokPN-6f2d!JwFCM-@0P+n0$XBaoer}8s?C2QiJOR9Wx819>ac{lmCEd zg@p$X{#SbLD~Kdd=7~Xfdcu(GUNPl=dr%@EumP4X1h37>%eA*SV*L+pq69=*32H(v zpu^U#OJ~n=51;Njh0l05HZ-9ayXv_Ms66eX0MwPIPN-O}3SEl@T#Y7TGod4DH^7I7 zxD*kDi4D2}1x2)a7-4h?*-AU=>rnU{hs>AECp04MY$dr`4OP(%(nG`HkrH>w7$7za zASu}#Hg%PCGQa$`6waih%2;2p6DJS!VO>Rma5)+HE@VO(359}c0&7biI{oq<HJVgq z>`rMaRM~Pu?969PSB%%%??uvfXcpNf1E>e-13PgSelff|Dl{+|uyYT<<IK7AyVC`O zc%|bTZh3q=#o#-q$zKL-qw=BryNKW&%Uej4?LpCv^yjL#A5{P59a+lNn5W+E(i}kJ z{U>+Hg_aE)J%X4UYEig`p79q|Rr6;Vsa~{^WCiW6tpM(E%WfzT<XR|<#oAC(!AGA` zkpG?rL6%NtpK0-M0hRTg4G3CAjX@ShO{tcT=ed{QAiHYn6o>);q>Ou4qIK4+BBROA zR7|qfSL4&fm($sXsJkQk#YkVLb1Fn=9?$QhnuU%Rap*}&e^3*^R)=JC>&s%PBk%`* z!^Z%Q0ZKkN^4^)QZSat-%6V}z>;PZMC^`9PO(<A?goJNmFga9ZV79Lh2-56#;~saV z@Kbid7)Uc{m{1reRAKr4Ew1xLEh+d2l(mxve0B0eJluKOv~J$3%Hj=#FP6Tln`&|t zvrxAbKsW4+us&w*l1$TRIedkql!Lpn<|-~6-~070GypO**$@Wb%iJWG+-CV~EDK7{ z8VV9z-d%r`v9yPcjKRWw7czherkD~J2lFLEKZ9-wK+QRMe*Iu`Q<V6bEDwJW<0f3v z0==w3Q=`qX8DDySlpjg-(K+}F7Sh{j7-q`ZEPf^fx)z%B0XG~^C$vz@9sDaKU5AyZ zT5gDK=3q+!bZGpEQSP;r5}uyOJDGrbGw!=T@Kb;pLQJSab-Ga9soDLB(k$kYX<LRd zrtF#fdiee-xIm=9P!*UU7F|RT7)LRji>Te)6oep-mn;WW-~vq7(VQPy(|cE0*wl$! zy>}QoTs|H8n;|gLB&gB@2~Iy!(y$v2*|!6esUOV3OfACPr}9-%?pnwE5JU4+PfgsF z(J8$<mbd6H<B-wT_yZ0m1tf+YDmST{`}_zTH=4o?)AERb2TMKFif{Tkt7}}hSDC)G ziXvMPa+~sBlTdIu0Lv)-*-^_@U)!<MNCAaZvX3N;k;}};h2$a+JIdbDYuOg_2I5w; zm3mZ-7V;xyK1d&HtG<z{L-U)Lq9@YqM-EiGH%Zm9?*L^8Z=-_C*duC*P&_OKZHk+w z%*2POqDIeYo|00Na)>949ynqc0Zv~fJm=?$wvn-60RJnD^+*y8&6Y;*47+$`;7=Y_ z9ZQBQgv*JG5Wph-B+xHSRMHw`m+yJKz}j{aE3C`_j3E1VxaTrNX!~=?gR0kBUF|LM zae4>F{L${u7N0)F&-M&bY=Toed!`#9L(V&@Jo>K<9kZKw!%np>o##nuVl|YWRrxZJ zhRTb%_3j9@H7V`nt#>IK^4YUNb-|-b-*BpaU@{1h|D@G|+s0+8QnXMHkVY%Yz>;c0 zs6U!4!j6wqqW84KD-Ud9@5AjVo;1%MVioe1c=~~>Fuc<NG1}4U15KCw@_6aqY*RoF z?uh=vaRY)R@3VIiHWlYm&1MRm+i3(kTDdd-0l$PJ1eks1fFX=WV(Bx~!ZyO&rJJ`e zs3UOmzn6Aw!j@*YdXpAb)US6OGX`o@fDV3(<asGvCHV8B4$&IstDyVPIc|kkPe>}? zx4#;e9^Wa#7`=hbMFvM%6GNXf%fxZTr;nx{o<WsnUFoP{#;fnv<Pt5|zOesrGrY@) z2<dm&TTmU{4ITG>y^oRrDTTyqla0=tj+|E9=I9(dz0~f{Hs@2^W9RE026<N%0mR2i zr@zS8i9wN3BqI^w3jMq5AErEy!*9x_51z!cA%B%Jk87xNFSfm&zM0re#fF<vEeP5; zB{|f&_o(N!qeg1@^~xs@8}_E3$>gZ0!;XRb`#zeZe-yqo$$Vr;B+MQ!wufAwE$f6V z#9p1Hp@ha)>AuScPToGDo40SZ`1jNe$UXAoyn7Eb1pVD2_cBf1EY<oy0fpc4n-RG( zg}J-WNB~F6iCb84bJa4iVyc{s5hE1H1nmAU&TLWGXkFn{S$rZ$Ng}901-~@#{_>HG zE;-gGLR$4R_<>E5cWhVisW0Z^nun#fm3enlpfZ5P%l{aPb-vdj3wjN4^vAX?sM4?g z*oGK2Z2%?aFgVq`WO`?kJmqi+3a;8&bur@+j&SpTtw0;tb&7FJ-{9pSvV2rku}B2~ zKr@tWEV<nR1uwG>foq;z)FjHL4PL`>+#D~`VGL$>F?L1C$RkSkIkSWuvvK4a)p<OO zIm*5X&b1UrKM&aC*)GUZm8f9{4z``&ML8GvIAw8NZ1yoo_#UoX$CCCgw}`aq4^uCA z`$p-m;bW9Jd;BOk0hL)McJOJDPXOQR^Vp#9H2L=2{JM@%E?M&1XE8~-3V92-xm%EG z>6MLxLg`t62@RTZeQRNx+Pho8jN|@LcDF9c>-T~_n)9=s7~LpTYA_K*qS=6m;PR2N zYw{!T_5qRsHm<6a6c!YiUwY7*qt2i}Y_7gd!L}JL%#^&k_CP7{jk8E8d(MBVh#}m8 zX3wAnLRi7_WbvLiLmrk>;;}wMjA3E5)Ls)PREG;HDV5wOi${{M)=yza8830PIy=GO zEdOLl9;rT;G%Jiq$@35hlY>%aUnr292FLRK>$7D2)ude9(8*qckzko`KtV7FkX1?^ zYvx^BD2IfU<wa7oN0$_1DH~$Y66pnD7R}B}LIp3ZQ36_0a*1V&%2_~x(sZ?J-mXWk zJ#8YP+O|QR>0<Jh617TRM-ADpCi@24<|~r;TUcoJ`H;n<Bw+*lM9qvP#wGZIZQz7= zRZ4esv+F-YPj>m^vhQ>`7LA5gL~D*P?K0)fUhfeXm@Z1)bIMRP!EWH77p+4JK0np@ z+ztOY7hChX*zLfIrkt@D)ERS~<j?$T#SWj4dE{y%wKb&euJZlvp|m)0K*xr`pNc~W zpfr-DE+4H9q0Hw^kVltLY!aR(P2v0ngexX#{^VU0pv=&SO`myjsN7vkOin+p$H)e& zxZL;HsVsnm05(AqCA%ij;U&kxp^HL9M$fJquqJXAVj%#3w04hFr1&oeI36f!-7Yh> zle$_@KK%leIh!KwAIvd3Ol42(kZqUf!6AcgwFnwandBRC`KO(8wt3c@bACORgq%6+ zq;A_PF+qC$z~7_gHvKqJmf*}}-{q~v3u@S)TXTebFo3zH(7&Q+PY<2v%Ppp;#j(_q zDs-|~rs4vq5q4ZYC_qPmh|J~136lI4HgW8{^t1q!kXw*y+N7WK=E39QY}8s>8Jk<K zly!(85{G!!E&c2OitYU-yt&Oc<>M-ehU>u!#7tlmt{hOfz!@z5SK_?Rog9G+{xVZ} zlW=-r_R1R#>xH*748ho4-nEl&)f|@&v1p<Dh5}vL;ow^#lC;o|+suHb^6^fMM2_co zfsCX4^8l_WdGN*so{!7gyqk=)Lg^Z5!j=in!k?s*N)MC4q?Irc00jU$Nd`iBip)qe zjSoe_fNxTjqv2k=MCfb65@1sLRK-7Evd9q|xvXyaD!Rfb(v9wJ&6nPxar}3#O708y zu8DH%Zft1ERr*}2x-V<|FOdRWr5dQ$+QVJ&g4}+2YW|`jk!2I3k<ZoIg=aH!U*VBy z^E$LVdO&0SdXt;m-Y<u!DdEayH>p+3S&Wy6+G3c2fB<&&6sL7>7OcVrh(c20n<Frk z57hv?HTJGbX@!(Tx-ZVYxs^77hK2!i)RnRDBipI@!${NRtYUs-01cB}9ptF?oJ!9O znylKeVynlo6h&?YB!H`zthEhv*a<!A`8UIKm8n&w3X%f5G55j`Q@T-es=!9L1siB* z->!!x)nwPV-uT@%IJOen^-j@DOi)AUChQZiv}`K=c*l*o9o6F}JYbgav{Ou!RCa(Q zWqqEnj^N7iX#l239Qx|7XtX!;oNHC8A@m=JFWOw+at61F@DrI)lh;%2j$KLwGZg-0 zoHnJ^i9l<+bjc<<Y!g50B=AD}`VA~ppACMo-Z!T(!#E#I-P+iGhjA#&%u9!jcuOKD zm}kuVW>P`>DZIjuL!3XVWMtOOoysjz(DfP+3G#=ZiEgM0N?tT%?+w1xUXk}JB{E<l z%}>|*%>`wuK}6OX+xYuSY3sRdJ5LvJseq_mpV!N~TY?`S=xsD%2Z_@pr8TKbAF7h( z0~08chT*yWfjxNkDJ_}2#knV>#^$gg2}HDY*$7p+*f~FK;bX-L9y(*eUcG%i;Ll8| zw*WPr_s#|`z(H5A&`Ri_x6&x`+e}=dEOiu5%^yrBtpDzD_`N)ul^>or^z=j03_EPd z%!2mrK#$>UzhPDBi+yYj-(vxE{lGuup&0PusxHtLch8*t5=;s?svl@}>%!@J7j;_o zNA9MPKuAT(2wi;eUp|SyO+u|H&`qv)nbXF2Qi_Jq=jJq@<7$+W-hbdUZ_VBxR>(F} zwl9cuV6ySy4?AYHbA`nw>4nO_yP3`gMaF%!PrR5{u*Sf+#rs19c)>c1g3uk6)ilx1 z=QMsVjte=BC37gEwu7;gM@99GkPwmvv4yawUZn}FyxJFXzBErphRV^Wof8fCL*MkG zT{56$#h~l3Z$yrkkZ37m8NL`F!T3~PY)E%ocyqwFV^rT~ClNHC65n*|59djrB~_z3 zZyQmY5JG8bd#f`abilF$F)e)mkGj{cHB{N_t*W^S?uya4<GOeW0WRkbwdMdd>kg4v zt-F+BE=8Nv-EQ2o^DE)QR#^3Mbh{ZihEcwn^8j_b%Lw|enq0Y{P0k;bpYvYb2R(Jz zT24X`!y*;KV3aC|#b)xq^>{9vJyq~BIO#G1YD`sJqn0>s4-VX-(;Kbi%Wu)Jz%grf zCVk$=Xtm^mVbIqe-QcL6xI*$?hZe-6ID+VRYE6-wO9qi}SJ)zxSY}Km6ljp_3@1)l z*_LfQi0HPNxmyxEICJ<D@N(sRHI<R(bWZn~P232<n38<O9cMs}lck6G?9WxBY_`}u zPkB+KP2SX`LrWjpUw5A?ke-mK^(WkkZ9u<`EtnEA#M5GDYYLtw9ID36|0;okmHS$5 zex+=G+M8$Wp>fjft&q-?b%YdDGl8X(G^dM&eoHm}d1*0czBJ?-G=H<aG2_eht;&Q6 zSb;)x-W*eT<s*fx_s4+tCaQZDU0ZhVyUsz|w5lf|?{yA|vNPOFfKd<AmE;o(cLNw{ zkjORJ<b)cK5;^G^2@$owU%1t%;-QHk>-}~ATnW0XCWY{Ldg*hug<C&w7u9h$#q0~o z?5?{on$Bf;TzRI8JjqmP6TR{yfV)0vHO6@Nb)S@=T`Ui0l4xDluiW-j=^ImeG&7=! z7?pbD(fcvZ$0ZK=jf4oh93JMI#Q0$afDHhva_T<I!TlXVr}hdwy8}x12|@&`AcyS_ z2U6(Pgp~COm(i`8Rc-7Cw8@lHb`sA{QNP{z@Ryix(ujC;)LlY&VV7B8A!`pL?P3yZ z&y~{w3{x_@Cs*%e?!8*E(DzoyQgas6@|J|`vPKL~o+1r^@J10M*lE&Ww9X|W_^K2| z5Uy*SF@WWgbWpM3RErMk{%>Z~$jfDBe6oU#I(|6y+f3k~o`>0?nJzm;#h3FFDG!3) zCDd!3ocb1aV)G@Kq3GABHhQP-3|KACIH8DDXbdfqO={RM!6&yg91D7Pc~SlBvGqB5 z{qIvxTm2K{^lT+VsMAap=r4|{;458$OxUH6JN{>0sMmnjqsd46nN&x#lfG?(z0TkF z4gqj({@2^}03fi;@nxhw=){#@1N)jrJLq*aX98))*|%$_P-OwDKdFwY?14=Z(pFQj zNT5M9&5|PDsy97qx+qE`5{*1Q>5?%mi}A<q+$pCAU)6GJ<N0d^y4D)~q<xvZ?)LO{ zx^3!t6CMXlA{n;(sM)|#1m$2p)A1>Y$k1;+OEvM2Ib)J0{=yfHoQ8>%k!;GmQ;%P_ zAjf=A1iZ9-rY-^3^Lx*QdAx0X^|g;hb9Ff9p3Kt03~40=HF*e{JWz&oPO*!nwr?^i zQo}-JZ*=s*(0?~}isbvxjMYDpZ8`A!E>$l3MK`67Suuw^`&fmNwEcwIq)vS=<5i(a z$?vl??9}w4VN(4pm_);5wx6bXx$IA)m+S+{Y{L)t=F;M=U-<9xHr+jw!aPfHm};WF z=nRxgYI>WZN6SdeU}>mdWJt92blqz@i%E$nJ%c_N$%NJe7UT|>4S&L_v2~RCCdp(f zQi@$8dV*U2j`SW37{K3sO_G(O2|Fg-3(=l#Q6XbWb&U3qXrMA75*Y~Yk@IZZbm}%2 z#o6rSsa$9j5ixnk)}~xqN-j1qqvnVQ*$KA$xKT|@nZ}h;Y=%~whUX4i%5rryUF7mO z=Z?ru<J=QZw`5c4L_fNHHTlLa7n>KDyGz9^E|$`x@Oc}}utuYCJToG<Cqv{j=^Lc1 zzGo+CdQUT{8e6opsT1ofCWa<bc8l~gB6qGd#Fb1j`GDK?LjyTD+teM*kFW$llB1P3 zrH~b2=K&PHxpBM$=;wk+&&s@jco1L6;BC1waB9L{kLX?R(qL|_)j?<>&<cQ3Fhf4q zvwKxY6vVY#e-N8u)gbGb8-P0rnB~YGyzN?D^JOqk+p?=EDK1wT<Y}~ZwoYKP*$Jj& zW<sB{&i``d<ghl|Dlb_8gOz0&D_jU5jI&7Adnz)l-KbTIf{Ot5(O^7YX1N^8-^nTN zO`%K-0RRWY*pVS#Irqzh+HPW{RJZ3D$sE_&+d|zy(<@jq!?gxZ;BC^&m|CN^#GVBi z!@K8Y?4wD^zs$5X{#l->s^hF16U~5{`6@GD-12MNx2kA+e7qUrM*cd%*xu&-xn)hG zXsnhRe$Sl$yU`N%CRhW&gAkK-J=3@DmupQ)G62yj)dmX%1rR`8DXb*V$%N>ZKWWEC zmUmhDgBb*_Z_OYpZmYg*9GD%4O1bL{CJTVVAQl`Mf>QxD%O__;nE`M%N@Rx;@8@F> znW~VAL090nEWGj0W3|`pIfQJYYKp1f+Q@$ZgXU)a=4+-_O22WWMREtE46{%4m%wH9 zqu@ljcf!}7dsD=>vxyjQOba6TZ54!}`DR%t$jTXJty!@&e>A_6)wL|gustF2tkPl^ zFaDnJiHZqPz&kaj)d$oxqk+<U4nUAvYhFwiidf@&lv(f|lpJpwQ!ZsHI!aRv^Mca= zKOsI<0yjTWRv_zFDK;Cl;faIF{*rOvz~#eUq@2;dUv{D~>fr0#L6dRK1&Vofq17eO zQXcb)R!z`=AIPlbZ9kFzxE%U1Px@R$^U%YJ_3xVI&cw7e!ogA@;I;kyVb6-&o4>b0 zxj2Ur@fRQAC{eP~nN6_=GjY23`UY4~ueexG0X-#d=Tmf7jQN)<i~aH{zc~G1pueo> zC;dtaaoa-%kV4MuRV=F7Q@oPxjU)9vM78{J4V76n;(OcrRCNJ?=~{gY48-7OiWsr? za1??M;_5M%>3I(H3e;|Cg1G@R{qze0+C9HV>H(3i@7Ua!LU6`okcEe!Kjl2?E9CZo z0HJp)=mMpiAus1#$^96W>nn{|<vI8<x-5E|NFbf|Rf$dI7qB`&l&0K;D1i_6^0ie@ zcVjw_22n^c5u?M(18;M@Q9ETH0D7W-|Kg;j?rK;hteXVWfdJu}1V2gUTqJ(VD*Z(Y zvfhrW5a@w=&>=)=P@PcjK8)HLJBCv{AW)J1!kM@sivO@)VmnG`en1vTO&f0KfUow7 zQ~^7HXwAMJoyay$SRAp0O?QcXH6&sqaK6wxv?$;=v8=~c(Z+Oy;yo@^PfLTPL&pco z^>Y74xSyAEWlp?>$&lclyP8MHNOvtjC!MNPG5-T2S^Nl@3U$p2k;U<Hf{*526|yU! zSYZ28d>hl7c-0hcRjpbQJzMl$&oHZS_x))!Ak3PkEZgp%l&=ciL|6S=he%Q_Ql+lZ za~!a%>fZKY&f^DCUi#*?35F;#yU;fd5&hh(We9P~oi#$=6KY=j_Nq%FU%6^&<SujQ zn5)lUJ_q8i7hbsG-!`pA1EX&PxAb*S83<7EORz^xt5N&Pi|e*SWY9bJ+(Oe*s$-Zh zPANK#SIG|t_5(X*b7lZu5&qUJ;!ROiDl8k8?q~d$r%*wuy7a>Y9y|M1_B;j3P4<U- zZ{4J{y`yOkq5I;Czc$^_nGRe57+CtS+h76)P`Es4tz5^=v|l+UWcQw;r8x3P-8xp( zJYClBsri4z^*wjr`(8+_R6O*hoOFhhO#b6K$|)i5Mtr7>=v9@o%7(K<|3jt&q`E3y zD8zkKOS;bQDJ1SLc85#dNSdfm0p7u=_O+<tc`d>{V|*~tKg!!fdH^$M@#k|T<=2D# zlrQ>{cN~LhzF+chDm7tq*n@UrE%#ICaV;5dR&;ji5V=|4LOw7~w8pWJcnXwwN&2uh zv|vbLozOIF$Z=S8c<{Z9081`8d_+0agCobv2|vKme|l5cLXKb|{KYdSK3=w7ns)#E z@g6tPFGc|WJ**|F;yWh3D1}glMF9-cujL&pdh+<*0Qe7H4T>PM!WO#4l5XW*DG)+m z+OKnnwzOj~i>dNYOrdWRzAW<c!<=Lbe9lKCn5DN?RODWUyW$}jM$rKy<`V+o``Hrc zU>z$QtEc%tm>lVZJ^E};;D~`O;_U<|c^nNpY}C8G>3KfnPA_$30_FM_RfGx-C)b!B z&M`UaJu~8;A(?!qkF=ufdAOyyoyc6<1})VEsZCQnJGq~9<#yLHE0a#J_O+g?!-I;0 z{}3wf(H+>GXBIXn?zKFUxegQh74A$A-b0cTxJdq>Go(XAlWWc{+#?#aKh+gwn9pgf z{eUNWPiA=nd>PSJZ17cH<O;p&6yOPe+Ydd$NqEz0ek;M5cq7l;gfKmL+u_zH_nq9@ zn<INo={e^kxJC+s;=XI&DU0aJgL_<TJJl;GQ9%%*KJAoEKD|I19C*4PeHi9;&&4EQ zKZmZk|Cj1Yg;^TqMrA%@rChdK{Jd1jW)+44Vi<UrPx9yf8{g05=uV3zCcdRj0Q?ir z#xDFYr?z1#vVNUcJUYQ_q-}=?hU})^LY`cDWu$T9<n=+3FMb?`f?icB@=|lkLJOGR z&OaRGlX(*bZt9=WzT)`iYP3l*b`0C9#W{JR<e}Fskpb^i&M6Qn)zqTjG){<7IDpT+ zdL~ReQbwHoW*?^HeOHUkt1uHwxB*mD?!&uPaU+omWLEsOX31MS8FPHZ#>(Oyw@dIv z`4s8D3pddh1vgq{mrvbu6&&>W0(t-4)g_g<GHWgYK^uqdZPlxK4ST07PI`pukt3AI z1Ek3vy%iM%suuaGqi^KwY-`Y4{14nF1I}(8(BP;2T@Fb@vPuEI>5T9XCB1o9ZH=Jy zA6rpf=PE1|8i*pWpl!lnAix+$Qa*^V7T`MXgSdP1gT;BI|2mv;QE@~}x%{8y5Ak^O z&Cx?9uL6|DH2y`Rx15i*(eT6I%`YSgFwJ9Eh&X)}C-Qg`+v5pco)%$wVS9wb$3e1q zpQIaY88Ld|u6wj3t^%$l)xv;l(25A_>A5nxO)@+x_L>Y{qzQ>9LV+?GZoMW<gmrK> z&AkP>3G4o3wA@iWrUA3ZahpQ!H9&C`xHQYfzx#dLM~yQRzN0&Z?5H@vCeDT_R$q=8 zb;7@|Gw)Y5=T%BtN+9x@Iug<a-w;pm6p4={w9sRm%~7#={c{)=)>Ir{h5$-!2Ez65 zB_hDK<&wca2_UgrETT$QBm|W8ekHX6bG~Bu#Vt|EiZ~)$)U7%!rdPb47BhH^C}6F% zE&rmh92XBe(KpAo`hw}2dtW$x=>KTg^U;tpsecB=k7UY#Bc$8VMlxFQP(5>uVeIDd zcUs*);(MxlC|CaIE&qcMI+u0D*<mtx`<dElb?z{d;#CoDB9rskekBrH0r~T(O{XjZ z1_0l1nXQxh=cWJ|#)E$@VuqF2YBUf6*cRK+f~qCTHAS3jL>%8-vp@PhNpDW1=ey&3 zLw;jQLWN}7Yy2Su-srfdy`4stOEabd19N{5o6_fx8}>NAzx`22EfgzJFYW)Td|M<$ zt}9zgzFG~xtT~8Qc`5WM9C1<IX@8e{&I^qgEg_)HNrGSfHX#Jr!x!ab_a}}>h*tbd z62{-7Cdn*=6K%k7u6Xo{MnkA!M*kaU0ak#X<yFZ)a>XqkIsB2OhkP6z&yv7j!k^1E z+T$*{(aaU8IDz~KA8EnPK+1<JpMT6|K?f>Ddh|gg*?n$%mfdZ*`udNIKTM1<ITV9e zqbjmP*l?GEf;$EHWy2AhG%T3(u|~Y7uVIC#AsC=wDA=SCI)_$#W&k!iVRF90`rOoR zs~%-SMH`<!SaR5y5knK{@e6_hQRDjKpOH&Mv3udfj|_-(g_-7^m~DH<wb-H1(Y`f- zK=MY2n(64f(%V0)#a;en=^kXt;49>QZOoXE!{b9NPjhYmb6POFCH=QrNJ2x`s;5gQ zi-F9LY6`XbCyY=Li*!tI@9M`cFB!Snn3jg&1Q8sdEHQDzPo#pL0X^&6AY}i<<a8gn z2@QtFX^2wZ$R*(Z;4+mkfcIAg5Wh}@($0v{q&nk_TGgIR51TrV$W;98dLM?NK=w>% zlx5q<Ji*UFEF$t-iYtR0%QaSzdq3&eidM*FO{><&4(*DkKNNqTl_2AZ0;ZS#LsDcT zzpE%iT&EyTZXr5XPI#!kjzNOw!63q;H{#BsmmDSg+hD-<CAY)>xMy9(fC3USSQ3CI z&;dwNiP|7CBm>|Nf}5~Q!Q`JNIWrU3G6#(iy<0P$-?%m3Dwc-%1EPYra=J|p-K%dq zZuq{_s#c%0*8SY+Tw$g)PzH^))7HT!Rs1JHkr5eHEe1X2B-r%pg-TQ8lq$VWuxx!M z5{*J_3VU+l94T>0Cr7aC?s#IB7jD%9zeSRm(%)2%H6@LyPBCgsPhbmj)nxGpW$`97 zg11>EMKsh0%K{K2wSNf#!lBj`YwDtSYcqWV41QbYDRy>f7>bXy0-J`_VZWV-X*XI! z;w4Y^IQX}oxU|{nn^;+s)1n?}cXApF8-2e$Ek*=JrR~e*zJxD`^jJ!`{yDcSLrTPj z2jirBkb|$_9~+>bH_R=`nj*vVI-dy@JyxmU{R(<N)baQ&ti)1=&~%RJJ~i#i9pJ%A zgculkR6Hti;9ti{oa++whXlY826RYZnPlLrOVnO(oFvz_N6SrZnU1MI{Gud&21mmT zHTbOu@yinN8Ad8@7baFuBrG4Edu`@k8*7(-+2*OLxDH-0eq3<`3;&=YyT@qx88#{3 zw$~Uh{zdu-raTb|`6&{L9}C*evO1OSAXX9n7l`qPh&uF>E5aN-8nH2=k&iKFn!nd$ zmLm_0sdCal@vES=+6ceABoH=g8`rbV&VthU(6zCDdf!S?@41QLQ3urVBu{+p{e3&o zLABnXXMGwix?MjEUH-?=dHA#Sw_*4sB4VE)#7<)Gttf30LClI#TkTz|rF3YJXzWmX z6^+(xQMIc58L5V<qS|V8*i~KV()D`%3Fn;8_ngo3ocq2mzLTThjIVANr=27uM2?`Q zKT8xSNeFo0Se`k8qw%#^sYsG)7(t=}0@OEP<mx4r9%7!kY&8~$QZsl?FN++x%`DcY zWR3FLswm9&x_lcJ-Ut8{4{0Fvv;#7=&nIVf1n3ykWNx{inc1w#lEB#|V{z1hmzQXQ zqrMk{)_~wl?27RdJ0nJv%cJ91Yr}v@@+JKw)&E5>qmK3X&*NHx?3#L%VA_c(E9WVt z)69O%$NabVZeY?nF@u+jl`IpEC42-LBuxmSH3YPbMz_iPy#1YItVnaf8<W^h9csSS zlesu8?N03Uvn+**&|M;bPd(EDw_xtnZg%W!a~EcQrkFl}3FsgA8)q{fF?dahY`)Tt zKZT8teR%D;N`Gj{>ZB%48{Cb=29*UojV`SeRexsi6KtKGLZeJ<<NFJSr=}GWM^FI` z81b-U8d&A^=Zyln#r-Mn($S$@x8n9}i(0*KYYPhfU+5fbmAzr%(}SdA8-))q%^P1f z_)h$vl)F2g#`>PBtVHB!*GJrYpSJ3ym+VM%#GGoh(gm&#wyzpG>l`NcXoRwUBtj*Y z??3w6=yobdOd{iTh9tmhKpm;FZcVw-v8Q5BkOJ_ieW3nuWZ>R$DgB!Hdo(e}XHyC$ z;nzL|^L`ILUDt_WA5;7jpe00r5ntT@@nq%rYDF<Gz&?)kb-{&PGnODi&X!XG6<e`H zB7cy9`4=Hb{h7gMJ$K(xqR}-^ck~B#*`&ESU8w#7{V-{n<&>i`r8PW$`L$Si1u95P zY(y%yp+n(nP7-e5W=hUK;(&s}4gL(7jMQ@M=;iH)P8&*@#><IUZvF1Y!H(*xgfVbE zig<91Cu6b$RGbePLmv~4Hg@W}@l;{MOT}#w!_c32_LQa+<i$7Idb>BmVx`#_W@)yF zx%S*B<Z1}GBh;UWuX1cSWYr*lYB|F8$XeOW{kc=3*yPLTGaX7n3G~L|#K5#mE8<(; zhrHcY6>07rmUke-QobXol=(aVeqScPkE;suwOdg$)-0OV6cN*Y`GX57el{!>-TRk{ zGo&ZIBF^g`R-t}p=%R74eFhofXI)@|*hYZ%f+Mp83DYtzEH+?qw*<g>$;Tod8%CrW ztny`?c%*_BY<yz(!ek_<>yeTM(f8CiOybZ-O%#W*e_!m$^lQZ+bCkqQLFl+b(D>~p z38}Kfozg%+ptk!<J(`dI^jOPEbo**DTRynqf*v1gR2U9>*?2X{4z7(i#kIrF76n)u zxLro}VC<>~;$gR+&eR!Ms{C&;dLSCJk9m3r`f~e*E|(|;pBQw`gELd~SwubksryQP zX0@5H<HbuE!4RsnN`pj*@AxUAYWrc_Y3!SIKYgd59KC;fFMo?q-K|WroSD`Ztvxk? zT^;*pX+Mp-zQ2I=cc`03;#%8ZoC<<dL;6|v9Ob1os8Jn+$t7nRJ>rYYIB8k$@z}x* zCp7!+SvdaQdi}AIu_6OgK_dGU?%F5gEso!zBeR|Aynx}qCljCbCY_$2T6v9K#hx2^ zrE>hIb7#Q+qQq<>ti4|A#8e#?8ma!oxint#_|jR`NjuWnk3Oex!;V?B?A?XXTl6CJ z$(htjfs7iZJ<N)l20xT2^5#3q#bv+quHK=IsW%2D1-k0i&7~Xb<~tG*gO^1x#Dr`) zocKl6t+Q`rNBQc{Vn4su%SacGfqZp6FQ%ZWQWeB4{`0*hQSrtvy{(FKNzfbCOMIW} zV>Fzx9L#6bN^)4=hW~m^NYjEKkuHG~x}HPu8ilabxl)>R9Zsn^uEE1TyKmj(wY!NK zzTP&bf&1%msX_M(&odp;t1nz+3-KWNwlUkIoD=$tx4eBU`U<L@fEw?Je=Ymu6hT7j ziuLHNop%@S2aa@#V9_y<K?syOoDSm`A<=W{)m))glCY(0jEa*m#J82v)!2{+{O>Pz zlV{jk9Qpy!ReKjG1%$&2Ap1*A0jP9}iPVsut~EhanJ)<31BRi%-54p0oYM!mPZSWd z<P6>)mK07$h~dEOVP$xDP>fn<{)j2Ssq3)>kBt<<c#t?o#1bw&A2>)J+Xg5CrJDZp zEZZgJY_Y?Fd8$k?wRC>@V&b0jGm1}d%$q@_ZE;PXv4xl?p@tqeSS&%@tvtz=j^j_n zC?cC%WgYXk1fIcXq5_Dl!FZPWVC44jJ?K|lzR$LnbuaJ@z@!#0NteR!o`%%ZgGCCA zqd<oQV!$zOED*5A3ycm|ZT>AyJF)Wy&%>nvc=Ay#c``M0cU3)MBKC+i*ue-Q1_uK3 z62|SgvX%DB@M@0&pCtk?+zbW~=$^$(W6O&YV1B1d0ztu^3Zg)0i4WlxSs4t4H;vDR za*g0XgBFvk{1IIF%Fcz`BYkjB%b*Z@gI0mHNy}1R#fK+Z9jYKwCp7~N)K-`v38R8M z!~R?rL9RHInu;?<j(7fnO%ghh8%Q99ivUkTdjinULwTqkJka4%f+z1cc_Cq2C6HTy zil1=-XKa|~ZJb(#t)MLrO7MU5a*ECX=&D&NI;p6hlE}1baGc^^d4|Ubg($lyiin|s z6XGRJg#6H+>dSggXBG1Q8-}tXzVN0hMpO$_mE=p_w+1yG6Jf!G4&U4oCzUAMeeV<J zvdJ@kiI9MeHfdyIV3q85EK~0648fV6{PNoz-rIBeI)N-kVY;K6FzzXQ6`c^m4^v&Y zsAA~DZM-8dy9KX;u>+mB^rV-P0Wq?xOEmeXG~tW@OPuhr%xlIMo*s?tP!#&nlx<9D zsixeT|FMQQlnPyqz}p!xb&ixBcN-Isjs^>$YEWvA<cma~+s~fGh?YSmmA`gy6_INk z&uDd%2VhBLFiT#~##!dfeEOE9{4G*e25iUc$rUa^PZ$#B_5BLI&YHW62ZfBUon>jo z6u|P2XgVVl%}FR5NSGTPbv{uH3y4;^UB@fQ+kCb>LnxMb=qK#9|AFLfqsaFGU^OpT zUc*0YBbbVwJ{L*ma^@#kDY(ynnK-c1qZ7gpB8}XioS3_S>Pp`Hz}vFJy@M|Nln=&F z`L0z!izX<(AzaiA%b0x4*U~LVRA;1w#CxuzxDzy;MZEn4sKVrQOg~;!Rh!9`f<N*< z&x++@{gRBB`T$IP4X<(-D6>=_hvqGz6nHSFP;A9buHgw-hH;)EG=?h@wkObC{sg6H z0_~a)TyniLVdxMEO~0>^5qQ}j_JwKzb;KBkiN5<6kxGOCGk~s^ByuebS|kz+53&H} zW38<2(5L$8McxVdI<Qol#GMF<tDSa!;nE!0R{)iNzl5b31Ea#*f@RZ}axvc?@&VtJ z!GDx(tQsf`{N@1wIq*pFK|!;sIQ=h>h|y|BH+=H|^Nkwt+-A;>azQMkp-1^u3JC9+ zAZ#^LH!sO_8Sk>k^b%yd)b!&3nG9S3yAv}Y9in#)0{EMZow+CKZ<Pht3}RkmR89zl zoevWP#JCI&SIf-<OYEym9FFUy7s1yQ>^Ok8U0VxNux>%_y3<Ujk!0+2V(}pdo7x)K z@E@4S(VHL{!zF?ud{YIb(X=3o9sCG_cm*n;ul5CvfC8Y{--t=f1sR6m0R)+Er3fP~ z!}yDE(c!uK1XF9thn-YmBD31|tFN!wE4j5~>kNRo3u`Db+hE7NwV;UqK#rmAs(s_y zX^h$Yd&+5qTLyL9CJL+Uz)!pyG^1;M+hJ1EXXk(&eG=pA-4cM9lUP}!v)+m!7TDKX zGhRV1#C>>WrjbF&y%Da_IJZFJZG8L%!21A8^GA7J>LM1dW7Z+~6qgzK47?lWe=8C; z+IFpaLu|6l`)0>E?sBI18d8~rRS&;^S6pN*rx9Zn9_$5XDZ=!R#WXI*QrMMmA~4UW z_nq{14+kPh=pOn>XF(USh`)#m!4Gf%Hk%(gJ7;w)=h{aEk<XQZ<G!7)6x2IUY~v&4 z`f5%y@loIr0Yx2&eG_)AS>;G!)3QKFiml9-rz%H{0(pNJY99Za#FZP#Zw^HgPH-2e zUn4J3h$GQs;<ikV#c2%FkYT~&GVl;GoRSxMVh9M}aTZ$3l$B&;VeAjykL@LkN{pXw z6GR`|K2gR_J5j{aD38;qf6IA=Sr94u_8F)!bo*0u{v3Zu1u?F>LvQ!ICeycnh0&QX z_pLGPrMMt1Y=XY7A?V^>&|DlEtdGD65R5-cv1$NkFRy1d%)*n!iKp8)@q5M#>9Agm z>=J%N4z8y2=ea6Djl3_XQaU_6>>4S@S%U|W0pHV@@l_6O!}${8>X%c(1Mvj^b@#mU zCe_tT?EP|md(iV*vtgfJte%Q{unbgG{Kox2=K1+2FQE7eGw!HXS3hK6zc=PC`lWtK zYKhzt5@S>=Uo)g3MCumIpt{%FT31k>eEG{&bX_M8cjN0z4l2aT#pb)eVG)2#ziX5n z1L_GttyAl{;_9duL`=d9rik_LQ^{=AjYHC&?S^HdWCwLz*%xurD0*Zjt4Bs-j;Y%8 zvYmVbeXGKsqPD<u`nXWG4YNud)_hwQaZ<wxJbo<4Z)UqF#@@g%#8LT-sipqdG4o?$ zM+Y#imbL2q#6g|p1mudy6$0LFIYO8P6BaT6#;1^~e<K%VDCvB#Myd=5Qx{IHfIQh3 zjDVuoRAf9A`CMkmSBJi1zsI8G59nzZ<+s;uc4(G0Ly^(7=lga1{o6I>1OW07j-ZvJ zYZxmUIOv@s?_q7vuiqnW>APl-ahBk+wzheEO+;cMN(qPLoy#sTj8Z4dje8flWpi($ zCZ-)e8rOe9Cu79&q63To02$8*<39ZOyucMPy0NxGLcXeES8>-RH$t7Z8prMp2g!H! zWZo)&ts^<d3<x-@tADEdvh=O@D683?85mwGIH#!gSDu2!7G0+o0)((@RbfTn@!S8~ z!MdCOBhrjIE~xEgkTWG_i7r~zW(H!Fo?=4F#T|Si==?KcD;Z)DV?0-$?8hvXB7>Qj z=LxbB?uS00&i?!gCRlMTj{rE3OL5x-=#=j)7eg@d86`+9OaL-eEGfj4ZUBbN1bpg= z;~t5)uuUik10m&N*E1u_R_q2w!Cd5pxl10;LfnW-;D7b}Z--si4*7JWE^--R2AOH% zD$z8a5H^?84P61<P{-RlxG&4TNUVWagJTsw85q_-q2MK>hd?Lme;y5$@5KJ6$Aew9 zUMW2egQRm&Z1xO5lbu5cAWLNcD!Ty5J}oZ-LWG<FZg>U&x^7aCf+$m17;1`Wn%Nrw zFfXB(J%tIG+_N#VxNw<ei=H4co(JeQvO)AAu+G?-IJeKw#;1&K^INzZN?bywJl9oQ zq3t|(9fYT3J~zMe0~ES+Sa9rO8w~JEboWFlM{pchGX!&~h@|w)#(u1n2=PKaPjoQ& z7NtM@APK#EJoTHJ@rbIt38;twes43NBe4}3NRQ|8FLw`d_a+Tql0_H6s}yDHLcoA> z8R3Q)jtA(M8B-mK3+qd~`PEDfcR_13-hY#{=aF*Mg(i9k9Ngx=W-W9R1CAQfB?$sU zDT?jKvz^G%4>IVmS%Jp%3uJE1q0;23g*>>P2GkSG$0NRAgfao#i-;rKvpg@?d4kvD zq=LlH5DVZ5Iz!=L+-(~u_Qdk6D0KE{-mQJwj^{a87v6fO6sC7J?Ar0fTiJ8Hg!*|x zG$oLWfXJ$s@iZn^grOrIMBYrf$W!9llT^%2;h)ycwb?1}3{NwJJB%6_RzMI0YtSGv z?+cRK%2Mf&8WL!>(<zt8-R4<Y5?BEd&-=4r>Drr6BDRDlbxB4Ud+Fj#iLNU6EDS7% zsgf=gyhi|Tfsp1yAQsevD-`Y^fQ<lA#cez{()8;O5Kj_yX~F0q4+ZS#RR&)Q3FJ8$ z3C5&j6HJZC2{|$cvdYj(9xQkZ2Dm=eWb&G~Wfj|~)=2(LSWfr3_br!P#M?>GG&hi* z*aP(p;bFhzZZ#4k77!N#_Jw#l5gWr;zvJ2rs!SZjD|C%uGZ6uW@SMT%oMf8D-4gje ziu^WKLtN5<Q=nRauF6choTo0Im3--@9A*#r(ctV*-Utum`fcc05h41#!IK-plpKkR zoe=L>F@h76-IT%dVT*P*v<$&uomc55!tvY$a*7MEF0JTDPHQ_@Fk{Yqi3AUbLic%q z?xx&OZ=cUU!A`*N@=OtV)`1J6pw%tC`U~v*c18xm%Y2SFPZffKKy`pndH@23z+J1< z4zdA1C-Q8MD%ajh6-L5;W+9zGRqU3I7)@1U#@S2Fgt2$_i&_$&8&ab)?D)VT$v|?| z!c|Rd7(8(Q5|<a!cvIa%5;t3M9<`i@?m`O?ls3FBC`yn%c%^xtJ@YvdJjHVj00g^D zi`m-=63_X2N~37c4e?JZ3V7w66_jq6aNURq3TpPU9l4(7eegd9sMT#wNSB!uPe$wM zqcX6k>f=7IIjzyf#Mk`$vXNe?Vmf^1z=IOmE%Gwb^Yqhj^p46jZ*AW965IiHl!v(d z6+{e3yp04kORhIGCAx%wo2KL;qmGEEv`?ns<Y4<dudCvHQK2uR22v`9O8D;sK&;sr zPJ|(=zD{k|_o75l+0*Nry1=GX^Tsw$R=xg)%aI(uuEc{-a)8Q5SoP0VOjEH~ieV$X zVIO*d*7%dVhFRRr1wqlt;J>0IK(`D=NQaLizvF7T8{$q4mmxotac3iClEp%P-ZJ>g zVx<@T2MakecOiVMTUaj*=%lOWBGDdcO26c|R|E<kcAxjSf`T9(#MAF7Ux%h^>6Io= zb0d#LX9-ho5bb;3NA-~T0j6?!c2r5-DV}5u&!$4Mw0et7Ai;a*c)^~m3g(K;&K+Gl z(9H&PNl)S~>ijy^`(7#HM{*n*c0NuQ3r!bS%H)CZmaiy+r%l!Pvys{5NX&<z2gL(~ z44;pc?RPurDsBCvkvt{8L1p`HQ<OkI%p&%Ifws#9)CiZ3je!snIneD=4eq1omB7M2 zM4DO8^|l+dD#U%Bh7dR88D}gm9`S4gqvMGzYdr~c_QDe&7lK>2%jCJcJPJ1zwy@_e zx`Eg2&i)DprN;Ei-Aw($Z^L#<c7yJsm&JJznlD3eg1@}TBP7Xm$&1n8`eLzTgy^K1 zAbW{_SGt$GA>qH^GxungBA4tp7B$a$f&XosdnR^RI2AWXN0w5@33rCC+w)~cA%q>O zB#B^jciip@bUvM8vn$U${U8di3oPA!=<N)JsO@z@<QLLYmBG_VTqa9gUeO@`q6*(} zb*U)|Lm5;U;}Q8&2DiOoO^GiEG%)$9(L-Ysljv4gugT2T-2?Y~>yZ(tgyP-YC`0AT zTfYolpbD%2x198p!9n6=Ig7`aw{V8%+PT5a--wlA9%3X|5N3>}@hq5v(c6CVPej(& z8-$S$QAMTsuxa50kAKD8^?X3eIQeCeUSWId!^J{)0z6Kd37e&y@aRLYjQNRc+b-W- zY>aGlIN%QCW?kjC!sg~boa73Oy1C8&NjmMi-hIgjv@d;ZqaHWOR7Dq8vB^sGy}x!3 zIa*<wGL@y{56<5p{Xxu71s3XsU+PL+imKY0o2dKBFsl+ZWF}plO6R6PG&I3X^KhPe zxty=M4m^NY>QJ78CqT{a^^)aH9FwG|B+Zm9Xgsju+qWh!6B#>?+YYc7Gib!DhD+ik z(=*SOGDG*d=Hd(XvjvdvW}M4|MIRyaeA>CN#Q>AnhQ*elNIpJY=iGWybs#bqa!*)q z4qi0;8EBr_1|UrM|F*@mI(f6f^81Gn4iA+NtQE*!@x<+`&{>hiztgh8VCvUVjw#nm zqTUDe>^BqeBN+_;GkSbk=TF2Tg9dK8=+k@@%j#EL<2SI$RmwLXsnHEK()n(rxas@? zj~w^uPHwje{Esy9?0`(a8&o`#<Kw=d(77$>U_fdrGSKXet`YDC)xhzr1#a`HbCmiO z41~Qc90vm27@<gzJA4~1Pq=m}2E1aq{|JWxqXIw+yB2Sz&g;LRxB-{jNDC?*B7ADJ z5V6R$Q~f@#RaX;cY+(x>S-LA*Ae^51!@SF8ITTSTriHpN*p1_bC}46u%oJb0Kl56p z&G3P)py2E7FKPqr0v$AakhtnYoe>-a_y_CFrGHhp*j-510{<l>YV1C26RY#zP27IX zvqBYOZ^KuBW`HVqGXBLHG}3!qdDBAY@iH_*Pj<oFKN$EgW21&e@PLh|t_obMSa||3 zN(zpALS2Cg6qFs|>5De(t3C-<-5peOm1=MRmBK1Hes#B9wYdC{4%0<nMxs=I2?}aC z97<dLLV*qJuDX5ffAfz2E_0th-!{r)%e-nj8HSa-21t?Zl)`P$rrAhEm-;VD0`5z& zmv|UN7ZN)($iSEA<%=cNJH_jQk)0x|-;H@iY!X=q)6Y?uHF)vVyADUtLJ(jcw4aka zGD;xMNT~n0LN17U??2FYWXT_RD%lX11htDwdy26txkh98CszKF@Yb0g_!E8My|}rn z$(DjCxa#5B@TQIv|C&Dz?4}=aVThf5PU~KubQDT33pNb4un+z_3nGy?!TjVvMBfbj z%nZC55ZtuOJ$^Fqi+UzJkf#78vhOLYi2!;`L4Xg~E)_*Vpxyb-_?;)t9?OzQuC2Tb z=HHR8Zx$Q!_mR(ePfq_pp5)ZZ5w%I#M2*iZE}eye*`Nx!SvSoz+XjKjVI&8b-TWih z7xvsXJz=gM@l;pyS*w&bPEvQS?~(`ja`mFjtOS#aIGKUS#PGaaf~718&(w<t=!k@# z5_@R@!s{M{M}p!dx4$Z%;6e_eitw>V!x2>An`-v@5s!1n!9sJ@tK}z!XSp9oPw=5- z6|bH$GI?>oJYPLlG^{=6nAEd7v$%*W7o=<rjdv2-;XhSg>_7trKS*ya|Ez<hY)PIe z?lwBpE+p8peGQKNpf0}fpTS|7gazR)W=SY9AH&nJE&Or@k)(_0Dn^vVea-nF7)Ch= zT7oC%_5n14Dge-UQQ9HR+gXBiEp)~<6}03AK=Hxoh1pdb9>K$IBnHlERMH5e4l8Do zku=9D)%MXD`wBf?e(e&j`hsIXvdGGEW~VUqD1rwG4L~$Jp=FC1|K`MBCOQFTkZl&T zq?yJNse<CgvFfxAaB?f6ZEMt5J_)kf)cJXl#zy0~mfEC8<M@BADEX#f_3qL|HU2&o zkQxo-O?u>xmS_ka>J8~q(lm}4b8JBQ53+Pc05UHZGM|`L=-L7V=?JjAmuFk!-WZyH z)#LM*KLVJa|B%i#%9~YsXf54Yfx0FMxCszOVbsfjHyh}j3ofpR8`Jb1+c#J~)^J8d zoIBp|{eu^PxZZi#QqQuJ4}@y9>4o*$pMm1F3S&q34JN@YB|_F&B)n@~jHulG9}EJB z10@t?qL73Sc^E;5;4216zHq9Wu`h!#1?tB)NFb~3chDINkN)e7cOxIA-LT_4D3sz| zD>#B6gf#5cb$_w|7J@kiW@&Z|AsS6X7|;bcY7JH5RlHOzI_kz9sW5<gr@+{AGo5MT z77NKT!>hv98DxYxt$t6Cs*N1vrS80`8oO>rvqSV1zynonfh||gY?k&ct)b)F>SK*t zpgvs_e4B&Rfus1IKFUh7jS!A5qZG{}keOh^Yjd~QuKg3|yObMF=*Fm)i!T-@l+lbI zepQgsNqRDCE#(#R;#bJ29~_zhmPDad#E?}F*O$y)#YcKGcxj1va&{TG(l8+HOjP9- zb2>mVfq+TD)6u_?Wa!Y0n-JfDdwO2QQgZ96@mb0T1lf`5Ko;xzE2{CNkgBzC<IZNQ zC*f?-a&AR{NXGd5i1=Kmx}Z%R3J78*zya(g3W;?UopaYehH5Or_MQ!8i0z}Dn%fHP za-G#9N?}y*(X`)(8tSBWM{~1kmT(R7X#tJC%SVV1Yzk_W+K{Lm#=rwOPx3VF6?Xu4 zHv1s|usgZv*kD>_&6)VYBr?>R%^Rbz`(()~w?JC=@6>nnDO@!+yL7d*!TCh8v|fk{ zyj~h#Q)ykvl-_#vi5}ohCV5%>UN2|+|7t@=2V|Qz_#a(&PGtOvR{c-jqLtP9-`gr< zZ1kny5wZ1PVtQ_^lsW_}TNB{bu#{zgr~xJ3xY;jo@4)ii^>09>0cu9{X}GM|x~#Qb z6)#7%KxHh}kIqGNESk)!I)2)SzVyR7Du#06Z~nD0&G(sJ{RpMP+@}a^Fl$X}1z(7{ zDk<SY4mncJbWeB61n_=A&{bru`+68((fyU}UDW<I!~YQ!Ka0-jIqKP_nt~_y=KRdM z2B{a6d-3GAm<YED^&w)ZwRk^XF7b##wlFYf%i#j`TLiE1JIU#dBz0yo(TY0??|sNu z{<4&WmbKz|1NmH;idR}rhg?MLoCr5}IXwR2qZT%Xd0&Xr>Y=rU&e^mMQDm1FpWIex zsxH+@+mQeqg7qc109nDYGXL!cZV7fSpX8i1?bUTkVGx%8&oeOtXua`>E21RlI#a`F zjY~LS<qUusq_@KyRVdQ6K)v#&Y6y@~Q$Q@vWbXLAgQ<C@-;1JVW-ajY%0|AGINWV% zy6{Qsi<g}$YE<=gK3t~`$i2AK4^ETY6ME5sHZrDz$ZT>gXy_n!bW|cmogE@*iUi6M zj`0??o)!oRw>iJR!$)&okwyoxLZ{Vi;?r2J{I-G1u<J77N7gU*K;$gvZ*{bORJ7-v zg%bOhXm2%_?Rg;?@#AZ?#q)_~{V?EO$^d9GAcj?hP*I|dH%Hqa=f(w-)f*xYS+-ol z>M4fyc<&VrcNJaag<y!JS(L0h-2ec?iIXig{%!&p{ECXi`4>pLm8ekN#rko?Sb4MD zwYJnqhPH2?#zJ~*10TfR<6E%FC;_RX=|DPhBE^uh)uFz>H6euT&dO*eTm@!`f6lAA z0E#0{0t98tc{nvCl?9cVU4qoy0)^SRFoD?>o3a6z{O$xFZ~9`{wumlm#u=+;DDXdU zrFs7!ZwEFjTHQ16d&4aN@2MZf(27m)1voc~<O0_iV!QRN?ccR(`P&v-qbt&GAh3Od zGar^Rm=vX-TCV?I5uZerj<S@oZp#|RkUz-p=*bfZJxu`2WxffRxP8?3t%&a&^Su&_ z`;*y7(#lgv*-CVd&dDb_;lFRtYDg!Ho7-*X-xX;ClM3IthwB4;N}F`q^f)gC;M=6z zC9|i=8cqx<%+Ni{w-h^hvd!aG^y|kL#tOf`3V=TvWST8yyItoWZxv_dwx`j?<%{Ur z?WXmuOA#715mA<Q0=(bPu8~D=E1%raR~@@C(#d7YB{}}}9&Ni#eO+qWvFnx*J#YUQ zHa>CusDG7xsutVt=_zvPE#nuQmGuh~(Tq!a>WlwLoy2N7v_=BXL5^;c34y<q0cS#e z{DGHQZuUN*^wjD)W>?{>FUKO)0WJ6st@GJXc1xK<7^MEZLswIQh|cke-q`EoFZ#x^ zdj&44n_)9C6#-x10LkNiXXrCsV$TePzWu@e;dwd0J7Wq^pgk6B0jx!W0NT*%IVpB| zpUqs+Cq)=faL`wq;}5;FSlCk8kxlfcd_xzjp!_E6E1&7Z&uI(Z6OA~N@tWLj_j3gy z=vSaIFw7s(oP$*wQ?bx+x+$QtHrTZLS+Ox4e`2OxpU+F57z@`#Ydq-N7c}i6rsbDs z<5&w>6Ac$oiOjyxety{wTLT+!TA3DWRJMgP^!aa*AV(7LX{#gI<ua2+;g2%xIG3ak z=0}|nwybTwau-qEwVr#a>V}uQObL_6w%lEM@Er%o#dxqsu~M1DSUUOXLYiV$<rDHa zysMF|#XI?eNUK9<Iy%#&$L|^(GPYzXKGIMUjy)WHf>`s;66?W>wfqlfnU{7Npy@dA z4LI>B&h>tESKE^78odMgew`kV#<~<2J6mMLv7k;DftgQ4Z@J+S`3u_Q;{h*4wJZAa zVkFZ9n$^*<k4y7!W2Ze|ynelgzkNyun@xcko+jY7v-%XeFYoW@Klog9JxvzC+no<A z{<hXwrjKPl=e1P*QlvDjzbO~!k!}k@SILaEcpMFXz<86cib8;$N+yRd(<<uPZ4rvY zm%mdCG^o8{3YmX#Jzt%LtcuFAD)L#QT1_h!qK6v_n|lyy12mJv&cTQ|WZs}?rKB(8 z2$3Q64Y74g<-=I6`wsKtAA~h7YePgjioZ<!1ELG4Qu~0ky;{iP>&>EKg<dppq7e~` zYLzKX6EBa-V1%|PjM+(p8K1_yO$LZa|A0@2hcFN%1}}-h=Z2`|=Q<3d{;fI$VCr6c zMUZ|m6cTP~o*NL=B%Pfwd;lr+j8=KvG9tsi9=OlUiUVMrCI0v4a%Fw*xMQIW6r(I= z>61vtt%JP*F0Uk-;WQzpwtD;3GPC0x|BFE`%T)6tzL}|uI<$or+P2Q9XS%U3;*+Tv zv`5a&YwQF`jfOCbx}zH_DO?kcklE@y0s|H`@)UU4g`94hYW~}3#HCcVVavnEKQL~* zJUki!clF6~(9E+Z-4>`M-2IAx2Qi#sKq5d5V!~nGpo?bz!@UP+ev=`SqlNX|a)F4O zJ~ype_{OC*Jx6i{o>=)$nHMe<e2icO4BayBV!Y?H>$)Kr_-jWOtpKzdjRDmey}!Q1 zrSi*CNRoYNx36HKq{oy05CPl}dGKkUpSX6Fko^^r<c2stqbKJpv~?=$w66(mZ(?$` zKfmq4*&$|}GuP*w+iBlykS+yoe;Ieqj@~6A8odw(>c-_Uh^Cf-Ea!>KA&8vwWAuey zT19yP?J{)6x{Eh^tr-vqP@~0{_ae=j+j8FGZ3{U!`<llWRV}|;BI;B5MTsQPj)CUA zxv^qP=b}zi;DbH|fdTi{O^U9@JXrffazWk>JTOtKsgCxmAGu8T;@mC_AQtxXscu<h z1>79n?jAy3T~TWv^G4{$cW6gg_>maBF^KGb4h`QKkO!Dx0YT`YAqNKQ1L8B;;#8nL zZRvjDX4#%s;Q?Ww4^lk7Z>~e9I<82WP|xRXMAffvvjr%nG9M=%dfCn9F>^KY-1Q#J zrpj6YKs2W``$dnwW<Jf06Ba0D&?xRAa`nm{Zx3v`hAK6wF^zBQ^&~R>iz#3K#y~Wc zbH`H=6#&n<Tq%yRfRe4zDtL!bSg^;HF>=>n7jfr2PCAq^?od-0L2s!l>Q)foF};JN z+)0zN={3mXZRNI_fj>OY@0!cRBeS;Va?5$|S0Hao<vQGdg#@<kJbV%AzKEghV$<e6 zI_IWdg;~~~X(5#{7c~a>GV;ZwKhg?BxB++wB7~hAwxV`$FlEnjMe^lHXc<d#+qW=O zX;j*i1=+d%r7LX<G@32Li9>-vfv+UhE?$>G>W$4P#NE9bh5NaGd$J;dS{0)_i5LB; zA$bMc+Adh<F|vkzMq@0i(8{)0_d7yW?TLjV>RqLA#lnAj5KH>reIKF_4Q(wr$2jb0 zNpG$z@kI1FWGH$<KTlcFIQ_I4ywIyL!i8Ksg4SL=o0US7(#nh79iQrK%|On5S_SRw z+*SM#HZxs+)|fLN2{PXh&cV0KdGq!^GH|Dn-KRVbR*r+5<8%zCpp!-Ge>$8BQ*%Q! zM{wxFnTMHH^$}INf1VXaWW>BaI*PW;LS#enl)hh0$AcJXM!K1xL-9$5_VRK3&hhGf zSHuzXrasl@1)en4)?kG%f+5Sll&McgtI(d#>C+x-J;h9CKcBv%jW}ED9grE{&s5ej zO_Y+oWOa13^O0i^!pcZs=!IvSJ;I`9Chyc;8u()WH=^b@15x4Hr6=8(*_kve1dy{& zFPpE1c+zK})q<IsXoN)xSC66C8#ji^2S$MX^ZitQ#)O+>(NjsEV;4hF|NF?0%A?bk zJcK5W6*k`qd;hB9S5}lW7wqM|jHkY%pl{M^;c+)1azqdPF9U9c@G^9L6QEW7iBaUo zct4A~Ejjl1pchqJ@nBCA*zV18b^`F%Hc~8SUyRb@eQ4;y+8ImQUODkSqJ01St3?@~ zR~J0#n>l`egdv1u>3<G?((jiTG6+R$Y~>1k#@Pv)A!pr<<Re{N)9J!QmjCt*im9sP zSf;--|8v8JuIP$E7sd})#^S#h(Q~iqn_NE@Jn5W<-!HQ>Q{+GS%`WE;Puk($f3H%8 z%KCs7L)_Gxl)-8{UTIEm^3{VUHvH*=^`Bk;Umv{q;lSUbS4~lfdc88o^ok$f5mP4- z>x2A?t_<Z`?NO84Ic+?499T>R^L&%UtRLf``BGPcO5~t|@Q=i4GVR2S4!r3yuI#a= z!%V7G<-?_MN5m0dV=d%#!~p?&d3qwpOe|F52ILxTn1S&0?;G(E*q@Q}*+TFsv{VWf ze)MB#={fkYSB3tR_Za1M-_P}NBrFkMu6Q4$IdU&Px}lalHzkvGh2%aI4+p$8ctnt{ zsYafz?(QdRN)*Wd+lJ|UXIQ(67wW>Su;}qqwr^{t(}yj8j^rxLo73==ezs=8n$p-y z@?BqqXul@C-aq;)!xTn+Iy$Vkv|Mw6Gq{7Nt5)rqoDlV8@P;9(WOAJ(wP(K0KeBR9 zv$CVrXEmLFnKit8EL72tA*q`7x;;-pF|YeuQ#mW~X5mZ#efu?yc~|G9=_f5)6V1G> zNIXb>^R5D2u<*jfk`Y_LprbE`oaa6BBrtOZpTP<7tgMdTcQ3eC98oU1SfG0BYUl|O zyMdodrMXy_v5I5=d@IwRI?y+RW+Vk7W;)!(6{QI9%k2}cH9ap6aQ4ZfW$h7Th`{FM zfdWQY;hsGm5sAKMFe`nxYIh@RJN@a0;3JV&w5ihi%t)b+*=FeZ5X+J*wl&RpUJA9y zKD=VXXW~;qZwNzhZ81~}nA86da~*u{2p&&v;QH|bIk(bjNYCR06}Cz3;4tjbk@_}G z^t5V&NMZ!)E5kM&NA&G!ttbng4#2n;T&K8Z>3%qr_o8sy7^(=K!=mtqrOi9k%4@>_ z^yPn<N~ST4J88KQzu)|#Ao8pbX0eFxE0JC4U5WdnzQcc7M|B@eJbO&*e0%jz&3K5r z@UO?B1V?0p09`xJ$K-zdIKS=HM<RK&8`f7zjDer6e7T<)_*8lRBul#L<pKBVsozqY zPfN0qP>C`%)6|guu-JD_hzhEY0N2&<1LFg|qx&P{lmEOuPJrF}Dk~!9)b3%Ux)Uw0 z4`07<r0>PYQSh}O1*w3^Gmm;>=nrP*f<6dIxIf|>dv?^mtKqir5R>nxncIU80WGV= zbWiz=H|C{x+dr5N_8w=XN_GhBhXLE^@1_%fMrw^Yyb~IV9WvP|0Hquep%n3Y-^2Hn z%Zw=LL2V^F8Q9yS6|hNdbee@xc)#TPvnb@gEjNJ9D#sSVkpK0mCN`MuR%r^vt`r8O z8Hx!9eLB*5x8=&VSRM2yV<J~-RWoDtcwdbDvdM*(Z6u|9lB&x?6~#X*1$@`Hos4ht znXB$(QNNN0D21xth2+F)(@-br-QOGG>w9qPO9J)gpAZwz1?Kqs)wbC9yuqa(HJTMJ zHb3Z|yV_cLPxiiK1?2eUYlU2`9!-(@2BEsYHHX~6nK=3r__8J7Ku=eJPdGwM$t%l` zGHS)B(e=IE6nW;c=UB@99IX-O8zuid-}Y4?eGG0$T-vdUNggtZyTDBiW+tbLSH5qR z5r+8v`u;Vfe2T_5bV&TnBKGHK#V7v#gBvxs@XL}R?8wj~yB3`7L%Abx6=zD7?^cff zoQXb8Z=OEmWohAvDEooP5cZclzE=~T5}n6~P2)FJ5y;`G73aMPqx^bUa=mbPr=S9U zl8o56^H@jDacq-5l7h-lEj{6xbrR6wmfFoOs(6Hd-1GaaMjLIuc@}mO0SQmZzhFMJ zpp)<aq@R1LHRb#DPd`iirB@zJkE-rfyZW3BW`wi_i#|U~+pHZe@JvnH^h`<^@I(}- zluEUK^o&KYg#3hB{v~_og_^*v3uB(gz3#`EmdU5J1?75i;v8guItWW;)&Cj`M-VY5 z=>4f#{qO198F^1K@;5eDYy6Y;_0DFgQbN|jYU1Z>C(NdfF)U6p+QKxmQmn7+CY@`` zK`Ml893`-&f6^(c-4JnVMQF4*H3Ke;8=`}OI<!$KDA+rL>B<(@3G(fqdeNQxwnp%w zXS|n95!}8C=FGzbFxcu){11_91U!)T{rBxo2~y^OgB@)9$umL*KLw>|L@8-5;lX<O zo(7RbqS}s3O>m+^MW%PVLrgcw5C%-*U#XgK4fD~kd|~*_;YjN<fD=%W%giK*rU>5P z4p8VIVEONd$yma#9tZLv3j<t$uskhY+r?smyw;Ra#TToOuDUUDyhA`rsiSl0apqu( z_(xl*tKBaoC{p_$;rODHgVTWO*aZstUA-7&=x>uu6~RwbdMmLm;r4+i$4TBTXGRqG z44C=-_3acHe}pjL>a0R))E!RZJ0kwRDWLpjAis#|=GX(TQErd=_!%Erv|&2+uH;&w z-^IW+4=VpJ9%>*0n^hE)Hxlj~av3sXW4DRwsZ2!>xbfit<I<AVvzC5W!YJBCO5f?} zvmgTY0R02}*QDrcZGO$LO4oo=Qj^I20#=<5e`->cv>?gyBRD4T_!DYaZjIz@=6GF* z<TXQizz;as$vVr>Jkz*~+{L{mik!i8ZpjFyp#8mD=~m}aYZ8EJj}a2YSy7mkaKDrp zDX;zXRPeY{!-I7OKS5-IpjKe)ZS8`i$>ze5p)S$5`^_tP#%5e0gsEjuW~;r_w=Jtl zGA)c?=>BakX3j{(MTf>q^Cooro{@5~m7Sj_dS3g+iJ>)n%*cxeey<A#IM_LKP_Y-? z$`<In7Wk*uX!e966&S98TR4OEof~v#-wVs%0|bI?Qx+<DWWAjmxjVWxiG?pHGgsxk z4O<9hQr})ES4BlJRVH!OvzpzYy+jhLSCP`PJ<8|UcIY!g-_J<o3AAhQjolQJz3G<k zdUZF4!lz8g*1XP2;gP$AE;>X}n06|i?Gcqd-$6JTpr{P|kUWS1+oOBJ2y6S|Zd^cm zWsQsPSy^^CL8U%G=U%2u|4qU_sO~rsS}mgn<dcmkO*k*Lg!>5DMI++e_uZLXLsR-x zi}J%krcn%<UGuir2=>Hba^e~P^2Ol)_1hjj;l?}0Z`!s^%=Cp1&!Xkn->hDFlZ?{1 z^B=yg_BmE^V<QoQNhe4$E+FkS8!WK>@E1|d;vvc3b%uFDbDa<DtXc7d;^LH<cM|J< z%rm`oK6PtpAH_xHE!lz;YuP3de&ETg*u_1A5yhe@<cPqBxRA5^k#=HS!vj`z=d=Tz zO#KMvH0B=X(vc1>ya+SkHesSb*Vh0s_>u=WePH?eG*?SF>jC0l?7#N|5dMU$L&)9% zL2Udj&Q}1mxJ-?RMGw?jbw8J7ra#7*8cwWFy(?iG-3Sry$#=+s8PsA}mn2#wt+gLC z)>P(Yi7yx13NXN*Ce|AHlv*p#L&)d!hZyi<q4yCJcJ`DK^z^`GbfCv*rr2YQH!yr& z>=rt+y)%_366?1X27Zm;1zboR<@TPt*w67Q86O;fP4kd)%@eUDdx5PHB&nF5kw^pH z99`!*P%%eQBAY~x8axB4YFpV|`dEYU;T_8b!L#sGVd#JfQb!w>C#?9qI!brMz=@PE z38V7ti>aQut#?AQYg7ip96G#`K<AHK=C{Hf8uSZc?jzolRLr~Vaw{669X@8qXz%J} zPBj<h%kbKqKaIp3(JwySx>lIB>U5d4sYHl880DY}xw^B8ZW>BJSi^sGnyXbggESKx zuBCMk0`&SKJ}emDZq=gY^^9?b#8(Q=?d6~0PX&q8OQ5I|tMaj1gJEqrGb(JY>ZuR< zO;7lfTt%@Eh!NQ|``}<FvlMm}1r0aO9P`MhDJn}wi5#_Nm8FQ37>nc@<P}%tg(_Zm z#XZW#7@0)|u304GF@U!>=!>I83HH1skoN2W_InH}LLMfBbGa_Sck-cmox$Rd-n<wN z-M{wDD;Cbo!(TB-*;X}KKY2!+`-asA*nWX^%-H-{U<G|B@fE?v>T#3YQ`~QJ#=7S- z=C5B+mH!=}5YC)sN}j%5&pPl@?LDZZ|L9VO|H?#31ZmM6#IO+-4DT@$VrC~PgFpL& z)gZJx`BN-T@xF)MaK_Phtzf5)>_?(do8zo6yO%rgV<$Lwm(sc!EJA5qt~xCZ#L%>f z`D+~F=nKzBSqj^JjB~>JUTZa9uRMO=V#OdD0<<kxNy~MjNodgw<DH1gZ*A*#mqAZC zSS~;BXF^sq=odEMfzX2hF+5a(sU+M%J(;H=_uv&r<9YCi+#rx~^uM~mNL+*R8B4<= zuIq|%Z;(1bg#F}Kv!<{iTxZ_CCTD&+`PnVjtPas^?rko$-l$lE*AP1Cy*NL9@Kt&i zi5>z&FNhi<Dm%X^X9VVvO2*(j@dSJgWw-(fC>kf&+$kgQnB()~i#`)#hD9WGLQ))= zQb5#s)$8m1n3K96<Ssu8llNJRWnmMO&Yt3b4h7~5U0dT0Oim9RSEWrdtRpTlA||?y zA!k%onhB0#cY{dc3wrdTzO!T76=W+ta|9&t_hKgLbP}I0LsXspEVrj#N7k1E6>w&r zS=fA>{>D%5#oTcK^AeY<&A9rQ?|l=++p;XJ$yIfz_Qwn2)ZHM&>6%7%#ou`xE9-gO zJqkZS3l8zSvzq|U?K|Y5-x+mH$ebiKe%N`r5q{-;lv2h<Y-arf5RrO{V3@}YIg{`L z5oyeoUtJXOGZH(d$$%K9-3fxWa{tutu|@ketLt8N`1;<Cr8G!nww*K9V_(bpdqyl^ z_nYavDbB^Wi(7Qk?mgo9-=s1^{Iy$CO?|kNa|55nRPn@l>vWf!(HeTv#+nNTp?&1m z_X$mbuses2Ag-P`RD`%4Fqo)5Luh=86ZKqF#MBHRUYuqwKa~Yc-hCL@Q7ukVc#Ugx z&dKDT>qEUD+uBDB-aGeot(YR~f7!x4EFvSnZ12ejNi3gw*>;OFGWsK2?eKoL$`0L7 z42##UI$2=BW3jJ(&OsDw+Fy5<8S(C)HhgDzaH|K%43H))$jyKK6jjvwstrR^%O&JE zCjyH19P$p4AD3T3avscM<}WW3wPTAW`{HWW^3JEN9xh6myMhIr`Obd-BBo+^YzPI* z<;bz0y6s~~IcSnn2^sSb=@<Ws1e}m4ns{aPNV?0tA4}TxBIVrAy|i$@SabM5P_LIi z|7anb5V0hkE<d0qXHbj!rDjI}{F+eCg^|_-Sn;3tjwK<mOv(A;ZM#RW7N0edkd2d8 zo7VrU6s`N0F>GNIclt4*Qu2rS0)ffHWrhJh$^n>+ha+<Y&mvhF>0XWvcMwTLEPbc) zK3p5NpU$T9WH{#1>LGanpNFmb8tMr#@<cJn%0PYmFZ*A-4kSlR#vU>}1rDe_bD6P1 zwUTvIUlBEB6B%VzzOSD)vES)6Sg}R~Vn{}us{Psfd9RApkT43!f1J=rQ00Hw<w7{U z92iJ~c|Yu$s9a1LInT_tl7&fYv-KduKH%j#O?GgR^~fu1pCen2&)R$FVg1?zd2!k! z6bZHDD>09htRXx`;edHeh`C){(+Qz4cDBis70atgmc6b;8wzAMv)GnyI6pU%aw{hs z%ho+jlEk1QJ^h~J*)+{pj$|BOPFfwea32jjp3T-Uv$9OWevzeN_hgB~V*6jIS4ovu zFnm{Z%4BrAXD>Rycs6ZoH|dtGh}nKL5Cfb5SFK1KLdppvZP@fIWjExx^&|xP0`fbM z-TCy<zRCR`+sB+Fy`}|V=1w$oZQ7|kR||i3$g)Dl=IU^zfa6elA3H-IW@$;LH9L~> zK)RZqQsja^RGbtO%Ek#)hhku+-n6X>)Q6N@tM+A5C)+0!cDh9|L)XDxO5yIS*8~7^ z;{}U9DEL3sLIN7+CF>AZI!zLgl@Jkh!_%AA>QKfDq!K@ZW~g0Eo@?^TfwoB5jN4AY zl3XKawB%vuEBnriWMP(hicC|~myEmy%k97F>X|*;(L`_v*|+w*k3q9T-UK{&4Uwnw zN<FKv>O}oqrs`nXr&EWCJ!=pB!Y5M~tv1~q3#thL3Qo8jEAtH^pybDJ3iHSM4Zp1r z42Z~4)}7cmH!`W8m$!;2wFPCO=B#uBxKJs0CA_6Jp5|$+_%UL|OT5;qQ%QnPB~*%S zg$uvrCMy5$jTMWT9|%J`(sXu|fRy3nAQ)LIn`{0lp*?rEQV^J8-Rr@Kr9AY*@fl(d zHrneU{vlz`MVh@Q2ocITx-0(+fw_EhRIgh9SwVV464#~6`QaPDQsv^k=2N;}%_ytu zTI>_k@c7o(Rt|jb^_R|~!>!5IBN4M%BagBsk^A}Mvm%%gs|Bh~!>cQrCkX8|ZzH&% z003h(6WTWkY`j3kBT}b(ivKFV9Br2@8sg2CciSX=Q>Ec(#zrednYnYy%`w;of^Nhq zlh9)hK@Tvp`g<x$>*FO(Bwb)wj%oSJQ>{$DCR)a=Gq2Jvs`cc^3c*|zfXz8;v#qKM ztTa_5{n;!CUaBX5(QV12Ukz~M5Xs?^j_l-(mJR%K7|WBVqM{Z$d^aNhV*R5kpfN@L z%@YPYH3}hL6wJc0Swi`Q0A(U9U-^K3Ly=SawsGx^)8%Qnh|_x7>vyCjgi5lY-Zr9u zMs4DR>6m1q%sIhLaDw@(qyXA}cl`@OJoFu@!j{ZkKBUz3U0lvQN46ryPIJ817gpu` zNJK!GkWpRl%}!1hgSnk}ZjR51jZTsy35vDaN=o$SRd-CO3V5>*{aBOh(&&<PWJSpg zxwMuEi1=h>l}pvHn`Yy!1LJ^pGCIb(C#Urv=W;7q4^4AQK?uVh>Fd6~#GAg64YPD2 ztp~;k{}8_Qs%?e=LpzZ|1MXM$ItSAf0KDrhW2v1Gns7wG4=q@>(32~p{ASzt;ShYz z4mW~b`o@t>Yv&EZk30%gIPv|dlQ?Ov@m+GdJE5e7X3aVo(P|YiwaUqQ=u3KD7N#UP zCQ>%#UPW8}`+-E}+P_Vzu0fGxU%BEe#9#mRe(alFB}ux8gLP`d-fF|-|8``(YPP~( ze)7#;<|&Id9J7ptosy+VS-iddKffz0SYkk|HRI-lZT>t7VvK_&o7NE=mcGh3SVM<H z1x5>SqpZoclOMO<Y&#Nq8jB~@@fW;Q(zF!QVL-n!0Mils-*_Zkb4Ydc{cBou!>elY z10n2}KX=2||80=)H(i~-bWY9<j>=juG?NXT18H#tU2Sge%LIXqVrEHwttWwsKe&E_ zX?WF4^ENWJd%Awhq&2{cglUf@&@^XY*P&JHbG^{=s3`*HYP4-A$+t15W-Df%3os#C z?2YPj?Div`swlmwR!7rxKu;&7(d!u-q)wdm`HeFI@4<oS2ao0+y#6A|gj6?v;P6i7 zd6B5P9$!&xnW~7m_6h<kqBc(_6T{A}l973&<0<1S5?)^OnouAP6I&$DoX$c$9`6e2 zB7eIQ8%F!&L_)gw#aHCT0;9&{+BO+f)SE@qyHLOxs&qb6r{6kvcs1iTXAIGDaz6jt zH6Gu(g6~e_i;kFXZBd*A`{xEqpQ7=9hR(vT$u<hZ@5X?QT+rn<x*I8V8v{mngVK%C zqNv|C296$Gq9Y^(X%P^SQYq;Y3lI?j6%-YdkALBP-rsZ1bIyI=7mq4U`gi8NXKRNF z=S(7-@Wil@h-KmgUib^eGjO<?p!w-uP>#f~gyh@Y1TIvTx|fh<Uccb;$tQ=!!!A9A zawWrjJWTUXE5D;eXy5jYcO{OrZ1zvEkW&gUJs{lAR~xK7lRpBZD@2IT`G}UEB9~~Z zl0gs|i?9Va2zhJ@n7DBL=fal`d?X^n-!a9rN6|?N%rCrnS;c#WB6y;9I4CsgLPx}a zwohN`{+YzPcmBM{Vhs1)n^Nr`#D{BdEAOf2rP$qg*NSFs?)FX4%}_86=20P>vI#E1 z%AT<ODt<$r0Gw#M9E-<UxkqRc<UV1~kZ!1*Ao$m^=4|Qxw{v_MJ&1fWCIPvGrL~!t z#_R2$Z{6dAsVQ62+#5*XA5SQ0HYQNl&o?vrJ4Y_)4xNO2HY@)A`Lwo;_~`RHiv<$I zBUrkz(6}*!Dpy@X%u6{69C{Z{tMY%^!kRYBY($&v8Q;YAgT%(AhQ`42PORQIwo3qX zndj_FOU_1Cvvi_Z>a9nA_)UtHocC0phIj&!5OgXH9L=NDC#x7F-#G8_yJO#sB>cH^ zMD688A=w;b694b;kKwzv5*`u?V(Cc_&ue-Nqe1uaj4Zq>!cslxhSjim)MrEx#4Y$1 ze!kwA*}Pf3HRg5yCWd(N#~M`F<c2S8X3X2b26f#q^a$L4G-$4Hf;jA-9j~ODzx$Pt zA=9hm_1_z|dW4oqHF(s!B|^@w2~CS`xsx@_rrxhi=+|K6A%Q>A)F5_3WZKF4cMtV- zTR8Tj&c7t?<s6B*9umBD|A~#oq$OV$IeT4@*a7o1A#=yxk^`U)Y+mQhSW<k`!!FP$ zf*JU;G5#4r9T^_+diEX7O~OewTJ|xfS0wjxZJ!pn=t=%mA&}w%?vYF*_ec|C3)+`* zY>D9y%yFjIjW-4h&R`e8fWk(Ybq;un50cQBn^1S}!Br(f;~wz}%%qXwpM75Ql11j- z7#}Y4?qxL(cvNhrQ0LF2n?vIe&oIl%RW4|cnbL3k@&)s~oZEl#keZXg!In?KNb2gL z-J>_e11mr7)!wQ1z1<`DgBX-DZLM)G_kC6V4Ba3AI}q^dKT}ACQn?0trbczRp?28y zVqkvV>`}9DToNZ7=+ZVJP8Eg6R-!JL)3u^OKwSKLv#-J?t`E{662SbZMWL(ZdI^U> z3clF(FwWJ5Hju)Wu?-Q7asU3ISmPU5`$_v7_xs389S<HnSfAW&xDuv^hg8&crG%yO z_KO?{M?m^z`JK;wb9ysO)EX_=Ppo}WHvZBN4;fPJ(5DK}A_SBFO)pL^e+&=DK&S<+ zaew?(L%FU+&tEYh1V7_?8HsmfScniIxKHLooM~;n@7DKXqpZ3xf$4&@n20+6@sg<^ z+H~_plkmW-TW;pM4<mGYA8HaauCxl>B5uX~4R73BqZx^m1^$j5az3%;z?T0a=!5;- z<D;o?s?3d%_YEYpWxA(?<!jZn);AqzC7b3Q=|A4FLqg6~@cjEyvVq5`=sP~hB)%~Y z54r(?etCF+AL+PJH5#+&??1$SoqwVQRa@=5;;{U+$eLJ#9m!_ldw7rbNTgyDptS{z z1AJNua34Z4ryvgt)ABjNe?-XH5Zb^*11;A+C~WO}tE6*9VDed4H%RF>kfCkRdhaUZ zOd%00F?f354D7Q|qn|C$pbpzpKCZU`6{sW&zF)3g;0pGFe}C#7%_h8Qb*yGWH227q z$5NKOCLnJCoL~|O(Il^{wPw@cEIOkE&8rwszR8t_4VcbfaErP7eVeuatxwY65gpb} z;%XSqLBKr3UE$b3DpX!!w{g04@Z2M~uhw$ITS5-zZlRXhVKbqyV1GrqnC>%4y~^`N zJ>jYKaRdN0i_34CgK(QQPb${DILY`<ffGSj$V&l0vHMNb`7li1DX?dsh}|jlDPINl z_zv#w)ev5)^Apk_XnX0T%Rkb<t1f&;0CX1(wzC^49N_8+s9rGHHWq?n!W*$83cn_> zV_dTg{S=7C6ZEXiAe@{k(LU08ZsfRMN{^0W45axgjcB{so7eNF`-+C-C8@YUReyzI zhneLG4Z&U1*8rfBG^v}E@n!yaXodyg)CwVvUt`Q&4c!q+HpiW#J4UompgA-b$2LHQ z_YmZilF7PsrSvh)EkjzGBI#jryawrHvVbs5^{-GVH_-P_@^Ld2>S%@su;q65l5iSZ z_5gN1zg2@9yH7~dJ%}Ajf=1H?fj-b`k&iCqo{`rLv$)bZ(p@>}<;Lw9=810)cvX8P zK>eLGE)d#Q^1Zu8g(iTmLU)oLQYzpCwXJavMNWs~U|idF^hs`WkWzXYz|;du0dGCv ziRM<9`UrZ+ExGtzJM;TX%`K8Yi&vd%$~DLOJSqgjg<&z973g@Z)XTrfWf~x)3ACt> zR8SeI8Ef7E{8*wGJDR^vjlNy%a)S3)K?Rw&?FdH30k)m@sh8WJDsoHuTV5SEyg5?S z`pWR*RBN>X2=aKs&O#d;2E>8a^1>KskMYQ}lcTK62gf{Lv>`z5M|uH;uJ>P2JEp;8 zg9<D9b7n4)^oACV-Eg&M@1vbbvj3#G){Q+yw@*GF6)E*p=<V_xU2!a9-p<OhPGSy7 z=$e=Yjv;`jTv>7IcewRS^o>DsLgYuN9@@J!HdX+U^3Sj?`v<MepyI}R@u772S67QB zsgugVlS!d<80(bMn@sd^U0geH=X1#llN~w6Lq^%!nn4vo(92S)y>g)y6`#E7-X#6A z+KTf%A^csX_>)oaY7#skL14*~<%k(M<mMr#&W=dg6j{R9ac^jFmMjy9v8`0GK);d0 z<hRHmxGCT*f`+{!{3?R~b&@g#bZw1^YpF;9NSr{(E4&Ek5mm|ewCWt}IN;(W(D+`q z%P%)?u~I-;iamkd42(>1fuEpdx{pX^eB&aVn!y|sQb530jp>f08)O64RtkP|{vj1z zp|_*J2`roNeHn<r#CMetj>%1Uc&h#v7IFp0;7Qucsn{dDP?LQn^Y8u?HlHBo%crR^ zjiE)c?oNZxuyj9__ls5>TvnxH2F43gC0T_Zdq&R;B<D-vtBjxuCS7oo(ZD##3NtUB zTzaqYu*{ADo%<v6Xef>E_C+&0!5(@7yq5Mp?CkSWV*xebfc^<>X-Hznp_`~&4(U*g z2jXtDiQz|ve!B%}*O$~t9*t7@p*fP}NYLNb4Q3QyW&(Q2mKWWtHE*r4>Zl>{+kbq? z)lnw+ni;Na1{d%_YQmfCWDy`ffxTS+#!H`uTAAU-#Jrf(zU5T1nUIYc^@Da{;Wgkc z+t|<jXYqXj@SyXl`oRwZJhJ5ViK{hN?;~aF1MO^+{^XcI5p{&v)&VGjfho6#vA)vl zMuD`W>IRs10rR$Ujp3RqPdXXyj!2e(An}z`J4nQXWhY`8&>{|O+AdNpJIwfB3BMq- zv&J8ZL#kq6AgIZ&Nt!MKaJPfPUPAztOPQEeKaw!W+Y0E2#awiKYXnNZpLFFLT0J26 ztWvJ2sk%R{O-|1G-aR}`jjf)2;HB-yQVcBDL?n^Ks*|E#O6~ftUOwh{GIl@BTWhEt zcIgf~%GbKURRGYu%?Wgk!LKVwT~!GA@B$7tyiK=DP;kR@WG&Wc3vYx1x;XrS-HIB< zpCufOJI7sVw=ON^#TM0oU*3F>#C7}j;~a};aIB_({cwPrGE`i!5@zUrJD)98!3R>p zc&Q)W!DZ&3tl);N%nc>-{p2!M1Ch_SYzq#MmD9LbkT^b?<N(xUE8fHXltlHBcimgs z_IXw}-Pac}e)pihqwj}K^faJDSZ)<;9^6Rk=x=6yJ~@lT8Uw`7<!9W<cm=gwf#FpH zk6}DP&0Urz_4HxHz$X5eKU}yro7CLP4fx8r0l{%u>^|z-eA3KiMhuQ!LHYyX!{m_M zrW(UdZ9!t9CDr@!y}2$E1#I+c^2S_y_hGHIk7J2`x(23({52Ip)fZ5Wy%s~+B^{#u z+P2{;VWeZjsF!O2{kWsQYON*+rt%y&j}Wyeyg>i3Omlt7hB9fUx);88Jk|&_vv%jx z*zOSV=kfYJhtJySp+U^f#Lh#~Yt4&2--X&c?tBRO63*X96S&!aq(V>Dea~=5)3o?g z;i0ju3YIxC4rwwkNxBah@T{2GRKl9)A!m!Tf<OGb6^R=(o%fCW3teTM)cz!r?;f`( zX2-l4e`O++CijeGW)$ce_JT)jX<IE>K^@babJpBSFn(%{xs%(dq^)$`(Q>b1?m?^V zgEEXv^+CYLayV<i0}a5b)<!U9KFfto<3E`cBSV?$*b80gvM)lUv18fUpTX!OkLek1 z@XLAeVQJ2CB|@-oAPqj+2Y%y%-;In+&tE}1v{Ct~#f&u{`EW`0{_jsL{4WUmj{@Wr zufO}eaDV9sEw8N!eMV8O!n9Jr^}<+5B18Jsj_d$M?}(7Q<GTF3SL4seGQ52P<BI0S z>tkuz!@C+9QwmLQM<T2JH!EY)0Firnayf)j1Xr5SrrP9Ih8Bl>Y{WYS8c1cDV1B~0 zg~i*u01&YB95GLt2$}=nF|I+vH&&Oww7@Qub@cQ*kE(8b^41&?xcG|dqi`3Ciez89 z?+aH#%6M6p7y_G<I-QQMv76qfrr)E%17E#m+jzj$9N0O>6kk3Q3|k}iEK!<kv>#{j zGUJZ_K}M9P1^-!25p>lDst<X%8eK_o@&>&mR1OQQ``b5TR~rw8%}~Qx6#^|+BPD-( zr(kAlKe9zu4)V4(ajgqsn=*o$w^T8kynz4Fvqdhfz5sYkVbHvoa5Tw_>0PyM^z91| z#&FqAJUQM$N2*BNMw^g+O0nY2pB$&vx1)(L<Lgmu^r&TT$tNG9zjKMEtqJlB)yLk^ z2v_)Nf_*~^JJ6T<J>5hSO8>Z$)hMuDJn8*zD~kh#{Vehs-D$K0pdSQAgo?m{^W4WN z%aGDhMR?^B2Q{1n{7wkVl~#F{qw@A^Twiz!f|GEZG9VRLiTz$<`GuSN>g0bNRs^0( z?zem8^nqizjv#>cYr_8kR{6a_0%t*hxesSd#RrqYyv=7=wj7Lg$gHdH<L`bIBau>V zHkd9|Oyv7z(%rM24CLK)y~x$Di6cdf+Ug>15<NLQEI~d|@&x^hV<h1&wsGPv^&`5& z785ul+cUv=Q8G~G3lNr-3@1Di7|b%Myfd-Kb*2q%Zv*zK#%Aye=R}FLR2-`$Q7a&f z>)KY}!2R!Xm^yRJzZ4ffj`y>O)k9+pUjt8cu+(c4cj!1afeYAf?WKle4%9Kjpyu8N zbg?PM5=bXa8mOs%?t@}l_s~7woSazhMfBZ`9ofwtPEdf#s;s2&G>E_QCsz#?-C`NZ z5ydttWn&Nf+k%$*FnE?z(j+7Fm#K{KAfKVV%C`uWL6v8Q$?Q=%U)QOa#nobfp~kTP zn@bP7nfjSykVOaW0UTvNFi*GS8XVzS-|H|+{KtXf_f>-XK72AHr>Gz>u3@$f{4wNy z!UsNZuRFb0bv&|`=E*sL6L1r@vs*}M0TXHW>3$@3U~`aw44E2}(y07O#O(^6^%1%= zgQgFB6B$-GUm?ni?I-!nLWp*J$<iv%1o`0@ffh6}M~#-NJ83G=&Ip>WL=Lb3pAff^ z;6-9yL@`{rYR~->FW`>0URIUot%S}tczth1_u$+akmnko-}z7Uo#g^$Ki=H-1yykW zf>U*al2m(DB5`f}q#!BbK`;vk=JEhI#L)p>um3GK^a@2wtMQ&rikh6Q^so0bTv+b$ zYEvB_ROL}NsJ{7^f~0J4AZA(v>XCLu<v^*<Z;Y#Q15UM?-&ky{1)_8Q5%Ltlv45v+ zS~#eL)Vpr4v6wWLKf|FaUuw$8!|3=~G;N$_o&BDtGCQSJ!+mcONhL=+N;|i_74y>< z_0uw}5k@%OcYlla^poOkH=>0FOmYDmF;aA?RStsr^S38~RizUM;FIzEh!N&6&swGl zo!~vD)P(M=Rcw;xKw$R_)iH;5y&Xen@&sCK=4tPHZC>9m9sLhC-f^v3+jv@M29L-t zATc;cY25zL?^<F-Q&@0;W8kpfDR8~{bh*^Ga_E+t&O4!{5OBTZe}EGvYhFR?+sWrg z?3j6V$DDD_ncR1c;DjrIUWI5cXG9Co->ct_W}8RDnJ5rb>+#*uiC9e5b@#!l1Y{*F z9~&`3Qtr3ED|g3?I*lFSE9@}dr8~U26N=%HqFJvSCux-fcWn8=1~8*3o(S@Y6PeFx zKsRM;e$<%}^55CTd`GOA#R0ly0Sz`0AF{>7qMRJ=VLMwmJPW*-VVK}=%|sPNDnGz= zAobrjKHf^-s}tyJ%1_%m(Azw~DAGFBNH<*l-0ZB;iSb=Hc5b>AU3d4HV<rD5E1CbS zJ!tbnD1xV;QOtys>6r$IQ4(3_9Ye`DnAH+*js0djU}HeMP*m9U>7G06$PaiMkMTvw zGb*8XoxPJ%ysyV;me^x%<X$QcHmjU1{{q?rH-m`?fX61WxGlKvN%+(|&th=cR3*n9 zrXPZ^77ta)m3n@;r7yM$dv0uEdcsy94W)BYYJ(piyjD)O(OT9f3M>U8w6!M%r3U9B zzvd=IkD+@{VrE<TG>R~nhh0=KXK;vX&LJ4jiA=b!>;ZH2z#I7ajhkSF=?5^?=yi9y zzd%2mS}W^I)x=3YOdS&7V)Ai-M*}}v0J$hda4EVA`=vPng;f$HSo<{^^~igtu&P>j zUf5bVP{6j+5SS4MLj$SUSOMNqmw_*g^7D`N%zPu2mPoK8$!uMaolXVYPTjSZ1(i>o z=qy%8S$ju>Z!1rwIlH1><01?!;LJHFG0tkmJD8^64F=o8IQv13e&E=pe*l`bv(TAy z9g4zo<ZCPcn=(vcU{;Jy27GwqI~edKKhDzenQbH5(a|GT*Vz$#WzDvOPf++mAwi@_ z%{Si{%W9gNV2pCmDecNKck@`4lZ{sIJ|tc*ekTq>7X{9t2aAia&E6*+Tp#iQI@Vb` zX*+$K99J*Nk9HX~7Glbrpo-X7<;v&h1H5g&$C8&tDFS5p5M%KhgWMdbDy&GJQYXB( zU%pssv6*K~Pt^WldgU>CI@~p_A<btrq+R#a?$Mnh30~OK#cBXoe34(c0LIexm?b*G zz#d)1>ucfEYOXLC$~mYZ=&M_(r@^_NX>OAE;~5t2Ann?0sVj`3eJaDhuO;r}^2!eo zhT4a_^Ug_14di%m`kJoWV-$KEPOLHJW{;y3o~OM%d&5aOxSL<~J6l$5oE=m1y?OZ8 zu?zVvNxbV8x~ndqFNF2XV>K2PkC}+YVbFKpy5}9-pO0j27y8(C9yrEh)Ou>PEKG>( zQ~zLB_zCKKwRZ3J0u>2_=<#XG7Iazy<_~n%TWywS-P>>=ClOML8g#hp8z1`q6xS!W zf+h3_P*n3PeVwE3;&F8g2K)X%_l%$TaP%2gwppi){oDx25Oa-ii^CL3LErhNqbiLA z*R9`bB0sTsMC@JorGr_`z<si6=V-S_RT^?rBa;&`yCSh%nV!4_EaUgL8rQ2><f1`x zug^cWXZMq_;&t#60j%Zi4DpZQ)D`!Xn)Z-Dsp#|1t)&IdV_+;6Ekt=v@JMIjh}3uV zr!@(Q_{D#|AhNLMv0trmRzc-ET1SV2{FI=$F8&)*d3U|Rv)HwTLpL$m8z{SW<d|;_ zzFVcxb@5P7`r?aYXZw<TknlZy3;pd+Jwu#=CbIYZuXvcoLr&RDv<2%9a)PVf>uQ9t zaPS&$NB!LL&}yWEoB+6ue?7tO=%RNs1Uezmr`d|O&+99*Ri%_v_YD7o3t)IeviS*^ z1}4-YK}z5c=fE%5p8CrJsn={rD=(hEVcU$|ju=XP;jp6SK;|vu&2$jB?vr-G-&Ujq zd%LDkQ%d=UjGrN{$DlMRtfq;>Rez!7=gH3O$8d1K)8`1@6{CrOD5v)6hnG|Mg?&fw zN8^RDF0weVwI<I#2!my!+N+v71%Qq}=3lx>H?eciMBVy-{nGz2pdRgTX#>5otLpty z;a@zrqEi*f4ij&&wbH_UwYbSnZ0fp@y8V@_7CXjkN>A>2WZTzy|Ep;!k5~eoe=0n9 za&I+|*82`F^vRKD!sZ3K^holr!h<+|Lh+7=YS>4#?j+Ups_P?}aA!fCB^}I$^hJ^1 zC*5D5cX$3%)Bx>kJ*&_SIIQxvpMN$oYV(;p(xN6Q#pCfM^Q6kjl^3J7Wd^}Pj#o^< z%(KL1<@H9^@@Yk^u~Q?e@05qMr_BzZ+itq}8<tm^SLIg7wSt36S5o+|*FhVH9~z5~ zxRWhN<fgWyDz5dGZXOVB8Edl4rcgM>vrfbCSa7cwbX&H*^edRMJ`FXp`Muf6`{WEy z&7ipQbIJpa>T<Q}SCb!lyKE$cBQW^z;bwlq3mdr^J&a0osDtQVEO+Hq9p#(sS*NDG zVnw63p6^`b0DB7(`X3$@X4!e~b6{P#v6hD=|NhveHL@iQjThZ_9)BSBn*FAJae(!Q z1A!N$f`lA36-+OJV5jyvg&Vt<eN{!jPf9f)Ng!e+yA1QEWvcnPJ>$`e@Zeic>|{k+ zw50SQV$jAZyv9DojQ`fIZ>X*BgT9-cj<RnINmfb~?_RC_4euUdc6Ts&!HIQWKy{v_ zM*Fu+)tTimw0#GFgOj<%SYcp9F1#N}JvK0aY?Hl<Qi3>|LPl~{#SI}p56lj0F%@}Y zD3I%Xi``RN!Pzk>ISxP`(1zvqJV!VUIBO<xJp86nG+iYYCvSC!Gi31W!>mn>v7EZO zhBklkcW#U@!jUy(K;Y$ki@jy75~$8H7~0P)x@w}+F}G(mm>B|WC=1mv3z%k54G1u7 ziWlW}=^X~Vk2T$Z7#tUS?~7e5unFa!QBN5VW#yjA(A|G0q;VP47&6r3S58BN=u&RE zt7wA867tH%mw;*#OgoP6#eSf5xtJA#_|Bn5d0h2^o0TqqPu#d|lKsP*(~DnI+JT8L zlj1>E_S&bCxh?+4Raf<ZI#|gDwgW3y{AH_uw^`wj#4a6&<-12}%^-QTAw(nkGoT*_ zE9rM5@aG5l82#X*;Rr~n4T>dvj0gcJ+K%o4fWUz};o?@&3H*N}PSX)EI}^A?y3#D^ z=mIy0ot(`IyFMRv_Sw9rGc5U{4`DX0L)_G6EdP~-gNnRkKH=&Tqi|h5WGxDa#LBpR zbX%ln!R~6`y3+NK)sLXDK7+-Vg3#B!B9@(OMS}e2UCse~P#m9_wCl7tu-Bgx1jrRm z)5Hj?<brn(k2zHuQ2+rdB~|T8hbb@TRNO|mGst2Q5brdF%Y34Ejd+@<2Vh$xYGDZ8 zg94xVW1Sg<cu0*EOg=~okF&eXUuf-A-<YSNp7<)p{VI%n8RBCBcLO3H!0u~&)6X*x z8{>Ox8Q)mUxCx0MP79Hd)sN3PInGZT8S_bn;+YG!jH>h~$M@|n-A0Tf5CpF?2a|&j z2XoUO(uh>63EH+@+@gA<?LF3YnY%j34oRT9(0E!JU-^e0D34uF?X28&RKh=ro)<G+ zyX007XGJhmyKRO4t=YE3?*?~$qeFCVA?=SKyJ6)-`c>73TRE1ycNV7~LyUb?i4fKl z2*8Em00@w0fC3;Bds!ZzaZ0BnIZr2kekCnU#(`LHm#tqE2z9>Rb8+IQg6V~;o{YQP zA6InopFw7f$W?)Pjq&o{{JaV71+o0eS6)kBUs{+qG#0-7;Q7(Xq`CLwM$7od;rWxu zYWopx?n>Rpg4Uf+i>xsB>C`i(dpN>R#wSMv)B)PhR(#$Zel!HI*s`p^GK(*GTRGmC zUedhV8A{mZFxI{*rhe0TwBze9$;e0G{@DAFfY-JYl^e}@Guroal@gc^68Jlk{Y;3m z+-yl!z=#9Gjm9q5;8$)rHqZFU8W0~g;Dv{_K3EwcdPU2T7Qf`OX=Dsw7u7uoY_n88 z_%H+jDD3(Gnai<XJ;x1)f1OhSK8~<1)WZ|R9O1?=Hb4@KScVdM9|7dB#PtzTjg<Va z537|$q@M30!LX=uW72@RyX<gucUZ)EnHn_#+kZt;kjV&zns%hvnk(O|u`Tt7XqKhc zfGIF+6aOIE><WAd&g-j0<9<FaY&(ZYEV+X=I}#E_!dQTZ{51N4B8gpx0Z;xpt&iAZ z$cU~FrjTVYTxOL<XTg24Y{oY9m%PB{JVG%VlFn^5ZZZ7s>1e$Y$-nW0sr&s$rLVXQ zJE7iqzQfVk$F1mY@68WLFuu0qysP<F=iSo6KKF;iR;?VP7MpO32Zwjj!WdGooITt@ zdksSwEh5|i%Ueosfb?JbXa-?NQ~Uwo1Q<_%fPtw)MMv(O_j|?k{N5G?O$f%5(8vY| zcaOr`6-KVaj-K}F{%i^yzEchIJ@buuT`@#!_SrHC&JHG9SW`ki+#uk_Gnyo44aY8m zN9=2dGi1c@?z=S2SsJMcEiGDoWRi@mbuRdPMhMh@>yLdi-b@OUlVAJX+HIPmI|fn9 z$JA($DI5r?Tfg&RaMATq8Z;lx{Xpti>bPJOM@!)DraLAf$EkbQ3%Ogj_#bu)c>a{Z zV7bjVcYh$K@TN7+Js|-%FZGXY%-0nC71nu*%&(01Hw_tOTE@$w-1};pA!dkMme6LJ z>slBpitv~#ZkPySHiac&@VfnG?O^n+600yHfjz+HUmluq8TMVIatyNnQQCHXTn~o5 zp258<xvoUgy^v@3GZtc%&0_z@@OQy@$hb^dxf?#~`5fE7427v!`?z(3{EBy$$ILPr zV8tM>wEAMUtmMdvr$_g6vmzPj@4~6<=MEJ91<QoF8`Z*KR0YM}#XAYcRKp*SS;UCD zcr+Us{_6YjtI?`!OhFo;ySkXi4=2h-W0T)#=ehFm0L`FqZ`69tr#@nls<2v+pG$WN zToW@<Z>eDbem=tH5^HldmxU$4bZ7Omv^PvZ$R<StBj}&5(EaLUgEM33)HfAwp9mq9 z__ejsPPE9)AbiWyy6qfvx44f~+WQophxO3~gndHn+@3*J@22*j4<y|gLYvojjcOw+ zQqDQ&5-G`mxG{h9fK(adwo-Z@#6c!E`x0MxS~B$uDtF9xa9s6PJ-TPW%On2&Rzv;P z#K#p*K;Y7yBbBXt1wfsv;qe`u^e<gfq9w?W*!{ji7XU-l6=gXqUr@PdbX_%HqhG?i zP1@BsFI>URq)K%$_S?MTRoU5RUd&|GHD(u)++8(fWqjPf%2Y@0THMK)lhdp>?6&2o zEmOW(C?E#>{0p<S#D{)j_GB|oZwtgNoM&l%a1j7(D+~xs9l>E(hjdvVbk-N>g0o5r z$knVn!#j|k@g<>jIOky9i)dmZtJyRW`fbDkLF4-1=oDJv5O$)WIbN(J!4m1Aw;nlo zEh8d4`qvTzYSJ<ajD%RXT07WEJ~k+op%<3My0x6RB6Bo%GS*sL>?i*QvWRggaA|I< z7I9SVsrjoI1KLyQ?@PHMyhI|*b}xbW>k6inM{em6h$UizfcUHr=<IRO&y8gxeAM)H z?xebFDL2sPIPY7!YO4)^`gu~4P#C*e`0eOwmxuZaFWZG{E^|uXE^j}$COUYogzLr^ z0S*IGA?O^9Wi@aNpS<$0@)0dzFu?RJbWAB>z@(X|EMAhW%t^4LPQQDiG4t)gx-m0e zU^tQ6&S&KqO)5ADpMph^$0<j-AgyZfQS};U(5Dt=a5K>YC*tzhnmdXREJKKo=6mG= zmq<E|o<pK!ReH7T31Ag#7qRUC&BDzyPD>^#3l}Pk{(HIaKUytyVi^%4i@ITCe>6x7 zEdnlpP2m0NQ4eQCZStTZw2OF*Z2aC;=pj;A-KS|j>XcwOZ!1JPnpn7@#!}%6Yc*4C zwZ?9p{d(Vnpw0qEiC|A+No0uGGTh0V)jbk%7M*N+PX*(6o-TuGMMA$1T)udbKYQ9( z!xf(|8S)JkH{D7R(?zL0j&n%h_pH^Nr^cJE>D|aX^WMp%^SY}>lw(0flB0vD<bZek zeA13ateqpAkl=EA-;={w=Xb6S>w?_830z|yjzr5-4v|}th5!(O@^%)R21y5kHEV^` z`{kGw5s=mdZoJ(0N*C4EsQ*wFH76}z)_Q5ok|UQd6ON^7F8F3m|D%9m4OYAqzCw)a z{<*6pIP7GA%i0C?d(vb%oGd-EVJ`8py{179eMQ6M+>C@}l1B8BE>3{&gx`t8CHTeZ zq<4j>Vy*6MBq!tI1TpnAMduh*2v80NYaQ6=@(Fh?q;c;XM6d$C1o@V#k_mPqcRQ@t ze<WeF*k!u0F@x;w0|uQ4XjfF!eol6?VA8B<qBkWJ7l3gexZr^lhv2g)TheFS{7GLj zMY{NPeZ=ygAikJnnmAp*yJ`0@2ijx`Z`Xi+$7{FxrYdXbihezL>4~5iUJgZZ$=k>w z?K@|i!i$1(R6)lLU%CX^wtVovYS-wX56KY9H4UGXI8fn{SWfVBC%Y{jNmUBe={eks zPcLgLet~obmZO&+f3`eE=}eS(C0qV^d6eO$D~tL0dae1n&i?fRO1O1NyKW?Z5HeW{ zrA!b!S3<gRh|~xyT*CWuuL-rt*@oRK`R83!NJ)m|L=+Ms#{Chh7`c6LEOiN9w*W`a zTz#<w@5(Dq`(P}Fzq*s7JVfK;zR1UXYj0JE+mQDp*GU~NP`LNYNdx@Peq5;vxvmKk ztN$6=DTz}3AoE8K)taNi3Q8b{WM~S=Y5K@<+-4B=oq_&njyc1^*|M@xOy4_DObI;d zF+;rKRBi`kE2!+hXb~7bn6d=F?i`r(Q>NR<`)Fy&E*%DYgwOMthYwd=|MB%)c~v}X zlqvJ8_*;3asr|&tulCg7tnKc^k>j~{VRfJs$FjYN|4jauuhdMp>oJFJOV_We4&bZ5 zArtyfoGvEU=fcYmPiZ33pks)BH{bXe=SRlyAJax<Av~y2#BoF?WQ~SzJ*A293lZRp zLzex*%YQVv{%JG*s~@Fw?uzrQL&I0G6T0!|g2dmu3XeG|e@w3WJ%p&Jm#|%eRSWY4 ztx2L>F1~E_7T>>3{$UG2(B1_4aK>GOU~Kwb!&#%E30fGf;plKP0I|mN52z@U2gK~* zV$2#=3OEbN@<awTlFINqB>KSFYI6`rwD&4-6XWsX6RP$|N6qq(TzG>XYDHM)<0byx z`be0a@&bXLw=L$q)HGL_b));{dwomO8q*hi{@LFv?+TDe6-hs$Dr2a3>TlnX{E6%= zxn@j+YumE$XuzWu;A4w$Q3AYQqyhp;=QM|R2G`as!><Oq5Sc|+en!a63%*^1Q;aGh zQM#0|yYi){n*=FYd8Ot_*9rSsLd&k9v6v6gE7GnZCmovcIcL1FGMPeES+Ee(Rz<x^ z0gY}vA?L(ZSv9eWJAf?%W_SEqRhKncw68}m1U6>P6bf+yIDdI%c5zL(`f)O5kU3n8 zBSj+~F`FiGwKA0(QI<T1J^E=EW;cg0T{>;Xu7~~>tSfr;yE8oBOsOEGNo?lq#SVuv zWzwfbJJ^D*;3?IxR;sy(V`g!Ay+9J<(9K3PjP1JsI~(v@-r7k~4KCp1CTht1K@$Fs zTnP*hGiu}pfqov;2bD3yW5E4-L6BCOR5XphJ?4_OAG#;(+0R?C>sOVdb)Dz3yC@gk z=7S~k;MuFX{Rr5`x8jX5<z?S0owaUKeEx5NEZ-kZfiCbs!AJTF{(BY@dzY(;FUmD$ zx;B0xOV#?$)>OV8F72$i+_WPyXHZ#o7{li3<J5mI(isvM+AEIl^<lLQXHB0I=+yuf z3H1v-G4GXMC9tfu9I;o(83GU`OC1w$2pa)z55L@2#@16PJHMc?$pT1M81NJ$Us!0U z3|QRu$P=IG^43tg&FC|*<2Y@{VbME0?jzkXorkx3{8Igq#q3!drN_46S`|N$|H6dd zC~DlR65Xdjh41yOIKeM7`-2K)BUV+w=1iH~mi8XcO#8v%-$?%caET1Q7!F%B4y-n; z#xs`?Jj9ZMQQ%mBSd$q(Tg3QuYj#)RRt;olbq{YbyvttWZlHj81<dx>qaAz+F}m5P zUB68&fQR@<6M>uBZ*nT)uYA(I!_Rle@W~5g&jogI6_CHLOxXE>p1URezkPCLV0Pp= z#QOcffvx|JOgqrfeIJdrR<SjY;|Fu-Z=`5Tjw*sBZNjqxI@&D47lb32Qc^WrgP*^! za&d<%wHnjhhf@@8r;3)qC};k$%G~*b+)W){?aEWt9$&*a9K0w=Sw>A$63s=jE#1a` zity3yD0&>5XoR#c%-nUMgkd-yZcCy0JMXa+!+%zqTj;WQi~5T1+XNQmyih{5=#H>b zMp#<Y|KwgXbA<3oj@osFNgWu-x2f;;`r#=TQ`EXng2&Q7oMzcA_K@M*O7wp@GA(8o z(6q~^ABy?25IG`?3h`G;)5rVnD}QB)5<}d1ZD0`le$=sK#&FZ`ubf2*;_2lw__YwM zX2rFmq7A1x7T|_Yqq;cXXKyued^#Z~**#dt45uzFZYVgzI{mVrz+Jo<cs{i=S9L9e zcSLt}1@U>txY9EZq$D=5K5ojT`De$dvL=rsqFN`0{z~{s`i_1-Ckn%V=9}<TXHwE@ zer@4z?9#0lTkUjtoMkU!Q8d9>R**+Ql=-+w>-n$9L#<_@Sp?az6<Y{r3y4X71*hOW zjD?=F`jFWZ`AfxHo*aj!Rv>K}N?(U{b&2x@bC*oIh<)Cgvc|_9!+64CF)-8V-lyW* zVa+e=r|e8iUsh_!X(ld(+%`*28a7mPhIEY`-YQjRznqIrP7#@&(5{Kbe)gXYFfuzD zzc(v$JzT6cE%-L?tKMf9^l#);v=&6c#V`;_jRt>r_;3P&RwTIC(@(inX~@;yiH8E| z7RlPEmZ!ylz%A~m%#|-w_t~ed*Up&8^MRiw?xxn?D$8S+;Jd-J5*(D2^ebog6kc7j z{h-Bm7MDS)c>DU<tm&E=3|y=Jk(Vur>rsIXa#d&=WyBLQ!sTENN2;&r2t6r@k@7-Z zQ3y^lg=5X(@pic`J|xjou5T8g5ngbbf{NGo@rw!V@9b8Ct0})<ApR8cH>z|@<ZK%x zp853QidE>DiZZR5Q%!iETR+^qO>;(@XKxps+P&BsmF`a-9;r?IcwD4a<4husFwAIH zbx;<lXi=FjqU1kS1lFy~vvLqV5^}A>01d|8J@MCeDx^|#=I#Y(%i=(BMV9OQl7w#e z%934kb5mmB{>o3D#j|HaH3!D6<xxR)u!HA_UeMXT$x^|mh{xh~a9+F1;|lm?!5n47 z0EOsEU*fs+3Z9<>e522nUL&6QeRPH{)BYhBGkRfmZDNS?p6xFuVN9|<O2Yqy&^^bS z;ZJB`!U_)lwkr}^E8V{jwp|A7eLlWxIWJxJk?)ajdv}K}9X@QC%$~qFp)a#9Ug3_X z?@FCQNe(Wt&HSgTZZxF-h2#Si)i#LbfJ=xjK|>=GuWeqxox2?H$>R*_Xt^iD<P^&6 zFEVKGgS5jFf_mb&Q&P+RRYx}|FMSSv^c?`?`XIh{1qdacvvAez4`Kr!tkYwC*<Lp8 z+-<4IAUl0k&1s7~?*t8T;q(<s8+6KafzQ1Htvo}hW_=GexTLw(dY;#J@RE5S6flOr zw$LJD<el8d`(gXFwJz+Zil2+kuy@inwC%k=i@&*^+?6SRJHY<)QtKh4=<}~@+okPO zzm!n6rCO>9hf#ukxsoco$FJt{p7)wdS1zs%pS~Ps`}D%iUjPWVilYKF=z$#^#|@}M zYHW4YSjZeGz|eL}b=@RO{M0o_{od<`6d{=P%Puf3oub1B7N$!bjUuz`?gR^O1*{fR zBlH&$!L{fUm5^garj%L;nvkL+W8YPWAe*u_2sFl;F&8QB+7Sv+0VR^nai$HDURYJn zU^RQFOgC3iVASls{zw|D^2)yO?T++v{asv3DIg@^T8{)C1IO+PsJ!n&Ju6B&+MEF= z<4K&~KWH*|$ukHF$BnA#+I}rylCh@O!Z|62<{h-8vyjhIG{ra!F$~C4C=bAgCPnW> zZ$6VeuK{>d`eFPEOtIi&JoIbu1+*m;g+oY@AhSxYWlZaGzY&HWi#IoU;edS%1ZaKh zHvn5Ciur41A>D|~dI5Pjd5n!pY@@WfXD9+kU4+KFZ4l8Bl->MngUWl|N{c35Qz@ug z@|Z{+iVL61Xniac4hPuzD;qWHfUZ{NB%9eC$<urNRp^Q@Mpn#|kkaPNpX-UrIzSHq z)KYH%%v3t9Ka-sj8xw*q<N$*JUZ9_h&eKP$TWO#AB0G_(v*kTOu|;p4%%ThNlBFgc z>U0zrQF5J!*ue``n7^FQ<fay@_Z0;1+mldc%7zGIz;ZX;&I-1kUe!Lm5-G{0Cr@|G zR*)j8KNbm}o}oxY#i8q>rR3T-X>BZZbKiG@r>V?8!Bdps9lEqWNNAEp3zm!PvAVUu z=d`ULH&><lkOgN!;aR7f%N;?!#60}YSNi!hz+siSRH4gJZ3=|*%V`qfspbPF{AnA< zZ4dXT{eUwBFn*}-InH;yYE|^1^1Hh-Q;alpt9gzTM(mSy2fC`v_(LsC-Ulnw;UJiK zEE8?|py~|e;6-qz_I6Ar7iCb0lzs+O=ZjV-!`U#gT=vlGpCN7SOgP(}cqS{?*6NAi zTmNjUvI@BeXsE4?ET#(QpaVvMbIc7>`bx6S6UgF&dQly}U#P0e-{uN^qDu((qguX$ zuD0Q{8!lM#`;Pkndud@Rh-Y8I)CSK~b}?;LSpo0&yH8HO5k7fGX@IizDwxqFD6Lm% zBuRB+9ww}(Zps}Ee5?yP&psO;wpn9fdH%&2tq>-+?q1#2tFB20v?A=6Ge*_1NVtz; zF1w|L<>j8Ok~pI}!VnFKkaDJq#lhPIIeTbtRvwN09=142DP~gGs~VUOUQcOZ5BS}q z8k==03@Zg-V?U}`wLg!HTp=>Hp5x`>bTh@K+1eMY*J7=a^k;nbhKkB~S5d?Y?#lg~ z>X5zo6XD~}*k+Z~Fct;?31s2!U0VSny8`IJDMMdYc@Qp+B}W)=N9Fw0Jw_MPC4fEK zHfpbxCZa-c1X6j5?NT`UuLIq=L!*$sYJ~=NXpf<l6_kl)z0V$=G1Jj4Px032AVsHA zmDWc`RL@CCbN?k%^CWf_9-0dW-$>|Y`;gcsQMSFro9HhGM@tPGw6Wk8fyj<5OIblQ z&EF$hmcb1rTCc#e*iU{Toch28oEvhJtI%qq?Ao4Y!F%B0#V0CSK1zN>(gBc~Dkbuh zi9^URRc7dn+_eh?`f~{X5Y}?^(qM5A?ZzJ+$0wxd;q-{nTZada5i%waGD4k3u45-p z3+<o5Mc?ibpi4P`S5MU^+UGaIb!>S2ZH$k%eb?9lBA6YJRU*x1u#hiwSCt%z(a*rZ zAc`%gftcGGE@3EXuiq9e*oa)Nv^5fq9u5y-!STAtzzw_XF;^p9ltAclH<=?lbm@Z{ zLJ#|6x+AHSrL}Sc9B7#p40W6kBMnBb+(?qo$dIs`G1XYKM>^%{?QwW{Y_^;*TwyoU zb(An&elB42dX-Jbdj!X)Cq|Ah(3`OvVO!N=tcf+Cxz;ibS+RNaI@$1keF^;Jbm`CH z%u6gG(txADu<qro>d#mx5c3@I>6E&9AJ@2vuYyB%@RkzPVY%jt0*CS}UkO-v8%Kl9 zUBx4_u*&Nueb4O*l=-VT=l%5FumI)6y+DV*)dtU4w30g_r4`q#BZXjOo^XJLe=E-= znG*=&^1rp9S4Zg5WTE)SNhUSs-UpZxfGfxqyiW*oL*+=04s;wrMt6?OTa!39wv3}S zfY|l}>U9~?`uom{z|WnoisuoTnYZPuvMxQRL$sv^xHe6s9`ox^rJP&9u=ltJR@l-E z$!?7z2a69PG4Zr=X7%XJzz51%e>N>jq)5`ovFYhtOT%NJet->0p?8^KmK5k1@jJ5g z^R!BX=S?(8C8>u^iXES#i+~Twj?~p$Np&RYs4d!cuR`I!v<M|X11eTo1*KM4spQr) zg7^tWw?m#Ui-au|jBy9zPufQ+pQ~paMaEXW(MEPdXH6H8M9!Am-j>XUX~7txHLH(0 z{xt}wFA-w?b|l@ftb=b(GTB1J>F_<`O^Rzh?6KcbIh0c)1@GmENd~8ZK2G04e*tNw ziI7OA2+a^~fq@fIZ>##bHj7?I^qp<`%<sfEAJi1GgbxUBg3Z07kj8GWDyn7Fh0G6# z-5%ihP$#~y(8eY}d@$fdnu6MoDBojr%Q=qRlGj+Li1km)$Si<^O%bbL@<m9i2$92g zf!e<j2gy;1)3&OdpRdRo|9Jy5>A}!CSA+g24Q=2`FOU=17>z(!UXzraJJAFuDq zS8ss(oc8>0HPQEo5ne!XWLs-nCj~+gvuyXfm5&z^diOkrZusbT0xf8Km-O3De@tGB zj^avWrj>{+-qY_tDbP=@Q{W75UGt?<+))RyF_BaC4Y+>r*7?Ss?(<Rw$zxm5^ktQt zzuKuM2_e*C-ROVH*O!N+I-i^ze3K^bfEIitlrOGw+KP5z0&QbC7_?F6dONnTEPW(U z2X#{N+J<dRq{PIFN)(I-GG{Gx6SpoON1b1Np{BEQ9>h()Dj@O!?U;pQC)lQTJnp7( zjouGMb&8yQ;c^Kwsvx=kB`7;z((J~Pc8q*MW{bIo=H(o|Z?c<1^QCVoIf*VTf8H>Z zo)rDOti5UP&eURwuV!&c!-=StQm1ny=bY*CL;c4`JHRoY8G+KcMdM!TG+@;eaCzlr z8*MYYMLYcv;8UkUv-sRoFEq#|!;b`hqM*+?rSHC=*R52fZ#Vs^V>x&W4U%kr{Pp2U z1?Ui}_w56*!WF1|5A8#eYPKlXQ7Dhk+qU;#>DtI!Kg_$NHSRQ!<XLz6!m*I4sG|KB z^sHa^4fF*UTr&@u?O|mqhv~`@FWT!8PbG3RL@Bn$arVcw6DT9VYhl!13#m$&2p&sc zYwd2Sz)+zqr5~!K_UUubdlIP1%|peV0mQ^UG%y{n{z8dA7SHG}uK1;4g&*+!P5(^E zkV(sMRqW2M<i{oo8to~%f`Oo~bo6KeC(UpkcrYr;_3PNOtb6=_(qD=6Q-Ow~2ZUyQ zV}Jpy>en4B8BzTrFP4w!GJrHS@=O-}PF6ya<7~l+FY1nx^lIDQOs1g67y<%9e~jWs z9^A~r(EsM--`}C*UMc}YCcsyE`1}(eMXrz;lTE*4#<JQ|xSp{ieWJStB7Dpm(3>(- z0Ovl<<Vcl-kky$bB`l&>Vrp%apvr5R7f{f4f`A2~G))fb0f)|67?Z~clvQ$oPZq7N z$2_lzQb(=tX-d43`QimM_QT2lzSdO+bLL=llht%t<hv!q46=lt!sJbdww^H5I!j|u zQ&&wwhs`2-&2*6M7HULceA^xG2LoHDli_gm+ZsAu0zII3d01{iO;o?3UBo_nrOVjn z0Qv%pL#-YuoUE^Y<7@l@r}dxjNXnnuO2s_$F93X5Ssz0>J*SuDN=;Xyi#~X|pirhG zSMJDR_MfOWRqdV&2Lp&Qt;Idz)#~;Nt@<=-q+^eFZy()kFx$4MI_;lBXW}a$Fi-vN zoz$Y?w_Ij?j~I25kU<>P`{t7O-7CApmt!!K5AOVCxgYt09{2ltmC<;ULM^n82PlT7 z_SQDY)8BM~NDg$_joNn^P;Xe0I+<y>J$@3<-UFvr9h+pg=?5H*_1>zk=^2h8>EH(V zgnvFRBR{wlp0zwdmov{&>#cI6Pukwg{slWw<m=e)*o366xlw=pemZ%a?Tm*0eM<%@ z9jONi(-U>aU(u>@FQ8f>Jyas*l47X<wy;UKT3YC)ha*(3yFwe1YAKZ)7t->YlQyX~ z`f(WHF3&JQpB@aYN-mQDg>^j&lksbx(HiZ`BF}s$XlkRZZr4qD&o>z8GP5%@rQDLD z@6_p|=$RSxiFB<MEVStlfv;bdE`_2wieT~Vd@;6UECdXPLeUuWb!EYw_DtpoW!W%7 zlrHBzs4@*(h(a&!rS@?daEd`sh|t+s2-D_j6re=tBfZl9fe}}47OC@L(m?0old@sE zMw}8dHp{f@7?Q03isFzEeo_q#o`zPUqa~Qj#D$miZ<0_PN9wKa%;g(Lwe-Vo${zWm zBAs2XM?GR>M~JQ#)suy*PDz7C_zi9ojKu7nY%HA4#HpP`sqTu=yM#;ljj=`_t>ONb zvRKXjbiBB<=}5lidylH<+Y{e127dIM9(Z6RId?msXjnbLH7n*wfo9HbWlI@n#^&@= zmZuVFv$4M7n|wF3Ry&QhGvA;`;K$IYJu){*1**o=Vt?xFM}>?1Jd1OL<Q5T%D@e!z z8c{z&ZPCk^fRUeJdVIM9liS~ep4jg^bVNZD4o)9vIJ!sAY~r2{T~>|x3yoY5V&1+N z?3wj<wCMXwHxakdtjOVu9|q!o-nb7U6#0qbK0;+#m&0Nf*cy+tN*NA3Z}q5$oiE+1 zDRArbhlG0hrtIarS<28&b6ijL?1$2(vSpI??#R0jFoX3Mrvo(i*P)<RXYF===Z2w( zzl`s+e64y*q`b>rsJV&uQ<2??Y}=Na@+ItFIcyuTP6;Xb!KJ$m<D6;VST<K?#A}mL zdj}=bs6cmT1$3mLP=07F-or?9F5MRTI>!qvKAqeGDw^gtT9@*{XXk3)Y&E-ScvsQs zn@TcZiBdKj@Y2qAFazWmE(UsI+*70X<~J-diZY~vJ$1jlbKb0zfeb7rL=8^>3qCLD z4k&Sn&=OdBwx~V5rNV*tV|BL@R4fvfA}7M93u@*&f~FqWr}B5a5O2c21@X5J#-sAu zz7dk4uRr&LBGy{YW1wX~e#zPh-YiKgQaIUGaOC&nnO2wN!=&@2&dL2RpV?IoxT_la z^F03MMz;6-R4|hprW!zVala$6m-NOi^EpzQJ|Da|izmc}rgN;c<OJ||^3$~fR#Q9y zqQ!JJN$zqeCISS;FtiLow&8Q&8^Ox&7RGCHC;Ohsoe&Z4<0zkI5Vxb!9uY?K9iM#s zFq7GpRvj@fE@SGS=y^-of8WZHgdRB4^zwFqd(AuiETo*i#ZvS_j{mgitX-~Nx;2IS zHnpYW`Y+<kEwwk&^eR2u<Vf;|Iv`glRZ-xmDeWDUC(`0igOlkFl7z~BHq_mH+at_k z2sbm147~Y1&JUV2)Cp4#DR`bU__oxFcBy1-pfast`Rti^t}8#$P6+=Wv_dd!JwMUs zP`M;JYbf*Z@s!tW^mEKN2l|<Ms$ZrYRqkyz`PK4msr==2s<*AHNspH}^tF=;=WFDN zRjIQ)Qk1TeogRm+YV*GN7X&-e_xpAHH5+Dspt+&$-}Ji}=rPADT%%UQoeA0z+E0c! zOENd<Gj$s}<4a7OuU_z?m|rgLl6~?f^xSJ5DsJ*4K%S0qT@%x%s+|P3g8q|eVpEpO z$DzE%p_g{nMOr{ynO25t0p(4?@>h?nDGXuRhjM>_2NK71JJQ^OXa1+yY@X-2-Fri0 zEk1>Rpn;lw-KXCKSP*gFp+Zh?E@O0m_WIR6>!0dcI@-!E((yTKCT;USMd#s9_5a23 z&z-LQu{Zb1UfEgc-s@g_TqB$8tq?-gy<A)h*Cr!-Mu?)}i>?`>Bt#*EB$f8?^ZOUx zkH>kR_xp8Tujl!~S2?CKk@7Cf)FXTKxQ<L~z3r1!Xc?rCI^+BBdLQnHSDPX2f{G|} zeNNxu`?nr5Yi74n4opkT>RJA{b61SkAOBuvuyvxeES2R)-)?f+>W~vcvk$CI#JTF8 zxnH~cp$GRY`G-nJWpJNs*nHlza}CdvljNip?!27!Vu!j=z|-pEFDTA#)7ssaIy@-A z_FveAlhn?MwA0D-YGD!Qa^1(aL!F}cA4Tm9i@kCRI`QA;NRXcRk@1bQ26xH?7;H)s zk31{b2fr7Hpw5AzuRZCxHiF{Ky|!9Ye>v}1`<&``m4YwG723&6PAF0;a^$?S>0ViU zsOW{TFW*{}+@B;b*g>*7$G_buvj`9M<@Jmd@7ELJ9|`~Qg6*-TuF2sCVnJkxp8RFV zAbNf<hctWeIB2%T54gZV3wZbH#0rO@2WS0900Af=7FTwaQ)iqF;x}a^R5o>P#N6@8 zD4)68aqlH22hlyeS@7<?ut=A@h?tQ`#}+M<U(!M)iXIp6E$iiD>GL9cZ=V~D3detz zzV|wBshpK_DtC7JS(q-s*?8CMok5|{i{Lhm?7;YuzJICDf$*ah8tqA%Sbhfh<Ydej z+E{wx08`@FSM8@?O<h0I<OVKVf7+jam?gL9%N`&bAC!z*$ucedkwwE<&5G|uNACAO z?TUu=1@K&p4xh?3b_k|}XU*Bf4A6Ux4)3yiTRE*bzhYmH{VR>z-LH;p|0qLQsfmfI z^$5ZayD^d7@1?sxWx9Hho`{O09#z#i(%9sPe|TsoDHi~==T8;ijh?&n{lVwf?6cz@ z>lC~lRI0g$nW{fHO>xVPx9xcPtp4=Yw~yTw=TEAKh=a-C_ejnRf&@$6UgvD^;`YcR z-3Oyy)8}@Rp>ja|8dp(#4sEe+@6`kc%gTT1&4405$^$t1k-W`BnMuDWh)M#;R~8ap zaWz4m{T-LzCC{AMr%@*Uarj<{p&zVrj;JM*76%3MGPA{Bw>n+2{5hb$V{#7{gzI(g z+j^=nUVenqMUIS|`@Wz;<IWaZ7-*-B2`zA=Cf|=%e516O4;)K)?RG_33ym{$|GIx) zJ0vb=lhUt{;)1xI^NFav2gvDHJ&J;U7olk#6`cvli{<SaHK$~M9E|0J&Fd|-E*VEF zroWj2b;_N7HZ8mz7=1mE&gZ17Dp3@_mpZ#ib~65sYW(4lv;Esh0A(bb=TVxn-QT3q zd-^0fkNeC@)&h^@Du0QNbL00s3NKBBiN*nF19C^s2ZPDUI>54T&;f=)<Ce9%74*sH zzbo&iA=}#fE)UWVXBO`;q0jYSQ;`0ZFF5FxN&(<$akQFM7C_C>I?S$<<!N#-&>if1 zFlDQYd@tDjn3pV;5%<IW4=j>Sz;kjD2@Jj(r;LmdWPR`UUQHMO^Y%X>xuAPnN{8K^ zeMinpdQubr!;7*$bGjGV6bcst*vZwrk1Vf$1~YLtk=H;9iZRL%Lb%nf9t%JCo*I+< zO6QY>gGpS^cN8CeUU`h*5FaUEUSG>7L;40GNifNP6ugv5ZWtJatMU*}V1An@{Vds( z305V}xBiBfcw!yl_0<~<tg$|OwEfNdND|ob5FtD%dNlZzYg0fIKG1L8hJ5m}aE$4s zM54cdtym1H(IFa;>P4nxR^W_rzJk0+f~zwGAdTtTl6VZ2a|yUY2$l*y_8v*WKM0qZ z4HpOK5I~S2bqs(QymTTP*9POz1y`PvvXMRTSy=br808qb$Z)$5q6{HNa_S;yqX3fJ zEQ!{9IA;&8L2NH^ulc`}cw<JDaK{NHzj1umY;un7lSOna53}>z@`yjXAwWrq$yg;A z3l$)R{H|lXah|H*=zQ3(nu|0f<kJkEtH<lPk@5t5HVhF11;QdTTk_7-bLi%VaP?>_ z7-6B<G=OI?2t-Mh9C<;3Q=9OCdai20asnDk5+%@yT&cCZ7?#{3uJKPuJ99o~ForWJ zc;@P>$i_gz+RnSB8*43^jfsI70sBVB?$k;r??P?ytNumW=pGM#2WJ9J?FUE&&<WCn zal`KFbhMp}JTQ26w+#1)Kl*taG9FDL+`&WutwJURwm7-?@~1hR6b&wYVUsyhK94OM z)(RoNcwh}y2SpK+%`Z6+UO*4#dJqT{`7W0W-&mYt{dj(_roCpM)A=nX@|9noWHl>! z5i4_ql(lR1B%pllb|H5#rXx*MSXOC>YsD*tP{BtSGOtjmIH5a#7z7&r@T1x_A9TlN z8*amo_`04U2o55ED9JsaS@z+>_trO7I#h{7wCxPHjcZ*hfp+Du7BFS#cSkf?+5h&V zL+B%?tFO&AKFoey9B+BRpKEa*7d>P`!%!!Qujd?of1i2ke1<Vcam!Ijz*VIvV+Igf z3bSco5(>-3$$n}Fue0n$%6|YQD=zaU#dft`%+c;59F)VcXIlB^tZ;`01-m+kKKq&G zT>(E|f;*i2d6NaG$SB2y9Xu*+CR{Y|W*hjW)ilF3j83-8oJL29z4%0RyZwrDuIig| z&zy?2^g|mul<Q%kd$|7TJ5ET6ysAQ_Yqnr1cRJhpzy!@S9Pm08D1&m@Cs_c^yd%`w z9|5U_KW`-f)aWVnP)=saMv|PG%aM3g|58{LOeLh0NRH!r(k$h2*1P~0QgV{j(2pZ3 z?nF<lBc0u~O(m&Gn3#B~_)X~^6$lbQ|CPJ3*jyLHKW;&G7vyVLSksFtA4`_`tcAiI zvrl_B4jVM3$HK-am`n$p3JjR&neqp@P+Y80h5)}*lDVJFzo9h-2|^ZLmK)>!Vw;z_ zTq|K#E}|yR4Pj11!cN+i;|5S%=`XO?5s-PKOhD4cv(DTjX!@dO4A--jR`hfAN{4nC z1KMhC5TEyR)VcWFh_)Tfj(fH14?6?EFEE$awlZ0K=wY=1D$LQ27dTQe<6<Y8UFPW< zTr&UJmAss$&7*4C2-5j4{jsa4tu|>Hvdy9Wc`Whij*0m}8t0|eTC~h;y5W^*V*OwP z4^oGwAdv|Xj0fQC(rA`t{sM81P-%gLF)aZtu3;=AfF-$>AZjLTU`GwwG7#4PXk>b= zh7^ld;xuS=lxeUVR{2sV%XG(>YnF>ovXHmsP&GPN%AG^<F=gy~ksqCRc>~^?fXZX} zOe&ekssY9%&&KB|T&tr-u*aJ;8T`sl>$MBsQFP5k=RuO^3jDcJXdpX&;-0V+^IU;x zS9ions3$X?+w!_MN~44=wmJ8Tt-{?6T`rAWGXvu93VTf6ku_~0y`n$--ShcU&6N;; zYT_-Fz3=b(+rk?h9Z7y7pP0F7KHE!P)AQvMO*N9k)wS()DlUhtLpVUHscE#S7x7|N zER}(lpH2V$PvK4a_6dmt@+hC1-K^8d44P;u)4-CaUU)na393br$e-<}t%6*@C~>LU zFUTGBdXB7Pg7{awjKO%T(#6FOSyx!y0nzUYg43#>*q&*0gmh#zXpD(+A0lgo`6LS* zY7d3arhYJPXdJ@hzs2dv1FAE2iZeSNtjTo_=8Ooyna}I_Wv<_y0>E#tH}qA=v&4c- zUu53}#jA79@-TGQzbUNe1s<pyAE6N+9Y7%Xt!5q_EaU-XFJWo8cLp{zEw#DmQ5`fF zNM-Ij%bKHGCM<PpZ?+;bK6<aEhMN~Ql{(e-P89R(T;f!RoI*9|$}Xu2piR`xyjm|A z$#dBWZ;YvEKp_4;lj#Ot+Q=ZegmKY=K|Dijk8E=0^DM!mRT^PkiOPcq(aW|+(m92q zhz86;8%;fEHf<F41m0nb=r^Qs%UZPhnL8iP?bd>=Y=WLUSL0T!!(}Bk0{4d-e9w7Q zpC-}lR-Jt__k>=7ePE8o%JXEPv{7-<jFllU@cD+*c}9N_&Ou|LsOfF7+~0b0oXl3C zp}V9996$|>?PYYdjqz4*rL_p;-n6D3;S-F*eI{7O&#U<7Qrc^uPKVRm`p+ArNqr)$ znynj;x+#B{eqJ&$w0u(6u9<S>)3#*Sh0@=zmTIi$W%}Ic_V$DV)}P|9kZfGsavHb! z7D7wKUPp?)c$^V>(&85fc%#_B4;IfpvEjJxakJ^6Qo6e7e`XiI&}Q_9Q~OPy1-{pF z{Oi6#w7+Nm&z{~4dM<Nz#`iYYKTLZ6WaM9FCBfNK35bq*ui)JS@>$2ypZZDWCN<+m z{(Q^qK5><ciF|rl;MrnM+P<3l*osR4J=K%JWR#}O)zxT}G52$cM*)>;`CcoDpZZFt z%(VFa#`4~b2&W={;Ms}sxY+bS%k-mj%<swCTp!PsU`vb7BUsmWlC(aKOb=?1)CyMo zY(>l)kN`Klir{5j&o~QeSq5slSuG=nCtbsIM3p}sL$_hTm=P`vmN;Gs&tn6yM!3ll zi!t7Vc&vX$xx1QWW=T1rPI!lp+Ie_0=Jd_OO;(?o5`rA(XDp$Z*RyYp_7IVAc7f>0 zhOwFC;Y^Tt#Qu76Ws;!zBt?+raK+^=WFRVnW6^;+c-)-@SJlrl;vUiBt*FTJUc?B( z8G?||Q2GsJ5nykk{?M2mU0_bn?eNQH6@EfgG8g<)@gHyIoCo7xeEv<rr}hM5><sJX zSGFG+X+O0jrvOvQ4`%j9e}+#fBYJU!n;vh3W2_gJh4>7qd{BU+aEhfJE-*rVtXW2& zza&hi0Uw?UHdH6}nd^}=l}4DYY#A&xn+XyJC-!;7m=M8%lkNOVAvNQRiIq>ZFn?Fj zQ$4xTL;N?FeS&*QQl75Py4*1aVmuRXWEv<wq>4gv<qIO=NQ<&nmG#*LNf;=7%*G|? z%J@fmOWb>XrU_=wkUR|?F!-0FV8+knFmEKa$c%@#o+kK<I<w|2ZSgXq<R;X!AwqD^ zBHqF(c+E9p?dDhFqtwF8B(pVX?u%1aQnBgvW>ga&2?83`?L5<OJ7YxleWL3}m=iKW zUc1C@l40;%?uZXAU`X91!kPXESVG7UQ?kwmOmF+Ga@2BuA%XA138G&vq{+i_()<8N zwI))(A4(Aq=^dK5H+`!wAmr_xHSy1^lQCJ|52b)rdx{*!VfhsSZsl}(SrR(X)0F+3 z{k2zjow=&bs`o1)1VRhqg4^D3!`avWF`nq1dP1I^uw+<xr#N`R&56<u4TLl90WJhb zHCw`4Q|e>68S|jEjvw%z!73L#q3P%IL%y?anJ+#aIyo!{{4PxWe%AF9%`aF=eA<?J z(Tsrcq(;ZzAl#x@#%94GmWMiTwpTU=AY^=05w4_M!@nqx&iP(?8Y#%Lo`@ca+cN)g z9Hp9je0lSP{p<D91=n>LjIfeL;%cVC-M2O}Z2YcpHa+t~^jqE`nL8wSlqbB{y#~1= z!pSYpZT&hqZ$!(Ldd||9I8emxLo)RCiR$v7JWZvp-mKUO#OVwMdfO0wkXiT{7qEmR zmNyJuxNWlW?J0qHJk@^vb<)qr`%^)Ls+2!uWRUfMr4_?tCo@x!3bEq=o!=P+adh%p z9AU0)Tba7vFQ@WO2$8cV`|8<FpRmz+cFw@byd{UKohLS9@on=u5iaTF%6M5fSh(f# z!h<`yor)Lc%_R~tq5hE51QeOv^$9M#8-#00!A<(+uqY6ynXuT2pP;`LNY6V8lXi!g zT)|WQu5WfW6@Kv-`S-V?@Y^eIVBKx#=5g$))ZDiubE5gKbCoWUa%=vyiyx1p1n~z( zyV@2TIc<|wgFE!V5#im{W4Ibg>%CxtWk8%T9Exrsf*gia7*O!|bQ3IFy_GOvtP7Cy zapaFe&;5?GCM`iM8}JJT)L_rXmYCvtj>$+~LW65r5ag`7%-d?-2?A0s#raK9o<huF zF~|PoRAI1PTT2l2>}f4AFKjU($m&#fVgH6AL5EYiFF@BE-jgN0MUs_cW&+q2holMu z{P=-~mU(MS*M6M<B9iGFOV<OIbHI>5JJ=a0U>JA3XGEM{Vsz&y^8L@=pmhQxNcg?c zpEP!WYxCg?x3;(WIy3con?`aAsm}H!TwUSZ`;@FgTu_GX5260e>;DD3Hug!6FqT`) zYinZEQydugyrpaf5jvT^ILp1iw$)l5W2s&%1v-#HXU;*P<D!*-BuHoO5)`tP2&+p* zRTZVg0p;aALKP#4`51!!_zb*kL|28NW6LZ0O7-h4HN?h(Q0tJIrAFa4VRDhCQYV*r z!^Lx~CuY#7W%I@P8lvEfd$|hN+X%l`%H6Hyh;lDp;%g}rB(yN!3$6*a<f)5QXA76x zV*Nd6{}eLLD-k=aD%YuXEH`ngr7$RY`Qds(f{b}p!S5pi*B@~AinmJc4{=Yc04wmO zdoXgg0o_fs4^);=yB|8xy;UC7q^<ST)lp)3Vy1tMb*_11Ppm^j@<pn4#5T&jDa1|q zC#ysnu4%BnJ)jupw>umnhPR`3{HoKRet{jbGD=z-$5Ra_ec`UH-YYPZIU_CVV|v}~ zp2~^Xu|Qn(Ny5fRCW|w!T+zmwp=U@a=-6tC<VazD@mF^=_(l7l4{o+|g0K|j$QtF= zs_-RO0`hEU@}#p@CdYP35p{JT^zQkdw)W?rm5Fk}C>w@;|CGE3!-9EwqUFM9gbWZt zFq!ntdL8z|kSZVqFUyU{6|N&VH-7G1&DU%bK7t`Q{yKO&RuKMuEb~z&nhM?=6nxC> z_TLqCL-wFF?Q8x0!O|-?1qM`X4nkO$)}o`7fQN;0Lc#d@ph>CnHSW5b|CET6BXNcd zI=m(OAFVj6l-*aQKD7}`4HfvD**8&*!#<a#*j4!Ku~XJ%@r=R)@8yu7G`!lY&!Gp% zjMV;3wr2TPyZQYiTY_iQR_v%>c0URmQ9F3m^bHwFj)b4&*%j{rqa-9e?j(T5N_TTV zSyv;JV9pR8n;od(UrJ95QDKtygsK6~i<?G*=X}l|()@A)iD}NRUnYpbgs_XJY`~Y@ z%5BqGUftam_cWs)){{fz?<`#ZYDRx_WQ;nb`?eR=8{`Z7@$$ATej)Ip!PGEO3u@e_ z&#MN}get0DQ;I%8dTRZ#8Z3%viS5c3YX@(N-1W_v|2Wd+#i1tg{%*q?B15QvPiNi> zfeWK<+DG?pipbmO*}z5D_KQAKi}oyBj`cIUz4U*)N0`xJpRmE|Eq?JB@asf-SRh~v zhi`Y-x5CZ0t#BLcfJ1r7+1Q3-k66b?LiZ%y$MJSh+N?D-kHt5qFqi%7N25J&=}TV< zq1s;&!#5Pzt@OjTo!^w1(}g|En&j1jO)t0%xIAW)Aoo}@!6lY{ibLEpUlnEsJ`Xb7 zV6UFHJB~+7yzSf@mtFFos6BEduoAL!J>fQscNFg_x_lNiGog}R(1UfKN(Y7mZ@y(& zc3ydZDsk`HCzW@E!zW=HqgRI%g&Wm~+sYz5F+?c`+}b`;LCK`r%C4AXdrM;wmI z1eGFSjTpDA0yy0!R<-Tj#iWRnLV6AR!htQdhbQ+GSa?okO7v&yYp~i15&PTk=xMz* z=R7boG38ZfvJz%Uo%vwX>i*SqB*Ff+x%)?b?N=V9s?6rpR0#lDo?hb76ZqX%JTz_( zg2k~$V@=4Ztn$Qyd$>7rMkCGGh>-Axw*6>d%WSQ%<S?sZ9&nS$3B5iA#FO72e(^3N zWjXRm{?xkNY7;k>e}uX=n4#rdZ0u-9l@Zh|u^||T!Rd1;hJN4c?cx48Xrc}Wi&RYI z2p^{d3n(f<@Z;R&I5E=IaE-|!_obdI(T{P3!`z-wboe#f=}k7%gAPu8_gc-WH<y<G zt*CSVkQLWW34TeC>thPtJG7%}!Un$oN%P&M262GBzlsToKhC86Y^=3$NH6#qdoS=* zQMv`=)(nAK#!bC#I-!%_GU|epd!xBS!pX<^I*6oLbtx1d(vK=CKe&WDF<wD?LskE@ zk8YSNeXJ?(G~#dIdw7Z%J?7nVH!s2e?&D7ckaY251TL({_V@){`1`Hrsesy?2?2uC zjBqw1a&}8Y>FBqzP1AC$w6p7M!b6p`>l&Tbt+|ipb-M0M3_U3?!!J~`#c9V#4xf9q zBB}S4b~uk|@ZnS=bm;yFswdKVJ;kWYw7ugjsQ($l{-DuRQIZS!QIx=YNV2L;?=O=S zTDs|NtA8Sq_GVWTnp}srvM%2Vf2qCp>Mm)_J*kYZFwJV_OZ0H<*DvP<LfhfCtdKg^ zP$xqM8~yK()d?t6!jk&e@6NNyt|TEmyt?JV1dQ}lq30X-o8AyZ;4p2<iQtd&s^IXA zHqS_|?uoH|NObs|WubJuhYbfe%oX{mFVc(idRSoESTAg{8=E*<6Y8>!WZwH?S!H)p z;5e?EvU7ATO+SLVd%J(R``;Rel!*2hjeKrcTSBV{+{Nj1Q0MuNifUn(eRz?NuD?{k z0-#RXsvvMoM0V&URpZnF7XGjxI)<$34a9LR)LR&5vGfFW=FONFQe~`UuGfI(M2eZ` zeM>nwnKRWuVcJyC$cwcY!yC1L=1GQ85I0cKviZUGjW*TBg%fi(&rrT`50%|740XEA z`cXb?(++B1#cT!WKmdeMr4}&PfjK||qAcN1;B)l26GhPsDmZ>vJ21rjNb2tPy<kS8 z0P97+CgSR<f;_}4V7#k-sE(x=4I%kO<0aX?uXndb?Bj1T+cy<Xb-<VaAq70(bu>2s zOLY`t5-=3qJN*{=nA@p;`D17;tE_{m4ljTL0dgLRRuleIQ15NpJ=;q?1CRKEi;%$a zZogFP*NX0oLfC>rc`c(4O{$-W*I7?U1}S8gXNH|A#&b`0{ZW8g%6#YERb-yE_BBP_ z`0To!HqQ;Usa}}pHr4+C|6B!2Ri#fiUn&Wm9d6$rH^C$Y&Al5I$*`D~W{S2qB?3(s zcc}ZGFtTjJKK_G28o}2FjS{M{sn1lgSFNVY>C>B4cvBQQPY(Y1EI)o1zKT_p(>I%v ztEZmC$S(g0!$=WAL&m9jVJ)eA3ea68Anf8UIn|jlJ7dH%AuA!aGH!At7Q;()u=_7s z2_PfNSq|@?u@dAa^E%Sl$^1S#c2#}n$9R~;<HkUmv|@Bih6^OZ9^<y@CMT^J*A~{1 z)m`55q=8W&@2oKnN8?gSQ4!{85j|(Ei%mln9#gg9UMif|9OM|?g52iS%)AM!x|AZb zv6dE@@O#7<LA}wH`2Qrms=MGr=xR1?olZT#xcq~?q5dKGO6tq4<{D>2%Y6OQ2tHHu zQWcG0scU?{_?*>qzFw>KLkw|SWL@Sv?<ki~ZeE*hkxuq*3?nNVoOlqEK}b#ZLqXqg zC!lnJ{Z4a}gp5iByR?H`r;(b{qTpsKvbUhQT4#G8h1w0fcl6*c3OV2vR<WdbI#ofb z#=21PMyz6i;H}TZTwKj9pL_4GCGV%o@XPr$?(#NW02C6ns`bCzve?S}=GR(NCh*Lu zs!NJi)zly#xIcUOelt>nlHLCBb2WsPa0*Dc6$E?LZr^0zVA_UCmpc1c{&6RyYGsWn zv@PgDMn%g|f2QU)#kikW(p!GCJMgzHNxBxv8&StEn$H;`J{M!6{GT<Fp7vdBxd<#k zs)T_s_wLL4v(4MOi9*7=A-C>XG(D)`$A6W1h-8vHz4XqVGdyUG@!;Vn6@^Q0Czipn zs>$AsIP1j<{O;i?%HHi*Xdl0k&SAmN3^`0Q>zqB>3l(z&`H(2BG#v>5oN<S5gYgy| zhT4Jngr7zxk1sNxzcotlp$2)KwnfG1bSu1A&2eSLSXERNXg}2TCIjRlo_fEVg#;Xn zN?tN=gY!K(16vtOstr%$XZ1&>{%%@7mhjrWAQ(r^Qumf<2#}!*PSCU2s%_73`{z`> z$PMzwVSsKfIVK%)AW#B)gGcG5sd6ZYCtDnrM9HR=r)kQEvM`{|Tq+@5anqkg%f+1u zsRy@XFXu`D4k<9x2`Pt_MGWvPsz`et31q{_nG<%VhWlOenyx6vIJ3Tkl@v}^c@KP; zi)85m3GKl%mODL0f9M_|!<xbOMFCo!FHJZKzn3Q{*asy>^vf3{T;l=mm(q_GcM94c zK%_XG?obmg^s&dtRGwthXUrSAa%0CZ%^Tp`CYbmpFmUQ07imJ8w}_eIOB8kLIqs8i z7hjqI0$TaFk9vczyvhV2Ir3GG3;4h_b}MKTJ3{6*EZwWIu-)Y@9AtRkg9U$}Ml@#k za{#T00lDR+#+MyGra*JEGbPb|RA&WlmKX(Kx|%NvAWJ}JnZ$1@G@pT@L6&$q`^?Ou zOtLvfIcQ~4+m&lE>9FBsD;@sQ#SYaYn~`rWZ{+ifS8p~$Q&KBO(^meNNR`?cto5u3 z7--y)Z?6tCTj{^?S=0kcP8&FaSUdV}XJ0@O6wBR&1Gst~QPmKqSmGrHgcU>rWEi*7 zD=5Z2!(gQ=$vaHi&3^l^u6JUi{horXnTMTI!`@wQ?XT}wLlpDF;@fVStmkWp+$c(j z^(V2!kNV@>@NeaIMc*ASp<OLpi4V6yv#NgVgX7yJAUi29F<i_8h%!De2TX*J&BEQN zDe8u{%mXcXz5G1u#+k4GB}Up%q=VdZGuitlP8VXeg;OMB6tkK<#z^K5P8?>wY*y$V zy(Ir+&5S*~gH_JY<<N!e`-ESonEF}!fKZ%7?}YTIKljyh_~p&2wgGt~x8#Z_Owaud z6>VCnx8k#&ySMoDbskI|edUf)u~36YOR7{G{`<rsbk<kCqDQ@^#hvS0-$uy%;IzxS z;u#5X?OHIv3W><;==s+(qTU&KMAct~{(gEv=i8HoX&Ch(+g*dxQ(o+=+*WDb(o?)v zC}oXA3km@M3Xa)<3i<TLq|%(Lq7sceh2>Y(rJ%l^x77urGy+DD_t|vcdL+7PifJ(N zz+0VJ0(%Cj*NaqCX3g%YPWUxS*`r6{U+wR)0H4KQdE6(BU6czqt+h^n#QgKQLHt4y z|JBr)c;>^_rC{M#nPp)r*UY)(n0p(0Cr31Ao4qa!DcpZ(U1+QwB|7+JowurLc<4&> z^yg+eDy#%n44VEbITD+(I-0!0d`Tc-lx@+(O+@+A=Gxt)wzlqxK1q$rPK)Uiehtg< zigg4VDSHj)O736%UsvRk5O&_FY<$mbrn6K&Y(}JVXg-AQw4aQ*(u6O4oW++B?Htof zPdZT~PqU`wzUO}17=76AMO`;M|MD5Uz^@3Azgk8OFN=O!eLpt=@5L{S-norDU3E2j zRC}XIuIkQTW7HX%{h`ZJOX1HYsM_Eg#7M}!IIG!5`_1of)fY#cl$tr$cmKMOIw4;6 z`s--Q9dE0`UPo5Oo5sQksJ7*$RD}s~=iy8i5tW2X-n)?5G`aISXxpdhfLxX*>gGms z{%u`ux8}@;4<U-qN2{0Jb;arfHie*OIvU^Q{r=9a>(D~52<B6a{rX+LOpiSa^WSW0 znVlDQdT9!GCawD7eB3_d3rL(-i83?HE#rRBX0!R$vh+XvZr;`6I=<T5rElnAHkkI5 zB6_=|J14+~zLe?vd$&pA7tRwdDaxM>Ik%ysJr&3ch00|;n|l%+2D_;sdAxsR%hTw) z!A4KH<gQ;RhWu194*0okwaal^a$i}6?aBL+Y<X9usi3FbG;_2%`kCO+sY+kcYcllJ zzPRXt!rejP78anNiP-}#7AB>Tt#Gb#FWP!TPdpT}u9$^F-p{Ucs2qB|Et%lMZUUxh zEr;nSgeeP$AK6<nm5R!)D@ab(b!3y|B!(z0MMIE$WzGv5&r}fE9HgZygyS~{ll>F7 z%JtzI=JD5-ZXpL10jliv_(C7WyXDy!RZhg>-Zyy7@O_xOpc(r9jP^8#f&yg?o?CoZ zK^Tq~yI#xx>42{=MUrjc;qkS}VS7`Rd`^3H&n_Kqt#)N26tUGRkL~Qg(T=nkW~*MW zX!^8MHM^;&R?D_^ix)3+Z>o?nF(lKH<*2q=;{%P%&HjgK1*#+ty=_C(#7a*nHIdMM z-kma`A%Jwc!R>J`W_RNVUYGDM^K9Iucv-1VMLji<t0;uk=J5I3FM3aicBbXFzfHm( zu#6*)&L#SOklEtjw0+>?hf!gYGP2VxU*m{=3rxOm)tT9b*MwO6eN%v<M?-j@utf4g zC99hcde?i{kdodiovPDZXVVj2j}m-xFt<)(#JxV0(<ZFdtI(>LxoU;R&%~M8-wN!& z-c01-d3i{cL}=9PfVFIOvaFPnj`=30%w}q9T(0)1VCRXLF*}Up2Re81vuNMP4U<&` z%8C#L7Tv}NMI==&gpeTA9?wZ6)6XSFV5WTtGWlO-f<iZ1gA;uczA5jmkG>IpKiOhb z)WSp(z346;c+zB4TF@MQpHppTTeX;7`>D_?q?V*n%Z{X{8eB)>eqMVoVq8O0Un6 zWErz|rkz5;Y-whm{xdm%53i3!!}q!fAt`z-Po)ocKt3P#xm036zP44<#f0p{=|S<1 zA*tbuy6Tg1aa?-*c%r!lN*}oS%UVWn6JEum*(Zs}%U3S{qI)#WE0m!k-<~zXZF-<? zXfvhw;Mw*=drZ-~*2{~<Ga8Dk5Qajut|d3561M(~l{oNO+x(gywqx%`a^$~#_@Tzm zTr$yH)7Za&*qLQ4B&qButCy7<*`D=nZ>KWENJ&}+W1W>WzzIldV!&+tse<f3m}9U- z$&GGe-U*Nrfw^9z_SRnFOh?M=bS~*HhQqm%#gDP^yq1cR@@?sQ(;P56sUw1z16t+@ zKxmYFjXT}gefjPaTPa>~G+p(}9EqD`efg98jXXmkC@v|QYgqF|CDeq8*DJeIUi`@y z%R0l8lhO)RxbJ2b;ZW7WDX{}hl9e1Nk?O#nY9{+0;`|jiW&2F0P|xQh!J1%d>!2P! zg3WkrBKAb@J_zhS*JeZshO3;*lOK+4kQer*y7QbJejg0(t5)!t$jtDxtP<F~Na7Qx z5*S})s+6?(WNs=cwWT>;9Mj8-+7j+joD2)06)q){?AH!)`4bDOQ$W=IDY&FTBVQGX zcC6c<`~8);?|`9Vy2MvaN2Q0C-tE2Sv*$_90;3hA?j{`U5MK8j5p142+g{WcsG)0L zci;EIEU$^dW4-j1b;XJ1ws(WA=jF4Mm-ag3*JDh1m;)zfrKw-{LbRVP7hrT^JhL)x zPP_+NEcEVASex|tD|c)0Z3dSX1x2l48}?3L=7MHt=-cL-p6Y?#cy^MvvnaV!{)*$| zjI|bXj1~e4QCKy=YK7!v8Rw-4SApmI-f8kz-7mp6%P141SKS(?)V}&hq}(m)pv%WU zj}RG+oDa3fyz_*gzv=D+k!;iYFuyioFJb*PDo_p+##juKybxn--T6&^FXGXmygPeg zsPt5{$IwE5CV<p>s#E--(%2~Uo`<tvP#ByKTFpFvHk`Tn=z`f)7>`eYVzT!*e%1Zy z!XIt`<wXkH@rP+#!dcx(oKAQ*-1Utwdha~u^NVU)Y@&2=TzYNviPncDK9Huj>|x#* z*XMo$$!RQ(m+w5$F_^r#h6wrKlqMBK;+kpgh&HJSqqF@W>%Sm3x2CA(DtP9b{k~L8 zwze(uN$ehlK(vx~HZKc6xpv8xH-}DFcPXk`VOY?R$Xbfl5588P8~{+<I-lB?o**R2 z7POwST>vzMks!_&goZpDECF{P6(kNl>8<!Z=8AvZZ?C3zKPVE@6#nA4VtTJ+5rr2( zbK%Vu?ysis4K4CM=lc+yd2W`!_8_)+#C+U2nX~>V^QE9b)?3x$Z&^FN*=p}4CZ1=1 zjmr_~koa6Iyz4DLSCYfrM^|Lp|A#Y1FVKbha?fo9e_0cA&G#4U%Trz?lA7KP4NBa9 zpLhCae(H%7d(Hy0zJkAaMdV_^+4w?x(@dA2h2DLVhY)dLBKnuNl&@~_nMM9hNAz8a zM5TlAJ|-=uuS953;a|0QOSNc63(LE)l4_Tnd#s8KifB7UXlzZee^B(F_r(M6>{{J& z-S0uW7``Q(_(N~;0dLW`YEeJ<rD5I5o>SSsA)dW!LQB<RTh(Io-r|+sBHZS-b}p67 z_x<@0X}tatmEK}-AF*w3u}X@_Kb+!^dsWIyN9QrR)i=E*zEP?r^lBihWrII!%<h}< z4MX@6B(|$-AwW$ZrVf!%(%MlMoZ$MVQ(_NO4<U=kE!97WuM5>{YUIv?tV(QqSASm< z))B6`y7*u<vMN=trSTc$L8!=x_svm==$5y5J4N*0nrH#3WjMiTr?2TJMYQNf?e{g2 z<uzMTdda9>JK{^-5k+Db0_;|c|G?yW2ia`?x_##vzlojVeb!s8$!TQa4nDVc2Lj?V zUpgfor26ZL3q0tG<f^{u*rD~ROZUNbEw>JeOsD?k?vLN^Sc$Zl>Guq?rdq%1KKr{z z=s^!o<Zf`;^ZCt=Nd0@95AMdhG0wZ)qg?jSy?nX%lG$DPvff;gJJ&^e@*ng)mF=ax z>Z{i;$*%2b{C(fPh-xkJpikc)_bTVU{=>fX>VKH($p=lt`j7fdx?enabPs<;F<Eu( z)uWvU{U7w#7;E7?lK%+|iB3@d`=~#FkVFFj<|iEC2LOPQ;xY7&8!80_P)7g+C2HDH zHJF0pQE(sYsD7Ldo-i*r?W`H5eBYN(y!5dGdlil2NF0sy9=RrG-{O8O=sYP_^_?g; zyA$vvU&^F1u|%zQEM4j}G=d5J&brJrU%_MI7;xH13T5H@F)cB4b-hD3f3w*Zt?$?! zhp~eJIs77e(FX&A@c(ZWUvOR@W|5$jpI1(i*}wTFMU06%%e=Q^?J<o<F*c-U^~|Ns zs+ABwSr!&f9<&k|R0WVBaQtQQxT@}*<XUENYzG>D%tJ4K*z9L6q#b^h{k74lxXzDn z22xlhDx(z0Bk(sFDGi~vXeoJB2WKxb5J=@fsx0&i0hjin_e74CuagfUFo1<kjy!;) zvdP_`4yKq30O80ZD=q7X{~a9x$b~$U{oXIrXW%Qf?Amp}41rzLi;N8fs+?ToUqe>0 zv5UbA)i_QpdYvYf{R2zm1iLZm!Xdo?bh9G85{u}4NnsCP&Aq0*g_fgVdBiNYK_~F< zoI4BmM__q%{B-E4AHwBGnLs%TfWwGY^+n8PtDD7MS2Dn2sCTe*rs5S80A=D`m4UE2 zkcWhGyi&3a1*?5GDigo$$Xfn`8`Jd{419*!xJ2pVKqg0lSmD_;6c(P(Erl!gV&UCt zC<_UhDJm#(k%4pGk|U*`blhHq2=S_+)Zmz-u{Srn=R-noCUbA(=w#>&4pL!)<h5G) z2GiX_=Y(Ang3l7bBA~jz!R}dWbXz^(enYyn#?ytA9>(uA01;UoU^<TXwd~*D`}M9C z+eGceUCLBJ`(G3A1_0zAZbF;+U;b$2yYSTA@WQp8UY9_Wsn=tXj=PGV7`!LypAO?6 zDQ0684Q2vxBR*!$gNqzeg9FgBRVQ&m0DbU@%7qTxBrq9vaZ2Zn!9|?@N47h7MGcF# zJI{p6_nJ`}_hpJMEJFbU*rvUMVcfdQrx(tF;UHzK8kU98(9z#7kj3A)H7NW0H+@oF zgfaMv`_U8yd-2QUH{{8qa_|n!<0v$`R3!FZ5L`ZplBt9LX;fhBdTPIyVfY%BC1d7C zCI@aN1>M5UtJht66@7Ap!X)NiSA?xCZZBGn;hc+of<*lJ*t6v6vinGr9~fi~T&@XB z&S5&4cyqmK9nM^=|Ero-_$}-61axp(8@L4{>FtCRirb=Kl-0lAk(4*5e=KprFEMGn zWWWDfq46PDxLWT7AgyUoAo+XUHCr2Ib;CbLfTcOz00&3)nmNDjEWQ!)PATM5sQ;NV z@vmF4{ggNWs69dZ&W493Q&&@tiyUt__6RKMK)-=Oc8xFL-gl-ZSG6uqssj2{)7DtC z_oOlwIz-OvM3giHYjgDD6yYD@fM)7o*8XQULt3Xwk7=7@|Aq-zu)~f~_N&HfkI{KJ z7;qV9l;Eh&2sJta?aAi-o#h#1{sUVe(@!V-9ub7sp}{k7Pp)ev48vb)lGlwm#4Skx zv_ponSY1$DLj<?`EYYWHU+t*UMw00rDS^DEGF(x~8PVL=Q4oLWQ!e9d9CcZzFTceh z9Uq{ut44zO0hV6}`oob@q|3Zxw*ST~&g>K9J~}g)`OyF|X4{A@`VF>@X|%70p6BM^ zjWeZ>t8&-nv+6>$rE9EG!tRv87p1gp<*dv-!NRs{6~CVqNhh{7<GD?fRT2(!{zUra z{Ci(-_`BptElkiG`Yt#ZhOaZN+PPM`X78)R>N7<lUqs8%wvFttvze~lH5?gD1jqp? zm2@#b_~GiZ!;Wc+d!~h`>jFd-Om+Y9_~b`b(D3iQCrL|(A^RN@XS#Dyyh>GotyI~7 zoy@37*KD4&lr$hbVN28giss#1U}?}ho6^17;ye}N$ZmI>80ba|zX-w^%9{gWUFFD6 zi~Y$B^vgXNXD<$n{QXDCzP$dWA+FxplDUQrqjc*uUdsjV+AyK)Nus`W-_`1opUq;C zLcm=hK!@HUztm<6oT3Dv%b>@A&pR9|4KAEfc)p_SWY)epGoB)as*wS(x4BV2s`Ta3 z(QES)`v<u?P+JU~0}e$za(L$)VEDfD)3y0O0nY#3NN%>9N2>u?wi^AFM)$K_%(y{q z5tfOZy!^aPjTTX-(2ft5O#rK4in3RT)6&wnM@C%}UW`tZxFyPO!Y%->LUXjbV%zx& z9**m11)rE-y02D3NrrTI!C9s5^Wape%usKb(>F9cfTl$hO6Ew8NC~IDGV&a+5X&3j z-3z~9wf1BkSiwN&$3d~2G<wBUxH77_0ZX_x)ui{b1=g&RB4C%&)#QidYCdpeQh(8u zVBa0kv!!E(0>C=!%NniKSEN@bn8=M9vfrNgI+Q=<FLP1r<)dkrAJ}i&G9RV?juP2z zF#tcZNL^ov-V3nB+Opcmb<Lgbz=d?IQWvmjVkIqCAlYx*&S~t*)<OVcec^+O*7fE0 zRhnnzp5+R^sB^tv0lROMY(g`V@QwXg>h!nZCY#?BN^qd#A+b5MjV(dLjrA&@o@=_D z>ws;l66L182g1gA@EQ`Eo1YYvqA4$}9rO)*J|cx8x-^!0zWc1QzBiy*TEo3^-i7Fl zS9H6bwF@WrJlvQ_7DU5hXl<6nWKqXgzvUMqpis7W1=GS?XrbOx*I18t*F(NNh2f&A znO63K^p}w@u4uc5a2IEs`91UEF0O_-Zx3ejvMbjU;-@$@<C$JnjyW0;I;`qB&&RxB zz|oQXa6Iwjji+_5kG&e7+X?FAcb4ciK2u>MRsbSUhro*;jzECO5PN+U>)Us+b%vn0 z^WR-Z6SLu|&qY)QV%P4H&Zq$UPOZp~Rpw7Mnr6k*Not|cmioC5^VHWWlZmwZN_VEd zd*&wYF54R1_BpXLe?Rcs{gevca6(zx8amW%F^zxh<$s2BnefvX!?DB{d{JLh{KPOG zXK2qMstFAiBA=nNvCm}Rf2gq+?u(iBW9?yjz@*K(?@*8zxHtWp@5|rsT)7u~>pJrO z>G72rpBWpH=l+!(Bo1I{R}TH5aNtMPFX$)8G0pF%jP38k34y~S9Q>BYuwzu#c99G6 z$MC%+?{SCiugN-}ZEYSvkN#nWXgWX8kf%TN|6?GcqZ{y^42QB|7ojwlrMuB6Oib~+ z#HIA4850msq9AQ4_y`I>rid<3#7ihhOw#l3AV*vz*DUnSw**8Zxcl<tlpXjnUBM8| zwuj(ONWZG%%nP&SNK}Pr*r^_AgPL%C9e(riLYEmWKbW_lU^>W`9^-T=Y35WiR4p0Z z%PZJRVWK1%&Lpzp!Y%Jn*)c9z-_4k9_2OU}zw9)#@g||kFu8An#?(u?W0%Ce`L?Rg ztC$c|m`wh}MBV5%tLcGWnGZ)|!k3u@Y-ll(a>;y0C^-H&4BnI~qLZN-nd;O;DbN95 z%2Ep7g?R~t(~1&u(y3LOF0!C8d#Yo|ptkazG^ARH4L5?uW1r}de)%02%7^1pB-rB! zYC3@FFG64Px=?k%Ty5BREUe&OJTy0^^d;@tI|_Y)LWsyBsDdwP;G!JY!a^34cLpq% z@=O*i6-@GIO!6#_tmzHXQ1wnjoo|wJee3662QyJL(yz`FD^3AIR|S5O_<qtkqiNTa zi)`Xe!4-%*3g<k{Fk|xeZf&GmI)zV~f;tEB0p3X!&RNgDQ{D*XVdOy~2@ZJW!6|Ts z3^<={p7aj5Zc5=^OVYu{uq}kk9nm~Q>a9d$qnaN>THwkpXXV*D0QLxR8CBLRYHsZT z^aFps@2i~uX~?VHr4KlRq9j9wIb2*ra#_rETpDN`n|pICW8Nt>J19d)F7Kr?oUocl z?8s9ng_|9tI7wi1Y4N4z;>5+`M0rrr43x>p13I#JgEC$SB&jiHKG%+fLat=Xf^vdq zt6rE%5TO!qpE;h>kpb!j&j2BHz?8&sw90vwORjh0vh}z{Lonac0IZ&3x`Q+k^}A95 z5A*uz#cTo!7Sl3xzzmlxG3OF!XVwMgVrkvt*ydu34mhw{t}$C~5m5|aE2PXy7%re_ zQ|jh+qNh$w!)SKXkwDR{cP{dPe?V$!sXQ5)o3rbv&rT{3?m{x*xqGDur+RPn6L_~( zQLF<Ok~Kgg@icC<(8fQy<g3?{Q<d=9#0zT~FWylkODjyl;;6pzOY#-M_p7HD%i(L~ zR$z_fFL0(5lx6`G<V%=w@Q~7sN~TPI986uW_M@Oj-V3NgN4~{ZTPZ)+{KL%aQs5`% z8!$Tb5$Oi<S;4PG3sWe2Aa50P;#7AA4(@#2^Q-UuKJvVA0!MYpTb(?q_;MwA@N#K2 zY_K|Lx7unI9jZ`ceb5k*2}bBOiidzPnc%!G=zAZO)S<j+%ytiqQ8y3bMMKjPAd*;^ zd=*sj2n*B4!W3qpH>AB{M@|cDK%|CEW%+I{dIQ>6n;-GlEQGO|F-$yNbmW(lf*l(5 z_SVSE#P*k<ph*n(_lmNntT(7)0X;B20klBZSOJZL!Zo@AJbK?RNhH+7nl~iqfeSk| z$U&IpDohItkw8P3RU!OdZ4y`r8y3Pv2HJ5DUN5L_1eD$at>Ck54uTroul(M7CHay( z2;MB?g2ZBPsMp`9-PQRl4c?(c`nBYTUKqlU>8=2tcF$H0D3Xv(^VW&v`d&7`oS~kP zHQtw($Xp@JatlVeC2{%I#a%cFK)}4app-5)wJyEJt|;L~XlDZoQ*o)ZM)qi@2nETo zq{H~VAZ%#ZNfHz{Bjqv*GbH7o8i48o-E36=ix)(g4pTTjsgd^m7PHcf^R0&$U<d$; zg-&-AG-h1<yQK3Knao0!Uh?Un*WnNX#^a;mx!ReCPhl4zO-zt%!Pd^`jE1Mow^S`a zsmon*Ze3|22wSf%+YTv<<lgMxz4QmYY~H;jpetD)R1a;ONC1g+irK&&i36y_0Zjc@ z<5F?%YCKG{11hU}Rug^ybqgR&_qz3<9T|k1d#>&(qg>a8skepodf$j1yY1hqVjsz@ z19u-PbaW#GO4K=E`912#l436xWdvt0#DR$qs-G@ahw61fk3Kc1xPjS<U@mK)ylwy6 zvMy=GMu`^iQZSr44mYWS@E$;w=t-_}sey}CQQm&0PB2MT*vZv4HY`+a1}a<Su@r6W z4u@i0PR&Uc<l_}sH6WCTW3`)y;r8%uvgqEdBuLUHYH5hmJJt%~EFHmCCw_Wx(OGA3 zH7L(_BF~K8ARE#LboA>h^)cBZ020C$%`j48Tz~)gB!z((d>ok2`0#k{#EQ_4_)jSU z{@kQQr6pTSH%9CwRPy*MzuLx2hnU`L|3|!Dpn2-ovy(<Hw?owdL4aK~=BBuTTE=ta z_f2cODVRzG@3n#|VK83(<jkF#ljC{5$12T{NX>=&jQ7|2S#1${*L(Ba$BXtrtYtr} zn!#+_&otYQ$nC?lz|9BX)-!FYbOav_ZXA(^_bQoDDDwW1T{jAq#I}<gpfxc)aEzVt zrc$d`2rEe#i{>~O;LtcbdN<D==wOrW#zw^sl~XIvnZ}@UDYp$CYwop9?KF&qbmdHr zBOnaZFvM2k^mh5QD*(98On*oO9l>#I`S^z7^!w0WOj%!p0pi<bgarw1HZyVAwInUR z6$QDXt_M>hL+3*vXmT>~`{<_B?VIcVp^^X>!2ZkY=CM3-w?=kb6)9+^ssq=6$yy<Q zB@D@w@(NXEGe3SC1YXFf5j;u&Un_O#i*n^yJUt8pxAvy7D+mt&z$?#jL{76~#>*1H zYl_owu3N@lZFUiGj?awg1WM=iTz5Ut!40O{0bOC~(U`Ffy6z8kRd25|VnQQMYPk^# zZi<Vc#XH%=Re}G8m0{+AH~h#`{@$jeWqI$e$CahVnHR5IZs3sYTEF)6dMkLXb*_*N zc=vD`ZaYU*28+TMVcv6GYID%e>5m5BR{40|`#Jds49fwy(*Pi;ifBGv16?bh&!|{M zmH!n<uv*VnuDUL%3KbZDD1xx#wkri1OVK;F=3~Q3#F~BJy=(Ibp_fL<=qQpnDbq-^ zpfK%HASuA>%F)&k;!}J|Tb9%58S6w)>dAtc2j~huh0RV^R)D1*bDpF(-##F|RJ<uq z0{7j)ElaR8jFDvpX0~4Rm}xr~0k=+i{M4mb%Iq~_Eu%LHHfs!{YQr>DVcG`}HZO?e zsKdzAX$2{t$Zsd>@h4DKtY3?7h$*dH%jNnr4(rmEp17<GxmSuexz1`CeDO(@|KfkH zaj7f4Q!iY=vM2r0tmC@uPd~0~u&B*_RR+I{ZGII)I-cJIK%{;D=68?9-)&%l@}eVp z+;@N6q8yQ?hq&6<6}roK?s7*~=sEJ(H2?BCQ5)vu|KxQ7M2ilMc;X;^Xo=NRHSQC3 zJ+M<a+FJk1RjAj*#%vUN+1>rZ@6o(q+Pvu6mMPeCdd4Q}HT+7yk>&W|-s?TlEg0nu zu!=x%Z8Ar0w*TAZ8Qg8n2CG(He@dLrS30g+gxxCKT@}txN4TuQEjxPk5*IrEZpoRK ztj48YRfw-{ill1ysFI)?Ef5Eh)_Ll((D7(RE9AE}>`b(Ut=Zkoe!;e%oYWaP`16z6 zJf6c-wpqhN&F{iQnv-@>$%w29*_H-G<R1O<xX-^uCayQl?YqubHeJM#ZT$z{sz^}c zlkdSU@5f#C!2@{pZr5>mF&yzw9O2$E&8rGOSJjmn`dsZ5BYHefj`_)RCOA1Hp7%&R zd_o77wF~8~0(fWK3+`Htw!Os4-#)1We$D`z$aP8_FW-st{e%HqSon6QSf08nq_}YE zeW<5UQI;dDm}7&dWXCDIf!Vvy>d|we<<_y+voLAbu5uH_^~n#5<h}s<qQA#Te2+W{ z#z=euRFO%XpOS3Aj!IC(W)67{bRR(2do`UOfV%?#Ll$JDGsY73$S!$3?B7&5Kb$jJ z!_7CT&U9ylKr3Pb-FUa#PKZr)<t#=5wsbdLKJKmlL+TpW0u~yZ1S;km%1)kM_O;r4 znSiADT^mV?d!I4PT=Fzyq15db^}%?J=lFKmZpov?)Q{hiZXW<x<g25PVBo>uRf&H9 z@Q>-!UpVFa^2r}dS9d+VHe0OcK3?5*2asnXAfa>w`sQ@ql|HpsTgQ~gssSleIxj|& zZi=Vik%kP)+Yy2YG_X6!`+pRji$7EUAIHxwW}DkKBjmEpHTV1dvdw66zu&sJ-^ndW zw~b-0%_T`<u8BxUl4>-eBuOPnNbX8fp}zU~Js#&zIOjY*pZELqdOiagU_Kp}aw2_> zOGM$M!4oW!9}gV^H708AOUf>Oo!)t{=y+qK$n5+-sD#^+Q?*r|v{jkgvP;#sub>SE zhXw%z30uRh^fY48zMciT+-{Xyq!%-T8nk2!;UMXTlBKOoj=a#S{vjW$+s9ST-~Ib$ z%!<!R<9JF20^-O2x*}Y19|<w@-DXhe<xz7T)^Lb+puWm+Rn0q`zM97@SZhWf>ooxU zzDuy`BpxE}eSdqtw05ztGD6n6=R2xK;2^(Pc`1n4PsAJrC8N4}7vD6xp`&&ezb!nx zF(rPHSLXQN<jpURyTaSw^5}FSfLhAg49d*Jm+?_vC8*NoA!!gNK0xMNSc6(k35O3* zEKi0b*?xSt_z?2C{4{mxMklrwneRp0Ff4T~cPJzEmiAN4KPW)k&CTvfzcmDstMO<w zHODZuizA@k)i8>rHv+(*60j7>#`DCZXdlX`D4JZNNfw?yNkDNvDPS5hBs5b=P#z^G zhX%pU!j>DnlF0xFnyk4fb0Zc!bLhuHZM%cXH@Rn00GHHD;}K;aVQ*{h7teQLyU0C2 z*ji#)u8roB(|qWo1hN+@4n3klKW7@=r;dc+o@81JFX@PQVwKvT7y8t^(Q`@Ad%NE> ze&b%}aUSme3NRGlKd2@)hdj|c*pW@Rc*F$<yTTCw<dS}5@rGY4YN(b73!`To$Q7n% zSn+E6Ke9yhv%y#Ph23TVj7Yk6apHZxiP87kd&kdyGgCfrSvpn2d<Qz&*pw+@<)1F< zup&fjAM=SE%YZ2dv=qfg#<PQX!J8Ak>Kz-e`+A7{S^(ATl+`fwh-`oL<n~R0D<?9H z7Oq^5xZI{I_vC83%ZXeq0VyRGgeGRW-ofWU=Wn|qo2d*3vOrWg^Bw^7?eT`6VN(6+ zVH4UJ2hIJ63~`6BVk5edk}&P!E2$+Kg#XomOwxS+y_g5zp8k*l_>I^%5aTe~sCLy^ zrKvXF?AcfB#@b!~2A-5oMLWmt?ZX6~$<oixmV$v#1T9T=7M@yT_qi)q3a@^tw)>rR z>iGo%Bv;pZv?}lT`Nr7R=YPn%RZ97{B!MY5Hmv0)pQMuyFiKXjjq={u1WOExDoxc8 zVo!o@mT(5_%a@*-oclhYc*G%r!0SgZ`6o^7Zcb^NzOip>=G>x#qox$^vvAWlhSHx+ z*$|)JA2~IW0J+b<44X54m!27{EzDdAQ|Q&zMFrP^i3i(osfJ;oJ^pLUC?~lsl>Lri zvQ1;@25zw<^C1shLk{&;nrv|}DAJdI5Cl96dALC1Kp4+CkEV54L<Ej!VKmd^5wH2C z-m9$S2LmS1LJ*jrVN8oW!P~tlvMMDAWWO#X{<FkpupMpeW64OKwvJC`L7LsN0u7W5 zv6tyiO4TY-t8z-k2Jm@-i_jn(4+0?l`i`edGV$lN+j;cc3L*eYN%mrf*i8`Qpu}L9 z?r)ULP6Na8=0s6NItno4ro#$nHvuQK#3+r&hz&rtE%ggnY8OVo6DQ$6QM`W<`+BUy z_DQMI6{fFB2W}N5RkXq3rgGrLMvl7k7^n|1Z@#m4hRTmocuLp(h8HXtL-LL>LjIFO z66bOvq1t_h`Knryo5LY)r+PET*XZh&Nb`b#K{7#GX*bB-u_czSZ-*C%7#)`94G`nf zp5<Lxy<WhAVm}hI3{D!!e;&n1?%IC~-QT+kda^Bj!89n?WZdTH81Pes4VeP~lg&Ha zGx*o_2Eor<YfCdg9lR=#s(QV&>KD6c9`*j`dBlx2T-BO<bu7P#rPVL-#+D-#GjE8j zPS@eezju^Ke;OsZ#&7A&%PjJ%2&bUS83z1S&_wFxM)MBw!mNxSy7S^I35J}KA(Le1 zQq|56)+6}2!J|Q`n;{d=Bqo3;r9sdhvP2lO01XDK(}`?;Cs0_|vh)tKsHZ2*b*!XB zDZHVYSazoHSUj%ITx;S$u<eryO?CBt9ob__i$yn(tz^QJ`I}C11RirnlOia{DHZm% zt%7l%bk#C(5tnJSJ%4|QC)@K|LnfM^B&b}Y2#Zr}wD%!VF=jRrkfy#+wc6H!nzHCC zp=lm%G@kvtmVjGpDt3zj#dE%3dFKjMzyRn9z%iMV_j#>9(F-PB5=L$mzWEgd@xiX# zOWDV(iZ$R7{?xr^;e8d`b&8Ng=OF;qjkz<Dn&md{-Ta5OB5l<@CNh{;!&fYE>F53T z{VPPJ*mQlj4fmF!RU7i&k`rHCd>-2Ut>I<m9(k->0H4;HzjM~(gB@c${H??w*U?W! zQ#YK<&v3vJ01Z6T+s>UDO8XM!y0w%Chd7;ZtTsXkqDF=x_#X%E*;v;a-}L@s_jU}{ zcL;PLA_%fP+PJYT<_StHus9?an0Pc08287W0`&4h`&QbMKHbknnBIXsZ?4w$3Rt4( z2PI`md?D7JDl1L_x&tH6ug_EWWEC%4ok9IBi^mNK%bpKsrAf{hz*NMRi4s<+(jGtL z&`eGlPj%+Si6_!KsP(W#)34u`Z6v?f9HE176roZEGzV#`f4<KYB)-(3xGZxVgEf7w zCDC{_5#6XQEWVf084)7H(DM8Qc(jf2jSFQOHt=A+XRaoXzmflG@fwvW3B?PZM15>h zqHc)Xh;ZZk*~cjRdotI(@fml){@?Mz)}0jbVO6Kzc!vOR1mAq->eB#6{??3(T{mT( z$ekV=x<ao&Qa%zDvuv6(UlbI6@nfwZ4A-?;XpM9?JoMYLSM)M`#BgA=IqvBb%ebu5 zW$PmMw(}0>9Yyt%Ag*l4AiYo9w5(@72jL%3dTZpz<{QORH*=KGm>-{qJpG?%)NKJ$ zVO7XlNcbwk4(Y@=4cD2{b5B_+GMf2iT6BK>Y`&utD>dxIe|Qli1l{y6>R+B~-lO9Z zH3wE4sAu;UEYDlSuMA3mcCUnfj&RJDf(7s{7<}4!8T#l(&0Z4o@IAq67Y4l+HwKLC z@Vtpki1dezj4}bnn$iRD7GDa{`De;)(H!l|S1&V|YXAIo-YE(CAkz4}Xgs?j%u8Zf zu{-TrXlDG*LHM95fC4bIL-OEzvBD1#x<VI;y!%2~x|7VQI0ShpTU)1`#qQx|i30SJ zDNbGsgf_EWyKk<4rFj|my5`Cu^Tpje4#Ij>$>!`Zb9z^r%zj|K2eOp#h?!ur!l!pP zu*G~EB-)Vn-2_3??iz1kKT<L3!$}Ok0$WGch%g=>3M^4pVFo0W|3RQ6I3TY8;2<t% zuVCeNo6&xUAF+%g{4y%yolreZ%6wVFG3UQj-bIXJ0>1#@)N&U4NbyPUhitK$yR5P& zD~L3|5_)O*jB|&>nU16Ame%L&ac1B5*XrcPUfFVp<Lll^I9UctGZBNE#`b$A_E(_# zyr+5{)4F79yK)j9nA7O^(KLgGJI+yZSI&sMG7_f>UsaX6d~ubmQOnguKDly@PrJNO ztWTnYO_%8ccxWI%4k<Ws1z~8$%SQ5#TAFV?Nwmu@9~CB*BX#d+Rzm0$uF$gtv%O@v z^af~Kf;mVp{P2LAyNq}tp2i)$99Yc%%E-c*s}5+Ye3s4b6oxPIAx)i-dtTf@&oxAL zIrU4;qs%1;G8W>RNX;yUSQ)Fg5bkGswH;QuEwghy#0_QVkBLt)Dy=DQ^e=7i0_kz- z;;r3%H+#l?5h{)Qz(gR5S`7~(oJu@WwZUtKhryQ)c8bG$wXjBZSSfHvlSwIwFZ=9S zxI!=1)>QE~q^sjE|4|$2ogA_SSWd<y+qe~y^%s#RcPV#xu!3m?_&su88zh|Ta;||G zG4%>5O-`oQ%kK2uC*RM1MOK^0DgAq0&Y#7TW!-Or=xQij2$zp`qwTqZ1e>IdbP+<y zm2Arcyk6}*@N|Q~)*Hq4m0i4M%REp+8c`g+Gn$>LsS^dJ?KOSYJQ&8k#h1P3E&JT& z#*+<%HlSgea)+XAbLSbUP}1(PDZ(SD-@SucH<R{l9zq9RewTCHf6STvU!lmJt>^f2 zk5&`XRF&wKPErr}v)!+e?>rE{j2C$_TCS$60c>Aa7AwrLk-gS4G=P3y)JoT_rSY*V z_2)HO!}1L&S<4N`^+PnP4b{Z*7w?M+fEaXY{6*1dwk5i>$WUy|O}^5wF?O!I&29uo zx>31ZdN@aSBYUJ0E^+^XL!sNF%n1j;$*~&#vSKMMb9=<xZ%ppLtRIZA&G~&VNSaKP zxswS)Au;XCHACt1EgkW;kDuI4rQ{V&kR_x>MG{eaN?s^M=2MX)%(FjQb;hmtYCx5S zl10R8%S-Y%!=Qi@p$v0R$o?>oFmqgj`TBYGc=<qu-@}S9)iNCiLbAk;YZ>M&{KXKf z->bkzCp$ApeObbe%ReR))lWD-M)!015jN%#?GD7cD@tX1{v|mjq{$kBEgQ64`CYiG zHg_=AKOos7GY{!ArM(-qjxMhH!G*(=)ST?sMKkn+VWT0CB8>>knYFCn=xThMAVibr zrKK_1{%~*`3z2r1FF}oR#^4T)Z`WHsqqkC9HFb(SVrzOQX^izwtL1YWiD}p8(&HfW zw|DCt+{<lD?y|da)|-rDNV8Fh=Pif@6S9W}9(NX*Kkk4yJb$!MI8rBO%4ViM3V6*E z{+9a(k=cL=uhNhL+HoA_zd@k_Cu|E&a+y{CW{L=G^i0TkB6F*8%QrD*lux-b(O+5@ zuD+|>7=YOn%A%<YP(uf^tfi?M^J?|{>s_nDUQR0R1gkf$JT%$<1DU7X=}um(sIj7L z2YM^jtaQS%i)I)Lu>ka3KMr<py;(}3iZ@MG4(1*p<!x@(mL7ep|Hfc4L6VzYrM}wL z+AGRF2anRGqu}(G31B#(d&@?qEH?8c<YA?}!J)QP5RqmYs8-n}q%kK%$2pwbtsjUh zyN|0-AdOUvO67|Sa8&NIgzxWF%qXv~x;V-n@4nUl$Zf3C%%x4>l11$FV*2#b<!K9m zws`Ers#Nyf^f%_C5DT`Ks2Ibr)tBjRZnkY(J?i89m%@2b%SxC1VO&_Su2Mf|9O^Au zQb*TFyA_3o8<^5#vnm%ykD9&CfI>cwiX7uDBADZ7udP0^!``(>!dtP~N8FWn-6aBt z##M*8uJnD2{E5$>b(=4nFC6SkT}Nz8O{c46FV{_1z!_pCv*H!AD|yrO(&M7$$Sp~R zDm<0MfiNFJnCs8iO+RI}zRYwRZUz@9OurL2u9#b8SNL#PC%#Zcn)yBlF9A>eqYV15 znjQ+_V^6%U)C3aNy!R^YXN(@CgAI>qCkYlwz@uMaVvO|%=*}N^`$~SG8v+_cN$ic? z#`X_`4m$q0TQ0x&9nHPoxa(yf{DqJ(M@p3V15E!#0qA1$@q=&Y4<Bd9h=DCf)4oyM z=dV*Gn$)@FErov(uMb(*YHHvMKJ8p@QyL23y6{P}LDF3sb8@{iP^3_D^KhV0++Ze; z>u0@3hqh4gFel*=`;QInLRS18JIe~f!vX1jcvX+W?H`B|KJk}Sk;3*HmMar3?N)1U zi@0&yEyf!W1*DW9)HdIrUK+a5Fi&UCr{vF{O$w@vowgbUNfDtIOArzBEH6oyQ`P|z z4|-E}j}3Gw?;UJr@y$wso9%o$0|vuyPuN#P^#HJKy2s=tQ7^icT{aj_=j+MxS5^pC zP%{&+t{n7!)3i_x&VJwYuCnV`;GNXGA@Y+6R8eo^=dl(i`^6u6v#!yhQi9nB%(Kq6 z_}7Xt8l@Q*rbAO&=FeVW+Ga%1W2Z0vgIK~#$eK$E$ATVhWjQ?=LF*4)5^!aU3H16Z zPQVLGZ<S*SotZ>cU<gFm-#~2JaOsuw*3KfYW>6`8EfzVN9zHe(Lo_^ND<NXhf`00a zTG_=e%1Ar!vP5tM3uIW`qNt!BD*dGEi>o;n=4)#B@}fCHaXqN@Uqp3RL=_GS46awS zuIx36GN->rUl7e+T+doe2N`OvwjTfR-EOI9!fW34L>Jb>F$$-BO40d#*t2uY4^ozo z@-?!=z_3xE^r7qfY<;Q5(M7Q<!@f5Je~u35*Iy)N3g9S~Sk2{zwJ|7A+dp73QmLJS zso7puFu5=4d^NuQft&AYvxrM;@XB{a^!J&SqKRm<6_U)^;C~k_@G_bVd?l4`+>mBA zRlNM_{&h8Y8fJm$YIpSb<@@8uyJKk6wfryo65iQ_x`yRQ^$_}K(5=i;C#mkb=RdM| zBmwQE(YW-JL73Evl$oNid-Q_JUHr(oC?=14Zw0Yz^byO#nk{skD*m~{7whsxWo*yt z_?YK^Y38(urT$semHC>{jT%jc@uzE*gRug<U(fx^vVfmJ8bb9gzQY~k76r%XgS`)R z)Jf*|GoD>n8|UlM?<pE=eh*=3=;VmAE9aTbTKa4LzxEGQH1pV#2>xdI%<48*HFnte zY1z^r6_xMwNCU!(W*#itV>i@4x$$S`9<kkM-_<%1yi_C>>}59A9_`++@S~+O2>mmf z?>E8{xMY0e*Tb7hbXHP?0RwqDN$k<$hv{piZ5r`++L`<}*d$-?prxgMKiRE)_Z^H7 zJ2?^>qgi0p*>H((q9|Y{0F4TN+DQLb>SS!*USueIb34r-A>2(!CS-(-P~q;4s};2{ zD~Ym=?ml9N=ht}Z_@MVsU3kL!wfgab8q)o%OX`0JZ}*Azy6N|C7f(Kp_yqf1)cS)y zlT<hQE9zcS)XQJS-!`uAt%tr_ZxLir!qRqXqYqwq^HVoCPb&Kn&+%tOwwUf~uL|cQ z9ef`L10S1%{{}Ek)-R>mfTAX!EiJuWVP!YPM8PcmGHx6&TTZJw4=>@+Zm}<61&H+R zBh1m?ANo#zcyKEBeSFg9rpD>oKYu$aG_87qKWrpMcs55jm&}$vUNOCQrTkt}_~K6a z?K8;7J9H(61&e_fOSRli8y)ap6+mtTIjWyBA)Bu|sIJ3Sa=BqjYV%TC#-@AGCC5O{ zIWm4U@eO)@-`k!8S$mt=C%T<#=j8!Iz!~+<FyYVHxMXkmsk=A-WX9gh{*9QB&6W!* z**h~y_q$&tW+;B{d#3tv5gGWxu?g!C7wQFg?Bn&&fsLvG;o*V5!|(P?c>kYYM9Kv< z_~9)IF9h8gzkwnF7Zn`VUMtQK%^}}`8R~|hHE;_44736JECEEi1V}<~!_Vo*y2D-t z)FFG705*RVxs^)60p|cXAr-_Yp&K=hD<$v%SSSft0{kpt{7@M~AeJ_6ar)oa9hFrL zxyg=*cWu$DztpC>!tR<80S*a@fapZcpk8sa8V-2?Os%w;yuD5;TtAM?Qlu#vHis<} zMxWc3LS6z?9nIi_9rBCAXs^&(s!62Y@p8kBYO5?^$SXm)SSJek{;B8vVM{oG5`{)< zs2`n)OMQH04+iv{nIxx+^%@cmIpHV4(Ga%%D?J}`iSMifa2IyO-T3Kp?u3H8?Mv`L z7k91y`EZ$myv0|WSS=D6)C&>D9>p;P^eG)+H%I}_2@b?^dSO6VohMW<@h$-P=baK_ z;(qB9vgFH>=ZL@ITlqwhsq_PYFfdb1^l<)(BQZquom>t5<e&f%)4?F-S#gUT+`V3v zoP(r`x}1ev7cG!#{1|uquo#_}W_9O<hi~*=*T<ylSWZEBxeu2o6Q00(Rs6cl4bDcI z+}QWG*Q5PlZSp?n!)no_<Z@5>aG+S<$!6W`YRS1EK+{_6_lx3B_D1M=XaNKd8YhzB zy$~TwO&S@cqkFf8c!(;`LO{LUXNj1gE)FQ=%a45Tkg6_~+YdKWM6J)<HDsLt&x(nV zG6aGw15Ekl+*kk#1Ym6BKpc#<V6AHqpn8*sRA$BX4rSNLAGWEtzj{0cT(F2{w|%!k zll%m=2d^`xmPHeX{EOk7IFM;92aV=$jq5kM5klqKoQ7MT60O#V5&3-cItA>W=uDB! zF&I6Avkwoeic0S+Bvuq0ggxIYa6o=74BL?##n?nm-X!jC))`=%S2T256L>U&A?+oC z$%G~Qjd<fTmQ==_ZC|`KkrdkifPHG^XZKc2P+z0kK77~z#)4fj3j(Txc8V>_@c^-W zQ1z@FOrjEL-MTiDC=+`0n~WGwyvCzli5NKH^zJnef|y#L$7isWAm=mG>=Aq+NB4r! zm+L1gm<v@x{G9o4v<p+tG6<a&^GA^K{UQF9ic{2W0j`0MtZal!G5Fy->mqQ$tP<cS zcBztRICMVT@hTFEMUjpEfFR`kQ7WLrMWszNwnTv8hP&=nIY$G{h$4GEH9~*ZS9SFM ze*e=rhk?Lrf41&Hq@=2dF3Y9oe?@Rq0mB@nS7mRBEpPM()@pqX#o-@Si^Q)0GyLIj zX<LeLK|wCm7L9i7fw>f{M`fCH;LB(E=gMbw?bNQGotj53^c|>{Pk<UtERB&R&)3BW zyu(xG_({wOf$zut2-KOb@l3f%b=!lp%m_EvOe4GRPRlOEAIW6cE>YQKyTGpw+NX9m zR+(zb?nSA`(q;U<g=&dWkzk#D?u9(W_j4J<FcF|K`okTHWN?u8*9=fJOD|cbR8wDx zfqD*2?CRT&MyvL#c!aDTnh8zk1r84>ra8FqO&c@O`P@|#JML@ZCKS+GZn9UQJf9N_ zG1?pcxsu)y#kUZfY?&q>5Ri!iN#UwAyp4GcEhXn>Qa&3fRxidpfN(?*V;R3uT<0zS z_Xon~nt7|!sqb9;I-nSaq!IuN-FoFOmZe%nXJ7Y3Gd%zl{Xr}hxAJFHhUezX^8s8b zV1@#M#t(`iYBeCUGHn1+><*8n7O+tu#6HE*?i5h_+Y7hz@*t(MRppim@Cc&*k@w%T zOdwg;<0orfQdPg6xSU`s3*8*Mt6N>K|L~B*$s<O-W0(wx_%VWmB0`kgi`gb9koXUG z)g8Z;C5Co919Opo%?~|Ux6|Nb*ltC&QMQ;~DIwxqYp=ey^C5x3&P?J%(9WKc_kTHX z_r^9lGTh1<<wf)~^vgfHTTpr7%c8}w7K>*_gK+pDwFz1+Ypvg3Wm(WbWI8eWQHOj* zzbF9OH%s!toS0-`s*(Xl31GC=Dwu^+-JX@tbkrq^W!-dmg>ePOv1*sP)@38IKOE+- z?L^NWT2xlFoRuR8l3E$prsuC=S2Au&@J-1WKIK}Z$2z(4L{k?xUa1BIHBA)bh8sEd zcZ@?q04mst0bpeqNAjX12mPJoMUs#~Wc1ZgPZ$9Gx#Mhg@xO25|GH9XZ`;-4kE;3* zkiejeEqx@1idE0H$z`boD;LxgtzF#<bX_}YdE5>a4Qkz6Qn<g@bWAwz*oXTa+ex^d zhibra$w2zBhuVX5E$i6Txv8<Y8RdUGV<qC?qFw=LPWVyVocrZ?32<G&Zd&yAmV`w= zpWJEc%RwjCGNqp_?GT$M;v=nA8X+Y(cQM&B*EQSA#PNjBK{URW0mwkaehu~Vv$Uz@ zE6GSXON;fui&oGX(w}V9F9?VDF5b^XM^r6bn0l8pL~OOTw$T=6b{Ri$&TU<6cYAZ~ z@UH$`ZuD|-6F2YCxxl#v$-^1i0$BoxHsAfLGsR$`Ir@}j;M8O>PA?>!FvS7eh<U4p z__UGyZqzNsBV<Kys#B|}ZL9!2f?}Xe>BF-!aP{yW0q7p5R>l-1>-6mv^nQYyU92kN zOf>Eo2>`Qt-~GdMPs?xKRu`lJJ=Wa(elUQ*oCRZv=~Vz~#*#Nxzg=O}f;IaV5}2_Z z7dKuco}u8gRZ@T&i#dKT>w0Oi3Txr-Q$y|CpOK-)kqsYr)$T25MW2=YQKmp1G-7e_ zxUrHitq9`)OcDIeoMK2yY_@yibBTG`kmykDqEabl*~Lv&8U9`{0S*>eI0vb3XeU|b zP#=6>5<$R4J$E_`CT+$+kSQK8rj(Ye&AGyahRg_Pccoqk^2nA($a=8(eI%_~W~?ZJ zm1^Ep5Unoxu0pKr!iY<b;pRA4(Vq#3J=>FY@tuIReThEv{dw@Moie@;n8Itz#Gs)c zbG6-`UVWPxh_T?*pg(2DnQjz0^QVOH6>nm4JKw}}h~x~Bq~oWQMjoTzAE8>KIhCN; zjr_BAk8g)RzToS{NF!rBG$2|^z??BERaov3$!O*WtPL6`6r@cX(B+XWgpIWEmSx;t zsahFT7b+}KOK%Vx6=w|U*%6LPFMJ&Pyfw-GSb8+MBImvr!L$#5lqN^*`(iWVc*kv} z3gN?_Y9r<B!zeog(6DEG?nY1Y(BE$)zUqv-HY~?NM`fclK`6;yUMC`YhEs0E{e^<L z$%z6CKng@8_;Z0_dZw4mFSR{?>b9$#7zd0MBgJx17{*6`hCqi12^i|wkm@@Bp)>jU zpMI`yIkbDqp6Z=7dUY)6ugolVe{AIx4;=>WmV&dTvx%wFWU|j%mCV=K{EsEl)=-Es zyEmv$WA>;5B|p1h1hzSKZNoYNB&9rL^&odR^v$QxTEEUb@emXxd70q_qMe}^5jQwO zULVo?P64Atfl?VaxB$t|iV~ad+0kdghL|HHgnw0AbnUy#(jJM3y{k=^6fY-g=7=JB z4v>AQxdbQ(_y_<YL1pRh?Z3^-WEQaJzRUO!y-$~qhl{xSlxC^Y^VMF7MK@0|`3WsU z{W6<)-{HyUul9T>M6$g+!Myr7mEv%<T+DhS0}+>5{L_9fc!(W_^0`Gprd)YGKmE0i z2O~z>`b&d*5mDvU#J|JD*h~54Gz89#_wPZHAqQki)8BZf{wqLZF5BW3fPGd3O+JAp zh)UuE1H-F`u~k9te1EJMb!hJTP$khz^4q>NFs{a+E#qmJU39q{@Tl-)d5s<Dihc9c z?K+;^p+H}Lf-eQ^l@aXKZMF2KjJV-%Ck5tl!!2+`EsW<JMR*h0=|tlX4L@ZD4o$m> zUoW{{b>-NEM9%<^+Ofa%YOyR&iZunTT920O<;ew{4Ed~?_M84(l)@NvDLq4sgZ%qM zeRGdsTQBv~pYJz__FDuiBJq6ty*NqNYTBkgV0YfDs{geBR}A$sRPMU-@hScInz{2R znW;L;#8Vtp@Cb+~nSHdd_lv{bFNCGHCL=Z8Ej*rm>0YVwKFnb1#;kOkEWoZ~Wf6Ja zmY@7McCtVCr2x+8k=5~TTZ*J~#wm|;{Pm}uYtGmA*XorM;pu{!M8SDt<Roq9P;sLn z^%bl30f-1n23`Cj9G0O#+bL2-m4>Gt+s0#sl=*<5D%o^yP;+{6o<C(K#Q9$xar~3b zyo|`z0hfG<WQGj}eIuc3Wd4|6Z)vFGv0&L5uf%6%X8BZkfG7tL<*~~?*qa4{d)!m% z%Pc`I?qAhXl{_FvxD!2X|GnmnD7$a#*|8MHbWrtOo{%wt`qF-xuQoMYI{sT-CCcd| zPZ$SPULa)X;VNm(hk_vo3;t0Uxv~9VETEVSHwV$!W=f2e*A{+Hz-u4yA~lS2FRH7a zWf+%$tV97j4~*fZGxC=TnM>zXYuB37B~nm_;ffV*cG^|gyp~Z(V~62&AN+z?vsqtJ ziu_;PvTtr(OKPxbMewk5c+QT*7hUj*RBl;=B1uxwcY_W;j-bj{RL_SX8`*lZ6~SR1 z7e|NBtjh^Yl2Do)Ar$ItRsVJCegq515QOFx%js@C+4^$CTT+>}v-ghnl$kRw#{p$j zw1sG680~PI17P@}3`VjQS1}@ErjGx#(Q9gP?%5<e%0?Et858d!9XUI8tFJMCR$?hm z9*2P@%{BTQO&x6MmoHx%!W=482={RVCmmlbstESUz9F|=(mdkj6DHVqbj`<!z{Nn_ ztSB8nLo(ic(mnJ3NN#xgF&OkcqfYbbaBMba%1?L$aHiH<YPs;~QvLjvVB?p=$wW^v zB5!f}`|H<xHieCQxWIVPZ-1atoDWs<iD+1oiDVoSga$$7UuTf~FI>$s7q*t0emUmg zT83?OR{e5wDBj~s!e*G+*GaQY|Du3J;!&`*UrQD{>RIO=&+|srg5!(csbBIHs^ur5 zj?NcaI8-ce*-(#CdWf&&3%NF?L%N8N&@d5C@4!taS}X+l0h-nDS1}DFU=7DtPG2Ho zflxP@$@*yAe+0k~(xXPKMpqHCWUL!r3v5$C>B82itTXFs*8IVL(bB%>N-pP#`uGhW z+*P%P^SY!{JVsWYPT!LDX!#-tEv$~Z9ow?dZN<WHpLO3V#4JaHR`adHPtC2VE~^&S zRW!Qan$xeNz(dz6cxN*j*O3b6&9jN+%bxVhN)eIcNV-+up$4}I>dYa|!&X8a4_Ng{ z&#Qx5PcK>YJh2FaG$*Fh1sJ_oU$oOS?z)Y07WP7;wbyG{y)!&t*ZiS-mm5piW89Vq zzTUD#B;oY48dJfW2lyzU0U_Xb#)4?;py0A>F8K1aN72~I=?k|mr3k9&5qy<Y)=L|y zHfZ<sh;;{H%j2Wxh|g@#&G~Fogmvi{Ea{#!{i0yM(+o!->KJ7zJdM3t(K%?B-E0#> z^D?}B@nh@XbDMX!H$J!nQy2>T)-|#fCBP6nS$fcVUJ)>5LErP*O@#<sB3zV%eLG+g z=gUPrr<=U<^M*=AKiy*G%kK%c`a(B|VW|ofu7ceU1qxL6M7x4v0wq=*AnK6VQSz*{ zMTJ)Qxm3B<JM%H2rzWwE0>c(9=`p!`f$L&1K2aMYA6sM+0=igLM~89znjEwpU(_@W z_2E5oFaS;?ip1DMCjvkyvU;Ia3$5+%t!ViUH6N^PcLqhY^KvS}iX#z6-5Agf@#&NJ zQhlzZ<4mBBCVKRa3uVi8WK(STi`PJe;-FyoVt2pZ=>%P2hQYmlg&-YWPaVK6!3Wy9 zUy20+TMFvGOIVQQW93`$?YC1L5(029)k9bD1vk^7B~h9ulS*WK%WdJCjJ#L~>GNGp zI?4{jbBl<A%K&mPSG&#cPh%<b=pKK|G;;wf$2`Hvv>J@t`5h|;bn2J%(PNp=pfAnS zot4aNKH-5IHo13;V`Uqp_U5sV(+BMZ7vFrlG<|ysbCbwSaLMF43PD{i!S!4de4(eD z41PNBh0F85S1E6IyOyMV>C3=$l>IBzGDY*{)2-5;7~c-Qa}`SF-xl_NJZ1mBp1J?? zngCta#8&RpU1HC^68(d}coJ5WbK%UUB5&vI`PeBGhd5l68`ggsLaX@q^5)X~1th}C zY~o3J*o?QYZ!QIUC$U{*eih3&*_s|^F>|^?Uhe4PvxtO+dY-6n&m!+7Wf2pi`EE+Q z&XUgsx9lVp8HeBgRT3+74<>O>#ALc5FY|C%Yc~t}Z7SyQ8Ccc@g1zd{SCVzTW-kUx z4{QU3w`m}w=f?&P$hz;vGn}mM+*&1mFYpp;JX13m7LfJ`U)J4{K3ZCNNmUkAdTrbI zsggpyH9gkHG)p|-0Alwy@B83~xq*KPhqZ27xqriZmE9>Y?s8mx%{Zu+<@ZA`GDdD6 zom!eeIoIU{Th9ED7{g=0`nhJ%#<S-?N9+ORx(fSn7$I@C6#d@a0s`Mr4#tj;FY@%c ztUO66KB<1S>NqNtnP$%VUGxLV+<s#Hq=?9m&!<}TerMKbP5F8~b=r-lsy-_!XZyzH z-rT*lB0fxX8=-&mN`(-vpD=Wd{1I_lCo2}*8EVpL`-5=}uJ>cd$&;LMEkWXkzBQ!} zI7~K;uXFgX%tC)p{p7Z4;;CUPCeA%e&;0Q~%-G?p!DD%8AMg;G?+vtIhq%hgrCzPE zJ<bMk{POQpJRn0l`{`;^4ZKyCO#J!&!}(ACAnV4zj_1Pt>-shiJnH}CQ~t3w=f<7% z#Os*6ct2P~1w=UD(&o30%pYP+Jn4LtyG=ZbaPG^;>7AixscWW;#howtsdAF<6rsz2 z$thNLdletF`*maUR}Z@v*p(M2DV&p3xA#}CSr5r&*M9n%e!u@U>FID{lfY39s#WuC z2Ic0DOT4i(sb&?Dp{0Q5-xj9j{v`bJqN95<vAdc>28|L`KNG1XyUkV#A2&b2T6Dyp zQR6yik9g7#?){GIm{k4G2Xcd_+r%uoGRmo4-{r~$ALv8hMDS|+1!|ayub3HWen&UZ zWT>JK&h1r^?A8fXA5sqYa`;)LGxNAuu;-I?#lCM|Kq_ZND-4f3Tl!z$Qz-tV>&09D z5l#U7njj%6HY#7hTF!$ZDVn!WD$~7>**t%A3ZiLDPqCf#;fK{AD5P(T7d3@+CDznV zx}@_65j#M@i~!9Df>v-d+;~};4(An+3xWfL9H9gH5nD^nWU3g5xC_U*$TO~}gQ!`X zg$nk-(TK?oL=f4*ATnv}e!HuE`gOzaP~5oUjdY!Y7;WQ~S2r;^av-sO7yoDUE6TxA zVp)4ZwfO`i@*K1E)e}mV@>{vu(JIINYW(<3o!GCvM)A}0A`{lQKAoUJe*VuqRU#_z zn*YNXhcJq&>Z;aDfirn@Jz$urh3dByM93?Z|9JV)>~;OedXI-?ry|pTPlISl06mS4 zQE&rTvk7EjMc|g$#9Uim`aZ?ddqU2Cj^TsK0BOQvXBg+u3&)aCa+QqpK!=oAm=l*F zihgsn1J0Q!la(p!>2?Wzenq`N`JB;4$X=%D>G<cuj-udE#cHfJl2#kijcD@BV15>9 z{$&fV+nN7>#8V0ARdnklUtE>dsKiorCJZ5mVt8PMfDM2ni#GvEo7B_h_c*q<9|2Sd zO=pA}*2-v%Ro5B<oKg`A8C|$cS(b3Bwq$ZEf7J^tfzF^Ci@_luVJUt%C~If&`s=T8 z_Am6_yS?bR7^MjSA4KN>C`ywMgZm6{KzKY#nSfsqjTfv^?_&u9+NqQ<0cqY8OTq34 zw`M#;Qd@|2SKo?(+Cm-DlC7jnq8^of&B-E_NxN()LL&)IcR}IuERTDMZ3sn}k+^)J zYa9D>(Y0cU!Mer<GPCKD;rxna!OUwotxc4y@^IWON(=wZ?Lp*W`dcr{DlNdNn930K z9Yz2p<zy%}0|3K`boQ+_dTSJj2kW3oXP|%$KQ=#hFP=jOhiD4F&=-#>ot@C%r-Sog z`iOVMLI5^QMT<<xqL<-1?pyLSA@<R<R$(poB2v*bqJ(lSi^%_Ki<`4AOTkBINi2`^ zAIJ{xbq_UeBzg%;ux5QOCp9bn+g`n0WZ!BWj5L<}9)vAdW-Qn8*{qK~q(4=UGy`s# zY2nGwT*LYg9GENlLSJjOY%%J2qmGX|o7j}i5RD8#DCEOa>39Y)rt07}7gIZ}+~Aiw zD(N)?xKMu#$YdIQo3g(+nl%F$3s3q%7ywMY>V@`#Fd)OqiLW|^wjIn?2RLR`)-uWs zI7SzQlW!74p?=-?mwc9xH@D4P&mP@VaUN$poAbtp-J3%KY&AFLl6}ymkYZ(N$=!td zP(7I{0JQY2-dWiwn5pk@GbplV6M~4^AuL<e{v*}04tsrzdhI&sL#RF^az6^ke~v1( zR$XJTp>)*zl@#y~23QKr!(C7y{!(_=JLe2u!&d$fRJG!pxNrlY)vGj07!;?ZYG2Vl zD*$RWI*qCYkRag|SU@Uc34t$}?Olx+W1J%4kyIDBe|?~o3<xlB%Pl5*WU%HyGs(b4 znhcl(Cl7*9!R6e8+Ri0+*`c^Fql4blvW5S4G%P)O;r5R_JJP$9!;eIkIa2W1bQVF6 z&R@Ix7RqLCt)L%_?vX?l5)tMSeE5Mfp^45LszA0C4N~xyn3z=3AsMSyeuSCRwN%tS zzkV7r`++E-2TM3b;>)~xY_J?i<3k;RZ*9_rj)X~KpR#!li47uolDg@3>fp;dM06O_ zGTd0z{!ZLeaD;6ARF{<@B>W>WKTIQ+VW%b0A(aRaOEsNBPeP2m$*DK`=^J#RnQ-{< zt{;;e3la$N8nAfh4AXDz6}seQOCW!-zV6&4E7W`3v(s~c;T2DU?^ImO*z7Qu#sF=F zmvI6J8mn=LB`Za>vCS^908=AtSTb^YTG?4&4__iTz5J&QCFbku;sYUdzWlwN*!%S{ zu&Ym$_vF2--VhbjGUCY()KO_N``-nPP!-I$DbCoi#Xo~`gcL()zLbQr;ON&D01-&{ zQiUAn;grA#k^`U_*oBnqYk(8<(hj!-j_1EG>OxAliwOQc<sq}Sj4C7f3zbqS3V<J+ z8U{tb<51Ab1=7wdQ9k_Z-kx2BB0GMY%0eI+m#G`<qw>u)1c7;*V@(n+@J)Pe>w5ID zNEZ;kExcl4h-O`dXtG(t)Ran4IXALO#wlkLOhw2N5oQ1bBa8JO{4nJ*UPDHmG<JEx z!V=O2IwPSHgJcaw$gpfGqX{`ggdG>78%c2>dmFrE5n&$xb<68FvtCClZ0w=-qh*GN za0Fy8!en0}W0dAH2>Y)QHGQb|va-qGv#)FxS6Lrb%Aw#VYO1ef6`-<|ptxV7(w3~j zqM&OYjw0FvOu<@A(pp*gi9#QCm@d9!{Z5Ps*oEA(+}R}+RN(5`l)u|442@sL&TnMT z3D#9Rowd0T5U<)aI3Rb8-_P3orbISwBY4tB;PeAuf0bP;D&G)}T>2WSbkq+{Q6i@u z;HUlEv}vM9!Vw!CC<Mh1#HYjwJ5u!NKXnPYFe_$h4-~iuCNcrdda~1!;u+8pqZIo= z%nKuyfg)0NF6GNNeic&*DN%en+Y%RXhlfZB<ktNyw&FG*kL;D=MGCq+a?a{wjE^MN zAM$r6hs{0uB_1}UC^9cY3JA&&dEXh;{ie_ik8~9Kf{ml~9<rYG4f1RwTeW9Pg_fJG znH}gBx?ge%z27yzHZTnL#~sC_h9Ei<@Cy=y{<&@=7cbJl&Zty2Y}1x8!;XuS*QCyw zXhBtplHUxAs>QFz?S~+NNF^e_Wf5xs3$RsO%02oJ0qnp0PD3EtKnXxAz4DrRvc*OM z=gum=X_pK+RB?JY_U2g_SfFT-i{pxY6VAe5hLclq)^W{w@Ybq$3e)3=ZOoCc&LnFP z>W?NN8!yWpXp=GlY6SpS9AokpdY*OS&m<_WWAB3nV9>0Ph4PG>n=lwTa%5qm%EhcU zC1*xF^rHPU#`qt6@}TCiEqm6(hnrc*Lt{k!C8!i-0d5txGl#9d@hg6)868$%HN<Xx z5$^E0x$<>64xl0I00?vyfWu5FKnE`H_YpW7kZ-tj=#Ih?1@0%ZIr8>sw%}c*Cvw#! zUah`^DP5vpwA}n*R<Wrl$%2*~oA{rvRzh(Done0zhFs)@xaWvTwv(QL$PZ<y|Drr! zM5fuPM4zq3mbCs+>Wd~S9D1MoG!ok<r;Oh)PrZ>;FKhT*vEk%*)?s`nGiJWpdSgKy zUfp+mnSapAxCh9N2*s5H$TAwDo@29@&u%;#Gm9lRwFPmC5fE^cL+cPoSv^y8<Y)b% z$4n(K*<lQ<FiPb>jRSuJel1&ecw+&?OcYM^iBnX5g7nD>=>YUEKa6M<YJcUAol_lq zf|8(1i~=kCVfep_MQ#E0tUQIj!wQq3IFHqP#ls#KhV@29^p;Kvy-}Z>`8F8ESNBT; z3(S1L)_QCYD$TTpZPbu|DV~LD$c=vny@tt6!dz!Ud^h}Zlu<AAM=u-4oE{`PQ$~^h zp582x<MZP5&}axRRJk-52BMw#TbGCdgOPc_2reOs#rv~qw8O?gwcbFpFU~_f2}@XD zY8*oaAYb$w6A6cvg01&*d0i(7!dQ?%b(N4uZ83JvXS5oPAxXO9-v;0@4LquiG5FCJ zfJ)=HpuWFY^4?nw)+S1JMJV$ZODJ+qNI0OAD~K~AiK_ZT9YENH0%GDV#azO-V!n?Q z6_5#q0>ABJ$HgE(544>xkKTH4L;!y)ZCu(8Up52JpNTCdI{7&Cp3~52orl{4ej5xi zbai}$<-uX@fdgv#z|7-$TRap7z}DbJt-n!oO#O9{+1w=S5WVT}#kRr4N02jxiYQ4s zLWv|ov2#Tc+)$|$-D<Qb9#iViC+Uxsn62u_e7aCm*ps1PTot($b`I6&@r-vJZgY<n z_4t>T%${c&cK#$DD6BE><#F&AhBG=-Y&{ae=NhA`d!FY1Q@5O0N8Yq5CamI7@CTBq z^rdio*nCWPq|0~|uD&5iRj99wgH+=1lyl%r_7_SRKILU;eylCn9*<+kBmJ^doE1$5 zWCCgq?8l2m=NvGpN*b2<wJ$%8$KXOnQYo5xU7!1^U6h{$f`zO2v2-)862T6EkGG~t z%!(<21RDL@bSd5rbCJp`@<b4R=kvr;+uaF`4{KVe@0Zpa?S=j;)Z2|;m&{<r*kYY# zh1Xh!;6vw<hpRVvW!K>Hlt^z_z=m;nH>S@=yWL+~^~rqdgCvKYF&vd8bUJZhVQ;LT zheA7+%Yio{jksAYx-h&4(MXG+8~a@WG-F3|Eo1zU(U;A@rb1FNcn>P#Pf)M<C3v|L zzS?OVVBa3g(o2ew5J~k_=K<VE0v&O#y4t3sYFRD@tKct0@n4w`2n%~wJy-PXU*O%8 zD9s=37QYMa|FtV@w`v^BAbua~6ddOfql=hllL}U~hF+lMu`2U5+BXlYHs$ON+R36- zOis+}p!;Gdu8@yI&UOiS3hMg)F^M+-DK=x1J2L|#GuED+VtyWj5q|qne*rUFDMh+Y zHHXbY69D!Ben3nm1kyeK@<O0t04FXNE*B7kpumo(+&+q((-kI5>_u{|=d5ES=H3LT zskqBEVEa&*+c%Pr$aYroU&5>1JA9VHr+qSab$%oKnYzP=7ROT<k)_MW4`%#p$itfB z4`cv>VgA@7{;Wa4&axM3zaY-{L)8?~(Ue2{Z@Bc81xvh=%N7{hADsOZ*g-;oT6Q2W zn8%6;ttY~dqGvIEjz@WIK1C>?t6`^I4{Llih<l@#c-fG;*c9=y`G~q<VJv=48NU{F z8z2UiQ}v|3WG8*?!&D;;+VHzLw9_q&WN)#0A4&-vnrbiGdXmqLUc^0lb`q^H*KRNK z+I?mV57s{MD&KzXa>9y;h+(Kuv<miIuRse<tW6D%=zPDYtNhIm?0<(WpjNyw4UfhU zz`WI_y797qXhPWo-^n_z51(Idg!|ms`UE4mfo5*D&G4$u^ptXfTrJb5k$6LzU(6HO zS*}Ou+l+V;J~b8xg?SWc;*W;nH|)F(uIMEn-f<ByF+kgjG@&Fx0;T@G2j(I!MuaLS zwn_V=4e=tHbYW?F{&?&vDj<qfrFDg$H0f9i6ij~Y5R$5o7O58TA>pUrp8M{sx7~_0 z?>*2m6Z7~0E@AaO97>e@f%i$3m(wlkBKzOWBz%CYjcnjspVO5!1FUooZ)LcimD8-X zG*)K@>Ky>`aeS%(?CqDpe_WnWUA(&eDL}z%FIW$Jyu=~7?Ud1BBmVjTcs<qV^N|oB z{Z`P!g<#y4GNQz9fhdshhT?LLY<=slj*dUOfy6cLcfI9Nbs;-cbhKZhO5zt0onLhk zrMWtP=h%*AI7hJHpYyqaee8#U-i(L+s6pOqL;R?x{mN}DxmT=y1{nkL<LO-6aQtwA zEclaZA+0SRuY49>s><C2@%BZWuhu#C)FdcKSbReGM?mWK`nLM-Pf>@E)igxc48)v+ zEao6`I6<MW4Yi-Xl<sR%8W=stP&|1#{T=imPCyQ*hkGvJ`<ByAd<{(Wbn}!IP`a&` zuXtt&0FprhN+5JGFCKNDAX6=CJ}<VXO-H)*V#v1g#VQe+0p~ncCwHA42a@$hy8Oqx z@{ZNy{u#x3;V<0g2*l7uzJ5Q}`_7z~p*XLl@b{h+#Ea$|MJst1d&T=IDWE{=Ub5!T z7#LWi&=JqpIt{BX`L~dIje;!Xr1@?r1?#4_)hf6c@*cZyKL$n4GZHyLW18Jc?juK( z0`(81ifb|Twiiy%<0@K;a=PIFayA@97troS&o!$EN2KWYrI-g<Iw*@M^a?+H`P7gk zyb+r7v7=`CtF$nI_%2^2GPT?j(!@&^?eY<o4#<12UycS}x2!ra<p+<U6CWE@eA?>D zpS$!}A@)uT%giQJ8WrcwHQh5#@P!$F;-91+2*}n<!tWl@b{XX@Cn5@oP81^>clE99 zx)U>vw#DJ`Nv@YqZ|NF$>y2?G=OaP58O398V68SWydzZOb4LH6ZH9+iP7+>p@^Enk zjz2QFGzss=MQiu+2au*!=PC`J7m1<%21Fg?a?ts`n2pe52ep+dU=G(pEJVn}HzU_T z#9L@`6NvcWURe_<Ks2ORt$VUbr0>D!m)MbHp<p`t!i<Qyzeu%x-CN%9XBy9^bgIW< z@lX3&9$;?wVlTJ4zLEQdYfLP3PQa6Y-kb`C*8AD`Y^4Qm9l?-K0WToTJ7Cy)unc?7 zBe~uEiA)k)C?%|UFWEA~GxL<T0KPCDr<9`CM{`#7+zgt+DQU6`6osLrgHHxsr<-ZQ zRk1(+;Em_SBIp90c#JAtq4V^4Z6x++dd;t2_^-u{%R&$OKlB)d_S`Ag8}mHh<m==( z%WFQ1rP4)qwY~=M<vzbHa5<-1PFH2~psa3c_f$aKZCz{FoFFnK0Bzjr7j9fGa+>`F zNxsZij^j(60ZWu40!FOPr<NxFnuUQK^=W=#v7^btfY-Yx-cKaSUqO_Er{aYCGDJ?G z=90X%jVSk=u+^zAaRT+!9c;jxjlcM=??Nb*KUk7T$wUNNTu0zi*M~IcdtecOj-k#@ z7}KM^pepv(b)NC2cHcNF^v*!9=iu`PDR|BwJm<lO=f2Mm^ff)X_JFtg`J2=0rn6Z7 zO%c=H;g6}E&qmIb4mYbkd-MVG`0nC;*b+!!hX(jHtgRmjhN?@yZ$SR_<|PLjl<;-o z_;j~<C#)87XGV(SABvJs?8@U)f7)tK>AQJ_7)jw1PvMRm;wO(NMOL3ORCo!izAHmO zHgb^cnpEKwllr)1Of~pGDk_4G<To(8ARu|eR`szXM%?{=jX$3$sStUn_R;BXQtITV zU-*vlp2)rrT79BXAlbeLA0A2ro##K00-m><oL|2z;(+Jf&jkAPUO!)L@$L7qtW;8z z^6IoKesBBFqShQH?xD|*a{6~zaKyit&P645X#68Ts22_?0Rf~XUt&_@oIV&RT<>tq zgn?$-&;gm`>HWacYek1^1OXuSQi+t{T>}L?W$?Avu{8cC+ey6GPd4>DkCG*+1T5(W zo^R>)uN&`WhegQ~q6APgT>$8nz>)5MW(~d9(A&3)zdK!y?pwKS-Xlz2<?R#YUchx; z#CQDrbMN1SW*K1k+V1-<5huFH(G^~~S&`BE*js-c24XBc8wElM(rR+CJmPY2rauTw z<In*Znji+}$fTZ=nCnd#aJZfY`7#LF2=O}zL_#Y-n%3+C^kW@BD}m>Th?p!}(ti(3 z%PJs1&jT|cU_b!S2|z*p`WQqZsSDP$8Gr_f-n(FY9;w$je$x#xho8Y6>g7LJUIC2u zEsrz;Y|2jzjOYV|LzDhqb)Jy~PQm8H2M3nPbh^a4&0RPe=*@ybl=%Ie-Kbz$J!!9S zb{%yfKiVi{e|`#7m?GA6QCn^<uFhymdiUiO4@j`hbsj+9&9@Ue)*=8Hyz%Zi^Q}Vu z`Ki?z2j4pZcO$9g$13uRM5sP&C1<cnrl^2l(XX{@y5Zfr8<=Ez?*BMC7k{Sz|NXyq zw9TP8j5*KD`Fy6tHXEDsImenaMa`*{4jaRqYR=@4W0XTkLaI52C^|?bAxfn_qJzpi zU%%h$Pk7y)&*$xNyB^ndzhG8>ey^QXW@k%CNv?lid~9_N`sBkFdbu()@%`joY>7uq zrtuS^Ut|yra0?h<VVsRYyL>T23~A3V3NSpJ&E|-%J}$91G#sF@Jl&0Z-#w1kY#YM^ z|Jw<<2n8(lU13<RIT}emr^0gyRWjg-L&`8PIv~+AD-G#J5YO!~WHOcgH}F`cO^fGa z_|K$OERaVU8CP#{tfgsPj)tSuD_f!hy=FigSBXt!rXP-;6#M0IqH{@AmeghN@k30? zf-O4w*6*Jl%t7IVdEMiVc{!y(DS5j5s;eftVJ6Q|KC$BT`@)l#BX7$C3n1JAag|i0 z0DQis=8Dh6Zi=_M%w%W*Nh=u93;&IqNReXtsjhx7k>NCP4=!&A?Wo@Y1#GbfJhaqu z*AmgHb#b>)0Jn!6b)%C2q7|zuyN&pDZ9j`B8hwi`;1x@oPQ#!Ip@0)2s@Nk?u2)i8 zu|W${m{sbQTg2r{Y5C@v|6EN1pL>v*R4jKhL$x+~Gb*Cm{lhiS(kj!&D4;z&LMu!6 zRYc5%S3l#9Lx;52Jo*N-U9V(L1k1%85A6`tXmLGi=vm@z?>bh?+K*PNKmMX}7@GKU z)#Fk>s<{Qg27iusw(3&65a&x+w*?FL%(}P}4p4=a1HMIb=s1$n9wUMy4upUfJp?tX zH#`L761)bWOR7{r+DNah*7`k#$%m|@o1+nsN`4*D=-J}4G%2tvln4Iu*8^jF(RkOL z7GeFvwjJ^k#Fqyzm6V)=3J1I5uD6piHBrhb*kWta;M~w*RN*I&3ZLLy{81l>LS&3c z*R>gf)Va;0FPppLnA}$ZH?wZ%xJcGGzu9^A3#{>K4MS9XVDDvTV`u;06X9WFl1sc9 zPqpcyRM~akDX(>l$(BAiKwdnKhQ1U$obUsEfaV$v^l&}6D!eXH0xDpPjMmkMA@@3^ z_d;h*%#>92BoQ}H9zZ&x!4HLXA=oBjkHR9bmk?F_Uys1M^V<>^TC(?jc`^ar%i*&* z49)Ko<!Oj~P9%s(gBnyy{!1jJs7K+jXYB*O;tn)Ue>e%yxSG?hT*qB>ioUhm<mn1` zOKxU_<-)fk*NV-u+;BPK6$q;5GKH5X3^jqcO+D&+Q9i$>9sXGQtq!m;#x^(1hn`-k zzP@Q#@)DnCQBJKp-!1r|J)Af9@L2;C+4$F@LHulj%rz+3WQ=ghvRP*AIbu$s_4(dp zu#ydl$WY`u^6>vU7%cO_;wwoYA@B@2uagIZ3$X<qBgx{0)zH2-pViFUK_3v{o=FT0 zFfo>MM>7F`<B<$vbR$vjHXDMSv8C^|DHp5r#DO-ux5hOdJRB8)greN^15^H`N$Ok; z5)M~>7`VMi_)9Tna}dLLiGg%STySni5QfAR0Nzn^b}yb>DJ5>3X9cU1McdXU69D~6 zSI*#hFQrf=;a)3WKp^i^$P7V)US#(#;p}bE>sbtC*~*S(%#A%EEJ>B;=Du3k#L*}X z@V$O0UCqlYeo_|pgxeg0^cGA;L6T25Gg1uj?GS#zdj=`jTtz3yTv7_arD^LwM9l^a znvf2eb?iWyx;x|W<Do-{#dbjJtX<ap$4CBhL=EN3tlV@mMs|HT(>YV};~yCC^gl`} z<Y*Idfib|i^+Pv!JryGE&a-O|63ffO48g@_FM)9v4})Dcog1D%_5lM}@uv=-?JobR zjB^j2Szvl!RXf<qJ)152$%7?RWHpl_3G7Z^iwf8?9@2h<*5^#bEqzyYS-nxDnwYhF zei;iA3q9y>pOZYXA8q4<Jmvb)=F4{@((S=S+=KOCzfvR%LLWdf7;MBnCRA<P%g>lS zA$;#+fds&~Vk0UiENE97n+fS8eqYMwGJsYgj+T6n8p)lnQ}x{gCoMx;19*B*G-#S3 zxK#e5pOR1aoHQqacMyTij3Xjo`!b@9wwTft3O|eG&c<&3G2{K*-*Ead<Z<i=Gv0N{ zi2fvZ&*<Yuf?G}_O<#7RJg0w!&qu$I?3{)PVrvBbpaPAJ1}7T+A4IS{|B|0BCKUdp z!JE_|`XkN$#hKp@{eTZ1d`)oIYfK+5e3>E`usDd;Wu%=q0jV0-jK4YBBAzmgRfkH? z=c=OF2y+GqHa2#E)^D!(&qhv=$j>=H2s%v-i#M&7^4z4NrzMRC0DkZ#kbZmGewDU1 zL1o}*#tKc5g1M*;(G#0<8*!Dscqwzvg<ltDB}TZEY;LQu!##XGzxF!gJgRDQxZLS# zS)TQPZsr?pjQPG5*QkZ#(cyX7N|uR|UF`)GD{5oJLm!M%PhS4l7q97g5LWLj`pffs zvPv3y<rt%2jI!WI%Arsbt(O)hbgQ8nIcPFXy(aBw3%MO24ymJ2K=Im=Ou8T-Xb!;t z#a?=_e3|iwnGadmy%pRD=#FYZS>f?`w9>qA0x=(tfw`w?`YdHZkeSO?gRZ?|(A5sX zki+;s9<9VcT+0h4EACPH<1A)o^gz|9QzCNruGxW4?}Z}V_h)+c)LyDF58E*unb)_Y zHn#ivswKydmkB3sxpnBOHUw{c{X-UDBH&t{Hv_-qN&)e4_QTYHYad&$E!XsQzFqw+ z@neS|x;=G*#1JgnVa=>CmBwV?-}4+JI?4jLgPlws?ARwkz`kiiT(5BOt|%d%cq(ye zI1PXzhNuo|bJ;*+a0<fT4oqif02@;h-h#mE9s2#^gFM}OUCnTtFD~AKnETMPsZ62p zYQzKdE+Q?@p?g>b9CUoiKojbgR1He5az#CNg^w_Wu1qI=z|fq7Jl?3t@n-`67R#0! zs~adYR|V+6ZSzi|5K|xaXd0E!9dY)jxDqy8w9!6YKn8PLx;-=!`c35)1>L$F>k0Bl zDxDg%i-LSp)O;ZN;DabGNZZE~7QlpC0Ay!C{FwldP?vbp2K{o-Oq+mKC4#q~fn<p` zc7$V>x16=Py3;uHM*$$fKu=?Za>e7q{&2~w%6>qd<a9UTs6bj<subEJ?g9_J7lpkW zs&X9%zsN(TZ)l!2J1&$IdEwXLG+T77f&AHLmMN}6jv=UK*AoSXhI@aN=5@N{_U;Ld zo|FW2`b8-HxryKeAh3T?sD&xGFl2Pr+kSRSynaUYrdcH5nsikR6Bx{SzofZ$9}rz8 z2+&z?km+4_DfJRj5IGG}Kq9!oPE(<{ghO?yA<k|gQtvVBf(-I03G3Kn-DCJQSCWsL zvKbhV$LVc<$26;=UzuHS0r>@&T!7S&#wh66rM-GF@6Oa1r)7yenj63uifl)uSF`MB zxk|VEMYbi<W)IJSG%NV1G5|5lM>gndG`FJ^v8VSs66hw`8fzz5<iN^|Y_KT3>NeiY zCa{|!WN0qj!blB=ryM7HY<tMxY&<>{shMhKa#1w5+t{1FmW<-;dT%YEReo`@w#8#+ zB(s#o#=uSz`c6l<dbP@E;v(d9NV*jnZKa0J@G=LJl>34&>EtJ@p<VoxlpzMrdOyWY zaTlE3E_fM;1x<%IJfXU-d7~}jTtS(UFv~(doJZ993IaX^aV~A>^IT2Dw&X>zY_$=j zss*~1j~W3GlZ&XD#eBv|W6Ha%n;j{aS5nTM&MrvM<rrFZp@nibAdV`6uc;|%6vG4C z62?E=<=-JExbjdpI~g^TLmIh{MdR|`ANg(I2%hCZW+Wq+@X}(^<S@*OSA5Ku;Qn30 zG>^PMKnE%DtnDO@``7>*x`MondoS^|u0Wv)8e6@ap<8UhAeET&eNEpNk4yR?gT+u5 zaBTrhY*-Xk6`cf}LgnSAGPF_wWOOwmhmBaiT6E{RX8lVQ_Yh6Fck*&W1|;)XeX2|? zPOu+9jNs4>3=hvAOt)KSK0vH01geXm6*?)h22a(kamX48>kb;a?%5fh0OqHSe8(@1 zi6nRHZ}Kjp(!+I;TSY1!aEy{#T=LS90fOU>Qt<=Nsu3~xq$kX81E%c?KGM#38WCcx zRDzYnq{RDtCF?GI5VG^b{Mx`f@Pd=+7HJx2xu55K%+OcfNq~Qdi)Tq*Q@;4F_as{5 zz^thoc&>=Efe7cJ0#mSxA6dx}mF>`7)fDf_86}U`40w?n%Ic{7>PSVao0Sft@MGuc z0~#2*X3OnGR2LsLzF6=2$FLpiHM%A-O_x`ADt)u@vfq38n=7ZTe7t_8H~IOR#Ln|Q zpVHa8U~TA0M+iGg$)FKD0Q1v_O7LJJo8n{M;yw?Qv?L@i6ev3w+nCo%{QGUO&S`QB z5)nsR>;n>ae_u?YhB&jM(VK}dlao{Fgi!&2e3dIc;|<zF3P-B^DZ;)P6{MGP<X)U| zB^9+#<Xmy9^H%YgB_gkuHs3mZ*tFr`aE;LiaiiIyf?SCftB(@Hs21C7-HFR`E=L9V zb2sm5sx^3eeN3#Azp47irsxQ2m*_Eo&5_g^5LbkWc6J*baGvx2&ww#%rtQLJeA|Cx zFCF9oz4Ak<#JNL9?q~deYe)C0tRV)V)oBR<LCo!|NH`8%P<Os~=;(n5W?oVl3Nu9X zNu1;{F(0VdI0aMOU31gO_J`=HFhV!jAoGp4a5~dpk!qRa=8)IXs#7i>XpfE|%bPW` z!x_T0i}@|)G_%#_w9PKHxf7$W@CSSGy^94a%KaaM1-se>WA$M*o<b94p4JBSw=G(o zG~^wODr?;;|9jUrbW=0%PNrKBB2eR0^n~}DHSf?=Zsk$!%9AiDG;|L~cxt5BI#vhL zdn2JYNR0^oxuWyuqb@jT7YNkofh_II`m;}!(X*qW4E`IxD|@YZ)M7MT+&@Dv{{S_t z2AA4&K{~WpPAOEwEOd4jT{j^msezV-0cAvFxIRjbexyYPxf&Ga(`@ZhbC)S*_(K`h z$4hEQqngkKZV&I^*JR3#`}xvcREPfT0zo&qk={~W`((ub#P9Akz)qB@yRuQ=Z4dqo zX{{yIxfs|Lp@|*_VScHI0Hd}o1KStHiZS+5UNz=caQKl$Sf!+Z6cOqRz>Y{^HZ{<1 zSCszkNB=(UbM8(Fj+Y>?BQZC9jQ&j*!^;Q+fyH((GAGl||Dlk9-ddxel(S+*<s`|z zj>c8$5ss9&$*vo6#>6`xd9)f{HjQZXR~Qk`&)ZOG*EBHfv%fMp<oxaOem|kD;ycd{ z9M*{sJeHmv4abc7W8AezJZl6Yq^T#4`duA@8EEKudw*Zea8{SPhyCFeJ4|J8>+hkQ zumH@h`ef&sJwKRYB<$>uJgL{}q$1NY>kiQjb@Uk_xZt3+FB;~I8{43x<F4rxT&LjB ze8^1uJ@~kFhi-iJCGgDcJ#AvJTNyF~HfSevef7YgUPzEry(1b~B&oD60dkiT3kro8 zxZwr*tb<hQh_Jg)5v8;vieW{R(lD&qGixOoN99<+6;;6yX7P}-#ByC<V|S{YL*H;W zW49h$GxgL_vakI)G;iui?i49X@D2`X(=O<gY&0Jx>+JT(oMt^nJ^1NtYYoWZe?J-? znVZNpR<`4h&u&YIe6Rcy9ku%{7i^#n5gTOi=YU1h9-eeu4CczZ7QZF2^;>*?lWZ?B z;{sCJ_L)INmx$s(#X`WhPQ1C){_Va2b|hgpWx`GL5CE{mExKzCpuNb5eg?ddDa2u6 zZx6Ff*H5``WjaA_(v@Sc<~7gqP|*zGUKBt*`v_ke-ceIfaZ1o_e%Po^@a>o99&)oY z+OwbtLB}7E9JEjuQ}AK)NQ^wjTs=I#_0gcVOhcSz>W5nQ4wXLWoDlRZ8@D@mWIVU! zon%JS*`N(Q#xzul3H$MI;K+w!{}<JjJK_e<($5P51qGnb?lX`X!Gc==R||~`wjj+Y zc?F%5wZsH1mg)wc<r@klGGbnMxAjZJ2@d7mV!+E74=*Qiu3UR~w?eae+FEt>QMy#+ zoIk3*dap5g@1Zqp-MDj5#mLK`1;8zM#7=#ME(BT`buS9pR4@4aN2@s%4*7O)bw|9} z=U_#rvFps?@{YG>OZq}%`>gZOqG|U)vyVS#Ij&wakDq`Y;lZTzo#f8ma1V+OngPp6 z+K9%C6Uh9YQ|+JK3I8ncp-aj}KgBWmdZ>eFq@kaOl0fiBiEjCBEume-Tq2T%MlzZ; zYkMCa7L!i=*QZxLub&w3Q~6C98P!*fxW*G4x2&%;3oI}mncI23csJpQ$oscnBpzDL ze!MBPpO3h!Proqu<@mvH!`~H5g%2;jNi^b3B6svnS}LJRpRI%VA(X|x+6<-_0}@*W zu%dGQgB{Zc>jLlqqAQp^EhC3X7n0<O%uwB2cIe7*SEa9vcDw5d0L~>j>XqCViHh|e zC_P<zvXOCUqWCkc!-=6GrJd*|p!k|t^-!wT0lfi2UTYU9nf|2ovDNhP!}r}tTV1y6 z60$wQYpp2t$XUUec7eMaNzrYzgRkE>=k&kxm~wGjI4ttTdTDq4KU+*UOX$!dd~|xD zC&`FbWb`ZiktaK#V!6<|Cd_r_p{WZx{3v!7TU+GY{YSej$^o50ga7X`EN1$D3_jG0 zIjwyU+Hx>@=kxu%e>zZ-vix~IQb^vJt&9Wn_Uc+)l=heYkvPoMuDsm)xMuK0QZ5%j zW&wyIV8w15F_Jp!k+(v7r!n`JIn|1AIVjl1T&E_ldIa@PR80XJtJ+Tlhjzt>PVC%u z#SH99JhA%Xp@+W9N7yV1bpjPk)t~!qe%^WgKK6}<!RO8|atdVmX9~Y1ZW>|)2R?*1 z-y=l($+Jy!-u%+$gDbA$sD|h?7c=K2O2s?nG#FZyyvy2{1`*)^K%gY?rfaPCD*Bx3 zeP)8GvT(o{>I#AkW~#drD%?c(tfwL+K;$0OqLAy|l>l07P-Pi}inW2J-v^TqB#CY2 z?V%r)0GhZAn1yg75U=4({*<-nQ=EL|<Lt-0YSr8U3RTFV!&Bo}2aqV}l{KrK(M?$B z^STur2=spc^t|EWaq9gG%|BJ54fLsfNy=g&^+PXPhLbQ4D#IL(Q+zw|mkqr-j5MaJ zAE<sWY=25|D)BtRfzp?i0Z)0=qcSr*r3N79Cx~CZPth{z>wJfY04o-VSM6RZQ(eO9 z&wzw_+f}n|N}a`YN$$h7xf}za3t;W(zeq7909&zE&0=hSlfU;@?KlV!KobByT9orA za~Q%;msQ2rA_(~mjaqfF>txl-$Md<3oCPMWH;daD$!n17o6?{tXrxNL1ejA408gil zIB3qGSPrK2$O0$xZxdY{iiT6|BLW##<OQfVV2)ih2$4M$5T&Bjqk38BUVz*yEvdmj zS&wfFt<*J5XsdN@s@(<F((;rNI#fEjRsA{i48uAEM!{OpNkabPd<R}y?RtGa&C~K5 z{uR1I*i0nxbL(xZKY*_J@+ao^L6mr~F23>}_js0I=NK5J3q+z>Ma7FE4VfsRkNw{P z$EFmdX&eBcaZlpBceCeb8uNZBaB(&NfW<{?F~EGlGV`duNo`?&UDJRjeiJVQRJV?i zE%Xz{L^6#N#?&+7KBHL_^bAxuTp_R3B*D$ot=3Xw|Ch#2{2#Z&9w~GcNguzOup@pI z^(HkMy*rzDtvd-#C8@Vsp0u%*QASFACx4Uj10yZOgSj8GBAtNns3%j`9g$AP9kiiX zybNfXQ1iTPGrrbV(sxCT453HfrX>3pnnxEDjFB^+m_q<V{u)@w(ZmU%n(6J{?U^q} z-V52d|9D>GE$;`EU$|36;|8d00-Q{5F2WL0eiEq~-pZuCs=#j|S!S$JrpPg^<=Gmt zxR}KJE(Lrc^pYR0%tDFwC*V|Ik;%)I{G!{N*9%U?Lve?*-@_Q=xWH@Smk#^og%zK> zbKVE9Ep<};VY=EUSWwpCl0Zj;Ab}SBbm2!1B>~YvD&>lcwD-l?|4q$Fo(Huz&;jGW znMQebs$pFRwEQeK9e}xl*v#Oz3IB|w0|{<R>*`<4`&W4h$1@W?rDSVS%<+P{bB`XW zWI5X-GP0bBE(d>l67kT|vIG4;ZzKbJmcZEK^J1N#JI{a^U;_kjcxb3aJ@VDJLYr`W zjed?2UZU2Y!rOcQ>GiIA@%k8mhqNnY%j8B5U%`J<!(MX?GX$sE98EBES&uwp&Gy)( za-m!|pE^vN`5tYrt1nHuCGnO`slGN|NIO^*@O~Cd4i})#uRdb91yc>rGr56iJt-Ln zalqJH>Y@I4$catI@8l2*04fR;Wsm*vF1{<-Fh((lvU&+*+04ao{PI)jIvGq}zf))= z^&MHxhnK3s96<hX;EMZg-r_FuJyqz4=l^b33A2WkZd@M#?L*{3aKu9*Pyi}U28$OO zDy`6IdnH$_f&er?1D;c@e8i(HIBM$<)}M<ZqPEV^v$shE;35f0m4k?SkPa>Xq~xtr zS2B`~%OX_Who^MLLt2U1$`V1jgx*;1<V@}-F?_p*!g`|bcl?*8-R%->c$d^5uX5mC zPlGOONOGKMBYCpM)p%+(ci4d@XRy`(kp928kZ+ueEhXsnsK;TF8Z#8=$Y6}TrcyuB z`L|q}*%hZT3#5h341W<W`V3bPz$2?2%)FoJi3WBcMB#8;6{fWDsOUKH#>pZyk~>rs z_&F8yRXp!-UM?P-#ofnZ4ipk1RfxC7ZZ4aO-ccDgAMF^D7fZ>I0Q1A+oKW^4mOBN# zjLl*UsY@<hwj;E;yrnp;06et`Sgc*$Kmhp+Ax}kxBI%HjX3{bMPcr;Qzfkkx;MRD< z3*V24o<eKX?Uydw(86j@%3S0Hcl}jZh*TqsBok93wQFkciI@D(XG=`XcM4Q(R526j z`+dxgw;!7Pc4fh3&_taKtv&JbsK#Rjs_2!;XG#G;s!BXB4e=kP6tkluqUtjtzWrE9 zZjN}t55`WH<Lmve^!nK~BM7A5Ug>i#7wHVJ@&FuM#o`9cptPFHoW?5=hNd-ZE9@%K zKx_j-X+7%+^GlKNgQlQmsMZs!@P<I3U37Jm*4W{A!g%oDhZ7}*(o<dJ(dNieLa>t1 z*ra%(KiTKV8MlU6v97GZ1TIG4x?eClB)hSw@|eS&(C1<=^}4q{6wj;s({~nYZr@E4 zf7<1nVH_p-=yd=&Meyzck-Rg37A@xSYrOT|-IiYQ8mH>$Epe(vr}^jr&*&6B&xpkq z^gs;4u1=FQ^kYckGjIQ0e4Zj%&oBH)Qlb6a0tAHk7Vwr6XNN%`=-O>%<Pyt<Nze1% zPbeL?-*8#HDh|}MIT(YB{vcc-cPFS#r*Q18Sj{0Sa|!!qy#ROP$%9Ph;PC17CZEBS z-lfaZ&W6R>W13G<J{!SeW07K|dSVSjXJ>D6Vp}N_|G8*^apU&hzxq^aUu7BlF5J4~ zu7A8E`_Rs!1S+tuL_WXt&8r5?8t3qLxz6R#zxpmpMe)b_KHTNZ`KDn+-#+@fxQBb! znH2@uq~64(XaTH7F}Dq>g8WB%vwhL7%c@J`QvAL@XUNJTN!J1S+UM?<r<Bap(YxNl z!2eoS^pq-i_1cCN{_plTh<3Eom8-ZR?QF3J+sBS=OJs&*8-?X7M<~P>E_X6*4~w&7 zOF`9yV*puVWK5@YzaUHhEB0$2?^l#^Emb$zU>upbS@8VL@!+*{_zmY@`Q>t=n#ypQ zL#$LI{MN~LBWWS;6SQMVHd?JMS2Z)5Zwi(yx8Aj=?@PYdCbv_u7h&srcch1psYk=+ z)aF#kX8JJs6i6Ma2S#_gK_oA--R+=Y-52=>{>`Mf=e|->*hW4UU-oLpt0TLva3vSu ztrh0mYVkb%02MKAuL$_;`RrW;-ga*%;#r%n@yg@x+ltGfTII&1dJnS9U!R0-r0(Tw zliK;ugh|}A<6N~n8=YtWba2Yd;+ygJAeJZViV~BFL$4bX-Zh@>MEI4$M^n@9@`SPh zqxVq;lH$5+9o+DnT+yffSIjH8Tm5%5QJG^#OYOQVd|q$at;>D~Q9WRtrWDP!YwO$B zxM)>iTP2grep9fgb73+gxxWA)0eA08Pe$@~hWMD?e`7M4h~lg@i_mLX;d$IpcU8aS zt5s#~wR0v}XbI9aqoz8rSM`2zY3(mT(q`q{Q@sTeH?2E9=P8a`zqLnXg8)C*{9x|> zI2@nlQT4E0Xk@ywch{!%-qrz)E-wFJ?eG?Uu0x(SnH|PT)ndXm%koV&O>O5(vrq$X z@dFcoh5ja+UX0^D?GZIM(r#vQt=YMAG=yXYqR`zY1E(l6%<Gd@vj5m~sT{1s1?w=& zor96Dl)?CVt~ASd0Rq@Jt7Q0ammpW|Te2=pr^67p{_E`JY+w4{oT38ydf}W%cDq$5 z3KGe_C6IiT+kPu^`W6R$|692*bEa9xHO+BDeE($Mf%U8~t=x;`o-AOPxL$hkrPQJ7 zwBVkWqe-ws-269BV8KlIr382+E1mE(O*g(WZc9+9z)bU|JaT6g5o(5SR#Ts#WFXQ# zwm~6_+4;Kx$~rIao7Qksnh}?l>soEP<?z}WTJ_|tvc2!<CYnq{G32r;HAKEPLsogI z!7W_4KLj-mBHg@KmBlThfeEzCC`ZJGz9yl6bT`N<b8YnRSjLHd#OO<mP69%;kP9wA z1fO}Z(TThqhX{|mdh0S*0(JL9FM?v8&RS`g8SHBjY+RQ%7!Ed#xM`h%ZF^vN^Gaxe zX&h`%>#*mg2QOm%r(qErP#ZKD7l~9T1zGiQd|B|&X_`~cZB=FU^Qiv57H-M>9nFIA zD+qY`Gf+rU+C7B02ZfroxBhvZlk(Zo4U5mh8ek1tTH<rXPecD#Uz2|wRqi%fyf^=5 z-)U<#wgsB5=|w`Y47Tx_h6dIlE9tVW?Dg9HnzVA6yHHSS<aG{<bw~r4TkLvUh|row zWV$xIZ_ZM|HH-Yg4G77gf>dvTQD-Z-fgY%SKO5z7s8^2?#x1WI(fD~-^x*!1?P;NZ zA>uvL*ubWAdSrUA`2pJmxaV|=1du}7a30E&R%l|YCqYAbjYDf4N*=B3%_+#O;S%l6 zZ1eFUM0&s+Oun5H+M}Zxbtiif+rtz5P^SGjdPFQoDxJ_Ft)ZP^-u+dZ@IPZInNK74 zfA^E-ZbjPnNfYjdgJrU}!4?eAb`Dq{VMER4;)xDTAlA{Gu1&rzu-mCp{tf{<odG@i zBzYs_RJ%%s{sRsIq+5@u-5mWpFS5f<f&VVNJ&;-ZIaAENS$tx;@UndtqJk62p_t!y zG>1#{Qd@@}9VEB$z72Unoq`V@ID`|RjzQDh6#$=fO(IAn79K`SC)mJ`ror8}Q|D6C z&u?}(%};5^-BxYjE*27150>`Cmj=+%HMpr6n(1y(bB~-lld`%GWse^I?rWdRb8Z*) zGoCPu=bHWJd^N#-Ux!v7>Ix$PAu~K-F>P-Z2>AkL=~btSsk2QPl7Ac#)qfreg26Re zT&mY#KpfZe6Bn6u9kK=_@QPw{xjRhmKgK04u9$0HT(CQR<-WG+A;B7hX{(ItV!=v8 zLpC?CTsNciDYgAMjhl85o5tR07rR^K#FR_3akK2>KGHTCcUS0PDD=_9j*UU7SmL2I zK}8?1zYl!*biaBpEQkpY?t!Xt!J%ks&ujd>I%1IeixQO=YKaJyzqN{gJ2ajMMn}Gg zW~BKq%FiEl9?#}Z^t`C9=e`RzYH4?%VSQ4H%8vF43*Rj}pyRT2`dUU&xo@4%FV5cC zEX-Z?soC;jh-u34@5*pNglNz2I8bNMjbaFE$)5#breD~8%_%|%v2Z;JT#3bo*A58f zuIff#^cTiueJD#eshBgJX-rEU{9bkla}c%bz$J3+IWZ_oewl3(v{63I%_pz92j$St zVLe9;f8vaEKAKv|GsxA>bfx;!@`Kgk#5uSRD{YGgIqo#oyJdLSC*79?R$xIN_!BuA zhhj|@IEY85#0{OIb>>gYCp*CDr73}9u;lmvRx?U3Y<8`_M67~q(u@+X<W8;5+wr6y z2WD+mYK;_fpCrybU7e^(dTb0pG}cI-4Tz{5ghErGEaTyucP`OTpa(k5RcAT<_3xU& zWQ?(dt6$m*>$`7~vk(|WZp!DW1^sHftc{yFcWz-V7e<ElGpd!G_*WGSO;fu@T8U4& z*j%HS5$?uY-CHxkJh-eZ+-G+KuwbT-Z<(<~;n4^V8Uc;2zQf+%M9-nW%k3PQ_P_T| zZK$&IFai$D!7^XomMC7iU#ff&q-)e1kjWisdxu&-E4o*(9Y3=~B@*u7IUiAXCGZC` zei&upQcbX6ln+F2jRYhGR;d(yI}^N>A6$4~U&b0hi@{vfm;JMU`qYL%d=miobG_@x z-A$2^^Ldb!H2o=&tBJS~sdSlBI>%{}%rIA~QTMyEjb?&?A2CoTS15IwW6O{eyNhTm zt;p)>pIUdEsX=%d-;M-0QFCk)R{HtV__={8PA@F4g{{K#zr4OO*qrrrGgOCd_J+_o zh|zgxoF2$v>+IIKpGlb?)A7y#+7xS6iMoxx^@!~{?ks=F{Kve-7s;TXOOaVxISyB7 zZmOAIdbZtUbXgBRui{|eMDQzYwR@oMXooFz-yd_Vf+8*oopAy20iu!)@d4Zlxaf^% z-^rlL*A}i>h?1s-xdT_r&9%-RzuN40(XY<lM(ORj72Z}6cSstRYP%Nvw`nv_G(%T9 zlNIT`9%b|MRn|p>Pg4us6+*(oRrB)$m^!?+#sC~VkiSRXo^>2%EInfgw0t?0T{-<p z(DP?n&>rs*U@?3i>D?5xYsnsmNh^}lu(OU2uPMaIbnvbZVJwb5`mxH7&B|=@n2~>T zEc4UT-LNYr*#9YiZTsXp+H$h|b0s3IY*d!JTu0W+;xFgY5N%QJkfRVVla<b6^$+)Q z5c-*j=Wei~d*ORo!1e46q`7Skx5wj~&0NFbR~*(leUW3w?=vYnqL9zMFm<StTR>K* z%n<4sXQjDs!!`BUCzvp}ZT}_PrvB&YCXpa`1w!OFU3lSu{QWy3-S`ujC|AdH%^I<V z@$CD=sf(G;SHh2X#2=5?Qjgm&e58RZdh4s1)2Ab|$Ftg>R%CLe6C@7M6s_JMt6U*l zvl9C4_kP^t7Bp4A!hGI#*1Udgxw+=V#nS$_mh7JQTn_Ng+3Q21_cKs0=%2wL_z3d; z?$1I~H5s#R#MjSd=NEW=%O(wPMr?sJIs@XK1pSrG-S;5C>ZtZV7z-~}Il28R)4X7u znRZwmj#l?S#7g7SzF-A%X7KcA8bpns{yZP?s{4zu$h?+)6n0;_OMgn}25hiYjP+Y^ zq;%fkb5vCPX6wNoZjzMd<9Qk9JlVb_w$mr3?<Wos_4V+z12EK+q4K_<tJlBk3YMm5 zqm2R910!!9*Bp7Qo4pNZ^<U&JhF}g290r)5?d$i&66_A2uKt&ga9_T1(zLyc69K(t z_2po5mcC;(u+@XQZ~x)ecdrR5I*krMU6MG*e<``ng*^P1)$&FtE2+aXW9<5Fb=u)- zu!$=tW;*Q<vGlpB^BigXIXj)y1PVik4U8}r*S|TxWBk@P4Ag(*F%3GxIH_n8_nUh% zS$>xN_v5h#b)P`q@+hAZ4>q-5EUnve6z)k=d^MU(1Am-`oU)5IW3V(z!DmjPGq(w6 zT@Ww6v(McR{I=Mj61si(B?7X@zQD||Ke&CNJ+0^7^|!(aiKCxy#&UVB+$1<~yXM0) zqy1U>ih%i04MNfPmT=s@mA&m>ftq%#-|6Dpc}ITi|1Y;h%{uXD^4Q}AozQBC3_^gq zn0BQ4hw`aP4ypA_O1d!(6v2;ec<`kpmv~3tFvJC+SyXyx1E%~d`{~Tb%-y*&V}FL! z-X7^7_S9Ip)xm#h|Ekgv$jhdkvN)+_rMzWYDtm>vW!}!x<|lsz1FR-60|%%>1@IOK zC}N+SS@bgiT{kkoR<dNy@z@L~Lcp}=&Z!&t@qASmk!T}6J2f9i=3$e-)Dc;L32el+ z)AqWcg~9FQX~Buqc;FeyPl8y@X2U@^&jhzRb{WM9O!(y1kW~Ui@5dHD<vT+T3QMGk zVXm`Vfqoe7Sg{Upv-lN$c6rA5Xjc6y7@hQyfA}sSXVoO=FQGn{AWu*|-5ClDBSIcI zx?)!+IGIRgY3;c-rTp~OCk--jBLS&KZ(IF4ytKNb_bu!?J7{hl%Fn|cMCtC#)GlX> zsqE>uGo))yPMb;=5r5<?PAqiMk$_OC2EH>CGz4>WWxE091{##H!E_POGcJf#J1&Gp zSP|QS^7sD)-tK8qp#Sd_g~Ton(2Xd@Xc0?jlB*chB$h`c<hm8gLFL09(9Z!I0wnjc z!g-=62tX35>ubkU15TTu)uFjwlBD`3lj-AxTd<N#ka0s^wED{wAq7jJcPI;14nCJb zy;eLIH27UihLru12RHTdi}H=A`YjbsKXNpDuhjtxAsX%(N2jz0>eI3G8^V+bH&P$9 zJm#Q6SIEUk(NIYrOca<{14;bxnmM=&n&!riDFxH$kJEfS<r5tv-pB%>FGgje0CWc2 zqidj2(z@o*(q4eAeSvJX$bwLSNunZM9-V+A!51~c!<ECB07-n_j3=O<N4Sy-At5*% zfrbb%H%Mh{`bmKp^J%%nq$Jk_2zxHTQ$^*2x|b#x$iina!OEl~^7gZ;K`$foH7wu% zuHykhNWP8=ri`q7zvqdt%EbgocEzFalP^gVylDaBKALLINJZkTqM__x`zN82W;t_Z z18be{F)zEo5qj4_d_&Ui(UXVhXWobBUjeGaB-Oq@iHxM)2i;y%ey<RLw`X$^x}+q} z!jFkDL}7j-WB6NO5@R=V1_nq~MYx`EAh<zADeVHBeZm8F&8>u(_5sp9b638+e8kU7 z=7MW>)8~$-GM)%QUK;b9)u{(~7~g#q&vbz>JJ)XLX>&8c@et)BF<)W0A~W0gGM@0U zdkjf9k_ZF(0p2a6yD6V~JTJw<G#qXS3<S94o!nl`(TbFWAS_T<h8xB*ynNmDCf1hO z8jmPH8-~<GQyr-j>Ncmgq(dYx7Y%&RpH$nwUMu)Zt7OHm^5joD|CqB?l!@cDr6Ygn zC1)|n>1@+{>kk#OI$w$O66n78JI~y%Zy7g*2?!;iNwRHMVLCqSW6;<X7XWA4sl&mU zOOL(UQ>M_Y-D-#&jtkwt3_uq5%%s@NAFgB}D0+-I0w%ttJxRGArLWeyp9T|f?-3M+ z0igiU)MkRVkb`N=gZc96c06mKT_Y7YLoBVc$gg$~|NLqAgRWa&YW;EXN}Pk5Wu7vy z-sE!N%o|eZZM}YNh`>4G=>3!#A*yExw%y$0p~#blsS1kJv=8O&zctH;g`pvG4=3>; z+(ElOrr}}K)5w!~If@m*#&<W;9{QQ1%f_kaO#D&R`X1KRuo&};VBo{`IXO+RYm{2q zBT(H{z8ot<Xyr5m^XTa<wkH}H694=qGdMM?9)PLogAfK_RxWxNB*5n%+!-Ldcn{0( z0$d76(iI00txw0)j0r`zlL|cBnGg^j7(~OB#5(ZhPb7i-NP)d5^1h`r%f#w9vAWgA z@mfbkrIO>t4DzWG5fo+mycybbV&r6(QKl{>FGUShjeS~8(XOb`w~|b^hxE?5OV*_k zqLF!r_tz`uee1ud(b+IvH%U8kCO`W}u<<A@J&I>wHKf0eYa?BuN6*}_oDouqvgGcZ zvE@B^=|Uwdzrq&}RTL0s{2{UU4C6H7Q72G|ulbPfzD)-;Pjw^>UEW-QX>Kr&$B6?( z=;lpD06>(hoK6MO8=8gXv{Zr8abjU&LB0eCdGK3}FMacol1QlV6Z$S5z}s1z6AQgk zqCBY#udTIj=LXhkA$@`Bn@_|j5>fpnbjB}w!LzTpZl<m5*kaDB|AJ*%Jlj2Xt6()A z9x4Ee!gbWZEQxhex`~Is*EYVOm~NganpsfH4#ozWze9V_;A)AnZ}N%Z`W*-9f#D!~ z-zGg>LXeJ))b*QL(+=Vp_7bFx+t!EjIp}{mD)tu*U0g^y!co<!K2M2N`2Y-X@WJ>$ zd|$;ct3M%qjm8#Y>cv>yChSw6h9)GU#f6Gh#RirvPSH5Sx>&%;HNq8b);c0uA1jAq zgzpQsm<(%E*YYb-!^esl*0vFv?}`F*pI^EBJl2o-2ou>=Am#Ws!6n<*;JB=y+(90+ zsd`4pFkuGdO!(!X>$Re6B=n}V?b%hOo9~p;S;8Td%$^puPTp6%(f2GdVBH9otOaiR zl{FG^RhfGU#IjE5ayP>LnI&3MDx-r0*indMk}G>~G3-U$2c@x;7xtz<<w8@%L44Hl zL^KirzyPnjOlwmFb}qgR@u!**;r_|Byk6~~_88Gro`My>>d#SvUUYKD<a3I}(^R>t zYa^M?IEjd#pKiu{|KXRfUWV(%!O&Hf5k6;?B~!NH+UEy4m#J5+2U(*k9DYBWmOeQX zlZY=;I=G%j$JSY-i5%__bZU!!bWY;a!$P55qq@Vgk3T)#s`@Jg`~siB1zAXZ?9SBn zQaCU(GOO2M?2up2n25^z_lz}i{h@Akf5#e0Yi@2oI>MrfBoW0nBn9M)i3|f)<HyqN zf-kbWID~WJ>qKvc7UB>`?PCiK<7|RHH5iYJ;>A+)gENwYZ(VWMFs*d~XVN&`4<_3X z(&c^A_(Pm?#QZg4rw$>)XF%|FOqs5PYHo=7@&q0NjEN0N?`o?G#n3*6tsFd&!pu37 z)u^yMGZ{u(_J311o-RVj6LM<1imxPmq9EN%lr$`LP2R;*nZusXYKpZb^d_ba&wK6q zwv7tV?GJ)B%%SHsMN|cd6SpPPoOW#nkP^|q=fKc-U>?WZj2fWoxQp(CECSL=8P;pU ztWUy}=aAmVh!}I8j9dXORe3D<kfYe}t*s8s$7kz$D(mBw!&g-4#w5@0iPLS_5@}Wv z*pWy{;_BE%-rm`Ar*u@_@8O}f!SccZwiZK#=pntG*|2SSr?gDNMWPyUh)BD%R0Dl? zaB^8^0XA4pP*QjsWUD_<Hg#kxtq<z$NYKI#S4dF5$Q7+?%MFQ+Ua3(aRnJz}P$Cj5 z=|bcOQKObrN$F6K?yUhS773d~l8Pi@zPpD&6(3&n`X&nH$Z>+?DF``ETjX1C<dAij z49jznwSodB(ZHPCE=k>CTLb$0iyyW6?E#R#=sCG?OS|<VXjW2j*4#cV^+5uMOh`ym z4Itly+3(Q&{p2`9*WQrECf#8B)FxSm{K?)QgNDOk6{3yq4%ndjHGw@|S_-{`1Q|<I zEls^f=%yjkaY4~JFtS(>4Oc-(B?ysB=g9i5bTwg)zAm+UDrJ2U7h_pSuL!)$m)ec8 zohjw4CI$R`UiAgUw`6C1WefPm3QSO4^+*F4Q&MB*6p1*Nyy)siR0QMr_ctmI*FZ#D zhh@U~@I@4We$#5el~b(@eqKYOfDYUh51(EjP6{h5g6h1Wo=kbVCp7|Dd#QDhfL;C| zhuVEyTC7(1WT<R`D1-y`jl8<+oqujo7CkU8ToM<PiZ`~oyf&zZ<{<MaMiQ_G*cY-4 zo5-GEfr;P?-0J0^bo@2n@SIWIPeju(u)b<K-=vzsRIry*Hhj+j6?3YMi-t+cz*$j> zg8%OJ<6VFi9*g;+GIKTBUKW9sZzn>eu@WiDn12cuCuIOMi9S!HwA49Pb0FG85Td5+ z?vV915d@Vdg%W>#ROZ$Y1?RGa=b%!90l`iP5|*<!Y|UB*y7dpdBZ^pgDSM15(x<PW zokLYh$=)p~mtx2@k@ZpkT{%vvy-*tJMuLbg4jAra^Zy$x1f`hxq(Xm!cQx7y>BcsR zUQoCFHo^(ut)69~`j8<_4WNBUsNy8LtC7?f3|TmPbeNm7m_2mJxff7&guEB6<9{T3 zRt<Zq)}67K&#iE?8$5JDPL`zofFvOcoSv8Oe@luC84n|grwm{zN>HyF%vC!Jzv;j% zMG}Q0B_e6x<Od?m#d|$H@ZHIQ0?1l<{K_LbPC_k2p-)69q8sQNApX^;Tq%iADov7< z@P1t<O>w!ge){cWX4p}g<<1!J(N>X1Ks7M>fi^he&w9e^sq9|jt6ECa`6+q{skkQc z;8>^=@`dANT+$<gu@D&5ju)8lKXu04HTVks*|NqT(Ks>6u0A@|fRP$yo~k+{pOl#y z?YL@iFYU~&eSTc<K6qK_yxNEUg;g|I39CfkZlpsa<*NA-p=_D1r&9HD7?EM~>!m4a z!X!Dx&6%vu=?X(H&T9a;p7zuvtkj%89dsr#g}b*aeoHD{yBYc^t4;ktj4I$GNXON< zhr&CiuDpm<$#x`bY?mH8tU>}%dELeLSYmW+k<L8%J{m%(;1}c%YdK0UIN3N}431=K zyk$p}4ak}zNQ&#B?~n~Y0^jzjeu%pk)mKK*TQ8LD88EC?GY|=2OlPW0%&I9VpYeSi z{Rwfdcy?ds0x4nkoTi=NjDnwirOfaEtZP7mrnw6^I-Cyply?0&efu488j9oq*iXWb z=pN9Wfabgu(4K83@(8tmn1q!VDN~=ch@>JyF$ik-cg-*VeINlmn@<sOE0MU9-YPld zY%ckbVUcpx$V<#ezSXhUm^6J$u-N3A3TfLD_NgZ7gQjbF4mz;%+F?U<DspYmu&c1F zO5^S|ow9u2ez9~tXsThw;66gC!L-irXBwuxjfS7fcn!0p=|-RatC!9>Gem-BE<QY; z8)ot-cV&7Z-B=Sc!j@zTG=%%LRlZ9-^NILuqE!?w6vJpf=S*L$qtCmhdP30%P~*~i z>(^+h{<XHvPwA}r$IcVhUeF<#%Q;<RyB9fWwkOHoyeUSe&4Cre`J35>!~wZCU}10x zgP4kU9nx=l=FVw;K(vvk3^*Tmbj`}V^Jn6eBrNIc>wVav`><3!bP2s(?X`SeRaWR< zUh#0=@FA>({kE>?#DcehsJJ|VjwqE4;7d4yPVq~_!ERkFVS3J6cNQP<GNT1E23n;5 z2zqLn4+1fpT0p?HKf<4j=RVg$F<-SuMWE7iZK5+CVP4QWsvDh#^6}<Syi?R$vNb$Y z&gN0R#jSi3;|y8MulI`{Hcu6%q&PX<&=ayT0S1S8Um{qIhG>W>z*Z%ue&_y=o?wuW zuc2J@^3;=16x_yCXaG-u>>BJ8maSgn+Xi3Jd49Z5jQ4Z$-x*1Yp|1C7xkF`?ll5$w z9yZL8B$p#_6_e(Y^eXW3RM2Vz#g%d`6Dyp?q!RgHEMMX26s>{?LerpQe!<=xfxyDE ztShO^C3-v7zMhm*3$+?i1h9iPU<tZq%6|c1^<gkhuJ-0PA@tLTi^FP^#2npHvT${Z z$HaKh@JhafjS;Q7bWEpT_z8+J6ju82yXU^w$Bi6w4a(9Q-Kt`htl=7PxgGD}d=X^T zqY>?mk0S3U>Cq~?3Y0hrO?&NEq%~cV#0KaA8@#1p?>R>7323~$)_R)P;mLtET?Vlb z=|NAe3vFNs!QDX7VR#O@laLT3%#pilNZ+P(358Mtf6HF|Fwn-#b_VXuMb(W#h3G-` zVZnb@RJ*Df{fPAYws1T!5HmAAL9jh>J{8|IXhvHsIy!26`x$17r4)^Oee}b!mzr7f z&C=0lKhHRhpB+T6gJsJz4UhSM&`GO=wXCrTL7}U2Kj7yokGstqy&pRgIk-VObCu;a zB{4RDWr0FPZNu)#0cR7aj)n+f4x&*8iY8)qAe7tFjH5%K6{id_Xd8c6Hh&mS;v%=E ziN7vC5}`<`KO(j4jU8{?gxcxDV(s~=r0uUSVmt_PsnR)v2A(M@IBoj&M?Xe^Av8sp zn7ZqHds0it#;gg9!zLP+Q`}w!zk7~1_DnGmhj^xT+&OOK_4fh(G@}$dq{V0HfkX6b zDLZErNTnsogWqB}1RGLq=d7B2^+VG48^V{eJ*qkK414<Ak5j|!!&|o|VrAyq?WxsM zr0MzA9%1+-21;as5NuS<Q9)72!@l*OUeKAeaWQ81deua>aGt{KDf?`Ctw9UrygWe; zBHJ`*KuL*tnoz9(-Bi`%OQh+jL!Pa@?}w*C!D=|4kLveM6h9*L`u*@Sf-3|VnGMxS zMHrQg6!xcWUG{##{Q3;7pW-r3FiJJCb&GLxt3B=3K)ZVTN)xO)VWqz*kxDqe`#*0= zoMmXZ(8jx!Q<B3ZsiuL$iWHQKtNdk(@FIFEkCOth+7gCAlYDFLaJ&xqp@J$rnqs9e zOnrl11Ws~7N7vJT(nGT!r)=-mLT5xM#E)wyDw0&?QdQ=DTE6}+t@C`+bNHDU(oh?u z(V}L*68vM699IJ^AJsA!=NPSlMQ}r}<BU$8UvxR@C@@hz@0WS`H`tT`lB<Z&3$O@X z)2iePZM`Z>UWU_bzbFrul>MFbyTV!Cdmu1r?Ug5G`UlWlmRu+aSMZ>Vh_2cPjd<ID zyz~6m6u${6-xkWMw&vSa+gMp9J%}t&G~5rEpXsEXxv;jrL~ssw6xb!#o_sQ=9yI5I zQ-EOVd#=6x86!|l?|*b)_w(jLiV=^mf=;buSbW<V)OWSfbc7fyn<T_Cev14idN#fc zPVH0togXrK=av?tJI1X`$Na>N2->Kgc`Ct?ZM2=D=St^${XM3yclvc&cR{~g9jBj_ zT*Lj_Swz{*8n@a<kryH%pMk~?1`&^ihs!C7jLEft`2+|ng(x1lngOkEQH$D;6QZ$c zM40}W6gj99SNAjgB$ctfZzlQK>7E2_*o8d7aL<(gqIV3M%+;!kzo88BMAtumx4(}I z*za;loCj76t2%|TeO53;@Z1-d+{iOBOT7MN50t964M=4(b`#Sx+Y4^Y7@4^pO*ilq zTj)HY|EP?gX~r-7W$?-267#>s6u0b*1GOs#y*Hl_=i;d}s;F+-O9&vp!{0YKAYISC z)$cL-Q>+b7A<y4=S+5)rOI(1kAU$>FYc>PfnbrX30N{l(PXYiUj00HW_S#BeEJ;L+ zHU%-fJg6$&9QqwmJ!O}tu&XUZQCF_Llx<1A?x`VG9};aSe={_*K-C%8pZMw}vPR9# z2E@Y`%}4;AP3Ug2x*%&$3Pr!l-@jSh?reEH_gNYbYjEUVpGKeYmlrn<OQ#`ka)rJ= z=)q?OC5yvk4Z@O(bo}27@jLTUr8eI<U~4*WGk5bqIMcb9QO3YYr@X@GxEqK2?wy}3 z68!eSw=RqXTlCZbJm^vif$9_D<Z3}P-)GQ8u|a!;5-2IOBX5KPc&4icL^zLH>D$jM z6}+D;)en;N1EE*{*bx9OfKCxrx_C)V;Y<Z%ujA^}=*z$A2#`{G4#BYk-~}&}WtTx4 zW86?A$F#GlE@!k|J=erAf2i)j2KpLd*aytWTeN&7oKFjvSuLfRkJC-BSeEH@&+^FJ zYgent-0Rm7cf!i7@|kesO9>yTrMJ%fh83ScWv<EwKIvTRxDAvZGZ?Y;gO^FffpYZj z?*yOFA8NA9H|WXQ8EeH4UDlR0>zv+IEnyhHZn-ICb2CiR)ZxI?wFav=VWqiHo5;pj zl6^X6m(Kf-4W^~r4D+-Ol0^WxcrFBv{giZE=@VjdEHkb9voiuXi#Sn}>FvYa!w3)~ zA=wIhe9q}vqlES>fJIE<0CUw4fL#69YUlqbI`ep_+V_v2S<M*B82eJqW(|!sdt>Zt zLy{#mW6Pc`A=L~s3`52el4`6;Xe^bjvL#D2p+YL8QhAEL)uYnmH^2YS`QyCK>s;r) z@9T5D-?}|?0dQbY3b&7_E+Veld(YNbQtZa?cH%*ygW?bve?JTVlqY#O=G(>{ww1OF z&f6Y&y1LHKEunh9Q{b9TQC#=KOQxy)4MAM9z=%i3>)PPx#B64L+W^l!QP4B}|18(K zs^VvbTQ!Cg1msH$V=Tp-$PGG&Y-pLx|NP0p)amj=<H0qx)7A6e)_tGYAW=JU6c$=r z3J8ZFR|z(TO%TAos6K?Vr`X814h&*|8LlAb74O2W5=0c$35JERf?+fe#1GR*FMRz= z3<gmfZS-NqJ4Dndg$tN3xByUy0A##XdbI>I!MJ@=x~8=}OxP)OxOLtg^;ZDrqmqLh z{h?hIAe^b0<LERUeMa?>0cM{6T`Nl$85jyR_#kt_)bnuzz3BV&kjwOJxyYsb-N!K1 zay^Oge-}ZY7i!rT?R6*S=D#5>9jju}6+<{5yT0c~t*TXjI2oA~+8A!zk|_ImJK}o& zma!Ek$|3KPna(N4H7U#WC3AD`d-Sr{)m%qs@1oM5w=Fl!e(WG%EQ-=8$YBV%*)t5d znow{WwV7kSnuO*GqkO)%joOEkD~MaJkqS@2ulpFhdwRnsE$ukFN^dt)^q?|BpbO3^ zNi8ANOw@A*)RO@=KUv+Zl^pC5<r8}EhTucc#2Q7l%GLsCh5`F6R%FgIC61E`@;Cak zdFO2VIBBb=WrrM9H);fI7j34WvF8TZ6q9E@qBzwBCh!If)Yu8QuX(ONtTOevLL`t9 z;QTKIk{c!I$VRozQ+|_2*>xw+?k>tw^Ajn}8*zjme@6dWfv;ZIgTnrH$ODR)y<2kp ztTo14%CG?wVul93-B_44#6bRje<b$1!&$bHyt7|2U^NSY#8DRZ4`OT@dFx0b+i`l( zS<X%-#%v@fE@Wsv6k2Gxiu<_`D)S_*ZtnyzxT}mloR2jye4sR9pwX5e-ZzyO*6FOk zRD=XAec@&*zjIPD#TZ^~qa92hl3zRQFqzRo4{94HyZN@8Uuv``FTbS?D#{kR-^^ek z-&1y%-e(g}NJ#_>5sN%HD|METYE<b^9Ix&XV9yX$5$J9zuzNe?aP6!kG(Y4TdzKL^ za@pw`c~1l8ph$%_Dg7tpPSf>790$Kl*&=xjRtfQ|funn5oRFq|1k8oE(5`Qz&kCz1 z2<;Ivy~mPK!3fdLM{VpQx>zA`2dGi{(2Oq=j85%+Rxf$7A8xqf|0HcipTxq|T3b^j zLWo&1c2q~wESNF6^x4%>t?}?k6m=qUUm>uia1am(i;TY)GF*|9l%brwrYC1rE<#`e zVA`06D-RN8%IB926o=cFwW=V+8XM3oazCKA^~m~*fyk-}fTS1)bq+<zTs{|iNTKMZ z=;50S(Gz$l>sg$L!+Jd&+5~9%h|5s!9|#-9sN}I#$}Y*GV}tE&=XdWm3Vx)J_N8*p zJ{uWO{hXLS{9t7puFfbe>u!J4dM}V;ls*6nGpoII?r(I&XyX*yPYGAzG9sPP#vSW? zcx=bGl<Z*YJM3(<(@}Z$y_Tlj>wJ68jaSys9W8s%!Ox^mq6R$c;h{zDVRd+UC?I~- zO{WR8WVK-qAcV_>D;K7f;ajne7X9P+eRZ)<Z<pRGR+!C4pa42{NZG0<yEdEZWo5VL zre`DN#<^9ENAWD>vRqluwHx*&L%L_J6DPOBR~1G9kk0l*J-*&SaYl)azi&`>+zLLV zBqga-$SN>dyLf9;V%-X7>L+UaD9u+4;;hv23pq--$n@PGEcR2IIuU2^bjh>Vx~Zx? z?iteZQzTJJ(H09GL749WLKlsIJ`j*F3PwdqFkZN766~(1x+FvwVF{~sh{(~RCmra@ zPgygrI|2Qoqo~^f^lyZ|9wMcI%lo8nj|xH<WdgMKK@GoLS?H>c@%@ic|Ag;HD8sN# zn>beT-X~^{muUga$|Hx6#^DbKbhmHXkLnNiPxIi|=H(uZ5zlGl6vs+&5rrey?qm8Z zUB8iBA?}t=Q?MLHx7(r)y=)Xlsyy!12%JndSARaQ`dFjqwkB(}fz6`3;8XR?3M-!D zQ^<%XuZ8gaf+a)(72*s6Vp*$mJ=U@E086dtLtLQEhiYx`i1m{n!n@#a+N!`>lJ^n3 z{i^^Cip;`U<09$@a%k(_l%l`;LvCK0e7LzEMcBmn3Ydy@T0P+dCi<nD=7d>epPk`y zTWB7)P8j>w!RS5+5tZ6!P<-tAs2-jkN*fYq^=B*A*ID*|k-9)sd^=%RyL?EZdiL<+ zr?lh?7aO~N=Ugg*2_O7c2{=<{`YO?X3*M1D{roX;xAvV`#c$chYBf-Ej-5)E%}HRi z?9TJarD^o^uEL{%#M?~)cV!ZRGTA_4QaSeG>hlnmJ-yCqt=6z+gXB8tiU6|p2<IgG z@J)Rg5Zr%tn_$oVej-NafUMPLlUCwd4gLc9twQ>M?DpHsajR`wBiHyi6%CN8yQDG) z_X7<clFA~*Kf&|q^6`KQ01PU?1%`w0uebJ<4$sg|;06a31-4?IbS1SN)bM{3D+-in zDXkxh_a#+4Ay6NC2HS;24B>fS;uB-p(0Wh-1SB)~r&a&+=*e>pZ?`pa7rKTlNtp+h z_U)i+UXEz|x~iKmeiGMH0BOqqG9H3s#o#*gUx7o(nc{$Tu*4|Pi-AfO7TCUD0-W%3 z<0NC1uS@7m`JenHHBBu{9LXDM(l|D3bAp7wpoFQ0ZA9i$q~B)KRpka$>OfcYn_Cff z|GoyRrUEiQn|>xfBAnwXsWvFe4!vu2{;_)kF91*}8wFPdTmS7%PicMDJP5f4M*ZWA z(yKusYxh&!h^^AN_z^;tIOsE3il--Kk43Ej64;LutCIws9ri?%$APGRv_nnzcl3)T ztw;X}M;k_<?XkG$Eq{Sf<n~tr>zz#71YZ0WM&=1#E}kSo-^B6=4x;2DPJseCm>ztl zU2vcDsQpe6DN3Y~#EBFCDTs$&OI=mfV9LiQC~1YmBY9WPp}7LO%zFoen0*LE_tQP_ zK}U-6G0z`!gUXoby!c@~UZaZMijkm3d@m}gZ}S2zq+_s%J;+n5jUovXNV?;5ynn>) z$@6_DNloOxKtJwPHuNO<F6m>p1wZCnJVu6dy329gD)@`z3Ve9z00W5o{p6L+;BJvo z^TUVN0KeQ2OmG@}h{ysbWXXBcF|N4%7IfLGJ7eE;!4Fr7K?=c1HdJCO=GdntNk=E~ z!nHOQUE@5xU#(honsOz@o9OGQ-DZn01*yb+RpJ(D6?qK+3<Nixl+IL2p(BogjDnxy zLq!uK{}43Xbml@GbTjwr4en)vb&YBcwmL{Sa3!igu^xL9ztDCS>dot7rPdhR3c)9d z+WNZ;50NsVpe6kS4kWQ8-0I{$SuGg2BxYL-*P4IGnOX*Aku0>z$-%a|HBxASp<WWf z8lPeKKa4$20jQSKVahVVa>0ZrTAIe*)A+tI9U1Vk_Y4Wzp_c6lWrHt@4NQ5UT9s9u ztN(aV&M`mc>;A8N@lKF3r`?RXLt^qnSD|(WsfBI}6s3M5LJFs>18;9m!U>EBO{8DC zpDmAvbeM5nM=%EG3ak&TNEH4f`Fcs*5i9k{12Y3G4Dt=EYaZp%aJ!RnM?W5Fje-1} z#y^+7usay^9gQ>O`;eD>KS2z(ll4VSuZ;#2QO>p#C8=ybsV`?&U`IHx(x*FU=fYI} z*)Q+hdFFn-eT@r|I%GWTs(#qZ<d)Hes%oiehT{y;Fiy_ta<!^P^{J!R4a%nJYud_U z5S1vJLUxH*ZZhdYiEFV50iSJPh}YGnyg!FkjahzQ=1gorJAx*4dV-Dr%g;emP!pxr zjkkWMUiY~7SuC3&^?ZkHD_8e<P*=ht0tY6M<GA|PD_?9V<dacXzYOe|`Ueyd<)!+= z7hu?;WO1er-Un*DpA;VdqrnoF-dvoaQZ80#go=u&oprV7Rmk_$Yu;yT9X*8;!hHRQ z9U7s>*2zbDYaEm8H4fnQDnY8=OvS3|yw->->9VB8XZR|nQYT1!9Z*G60-W$s1+`i; z9|QDs0~H7VJx5c_Sbm><OXucOx7wO#=uCwOIxaZYof~|#&lRFKXl049ek1XR0x8m^ zNd3ovtz6&!X7bqZ4!KWvk6w+wKf7L`hV1_?dKd&=KS|fiyc-j?qlNgo1(7)siR)Vr z-e+R0GmWv{@tq@|!mXwFK)#s9)u=pX*pWjY`uGIhGm7o~-~Fg(Ml?AUDY!~hoesUN zC87xSPFy+vaEhb$X)d6$iVTR3chM{eIDdUm!%>${FQ^(&>^FH9Lo~KHk>0tP<L9$B z_;9aS$hT$(3ef*Xf(b%Gk`*(h)<pQ%e!Ya;a~7k!Ey0l+24r6UUvy3U({LMw8XArd zq^c)KzT5TPR#mP4KSMkO|1bTYtV9qw_>ChmD$+oPvH)O1tikiI0snM(@+Q{qz~Doj zx(Z$Vy*ylCOt7Z6&l#$2vqV$S(eDli#8i4{NZO1_?y3RJt7^;PZSo<aU!gT0s#*qM z1Ut4Q&a7trov7N|Y0T1yLSfqlo>H=Hx-?xm8G7{V!(%<OL8((m^)em&A=xGqgx3mj zuS^IH?=mLQdW8j2?KJ2T?X%Ww*3ZL@;Qf&R4Y{HD>Ztkw!{8`a7^J7AK7MJ>;=mrv zT68A}Ja>Vqw-RF*oM~s5q$mFvo)sb;>E9n+v6g~!R|KXfREGHq3*2vg<0eyc7y3@C z$G$)%Dj5r*xb%ysK@6u)wlaovmE>-1Cl_VGvP?WV_u8qbArEt>)&ONf^Z~qXO`5VN z2+prIvX^*f6&!OwQ`K5bhdOjYA7%A5lmzxBV#RT@GZNOp7qkJXQR(>&6K{*1h&x+K zxc~f!&O-R_qGB0*;yVZqlUAg9>GW>%;+Ju_%Dq0ilu>>Eb?od{lG!6{af$h<Pb((I z<ewmiOxaTe_K~>+SJuq{WrM!*>^7uIxPQ)rmCEkUmUN<ml1J5-!mIoNv4G{&qV8P( zIAxAs-f^@-FR@b3QOpKpv{<9VY`ko=a(Q2lv2{)Ck;mDM&?}Qq<I=`3?-)|eeCXnm z<ZQq6Uxi1G;^+VOivT3!C;(u_j{<&!q$s%F_j@pY#cv@vXhO9Y`H0GI^t~Z(XsC=# zjkvyV*3gnn2kN9=WsS}ANiFD=^Fu)gkJxG1%J`*TbP5Q1Qjz~k{mh{qi=5uz(`hf9 zk~)=sv;FM8_+7t!y$y$+UaBZ5S3K-Fm_Fl*9^BU|@7B3`srr&qf2jB(|Gj&xQP*7B zxVXE~iM?YERn|49{zQm!TvtrI&N?}NdX1Gz>=$3_pTBdt_mzPDTNa4w$N$cOQphbk z%0>QP_9)$LJrwCnhP}jRu3N1nYOB|XovD%RJ*koSsq1ry!%Da03EYaVY^%=A)Eak( zfiSV5x+7j?2mZ|V2NTm%RJ^NCRgPXiA{~ipuqsWye&)o`$4G>{ok83geX!$Q>rB&u zn!DO|7#dbJboqU||Ive$AE+~g{$KWn;IPWehp|z1GD9KHK6psmLZ9ylwtp*RL3pHX zh*)Yp9R3_XTe&#h8#~D9di@d){9gQd@cu9VL)(?FzRYK4MG5pM#mO#bdvDGGG>^;m zZ5~?$i-iE)WhEb`xS*-Svoy$w(vkK-!74E4#h|E9dE~sjYA{ZLk5eqLPf5iXWQeKu z(PT>JhOW)sF)1KPWL=35gfr9cwwUSZh7Wnt4O?HN4=C+T{i4(P&A3XX(l8UX+$h6$ z=y{<GP(Mp9@}Vn5z4ENj#IP*GyM;0}bz7zJ=IY}+<>UWY@FN!pt5bM{3~nnuc<1fa zKT45Je1e(Q;}P1q4L=qdEIoG=^d<wx&r`2!O13nZ^0B>Swgb}iGhupvs{=`@jPxUu zm7dA06jaJ8-vOcd)ym2K`k!2#1Eo~#L5OhaD7xjp*s}&4%}TphdGrm%x)+iHoMOYY zg@5t0_9BP6LF42_!cj<Am+(=6RGbq&Jo~Mo-r$WXC;v~3(Z5ULu1nIZG)c1f9O2z( z-Ia4j;CaPNvENDaf4b)njg9-aM#;(ZZR@RmTJ+u8PP{u*c>C{Hur$jCyg7d51_JqN z#=KOFVDwLn)8XpakM}%Dg{0xUGfc#hlM052ER9>PqS7#P+HgoQ_+1%DH2{!L;h7x} zp|21I;ny#<XjP{5u4K_wl$OQw2b5CGp2ePe=5S8OdB>*v;C++t&eem?O%Wp>fhFnt z(UZRerL&hHD@$2oymOgX=Ok~h{d$2fK6YPhh}mkzL@Vqf(U>9Z3Bo8r$GPuMfD{P$ zeE!qd`__v^O}4x1Ca*;$>#ZDIc!f8^VMI+{e-R%%`8j*#LO$fnAsOh0t8Yr2Klo;d zlxC(6s-J%R^z@I-j3Qk1H(#=I`84+R*FWM|0HNm0<F{u*ia=C9v~pXHG!i3=@bVMT zdXtrm;N&B>3h$x8qp+p2(c-%?^LR72GF@g1v<Bni%GdI)u>!5lA^}a{G9s!cxxKO9 z-cjtQOxg+BE{iNzi7|rVWIqXf8=VjCAM4*C0(k(|koSnJ3Ixj$nS#N7F(8h3#Z9=! zLPAUp;E@Gc<U8O)og4$vC~LPFqFBAFZtsAOFCtqxDVuiL6!BSNILj&Y8reY-2NQ6T zYilkdF!y}K(MH~vGcn(ZdHRFpcig1<-aYnIiMX4LTvyLndX(#M{@(9~yy?5ghd8^4 zqe6cBN1$plXyl5ev6q8DPj#)iFRkd+OyR+vb&Hfwnwpe+1bL23-_pZRm=1dz0s{cr z+Zk4rJgtXl=)?dWkMTmcmSJeWJK~u!)zk9F_d~XofJn=Du};B-sCg0IAJHu{J4;R; z#tq6P`5orv1GI}5ojnkxtQ|kD3@c00r17v1T&WAz50RGRDFOf0X-!+FEY~X@2gfcc z0t^r@lgxg|76v;bX8pX5%{pHSt3VPTsR0oh!d+K#p$jfGNS_6Kft4ZeDx}^N?NwG< zERJm%E~_rNi(KWCQM<L!CzF~%YPLOcn*6h4wl4~d89bxM`!o-0^3J?SD1VtcPJ=vD zpL0L)It|w1gl={WQjGHY-$OAkQV)?ZhMs?n$=`>SkKnt&)Ek#vWXA1FJis4^OAaDV z&7Dvu7DveCAtwE2^MJ=iP73%gP`@frr;RQ!jjEQXn1gxt6|hU{M|cP}30(wL*H*02 zbV%zj@&VJ{?Hos(%AF%qzH2pjg#{m;Cw~HC#VGMo!(z6t@jjZ74WRxLw&%p{<utES zJ09uOx_@>#Xff$f&C=Jlpw>FR%FM?_YK8C_yOBiqeHG!qQN|@P|GVK_bHVk~jaT)* z#n20CBDTW<vhM1QJM-hll(|W#H{|~Xb-EeaRZ%2v?Kx#n)jzPOqS(31#hGra@Ep$Q z1jlNX=78B1rMZh1X^--fBq(2SQ9?7`;n3NNXT1P<*{{!1oM>;GyBx^750;5sEpi2K z*B$s8%2R}9&}kcF|2QPM9IU5}_Wv%*q)<xB{izS5@0e3Z60@_ZR|&E{hD&FhI-ImM z|CNi~iB-62{6F$OlTodyu`iB~@dk3%yn1_Cf(;-$pCe&7=`QP`BeWM|yg+FaKHJtW z96a(I7!9!BC-jqkK3;1w6DfHf=H)o^KF21H<DoPv6G+N0%HP`sQUQs()W7zX3!7}g zp6a;l6_;5Z`70K?>o;!+0CMZ(;;^g=RM&fSjv92}=vw8|!*M?7TNw_z`0jF^jiSX1 znL1!c6p#`bmCsl81Nd(5^#GD3Q#S@HHFL#F5M0Y_UM9wYflY6sirlhxny%bfj+vLF zX+BtPb^&SIbV7Ae*HwL&{c}AI2#J;R$by;gp*$A@BGl|;gcY1KOAyoF^CLdvJHl*P z^i!R0M`N*pNyP-G+h~EjeavVA*1!~#A4v)pAKQT0B8a>$bvJ)#HB1j+r~({;R(eTU zc9Vl4vs3i@vO0R`y=d^gj_GkMV^Qh@SOJT-=P+@IHG54o@uFug#P-zzcff&l6zTS~ zIapFytb|>Z0-X6TzKBn=GwnUG(ZE&mAVR-(n1|idQId<UX*mGu$CT07Dq0B=*HTx) z&SWW2-09*c=D*pRhWJdm7jvyG=w6O8M9R5M?n%Lb$}5IvoC5OpX2x~#6`4`s_K*qV z-gR6usNQ}&TV_|^pwc}AnsV;FtMs&_2BuQ@Dj#pn9EEEEg0h`h#D}{2K9_uvOpCjU z&M`jgbqV|tZ>#&SAROL?-HYZR+dG*O2-ZI7c=E?ZrU$bx<nk-s(fuHT(jbCW<>;?z z+avTW8ZN;q%Dz5yaJnsXRhCxP#WI=WiAURK%2sJLQBZ@_>Op9YtUAYq)!~GDOv!o} z8JK7GThbwP#e7I9^2X6TNgNNX($PaSJw86#J?c~X9_6^NJppDxw7XswRlkTCwq`+3 zHR5wGeLt5t%a5Skfcy&catz@tey4{V{4s>~+sNt1vx4x;O$w@S-7|?^SURlV55&LK z4(@l3x5Wc<3%<X>G*JBf3ph=TAqz0_z{(%eJa#@<P5@;d-*sK-n`3%b^7YpkkTnCS zXdX6z5@6nqv{ljJjeD-OcP3-nT{H7lMl&yhWiFiEkR5kF`<6E+gf;qHz9Ls}LU|66 zwadF{`pA!4^|1vvoQJamxvPUm`lHx!NpEeT>P=-3+b`s%99)#i{u|r6<2EqwpdPbR z*p#lJJ#`fMuY-rMAxl@}o2cE)_0~Q}Hz)w!UN2k0z<xQ40#>8nVBZ|s_Xm$ae%XG* zL{wle&v=D=k5Ww&S7>TDLodUv<B%sZC1LCs{T~__>Ej2z9{#fwCklD_0@G%pwJ4`v zF9|Zs__nd>E@S7XnXUoTR^*>a-U05WBLB5O@kA1cP}vsRQ$e%^1P?g|t`mHVP71QX zG)XLRwp)bFasJpIyG52~4i7lQr4FgC(%v)c{1bsx#mf(S*8~}&B_;Ca71;E#j{6QR zi61*a^HG^#01)Eo6G$pR>mdbTW2QclUu*LwB!~i}<Lsj^M6_|!=Cvxb5rfCH<t*0} ztQx%AE;3uo8Uqp2^lYmq!3OFOS+xWGj?-0}sBL=A9k@SyXD-VnVwNUrH8piJ`D%2~ z2Y9J;A7@`N6Sm)skTvr2<0N@)UHXZ7IO4`nvSVG?TXk6PDL!4n6%b3f?ne9|Wp_#I zMfgaUD)2r($u{&w`Csv!Q1H&{|1mC(o;?4?IyvQ0F>>3@0rzU@xDA%$_dTjxiwws} z9QZSzr8r^+0(v3-8|0=x6dV7lh0DO2mg%vA`?-|%bW~c7lPB8B!j*UzosEvO#roD% z=zspqHhNv|d@JY#6KTB5P*9X@3O&2_$-tuKanAP~T9e|W*+aDV4b&A+xp^4!lx<zr z(Vh&>XIQtXEry9;NvsevoF6EegmAF^j0E#O9oy;qKU>6ybKJ;a^yFC9u-a9uHUo@k z1Eu7gP9HeYqX0f92BaQQ7ln#5KOCo<*xx3g6OKT;jnFF(Q@}E5@^9sI@R;*7Iay6~ z+R9m*0c35z_)ZBQ(Mm&V*{LQ~r_a?njW0o1OGXHsP2W$GDS;%%CkeqKJ1~>}KqR}V z(fioZAFHGPN!Y6ivYpJ)4mW~c+Xx(3avl7k<?%dS;u{-p;A3ot_A5W-fD4k(iPcOv z=g1VRT!!oNV9N^UKL^Jho%IYTieFL3B-|w?h0CRBpr!b};ngQyLm_Y=Ub5>rdQ<^y z#)K3pS@BXKOeUg@c{WS~Y+w+Xsf<?4EH78hIpwHT;nQ4=C>4nF0e=81UX_9giI7|P zSF5mHA_*%twd86)6P>)N{p$a5l#=5>G#Hf8)}EA9y=ws^>DiAIJQKMIGCc8nuYNb# zaWr86kim|{Bm4!Z=vp>mfGtRlK?I}Peb5F8ZZ}WkLY+le@>5V|HlheoTqc)JI(TXc zE=Lwi=Gn;^ofj{U1Nb?JWp^?!^^TF^7ZVF98W0xDf!jl=(0G6c%GdIR+A_hmx$k|B zZBo#_8~QLfP&F5iuU7ssY%p@@Tx~+8!zON5JF<$8%rrzclf=)w%{v5-UDS+9N<dA} z5FsS(p#<&Txx^#`2?1Ivsvq@+Br&|@>{*jvL=-z2pD`scc|{M=q_eJcMoZhXhj|jW zmcYGBDB@ETk*<AUhCQe0RiRE%7^IspWuH>e&)|gsITCMMsNHU`lLlxe@q<W0vFMe; z;+$~M7*n$-LSE~H2^9_2!qh?lI4RRn6Ds@b^iM~0$t8sj*-NnHir{ZWU>O)rTUnE- z%+a>e)<#!oV>mQKHuYSJH~Lx*n&c<RAc@z;Qw_KBjQvjO7R6MC$vs+;I3<AEBaM42 zqLSL8a##Tp#^__YE*$UOJy@u~fqbChVqo{K*@!ES5&3;T$-NbaZc%OXHwt2h%Ctak zopb30c+|(Om_{-#<yYP;JYD$CE$giT5PuM|DF#nZOXrJuc!@Ew@`O~bydB}YCJ)?} zV*x(#S5cAdjs6ejxvL)p9^k?GX|Ahw5I;GJq2~_A6#c1`U^6U#0}04<RDSSAYq|Jo z(k~}h>)o)GbG>~z91!R8Wex1CO_u3TQZQyl!J4)h9tAo%FZ0CTCW$FQ9gAXYl;XqC zFAXlf14+6Gk*{)HF8PpG<}Xr}4$0dZ?`=4fLxMUxYeT%eyq&o2<1yGf;y1Cfza!<2 z{Je&Lin!humK}zG=3NpS7efY!o!W@SQ&T=nS3(R7paT_95ng>J=d^ky9t7T_QUj#} z$#S6?OQ&V1=-vI*A59=e{F=1G=nIO<{wDAe9A=N%L7qnD-blG=d3^Z>&PAP`heb3C z@&<Bcom9Be&%~)CF`mA1o}VO`q|zPtbZrMCQ#&{yd}>odmE4?h9xvZjR0<EFn)pMm zHW*&j^h&NWb{;Vcl`q<Je+hMXOS~7@uWfq$ZI|l)A?ryna7J7JvUDO6of7I!F<cdM z$(JvmXmqrd&yPYJ=m(pz+>a3nMOpG^!(hJs^8cQ`5nOZw5P8N2s}XeH+71A|k>B$i zDe9R@#W%@PL9HcCw8QPKdFYRImIcf5RP@cShROlznDFf4Tgc0#x>#l&`rf#e_As)H zDiOs;yacia(qxmybP;saR6q-i5?siDRLceYl)-qX7Dz0kggo&+Kyq@!`!Wl?d<ie4 zp{z&^Z*E-tYp1v#aCPTv9{PU<#(NBm2WY51w(FLTNU4lT{#~|t36uJp3ch^J+tF!) z?bB2wI1`+iRNV<|gn`={lV}J$Hm4{mJenpiJL3?5y%~Gm0Wom?oE93UiO~u~FYq&_ zXaGt8K<M_Smgrrs4lQ{{EG9ZGY<3iu=K^GSC{;N!{&2H@XBIonxi?LdiC=l7Nt~{= zQE4tC(HXo*!@0aVQq#!o+Z{r!CzWyo%aBH_L_*2cAJtyhi0BcL#7hz~?xk^p>fZGz zxrtH8Er-DL-n$M4cc1&qu}WM1E!y)7gxNzky}kk2*))xx>3WtPGm`7yg+raOkUiy6 z4#W9pCt`Ng356?8jSe!G%U_74FNvL_x+e(5PGRHT`J$Vn&mSuy{EvceKXatR&OuvP z4M|XM9a2n}0j=<*9djh_qvHEf%t1Fado$-zFVs5Fe77a~tO@)H3NSXjC(<zN4Ze5W z6v5(mzPnzF?dXPqO2DA3N1_TxrP@^Q_q!}NrGZ+Q8Te-}cM1!wAxlJlG~F8DI=0!2 zQj=Cm$Vm}1<II(SlGZ!R5=F*h?-qjBnp&Z@$qq_7=U+xMCmL98YC;k$hbGZY)$RsR zJ-h*C-|Y^2Hz_<W#VC92B~mqUaNG$I<HrX`nQqHI=SfhKFzA#(!@MsZ+?LWBZN8(S z(o3-HH6lA`(T1hh6tDa`DJB4|@uY!xY1^OD3jhc~E&@LVp%E4f?vo+QaW4Fa9!pT_ zM#t_6=GRrT58j>ob<oG*JqY^cg)^AH&}JJtvi1bL{(59f7xhlH_4?=g>dO)u0_3RI z8HcP=Yrj1YBkJ#ONS5-&XO%P7m&Y91@+*OQU~$ZGd2ErHbbcaBo^FG2SG!m&5zmLr zER8GY-^#t|KYVy%KFiv$dg8RUQ}fzHU%JP>7hD2*qULPL<^VW(+gbf>tar=I_a z*y6ZJsO`Sc1YSb6LQwJK_Y_Pd3{XQ)o%<>EA5H2{{S?qYwH`+PezbbWYbjOE;^vcy zCoN-*-8w>`KRenA4V@gscbqy)L6gkHACizasNx2k`vAY0_y~K{^67zY2{Ku{FMM38 zR8C@3`^^$!s;&NLdV^LF`dyKZUcc&iYU`Q~#{bvC!A5(!i}C)TuCWcsH34b>t=6_Z zv&6vwBsY@|t<zcJ<CShIgGbw|%e7ZVF6E%l0Ym>Pi6xUkaeQUEk6e*aF(7;>U3(<q zw8G&|aI%;M0;C8Rf_FBgR+}?EJ?8vQJOTFWJ!aURhuhZ^Qn_|ko+fecgys!^Cf4nW z)^8rkh5>UyXua8co_{p!(5O72xLuxMi=V0lyY3?@Y?r&@PRnCeFA{u;+ER0P&(!Gx zU_*PFCfTat9e+lryh<l2{-Rk<Yv;ER&*`UfpsvT7T~KfBVY+D!!}Tt8v1NNkupj-w z3~jK9!S;#UvFFPJ(NkfDSn#7NOCc<w5ellvPe<5pK+Nit6+;eRFzReQgCTdCmm+`z z!R@CT_F?nTP^<zv(jw-zxfB3O9RXnlZy;X1RXP}28x;Eb;aL-9dQ35d-UgNlclAP7 zAeW)(n3ZzJS6rcU7_u6TVqj4Z(x`i+04MRMSOqWbmAY{n;_+A=WH9mPUSr)6uW6y= zo*&wsVFyYVLxQp-3jx?1A5FgF9lEglH{tHiab%a*+Eb%<8JKlbh=J`b0CHW38rWQ2 zPQ{*gUukEEr#Cf2p33&lP9zsuUHgv`WU4vbEO$0u>=e02frvQS|GvzY5E>s>=q302 zx;a4o;9wh}x!fD`Uh3a}PJAssei&TCw~M$P4cQ4+_^h`Sur3Ni3>DibzSTpg((Zu+ z(6Sd)9vgjHj)vdA^yqfmqt6v`MXIO9$p|vK{_c^5WElw|8QI2=93ZVH;lBURXtaCj zO5){=y2LAz+b)zZEB0|VcCrHlFyIy-DPpm%lq~iP)DdlP>6O>;UaI5rPLAxbJDXqT z0@2^}9|P!$v+*#(hFCJ~BebXoCAP7Hc=19$0NveT9!~$@*R1}vkLM)U3Len7k7_y{ z+o3_;JRIr(mf6A&L?rBnn+D5ouLsGzP$r(A!+QnEUbT|{a*!8`6w$*k^^0F7tL}S1 zm$ClemoumiDVSHl52w3mr$eZX83`lD??EnOQ=|+pAtLqV`p35KJD1TtnAPVO_Lv2! zm1Rog$HPJ<eiRzM!`Ztv0)zNRpE?q>X2P}XaF}mqg$^>0390;RH^oxW2wf8FG)XMw zd|R4yF|CC;qo(0c+yX#YM--q9Q~?0ieozv*mzWIj8PzO#y<@`_Pgm5rvb(`cw5L#U zV6X1;t|DHJBj82~cpCh4$8FF^_XE%vvMB{vDMLU?buuyxdxbszthyqCre|56ws%Mi zM$=2dMctTfuy@42Lnl2fa`U+!y((k1r*SWRANL-I?XmUq1u2oiGqD>n+_#uFUV1pW z!Atp$1G)1aOf7Xjc;wu!9m(E*@dm?6?4bLp{z?Xu<!3&EUn!7VLl0s90mq|S90QN< z9e15;k{5+reFvWVnb5C$0%oAOQc~)OvwY#PqjF_<DsW!+8;I}pWRHd7B5_gM$<xm; zWRRHe&kn;770&t$(`!faS#Sf>?TUCNbNSz`*IxrgBfm(%(C6qVi{<Xx2ru9O{620~ zBceec^IN2)-|<_Rs;NpDgh;RH{zkU0=DV#m))n_~YCUwjS@KSEb0e6hWXO_E!JVGQ zoB07*pA}BzG3pGT&bc}(ZNL8%j`3{(Eh!cd-+ne2F${n+j&c0-a3f`Dx^55fA=CKr zjhh_9DdW%YjIeePtWsc#`D#vRoHo2nXJ6Dm3P9hW3^0#rij}tk@nrxd(9-1orA$>R z;DWyEr>;C3q7H#VN}TGp+3q4-(Dfs+q=0o=q-13eDnz5J4Ew|i@CB3aDF<sI$bc0B znN^5wL^zW+XW$^H+T2$>TA^u_=qEYsjDYGT<_@r$1o&E{K{^C5j~l;Hb0u|f?K*!4 z;XhSVjmhl9WA-);*LYN_sFzq@*qoGAa(SvpCGX_x;r#o+D2A1PJFHSc<zqYExL(ds zxBJ|$1_jsqzuqa1>Qb`D9{Noix&mNSOh|BNBt<Slce;Hw*QjZ$=E3mdVR!oYx`VTD zwnwWXFn?YIKdJPJo#L*$kM3RkStrRj>}w0V$+h1M-T(TWs=k?roWtF&q<vAu>Y9;< zT8%7SSif|ev@Jc)3`niL5c5mt$9*Cu;AdY6Joy$rz^I>(M<@VGKn#%j=zh@V+dwd2 z^NHpMI4e=HTyKkm2%xMbB3A>GiLZ_bsr=X*DH~NQ*=aO>=enf1dj!vA$3Q1<(V^W@ zr+5W$zFXs_+ZI|H3@oe5xmj)2-ED&39xZJyo>BxB;ddV@??HQwd|*ZF-Y!4ZpsX&R znC*pmC)%nRxm|3Fd@C98pN=w6a<D-uW8c}~Ct(#~;o9Zzm%D<M0~3qx*97*|!1O{5 zj5Bt%n2z+8YssY+d6GTM?sPc!V3)PH84=OTU;x+myee<oHs<ukkeod_r(+pPsJZFv zp%bhF*iYc6D2HWyF7itKSVS&rfMUkje@_npiJ^0B!28Y0`t0_+>+c6CYyde#VginK z)Gr>bP%aquxposF?vk^sAUPsSSzB>k*SpGjwiREwG_2(dLhLwnW@>xL&N_hE{WTw5 zj_)6TYPdjyodERo6raj(>tYO|Ga%^I4VVbV_u#8Z;*oQ<*@jo^BqCD5VsqH+GUo=H z&9qx?$EOkDhKZL9BH@711Y!peaQ9>kD%Ez&2xCHv=4XpcZ+9P|$RTQ9lfq=Zvaq#U z2!^BXVCK;d&Wr!3H}byQO0%~5<-b$)ELT@G=*kdap+QFTsFc1*^Qffqb-UeQELeI2 z2OZul#9_P$|80o5lp%njuwf{|KtU2ja>&OHsF$4?69<vthE+I8z%0U{2?oSm+Q17x zW?9PONAe!W5$^mCx)1Qm_adp|zU#bJGcdgDue);#zcV=M$Eil{{_aJXMR^YzQ}Q_` zAu1(}BczO?^32;$&i-rQpXr=nQ{3{^;9r>%EC@@i9|^lrl{<gQFA)_;BuE``&VE3< z<b4ZDJ${DbpdH|qx3DygKMdMkt+J)MbX1N|0PasvDZ0HHBdI^NjBSueV9BVhXruu0 zc6&>CCLD1<$9*)5qjlF;on@`p_>y8FVD9(~gG90(#Ovk4)6PDGE9_@ry!Vs*C0W8Y zl(7n6hhWwy;IPQK=jS|UtaJx2Iq5<(S*hBGd0L|gV{?7z*&+G(mJ?Ts?m6dOKKE`- zVK@Sc<}<x3cg5%#PC5@~fC{4Oz$!bF6{zDXzh(pxE=mjWg9QH5nfp)^-0G>O6K;{N z6~V*j2Id~_O^(kyDyTVc3jy>>uUiT5Pnz8zfZCam#^YCI2)^9C&jCO?G+c;J4Qdek z9M8do;-t=1Kxlgn{RXG&@G|YrasaPeAc)HQtSpq=YdAkn3AG{4ty@Ds_;W?!cn>Au z_!oc7BY&t^v#Xw)kA$9H@&M{(Gbh&R5jE#r-oASt2nU^vBD!}Ae&F`7DX@(2ZFZyf z;Ep+<BcA)NPt<9$x%yNPYrb)WHZ#L+4Hhr&79I3YM`RnO_BeN$6>~-zaC{|W>|0c1 zpHXbow#C~^huZD+LK1f13X8(FYxVCvPv=j@@Q#Rg8MjblJbWnnZCYhiL2EJCH3typ z*qA+%PUqO6S479m;nCGzrn(9sA-f`9jNlAsFllTVwBIU0Mw`I|-woNVIlSw+4%yL6 z$jq}hz&)Z!0}OtVjxTF$uLLB|ww$-0XNJS4TrUg!7w2@!Kj?lps{%G4PNlwkoUk3? zys3V<*ig|O<Oas^=pR0|yemx)=N94>%4yqR1qYpM<NVF>KKmYg;qIe*q6M#O!dDI6 zK!7v;(>`9FmD6dC?|iZn#CP>k(o@<?j)W~gGo1j--|pk&+k>Vlug=65R_v_{$SHCe z`yD;)!b0twqjAhuePdtraY~Og`rUW-M7;InNUGhGkp^gxw2o%`^cAUHM^p&~q<*jh zx>=mY$GwU>=rC8p)6Tr&FF&?e9F|$cYJVA!ksIMqb-^~Dm{UVv=4iw}5<d*oI8+P6 z)WV3hE0T*Qe<|9I;P((at*qtvwE1v^^`&F>>#BK54~;igJh#5FmFD6pgy%O6?&TkO zr+b{3VyFD9e6soe#a7PWrcdzZsAuOx+8mNX2&lTvkNxs49o71VCim6UKfVJ4@FOoC zhn*{sl4E4;X}^8vpKS{q`yl5=6MseiNGrbCgY(896U_3f^F`(YM+bD3t4;5o$vH1% zL&!Uf?j%I#kR{jePUsEJ-EPG1lH92q92VvxJ4$Qs42M&E+eP_7Ud7#f!Tu)OTH|r( zL{gDivEtNQE0h2Af!sL4kb*EQ#6|^GMnmDWWe=&SznFkJY{5h4v@h=MT$tdzL_sWR zoq1gt=Wo_;{)f3s$gXg)zOlj$_EZ0B!4BToSLSzho^SK6O>wn}13QBidwbvaawGC4 zN3WN2&95QQl7-!3+Bsj29V`3Ui`cR=*z8x^{q{kAJozXHfC}OL3B6o1a_k1~eq@bA zmu0XyQ#G$YkE7N#Ai4%OKiv?Men79OEc!+}*SYU~yhWLx1u3_WMJ13qZ11HV)?0D2 z?bMEgLxsoYSjua)ZznF^*|II;R7BF)E^FB$Aa7ZueI7I0ji>+f_YLj33dcGT3#mk~ zwNFHM+{?(K3t(!Sgckyi;jkjv+-`fx#<y2xm4T83Go)_V9f;4uU~%Z7LSu6CS7GMC z<_CM+5aOK(qO4{9+Jn4CgCUpeEUkXWZL#D=K;0FAOhvdtfrs6iawKHtQZI|67Ur*4 z#wgQ|Z=csO$gjw{Y59=bf0G3$7Wi3g3?YmH@)nC=4pf%+)~+;qB_C39RP9mz8qA{~ zRKB2-Pvh2Y+b-YaR93>tX7CeR>}z0k(SQIq9!>|qo<^PAiXBR6uj{ic?p>vlJ=+qW zT{-4$vj278IusA`PlcUFx|aFD<`H{4TtxxLy<Lq^1d8k1jL2g=x-~|!qcOF$ptrpq z3!EE`Hbk@{#<}m09&7K1xfq5*N^*FBh6O`zBPV<oArQ%vc#Qu9qj^e(_il1j$$DM1 zHZH@R+o(5W^za9S5&M)U<=vOhyX%x@)m5QlyaF?&vAxi2#b1p#MK?WGUu~;B3lgZT zqOeQQ2K(`&Oy&B-aUUw|hFa%X<M@DiQ(;!NmJ;g+Ww7w=jn>c+(!Bf=#wE)?gy%Ha z%}VgB09IwG{n4nh)>h?%`=ccn&b?;D4X@h<Q9F;CnOC0Aw+}oPMcBbI8#ixP8|Diw znCS}g6KW?SkxXMl5;AwFtr=9oi-t_*b(vafG17WC?K7NvZn@gUs?Wr^TJbmu39h*R zgV^QVnPnb%O;3+2w@s?ei!Tb%$_g=qdu~BJ5$yGnS}s;4tG7^8C9Rf>cXxVz?!+7@ zxyQL-UHBF=(VuM;0f||f{+V`5n>ewN@x<k(zV=h2wo%RzQuZD*SRk5ou!GYI^wf?a zRBUhl>0+I#+Xe8hB-vV+<;&T}`!u}7N`K3;Lo>BWtf*<o?QXr(Sr53W=-+21&rfrn zH*@5$NZE}$BH(!LR*P(yy+5^v)4zjI3`53?qfRy<P#K1~(=Bmr2nj=|ol+h~O|5|g zJsZMK9k6=;*p2UoxaBG;@Ni-mq;_=xdxKN%PqeM%#?m0sJUGdLV(?JuyFc+nMMoI+ zMN~{(9lrBB^kCzseDm9gib^*?w7-kb(pG{W+2{lo4sG)Z)dU}etKx%ZJ~writHjEd zWLfC4_HF@9Gg(mqV_J5NLn@71y@$DL_K$T9XZsL=ZHVJ(+^NLF{lCN#HgNv(UR-Qh z=905;`vPfHV;HmR-=szhLDrQGuL9sXU0w0?;I3#Y)Yc4sFy8y>Dz^n|ca}L7@sDvJ zIopz)$u2oq-6>HJzhmuS1}9z`FFmA`8@%TP2lR8G@T-dsHJxkx5HTKazB(cENBmKc z64+$}79pwfAJnIXQ>4VI&HQJA)m2H?5g!S;5FT~GL5aDSf8pQ_4UcyyukYYs!hWxN z2wp*39Euq}#Nqe>3C{l9rDh2;Kx3SvX2_f^)sl*>rgINm)@$Sn{YAg}tD}f#1Bl_j z9?4G;i^}W}bXM#}0d)h)`|Ywg`tXmC?Hd7_8S2OfMn0$SdEv%(2VUN6rtBubBZQd; zl$39}ci%qsV(BfHmC$WyaQ~M(XP4YPlOm{sbGAR41bX{~)m0Ekxk|P@cAqqx1!JTT zHMZxlmJ&Oem<sCp+Oty-;AJJ+YxU8=$7<t!2k`u-0&K1<`59}8(fe6?R-Ji1qW7t! zGlW(%-Hedp9|keWWqh@=c=Uy{58(Q`dQC!BW0oaCckz{csH>C=QpWxnqG1W@vB9$D z!w+s<2~yduJm&U}DLJ<$E)dvSJZ1X}Kq9WOWo~!+#Y5VWsAX=&@wMy_fOS&HrlSKl zPhEc*okb!ax=DOvo^r_fjIyq-jc_a9vi53hjO3Ac_(_RuUto^$!`yoFpn1U5O<qyI zx;IY$DEl6V_P6F5T6I64VMc=PZsFJr&*iO2Aq?dARy@#3^*};_Jxie3;6nFV&I#@g zM^S@*RS78fpa<wFJX)|UShGKR8!_c|SNRT|>+B-^n1}j|#!hm?vvz@`G`IlF-x=n> zhuv9FCyl+aTvj}PiEY(=<a`2LD+1za=eF*H`W~dSt`ZU|gpt>>k8Q9`uD<JHWIM)# zBhYnvF6N~nffjJtE)VM`RPI}@`C)OCo(&t5%I=C`uMKhRr|OU5**ArfPE#CHtJ(au zR~uQg4JfEhDpXMjqHM^ijUdG*IYx-ESi`aNF_}8v=w}v%&y&Nr{EHe*2oOh0R>bu* zVnfytKs@=$r(u?WoQ!%n|Bkyj=&{Em{F&|1=C=LZ067n>S-b|@kGcc(24G9f+Uk(0 z{KkpZOZD+F#|tW8Cxl@0c(|H!#CmC<_5W;7{Rg{T360{7r|y0;z<e>r$W~f|bq38` ztbO~l^KE@!KC|`K?}d?;V0KV^mf0N4m(M;|bl=xm1*$TayL&bWv~=^=WHrr-qV&Mc zpQXD6n5|`53Lzzqkp&gJJCTuEjOsE0;%~GrxA8Iy03C$`_Qt?1@_d?OPywUHTb*<1 z_A|kfPzyaA^rK3a;!?FX&l>fZ1uZxkh}WTm5m7^jE#W%U>C~t7xxQ0I_PhBL53Sm4 z1F_i-STN3(d)LwWDeY3_V73oU^u547=UzJX5K-D;9ig=Y_K45E8}Y*V^NI3bnBn+C zjQb%m>nqJ36Mwqc8DStt1biIM)v{4p?4Kati1>#fWc9B-dEXAYVCND!XUp?(y^?81 zRdsJ`zn$>FM9T^hUj1uG4W1VH@*I6cXH;Y$R(>1%1`hZ?grBYWAlHhJOTibJIs07# zl~Qx_cxps}J3!;T&^5h}zA{jm6?`8eL3e4GFvRUr^Zj2zg8*(yUeI{wBCz?I@2paz ztsPr7CGc~T<0~JqsE8T%To=J_8?{f&WxK>@)A+;~M)t9_=z|L%E)8Z|aWWr#jJ_jT zGI%V$%j1OE#n(Pj>p;gLGY053pY4lQ@sEHVNZ9c-37isfDqfk%<@-HyU2|idWyvnS zdbOJ65YH58)-2JNKTYMnfHO=<%|?w#FR1k1`0CnLn#x7hz*wd{uWgFWU5-oC@_Wi1 zWuRez!hOU~w59Sr1gyJC|8&c+E5`uaSh+U)PnX7+Nm3blpx-B{%&gp%mgHep6jIMR zc^mqMY?O}toY!Bk{Vd!{v@jHayt|AG_%FPo0)xrf9GsZxT6TB^OoaDOP^h<?IR-G` z6u-=k7Sr>`?!gP=W31fr1ut&LtfNk_ABmWxb+B>YV-O3HitX0aF}s%oYi{HO?%Y}) zQ0{`vBX4BQ=rg~UT(~lqYtg0A4B6SG_G0eh9fa*LM_pv2@q5R`BEY!QJZBCPtCtX+ z$nDR<c7*Zz!-}yYTvV9%6*40^h`ZF2`ecqih1mUfK5wh+I1C8?((Y@L0K^x0DZ$8% z*{q1lTNjG*oVQl1y+1&dPHbH0C#_{?eLgg9w9M@acP>7%2ETO?jzBN~GQ(+~@#gRG z5&`UW$lI=n8FML{azcr);*jyBR2wmsrhpQb4Gf^ML6lHPp0{xy$H(n93t0L?h7LdD z^OY{6I1uIQn=glv%?DE=m$?g`yqedV&sY~PU1{sM$@s641MU)*{(U?Pe9GJ4^ex|c zJ7ozhjlP2;05D8Lc?Z#t1hn8{=|~78f4~&}?y-NwiRJzSU=uKw^;9_M2<)~tL`2fm z0d28kE6KU?e7|}i*-$G_4yaOs)u_z5@^zUV@P!4JWPeqyshD@;r=t1#wWu@7qDh+y z!EwR;hc!O?C=5Ymm6u7L#3i4s6E8g3zIM;sI}^o@wM4&&yVaM@Mt**F<cLpq_j`Ta zym3V}#R2!RsKuyfI)?!24=C1LQ`?KRKhm%ZL$14mR|Gjj0U12c`-g63HKFLLP5Sr6 z8)w__4D&>ZR+-fI62oj?1-vn*jzh*eh71D&a7d0MN)bR)XLc>GM^3nyEdiNi31uJ| zK!X`Oxokc7Yf?bnQvZrlZ|c0ZSJW;b<xA+lW>gbLb)-EeBC!pF!rqDSmIbaV)t4N# z1(Dpm99$ljYMLk+SCAQ#hs($rpp6OAgXE-q{2OB#Um%xvyM(kb36oS#BFl!Pn7N)( z^v(GABgAL-_zyX{J(z~lyCWDJ*SB*odRz>2V%}w;%tyz_SCF&w>gA0-E)fej5oi{i zCg;58oOAI*M7*5g%b3)o#1|@&TN*q&)ZrqbEnsYL<P6y4?rS6}fgy8BO!t3<`2|wR zPb_z;X#Hf2L~^68R-KTN1U#mdq5(N3i|qEjyF~E^+W@Y70uYRx1&?iJle;8$hW7wx zLpx;vCO{gcG!?-a&Ttt{u~&^fWK@g44y`5&zY&E80cYoBszPum>h9p2(3O_;DiK9v zjy1m6H|gFXW?s!F<!FzttwmfAV!ffJ*y-Mx!)O0)y**Bmx^(4^Li_Z%{;iDuQN3oL zk?}0EuyC~I6;c<qTu0uF$FRI)`rfl2Oy#J`btQ22oLj6Gg?JvT7hM4t8H`W@eA=#4 z5Py+xC^iUI)^(uyE?AtcPuvAy>^DS&M=Sp1fv@W~Us>0SuQJH;605cimh)Ko8-VWS zb*~>FK~%gz|NBTB_}%qA=QF-ne|Eh8^LMlWBI&m7Ne@oWRWFO#3CY%ZgjmfDmvOse z=7{l(n4sFpgz@x-&7Ni(E?hv7yAxpzA;%s7OYS<)%pj7+QvgGO{(lsm`y*5TAIHyb zY;!x?7#nGu+uZL$(l*0fLy}uHjF8H$KDuu+nrm~vM9npcau2CSZlOX*r9S9>{YZCR zeE0qB`~mNC-mmj|JztN<=P_!wWeHGa?{d87Tn%mT_qAiElL%$_tB=-ZGWC1RR_P{f zMloppEX#8Rv<xMGTyapWG$Nv#)&a&|aGOOUwm2-i#&r-lBadNE9)wI>&ds|(yM=MJ zaTyEi*p2p!*{?qbZ~^X2{T$UxnXRX>NCa4BqE~=;J9G&Gyw?LMf;-zTSP1be+F$@7 zZ9l9G2Q2Ge-KD?*DO&fv@vTA^<#AFK%1g(wJwsB(!ptEn^b)C=8(a>OCiwxK8he!w zY<QvI#a&N-4onvIC*LLYiZdmv*lLV5j5xtUSh2}8R}_qB`x^eCs~dcrXKwlejdiKO zmL~l9$aqwZ(1;;}0ofGwo$P*-;!R~^G?v~pjP?~@o$>C73?Q<-%_X*8JyTVGj01He z|BgrE<(I(YD==VH(zba5B}ham{<eq)(+UkxBN$eLwi>kx<3&Ql0Vu?WhYFQG_UEd# zw`arHaG09gw!io`_f!yKCzE%N#w^nd81mdN)9-ci?c(iF!r*~*w=9;u4QW3S9$##m zZZHuq@1b#-zS%Q$nMH0M^B<?Si!?BZaJgL$4E|<JssGButUcf@!YpgZV!ef84|#f* z+RK$uGQqe&b|V1FYTnJe)S{5ledmDr(3+<`V1Q^DcViNQ=bNL)d|n1kd4zto3EKjs zxJ8_FdQNlE5}m0W&Vv#LH)=v)cp62C$h$8aY1Q72s+FsThuk9}xmS!qK#z5XK5Pjh zeJ%jTcj^vzbOH4W+AxhDd!YAI`DtdeRF#<mm8STa_SUf-&<qtII#OiMN+Km`g`xgL z6vmkdw1r>PJ?#23d|L+OJ10?kiSxITTs#bl%0!){OTI^9_u<DRJnBRzPVvac3_v_) znmnaI3v?phRHFvmpLTXgh7i{tm3)XDvCCjYlCFyoR%27^nbmB6lTV)EKDyUxw-?f| zS4fD#qtkukg$26M)_Glj1Cd8GCBi&g@Nf6SfipT3Ob$GVyar_Ghf2IoPO>ytNj26j z_jX)_(oXb}wmOCh{F!RPdt4bnfiM_dV!?tpjClZN?xY<a&Hlr&U@#Priog%ncslO^ z-n*TQswrE01Uy&(#EMDccPC#i8(udVwDQxx?FPKlxjPz;Er@pZ*pfHD)qPuVOu_=^ z42K*-f}sx5(pO9xE8E~N4T9gKQ*x&i_EZ$BZO_^-9PJj(Lm=u>c<%L<-$AE|wW=M> z9~dlp_Nmf{t6%a%BjnrAx#z<3vs==rf#$fE>m~v^Z^Cc5<*NCV+Th^ROZsJhxyVgI zl4AY}Y@^J8#h>RR0SU9-s?r;Hi`!7C+|)sZsFrh;B%giIrA8W5$nJ^e`H7zfpSpe+ zrm+Gbs|H4~AT*7NtQ~;HAOW+c8&4g|Z*?|a@_&y<;!f6HJNit0L_SD-F9oGM_6VkL zU*NPM;5PM4j!~|@-Zsu6Pj(Wl_AOs#)(8$5_OYf6-Df6!BL)fOi~Wqqj*ryGbK}?( z&A3gFoREd3jkU;CZ^7x8Rvt0AO;k+{N48v$0D5#w95@7hV+6!stYf1UJQdn@{fCBg zU?{luYZ_!zk9>jg*?rA(U82%T<MnMW2%uSoF_yNl)6RWY?4-a3#8!;JUR+cL)~<#f zj$p>#6c^GcW)OMXK$0%i-)w7IQov&z;KCX>&+*!ahS3VyAX1IA+-S2BeEC|{zSD>{ zi_~}yS?~R4is$`-JR@z-^I;ctp;r}Xwgd4MJ~81NIG|r4e<dmAf<|7UcJ>#>;iY19 zp0%N<t#4U<*5}ry<5fpYa8F1#xh^<^CHa}yR~^-lUpekG96I4R_4K+rQcq0J1Zc|} z>wpx=8Ew#Rjgy<CF=WyL3U)0Bj%>#C(f(@g0+?5OcQ+2|P!j&B89adzE_RdU6Lf*X z_nbp3saH5!;G@N{{h0N<ceIl@jUO(-q!8D7Y;9s{n_~)zv`Cb-kV=UI-AS2Pp=0t> zZ&8`)iPO`69x$l$w3VHSo*>}wgHs-v+tGi#xniv$^w9_S6SlxQ4EH4F%oAhgqH-!l zJ80Ezd?SRGv*9UibYQcJGZuq6Fa&6Sfl9Wd<r(FLraX*sOSSgoTSuQWwJj{fRGP41 zAdSB-Ax~(;#KoL8dHvW(;H<T9>t+Jp7fz73_crV(h#Y-r_+Gj~%4HQX^jAb^#|I3S zs)zC5m#;fAD$~hUey+-lSRVkd&Dbc|2xynny0cHJ!Pf}zaRui8;iybv9UWp(mha0B zhPfeR*IBa0pYB1}Tsx%Lmxcy@a3Maf)AEBdzcr3ZYY;{F_Mh4Gz+l|uw&pvkmyO{~ z@|8akl*<dVBPhWWQQ&#h;L|T&?oIGT{{eFjR3*@<bRw{{4j0z3y_~M-fKakv@-#r$ zM}@(cMi{*J5P>cwz^0mi835NtcejL?(wvAL{n#71H+`I+PkAUaU<NHLmA_{{Mpn_~ zL;v$ir<L+K+0d2il7ehLy86DNelgAH-{Ov?5&??6VcI+Uw#MOYWGjY-P@<wSu(3kb z^+(mCFoEn;HGQxI?-_jjM~1*H?IdC7h!H%M&V?y+L1vDwdm6cv2r#+S!!)CHV*#vF z_7X&Li6AhXCL&DWzx#^P3C>ox)2tB;*=q1QGGb8*jsu{kDFZtc1W~r5XkwbGqH{#3 z2X+I>oWxMDbqYE#%7}jE-CeWW=$1-Pu_=upA(fg@Vfsjj73-XDht}(4f^hMy|8u_X zs8$wSqSXh}Z;EtucQ%AOZ~IZh(U>so8vq3})J6De^U}Yhak<Em(&Iawr~75ubgkbI z|E@}Ux91u_d;Ep?&{*)0<Ky=6_M8HfuH1h@VermF?#!Et`*}cM<Q?e-yPGiBi|D*Q zI_<4?Cn=8TB41Zm_k6B@*+OB^=*DcQbzNxmU<+n=K_?_LW`edp;bU01XdpRP6z!7p zu++ac=(&%#iHL#b1f;!(D=G@QufKS!?_}-C*b_eV{Dky+6~6h2pxZg=ElBL=yyJ$1 z${2D0LD#C35pM8uvydNwMo4zZxdq82Rg(2920%`~Ni?+c1DtA`RUG$%!O>_7V`}ZF zl>#Ae|DdNF5^tPK_Z@u6n3zzTiFyzQf4Cy=(jgoFR-=lhV)Q`(BT1yp-b7;B%yIM_ zlUpYokr|x6Z+Du;+I5U3f`6?S^o0M8rq^CCxt#EdHu&<f=Y5%v0@v3ntQ6_)+Hgv* z=!=&s5D3-thpAi1eJ<MW<@xy5!}(4XjV@m#=cmAOeNjRRj0kSQgr(pCwOclx3=^x= zmv<g3dtnGFg|R5O#p?lu!SRM~h>M2_uaXIloiA(*rozIb(|7Z?ilE(F?ry%LCsc%2 zhRNuM*2}#H%;TbN%?=KQ%9oI`XcdE68dzpMf&wzgfdj-sK;s9YyhWEZM~S;T^otb! zz$^HGO?88sz+k!Jf-UIcS)Bw0Jc$7Mck0%K)UE#dvL}~mlYTPE`eCmh^rmOl5eDH< z+OPc}b3Vgz%Y9m3)J7BL<4RGbW=Px6>pf+!&Z8CoZRP92&k=2edMu9?#leU}VLnze zX*BN=DS()BSM**l#2fJ{&N<&L)kI!7Y~9@%#~|An(Kmj1A^7+{#6B$S+XdWQY<fCk zV<AjG^lS|@4ct<^l?eYVVo<aBdKG-d=UnZU0iE}gl}iMdA70w5cjPU6*2I$$5K6Y< zD+;;l8bqKW%HIV3==K=tMrI{&n$9f0GqKH`;(EszeoA4CvGDJ`BjtUGdWSViZz#g8 zNC1>8>v3b6)@=wZRDfUV=Y<LnJs0CS;N|9xfROX(y4TM;F;5<G$|_3RjMd!(p@u$; zd{jUxH%^blL7Tugf6(%2io?Db&|L)T*1Xj}FwNjF!2cX&hOtR9U<gkw@p}59Z%&Y? zDOeuGnDEG7bkg!;<J@*Pt*`1$ADGh#jSfdkU`7&nv{M;s3LiYa4e5K^aogt`45e;~ z&LrPG$g`^6`5SWZq4y=<()11P48`LTGQi!qQcZh3b~S2|_WlE-Bc|DzCv$IsR#9}v zm>rKDqgA*j1A&E_+yec*&(Q+AI0=M%+M763B7-{?XA(v#pfwd4-56t3Y(U%_dYo`( z7=g?zdgUHCprdh%T1dB!hf0xMi@PRnK>&{0VD(34yv~%-7br*?_!JO(@ROd4gr6a$ zL>|9oD3~iod1C6*cKI~$4ht<;==(Y~r!1bnMGZ3q<{l?P0#j%JiF>^~)m8|z@s}A7 z9+x^1y#4o6*SXM@4FfULc}ax9thW#Ms+qNB%fuwNJq~{-`-Q8m#vm(0TUuT+R%8cF z2Gg(KYaZIBGN_>yETXMM862W0H9eP){>Uh7q1#Fz{@l$A@6hV-!!$Z1($(x!8(m%} zpJ-G^pb%<vNXyO5E3%r4JlC!#EfBekCvRF-idr4sokIzv=v;GvVNl4}%g$gQsk3{- zoc%cXUzd1`Tw0-RD$bv05$(Eq<D8VVY82>XUeQY1{-40cH>e|aM|Z37BG>XYBQEmb zx2N}~-tG;lH`Rl4jY^#Y<M}2`-Uj%94*VTu9sc*5mdoOxZp*-@-(2lUC_O-_n92!` zPK;SEEtTFM<kws|Hbkq?qP4kxS7n92d^PinOuT^Z*L&XhgTUBTq#y_X!@Fo$Hv|PG zCoZm_J#vg!{F0!OltNjgh+E*Y_ptKdyb<#Nkr{Gb<%*m0Pn5v*CE7I*2Y+>u)&g$I zYi~cm&=xQZfB}PSsCs}B5zpCrxBYhbr!5DO+G1|7jl235GN63RN}FJA_TR_82;PC9 z2CR!Im}*p87uAz1`cYT&yPbh@(pI)mgwtfjP9%o`o#cT|jK(%GLp4|?jFV1H;p=t} z7>4rXCLo3>3>{>#dqVoT9-rZ6<HxxJD#y8s@I(5)WPKw9`<pCW2CaSjA9$~e{BSHa zEC|8W<|{q706JXbyQYz;v?H(orI~qIsD5TF8rrX%@h`O&7_;jL2z}?Il>b^t(2II8 zpBZ2J2M-JAeIIv!@APLvM*;>scb-wS6E5DijF1~V3cX_a_FUQmRFTH;|81#k0ymQK zgje{MW(PG!x~GPPKcwS`8Jb?j+vk}2sEb{=pWVK3eB<A#w#jru&?%4&vj`msR2(#7 zjb48GAEWz~T?TY-A5^<fBCEzX&Ssn=APz@{x>@nLRt()i-aZM>J@V@As@3NB>G2=K z6IPwuop_AGf838A&<hv9RPJn7fa{yUp^M+WneHkeAfL4iQF%pMXT1uoP?1$f-09xI z9Nh7E-d)(^x$B@9^@(zhIDRfX+s+l5*#fbE#;zvRHD*Ph-f6yKpZjc{VQA}w6Y(r2 zpqZO8dq5{^D&HcW<$NtRh~=w(>(dsxlj;J*Dn3B@O`7fjzF9O(b0Wu%MU%>7?3x5! z?;DN89ZI*`y=eF7M;TNBUpko8=%Xnu&<#@tsQys9erh!99gD_4=QvQ-F4?wofCA^A z0{NqGsKF`2wc50F{jUUeOaE#HuJ9_YV%l4NdoVkb?lTgYaLC-l%Wx(C1(A8AVx)wB zvBq@p(wm>>sqkj!eqYLaTGJjfS|Cf`F6^AB-&sIgFGLAcvjo!2cx93<z_5njoe!{B zj+QxH5+{gbX|K>s7wrR%jGD&5)NOAyee8~2XBDDSpTB@w`SWu8Pn-sRcJH4Hwc4g_ z#n<}{u>l!Cg=Fi*z|DR!y<@xT?z8q`%y1`-!52O{-B$Q+uH0n*18l7vVcM<3M=P75 zO&U;sy%`?})&BA8=CeCbEMA-q=#@_VAHHX5otuRb29Mo0YaF^nGm-!-xC!Q{)Z1uF zlZcfBDeOU1#WD?0cxBJND85*`VKxoIy;MsNReGY~57!)2aEW8TD9DKUy_}*sUJ}ZX zhX7#^hVkh92ocUu)J!Te+PuRfP&d(JeTA#L$iBR%BlF#WQX9k4|Ig%8bIoV!4=zOX z{YlyT({|oeV3Z8iGaJ^SL21I&xoztDeqB*_pe-UYH=r3`&6pL1JNcdiLI+3VaezmS zOC|r=z|a|6u?f$=%rCOWH6vZZo`U7pxd@Qtu^!Rn08MTkc-;;vaW^ZxGAi7Tk(66` zR#_xZbHXs`4C+(Br-q!FrY&v%Ojd=#(`A#LcU&trzJKid-)6H#fF?l6ZSrxTOM7F@ zDy?nJ1C!&@;&ikkqqie`D$Qx*`cJ|v2rvPx^>Jo`Wo=p!5W0%AD53<F*w#h8j?v=I zDR}Lu=mx8AJyH%K-_Ku<de{_l^KrmL(Is+I$iFi)Z)M~HuB68tb3Sv|e`j#Rth&8k z)R=7RqROQR)xR6U214rP?QXdUx79srD}7o#FH)Y#Y1-WLv^2P&-nAw)kD0ESxEPiR zyJG9pukS}%O4Dp%bJ{1si=f_lnT$-On)kxDIX3v%XBRIJ4Lpq-^J&$TjlaXAWf~k_ zb7AS)X8Rz3E^TBZaQOG#k&VC9xF(&R(OJ%!`GG=%%*GbJ88D!xWe%`HVcboZIY#>F zx#0%Xbm;9Cy>yfDI7~Vb!nRCz$btitCYU=|k6e9NZKiDyb!$2klU6m)IeUkkz8DgX z4*@3YFdK!x6xO>psuB;7U-n`I`7d@Sm~8GEjM!)YDjbxV_9jQZoeHouf1XP-A=ecN zkP02mj$h+g*6DugX$9^sVQDHX63;0;EJFvM@ASJ{JAd3LB6@<Z`^&G{{w+I;*;y@w za;ai5YbXu+nI~Hx%tjgk;hb0=w3s@(tLrHQP=|x@05mfS&V}Q=S7NIYd)DN*T9=?C zx2|3`Ys^x4UnXT3XejnDeQ1E=T3Tm~-ASWlaMWpVyL6lf{t>6ZVYAy2^0w&aGvw62 z%3o~iIa4oWwjBr>_5J7cc$(e5rZ6cRb9Y#y>hjYk%G{bG;8)jo0;fk$1U@~ZJA#y< z!1|3cLOyabEp+$jz3kYbqUu~=w7tsR=;7eb0RAWIkG`5QwHQm)@Zu`E1qa!dnfn$r z03QJ63PZ!TM)JCyyBZ#+H&OW23F>d<xXOSTPXH1J#Qe062nn~Mz@)PJ*wde<1u%RH z35rsCBuQP2XCsm6{thW_>DAF~)whU;yA_NefwAM6Hnq`h=ZBN8-q}Q0qvB{yyg{rF zE$DSX16xK?c;#BIaFT(GO)E7Sj<5G|bvqTTTFt|k+xe9gA2s&6usy4ks7W6F`%WBX zpYG5|ZlfyCwGDSRaIa7dZWTQO*cR#jP^%3v?p~XSO$zn;UaGe|DOg|fi*@Vg2bKF% z7lC+(`cRJqfE74^w<ui%<^5V<k{p1YdkQH!?SR2L8E|=N$pE|}1c^3#MN$8qChLlp zcY5TUH@pP}NFszqct&4ZgPFmJmF1_vqyymZaxnIYCc>27<|_<WYDK2$kQ%PH`3^?@ zn>BVkx<1PppsNZkcHLw9%Ex%}iKEf~GLrLduJ2%O_Xrs`7W>-nHEJX0hof~)FlpuH zOrBhrIQVymUb{2GDh^81c4!B$8N(ygE{&E}>nL|kko8AkzRpCv46d^dnGXX%E{dCg znn-+!=3!JR%uJ)Z8@9Y%y0&a>3U8^~<9l(#3pGE%!4C)4Gl5B{ylPvwp?x+Pe74N6 zDRihRj0eNx0;1;I>T`NxaxMb!#+4aSPIhzdVR^-$!DM+Xa~Xd!Zj^jeOMkDFk2y&l z{&o4j6DyXCo)iVAKvUd2Wn2pYv*@|#``}N26!+9}R|WHy`6ha`rNY!AW#yZ@SzZhI zt(2=desL&4=2b$6oT99SM1)+}S3VXvy5(F<?>`eJ2A)sk&;hhO9h2IOMXBHx(js_b ztc~^#W(}Z|)an=7$g|jrh#x)-;JCi$$50PhRm#1z!HW?i^G>=<nGvK*T7U|9Nbdn3 z9Tpgd8mFZh%lC=~W%k;(sJU4AO=X{M)T#MzozEdY0&+qGdcONwIerQ|By`{B`%Db= zoo(7KI8^26>%UNQ(rncQ=J#VdBi$n_I>Bg2ow;wT4)BOOlqTZIherzWL?}WJU>o>+ z;&lT)*BUA=!H)D}-fPfQHGe<ba2IY|>r*ld^=As(B3OC9cbG_t$Yd)xfK48`cA&8? zUWNShQ@lGS=1*;9w+_yK(H%4CKZ$+pGpHU|^`N6uH<yDOiiyPeeM(rxXEi|HfKdIA zjw`J#q!CSi>r|&d-hg!tVS$|5AZT<RblY4wxA0<Hey(w6VjS|3eKjgGP*m3zIZ9bP zs+(d{t9LDOe8YQ^d9aP3iQ_!6zTDR`ZorWPo&=kGJo-@d*!jDuX)p`j$KWUFv_t<1 zV?jcHKAG+e2R8MVC|I(0rN2)j7hmHgtMg~67A5+NP1Omilm)}<kZ^?rPv>u&%NlCS z^zqrdwO#TuEaD=(!8o(=0IjZ)GXLWicx51phnB|6u~&f@XK=ju90b5$CdraqrsRRr zAFe&5Pfa_wNYtCUDSak88mla_7&&+V`_pQJo!7J{jMjN+fAhXQS^b$mN~f3~9|!A) z-%mpxxc#b@m2l`ynrdv=n2%lQ2bnp%6k^f<G++P?E`SokfP=p6*Zg)WqBH=Y>X!y! zLo3c?c2YWPs%&c3yB7|8O(u_i;M=PEbz29bJOodx2YUy>v)|~!K=)xMc^=Z`*AM=A z-xwEQ$pw+bJU_1c;lWE-U~?x!6{k0R3A`3K^j5>5`J;@E$qRHKd-_3LFTy;Woi)~W z<+Q{121dG9T*SEA!!J|YsQWdF3IpQnV%Ks{-5R|boe)~AOkZWZjqhVTC?Ru@sV3Ke zyNMxXlz`T^A7U@4TsG2f{2R>bEe+>x`VHH_y8h3!fCjAkJr6x;svFXf_@YzzIau+M zty5R>oQX~CO@*+4PFS3~t28akB@I!Po1QgYh>KIHIyzAkF6TG6*rIvItcePZ>+Bv- zxdRF)z2q<J_hM(-gwG*w><uIprg-0z*}ccZy$@Y7JQk^zAbw;&@Mtn_-Ae@?5NC*8 zi@I*%lxb2GtkpHNn7#C2`J3)`?eo<}JD-~#ySc#lhK05QMHD4K0ue!g<rgdY!!c`j zjPR7Z@Z3<o*3vx1oyz~v@w&poq`6~%y+L(0vHFqPfR}?AHW#Aczocf6qwnKVxcgSY zd+OQ^S)V8;yeFLyMN_PR)mGg7c32504^x&hK?C>CJ)-=KS1_1&RZAgZkB03{p}yib zbLE8vy-_y7X10N;5B)E3I<|dX9(?YNN@ZQfaNl<|HIwbVp9%Stz8uOq{+}Cf|8%8M zD%k7y@X$+Y@re8ea^oc<U=gASApZ7mls^Ofo3@y)T?TMrrLhyp1BL*NJ;zur9gxHC zP2fw}A_i$)#<q^R`swe(ZR0H$1n+X`7-b&Z7-DS;-EU7u%u?3!b0`PM7$H|J>eiXD zRQ*zseu`3bgX?Rx>LH;IQhfklNJc-B5c1u>Q<rDho&yx<nfI)h;^nmfLpkRNxhh#J zzc+IIBC>tnD6)T4)5+MvMByQ{N5&~#E!^!!nxZQ7Ubr~4I`gh5<4IwR(wk+y1v=;< zo5qj@%t%r-kf!>;c(tKHK233hEHGnUK~gkmshym>Tu&X=8x~SVk(MW$*2&zVclIFM zwO`&d4`&7W<&P<Jh#|W#&D$!dpb;v`RS1x5%+}e5g?>+;ssXrfQm&|#S1H4&vj@!7 z9t_|s`V|c_2}!1V^ObA`7W3HU8rzsCN3XSB+0G`PNdH@$Ko2=RAs=5oLWRoT8!RfV z%N}U`-Qv~Uk@GlHFH6jqN7k5iNZjh9dy2K4XZY6vu_-=J-(peonKAVBe&8p@Pd=&q zZ8aHsfGk2GX0kAdsPWS9OW_Sm01aCO2kwejiQ)R%)6_}#%CUG0dB}ScC)h0?OU@-e zGYqR-rCiPU<@2up^)rL@!Q5avg~d~AOT)LnMEzlry%pBylXLMWc?8`sVrIVze2RKs zj1-4aBa~!o__o_V%-HMO)SjtzA0xTD8*X>vt1)nX=trIz&!Y^z%+eX96pe^Czp0cD zGu!kH!k0m<3SzYhfxpz2VcaJ_;k^i#@JZ_mP)#uq&%LH-8S}S)tAhESFKHAC&I}-# ziAb471r#ew`Fa7lLSA9h8F}-3%9p6oSVM{Aze4vn*hU`OrN47oXtOKA`gd()__Geq z`(vT`%JFQx=JFP`0o~K)t%|o*PV!WX+wCepuLwUW-jxs<+NoD?0TrfisSI>M{X<)x zgX(~TR3$d`neTUzGL}fDGGVtyDXqo^x%~BDM@y?K&L)NfXpZos8pHI;+Y&)WIg!Co zr9glG2iRYvpBlu=FQzkG%bpt<#IhSZjLu^HjQiY6_)dyl%<wh^fYt7`<v_ONK(<kO zk?o`<6&aYzQ=l%XQFt8pd~(YLEnA+-_lsXio(Qe#O$SK|0*H!c`0;b`tfG8MX@t5i z9iItN^BTbmcv3*PTD|h@%zzBtxCLIfxr#sR7jJmo%JTu^QE20%8|K*z6)NdgJyh>c z7mITHt^D)V55xg)!zA*JNHRCWdFB0{Tp>A|s${qfcrI@I*ndra*46I<LVgkQdLZ45 zWID*0$P|!+CFAq&$}6JDx<%{yMA@Fh7b&A}vG=!q9?m2G70a7qpAR22wy%Ge+mB%; zdM8c<a5`T!Zj1YY+O(-z#d8V&mwP7s*-q5~t{{muJMe0LQH@Uy&H(X8yxx$i7^zM% zmEfk`*oSJ!y)kv@pghB=`mOM$U+yNq=RRM152RV`FcxMhlvR_@(#Qm8Z*VO+Ur76U z=HkZ$B?udsW}ime#2n!L`&(&`c-d6l+`z)$__(ZJezju0(M`o1<}Gcfv9FaUJ%7^@ zB3NiJmb|UYY~+A*WN^*bwOU8_cL94|;^WzvxPG0CW{Tnv>r66!REo|d$NcntBj73* z9tz$M`U-K5e4IxZY`x_`k+N0w*Wgr_L-Oi+R3k_n%-YY(&`G0gz+5yDw`8$Qq@*ld zF&XzVctqI)5hH@R@dTU{b|i(VZCsn%CG%~=xBaX*<f4XUQZ?VSjN<gdXO-9%@t-9# z^K{nTF3Q6~{ZfRplWEuS37nKW%<T8_bN|Y=J{CLSQgmlqVn@nNSJi1Y>S&eYxfUN^ zuUAcE9QVxkb4jNhs)h;^2vv*}=RjgYQk)5&yy{d~_|N4~IU~z-{pq;S{sv>{UTzg* zQoMZZXVd;SvyE-gQ!hUCWg~s|k3!H~<d=T4$KPH3Udf}y;M8|e*3VdT$MN&X8+gVg z14;s6nGES(uPDx@ta>!tdwcrWL<YJ2CPIt+4#77?;f9m1lr~e$svXx14BQ(L_F<cx z(b3L^-_`iv%fpV2^1he<_cRVdpmA{r_Pd|9jIIigQhVr%?s0(y6%ykvYj+>9TixZI zWbEGHA?(h%$SHedmj3e6$H|=Z*hObeB{Nt%FV_HU?>7ET-Yt~{;pZk^Ulro{d$i~7 zQlW+|&>IUjwnP`Gd4i)V<r$S<iLWktO!-0zi~Jf0=FUysuqxV>Y7=sB4X8^wRE54P zRt--*RMnDKVopBVrluRF9=u=AH86H|0562d2Fxd8mr)6R0&-e<P)%j$tHM{Y`@377 zkNK|`QDIs`tf|svMYi49E6ii(tHWjjG9{Z#-xY0ZjUh*oG|!Cwr$*WHSK+Cm7zQtP zO(&Rtg&?ph!onCAq@QtPqw&!(v}hk$8#Bo@JVxLr=;f1F03{O;W*DAm>hgQ|C*P&Y zJB5d{k+JHv-fus^D{bBuoE~?eAeXa*iK2Zw*GlMgNx7u*{pd6is3PvJa-$on9)lnc z&$-eJQVc1DF{xEQGxc|CS$h*a%c={_9@NcP)@&`Rcj;;hCva3=y7h7w4EP4sNR+l- zXaEri?mhm=G-)`S!ngp8vQNJ^zMwF7?C2w-i8vVXv*8aN#F&mu)S`3jt8$Z$b%O>1 zP|kLONE-6&FJ@$sFV`s?h|#|rz?nt;vH5iNdR|eK;k7a-)+P+A%To^SaJc6pa<0Oy z)uLVPLJskecWJ6D`el8}+xTgf;C?;5Dq^tL70cVc4M}(*9l1tROSk@Bn@_+|3xoWO z-5W(g=Ax@@<h6(+dc>o<<qT{m8`b$W<KAa`SXuC9>?{;}Pr;D7y*F;r`S~YBLUr$> z{pJZs^;~q<sprQ2r~l<r>(%*pOBsgo;*4{nAKTm`WS=!y;-F<`D}=5d{=&1Heitpc zdu^dg&RvLTtdh3~Q>IiooAO-L8HGOvttW`pk=e=z$e<r-uQrtO61MKKIRhWpufhpa zNvy&vlT|r9DQH=OVBtj&WG`3k%W=YX<4Kr@aZ8bPN5Hnrpy+zhFY2QylSiIYRt5`W z0wVN+_DgK@pr!HGZla%?c=<5$rOe-fI`da>3Lfr2%luT_f$%AftS}bEZj=oJ7C&r+ zn3(d3v2rDe0stwH82FXn>vrED=VYl)QJ4m{njd>?UrWv8E7kWNw84yxbWz%ffJ>f2 zQx(SZtJf&*Sl8Zdn!Tc!`71w|s_|@a(!p^#<VKkDYrh@DOo+-C^^PdI+OPyIgrr<7 z(vQcUuMrvGeydn3G!N-^dJ_2BYU<7~qa#gPQ=GVca_i@;Cc(_?@R>#@dyZoG&(YH! z2@Ch`H8znQez8wh{w-yUR1FxVbG9LE=E#vO#|uwN%k(odGTy8FbGI3#e0l!*7&Cjp za%+;~=30;HwS&^c##;R}Z(i#bHjuPm`5RZ&2!b`Ka-Nbo7KbRkbntxWf5%4qlyc7~ zV>Kw<FS+T3-y0!dV3iuDUnRQVr_FLv=}=6?*O#;px<7a8oi(#v5$Zd-CC7YQyPMvs zPkCoZUOthcW&C#wgf``Q`0N8{yIXJtTR7_FnCUmT;V~uL?)2=z(I?5stjMRX5-ugG zmrN<9M2Tf$xw3<*K&JRx5e+q2I^XV$cH96+xa;1x-I(-p@)xdt`m&x?1<1He#zN{F zKVZ7dyBtzw_4;udUN}#ek-iQsV&7Y8wX)>=rh`0LO&*?8Z~W3R`q>TT-Cin9(i613 z6;JttI{veEHu^6OEo%L_qHzxb<w|&PIikaS<E+FFN>J2BNS5fn)r#naWS{$W{1VEJ zMmTAj#>yiRLJOlY022|UsLjF9&Zizm-#r3b^g3(3A6}11i4v;<yTYOI43SX8qscrK z#taP76rqNm06-@}w4h%Jf6z8f^QnK~_J*VtsZw4AovtQaUfj-eELYUFh<7W{Mb!A~ z+xnBr#O5!M6)<rw-QhU$@46lGK1eUl02<(v4H&NL8D#!(<%{KIz7%KlOmZtJmS1Uq z#3DFPtiQcBvD2;E(1y7k2@zAMhAD%7&vhdWUK)_OK^;*F9g+Kbl2WH`-pzMzx|<z| zmc6^CxxJX~e^V*{%<auD-=#J~;-TD6hAe>Ob=GLKr~Ty^Ob2HLzfVd<DzoU83WC$L zLq@iuFquDaAS~jOHHdXa&J-#E(ww6r><-BX4J)G!gdp6&ewZ97o@=w-XBm)fao2Wo z^WW}gJP0C;1nz*kMS?=>KyCQ$BcIY{Xui_W5?(fsJV|8VshZ#5vc*M<UYR2Z(i)*w z4^yS+c96Axw&I8`aH;2?$)muaE~uXfHG3S_HVC*Gg16Is{z3HkWm*>^{U(f>)nY|S znRx$Qo|AOFEVCpI$@9n_lwQD5mk;_8dLI*3ce|)h?Tn)9CfN8y<%9-^POYm5UhK?- za7$^n80{DIFi=N?50Hls`6{O$N>y+o&i2b7=!+64tfwHdW185B3RdJGXdx~cNI+<A ztmA`)kx{f352(!~8}^kssjg^XyU+8C3QH^<OvwPJ;MV*`nr@^`ra_1g3~;Ma><B*o zDGjl=0(wW+-DDqW%H!4^{k=ZsHKlZK{o4xK=bZn|k>5?%J|oYq)c_+dI+Mpo-_X~S zpl0p9A5QeHIIHby(=B6vHS~!z>Up%048taqfE*npw+Q;s*R{FpWrv9XmIIMoHYd*x zVwWfwoT81qvJ+kV8xoKSa3hJ@@83|^ME@(^-VfOf74ZVC=gm~pVY{ecnp^Pmv^jv* z^O1Iy=wEPO_Ri+XDZGx~!^m<%VUTW<C*Mt9yUgaiZbQ}W+q&ZPH5KRhVWV+*(J1zF z%5{_=bNE>Dgb$<RhyLU^yz+Q!t$ItSPyFz`b9MCx13L674&c8$EnodP@q)IdFu0MD z4k~at`LbBn#^n(If^hliwae0x-;%ShGp`6f509B&+WwT-Nq-8rTLggh-A?LP0hf2! zxuZ1rysk(gnMNX$AR_oQUyUm~xWRrjt<MImg^!ccvhq@6cgT*QYRzHNbfWfNklC%h z$DDk-vC&t?HJhR>6NGb_)&^&)K1PkdBj0(NoMo*{-gI^~r_QKOv_m-pJC%~gl&5Gu zz0;tQ{}%WJkepN5M%&BFbLgetbz3SF53SrLoOrwadTMg|j>3@J-|BS+2CbrFVYg>z z<sYP({7xgW-0~ktqH1~ZtT>C_Oxl{B=oB(O&vNzjRt6imssM)(d;&U(q1~lF(ss(w zHGtZ|%XXTBF`kyA8$E52ADabf20ayf|9;i6jEf*e7!=WL*7;6+0oosbL_weF+aA!d zc&OF#-Vx*g7{GGEv~q`VS$gN5<v80mOd>WG)8t<SakAhsWxjnZ(VhSSg>C*U=5CBf z)`BZ3B)G^u5K&e$^^T++_vn5s<I=6#D<mu$_Diu%`!a;fz#AY>qb*X~62?jDEzfD1 zTo$h|El>H+*cNsNYJ<X{NNpaFbpQYyii3bkeKrRsH{B%EqEam%<aaFIXsVNAIOvZq z%ka1H3#ZKi>LlsoESA?4Ps)m~i?T?Nw=%nhy_zjxnV6q%75PRz`!Z-eO@r@BVVrfb zi?TRdg>+w7E(^O&!Q<MT{hwDWd6Qhs5#a&rkG#f@G<}-6kbD?Sx;tVu^Z0>QXiVA8 z4V-gl%)_>PKyfSP3{F&KPcF6D6jmumo`Di79+)A4KBGE)P0Djx0I13niJ7pee`yqh zsm#VXYA(DVqFrXJ`IFUwh=I`k3_uEem84!c=k>X4-nQH#Q4ikev-38C*YviioQ06~ z{s;xOMa8kxOcPl@`yU;{xP@Ix6+~ThPzM_{J$C6xespFK69x{kotYh_I!|}BD|vx3 z`hA3};Ws)do1R6+qWQYknCDtnM)MaH6MM#y&Bwxycuv<#gMqfMufBl-a{#DT!^Vq% zd80o*_Tb}TP8T$TmIeTl*~WES-Dm<53K7$kxMH5JE#zU}A)}kdL#$;iG72?a%j>&0 zVE!iK8jS^Rw*AloFMG8ORpriWiN&n=AJA%Sm37sq!RVk+ud9!OyAM=bJ5&g14q<W* zD~tGhmk5FGzM1<=`-vmK%+TaoQH0}reB6hj6Q2$B{*(umR51$d5XUo8QJmgj3$(i7 zXBWPj7l~>$I(<&pb<w4pbl3q_IOi%dvCU|c`Sd95aLCQpAZ>$M<59RaR~p4jnUm>x zz2)yxvoJP`q-#%)z7{#zn;b|gvl`9+yJ}eVW4jqWFMq?E29l?ijS<vBcq-81#g0#M zmRYvxr1|)4<I05Ib$0P?x;-TGgSQH>ut7+*4a*{e3_M<L{Gg+6W<<+(wYnehO0^jD zu2G)ssBl-M1XWB6d4A3O(?NpLe&zFYXfz_o<lDmNmUaK~b5J*MW_T4hz%4Jh0iEkU zu5oih@v(_HotLu_Ih|@N2G}0v%?A~^k@I)<o5}#PQJ$ds<F2@o)k&J<5cwy<+YRd0 z<)he^zE^$l_z&f!R0Q@CWXH9w^1Cx`bU&$c;e;z6W2NbIhi3fxq5`P5ngBEin*TiR z3G5S7FBl_Kn;*Dl&OlT&S0T45!|p0M{dml(%CeaN2-UXT&w66Pv{O^z2io>2`u_9e zzF5XO!(^T1Pfl386S%EMb!S-Z-a*;=Bfm+B-Lqcz0kQ=*xDANUcQ)%5@QE2OhM?be z;;EvYR}}zRNjl{}UXn^lozcf1r&Z)7H{BHBKY(~~j?!{fs$z)Ij(B^z{6C`MTx^UC zML2gV7NdggY^Xgrs1x3rM&Rpyh*(QhSkg51URZ|5bUW+$>shvKM^^zUe6~XTOYo2% zi2k9HemW&{Bt-^t1QE7-+{ydUgLqipkyo|RajqZ*a`Y#U&6~wK>BQ*yGw@YMUqpbv zln=o$%5C4bIRzkUi&dfIt>rtw6F3;<o0j|`5bl#SUUIx$M(a@vML1}qCQTu_fL-e< zbXZt2FsZzVH3<tl_M2mk=cx(991*SCp=8HEi*0+RT>Og(rD24%dSpldnC-&8`b9-O zdS~%obOwpSR(1*dgsP$`X0o|ITmlqWdh%*VdRt_&b{;hM<%PjL6B(EfHlRbYePkhq zy<|xVOo(Ac7KHJ?RUgu)ro;O=ueKW=jNiV$1-JDR&O#XG6b1I@YwQ1$?EhMMIB~1? zAy9I`CcT3)^qt~tyAL;eJYX^$vE&PdBm?XSIcu;n01Oy)MTDj9v{Y;P?k2Nj0>_wc zP{mnd3_mMJs$R`#6rudZXc7yHfSqQ~@tSz2Ude2^+5!()Jf#%I!>@;-<MHSrF`CO( zsG_B0`>SWV%4ew^F{gXye<waU6a`(<=XCH^TchtgC;VdY>4%O2AgQIA4^5CI$7EvC zGnMj9+BbngrE~;6YdVlVOaY%RXCH(>&3A%-oPcGh)&OgtDgt0p_wDly)>!m`^PrR{ zKiU37XD)n;3;1gKMDU{auElK;@lqUQ=DS40|NLa_bV6Z}T-eff0XuY;tKFWfp*d#g z0yC6&5-A>uj-2LY97gR8KLD_I+DbW)uAn-A>g(SHATe1~z4lf#w?zSJ2cFrRB1h#d zCCeS6!Bw1iitX`@Fi-qzQFtrrzy;#IM6*m6-SYLo1ZPCxh)N`s5eTpu7I{Yj5h;LT zefFD4P>l8EdB>026Q$GePut<wWC3D$a$}UA{>nZp6fm<BGzvey`F6pWEU;-+X$K83 zCr5M~IuYI)QN|=+M*y$#)55sc4@z_3Q@A(xbL@xIG~aM66A1=%g=lf)`&Xtgx-Q!W z{7<-ZKFz+IE$0KmdO(8@hj~d@^~DafxJC9cEu{~FIS?R}-I<c}6YPrj>Zytc*PNl| z-g&P@DpR7>AA8Kr4J!4@|6-4pMi6!kA2JOy{mMVIhqvv`!=o}&f#-C$6Xuc&t!;tD zv%DGQRDUBoJVj;+qDc#fn*&4NDs0y;D8P8eF<PMHYPQ94zQ;;L-$O&Fx$-iBy!BID zmgQME#&xG^v03@axBp->d=xT$WFCu<;#ZL}<{Lj!xAY`C+51Pg#Y6ug$sO0vK<R@` zBss1`?lOp8$8WAR<5}RMMbUBx7vVjNsQiD*5L3JE;qYm?_P=5<Yh~3rQ3=dQWuLAD z*-z|TOT&m*%pa!o{}$o!*442wxr+*FLJPj*aAR)Z1R>kYecxY+qD2BrH;NS&=4UPP z`{D$49tC|f!U!@tdx84py=oh+z#VNIPu=2|4-U!F31?Y{TLC`8^1?fR-5>hwvn4wx z+fnsgS#>kH<8KbUx50?ledJrk$R1IH`D#OPu+%{$=QxSD$`z#s9XzXFT@VeP9==?; z3BO!yP{9HXJ{_7H&T~!GX$}G@GdaJQ;9gMq-7`c_&@s>O#4T$zC!fJ&t!sPVW{;K9 zU}52REr67;BuQ`hce71MW#2+8ki;&0bmZ9asgU3?!}J;x8}$A?{j#2i>+=c{^3wPF zMG-_2xk$5(x}WS`6Y&m7C5a`vCE!7?c)5sxD7?AekO+No5nc317{rfqn3VnE0+tfA zzLY!R6LwWRIK1X&@WY%R8x20xiZSyoMl7@07p-iq@tf(kEw7XNmn#8r^4U%@)V!7h z1BOw+-U#s8x(s0G2i&>X-hb40eNmqtgQ2K|o5z3yUCNv13jemlx2#oCe<jP154m*Z zNOs`d@#!u3hg=f&^Xg26@$zw#>CQu)9Lj~Hqb^r#qr)y)e(Fcng3vP(eU8nMRx<i0 z8ri|V_`LSC)iSD`3v1xDs79B4iv^D!+X;N@OeS=He@8$bF28LJp0^Eb3IcO{GpBUj zUzQnCvTU!sJpqLv`d1^MydLAtptTRIcWoaz&E{b^%b*QFaBUrq^=>+S93B>4hXBkU z>;uGEo2j5|WSXbG$<{8q2bRN}syp`_x9n>D`e9Lv9iss)fisGMd<MLKV+QGPBT1%p zopeE`zw;e)3#lqvnt?q05PeVrYv&R_d?T*DtEx_rZ(1a3WR@ZI@s(^j%@t(B<PD%f zgs1<Lyw?Q`G5GqOw-twzn==@k-HtcMokm#uw>9D+Jv2IJQEKQ5$Ixh7U1TY4KecMC z>wap1rd@!n8RX^4C31Gsxyf)PF3nR7Cx^JbVE{H!9#U4T>gsC(T~f8yz=br}Vh^iz z<exjaAbY{zl!J<lDm5*Kpf7S!o^=GV-mb}g=fwr*)$^j?KWb51I<Gg0=xV|Ix1@W; zclf_y)SQpZNW6TN1hu2?V$d||DjRxcvO#VisJIFLi9YfsI4^51S_`>t?|Kir@yqsq zYsOihJDxT)HZ?j{1ss!G7|V<!OJYDKk)oPyLzu+J-Rg&uu&>PqDi#W)eDRU_6369U zgzs4Y?ZlqC<VzEh%L^x*(nlRX#oajDyhlxPD+HXiAu%m;fAW#lWaJ1NIkk^ni7DB0 ziKpIxItQS%0o1!zR6bI#%FJ8b*7sEYZmKQb{my~vNfc9ziVFSbS>M(0ET`)BBaq_r z8uVSOq36S^*nfUCoB9^h9Wvk9fl}V7&*#?3Ih@~4&@TodmwgRbIg7y5s`&eD+|V(z zmo=YX08LO***|4qGcd>nkU&V`bKeIj)k-<KdCR8BlrjJAO2_rsYu=L&o{ZG(MxSiC zIxVx5=2fsA*5CZp0Q7x{)yG%~&Csnaus#4)M!qoImuo&SVV_h|GKt>Lh0XMtaiV6| z_0S6lgE;^hEOWO?GW*;}E(JiG>Ye4?KEOlg1yQ7OR&Z1Uw~|aSS-MGdB}GzelK-eQ zQV$8=8_tgAccy?5mf92-KRuwAAs1m{10q)d6KrLU@xYxDnOW4LS2TFza3P{<62VjL z^q77TZelGoNe^{Rxs&5ozulZ}%Hy8QGq)=+M{~u<;zg{(AC-Nl&1xc|;q-+~Vnjnc zs%n}T?;0hoT+d01R}wXrtxyaY+$*>^yI*;2{Q^Sj^`29|nK+`0f+d*m-i62PsENUZ zP+AGMv47R=s59j|OPU)u;AG>#meOm%?&J;@NdBYDj1Bp{3mnU!)W`vF5_+Ahh>KjL z{8qdiG9ZJ2Ds>Ea(?N}aM4aZW=hGpz0m{<`WR1%)Q**W(WbdD%nL-n-taJ8LtNOwh zWosk`Mke?*RChUGVAz7J<q~c0mYfSm(Jmw7%$^t1o;*Df#k#9`mMs@}sLMv{=8;3u zJ;^0+W9L5JW{BntE~qY>Cj?%SodiJl{cP(tPvvTt$!B~zqRy{Dz5wvCF>d*nou?wl z28>sf93Q^AMFq|H@}r5MT-~Ll^{I#KD*C@a#~8&XwiPmmlea5Q=M<S}y;j8uMOc|D z=uU3#`YQ6q2K-p46I<cg<_Pp58Z@4NDx#yL#e|wEL2rHf%$)zOcLu#{Ql^dePkhBH zd+H+R1MjED+aGy^9qHKC>mwKRwpFv5IOzM*aO1Ql{u=*ft!|cjv76@MOHg{Pp$Pi> zNvur2%>)IUUsM4k^Y1PnpInteD+02~O%{e=m9w9@s41f6L_ovqzm`6_stBv5|17@N z`L4RzFQk>Flm6|#2WPA_)}G8*#Ohr}mT(8pE_Lqx;P3qvlVN&#&(y^twwxmue$}TW zULI&YDPP8x8DV4kP4ExbJ)n8wck{D%cjS6ooHSzx{ICdL`Lpz*Aie&;9osUz^#|w| zXlo`SA*@0<OLi)P*P%R-8B*c}HD7A~=Um$H+^_wainmUIV*^vS{>=tC;G+`d#?YW` zM?jr@`T4sIlg#S3Y{XS{&&5_E1zcn!TP9b8DyNsrU_SrYhrwQv>etcwG#MMk1ZbG_ ze4@DkIO6~z1x}Lsy-_NM8Qo^&ey>`G(D0PWMcpidDZa1vlb<V4WI)LFUzyU%0W__{ z%cRKC5+Vviv}$0JfKyhhcG0r5O8X?_*b%3eoMB6;K8=Is3h5-^_zEdHbuqh;<mX6Y zK_%CZ{aycUtrIf$KByz+2_!Hb;K2Y4;MqWncj^bVy+P)bRjfasnXeogZienRfHz0S zl-J)Ww}xja7CHG)`|bY$qP-tpxJN&0bDL=Ia@(_$X{25`gGBk&y617uXjA>Pxo1kE zRcDx@@EZ9Nhp!*^=ix4R)Q>SYE3)q=Wy9?@IP8A1_JxmG2gwL=!J+y|OYDO$t=&Vp zTK|+-2`#kVx!`ex?6N5lnQvRR+7WnR@x@rS1=4~)ZJR1@F^r7R2YLZX<{)7EUaSjH z<xzYA6^Y!4?B$7x^6n7sjXtO(Rq^APm@ob00?=-tw2ss|-S){vBdIo_*$%x<r9xFd zP~<KVVp}pv8~;v6XP_-JLBLeX_U*Tvrcy0#%VWp3N{NoCmg--%kXutf!XzNm1;WW^ z?anlHEV4+<A$^yB)NFGm|JXBux78;c_jBztCNAJxLzIt~c)POJidFc`rVw%b0A4h9 zH1{g)L_}<D?tH`<5-ae2w9ZdtW`<`O6k{wEwi^m9#Xu>H24vdD(hTL?L2jJ}bAm)g zCsq&W$g~TcfQGjIbkNwoAD$DOJ<dbOv|u;10BRnt2d;gc6SqvFmH?oe(r{VcW>Er5 z{pMbkcBzpfG~fg64H>$X?6Iuu{IO2)Z9o(;E*7k!Jlm4jrAychD+Wgw@HfAe=LxVB z?#{l3v%P)Db}XB3AN$(HtYEignP3;}e<Ux@FfF{_(U33GWw(hPD(X!lgm!kdli^i& zCG?sN;Fy!-pNcn+b}R+Ww`-;Ev}T3XTfJ-Zs6Q~P0w7SUonpPT{nHc$xdF&vs^9Bz zQnURiau}uy?rl1Dqx08CjjM;!7ZAvNHlJ@3ug>lBoZpAwhf7}xtv9={+}5vN8G9~Y zfRprrX~{InPNwU<MUztEq1eW+1-&s$&D>I~fq%l4x=l*UrFZSKbl-^cv|5MYhQSw^ zzORn&j?8z9?tx!BxaE^L&(X5;wci&%;!p20UhCLd$}G~aT+A$Ww6434s_xZ4Z&olX z=0b!`Ij10`RIxd-I<$tZU{QQgOI22!)>)+hfh+GP!GH!2ku+ZhlYhS9Z-e?%jUTkO zAI~<di&7!db`pv3+=PUL0OCXZ&JE9H_BvsKv6ss77*1S&<G-m*KA`^471G~czh>L- z=L;7hK#kVuUU$_S{Mx(WHKl`^lrZ53jJ9LeXrO!4POF+2De`fYt8sh;BPu+t+zBuZ z`NPIuLJFv7Hl$ivl4m-X9<BW=kRG~yOOC`O18+H7>a#;sCUn_>C+wjom*$UiP(bj$ z)VYO`|1oqHY)v*`6n+<s(IchV=xz{^*hY6qm$aaOl!%I-D`0e&fOL0=fS@C#L|Q;m zN~J+8%zgZe=Q__h_x-qvG~k%5lx(Q@HM<6=)}x-9@?pMvXE1t}%7>xIpkM8jV2pKk z1vF3hEr<ZoS_g$ojRAD!oGHVl(jrr1R}!sBgXmP`w}z|U9+JASFs2CTN)Z!Hb%y40 zS&aEl#)c5#hj9YiVsW)FUJj+iyeU@8h_}m_W+TMP`jJmDTAvXyn~;%SgRDHy{v5*S zO1vfv^YUpprmYQcrX<TgP7*QeHYrhZhUy}=Dz3>6(mJkz9H^|ONR`Y6$mc}IfrUYZ zo2n*)Z*k5E#0v?`;K?Vf!=TNX_%5u8Y4*98Jp_;IIXAX3*6!<*E*l#$g{$8+_&@@> z-(y^i5ps&krck;e?##^=Z}36BZV%N)g~?l!fY=O#j*~<tC`l@TEcc}G^Umw=b}P&v zJ08G@X((v}<nv0MWUQF{Mvd-<c#6d?S;A70*0ztcd1Tz;O0{ujXw+1ph4ZE`<9;UL zEh~UXs$K~7ww?v8r+Lt?VZdK!noP3GxegsVyk}-vLF<_k;e`OxDUJrY4*a?lXzHGH z@yfpnCRiv%TE#ebMvz3Zt$V!%l(x_b_$ys44EQs)-l7^Xo&LBt2>JA@nC>Y8u<WO^ zypFZLf)Zx0TZV`-4yab2LzK;9t~eHK3TF3x)~?+l(CU}bWq<&V8wMjGxbLid!NP1( z%g~vbQ^!#3Y)Yt>*>~z_;qZz0lCVnIIP$AV^)5CSsa4SEpL^$7HHS*MZ6=%bRSgt9 zYo!xyTV8x>r!LTlB++i*Fro-i0_BEWOH~`>xQ%iz5}AV-GfsMwlYy9Rm+A>3JQJnG z4cp;6l=z8^2?YyZIk&I#%$7wm%)NLBwIh>iM+KXuc=biSS--I!>weg7+wcF}AgvV3 zZmd{j95bw5xK6`osFbLdJMx^S4k}f@AkeXFSYmjk<J&~LMTodYsWoIX^0uwllv}hU z%=w6s6*`n`UK@MH_PK2e2BfGrAg_0@f=g|D>~v2A0H<A7Btn#NdE^Ce;J{|%De6T* zE7I5)oWXa8n%-h#8D~H77CC!y_n)VQN;Cz6WdW~zUfhmUsk_eO-3I>ypY{G?!+YRz z3RjE2XDMN#!Y?%I&xWiK?Ml#Bn<!26(H~^H^K4ceJwqE=t|l5$W#PH_M)1Gt;S%bB z$Nbc$XWd_n#DW}LNPJ(cBvLB9I4K-2+b@%Fw+Z>M`6_$(rF>y61HJE>uC*XV;;ZUz zg;&A@)a6@wdAz=$`%lepT)7{?A1uS9vndMlVFCvJasy@dZkT}G?pm!_WWV@W22;5& z5%K!|@x5>q%W2%SNe@!z&e;&trd=!z_Fz_@6UCd6C}(|O_eCli!+68#ONjZ~J+UVS zSo=hADydX!F$pS~3W6K)Z>bSrq0Z79398E!j&ww%Gnk=1#O1gUeEYW-!(6|9WwXwe z5fO`F=8f1V6Uc{{e82bBVM%<IH@^5(lA?aPa&n2&Y13d68aAB?$Y!Kmi4^8Pc~H;S zU_i9<(sW81S1Y*+!WFsuN(J2X7J|+dT$Q^Cf#6)fFPJ=MjLJ^D8|UTnchAgE8pGVh zLv$*zuabce!6y6+tT(vvWO4J{+)hI0a7uUyJAVJsgDU}Gb~JO^?o*$9?t!F^WTcjw zaGz;3)V39WS)*aJL!fnnoOz;~)yg`#^$2;FPT93Jj;=(9O`t{Qx$|sh<4~hiMj2Jn zvp?mYc8y43HbO0Wwm(gi?BpZ%d;kVGJ>Fu#@)wl)A*6_*IxHsuLXmX{#X3A&LR`l) zuSgNO3yC;Q;tBXaFT{zA`nNXn{AD;*k=x{V#q4KBAx*OOU<H;tRvRE0!%6vLTAJ4{ zADRgNg<MSg`J_4;Y7-4%LojCtki1I?P8zV#A@mDKwoxtq3}}#Ctr@?p`p5MlVZN&| zGoereUMx8vfEAaUCA&H|SBAEGf^kbSNy5vBy0OR6ZFR|>dC8?*fF$l*)6K(<b=OL2 zb9$_DlJV?Po)bI&lU*bcjh_)_V=2fpY1bYct4dy%^$1k{!BZ{4r%O#T#wc8Z`$wqj z><!ag&U#3W)3%1#=hK;Y>au9Tt5zNv;z+mcgsY=djH97e0R;M1h?Qr84+3I})(1b$ zFhhX#mr1zn;?OVECdnf0ls?V&3UhPW5iriMqMf}+*~O-w5Y3oW(OZ=-WcO8Sxo{vk zpT61&|Ms*r7lM=)MixK-hF=5jMJAm9Hj2*BOBNobWSAt`Yb8_0IPi>!8+|Q99x<l7 zVP0PWA0om<W0m3lmj?vdN@`qW3EWWoQj(l!oIyZ-V7Uk?d@R}eA!gzEo$M6D6VfFz zPEC?VUjwFI8|#B(|E^&idRI$~Emj^4vVm(nEfjd($x7|m7Ca7n_&eV?p^{F=luqX? zdHiAH3@ClFyi>tW`{i}SFTA$9H+|L=dG|7$eO;R{R@npS5S(z}P@RWv7VQB@Z#0m! zT$v1@(lT|T2NKzRMhH#@zvyy@D1)$F!cQJZ{gsjz%SEo^nx7I?3F#BpzM$&Im1%F} z8{|V(cP184(3cfyC(0@*2~Sn#1+9!p?ABm2oS6}K?3t5sdp8NajMI;%=xpaw%oASv z(5vuZ_`=i$+8-u&Cy%4GCsEQrl}t<OOGI1=V#Z~6HxQ0f<e60l_BQxBF@wR|f>AE% zo>P(vH?H8uGlHZcfW)&TJ|onEM1H2TnQBsNxF_gm^GfcfryqbfWSfZrC8k;JpE5hg zq~Wcu+~hFD>i}uVtMx#OT~#V4JNjvd6Uht*<xm7UL>KrNGpUMPlw~r{M#gfJ!M1=^ zhtt?9CV|=ah3Kl*u=&)8?bOI0O}cxW4D+*mY?a^@{xni%H9VI`bON^6l)NL!(JeYV z1&`pt9fiijCaet}lli{j@+0eJp*Uw5`0WfGKXaS&brjnbP1da|bP0skG8>}gG^lJU znR_Vsz$PU?yzQxJpa|(}%#e{Jbb+<@R-gS7J_R831tliswIq$yGG4%%CWz42c|zhq z5G+ro`4R*^&)I+Gom7q;%kEC223&9bvy&Xhr~UP*V#4JvJ~1+xAe2;FEAdlmTq-wR zgrT7ppKYc@JfVN&o9H<{V$lDZ5E}mg83$SC6UeqB;+}D;z-`QOMcXb2OM*Q*5aM`k zN%CxZQ2GX=BUmZ1YFN>^C)sZhqWF3A6BLJ@p$n9OVi8XRTC2@H74zUKC%w<b?8^tH zo*ULejR3qCXKcP$k|8pd2LPeXl70>AD)#GDwdqaEBqeGwlt>CSel7wM+P~i^X`a=n z&~kh!noQ)rw0}-s2*zhu)^Xr35j@4ZTk#Jhbz(*wZE-Id<j78i3q*7gSGrguLOID= zGggg@My|ak3$e~IO)X=4O_UV>Y$jy)VK#UX9$WS>ARKDHOt3>kf4R;d%xUE|r42oF z$ftQl<x}WZB{HuQjJe5W+GN9Ss7(N#{cI&<qo$}z#7rwIvNH{DN(cX~`6yIF7pqGo zb85QFr*=+xf=xut=mKIy*;L4HN!S#GD@6+4ea=K3i*GS@-S<OIaswh-SR9knZG7IV z&cwA$th*2WvtUu#%2~Nae%?X0K>_;U;bnO#?X+O}AFi_g(O}atXxxB&QvTXe9gD$y z{i#bzmJ>-IXJ%g;%W(oo;h;99Oee`{rifVGb%5_|PG@S4x+USiSdUy)zcp+%(LYh& z*M6-7PW8VxL2i(}(qs;9GyIv+yD0`o?5hH3@b=<rq3tXoU5q~{@zY~#f}|90n@7x{ z0iaR%%vp?ko-D4fltQU{*G?X6#kPKaQ+t`bbvpQMoIL&~frC+?<%+HY6VycvZf{MJ zAjdf{4dnETD0k@1zZ5*eyz*&<YC7TBod}w>&;>abam`1T-B29_0f8i1O0ESMB<wrC zYWK7~E?QGoB9FGim25O-@8!H~<sH^0o8AygD&5FF>2{x7y@P`DpLp$xBynANc>zTR z?=T_ty+z+~MIu2AE`Y>;9)uGmACeC7%-q4>z|}=lN6e(O++`B<eA|>x4=gZA=A`;* z)(V!($KJ3f20-^^q57?KSmesD-&aM8ji-E`Rx6ThJRzpsG<rCw<rz^dAJ2J$7e^8= z?L56y3zk?H8eJxZR0yP$X<Z)8I1Hjcm}qAgXZZ9dK`GlDq@7r~$*F*tHuzN~4KL&_ z?&q-WJy#vs3;JK<Suj?E3z~hf*K>7sSg>c0hp+Q7K1|9yCx=OsIdK=9WZ|cWa!eZw z11EOFt%R$l21y9N>d@N2kG`{k<|F-d+UqoE1jIwq`JjHypkX_id)-}Ic1q96K7e#| z2Wp9?Qve8JXb`_Kh#d(Q$|t@L+XjE+dU-2<HsE=Xz24`~`Xo(^mA^Fg!ZbNS2QD`} zMZTr|ezT6S?v<pGxvN*y&)t;l$+{zl<Fek(8Fh@DiFX@=Uky=m7A1@K?fxy$;nUD8 z?Ig##qxhP=>_o3`j__AJx+3>;KRG}=cHZ~%E;0Q+N%)t4Y}Z7)@jR>e>XZn{rj+nN z6ngxb$*P-V)XieN47I^Q#ns%I-`Wq;3vY-s&^}#z6U-T(H8IxNm|{)`8BmpUuB0_d z9-2{YbnhMJBCK|hy&W#io(i?bx{5?H2=xU~|0O<-Cgm?+78`e;&Gh&5*ZBq}#s>E` z{LP^?8Sxah4=_}h3zJ{9<Ss_OSZbpy_G}z_8*<*Bi})^x-7%t?o?TZ4wJ0XJ^Y1=- zQn*h<gjLt-2EQAwE>%oQS1m<fPpNeZvq;?B&Py_E=Myw#Fag6B(~Iv~v$8g^R!Jea zi?TIvdVh~|npwx!dx*8TCt_s87{e=7xJ$jxf_#z$s`-lSUN)r{A6TnoIWTuaBd)@f zAW1S`CTgRhu^H2i?GBx2_Q{uhKfBX>&_^xe9ee6YT{2+?_agD-VZZxtTx|MMkJo72 z{Y;2<0V$EUf93tSBLu4pU{N`B2P=6O^d}?0KgGYWC*fa_PFeq!TotzioB+^F8IRe* z<a92PLL0L~%jo|2tt@$Zn*0o@>Du9HbUl#|HVyk}Oof$&de4y+{}q+s<Vk@$EnA`X zV|0N@^&|8@hP09}3Xut6Zcnn7Si~77tG3Cq4AiQz#6J+#&fps%mc&|rrPQmTYU-65 zl_-gz3%?$7X?oZ#*;TxeOmb3sRC!8B2b$3qjnVNgqmDO_v^QGGF{STv)M)`^UU#&2 zanKoeQXWDon7EeCb|ZAm=A$&QctQAjg7EZa%t!UB1IaJp&BTdhYi?~ygm#Ori+j%d z)cQNu=!ZC3oFs|nl&<#Z+jS+sh>zAP)RN-He+Be@?(@)4?Igc~AJ-l%oeo7!o~@mF zK#EvymH#rH@@4!kPmXUIBv^;Pv+J$hLEQD?qBcgqW@TN7e?ne|L`0^W7<@as0pOzY zX-8h1COhFEp#beV#tHUCS8Taj0|nE*nv{Mg$+&W&EDCp_a=y@9C|)Dvt%KuFi1rL5 zT$O0vdOJx&pw6o`ta{%lpvE|W`_ImO6P6>y^Sg~duFeAGZ&DS_-lP6;-;1sPSgKgU zN1y*8F}b#CG+E?bYoO+MAlo6sgo&-+Gowp0^ktafHuFpicz#d%56tbEQ!0$s4GP@C z#S;+mAx;bT#)7U$0?Uz7xLO>D0t5H~q&a+@gpE}TLT-a7MtUf^EYYAj#l%5rrhWik z5qi%2yoRU-wfb8Wl5V<9fE2G;VyO>-g9S{$3+6|0(RWWbh$k#II!VAG%C7cR35m!H zhJUr&Kw=%rz-W@BOqpTbjN3&0Eg6T{xao3>hVMZuUDi!(V8wvuL9|nX`eDWECTl?V z9=O}b$g8+WIT%c?YZV(*4_*R{1KEHAC7(gEKD?a)kO?jZ0^0Q}Tmd#QaI1|E496{p zs77a`>%(LDlo_FlC@_?kjt>+XKXY|=b2LpPo}L-k9mCWU{3bU>^IQ85#3l-Nf*GWT zU*sqX2BU^J;69Rlth15WB>1^pF*DS}IhF3xjp^i2#t(7noX<!zd>~;}cJElJ$QJ^1 z-=I#`z)4xWU?0#<HIO6De9m@{^5TTYhrd*FbOX4-Xtz)`<pklR<XZb%3hI%<Ztz%c zdpp5*iyYXy-)0@I#{5~B@w7%&a|0mFE+=2QVmoJJ`miN~3y<#D<pzZG#3Pu2pq^F6 zW-(DdZ0AaxbqKv25^a7=S*|XG&vvkA0|yn>+UNVN6zun%FV!Vg?z8|0L>9o^?7fqR z!3ad-tb?~ftzfKN=?mVxbLcQS7eLsMV&Jp!_Bq!0Y-jF2Id*QDPCRi4!sVO~NPz7$ zV@%W)?mgx~zq{i=wja2alaOYO85gEUDQ}jHj%#e%!S9@T>1lu|Tg^^%oT7F_RIPOe zL|mNe=_BoBKj-%gRT;|#xAzhPj=<|Ac8hcvnw1FzLO%=cUrML*Radp9VMA{7fg!`8 zX}UqM-o~M-@t>{3^Zgy6@Kq`OliRc)Yd$(r#RWtaUES-Y>d}FQW`7YSXI>x31ZxDg z32f~o5Cw<jbRqUIv<itqVJWD{<q<m}JVI?D1-ZIor$^*gCUf_>aW=M(=a6$22Qta& z9aeaOrcSzVE={i5;GQo8hUvEm?}TxTr!&<ecQ1<$-zkr^p%kX~eOony#=wgiIrD-1 zi+orlFoOw%|Ng>KIBel|2g@qb$!s_6{O;#vDp>^s3J#{Uy<ix~B~*%BBvB#ETENE8 zv!gqjR|BlSF#-Pp*{dbTbS7QgK1Oj#i~OoA3HE~UT^nOrzfcU9$AhmL!E<(M_wA7d za9fyys&wbKMZbirI%k989Ko)y3z^U>Oy54_S>f6&R9=S4+~I$azt(j5>2a5sU70jE zMm?ua4pViNo+k~f6^dZA^8`B;;B_Tm_b_1n1h&v)x@?1&7&WJac4p$$r%5@4XaHKn zz(a3G3((|>U3rK#KI8yvNU9F2{L9L`fG$To%@H#hVo1+;=b$nqYK4kUM+oe!!;L(_ z7X;^qzE;Po{%A`xyuvg5eSs2Z9=&t@d3lnnW#x!cCaeB}^vmTaJF50GNu^YHUC9#; zwk!~9K=k&Uh{IjD7_cLE8xCRua$BLvc2F5HGdLp%M|hx??qe-w2eS0UAfiGnt)*xI z@z*Tong^N(XYuOFp18x#*f1Zgz@|eyVrkhkgB>&W>>ZILip<pEMTt5@lGE4x;zUR9 z5Cv1V>wQ*bQF`8Q8h@Pw2HxT?1W7s|$%g8c8y^Cl3QXm?*5US{JI+(4)A7Sy&#J%f zxm4{kc(x8sJrrY=S<mFdI?bi8i$UG#obxyhWA$Q5^eFCg$JBQ*R;X|*EGyA&vvsqZ z5kL}{oN*w2T2sa)IvIh!fKR3?x%m8$98|={m{Wxyl$u+0#kgBc_~wsST?Zk4a49;3 z<GDgCcZB@o#$vi?B`u(p6_AA{^4g(Lvi=c9yEh*GX7h#{w3e~Po)O)zcP@0*zOt|v zee*lLqvI0qEAh4KaQsdkqE{|K*ZNchd3iql!6};^5D=&rgX1N=MQhU=SXB;JYLKFl zT8IU1fPQ3lNLru&yLG%Kf)5*86b^bDR*OaFA~H|a)Y^;u?ghYS-Xzqg{TxnSJGms^ zx!QJKlTQ)k_&P6Mf9@`zKn38Rue5)ruiKG*gIr!GhdVGA_rxYX&irEdq_4xDiDy47 zG%;Pp4(6^yGR-+JkKni@S`Z*ymB)?(n<|ug5so@2v)gsDzJ5gfbU$B1+7m}33xL-^ z6tw!fMw+vOx_pp@zfT>4CznQ~m&4Ave%-7V9-%xyWb`dcLip65ukYPvERSYZ#g!oe zSxBhBzxDVx>QxH!d~Jeu1LxVpX1B<@y|CV1?{ZI-q_Kpnt{fcP#c-1zR(a;@^Xoo4 zE`}xaZG>y()?%r{_RWy{R)Jl=t4PN6?MXMxZqiqoZZy8O*pW>6*si5?JAEcQmVk!B zKNcTHqGN@8#5TnZq?WYw&CWJC!b_23`QOuYC6t0QXQVHVaA$}&P0&qC@^g#t;ra5H z!D974=eIJO5WWqEj?fMAcQ4jU!Bkm`x!M{L<GhdEsv+<<aU50xuV;;!J=jdA0r#hV z{=IaUTJNJF-6SNw^rX&DPyJpIVcXE>^l^J0b@)<9_6I(}KfY~$hpTOQDHmDDfF1K( zty+9zj?>Cfm8L82-4O<q!kUDg`ADToewW+>b;0_yOWZ|2K|myeBovnzXE?u6BebOV z?LR1>3k9<V<m-zoui4i&cFSso=hvbtJ4o5RvOfwFlpKpgcEIb(&+W+XY8Mb#aUN7p z$fWzt_3f#LM&^umaQ(9IT7N2?5ODTFS9%%a4=J@e!ToHPbew=_AfGMBXBn`1gX4Cd z$hAWiixre#CwCjf-@Rf?JvPS1WqJD9pQ?JhhEyYT&+yDZC{#=wpCDk3Wl8;a+bZDv z4Qq{M%p%9Bu}nvhDw~S``^n%W*0=R=-O7#5dA$D1xR6k|p&zX!JhRM0;9KbBj^JJ3 zg*hDeuCFia_JdjNW}mdK1Abs{?N8D&2uKt6-SHQOS2&EDKA$dqS~o!7a>!Xyb0JgJ zq?uq8Nxt^i7e@XTr06^;Ee}_@C~>LnL?GlNEym4<!5<(A0)p|^6PpljXyQz5Ui_x; zk_$_Cx9gc8x8{+?Oa!?gW6D&1-uv(E>uUnKzb{EY&k=hK9eM5k`EGb)BR@729lc|S z^%MkD6Sv*ib_J-kS|ks>Wj(biHyvwFnp8muZ@gr&2aF%>><Q>|3Pk4^Fh)8u$+|lu z7HYNykN%`xYh?Iu-RN8q^~fR)TZ#86&2?sF_3|`0<rwAvv!Eu+%h?J-*5ZZX1mRE+ zUnxl3njo_6n)Y=p*xk-LdG(#Zi_2?PPqm%aduXm>V%Nr8db=0@O6iY@4gcfJ#-20z z)b#y-F6QT70LXb*PY+skTA1dPA&L~?Rw^h?TPRApId-9(KYp(dMkh|fzFc9HBJpzB z2Ar@N!EIfG-ShyPKWlc{n2{1G7)jt&m!$ERaaW|))ys_#aV?^B^N{8k2GzM_C9rrV zHhfk`olkZ~$^C*xanQa=7ETS@;G*|%oq6daIczdq;*vv?bCS}%A%snb8P<Bv=fsZp z+v*L+&0eAh^9~2=+v!2qq(1N?<r#$j>G@=ce3F~mEjB^@w-sqDC?X9#kQ`o@gbJ^% zzEgbHxSNuVB&9!Q>|uPT*yj3Xha|9ru|hEkOkvp7GORF_R=deWw~eqrBaV+_e|}h= zg8MwZ@4a;Cf>00d=-;iZF<xB|`f2xMH%4SVxk&q;qh2lSwwFkun*N7kp3=%KOZ7L} zG1C_{DU%jx8aNcoQM_+~u-N3RUU+nkjze{cc5Cgb?yuR%3{3rjbA%dcY7ENqaluoO zDk`vmj~($A7%P9*l())XsVpVb@RsE_tCgOH;fBDLz00U>BB}8(mFJOHKmatVXXII_ zo$Hw47}+yS3th&I+f!q-()91RV`R-$4&@ZXm=|El31AbCCt<lF>cgr>nPJAo)a=AY zFR_LdJ0iYpsVeuq)D^9jWG|=XpJEpb|0O7_=Ko3FRFHnp#q8ot5p(V_Fw4(%hdCRc zW#~>nGzx`YU1h$%KBwxRU@**lFTY4jrvO_-iB2Eq_crhbqd{n#x|aW)!J^$j;ypE} z-&|ffznFS6<wonY?LWsWbJk1-<zZhRaheObetQ)WC~W$cgPDNBAy^!{m@I>+la|XE zz2++H`qWdU9nS;*@SG8n<xUEw788!T5bo~Xr%x7#-biIQF*eM~pL8F6ctk-y)wtGu ze`!9Y$o1`_xjLz`_8csdOdE;2_-rdmQXG~pF(g}hhgVAcC**E@4XyNW1*HaS{EjIo zL4Pdu*#ScgJhf)sHn7hwLKymB(?TZ}TEF1w+6n!fL(`o-8ZXGM_}$ahGoa|vLsvz| z^9+`iMnXFy01xxULY+NAU@w{&-rH>=)%4lMXhE#0*SctK_+HafO3z~U6kuk&$!`jZ z#A)#FRyR9lKJu{4jlCyaDxLCz&ev6sVmtoU{%|&x*TW<*TB>gQgRTn|R-a930KGz2 z*M+XKl0Y6trcTOAuZzNcgGT*dvyK*nKN;=S2`c5guI~kWW;sU3az(qTX!_{&Ngt`L zjejlikn(fo7xy%oEBG9T_1y~%-Rl+Rl1gBX`5CwO_}VTB2|ztJRoQ^rJ$>upNaYpP z|J=H&x1XLoa?POkIE`;IY`|4ROG3OQ1jqSWg$TVC7E}7UJn&GitHb_l-JMY8T$-gi zPJiI~V;7lYuLcTMEJ|#zd@j?q6?V7ODBC_aD@x?P8WhUC1ZY^&vKslc-<WZk*6xN# z*#jUB)0iBZ7qx73{A<Qd)Bfti^~%nAK(#AE`j{vGsLzw}E)}D=Qf~sS_0?#^&9Do8 zt8Z~RD3;zYYz-dm8X4||uF}7{u#}bNHDYqWa^k+(SS1=EK5X_mlbvL0_EPfJk_VqA zkKIh8D+1|&Kr@8SZ39g+E=MH@+7HRLbWCWhIhWnCV?`umbOA1?6rk5%iJ5T5o&fXq za_)~ubVv5`x?<~!Cd}8a<K|L^ra!n%2fIx$7Cy@3w=VLYIVATo3Kit~y7{@D)x7tn zF?(m(kF=d^-q0^H#7_B6VR<%(y&(5#9iRdLH-$%^+0O3hL;Z1~?38Xk<Uh*3@1unK zFHzB$V61Ud(YLG5;Ft}7quZ<Ly`{jrv2{l2AlwqQsb1s4lxOU!!?clL!e<z(d%1nD zn121+4@T%%W=>gvrm<|*GEh-~`7KT>*B}*)yB!rj8fsL=j}`_fgO$g>=1$uG_*zA- zgZUGo#_3pN+ZW3+3~Jfty&F}XN0U06a?XbVS|WWMd-u&{#{G-Vn}v3NjFc=D6Gr6( z>!j>7S}%af54%cwd5o@?lV}uzU{?elGZ!dSHLeq2sEkn*O4=d1A@|HB42PqC<Anv> zWdb~C7Eh2?$;fgrtS^rlf-d-WLd&bakE#;s_X<;V&qZ)VG38^slT7~wJIBcNo}~G? z`I+Q%`KrqLoE<@R4-~nCE<7K;P#8=ur#Ah@oNpv;d=ND>x_MZjk_xbyMv-)2&0A{~ z|9Tp!;U?qxp?Vztfw=lIBncFaQ#WQtxqhKZAks1dU?j8vrO%RQsi$RHr^&YW%vx&{ z!FF>ZH||97p5m5vn6sy0lSk->neb0DAHp<({;a&*$f;Dgjrn`)B#e75##jW?V<h(( z{r%VbJN&7Yj7p+8vA4g5qU6z^gh`hp-!Wc|FnT_g%W2E}oZm}~wBt=Pr`D_&`NnfE zY4X3q33U>W3qIWT#)Y>bpkvyCkM&IDIf5S|0=vVlg^mjY+AO>bOzqmTe2Y4<vDwxp zId9*avVC#$f(m1V?T`z?O66cCYFmFVO>KDmO@1^-Xs1!(t-?RsZRf*Bb1swk2>N)+ zLyW=ZFxov{#w^0&O4P)>7zSOoarq*NOP_A>=cmZn@UbqMm4ESaEwAet(`@t%PLNx+ zg$#=pH}pi`0X2=6X}Ou0EOQT%7)?lO()v-#9Jk<wLP88!N%QkYkn@mwa;u39GTiGh z)Kz1*TYf>UYg(%}BzIZlfWVc^=7hBy-#lb?b^mTlO+P_}HaFvaE5mbh<ZyyMS+d{i z&YPrOQLd~!dA!p1IgU*0HpZ>>skg>OjZDM-gicFC!9aM><dY$I{3QS|ye2qZUhuqh zdiUtHTGZ>PvTVkl_<M}h)EJ69!2YBAW%B});x+UAC@S;O_uaSXF1PaV<LhT}5#15) zVJq?n#<pi+r{Nx(JcqrpUo90J;HhS=Bt{e>F#g6fY0F^6X+U}yny!lVlvbbmk>(?B zEMoidP{S_y#@xp7nB;=;kCJO4ribt!q0c!ujBo1l8~{J8kIy8usWYU)S{<TqyqWnI z4@Jb`;TN5j3GR#Qxg%F~#q2nk5it!Z;-muuXB9{omP3EighLuc8R(?I@v7<UzY6WZ z0O0=Lk5Fu%MCHzfm(rWUxdw7CEw8;Y(xEraQ?B{z{&T>z;XlbOQrfohBT1ajlcD5Z z-{-sz2WhS|k&nx%-HO*5`j)N#d)9;fs$e&Er)33r;zjdFhIHp=02W^8#ffI;2rQHN zofHXvO!MIr+Y)U!1v9lV>+WEBrQO}nv`VNR;ACUpf7JLiU`g;tgO$;s`tYEjkMEh& z)2H`L`|kBUdAgk1OU^TBTB<iT4l_;<;!Z}rxc>vs6d6WrWis&5i~0Ud7;4aMske3P zzu6PQKD?FsT39F%)ED}aZnHh&Pg4F6Jt8rTEMIr`)*a8^!oM`Z0&T8u83<cGm?s8e z%vuilm-#M|p8c*nNeTbrArS8CU69pNQhxcl!Vle+WDgf%+6K`wm^{DUhbK>H%w43a zOJSxt=C{Lcd4*6vsULlQ+4VN9{Tmob*^woF%(?ZVLfavz;Ib?pgalAv+^A}}-iZ=+ zc*Fl8(iDX-@SPa<ts8ST3F|gn8ts+%efs)8&B?RCJjb|`wR?J@cX|$=2B>{Y_{}!) z%uJ<uyL*Il%4pMcMQ}q@6(RX`Z$jh2V<5#yd6I6bJYIW0b!(;O@4=H1myTN$)nS`N z<lF$PK0L3gXkkyBP0g0ptX`ulHIbqI=lwIEaNY6k_c70Z+&eUVz@ew>b?uVt;-B<e z%32p_n_7a<8@AaJs@422HUMPwO0=t1hnE0F#8>rj@&OWzQw*i-aOYw<s^|(j9U)Kv zkbrV=aEnl3I3Ajt+#F*=Mi>+<0p17)=rTo_^MHW4;WCUQP)?E!95KaY1D%}<Y;6AA zcn=`D?ami}?qX%H?@-G8wV8Bznrc-iWz+F=>wNmi&0)_hF##rVlXJlUYdpFe3|fDT zWWj5MzHPNp^kTrvIKcJ26!qZ<tbjbC8^q(@fA8n_Z@<q$4g*9w$amWHN0)(k8vf9A z>vKmFpbV_9E1rY$LO^}NGS*E4yg-oZS1Dg_V`2S7-?wn~%J~}Mf>haj4m9UluT6R6 zPd0H2z@2<S!K1sCs{+V%>}j&A#MGjEuF#zD(g95_Pv}R&z6ZVHkh)9A-@lDZyG;cj zqi$0L|BLzgWtZ>Ir<(|Heg=c(Ge!yo_?UR3lwgfK?npO;P*j0oHc4T;Z9@QdNwGJz zqE08VsdN`w&jh^5G`)WDBh*%2to%=VpvD$dnR!(HS9smUkG69uqLut?Z7pf_bJM~} z@~684{kG9El`k3h034I_P${7oaKZt!yr6ZVVZ@D=XY&1j*rpW!x>#{D)8~idX#q02 zl&-uliAYtRoPq*-{BRmkjG1xSqfmtOV<gSQ(PKjODSVb$n{l?Q!jQylM9jTnGx{F4 zH942dD9l`)V>%qBU&8xsvX{Y;C}j-@GfHVulrJCa0^$&yE+EKW3s40+LF>iem|e}! zj{t#Or=PuO3V=UglSap9YvGacE&=#ggzFj&m|k0fuh@KMi%va!C<A?6c#=y()w>1z zIzyAZh}Z779I=jWRikPNl>&A9brskoN$;@*>xu?@fU5}qigRpVN(BTuz(FKv>OBc+ zplFIbls?^)Rd#KoeL3AguwXm=KN_HrYue3og&-X#Md`^_-I$){uU}f_i&P(@73!AW z`IHXG4@%=r)v||nJPFMbpJG;<hWpRg^1H^dgTZ#asnrwp2hcUHol^QE6RVPkoVD$x zj820^vS$DB9d*asHzLocq5xPORO{K!s1C35dI?SB!ck)}S3)~=1r99B330=48OHk$ zEi?hH`<9Y5`}ebV`!znr1cnQgzb&gAsM=p>q3lTy3e&h)yOixQ{s|)bADR%H>3cu< z_S~m7{CFRGtp+JV?@|iN6ZrKM`6ZiUXPSKi23(78w_ilIiU#$SCilIootc-r%0VyD z9woUzsB{tnr1}o}JZx$TnMLRIel4Mz1ZnvO<2f#BNXi)_-1CR~2>Rk+1i~1?914h* z>Is2A8=a6GF=e<ZLf9ADV*q{8H3;b}OQeI%`J>}$nk{GA3ozKN^tM=0EJVe)^xvX( zNl-2F`|p{bUvIT|X~#y|43y1cGf8!xBR5j13<=-4F6L6{wqt<+l=)s~!OJl}dDe(A zC;|?mZ8g_L&cvd3x~do-v5Nm3dvSNh38Vgf1JK!U#mtS0#yiiVws=Z8exD)_X_$aC z2-|k%Sc{nGVfe`%JI{x6StxL+h%G+BFthgg{0R#{eZvz--=5BGo{^Xz=9J~jnF*~A zGzFVLpq%r9^j)ke*GW}0lhFjQ#we)PPSAY1qTt%CIOI(e459V|wqKD|R_`wV?VxB? z;k%XpwU;rlP{G2_&c*`H*p1KRNzfzsY1ryM4@;t5W%1+ds0B#XM&?2vpmfuLeZBmh z;Fo+*v}bZl(FfVzvuXGL$w$XU7f>OB73h*koJs%i);eQk2Y2N>%Id&GzfTw{KB4#^ zlPK!mDkXpfXXt1aP1_Y+8gEp*B3!rmo;c=>C@%YgY*T@E!hiJnn*=G}+)Tq9hMNJU z6+|k>p7pHp#R!tV#oa7(DU&;c1g%&8+a{O*w$qtM%cY*%G35Gx<X%ER)eYVr%h?#L zZGHB2y+DC-7hP~pnoewGWE;J64-I=ZAtizJ+@8ZnuwNd@P6J=EU4cuad#J0`0MR^! zkx~ejZEqzZkv(6j{mZxctJ&Ek0dPo;-J3ECBpnT<=)g`z^pG{1p$)^-Y|l$Hj<g4R zm6N)}#*W0=Dq)xGLOxMd9A8HtHxSNYbAAjcAr6yrC+*3AxrB5n=>xf$yJj!>!EOHz zEZP*q05Gf-XUYvF=5QWI$KO(pSjPB(QIhWFlIfJ)s(f$(M$?Gc1k33_Hh_Jt9aKcK zqZ*JARX1+ZXh|ObZHP<l2oAHCu<ZXeEc-eu5R*D=?ZGAL@PysCNio+HYUky6$f|V5 z#BEdY@1ElDOqRP~`o+BdIwapZn%3Jt{Szw*317`}Ia7WAdcbm!dAA@4kDERGDSC@e zz4Zr0V!a`hUEC_l7*%ud_@Dgp*j4<7gNoFw`8(X>;%o(T>8Y8)U%n9Dcdh8?yEt&9 zCy&!=al)?KC#w7!q!#Fog+NP7a;3icEmnnfWJ4D{x#UH)p6xmR`{YMH6Pp}VgA-T} zwAX)a&#l^o8|o1rCREnTC|+uIK$++5#m-qOwpHkz>tw3H>i~pI5$hf{y!@W`_3=h2 zdKd$f{`nKvInnGp2gBJveS%aKDYCQKN09&7D|Qs4epu&eiaJ(4zxVko!Cqp!gsDJw zLoi9tY0`~|?nHtYCcS);F9Y0mNC*xsFac_Gd(Zd&D9i|2h9Z5fwnYXdnwS0--vWwX zCRzvYbbdDu0q8}?JamrkX$b@dGnh-xaoq|Un)^UjhBtT{njLVA7MyA|uE7%KyqUrQ z2#&hWx|tsFEYRZ%r4J(DJZQ)lBKE?0t+^kQz(wy+dQ^zvShHqK+)s6GH#Q<|wY;n} zYpHqrng@zv_Db5AX0-nT7j+nkQz{Im+0VP`txZM8HwC|odNTh(AjFIafg!Tn950~z zV~)$1loywaU3OdK%#2+$^Am-76x>%@(v!@t4?gACti*p`e8GP?N;tvaN}vgI-Kc=@ z*1eyB>;s=^7VCO0@U4#arZr7F3_z4haPr-wlk-XcBHM}7Q-EJ@`qj%rDo}M$h|wRC z3z2WQKBk}gYO`=>m=Ilnxfs29)$8I_E7OL-n*&;I+uqAFU9K;0cW_Q_!oi(X5hZH9 zBlXvAcr`)w`<ME-qz-!D(?}v4YAN32#x3!`xy=8z{t$K(#l|?m<@I|Drm0%xvDMHT zuV+W=M})=J^X?Mx4~=GL-cockDOr96u~A?GD8OdzBMwPr7_+!PBl;oj%3W+Mea*%~ zf=m6Ume#$ZbI4-i%`<3v5lj&fVc9en*)C#|tCtq#@Ym85=`A%v_Ax`XN~0VOqrfQ^ z>lR3lX0{juGo5q>?HPf$;s`CuhwQ3PQFNWY<}{$nDDX8EWh=ThLa|eAY(32xy*K>! zN2^j6^Iuj$<vaeB0WO^(TBo8v;DbzS`=FAU<<7A$;;^q1&3*uqEv71&+B?Ix!a@Kj z{90u+hBHVP+2wNRj$*RO!`L-rPZjvJyPl!A1wy^$%NK-l>aU3{4x=z$Z?2!MK*ddX z-hRuR36-oU_lSY+um#jmJLA+EMF?4z9R&*!|3HP=M0W%R_t{!(zHKs_g?Q0qj=Tyt z!9(T$X|*iRrT<oja9)x7!6<AMX)fuh#LYP@k<FlmO%>dq-D9kNOP=|~thmqosRx#U zxRyv)*h+J;#W{al`Cs)i;cyXt9mH4)Xn3;GlsmSvimV(f%AX2_;E|h>IUxq?*GG`b zl$+io-<f3u7H3iL&*->1iE0CJ))OJGa-o~y3L$K3=gn?bVL2+mnmxxf3u{++H<`-S z&iY1w89be|WCo@4gdjJ*DrZWs91F^a7uM?cL%|%c8+i&Ql&zKhzfL3dus>ioygZd* z7!k?37ZNuz72cg9>-}K9nF`6N@_WNj4tX&j#z&(z%U|Ox;Co8m7KywAIrX+mJ)y$@ zns3z;L{9-Ul4Rb$^ga`r$-fTC56fosR(N?j1)B?9ViP}Tm-~$sudA0^@y5+%3Vb8= zUjNw7FO0TkQ+%#0D#{Ki^>jQ4R(g=duwu+FSO&}d032*8Er{~xg?pQ}D+`M|EL(h8 z$mq3RpRrSt+X{8k(W}o6<*ccxrnfNZRS?a;roz`QLFItw&_|eBda|D;YvZoyXrDN~ zHM}r~2E#m+Cyzku$9~EYcjz~l4I8{1+L5%MrluQ@C1uk(=Z!~2=-h30==W)|nvn2H z6`F-3mzOdtj5)a<%tcEXItPNIM|eN68`!@RSgz%VZ@@AQoP(+uFGto9!1MyxGX713 zSwkyqPLl}6677tMUzuVF)o`U)`lR0IgtY_motZBd+fs@RC!o^V0~iJ5kK;(CS6bTA zzrtZ|ukZ=#&9jO_!jYt0nt%Bn68WE$gF2l3vlJ%h1_@GDM+<UCc2+;^teBuyFWV(@ zBfr?5(%s}Zct}Fce~faNMt!Z;WdMtU&~U0ehJP+K<(aCv%Hxmfp-M}7d^V#9Yl^(5 zs^Z{HR-X?+&r%hjj}-&r?C%p4>~GOn*@H1=AEa@50$9APwFLs1YHW}EiXu3$Tv1ze zdXswi55q_9V7x$)(gUlsHRvuJ+}s@I|E(<PKksav;revZ)iK=iTe;UXtPCk`X)Xy- zq}YK}*XcKtrj7vhbw<haOYzj{c#-W!%3HxL^RGljIhF4Zzx0|0s5Gf{9>D1@ztXDA zLO;$?<XVEzt9gy9$sP}yn6qiqEJ>^%CdF_rp-UOac(V>)>CcP43bP&{G)LpQvgnuS z(nX|noV%D02kWBeR;3&5%T{JH2P%z^H`C%W#~jiwU8QDGB8vW9u9&c{I#VhBu=B*X zB3D|*Mrm&Sj&P1l(+u(q;`m<l&#!7NwFMUiNEve!nnn8B{Y?w%mdOYBsNgKB{;S_N zJtzjpSmZ!3?{uoly{Xi$%>{ys12=qB^JGV5df<wSoL?6fk%>zR7umx_9M4mBarJrc z*g?CC-@Tua{glPuA=ja9X=Z;=ufBKPw91nnDZ4O@g9-vpWwXxLR3(+O!gy|z2DyTj zxqMXAZyz=*WG6Znvn2zi0NfL#QOcxIcG2Qhq|NI)3N}KPR?a3EdUIqyGg`Oa&SJw# z@y3Wn+@W7N>1LmUr1Ve>H7i^pRL%c`iK#`x%af1ZqY8#hI6%DtoJ?VF9YCIL-1+^( zX$}8?M%YXcL~l%S+-JUb)xl7R^JXWPzfI`<oN$HZJc7y<uzbGg8_qia1=EDv05cM7 zyUxfvz;k*abhnD_uVd`MSKnnzeq%ff*%Ojp1;o@#Otj(|gu%<c@o7;n6}ibo4aul{ zG86be1%C@4JE&PZ{0QJ#|Dy8_6<c^aw&9HJxJ-$2>&gRDet!^45Do&(i(Y$$^mY6b zxs0c)AZP5^{JwH;cGyQu#aX<9ZhM{Uzj~y)WG(L%g7{b>RpZKQAA`ST`m<&HogmH= zw2U;R^!k}On?@A%{jp6(ex?LZ!Wws$pXv<-*v-uD15YN$X?^9i+ptc6m4x9_Zu8Is zCwUPPK|Hy2w(0Nj>3Uec(lXX<3jK8?R2&Ibg?*<78)Dc%T&4LUJqpPy`K%O2zA@m@ zon$&>s$wa`wiMn7uo;7RJMm_1+d`(QxkEhZX6mBD7`|4_1?w`FF;BYCQW`KRX-pv% zhI_QXl5yM<y<hN%4}R|g5-bitv~bX90N(4#j40zQ8W7goEUa2ac{mq|^gejZUF22H zKMdk)#dF`qaL9YHt7F*J@$4s_%zK{9maCP&OWAdJD<d%6k$CP_eBtwxLYZFVTTqRo zb2;_)!y3K8C0i%lt`FgEZ0)_(+B9ArGH*?uX3af9-EMX5lggZohxHAs^)0*&9WD(| z9yUB(ZFtVxIONj!;$h?DYU3;3rg@j9*AJWCtTw&Ze0?w=xc;yi<eYLkP_pOJ;^mwR z6~_JGZM}1sA6(dK<(M1P+sf{G-A}6J$9da`(#Gl9E>YMnbFW?SO}olH9cnL9(X~U@ z^-2$@4O7^uz{(GEMLsL*bS!-A`sVTda=~-y7=Y`z`ljoBv-UIwIk(Yu@6D43eBDIX z?)bv)q&MAZd_7sNJ$Z#ag>QOF_<Ac`dus}N8{YJ`@ICEtefp&E>C-n)pY!z%x%O3j zZ&tl@+3&}bu7s+-*O&WWyy<_>*X`Gg+&e7acYT&-`s}$r|H1F_r_LY$@d4jmDL*ei z|DlNl0Mt(?jV}NIvXX!_zzG%w18^z;g7X`<mJSf%?9y&ytz|>;2ocjF<F@h<;xVk3 zxO41o2nf-Ia6})Mk7r3<sdpQ1ubRwL^qD9!VW$|Uv;Eyo-f8iDS%N0g3z&A+&Q=)n zOoLC1J#*x}pqmtYdOcbcs9)!Sdd^eAS@ggsd7X_b9Rc(8?lSDf-S}HDQ?yg*kpUEH z0`M4LFF?1$*Ao29x?4Af$m~X6>lDZ70d{&prya@wg@!@;Mi(Pa#ek06R)c5$#ey8L z36t@7+533^wJeW<8({_j`e538F_hn!A=;e#4BLmH?UZx1FK}WFp%hbEE6hqP`&$nP zdGJkn@|{x1yWChKDjAm<Gx&K6Rr@2DXK(-l3xaT?TQe|=i(mHNzbe`6zkPAh5dnhV zH+qXc;^Y``V>F?ZnlMWTybA^3PtGAm2&mHo{-~Xec!*jX2%tek<H9HGmkQ8FDHm;g zIqekFlbOejMN(iEC#7gsw(W8~o)cU=mX8pyonb6qy$PX{?)1T^Z%QIyk|S^%UwFo~ zGVDcB4$n-_IH`~NRCu-(R!&mXEepB}cgENWa!6pfeHGJ-5i50{$TWV6pOV#?RYAF0 zVDvi@REicCehNCzz`B6YYP9#?D<AXo{iQ#~y+(yw-#(O*%qxQV;cC#;T*G*D4BNs$ zL+dD&ejmf%m}uPq^HTg&s-;7RCa`$Iipl|g%E!vQ&6?fzsk_VLY+-_-!fi}zXV>bW zkAF#H1fy}bPu6%l<(lt5l1|ULDZVWTb>+H@pno|kbMqFCCLj?#N>^DM4Mu5-0I%O& znjwosA+2fG@5&(HldK$rSd_kOo8G#5pB(0KI69=65OuJXSiCEa;P{do6n>+eBg{Jb zxwxob&*n4UqjTmSKp12c`Wk8=Dw-XEQK!Zz0bO9v`bQC?fmMYJax**Q)<!A0j-qol z3P}~!H^fqV%cZSn0d8~aX;#Qd1V&W<t;(usXTQ2$@V;BuE7kWCpJqep^#hjP$x%Bu zENyA!&rI^b6r)#=ZC9^JU1^S!0s0{($~0|%N+uosh_>~s?6lynm(9(+pP#diNX!Tk zYnp!<yk=dH$7q-))Qr+j9-d$&09+6D<Q#Q+g!tAxa|Hg@c;_?ol}8-|0%Xhd9#fT+ zZ+?V&^BE(9=H|b9PCTV&FZkzqqlUnDCQn`!Lp(2?(6psl)3egCJTN%oTll%+b@^EB zk?N5)>ggMXQh?JNclb34$+%ib0b23)1|eP$6QR#BM(OOO=xDlvt60IIbX6W-8h+J; z53-I3BA&@J^3)0Ys5%4GtLQNXfWgT=DD}TdhG|J}e+qZ^;9HMx(_#kxP&M+wh`WmC zp;b9Xk&O7knnq&U&mB<z-cA6F48RyP1N`%#y!!sVWFmZ8+^FY#5lVoV4A9*BG=Sh0 zwJ_Bxw?-SECtWNaCtz>v$B%OC?bji<ux0e@Bm=z0I-~ICa^b8>zAsaLH`Bfp{eofp ze#s4|&?KCjCb)@~V04xW`~xFYc_M+_o?UQIDb86w%vqX&9Gu@0y%yMYD)$27?dn;` zsFp4_A_1*Ljtj^Ce7KY`cKQ9r2RFf$8sdlW__6t7v~Q0gzEp|E0E*JH>zN=dlxEj< z8b??=6F(w-bBqqE(V6f;$7e~%{G=M}L!-+u-rzi1)k=)D5*6Xc`lTe%hPlvlIK4xA zDtSIqi2eQ9xJX<kvK)%L#A<69VHqj*UUf`QNE&ggxq~L(ocwvIt7Ghg@=eZYYeKI` zI%1i&RMB8k`zS*jj{uUHKzu_Jl8C8d3Y2}S`0@uQL@0A*(FO;ZDK#-&zSvjV)PB#F z#&){GBN8cSzlmPHW9a<xLomyi+$RASHG!#-tB^ZIN<I@y`5Y#EjCdPL<iou0&hy9> z{V~bKJNES+-(VM8Con~;Y!v2gn0kIaQ+@qxd8)F7Ad?h!>AQNF_D$3DU7N|(iIs|M zedh)2Sdm8PT(7)und{$53EE6MK=gYno(8b1vPBF~>q)d)`4d5ft5wUE_T`^q0vNRD zfpO(9f>`4<jIf?0U)1-W5Wlhghk;h41M^465ytv;cb!(Gp|suZ@DL$RkJz*IK6aiK zOwezaqfEA(hQ)d`widJhaMnR&vjhz4mIPW6y+GI4H3b7@`jiRB=0vxZs3nz>XSOK@ zTGy~#G6)K96mm~a0V61e5c=b*00Ds!)B77t5&1~Vzrom<g0;Yp=a4c3c!awV0um}N z@{h4KmEAT~2MPDJ8nkKPFrR#6ivUhGJ&m7^+i>hhJ>gYX0%Cwows`JgC~F(Klb@9} zq5y>^E61q?aSl72J-MGE3oI;OUhiq4UYoI#_h%TCr<F`ZqjwB2OTAm4z7Hd5cFg_h zt1iZJcM@*9M}#HN1L17LMbaK)cZ`Dkh|!mX^~XA^FS@fL;TuR7!{fM~?N!bv+~dqB z?p=7(D`IKItNZ^V3hpK=WK_)rYzx1^gy&rj_Ri^s1h!x;-+I|x;{mWIomgcic43X} zd8c>nX!2ogb?(E*y!M}bS_2WSw(_I&pwcF<{;gDaC4V$I8N@zp-U4dMJu#2G{(8m4 z$cU3R?$-4XR@+?}_U(CSSeIU-L@3$m<_e7h838ck0;~##haFn3d|s=1ma7ai+Fnn> zYfkp0SUrHv+CBiGOI6_!)iG4@Ck#nYE&_?x#+H{gkhc7W$Ww(uq2SJYM1eP}Y{UOk zbSC~#HQpb;vluhhJ7Ztc*mof$>&zG$48|IwkZh$W390YQ7|d8|EXm&3vP9Xb@QgKE zQr4ofl#oiIN2<rq?@ze*^*Z-;&pDs-e)pbvH_}sK&Sof<Bd4vP9`%`+atX$3<S~<% z@)*zf6DC=3+lfC~Ri>kOXZemj_j;R~P_HW4`^sy!RA?P2yEGJ^m3lp)Qk}gQ?e>W` z^j7$T=U|BCU#vB@ryCNnsWeDjv(+`j=URZ3ygrMAKcC`>4ja{yIX#~yKb$?S-tksG z+sSSH@DaStmO`!-_G_*>;BxclmoJ^R0zDaz^J8o}FJG&1RMv{^mJP2qy@|Es#bI(R zz&C(0YTyWIQ|1!rAj4QZWbyrC^<{t77!@(^tBihKc*6dj*8eCqrTZz+@XP+Kr>UVY zn5OL^EeRXpKY171t65JcNpsV^e}j;(gvVlNYVY><dC?AjpaX@9h@tWz(JWr-Xr(@- z4HQT|E!%qPotQfU4ZB`(ReCb^Y?<zkXk3($7JvoRIQ#&`_!BS1^OfP5qZYeO7NnqS zG1tJ!ljw0(klq&0uLcgOQjv>r#3Gzv%piDzyn_h>88Q6r@r-K`(6)$i-bBF}|65D` zl#j64185%wrig<m;y{ghTL1_1mn3W?_`qJ8MJOnP6e-6n`sqO4_sc&22HLkBy;ikj zdwal5jC5+kC{bPoZ91D^g9Ply;r4#<2qXX_iKOqZf_6xNOo~8#isyku&Dxk8@dJfR zAx3^lAuxj*MBV5uV-1DFmH$da#OT-D)qeL<A?}C1pCWz(W+`jnBT2Hmc@E~=c<qI1 z?3l{co&&5Io@tiLglA9%@eHUlLm0v{?&&wy4x&QR5Df|cI~j$HJm6~pWj`HO7&i<+ zxB?Co0FpH7ud3jnxvoaX66`5UikdAcN49|#nsVcy71IWkH}JW>>dmaUE}3)gOwt7& zy%^HLvC<&(wkL>d2ggYu`WNU-$#CX?RwOEHmMv%traX&E_(aVcfOj1{-GZ8kn%I{_ z=zoJ0Z9iy7v}yJPL`GM^4WlZszjUO|`u6D7VG+G6@3wUFkK)O0m*A0Cr&j#?1|qDE zp;HIhNC=Ox7bx;eM2wZ;ng<?IkIx*8vcZDKj1zGY5z5g4w+WF!_ic|;e5|dn`Odib z^XSMNKvPyOM~jE}bZ1e@)O6^#A7YG%1CgD*;o(D980SKH79)&FF}+oHV7VFi+&cip z4;7h_qYj?*63JU*^ExwzJ;9+*@RjBq1S;JBS48_c&)p<gDI*ftgq%U@5-Ls%_Uk@! z$@+5?T=oy{cLChX@1CX8zp5%Wod`T(1Zr|aVrFCyaFV}f;)Q5whivl@&UaAGJg~?N zfK$Zh&jZqmwD5Vw`_*Z%TzK|zIGGEl^8$I(*{tK971OeM<Fe0b(8F9nJOZlC4GIzQ zSU#I2R3f;)sm%Q)e|S+qi5op~RR?xfH{ygXsg=U@2%}hEc(GOtMlx@&!d+~^0v5R7 z1-@GY6*WK)N~tKi)T;!Xe+*6-Q^m2M0~c<?fvY&*xNZo`ce@2N9VOh6h#b<`oC*5@ z0miU}JbUshl$$yUdV9vUdU?q_-Kl?~!Jb^UAigN)bt$hi&*_>{wJ^{-0z7L1dQ<KT z(C#bnm1@}C$yzH-iUFsM!OH3bZKAujF3d23D1n1Lb+ycH(ul#>zGju%zLAIek;pxY zjD13tO^}1}zqX5Ru+E)i*Pq44#!-KgEBNq5ioK<pCZH-G5FAztd&y(@lBdcJ4EC-8 zbW0ar-^V=86JCS6Vk=?(F@H}~l4DssFO^;09rbW9d-q$2WxQp}t^Nc{WVZ^89btI2 zs{VTzu!%6XHZhDPAZgHx2Gtf4%-8L?J}7kN(EYr%irSRY2O8+ld_YYY=9@PdwpRnA z6*WF7at3%LyzcvA8TY*6A!-j%4HAECJQtWZ(pqe#lg;G0x@93c{-5M>@Yu)HxL5gy zSH>@e^lPIaW*I3U3B`OJVm^JevM3Ie_*H>=S@T5$JdFjvzX4C{HXYRzE!)o*TlEGP z9_O3{0GwLhK3@#NwzA7R!J8Qbb%r*qS>*(RR5&0u?$cEw%UfR~gRYY}FPTOYU|_s! z0(1?NPa+_pH&+Ycq2P4cgZ;J=)$^e9LdCJv``XuQbW>|SOCt>J!6Oea22a~~_1bhF z@KnX!e|P-82ZzUfv-RB&4>a=D^D1y(x*n<C_&>Fv6Nxu;#@iL@?@`~>x12TjAKhb} z=;}2m?ekJiH`pMWu3HilD4nfhd)2uQ5r9o9@kG}njMGJjY92~A!AolN=GvfWF}xmv zcd_m2=cna%;JZ+s)6zU1SRQ}_8~9wrvr^qZoA5-Veh87XVA5*1kAs;=Ck6a=MSqCA zBBdKn()yP!Qt?zeffvHmSFL+>ywCMauc2Mwd2libd@8MgSIh9NDe|xB;Gwl0N$mjq zI(lWq&T_d(JmM@45f}lAk-H@X0MU3*c$6y~-@)V0t=p^7kmkjy@f^FJF{@dYmir*{ zK{|D}kmU}uPrMP@1O40#6%XuEYBBqOk;34Tzy9v3*Ms!sB^kN~%B5cAR)8tCU_#{q z$${xLRJ35rP5fMgD&Ybg?xEUlD5Tp^exNrMym@^<d+wnZTkO*LjDqS%_x9Qmco|#W z$EWUJh(89p;r+LUu1SqMtjygC%~j;>lY(O_h!?~S_os9SE1W@?+t+10S;ak>l}piL z{dYGFx6AZiFM*eoetYxq+I3J!3luX0gQ=wI3*rOz194B=>IIqrD#@fCu^sm4MM2(S zJFq~uIqmpk;1lfc?+~x{96t65X`<OEUkd{R>F@&K`GcV^l|(>Q{h23uZCR~`qv_Y4 zN@TSA)bxK%skteG=zGeAHFU4}fT7&-U~c(|hT*mNVIX2`hurZkA13N||I2#EJ66#p z*}SBX#&>fOPHCVfu8aJXvJ3kkL+N=E4Olh;g_=jJrt1W{VII*5p)!@g=*XSejIjqG z;sUs?1#XeS%|da_bW-_zzmL|VQjMCi{RgGfQVPsjHpH~K#K==LClT84qVRVB5Bh91 zrX{*sZC1Arydg?63gOoeCMp{7CZ05|bnGBiz*JeL+Ryl%GgeLRho;rUT<7-v?%wz_ z)>H_#3IJaU5#e7j;kq-(mt)A1;q&I8h%BOV<JBbq0fiu_r|$b}a3kZv-hbl}taEpA z0;Ce56;Y66lo|TR4Pt^*(g!KV|3m*KExRRs`oQQdToe4r<}w8(@A)^n0_eEI7x_r% zbK}PgW1kNc9)$><B2d$OCL93HgEL28&LJW58)UFjpxbPnhg#Rxxbe_LrUs^$kr^7F zQW?{|dI^4trf!q~LnoQ;YuQ#PON3X+)P8!cg|C}-C3Q7I{A8|KM1h`Pd~1BiQO}}$ zZ_FZSMQSFGV6+Z@E_c0fPQd?i&+}<p=Y_7K1w_UiNals%=Ni&M#f>5#jkhiNAjvPv zvsGeY$~To~5}@{;&p8o#G%IvRzo$f24J(us_RawRJaQ`<9eBJ|E$NAxSaS8t#o^rL z;T~Rmp2qN_fB4Zlov-*Tz|KQ6|7fF;V;?#kW}q)W@IdD6PS3;Sp;{pCeV-TGe-?aY zdq!kR>x<H;|59Cpt8dOik7Jh%>cg{}jW}mDv9tEDmp65UM5r`1!YF7wli6*=c54Sy zDw&+&4wV0k)qS$aB}!fD>AG(1k9-Xux*R@2OFnvmyd%%M&zUvpJ?IF3(!)!GJ4!Np zd_u2lfu=a{CZFZzQmnGOfiXd@H7D-ljZZ?f77+)7@*9P`4OtT&0WBlN?R(iDpA;b$ zpK8x_-zb{X?EH}V6}$wjAz!Yl$@5<3fS1@`UhAMuHWSY*Ovi@LpYeGSJ2&qyUF!3u zhac4sRgFli%f2oF%hD#QZ<;!oDmQc)^S(@JwGesm^fPb9KPEFLZ_`;;Bg>F^F!}R* z<&&E0_8q=DppDKNr5F^u2hMbXS9E!&EWqhom}?X$pv(Ku-wmiE2$DMn=Xf6Oy?FU| z3)zqW-@nHC``JwwyY;p+wrk=RN6~2A9=t<QX?gbzM0*?eK#pGVg+nYkec%f(c;C#M z-6GIq^I@=0Q}7|Q#3k^R1(;g=9oqff;QRLg%Pp~&bAC=+0QTeK8^dVf#ha$>_X@wh zGN;0CJaaXob;ew6ZI8|VQhto3__ahW9=9#lEva!9clG!nAI<j0l)uok2$EmSc^PzA zKKIPUdGw_PasMxuDL+*jzL#3=arQyKZ#$PF_R`+1+Q@x8{|HolG4E4*Kgy}-RBQxr z_pR&z%>4u?$_0+GiQdV0xtZEx=Uq9y?WBKh|J}igZK_)K-g@>+GA&5#!%iX6va)}y zC}97~rl0_N^UnrcZ)VaF{P<{(-<fy)f9Plch~E4U)$o11c#kg<zVLPLfJ<8Ut#QR? z8i3#yaCCRL4TK6(vuF-T6*RLPiI<1nKz86GYz{vDqHtRXr$0qh4W0=cXcUmZA$R~+ zR~HKK!sZ0FPf$KN7MtJr4=(MtN-4EYm$P2K0>dLsj;;#OE-#>H+C*qBgo6NNfC#Vy z$x-NLnHA_xR<k)`fHx5JQYuI_?_TIDz_aOoRpBw%$3cimuw#)4u%cvbwy8_)v4n`g z|Loo#>oWcEZs#}xC;1rGiDa0vwNEARPU#1(QYwiwV*D29*=u7%^V)yJXP_>&N-p{e ze`hc2vm3G0pU%HiH-UFWSzcXsY$#O?r{m%j(Ctc3aZ|7o(ZIQ%b)RVYysy55N*uv= z!Y{4=F>P*eG)<EDx7I0p^CpdvxOeYc<!^wQaLe#b46NQrJn&Ix(HO`6=-5Gv-o$4m zGpJ3g(M8H9j;}jnne|t~E9(L3mn4~11riV4PT!vcB9{Er0S)#VgoYSLwJ+a<>yzXY zE`)IuXmJ-SrCQhRu(QBsw+TRHH&&|15<Z(2*@=*>woF6@&1ho_YY+d8Hkmj=htI9) z?jwhtDuLw2GDp*IX<3z~yu%Y+T*R;y*7ED#=Z0Z;0A>FOFE1T5N1-zLt=i`m>Y69u z1bZS-uX&!MQS!&GU;1K9W`71E#hD{z4p0+{^DlF#v`m>sk5iZWuU4S~FoW)Zr@|^+ z)T5q{D%tqPuJsXRdwW7*m|j%^Uej0W_zvGoBLD;AWb(F_DWz&R2D4G$ziuFO`_yL{ z5Qu(TTQ-mTUptKYOs>hcl6bX;tg3fxqE$`1VBB%Sp+V&Qa1o)RyE5};BN`@qrJ_9` zl|~Ha9L%&A22t?1;fmrUZE>%M@V)gRHOsfveqZ#(NcKe?O2Vgru0vJt?+GQ68_Isl zt_qcWu4q4P%7gKCih6B8Ry8Nq&wMJ{TZ-N1SU(d*2Gc$?*4uwaEV*dYbJQfMAva9W zRGEA?Q^W((o6v#Nyh~SAQJi1A)a#d@v|sw?Z<p#>x^Z-kdvQRyoe9l2Ak&0a3SYkf zxFy8)YRr~OHRl^DiU6acJ8S7RGZ&hC>Cg_?+r7!Zrz*=KB$Kh@zLzdFyjDLuZVvoZ zMg~7N8HuhFM7e}4eB}!Y*K#WPK;xBtB2C~NcH=BgvK{SgFVffLm=TWNyq58)s3Wp~ z$F<VoavIs=`s<Ie8iXxP_X!vK#Ga9kp1R%zkID{NvIt;vGP~?cxkYT;+x}fHZwaU! zQh#Luw-f;v=gOb{Dh+nU^fb+*;QL356kQnzs7eu|l24A0k7(ysT4W&1EA<#S>FswX z0K!$$J2=0IBXrp?UnE;93Dv>3fOi5P)b0IQKVx1&17G8e92M-E@ACj^@v3~thG|C? zB^CYZX9*T4ze#v0-uMvcTW=+e$4H7!uQ6yBeHLW0=)5Mc&}vpA6S8}y39^N^^#13T z1@KCW7TwT1<;xwP5mhjvN2#Ka1xU0{nORZ216Ffkuoqz0D4_xapvN)zcsS7|CsR!b zs{rIrh$ss&JloKullqNXISmo2!M{*<qg>=M`g}gIsG`YDMfOpX%{1$bvi_ynfs$rD zAw0+Fe}CZFx_lq>t@csxa)cDJLmHBh+1ale_aqC%-Gp=OVp+H#LOYZL1*Db>)IZt| zJ43mEzMhcK{9PkpR$onDL=X=?ZV69R58hC>dpf(VGQ*>M%WBVxsBGe#;xU<Sy4H)^ z#GWug)SSK;Qnmi`iYblhn3nT>sO{#A{Uc@NOlSt?!f8^1D#Wj_|H(Vs;^mr3@B`$7 z2y<cO_~hZ~D-a<yg~0;`W;MuAgyji(mJ=&zq7Z*jT{5i0m7UXN{l7VBm{fD?(Ja0Y zT^NdTPhmI9B5=|;tJ?k4wNhS-4<*7k0f2<cwmGVku1o$g(uvR~6~~X5b#4$=;t58L zQ5ycLrPccmdW3|^718SlXIzd1mPl!|QGALr$qDt!4p6&=)!ITSXJuL!6g|6J{FHwc zAtO0qE0P{M$vOmC@BoxV^w1ycA{6o^5i2En$C(N8+q%thonLcrDlu0##Rja4<QWR0 zt2mVw5p5c?0q~@M&~V9U&ahL}j;RrJ#@+c8#dV)oJW$>#6JJbAoa|als11RNKE8Tc z)rpwbgIRfz1eRa6uvNm>&K-a8<zkq70Za;Voorfr2OGX!N1@7O<A4KH35v+HHVZ(D z1h$i2Cdl#0gI44Cvh^?>IAl%7-%-R_t>ylam%abwp9_geow^mx=1MnI<sc@10YJ_E zG1vnRcgT|V2qzl>{PuVq@OanO$sB;b!X)xaL{8&|lX8aTiFe_@$iW5)a)|fFPpqqZ zrGE60X&0K?q!7cbAGN_tj9p>*cUPQtsWWm=DhP~QablonjdxT}r)F4%KM?1B&Z$&I ztz4uXwq@Ji>gV<Uj?bLAA9yR*LzQdy$<bK+oMxN!$-^Sru795z*M^+Ks`HOjvLlR= z$&psh#y=c;;*RR;?q2yCE8Hde=H8#$mpz?{KPkIfY}_BI_(MtOTQqAvE&iklvBANT z9qt^@iny@Q1#&S|NisfC_u32`hr9uO!|1yp@2GYPlcGEH(JR@6Pm&a8Rcf)n-}poY zI%I3^+Zj>bVO0cs=^S!`U-Z_jjp~{EgSbpeYn_X|YQ!3JpH$Ui;FBJFM{1nFFH#xI zUp`OFGYUZHA%W5O6&Q-~JXB5=xBN#nVv2^_#<5#pd8NnKIQc^j9^$(y^K({g1FpGr zB&Ip2w*J|+P6MoK+Yc}W+U<@CV-bzK&yFoox#l;PFv3xfRgFkqSL2rS%c2$^bZyMg z-qcq${&y}a@%VXzYdxb2KR@)E95+k8aXEw_Q2ISd=$LbyPBumu-hL<=0&Gen+w|FG zVLqDwleKz2+U#*f8u}9lLMh2eDd5PBjV!tjI|(K0UX2<26$71Y{CB@gZDn=nS-{eR z|6D$*I?x>)K3N=J`Jprm8BzIXt6zlMeBLq4w;5;hEvx66q}s7hLu2xmpjCbDpOwRW zyC{9;kjzbN;*q{_k$syonL~9{;qtG4+SH0d2lz8y$=+j2sjl9V|14_f()A_=y(5Lh zunYcOXF>hyW41c^-~gW}z*(iXT8RO=UH!I4iUwOW8Z?GN51g{l1TK63I(YLj>w$At zc3H#m2Hl{ox-<>5k*3yrA^*^f4QSv$i@J<0e#?U2cwn`=7|9Ta0X8JPG5Zc0Tk(C^ zLsQT^Ghh0_V`;?iyQ{99M>^UL5;G!rv@9}Ja#b-^2IcTXYk#<jd+d*3v2lCREY7W| z<PpD+`j+8HcVYWD%gFR#VU~YxIg5Wp`>v)?K0m?Al<<!{<HQAG@v5%1sAan}#MrZ; zg#Eyu@W4^&P|t9~k;|fbsN$CZVBan3aA3x?m*fnlfMzsdgL^`t)bp+5#@pr#l=kCp z8cU}X&a%>J5wf{ZKA-jWkp`%?WYu>z|D{C<$w}7lh^+D}clW9!4xnm+BSznTu!KyT zi_Z7S&!ZGZ#V${>NTQY(N1@{59b(HiEPcM|YKf!(0WDd+2Izx2b!$O&LFy|OI#O%v z2@?Z>O4rk*s)}7SQOgtQ-p$rwz1IBAmY#Efke}H8<L=J6dgB(9ZV{(E{iv>nf*gIE zePK`H0jhsZrmSDL$l^Q7?5Lg+T+c@K#1+xQMDXBuxTh%ML@~3+6q>>>tvEb>7tt$S zm1=Rb`B=sWp#=5R?{8R=F_^h3dEq{}oQNYpOp22N(g^^PQwKGkCO6EZ%GXgk1ua+B zQBzMUGUicnBl!WpOJ$z2fJ}T&Z9>k7O|I-iA$!6_B_u)ZpDmHm?;=7(9J#Phtl&?A z)$Ac#wk3UGK$h4Sk}wo}UO*p%eX@Z<2jIiwx@snjJuX<&{2)A3TH0*Nwl^e;*<Td% zh%Z+X83DZGw{O^H-IhnbwI2aD2Gg2q_FLh-ap%?BnHEn%j{3bpbz_kCr38{1Ex(kJ zhie}fY6<l<50&A_OKO%Kah47ry3*`aOiOJ}e3rTwa+~lZFPtSxHZ7@`XDLzS^|hdA z4mH&;qtZl-wu`Hsr`FX{Z@;dc+t&IYQ#Cw>Z!3e!=V!RMse0Nz)pY|y&gx3gu)EhT ze16jY-J8DLY}+DakK&|l$*d!Q?b#4WA(9w<SVF%+3c(K!Q12JP`PKzeGz?x8Euwfs zkA4}xKdz;_xrC~LQV+KSf|SOr>f!sZ1dA1zNGdR=WDhm0@Gb21m124e(9$MRD&JH7 z4NadBIa)%&PfVcnk;ISlMf?9Q<N=`qWqKw;{rE3d1nwWS#9x%z6w7+S)#4DJxdYi; z47ovcE@H!J^>FSVn~UUULZ2!0nBxHZ8G-TePp{sNRuw-=%@<Pu6LC%a4w)T<AV3>$ z8RqBX5KM?mG1K^OsmpI~Y6C3KvmiwTi5l5*c`Tw!n>Aq~(P|Wan}g;wm%qeV^m*;G zxyJgE&*KYwL)HSLJ))B(p74WLVBJ1_!I!b%=}a4+zSKV*G38M>??GSnDDu>^*@XZ= z+r5Ym;q;-Q4=f>Holb!in6qn{!NmED@mq63x0;ZLv2^sR>O;Q_sd~XoB+G3|&;wn! zvRj=qTyRoZc|Uos_iZ3csX?nQSMXmna*B{!jP#(@=d7MOdiF~FM<t252AeB$+G)ex zeLpOAL^8#`Okd^!EVXZiyT2?_bG~==rPyzpQ9V3g<e7XtvHwT?-6>XUoEq}-kkoZu zh62-o%6`7tBl<^=gY=p~PSKE1aeUpYC%uSxoXnzKN>Sx?!2a(WErCHm>2m)pQ{(nu zRw%^d-k{23Y?j=OCTS5qfvmCCH$+n&La%ZP`VjM;vT~6!vu_gBr^F!3rfj(q``*^w zi}wmj8LOBhM|cU}XvwouczrY6{$OW{Me-y3XcR9rom#*;r9tyl1~~dH+8QOVSnejJ z_dH$pA5zf8*m{xeXGNs?|GM=`Ma!B?^-8ewX?r6y;2B9YrTFbcNeE-(5R)+X+F}P) znC=5`ZHW<ND`N&(%T0m&#$=}}SEM<KF9rW3|IoxU01nh0LOO{ZnTjjP@_(K_C3hw- zcV)qPey8N}f>`-ddb1ej?0n`YQ%8o0NbyT-&){v?lRDFc*AA0DMQUzau0F*P^Ti9N zIpe2+!FQq_i=sCfCn$@wki{a>;=NgqZ{`M9WZ&NdPwdzeN`E`r-r%f+J62myCwPk% z%KK{jY2U-;UMlTW$0Fq<2VN1}-O)^;dUVl3F4WH+c0V^}Slx?<S~0lfhib2_H{O3k z;?l#*$xlz9#!lLw%fHjBeO0|9DDkAU*grk-KA>Y7=G|%0i*N}We|ijKNzFiF<(<TT zrw6aVB#qsyOlL}ro6%)P?Ze&Y)_vAZs}ZyTG)Aor=|D%L6=#p7G6Np1rqt!iHy+Y{ z9Le%bpz^Bu9r;-x{FUYA&rMh2`!Z|gXKz!id%M9dD=^i@>4FzY+2nDYoAh6Nnc--@ z>|{}HU{MHsQ!H@PE08ujeO}I=9s+;X3_lhEU!U@~+O?6k?nul3C$NXy8<G~S9#pnr z`S6!OwT$gI4B9adqpl873&VI=xIYN2(VVusKYIkgCK)$>JhdpJb=?Iu{(Qd(OOwRY zR>zqxcb+yNU$dh|9;s^?4D}dg++Xcje!HG9{A1+%sWbO<8O83Sm)^0gfk0Z-TFF+> zR|mKi6%u{b8TS!&x!kKLVzPqA&e+*xca^2h$krVcS4O;Awx!pZo||RLKjf&Z5<Is{ z1BwTSli^g>#nsJjK<1@+>OhEJv*5D^q0d!Fh1nMDjfIC>H5Ec{Gc~G7Pc8Sj1BX}q zXoE&;=k$EU&xr5<V!qB7{$p81w@7_uS%DB+D!k9^<Y&VR!g4*M9-oT1t+9VuzjALQ zU59o^PL$|%_)+8m#Aai*nemG@Axl4p7AyAS&b!v+g6GGiKc9-t+|MUzy#DA^M0%ti z{h0|2-J>AS5u3)iQk}D=p9VfFIF_xt^<aM3gvjv~d|WB@yYT+}qSgJiTe>rah9|$g z8yoeQA4u>xw6PGfj7p*#6t8k(ezTOv&fI0?D1cD;5GWr2D6-XW$ud2n9g4V1`Z@aa z@waagnb8OCC%Lo9eS-HmLW9+q_MF2n<LygAZtK=aOTz=s-L&jUBw_4*wq=n0U*(Iw zlob3YL!w6VI;BNxFA~~U&Od*B+5N)hKMRVr#IL_u#(EOHF=;|QCwXM#kJOtUhV_2i zeW=U{%T19}jV*apMXOy{FWv-DcN=*QI)(_<YZPOIaHc{^<9>?x#nb<xo&{JWfgU%% zRNPd5%mK8lYRUJM)^{GBrc*Wu2&z?dWNAc%l&Uf*hH<fi>cobh|H85eo{tnbwli>i z^tnZoes<9==fQJjH?4R3j=Adlkbh&}*3_qb)`Pffhrm^t$G4O9RDbl5ASd4z=U|ch zE<e)0R$?xkbrNgcG2@#<FQsnzbEli+41&XcPKR0e7q5Q3$Be{F+#<1mk|LrdCHQ!g zrR_I=*qrte{g+jgFs)WjmOL-;r=add-N^cSLyNJzjRGzm2B=gam3KWg?k!21&|HHx zbSyK|Z(Lo9m?|%IFVbx}b?Qg^=`R`0mvX{%yA+Fz&noW!YozxXF)BQ;$dUXIl>D=V z2`B8!lLi?<&xRyh*DMZy3r#m0c;FglHUGubBp@K|&7M!lWE53h-ZwMvt1i^_zLIz& zL{<9K16>OdY#nfi`sVMyi-V|o1EA;E7Y~22eT|%kw=7Jz5VfWBK%+qx=IgY1(5r^! zZEQjZ2j{%Mz@hqF`pA+CxR8E~FZ9zcsR|CXGoI|Tp0r)3S1}&XusYvgr*nQ5VWW7R zw!=UD;6%J6IC%eTni$%(wcsdT`<eGEq-`h0q<AxP{EtqYL_NPTopMzU!fTVUc?}#l zmkqt8_?khB*eTy<={-6pv~W4Az4-lKlt>hm`lR##q!+_sHa~0cDx%unJGJ&*@q$F% z$`_+QocidZn4ewyzf<zAcR8h59BCGRKXKXmS8)u{{1a=jO;67xTY`9*@)aWj<x{(R z4KRiR<Fr)d-{LCy8)s1WjE#eHJ!gb(L5gmiL@*_f0-%;B$i&m_Ma3B|x_p49w?L9@ zNW^pLRPj%<)vnJLicAr|J(WUrK`LJQB!<X9aussmGDBKOROSE)rRiQ1TCYmAx3~sX zj<F4SUTWoK@rpDNppcp*Fr}0Ye!OQX{d=?eR|7|ueo3Ge!oI(dM?dZ1(J%|=W-2?R ziTWU^C_oN~0P6h{Do_|DzG#3A!SU?V(Q?LWew*)J4Q8skK9qfZ1`mZFCg!qt>$?wR z4ItThA{np1lQkQT1eQLx@;n6vjv}<X)1*XhrKhRt+uiZFVUswtwKkD&ENJuU*TkxF z1zy|rQHSiODtczTMc9)@W9nU3FGu%k=Lgmn|9Fk%!CL(;0Z&EVwHoV{SgDF<h@vy4 z4e`fjDZMx?K?I#w)~yYjAZVf{V!(rEk0bc#ejp#B-*5a3{1+7@pp>22H{p0C8GN%d zqrgi)(R%!3G=N=>i=Pe2#Cw<U0(MrNf#V8#%Go|wN6cf&ZSG(bMXvzHC&3JIEHBR0 zNt+NDsUv1kZ0(UJ!HnJK*`X=oeQAO0>u2f=-rMceSyK*3Q0&8iaw~$1)_i*)>E@A+ zqN7v*thBw5F^;Vd$0sS3rF*xk9Sl~>v3N#MI~{*hMN|QA4d^Q1_l_%7iisyWqk+J} zNDusloc_$THLvU`_iWlRC9?BFgL4i}CVQWqPoO6Yqr}ZILyByJDc@_-v8v^G?_q;^ zEY0&27}wm`EC+nOdTLzuatFzy;Ady6ix0n^Gu&6ao+^Pi+Z->kmV#nK2pk8>I21wQ zTYCiIAAMB>km`?wAQtT@`~Z?TekT5qo2!VBveL^N`sXGG9(-4xJdJM<@2ex5+lY%b zA62e=(6rwnZA($^f>N~X^93qUV@4z8O-?=DeM%4E;k->*!>t$C*R&**>TKK+^OkQ} z(FAnjQC|jX@Ry+DiQ<u^$i#ls;tqtzW;Z#%Z(BUj8=rtCsv{60%>dpFLVeAR{T$9N z=b=T*+w)B09-RhuKfQNxCuO%-d&+Fv#4kfPGxAY+ENxqr0<+0FD}=4cBk{M4i4jZn zp@~t=?-#Q1<cnK-Dw%6$zt?$C?$<NN9oj_j4jE$?Ry$va=DkH6|GP~I$|SSf^gF{q zDS)xaQxj3D7EJh~r`N|L1%+URj?Md_@0Ux#+ih-q>%94HU7{K9zbe5{2Ly!!6Z-ZM z^2Ot)5E(UzDaca8Ppor_Sp}mjX}r|MkPjzND9oLlOszb@k?8F2Quxa`#|rv|LM*EL z6dQkJk@^IHGS}(GeCvvZhVm<mdPrEcV%ejZ50P+n{sIsEPI}aHL**KNASD8B(f|4S z^#)R}3tJxN&Ie>exn1JR7C)Uc@c#jx1dHXq*2NJ6K}8a6KqBwIq6gSi5x;PNos;So zt{mz;^byci$-%x*(1~1tJ#rJdTgM18j6DQgPHNH+4`fS!$BxE96P!p(XsqZV{6(nQ z!Y`$Bnk;|9e{60(vo;o3ef~qMalk;lT)VME1jrw^bPDH_k4Lj@Hh6&jHgq5il?TdS zi7i*Z_}!`E*HRKRTjH;Bxu1%+tpp+@<5!G;123FPvT4n%5-h#-vIe!v*F#7(t7h1D zzun^wVT%l{F}iAlYQ@{-BKcs!i8o5B$`eV3#yaw+ksR_;DO_0+kAi=%1dUrV#W>v4 zyHLD8#)hrF<ZxGL2Za(CKZcSd;!EX4@vFQ8bkSP@R<=R-byv25ZWHxL{+ka(BPsIb zAzF+9a#dR1HAk}gxZ{?4REUZrz3(fjaChxd#Ek2NGBIezOI|tgBxsN6OVqN(<^`6j zTuRrpkg5(2&knU~)AGM(!%gM6OaTFW8t!QB!PN)WzDIH&p%*X1wOaNTiIRM#5D81? z9sJiiff*SfEq^v}P#59eqLw}8V{34u@v(_xMGU`2(ORi%Q%T=gP)>`KDn{SU2GXK$ zHT7CmizZsEh6*ui8FKJY6RChu?KM$C_=5z{M>H|e&_~2vBpCfSdk`5VAHX!`u~&cs z2NYm8zm1v<;!w-uJCMR(F7-1N*ltzl5c>f>jCqfD`B{KHZ?{?BF@u3;9f_)S#b7$Z z<8p$j+e1!AM<$+&my4vueRByo#%Eg(0QZ=;<nLYa7HK@%l7oL_6PJDGc#5t0t9X^P zuHQq0lo!~Fo_B?XSc&)I<^SMtvSIMa5=n!N)cqA0^^X7s@~P2N@s{&N|8;A&-_JyS z@m}5Kn&c^zy<~^_ohezV_)La@k^C#@i%*jU?7PmoS1p?aHUcqcemM?wQErVYOF|Ns zd<Y^1+_xbG%MV0qbVCgq%GrHQnDfIPiqVu%nR|CnCA6#S|F^9Q7%adQHk=fdbOu?k zz1cS))QjLnz0&u=_UZNER<Jcqs?Z5=S~t+qsv(^mw|sWE^Rbd4S}4Q!ciGrlq`ILt zsX;5X`_A~uVV;u94krE|*Q2JfyS_teju{wLd1Y?vi2AYcr9)z`h$mU?cg|}EINW0r zZ7ykHfzyfTU*nJCP}PJ}JwL^{2zewNvJVBfGc6s4Ucni5;|P7QjlQY>(k-4B*d-qG zkyaYWSgXPb2HdTO0M;P_q1$``v$ta#RR}h=w~_wE1LD6b?4M6PjG6kNDpMZ4kmmb9 zUGXzdEVPSfsQruF_Z0Q!MX{V+{TJZzrhwzmLP!p8dh7b!(y>mb6uoR!QA=ls2NBmT zM}PDUN?+17y1;Wmagb&JrSY~G^ppQ3pDL)zSQ{8o{hcEq1?^f6l7^3+f>1s9oWVuU zMEhtNLvnIkAdL6AGP$w#nW5aw=$N;n0vso6@%`h>m+X)#ox#w&3N&)sa8g>H(R1y2 zrZLpd{7|(|_my7Exq&3&)qtL&{RJMX@S#W?kL`H^G3%m0?e%_#7s?%qin%({jP~!C zy>k97@tY$mPk}0@ZJWoLMRW2E`tn)w7#hZ^Z*wEzF6#RJyC?ZEQh<4<A>L1r`ozgb zv=qzSIc%4Fl34mHqvZ8f_@xXRv(j1nl9br+(<-S3rhficdQR1D(*FB;gcxc+_)<L( zom6b$$1c$XBylBqr|}fKlnUT4JnQom@jMQa#KYFFa~A644RDw^oNFtOgaR9Qm=rNm zwjgj<D6{XbHRUi6<+CHzw_}^MbMC!M4B=UcA0Y}Vpu%{VPFEql50cM3+#=#C`tFsn z&s&gTXzk#JcdfiSa$;lOConrjZ1)si7V?i2LwImRQ;czcenhLnbKm`d3x&j!k=Atu zozFALRSph+z<(fYZzZC4VgHZpL|Njyyh7etbPpN>$Li7)4e0V64A<xLcDU)Up5uX? z`9I_XP{ka98b8H7xH<?|CoZ{=6_iyN{7^0*1}^AL41zqbS)5s~DzpJh8|tU|mEkJ> ziR3>vO>c7;f{A{tY^j|B@+23HgfP)?A;t?Ey-_>SfhXuUC8AVqfNE;sCSf!TeKJ+5 zE)W{?(glQQHo!&ggpDwLYLNonH~6(0;kQ77s9#Uc=%hj*6j&e>D?#aobZkxlPlIFs zjY8|beaAYfK6A%2crKQ2niJ?#S{A6F62=f(DYKzUWr_04N!i0=IZm_bc3K72?MrF# z#1FP}@r8Kq--5)&Ts#>9h7|wZQTUZ>!$Bf|7^-$%fwkJQzR@s5R2l&N96~1ldNRuO z7<#XlT#U!KhPP+D;C2GM@&*Jf_T8rSD_13`QU`<WGvrFPU5lF7Qf5%7J{FhhC=5fj zc0q-p@Dn9~yZKR3n&{QqtqxcRIZF*Rz|}l#wv^|f>V<Y{vrA}(W?Yf%_JF4!<6?-! zIW0U(m!@-TiZW}D^qb^B0C<(tdgljj$V)qlZ}KWn*oQeghC?+6{ZTB(x?`W&gl3S~ zWRI%%2oD%A4v7(c?G~6U2~d@F!C&}HGTfdJ((|R3XmRmlZ7lu9xx+Z`0DOFfPm7<! z9~?H4pxCH9$m8N}BK3+mpg>))FF9l9mP*!@!>m`>)U*7Q;WL|o1X-GB8sNw`S-f!1 zJFmn>$%YWpYl*v`u;Ab&=}j=p2+0LPvnBBYj%RMj098qq*ls3}(~m1@3IEW1Rq=NN zaT4rPGbY4Jy||5~%M+o;0IGCV(Q1c4pg;SOVWomjsiNJ|Nk@fqxpaIkG*udovpIm& zR;btoDD9Qm6p8?(Gv=?#zBb<qd<|#o2a<92ZdFpxm7SJp`$P<eZ9SjV651{DByl6w z4qcUGJ#POJ4Hr@N#n;Moe#wouKwAG|*zhp>BIF33>R@PJ(0>Ij&Zit=>?xSOgs%It zJSV<K*eW20)Hb0&IYCKR*})pqFP3?wk-=Oqvj#t<xeTQ0Sf{EG(+EptVWm4I3(C+t zwa#aPSRr51#20>Ht)SG0lGPe6_5|Y8#}DVujRvInoU-~Oi+7W_cTm=&vl1Wg&6#B| z035j|I9CoeF~r~$0#I-GnN1$TY>iWMHP9J)QBr*7?`-S=T~X;B*xKjfpsM87D{lOW z?3`S`J-MM2P#Oj=>run!5-RkW%6y;7b!sB>_s`+up-xjX1IlpKcrWat02crLE6{Hu zZ@br`U~nU7D%)Dk`h{d#cb3U{QF6&55`RZJ2%k248p5Z2+_{J1ribY>^>eQGPLjm* z`S&>yW=En}&L_m+G><oWok_$65qkky``yzjYcvgj+ZNUzft6%~asUUfF*rl*KN~Jx zQ}=q=&eQ7&6sKfSm)dpysYk%oK23Yhs>)4zr-}mK#hOx^Gr@vl@0Am?z+Ckn20L)5 zc~VwZj7Tyo9%v>xkl~_1#sBlHMmG@iE^6W3xbO}Bv!eONW-Ei<1ET8L@27>+zn9un z4G`v0KkNOa@tT)(U-*X-PqN_&V*7Y4W5QD2%wbF)+Z!XzzQ~96<jGjNjz4_I`Mt+Q z1!W73)Y8=ixA3bAIzJQX%A5(6l?SyBdH7dn-xq~DlnXS^qchNp-=z93jZ(VP6Q75b z_fGRZ|C%ETaF09J<~Q~wjSGk7p0e8tBY<2RxvwrvEj;KwA9XMZ46;#%OAo{SUY9PB z84^(|6gS7r`x<d<M$zfu*02Yz_upRFx&Y4@BY5{=W2Fv6EuSxbw0OvvRIshEQJC^b z`VthbzHv4>>YRhXw{Q#ImrO4!A(p8){A$>FJO~}%>-(X9yN!`bPJ0C$_`nvVG+)>B z1^RO!I4O*GIY?YAy|gF2&$t2Q`g*}XhY}Z&ZfLg|3c0U3a9Pa(Yd0l++FPg<peiB> zFEri(mo$^}DT=G)XZRkfgAYQx?#JTYTdy=D`2z8N+6m1e<qtJAHoj+Eh#<t%H5b$l zYTYF;rys?mAd((<Jo!o$+ZuNcwwNJ5sXPf1<!+|slg8*6qI6-mB&E1X9PSC>3fJ=6 zf4JQ%+83GUf7<-4WFr$j(kJFc9I`otWN??h-Z>-t(vF&99TR9hZ}T;>(Pq5lP}*Jm zDg@}GYZMoOW5jA}mO_2c>-D~@jv{j51HOlTlO}wrH-Ah`Ga`oJ$}8VBLAYiNRQdE7 z!RW#}A3wVQ`wmV5l8(mu+4TYwQ7p;xI&vYZJ(>Ku5BrHBcwszaWli{A<fMxhIjy0b z+#0Ag!T|K|(~!g7zffnIYe#x`PMn#$I#thY7?K%Z6ko1L7wuC~_OXYc%!+k^NrI9V zujBVsnO-4O7}3in>FYzdM(vAZbKhN}>Qhg@FWXzb-{UPSp`mzeD=twJT)A>yzBtxQ z4cPrb8J&Qu!0{3cQ4&M~;EKk~i7xP<bJP2$Jqh5XFpP_+{h+DJu(xTp*1}=#33Eaj z|7#=~Hd;IQJ%@MEK8!;4FFsWM7gERc<rkrE5e&20VU3elT#5Zk0{ZKNiVpuY+|A&4 zIPTY5*ES_=Z@V<pL)r+04ZXvzydk}6hW252K*{pSk6H(>E5kn=S_;FgRg>?(cA@O- zN%fr^-E5X7dK+v^Z?a=@kT5tzL>J<_dq)>CAin1iK$(P1w)i}PHx2i(TDZOQ+`O;6 z6+17g$O9^$=UeA}2x>?1n{;=zpE2`jtWk8-ty_*}Jx1Bxj`L$1<1-GQLN3J}r9A2j zF&z%I52HR()13V*22gcCqI%R7!gg8L@JSb59`&Dnt4xiH!aTlX!_V_<NxQAqRE#}m z7<UqXa)xy?`yl(#jnTzpKw5t0)c+1lQ;^6fQt(dSHnQw6RNy?pXK-oywheWkq*sy2 zjX&!?;;iz8smM8dUi}*k|HE`3%5`Hy&zN^SVmv7Jy@LL_<47M(l@Ze96n2UzSN51< zACNEn0d@Ml=}4<kP+^qTrlRHitEwgFM`oqh4jmWzV(o<JDu5rizPfXQz|l{F|FRR% zWdAT8#Pp>uW?Ieg-yhGt22%t4R_tN|pTDDMH6E5DX2pDu_2__OL9f@H5oE?#_9i^* z`EvZCgxSnYY0wwPvtP=KA3F`wAB{lsgk#E@j{{Mgsvqe1dgxP&b-on?i-87XcO&!L zXULwm#SfOSp4J5o$$m2%7X{j^n?qA%82#hc{|=AzFTGFy<W2znyxaGC-{MTHCHiug z#PF-Zq2RANM{@o!qw>5!0rlhw?rYnL(AGY<GU@W$kRelrbfnRVHD=EITGaHz&vbSx zdG|?RNIX6}HgH34dJKwhhXS0Qu(PF;I+aLO7I(lvKL4;i45wi1WB7fLRCSoSthM4T z`1T<@JB)$Ymbl}g7?k2n`*0>;_%?VXyF-<+r-b-Z-#5IZgpc}W*IfOdO5cMt`$OaM z`bQtTHG9}&rPh9?*c`-JJz);pI<n7Bc5Rh;c^_7fS8lK`wcd<#*nRR$xL=DIpRn=w zZCPw13<q}fXfk`0^?xg;&@G3te67;+)rBJ`F~w&vKeis{n(cemvJI+4`mVhSh%xyr z>`7gWw*z^qY$X5UC`I^oeL(jRWL2(Qkqg~0#>X7Y?TAV7&f+SJsq^sG*Awn{t&iSd z491(^-XN(o|I07mQ)~ww%ZuREB&bJ8-91|OzXyK7u)w!>|D-q`+*4gA>~@l674d&e zo;e}vEB~<uEP!T$Q*bg8pej+WM0ot!G5o#Vf7eJt?7-5f3vw0d@WY1QQS3!L0d`pE z4{YH@Us4P(5AjQ0EIcNNDu(FZ_m|KH%88LszrjQ-8KHuQUd9U1k0KsoNdcVX1Q8Y4 zcwpg>L)nQ87568i0Iduwy<WZsqk?qnAnCe*#C^_PUGn=u2qkz-mK~3C{39~>5=R7( zo#E{feu@bK^5{{`2tQ>Yo;U1Gd2^O(FF-^q-HG~+ce6d!62OP^IOk;${M;_?wf?!W zyXiIv*1BFV7H~{IIM4P!o1Y{s^1<Nx#6m*8fnZ0}_$4JS&o}W}`?ivjBw-Yfv}Dzi zHC-AqT74zzIbPrQDPVlOei)~#KzZnsd61}mU?wyTP(`S2Wnu^$Nt3*rH+~!J3z{te zPyn@g6rjR{55lo<QGi5~m$@Lx<gEz_3pm(sVyjH)T_&V*14NAw)d)bQmY8s0fUw25 z3F&xh+T2;u6Ci5@BnsFnp#kxIc^%_U>Af#U>=7;>u#U*}gBcFdYt*nmM>bvlm7U^& zNIWgSLZ7W)&@Wzb;q?|r>ozo9UPDG99P0rX3pPx7o=-37Bgrcp0cqLK)#d?ilRRmw zv^wJn(i@I`EG_*3n~JnUE0&E)BZ+ilS*8-barq)v)e(c|1M>ZPn6*eK6es{fBFvK< z0cvFu-2_=c`}){v+AGVOQz8g#u3_PC&)#-pXL>>be~70#Uw(&VC^iEbx2?z~nIX$W z(dMgYoahkzVRG7oM=uhhM<&#qf(nkd_8|!;tDluB4U#MLMMRE12RLmdI^TC(JYw&- zgmYZS%bk1yvwf+mF<MAdx_sjAn!dJ6*W7AOB?%a2bHaXkx+$6(hecr<<j#?lGP`P` zu$o4Pm~=&?3*Ahi)&yx@!BIe3015!tL&2|N>eIbQ1ecbefdqjn!UC$hoOp=IRA8Q4 z^#s~Y)Lzpb!mutUP?%KtTNrauB|C(^l8*FWGV&3v%X}T<3P3ob3Pakn3kj3qmkpn> z!>(cVg&Pl8N;}F`BQ!qVJ#4(hiFG@6nwORz{Y{j}TiTjgX31;hutS@DkNIj_D}-mk zNfsjMRviYxX)c$2h%r(>LS6}5r`<P3vbGQyF+#zGD)}UuC~*-katl!cqf^7G)cQ;I z&kP@?BPE|$(j)##v8poGm)6SzgR6)QzX98HbIJT%ou%oZkYoQqM?{X<GY!s)UQRWe zz38$~xbs#QRhl;%uO7G4AYp}=WqXa&u_qT!eazO^eTpVuA(q-+G*dNc-C;RRo4j2U zryH@so&Y<@9Nx?Z6oxDa%;bq$JrPONVghEcP^bgZ@TjYyk~@H;@#b7(e^!4$wKlW6 zDeXcl(1XXqrR1(7p(VKx>NV1F*3e)?Qe9#icJYdk)!sO7s!}pG#n=Wb;H>y~o~cqU z!@Rw1An6FKVR2jV6->h8m%9#j_Qw}G5nInHbR8p;6C_}~OGyc}OIVP+pQ5&n#PDla zV`Zb3eGnBU^xQA<%H@Oj;eQJoMr#7!EJCgP^lOzUFU@cqzPO7EMEW)xE<Y&7i+H8+ zS2E+S4eH!@ee#2RLwJf{o&vzGw=47XHwAX(tO~8!qQ&Dx?5}h3BqVSe;AltK_DS0( zizatF9TUv^pa(>x(VvGpWc@k}0H2=4D+|T7)mNHBa87$lx>RP`C-sm3z7zU^9Gg5P zlJ1~Pa!Xypv<qJwqC~dA);?Q?<v7C`DiPOLGWD&8N;tAibD6<+%+3yuO1^^fKsc<n zdFo4KfM%S-qq~NO1}RDrY=~5%dBX+fK{$W3JP--YEK;QRr`eMUF_GBi<=!KfwxE-E zImq-|#!E+<$XSo72^1{ja92`kk}H?lN>%4~XHT#<?b%uA2cDl<PVGJJ9+2OCc`C>9 zjMY_q;r^<hG6{~Y5Kj0t|M$)cJ?t>;Fzn=o!KUeYLj?;Fz^6)@zkLC&YT$3?XsUuI z_sbP+k0&2gKRL1Wz(+3(G&EMD1?#E5;7t||GDr`$i(yg+MLkF!eO9J1Crmjx!Cl$y z#-F9T#utS|n|}2f%~B<MH@{s5m|5@UTk?_w9!A=Ce>#ua@+|}P+4-S7+JPmhhjo|4 zv#zVU{7h+6b^z5milkNcWr?~mwRAX(S)%l0Um-~?MR7vvoL5IQIOI4@kT*w)3}nF- zbA$0l)TIz%C{!r$h{eK3Wd~jt02mEsnd;F{jtA?_K0wt7D`rPC(Ly;75)2OP?72Kt z!w5a1;-2=|5<Y;%=XE?>-Rd=$HD&(yBYiQzbLAHC1R$EwW$W!yke}_rgQ!29|5BCI z_t{@pwZfjCIG+>rolmlmAYQi+oR|AblJx2tNnmK<(_UkD(io3AOHg;91~pGBrzC2U zt@u^l?UG3H=kV4l024erE?3TTVhD&=(k0T{Jw}_Bn#cFbMg-xJ*g-3rqlP(bNAjFX zPyTm&D-_7GwL5=kDROt+FL`ZWi%**(xOG|InP0C;p`o)m{VfiE{Au^vllYHw@0EVE zmybWFD{2+?4ZUo9<8`S7;K$IOp9fzC-ql-nv0L5zeH3F8RVw%xW+*s+HmSD0N=b1r zS~i5CrG__aON{y^t<X^@P@ZhKyoob->wR7V4KuKvvh%VBw|BX%W><FXGz{2thm-`4 zJv4N|FBz^Gh-XV^-Xm&?GyAqmPknYJ$(X8nzMap*whYMv#w9vK2G<{@vyPB}8NSfq z>x(>pw(_3Va!32JIMBo+`@1t^<sT4lV}tZb&2gZ#gMb38A(zUVSvs)(L{Tsl);Y9E zc%v6M_17jSP2NC*&B5*WKaNw!U$z5%Mc+;UtNvBOgfLiz<WyxCGyKr=YLs4i9!!26 zznb1NCB~;?m1N(BiJWcuSb=$JdyFJ0p5n-W0@n<CafHaXL5k<*&p;hc%{@`R@T15g zsqk))5QKV$d(<FZOU)`?XQ+aE#3%l7`I=IWLw<*jqSE1WQN=rGxoiD-@Qg*g(No6Q z0j`Mo46hZ;ExwaE-7FBx9XE2gzPhNdZn&wQc<KKbI`cp#|2U36wwaC5vzhza7MlCW zP1@$ZN61<3n_QLX*hMqf$T6jI=Z;b-D)*IyR4SD#p$nDNuk!Q%^UwFM=ll75->=vE zk|S5v;m*tX=G@odW3)F`rC1;n=iXy25`^zq+a9&^%O&UtT93xJV0p2)v(B>!ig;81 ze%-#U36x@POUZCn$-RCF@$+<}V8<)0yzk0(g!<(jkzRvOS%!$L)?AlwxqTmB<>1%n zSZlbq1q{UpHbTxS0-EVKb`3)DGwuW%x0dT+9fOOp`unL*{UQh`&xIM4hxtU|d}z0F z!3`2*5x@y*hTOq@CDt<c>QN@L32kv9Lh|$+SgWSs#2IPE@>+HPP6bP$=MSo4?deWo z1CLPGj+9N*wm#;5vXTOAz*E=FTR-CThRjtfFeq*OO0PA%<{^$i`16D?0qOWc5{M*h zYO`)=(s1Rpo1S)c9qa$W83#ZZISL8b=HPI^UwFRCmGk(EyFT&qDG@?3bqyDvrMz-| zV{pzSvB`UD4|X3DTnNI+;|aQZY<50Dw6;*dlm-(!XaGdxFwF08f;3J$fIxkuw+@M| zc(oY`)t}gkYr}tulv~YQ1+MuEszS(>jC*ZKUmmT!9VQ+T0n|5kgUk(BHP`+xBIfyc z%qQ2vsGhDlA;(o*+=q-7$lO`i;t0my>h;>GuX6kL&cl0)y*T*ZJe;l47X+n_Gw?ge z>G^|w(d*aoh-OruNa1KW!JbG!(6vwt!ZHhJR4*XYyBt4$eViX+=OX)hWc5m{?i5<F zC%UDdBOXCtjR<sDs`)XezPs#BTKQNWmWzii1d<leA=+mIr*_UFO=Q(hz!~*ZEx$uz zab0sLKLF^S!*yK4?|A97XHyQZf58=#RZAd$f$DuCjNM+Fn}v}ZB!X$&Slw8za-v2I zZ?~0=VB;8$?hu6MGekc3%Y2K_yQZ%5o10iUBquDI+68kuL2iz~A2F*^%L}q2tOtBi zJS(!xz!E+h?LRI!C3Q_u(I8`|whEuKpcXMC)E=;S15ga>RW<(zcMMIjegyMOkMOx^ zzP*UEZpIf-!-(UN+)SmCg@2SU#C~T&Aq6F}&;TxIvTiU>!(?(QwMmsa_VX=ne301v z@%^l$gIRLtlqC}B_^|6w<9g(tJW^eJ|3j5(&uhUuR(xp68t2@=H+&(YD8!qpM(>~E zHJ7t4a+G%}RBp6pEOyau+z1#{pL$2(SB$6BNcQf#VN(Jpe7*OSm}q@Xl5zOYCa#uP zI`Ndkt9L7SFL?p2f)EDEM+tw9T>xm9xkI=<q;xt)(d;Y6@}`JFTYi%e@W;yH1?Q1u zFDWO2Tmm7-a>NRH=miyGUKM2MzE$EPPI2*mHpO`c83=grAAI7&ShR4x_Jkv>xK0X& zQv?PmzaxTBx=TVgf=y|yO2*M%lD(=6<JbD1e6=sY+oJ$MoNLYIQ+QCs33SP6hN5Wo z)M+&E_IhN>a->KvAx{alCkQot0pAs|M01SEP;blbbC;mN73R0wUC)j+<LxW<9H@}o z!S-RjdQ|c#wCQ&C%(S*}B%+{4HFjPcr{{3{2IX)SdLu(w-qj_WvRtsBk^AT&yoWj+ z)U6wIT0813B}g&lhuX!+-ZI?c8q_prUmqNDD>)2zMW8=5*@oWUzEXt{paiId9uCD^ z+&r$*FhFJB!by-D8_-6mc*83wpd+CvcftExB<__EFcr0e`0(gPk;?67;h5>#0zSYi zgT7)<(`;?ltkOIC6}PVA_&8FV^Z`TAA-37$RX3~`!~j9v2BM%zBK5@;tm1Ma?q0z2 zh$hNKoOKREO!!z$%Q`Nl5cj(xP#_4X1Z~N<NB|&vHeB-({!hAcLoY;k$0*Eof;!x# z*`}9?v*trHl5B2&XRP-(f*EnM)%b2#mus=1p*3ON#VT>0D!O;f7dFgyxtgVhu8C>l zcA<)LM1kbsH@#uQ@&rxQ4UAnOPH}BdxnPG8<I`?T#xjF#GOh^BC1oky)b_9@FB}dM zb4L=`#Sz3Z2rx^JJqJ-4e5xE@Zgye8%V50JOhkpp*<q+P6!y9Ek;Ebv_UAouaPs7r zk$51o&@!As$r`_6V5l<t-F$1jS^Wj^G#}i{APgFr{4)aAbjt-f7?*s(LaNg6OOpAX zBBRRN7Z8N(-oX=*3$Ek2%H05JoEEBSr4&<V?nxSm8G*u{9^8?H><%@tv2F7J&g^|L zo)C8kNl**I>dG(<molV^Dvgj8=pZ_-MfD@xA;GXG$-Y?ScPloxM|vhe<~LVuUu&mG z^4Z9RvlY7&ONqGPx5WIo<eD5uDp?OMNqVZpuU5BQC$d~XF~8g58}<|T>gF#5<-7o; zio<bh#|gE-QDwNa9OUlHQR*4atyw1Q_P2JgZJVR5`bqhC?eh7seCxbQPXFz}Pn#RK z^tZhf^%Y4)^(R4yP23F5aAm<|vzHnfMEy8%eXxD?$}KDvkBt)-_rcqrE~ZTthJ9vo z2Aa<12l+<!NWm8*zAK&kI!!q*u2aAYnEqj~osZj*uVtFw#2m7T+7lGiJx;V|<-R7} zXjwG5hcn@$o%_!#;8;Y_C==nifjErgFIE=6D+=f}=U?VNl?V95Ns8p&1Mr|{aEekM z1a<t`1}Dmb^u;38@uZv@V;@sXl4?Zi_2*|Qs}mjnv!VS^wvYIwQ_DJv2@fOpmXIkD zO<sS&Le8mDT%0(19w*uR11IR}@VxESSX+_Zp*55dwX_I_-IkUjG)fbqWO`pLq*M&G zni!~}whD0Ob8gZ(_%KKvHHxd|w2wL$b93L<j4<fROQh6^{<F#M`P98KOMgWe;hyyc zd~-@43veNcJse`;h02Oq{WE#JmA<F4cLXSV)Pyd(i<k6_@yI`MDZi>eS5>FkRe!XQ z0#&-W3y(=b<$irlyqD+~FG9Sz%BuCP3}{sPy&y@GcA3fxou%mp_UT>0QN*phdPXX; zSK`enTu}aBFJ5aJTrrx|KjC7N!?^XQ)HZm5ICF3D0mFOFM?_jF-G1qXNH4YaME<1P z&2!8$TZ6M$YxN&&{laP;NBVU>+&y@&*sD+HBm}DS7}eK#c+j^dvhp=1-vQ3Px`q}T zG=e-<<v+~z-w*{-`-nzKI2|2P2O`M(57(WM>+v0BNkBcoStQyJvIdwMy2!$j>V+?d zNxRSE-B6>=uw{#5?<U0s7=k-LPpQxvwDjX}w}aEPPN<B7_72JLHw@};%ZC_4?~0dN z1>$_qeiHvim2RZv55u|~dc>q<xGl~2=ce~p7tb=uP?b9guzJb`se%Pd?8-;mY~7-r z$?%z26_G!|%T70J2YXD61a-#=C&R5>3zXeasz&P9GKijE<{N*BWU^}UCNvUdE+&|V z@1Uxv)*OES*xcMZ{(TS{RT1KP7tcOcDN`w`nyTwKe?5|-i!&Wv-8%;0YF__GOvO+0 z;ilibu0C)8l#_YZW8ZxGt9kqE_|~O|MHF`A!lNgQw%n)POQe&gEc|dleNDz7EsO`= zwz*{OQFBLZUsXZpUeu0CmU8k>T^GIF{{rl9wOr&^(n`VOrRNJTJiB(GcsbimUC27G zcu7b7vi<Ffrw)Bx&@{5k{Sg~~l`WC`RpBFiK-<Y4aWB4i8>{i{mbCtUKT+-ByInTo zFPRaSH)kg;cR%y=Oc6x{)!62pV;c9$9RtGxaCMB(=B@Mzqpt`+LcUL*l}f^#jz zLxoxv)iP|7?TghKO%tF@G@LO80zi(&$Zk`*^UKKtT86n^>NO(U7ni&hf@yAt>~sH^ zi%-8@wU`!QRR3&w%_2({RKBkMhqJxUzEXxOpkG1RH6hM-L04#%)uUR!<JQ#ZX;+ki zGW@^BH@rNYiS^h{Btf`^S!WLbl^2BEWf~$Y7b7cK$5jMvj{JQf3TWd<Cgox9>nZPB zRR1+|!iI=?rzXnsaL$T@!n$?)M~=qtdZw@#uNP+`a#ud@)vc^vt&yyrKjV2%xb6Dc zw-+k6kdTk$%IQ02*D8*v#LbT^;!eiQf6VJW_brlEnTWnxkXUv@Z)nXn+u)4HFQT4{ z=DmTKkP?E?q^QuR;4XI7^3>R&vcVW5m4N>mdiFOW7l4#B(CSkv<^s;|7XGc4q{dak zi;K~X$I|#9v~D^~U>xoBK}4Q@S`Z_v$mLqlGf~23#dT;!Tfl(A!A35SoFT@?2`}rP zl3XBGnTk6z4IX4~z#a*6zggZ~VkWTs`=uyN(;s?%i!k#sVuEgS!NlL5>g8H#Q6Z@4 z<A}?m-%0(lWc;zFJ~P-C68|#ksWNa;(_3tYjUxa_N8yllo2AS2<CeF*4}mBNL+IW3 zOx=VL5&=TTmhDObNLbPRsO&jXK+Byn<9ASyIme>QD7Sz{RdAXNzuX>o^;Tpdk=^Ju zImJ&a(FO*&#usWolri}wFk`PpT?s(enxO0t;+LviSqn&=;>2ekCw@DKEt016s$7@9 zSOE7(Ov4k1->TGKSDSte%jC4@xvS8sdaKuLR8cw*5d_WM)wr<G)>&!zkk+<S^^SwK ze}dHni#lTXNL?@gJ=Hs$kHoQ1O`t50F2&n$eIc>#RKJ}5XHRh_o%+uwi2SfBvklMY z10=ow03_L6P>DYlKp}lGwp}3>;m+pBP?vp<(@P|Cgdz-ZP<`I-8?JtQf;_0Nh_NJS z+(G!m^mX5Go;$G!<hO0uE8b?ORzQvQbbYR_jJe%AU*wiegbQ5I7Szckta0f%n5gn9 z1|;4=8}<@2c33>IxPo*}kYyj9oa;WJqzZ{wwTazqFSEcPlO+<NFK49k0-83`No?ck z8j=;Z=P9b<zWYTI26X2$an<ylNC6QndMG5FL=}Vx`zq}L{JeLl7(h>_+V)7-bOz}d z+x@(pK|!VjuwP`e!J^sZI|0Z~!6HvUBYTgPy{&f-zX?r`c&5INOkO8K?m|M#Z9o5f zNBZksv(jInD(z7L_4pIwVRb*G{xr~i<7L>L7-{U)%aw<zb^N7_aF@5pYVii=S{1Gp z6dkne@ab*fdD{<yFdiuc@!d*X9H8<`xY_FD-+|~TgLe#P$}fgMOGywUzXw2qjpcrx zm?-7benrAz+ZiETvFhgNYz-tWh}xy62|UbHv>~6VaR56-eyF?c%?u$>mAQ_)O!%=d zoBh7Pm@KvjCc32SbncbzBj;u>3#1az4sqxU+5cmwuKJq9i~`d|KeR|=9Ei8o^?$Rl z?m#>@aM$94aq_S8YR3;xWCol5<aU16)l;L8g{BPwixM@ebO^0yk;EW>24lM2?l+T+ zu+=}>aVcP-Y2$vGo;GT|fon0K$am>Ynd?_-Zkm(g$8mA|_1e^&UKAiXkhQRhPV33k zn62=0VF=J}lznhHEsf}V6`Ygr1Pi6Qj-GQL5(QhX<6x;sg#S-WC^y?p){ir)j8S#( z$j0gHMRd#B-n@<KcYlE#X#l_yt2uSzepTBX*-f*R`%4ZY`4lm>BDd4H;_x9TExP{$ z7|j=84_WOdO)YazZU?iDkx6820EpaieH85n6P`s79@6#b97r2O3^tYC73zZ9K12W# z`!D?CXT-CKivA#d|A#sV2H}WvUv@W^zBq)3i@xL+fMkiM@~hrsdksR|DY_X{9BM7| zjQuL;HTNNej4rhenyRQ_2f3RW7jc@t^(~oIv-ww{&7VL$5~ex=X8elOK4*C(vtQ@c zC;_0xLolp>*a5;Y#Bx<J7qR3$L14dtQKa(qM1h2*5jkY94C8wnPQb3xVzbu)=x@Y5 z%FMDlq0Kd*S7WX*WFOk=qKipXTy=+^uv}0UYjmIZ0jVeXuqgqjj!o4)n_lG9d7@Py z>XJjLS5;~+?!T^p9mxmfd(?crxq_apX8U1icR>6uV+Blv@MYRg>0Qqpw#EGwWhZPw z#uP^@j(t=Qdl%5HSNplaH~A7GIwjFu1Zx>1+pHQj_u``Jpt2v(aVd7Z{!*7POuIi@ zp8TmCyeeMJX3~buju#{J_*`)f+H-qlBlpw$?G%BemF^?DeS(``)CS@Q)DUha;<+Ng zwYx$#Ybsn-5=E-+^^-p7^vN8bXR3tRJgd@5g*-ck+r?83LTUR7m=7$Kw3XOC29r-5 z+<R*c`AN<~ln&DO_EP|2S>dq{cfaiC2wSBB@upUHx}&Rulg99~REBwdW$YzD8;CJb z!~76l@`~6=W+P#h1DSqyh`HBM<SRy?7W+7^2R#xmdjmYt=0W%dD~}bZ6!c&z9u-uy zeYm7&OrO{c6)6p@``3>5ouC{#y_P|`IL~pgwv?D4Szj#-EblD;sj8ra2lTT1!%pcQ zET)WVB<Gu6DN9!Q5E)4pG?9OPdrRr}nypKmDVWutRU%yBacpO$q*BLKL;*xd0JK?# z`r#-C@196mf`729N5e0~hJ!fCgC0V<Hx1Ep8FXMB)i28BcRlttTdK@lB**B?JW>l; zv7bI8!G4OLBeko5XDdfF(gp&%6-P=hvmGb2@u64U{*)7++YsgT+KbwZ7wEP`sRW$k zPGr@zF}-~25D>rN`}~G_*@J%Yo8Ma!Y#+FQicJM@%E0g2Mf;-gcWu@%7cO%yZX%aD zp>3#{UO2Gd{P*P|K0x3(95Bc@)RlE=#O)T2`$M-a2L7wfRBp4SWJymm&tmRUidPq~ z2NrMz93c4`jQp4v0S^9ZvgjxZdM<n^2K}whR{c1ej)flFI5O(o>(&FgnugPXudEd_ z7un!ATZ`|DmsKTyL{<pW{`VCz<mPmg@#=n0PX*5!OE4z%IPT7}YQa-A?t#sGoCWj- zX-lHe?S-z`Jh}WnrLyuY<$WUbM>3TPM;t+gL=YXm55Xu9_WCsvB(U&&>CXG_yHt9S z><M;FHXqG@X`%mb?qw42U?%x$-1W<m9%UyDxLw}^anTBh2{$=xFk}t_3>S$Tn1L;j zMjgpLzb;g$W18;=zlDwH0u4yuh;Ou)!b8GH(MRs<a=$NT^?l@5V_ml@-{40BMac3M z+6*)24+TPX9;e5pf)Mvp0Yu8PoVer&_u}lWw=thD1%3AiEh&xdqqP{$l_If}n|HCp zgn*FOtZ!qEod+5p)fhSgun!Ia>_2jm8U<=OdjPLX^p?9F1|lKlog$M0^GsnN?w>R; zy!^xR_E+xxhnAaW3Hq~qfRV!W``66W*k|%xl0-I){?&*R@c{yoI}R{?P(w`o(o@ma zR$-1d*i22{3QYE+qwMKAw@#k@{yeZ#0JsSSh9@YbjU)g#UH2^Y=0wot1Pf7es+ul( z_$TK3aoGVKv;bb<!&G9EAt<fQ?+w6D3INtq9xyu0ilk4PgPLiZuYUmF!GI%{X92F% zi)p&2E$A^UDs^6IG?{fWDUtX>)FSxQfenFk>tSRv6Ts1>+m0HYSN#Kt0;uO9PenBs zb(>r9EfNa+=s*Amf7ebipVyJ#;cBXd+$O!tp0PbW)Bf@Kl)!<Rc(3n)jEj0`$zI(+ zK8KatSgn<C(FCnL>S<_xJXB}zsmaq2v?EWzZ_99ppFoworwh7STDc!`7MX<1KMOtL z4u<zd;xi!dc!Mv&G2KQ|F9@K10MteQNZwD4kT4mMibO3}0p7_dL!-SLh5NPmQa|Gb zbJk=3b4!g$IN!c>cxf`V`R6e*8QZ;WN(rR%lXttTT?-^-ARBDCXL)(g^W1cVVPu8O z+DxsDW9M}9E{kK6Df`N;PrzJ*Qw+c#geXEF!fKiWLo1)P)az-3N0GooB(M|1Z*e2U zmU_f18M-bi{T$*1o#bPeq(9dK18(w7DW&`9sW<WgkC#%&`7);p6Q@2XGH&KW1CI^~ zAWP$om%M`ix$h@zit8MbFAWoWsO{WJ-C^Ub@>(xo@6v?NQI$f113eRpEBo0J?;{`^ zf?kJ@V-xWk8)Bz*v(0qkJ<&zc6wtyFG`Si7n#UAvgVQFD9FFJnE<ZqJN{-Y>J|1v{ zOcns^25O-56e|YOcD7W<oO#~=)p042HiLI8$ozol=1oO^ij4>Dq}9lgts#m2gjhoa zunr0TXM;YivTw<VhSDq2YRf&4P(qy-fVv80*k)!A24)sxb8kQ<z({>5CAQl!*;?o& zx<cmj<1W2!-Bq-6TXF<+zJ6%1*y^b|1dsuS|Gmbc9|BLrXH4`lgRLBsZ9vQmQSSn! zSqAjTw&T8a|7i%Md&VDJ-vI`fOXWJwinv~MS<V(g+t|)&+z(3R&zBM5yEH!J8)FEr zS6(^Lqx}99?Y{AO2UqI3ANE%^6~#S~QzR~NP^!6)J|%_4E$8*FldB7bH3N_%-EsGl zxEI63-qZKhb|>|$g0nhTuy>WU2~pu6z*s}{lc!-KFQV{LipdfJe%dU%<5{;n4Uc;1 zA5;Mi)(s$&)_S9&0quOFM&P_Y)Bs2q6*y(J0(R0X3=4AB)1zX<utRrLD{L^(y6WRb z94cX#8%3qz8NB{7t+wRsIvssL@*a3xptAN6LF`U>+6DK#0|`E&^XG+DFT=ujUF1pl zo@&v2&Zm(I8Izq$TCQgZTz<|-4LKni(gS_9>31Nr7KRQjZ7AiR3?=kPQ;iI-Z`6bq zJ3DL`YDr*sL5`jMVB`XU@CvOsDp!7@4whe1IGyV`3E|EO!SKRL25AY#XsOVu^FdYh zC+qvfaSg#LCZeiWZ(Y7*1fKN*tJmC4^kVk9VG2d_(~uG**8WF<wxVqux8M6uFM?6H z0tmSPnBd<oJ^9WJOwe=oIt1?9wRfUJhqr@0Jw?KkF8H&|mlmyOf4aXS9Nat%9`OJl zOJmbU<N5Oo%_fzraCG&+){=5$bes5_-<NscFo8O*GsJ4>q_F>F#E%LE@x7SdRuu1E zr3ifo6=}@yOFLVv>tpjlls{0H{QLZ6^nT5GB=j~3N|$T+eX8u*Av3bFwvDW(k6tVn z>b<VyKX=FW`9=3>_y3GRm-mfOG(^5UJ7Ahl6apgJZ-`7@2z?o&+ZbWiv)9qx9Wg0- z23I3_7h6S2dRq~`Y}<Zee{hZ9eu7RJxdP>KOLTifh?3tz*l3BptFR-fG)nS@B@|00 zbyA10H?vGG_ly2&xZeDqctrla<(1oipApV_D}VllA?bq_9=oh0JhmHh_lC`h>5I~@ zMgQH6nbJ$oQv<!jq-4WGiI36=71B}?h2Qo*5R;BwEI9D=b|P$2qOIZ7Ti%r@w`L%I z=P*P^?qHgnnQOah+wB8w_v}6@5?e(Zl7*&7NqzD5*OOfBD>`LvVxbGS9x+fGCI&J@ z@bW047=v=xxh-}hh|ohGRkIL9m%Vi*P^U6r_#|NcuI=~JqWSP-ZE!HT;y@c~zORwL zEk-x<L3eSzv9U(iO5^$m$-phlZMqDsA~AB}$cwad^zWdlqZWJ?T_JFPKI}Y%PoA*R zY|^8CDM&c;I34p%+`m<VZxhqwVC^f@D?;uS*%0c_YMJ0(&hqpLi^iWoT9h+VKSuN! z!Qu|!?<a<d9Y8rAQ9rP40p}orSZe=q*2zaT9*3(nUZ1Rmku~CWQ(o&4hZlB$SxaeH z0;J{_=I}zwT@$eRWfM*c`-K%%dqSDegH|9rsABdd?>4&s!N8wMbqgpxq?*W%<wd`g zn)=alMmFf&tQ35z6QH(C+Hr?Jf_)JIZ+*ZjiUU_Y|D?fS$KCxwX6V@392i=bf&#or z@T*--W(ig<$47njKzXnUh%Z-q{eT~@QJNXO>uI%`a2HFpx!WeQ3X^TV?cCchdezic zlx}uGHrJFT7uzOh;XqKPm%t1}RoBMWw=3@fLf0pREB6aanVk@&6W^E}oB5<j_X9@) zx@M|}%X<gUz30Y!RD7D>$GmXj*?%@CUo+3~0b;M=cM~1$l&s!u?(lrX%*{`YKF2r> zsA|ZiIC<HEM_>?tgGYz;6QTHug^wVn`N)0ONvYoh0Fb1G=B=n;elBDv5PU`3kcR5w z<jM2Ij`nYOY$iXj1PJwiBpUq=bWX&o-nli_d&}sJ)T=+@?@hpBQs=$ym)H8PBN1km z+71ZGLnl(sJLI<-oj3tBRqT4Ux3X=X9k!viWfgt|>;GUr`Fb3_bk_Yx^h(vl7-F}0 z*_rH`^YgV#pXGsX-XrH$L8|IlB`N7jxl^^o%-P}+{p2DwC!fm+SnHn(zlPPV)i7N` zK=)(OqBl||axWcvo<is0Gum%&nHp3*#`iH_4cwIT<l9?syA$&zQj9zX3GcqcpC1Av zhkdoVdrujJzH)Mo@p#}5W@jZsH%=1BN3`ZWPFQA4emIh({p3DNR$f&CqK<j$imcQ| z(x`$jKZEp~+m{qUtxuq3g>=hz?^Y73NBj6wGkdeZR<nw?>lzsG!OpIaZ(S;fz^Qrw zP!NIW4E-lw6(v?3@ape<bz`&e>w;nj5I{J1;E*t|s+chIA_j^s^;l?hFawuLqy)eq ztHllo`mTD~tW%}NECldW2VaPJhYlY3&y;5@B<4`+a*`ie)Gd!=B%$xVNl9t%lQ<!R z#ZHTM;+I?{2Si;oadPUQ?YNXvoCi)>bj}YXb9NTfx5RzkcHdGQ)6%g73SWRf9>D@@ z5?b#BpS=phXH2btucj2kQ>BS>XHPkUaP64ZG0|FY@T@snjB_>U*#J4=Mf)$z@%;GO z4s>a&AfSzmKr<JtL0i@7N)Dq@9@}Ya?=CXz_>+AxM<)^~oZ7Vn&|bE5e!buM)$W1% zNC3(N03HW;yMF+E1scM#+8<?qsf0a=;s?yFdEubI0d$AA6ZoyM|A6bnR+hg}W(O=m zx^LmC?7KMti2ZE_O8CbfBflBN&mpm2dKWKUk6SIRGDiHuY~d*rD4=i-!A~FhXivQ3 zu*Sdfb#L|3+5xoP6Vb9W2q+ThSKGlXG<|{Lg}&AKgjd`)&|7pN%$bolB%43BuYEkS zKGF`CdF<i5cnDflZ}p|b8lof3@85LE>iL`ZR?+UD^26te?M<$<0jp0k)Xhg>grs1X zD-{xg%2QI{QqX9csi>~2q6z4E9sX{8svjp-{<bF%@uTtP_o`!0VLDtV`uah^z5q0~ zA@tSRTZ1i1TXDCiOG^&QuQIzsZ+1<oZGK4kYqy!?0+~PjGe9xMBlN83q<{DU^nul@ z4=}Y3tryKI9!^MHiVK&xrQ(t(l=~hj2-(;s;AiRwa{r{x$e&gy|0^g}_|ip0?2}y3 z{jA5eS{O2|vl2VaJkwqYfR}+C1gsU=-NU@7iQi2`x%JuPNGeCMcOm?&bKoYKEkL`> zOrnhPtuL2fWO@TMW69bD2cAH}jL{5)=9Ga0;*HqzI2Mnb4$onM5$WYB;CPD460She zf-fb|b~)R<iHQ)#sBXCS+2*V2$TqH)lYz2nLH%c-7{yz__wmK!6XJcH<Pu|YUE}q4 zOxh{($8<58Hm{%IsWUsHLkY>-BNXe|rv2PE<702=wm9i^Nu>w}W5vZ$oP~$re|^xC zkFtgTi~qijrrBmF?-}GP$0$jb2s8t1itIcF7|zs&L1+TNMIcDl{Z*^Qm}h}-CzQLq zn+U}y<GM6=e%#GtKFaS`&((HZ&xk(qoSbq#P=R%39Xco2O%1l?s0tRk14MpWx~f~_ zg{LCB{Mr+Mt!8=;7*?wlN{6Uxhk|SGB|f7pglM4@y#!(i!8E@zK=l<^>nGc&*1{n) z*|uj$I}WSg>~0_uUP!O)+56Infiz@wb<W|60fckbd;q7RV)=?`1iThBq2u>Bo1yuk z0FYN9EKT8~iAneN+|4KszRn@e%P{f3R4bnt@U~3ZAVvDO3(*$R98w4o)s5(HHwv5( zW!atrX*PiuL7MlM(N==5X6yj`kY@0TRYu{4yRKM`Ppzfap=R4Q_oPU)y9fHBmH3YI z`vSosUTS}XexKewEn)!>v8b5Q;k7zKL^B}31Hfw!U?|g2QF}>5m+qKB0OsgkfvMN< zap=)G++~K(&B_SA2na27kE*8kc9&`0IES0PO8EDukzHwZWI>E(Yqa}cpn`sgNv0%A zWr}I`sO7o$;yvyC75`4xOLPa2>x$!C^-vxdQxR3GA)o9>_s^OKB5r<a?G*#811U4w z93n%w_7%|jwcL~sAzmT$iq~tZJsgj;A4FN~p~=+d^wjF@A&~1J1!8wA<IxKvV|D0z z^SJL9lg4Va2XTF-Usqy>kMP#5>Yilc7(^<d9yt6ZBP<TlUgDD*J-FkOcG-X!c=pu$ zOYU~L_0xGSR&|!#>v3W<|J^0`dro2|8qcX2b-z(^^sGux8)wr{jdeP7*tRbt6q&7) z3oqwvfr&wH!qs}`KV~%S#j}_xqksxh@nHv{dN?%VQA?+W>4^T4%=2+Ed;uH(bZ5Zy z7B9%)(=i{FSasc7c?!!o13<g%S^trs9i>o{(=k%vK?OVg|H-6Xt#Ea~!gczRory(m z-r=p4RTVsET?@B2)@$jY@t-EV71UXxeXfPm6m74aDdK!2@iJ-~hKKWt54H@-vD5*g zUxANREt8v6a}7TnDUr}XO&5AFWOulJxb-bf(e(Q#9r0k>o#>S<_IcS5tQeVB38sJ# z>^Pe9rnX^%2+^@qby_IC$zaKSg^!U+iR6*1Cms;Rf&frCPFtR$c}vQduiF}d7q+-U zG=@V+$5VYSJyA>nE1E-`*GuI(k1$vSQX^rKZ2JwEsJWsS5*-_3y9w&*v)uPNj2W{J zF)-;e_dejv$|P_O4Dk2FH3MVOsVkBcOW=DWKDp7-YgbiNPHe*GaVlle3sT;W385Kx zg91d{ct`(Gf+w|6I$rO`D*C^keIJczSlfpUr=dbN9G?9PDi~uDmqEbjsFom9jfc=C z9@Cqn2AvpU0OdA9-olO{Dq=Z$>$U<qnRX|3!UVo@1Dy}?b@MX|IyvjkCO$#7r-&~> zEN2zBXgmy;y*N^%7ZSPaViPTEZ3?AtDur_otKcOIa*e2Yr)LFcQKH4EkZx2%oy^<u z$~u4D>XM{F4{e#san3BmV<iR=<X&hUAvjQKcLu53@e=ILMgwy9YD21jPjK}1O5yME zQ&o^p)_STBrUv;dpetq0-moke)``GIy-)`fH*p>&Y|6C@wfh5w8U^kS-3ihisegaG zf@~*YK@r@SK}|25wnP+o{VKrYmk$1+4F7074?fjE>%+Y#98y-rdDAtTqB4R%0nqv% ze)-%SjHFb}_xNatPMJf|n1WQI$4--<=$*7!+w5tCXr*~=s97v~MI^{)<WJ*K15@;C zfOMX@O(tgZsocC$V0%q3JhCedf8<UwxTi1^?;TxL1Qv9CWC1BTr|nQuH+py}^q8uc zv2n(NTc6?vPH@c937zb>PnU%?S_^fw7P5JAfFC##%N_yd5I}OD1TgdNm{{NRAkjhx z<?JDq^V2uOuR?f)h+;drJ0b@Xh=cr8bQ|LxZ*E=$w~CkZqoOGyRxJSN>wk39pA{3} zhpnkbmY(1WM0~_a&AdvbXM@&o{uTkdSLC{dboz;F&JnTM*0aw+OB?}>jbw%HnUeOE zhk<{cvXr=uk0wv=coMO%P#l>=iC-jU&wWz1;j^JvOdjvHlia9ul#xgNfoGOy#Ya7_ zaZv(CHHor=S^kn3qbBXKwD1i~l2RIX_#X$4OV9+)?iTzGM?WBYzi=>k#clbkISlZC z{8O*F2|E3-ebmw9C@R$YLF!OOsAG{YrmR4>|F*y>bw~ELg3bjgfMoLRteRW)y@aoi zbAr4~eU~M#Zv~DP>*!bnBv`XZ7bfvHk6M_`YJ^XJedAVo(uf?BjZCY{>ao&@lA5~f zh&LK2|MAHI!SMT>BCU2hMjd7cd9znm@g>>YvvK|rm~OD-<D+({8SO@MySAnPkVbjH zoT#$JCT{255B=mI1~sEg2oF_Kvd9qY$(Zm`)jlh1@#Poh5@b$tRtBADb$G61+SpU; zcWjK5o77JYu|5IvNyn+yriQGTJBKe(hPShIgah9vK?J(*Je0c-w|7Fl8Y)To_Y6!Q zvb;KWJ5O%8`?hiSZa)FfXyDm#uHvvqr`D-?CAy)VufrF4WysdW_-^K5Q#Iq^diFDb z1h4;|T@>1kcp??F%#&qefL3c)P_r;@-x*#RbT8%89O~SDOUV+IX9iflA3WRp1n=v^ zx?k@6a36SW*(I>|YUg%6?42<&{Nz{<`o@VH9sb1N2QSIXB7l^krN}XEz+*npblbAt zNWXf=OkmF@rKdpU#hu~^#TR)X)(C@NZnph}?&WEYm7#cskyeat%y^no#)>h}Dm5Vl zvRY;M6WNQeU`wy`;zT(Cgw6`~0S$~`jxi!KfL&juz3^1%<ZHE|OtFLC_#=$ik=*u| zY58*v?OtRPR{R5A-L*TfB>)^Li;aBMs+B+U;KN0EfP@4(1lQH-=Ii7#yck)g><<yr ztGwLrS;)9jk%y^uf*^i>Ci3?Mju9F0H4S+=`ZhB_Mcb5p^}?kL#66}F&r%A($3#vT znMzl5i;|`Ef2YUQrB8k<+%wjyvu3dstz0paet{3Dyg@Q-U_XpRiJP`$*m5g&B3Nmh zP7VTQelh2F9YS;Qq23(6p_>yJ+{=`dU8`d^w^frA@BZ9h!n0*~HX@8B8Jfd4@Y6Sb zAuR3&BmSfcTN+tN^j)zH;J;|nlD?8Zy#jNgksd?}NmduyuS&Yi-z444UVN>P+-S(6 z>Sa1u<*VGO*mdXhbGz!e^uBgZN?{3opMPX?IhVa(v9h^a!U3y)xlN13lfVD*AOj;f zJ4wvIS?xkT`-0g^bl^f&wGLTOJ%sqiPOQYM$-Du2S%?ECRK6&0DnVrF`I4fBZ@14i z(RY0<5eUbd`-ixLeRDU>O%Zi_&qw(gYHbM3r)8!zHpKO44D@hBc38;%^}_gmZs0wk zBtPCH8|f^GX6al$KXIMc-IKAc3v~B0TWvCi>A02L`wr@?R!H!r8{r9}_aFeR@F1uw z$O6x+e%f`BRQ%u|e^S`J(j3`FQ5+1&40-6#!LsdO*&z8VWe`R(g3DD{Z*4o?3b&(` z^vuo9r7eR=O&4`E%rL4di!sdTs8yZg?3b=WS1Xdn4p7VxV7`Wyltv$Eh%cJ`G%YhV zXtbo8{AVo>9wgV$#BQWsa*^ePZ&bI!hB+$*b`YAFplBTH;Z|y<+|7q2JS};S{2@wB zrlZ(Ibf=zgjt7y+BC$ih!|341P~Cnb-7$Ln^`spWWfrwL-o7?)#TJOjSQO=qvXJ#_ zTtr)KX-rjP?_fjP)nT@y;QoE_kWO%f`-ILlloh<6kGgg`^P`ZUBm%P1JL)s`m}Aub zW=Y2t>kviHoI8!&n?~I5G3Ld0W!O4b1dP8P8@-3Ee0B<T6w9$^7djagI!!1cnh+Cn z^$Cuac}T&+GHaHR!gjyvrRl73b!Wk}Of`gF5bkjWwKQQCWzx@)x!e=ydKri@0s^Yo z4$P3M0l~kWiZtWMQhKitr+=||2{}%8zktz4En6Z!e8=Z^I9#q6%9t6DL7^u={+m44 zFZFJZ0mG}osB>y4Q!^JJB|T%Ce_`j5$&j(z?niS_^2n(tk_l59x|a5b?%#Ob$e)aY zM@^K><&>{8{y>2i_hR0<B5VC|d8^_D2M4WR;&>vhgjb!@C_?=2;vK!o@__LN7WG%! zY%<bhvQ~}lld})TB3!_90lNc71)CkwF2@Cn9feUYfnxfqcLH&6G4h=!EMy2RgWzSO z_{>@>f&UR3*}XkdUY_6cNj}4t8Xav~;YFneBiv%ydR}h7DTsgn^$RuJu!u$+K5#>r zpC$_2xDkW!D=OP>JUlmfi}<}Q$!>;89nV-{cwBhO?h>w`ULIbss*iU%m5Ox_=<A-n zbRr5dc?0|WLiSa66v>pm`|h~g%=JQdjcXr^$m`Cyddpq$zIU*jf`y}x1Tx$C{iH)$ zwv+E;Z{2KuxdQX<sb6(ZRY3ZOUbC-8O!}E@mIrZ9kk{rM%}?zLlSpHJ=IOY;z6{WA zpUxyUvg_t%GPY;#Cyl2s9%f0hs7$5L9V{mzuN_dcEqz|yS?JqQS$kjhm?it@@Ezg8 zF~tE6M#W80W4ze};j_KJ=0`!4n1U#Jnn!vm-NZhK)CY#$GI-DfB$ak!Hr>gi#gdXS zqjPPhE<1R54z0ymD882?w#SI(SL7RA;rsTKNRCsk=<$N>fTopMV?G#m+L!I@1%~MP zkEG0&04Pgg&d(hf5Vr1OnTD*dygJnV=CMbSKf(#z5X#oM_S{#SHw@n69ah!P=KUVP z8MB`~%f)mY(h~DhdvuU!%)Tw$g&q)`dn0b|c0-Jj`E~6UGeB{<`QeAlj|S(e;DWQE z`Y4ZpbO-LMq{8PzB+KWW*$QHu(}!4*b$-D1SjBzEk?5m~ll)ch4J(M$DPi=NGswa- zPHmf*Uv(E==~G^vLc-0*zdbeDWLGcD7vK4`OUdtE+>HUm<Xb8A3{u|mfG=y^ORiFs z$2;=k%?mGM_;f4G1u<Qo0xlF33AzU=@Ru(JH=l;mupwg7%IL>d?>ODovf_gJ9KEC4 zphfjNzMWg#jEST5h@j8fFCRWG$(Up6i6eh?Lr%^6jwNNf3v-mO94sZVS6eeRUK#-% z#Et>g*bStnIXmkBu?Z*h?~=q|?=^c(3sD^=v$ekX%*&Kp?W&`)JOuN2g=A7{zIY4! zC`lF=ei<lv^w9jEv`GGwuB(=36;j@)*@@&g9M3k?es;)*X&~uI%|^PZ`vOFXjEK;Y z5ox8@K{?PH`_nVS(TmJ=uND2pM)a(x&U{7!w(SBcWO-!x{q8WzpRTOuu?phYS){?) z^PDGJk*&c~(?i_DBiqY%|MVQ<Tz77E8m>T9%0+Qq@0qr9<p?WcFye$}i7x&MGB-SP z=VJIeBQwof0_b>MJ{K+m?{f^H9{&BVTr!A1A-J0bGQ`6q^zvQjJ&%1NNQpn@cos#U zC3;Dzj!2D#O*;>fq6l#{b$a<GzbH%waw&dQqcAkOM^Q85L*u0Q`h@uRdx|&D1oe)7 zxcdBc6PEL;{lP=wS<#C63J2jYtbOhgYex%ErptC#p<=U*?5OyR$P?NB#bmR_HO9=} zHLlM3)9ke7BL>ou5&R!T>&a(?S1anEvy$`=-zly^`mBKHl3;dL&PP(a;>kGn<tu7Z zKD`;kkIR>@9lXK3Y#038Kelg9G6T`dNXs;S074ERgg!y$GyLq*B7UhaMb%dO??^JX zV6=dl#W-)vl0Zb>3DmOl<r1zAw+?!N#w^)>RU#=8e5gbjTvUe9oG1v7IQBxt%>6as zr1L`w>9;>k*oS9FHF0r8npY3rV=iq4P=ntzBEtkuArJBPsvP$bLc0u21cw^IB}MWx zzr?X<8Q8qcCO9o7YHyG>JZA1{)n}fH7zdYO$s&1A_)@*1%Kxq-E_aGru$eD!eU+`! zT?|<NYtFV@)5+NWx^xD4SG+V`@h($4{_=wWH-qf?b%qOyiFolKqkR2O9sAz|XYF`) zTPw>IO#glg{H$az+sw8nx2~Bt2mKoq!U~!>-U*aE{Fw@m;PKfizZ%?0+4#jrQ>jzE z`l(n}qI8=7Ko)xT<K9FTSM!iPH1$`nduaBnNCw=c<b&4*r;G1TwnVB~4rrdwTn_b^ zPg&Q|O6ryue6G&|#RZ+ba@@W6$EViId5hOhES)p88({lIZN-c%IllWASAh!=MP~@^ zmx}+iT#g%3IFbG1OF|Q^h8!<*W)tDGgE;z9>VbZMm!9IjYh7|xYVOzBz_|}^tl4kF z*f1M*P3Cca@mwLyw_^6X-<8qsx1k0Ct6*fh9XtJY-M1BaPPqD3*NiM*1N7_bs9yX& zAU-aqE#lGX1UC{yd{=8qG`#dCT?O%M!lTH0b!CXOwt5=nbVuU%P6{*mXf|r9H(QVc z76HuuhWH-JWk9}%Lq9EW$vH8bjM?_x7o{)Xo#Dmeok!aGy}U&-75TX?{~&8f1RXRX zIfQ+D>;NM2YM|t?jf^_geRZt-eWylNDph9EuY6Az|Ma`MvB>hIXT{tGb3LJ6vfz|s z(x*PrbNZPsd6|FSdRZ>iamo|x^CLALY&Pl`SDgEywXAdYI=lS@#y1bSG<dwK7}Xi5 z>`e?@F}LAO{60PkmP4fYj%OcpBH!FMg?YJ$a`HdUOu8#l^J}_y#&Ft?+@ks&-&5Gt zo)>r7rj7Jt2-mClju7_06Q=<j-*EUtegNo{=k$JjGnSXBy92L&f7PCc^X}ccJAWPF zfZ*S1ho!xVU)}mU2&hhOxi)S+IclVk_prI%?dT97MFZghxE=<455ci69&eG}33TkT zyd-V^`>9G@&$Q>&y<xtwvMVYfeOAH(!uB)aIC--Z2+S|E0O_J3@LW=n*~;lrc0!2b zA+YWVx&bhTV>56_5UvEItkV>qF~MD+MH1RQ$)p%WO}c4kkJDqNU){Z_twgbeOXw5o zk=<?d%LaVwdKi2?s}3A*uwTz7`$IK6|LP|MXon8V3)S93z3jFGimk?*c8~PvJYr2S zV{(1jn=Wug9-+H*q=1VZ%o)3uCl6?R9@{aF5G7r@340{Hn>PDUK(}HOw0OyLQ*@`R zapI?o=HMcNcV2by(QJCIA7GxBiw5^u+(Nw+*9+0U-D?lmdd5#3J3w=W+5O0of9Xk~ zLo-#Dj@lNko~Q2f1j@%KJTY4_8Uh)?)s~cF@hH;5{YROCw`vvAp!MNYoZv>F4AAk6 z49dZ7wOMBYWeM<j{tfH^$y~S)hT%^T07MYGmkFdID&!4GG^S%RSxDnquO}?wFqU#~ zQc|8ABGwK+C0KfLLII9;<NCT!o*W?+qbx@ZioGgdocSg8{cr*F{S7eELl`Oq6xQiJ zE|anQ^&xCefnH#`q$@GPwsMEv&n+#@@t$BKifq9+Sk2NU@1@K6)EvWQ_C(%6WxeV{ z*1Lt>0`LkhgKWr^UZJ?ID?TR$a*N;|{?gxTDES$dN67<33b?N<dnuC`Klp3%Dr?OU z1-wChf2`d{>de<gxz*r+u3BkLAY;6~qNDT-0%(OgtwmFgHyKTEI!kM!r7uf|q{qYN zd6rbDus(K=QH0HeAU_%jG<=ZO^B^~3u+@#ok$Zb7?T~<v&E5Aqs6I$16EGDQ_x%;A zS2@Iv*sSwN8yHT}{t_q<+Q@AOysFsxhKJwBhGgH9ZPETG^$m=;SQ`E13E9Df+X<W3 zp>kmUI>*UcJ8z?@68tX_q=!4ohG2b@$zjFaR`eJe6lr{XB2hoaGV}#B5=D|+jLn=F zl1aClxQ9SngQGw>5)gZiz4C%|hR=yxX7{|FTFGx!2hyP$7N}4z@}49)Nn<!UB*QI* zUv__13-=6c{@KJ{`t=tR)%d-7`a;ke9fA7~A0xV-3%IUop`mBqGiQX*t9$}dDAv{n zr{VE!E?ItBEb;9bf$rJkuXBD<PSPAEN>p+jbxU_~`P9>sV9N{JN4Fh4q7W+n6U>wH z$*%7aXbZ>iG3{VN88iDyK{YCN?j!Eeoab7@g2GWfIB?L`?XT`llfOKcV!JOA*aY<t z+U`u?j!jIHh9^2%u&+k^8+<3@CyK;@xd23<JWw`N6yMyO0rTdO1BUmqutU+%(%0lK z#Y)U!{QmbAu-3U7U}0pCXi0=s8_<nZQx!Rg%9<smCi6yeqR%1j%0}RB8jtC41BI~I zu;B>M(15kO2<QJN9U+lU)3j?hwUrkvV5-c;9WqpzN8Ty{&!PKGkI1t3e2xG+G-x<6 z5*t}3K(me#5Xh3X1>e_#>Z@zYMlYQ(dk>i(7wgabOn#?a>1AYv4Ho?h1<uZeaF|VS z?OjC8g6nF3#6E&Fyq(@Yv#!8u(!swj$R=yn4UQ1|b=*t26%4+76~!uvox63xwlVWg z01sYvDIx6RgiV1>wNQ~vg_DAr5oqK`V)+o**|f!Ux_e-pGl_i?_S~XJa>GTu%6_jf z1ojn`d{qyVhqkZ--NZwVArfAwAPdMq^?nRPjjbl&HsGAh2+i5cR*^r9JEBS~2Y{+E z1IQ3dQ54TVi-4ZA;p!<Pul=^e8mjd=Wt<i*oA(>mkXUeJF16v5_ajW~Hrwed<UOu8 zedH69`ss=waAe!xTuQgAGUi5pu_GJ$+<<WM4-&yYj0cpFG-1j90_`Tc@Y#Oo;whVS zepe#E+AF>{m(Q9oeTiaZ#MS=cbl_aH<vl%nj4RFE+sALGY>|q;=Eo7$SL9pHV38e} zv)S1?R<!|U5-lbFMh;eP43I>6nkPaA_2eVjDjfTl*8UqfJEhD}ka0!p2fhPXfhug% z&SU@1pP+M@vb#wm=Qs9^esTn0I~8mdsfIsN8AdvS5FiC;;ZNv>2vR5GH$ePLDfS+Y zuGxJNm>|+M@|tYa1vj6lz3+uw!^Yg50XAR6mDW8~wmNP@2`t>V#&XIUaFiKfnT=d^ zB(r~Im9BlSy=2!*a{M^__&Y(e>A=N+?JE3BRhXDnb93d9^OJPHcHEiZ7bMo}9y8u~ z5iCH8Yx?cCxnfy!=Gg~|*Ua9}x|Ut!J|^FeAVV>o?5HB3!rOrBniZtr%YQtU$=iF6 zOZv2dyYImccJbsULVEWMboA3qmn5EHL(bL*YU}RcmR9~yqyYd1q<9vg)cV^`LX*S7 zqK2;OvP!-|Y3gB}(qiANup{@X$p3sXSq*A#tlcp8mZZMyo)Cl^v|DC9n%flCbX~Dt z7l;Gy?31gGwb4Zwe8<<#iYuxCY+Xu$TWc#{IYQRJ_Qh6FC;+?t0Cg%e6U2lu)+GkD zG;K?dr*UUhqj3U*p=DJT*~#{{y?SX<k(D~ak(@_TYj7aLtVzLQ5A5yl{9rO8K`0tR z%OdIP0ENpd4_j04apvFREDCmdY^4Z}G02;yAGMdU#y@c)8f@`<Cg4Zqg8Q%peIOtf z^oGuj0PLl^GlI0HCi~})?QDzMh5}WkFv0v%76JQ?aNlh6UV3DnXhm$+F>o!euizJB zp%1uLT9)q=MGS%8cR)UsLEL6;ZCI<00d&;;t-fe>V9MPru*AsXruK^{pTH@mcB4fZ z@J3nvK37t!SNG$B9vNlIHCrO@@#jd?+j;fV|7hYJBn`-3PGH_S9u6UC3qvpxJ)2K2 z!h7WF>Y}-6@DqEDU4{<{_kNQw6bG2lZsm9<t^pqjo9%Xn5@X7JIbN)q-^bm@3Y7fQ zmW=-k1*NWygC}<kS>(F6s4$@U$I8-`?7MYOHH;j<ni}OT%lolp&+ybc`<BoW{+6@P zkTez)IH0BzqaaYpeC_QavKNK?iK3*ix=c0%BF%u6W8AOG>YLCCUDs9#%XEzETt3U= zC4GFJT%*Urulr@AS=Kr7^Smn)p}yq)J!IRX4=24T@snP1{S$xAcc5W3s+Y!h@2-JM zUjuXhh{2py`lb`cJC5UMjv_HRGo%REKfR;h<XDDh4h0xpys6humlIn(z)6d6zg6Q# z&My6hg$alqc3&mSu|}{<WVtairuirtr2u&GF=Q<hQ1TlvM{@sFvf|hw$MXfT?1Mn} z!E%coPouFBG1xzyp+Y?Ch<=axh8P1eC&}%Rnvn%~K4;M|2*wgu_CG^s;?MLS$MLTj zhGDk3uWjZ&a_36h%zfm(k~VipNJ6U3hPmg=Rm~i^Dx{KBj=3eIQmK$DNl2xBm7jm% z`*?gl@6Y%Be!ZX1=~X2<H>gMHkL-aJufo=EU3V;4j>Ge#azl)+y79~k28R3_3UZMI zIDKPfq*N9O4=C6n6{>rYv>b8#@Y^6(>E=ZYFvtH`inFmyA|yVa6(hbTixV^*);$#n zNHiczCU9oq>fji$SNH!=&+Pg%ZVxsJ5lK=7k6AFF`$Kc_!st~p-nOR@=sBXArSuxs z2LOE1^o0fVpcv=KX?mmYQ~c~zf+o5%Gk`!z#pk3hE?J$NfqQ~WgpBCZR?eH>L8_0( zb>8LZih}i`PHf$jv4aNg+iEg3Mi<v0*6bcU{FB|)C4#W&2d%O(7am2xN4!?_V*qq+ z)quSwRjt=IfeZhD-<m^>PvEz>AZe2%HR6gE5kXlX#K<mk;rgNgAt9phiPu#u#ds8$ z-(#8sqkos=(0KUpvNEm$A+~$=$CBS4$I?eU`f9MAms$xIVZ;n(>gTp4{2nR3=b&DW z;)s%#;m+56`wg~yuRroo53ts3U$lzmScT5sgVq1_2)6X#;5q?q?URpB(Z3xzX+LpH zqwH!3|6Hxm0)g1)WCS8_)!Z?0Lf6|8$2ms=JYVW?EToj|RF(Ksyxr61+;0hqs@Y@h zD8mCUaKo^Dw>?IF&&Qbf5JHqxHuDW`Z}vV4%(smN#%F(WO*pC7+@(5$yZG@yu96Xv z*P8dR;gU6k+o}));4JlX0&UtcHi5zh!vg&?fzJzwhnCoQ+0^S=;3svG4xqV<SfXQL z0Dfl4P4}bUqz|4b1|UI%StLF<ml+#mIXrs%MYRA3SM>DFaV_X~=qj{F=t7%x%3tuw zFM{}B`NvUqGTmGgR$&NjRf4f%f^>tUI=FqyibtAg6C7ALGZnyV>p61+9~GP$FIat- zL_;=O<~am7PdwdC)sjq~7Ne*CS<Kgyu1Zoqpr)P=6#cy9>J<7RyPWfZF&y)~R{?fq ze;DWKV?-BEM8iZyif!LRRh2Ab!kbv*XF!=8f4E!xKz@%RyxadA7bOKvx97p&_atwl zNEUu79cb`Tg6OA`_qvc&jBLMH$lG<-5BM^Vnh-`}fGuIBK*wC!vSXEKv?84(m?GUs zOq?iOx6v|vcM%RwL-`#>6F1JOSyI&8u7(h*l+PIn@!g~=Gz>W6R5*r2+-avYH=ZFa zFo#4ro;l{RID@^|@D>KH4m>6*sg5`1LaIh&DRazY`QxPn@gBt(d5w#$@5H$3ZbVd4 z3uf@h7ay5TrEUXTOwm)j>Xtb^ZELRy$WQnNnLsZ{|NG*WLQY?WN`SNQetHisy*T)? zy5z>`PdK2;e|q}f10@?SoEw^qmu;>bZKz%8L9YpLLV{I!r10@npDj9jLKy&y=Ko;` z<*eah{18&}y+YZ3+0#5a$Hq}$=u_N@Ukr(hJP+j6UwKf)A@lgw$S+9FL-|E=9UqYM zdURrG<eDA$fGwKdgdZM>;;LyB2kVH^O4jQxH$+(O_UW{WA3}m7PUPLxw$(GS+^#;6 zQ8!-|B|H#K+!W<#)5RaEaq!X{o~E+l<S<WjmhY%A0C=N8lt{vym{FLeqj&K9DHet< z&6{gf_R&<B&X1&vybu!(cN<I!dgk~3ag@-J(2-JuSF6e8`<aP1hbampM1i2!Yi^Ap z)Hp(lB+>ES_-jK3dgjKvTkE(#sfYgb9S#N+{3|EJ!A4cti{cP1o#8-Iedcz?DU_Vu zK;3E4rBGw>RB29Gwc2XdvzP@g$cbLamUq4oCweK@c}p9=wSp%uC(Oat4>+q>qO35- zV`AiJS-(4h@>xA=kn}zgNwmIZJ2M|-t67~};alh1r_`Z@rxZ`}H-wVvXByuSP@_u} zwt<Vo^+$brESVRNRQ4ju*vv!p77yDQ(a1+JJmf{(OzG6kFLKpdgl^uy&c{O%PgV$f zqe~UU=ct}XR?mtN(Q4pLuVanoe4g?+aIs~RZOr~RKm|zgHq&#%x4c4YabAM2DI^Fu zGlzV8)^KZ8c-x5MIxq0Hv5FG|%AEX*ol^PYbemzqe}hwsdK|h7qX^VvwEOxHOGUtF zg%UL=XvE;Vh5Se;!*i%pxXo`RO)drMt$r`z$8S+eG}|zAYq1@>-P+q7r^Fe!voG;k zI#--bijVvfwsQ%<M_CDI4*1kv!MAKzX%2aG#BzJ{JP@a|-!LQ+@TI>NJmrWI8XSiC zTio1jHzguc6fBbiQvFkdIo#IpSiT0oQ&*=)aCA-*Rs-UB4Ly8d=iBixZX+Dm>xgjt zZiFt3e$f51kMo)iE+y#13Q7>8t>*WYD0$_w4Wr7Wz09+yS;=_6(L*9&alKUu8=I1M z6rm^yFJ+EFcDAGn_&aGiK?^R5q#7dV?1-mrV)R=Zv3PS8$eE501{|%*n{_u|9~Y0d zG;dE8<p@5nGZIVJQYY%qu&%=xLEzX>V?{gQ*4Vs?B{A;-)RO0y%4sp%-g13A`tX^y zQ@JKivW`z3bgpoe=vB$p&L5P30}x4Thrs6GlrX(84cL$dJ8|PmPLvO9eE;yGN`fzj zK-r4YBzEN5@zxc&Ue{D<%`}7(Z>*%%CV>=Hh&5^MaD6abGPU~MdzibkgAiTyLa9X& zH$LU1rCyF#^4(A$y`~lU{eR)Zf<1j28zg1n7f<3={C7St4)5U1+e{ufE9#JZe+X2z zH`;Xq=q<SuMVzN`<cXbZe2Q2zS(QMkx+l!pn&2m+C?lf8w~{|3BV|t_zzf@+uYzyl zyCDiP9EWat@>p3Jj8o=x9}g8)>B&%(%wB|r-vN4b0x=#oe1_kL@V5Or;XAk}L)9~2 z0~~(-&)HDG_RN_<ZR2MA7E4RhFHYs~!8R#AXNLOVDptfA&un#8ZYEz%#N(RrlbY=Z z@l}`RPr`IP8Sw4b%;owl6Lly+!I1^ShO{!GpC1OG9_&kS!XEGC^W}B)XZTt=2HuIE zJoM-qKTsR9k9Q=kdvJwLp2p9Avp@0G0KC-MvHD#cBGsv^eh-!L5c=pff7bEmYL1gy zlYLs<zp`lbT{jk$u8idF$<-j9Q|5?nb(X3SN!y!MJK2&yzk^h)@Ji5o>KuKQOk>UW zuc7zO8S@mh%q1v+omV?@YgLbN^IcKmD99}Oz*8{+M*ia(ZclkMY_Z~o&L5dSXt#MI ziijZ-q7Em{^nq|f@<iBwNrYhSXfs>YBBEUGT|E+2#+W7yiZVai88OU{SmhhB_=ztr zM~1n02aVb>47Tz%@$vR6NxfdDa#BWu20dTDsNQ7Kf#Ky)Jj=7G+tR{A2Uubb`wqz* zrti=Anc$H&UDHmwS71(MR(xhETjHcwrf-u<zTqc3mHb_G0g#e`>4-G(iQXHX0JT@k zXQSS#*v0dzu0}XN9SMTdECnEHGVyrL4<YLZ#3QqZnPJ)`9?RD8`lr%E&qT-E1SeDS zlm4{-KJ{hL!CUuy$&<rIJ=g><VdAv|2tIlwzB8x^iSw9MurwcW<=9_M{)nIK5+mKr znqXw3z+7*7gH<?5a>TCLhVmzM>fLq!X^x%mGPdkU9V&fDSR(x0jc5|i?Yv0C5c}_j z>s^!BU9H(053?Q0TGu#w#IxZ$?qG#je}2_zm63BjIS0T~L@W&=E=5}7rReJfU?2Q2 z=Yk0Mwj6OX>(Pa6&1aj2@88A}qJ9nicVxBqv&m^rv?oncQcw-5VdsyU!*GNwG_{Rt zmH7GtakRhVBQu6gib?{KQ&W@A`Ln(aF{VHo;l#gxG=_QC2%Y9_;&bcVV1Nq93mHIq zn0Nxf%VTP+lPz=f(#C93;`X?e7SLoK6}KIjD~ZBe03=GVeTjyU*TGnMDJKI5g(s~A zlWeFbx+ziI^Fn~hS^4)5_Er}NG={Jdh(B{l*`c(BUo(`SqI!%?l*2B+Kms0oAtUhc zG1Qx4E9m;P)y@|ya-WZ|;=LX1G1@SbYfYn73<$gYy?y-nUf`h<kM`#Ux_NfmdO~i8 zzwQc&EcN45a``7q@&hxe+*gGi4Roq|W<cENBZ+U0$z@|NOJnuZzYWM729G+Hb6G|& zB<llf0B8k=6iIr8^Z{q$RZ$o6(A=n8d-mB4NuGn?sRGqjt}r;F)gWvVm_dHq;HRkU zsXdX73i-iWDG@K>kFRu-=z<19u|8mF9spEe64jXvDH^}OARo1b8d!8w)1$>D<%m;T zBL+%^dDK6nJq9t2%~aFZQAbj39nLh;An0Hi;Qy_kh2LzT4bf7i!*erY-i~Ay7s6~A z)RaWqdU2=#9wjWCMWRx7tC@8vbGoXj86?aC7;uZ(FT_^hDx6VQg}XMZ-|%7tD6hfr zGpJYKCf7zu-w0RKGhm)x6lDFH8)&&#__g}CcEs{yYN$zbE8=fZ<^gcQJV%?GD`u(k zBtX)s<8NEax$TP2YIa)?9wAGJdg_S+?!i{u)lTv|XIb{z(oQTZ!1xPmMpl4>mc0yX z5C#gr#IjhI;`J4Q!7a8R&^4=Cw+3cs@=;@e5ipzp;i3y?$v{AS0A<>vv=qR-gJ2~a zxC^b5!|i}Vq;}1Qe4!<Zt-iB~GUJoR9-~nV!wnk1iwNNOjV^HSQIk(iMZchKyC`?b zl4XlOurVu^Z`_F0l_Cw<wWC~o>-z)C8OTq(;wQ~dUs0OF)#-#*@nDkbpgcRso4)dL zsyc0?@1rcFXul^a;E<mWnlNg%2C`gaI8B(WG;ljpFYO%m0~+3qI|5xiJ?YW{l>mjW zY3|i(F+>LvT@u(S;c!hm?pt**7phFebm*Zz`GxR~VFZ<x+WE{0xG72T(!?7)wk=X_ z3;w%%K~<oX3;506Kd?Bjoitano^d%IHsT%j+dZ@FYTHJ6kB126$QsQwUJUr-D4QKr z&*K-1a&}AojcWWpE=qa%Z_hH{ngmePj({t)q6$YXWUwk0pi^I{DGvC$?q=}Ut6idI z-Yl4{4&w|^;cy&<%>(bxp8zHehR*<~eyKm_L@E5y2MdyO_=sI5y(&Zh$|OfwRZ<*i zB_JsFQ(hi$al6b7%yoT;K|EZluwav*neF>bTMr7%jVE-xg`TMDfV#KoDD_Rg8-v%v z-^&rhMeO`Y*fasbb)F=NDdKfEH`riZEt<P`3MY)u_!=eR3#`4DW-0YhJwBtue-9T# zu`6kstElgbh5z|r^3)q6QLCw$f7Z?)x=$q@N2wLw?Vc<uk=5~yOJ?*U!(f&=X%Xt% zh+Fj_Kp(n<aQY|!*t&N6@GlYfbfs%~;Y5dn4pNEff_*~b9V)mV)!J~CZuAj~jRHwW zIgXr2nBC8obGEmX#FQTbVi@;Xbz&Wo4jSo)OMUrkElRLy&rJ)6g$K3(hAz>Pu?+ii zVqO4i_fi)4fzakvQ;gbC1dQ0qRE7xf-`mnRWkk54Fx?*T0Sx}3$7tP(3R^ifI9$&y z1j`kr+dvg6t~~_I(zVu87-Fqr=~O7p3?CtG+w+ZS;r|8Gd@3+pSg)5s4w2#JPgANY z6$|!@LlwS}t<_r^$!LHAYB{F_-W4`EoB&Iw#17&D8wy{!&RnbV9oGsGpd9bqMcryW zro-K@+U8Fz=f<nCqIoFxYXWg=pTr`9Ik1;|)dz$xNpY3r0)tjHD0yw<E-%I!*iRuI zH|qUxpV#fl9v9A@y8r-hN_o(Ty+F+PTi#6pWy<DhR`&u`gu<-VbF*cGe!2Dxo8HKV zg6_CKkN9RR&3{5FIMc%}4L`4MXJ5}rEtD2jG5ZDkn=^e>LOmjIEl$G4ms^}M{OSh% z`ST3bncM2+TG}=??KSlrJv$kQ2EZ-pBloQX^vT|?=#}fyi$={TyIQn(J5&18f`O(n zN3PzdAf)6w=6-AgzN6I!m|s%-h!_q!f1JBKhwez0hLE}D3p1kBI!g~`<!*50T`m*> zMHXDsUbHc4#4;gBTLs(co?`QD)Km&Yg(WUPjd3y7(5k>Q-wb7xIq#zy+v{*%5P-Zf zE`0(HF-jkEf27Jibm!X`KHgvQLuzoz{SC6cQSFtX@D(uyphrVE5VM9UQX1tR2~!xH zdg}Nb^@bZ~#KR6TtMXQzU^7!zFEC|bNZ_YmZxJxhB@FOkH@7lQe&s3@AhC?)QFf_< zh_uPH2^3ipZucH&r9viD(_}=_YKCBfBH+~HPW;zPRhOw{prqqd_V4`HbB6yp9s*}c zjaS4<xTgmNI94s^^R(N)|Gj+U2S+aUf<y;&ij6!Jq+OG)!c=jPm{o6kVcFV5mN;!# z(6qgY`aNHah6HCN>fCMzWB7DsmJW8#){NUq3iXsvoetZVXA}u*-lBo|uxEw0aFDr^ z@rq$6vfrH(e1!Yv@|-H(ZBR7(`zg!MY0P}1T)fVPvBr6WKnLW3FLnsO-b8$G)y(gb zd^@}NQL&P0sN)w$HJB2F2m~F0G=ERE?2k%c()fk8Ge0jXV)_ehgS>}BTEL#UyiOYW zSAv66A=hn8lar0<$eJTw{4`<})W~)ppwM|}53fdAfBduC@`|<*|8BHE1#r`1p0Ah( z|5hr(MfFrFncVyIpW-*m9^(mybnPTBzf9s*EAC}kSggpDPI!ak*<)Lnv*pic`|<GD zEK6m*!#JKv`LlXu0<Y?uWFRQ#%5<mQvfQMksQq^g-7B1#J&Z<%qu-_TS=2R~mB+jz zDGjDfrN#9X*%H4~*AnH4yXMoN8~1)}ZY}o(2SY!L*<RoR!l?!eCmd}19=$&Gq$}d; z^~AIfIALI@MG(u+!>GjVlzLOwexgDSL*BIQdsR`uIed2g(tm_zx+HR#Rceejp}<cx zQnW>uY2d}az`cpri)Srv@C&SkIos~y*lzS*_f)d<f#)WWA1GZI@aX&ImZu-Fs=d<p z%{dRd1{#=!XoXi>jxWOedo&qpUXKaonx|-f&rn9xB;M42kknW>e=3|!6~~W=<3)bs zMD_rYWRdYEA=PPzw{v-l!k}M!H{L_{*D=<CPqjhZI;b<esV5HV>#f`G)|B20NAki2 zfi?S+uq^&p(WnlVpQ9sX)S8{T_#qkVySAz7qZo@4>aPv`2L=5Av(;6<qIEK`ee8W4 zL;t;1u-?-48;s}sRP9St-DIv3ULq<`C@i`Mft?KV|56k+QW~leLQxhKJdhTri^~rn z61ad{Di&o9UZtVm*&qNpp^sB+mai5Sh&G(yCPN8)l4#$5ERmfa)dcz*<%st7k5G9> zA+8>Q9U*LZ;QetGUcdPsM-pmB;2m`F&#hxRuzB<n1h54*a3H>}H02*WrqDj<Plif2 z3W^digASv>jijjBX7GOBD)y;2i8CKH@f`pRBDjDo@)2V$3!RKD?WZ((Lh!+c6G4<q zsLwsQnoEo<joE(j@-+9m3~hRgmc=$;*|03T>>5rTDQ!mDlfAOSx|S@1RF^~rgwar{ zvItuQwZLaFFS-ZVq_(kB@|6lj5C0CYs%X<0T}ADTN&k$@?VLib+o5C+9+5oJkmmKr zUwf*S1P@{Cc5P6lq?CW-RWBnc5FI7nK{MzO36>6vb0q^Lh40$lZmALhaVP`cI*;3N zyr84fg&a7~$GDLp232>MDsrOXV{j&p*&1!WgPQBxCQRR*2I<?^$BnWriVvDpZG{yp z{op>Hp#5#k?@e@KS}crg7y|?T;NajzSTY<)fn~3`M)9(RnA@h)>(H^ro9_j0iASLl zS;sj-!0>6Mm4V+?Zc5!>(H%SJHEVtz&?Mo;TS@(P<<FCgU@S9rO3%SqeyB;FfM{h0 zL#GiHYFnywSeTlQ>kVDy<x;qQ=Z}FUF9J87ZQ(Gqo#&t=tEXkZ;u>1rD4!}m-;Xr? zhFJ-+N*C%7CU}Q#iN*<|J!lUhy&^loYcWKTj&W7Z#Wk-~-3u%mzq>oYH?r^@ZW zLIkk)86~Vq7>&Kki;=4&rA%T4BqLOk36rzIe*qg+rd6Ln#+33nDU`$9DKLoNzjdeY z`7r}>W`wq;Iev8Vxjr8AeK=5wDD2?YAOnU2q+WNg41$geLa|UkB61kIXz><=#hkUw z6KHfkbkw@#0Td*bLniuh;oU(;PN(682;R0u<S5ta&>el$X-vJ%RChn7iw`@R{-~@? zF-PPou95#+-Dx<Krw{ADi?O<W=#V4kMZ2pBAOLJO{Gy{yXZ1kJCio|b2Tz&5081z` z$gBgQTg=uH8}!y0pSAc5|LvS=`z=l{tV<j7YSuO!_mx`&R6?qjNyLlxdF)^hb+&(w zPp_Ad-A?QJp60S#sy?8F+X-IjxC>_MiSvjBlgkeZLG3!qjot<9TP4-D9NZ}www>~J zfwCY~O&fSqAJ!+CYb3%px<qh$rsI@+7L~&q?>pux5_oClhSh`oq2jaGA8(`ned<}$ zlFkN<>w*q{ciIClK2PmXwe53Wcd40&1ADq6zc!noi;_@~MzKofO8=?fyM@Ap2QQza zLVKlx13RPfdNTdewbY$UcnR#8kN%nsRlOkJ4Yb#|Zl<I2{nDeJi>~Tt7lRjwgCH@C zn$m_FO48tDf6=i}otlVg`4A@Q?g;9iP{`@;sLn5_`XK)D=x<dby;<&#+JW3zH6Uk? zAfZ%cS(4z5V~4g@QTGZ==S1JWVJaa{qkbP4i+C=Oj1DXB+lT@4lA1Tm^@MaT^1AJ} zciP(NrVpZ+Xi3?r(jEQSbE;fv-1QSBk;^j;OhKGoV4@G%qMamhkDWN*U;eKEYoJMR zPgQnToZi^X0^NAisvqLLc)4s+`QJSgQ!kX}4|N{Q3l~f*U!c{4X#LIbHUPNHuDSeA zMW6`~;tPbP*Pgs3frX!DZh((TgX1)Bire?P*hX$`#p@qRg;|Bu|2)&36w{8!52Z&8 zSTshL_9DYEk;ikj;~7q2>k(-==M&DK_uWJpjXdxd22${RD`G*yegBMU3TnHg4%G-* zkYu(8Dmh>2B_PFv*-J=uvsAh8E929yl5`{~aB4qHt$OL|?9I_pZ&VWpl}a-innGcM zFQR|${mIBK()kMp$-feL6h4dEeT5q4*8MGJZubqYn*IO`LVAId3cdH+J(RX;^en&X z`U~8f`^LFuh*$Q3`$lO`cqpE<W`<-TEDzDG$|CWYd?7-339r}t#F0Y7r03!;-k4RL z9JToblqyP?mu(oui7`cDThBVhKlkhEdBoetUntVKvwWOs{1hPZ*v4Nf<i>KUFCO^S z0hU0nV#=XZ)?=mM=bx&!zM$yOG_zyc=a(#n7TK&Jt@CMjWYZ0_a>cBvO@LAmZ(t#^ zF0sAC)p{vX>DOkQB2vXiB9R}Kg~rS77bFO=Ba$LP*VobOz7Yz~b;HIAY>bbF;)8>! ztgpy4zD1r}D2c7FD3GTCLJW@SNFpy8L{Gvj(1KtLVgoEGLRh-j2+4Ip%|z_wxS=LF zXTm&C35u-2P4xJ{!F_IjNviBSMu0E%FlUQZk@u^irk3wZ^yeQ=yli$9yhgyTv64_w zwszUly~|Ofi>|7qyoq8`;5_c}@{1Cr1*{D<G+<3)F9|pN233qRPv&xe`Lq-CyWm(p z%OtE(M{UKqInW0H?0e01hyEE*lNzGfYHwVQNGN#LzyK1&npEt4$M83h!8hb8s<=0I z%eG4Q>Lt^;Noak4EXsVJ70@0lc*gIV5Arr|pqeX%D3p5R$l{-L<G)}n`HNue`n+&n zvPXqC?|<8<)<sD$85JiE*h`$|F1S^&a#YK`bZ$`$N`wXCQ68t9^b?ns7SXI;en_vB z>5ix<Eb_KEj&Pg$?zi5b1DGU@m0z#P>v7#|rI6SgB{(3y@jbvB)T)-u#xI)pW%JCV z5Nw;DYfHlM#wD&VHJ$uWEkNDnNToSm0WQGPsuH_Cj@oN_A`jXS{)|ejfc|`mYNE&` zA<0yvvv4VvQFr-6A=x(dD-;9QBqQ_iPyrr;eb{L`{K|%8p-3NJp_8$C+DI)K6~SvE z#l5@4cGB8UORM4vHJZLgaP1yCt~D)n3Nj^jD7P@Gs&It{8m$yFuPJAlx|VmapMPYB zU}5rF|1b}AqJ!LuTo~m#m$Q15Sw*LlY42}sqiZGQP=BIzegsyQVJo=RzGYy|{Xf*! zMNx{e>RBT4mBm-y7&t3xn|#I$7d=2$TWWqW_uU&kX?19PQL(*(V}5G6YeBM;B~zvu zdB3t)AgJJQ;fOb{!<;k_`3^k>qBr>8#RZlVs0JT85kOihYZrsF><7J7`~AX@Z^W9p zSnLim6SQqO3&NHj3gkka?E0C~vW5QRfa(zGo3cW6KWf#+ShxK}XLa^-G2(<km+xDW zqV{)kilmEOt71vS2tN+oJjl0P!=O@apFI}l!0A-c0-d!Chfm=s{$eb$?x@(}yN>H8 zth>I@GTd4S>H*E3KhdB!FEtRaGQ@)!;g6mrpg?zp{~Y2Cfr;2CifT)XT7P^E?t3Wy zH_HO)rl?_7e-*nF8N5AI`ZbL>GQhnXb#N{^(0{m8=R96n$;z4k=?+1S(;?PB9%bc! znTsa#^+jupwXbu~zrAZH+M!Avb|>=9xlo9PV!XroAR?Ye%Wfs%Vt9WQ!DVIrz)&8z zo{y->FbIH8<%DGUFQej|t@b`f9!XqE-u~%!%DDeFUmp*s7pG26Wn48tFFbbNpHmA6 zK;>Bta#5_Mhtov}!uffXK#!Bf7t`dvFFU#8moA|uqj)z)105c!^<Q-8AOW^7Q2x89 zxUM=o4F8PW-#35D#{{T@qxU`<ZTR-7jmx9Hmx$bC!;SF^dMoCu+=rIshwKQ!rFg0g zR)Wd3<(AWc{dZK{L<w9TEa}d??`JG4xqbSbo|MAT!q8KBnL$V%lz9@IhlHZgAfIGg z;y=MD_7Fw66yo+&uQfuH*Cd=jsG3Ft2@&@A(13-q$OPWlCU3-$?|Ip7VSA`O7LqnQ zm)UCR1Tm)x$l33*TCU0h6aWW8XVG+pUv?f4+XyJWY`_P^$}HM1_G}5CierY38tRDL z)Ae0t$rY(amYPcryVw&AC0=(x_!lknAg`k|Opz}pefdtmCa6Z~F0i`XKyK-+-iM01 zFh_4i{n}Z1`oPWl@wrIVPtR+`ny(E=_qYN#{VNTk_E>5MY&k`&m3o~DaMd(+ahKu# z)D@5gQ95LMYOKd)4BN|gcqq075H6kCBf+fdGjDIjk9>nl>6ta7=<P+rcm?Ii8DKKi zf`Wit`8`fqxU;{{_bzCf8%87*9zz?HxIy&+9Zyg1kh`AVC)+Yye1KasFXdv&4J1w& zp;NsvYOWcuvxdHLF1i;0lB`N)d>m7y_XXDejQOW@`~B0cT$D0R2AY>;SNEb;3dKBC z>g#$Xr2aLNkQVA*K&Vd0j_}c5ktE#aKX=^T7=xTUqn%8sveSVsu(OoWSEkWN|DZqw zZ1m98^NJ-iHVSf!TtJ4|qqg$ojf*e9-b6!&ivV9a#l;O`2lRmW__>$s%<jejb$FAA zA|c2&g?Yi4CnU`Wi0A5&<hzP?cR3rL2+O!s&rvys0pZvI5Hhkj4n~c0iK>iBh2`pj zhJ);HpUa#qt#r*~YFJBuS}Fn}?rmItU|U|;;aSg%E4|mT@-g(}jzN97PBc3+d$1f! zYw$%OZR}MvL)_4e*^uEU=}^M3t=YC~<i2aT99_OS^n`7=lb!66yqA$x2m&IHGU&w% z%VJMa$^zE&%?Q6d+%JmX&wzOc@YJn01y{wo_(k5dl0Sa0g0t!mejDP3QN+|<xh*A! z98tQ24z^Zqp|D3{9*cUw$_%w+WC-30SS)}e*82<_^}1=zI)LV-X3K7QMMs_p{Zi)? zTv*=XROJuPjIF`Sd7$$BQ(YD5jE1WTAE>ir`!igV;$)#$-~sQG+t?-#vvOFUixW$( zonl00QthsojW*aBQ6fBD3TPn%&bN1v&31f4JUurdV%OZRp4+jHCkiU@QIu3G3}k19 z+#Xfh)o-o+XkC>r9{W`B1k|&yONsxOHTyFC54Mw@B%^og<1HhH2Nw6*yH5`(AnSjd zDajlne2v(-^%Z{6Z4}=Ez#RXz?7e|(QUy@}1kcEqU9u$j$`ZgY(mRI1M}Y7uJ2pU> z(L(dr*=Kq-#4&%%E`j%6+kv4S6j1mk9f$#3jCd(RH~~P}xYu32MvPdetxCon`}{Jn zs04e<i_gqf;UA6&Af3&wlk<p<?E9x17><19$J-%&GW0cNrBVGXyS(YT5c5decOc*g z-R)krD*tiAZTaG^x<PbXsO}wR+8yEcn-%_|Xg3;$kP}jr{%6@#q8f75*5d|kDT2a~ zl(e;NM+j><Q<wMg5T|fLDb1x-S)y3-l_Thg)lE`7-!{N!#Due0uqZ4yzy;tAShS9K z<;G_z&a2#6FKR>h+9sU?Uz%29wUye<P@u1DjUvrHqFI5hl6p1!57+!97R;-AC4nhp zCv?%XIrmr8bOmv3=|bR44u-v*?O&{=w~AFHO!`O_weU#K_2(2t!3W*{G4hNWgSsGb zHH|Om`4@KOzLvR*(tU!@(+{wLi92%Om+Qg{<=j{iOha+m4NW{*<ls|-Zvyj`TWuo( zQJ_Wv)DoBB!kpS6PZT{E!0Y%UKM7-+m=)MSwW+#f>;rXRw=e^#^o%G1Cz9*InS5<y z`-DvP_)-JpaFJ?S96j#o(9D#f_ahH;^3<T-HJxkU{7>26TWQh$5^i*UJl8IU2#a_V zd<hb3JB>mQ&ugW6Lwd8H-K(($mNF9{YU}v)h{AyMUgay@OQSK#%rh@Jfh<RUwbO(g z+MZ<#&=n=%8UYth#GSmBr3pmi98jczBYv5Z+D`56bXjrW7Qxmp(Tz`-OF*R8(e8vi z&2e>i0{cRTrhaLNzw@`UO{eckmw@L2fg8Ii*BcLV3*<uG&Dva&z6wyvaURdhRte() z)C<qsxYcH>Y$q!mTS{indj_9RTpmH~dLW8%9m<EBRb52%(qC1CoKv1!rW@>!+#Pul zTzjj9-(Co(TatW5NAa`0)9)f`t^cM4A6{oUYSCxtOD$QqQi_n+38#1SxR|S9j{Wds z7qcK{!fixs9v6T&eqlVI=apNpeD{0Z3#0oZY`ZrQE%q$t+LiT9=kACxHtJXQb!yPJ z<lXB{6RJw<xf+C(H&yU26HLQ4hm#peaE_3Xk{C}<R8nBtOAIzn(vd#}3N4|rfTN`{ z0@m-h=byz)`0~E7gIGm!3p)!#<lft_cw8xztq*<zFfB8=w#Ir&rGT@)V7(D;wg9R2 zJ`?gCU)-;3;6K!v;^?I^jLniiE((x;7c%cc0MpB_j#>%icEq9Y?H?yyQ3<%1Qz*Lg z`57fL@?*t-(cARyo%Y)m>!!8`<Cw{ewOp0#y&Y%fZ@D+ycCGN!V^1Lm;erRRu`*8a zp2ovPIZiK?mw_HLgSV^u#;hR7ClNp|v`D;GlVCP7C*;1!!#~j?WSDJ0fM`e*<$xQN z@kEU2mrvq{R8EyJDlO;0hvsJ)NUvKMX4?a+^U8z%F6uk?0pM}qe>Rd?(`hB?RYsMz zNu$0WT@$~ABQ!*Kd`2E541>1$dIpz;`6>;7X()yFl68;l-OQVjY}Cb)9n{BLhl?G5 zsnU%Fj<Q;~8r;~Mxy~?4H7Y9#k*8n8GQJO??|q4wep_t3zXWd)SG}9-`6ZRfzeI+c zFk{aKRQkKxp3J^ATgwI5GyA*Dlk{9`<L{NE-c}9{36O0|XSVc7=l_e90NyWOQA#jT z-8SThpZ5Ncp}cv{jJg}9_iO6SD^5|sVScq=G?=@W*Jq$>9As=Inf;FP&dBu(n-&;j z*vy0WJ;oo+mHo+TM+|Loyy?ab1hQIi;3lwTawge5aa-?@MQWT(q{}sUNhL?@rETWe zE6Ksp<de;KyY77EUupTjl2IwdWEfS>${q10LG9;vaeHq><RIc^h^iqP>~s%h)_X=7 zt%mDW{fRr%b6-lI<Et4D^OCRxV7@GZpOKX$d0THkK!>*leqr)_sG+Ne)la?_3Cx@G zl-{#)<GPZ73v`_9&sPv(R_*^_JLu?&WGUNl#0a^mVm&~Cwc@n+79us$pzCeWV~K>k zHc1;acB1gCm1^R`>RF=hQSR{Mrwaj%85flo^ud;)yozQe>7n^;rddj4<pozCvb$`p zYC-}`U?=)f82sBy>VBKO@|1%1fz$wS04N|uG45}%DP{$DH9Y<bC)J=j;aM2`lviNM zib^lh45W{ny@x<@@jG-l@+~O8Xtk-_vKS<o8&MS>kpuQKWZn`((wTxcQ8p*0)AI33 zF95+Hu*ET>%a&X`6Z4n+^t9*hD9ztV+s`XVvW`WXEnYU;z8qU)V<t*b##79<Wvfa( zY(j`HB#?J8@`5w*l~bXgV_~6(v2r;3-@Jfmk1xOykzp|Ywdo4><STF6D}VvTWqchC zre-Ut*{L1`3%stXdIoh$&sc+4r%yST1>Q{`n9(q+Cc+jjUNT5l<GS>RbM{y8B_mfa zM(kOu1<9<QMBr2uu^nNRaBTI4Q$(7-cX8ps9jSzxbhD}Sw`9acLo;*o@y)%w|4MlE z(E3EKbGe>~jZj_1@5pN);1C!<hXaPc6dDc4d}O`cI9ScMGs>}ke7!!1V0hCskHJFf zwOI;&JE5y2Pu?z;XV&Hb5xGA@;w|a1xondB?fH4-si4l;BD1!$?PweS9qCt$sDZT; z!z8{(wU?(bT4#zAj~fRx#27Y^=&jZjLt;p_H)6Jp7Eqd;l2mNck4V@`78r^*+D;{J z>G4&|BZ(!RzvTI-DVDto$|3M#sZu%`yT=O*ye@H$g=G=^VC_<_E<C}mF&Um$j9gvW zdn!~VA6q-eH}@~bpO=HTnYr`0+$jq%DzvENI%2k6*x`k^5(fXJm_%~-#knNuW(IHE zHyrvU^*Jcy>^F<&2{1w;=J9ffVVj5GfE;1_v~s<%vgk#jVVzLCxEC`+ZK2eh%NK$N z31I9A3#8#+lEOghK2IhL4Hhf*3AbePbp4VNOg#Re1YRkQIWW|WyYf32_-}nXw(;p$ zNJE*|ZqUj=;fGkGvmS^nQPwmFQZorv@l!JIy+nvLjQ)1ngGY8gEPKWap~P>yY=V5F za{hdy@j2jvz<q?96duAw0$@B{OW<<L3kTu+pet~FY^vS1iFq&8(_V6{JU=uOrZJD_ zYrA1q0G5w{$Nl!xxpP(5w)(Vd#+6XxhH!*tf~Z&+TovB*L{u>N0Q^}LH2njEx2qks zs;Flg=DJAxB^ws2T|e|ma^5m6ZxY%u8TN-Cbs{mhZ&>=IB+`Gh?1hJ?0o-cy4uZdn zNGykUr<&~x)Lk*}<+})zNTdV;E`dwEmbmZrPs`x)ckLi}v2VJ_jNiJ-+xawmBnTdk z4LMgJ>HBFEVMTFgELIj`8yD?e9aiCyT@<NCec_CH8<T6MlIBdEqt|+1v4%&#f(*ZM zUs||fQC}`o^T4^gq0Vrsw)m64Em+!WhA)GQfp@)bHC5YAH4OAYlBd1gu&4J8knrA$ zYsqFA@vvrZv$g{@Q0vVE7Vfa(g;pgy{R($6B+@;j9qm_oXtxA{Zun}C<b)xZ44AWq zx({A=*&f|;4yNaaXuErru$-V)p9iUy)4b<$+xHr{lUPoIr>Pz7v%KRP40nll3U2V) zA6i#<6ag=qudOJ*?xl{r+l4s0l=Kjvp8ZS4Y$cZLhaf=Wc}w8AItF~?V)M#k0tfLn z>!jm--cvEvhUol}48&#|!YJmpd2GIN?>YD5cj?ta#c_9!kl}iC7<91<-~+5E;QY~Q zQID9Li|!FC@q);U-<Q$Ku{4rbo)SS$mB0_Q3NcYZHAbEgu6knE{RN3cGcwO9mf)kQ z>?-d#WxU`N1b8{`n0YX6TT>YJdcrih{;SxN+s_l+){-QH92|HQ?03FG5J)t<b}bSy zV{=Mk1aW&YQ-1Jv-U}uGFxZ|5bmy5J>xcAMk$sASS~3j1hHz*rfvj}w<3)8t&)dC} zx&pv>MKineOX2Wk@i}$mjoHSJ{Dn;qXn|X1Px@g(X!@Pm*dYw;#f*%n=OsR_0~mpJ z^`~}Y{t%!iai&%3IHR+)uhZzK)me_wF9#d{Zm(y92*#;Gkh!PvLsmYu6+(soSQdxo zoHImUxcyzP`D`>dZ}*c*wSX&kyE9;dI>4df-hK2#u~4e+%njw<=q<8CZ*$+7a`=f! zo`34cS+h4armoulyz{vsd9hsLWIYisD$oc(uEO{)>3R+tp8mWe6FSU+Y^&dG%PqT~ zq=pxKl#G1If^@^4Oc4eM3-V7!ow(i<e#?9uIG1Z4>tvgw7P%q2KRv~=HPHe0tK1LN zF>~cxH0n}Dmyjn@%w6*hJR_CKx>;T9qJdlKvU&)eJ|Kpy=h>?k8;-owwcDBUQ0)dE zx>4WX^>F{wR!d2m4&>@@$$}nPc4)+9<k5tOi041XbsxxdR-cXTZ~re$u%p$m7d2j? zFIe)z!Ff&b=YMU6ZRVHX-X}&3sui$|sF-s<8wuNoxQlB{53neXLk>SvBGcvnMMbME zfR~~!K)9|;B`~+4K*p$U=i3Q7)q`4p2HWzm(Ds?Io0#E%p(!5xt4l8@0oDYc(B6YX zuE57XUsY{W;j6uObu3V`-Yja4(`#w)7RFx+wAE*^Oa^WCUG$YFf5_DT3Zjw(N0-Y! zjU5=I$5c*N4M7iJU(if+NbbAZQF9rc<Ma;~3M~@{9hU+TRL4|<o6%+P{po@i8BfnR zdYHVc52L~)UYvY-CBt7d>`4;Li^`o-QDVf^0HD;00|CDE8LMh`HI{*GEdf}iP`ep| zsCY@Ox>gxnkKCag8<-K~LAI9EeI(ly0}aIq%~n6ENoQ&QwfHA^`g)l8M~vABt>v!k zbX(h$AL4_usLY+oW*@c*bso%ocPTBh%8&RuoI6jM+*aXIW*B=p;GUU?{TnrWD0gn4 zVN~^<7M-*dSW=1u#1(u}P~nDRRf0HScfABaJ>2j6D`l_^2$Bx|XSjaH&8g~G?(;6* z4Fg-lbh-HeH_}zhh4?eA;-|d$GHHzvU7~T;MZr2b#dZiX!%;wve^{44izM5;VRH;I zcS8!<O%?bV^cFI;9Fzn5d|2?rW6bDFY3k=oU9z1<y(^45=*`LIQ`ZJcPJ8Zk<kpes zUZLsQ7^E%DfIHmavDj0`TN+ozjUl4&35U>Rm^{IG$f{C2fuC0bKEpQ!&L|Yyi*h&a ziPmB@s4(vWlM0IQFy;6~D>7U9j_%)W-|aah=?YvYVj`cKaEpg#;8@-2u5no4kyY;l zwKl%X!fls>;a}qhd&zB|9wAO1pEBn<v401b2I*aCD=_?=F)sPe(tI9zuK3Gpki|I* zB>mM{o0R*BZ>QrQh6GDTm@!1p-+ka14GA+fj&L|>#HA`wHgZo2;g+;upKS-Uc4b<N zu~JLW(jdiay$21qS(0x<02^Sr36kuUzq=iiVL%ohDz|l=IFestac}a=8$CrtLZ*Jc zu;XES38Ra7(;Bt{>Mp_suPl8Kqu1amV;1@_e$D^x<H<rl5vvMsXNkSiZQHzt^HB5a zb*n*=QrRtaNo_#iBc;Z}x=x~x2{+9i-g`N2%SYD1gIyP@pHH7aw7@4M2;JG=D=kQ* zn{V-ua$k{?$U)tdy}@<!0;U@Gk^P@hh(_8Eyz7ooN`Lzu{Y-gCc#{Va@7;?KO5hf? z4T29~YGY{cH-GI$RtKj)McAM<`CJ7K)OA^M*NNyH|7m~g{M~)76OQ}$(+*$y@aoZo zsb>#-ZA$aGfEC8~Nux->k|8w^suFlhsP~~sJ}BM&<lEskkJPYoI421P{<IalFNwGe z8+d?#)HA0a*vTn(UvQK>qkiGAWh>9ve+rAAlf(>o=dNV`wHaN2tv@(lr13!Grp>6B z%#^9jIppR>%^1h@H-L6vX#zY#@|w0APC{Yzz<5QP3mfl&;PU8TOp@_#wE#nXZ6r{I zUa1^l$~Z{-+wv$pFrQu9U+%R6;AjG!If)|h?f=mo&dBdI1G3(z84u0N&`(d>Lft0? z0WCx|;Nup<f3Wt$0AL_W2403Itb-}ZCh=v$08Jf+_DBD&b6?)qJtR?SsR(rvFkg-0 zNAS9%T3kyr@-uA@xSDQT>hBtYhO5+OL!I#TaR*RQ7e0zyZKB=}6G_z?bOn#Z2ywRE zwbv2wv+u5LWNj8!2^2!r^o%Ka2!-eG5?f!ydGTaR#fQX{;8S_f)*Q3#+}v~k9D0-? zpqRL*zy;aA8e3#XtC;)78^a%>R2r}FG~u+)4LsqmpfCZ_Kuae;)Fzhzq3RnGs2Wy- z@N{36`aU*GQ*m%zeH<kWZ2~9|c}ljqs0~&W4HH-ttQJxtaJ97y3w+i9vW5jTGMidc z)#-hbH0^pU{EGq2gBu0AmTanegXm|uR`(WA<p%x$tV56A#h*Q+J&y(1A>D{v-&p1A z_Rc1N*Qvo<UftQ@PTi#l*Y3>G@y)RvbNnI24;zG2?9xHa@Ou?eU8jydq`+M;&k2Il zsAt&ZCKhj9`&!dTl)0@npl#5=3rzY|v!I6K^C*a$=I~XxcgPFO<phm+6u<D!Jh3Za z4hd;h_QSM0aFyu{$#F3{SWopTg7U0sgqtjj3OP8=lBvlstQ7Ebvo8-Q{B%!iUpT84 z{#zZdHs&>^f96gAt}C)T)t+nqfd{ET_%^kv#^FjTy}F2<^V<rdNI9|tuh#mS`iy1K z3?|iOZd!(q{Do>U-lYBuH*(Ehx82eQ<atQB23cASLk(T3s(rLeJoBA7(K-+<Kv-WD z48xI{S;AUftNz!IfAMY2v_BF)lNtz+(xsz&@a$GtL?1s;#lU1`c0+>HML*-38n`a1 zw`;#_w`vf*Q<t(-a6~XGSSeO4@6dg^V4w)#ytz_~n4h%FM-~L4z-D=y>H|*46Lld0 z^tmWQiRX-8zfk#`qwegxq7`P*>Ziw?7gJSliBs^54ndLHLcQ=jh5ffWwo9~RPBWn^ zMs@5t%~_{H`-<Y~k+>%Ue%mZ0;WXDNAV4<ToyOF$O=uSE6Ac0C`}}%om;NNO&BRY2 zqjIh8OH%&A(MMgr$ykRMUy%*%oEzuz$&c<H3A&GR2PT}iy)^u8v8(CZua`FZv<sr_ z&hYfUU0y3KxQ|~nI#!Xr8k5RA^_?CMP)dJT(~3iM)6SKfKti!@Vq{+|{}BJ!b51Hv zW;PmwbrB>a@B$v+C(@U;ZJt5lY+5jhn-|RmI8suPtb>dUH}1JIyD`=FsT+`ZEw3Y# zsc*ilrtn8}SQuWr>4c><E!Y*dSgF#wt?gI2afa7s?(N@4*B%4P-X_1S>7mg-ncs)W zeH^ZN!s!*f-0UW>1hT$%6hoxIO=g$J#g1khv?{?2Ae;%W$ItA*cD4V#f2PdyP>mpx z1(Z4F!r0BJ22PoWi6QEuiz1#T+yEq|hx<1O=mGPhRUt2KzzWT2umz2WMHMqpc*`fQ z`2*}RBb4dM4B@fD)Cz(N`ofq>1*ctf%7^Xy3`O6sr58MGlsQ4yr=?OpF=b6|;AP=i zsgOR*Pg)rIYbsGxOhxgBf$d-Q^Af*$+E7sa;Ubh&gOxwxc-r&`3c#|1lQ#78f6q(j z4X_Gx7x2Iufvz0PJbAShrS7<h_ctz(oZg26Vr2j@$F?t>t_%B_DCQ~9(_bXMlyP5i zkx25AczrRhM#+E?0*lk^GC+uc+lP7d2}ZB{zu8@3iD2KX7(Kmv+kc^I_}Uh>;6SRZ z-)E;{ddFT^bl`c*R+XUc58o@T(nQMl$P(qHewlQWaq`(Dp-W{E1!=;kFz+7HUdeV9 z=P;?zBkc`%+lGe^nF#cQJGLzX?EX@(m#E?rTYCqwZj?0ELpMhA)*zd(VklC4<@YIT zouYJ+I9~J^yv6F0o@ll!G@h0`QaB4xTmjVSW1#T==EJq=lT)ZjIaf6ca;`@M7m%_c z_ZggY<!Ex_rI;g-xEFVNXda(#?Vs0rdk^bY^vDYeJm;W*(Bn+2q%ZM&Q-Q<8gcduK zh9cg!ikS-3=mXWMG_CL{yuE!#YSm~vUnwM%i$swYr-!3dPi4owRx8V0t_i4y5g7a> zsSFr!Qz<GXH)|$4Wb5eafJPAzQmIS*iS;&R$cnVr-IT8txW`hoP+AnVh`8_hJBv#% zrDdY4#}jE`A$b^4s`GVmAm?U*<iH?<85Y7ZsKqOdt+l%ky}zX`N*M#X7W2w5v*Y4i z<GiUV-TtE+C<)M~6D}(}rYC3mi9CRN>lM?fdFq7({B-ev_ekV&m~!J**qf-2IGPTW z<(pN5|4|$qQ}^8YEPTIN>Y9V-`Kx2XCklqGW%XJ|k~r69ot_aLQ$6S6U!msZ!m%d< zC$Vz1N5wXpBOG%)dLN%xyI>?PRugxUB=(>8k$0X|r%7f*>FZ$H6b#VQ>DTv`L4Vz= zwKATh`l0Ee;ZmopWrGUTqdbzI-_dV_vBO9ip#~=vMc013VN|3v-`BV`CX;b|PU_4E z)^)Ajs>efT(J@c#DVoo2*Lyv$<GXg^45MEZRA~8TYG^Pm_QDFtWg_jBQu5Vo7FWmn z2b~h<crwonL*b2NhuR3)v>dNO7eAWnGtKzk*SyiD%@CirtB9nY7TY(k!(=#Z4u~;0 zUhb@r3^?R$dhzJ~(LcR5hP&@hDsD4IBPWl@evA^1vU|I8vvO_^K|Oz`3hy}odBd5L z7XlwpIJe;?_u*LF>;ADh2YSNZ-5b~ci|!!Ghl?h2&sP+840kxU1VAf{ABle|BW|Vm z$fuzr`&$UeRrqS^1`^PXIXflNzLHb?YqiNk$4Lm&kwf>w)EW$L3hbCaJzp&t&kJn$ z-QO%e`RIa8?%|?|wYO#Fi&VFBx`%J>KK&)tf~blq(#+9-CzMwxvWKnI-4+Cn6%(#u zr#-z_F|n&}>wfXR=KS~1<cg0*vVB^B(=lsr*on%{Q9km+$Zt>rZRXWZCm+CHedHs{ zq$}nQ4T2GY?dQ1JsR7J7S|Z<bvm@XOJ*f?KL+YlBb`=HEg0q#P4`Jf#YUMA<H-qDf zi_ETS_X+MwD-e9)`dK`>4D1ItgWYmS9<Am~d(}4$!Q;cit`Hs<orCm;v4@PPE5*3C z@m^O!^G5j5{u)C9!r&#q6m-k|iqEZvv^3vg98ql2w`~~{?1_`Xk-M_pM;V0`J%&{+ zDFjh~N#Qkz95-S3vu~vOK!GisBi`s(T-V#rPYht?Mu2Yd9laf9X&t6m6<S<wTPf}M z_yOrIZT?{wS;F4z*4+r652(&K^&1$DAaf1u+sRejppeqlk>jJ`NGvOE$fh>o7r65^ z%=Z~#pSY`48D_>;ho3)TqNQlzCdDJ&s&OEd@Kk|?tlK1vC|M8+K&xxmV}bpneMW`` z5QRm}g>s0&O#g{f<*94^%~JUBPW`@7`AHW6&Hs)7!(EvGY<F5DN>rh}G3`GJ-3I%3 zgOYDo49VHT1I8#Xb4bFQw(Fw&uyDFZm2tL@M$Si@JKW~#1tJZ7_%7A%%whgWU1S8c z9)~gsBiq#A1kA#fyWidk{GXz;{%iW{!|;b~!07I9z!=@#8w?m7A|fT-DUAi&gprPv zmX?+h0a3a`T1vivpn!mc0T?_yf5Q3Uyv{lAbKlohErqY5)biuUo9h*d64FXJ*6zG5 zAc-NPPNO6ydAHWxH)pxI$CsoWTTnx_B!=wTNV{A~)?UkDE~hFs7X|2BI~yTBmrS~H z@ASr?nEN9p?N^Wo26W(ki28C3pWM@EZNlU4T!;L{#Pi%=u!f_W5u5R05su8{OsH?J zR(D^Y-8QaliGKz|@3fly0%K4=gUu><>y+3bxWvOZ&9c;=<v}Hl_ZsRjXCeJG3TEo0 zKIVgoQd6kqNv>9_cS*ll5*{p|?9WRQH!Q@m8{oZ$8=Dj&TkHP_Lk$}#gq)k6Nx#!~ z;o9_}YhF!B-o@)n$7V?<KtLFrGAymi5Pu92n2>C4o#F&jY#u|B^OY^;P2X6+j5Evd z2HggAwJ~|U3Cdh}C-l2?=&*pyY!%MKkf@!^JfSS^I@?Gh54BJoGm#;%$|iv`p^LbF zY|ItaC<yRdodAQ2I~oo88~bSnbN~q`3=mnqX7E-guGS`J{%QQ0OK{udOd9Fbq^Dnq z(Xakf;D^GamB|d3K(}&I?th=uPkx0_hn^M?64|LtHXuKH^53373|q+lgXN6OsPBcE zKFT1(w-UO2TNM*izH`46hQExQr?>=jiE>d&$P?1>Rg1xe|KvEHjYDa6)N}Y=s4?@i zcMj#t6UZ`#$X?ZvT>pwwD&ra(HChS6&7k5f1_STJgsM&)K>{#GB|yuPb8?b<Bocs3 z%)Aoe0bNoL$)5956Q?OFxohBIoZ(-Zw<^U97nH&Z>;_-etUg+_Q>eG0-d~Pf5q>~A zeDe&MKUqpnmP?LxGf~fUwpYn?B~{d#HzNu5j2as<)!3M!Q*#!I)|=V;;vNcw8@3FL z&{EctTwEkWfIQSiLFb=3bi4&xDL-(*oYHW?Ic!8@m*0FWa$`{%9Ko28d(Onr%a~;I ziik|u*;X?Q6=)S(cyxxAV8CeXy<yj34`H}<tu(N?ujP|IjB0_;pr93;iQ@Cxy?JKm z>0R`cHQ8^HhBqjWmlhWUH0WfYpQ2bMldZWDtM_VpY&)xyrHh)6t=~izrN|QYIjkz= zdp~TmFUeD)TL~1hkkhD{{Of$&wETbNy*8PIH>FSG778{e(i5d)O*gJm&eLQdiKbuL zA*RyfXRz_kDrn`#aI8OzMLlC2g<5=x(X$?<N_X3?c5N??L`ljzcZ&4&e8L}f0{7-J z4mwQrHfgNDIw6Op-3IVFkH^L=KC7=IwW*%LDFT>9R@fwQzXumYZ6T|}HHTFJ_pBKi zXv<qg2-q^!4_5ijL(>TbF)O-nXt+t=RF~R{46d}#;IkT~k3eScK0z|gNpaOOM{qi8 zQo7F?W?H#+|Jj=P$TFjIv<JcY9<kYWaLOJxM2I?6Jt^}Kvrh4t;>gC!Ikdg231>e& z3$Ah0Ha(`uNP0}S@p(C4!cq)valb|GG;U-Wt86GyM!AQ&${jO*-2rff?)1GVpR`xN z+kJehE6t2ze}b0Ir*4BjxG%G|;b7@SLYGfvx+?(?;tX_b9#kZqwIrQ)%(Law?Yg(d zcUa=u7m@+W;jdt=aosZE8C(u-ohuj1e)ppov@Z(^ic51TOd7LV?2L@RA9UyUTRy*= zaUGatY>qU5NiOu^%ohW>9QN0U*yCZtPOgOt#hudrnT|BXWo%_f4+WbBRHrHd>tnVS z2IHw`tX0T)bW0QPqWv<T^4Oil!fCxe6Z&g6W5U}eKFu~^DVtES@wa`maJRN|<5elm z%@DuWv|_nV4hClmP$A4+>ie8jH%lc~uc!S~^wL+;xZ-NzY!^{Yxp(dM$GcmztsP6g z201NxjGb>)ahZ#@pEA@2fQ}qol{TvhW5MoIZE2{{HOWY<3X}cnvUtV1pZoEC>%)&0 zCc@4>OH<<pu$?UV|D+{D7jM^{x{56qblN6xZf`twHNyiu9@bU!$Cx)8OCJt&<#@06 z?L1r$I&ANP^WuE}Mlhk#z^Aq(C(p&ML9q>p9UQE9Pc@xPXt}9J2+1eh-PY29&v-D3 zZ^#jTBpP})yvpCD5IqL>%c)bF<}U{g$fVh_%~>RjP#&0TWdis!X}2zRpA6&^P8);p zq9nF=sGzjf_`+M9+?s2D3Lfam!1rpo+pe@&l1=bLoY_!I2a)J!XPGOu>`uMzy3p21 zSR1X_&DI7WRY<A{U`jT&G-T_O^RE0WhP%t=Jh@32mF&hg!cwwCxGurCG8>xeWY2>0 z!K@^$IU#eMo5rE*uVn5J@DGg>QgWW4X+1wp=!d2nSvMU->y@3P+nkJkDLj5EnPoD} zR5#MkyJ+C5&Q#*WQ`xKu9ai@Zq!tM*Y%FcjyU?Bf3;}YYzy8)GK)tMik*$QDtYp|? zvhdp6By^Q*tMAeKy5B{{Q${*VPm3!(&VAqCE>EgCd|}&JJDd8%0ElTcsW2fu#O91B z8NL(h9Zt@9HD9!p>^1+^>N9rZ3OumRpV`k_Nvx7(aju@uOCIY=knSI@Ix7F#^;7T# zg<R~QLx5d)jC~~w!^vE*8q~QtkD?khD2^~7nJLyKxET<aM1$;GsgD0~Ya<~^xnpWY z>ksVZ{hAL%Zn0lfrE}P%Hyh<BX+KGXGu$EOSx-ZFx(*`r2!;PnI;wj21i4hno<4W_ z5dPq0>PM}=8C3}z@E3NY&5C+=^>!$4@!O;FGBmE?ggZFmR>IM7_GJ+MxWtx%q_3(! z|IM+K9)TYTf*<d84^<TvQjU8ChnVn8EAyyftiBaNS={#$DV`VE;Op<xJiwKk>qGA) zJbj~`V3=ij)9K!+m$t6Q)xNO*z70!8M@~B7N%yI&)Y}Ieng2%K9y&X;5?)RbCcTbX z%yOa6pf?vOsaujXSom!>W2oDaS=xlci4e#ea<Yd>%xO9auw>x3c!dg~^`CVvj#>yL z2u*|5%eYj(p-La1nxD>zI7pD$r_jz>Wy|!gZlhYqFFcllDwW7*0;!gbr<uD<6RC72 zRrszc+I5Xczvic%RgTlnen}iE=nJt@FQ>(wWc_O-Kd+Y*kvFS}KygDbM?DX#OdbDp znxgo>tnQ!BU8gxakx80R|3c||&9Rgr1|&a)>yCZbE1CZqkG`P4V0)efQaa9>`eA<y z=L*A@*CTMUWxUU>tmd=FPoc3e9=0|MSe0#-rgPz~h_c&r7B&M(GEHIHWj2Mobahja zKgQtFH)wi|iI?)Iw93riqHDFti)2`Y5-C9Y{9-3HCP0c{qX&h%<Y8l4?p^5_mn4a3 zZ<L&FCr7^29kodqfg7FDEsj9soyhFpuKM<U%Ig`^cYC<_+M(4f=?6G6n*b42(hC1h zWA!>Pi4f^${XT~XwSS&;KYsXINib~r=zU}7BHw@uNq<oxuatDuAH!cW?nRWZp`b#- zt{$MK^+#@wk70|-YfT(HNd)E|;V~sUGG1BoXKTJD$G84{Gnpq2Bt85|XZoC=-L&6A zLeK-qK#^B&#~Wo>3UY1E>&`nILuW$M1=-;1O{SCZI9O`36nqM?kYM&^EH`)}avNmR zDr>=?4WXc^Q8|8p19%AiET3>~h)NBCPUQ-CZg2s<nX-q<WJq?v5eVh*sxZ_O2J+m{ zmiS`&G$p?}c@h8u1$Y2Ac4g;l{}PC-^NrA%<a$^1uT%HEr^VzzFoiWS0lSeLs~8YT zZA5QiSPyOrr#@o_IAkFo#0Ae0A~EmvNtk(TUzkq6gMewc(OyolTi{!Kvdkecezb@K zE3>jRUmuo7z~cehXEecN(37byl)`n)h*gEr&!)d*m?+Lw^V5MbCJ@_2vNlvW`}wN4 z>w$4)!>3?cuW2JSI`xbTZ!0Os8c=&4%QaqIoCL{8WFX1LxRFfvA*u6P7m-g$01^~K zRXAT9htEj51BV2X4`9JmEh71-L;IXXq}g$f2K4e9k29i}Z|Qlv&FgVtc9f^RI1008 zqj`VKTSV{WDow+Q?ApYDhaBb85&Rs?yg(`P`-sf4LVUV$mXmxx|1+=G&W>iZXm>-S zyziWVZuo$$p%x83zMz_B+fh#=9DTzBu-Bu1{Eq~7M_&>Yw1G_hn5C@;56vVYgJ>X$ z;z02kTW+pTr?=q|H9E#Az`Zq=Jk~uF1c*@&@S~L7w!udBQC6h&*3?(qq$v>Z#hFy_ zPR_h}^dWP(eh`Qr>bu8)6$iYa=@fubje%oS1kd+X!w(>64-bdM=CqD0sAor?H~1M; zD2<TM5P{GYnG;BX%CE=C_lDOQ_eZ-4p&}W}Ul@40W%}x6>dFW^B70V5sOwaB)5v*( zq|M7AG<wq-Joh?fhPhT2O2AZ&+rp@Li4hkUK>BlyKA|$S@!J1^j!RMcxl&tn)WMcn zAo~L%)T~E~#vq!gTgwC5NQhifTlMglhT^0jTwg6YGgE{vC_o(GL*A{o-$Y-u5xSCy z5|$apNdq2wL*ds*aPT1nXgcUn;`HJ;xpUUQ6IP--0cN;bIYDx@F3b!9T{_C2QqFcn z0P;G>CeouM?;5a89LzD0>~2r5zaIEE>MKXbWt!_U%u6^bza8bwe}bgq1zzr1zcTJB z$xY7%f?S}KdO_Oe*(qp7MaOR*wbjcTPso`vASU^Ys{z9wXQD$vFwesB$xSJ5o}G`r zoFKaILZ}$9({bCAaAsC|aFbv9D6c<p#*V{eU-|0qmxTyDJ?5O&$N`jyoPiC#xGEX4 zD|u7p2Fh<BmpiQTwgE?qHvnj+O-KlQP|G#}p$OtUll0zpwyk8A644265n?k_6p7av zu4z-{gGA_QcE6;_6LKGOCW`NueTpR?(E<FUSB`qoZERC+0}sHXX8Mq@#$JXh8IE9< zFRG=YKtYfAb;i{e;lT)r@qy)>-r)QjG1OvHC&0BEQ!Q)R&DuyQbvGedfBqK|I%_QQ zK${2HrWdDSB~<`7;dpF*F}W<%3pJ>*PD8O2MvZ#5JQj9(F4#9MQEm}8K}g}HNa|bd z(ozVqiVQ}Vw$C$1@sQY2|De|h?Z#0AuY9Rl`qIl}>QlY0edCKubSHKYV+}r`H1Z27 z<d7G?bq%%!Fo>a4by#qck$~b{<YcOi7f65~N`a~5V~>J(@GrYQ2VkhM=xuE5cMCo2 zJ#v*3R08iG4mj8%L%(LztK;HDz?Dx+>uMA_yDK=MO*NfpROKR(D?Iqbg&t%f&maGg zfsi}4$RIz6FOK3XUEP@PP5xd&7siEoy>@dXmVHO=T_*$6S6uE3WA~?Rw*Mh3cQwU^ zqy#?9xaf1U=v#zszxZY2s+dt@)pqPI^HQ50AUajm%kv>=AV_8(cgF7&el*^@EHK@z zmuj%tB9Uc^mZK~t{o;~vymSfQJoAT+yha1j`Et}9um1g!W`<~!1R=#8!xvH8FNM{` zf5iRdRAONW;1v=1XgW5I8Y|I{IxEv3apI^Bjnx`}Ls?$zr#+#8C&?zT14l~q6vj}1 z-%ix8Nrf$qyFuWYPA@Bk<rVHZ?Etxk;0TY}y#?WDH_>N%c9T8P%MOfig%yF3kQ={M z+a}!_!Y4<<ZdHA}byOM8pD;*?U`;T+&gDL0fr^kdk*rsuVW*cRfn>f*x2>rV#yXro zd~z9x`;cbDW`Fe2w8Wzyvhw`iV9!~nvOF5<!oLX?CFuLbq(7hByLKe`k~C@o+ob}W zNfHDlcbqJiASet1%1p^(!2cKb!46B-^i9*&<OO!;lbLRU#BUrP5ZAUgG(M3Dsm}Ka zw4xzlWo-3d5v2w)GhdzLWD_|qQ=fq;`~=sZ2%GLUWV9xw8<{UN>}I|2nUfn$C)kMR z(ti~qKqxJYL5r1F^zh-={0%C)TcsOY6}b<iBv3@oEtKyVnqTY$x#HrS!EKKEHrIkV zJxG&e|0R;!)PjL<h-djo3v*4dt^ISV)24Q#N^n}W`<mDnBdPL6q&n~ZXbVAH1)B-6 z=)*?uzvRSuM&3`6GP3U*qi*7yoC~qj*HoVE;&y*<-$h96xon*Dd?@U(0Cb}D-U7*_ zveYBfQF(@E%ElCV)1Qy1wpXAr)Z_3$pvtw@zMzU-%L6t<O+V4>!}2fkXM1?62oSVb zX420goG@Quu=TUo{gqy{c+<9nTA#xUK9{kjPAIwx^eNd~Xi;K2N&FUWe=rfU%(01k ztj5UvXlL}QCz7w<Jud2c_BN1nt*kYqbp-{3V5uxUK@fg=HgMIL<c_A&?5z;0_UX1S ze(Dx~*9)7!=KOpuDW=WX$>Z(2nxps3`MBVVdeGy|gq`+-K!f0Prh<_puMwA<_Q7Xn z9peLK-~B0!o89DfA|KcnPH*ZIb&Vx_)6FJSaUyPOI|x*B06Ld2l<^pEcJsh8Pt(lv zpHSti=?AdeuT<P5@mQwgt{_C3{p?LMgmK4oezbFw_s#SlS=Z32{fxw$MIWc;7~FAF z8W#?i#pI54mErz*6n8(5l@GiKqLTB5@b8A5-{5sr=qD@H&yiyKyY)4jNdC^)@a9J5 zL@sRZ%GBVCZ^N^Tx2pn(W0&{fn|5h720wmw6CK(_(i3S0zz}1K`>%2wgLJ_>)Ydkr z-6b1+Vl2~Ni=Hs_6mxpFaGG1%{96LK>rA>YJ4m9CV}xfE$=z?q!1`)~RLtS|72e!X zefDwGfEhKrQMGBo+nY-y+(1DuyBqIOE}EI%Fh;(Yks1>_k&oHvv7sO6k3>V!6Sl{9 z4cR~b9Yt$>$LVkDXg<j4SOBWvQ%W=gSHTuFk!axalSvaj7TCt2!JrjAHSlBb>3NRh zHlBBvL?H*YO0@OuB9joj^U>jUfH7U`#)klEUOqj#v))-lue*5#9QiqGCIgersM~s1 zjkM}b=!=CBn#)n?F!bfaB2152U@n>(?yOI5-X1joI8Dq{@T%B=fmRp24X`G<ME}nX zhz;frJ^szByJL;iQzFx`^r&5TG{@(8j(Z=OqR^=-8xA9|*AsI{$Y^wdRn?DJ0SJdL zJW0Pio*c1-d<D7Y8%J3^H||MSA!ATnwj4bfFx(yAXSVlA{;#_$Qz~qT18Pi*HPy%D zEt)KKb+G@QG1H4dIu&en(!eEXA?nlvngF02qoWq1qy2fXgn<lYPD{~qm$GV1xNr5( zNWN=(vKPxIH=EwWy<ysL{Dn9vRz~2d&7EEfo6s4P?L9mx2;ef0^`lNmyXu*uuNH93 zF&7ZV2GMKlKXlzJNvS;~m8ds4Q7AGg%7Pp63qIo9xs|QIw4p&e(11+ybmsEnqc)1! z3Opnwu}Ed|z$-dY15TT04~VL8swO>J`2lXfe(PGzfV!qTw{!8-U)LBQbUlV<e3WkN zV~k5{8*7=Dk*p2n8G_O1sh(V(jf9w7^w=a#YYqu78A!7}S3k6@gBmT^m{RkE-JB8a zb41E$vh}ogyBj*Iw#VB_k?a9XTR|vIb2Hq$^6RMiu;TQrqmVxgcy`@HNaLb!2`_Mt z(`w(b3&(4OLKK3)Dr-B2U4xr=u2J;IyP|P_%Fzs%EQ~yT$rX1oD=_7%NuT1x`O<#G zc#EXz0J1iXT1BQCBP+g_=k=3-4q>?`&P?PD_(u(TwoPc_1YFRE-r~V~Y7e~81;g{D z%8Tj}PZC;d3@1uCR)$6ZmFe!7L;Bu?nv9w3&17-Nmizu8SVP`TAFrbkIiOV~Ea4I3 zLxWeYfa-ggdQ*HxX6{6qvKY8zk^Cg@{&>f533DOw0e89Np2yO(i@LE*;u3~XYaWQr zgH$g&$LNiFE2i>>LvDN?{MCeKT&C!D68x3`!7b}QK?vN6w7!hOFNWdiHn?3v(UfS1 zJ$IztHeJ6sEwi2wYFfuI6kNiH7Tuyl&0E{zdwyS??C2Ttpp^44?bK0}1buqLv~X4< z>74XLI{dp~n4snBf_-d&*<%{CgmE8Jxwb$<A@M}_`t~9rJ_?;0;7zS|BvhW9_~bKt zDXQ}S^m}jc7oRUv^~-JANb)vb6NdXiaanxxmRD@?l7-&D`$7=#yMns5E@qVZ#T*IJ z){#01B_z=%jB4#yjnui`>ZQEp2Fjadpcu9VGwPmoWIH>Z4G(a<92Z?=<Fa6AY^NzH zU^L5N^qt+OJwB$e1~XA|W1d#7m8Eqz)@0W6S1(yJkC#cKi5(4%(LqhqMGdA7kzJYf z745P;X+mnfg>%_)*Qo7VyrW<2rf2ij@G58*$qc>z_31jXrk=O>ON>dNhS-kP#{bpn z3dbik)ao05L9c_it&k)WVzZb3u`So?_vC+e!*|7cy(jbgo#Q;UE^al#j1cwX+NL4< zXuw0QYXM{IwnqTFBr#zSnuYSm7tg+KqqDa>e+9>0S1er)ed-q>WBmU`Em=m>*S_~l zK7Un!v9~r_5eKU>q&yG=%1ey@92mmMx_HRsqnyheml8Y%?oNAkC4vEQcu9kWtq0`F zyZ$Y!kVrTh=>h4X^i!#L3euitm)_V}@LO%b%N?Z`IvspmKjfB`0-$}qfBX$@z5KyC zGsH{v{pfI7_{f1?tQjA8{yD?vsuDli1S59UjSXgWj|lXfTV8B#^tj<)G(+Cg4#Y(6 z-W=un(wJi$6tkJ>73W~=w5!vpaEN3V1?s?{B#2t%K%8J61}$1shh%ircRKny6b4bD z`QS-2aCnO}rS;3ozZpUPZ?NUV{R!t7QLI4d^p7@ix4+3vU1V%-*c*V!MxNBCa{IVO z(_22oTaG(knRolfGVdS72W&k_+7A4--ymCWqt}W|)GbW7jv_hO81CK$M>H7}q$!7% z7%WMCpv9BArXD%&n`YH-Y-D00_rW^?sU1StkAvP-nd)P6A6MphxsABbdk2afhO7gv z?uoOpr<i6|$3=Qzc&h5IY8>v)-_);?4xu2u5EMZiQC>c%VBR5>t;g5eli#oJk&AWK z2aY$l=^$O!+)a`tn)PgS5Y-96E8Rwe9KudHB~E%|J`CLriUG~6%6N;Cw9&E1RAQ1% zAz7(a?}q*2-ovduLV~G=OvQ&xv7}QeL#2gu;2w`k@n+%E{1}hsA9Q(rb>`nO7n>s# zI;5AO=;+T@Tt-8;CLI}Ilusy}o<>93vCey}Zmh%2KI&kVrG6ERKX}-koo)cMbczh> z0iFPoIKF`TF%ox%--70Mxs&U2;44!ThBidG7POD~7LRnGdGfq3^afS8N!2J{LC{Nv zCci$1k(D2V%~uAjUvqf;eh#j~<!%9nUw)Fie@DbbHhOu7Vr^<TBGADuGN|qM<pYB= zWO>L4h{k}IJ>_@th-*aMz)bW^0s~~MDp|^-)?i{OD3{3{?qq1~#kIfWKKl80_Qyi| z&phUPJk!10kbBB{yi{NOt&Y&V)1fM^FO{j9E5-Bg)PKW>i9wnN9@I$~9qY%1Ls(M$ z8P$Vpt@hc+2FTXD^a<1?5~*TBg)DuNz#s4&2+$5Wxs{|-4safdI_u>%<9b$E{t8RK zK$HJI+L#deVwm597So81Tjg9bH}+7kpEBs*Ko+AopnXUu@w2fn@{AD9a**6M%EdEd zh_lW2ij~`~c8VvEK7$cLT7ma3x*;1~!#eL+L^IV^fwu9J1|IyZ_B(99tTyJBF7Zfa zvE{pFV4+~&?Hv_Rp$aJZR%4{--8g4l=Bu%TuStVX=?VV&%w=xdxd!XJ%sYm`t}bdy zwUrgLe!TV;_MeakBwUc@hqUPAPjJ6F^6!#aPJt8jXV7)&79;DSN5vWSBfkn5@slis zFV_;eXf$(%LSjmjz7=xc0}?arJ48LeEDBd&0&Dr{#DaU6Jvxw5Q`%B7xEA!S7igEI z7@C8C@#OlqGUi-Nb=DOnvcC;H#6u9WGn|=`FmGF_lpBt#3PYM;nl;_mn6k(aW9qB- z6h`Lv)ESn}M_moYp9JGVSMml5e5&+!rIz+XG9s=oWNB!vQ2p`-65)1Z_H(4MC-$xa zPA=3?+}5xszpTS>X{<;eLa+`JMcI%%-qp9-PUQC7365uJ{x;YfHX!E&l62}Tr0&D) zoIkcubCkbi;EOIl3&nj-a7R_`&_a6r1>I%|kAhAYC!^@Mq}+nq((TTXQ2(REffUtE zD>{f`Yg<jyK<$@)m4i11)8YElmpjJ$Somgrw@sW|IEz=T>pI7ybA#ve#`i3ypZ*G^ z&K`o##rAI*CHE)r2b;O-mzAB7##Fz|tq~m$zJHqPBlnF$Zs-Si;oI$S-WOLHb3#e@ zxcqAt@LUfQx&uMmL#N?*-Ve?Y(-GjjI^01Xlm?8_{oagt+XU$ct9|jf^l;y*_?mOx zg&M!9sty|D`7<&WmQ+ygqge9y9lL!<(;q{1F;9TIYJV)b4ib3TK>iZn)<;>CIM9_Z zX$1Z2&7?7No7(?&&+IekW2OO0KZ|#jkg0@29=^}kYor_V-|E#ptR|YU2?LPB^={)M zS0lNPV@&jA^H|Lf{hD=gjqg74*N(mAc<tFmpRpgCJMaKqn?h7W9nA1b$n;(or}bm# zJ2B~==SiCdwKn_z{qCCMNOh#v+^kjgBR4Pg2hiY0_#{YR)7}3f@bOn5zC#9xwekbQ z_6SvHPNv+c)nTXo5rLw$6T_UEk2P<N>oosqxf-^=-OYy}yGW#o#YimVL#ql#+T=RO z-p_q-&wLyy2B{TSU)tVagmaRENK_c%32E$Prm$V4KxgbP%uuFEhKEVMQt;>bj+<p# zfTVs6cg`jZnkUD)UVH~)zz7)WsdBKB0-4opuR?R7JybE$cNL2GbP$t$%}|u6y0E9j zh$_|LK#EbL>BraVVJi#Dp0K;vM{HxxZ$c(HQ#^0zB@3UqWF^a}NE%zBuj{Cqk@Qxb z(t1hxXffj)7#|1|5oz(l`fXmAZ?3er$CCLy7-fnKFhAmdr6WR{j)p!8y$mg1c*2H? zPFM<?=!*xYXp>DX{nu4KM64{lbCB}s5!eA9xe}dzoC3@Z-jO*Q?7xo4!$})|C<DWs z6(GWcIekkmRkfVM;u%9O0zhkTWZp~4;THsZyu?w3eF9g;C_*%jd#dQ6swBWFSs#s3 z$^$SGJ`Mn>&@tAPKv;EE-k2sp1Q+u+eC|)HC5*7|^2M{tPN=7h%y~&;A$C=go!O!0 zm2W^svW=}6QSoc))c%avMc0^&P^~g{ANC@~D3}j+Ieq~9NP9|+#u{(Y19ZwuF;!1& zIHA4I3J&JpYhB@`D?nr})qOaR)nYK6%c=Mk8X&4-Ot5(ND$7wQ<IT$Cx~jBy^{l?8 z<6kP@cw^vfeMgmu;LfRqZ$9@}0GkNg_jR}-A4!A+XG?X$Nb$WyT|@GHDH9-QiMpIw zFP*8En!rd24|c@TO#3!XDhm11<q=^}sO8?&6Jt=1PCEZzI)K*@KGG~}FdK@H5G}ne zaIwbq$||l@&aaXm#b~?{OZqdzsoPEC6c*#Ta=VN-jAu_zLN+n2Sh(sQzZN!z)JZwl z(D<j8A`dBylzGZwq^iVH)r$n%I&b|s*ZcEmEIDOej~(`!KC8oIEd5JoimV3ZK*U#N zLL+k%MYKLi*D#1-TlY^jc-?JZUP<Q-jaNHqT||GvJem2OVT9d%+cY#xi(MIvO+Vi? z#v%lFchf9+F;hkTER^<GdcKhtc@$D>$4~xc6Jfe^{3UCdx7n*m*NC!t<wg{?3`Z#| zywH6dZ+;$3>e#_+{>u{A$bXL`Tq0r3p8PrLOYifmQ&znbFJO(GHF-W*PS;hJs*3av zu7L0xW@y?aR~5SANYjh-+R?>ikwU3%|NGFht&JsxmdB?}_jb0N*Pg!5ZGj1L+vt!~ z1xG05rz)3xJt^{iZ0PK2KWEIfcdT&X&ZuGCo6!%zhU$W_xq!A$|DrWHBY_9*!dcDv z79Sy#6143PM_G8R{CK{5WgvM^W)E2?8^f5}-hX3lYn{ruN@AJX%^fVlhPsw7r4ORv z2V7A1ZN-fDu~U!8)6CdINuM{J3;WXQjAH`Wbk|fcFo%`|@Itdf95tSrgnPt=^`0Wv zOqCv0!pxuVWzYXozknXwV$QCgm)Hp>G65eH#ed99EJMVn4-e)x)|E17r_BZ040>tl z?kOphc<~{V$C7BZSuPg>VLwYbuP|&iguN;2*Viaqfhs1E)O(o^DR-^_XbeTPyNnBS znXde92cPz-KjxgkB{8R-JAVS3KQr&Bdo6_JrnHx8p@aR+F?KISFf6r9KS8Fy#!btJ zWbqlyk?~i)MonJ1{M@t>+{@^eeAuK>dOE{lP7XKA_Dqzq!sryR_t?{vtJHG~rM6q8 znX)iwaWc#e6Q#w8G1E$;pizRUHJA6IIg%<0Sp+?$1zLl0Szc9{283svF_hz<Hm}lT zhUMa<8Kaiw5&B!VvkcP9`QP==SfA_D^WK_Hk~{ez;<{vT%g4aT6-YAfg{E(Wh46{& zY$&j8_2clNu(Vm{cs<#Xv`n&6h9B{0sk~eDj1Yv4V8RsH?DWvip$We&(@m3dhDh&J zWiV=Q$RmNlrfoh#=Hq`F`8QDrLm^+8-aXTm+|IOJtE~1?PsSgjX@-62RfPhW6C}TR zL`4|P=StRV2D5do9Kc&x>W<>e!|0t&Lu)G}>R)aDh{=(zi8Iey<4$7~X?3jB66Obe z&YN8<^?^{b_hVQjEr)`9-1)~&M9gX4e84H6Ae0yQF-2TVp{2Bi0>O0b-HcX4G20;l zA-=H3%Corh;wV^GY-a)IwQOr6PTqhU_0QS%Vk!cbrc3~@ztMNLH4{*ohX%^`flom& z?-U4<erExnl2%Un<9DSo;&krzy(Yx5o1`!3Tp(RMt>_o0gYjdf^r5kI*Z(vy^sD4A z?fcT;0-&Dnn60`1Z%FA-*|(HeV+pbBa`sdl&)?HB%G2}Q%cI&%X^w<#@Q!V}zNx3Y zN|5^O#Hlfqe#4sfUwb*4@<Vy$UTeaW>!9?$q#JeTSLwaJY6hcl(QH|fb;g16YDJF# zc$ivXz~}RMwl6_tFazgt=&3n39p^AXzGNNPP%e2pI_+0VVemJ%TAtUfmos>R5ZFqT z|5{Z5VCq6M#6G7bFNeDBRh!t`-mp2%c+JH<T99E#@6bR6d~wexb1<e~#e~2td8Qwd zGy<SdBnMvcr}bM^`US=TyH9yHjsL7-zk@bLs0^BIDP-$59~kFDHW3(Zuzj1e;G7hV z=k08PAv2+08nQEm)h6`}=L26FA{6-lO)KiPx#OSf)P<7A;~>8}p7y{jZWQHTQ37lc znJ~nLxo<Gzf39W^rq#ePHnClf-@VJp{5bjQh3tY-mSic`)<+*6>6aM?Mu+Nk$-da( z3HgfM*7zEyvS9PhhU-LhjG|Mp(0|JdvlHzld!pdg|C$~Xl(l7Y*F)-o38N>|Jw6@D z5>L@*7;LL=&p21YXLI9pzNu49VRA<T%JM^Yi|iY%isBaxU-xob->AS+6O6_uKj)qQ zzU>MMw3Jcu{juCLv*(Y}4rI)Wbu$zA71TAy_g>!(1dymBM#-eD`p+uFNqHuJKs$KT zZ!1lTAmYccGhRah*3^+B)v^ZncyAQ8emvy$*c-r8s^$(T<U=UhjVZ+~uZYD8AE@s_ z<Il-rG}7^a@M!{-z>SCfG)Ffc2j%J^(9Fp~mvKY^DE}4H@MPxhN{rM^hB)1O2ETZK zEZ)*UuCI2Pb|q`7d`EBnpJ!0*xBOV&{=!k{2jB1u={th0d36yh@(7;?y>Q*%(HD<s z02s`S%!v<Sb}8K$<OD_#oPU$?Kd{0e<smD2+Dd3>xhR#lBTW=sVwTzX5x@5Uzrn9l zf4=>Se~xs0mJ<H62n5mfzll_ZM`q0{!+DmCi?(%$WNaW|%aoZ8V3#7H16|5CQhI;p zT_+J9tFK}93@-Q4k(WfcIITo}@|qtYH%CLeXjj!MM|l(8d=|R;;et(<FHN2u`Vmd! zw@yvot+@F;0M;k5HUg!m7*1L8TqN!^)0WC9Q=;XmX2`IC2j#<LAP|Dccw-w>AH?)B zhz|+?Hhm<N@I7F|v~-FjkpB-{_nc4xT^-J*Y}EA{4H-!N<zhhgcbXCs{N`R0+ZB-z zZbr*vgizh>VeO-L_h$*)VhHqdSKYvqxm>VHA>`AT>Q911&6i8fFDhvPc{9X48WFz@ zts%2TSc;`2siWbM2pKUX@nke|oYj3`7Bcf%e2Y%1j~6UM|7&U$p9cRaFeU3w0f-jU zZdqbq+F)F``P>=EU7}Bgy^Q<dwqh22722Y1%k({006&to@|Y8K8pQi_sL~=>TbfY^ zV9~-ya}Q1*AADjy{Yu+NbKfk*esZ+{pe!$){bTV%8u9NyhV9!7uctQUmId#o1z=Q1 zV>BgVo-9k0flpa5_&Tldrr$Zm2*|_t0iacr2y+|)@_M-8w7@YRla8!}=g^IqE!Lv} zlJ;xougks_BPn&l<^-js=$9^{F(1ch+oBH)FOZ+C?^s^St`H~WIc-Le<;`GB_u#hy zYRc`KSX>#m<v%G-lMiu{&%hd(^<9?n{_sD}*Q=mhkX7IquuV@9<OM*@o}NRV5Izep zA22B)8D@X5ICMfb^6j3q5FZYQc>3iE;Xff01#;bLeC;;v&6_bxn}JI``_|_RUo`(N zTKlJUN;Ftl>{cACd~8|z9-_!hVY0;|okqMV@B&RgQupG0jyoy$b@L>MPjyPk)n$?1 zQov>)d!zEZEgYtxD}!<oy8Y>fexGh}DQ-)gK$w<oI+JDVQ_38y-uFTu3y(0Sz$}|T zAmupUR%j>gxoe)Nn^?hXWtNaw4Slgs6M|3we67~Q=cOKOOhI&GkTi1f-j`=Rnl7qr zr94a-NESDY(q|sm(rw;(RfEz1Mq)L=^aKAro%;9^d2L~S<SUy#fEA=*_TA{^VC_7q zq}Ykrn^PSX*o6xS-4FmDVYniFO?&PEQvQ>%onFlI@X24^+A2#Q%&J++BSCZ0Fmr`1 z(}#4Jn{Eh$Et}NoC^AsA+g9oWZy0=5m!ecxp)?0t8n@1;+xz_{1-X5CfVMPn1|V~g zPVUBA_EV%vDS<1-^c0@s=qU@tw3##tWEO_~3t@qiDVV#v03T+4*_e}hVlDJRrZPrK ztB|1s%e-^3i%yyQtTDrq&am}fBUG4O;lN4V4sC-}Fy_Rv!&1QZmR#Z34ELnoof#;f z{3^u9!1q+k!PSOJLD{JZAzER*s*swUcpSj5N0;J`bOF_h>cMN|HL~nD!cpzI?6P4e zL$}PzYjh;Syn=3C2_WLt?zb$i3>wINQuPjd=)&(9xZvn4bKqiu*dEflXh~saInNwh zDPS&VZ$?zcM|WlLONIT`rUD?7NT7HLfY}+;I;XMP&CZp?dBZ()bdWJR6GGIe0X3F@ zUHX7KY0{?kDP8mov+Uj;u6^!ib*OBFM;4`=2PoQU77=*}V;=-l@ZWEj_C9R$INFq_ z<>#Vv;nHFb;7f&=_UMpBcpb|czB;nd8N0iOkRv<Ldw=5R`cn!1`kv5j#G0qa{gHUy zXAT8caz}n9p-f8lvLlz&jN}R6pKkWzwD3Pa1Duu2$;gF;Yt6GI5D+(_&xni2t8O>u z;L+m|)@N72A9Verst{AGQrUXS`r0(Q;TFEyckrn~E53+w3lQoA#u*E<@p5+kb^o`U ze9LP%i4(~7mzC$%gSfi0@TyP>ZKX`@JA0K=+-wYVmUh|k<p<9Y1A)FWwW4f&)AtA; zwjmel#rE!fr#%s|cduWDF~%>ML3b)kY-`_Q<33pToFCkDa8+>gDgE=4?cP}g{(|K= zUC&RSRnC+Dj-t+^{IP0G#3zrfO{j=^0!Xld4HWQ8;O(>6hwSE1!TW;?yYi*cVUun- zx=t*T4xUJ*N`GrX!O>PZt-ssXOG|vQWZ|yhdt$un(*8_&PSM{h`Inx6%`f8$_xRWe zq3H9g_>VRy`w?lw&;W(4XoW4g{$s>$2E6hYY)K)>m0u2sLNv0wVff4EcLMOVBDO%9 z>X@Q=<)(b8PKpbW)91np%N#WkeaZ@S{YXLG@t_tU)P^k^>IhE#+LF$)NA~%s2(+Qu z;3Fpi_L0Tq$_kVhi5c3DIA%Xx2NH6^K5<(JU@K$Z&J1Jt_qdB~>9%ZjE^=w~xvuHa z;*t=Vm!8R6a=+_>RQ8{V#OIwa1(Y{(lMLQ{>cP#jtob;KPnJF2rPQ9825y}TXKrWY zH?%8JdCs-X12-L}jWOaAz5l3<V&<9HPI+|fXY4a~q4v3eX%#sdNrq2er6)H9JbbU( z0_vY?B<`vU=p=MRbl)_Qz-#Z?2+-R+x9If9JcpMi?yJrr3^6#K^j+14PkmATzRQSa zT6oWL+0wGx#47@-G_IHduFVY3xd1vtOIMUD3Omg*ZFTE^ZSe-B`_2(QE-Ug2X}-O9 zvM2nu@^$5)Z5hg?Zj`faw<?X{cC_V&Ti2PtyLS043}@MN4mM}6NcCk?8r&tM+#MJE zZrZbsyu|GGhd)M|Kl~6?d$nxAPeb~exb79+0yk8r2L5zo^b~JhH;QH@sWmOD{-N6H zP^J)Z;Lchc;CT?pP;PG#%zqMh<|7dAVk@WL_t2m;jcXZUsOR+etN$uhj{W5o2b;@9 zYIMLt4y-ZuzV7`FD$n~UtRSS5Dvjgpfr&}VMcI?eptCBUV6O@e{HEI_tko`E<dtP@ zeB77vDvDCBy`{h}IUSq%K~5l^@6LRXV)NttR3TP*PaGJ}mG6)jq13ub$<^SXg5#il z&GMkvXy|;!7P0;_G!QcbQD>~pbJ9wJhekfAW@!ENyZ_E7o~|)&>dg&%xnR9uU5nC^ zQrf4a>P3S#U37g}fpe1ne};k!5bewM(A!<_D;n$dO>KQ!Ap^^gewsV}B5~<q=CAQW z{TcNo%WXa#pmO7qaq>KfB#yB>W#cbVXw@N83ha9@G1@gT+%?o9+ZRiAWtuA0E)^!k z@6@70JGN)<q1Y&|kEJKW8qsOLvQ&Q+Zzu4_ZoIw|L76{nwlN)60Pp(K<&B-bRRA;B zwjKIWk{t!Z+W3)-_J8e~yM?2CMhhIN77LskPv+FHeSzVB=O|?<lG!Ub{pq?j%hi&* z-)<S;&Ho@<!VLNZJmSQJnVWm!09M!v&*kvS{|Ocw5c}HBJS-T&R?!lvSKiSD=l-(N z^bpb0xN=je4&nw@H}^#FJSYwl3{U1KlE9CnmX`n8e$R%fqo~M6fzoKffY-=J;fSFM zQycDwBpc;-1a937<70Q9mTKsJZg5d9la=A1K~-qC<_uqbxb^DG70-S?tO)o1un>;! zuQK}^sB08P{&2x;;X~2MwuR=7f%Y~7I$-en@b5{b1C6rv<<M>bP(euEr;lbj10w&v zJoA3cmm|1s4=UgBJX~5X-qHDn4wK5-Dbd_7S%05d^wzT!`47RY@?fYbtUC7JS208O z)^gzU`BIiYAG?`tk0I9GahA<xzgY07{vBe#!L!T#ki@CGr6||TPN41ST(9P_JK}~% zAJE*CDdn*26q3VVtewg`Ew(YXsyQ8OgY8aSE|tlx5CpM5Jz?EwZ!tO6ef(~1lZSsB z2J5AmdU0^Fnq%Jrzsojl<?4C-F7Q-?Qi*%{<x|)-(Z(8f<s!)otUvso&|T`}a!v=L z)9X8B&Pm-Vc;K!rkJr9DdmAX|)cs7WyL*b3P;&nE@w=lE`Ti@I<TUF+F_|eRiHA%4 z^ScTwk9S{nLztjIYp?CU-W!H@gWf&9`jQk*0*dL0tt0~xq^Dy@Z~&{g6Lg~&9LGdz z$PDEZ&`n^HqW$i5T+;i5Om3jjrRte-$Q9(DFNI9yM6SH=N>_s1i>X5O`<H(x<g2Dj z&`F#cwpIl#`d}0g<J8z=4B^)efJB|eAgif0>Hu@yO3jD=fMT6Q#rl<3eyg1isgxSl z3ctZp3v;P@p34D|>;=V(BESu;Z<89y%1zf5OD?r5P5Tc)rp}$}-k_j6a|lh)*GS$G zgAA|Ow`7S-5#g0u{na<#Jfcx+J6LYr><m$3MGUNhzApZwQExxq9Jm%)rK)$F?o8yX zJ*L&@{Ju9|YuBy$tH^nD>COEsT21ws=6@qeT2D3KUj8^(ee;-3>)oG=@4dgi-qz~= z_xJeQ*%h5r%;Iv!dz%X=!3j(GFZ+EgxiuK6dE6slj-zrUIL9R|ls#1;Q-~~%<4?u# zo2?9H8jAk-gG*5a%)OiwWT!9!CTGAgM5PSxN)rzh*tin4X9?p<^u(U`O1pSvw+vG< z0-YuUWh*V<^`IXGsQ+=DO4rK%;g;ia6hEqT#Q~x3p$0-bI3rx&Q3yp}qkRoDSc-E$ zYwZ@7(Gi0GQ3!|sWS37Uj3hG$KlAM1@G48ydmUdAzf$b!`_wUUFZewaZ=@W-%Za46 z?*w~PRu)~Zs)jvEd;yTimk8H1Pwm@O|JM`p0%-VmGUa{Lg`*8@r8PRRU)gOz0xJLm zKz6lMIxf3H5b$eSbTqO`zGyF-)KdR*`c%?Ov}{sVBJUGd+kOMpyv8@L{uhe*jUivM zkIBXZ-d%3Z7i)d16i5|&O_;*~ASc&Um5QVBpnmY)+0*VVFK~(?bN(kE{wso9Q9tk3 z`_Htlwq2*Z9b5#a1oO^AY&&ms7X)hJd)}SVs;xM+oXAcWQ-!=g@DbwB{Ot89S#r8= zJ7o52(Qd%#i;^>1qM_NtdbQq8<FLj4Y+J`++s7ti)5%zq@MVwZDd8(VFDJuS1G;G< z*6zKp=be;)JObB=kn)K5FMN(Bas&I=J{5IcqNm*=P+3K81_;u2Y=ISMk)IOvX**U( zNC3VI2&o$YT!SP4QGgZ%2LaG4fCS2oX)Nx=L77DDM;c4|<LLzq3ouPCgZIJz(S!~& z#0*8ibg<}i+CqKoKk*v-(dLTrXVR`?1qLmZlljV2KI-SRW&MwlIPJAjxfe5Km<&;e zvDWIj{3FVLMp4JlmHqoLB<FGjbC`~QY3PaUqESwZb61rE6>^+YJIzg`zcNL%uNwML z^W*sIm;ZIgfLH%Sm=~x3ofuTJ9GQM1H3Kh9Svn}j9UztUU7v`8kxXQ=A&D{0dKrTE zAp6)j6K)Ia5n+8!tiA1UwLRo(-0saXwKt$w44=?dGz{Fl2rD3{CkFXtf|URItE3qB z6{ryykPM1Nje$g%uB3yUdT|sS+VccP3>y%FC%@ETvx6OeJU{#T-~0arN0!3>;!+hy zsQJ-QI(BI!3D|<nF`P={7>T;JDEB_0ryk(ZUT1Mbk~}vF>gOsz3ec*aTq}w7|GwJY zN|N6Cyy^>b(MjYs2x<gE0azn4p2ybnBc5H6xfjI%k1Btns~J=XHuYhHqsZ9lNub)t zn+eKWfZ(*%w|TZtId0kBpN(4ox~3{-g~qOtOs09#hjaX_aML!^#!S0WbH*UaWI`DX z#2Ow_tmP6AHM_atZ$C}&`)^2-JiiBmtvq2eZQn-b(_V9S$4y{0RSYSrKHBB7BGY&P zv*a8yqjD7lVu;&4&C~xSQS-H->r!_?ZH!$O2bm+;D0o^=D>7YKsA<)EPue*q7CCDw zHr?`G6dntKINNR_Gh#oZ7@m4D{r3{!UisR2&}NsWd9nkJ(FA9?8nFz}0w2LQCG$%l zg^wtaZ69py%*g;7wL>zHKQXqSUPb(*9~vkvK?Y^Bs_%t>kM|&}_o$HRbZ#R)kwcP1 zZLaQO9VygBPwo5hqeZ{7N#Hx;h9YjjNgT)N^ZEeE|3bA<n@njU2*nK>=$$iTf`rW( zF<B{~INS<@X2Gc1!)Zaa3)jf!w_xZSD~(M5VU%AV{%qJicgvD6$2*zFYlC6U>tw;# zEE8?&2qcl5ms&Gz14}pGyJbnfF0TXOdMoh)qOw;~!G%T%Pl~@gy!djl_eW6iA;vZe z6?XLT$16vnHR(A(y@4JIUgp7mWQZ;Pje5d{KG(LrX=MI2x|TL(6f9w0mnHWncG4O6 z6C$=dfBU}=zMZX2+94aaZl9t+H&;7bU($uXLbZaCYDevF=HH=S4@=P>c7x5YkWX(H z%D3v>fC#n^UHc64Vkmc??D6b37lGIaOrfEDu2A8gccyVfv*5|FFH8h-#@ob?Z=b?$ zs1qoRd*~U78?e{o4wuZsC|W-luHkDAY9G$y%25o`&AI&@nl46mc^uDFlBjr90L0Rf z*29M0urAW}^<GfG@c^`!LQA=ifqx*8Q6-l3B|$ef=NR82M>x1dNc`j3cB4`Tra>hs z$-qfUQ1XZxj06Nhk_QfR-9hz5G@bf8C7XsqDSDv*W04bIygCV``34a!%9s|<jA3I* z@59;C#FehBt|MAw_LV(J)OVk7%`NmR=gnri;uvXYwqA9U#5kMyx*U>eV+?5F>7;kI zwb?1sn9Gr{u5toJkO)KX=#dZG_UeiF>tO|?faY$_y2y*Yj&njkeY|)NuBK&dfo8zA zaU0kwh<wAsS)L6+k;wQqV_DR<pV6rFN?WjF`Xy$v96v2qb}nC)asEMZ%a>Im1H<V` zi~BjW2|(y+rE%<&_b_Su5efrkdI!YzGj<+=8flBEcu`PdR&wcINV75<CB&IhU_|E( zLnJ{vQFlrw=$ETZ=M_=Jg7?5={7XDz6lkY$18-DbdmmlH%_KXwaw$@f8Q?b$)BHVd z`H{m|FTkS60sZ1~f<rCNUBY+H=i_=R8s+a2Lk-+wF!3K-{OjZ<)YI9Ef(4bAhKWZu zWw;Bj>SGx9({oHnkyK>)L{<P+BbU>QWX{j5;x8`*->E^iDbpvirt_KUR31b6Bp!Oi z=aNRoICnE=wdGlBDQAfQ2hy?Rf=MmBzpY5q+gdBHejFtLIi+j{UV~1uEI>D2+?h_+ zHWr@UM4F4Dfmq@On%z2vbR|*D<2J*r&tP#5C?}F2jH6yU@v!WM0qLy#ZBBI9nhHRE z38Rh8{MmZE@Lu~>OZ8g@Iv}~_KmWI0<Dr+V?WVef_qO!6h8fGrpn3!vNb?4n6g&U4 zKL#&U`f<dR6<9xfiJ2Q-2yB@0a$BHvS3HjA8TvKwu*9%|Qkv&muVRAr_*cwroAGNY z%A1}iU&2Ubop^=V04A~?9EUoQj|$x&(G-g#3Bn<$mPdw6jzj5;cChVd)ugC>cU>R) zJJv+iY!_O0(2QedCgY%2(P%D5r^t>t!&NpXdIU|gN8iu51RK*B!S3w4A=n_JKo5yY z5ONpE#5t;DE~~@M1qM^W-*mM4xKqu(`%C-H^|`I(I<0i9eEG$kL6j5<i`HSkJ<&#r z64GU<o@aK-g~_njhmyb?cC|UkV<e$;kxpK@2ez<oO+xX-fhQSPZqrEk_cCyo!%;&9 ztW~X2DeIz;H;QC_DSOne;-c*9@lF101%lLS)W@pzC>S*L7{^fP>mWBke*BXJh(Uf! z?6Kp+)BZ$KPHu<GDfLa&pCS|O7O3XZ6Jm@pajKAO1+LgC{R={sLaS(J!x46i8+yCn z<PLK?XHBaq23KhBg*;n@om{a(>Dl@5*{`qDcgwG?kH}p|w(`#=0l(^`e26-<jC_to zKc|P{a!Esb?SY)gfoB24W%>bbUu2Ib;hp}6usfgZ$plg*#BFTIxkvVSG0!RP-NUZs z!^Cc2R_vz2+o%S17`*T6Y&{Ie%|H0B-6M!d)$EEb2cBiLe#D&QYn@%nPf)9N-VYi2 zKC~Jyyw!t)M4~&6qYiztH8Jq3B>Ex6b~44|2<`AgTr^kt|2R7Hf2jWV51&~u_A_H& zn;H9>JzF(1#u)n&vKCpIEQKOOjWHN&L&#Rm2$3awwyZ<;@Rn36MA3>itv<frf8hM^ zdYs4oI_G}g_jP?FFwEYqAIUAe^A~;Z^ynB{!#8N}d*P!`=(w6xrlPnX<OJn*hU|fD znvmj75%2lO!i7%;gN`h9ecgS?r4f2zulv=a3gX_Z{O_dx!{7KISN7}~{b2l1B3e!5 z_X}R^ahZzl#>D#+3)&~OE1q{v`;K;9XI%a0{qf@!TdX(tH9W@hG`9qD#_c>`N8-kH z@N62m_5`$KS^zpp`k2eyvx$PLVRU86(3{IH?%)x9nvV)W#t1CF;{tP5**$$ByaLI~ zxpIf=Fb~^wIWU&zbVOQ3z!4H{(lU_q<}8?$BpC~edWevjbg~X;wLyJ*Ck8cp`Ct2a z=}O;$R)>!N{NV$JNC4u9jRtl2p=>WbikF@e-`;)Ar5z{FFIMU2y+xuy)kf&Bn_v9G zSpmuOyb!qME**-8TUFD!bKwTLaO*}ofMe`W^uUox;(P3Kagr2-Gpwn~V~ER-hvEGW zW+o2R=F)*ppbzMJr2faDK8e&j5O5^vKeG@2oxgtwjG-j5c!FfAqj>Oi?iB_Xo{?Gv zw*`Q{B1Q&7#FoWiP#9v13<Tt|#`Sn<kBb6Dp}g%rh&TFKk1ukFgqQ#aIUSM@MGe=? zeK$I|q8g`$REFvzEU(MG3O-WJP3VlKP6d0odW2n4MRpZsL6frjcQb9ltbH^e)PxB? zBLWoDxti$q2tfP#)g={hM?C#XFlf*i#w3BAcT%3uS_3)&2F<@twzs)>LjFI~gYa<f z?UQB;l%t41E9G=9=ZiuVI&V6IAH#(1&BEccaEF;|M>enNu&?n#n7_#k1TT<7h6@!Z z0n0G+<$QsTL<<r`8V!mmgJMsiVsE@xf)CMNyVacsU*e@^3^Oo4O=6OS!kskB<~$Sf zbu+Kg(!YA!TV5S;3*^D%!jqD0)j%T?@E-#l=ztslymmBQ!~p=(O+Z2%xVM}6Czft9 zPrqz@4m3G8VF(3g01Zn>*(n{92(m#0G;i3~U6imc<_^cZAJvlrop^>W7Cwf_7EmFu z899}JWWg^vd@GT|h92Waf&U8ArVy7c$w`(>I(@f@Z?-6-vj_p<nlrgErv^SYK|Xm3 z9_9t6)rt^JOrdSq#@<38t?Ifs8q{>k^@2O@aDt?*!95AZ&#x~uZ<=(@SxccHI^wp+ zIlguU&_1as9`X2#7cc6(O-!f(ZH=>D))dWdg3cfp6v@`ry#a%8L7Q$oA1gB6e+U`0 zkxUXPiYInn=N>riumCMLNxyR4U-~}5`9DM9^%SB+QmEUlPdm~to%N!lb&j_XRu<x1 zxqW8}Lf4<>3;#?La4v`9^JPLn2P&Hf!zSn65cUGiJ3(f8*0N`&Do+>yrt>dAu}-k0 z6th0XGhI)z=kx5AM?F&;uNaSOr>zRe<K%^?w;I<?g}>PJwU~Lmy(JwDjs^w(O07^1 z0h4yGbM0-j<>EmXQ&9Bo0r!$?a^n@;kf5d~Sq#(jA07sNQt`mfKy{Xjt@L4MY|d~& z3eQ`DJfNEzKIgoR^4lWqo7~70i-67ifd7tz?ZFk-JFi=+g1#9bVY6)J40!D>i0Y~X zmg~5kxx_K`;*k8pUqwY-*L}xpz|KUjkgL;56f6!R$^s;6?v_fLA)3@~1_J&#$wQ{K zfdt8xnIkXRx4cyiTLKRy@%dcn2x~viqA8!dCvgeemDx|Jb9~2wJJ*c=s^h}f^Ru}` zZ9&mXO_DN5lx?NBE>kcBPGVZ*#9o$;J^y{t$AIP0L)Xz|Lfunro#=`WZ_9D(KtAnZ z?xn8^Z>S0#!Nrxexm*c6YS|Vf$?caY5jCL{|HZvolEL8r#WvXloj@)jGtdoPFFOH> zd4s+)ZSdJPKbdx4KhT{C2G!O%qnn=9fTw?F+5iAwCmpE@&+%v^P!cUd0<kP87dt!o zOF_d|CxMifj5$8Da+Te8!74%C@2>?}KCeCE5opwS*=aZC<(+(Tan{5c(6qQtz>Ga3 z-2{emRcL@-eqG@hFrZYlmLI72-33Ing_O2&;oEZWR>D>?(__J|q8Ocrp~fnK+SZ|O z7j)E|axHCJbuSsj|Ch4p49sw$nr%9MBDE(DX(6sfqPLEeK6Je;2Gig3^AoH}6V@$e z6xDM_cHft&M_p=%MRtAW?-L#nhc$_Rx9vl&v^Bi%-Fn~4<_BDKK!=$w$#<Rd<C$3{ z)#R?km+^j3Q&0eeCA<&wPBjaYc0T;=(y8i}|7;)7{0o0uU-7;VvJb@!cy$UCXW25~ z0`J(j_<{EtT}@_SWog%^+CCrez9;P<Wp)TUJ9NYc^v8iA?6#fKE;y3ys?G(m1F-;b z%&9GTlwOpXAI+cA!`(w9?H4?#=GOk+48*7rs?2g|t#AXFx+iX*iCKfI%?-%^5&gjy zIB{D}N4(VpVV7Lulfe~_aBfEUGl2A7YrF2I+IH{EuKGP&PFT~>QF9I)G6p8~5d}DT zb{yVWE~^h+Y34)rnxMo?qw_Pcuc)6-w(2+Oyp|fM4!{m9XS^B?QnAc~Z>LMG2uH|1 zv|~%8f^tw@>3Dr_-WCJ=Y3gEI0LlG)oN*oJT~XiS4IRxI&)W8~gdv18$1-dTsmmP@ z0WM8Wfstdd$g!Yp@U%u>fK2~hDchO9sJokS#klT=cv#1GKSXNJy$`pvGoqJa0l*9& zEO(-7NffzpYTjsKcle~FXRF5o#q47B%R^w|)4_w2AX2^lQ#Y8?GjtlmfzM6};<*JN zb5O{fVj?IP4ytK^mXmG9cHr55c$q-|@jb8E1LK2HGP44kSvcUF{_#h=MlcU$sKN4a zj}GD_zfS#*0uL2%G0lT%JuFZHTFobpf5DfX_Gtf6Sy&4W7d0+DZL~IDFjxY${toT0 zk8wxNkuh@sjypmS2s=D2r!^KZ0Q#Wo-L}T^q-%0Zie?1vllvLP{1?A|?}oDj+3KL5 ztlyX|ly)fA{gA<7LqH3i;QUuYG6@mUO#7BLvqb?ND<6xDJyt90<k8Kdd(KLPw3B<r zG=2O0`xlnY!LxrC?k95d<Z|~sK%L%tj@W+Qr3Icn{N!pFcmm)KkE{h)V?i&*45u2E z;u%vu;I#3hgEfn{GSc6+X209}b?C$~m6uJxbru$S<EfrM>Jz{vT&}hR)iUnrnSWc` z>JiVEYw@t-8ZW*ZWmE6nJql~;VtyEf`7gmSOVEKOGGqy0Er<Fpw`DKDkZ`spyY^C3 zgEv=@?G!I^F@pb5QRpJ$#v*@ek6@CSau8@cIL`yj^+mqi_=^fR09@bNKh-eCRJbk< z=kZ0dRwa^<9V{ol8h4HErqWs9@<NX63U}ml9wB6CBe%xvb1mnkfW|o<y!iG+-P9&~ zxSDCx^<QBe>(qU}jDlvM9~k<*_-)Pql!=`349Q9EwP6ynVi_=>%XteUiHi9QEBUe| zu9?<njj3g!*iZELUWk__ga;?hasF;V+0VN^F7qJQU9`b)=4MGRs_^V4FvAT)uJf^% z5!!S26KkVz%iNJ1sTa?n=J|hAXAzMsL#u3>W#(Tl5_+p(=ot8NMdj*N#DyG@%4qJ3 zfe+n>Zo!*EBo}5v|5b)Qd3@~*NZ0JDzd1yi5?8dJ%hN_)@7=V9e1b=AB391ye_RM< z6$4vb=LES|d)@^KA}38gR%ge=kvmu4L~g;<tMv<c{J6CBKN#eqoY{i9GZD8APslOj zj2CKK+kG-fy@e**mK~i-Pj7H*)_g8q*F4P8N)&hav@jG7y58I@7XnlqKe1j)Xk4jX zI|4pP<PO=>0c-wk$Yz6oWnTRHxH2q#KEL~7jxSk(NY;Q`MC-|=h&VxCp+<Os3t8ZG z9`Xi<?Df%y7jX@g`grH#I=rb7G26?BnO2*c5)c9ugufi@<5oVnUOWw+a{|wuM4r?6 zapB|-zNVd`m*2U!cTSpvU5V=!c5`=gx}cHm@0Y5TOc(FGtvr~1(?lmi+t%@Cipz?H z1=oyOV8>StHZqlZr+!Xz_cdfw-<k9E!BLMv+KFZ)W&57|R6`C3G=L5_m)CQ4ZvF$q z!5>!sKLpu7Vo!p{S&(D6-=OviptGD)Hu~h{HxEAK;rijfsevMYC@K*JcKP?p2Gx1c zki|U!D8Ba-#g;g?tkU=Am~NqQhe$=)L%&0fm$ydhzd0l&PfkBEnM%0@!iDDUAO6iX z`y8095(I$I1&~+-uJkAIuB*b)r>89#Vp{46*S1#)Niq-v#n^~Z9y9nOw4w#ce;+^8 z6YKxeg)OcH)By~X5=NBfPzLNit*{<cglB@H<ug3O^2QP9R(yn|APq~YBSV(qcoAOw zg$=;Zf?EKtLS_I15Go8oj-$&Q|MdS1;Nen<&)qb*T%DmeJ1kXD225SH0lBDkV9m3R zZBe!`fCCiW81U7Z3=`x##n_f$!a=xqd44JP%0REgtJs7Gk<%}p0(&7aMz+}@AEvmc zNX2c_>=1^^!y=MLm#svm+uhjIT@h_$1@Corj=w_4W4Z^j1dRuE@j?Me2OMG-ho&Wb z>rFdw@?XNQ^Pj)@0)P&FU=2c7QZ=tfjE8UmUI3cA8k;<-H;Go~V=GbbR`bzr+A@@B zMHUPtAP0t1N@3Ji-_I~;-iOi3dNuWCtWhG%)4b@E`%IE1#rP`D+`ejEv}=s80W9-k zHd9vxsEP(KswrI)=BIW*^)&>LKFi_*BoU_|fS8L%SS=vJrvU@hohV1meF9tT54{Te z??9Qrj3Y*1T(1r$jN3hn8*#^h<sX4+7dDT`T-Y9gCYn-BW}IE!vJyV3h#+=d9vUU3 zy{x@`%<(9f*nHO;^fx1#LBRxzro)9ZM5+l6xd6tB)m3O+;;8ecDxKVNyUcF9`8{F~ zg_RYBAF~6xu=)*#>vVmuGk0!$Khpb8?G(_5B_m+^CP0LFu!Nb;3>?`7!HjK$(44Wn z(2p%MfMmEk&8F6XlP%zNo1OC}KETptQ~j}P_dB5f7{jI@lqBtFsfwW4DKdz3hdBxM zYp?k91^QXqMHO0xfDIdQ@H`4z1(2_E!w>qQ)5N{{GnRtHR&kp8TI$Qnlo~Em3i}Ho z4Gr?)7~ZsTR47bXNP(hJ`bdeg#|<>sA;y*Ox2uk2Yr=n)>pH-evyO|ne7oJMdslZP z+tePhlEkamF=c9Fxm(_;k#W1$T(XPt*qzrVJxf>f@KgYuE*iIX6IG%!c-ts1i(5L1 z%-{yxahS={NN(yTUDm@70(H{i0e++gKZt$;=@16Ojd9Xco(@Z4_Kj@uiy?H;R#P?s zX*#c(88fBf4hFex9J>5F$Sl6=U|089`bw4jrH&8Fy_Y^&6=<DZUM0WIzJftjXD53c zR;wI(sBC7Dk~-O@vL<E;O+Tr2QUW9GvX%1|(7BmW#sz=??lOW23IFptTA1$lKHnW; zfaK^nWtI?v#bLGnf_oTq)?`oy51_0yjx}!r3Gdo+^NT95bx2vxr>Oh%N#%3AKVMpY zT2}5<BVIyuvMqM0pkW<?Bo5)NN=?@Nq5DW-8=8F^eW!w65vE6v$`GVbVUup*=l#Z) zfoyJc)r}NyVO6;s;7$voeKvasA^=s2s0vo1dtSkk`Kf8zD=AF$JX>f#K$Eyp!QA)o z3E2T)U$dtGR<~|8^t<?>4}Y0xlRC2X1q#yqLZ0?TU_aNnxUYcI^XGj(ugW{e0|-Eb zHR1&|b7OC3)VvY+_<Lr>3)Q#2$cJS;EqDUznY_yawf$VhAp<lfU(sw#<!uFE2?7}P z&Xzpct0RA4={|%Xp`y>%p@IIkI~jn^RoODUV0B)@KesnmqalI~VNqma%tj(z#>Z#+ z2bKYE!WI${$|AHhr@1>U7Eu+?_v=v)m$Oh^E8?yVJa?sHrBKU!dgOzl#+$4Wf?7V7 zKtE%yawa?$kQB8^ej*u^{`L%DDiS}9u%~?uh+gEJarimM4@YxKleQPQqe#;_P=Jfu z6a-9-tM5>qFz%Y{Zc`Xwp$<QpX`W+4r0cHu&`$|}S+TS!AItkNQ^%LGT!LyIqE1_0 z(jhqexUP?ShuFFA{>rtl^Gmt=j%Yesi+$3%j|nojJb#o05I{Qm6@==@cP4nx5^O{) zzA(6RJ!RQ!7s^Xtd+0z<+KlxIK_6EC7Q%G4@#D=qnz9>sdB=vmDqhnhu1vJ5P0H*a zw6VU@5X}ln;Xgn(BmRs<X@_>fB5co$(*xOXc;`)}*ClGL&hu`&Um5kko;{lc{Gwz! zA<3W~j0^J(?u`Tqe$ozojg^Ll!(j<&BN9gh07#{U-~HZi26X0f4*BqL)7yj7+yj<H zGe0*-HbdkrCHkq3+2`S=hB7Xeht35~u_Kdhm(K7W*S?`xO$ctOv;fmO4HXetIn||B z?t$qs-)3yLq@~|Z1~IQkp7sfDhgOv1?BK1-BtBNjrT*i+Ryl=bt$R*pJZr}>60*m* z?^K~L7#5&096Of`r$Ks_DAv%EJ%XC^`}(nkq$U(Ppq^!sqAt;rNYy85l=B?km;#Ri z{RhAicl5uAJn-hmFAocBfzG)RuSE^F+d~>6@e)|;;=DZswB?SI303lsFwZDqU{;G5 z-DD9}{lYb{j1mg5?;Q;|dcSC7XI8-qKbYO8EKz@xlN;?Bd226WOvED4e*7aW?X}41 zQxeY?Bi$Kg$H!JMs6)bW09F1^qlG930$kjEd1u4@Q1b8yQP8uL|4a1aH$H2Z?bMZX zG%PCBE9Vt(CrSv|WqY_NfSiN3Rew8tpm(0r;^2Vj;B<uSjjYYK-m#a!r>fAA$^*VU zLY|9x=kGl=jZ_FOoJc_qx*yV@KOK~hX*IV45363ZkEX)#OSq^F()GdWEXr9`Ban<e zz1miC-0dJXl;K3m1Q0YRiPedNbYRz?`UWaA7RH}%r~FPeO{jXxQ&F!3U2;WS(K^*o z%NA{O+qoU&A|6^}Dx{Lr4B7{VB2j<e44i8bRB|lyVd%&Jqn95YK$Ktn+5b~pb{clz zPk$wzGa#INv1JfEHT0Yui0zyeoeK3dvMEjtP<LfaciS-)H8;C?n<lNr^k5B_0x!Zn zO#zS!P`)OYIHw&x5g$pd@IQ>X6ko@iAM~}sVo!O+L5YzpzqUmZNmtn}S0ANVo&}$F zeY_cyO^oH|bW(e?FJHAqFDhI=dg0aYS8so-?>Q`e6fPHLeTe;GWBu260<v>as?=5+ zRnf7_$7H=C3s6Y<W*JtG@BGO8;{k-tq%G>>y85{vL8-Nw$}|9Udw!U<%*u%6J0Piv zK&rK5s&p{L-tzNiz0Xe5De7rr_pIn2`O?<if23ok_t!@6gD(uRI>r$XxCBlk6QT6x z9R`_+5WmE}N-1c->gS~Misf}I<mD(iiQY^`p;blYV;k<W_5Nw7qhUC@F_n+Pg01bR zI)-6P;MsX#iTB2H1@sFGL`6xzG&O7Q9|XFhf0I-S_S-Pj$*p48`<cbnbcSHMY2`QD zq7xSQ_nG|0{6`fPj2IieBuXX47T?OJB-)xR^GrtUi^b&{)o~3222<-7B!jh_RlX(G z;LKR@r)F$4iFDkicM#^r2DR#{wDT=#K!@pSh6q{$@K)dM(&LG{v&&51#U$%fx|59$ zWW86}hHyf=5ri^)=Hihq3jSj#o+b&Gh#N3}jtFW&oG#1kf(*X#gjqe~$Ujw$cR}Rk zg43^?S3Qfhf88*c%&6go98nWVapK?aehTRD@RSV0E?jNi<<A_IdWgDRh|1qmuUoEV zcs%bJ8Q|R~OuUQl&WbJCGntXM&md+p2QrsQ0BfW}lAhZ`%Ip}yqv83A^ltQ6=O~H3 zk$hAVZi;3QW=Pu#2*C;K8}k*Zrn!kVjFwJ`tGuPLylP4n*w4-7V;)kp4Qwr*3H;LK z>0z{~0wTDyE3s)Fe;zu0NxNd4^ej@(pp!tS)GePGO36Y+|EGtFl30rrU8}uQiyB`r z)@ML!+q(wN`V3qpGPY_*y3q6iS-VURYrxo!qsZXU`3H#%3Z0RcFxh7SH~Er`+aS}o zNJcG;uJj%wG*VAr@E}X<s?9^~(Cc(nsD@q@oz*<$EMV8o_#;Uj-s0K!PEJDGbV1up zw7Qzi;XN8F<KKWD9ZkC}sc1@<n5sq0`iN~{irQC=uO?gfEg?p;CJTM+IDwNK1NvwB z)z1d-6ywQ!SG&A?yG%r%1u$0B>frv)7;w_~ys3ZHn3OTcNuQ{V>jGP98Rfe@6R{S9 zsA)Jm<4K?)upa}7$fc+PLIYDvoc);xy@yb}8fV1ae(5n*7XMQ7>Lm%)44SBPcH5An zNV=fd=45s^qK&V8D!;`dYm%;N#{e8z$Vb~1&JW?#uXc#<I&_pV-4r%fTGzd@zqGAc zed2k(m~L(|!hYOBXuaS3O@ge*+%5HZaQ62NoV61~>T1~;r@v0<h<vBAJdufCYI}5q zIs+6D9nF|KCPCn3^V^M&K(dj;Cf7$TB8TdelNinA4jnUQjJ(+lV{5vxom~B_G?(<C ztfRc#Sf;AA+ygVoI)|%Hb4{lj9ux~6ZAHA*6kNx(G6#4&iTTELIqJH!cm2};e!J`` zFzhF8oE{w07i;?ibg*bOI;QHpA5052ovu1fGnSY_CfPdGwi^}*C#}k78(NJ1?u=M# zn;Whvjq{=7?qNamLz>nfWcM2%94k2SN;yZqtmutrK?Yv1)XXZNV8Yiw|MQ&mQ7q!3 z{@sLOR#QLl9V?eeufDWw;}b1sl2qu)Jal$PoE9t1As;M_o09fpR!O_>3G~cmdzjf` zNL>`93m;Lr;1PXmV(T~TLk~k*&e8V8LeJ>znOs)@@#KIT<KvejXCBOFj~dBmnO#U! z4E(@!esEX8U?G!r94ZFk_e-j7Op-#}q)j~eIw#kH%cM6Rq77>zjH!Q_z*mpO6Az?( z%<o*di?|~_Q@_&5SEKS%BPXGx=zgjEM)?sl9Db_D?VBRvgMb~K{HS0m^AZf`d(7Ya zAhV#=nvOVrz~0C{g^_|%6`e5b0PTy&WpTOJGo12)2YUNEPZhf+DP*VH+gB?itKbAG zY#B})JyaWgW8NN(=)V!6KAL2~7*W+aQtokaP(Z~wUujWn0}$NPsFv^=yW4!G@tZXg z*^Qw)_hl@@-n()v>JcOKOqsvlL}012@x+6UL+>7BDgf3aL?63)_o=TFKfkii7btl( zYo$n*IvWlS7iV6$orS?Mq*;)=6fZNH*FAe-8V>ls-CRkJ$2SUZ>5BX*L1%)@!a0Si z7fz<bz776)G26{Eh!ZJ`>K)|SPF*p9fDwF(b&BN42W=z$DGZ_$gNXCbbXpNF%oHOb zB-#-J^@v{uaOua-&)Fj$)IJToroRepkekCl40q4*@b=_|^{79->*8=BG>>O2i4`D~ zzf%rdDdXsnjfSmgI)MJR74-6rI|_{Fv!@t3NevzXdxmu<SNzG3;Z*nahGC5J8>ZG< z;sMcQ?-QAL%dd#B{1Y@CIC1xNcE<^^6Z<UgHDaoN4@;Bbv}Q#LB$D8wC)TpjbPLui z`m*;IqR&T#r`whKvTJP)*^D%u14rvLXh3o{lh#nfsOZmni=xH2)FlLoyJ@_J?NmYg zv!L+T?Bc59p2srL`>;?wBSnNprk~aAaz2M67wi}-FBUIkvlprE!xo4`GA7>)INffD z{nFFf@lqs}fBbIXPwL8fWrn!B|5+~Tc_DhF`#kDRz_6g_PsM7bZ`RL?vc>W1$E{B_ zZ_->+o?L_gHNUhmjsFEUoKmMt`?w>{c~ST7{taSpr=5w18%hWBuLA$DteP6%1bfD+ z$@8lw?%xl~#socoU3v4t*T%`7G5Pip9Bypu8{&Pz+n5~x(2zCB!j<TTKx<Wasn1ig z{bcC3;BflO;4k%^Q?HL+GbuRR7?{F%J9><iS?1isQ1_JBX+Fik3Dk$;+BRx@m{l3t ze!XDYO;a?B&o>1WF+8Diry8ZL#8!)!bxmQ+0lCNh1@FIjx(Ruz_yQp>zmmc75BtW5 zaX-yELw|TV?CQp5^yRm7)v-ZCJ5(xSl>V}G>dk|SUeQtp*8SvRdO=1b)X_(j<geAy z|7w|6)Q$dZQS3&XK7T8>^c9^nko92iTnR9M&dTXUH1OYyUYXM}D^}XldvMl)=h%VZ z$D&z2NAGa!5?*}x$jKZz8wM18$c%;4cFzK_^ljzOJMy0&8h!o}Otd;d|JI9$A<;>1 z>N<A=#x$Syt&QfwblZ14^xKfC*>8kuLR80bB+tB)Ye^Wg<|(||pOp9eETq<5ewYVk zsp{(QqAH`A!uAs-f1yeG^G{&TOrCbcnx@(2B91}f&HRlMJ^Tv&3?n!MJ7@mk;}-{+ z^@VNDCVk^<iU(a@;`0}wbF_$aKP7jz3x(s3cn;fHS7^H^)K5!H1+PJg`u0!Sv-uP7 z2I<!(6j$`nu}m$DQ*GRo4vM+=P*0%Bn*Yz`2axuy?hXo2O@G<WIAMQpge5Ig%FnLM zJd)s(Y~8Ti>iHnqE~LzrFf+?>kD>ulq=P%yi#N7{IiF8_9{rB6Cc`aQfwa*Rwj-b9 z3+zfBbX(9>(ZRE+<rq2((cd0$sph(>9%a-Ts-Q!|`Wa)kUIq#s<gs$<a5`^*MYy67 zhpv3-LK{YUQ0u-`)eEZpYhws%iJrW$KJJDPDVR%6+V1qL+^*a#sB<N}+!hNyo$1FJ z%lUvg+8p)v)BD3~H>&t8B3zNv`bEkJ;o7rnzCAtYsgpa7ELAfs2))#nH%gZH^KC9; zi+ZUJ@mwS3vUgIQFK+K200<wSahr59(w?p~$fM8jI{N642ne~FPHDY@6dT03EYb(~ z+w7U`cU&Qz)C-Cl=MGrWF-PeHR^3hRC5Ju++3nG^!<^r1k9#zJtv!JoRH&+PUWO`k zf+-2iK;&m+<@=@8VYl7(|I%??`u?%=;jz1nFJ>UX@bI_;f%v2zgF$XaH|M;o=GV9} z$~=g;CHV0eYCit{S>pO^DYsAbr^pLw2y)Rm=avh`;QsIjT=eYP`R~s;sXsE8&H4<Y zA1pDRuq5q}xw@kkze;0XBcaLwpyVVWOO{CZCY0Gh;4*)I?~1U?#z!x@o@?EyRCnY1 zKN@bUc4szz-(&U}&b>6EJh+sr6~>TU%j~${dvEQ){ja|y|Lhk1>|w+?IMPX!i==yD zDIOQPmRGJhx~vigDA7lyx_0O~vU3~N#M%Q-P<-^FXycKb3!O>$*}j82h}owbPXZFV z&}~r>0E1_L77PF<aa(9WL<P}cEcu!xNIxRP2XTV)5&#FiD8-G+*Tu=9rt<mc8-=JQ zfYUQbL|VYDeb5B=IGLe{Cn7|UKE%1V16IaqC^|e{b&PCNfK@v4m2!-ptrrvq&)=67 zdq6f6DWfwprEnfdwe>zZxGeG4vPtZnAh~?_I+Xe4jo^S0;u}i9I@qo#`NWZsrYIdg z{GO^b#K1GJ2>}8}JyeYcVL%Q82{8{u0K>c@a6GV#i-G`%)$-=EAAcE!E&lk_S?Uk0 z(D?v?sEr6G|B-0``%*GP(Rw61<95!bt&SkjYw>op@_A&iRSPhR66J3<oJn2@fW-!$ zP@SvH9aW&4iXL`mXA9Y=E4IB}Xdn(}JiZK?5rCK5g>qamfpbnXNa6^7KeVv)=W%o9 z0vO2oMZBb&B2ffL=!fHt{n|ZG3nBxdyzsc00d6V3eq@O7iy`@J!)KDENB^;|<?SQu z`e(TjDKohdz`Ro#gU52;qYNmnNCLJO7&CO?m=$CpkD9UQ3ApnU7t&t19ES%0P@>1Y zjMFXW-CrB-yvZi&w#hpeES^ybvwQG;G{Fo4yuC%nlpnBu75+rJ_|$5k9N@e2n7aZ| zIl%Js_4$d$i$=kf@Rk4oXGpzplC=_KM>u5wyQ$uAVU`i@{3niyMt#dPX-12Gzr_TT z;@Xr!SfE-#{EaD`6Vcjb{tQWOp9qS-E;Qmy25|RB$g-FXCEtS(mg<3EY<@6Xar6FT zr|kZRC6_Fv9*f=tTnC@^$UeTrjQ?oZcGexi+lF9CvERE{9ZIxZKrclSKV3;=raRe2 ztW;dT00d?_N&bhr5JZQ2F3zGzfDRIW6dec~m#U9YC+wl?DAIV5iZ|2-?ok(wX_JXJ zkFwT*2;d$rh8WhQ==)s_5JRq<iLy^z^9xn4%+I|aAT+$iK2e{3tW@rs+DX?xQ06(( zg?E~#T|a&wn@u3x;OWP{hOpfF07(MnV%*jB1I`&S9Ew$_YnCo>AaOoL9FQcfJmm2w zgA6=5W+tdKasi50W0_V=R6U3V;eaO4Y6Smz-soM;MUDZ0jDYJC_$z0e_-{O>UYnDM zY@PLYlT?<p;;Yg%Cb&G&O`Avj{JYh`Qz=EZ=T@i`bA+7^JVE-%%|-n#r<L+cX(jW( zXQyC=w(m=y2VUeZ`J_ZMuO#eAh%MLQ1%ZcqeTNdkC@GAU9za?L%Ud@r^-87iPFq*K zYZ{VFN@s1jam*QO^r2f8V!XsJ#gM2qO0Kgskkit~HrI-soptwpv#OM*b5P+-?kl`N z0rKyK;duBN@3`-l_u_m9lPos<T_^815E=FAJos0?n)4X=+%;uyv&=81gFJmf6+$u0 zOq=!si4a|cjz@F;st^nq4y)jmvw@PpQ}o;ZsjgD9OL+P)Hs>oJ0B7Y3f2nRUl~;t} zcW@s-nh7AQK`mMtAgbpfRjt(&oGD8qJrPH9?RZWdUqgu9Ugd07K4Pq^mG>GGjA%=? zSDhi{Js;d`^86grtUsiqekcs>;kN{}63s@Hkf%`a6-!fzFPReCX?=sPHH3gb0YW}d zt{J$dcfB)7FvO`sFc=;qwSQ`5{^Q}R4D@P*oRLYhI<OBYX;v5$B*JlJ#_x+}#u+1J z0lGOCYBG$^WEOKCBc<fw=Wd8z?ZOq`%vwr!FPVV@Lh&;#!<h-6ljyi}2o=SV?0A#y zw|E4eK_B>R_p3r0=;u_&PwOk3F}7&ao8ubtz#l_I64Fdv;TQv60L$`Wm_i?lR4@!G z2gV@gTS8}1Vn%QeDh#`93b+EW%UJ<;&4;9DOWFz<Uk~65m*Fqtve3V}=M--RG=;ed z;Ku@1LJ<RwIU9TQv#aScc&zkzQ}NaOd!DN55a#i`Fsu<@xXo_EeVe<)@&Y0rOK6~p zDF+7@>U9czdA5_MQLd;>9$T>PMo@Kp)FZXz_C@9qNeXtH;-Q*>rc+cCk>S}OIB(ur zWi$lwhZ54Pu71`!%6kTq4wK*7#Cs^qt_B8L+Yv_d^$3_(mKt@Bp3d<KpXzz?6{F<= zqmp=yhBE)H*(XTz5pTQP>yN2O<F{9hGlX!GPY~D$C7Y9w+T#!M?)UI`Dme()<{iQm zDi}?w#&|0<j7?i=N0H^NpX;DDDhvW<GnlrKJOKC7G!KKwH$j2{xH;Xj&c6|);J_Sy ztkT`R2+cg1^ue0bQvdO#i&Q1+V>>c~h?xsxiq;LGhd!>RDID26)?XHtk5S;TFHMmX zd81z1>lBX(nx6}e_qgXc`X2d1?|HXJi&4k47BV$&#fy!2Iw~}ZGh8S?c<b8Sps!8j zEkk8%^*k7j`GI1suINC1Et9-Kf;OD*58r=Lmk2Xn_kTKbS!4IbTN!Oq&h8|gxjyAE zdac|UeV_zJ&9_O5bsoscX=#7m_U=x3*s<fRGMfD1f#7?#XZ5UD<`i1isi@Y5P~X?* z4{W0Y>-~6Jya3SiI^FfU+Dc`X399I-EJw%LPu3v^$3$z^w8}}XHR?61!%!9NU*h+y z*r#tipYhaDu$V&|@>)MG>k2lJ&0WKff_aA5II)@-L=iYQ_#vy(=}*{6rdgEe?&O&; zgvpN6Qfb%jwE9?@j+EMa%OmazmVM9vs#rC5%cZ2pUFI1WqGr?+v=)vH7^L2bN_U|< zY2gvM>67}=U7doL`b(M<`>!ffbFKjBrPUa}oKHw7>v1IXpx&sleVxg3K^}dC?kB97 z3m2JS{}NHWEnaCRq4U5pqb=|G)o|BzMU75{&y~nJ{nfywH;>t!-=C?d#WVMwO*uKX zDmizZSgygCner)*HJ1vW&J#_Fw!tEV^DcBtnpa?mFdV{ELJ=4(MDwds|Lt9Fu<|rq zok3Q!&i+|UdKCrFd4Gh#$a-E;5^UH>jC&@zCg@w?k&AZw?e6{E9+WH$b^jD+cG>&C zCo96Y6v~$2(+ii6mop9)On+t!>q8s2v(lQlE}eS#h?D!=@#7*~?dRAb{&V!eUWNUo z7;c11ZnV(@{lycEMpwhQ7igW*lDAcpvY=^IF9p^s=pK<sval0zkd$}Woz8Tgkn-Wj zmz7zUiII`?Pto%u5RZGE!Xt7>r>_z}{>T%GvMmaHNfhW%I@%h2Yn$yyl0CqG*DtJt z6}mK`K_ny^-ukg?`_+x>N~Dx?LJBF;%HGeuV++r}>1$IB-}&lGs@p40mUCDY6>%UB z;CBH~6(!_@AsF1;l%r3CJ^!1yn6D^?m-Ur>FpFQ7BFJWAeTjQMqwbOPOhZJA(sR74 z06at1#Z`hJFlfK!Z?!DgpUX3-H2-vfTj1_AM*3uE8G(1{_({2^58x+#@VDaNQjQz& z#>ABBpjUr3<d-S4kH`Llta3;U0l)`0XCP9s;>j0Slp4gr{TT)9mL(R(H)T0c)(8&h zf9r9LU?7c`wH5Rb0veImHgaBjNL%}rR2ibTnWCsv*U`#?mp*=7)F(W>FTNm&!o?B} zf5h<lepVL-@yy$>XqpL@v;CMiF&290yBp?NLI1EDvU5)`VbbdNJ~SRcAXhztFpk!N z#0ph}yqJR(E>91N6C!&{o4&vc<h@1`U9&OA#wP!1QH|Fuw90dG%7B?x2SbPpB9Mu; zcXNw`BPwT8Kn@8_qGRAKWAaLg2k^2U+e_@wEli`Fc=xD+11oPQCBO=OK%gNYG?r$T z$771+GR?cqFRfHB2bY_a5Ey@!5J|suLHKZL+9}UlhTM{NMZ99xc0Xn-aPq|DDfV(C zT?)hD3WWT|bAYz~8fq#p=ayl#Oo-28(rQ-SSNzqAR9quTV6y+?BDFaIwD%-hd6d{H zp$VGH9)E8%4WvdFaDBxIdsd4z`g46t+(TJ)*sBin53*6b*c4+Z;2KPHQ4Vs}3Nme2 zei}5O0VsXp^&G|^Uwp)Hk#cv?^!qa@^VITJY^7v)>b?ag%8*oDeG3ao682bRzyn@K z(r>mQ)&=Rc0FEW-cJdh?{sWfqb=CMU7AQj8tX$-gJMND8?-T<W7&EY&LZ`)g{g4y3 zUS8x63P$f6XCA*ezBFYx{#ZC0P2ea1`Dp$Izc3WXrI*_UMWm0UhxYE@@C07<ljicp zmx!XbcIl2C1tqc>F?4D9R?yRExKMNrk5l%R=OFrlxeG*tn#t3w=c((J>vHrXIx`m+ zMxC^*!!ew-++!qxJpX5VI8#rtOTD5lIx;=8ciPB2)?$uDWWQnq0k5sogOq&b%W4-N zpm?}b-1CU$*bRJzGGI`h+^pv8N^xZpvisEt7YNu@&NH@JZ^uM`5=yw2lpgY`D62Ba zQo&l&qsK5H6WUKlr*;btPu$4rY6IE}FcEUZ+Fb;sh;FvDdUb>wre(pBqfasy(*uPF zOVfEqTz3R+iUrEgYc7A7U6TP%Td9tF1#TXQICGtQ<GPTIU=vB`<?+Fq8(34-Fa}L^ zM$MW5#j9$Bs@AHGs_obBlz3X{vk51iB{T|ND8}V5ndY|TbreGr_{QePa3x{jHp^?$ zlk$FcbEi%A)U7%F!a9&K05Tsr!xy%K@3-S}y;+OyhvHxWwe-$q^|&l`0$OfUaM(H+ z{yvwUV(x9lxtYI8mt9oHGsb$^V-3MoSAN~S2d({@y{Q=GXtjL&K3`DCkqx}g`<C|9 zRwFL8CC#wWI<xT)**>1GjL;+R;G}R@PtovWAfmS(ZUdekE)yN`d$!yuf;YhGCo!ud zoHVrIyu_CovhcsN;uqDKkJQ3KKal0fPO%v(64(?OUrGFYKEhe^6vy966|ta|!Ix<3 z(J)+?q3J0}8-S}edd+)dkO>IOLT8`4@K7hC4LTGTYNJ{<u12uam|o3lHPu*m`82t@ zM{k)!fFIo+^vJmeJ{4Sltt6BZvn3xP?%f*+A2xqN1BuHfC`vRv5?|tq6g(3vw4S6G z0s<Z%5KjkFjprBsZLi|9{%d4W`^sN7qq!83LRMMCcGojDoZ;)>^P;+xAK$~TMCB`^ zCYM9Fj$_69il*X4=kaJ!LghZY6<vy5ZzD9AUH;S(@@Xncn=yONDi*5JLz5Y$)JGE9 zrBx5Lzqnag^VRv}yI#l8)?u*~MY)WEax9nKU!jzF(aC5cMlg?edE=~W;QhaoFh=qb z(Q~1bj3dU7p^UfOS@H;GAT)@hvzq@)?lqqB_!Kee6fV!JYQD~Byj}9qd!s$O2HLs7 zKjG9*9^S?0mgv5ejH-dSTF2?*!dyxY#-FC6IB(w_1h&qFemJ;SLX#@h4U71+9;^-E zGzeKxz7heI`I5!`3+j&M(oc!wyT=af*dGZZCQ&|n>V~&BsyZ`sPdNdABm{{_!VU+` z_8eG?&UqsA2H){~@ooeIN!JFc8(X<MXBR8Ed79~?Dced>)-Oh8&b}ZW$K8Z;sJ3>o z2LbB2E1x_9BDoxikxQ}1g*r3GQKC)l=O$2ezGrHo?v$xu&eZBT*P`w91%&kTy0<8z zYU{npkfua2DffRLmMVow-@K^_`5%j=a41WR$naMb@s}Wk;YzF!+Dp+GIUolCpt96~ zkf>uz$w!$~2-=NgE(S1387%6TD7uV2C!X};QVje<G<;iBw^uH*u#k5&<3kMjk<*r5 ze~-Ot656`;$<tiFgyHLagXkMw+j!y^ry?kx)nxmG&+cKXqypUb0A0qL;JS9E4kJ3a z?uASbz521qK5YJ-yMZ-`C?ebMfWrGkL{U{<5#uQJW@HV>nqhK!-|0K7z3z(#4%-$~ z%sma@gqwBBoUfVwky;nL;~~&=)h+h=bNUmfx;)3wmXNy&gr$RPs~04%(QHJ9r5w+P zaW0fa(ft*M*T-o}2{>0~z%$HnfhBEoA>i&$UT&!5VB_9Mpz~MRh`LClw3WKbYlQ;- zryMHtj(I4+LzeX)MSgRVoq%rT))dNHsj7L(T)(3Ti89C&F;{;fy~cHoGtwN|xT)^_ z;|@uI=>7ND!CMcXn-6wxjP*3uo!H!LvZ<CxYifOIfM2dtn>UD4G$OE|K+%uT4uiNW zht}f<RT5}f-@l2MDx4Tncp9z%gFWqtLAh`JM+&zGSK&V%d)#)KquFOvrQoyFa%}$^ z?eog{4F=3^N2whRtgPZg?2>ZZg{H-Dfw3xK7dcj`r}4{l4S9Htq(W$dTj^oLq)<5r zJx5ea8`rz0Z(F?kG+a5JTW5qSPsp4n&1<fEHC#;F(~T4T84shz3mb)jF~_L1)}0T@ zFVB!Ky}uvhhzs{*JOjVCrIOG1E_>J}2XZp;&+&f%t}qTKgD)K<^0%(OiCD~>d4=zY zVZ5gQ`<Zc<#drIL3NSB}Vdjes8og#*(>=^iaLB9@jI^ef2YK2T&gorwsi)1Kb^bN_ zf<nV3@~WHAy6!{GGE@CanfGJw{J^tlakt~+UT0l94Oj1=hE^z~-o5d=d`^k(x0(80 zV?F8~QVU$rQ-<u=P~+rC<HLVa@a@(AJP>zelaM+CB@(wWhbwL!J@J`)EOWQ`s${?W zt4{6wh;j@(Ej{9H)nZmxYHL_wp|OH<gzw|!JxI(}_~;zUY8doD(**0Y58q7N%&RJH zVDXPsl}3GPjUm<!ao?>qjZ^FyJk62fkE#7l69NFOEP|TrrxT$+_{87i$x=7heu*C1 zIvXV$JkAmAOc~YvhG&Ylf90w)9<8Kgh!XLH7&sutBaP)O@bUM%zr4DvPYB$(^J@vF z>9)5*e*>5js{aefZ`VCs>ff=^^<+g{>_?-m;E$9EJJ;h;nV-GVHw3x(`br-j!wtq0 z2V<knG1!eWg$mC3T|+8Aoech5bn&!G&<(AqDiJz=iQ;%GHoEdW+!H6<c*zwhw0rub zZ^Z?Aa=j>FCLz)jjwJqWbrf^BfIIPTPil@D%eZ2OPk0IWD~g_tup(+&IsJRxLLy3B z6$?s?+0~-{D`C?gc6{m{KQjCy;`Y->`kyL=NB`OeCJtM(F1qR@kXoTT3Vrf%NAURs zHRIYhG1|_GtIDdfiA@J}E}{B8emO;me*T$_?A3Fb|AZ%FfQSLS2QEQ4<x?<`5;2YU z>woeu;fPAzk^BAOGwrwo@L9AP4gigrX~F=3TU-j!KSoFsKG1&VOGHk;i3G;<gTj_0 z`f4%&LjA}r%ryWNbYYjVt^hEx!*vEC{Yptj2cOQbMf^ADa04E{vldZ}bCI$ycInJl zyPM)rOe!#qUTI7!&yiNTi`uImzv-f&8xHsTFqqGfl}7FB*?_CI+lbaLPB}w{;1IAi z#|6Afa^5HC?y%`%NqiDeDaPxOeo5#t^RNB>7O6={z!+djQjgxfg-=VZp1=ho@_0&& zlTNL?PUA+RkVS!hLusjh9d1bedeo0Q3lo$klIyMWq$IRb;QGN8#RXy7OP$wLRDi?X zd~&9)uCA5Gu3b)Byjwu|!atE2{LT7$zmG*r@CPBk-~A1MabjY1`d)w8?DZ&XR<kTY zL#ti<*GG0XcUORR(mS0;nZ2!z(8m6-((v>d?0yCckP#3#U@S?70%#9_3S<3z+auvW zS)DS$J?@u`y1rMk(v}QLQ-+>FMXLFd1iVACjXpt_1sUql{v5Ma6hk-%^;NZ_%?3M$ z1M*~MCbEi3H;*P&A4|WcU(at-osyIBnO#vr3qhOU6&_8e1dbhhWFC;fCuS<~&Jyjt ztTD{4BV&SklQN=Ir&5fbR`jJrd8sNF%Et%RX>-}|0>pM%YgW77sYX2FeRXwt7q^WI z%U~L$WTmu5Y!HA5CP66~pwy+NxJNMPl?KN)<bY3`$2@0pl(h7dl)(*>Fo~|pEyp!D zz?L`6y6b*$Cw_yRURd%PpDp`qYJ7!cYK?9+F9_*O;r#iG`e!hE4*hpJuyxiF!{=D} z8Q2rscvKze>29#Yj8{FJ<bkPNCR)6ga7he>g47~(RJszBhoCXfBx1#=M}O&vQB`mI zgd9ru;i6`F{*EUfXJq+}b0_(DW4IP@q7=O(bw&&(+{e}9Ow}io7?N1=uL!o(l_|0j z2cQtps^Zcv{JmX>>u-+hhoGp410{3pmkUaC<GdW1F`NTFmGZLj-4ySuG^`lH9=Hr; znK>iwEZS$lE`MPsKZH>q)yQAfje01;y}WWqT-uW5=-{8CW{G@ME%ILT<&RqHb5RYQ zjpDRGwEZ2^9Ppak%_tjH3Bn~IcL^^ALBLN5M%7UktsYdbkc?vS1Afp}NuNC!u;Fjr zT1QJV&{+O)(cJsl?^!;N5F*MI#<Bp)AMOk7sJLn?#k}3wg)c9eLt!dhU9W}I4*a^U zu$&qo`?`l8nYrPjU@TVfc9H*NV)8uB=56|bFP9(tJYzp8#3w^oe)+e@Zvr}*Ns~0X zk|x`gxWOFP(pI<$>(@AuBqk6NfqC&%sK0CHer9fsopeA()i~;2nyi&E)R{T{E5hs# zTQJ-OW6{Cw!tTc<@k5*Xg=Mia41*Dj*6veYyJb)Su|@=(a)Woa4;%7ToB=3!2&<hb zV?sAnE6UBe91Z)XYZ(gG3_gLom`Bc9x<xk*C3`I#y|0<)8)3FL7D*`RPx0f!8h1W< zpi`AcN=Z!>l5vdFzAuVw&@sR&VkpXom`*}#qInT3uFV8v60c%}sVKPu>sD1_Ob?Kg zv3+r*G7qa4bR~x2B=WwwBBgcZBCOaG9olY4fwK5)78io|S^nA%S{}li{T2omRKtd* zOA|N%D!v6!wBT?Ifcq&<)AHfv@RT|8KGAmN(g5c8X&-LjVp<e`->}zCv#S_)XeYPB zov7u~#WwJ-s3g}x%#T%JZQW-g-lp^j;1Y63o-m$Lwv(?Q#?}ghQ1h!?m6Q%E**KRV zbA=TB^|@-^aG&Bk<h$jR0i`-7uZr{?erH;|ru2T#RGF!*L}1uC&)~okq>1V=r9l~( zC{I+2dX693nw2eX@;doj_<8h+gwy*%ZxT?p0omst0G!CWNcH+`CsjdW#8;*iZw0pz z`aK>!M^BBgCkrQ?s^e}hP1+I)f9r)vE>|zRFBpNzgDWdtr;TNqGDUuLI^NdY{VypR zRdLs+@-?A|AX?H`A>>~Z=T%E!^h8NmYzA_lv&|<#DlbUQ2DwT*->)JBf{t7`SGlOk z6sKtP6ue)Ge#rbva5P57hA<7FW$3CTZ(Dq5ws;;k3Eh6_ysx-{ICZ)W>IV(sqVf=M zM}!Y^?tz`sfAn0q?(xzO`m>}?T{YMP@4h@p_^nZ3q4=A8kxT!W#>)ETQTlAcxBC0w z_6FDKjj=~XdhJl>k3Wo;ysqDTD0<<UT3J@}F~g^6D!+e*Cm&zUThsZ*-YiF<98>zT zRE>gX<YaQs#$dz){m~2ar$`|>u&`o73TBIn(}{Q>VzQhCkZ;HRo+qhD;w+0i$tSM6 zyh{06jo9_&Lw}>WF+K#dfPMrZAON)S1}Z%8L|AZ19?D;wimn%7oR1m1HdR&AGBLM& z10>lL-V~iskE`c9{ca_x!#`3^c60>{x@q%Qr#uis&2omSa|;J*4ZDq%z5XNRAxNBp z6%zzH)R{_(5ME2;om0E&kHq%&zhnSO=OEegatQPO>_Jm;qq$NCihsY}=lX?^$+x5@ zf5b|mcql+onDX8}G<EcB0j_$y`*#iJ$~!)xn;4UKNe0+*`S(hID&OZ)g!FaFudxTG zpEj0Vwn{D(ueqt0H)thcrT{y)iEE&mB()CCxpq3bCLp98;z9;6{uACPuWq7tg|&UW z)YgghfCqNf?%-Ja7uWLo8@z!eIX#FM9#^b-@}T~hxYdyktF14~_%eQDd#TdDpeTI8 z(Cz)%HZjyuVDy~Yzi7t!%E9KgzvtMVC^Xi*0Ou#fiJtBx_UO}`4Wf-ATs8yyWR4JA znitG<3}Z=Wk++Ko(tFr$rzY1=y`)JYM3S9u`g6N>rpZxa=Q1~N^>g#P({tk(i|SJc zgom^)y+n_}o_@nE@lwwP<LZl$?ORLi^Rpcr29a5Xmw2#kqpi#Pjpr}F_PG-Wrp{sh zmd!{`Q$48K^oyn^Mn|5$VU9^#1^T$$RWy5Xx`354czW<h22bICDSn_+?!PU>y}ta8 zTHUI15>pyR)i!rou^O!j9kAc?KavCvsSB(QmECqtQ-=E81$>8meUx@|*52r6G^qgU zj|_br(093j@=414CZMU{N&Ku&I0$ktdt!kNgU@3w=Qhv;?^sJT0|+g|h3YBt<y#$e z#RelBwO#73>}A#Z+Ch=4RaDo(=wEg}--Q2nIaH+X^~=lUszzh>XKnqeX%%+rzooY@ ze(LJ3wsgwCko*4_Iun1U|2U3+XNPTu@7%X-=DzP++YEEh8B)!CM7fjt)yy#W97RGi z61tEiU9JkH+^JMZk}jmu>E}=Qejks|^?tu!&nI3wcwWNgL#I*b`5tI<bc}|Qh)Hxp z*$(la8tJ+jhszl7Z6dmC3KCYI=otxM_<3#N_wUTU!?#9i-ifJ&g+k`?kp&<@1_UCR z4-ugPTBJ+OsxYG`$9iIL%|(yQmY^|*&Ps)1hHyPh^~fdO4=KVlLciWI!Xn4hw`}B~ z(c(U%{#T#l-A_?$nni8b8j~XXBws#ee;>2y(x0b9<D<z^8JTbyy!0(7L5Fr~YN<aT zZ4wam#fX1j1k<{NdEDr7`V>33jGDgPAJL=Kk2=LbwF$Mg#auKJh(_?C7A1}fOn}!c z8nuouhRcDyg+oJlorF7f4aku~Glg;dX3G+c5S;P^rWh(RcE5Kq^zk33tpM)Ul(5^s zIJ_c1Q{mp9G`jWjn?WPmf&$CN+j%1R;cpmUYH}TKGlBPxmO8~vI)()(NggYW<rMAC zXiZ11p-OaIcpFh`4fps};g06IU7=qNzKCq(;XChN2rZF^FCx+$>tK{vU>=m_7lI^# zgC3Xd#0dXFKo|R3PL8J7I{wcg{6{RTvj1%8J!M@1%Ki9=Wla6?u&rRwx9zgfvrDPV z5n&%Y@INAOX^UP2Z;kCXN&-~~pcnp;d5{$TLCVxy>tM*|R`1{5Nx0~GBBWOmm`Asf za4s7I6CSGQD7#e^6GE|;7<o#HMKm~wIlb<?%qOHgSgX?$zP#GXkHM$iN5Ky4B)pJa zLclF-KtPrzT;LJV`xS;$rCc!->^J@gQB<41G}Bs$Tz}S!{jYeV`c>2pt{SJu-X@Og z+36j|g=>PXr5lAUbV}Ju5*{M_k?`>z@Xq$SJxlCf!@&c_5%rCTV#Cs}HcG~g8IYaV zm~22uHZ|7RkK$z(qs4!-Yxe8pFX9@{C4TV<UN7+ntREIpzJ1xy`szasV?sbL4YyPI z_|#@)9ky%RQv#r=6l3T?jiGOgAJ@&F$6igQIVLEd&=C&KR)3Q8&#YM7$$_}>2wc9u zMQR`yt=dA=?b`VbVD9U|1_NbBsi4e?$oz4IMX6uOHJvH0_6@rZg-BJ9aZUA-L?0X> z{`D)WO}Mj!n6DQ7fj0rKW?kf?geLlr;ir}{ntVM8A!nw#e`M1%K!QmT>|=Ee5&ekP zNXJOFru`t)i~)5Ud?-Sq(|vKp*~tEPCcH;RR`bI&CX6{LTGC;-L-+ooNjsQ=*D%!5 zBTy7RbbB=6K4Hir9q{pf<{hHSn&Yb`{>PO8{aO>R4ZS~@@+K3bkTUu%W4}O32XQ-_ zj5}3tLu*c&sL+faa!=F#Se6pTjn%|(?&J93g)8l4(Rh(Oy)>i9x)}XVrqJfPeq6Hs z<x3i$^1O~9jF#Fp-(Z1!HG!!XV0F==^sCapJ_Wu*tp|JgRYCER!5$^Pk~!PHfwR3q z`O&zFe@qwMod5fe2maxiqsx3RKej0{QGvl)qWgE@2<`&8g4Ss5LO+AV10HS<v;1R- zQGLIAButKf4-~u?sK}DKTvE}P@Qc5=W16>N6}a9v#czwa7HUTz2znx#>MEi5O;6RD zUg4P0nfx-dzhkCKsW?ZXQUSt&2Uld9?Ys5J0dMx!Y~a7hD<yMn>L@>_?S@6??@{3> zJh(_oc+UhEc~}si;3}^7CJ8GR^1+u+Ru+hayt@kHClvZ=CTR!SB0U{PqO#KhWxl#O zAq~eRY+Z!D9FO&)k82a*Ze0oZx|yvZ$-X85(Su32lw7}kYU{iM>Cp~CcNjS22d6u$ z`1JXeG4%{3mbWxPU~LV!zZsZ$-$#)ToO^f7?b`00hOk_zW|QlWbO}GYf!;41*g?WR znwPB$QJ9q$?<NUv@~~ok@f-;~+w7JyXp$f$>5y{@lVGPg6yS`v;rn{DO1NM3J2&s) zYX9`sCOuI4v-AO^LGDRSLd4{<?kfU5E#!R1>>(Vk;_-;V;q50Aqg9k28~ysTYik|L z+3mVshvM<epb;G?oI}B^cvL>-C<gdWuTXrkj^A)G4QS9-<m2)?9z}XqV}uAi57oLs zk$+4PfQ)G-VY@>LZe+?{&J>;n#0~JmN<Vx^@Q5FkA6Anr!&!WaPs&OI%SXox6QEfv zkXe38>y|{&&6M9s3nh@BMEOrr`%nZIt&=jjf2#P-iAWYFU$dW(Hq7!VdsFYh=WJ~L zg)KTYP{Q`e0If)xMM}=Q7E_o&9+?ph_zQRtZ-XRxfT<NVu1q;3(yxArbgg#io&Col z{J)X9Thckw6c`?x{&mssu8;b_<fs4yOk;>`SK$-iGpf&@22HYMy)%W?GKGBWu^bg_ zx@iQS5UicA-2s(((O8_A#`4_FYUt0bWJRA}ED2%PO>?BuAcW<E6<Y6-mKqH#ePrIG zYc{>XM-tRly;UPGw)_*>ed3M(WNO4x|0rQ;v|`xr_`AJ73Hzi8huY&c6BuuGJaHNB zxH~8)T@=^}c4EwSKu^k)`Af$?XQ)ZuVJ%nunEuuo@n1R|U$vEOOjQjUg}sQw>Gfl~ z8A9Hf;3iIVrPpQ7k!ZsLjmVN}5aC(g8DU6`awX~1n+xw%$M{)RW1e<8Tjz`U#io^s zdQOertx<S^I(vJrGJ*R(Bj$U6$#w_stRTg;WX;%Ycd=kbZWW79u=E)T4Supnnjv_~ z!VaINYW0&wH2|6vf9Bw)ZE6Ot>1)XKjzSTJz!+Ki6-4m|UAkrxU-PtfzU53sS)K2q z8J?ni$TLitaymR!?;k^~3n!(JDY7|#!r-wkmC))(mNb9}!$LfS@s>7@{C)gN9<*P{ z+xgiNekGvRcrnE7{U!J7S1RG$0)s2(3CNC=ol`?<pP?2IWG8XY_{{ecs@c2DM%4&` zKkb@?qTFIfQ%i9@?8@kN*hk8Z?|$#T;V&M*b!wj}PI{XWsj0|+rp7zDdr-DaO|j%0 z>fjMPOYctq3M}KN;jdV&?azt$e4^NC0daUg76uWnf^`2qTAIHHH<yzJAxVB`h^_(> zgGcs-9wzViZ{`y&P0R6Aa@kUs2Ks+r_T$@nOw>8qOE=!KwS$iAdgGS7FkbU*U}Gy; ziLcSo){O2s@ppF`D!g4#;2?#s>z}apJ?h`Y8lDw}vpZ6?gYx(+dF1H1jeyTlFjj_3 zxB{GTwCbSf>jmXOva#EsgR^feM`TYoN04b@(hE<Y=KlB`C9=X4OJj;DkVWVCxQLp) zHtj^IkP8>^k_I7SQh2eRr3=45?rvb|Th|LheSWQOc^29X=6t_-GJE(mW#rNy<Hj1T zL3xux{B8TPbN_yoZ;v$G){RT8f6`Mh&Npg`7!FLknV{)d^|;#Wu&0GqU5n5bOY8y? zZS%`G2#3ve$dwKa@q<Cbk4V|pn@IIOjIM_2jB#Fatc(S!B8t+_ctk#)KP-TmOf~oW z#SjJhuzz~P4*0QMZAZUUwqVF&%@FZfrZfSsdZ)*7{*ze8U#muz%nx0glv<DCxyG$o z*Miy+dEwdf{VL}V<Cm&4D+wV=i04N~YL4)CH4ms^e#_igiy8llr|tN7N7^Tnbd*^_ zUGZic$8dwOUgd>H5(9!Pt_Tou0)rO-O2B3)PTSH(CFArJv!j}<U-+K+?{ybW54}|` zsuocoW4m}#+f6^~Gb`>tT`aZBzF_Vs;ky@fgow#y77e6c9A<0g^PNixPes*ix0VvC zUtT*EITBJgA8u!Iii|VxGm%P1|L4N{l+|qHyrNxSNwjRYkJLO4y|KhMHSUM0@4?++ z5Q69RC-&a#K4;!?6@G9QpI&tv@%PCEG5MS=#Q{UDINr_GJgBBW?#>L}L&0g7H?MEP zTM<>!$`Db=L<5j7WZT8RpZE4YV`5fh9PtkhYktG`+v54_*C;X5zE8<{NmY`DyFM;E zyfK7ODoFrLNX~|15OO8^wwRTTg+a*WV39*uDx$ZjJr^DisY(SKFS0IKR2$K>RGqTU zm|>^3Ve?{47l80A_(mDnM}lq3EDZ>HlC6PNnToFnl6+PSvTi{})um4jR*usYAkq8* zJM?o687K)2sEZsNN=VqDAI|=}J%BPl*nc7l0VK@tjPQx64T{B)+wKc1*Z_bbClv+U z19$*e%kN>IA?%DmfRDj@azolGUF^*RPi5eQi}lnI(2MVIQQ9`6vw7Um!8bH8mTKVr zD9a#F>?3tdd}IOXUT;<0dUC_R!|}KY())5sR!@_(gp3#7{=?ID*T$hlncxy2uJmw# z7|^;1_Y(m9=-r22!6T&Du=#6!js;5_#Q*4Yds!1fAc@G9C5PKA!N|gL>}?o8l}V8y z?;iz70RS(7wF7|UNdvMBI)n`B08AhUToOI3r<5WJ;1t?=p>RJYgsdbnwVTX@FrXqx zcbO2fsFZKEWEo^ETN)^AXZRfGEM<@drTpd<{sTG$@yBJB%01!rIdsB>_M8_gJ*NFA z<7kbfM=D#N(zvdAkOcJv!9J&aa#PKwI(bO-dT_FegA>Sy)&3v=;<nGD8_O0qcQSXx za4*V|r66z~u6TItthyrcwab~{i8JJ$(Vs)di{=re6L|m=Ny%dV1eK_=rcRkO&68s+ zA-P7f6wF~~_|=0BCzS@t`i}_<UP_=N;iVQ3vWO02yZ37O9geU7z>6M3$fq#J0t8Wk z^lX%>D_s(n>P46Fz)s!wRv2B##qH7X<|t=y)zm23V&Ox5kzLDjMD9x0kYVe`%whGd zXYW9D?HdoUNr1tF;N+{+2hmQiDZk=Jw0v?~?DORYV=^qx5%V?9i8UHhTEwW6|0Pbx z(k{WUNgpnu)*-+I@@MPmI|_-34rDKr^l(2|%v)VxLe1Boyh31y!Vf{fHzSGU(B5tk z^bJKQ$b?g#0-Yc<2Z<^*1>Ak(!P|nisoY8Ux{IJ{1rIBv2+c+D>`{|F2?r3i-g(uh z;<8Y3(*dEVI)hKa^v7TNp6+|V6Z73}u2<2w(j0l}y!)m7?5L8peb<@W-ovU<`QrRK zbkDwKh2ist>ik`e@=ky8#LXR4!6)tn@DWYQgvH#iV1><o;D(8MpJdyA6l=tnAm1WM zFl^ybAieux1gQw1adpXx=>Y4R;7Ly~1a4cvUekPt^KKWQ4DB=x8u4V;zI}=uquhQ7 zOZXbk9=AE4y9>r=AgpD8$85E~AlvVxg`?K@HKdnszgW%e;5xXNS8W^ai?G~F#;6ud zUwVvNKK+;qirqXkTCCEwXXrObDRqs20ex-oFG=P?8(YQ1#P^d08C_brG!OqoSz$7p z!nK~QH+IAiDYQ9pwYDK57zVR?3haR0Lnf&1(i+PBC<ttxMgnkf#Cjx+nmZQ;RSVir ze*6vmx4;f8f-rAkLiI<82`-{|wBj-kt);<d*$vMlP)XWGs*R>sCOj`BL7BPEaYDBe z9EcY6>cvBCo{icx9_xJF(y>CztKhStj3ImFo-4Qk_FfP*0fx)1<NKqVj5E_8RT#!f z_W`}SbB7Dml^VlG4LM1$dsyw~A94D`p;|QSUhY~hF4%48(!U+fZaNlV5Ru<NLibTy zs+M2~#vi$;2h7iFD?s{+!9^w%h>Xij;TR7_sC0$&#&1n3qeYCMee`H;e^*)=E|1%U z{JiZ_0|6A#Q3wYMzNpk6d*yi);3Y>)YL6MzJY*%#3J?&hPbeo`grKCVC-HnF9Jsi` zoxhZ8sqC{?;>5G&P%&z2V$6`yA@#ymHJ{TD8y|!6=L*yge$Aa&=jdiQb6;B$RXYox z97@PJ&t_mwiUz(C6k6=7C+pX3xIHJ|54fL8T)_w}D*aqcARgDdkB8XO&=x762oDa3 zb9;Y*Z9u$9g-SYY54j`zj$-LN-fXs-%qFo3u!MG4B4(GWy}rK8cl>T6j^ZzFz7dX) zW$jGcmwmr&_Euy!!GxnqNGuHFEy$f+saXfs`m3i4!)Ue~Vez*QHLBl9scs+jN}KOc z1WbHx1)eN6J{wcJnqsOqJ?vm8BZ&!GqMQ+|Kjc(nEOdI<LG_x>^g79@eCe$qzPnv} zpD?R>yE~;0(Go=&LrxraCbui5a$+8;n;-aZ6lZ1xTr@ia-jtod$?I`?0LJw!8|`Zj z-lxPBRIU*FW`sISX(x-zz&U;<n6Z-@NDnnRE!OBCwOHc*b+XlG#>xB)XYeghpA(uO z0`#u4PhNU-epSgY-K-)|<ZNu+r$`???{iupYEf}BDfL32B*K2m4Z{M%9=}uk;xCl6 z57246H5tRvZH+N<diE4|dZgmZ@!W?+-|{5Z+Mgw_r+Bb^`B7V5M%(0|d(~M>l6o%5 z3Ewah-B}pd{XX*o(wN2DtUt+CIKt2iOh=ahExR74#<3iWqS-1@4<_`vY@H&VMBMm} zGePvW=`~zA=5eSH=(bmufFSF(WGZ+>HuqWJ<O1P{ht-=wRhzziXEy=KQ)^Up3%v6C z4oSTavd$S}ze){$B#ep5E+5`)#3d|RJ{f`mhO33IHX>6WC!hM7F3LY-n|$6X)PZn& zFT!{#@Iii|Bh7VXz}Q7pMt#&8>4u$%VNZ48e6@yH_qo|2?lL=gwxJFri;e2b4niI= zjZjU{Jq$2sa5MKHz#0>~Yl;8CiWVk4Kx1#kTZP@qlG)w{IL>n;Cfk}pd&5+N7xU@n zX6+^aSzIqd1!W~0R^Z7}@vaMsOJ{DU6yJKMC|zJ<SRIWZfj2XvvP{_XiDtB#pZ^Z$ z@+#*uuC%^<FEW}NJo(5XvG};M_ufQr*`DP>6CiEoDl0$^P}ZYevQnDN#R(URbSc?6 z#DCNeW}scmguwLP%W@WjuwOT4{>(UCJ^}C?u9<Nm3T<7e3Jtup17uWp@bcy0(Wfxf zcX?rp)43#z!X7kRMxwqvX4jMF+W2!_=AS|LZmxKP20~5E3;o8~{Gop%Uik2{mJ(Go zar4AcGv&vnM?c(<ez5tNEb=Py*lv(*t_eSX_{i?<bo4v>r=97AmEflIiKO-8G*xuF zge#&RB~yMR32$;{W)HHD0Uy_nWP4U6BG_;QVmzZ{oCaUefqThVtm896k`W7mx33@l zF(z$B*=0$g!TO}(iN^{ZKx$i1hB4`Z0N_FaJy_rYrtGA-ZK$sVn~7)v)iQzb`V@w- zgUdN;@LW!!9t6$EMa3DU)i8V=96&yx@g-Nud<pwp_0W$8*sx`da7lN^rO18P_Q6XJ zBLWTxR)X=T{MyB_oOcLd9&?4{_KfOZ#dnW%a4@#Fm)z}Io-1CSCXO7}y3+4)cslW^ zKlq;?c$h9Bnxp><2JByhe<kQ^n{P`N_F<b+L0bVpsTacbg`9+E!4gH8oq<b6p|VWc z(Q#=Fu7LdzR@}%*aDC^q+2{&K^JS14BA7)-%>D=q3ILD7fs(J}t76(_=Ta{b7&q%t z28kXzgXnt(s4756Zom-0X?+i{7hR8d8?w_R1AhqSm27CdzUKCT%}iH|vWVUnpBA-8 z(tX+xc4wYbOpq=QaEQGgfk-qy6Chss-FRWE2(g}c+`+RsS|ZaliB(SW@PY^7Bz1R# z`Q!qJr~>%7>ETT?6>l)T-3*<FuDfOzUtaLu+sR_RP%wnl<_FS4WoMAF$zVVTEVad; zEQ^$Xbwc@XNb&0j+wrHb7k^w4tEK0hB8ikU5HmQdMgy$_mRh`x^e3enHZX2F4NM+p z3e&8$6S;xc4x@(^hc|PhrL39D0!7V25(`Xrm-`tO_zRv}se$%SF)qo;T$w7RrKQ$I zfjJ}-Yb+9jkl3VxsbIiNmTf#kR%j!i*1|>@mQNT4$)%|v#_g=nbC--Db^%#PFY~+U zrmd$yE(Eyrz?QyKAI`E>*&=zoL$c_Ib~>ogC@%Q*2)zCz%`sS|!p9aWp6qaB431vo zpsviLVr9{Mf!qsRr4R2FEPa&}7pQ5&*2$LG^wX6o=Y?*QI2jM3j=v|24xZptg7-<- zUk|piFTY`P%fP%-X;J4(Uk7?vC!<bs9YnksqU8Kt<8e1bGZfY(_RpJ)53xqookR`o z@_j)>s>-tsK!^?q@sl%s%~lv7Wq0Uad)*K(=s7rGxOHaIa8FF5KImBO5aK*Kj3@?c z;aKGLvfWCZHjL(Y5g%oJLti*Khu@0|w?sv6q3Y@A%+S3TNKLDnC-8~>1%$I{(Uk(H zg*uJFEzNyL&Y%77-Pxl4N<m9MK`cfb&lBm>$n8?NF~vJhQ2^RXQ<Jn%rNs?{4m@+@ zQB}1KqHVK9wZ*u^1Aj0G$Iq}YFv<nr7@LPd0{4B*dOumNv?g-v>CtpA@c!&JB*QQW zMovNCiFUD|K&Ls1tnVtVdfo}w5F>b)Bse+@b9pZA7JKqc9vIY;id?8IO;dlOie5t^ z+ZetHNFe+<I#Me!=9|&m_NI-~xtF2m_n$law<Y2Ck@Nce%gkADo-C+6nKo+JjM0+L z`vuB3*9v+uO7a;~IpWR8fV0bBOk3H&ds^*tn9-4n&qnkmA5cN;3~mg<X4~230b^rF zOXz?|A|2osu7;YM=83O`!d)wED;FwS0vbn~1ZmYMs7hIBtGHqn_^$hijK=ZAw^w&J zojXessY*C?j^Qil)pUUiZe6pUi>RDgDj9^iCuDGi*DrtS;R<rLL1C=*O{Vp?jHXpG z*u*=vu;gF8MUhPhPpjv^*RR+|YP&tRSPutbXYv()nMbu%!}{QR8F2rx7Fav%NtG$z z${dL$h>UC5TsOM)!_(FoWG_LkIf0hdUO|%$BbBDcD1E{D4zuszOqjEwHZsoOs!Gdg zL<r-ZM$FIFb2SX~vN@^?M282VcRWiM)~pW&V(B-V?pK^m9f^7uaUQ9u`LWuF)xGb7 zr1hQoYcmp<>ucvHGVNzfyY!Q6^cHF@&w12WA$ji-lV32tSL7oM|I_{{;f(qZ(WkR} z{fs0F+B7YoOVYh&Rl!~=c;gLF7Df8IjSRg-L=p>OiQ57r7Hrr(=!iPrZ@s#1kA7LW zEOH$oC~$HztnUb^CytIB)@tiyAzR4|XQ`ZIiuj+^tMJ6kwRIGw02Ry-zOJnit|er$ z6p{Gj<{;Hiq~+}U{9D6&ZVBR<WdzQ)An%GjC?Dc}MC00=p^?hC`>g|t(wuX=f!pzC zls_yT@r*@&*$i9U)6x*=C|DM!D%~g8&ay~Mk)?no*#$@}1nU6yJf)8q=pi!geuRM| zNEyw@f*>-{@EL5t5ey>fhcJfj$ABX_U~{v@=nZJaTH?dizIkiQfwu<4N4E__)Dfk| zwV-QVFY1fN!5d@h7v@j>x~B=sxWOUZuMXRlu5MJDM~5OO2Za3+jvT%=3_L8|FnY-b zxAMWphAYd&dYj4S%I_f^{Co9J??E;k0+Oz4YFfk^z!81$pxzdpS)6c<BxxSny{b~8 z+JQ7Y22TVYj?oWckx-HzfU7`}lVv4|wrE|HVY!4On4=>tc`P4b_7x{sw68hOuk=My zimMODoZ6vvYATkZ07q95CJ#A^L!Toxt>uCX)q`wA9uNcOwJ?91?X!QRNc`{oh)@+P zu+qsSw{{{;pP-zvv0o4`UOscBVUv8Oi{O~mgCt9wE**;5lt?6j(>6oM@wVQ;C!22c zwB%zAZy`M^j|IH|>kCG=)VGPB3c;(fV9M2otkT{hKcZ`|`IdsTL=Bh$UM*%IT1d#y zj@`<C`VODGdg_mXjgNXj2AENHP;@VvUxRL=qnml1rXL@Ab&4sz9JyHo_ViZ5yrN)R z1ht}T6-CT|-uAL2C0uC}s@313G_T?*#mXL(DYuzxQkJ&To<h06YC*>4<nkV{Dn!-` z3f%7}HaqfN{*&3e&|qo+Ws-Fj`6>V-*<$wt=P0uu^P(#_h~Rwdm5f$cp@4&>46MGF z_xzZCj(GKmVg?f#|8g?P{prDi+AE2}!(siCedy!2g^%KpGbHr6Uf<ta5y)R9hi{}? z=ven100HTAiq5v;t~j$y=fijAg>at;`w{oJKX~=V%C|$Fx0oo_qNLLk1ieszcL12! z3tapOvL8x{cvYnPf<x}TnVV9g*+B0Dvr_pEyMAmgKKZWW%$gYd!*6p+kZKYmBl9g| zzSf&E*;wZGD&WYNdG@Q&S>qSK{W&gH)2U+D_h9a|2|mKj%HG!KDSy5B(|*_H`4bu# zruwshn?~2-z+DEVI+Gfa=f>3*K*L(_ROK*g{K(Ge;EB|--qi}9Hi=mUY2K<{M-*5x zZK_r6^cDjk*MR5qQr!*7TsrV6c-Q?}FtxKm0bhQ}lrM-yaNLq$teHO_8ONE(-4@6b zbdx!!?N{)`G1Tp)t;9#RLeH<Ih<$)Gy<j35*802mfLBREeInBFXeHdGv)Sg$Nr?1E z;mhTURq%EpdmL(DZSUlZn`&Qu?_xZ1o-4_t6rL5>NZe6wr+`;kNF|vT*I%IAo%~NC zfDcaK%PYsTAF2`fWJ-bzB@}8(S^?Sws8PCt=MKE^29&T3-B7r)E4aC{`Gap5SQ&Fh zhhY1K+7It}#j+zg*ZF~91_QZ!B~vNxoy(mifv#7}OT&#~&k<heMuu=ho8UAcbQyP| z1N_)uH@ok1Q=G^ZBzZafF&1|G{O*TtIY?|z+>0nP#dOZ=7q8I0$I`SyBC4a0yv*D7 zkdQ-#roa1}_;~_vJF3RAAPY)!aSR^ZN>BQi-qEy%9T#5Kw=fmImvqB~tf9YIc{lHC zH2r{OUN~YeIUv=I7U+>zy4dtCW_}cL@NdzS<<kIXa8JzB!@|<uh0R~qAF_+kjbrEs z48&VO;Bv1*=NQ`JiPc^u?m;=~jNZP)nX`ZsC;HXLG8Xe*iW_cp^US4Bp*Q_St2d<2 zKNajtT@*R~N~mn~&2#OL4DTw|OfVRI0@TfU35U!f7x3ScrH~;&WUbM^dC@1r4}|qq zj@U@4+AT`*U)Egy>&b5sssL|ORsqsgdnl60K+4B~Ns1d5s_G)i;>mEZ+H4zw3*a); zS#?xMK=fEhi}y_I>1WHW6}mw{<oF0}?36w0IyL_h9QSm%97w?iqsn*&tU+K1=KN^c zy;?8TYA_~Q-H1mn{X`7vjPzjLMAlJ)+9LY)I6|nY78iIs<yItLAf}b4;pvUqCqQoz zW6}T|Bt5(h%XEN=Lulbc5j@s^3X6~gL1wKLARvAW$}6%rg+B!Vd%6%)BUJcRn<2Cj zm8F1o!EMb0sNs5{&^-Vk(1(&lCaukb_wuC-Qv|RAOeB*SI#7sDRuk?sEg(NO9Fhjk zvQ8k*J<l4#;ep4(R%iFDdA)GjN$a`@CGn<mfLn4p@NJ&&1;5d%PdEJH-Z-_WI9F3! zKD4;-?G7*2Jo8;0tI8KZ6YHtQW4P)Z04G!X*?3r^RH5UZR&J*NQ=8u}K(hBpBV6Eh z&cqfp-}sn>)Cc~JUBKBD{=QJ$hp~FZGhP8h42_Vhi-wh_02F69E<pp%q9H>}0V5pe zsvyYa)tq=`$<@$|x9l|;k8CE>SjT2tPyi3tj8=rK5HP@)4YaX;DIwZGS~y6gsGFz4 z2B{krBA0Kx3jJVpt*c;3hi~zIjaN%cL=O1l2<nn%jWPEmix=hd?)(bsIOOw3L2S9{ zPsT4%Cgl7dXOq(mu~C`ajQ4Nteq*$THMX}f)!CGbdODnnb$~uqzXp(yO!qs`_XD-B z@(c7>Zm`}!*1y^JBGxdKSVMz3Vzj&B5gnSFa^+AF?>Vv`0_f>NnL{j+2F)2DS`^`; z-As4xk!=+W7SVjAcW-Uyt$LjPLpYGf>SaGtH5oUdb(;xwKn*JYano+tN}&e9sIMl? zJr0h4e5^k|GFlOH$E+p<Foaf9wK?dd2+0G$Y3gZzJAS?vcj;!tOt6{cFU`Ff>r=aG z<9_+>s>~4>+t<GJqC_UdSMp)ye#}M$87MScxf7VzI(@1{WA1%K77gVez{)qBezIDZ zEyW~bf=Y2qzX(W2ZsZ?b;cYAQFMfg11&)pp>)7BWWRjws4Dbw1Szxnl#xO*v#7VK( z%1#Z&zFL~W0!#uKo5_<y+|Lx$hkz{P{bZluR?`#W9$I&}<!0P~!8Mg~5-<62*bP#D z@lqMeVJ4m>qUb+xEtLY73=ICsu5pHyPMvJ&c^X5k@Q|yXynNfyz{JaP_g!4m)5F7m z_ymd3j~9c@ns+-4*ssvTAha92t89)gE^uer_w6M8M^%Rw3igLmYgmt>_xL0X7o){w z4JE^aty{=Tv)QLvaSSLTvo~gO>CVwVDoN|;dV7NbJzxshTk<B8e6akC8gm#0$4`d! z%xAMU5y0I<&URPmAR+e;UbNL9i(mu+797r}!(-S(NY*W~A4^BW_4JEhKWuW?O_E_c zj)vcR3-?zLw63i_d*WTD>2YJ^zxUch%sMH#h>KVL`)tf<UD~p(`$XizhEHaHRzKyD z(of$R02<-?aj&g}2U5vc;Iktr?e~H6Jc%|B%s1(oEVG2f%f)*uVC?sU2qWSUnohR@ z#lqP@6;KY)?d`+{l~?8qp#&0$@zsOzjx4+<JlLVIKUPH>b0m*dsj-ly9BWHHxzQn) z)XYNX)8P^g_BPjLJavbmy($F)wk+=AZd^NE`yd?H-5n|)Vc}@31{d36>Z^KSpI<QB zj<Bl=5dJU4gr12kbBfRi(>U_z+->3lrr~FQ^qLB777-|6riTV{=KP+c%V<DK^NH%M z*O}ja!4+bz#<Uh81ZgxHpV^2GH{$erqso#`ivX7!6#&}&<%e)_0Gkc~zLR68cQE}T zI2zo5*C+za(?l$5Be>2W4huuc6FF7<9XWM%ONe3Za!4nf%xaseK7oWO8ucL#W+bO` zI4|}%rYMr)ALuNbxCBtgxv6sOh8wIX&Bnw+qd0r%Iq~qVn*K8W&q=a`Dd_Q8L)Kb= zA#3Fv9VMIp%zK(@bYu3OB&M{`)++q$?>T2j)cZ2So<Z%OzoTg{{K4(AQ<J3fV<I#? z6jNO6t+~$-S!!tweqW*($9YljrF32VA%xUiOO7Se6VI`l9i1;3a{Dl4eXR5YJ7Nnd zuh6ARaRdQ8O^3?&1lrsjEW#a*7uxtf@^ra<6d(IR!z<}tY2g@OcDxsM-~~sla@MH> zfcKuyXPJC|xpb9^8p%`(ru%pa19xeT<lqZIS;3nFO3zR^V>4df(VPeoyyo%4{V$+W z4ngVA%i%MCMJ{Io&q+qULHctav=rcM9lU+4eX4VMpg^Vp0OXHcA&5T1J@8coI)b>q zM&gP72AqK*A%$ArwNNQ2Q^}W%(rRAx@J?}-6!w0-gx?m5&<Z<~(=Rq#8=$dUqQgad z2rFb90Id^6x65aJzqal^6)iB@M%UZJWzVdSOWkSnqG(q$!i9;|W^~8lNC`|{t_EZL zOMIerR7*f&VDdv%#Q;W?f+RaZ=uP6{aoCcK6f6gx7wc1xVG68u_23IveVr>=k^pIF zxg+Vu!K>v#_Qp-2ULO+q)BZp>ODvRbe8!y^$3@0o`3FU*|B|-lul&3wU!Sf0e6q;d ztzULi2<1HZ!1Lth)mVf2xCqo@bXI!T1R&GxaVjx^eW<ILXG?E_j4iMddS2K6><ssa z1HG@z?rV)a75+I*@UBdDxn<Jq#luE=Sqox&w@1{_f{{NzK&om=sLPluWCK6o)^dtr zC&b9lgG*@axbZ>W?V2!uA0R;xXVR&AJkZko+1&;IjL+Z5mDEWQI@KVTNHbLXrr|<s zc-bm^HY>;96d@0f`IERgX=5FiyVTxqWw`PaLoCd*UgCRe5`l1h0X;XeRHfECcu8Bm zc1c(ifBlrlB9o=r3Aqur^JeOHn`C3z7hrvFlT~*URffHL5QZe-e~BgEUWQf5SO6<p zfIjnH87`<N_6^Bs)6nv3u3lz~D`H^Fb@8oe5o3TzDE037JnXr!{FtY=USB2$!^;_= zpLdA>wSDDMGtu{z`0GOV>juYE4Yz;q+MD{1-;D0({W9-`iyRi%`y8KaJ~nfwD@5=H z^>{sAhbHjlLdpcHG`6w46f-c1g0~V~JIq+f8?i}9>=4TWS7SKa{#FZl?}p}=Aj>R` zT2`+mhF(-{4Pep*Pb8c@!OVe@fc+WLSwIo1S<8P!GwF!g9KclTy&Wx7WSQPui)1@6 zdK`Mid&JDluZpl}buE)9E=9eBrAt}e^)U;b&dQFTh5EN40>-k}T12@9clY()Gzd4@ zjH%|O-(+35Jj&lyN!Q>uSO1|I@R9OgVstCH{nVfN!q31}XkNun<qjkdk|dM>MNw$I z5_sfox=kzuWy!?>+ha^k9u$4iMrg3_*?N0z06xp2ta*glV1!H@613}KYX>s-vy5hd zyzufO-Gy6`SA~HwY9;c5p30S1#@agtjr-6%@~q5q0L<2zO-Vtv9JQ-lQC9z`|NEK7 zC2n?L?*JD70ur(hRw0v^@POu$qmy}GUtGWSCT|QtXS&*Ng$*#vciqg|)v|@$N>^{E zt9w>GuruNO8^2_pj0y=e?FsCl>LB0rLQlyRS|*62lAu5p%VJ)DyLPHt3+XN)5TV71 zn9OTn0Zp+T!97_5B%`bqKvYHzz$pR-YOFShT%#~g1>LrY#U-I=DS5FE<ypN2`-!l9 zq%5~>9Qy{1J&?@#Nb9F{!*u(voODJOhTTUWalEU-36yCM<>mwcY=%aTUg62#K6zi0 zB`t_(BNL9Ziez~Du4J1B&S4rUm?Gz2E@VRf?Kf5*2*}PpWp9=IqsNHa1YWT=(w->- zCm6SD6!y>Np-svk%#ug1+U5qR?%Z(2nSBp6kxg>Uy`9pkUo($sw(bBwLZL-<&v&kb zRWEq=E-&Ku9CHRZrmQL~tp>Wd))$TE?0=-zJ;Lrzx8ifIzALbMG0|;MhHhdz7Rj{7 z9+Mz#A$HF?t`FZmCO=@9(v~ClFe&`OS)^;buM_f!{jIAK*KZ9t{M=PZGi-EoWNiaf z=-k7|Onwj6?&h%keW5~2@KL1zAf!=lD6^x;#AVIm?~yGl=gTCkYaSGKJWc=vx{F5J zrKjx$nTec0bS4PkMN{%vfy1>c_{xCt7qTLG?;Q@b4wEbpW&k^^ieHNy=}fQ-mq1#5 zb?3{7UY>8>6QW|~;&FhRV>_Q6l927DiM;Z2{1Rqh%KPkliGm-K7ul{B<Gmh7LqN|E z*W9t}zmvOKkfv*H>Nb-ochWTyRj3j??c6^Kt1*-lGOpy102;;!$oexSpr@TL3<DIv zGTC`5mszP|42Y)-PWdP&CNQB10CM(`heC%$vlgp6vqqpSi7cbMJxm@R8#CiLSFQ<F z|8W9GVPu1>Xp&v+n8>xY37rhPiuY$5{^X~QOlW62rW5m*h`F|Oc+A-S-7(yuU-!?E zTM4@PNgpppBp{+_-q~T@IYD`GD;$1z$@P>xRLu0bDU`#)m5j}Sb`2r@A|er%civU= z1aVUCK<{mQz7DcxkR+~;Q_$|U$(^;y>V-UUHDjf_9nRCLC$z$&ZId}--}(>$38>__ zu{0E^aOS&_)}83I)4kiZ^ik6)Uw|W%RpksD6mp_x8_j2%X7zNpT%kQL?&#Jp3srjO zJfg0H_OGQBcI1STph@XF3((IhJP+~0y!z$!#(aaL+s~$J)2(v>{}5a5j*?wNxcl;g z$>W979f^6`lBSha{w=-!{Mi{6opd_RrUjYx2L`0x>t(f(bB9`F+I#?@bzEMnkjjKI z5&vD2){J2bjG>sRNZr!OJ*{Jbb6Tvi`fNPM+`)a?gkzRi{?sJD!0U<|9d5{hQ|Fx< zdT01^?oy*ytc*|IJ*s|qF0Y&ij|dRu^p9*<-aQH0U;gOgiQ?A04SZZ}5M|JPR?!J9 z<cd^5>S%BnZM)h7{ErzS0}Y7cLQiz2^D+%QDdVVJnvQojAKa`T-p3wg(R~1t`@pjo zseW#_2A}r$F&2k;)fU(ru*auV%r5-}YkR)(egBPGE$6y7x6s*&K)Ubg3ESMQ7qXeN z{Hs~qH(58|L(gnBQ8+LXz;<N>Yl+Fy70>@(<PTlDWZ!4eo5a~?*f^qU*uaGE*}D3s z(T~MEJNDO+)loUNI?bX_WEpX$;dvpdoSAQo4@9&xz?@E<NT?}095;f-qyK4{H#EZ_ z8CMrmQR0D5;IO>6e;arHl*$P9^kh&aV>cJvlUt?73IL$<qtF|Iny9Sea4kwIa>Ti7 z^2j|sFXzh<P1z7_?tIaP5ylk3d}^crdSix+W0PpGWhUEgsC?C;pG2<f!1?JJoq|8M z*GO@pG>zBJ-VfbEkQg~3+v(3X#V5|FPM9q{+iz>Za0nUgU*ZG)9(Tf@s)A5d&R#mG ztf=c#Z~iPcXnbse{x*cw?Vh_8B7yh09gVBhz@S)=<=eIjQ#S0p$zc2an$SGDuNG7W z_N7)#b&mivKufA@CvY7ZVurjKQS%H{Zq((#B9#Xm2*{czUie1mHaC)ZIYt`n)!Be$ zdA}h^P9`#(eDMB<F#ksmr~t+6NR5b7Kyzz-b+zAJ{H4dv-~F&%l_9nk<DAZ)FHl`^ z2+oI!%YAd;2M<)v!(TDk?=6Y@>n}au5J{TU_0M?@SzQP)%b(Zc^ywg_s<Q5H?NPE) z01VD4^cS5$S4nPLL7qWTO<K%;y3ym7Otr~JtTD`CY;Da8Q`YTsN{0EwuG*@Lj}EEk z_msYg1)<~>wN(HxhfZUi3!ox_*XtJzew}=sio9qM*n&J8>l<h?o3lUt8Dp)QkJ7+@ zny38}Ra5O|yLj7CqHTh5T#^UOF)N%8a*hoe1^noeHneZCuHa0b9cF1K60mSG|GW>b z)<7io2+3uyxV|wb`po+*L-eyPT&0DUU;<NsgGr&&r>rw~hUiBX>iHr8=_m6O@nM*k zk-)t0J%)Qj_f+*qCl>dO8y#lWj3^GYD^`^SGUjwuHQQfF_G*2&(2O3Q?+@;VNAM7C z2|35Mi=&TUK48Uq?5VUO(e&8)pnZ;6e%?eBmvO18Hd-{<#n&UEA%Gzz`Rc%^)6p0# zcQyiwl5XkV5ww*F)63|`m;yV6A_MZ_HQ-~$a+=}mvbfBA-$z8o?!k}owK8so<pKO| zamtvlu?1pf{?f;U&$M5$hwnVFC35agpk(fS&iD8bJa+#e4eqdl2+&aW#2;$G=d<Lw z;$|Uiy%1C1m0IBAZAT4OvRow-)hO#98ep<De3Kli(g;Us9+UMUonb7TWmUy-KOf2s zu!AN(Nhm5cx4<lJWtzN|$|aAQ7h&e?1(cK5BCH`}2K%vWrl0|H^1aVdtl%D_j==3Q zt+BOUsopi#mZk7>)K+$r!4797G>qRZf9TT#YfZKn2z6n?sObfcYvP~Q0!maz(jx1c zgmpd~*S%Q9#ZICsW+?}Ha~#rgc5kVi`24Ppao5LifKNNL_mj>(hws^T-09mJoI3l@ z)WGh+f!+@%v!jvcBZ&X*@cF%?qVD_l!7z8mQ&_w#v4F5wYWX($NISt%>r@U|Kcy>P zOX|-#Fvua7StJ9>G~mL9nEOp`Jb7*AlW<99FpDp?-|Ed|>`k<v)KmBOY2R2Y1G0jo za}}vEcN6zqDN(-rE@mkE(tCIfZ-Y^?x4qGtPqH9>`w$}JUt45dAu4Ra<1w~rC+p$u zF;h2LJZ{jH@0ERNM|HlIh+MBVz#Y0SPZW46==L6;-(o-#@5k4ys3QN}GOeUbH>z<k zU@LZxc`Ws;VB6twD2k9*bVF6<%ScDn9bEi(*2{URLuN>%6+wC-1^y_263zBCfYPh3 zK!SvtBi`-OJLQgCx+s*~-ux{?N?CDNj_qttNIG2j==XofH1vULwd+gMrr$&CUv`Hj zwPA{;YgzTAo1fTUwwfrlmE5Nj&1-)~?bz#{C-ZOgeZ<*`*tET6F-Hfx9ai9Zn7O<Z zJVyd&l*J4cWRMegc&XXdZGvhxie+VUKV;q1vNQxP%k>N;IA<lS9@?%udaCC&vHH2i zzb0$LD5oJ9b|I}SQ0R)<w65x(ekY0ZMX7u0y{~UlSWI~IJe)b3CCqHw2ZP{Xq&U2N z4q9A|iog<#^2F7xT)X4m+%Hht#lp0>ogOO1d*(<Wyq*pQYhYjXWRFSp2VM=oZIaEM zqI%*?Z`V{I0e(p)_%CxPSG3<6_~=$+Y&c5Q4*}CGPs4_XWeh<+6UiSKM2dhG;E&IH z$11UaZ?A#j;GmRY<WzSiR}jFFKq*MuV3>q<P)7#Y0s%~$#)EetIH%PbE7TVY_*m4U z7ds0i5MazPLsF~}B)tL@+d+i~ItkF<i^aQFn=Nd=8bpPt19sy1&rzjOlp0jjkqXOF zwZY)WsqIwcg);<)*C~Gq(O`Ys=U3TSpCjXo=^MDpn5Efv-J>OHyNZJyjWo7O4whlF zx?eUttQ>(DL<uF~u;vQXyVu^06F|JT1nmUzB&eJYB;+d6@x+q~>P1*bnLNC&1BH$= znf1@aZ|<g;0c(;0s7wPXAPK)YBOu85>dBJ+X6}VhNS}w$(%+xtf?86ggRX&)HW`X9 z8Q~S-X&NCx$;1$XvKk@?Ncjgc6SM<i9cGbnCvo8~;=A#kdk!IU*l60L`Y9FQ@mqnt zl-mJcN0r7cpaq6MRj0W1Z12uD8Q^wHZk?0DC*%a}%ihMqV;}R(u_^|TG1s(T>s8#^ zWC7+J6X;}dYhbKS6qU4>MOQsJn8S@lnRehP_V`d5g$-`VdY^Ho)%&CcNKMGm&ED5b z?~M-0<{(QgWB_$^CRY@gPZ&pQ?#z||W^#c0u2Kp+k|K_)fB;HN?ifmXnhWk1*US^+ zco?0choju{7O2>LjS<m6_~MY#6v<Z&D5VO#xY!<>G+Z68#%3g-B&)_+!QoJG<|kXh zTD{x6KM(bnK6(|J^lXLFkLQ}1lpZNL-l;(;TCGvaD5fkGj>$$$Nu4|SIQJm`ZnG~) zvn|e;XlZVh^L~Ke?$i1(5cVpce)*=Fcf}RtPpvqdGqwQCM&dt=BRxH)7IMd2tO-<g zwa)nK(wW*))Wtj5^i~&@3Nt{QQ^4ior*A&(LShp?x&BtGxE}`mIYaLt=ON_UkR<{f z!YPbu)4==tvF-73UC*4=6S@xjxTpN9oYPHrd>V7U&26`wrPkA2aCGR=MY;pqb4sJZ zW_xaY?8$ZWmPTjws@Ei>Y{knojfOqHr-l|fTRl)kXAKW2N9ewo>Dt%$VJD+gI~G+N zqlTwSvm_okBxT8ny;6F{+qeI{JXK1tGH-5G$z{&~b?_Plr#cAx`U@$##pe&beTc%> zD^xsRt9k_4CTVHZD`$1FIZpI`3@>1e6?|2WGl~FO!xYtHyX9e}e3IhtS%*ln`15R{ zT93x*<Crp`Xajrf7+01W-Noe`TS~WtK6gm(GJbnb5P0$;bdxG}uX2SSJ-d?aVsq_m z*VMsqV+dEL5XxM`Hy%^^>3&FTvDIW4BwTY5rln_#4ZQSZ;6iXzy9%yGdN|6JM8S5P z<Q`nW?O0nNR5vaNRTII(d0cDcQv~#)5MCbV3R7PxJ=%iAyL3p=G%7*SP!E?gKIk1M zlTL>u99u9Cm-j8rb28~SZOa=yE!JUWHoZpNE&sX|p)O<vcTlr`R9^QT#@z1~CAMAB zT|B~mN2NHo+kCEn)le06kDGu!0^-#ro;4J#DG-T&^W<C#!xYvtsS+u$-h)7b6X2`k zFP%w!3gDX9TUbJE!+vGXy^0dz2Q;$YK1?l?#>OQP+(C@W)o;?uq%sFR$`DGY#X^KF zw)3nc`CG}hc&I@tq~DWnQAh%)oVOJ#8<fzkx23|FOZB_U_P?7~H?xm}f-HJAIs1KE zXj6>)<&K3+wFyI?p+tfYlq9E55T84Z0d$<7>0cZdHjW#Ry}Oo8z4MdHozuZPo#9)) zFz$qTB@#aR%JKat#MonBRrZ{d(^{&SE}2?aT_vngQ{c=W?&0-d;`Ry^mS_1F!az&v zE;*Z_0Y^s>q#dA1b<79L?-W4gnH;FpT3~A0!)v)Wcf8OBS0v~ggdhD+mwx>i$%~_D zU4;QkJ2>cHlGDxhhJzX!<m@n_fLI?JHppqQlT{Ko|H~e_Z-FQspbX|l|Isr2)@j?` z8Yknd>u4;|0e-Q-5{Gz7V~fdR^}25^yJ*WDtx0TIf-tW9=T2*~**W32_&x|r6^1-U z?8{!F-xk$5^lx6-ti+T`sLx8GdI9(*h?ZPc-W-mM8L!k4b113d#CRR(Wn1j9n46`o zkh}K)HUQy*11;W@DKJNAq)F%1OfY06-Vn@hP!qwO`VS}^;)rpd@slQ<iw${NPgS4S zJ;~$^Pg|XK^9=KIKHm0Icwgh9yw>mRJ$YD<GkEt5{oyNPQ-SZgmQr_&^@OA00#D9= zYreqpQ=zJTEdBgF@}{)o@F^Qge?J)}x&<Y57}*N~otc3sL*mOO(^8464`A1X$+yG^ z5TJ7gIOU7$`JCzfjKZ$4{g-%9f5T$PSx>{xVd$-zQLvNe;BJvnBMrb1<*GyJnJQve zT-oz>ZcQAJ{CwG|s|M5;#J0U1Rg^s=gNf51NRAB^*K>Xh{uz`6z7~BA&hmekBIa>d zWB5=VmM{;=T9WAh;LDQLX(jENRf*rB>|zwR%h226#CFS<WLenV0-Ili^dZbSdkvk3 zogu<%j>z-ZnB(m9w9;U*vyeAaz^j}&rI;WMc+|#%TUpcA8@ZN)*O&?qsvn>rN!)9x zrN=%sKdlm9pc-X`i&WD6+Zh9@ZcZ=v)M}<mJsed$!~tW=Js+|@Z8-Pz#Gfj>k#`sA zXs%|M{{b@~^I3Pt2)lZ4g{=Q-qt5);_rfo>`%7>__=dY*U~83_p&~yh^V-Rr5RQor zkzcReXIBG;WB(&4O_>0Ca=M=Ou&GbZM{dpeK~Pn19c2u1cg=RFC@$FG^U6&F(u+ZP zq^zp!ZO)-1!dRaFF~Wi0oHA?&r)^tt0K<~W_Q7|Vrj8nzn_e`ab$-UKhaM#u#yD5q zc&T`(^`iU?m}Q!?jxOuILGW}t%v^YrrW>1Buv+=M)|2w3XaCaYzOOXLx~+m(vv*%U zVsBafR=ztfG5t)!<N3#ZpHVO6k%|D(@sp~U3VHC&;6BQd#JhTlVCF0690#@otgBM$ zQD8#n=T_g(#b4t%HI`{*&OK0tg=*w1eUtlqduR9dB*^p|YV=pGpyL$wuZBNWbbsNX zFf*_4fT1c_!ahx=KKPa>I0?%#rVbEESq3s$hHWR$m=2zS&;G1^?Q~JOXHB~9hSSe` z$}SQz-xHjgmWp4ivU%UmCLE(~_qRLclnPU2D1g~M3QaC2;Ql#CFP;fmj+;XZ0G&K` z{yFc`M*yXfso7HVZtr}N8`I*Cz2IjgOaUk+!yZC<FJ?ZZwbSw~%CsW5=+JBdv*F9C zj3rHXFC7};Pnj%zAjR+L`Y?T?UF0hS@1M;c`Z)CT(=bbx`d`&)LYz2DHp@tdy%iE7 z)$>xS>Flq2dmA6sPRzY<c%)3znRT*oGQoR3m|t}Mh@}oK45(5SXT%y8@F&BOKmg=Q zpa+fuE3aYW1%Ur4Iu}Q#{{N4k%{IHZ9CN><onh|G{Svj!+?7knEsZ3%gphRG&5Wdx zB2;rtLP$b=`Y@7&4=U-VkxII$B*{0w{r-k?&ij4dulMu$c<f2{merke6=(phS_=+L zDJ=^6j?0LlETSP0{auIta+*F(xfKG^bv<cu<L;jxs#ECj{OOH-pz8iR1An+Xj6!JS z(dwopVc-Xp{<@gX2nxnTT@^m;grcrw<=X95wDjOu12h{MDfR_T7n2$_-t2MeUhC&i ztVu()_BvjYnMvKOZJL*6HrI|u7xh6j6D@cZ*CF!3rpD8bG`b2I<+OwAgmN{?@Fte4 zNR-^@6sAr&lEMS1)u(I+$`UVz-3}BYBDpRr$QIXm`bZ?rgkS_$rH=%pQt8Fpxg1@Q zUx8@Sm0dPMl!3UWYr=!pm(6H&?;c&Rtld9Z!<o$7tYs0o)yEw4b!~{X96YD8B2$wx zt4iW0p<FNBa}U5zzxqrIx3AlusWavI!nF&#;WzIeuB-HHy2^bX>ZNes(y_)ciURm- zPx`4yp&qcjeHfyLhl#_r0nAHIMCbi2>l}yip)Lvnae(Nxo&(Yg^KDp)f}u}GDxC^h zu787RKD?-a2wKX%ue<3)t$vjlwh`Tj#;w_>9p=}et1wlVR$FAgB6=XGpV33uX1JId z(Ci2U=79*yo>0Gh0}mO!J3mYPzj)ks9hNv;$p+JGo4UWB_k>4`21X)M2fc1Uemd4K zQ$@b5GEdw?RJ<aP^sESmEsLnv7feB9q<PcIRNkM?d0(Xu9DDCP6jA$0Ej$0=88ikX zU>Y7DK*pCGg9AjUSVhZ?_VWFPs~gfw*Yyp|fNotcYa}u#d$8tL;JN6QA{z4)(m0vw zU~`r5H*uxXe<^*Z6~)D90B+5Y{>EJJ?TPi64^n-uoOG9~GDnIyj-_=qkZWiERgl{V z-G1$5Tu;*IhX%JZc-Phoqja@W_W{^ulDMTPnihh?({~trk)@4L!ivM*Zvtt6ZdUAv z!nkNs<9iw#0mk5p-ad32-Oqo#zo;|*gynuWIT?WNu^$v|v=QksG!nnhLbsynlmCIT z`QKtNWd}ljQ|>Yq!F3FIAik`Af^M}gGHx9)NavW#a8`3(^B0x9nl9&|kp9((EBHb$ zA1NS$RfFh%u*Bae$bNE1#r?dj^qu+yZO>;P5IMn_Wr9dL#sdY|qr5_>jPqzZckV2_ zS6>c1BWrB9ec;@A?Vhs!^J6Lp+V*!OC;@@Sw1#+9hVhB#Gv4T+O5*Ox&t5uCa04Ha zE)%}F*_Y;X@%!(qzI?cERuV0xUOw;X&hpRyu-{!Of#_(L6}=!knSL_bC80644ygNQ zHa5?)$*+3hh>!f9?Fjb8UEYY`!7;?eG9%Wp1JlF-5~x4al5q5KRMVjFO;p(RP~DbG zAKon{&_L=)uzraf_#Os~iKY+d@2~B`HR;iB(CE!JSI23Hn`z0)9XgXnyvfMqqxJ_L z@UHbc2XD}vM0#Ww^#b<eu&4C0+6o2<ICh{m=?Ul3=Zm$?ckycUCUpyff>QgrZhxci z3kUpHKKo}bK2MWaM_nunFt-%GXvDslP5$ILH1R|{ml9mR7NK`kkQBatSvtzhV`PR- zyP|VZxNzxwNqI6&tydpTX}^mIFLR-(&BMAM&T->u9h9wuW&n6$e*BAjglngn>Ct5~ z+K6F`hbf>XrRgU!aH4&mQ+V?8Lxm6G4QkOHH1ZjubAzw5FCzZEE3)%p8y(~HX2<n4 zR$R)NO(e-H8=6Q8Z7Nu`S=}<*sgHjmx#9<jTHUks$L5q*2XC}By05>UU(+|;jfkZV zYzz-yqVGWL(t3~&ae>pxXu<Qj7(6f(c>42@v*3y+wKqKd!|jH;8*nB{pMDhoZ0L9j zUxrBMlk0Qno0jzn|MLphlF~coIb~%2#KJr_S>_FoE_di$Rk9|HyW1<P!8$~WkmT|* z4ElX@_O^3s(wFAitfJAEue?98<vw{T+ev?qOTF0*-8^nl7|B-Kzc1z$zE7=?;Mw<L zy{ZVJzl)?lWFxe$@U?uo4HK>(XxxXRO_QsfE$jUlHA=z0YT609%Z`Dg^^!Ul8em+4 zua)fO>s1<+6kA+)N}!Vp*y;mpy^y!3vn{<Os-kM|<>QDWIYA1iqjJp_t#zMlNcNuG zzw`KT>?Mb9t0csMsdpzoobzz!uK)9dj*zlwxJajRLVjyLPJiV-BoZsBSV#eeh+GSt zzS`61e*T;2FwY0i<zG<fatPME9@l0MqC8fcw$um?m;iJ_SC$nmy|-{Xb6cU+ccBVx zzHMyclzTdvmNg~OwS>;-m&{wyUs7S0+Whv=w|O_Gr_!FJiR^7#zFU}Araujm)u?KN zX16YztAwyJ9@+GX>;~8w4Km*-datvsX^h4Ccb2Z7(mdvKt&+SZ3KlO4CvLKQs-9V= zE-cfh5Bh3u?l)!cJrLrjTIff0ZSUyShzPqLuLT&`Fw(v}H1fO-@7-wrCJO{+e2Bgo zd;`5%#~1OkZVsSa&G@OMGjN^6&4=~U3-xsM5mHgLQOWZT!|@S&xCtJr=4E|4fwT)~ zrOXFQk$ZOUc^VgYIM!UQ^SNA$d#id)J=})EF=tqB$uK(F;QnXgb&Oq-XU9Do+X<!~ z=iViMMn(|h(5LNtHqmvTd-^@2&tnshA_O9voocxDJFLxJFkspUGR4sZtaqq-MHy6s zf_jS7M_oN`X7&KWuJH7QFxsb(tA^F?9=F^>4okidbu!Lo4|iXeO+be`R!4FSVQXk{ zh8llS_l6!lsyh21efyo5vJZv#^4+Or2We;%2O;Yr*l%vY*)R!TOqywTEV7<#c%+z- z*|3^BSs)+3vnx8a{i#GN|M&8K#ML*)vuLdie+i7to%hrQeeO-G59gjo`p}6}8mIMJ zPhZ<fbOaD4zs^rh9lGHjitC1Fv(VQwYL5&YuAx6IU>lWDCB8a(l4*zMi;oM6Hx=A} zF9}k?D8I_~kf<|{gg#|DTyunl4Ir|Uk#f6#uH4&}X@~Xjwq;%BDs9-s?pfKBS`&<P z{q1DV4qPqd=kYcifS1JqO{1Gac$?DQv<t|PVUHn+-qAofbtsT=?90K2Nd=`5v}1?r zTy9Oa<`l=Q)$1V8>1*zvWDEXlaTng4Y`36i9KOY)Z`2%-C3m}#_;5lkyITFM%#WSt zwtP*wb9f!@@vPnb`nAvM*xTe)wxx%Zt^MMOYX&#oDF2vFtLVS{``&NKhPO7;+z@lS z^I!jPgAPa7**|w0-CqVgcX~XKBPenDCr^K^S~I?7^7bkB44Q`{?6b~TI}Xux{vin+ zP9GcnQ1&4#;B^;&%SpueZYx^Xr161USN9-x72bA7@6=loX(z#((=E^G2d9AdoA)27 zHITkb8VLC?Hpih`ft=pV{!$+)OBs&)_?;VezV44Tt*bXHU2BL4+Tzi>Q^U>V;?dY$ z$V=;AxCWO8uGs}It^9}sdTv?%&&?5ujvA}-<$f7Fy0Im#1=u3|=hy(2LjN}xk80PM z75tC77!o<7l(}O-R@aHn06kW>RxGv@8Na_OAN1A#4%Oxy`GAxrnpX0)=*_#q1ILbS zI>I(s{^_~k_!L?BXKmBpj86O|di&vii%&2IV4yV$K&v2_BMe#&P8}YyvQ*{52P%U) z;@W0u`-Ux(N6P%vEO^ADm_ub2Pw%sDB^!3s6$=g7wZJ$R^P{Mb4uGb*flI!Z*~b8J z-yvzrCiXV*9ZyM4RAeR73>MJFF@1U-`0u?%WR#2iCM7en-`jWY5K2Y&C1r|$1xx|% zMVL5|3L)~8JSSTd1{+ZC)tWfg2SgW<8=7yq2n<l`UoxV_QF?#}wpZA~#3L6JnL93G z^YQz}NiLy?{d%NnJf$U~C+;JB{9$Kb<n8UYN-H0CStX4Gz*gT*5G-S~cAw;~9wXj6 zrS^#E+okY_Rz!d$?eZuH`O58KtNUOSSKI?FDl{KUa07i_>Y6rT^pySoouOegkSWp@ zK*$grprW&-8f~!U301vH&l}NfCc(h`oRe5+0*oh^LoG_r0T;FpKr!q2)HrLbeT>|2 z{a;|n2r}*fO&a^K#tUTL-&J(cJ#<2W#e+f%9Tjf^=c_YdKZ~&5;r0XJ^(e`!S@=^W z`-9%om}{nXIoaLYopP8TH<HVC-SwxRJBWfa9oXmJv_cE>B|97!liSA#pO#F}cLvsU zhdN!_r(MgwV;z0<&MSqD5{&l+JW%A#oRVk$Uhr<vcS$CCovA^map3IaBu*d_=E0$| zdjKKM)D{6?IRss{Q29sWY)u<JTi6`*nsrv#r%hgH=I!u_GY8g;8uGX;MngFEAi<@o zPetTXcUkSbh5n$n1nfbfT<ySnIsZv|z$PNa9XUQnItXsC)_vzq6koJ=zUa}7yHy;B z|4^D-Ysk^sTbTHRz-5`njlEx}G;4Fl%o*Iyxs5wR_=?7&{OO9OLn=pMaXAEc*2TcP zY+~rp*7dCK8+k&C(s%i*H1uMBAsg&iF-(A=b)K6wWd%VkE6*Pqvs0R{5xTKG0wD&Q z;N7r?<=WcZfMK5!Dptm3^E8rsjiE5b{3k|1Fn*`-ij0PjoW0HHLXo>R=TnheBW$3^ zKR7tx!GE@)#n$ZV^k1)Xf)&;4e=OB~wtc-7uEt~t^H7ROh29<xrxc5=9C?*jTcUHk z%+b)(-WOwjf&(u`h0B51XM|!H`9f8u>sh6{C7SJDx3ZTLJz_cbPo%ES9X4r_MPLG2 z-&>rJdybW!KoKzVXX;ypb+VQ$E?ZpOLy#(ruwP{l`7UrfiVrM=vZqN4hC8d^;?rFR zpKr7YsVP00mI8Z}-gJu0NJzBeR|TzEM}?~%9}2zl!j)WNu7LMPNqhDf@&D~zHh&Ae z*SxyKDW96Je{4aIBExpmoeuYWtX(3Eet1;MxDV2U$WVLDMOw;zs3a&q;G~s@4glVv z%lt?9`{Olj)kR<*!6bO)Rs2A4j4VC=Be)n3{RG5SY@Y^NH+EtTEiyO>cq<`2Jdo%) zR>u;>d`XJ3j;Ha~LO)Wfy|6%9r(oNXIq1E<`<BdiHUCeL^5s@~EIijt-)71BW4R~7 zI~F`LYHVtH<mFwU_W{`k0rjuuSl3(R9YAxpla?!~l*9N_-Ag&wbUj_t`Zg?{H6eC% zevG2gsn}Pr7AxfMsycu`A6(GgiM$Z*!f$sM0b;knj?En*H;ovh1QRj~0KgO=ZoNNx z+#Z1Ai(ztIZSk0Ik<E?+f@?z_&|x3`kLscOyiXo^&+(Bo4HpkKr5ax&zNhVEaoL+3 z&pM+kTf&I0v(%`yK}1!`b}MzW7udWzEQ}?eRS>%_Qhxy;tZR!Z$C?9(&By8nzH<W# z&dr}~b5JtVw48YUD%p8y*ke}3a^y_yf9}8LFH^q*+wBGz=u=t!r<YWlauB10U9;7y zn(WbZ+n9>^2t8X+7{m_jt;7^P#Fn`U+WJyy!$w2+WIT$!QJW8Wc@A%CMKVdECPM%1 zGsoA}^D3>QHDkd63zhB*+^v>Spb<YB*4w~;{;(eB>3LU%J@I0RR4?OSXz;HB&XrrE zD&@~h+rgjQS6h;U<LtW>5b|6t_WYLh#!9M8hKp9upugijwC{he;PyCC#O8Q)0G~R* zHBmIcb#pdj@zRJ<svJ51)K;{tVSC&pJhRdSxPoBdC9o@aci&Sqo|xmoI5$VRPMzjM z=_=f&XX|Ei;%R}N^(p9Dnz7G(V@c19GH_3-m$2-4i>>9!ENqa`H|fLl+s0c1%*mdl z>K8d3q-s=N6Vh12L3V}5DSoJCal%3-K7H?o{A1>zd4PI<f&H6~JO|VCu%St|$H>i= zO?l+Ik2MQV%K?LgAz7=maP4+!8^mwDc-kBFDEKcDec()L(KSJpimrTyKwSm^Z^fw~ z&V-ooISYJe-K0`zPS5<Y44!2h_DMU{whsohj&idAgsz$bb|^uhIc`^o?K`N_{LuD8 zU(o*4kJrD+SO&s05qSU*5Hlvt^w*Lq%0~bOc*k-SN&Nu^3N_ZkF+*e2&UR>}<sRDm z>_nd}M1&4lA!u?GkD6L(2Sb<huo(54%&3}2J6)1K>7VT_CyZx3I1)0~)-jY=+H+2q zTE0F%;Bi5p-(U%#A&<Y9x(kSnDAw+uYP-po6QHoxFIpJ(>reMmU0>g%Qbon^?|5A) zL=m&%b(6gPz2BQQLRc^@KhPE~t~{cx0IWp_wmr3jJXaqcj|vhP^*$m*U)ulIPa_aW z|CoI86hgm@h4L?$!^>vQ>o`OC@u~x&n#@nU1NJd8X=!^j*3s@;8nwbU<}~j}G>{5x zftqm)(S28*mxJ!7Cp%1XP9~fg+wX`F)YU#CSMB0eZCV`Yae|(#G}HJOigXgfp;xg) zYML!l;Zy3>-SzteUk1NgRA>%Osxt!Sj&qJk0TrfkUDWTg%;Qpw5XE+l%5fObNxbwr z{7}s$&sxE@7f-*bx4qlw7!!BK+e!=AK0dle3K);1z49f5rr}K=;u#m$9*=fA%sXNX zI9lO*kqSJ|;HN+E-fw)KQ0lN}TbAud^IZDfq7pM?fSHqYCykENrp2>7`;m_-ofGpn zUbtWfV|BX@zj^O2GjU+zwFyMciq%#`Fs&j||0SpThxq|_K_)PZq+Y*xV>0VhP9H$< zg-=Oe^yy8k<e9z0{fMlEdI(`6rcA)wAIrH=dEPeO;yUp(fBkA1nuvFU6i0*_*i(<n zb*;0EEn=uDi>}p{hPJWhI$1KL?CbB*qN)5Sje;ufT#Vzf&pO%TlG=GRBksN0+;0_P zeS;j32?M$|eBKv)vZ2%$1iO@K<wJ3Er4cUcXttDk^*V~W41Ch5eegfAxlR|~T!z>@ zI7nC<`MYFJH)3o6y};t|p%c|&A_IUCq-Nk70Am)-HXC@?bmtT_?gtTDzu;*n=Nq@J z8^n%%-4`fY1_)NcR0SnS$+89^ecv;4|L$~mwo!bHcB9RL-V*@8?(wrt9`hEMcCHQl zVz#INRoZD$1P@~!Ew{m}qE(gp-^pxF%=k)-Q6{7RS%Oh@(tSd@*Og-r2!5>u1HG;9 z`pdffCfoJ8WoQP=y(hN<<%<-<GNTZs`TtobL+x|lI&yEXwh;dA0C$Q>a)hlaXIxHf zxT-EBg-l&rLbJbPqrn4!wyZw{P7nyKKU8RP8WV)YeEIT)VRUsbR`f=Oh^NZ|g;6+5 zRx7O^p<|*{kqRZ{`bW+w#pj<7D{7Cqb{`E_afu!Xe*f!k6uu0mLBBd3@?jw$5h^Qu zdQ4#l`x{z$?rfHcUAkFDh|I@e3n-*jNf92Ij?=)=G)^{XY-ye38R#q<68|vezX06> z3gus}XyKw|=Kh<*(l%j;7$TRjQvFq2G&?y5#Esc>VPQNys4I4M&O07Wb46SJKof)K z?n^@aM>MMC%7*2jc0&G@-esNRTMIvVeO*>!$>vw#L;h2wra?-H&S4uY-R-8;e$DTa zlD++mNc)-xhN9$CKwwH&Eu)x_)vh1!qkp*lX~A{p%+D(fe@xx=c55HyvliIU8iHkk zdQh~HUcqxEwuUj%SdlF-!ULVA#GeGY1p=hi2E81{1>fsw^)|*5X~mNLe3XFqgJ!M~ zcyED@zUVPDFwh74-cFF@_9?Xll^xn|apdCwnxq?AEdJK=kTCVRc_tQ8xj{}Flv9OU zLZkbz)i`HAOSdRo7EDR0!IS>xQJCE0MqO*q`o})oy_fEJM|@w2P06rNP-Dz$7Q(<D zs=5~+9r}T|)%}Cp{T*mH+L^pLGX%%1j`m&|>Sn>Ij_uIH!vB0@{rzIMxlmeuQc zBJpD{$RnU-`W{Z7fmXbot`ScNdoeFZP4y4};ftAu=(ME}UQ2>&128R$R<NgpR<{jj z2GMj8Seo_)w<M+L+j2^>7KIQ>>dZT)zp}_eaj#|D1VJ076cB~?g0ZwP^i2(<_Es-6 z%~}%|5;mc{E1g42(v1_S@%n0nRV14$sxJGZ4d$W<^+Z3M!O`!eV?Rjb!RjOfwMZ7` zwvGketu%11G_nP%wYF?fd=WS|p+?+~bvfB^3L3P6<g6hQVh%V6EuAr0Q}`waAjbPP ze~F6v(zp3<6iSZi`&55+PGp`4Xd^cs6YdOQx+Jmmw=hkjk$vG+fJ@-d!DVT&=&E6( z@1a{#wi;F8;oe{f^cKu#5q%(&Plm3_uDj=S0*hCaMD1pYzbt7%eNs>fON+!(u8&gV zn)p(3-<SLPw(r%+|4(v9S(0B8LoHBKtyWEf(5J1OKjBHwT|=!z8WkB3@#e`6J+NB& z2s{c4h}WuzUJl`3)$Yq~@^n#){;NwT!#W6mQ>32Dz~v+sOV(D_TWxruv<xGJ_+RDH zCtr*xz8#}|TN%g~e`5@ganb);x5$3Vy@aJPCJt&!CH0bu2`dScCIOD--_@dFvYpUY zuu<_+pk7mqbz<XQ=Z*7F+TLH;F1l$4ZT2Xs+kcc`RWzfmp0)O=(`Z3eFilB(JpJ=v z+>}nNt$Pr=BX*~%16S>6CX~)HJY%K&2)_5Cm8sW3$jn+t*hy%i$j=DR^c28l=d}9H zCaTiHpBR}gW^Tg~;RG=Z3t;}vZW_;sdO5pUX#hr`BxB~}w=<g5;LVe*uNbvGa+VUV zAECXJ0O!8cV5cgw;^mv9OegS0QOYDpnLe9l2OSC>BRB=wjJmkG?CPY!Njq=;vLCiD zhiL@#k#b=g^(=6PfZ>V}k_vgg5J~IBObX@ZnTkSI=JrmVlIspxPimQEAyGxHnzXe5 zw(`~uH^}FZ!}ZqEg3QBsB1?s6ysc1xUzH#?<k7@H?Z7jCOHYglf&dEj!rN~z@uNfa zvaa*-j>04y9IizH#>AV~uOHvg0e+6!{53my4vD$Dq9Xz}Nn)^?vZSUPkfn=aLzFyx z(aLB#dYctwzw6_Uvw??N+SA8${hkoKRt_HkL3Wi|Z!e-iESnahp8c6fpvv`#Q66Gh zuunayH01P|!wz(Q5N3zZVU9^dT7DH_2URts?^&{OwOU=CCOluKn}9dy`s)cTqU!FH z_}{mHwth8vO41qYI3+W8e5o3hKtL@-FJakIGi8L%s{m?t^UJ<NC+?{%Bvp_$#Nv^M z$+B=tzXy5*B~aw_Ai4y4fkau_PB1h;wi-{UQX@ao2#)o1{PD<EHSpn(b>7Z)zZ-$a zZ96GlztGWY=~dc=vzQU49D|iv6_vq1w>?fZGXo|+17Mj1Fz%^(+Sl`nI;H;DXC<vr zWt8#_?nhEL)aoZ9x@zPYde!~7ynfYd8||`LihHNMbYthG^5HPm>Yz(GP8CRuK!~2X zFFl=Z7RWx<`2i?a-*Mue`a*&4NA-)MT*7>jbGLr;%$3WJ<{A}=6wzryOH(hlJlSlL zxNS+TK{9aVcv>Fbd9KMhFlDb^{=4MaVu!pvahxj-&toLOf8nfr!Uhv-K-Da%@&!p- z)?(BX>{Qp7=#*YeEG*MIG4>HL%gP=~82WAWXO|UCI&xNr+4E<*uAxS4y(BE&@DL<O zB;q<70I~G>2jzzc2`c_jqu6NZ(YG(<guiAc!@uQ!OSY0L*L+0Us%}~x!((JZlS;IN zT~jfgvi)^C6ur-7xGSvOOD?(AAE_d*ZE1Qw{(5^6WTIz9XQ{6Ul_^o4_&X^EGMu2A zdSZCHT~}6o!`YktXOF@(XPAfx7RfzIBh9+AZ}0iGK9zS2WVu)+@&%N<rXO^+^t3>9 z^hmu~zDgVnXgV0;KN-1Wv`zDEbfT#ASl-SHK2R|of^QgDJT8RbtSuKY<qgU`ii#;G zW1%_yuMq=DkAHj}a)2aENwTig@(n_dm)78)*UME}L@}_82L>t$G@u1WX}LF5al_m6 zQCh(!5J3Ijqq)3|_*fvzPCaFy>99mIh46GQ1?xw6r%@~Qqa?NJL+WsmXHd<SJf7{5 z7}HABQJBUe0fVU4jO)<!Gt6m~A_g2$r)y<?1kf|RDvVOKfM>aT4D{o-+}d&;itIyX zQe$|w4&iT#li%wkML)N`1vQotG0`vJ7YSwFP<_xBHFnrbtm*Bk;R-S3-`}_IWZYI2 zUBb-)#NLP}%43gjBE>2IkpUm5H2G@{Vm4@Zr(4g+R$~|lg`da%Q=BAVcb$<_O~sWF z&`FS!T()d<Q6W`%oPp3BQB=y`$=Wih%vR5JhKMgF4gXa0+o3o=)vd=dLKt)crV$OP z)K{rzm)>)QXG-^Brh0Gs_e@od*{1%_Zo9HGR<zG1I9IT9Z<L61K2&e`%aO}Z!1CR( z#7V+jul&;OhbnW1lfC;-#0CvD%>j&YHTa!H_CuH$F}LaB`^PXjCSpou488-66~nX% z-v@Wi_KIew<7ty+C!ZaF<PJdV$C<e_8R>!-*hpi2<tpQSML@4o01S+aQc_y?B>Bv# zR@2=F=d5Jjgn!c^NDm~x5V>rK9{mv_lT{f!XkR?^_Nd)?OO(1WN*!H=tRzfrY22Rm zYwFS5y)75+n^kaj5mm!PDolr5leIEen=4AuUTQ~od+3xUi^khbFW{rWVr_tEiIbtq zFAC3SC@-p(3}a}x4v)q$>yPTyD7f#K`rPSXr+3LPP`#MCm)%$t(-$TdPwThb*8rxj zN`6tZtHpCuvIJ29jM6IX;~>8(eY(-gAaDUt(v(k85V=db^ZY=+M|$2brepAR@rwF8 zE;=eK&tsSpO#uNO=js>S7m7$#>CjW`Z4U2duUI!cWL%E~_>k^kN4)IzF)rjH8C>4l z%e?zP4cm_Qfg3Rc0_q`>w5vwac)d~hLltIw3+jUCvyspA%iHLK3XgG2eP*cRf#K>r zRf;!YWTze&(K<O;plX4yHTXuTqRPY8KP2prtFYNEnZ&|@e5x)Y2Sm*Eiwo2&T`1|T zLSXT5&igs2wO8U{`v1m0IeoBis!`rCHI1CFYzo{-KQ1LcU3ux)+7dLBVnwBahG9vM z7yNZNYBp&mafXu?LHjyg+quPcUj5b4_{V1iWco$KZ{&n86>|<p_kamcnYruPD_Qg~ z_6}%{FIP+MV`0E{qqaaau&X=DUU}!Vy`meAQ;-qG-`=c7q-MYvss(bqhEfYM;5V{C z?Gz)_fOhn|J-+MeQ&03t0kN99#-{X{h_av7InZH=6*EKnIEtcy%7H1w*DI7rfT>E- zPf>smMIhmyjt`zn35xEessX()x^WXhQQp}?wcaOErDU)I8R|Z+1*DU99zGPRdo~7< z+M%moI>dgU+Zn+Q@cQ-n*W?M*1@^Fy^Z&Ze`XE%$y(~+MAt5!hJ48SpE@QJTGYpkg zg8BtF+$|o0*5|@gjF8*)txQsJ)+V;d_e~j)jZVNnN>9%DNxz-*qDK7AIAz+g9&~nl zEiJIN$SqTXDn$eZV9o**FTouJ^=Lj-tbiYKxd5f-RwF|51n1)`CzLnh0s9FA)wLwl zFHyP=rI0H9zfJ(A*8QW&XFv<+l~T;5(5QwB@t~ZvUTFmdRLB<eW?3VEniPk%IO<3B zfd{sd0NAi+r50&tQMLB`=5AmmXVI6kiGRRXR-_CmD1~_xkZ;Sqd1&{fbz(GlAh}Y> zdb&x00~yUcscuSrfG#EfGvXn*={zyoNTuW?`gL_Kn<j5Z$Q~K*PHC&CE&fU)ebrHO zR#yOiX)C>TnSoJYDw3d}AC(Vh>QN7}-9U9|YA$#PFo^;|%f9;e7(@}kmfobM)OQfj zqKs^d-n=}v?Ky$j3n%F4woA|oOgPOzwf6gmI_mt}4GOZ`DR2aF;Ql6Bk)p1Gs|&T< ziu!qz3r2HlJh!;0I_vuf$(zkfpM+}<q?@^34f{pKM9S*$I(z$`7h9UdSW9V2sA<+G zzMZ?}^wCt*>t+@UAfvMyjHNz#p0Zx(?0FKGjO>1~dp#CRQ;0XKTzF7StWwB^YAshC zJ>CMnZ1yUZf%+XmrAq^rTu5dzeh1Z0nn^5sKrpa}eUFs}tYH+mLRK%Fr!RM0Tz?q( z?fw>W3UfwHSL!ev!1w@LfDXWRu#LJaFjrs%h#e4^5}z6RMNX0&@M0oz^P2c#E?9l^ zwG^{v_)S-qgqm_50QBP|%Sed`e{lnJ^$MHB2i)-`)flM?lHscLupB}YKFU8~ncAd| z)W~X}<xItvUJbmr>z)8LEnrpchg{SLvL0@7T0$QfLK4SBgh(+-r~BJi0xnv?cr^`F z%zRsn^nVI%ex%E(eD8UR8Aa{2;<HEm5UFZhZQK3QTSDUH(u6xU-L&puBm8l}DLSGU zA_8hHB-l6fC5HJ4bR`XIpkWhL7XYNem?I&}n=VMe0BppSJh<x&HP(-F+ZvW}auE;A zdw|+B1S87{?Sh>g<q&922*de1gdb&v07FqIL}|FC%6N05k6T(GeE@-H-^B#8OGz3A zu4tzGiE&p2xM)MC8t+p#-fr|-5}NH0ox48%-8J|#(mLIOV^I6K(bLm_?P#yl0}V9o z{`OG%7!?eDeDG`)JMRRY`m`S{3-J<V?wE<3yOwcjlCQ<%D6LgHJFf;w4N(lVBXxN+ z5%$S6DC!efukD#YwZcd0Co*8`paku;MsG`Ga5TkCUvO^-)vTP%=~94V$Ys<;G(gWN zBuw{fA6`RipWT5lFD9aIn?zv}4dBNIY<zT~>PMUyJVf$&KKbR=wg8QLC6)nh#^;$g zWmM)>0ec2q)#Ks!FdMsIWu8?Di>n#;lT&Uw^dy?=vucDsxH}3-kE5DZtOm9qsuKSY zHi~H+!qweH%u-yNp<?p+62f*iXY;x+x61GRcEs7wZu{7dwkqGu4DHeP7U|$iWs080 zsq1W~SONBNynS?u0d>_A)U^I;R)1BL_=aElV#fdIi;5~wUkQ_Q+}QcFKc1>&l^<l? zu4L$gvCf@(6r1+_%E}L2|J&?fwt?%l!xXq}dRt#@#E@AZg?C*-tpv#9jr~S4m9MH# zJ1_u+=ivGLjr}9t8Qp}~eX+h}5BLm#a<Dmt1eD)?1UwDekB;)Wt+h8sRph!y-qu44 zJ(v684y-@XL#h-Yqa4DZ8wiWh=%5M>fbt22EDGVv&auc_mEfpXhg3!tU=sc{09POw zpn5&Dm^+pU$9nctost9wpH>O`)iQh+8G2f=?mX!ak#xU=c}_zvp)_SgZ~Eutj=+AI z8V1t9cH-*#oih`NBgs^y(`RqVE$BacZn?46q!dM|!DNKIea`;yZr8ClYWcmqivKj< z@5w}tbv#~_&~=b;cix_7C||R<Rwvxn|3KwB!9y073ubK|c$Ina;jGrqQO@+I)aUCu zdtf-`mcX(@h`vcjOkI?DI*Sm@7deGLOgh?A?hABLUH89ahi)h$q*>MbH)qQ$@A@A? zTS}b@6Tqygn}~z3-qSE)lEvuT*0yuDwAR4Sy_xsU*!)<z^;GY}fq@NT00M*berdOl z6ZmYn9_tsmLL+dTKAVL+T9gT9U1J?wQoTzSTPyj?#?fcash5839UW0>{j_NO*9|3~ zB$nC#IN*l6!!;kd%bNdCe-TLLL*CJ8Pj9#0c?-7j=^fAh$zARv>H$n`qXKECbsQsY z++l&TlRSx3SlD8FTJd}<cMwi+*eZryPGNBBq!`E>+WGr2Y4=v=Vr7t7lonh&OU_RQ zvRFFNKKuR3rp=vX`vFtIEPjaHpk(GjGhB1UShPia{gFJTZ2uz`oV3}!8k^;NgAn`E z$gL`9I~jNBeU{vQ83`iP>5<GRMLBiQLZgd_$c3JRXd5PWV|;wSrj%VK)f8VwI2o+e zBRuFtqpcx<D}L|-A+DK><5CsBqk#2qhKJALvvNQm_EB_{LY{E@YnVbsFnEM<Oq#VL zGyrV>c?_*U8p%8^&62Vcy2V;sY-)vNeD_1T0v12yf>ift{6HfaeqB<4`N|1}oqKa& z$f)m0k<1X(H<Du@m<d|-*aRH6R^2!Z&c%XyRhUXY*`tDFp%}k9AzAYyzTaR{lmpQ$ z&LKrROtk74h}qF9^D2nFW1q~w0PeLwf<BS&>7`teJc0(}eZk&6fGp1sc8DAsGQaJH zC{_FLo<lnMTd1_zNvv2o*im7dlZ`#B6Te}ax_MF(VejLr!!YNAJ^bU;IiMaY3Z337 zeT>OJoNnMaZ;7%(J(fDofGfByJFRj-(vS47_j#zgEdY?)!;=+BDUeBS(m#oG-E>O} zRBgW=2d;Wp816C=j)Zc6rIY7Tc>_0PO91qToeZA;(Y7nhQEQwNw41FGm|azXF3!fX zy>^phn^wI=lB+wi>`}iX2Ukog4tw>q!jCg$S8`N+CidU&$~Jkxydlm;wQ*dmb{SJa zqY1<LdbQk|7?Zc$La7`+!+ZtqzyY*Rj>pdoY|3UF<79+CbO%vCTvFP|NGhVSPXmN3 zBm`>+$bg?CCBgv(g51X2{TUI5f$n-zgsPjxd8cg4Fx$+%!@-CKm@3s8oIp8R`X9(# z+N)z@Rj%OTlB#`bFL<WmwD~@KIRPgbvUGsfm%kgXMPW(1xNnKLt+Z{SgVxuIOVE(% zKdUGj;cOFHVa!kVELk>t@a*jn@Sj$haj}#ip~MWWYD%=5=-$Szw+3fbw}}*+TXE8D zSYLHUZ7-g0aV~W-z~p9tswa2~*edvO?pL)rEjH)gt{t#L29|w#wNk2B7tq7+45BCu z7(c!r9g3QzAA9Df%WzF?NVI1FIluir?*d~G0OYn8$+Fz)m+1-ex}%(L{<Qqa2mePr zr2IR4VfMhr8H;k!O-u!4vxNHAm?EQ3-Bp%lW<kX|=3u{PT066gM{0{xh^8885@KMb z1|J+<!d>^1KTE*`>JcyKUwja+w5bbj&q#H7rkFw9<NCACnHt!01Y|0h*+Lb~e%t~c z_vw(K_X0mF7Yxs<miPy_lp?f6KwKW!kpUw6_l~Y40j=aI_ssM>a9!!dkjs_`X)V22 zzlJHHkqR0y?kAluRL-ulp!lOEG$;bC(>D<(-~gJFplJhsLjzMkPze_d4wI`<Md}yc zIV;XyddgMROT`luaDlC|`m=F=CL-E?AKuuv4GGm=li*WnruEZk*cDuNF}0m2vk?>} zI|ZQUfg`E5>_Zc0rK41*$5BoxxQDHErV>(4TESjNRcf{3j%UFIsES05;($Cg=Qhcp z>hSF9C4R~kX$yqq&SN>>uB0v>8uv$zxq)=0Qp+fwMX&GSBcM71B)9-#g|efaGP^qf zBnx&V3p8L@BBR1u+%mOdHPl@}mH{Xuu`00)>=D;qya5pt&d<+Rqbv>!Rs$+2o6lKd z^2OL?*!Fdcrf+V=oXn;!L)$0qGN;C+$AISDju$r#C<RU6f?%>EWDGp_rrc!RZmdq! z!y}%H`xK(3orJiz!?r;<W97IOV!GW&$AhF8#oJ<d3PbH)7`Rf!-2kEZmuQ9gzDqMw zF5fT!YYA=E3qK{0hHa_Ni32C!>7g`zf5d^FOPBAbo<UXV8!(;Psi2~F^uH`X8j$^; zFj3-D#^;y*PpKUMG;8m5Bm7AMhlVC)XX$UpOcO6S%$q0c2edg}<AEOLhgHk{@O9lq zNd)xft9hV5*Ls2}mv!;!krKqLjBBs-7-+Xsv)Py}qqVv_7=~^l$UY7;nW<}<Zbdr@ zaIbJama}y(ec7PB>NcX9ghl&~4IVI3tPm^AXP(QVsz*AIl>q4+3V1Rlr>hPm)a}@! ztGMl#TkTpH*5!E48ri^wcd^0=AnbK!!QP4G8xz5eeFzwy3~N3G&K|bBCJCjj=1N2S z!wN-5o?qbOfE#NjCBf%NeV8U8Hr!9vE+?<WLG|Q)oz=IBLVKm@k1{l-bU3oJR;_bD zjQcm{=D%cF3Dj|3XcMJOWQ1Rg#mSyxz;BHI(-Tr~JHExm=9Z;`TE1j?Pr=p;Yfi<2 z=Ba9v^knm!r&-2bTyJ$}3phZ)z-u-wmKjL77-$E9QH)lA(7;)&l1`P{H?4d$6vo2< zNP<v5sSnvFLe8Er&`Q*~R)w}8C0RFK|9Obzk<j+UpGynBm19t$Q{-HA;M}*g)2jzc zGVMv!h#CU!YOC}up&H%TcIDl`CF`t>!?1rTOzHYvgA;f=uc~|H?{Rm>W!lQHj~LJo zTqo#1sP_02AB1-Tvfbo82-y9f6@I_BC?&aqb**uvT}Sf~@gijM?r*x&CFnmrnW%5l zM{BRxlp6fL(kS>OkoNC8ujxDjD+L4yH%aku7jH)T1X@pX&wIbi5dfdv)>FS(>(2wk zEKIT_7u~$-DV=C>4D=dTRF*;2C?06fiONvww#!xJ6LQ2i(C?x=P;J`hD7}V=o#t3P zlYq9)-gzm-td3BT(r5P+GrB*6V;^UF^$KnbKptuh^7w{}Oq^mQsJ;nTp8e^?1ieH4 z6y(e{`*8-9DcEr3|1>$l8_`(RpZz6c_ps|SK%L+}m%jgsRgzP&3a+m%J&PG~rk>AA zKcw^A;j-JNkz0BQ)}smkK7fF<^nVnsCPcJ7X!~=VaEDG{mL;J91jWAbn(WSjw(zHP zX{wt+N)@uo?F!O@=0_@WXsEH!xM1_p^jZ|bNU`VU$t@%O&L%m+tJQA~G4x<NFQ(u> zbV^SwdGsc5k+6!gKqEN&;81zR{d^zMZ|O+!*tbvr%xId1^s~&q<9e24F9?)x8a$<k z*7<Q{xdd1(cr(7aGE2cLC-ox90Y`=FTKnGzz%&UzX%bNkb4nJgB$rGn%B<M84fh8R z^;%A-pFbYOuFjO?-wx%~X(5ZcYmWPBe>yG=^W!_f6aZi+7hpOJOHk;4DO&%ui4bit zWIT97B~!z67}Z9`{7y1S1f5D=O0)RW@4(+_;Fk|49ZrF{XYX{cUAqLzF4$sozu|vF zP0mqI99S2*zXpW09YZmuO>;8G$*51wgs-x8bqluNUQPYWkbMoH?}%lRE^4Mb|7)Iy z2EL4C!Z_cxXoK0R=)bDC9Yz^R*h^%rbk&|U>ZPC0|MMnA@M@-!S_;(BSyZ2UMR%yZ zYIpf@vI|T|mT6be^y_qc)6ti)zz{jMSnSh}hK>sWFf%qQtT_p+!KRP5wb%6P6%|}Y zLz46VAlM#uBe<~oG(RTm+#R#EYM{3$mLY4CP&4z-eVqq2tT&r6E$_zfbR2?M_p!2v z#E6U?rm}Nvi)f$lHrcZPJK1gF<0&w!P^lY`<!g&wsXo&m7dG1|QQL31CxTz3z9C@6 zr>ag%RbJmcYryjc(|a$SB%hxtD#Wl3A=-8TV*lE`{m%XkzqskKYMGu&p~xbb?vx*r zK{m7<*0_O|xe0VxB_S1h9&r5HE2^BB^N2P?_ZE#Hzn6%K+l_1OAoTXi)<tJ%>&Jjs zpLnk%*!jW|S~~JYtLj1Tb-Tr}cfZ_}9?UC_x1#=i;DZY=ty`$G7&>xy3D?$u-gqq@ z{X6zLG86K*TH-Nbonjej%M#3G&Hs|XNqg0G<4enn|6P_FDu@Gl$8OkmfX`Xsp=F0u zRUD;@8Ucpmf6?;<pG1CWwAQsPcWT~jtjbTP0R20is9UvYz96&`f?%cJyq$ElW<Kx9 z^7!mCKp3SjuK>3S`Sa`BrBLwIp|@ygq^R?=VOvq07=5pIWG8B7V#`6GSnRoTCJGye z&%%xMN`D;nc|w#lHtK`Dz$ZqsM_Xmb030e%nKMT1!`wq`mZT>WLR%txfMrKM*h}L9 zX*PE<uFcZ(mG;A0k(4P~XtPm3j9z}U0Z{399MKv-r&nU?Pl}$tvLWxXH4B*T=$B|V z91f~<R%M|mWxU-$pu-}bDaf-efs4n<A`Vj8_N5f_=ZC5DUjd;3(AziA0FkQW6lx$j zz$wcqXHtSHHKW4>@m;*RF-Kr=J|^za+~ph=AXCkciz1etQnAUVTTF_)6m53Tl&JUC z?QI+h#NG3(H3$H_q{#agb&LX)&7YT_D~h5&k5F9{U3_=}(jL}cTvU$8N_pA0ZDsAJ zcj=7;rqIS)`+ubY(NCJC2%Y5HqP)RFRI79smG;+z#u{9;i4}Tio4MKYYDb3acBLS* zz#|tdT|H!V%&XBP8u)-Ntq|7ufz-DZzNnusLigkHH>v?b3#mMWh|yJxZY16erbI!C z02;=Xt4@eBk(vy-?wbD+CN6AMVKl&HfCYdHdN2%flr`E}rrO8iu3}oaaOOSU{PfkT z$}hrrV!sNliFl6z7q{gRPsOwkYxE#)Y`1?lpy(Ikx$g|aKGZ|^#k)rf&JG8PMpd5c zW*ezG9h9P|5yEEW?8FE?C4j>X^-!a$uDv~%OnMNbvAgz<tG~DEfrUv|o6!zv`R?rj z!)WFf-_qP<D-UN?|NJx89<{ED6-&PyHEJJF3P(S^2M}}x+hVHYsHj`z*C2h3Fg8R~ zAr?bdfH+o_q6VBrM8_c*7lLm6^s12B0EPZ=jD!`&$;q5gt=g>GSOsln0svpm&@r>h zplMuWfHCxPxqfD?U22%Ox*7-4&=xV(#;TLW*T^;xOsxD&+9X)d$E}0-;vHK?^``vT zry<ABff>%blT+)F{_QS7<Fj&>j|pGoyb8;bn_#t?A;<EP-<`3(*HO*JmZRTN{1$Td zm9D&0(Rrqk@I>zk$q~tv2N?Ix{+S*)Gc{V0pz94NQt7*dF<rVvG@uO6yg(93wbtJr z7h$ogj#C~$@$U2JEY<9fC?J6kJy#+bwLusn!vN7-o~&?9Stdjb0|rf10r|{Y1D?8C zG>#by3(2gCIiTaxaAHG0I<3lKZ85Q`9NmJppc#pZXY<!8lIk83W)Mn#!1#RG-WC2m zWp5SYy|a0av2h6{GyOv!iY^2%1_H_cu_%AC-s874{pirDw*j6=jn7whCUjjmt(bg_ zm;HN(oFd!p9Pv}>pmt~I-(25o;y{HDHr!x$faz}1XTxiaflPiEpVU^k;3m1D=!xd* z*2k!ctmhBd#d~trZHkUh)P*QN09~_s&yT|>rV**VAxm%v)hZpgD0Lh_@?+&>3Bx4z zZkNXa9D)TsQqdFc)yP1;7-B&g%uQ&F+m`&mcw<34TDPa;vUIYWPoGrp_eK`aM~S0& zDdkcCc1W;s+Ju`;ygieh_Dv9OB8ACJ;jM`FgUjje_D}i>&5uzFot0cPq+v0%6Q~Zl zsnIcmZlrAofQa*$x3eA@y5zR<ui&QWtdhEz7SQh$P||K)9v5_0O+?ymzhtP45Fob& z@F_l+kj-tJmnw4uX9)3-TPR<pnyD0H1Le6T@x=g{BRW1n$IU`6l2|DxD~H#4<o>n} z7SQ&%0g8q7V*CW`xHcSM%H5Tl-wKrikIW8-@{38;UjH&d0P#mmPySWH^F#p(FGu>B zc6Z1sH7aq_D1CdF^Hu-a(|~a1s9UW5ixCUrFoCOR^x-OPcF<2Yb+bkB3NGZ>MvY4T zD$nc~Yf~LC8X$7m;hMyfh2pGrj=!AxTe-3g$hJ(_Y{)PS{|<AxLlid0<Vop2x}4u@ zsnDJ@wDno1V9#+uzTf0Nmt)_HEGP@588u)|rJs3z@3l}nzgR0(Hk-gc1kJ+%1dzg% zdD*}D%<Xr<t!%c`xB(m=!tXYkWT%<UqwKRD(j-!+$u`A<28L0KTZz(<Tm4IaulJWE z*%fi$CL5niB@8f2)wj3CE5$wUH*#~)u)Dxx%CL4`BRcx$54RN_C%~<fChj{AAB6q^ zb%A3Fm3x+})hEm7HarVMKvz2U-3P_$?9{8XStUev`H)K*wLpC+s%FEw>GV&6ktQHg z(Mzo58_;I+W^8Je05#XI5#6_WAp$uvV~9A_3DRUlyMhkzTUGE|njQI&2YdW3Ki)(~ zuMO=Qg1!?xq%5DrgyuE8VKWzYz3Ao3BU6}f)4M?2&KTr`(R+y;hI`L)zASt1(5o<_ zFR)shv0PB(tWHxK)$nNqJf=l{qT4H5mkujD@=?20g|@YJsiGY~yZCcvcyw!9ookV< zhpKRaOG0JT#GBP7T)=8yy83-`zjZn5RoUqa5SLhfYR5TiC2^nnE%G^+j$5WCQcG1h z%v*YclY%eVZ#bd=u@gq_bCs0QPTk#f0tR3_5Y=En^G1MlO^09$<L0F;eHOrSF-qlh zlmWiF;*}b0>I~2)oz&KMBXafJV7wfl#wWSRF~P*NEaS*N)M>4yUBI+~lmR^2UVpNM zw|)Sk+mnETfyG)t$TfJD;KKN&TQPqF;!u1<X-_)5oJ@Q?f-x0^{soq`v?Fy25307| zH-{$0=<Mp$zSy3m8BXa(75SB4x-}BJ4Ng!)V+zUH-|}}IlLAXtQ6>zQU@Ps`zT}zn z<fJ}W0Kw%-__NKvF6Sw*<eaLD_Ib2j@p=A%1NhRigRU<HNVQf5B*;pCmX$&7PXUt+ zo_X%$&`>*l(ST(npQrT#e^YWAf0ULdwISCFyFK^hY51(a9IV2jB&(1}j~>2L>%5W| z2<^dr6Y<Ul7LgR}uWgy?_&jhLo$8CQ?2P7D8%jOTH7rRKg^O*+#r){USBL@i-!H$X zzfgG=txnIP_rAA3!d7*H27bEQb@rhW*H!8bzBOy@zfnNp0{_W%zk4K%jVvjNO}LV( zsNvlX<|Gr}eM!i}Ox_f@e^peFTKtNFElF>;qf3a+y;=q@1SlBbx%+>5Kv~wUI~S8b zFcYf+9Q~qsPGT5xL9{LVct%}Z9fz3AmsV^4lfja^;0<l!s#<=|s}w+c%b-*1Z_g&( zH!EeS7lcKlx$3tf;$>z|$=s2=|2)8eMYAly>AZOcPcX>IDZa%s5W?21>_oS6{QkK@ zL2ae5x9sIVsBtQ&;g?oz-cQ*aSJw64AO3jwxw9;uEd{o3wRiA^-Qtl3N}@u`GY!jb z`G1Vt&-1zMP{naeE*ECUi_^U2kA0hnss3Tqvx-*xgANI=&nK{6oyw26Q7MJC|9%vk zC{h_T?9}`K;6I2`utmHE*uI2QJOcc;&h47LXk(y0$H1{Pg=o-tMJo}#{iB8P#3o+v z?TU&Hp7?gKhUvL!?)i$G5CcwhTsJSS**{u)`(w)KC3=Cl)^WnFw5(?95rkF<?}`O= z_$YRPhNc<uV!NFFyS>pe{7_NA;u*CXwy3!lshgi}xRn<tyZJGl7S6YhMql^DxFMQz z7&-ZTa}#y&q9#b#OEcEEdwvKLR7?|waNgbi*Qk=;Rfg7Wb-7{Lv_DGnzh?|gJKrlZ zM(}~uacRpWjZ{drFAOaiGc>s5-2%7hW=V`t*N};P3$o1<g_|ca18+2CIxPx}u5N)6 z`R;%C<}8P@E$w_3#e13;D0a#TGY8^K4f-kh{PL&btJBPyNQ8RK5^LzirSOn@55oBY z$FRJQyg-1<KZ-0$$a9`+-B-r4W%BIS(4`~o-xKnpW6);<vHPs={Ev@drgiL&=el_y zPHAcKLN-Ll@mmj6>Q{yH{VS@Btg*%vY}(6;+P(U1Rwl7WtCX_(bFxVJDS#9R|8~Ri zC>?Vh&4q=a2U*53hurNV_@O)N2WZe*4ajlwc#xLon6-&#e^;Kk6}CLgLtD~^E;c3Q zrFk2jzQg6uO3wLAUmz#CjO(10bCw{RWhFcCho9SHcd44Ml`b16hPhC9Il|LHk8f1G z#O`TD#ZPk%sP*Sj<g5OVqH~XD`v2niXBTX)8=Ks1WA67`NZMxZ(%kQInQL-aRBD@H z?i0CJBljq`M5*RdE-BZ9RBn}|Qc0I@<>&X`=g-gM@&4<a^Ljm>WVqNLSp8JG7Yt;9 z;e8net0QOS0|rj<cFsX^GvTeRWp)`G7s)OLIc7uIHf8_5a_C+#Gj6krojK$`*sWk# zca-5&;CK>KJY(`+y62#DHLGZw|HAg(<5n7P2F6IV)Bg0<aEL-p!f)1x!NK$ZTn2`} zW*gs~Ae+IKKDXH3wAhk0i*B?VvYokmVQl1eAjc6%FKR41OksvjO1zB|OZl%18gxy~ z$F_FqcCBItkpPyd%KM0P%s;~)7LZ{}xhk65Z(RecY++p-b)@z%g>+zBiMF-1SKK4e zE|_#fhTSv(yer(VY-MGrOn3*ftUuW8_Q~!ANv~G2t}hC7RKb{A78w|&zrHYmR@MZF zwri2~FogzT17{p2TemZ#^gs}R_MigjS>%^S$P6)#WP5@&TDr5@4gg^7+X1OuhL~@6 ztD2Ohfhw<$<LbYPPMzB;b7YmJv!{|QAfXgF2gN$DUEX{%Yxk!UCJFAh43**bAL<o5 zywI8RpNbv?@N6q{nk>(P99I2{`lwd1Z8sL;2|*DuM27T)HMDF0s5(ix2%=^L$O^Ek z!>i?EMlVJ0o`p_AfsVjq{&bt;@RG{dk^7W7r@DPpLj4_G@eX?i&Ql!wv$C^-H4w=% zWY(v%ueW)^peJ2Rd-!gKi|#128_pJ{Zx4H&FbZiObh|srXQG3TxZk>ppZ_ILIypXQ zlPliDj4yhYS9{M<rR!K@#$ivW*EaKee9>o=RR-sFPUCI$YhpovjdL-)7*A-4)7&8^ z{%R%<z|IIB*^|t=>;8^e+wh(Hk*@M87aSgrt}AZLZ9B^0pJ-rS5vXPTW_x_|Z7!fp zG$aqCZ+G9LWSd)N3H*X()J<m4JR9`|vRYY&PdsmU@<Iu;z(E;c9vBp?8B&}b3=)5+ zCR@rq(51l7T;eZ#W3WIUn0cn*ei9}aRE9cf@Qpep9s>8K6C71Cf>qMOe=^h0ylC)M zaAg&^M_fB|qM#wp`*|#{N*g2g)?)J|SbJ(`rGcU)h3EC;+=eDmEzfb|Qj`A%&78nn z-`bHyS<GWq9Lw%-wi8N`p2!N|q)!%LeYn|M4e5=C{tIC_+;w4?nA2L1o%dqBbGfS~ zQJ=xxLjWwJ2Z8)yF8qjXKv<<64z!Rj4?lXtf7g4EhpnE0Xps+sb;VXoVqCK~q@hNp z{N)0tn^{Kl4^qHRBELE2BP|2m<E1@!vo=IDzh2BuBzV)wdDXlI66pg8atk|-lt`hS zH%_bQxy`u6zf<XU1W*`9?wyeK$4K`rKiKic4BIl{s)}j1aiJ=x<AH@%$40;z2o{!k zC?tp}F!tCU8k!+k8J^7g-8R-&`8vJvdBe~40z~dVKhaX1Td*crdj+fL<x)EPR#uO1 zu?mnZc|_n8ToOd%36PPS9!@<+y(O{Iusw@6J#<slullDIJ*lP}LVGMl&h9ymIkBhq z{NdfoRE{`aF2nPRBS+!{hq*2&bWt&VH$-J_eyTBW_3WDb@o^scMyTJ2qI&oAmgd?* z4^LKtvGqP^nU-$&^py*C?L-Anm<>dX!22*kf#vL-#|j4Kr&JQ)R9_c&#__?*o3Qwo zmI9S+qnAD2qSaTQmvLR@s#!?WG)bxK<IayIEO4hbeLX5!6ZH8E7QgScdBL;C?cDjJ z03iB~OvbXgNL<O51w2wLWD;$iftb%&&bci;)uzaOvZGPDeEGtd*Ld4A{iG}QvFQfw z>APqHMXOPFPw&+yNB=q%#C~F!=uDSKy$b&a%h5w+b!G$y?4y9wPo9rl8Q)v2?@f<= z3sR2Fc(J3u`ga-t8wAzE=D$TG*Wde5_wMGehQ8}Ct8c+gi$1r#*oOe}<wh7@H5}M* z38-QB0Inf{x>LVctWX%$rz*O_`pe)(Yk)x1N<cQEVK0}C9RLk&PPG2?g*TDXwAw`K z#xo3F0^_es8*gGEwB};BX<yhZwWw&4i5IZF0e|}?*XLApSS@-pfC>vbDq@kv6o+{% zC;GGIvomSw?^}6-5yl@|y^p^rx}ik3-bi0fZ(K<)$dKR^(64Y9cHLU=l#_K@jF(pS zL*~(0sU07ppy8E0X;m1VjMy69i2DrQrF6_PKhew7wIw;Oqy)AH>LhfB*JOh>*!Od{ zvbOnM*{%*ZqI@6?2$S~opH;YKR+3$fl5xp?eC5QUjlbgI>prZO0S)D$M*=mlv)@HL z^W5a}UoT5uDcWXYuRsahA_LL%T_Jo|bl5T6<`(Lc-W-qg1~ja`@%>wV`-;AkuXqU? z=|Nmuz0j{UftzaRo9|v0c}=F<!wMTf(Vgx=uXc$U8()mPmbyb-c3xdZ`*oSSPk4wQ z94cFwd27IJ9QSM1rF>MoJ3sjEe9NIISP!*3owAiqTh5>Xe4aG$JoJ9lb_1IRnY^>} zZTV);HbTo66vHZdCN24Rva3@d?VnZg71p$QT!qb-p6h!n&+0s6qCd`kx>$)mn!)jr z7w*eEl)+yd>=dv0Svd0QBEck1D#zxP5+^9qeGc=6|Nks^4wT5|)tkGb{_b{p;wd9L zf4Nv*SBV6jkB(jDeR`K!hI#J_%Iv(K;<5t_4h(xdHOm$1aH;TQ?+FY|nd|6rNXR2p zMhoj{(h))Bg;Xf*t}hFIgCE8jw!M;=O~^dcN3HAGVwDVLBW#LcU%I5lQwuK7Bir2F z`RAVa$lUl|`DUef9=cq8&q#HDUB`4s2+943$o5pY$_Os^ezCO(m5U7xy}fucBKpRy z3}2n*cFRwk)0=f)2+yP+x>GXHTu2bBb@@BY7`yifoPGEm(Ihb};rD#On96`=yGP^2 zh1JT-ZhJrX{8+8tvVR@hQp*M060*|$j1EL30uli4`Q*Bv;u-U%0xnBW1J`q2y8?*W zyI#0+QwO*i4T=$7|IKxmU6NHZ^+R8HpAjH<`dz`RxR1FlZblwiRZ5D4HeN>wTSE{2 zmf@5Fl~a_cGe$UGEC!l)O)M$~8LpiX!GYQlcs&}YLvQE#EIX$b<+=Cp*o*+qZ9G>= zS+C4T8w{*`l01r4Chnfhy7+qh&)?wewm<hqx?4Gw*9iQz0<H-f3+XV~P&HTJGOOS| z6{<sXq;1{Ltj^FmAlz7jkSM$ZWr^#D&bIA=mN_CAzAPCi8%hvU=DTJ94Y1tbW%3Q? zHf?+fzMO^yEt`xqOblnxo!uQ~+op(RXsm25l;d1yZwiXqgcDpWDV2byse4ob&ZER8 zB~oQfp{bxADAP;djJ)2$=aX8+!~Ng^bl(@f9vrfu;S>4%RpjG~Z#)ay0!~6)TO?Wv zPQJXK{-66vJD0~J+n9`IbaO@)`q-t-FA=l#S1RPTsJ+^g8HG{P=XTl)-`&p;7TrA2 zp-4L<^bU|Pc_&0OlAmxDoIwOzWXly{ypj<tkr`zN0D}Y*G7E&oC6;5iue{%wZn!|^ z<4n-9Mb)Ur8`U^|K-FxHOQ!_xJ;VVeJI@$X_7-~RkPFn*$^6S{jnXw{^Y12zbU`p7 zLJs?N3I{OfCKU=M6U7`&{Jy$aSh!Kk@jz5(ru@TLT()uz`FpW-o^2A^-B(sIN8|Xd z4Rk<ft>K)8Qd#_CZxgW9OY7dAReqCV7*0s@#>TDZnp3UcpL^&%-9YEmV}b{y@0EE@ z1<hFQTat=F+)<)<eQ~)pJ8{=3Esxt}!vG}oDy$(!`wx@4O<$D#l}^2y8dHds2fAgM zPH3@mC9;Lta=;`}7nlUw%OrXbEyurnnK(50rAM^^eeYX=k<j7osnhbrGn0bA(lW9} z2>XR1#%D_nw~&h4o25trEmORya_vUWmglN=N@&niXDDeEwq-8qRkTsD{kY`C72V<D z{#<7uH+iyz&(F)rO~wC>Qx1C6vrw}`#f2<8#BB`D-}n4J_M>?Q=M>6e%N2d?e?LQe z`n>6Y!QR)X__?8pyfiBM@PByw3aZfxF_d(%#X3T6=q)kE9U5kNVJFPlB4rVz0VIrL zGZO>3Vcsoh-Pujz+qy(joQ7@eBp9ZFaWwxta%iXiMBA*Ng;Evb6@Q*lml_G^8k_V% zdBsf;x0A@cC-2q|#b5p1&J?933gf~o<YF{lrkU8Pv=8x_ykLhMz0@Hjl|M2)>Vl1b zadIF=cCYG9w%p|xY^{RrN&B2_u=s)FGm>5o`b9%u?eC*MR!-+v%Dtkv*J5TK3JoRx z=kE48-)4a-bokI|%fn9RD0stiuP<pMHzK_0Kns+x(C=OxCaact`1sARk+4b*5bhLS zeaEnC$U+F)%uX?$Wj7~EP!`z`D4|+p>Wy_nlQGNy)&G>w<cE0eQm2$GN(0UxZgFq! z^f^1~S+dP%0x!+zq=S;a?o4QGO_9BhKy(m8+^P9irl(3eN^!NMTgv&;j1%5>P0GX4 ze-<GzT7$j=3}6zmIg;;fG=4AUB!+`>BDaWA4`VI;r8>0F$3<%BR#^59)ZhTls<<X> zZ%Fe#9xYb5ns^jc_`&yw&Xu1`2SX68T&nnPX{;ciWedkno<bCYZeq_hvaaOv0VZ4} zBfhEEMAM5GH|lE7%o0IQJ@x3j-vvR7+~Qy0UnQqE6wCw~M}8Os3<R47O^IS%11NGc zZNm!Ra|WJu%(3$)Gw?A1USnj@mcYEJ3-=GbNDS!UWDtV%D+4ha39E!mdXrd*3XkEH z{mn{vO$;9r$yd73pDoxPD<5I0y^Vl`l?~WBZpsv#OGbG1)JW4tn1*jV21ma0Xk7i4 zT_iPt3zmbT4>E=X<EzQBtwrPmJ0qw;1C;u!T3q$$Wl)_<1@TY5qr56Sa*yQPXL!Fl zPe`{SLI-ykAoRm^A%qz7Ai2hScqj&-CG>e9`A`Awj6aQuI7*>VGBX0*1OlQ$_qVGb zF}l}}|26-r=lkX}<|I{8#U}yrY&$GBAkoF{z9-V{JX5KVh3GU}Ey}QYELt*eW!Oz? z73Ar}9$gRE9C%Y0)UCowzuS+GZYPDACb*cWIjdLb@)Hu*tT!UD_5+fa<3a7rH;O^( zHq`>kuEYawe{ICPrs2K!>Xg4RDR%Df3yt8H@L>XE%)jMh`uEc>v=`=0#q-c~=dBca zn_wuZ#nR=nVP2J!Bm3pm!gT{`0T9b2R)MA$>W84bu|U*|=X<i2a!g~TJZj?Xnsb3s zEx&u?h=Yio{BN#OgQ`jJ<uOkr(7~kb8?4jB6K7!`heXXyGy=0$vrY!!gl;F#^Oz*x zY2nQ;^ZBl(#+pjUt6W1bD}H!qY$*Vs6eMVkkJR;)#d|93Z)g?gdt@~daiIaoPFVeB zk7D*|D{BX8v!7*Dji+HsZTp^p0<|HbgCZxAFJv+(v7XG<Qt84vHoms-3hJDZqw=hQ zfH)x5$u?yjBy0@u{i#-6eCi%vZ_FiPVi9&Bv|9X8qCn8Hiq!SlgNW8w7TR7aEerg> z&u_4V*I-IPnKL2m!%H90;$u7!$ebJNH(d00#E$N<Y`u|YkK~kA_;<W@(kN4yv(JAO zVxA75^fBq0)b$>ae3{FW<#ZgY{kWXyyu#!;fgC-dJ3-EtHzT+pU9<MOS-0A(W92%f z&K<M-pa4?biKHNxj!^9m#oWf){1dMj3u(Yu2zqKD&aY2e{Q~uDfhj9eeHx@3gW4Bi zZL_m9M$Rs+$x9p4AjN{T&w;a$obfoz^{@(-dk4-*M=KhP&d^RP$14zp63==UzOGJb zukZI%FW|S&PCeaJ#nz`74P^vXNj;l_C-TAf6_epSfVyJMxmyIm11krosOhCE=06nT z+g2pzVn5KHU3}dpL$+E&HNa%AEQ|6u?xF6K(Pg4_BO9aMUrx(gg`|Ls7gCt|BflLE z_<el{u?(X=@3-i)K8JXG2U#5h+O@8tL@RdfDCB~*fLJRqAoC6*F>eHr`CkbAu^9Qs zHY&Vuuo-`_*41lxf!{q=ZGRf(GXrQMj5L++jn?p^Bk>ls%VwH1Z12ZUmlB+I3rCG= z2^j=3on_7?cSRrtzUGF>6%%;e$w3*nCMmUVGz#AJqN~crsr>$h&H(LuU2>`_rT<KN zWrlj4v4N&HG3VvC^FQKDM$W$;I16mQLf36%;855+XX=d~{V^lkUL9vQWwtPNZ4YtY z0Rql#_rGs`bpH@;qI7vixWs5L5HG&a7b>!+jsIux+wpUP-hXXhgziPAg+@R!GPYi) zq&k5C6bL!#U|Ci&gLz>c1xy3nry5*{1Q*X1S+uP*mT|V&aKDXzLL`hW)w#~v9JPQQ zu&;WNXe^sb%d_5g-P7@pfKf6HnH3?qX&Cm=Sw}o||I#f41pyi1FiacW&{!ZVQ6SwA zIRNrbWH}-|LAqt6`ok;y?Ka%RBF~>!zIa*a0)gs1q|d4q4{~S5Z21~)mAY&_lh~%% z^%a$lxIC4GPDEr(v@b9WNC#xeI7Kkd#(!91p!HIrYN3NAtaw$n_{KT%w{t@zL$W9f zbB4`lUq*`yaJATrl?G(E&@u=>c>#U8&+JGOM{rMMp@4I;R_*SV21o6dUJ@~O*U7Hq zi08e5Ppn+YHzc0K8!{6>G}%VXg`LbjL6(FeQ_h`SIW8p>eZa|PxRXWFbzoe%<b7NM zdo~sNQ8HhtjH@BTi;DCfO?P>>R9b|3t>)^eu|ZPbV2vK-Yv?VtE)%n7gVmx)eBN%& zvO`ktHq!r~6M>$I$-J^stjZn?u(Ohsn|pbvQft%Il6H|eg*rK(aUfaT-iF+=ZIxJS zr})xy|4#Uy3>nIL2~du9om{n!u$Z7qzxX(JTE}@V-Nz2f2kRg^EKG#TGDFKV#`<{v z{GGt;^<bui)^O`C9pO`zL{^pT&~>MgQiF87XBrN`ZpE_uPr_BH&#o4(_&M?D!a!mb zBzJ0h{bgUfD20QJ5FIiE107VGWa!7O`LqPPI|m2-L6@$RP#SctrC`gAy1=9{@f2o- z=K;A>4pq>#q-1E~$6-u8l=M;&Q1oa60hZ%-Ep3^=zYJ?v$>b{ToL{l3Bh4DKkib^7 zd1;|+MFcTxp34sLmIYbV5@rJYETEYr1SUKMdglo)_y&Cj#8qw|I)9EiB}5Vc*B*FQ zorKL1fAhkr7kk|geE18rESIGJsb7r^eqFox9#!qeYh_n9qv5;HIw!$X-+1iZse3n0 zQZHs0CRQ2hydEfDN{RL!bh;Yh`z*VQfa`+!J#sY1g;;JY09Eowm!4AKp>oYftN!F) z*ueo+$Sb)+L2}TTP;o%zSZkS&rExLt3|T>LNXXaE!pzwsaotLY5Yq#RuzR5=0f4DK z{{;|ECvxqg{qm~$S<bVW;{Dg#tb14LHQb@k!%LnUkS(&EBg-Cr<{Z6;T(jrcri}+U zogZ>MM|L^<OtHA%=p0yir<|GE<mTt*7M*PZAAAN&^Qd^|juMv04msY^U`PRDYzEIv zlj@%gXs!=va`7c20_TmG%1dC$S(;WNqf{^V@K;R8pRh~yL!o^<vU{Rzdl?pRZ*+kp zbeSt3sZvk6|47;?99!QnsZx-Q_Q0KI!gkYpQkf_8INfeTHa8l7xmLa~gsR@>QIlf| zQCuy%a3xO)Eo-H3-ttLYw?58+riq5x<v!98W(#V)D?S5#kTn``+5dwsL<z;v2nUxX zW?khe>Gr+Esdn_g1*lRV2F@z?7TbF~^H=vA)SVaja*KiL9#Gh!r>XjWPi;v2^Ilsw zU89VKg)Kg@bg<|PY^fv1zgi&*Uc(mirWu7FdssP&X=*q_jxid-Iu4JwF<IHx_Pgme zx_q^;yq1#s?DIoV9m)7wrj;B&*>Fg`!l$}#SjjJ3IrXT;-YjTBN<C<^h;WC@@GNx* zcqNEqcYTt%-aqp|Hcf4dXrRIqQY96T6>;JIHJwB{8U`_Qm%m!itmqEbRv~GuGmM^+ zl=qw9P%dw*=75Y0@4aB<d6HD^j1p5`q=L76YmK(*c-*GheAJeTR*Y?a#QM@w_*Nul zQBkru(h_BN+;iP}>1D3Tn3<Gy(~{bR1_4y{dUSejA&CY`X1+Z$G`$`fTSpE*d_&_5 z{bXBZgpG>*&<jUV7Qs|CZT$wrGxy!T6Z&4d<|VMuJ$h!<E2bB_KQ8OpDTI4XzUC4E zKf>stO?n7F(IgMb{UoVUc{Gz5K+8uEX0W&UL(kr><u6>Mav1{wCEZ4C2^%qoG$^z= zN1@#t0|S`WXHq(6plgT2EsB}#`AnJhnki~av>X{-6={hfHlH7A4xm~r7ba@Z@b}Z$ zsal0oGh-Kn;uB>%UV1i<6xgLUI!xQ$N$+nx2PJ(UyLk?(jibtM)e`hR&|P0mjIK=m ztLt)vC7x%xxCuxFFf=?r_&Cge@jq$DCTaB%kw2g9$USn`lnGMd{itc>?l~w&Y4E5a zX%V=KrUdnK0!`R)i6a?qPFBj}V7YCsX4gvddj%1`M(IW7U&rACz02l8)RA-KpjCS0 z)~K~a@yy?>wNU2%D;y^mTXPj(S`J(8)eV6)xPXJrSkQJCh<2pU0?Mjy1#@}J!tHCg z$*`eyJ-sJ?n#n4$oY{5a`WAlzKgsSn5uuEA-MlAxve=v@{7t6ZI7fR=TA5vX&)A;D zkz#e_BOzjsUp8oQ2=Y<KH(5D-Edy%BBo$*kzVF@cQ<6N5j%~rhoQ8k>b3W{@u2u$M z6CXqFwI`g1%G&b{$2xSL_oV%FwS<O|c;hW4bmAkRZFn8aS&<M^GH_#-*tklZ1!C(6 z9p#U(D>U}Y!3D3cUGO|??OQN`X4BrH%6O4CTA#AycT$dtJ2>R<DkHjn{^~pxWY4F) z+Nn{L@zF>XnBAuQ^)24hY7qW*ZCX!LIhUkUJ0REh>itTq3yXzJyB-XbXhH{sU}>z} zFJhlh9H)Hy;ALT0MmJ;*?20>S&x1Xf-}((dJDp{gE-fj|4{#Pq!sp4yhJ+rD=l=~F zPoy+kn`zLOyoYwvr)8m_nV^$PkDg&V+77$g?(x3K*r=z4{zut?+8F@J+zofAYCP=) za(KFL%X;!H5d|tRA1d${1zhQEM#r9-zAdbA+S7QY@p#9YYum}-)p{5I`$^2T&_|S5 zFeR6PcO5WNVYs$`_xc>7r!BZyT=95?aA1R>lK5`2&tIhttPX$;dq|s}nxg+n7HouU zaY!&hh6-6Zdhhl(ABpg!_8~KuQi<;|LBF?xUe#D@6exKysi*kgbTFazd@5kT)S)YQ zVooU_ai0G2d6JGjfj{p_sDk_DmRhE`4fPvW%f5~G{JOsVPRxl54ulSJ#kzr$_y)Rn zWs5zkMCHAm4_1$bD8Wd&=WLyhOli|utaA~kiWnNcBwiN7<dW`G3qyHhAHhk|Zegev zgS{TC`H&y7C=%QMn3|p-B(uTVL2%+D)NveI?C;@VFjNb^l%f8C@U=)j-(fn1Y_mQa zf2&_=sWw~kitSy`5Od}k9b?vcX6SL(Cdw+dY2ref765x9h~i@JH7i?p^RDKG&b$<2 z8UTB_JJv(<O;2Yf{=iQfD`{m+M{WgO%okeY0Utd(t`k2Wb-O&}d7Senj53*|D`SD^ zl)EkbFhnL{lW2AI`#aVK32jXDcYkB-GW<O-Mw_cp;L+*~DRH4r9`?^z8gfzY;wo@% zb?x%79#@n+z|`Hr_)kb@Ttlt~ozW7<6*P8OCq`K;6IeB_iiSdRbm<fBP$<_Ov~FGh z^Yqoq334#xXH=JUa_n3+P;0Z`!`3-FG;bTW@n~+=2hcme)GzS)%SF-Jj2Um)>^qqr z<FqTsKi|ienF+=mK`Q|Ry2T7UqTNfOQ&0NG)wnFpWUf4+^Y+f2h(3QmN`s0-FK6$U zy1k;d$q!4jTNN4vBD!mU`6tY7L$8+iO(KjP=sZ`yxhkXLe>Ffn<`s3#Xy`HUA};If zxE@)-S?gLc%07VGnm-0grkPBhy*Cl5)ZB;;FsMG;al2jd?tbC4mjC8?a?GDbYkW|t z&<FDin^IpUY_?Gj7ocf#(or{$-g;d9(0BZ>t+hxDqtlb2L?dazlCW*y%fI475(ip_ zjc?aJw`L7!&eGvKqy%eAj?mdePkkdF$d5wrQ!_I5oc2Kt&6kP{J~qpd9Cma(sYLsH zeD~E8|2_3D5`3sewc9xM&(=8A;s&8%s46)0N!8tmWbSE<P`D8p1f(a`9xmL=N`qp` zAuJr;2nugI6sviM@0IM6?TwwGu~*Wo*tbzPYrD51O>H$^b*GsS0E97RxrUwx7@X;f z#VXnWav&CzizVg&2FNAF*y8<Ke%Z%B_c2j`0x?N)ZknF4EQMHRZPuR168F1eQ-}-C z4m(zAu35q#auiv2vd;VxE@ZQgTc)d-9l1D)Q+9+LJULygyH;=CajrJ-%zNiYIbv|D z#9joJ1mp+`8z>^C9umM1p5NaxG4c<N`gJ3FcnKBsun{(LqfUVK$eou2!u-M`bIgF{ zHc(jrA05qW4#Z-Z56(82G`QcZNIG#E0HYBwEQ3jxG0U_`-Lt?50|Z~KUYp+iHhvx` z87}s=CU5}y8n~~35Rqq`^AiPgUe;9i9#~VNZctje*;S(zvf=MtZXFH{@*aysbL}pH zo4j{soz;NL&PVt0>DJWIrdv7Z`0>R-`GJE{j&`c)s-;)HP7t`ecQ@4XIu=<Rdxvrb z-ul_I@3E{g=?&y<Q7M(a(jG_vo4#`gCSnGy$mf{wt~z1*f#iJ5Tj*wu?s_wVrB}Lt z4uIvHTXQ&w0G0zVa77xIJ{5)BxB}@HbQ!Pz^y?jz-mRztp(l!MH~`M!Aeto57^pv2 z6$|gcfiTXx^l48E3jGz!QCNOIih;5GIEmaF&S`u6spj)5#$!(RBmK|hZ@xGI1-ce; zM8n>|B=nN24xM_*o)B@%&C$#&g7atR#HgyXX*-@R85*J5Akc4sA2{Y2u`R)ak9soa zU79pHSbs-qa**P;*wuvgvm3(Oh4cy2%r#cmtms=dC_w&=@j<_RB^ipQ57>+gXv3yS z0_qp5wrcPf2{og$L2R)$A+2~0p#CrA-D6$JXk&-V;+_C)Q3(Lj>M3k}UQ>8>JmztQ zLl8&F*hMQ>7s`0v)(^YKa<T-47vJgwODbA1-Zp=zu}Thw;TVoxr!bL3^oWI{S%;Fi z!HpD4bB|WLtU0d_*U`W+>K*(ZTs!`K?Std}|1KH2XO}Bp^7);n`thIMxu%8E4(E>- z-K#dhm+Sz{nO4+HP$7rh^~N3Z5mxTRxp!aahm~2q`tzE^Yr#M8dXF&in6qE-HXUX> zo3~jP_GwFiiAN6%D$?v*gyBOF2-2B>1(yvk&Y;4<f_n2@eY%4&D7`*eY=jTEA_Ifd zOAuOyxZ$6jZH9}fO~Qu)?ps)Y;C|oLde#T&o4zeYx39jMb{?k5*nTSgsZ}dWu{aX7 z5>)JF*Q~u+?0Yc@<73&sD29@n;%^xh7H_h#)OD;83qAS<w;TARbM`izoJ<qDWOMwt z#=t>z;A6{}sgkEEhNY5wlAmI;q*=!w86qs7fcyZK?_FNQTKeR5UE6FDN{ggN-=7-# zR>~|L2n-{)rT}oc#elfdA-vj@{AYk>+}%|NJI8xk>zCjAx6rax5C>+1D7TD-(N;Z~ zCd$&R1b;>&eTf*_+O%-0+Y*uHsdkRv3uY-3f5m1i4kLkrz51ilY@f?OH_cnfdg}6D zd->V?myfOeu0oOfHVE3iEd@-MNbwAiF;yH(H58rOK)r~0yf`tteeHo`^a$QZvZ6r^ zn=L+GEhc7i-22pA&9)yj*7PhK{$o0G3r_aU$yvzvRLM-T{gj(QKQMMtpFQjf%A~Z_ zTi%D2NiV7H@e&k?kutF~;l68G|F(xkrz8(u;8@5{IuxDMGD0Aj%avhvAY$ZXJ3Xo} z6SCs#GG<(F>RMo`v?K0+hiCW`jO??h2AeojBA!VGi=HFr$p77_&aG{bXr3Qb^j$$x zqH4t4RU_1#%EvrEW{TbBf<zMAv-nMTbZUnxT<zin2?)`m!}n}j8cFJ$#Y{Dg5WM@9 zI{2|(DB8V;t|1plG+&L2IhW9AfwvqGy|eD5wcjr+8SS8}@K)@^3trS(h01<H03}n( zz$XJX`p;9G+`KHHrbAcd9|Hc`2AP6h=v*iZ2J^)NP+n)c+8H2e2L<E*q{^0D7XuFN zA!NTSWt#ylZpYmu)+`<0_F>{eIoXVIOJ+pjk*F9%Oy2?_@syjX78rYaJlImf37)eX z7k;3ZY27CZcZ`CFg*IBLGVj8#4}EL|<|k8GQtDn+9Ff-K8;e#ZGdV*;YA;kE*gBG3 zv)>c<JjF<5PkxEc;>K_ZFY>{?MyV@bL;(zH>BMa*t!FI)@kb>s-h>*n$KN1;F)^Fa zR4(Lo)HmD@a(^X2GX)TW2H^d`kKi&$@%;NL`gff&)A20GK6&I8i12VV1ql;ib_D!x zkl?A|(bMDe7e|VQZB4p85Y&Irma=9K^-%pX<!&kVB$!+;bsQf|7Lyx&u{V?5FXYfz zE%D$DIrB=AtCi>_v06{EKv~e(-@cQEF9HTtg5qbok3Q_nThCQLPU^BFFi`q!gGv_# z%S^<ffTtx>n@^dI6lQ9hoswW*u`ppwZu>)<>h1MT6rP-0&V*Edu$+TdsCGny9s@M7 zz2AXOoo{7BJK8Mg*2`1wWMM8TjcmiFA1bQEwAwEg<z8D*4hO4ch_4`PBzOQ>{ak0y zTg7!+&V^Z@PL0kERN~c$B}8wW=&<o4L!Ckvd#u62CVe@hre5^u(g43o4-a(o#PyKN zrTD+n`?TEt?29)R3f0PwC0u^t3sZA5yt2&@@~##a`X{JEQ?gmX?4ecZJN>2upEmQI z#Rd&nbGrHc-wAT}q{e5nf@?cR4ic9o8A8x@VF}>gBnU{zuXw{Z{g5SM&sKYN33~5t zSD9eT&C)W%5W~>7meYoOWx8tV0v;bD`&?chIdKA+WqitqH~vM)J1-p2vwZQ}-2KSR zb*ZaAnRrv=!J?|67r*YyD;r=1P{u3bTlkTb3!Cs-WV-0XNvQH~k4x?migi!ZrHS*> zHgw94Xey?kE28)M!S~+#I@wdZjM3o0f9byY`ZZF1IK>WL2|(|a7%%{%9k{F54~Ad4 z4%!Y7Lr@{oBLJ^~rj+P|8*grfJsDW?4%&x?7^w2nqVKCB_UQcwZ$Lp$h3~=2RwWu% zOBB*3Jmxy&F6X4b9YgB=VlRGB@tq{p=j3e6<C-fnYu*vBM)PU^?28*neO5Lkm)!ob zC4AM*<57I(CqCd}O%NoN@X%@lqO%cf@kp?UpDvpJCh}`otr_)mGx+1|pt?jo(gq9t zO^AUp!j^+DH|(@D7zlz+HNwtNqrmVAM3*<{x#>;S*-aeo<l1s}$MOffqQ;CGZ@V}L z=&}fmy2<CVCf`NeMc5yO4nP`*aL~7zS|7MQ8_6BEJ3G+l#Snn={+BN<9+QtrWR`Ws zV7QhmQC8LdU?jj7o3E+$309yISrDZ<;i%}U!P>jc%V5_!2<5MQxFM+1rU4x6M{RQ< zOM>{P(THnSuAcqKO)UkPaEvz(qh1ME8OMROg_Ay%xH82mIB?_s7%1-Cz%{`@^+O0@ zBj>cQ%qPNQZ@RR=0%_}ypabzif`IwNRn9g(U*sw@h}TO9V5%580J5gzeCc2C^B|lc z7q1n%o*egGBZ$}Nkt3ABcMdS_h5`B37~>PR=8tidjMYT~r6%lmeuNC)>dJlmEnJ8d z4EtWZS!-<ay-}N(3wcwGA*9<_^YnAUI9QY%h`JFdG8=$4rMr&g-}@x;7+4k`;V$X4 zsZMIX7Dj@u+V{c+KzmO=`obY=ZF`#+Ka!1Bgq*pkwn)p>!s<Rgow+H5f6jkn?bl<W zXl-1%KSQU=RySGL1hB{~;lMQ3Y@_4g=^{BA1N#0GKY#!bj35py8)metYOcyvh3hM3 z1i=RE0E+|Hs8U&B$BhJXd2z>igG~NCeslu?3`Ana-kfR6#0Y9uZwmky^97%5&zlxn zZp3XytBx+~2pa|}B%VOKg2Z(Ck?z=-o&lV2#|teGI+Vs2wIV7v9d25yjht4`Ckn}| zNc_=y4IRK8XWYYm!Ts4dSN!A;4vX-{ARULq_IR&DaU)P6=r_jXKaM7dv%+ls`t(g) zXot?LbiuMUC2e7y-}t?0SBn6x0kvaWyam(1I@GXA&y=TTwkr^X2mobl<1=i2YScX3 z&4S;Y!j+IQnBZe<3m!O5#$(N?<Ji|lXIc6<Vl(J{Us!(l<9rR$=6o#9XnND!MNB19 zS`aRV84?|1V2l)X`M_ugfIqq#TRtAX^i)BLiZTmSFcb5BG$a}~iW8@!C;`G+#4q9^ zVXG`FN-_Q~_#lX2EyL&Zc3FdO)nuCcZqriSa2Rjapj^H0RcWg9#&qxo9nxF{wYUTU znAzF{iO<y%p927#QaiNfyJD0i56R{(T#9d1yfB7Z6|fVq_3aLZqmu8(;WK@OX-TGX z>eCKqW$kI2K#blLnXi1&^u8wA`joMQx>l?qY8EJsqVuDw3APVEfBN)q=a{SA7(|ec z!W8QrsZ%ot3t0u$&Z<8Jf}5K0;T1thQxL3%AZ9m>+q$mWH70;R=BqLA)pbf^LUc-F zK&hW<efz7pu0pc6h7BCNZbpMxY2B>134(HU%HnP7zRB_KyR->Gi0eVX+FQlPhi*;V zR>WfBg?E7FW8)(SL22mI-+nueY%CXJy5AWNvmHMgK=?j&?<N%dp1D04RA5J!%2r2f zU{Mv<wQrNu&4*CG0jL%cwd5$GNf&Ee87K6s$;7Jjx*O`)9J}_3pal}~4iKxlkp>&s zTlOzH<Q~70oNF0Z8>bb6nX40m4pJW=DK($b+F|0uop5HFyBoxYZxvdmYbcBX4`Bmy zlWZ$D<cn8;8!o#VR+yIfLmp8W6#@MKO~Xen+zhIJBgIfK9m9BnYaYZin|%3JHSevR z*vl1^)c$f#>BzBKKYc@2t7=h`esm2;Y?teQWdASI13!wZ-(M9nT^61EMAxWBp@>K- z2*rO&Y~<-}3`*yfp@USl=;kuim>B$lA$z3l#Ia|bwr)<)MQh<Y>IJgSer}Nx>aWo- z<qr<!891KYmB|Q8>?&eGaSzE5kRTWFuV0qY9#&c`2*cQksh=(`I-se!cVOj2#DgL@ zXgQ|>bL@(dZJD-)$lyV^#bM1Lj(DBr?MVTr929&t{tY;)^u~lgS<Y|+JAcVS)#-MP zX3TE5*xMx0NkVkBW=ze=)KWV!HR67^2`Z<rmzpDHMMnYj0|a7BqovDn(q9eS#J-jd zCXC~yLwWmS2#tqa^{RPS;_psc!N5wb#|+)Y56A5!CXF2T1@juFCCgt|J^#$Bz<Hnb zz?XE|*8YjC>%Q`sYXm?B)@yl;9^vY5C2J_aLt9m=PK%dXU{Jv!K3}YD#8>MZEL|XR zJtZgN-k!L(HeuGKb?B>BT872mNXbZ0ffgP0s$0+*E2;>hDXi>?&OJZUixc%7<CSxD zC5MnSS0wa6h<t2nS54r5upr1U4Q`o!<OzsawU{?oKn*l`e-}rHWrnV6g?_`w>Qiq% zXW8tgSCwHRU3pR*1sZK_VT?{Trn4ETPj1MxSB?n$VV5ro2y(#V^sum=FuHsA0nRD+ zYnj?>xNa4*(t~<!&+xTIAsUP`Gl}KNLuv3DQ%{sm*XE(O;GB0|s!KSbdp!m&%z~}k zqN>?qo>-|}Of)<&TAiQ%AB<c?5a;jR=aHai0gyuAdGu+vN%5u%>Hbnssksf|4!2+( zm1f(1anQ~8)?{SsbDU?K5Ey@^VYkJdf+30UKi}N*_8SQHeG(e8d&w^d)E1~3V`BIf zd-~gcy6E~~A7FQYV4%nuFai$dv-SHD?0e%oBR}FY5?a{3MHd_mW!@NR4;Vp&wB#2m zlB}Zqa5dw%4JNMP<oZh#R~c$f&2q%5au5Qlk1$>lTlD;EKtx4x1iV)+w+f5e(M17l zVPE-e@zTw4?akHScz5bKnuAzWfFP#2B9Q6(S1JK?)|7n8$@Pnytm)L)tc`C_!X42R z@+0GGy87N82mA&+^fhk+1cP|CwsUl?=4vg`NB&Q>{8xI{H<0}HO0CNs$9!bwk1;&s zGfw5MYDO~E7sucI1^phc%ZceaXWHVvu~$Zk6L?ZMX+^QBUubMK(Rv(vPLm<_Bjsvk z#j=rQ^ZYgvvm$C%Eu})#c}+l@t*R;ET$dz@<{ZT_pqQ$Y+ZZ|;6)4bHo$3!KO_jLN zLT`Aak%z^#<O2nn%gBHk-(yKeNWO#@@oh(p%P&NSARr+F0sg4FQT)}M<d-&QUv zCWE*}iuC|@wi6D%b!@TfU-i((emRP1TcduJjmDuoql1yVcD*w@YLDxirjm^ncBq0T zWss0FJ~lP)C@m$vBf1B#{kqAcDR?WmcWqixcC7dG=#9H&etg>gKVY}VJ}Y!cA;vl4 zu)w^_4yj`Ukmdk!c8jQWAPTdxC*}+isv+w4d(vgCH2*y6J&ZDxU(vk1ris;l(D800 zIO9xmXOT+@Mum@?T`Qp2S7Uw5_#eKL#)<F|>IPY4@{qtoM0r=O)5LR_*%kR6kSzJI z?9&zb<rR7GWBKeU6g6!q>K%@?gNwYQ%3M&-N#PmZ{~kBFa!m-w*Q1Toy#0f7=Xq>T z+Gt({L|~xzquIik$b%QR_6K961|1Dx&_K1|E&=HZ66IDcV)P*;+(kG^RD+0~2gI5K z#nkNBmAC?#WQV07*BQ5{@_Z3@%!Fo-YTGsLf4FLpg_X6sP|dNafc9_uNjsjJsoo7- zk81=dfLA`sCeLW^lzJ|P;4M$>nc-WNn+3^z4V3DkOZKctmC>b!`sH?r^3F1s#p?yA z5Zlut26}}0^dAJd`^6@Yr%YpvkJdN9S0D8yjihOwz4g53n|c~r4c{)IrSG0^`W?f& zx^V5ROM6v~`#O@pM7oEF9H$8ZL}U=?uE4Gs2_s-LAll}G1hCQ9S0tui9GM8p`UJaU zGAR3HdE2-o*1u-rzx`UDPZ3|xMjEq!E#!G}G*j|k`|%nnZSZ$!&4H$M4~uJq4Up3& zskO)M$p5aM9R-QK#qPYo?zmLTEw9Mf9BN}HVeFy?QzleEoNMV_j%O4Mb$;VQ3;j3J zZJu)WZ8Uq;51r7G56}EdHT1TJmizZ!zEW+6+MKzS1A^SfRAcKeU^f>OH0V+{Krd)C z_&5Q%k1&@3#8mnP%V>Nz=yGa-sJS*#DPzsCUBZT$+!3dRK>M5n{lYq2Z~ib82u$M= zz@Qyf76Q1!JOvn_jKhS1EVw{7h;6kjNe>=??M&Bk&~zsoaO}lcTT42D25{Ts@mWks zen&)400>Y7UcJnL8#GQ<laX%|Zhv05ll0$i>xmyxJ`WQ9ensE&o_u|X4g-vn+b&v+ zqcnkH&14JAI72JgD9gmzzLf3X2S~W+K9K^>^7uo&8v+Iok^hr%FotnCLrf{@y)%N6 z@#EyIHsN%pNoS}{p_Jj79TjI)$11Ck)l*O2o5%F@9F{_lPAk}Ou<+cj>FzgWc|bC6 zTeuT(MIGtpOXY*q5}8mXe_wXMc-pz28YmkH!m{ZLfw7dd?avj4l42QOU>NFe23~;F zyLoL@5ctMZj|gXwVZeV6=c+JtC=!-PfUd%JW}^AE$|y(vZa|J5`LhLiYQE!ZGhsRr z`%T2`-_GDN<sYoe76c}?IrII&GQohlD|OHwe#??<d9;tG7`+Li$(`Y;tM-t-fK?nO zlR`2P@@UyzYZ6_Dj}Xk1z)`3Lpa7W?FEBxpa?h_`5~#2gg@^CmUQuF~7sdu<;V%LK zB=M@9UCHoJrP@kH0g4(HtL`Q~Qv%03^YIqgcu;~M@Y!|BX^a<z3`R#xvB8&0DSjWY zu9jzwz?_RAy0F9&f<AnIh9PP$JGf)-->FR7<`zvbCk&FRU7Qxyu&lNli4(^@|4Fj| z2?KyQNivFqgQ4%0v4swDyXGjyO0GP>!Y39&5~ylNvVpEC4^pw?(B)I~!xfVxK3OGp zV2;&~^&n?wIB*~KK8M8_!tT5&E!gQ+zEZv*DRr_teSe*mqBILrEE&gGs$N<6r9PCj zYqj(M{oMyuEh)3;i(%P44=2rnIEn!CFskYF9wDz3+4JfYl;*djw603B4RDihLVql6 z_C&uopos&VqPQ84m1_k|l+mrHhLX|qf#&WevPCAM63g87{WU*`mnVs{d7kHG=Hxk} zp%HO_<hqkU!Mo`?6XjBv2P9X%8b%ZM3;1%Di|};o$M$kN)?+}~pW0%Vw<kjGmk2<= z#>$=8dJ&_JHS^iHotKXYy>Dv<5vjxciR514d$&-^#X`ez<zneDIZX{lI5FSD)sLjj z7s_`!0}>ledUO8lw^wl0!>)}4H|gL>@GVcolw2&ug$MQq3Lw4Xj-Ge$p4cpCwb!lt zVAS_pEQ;|4vMdY?$t*vEK=@rx9o++JkAlT~wXueT5pUn={XvATteYYNEGm>{Gy8oc zR40<h42{>ZL$OQkkh>+&;zuT<{w_5a@0*`8(LmNAE3Xw1q7rl#nZo)#3l8sxP;i-T zg4iY2{9xN^Z}x~5R_<{Xl@T;x4q%bTNM6L{ON!~f))*mp?w$PG7w-o&V~hpT>Zc+1 zuDFr$Nkx^ExBAVO8lOPaaFsuRwg-$q5I~{gs_d<|A{UkiWp}vgW^dc?$C;(c>{9rE zuSktUuLk8E9%Hf@q6}a$)AgHbfH(g@TK24pl1f|vk<)Ncu9d6}8x5e$@u<?bLD{fC z=R~<-84CktJJqG<aJM~AwiXZG`24<M+B`v5|0O&CC_7qiw*nP3Ac<AlyXfljj$@4y z@aIV*CAkUqKC9}8ynP(2cwxtDOQ&ps@*qBu+m(4Ro?@jhwS*B*cJD2`Ih+{Wgy^tB zCw*1|Xf#LRfE<&>I8NsHFzacxNVM5n!8eIvv&H_rGcfXrELSQqG62VsIBBV5OegrG z((J$i-g?;$l1SWPI;U0<KPpYxW*~DEsj;K_7YQvkWgk>*ZCeZki=5qWJ|w8>sp|&v zt3w(iMGH&&P$RgY1BWKtg$<lqXK*%!yrO@IC^_l+7=FE>1yEg+uF1+r#B|jo9ez=j z4HB+mR&npD64^Gn40kFz(vnlAr#&vlDli|_2YSR@52@PZA#5hPK^Wc;FVG8UjS;ZX zi5nKB-Cn{TVVE90;q5Yf<Y%BzG&@*&N#&zacfZK#wlsHlBJ~fiT0Y<M1PCeNV_6l_ zEEXVQRf>X%h#opveBTB0Y23Y=|LenV%a)gEowL&1Z@eZHJ6uW<>v4UfaY-vPZm0Qx zruJ$4wbc)HjO@|3Oa+;V?Te01mzrI#^}>#|V4>7`=2iYjl@T~{Q!mu@(m+mccB7#a zZwgtcWgl7CuBY_;7bhv$eP$c8E_i-zB!%gGv0wBQKFdubSUF3c8KtcxphFXy1U<M) z-E;438&fdf{vwjVE|LGUJ$&R}pvYOMy=+y|$v^H(UC>L7>aoRK=$H~aPrUXT4BkXI zQ#r~UZ-s$v8FsE;OMVzn_5cB41?OGa_h7cM9x1MVMP2NzN7wJN#hPoT?drUE`AdtY z>fV-RhwZ#Indr11!i%qfaIBgDO;`2>i&_<?V2y}o+hEOs@s2GcPd`{YPJGbp?HkZ? zXib-Z1Za7huf7%|XwW302QTWH<(|<@cFKXOpkQVMWl0HffHuC0cqsw6Oj#dpq<f#1 z5Cz_;7`c6AZBfN`<OaQ&S>kLBI3@)$ZU<}e5LJkDQ|w8X{p3SoXwnH20(%!)N0I?$ z_PuzDPMS%l+Ue%dG_FAW$?npiY43qAp)Qn5sxeyh&M?}4yr(GXn-9#2SXRk69t>-~ z`t+|@E!_<}1@efzATmSP0QZU~?l$RD#dG^GirI-aRF8^`9i2%QaEB#LRACM)QY5hn z7KRk>d+RQ6D&!A@cCr^d$yhdhF0h$-WOfA`#VU~p2){FB$Wv$gj5m+SsdN^WIx%;S zb+G;7Nz*VOBH}+aFDn~VzIyaJI3x$16-}HDu{_juwu(sqAitsM3jSPwJnT~P1=S*$ z+3VgWYO75ME-+1SenphU`uRX$`t(@(hOIiBEHB;<QI=q=eFX3I-kEl@D_3HEtdxWJ z|6AlKIg!&7tT8ga=FWD7;CWQGRY<Nw2}tC<2&)M`<_Oa1eB+voyj}N~f`To2e&cz2 z34+5PJ^(>BQi>k5d+9tTcXFlm@qTH^O2Y!Fex;~CLO4+VljG-MB=hU*OZuNg2Tp5& z&i_jjO&$?NW*@?Ec&~&ru{+oCDok{|yB;YHk+uvv$qrw{n=KS-C2(b*S*lLn^3Z*z zS;M5$Zk=J&IR`5yfa5&1kRb{o5FWBTyxj-3A`ky!quhRWJx%1@w$}@S(07{GvF9S% zyFo|l4Yf<Gg`J%qpAzYA5MvMFbU_D6#1Na<)RtlT>AlWW9^wIbzi-U}vC$$Aowa>7 zp)8>~fKEGKaP2&l2unGLI#-G(yW#(mB+oNkFX&x}gC+M;VcohA87^OC0E~r^IaPlY z(iooILCbYUrcLrnPae|!f=EHr$$F^AYnoKRrLlo$VOmZqBUL%w7M}!()rSNO8_Ctl z6ObT8tOidkc!L{d@q=MO6rLjp^HhuMVT6}x-UAK7S{Wj)KZ3t}3nGkUuP0!55vY^v z8m6TToS`##DiG!b6>vq&Ki7BT7);LaygDFOHhmx_Ko#CDJG6$7qlSXxLJvPQ&PzDG znTg1<vBy)7hHu2Ir)MN8UHEE!;d8Qk*53AoOUqDcHnembwy>k#Ih0SN^X2Um!r6xs z-H=TvI>$PcnTB}hF878QcoF7;Mn($n$T`v!Y$=gZAgFAKINnA+V%-z2n;PnZfW&LW zQiT&-ty{w-m)k_YBZSu3-kUU$Gt6^GnxeGBg(V5O@cxT39JQ$fwmkI1n#<I1CxmRb zZEM&mIP$=Ir05&>bV+QeyC;%!;B@@E0J#ReuSy;tBv@dqNwG!Tzfkhok<(|xN#K-> z|46V)lYFwbk_F<)*>4rY;VAkxuf#UrDK|uuYeb5h;>4wBJwrwD-iXsv5&K)waO+F< zm;{#ytA<Be0EKY%r&9qB@O!UXP5Qf)794<4fEqSJ-?m7gL%8OR$Sx;M^-<0}R^`2s zpikQ(ix|+)P5_~U@fl9?KYciAjcQ1N*h-)TP-@SekxsFvOs7-VcUi>t=&Q<R32r6k zZ!YJ3J;W#r{}FG(!i24Sm-rim{}e9s&xn>23wLCL?3X3eV5m+-JUUSC_xnSF-7sYU zn%I=SL5)b*mPIEc&k_q?4_KbRq^~yY2&ao4ZG%p`KwTC@(e2__vo6+1rrMUA)qIZz z2LeCQxi`H~7j}exQ1-(*mD*=cw2l~z(T*rcS%-DvX5QhzE7UnLRK>58jw)7mVxrH> z=wKpItQ_&Okx1Orm0(Y&H>0#)rJUbTA>mM{CtoCfM%YKeC0T?xHlKPL0-nkSOX%=c zvS9)n=g+(=#r}_?v+!!_VFU18Z{!`_jPCAqqgz@)P)cb9qy*H_qen=Cqf-Q=L8a6o zpn!;gpp>)<ii-8)<NFuxJ-cV`d!F}sgsp~{(E((Lln~3)JTO<#V?&UyaD-yIhkaid z&7BIea7muKQF%2VFEv~lAOwox@Vy9td-WV^FmrYyAd-e7kg5s@j8<#(pR5^vu7)vI zF%GX+$+_5+HN}44z@YHnP!De{ALT!l)l$}MRyX4xUE#bU=HJZDK7GUEV}W6bs8ZpN zh_xL>hWVsW!`iQc*Y#&O65P>~3hutFB6nZc=G5a7R(-AmP$_rRT?)soU7ibZwILsq zU;+?7K#n{@ik6fZSGua`AnSKZu`>NlL1T@q#6h+ATPlL*Z8&8zOF(i7DB$0S@c=Rp z882e1%bRe2rWy9-8TPFie_J;>6oP%6?GGARPeC+tnpF-1{51%2Q!7D3Wcs-xFf$oA zG~npiz;n_(#Kp|%oJ4%h{;Y|RtnYSREE4u2DeYU!dp}T*08V3>Zx-JBa7Dz!jODEh zn5}@$B%)2)Aab7EKemMb^f6udjUv}6-XfyXr)`oCK@(5Z+!bwn0A<bQf%YFE?#c&} zJwifj5})C1Qo})jd~UlK_+qy@J31)WuyI-p9Jd8-9JZwkx3}GF{}bH4zRGY&VI(+X zsbb*G#Hz`&1lOs5$HS&xMCA>=jgE@li<7-f0>$8$HHqgAnU#rrrcGAsihKoM*$qRr zu>!a4;YtTp>dp4N&6_P>a$EI>J72C{ooKeSDYeYq$g<QzXA{u|){rml=wx!1M?kGp zNvB?=dZasA3J*=Tc4I7P0R^zLUG;>J9w`q*fit*@EXQ#&2N7h-#lfU>{(AGqzoX~n z{G3mT&N&mf4R?Y3i{QicD)ewWIs-SFYZhYPkMM|*&26q;R~_7g$qolSV9#_$4v4lh zRs6WX()n<ucR*1I%LIwbjJkjhx%xC<&?JUqTJySlbLZ6lC_>;-(2K$8qfThu?QAmg z^*Sv46eRD`JjP(_uSgg|bIv>~&{+kFA{{obqsA-^{768SAz6+~K^B)QD~>GpBv=F} zk~CUF2nE<_a21m@%RUkOe#kg#Y+Paf+z`^QRV|&Db{=q#k!XYBRC+Nvra~l8B_1x} z5aG$fvgtTLC&{93t8OJ(aA12u!{I{sl~H@H$82xaAAQr>M`;8`+`E>>p}Rczcr;}x z7b1R$j9oxAdlw|fWf35TGB;2KZz19!n)EATS1L!TnzE8xQ!*m+?VW^yjgf6#WvVN` zk4H?kILHT9iNy#)Z2)nyv97}NTdp8&%Mk0Z3#c7d_M++j34`i9^cj>zyD;DU6a&b_ zm;Eb!B4q=gam7~5Dec*?>v~4#IAbj|?N}@8_Y^6ShvWAGc~k8Mzc6)YtgC-WzpXvU z^m2djfnv9lB3iEvB7uj;QL^dOS?DBY?B`Gk0D{LFmVnomPiRTkP|uL?_}TwZDku7` zczIda6{Y=t!BjT2=~QI;FgotyyOx;E4Ax@+FpoQX)lycLESM3KKUh^664>X{Y^ij& z7=2B6#+H>Zj-F9lU$1wh*1TrLD)8K1h!cK$G!61<Ux3Jcpap`j7$2Y?C&!@^+K}SY z5HYgMe}x>$i)Q>Oym20iK6t1w8F{t}(AQ#NR##$v<~sJ<G`jSb*(nDz@3S)2Bmepd zh{dB`)^^rbzc>2BET7~VfwnUZ9U~Nyao>`qJA#>U6>y~orne!_(E%rPGH8Ja8&3Xo z7jQ;<p4Fom`VY$kv0JUucH@a29ALWk2TTZY3;#FWtIc9ed;j;M79y4PcwWn=QTV+- z%D^3(V*vLH?oM`B^!hWNJtFI+C31rd7YCr`hiBUH7N#O?b+;9ShZ0-&14lnZ?jV!- zp%OobF7&7e;gPFgvvgUfk#i^)p%Ac`@s5t^T}zzHppmh_?Kg-@dX8Y=;v=TXb;utq zo-gUuLU#r*M3q{5C1rys;3S~24R^X8K9dwKuoZSf=Y*e5gZdLI@BghZKXO|yAN9Vd zOT)$-8yu1<kFp{{1;`KqYj_YDd4q^boQ_Hd>XPMAb!sqiB9zY>(JU;H?u1R}WZq`G ziq4vsszjJ6F};d?$f!G4VuHuVwP_YgO8hYrgX)^5;>2&WvO|Gxbz>dO?gftk(7Kw{ zL)Bu%MkXHW-R>mTTUO1>tfKeOFy!tYfn7Xy8(Qgi!(4sA&2PV%*Zgt!)vXm(?HB2p zqb&anY7UZ2-YL%?p%UBb{3r;+>5o!Gh>SH%bQK~l4^yJ>^SZ+vr;&X^5&~jz$ZOYJ zSeSpOWj2YiOgA!_toG{-1!*umw=kvt3X%MCs^Ez@x^c<^Sqk1YP{>o;ic$YXe`+1b zu#Wqq%QD>th-k6o=q&S#u-FtVvpinLui<r={bzU^<~g4|knQn~*i=R2Jf$0q#APvj z+EiUuv}HKhjGdran?A1V_Hjp8x4{ip;nu700C}|g0xAOF1N)})6hoPvH)Cs8{Zqg@ zR?if2Qqh&mtRd%*Wbv9kI^09KKN*0wrZ4;fhYAW(4{Zbg9@5X?Y{q_ux$!d#ePt}g z10wtH;s>Yd^)`HR$}l!EL@l*t)t#%`tD)^e5pjH8?gP%=E4y0}?-xj6k5}}Y_pSb0 zq3~!&t~BPJj~saoI^B-cy3P@aLlI7&Fd<&nztHC^>Ubz$D}l?2K+J6573SF_ujm~f z|DJTpJd2}_@EdwD|Ahk@ApinTW1jE>4+(elU<7l$hMqJ2K1{D$@*0){Ej9wL@iUvT zc`A6s8)a_jwg1%fzbn=v;X%&1oZ+{##eR>U`8ji(#p4#yFDK{UE0z@o<TIXbMqLf{ z(Y{{Vvdis3n92M_0|Gz>MreAKAcd^vNes1iXO1(6vxT7XXaJ|nvn0<^oixNM0j~f} zpm=l~kE%UO?<x^yfBL??#`*P@WtoQa?~U<?ANpedb~|iDelD}BF}=Gr82M`Di3Svu zZX1UXQ3c|X^Q%#06p+bwintUeo^v%n325S(t1@(F2QJaE3F~i77AyPlw65*9O%XIg zx6nMXZ4AT_<o<#O9kIP!E9c0f&h@4u@rCrCz^%b!+_o-*+{V}q`LDdC;SAe>-wJCl z#kJ9Aaf-`ZaP%QpS{*Jv#Eg+l$pFP<-rb2uO}_&U8QL=gn1#`aZ9^jPpo*^RmzV6_ zbq{}KENxuKEYrGka`=7!rw)JQ$>G^=v)4%S4NCdGr;2ZtX9fq*K%j8b{ocdjuH~ZD z<E9l!YEmu1`;>S9?UkXh*Pkx(*i~zXeh3P~XQkO|1*!n{36l(QI4#SLNqMPEQQeav zI)J;Ux&2w$=TmWd6&$bLQQer+SMr0$p4F)teKcPM)#5}g%qhu|p23(kl8HYuP8aH~ zabI$8sHvnu5zQO-H}$%uD#UkhDrUiJ`(AX_E)ob|U2C+|)%n)S2xA!fLZJbi8WWn~ zdVazzwoV>W+}FepMP>5TeK8MtN|^KjQE!aC=v{4ew@N6Dg~3w>DMg1kL9YV_b{iP* zOt-7F-NBh&DaRo$S=fehnbCiW;z6HFPgH_eSvsezdZwxYvrSBZSebjUdg)`cm!k3^ zl5;pTkNiW&(2e~@vAE^Nl;Y?En|jx%>m}!LKB9oTb)4u4TRqDl9EVTnZ=&|5Db^O4 zl`@@vWodmUIU79ZW&RHYKzdEqdS*-eqqb*GVQ7^Jvw`pdvKY*E{u$5LUV}H_#qXX^ zBvm`Ay!T6{Mv@nq&`VuBaCeu0IObM#8W<+t2Sv4rC&`<BJ&yymt;caOjW+-QCa6w& z95wJ5V|92u{G9I=b*--K&f!do&VzT3%$6Zdtr9Q*)M-4IJK`;2n=(=*fiZ{37u8CL z9E9m5Z&ziGduOjS3l__WVjTqh{1<UrvKM|SB$zR9O1zXhKl7DECBnquMQV9*?SNj_ zl&DWk*1Q0Px5M7NU7m@W0z)iyS7jUMttHkomh@KzBW7K2t?wc#Znh4;OcAR-ITc80 zh<xdBp8r-wO5y(JvnVGHg_}-ItmkGGN6Ka+-7jWl2u1Y{A$)cyNlnDywcZME)wu!T zX3?i53n_xna~=EwP0|!B-r9=x3&@b=Z<tI%{ANo$O)YTuy_kaJkNbOtpJI@lYqe+4 zZ=jnnL3()jizbvQp^PZ3R?GlQ)(;-YzlzaHWG<VlW(X(yaKCFaj)^$Y4vB?B7{u>c z;@cWHBF1s9{vZB02|npqtufO{m?!iTxoP99ajjaUF>Sa8bvz?pW$}$I-?wLKKN>Ry z^eozJee!I(Af^naj#JcNZZQYyo&Mp=>~}=TOkCc<aG3d*_dc-Ne-oEaQN;rEh_A$E zR(I$k;WhT=g8pHHu@1fwr9#blR1E;y6)kt|jv=ft98q&Zi(2`)yVKZGA=fQLm`yC# z5UB#Ec^yi+SoQ|tgArC^cPVSw`!)%g6?S5&snc)hYjV)Jp2@mchsPfyY2SN0adlz{ zVY%dzj5ZfKO_LCgaV@FG*KL8-Sz!o;b-l7iBY6prln(|m(;e5KyTVdBi=#1zaME7d zGqtak4Bedhu3w^_p94h9Kk_DCdpS&FM)4)PB1z^s+N2M}HodsjED;e4VTH&#?(-k7 z7EfxE0OQ&`C9X|kJq?>xM<X)=8J;y;wrn}#oFn`uECc3zT0o$%)LKDsdU857cMnj2 zxrceJ(Q7tf%hZ-ksu8qdMz6?Q$KBGXx%HXc@Uv!HKlY%Jf0JUQ^B;sUs`KvonPzc8 zhQqTGl`$@9WC*E_7d6C;oy`gCmcrk4jkjJ3EGSa1J1O2D5rG%8HckiWlB9jQce7A^ zS5@9Qa?pIWH!wzQTT)FQ(yN+w3&8P;LiuD_nupR?$0ZFrYee#Yzr?8#HwnOeyz%ao z0I$>dIS6^a8L|pQojjjE-qTj^Ym``qz0x@Lc;tV^zHJ|-U>^+Bsr^gfV3x;+HEw}p zXV{VpcAw?p6*7G4!EHv<8q28H1xtKmwB_{Gwx_%(OSqhf)7oFZdo)TK#k_5v_q$R9 zzE&~gm!6saXI@t)X{$%_HdD{np&I^;Ag?b8TZlr2bc+MPPA+&J(isk14Sg?k_V@ok zVv6SBT9&|97_jy9sO0akV@Md~QQTA08+z7*W=m(Gr*COS@#Z`%Y;?eZ0f)nk-((u~ z3K>zEX~{TPDEw%?RQ(q#$^Ihqn~_QTfVy!Tw+Z8fv+^m!O{RRHg)A`xw?mHa1>e?U zgYn8dJ%)q8fgi{uZ6?CG;ESl)AR{Ov0#j07e}d7Bhixf3pv=dc8S52RH@5k9rj2u- zN2;LFEU>T*pvpR47cf|ykzPyFk7_#|VO`Ji#rClz{5E%Jl%#8tj<ZenG-rOK-l`Ha zh(m_!dAJW3YiVR&<-6{w^m55t&#rvMwzI^x<XG0v4ql|6hEmx+e%%Lcti;o}_e2US zzX|#i#<&Q}zOhhkwRvJ(vD*IP*7cP890~xithJ!GIJ@%g-zyVLrwm`Oe59mdd@Wn& z#{_{6(XxJwl2RZzpdDlH|HIt2*HRYRVU%s!FF&QZF!z?eW0Y0F+d)4|;(f(oAuz=2 z?8xEV=9m}-xF6|C<<5tQ{3ZQMW{w&8mVG@~pXYOQ;apeVbn#yya8rx)cr`tb>^Rf> z#5{}9%HlYJM%K=?)x_nPeW&4+3oZ+b$W6YR)<Q4P^-<yH?~Pohli(Zb#X(2*D~!1& z6y_LpL;ao^UMWzvi@VPwx<r>A$_xCpyLMG^D3R?_)b=h15X1HL{ILgP|NO>W!<Q`l zRoe{_qer6W4_*;M7vqf>f8xg12u`tn%>8e5?l@RGZQM;&T5=>chGXu!y`%%^ZMpwQ zUk|w4%g?<SJgqtb-N=*dyb(uX{(>xKD^xPPDahi6J2ScoZTo?8GRDc}>?G7d_e`t+ z|B4;+PNmNIeKnhX6wW^zXU-UlSBK4ET2tW}RcYKyI(1$c<3>zYQT=-?)M%+`h*R0C z8G~|8-+Dc;llPeMEABL3NJtwBEFS9m|9Px?v#*p$Un+R+Y7A|65xK(a3FCldODKAI zQF5gby<VkAE>TZeWh{{AUy&L*+rR%lQI6X|-BCwratab(SKKBJNw#31a3BbXOZMvc zDcPJrtcq-Yklm*K;44j=yo3RFzo4+{#MeIN%}l(Vs_rP~?hSMq4B(g?-X9(Qgwswq zc|0&p3ozm6AT=*XGV29}8(*aUx1?V}(JqJ@_+T?2r-1%Q19_FM26$tjZKVpad`%mj zN8(-a5Bq=m8lDm0H{|0WZ4BJAsfLX;M&q@2uq27<(ck7Hc^xEuX3Zg+8VgR*r0IO| z>3bzRO2u3Trzyd_IulBFt5a+AB!y>m&*CneEq%4N1$uN!kMy4;tY+eB3cR?L3)J=g z_G2W!6@GNj`p+wsE1DQ`1i1kaUq5^rdh=-lz!)`+iW<_qhE6#XJqQY!ltj_o@QwS^ zR*61CW5$8${YNoX>K>CAsZo;DYo;^`e+pXkZ|XD4@qwwYf>*xs2YQz)5eX0)N@zym zpuBOZo_1Xa#yplbLbxa5xJ{t5yoMyrQ<N_mt^6^btA&Gk=cIm@L=3J>gW&<K2HDij zo(qGh!564ohqAy)vTp<G7STlE;6++PtA@!aBC5A@>3ISUl1nXRMK^k|kWBjG*wVyG z@Or0LwO^2xhAr|znW*vbWohx8$H~qGuN24hCrx!V3xNK~i8+S7>c=`aNb$Y&a@H0_ z2l-u5#veG!T1G~h-j%~_)c*MQkf*upHPEM8($mdEVuwHo77g!3aC@0Q_+@52k-|?? z6)VqOK}EH~UzVTM1E%3<6aAV6vC}BE66*m|4UpeS031yH2W22pv<hF`Yh33qqZW&5 zXw*p>lnGY{+0)z`1AmQS`ie~D;?vLN@h*jsEQLn|$JkB=QiB9!C%K>fO|Po=P)LYk zAcmsP#%N|LL*%ORR$%P|7W8)@8^@Fughy42KOni7cY8~PHN-)B3om6b#0ATq_IntX z9<l>i2^;A~Z`Y|b4u+etgA;;033#!>#Bp8P>SWHbV!iYE&6!i148h;D=(%l$=-W!$ zpy!T@?|P?#%<ccUy5mecy$lqhN1n8KV)C3=26pR*Uo>oD`Ejc+6kDvL7Ta%(>j`P1 zB34sENyvD+6qhi&l%m4Dv($+=&{4|p5Jt>Qdq9^_^?PYTjukA48c35jZTZ^!A{xy! za__rT&-(`SHtnpa;rTysfnOHJW}WBFT2k%aq!u2}SgzQVm^@B9982p}ghGHg2-#Q* zeai6~aRn2XD+@#=zKKb>xn_6%bt_+J_F>ec+fIeStNokHc3$DkN}K3YXBS{NxAf9| zGy>6>4Um8M@wfJ#t3In2?DYP#6(%!l;O!oxOw$PKEn>B)uUf{SuonW43__&pP!g7w z7N)1l>ElXz3AmyjA?uB=k5ZN5uJJOLnp7Yb4Bgt=xl8BOl3uGLfX^P;dkPcLfO>43 zQ^`q+A=*B{sX}k1fnkW|eV$y3Q=F-P4_B15Y&hDbyd@s<ifPRLxs;l($D6?cj6(W_ z+BT!AAhrbpx+1+G$?4pnmMRj$KzS!OY%#JX1VVYqob;wF;uUqwq`M|hxzd1PC=oIg z$5WN9%DVWdf8=&EsqHVSe?8?kF@=2P;#P>&75O-)P;`(b=9E22d4E~ODCpkvS@oV# zxqLxdVT<^_yn$@yk$*gWk#61Mzmz`V>&m^Jmkqh%=I+TVPL1EU_q2N(Hih}KLE<6_ zXHy+gR^Rk50!p`JqpNFE%-ILOb7j<~${))zd_;wt)ZTHj@^Z*?fD!MQBp^&iMQv>q zOr?LlD6Rin$oYLDXt=j*nn_r^<f=B>%A53GXyd~j8+70OGSJfD<8m5a%-{Z8Cv{Ht zVJZ_>8AYhQ-Cej%p0w{~R$FXSrf!&^F16iN*>N9zYhp$Bh{5}*UI8&BG8lDRUL>Z7 z?+$3=^$4|{hy<xG5-7Ddxf}Y!NW1hPQDM1uu6Mop`DrO$ARq2jvLh$?1~dJsPtKgC z=S1n*gvYZ1ndLpslYbY!bYW6`jf58@HyUi>b|j(gkhsPwBU-++QUNB8*S7?jw|^Hb z!yByR(Fh~=&~aI$uF3isDuS94y_$U8#9ZgDW4F%xJH814NnOBSv3}=N`qk|07b>OT zg^M3cji*vQCOTd}YWm>b=%1SXlfIKv^>P_`mh-kZ%UMDAWX<4rrj&|6pBDO$%!Ouz zg{Otn6z%w8;-$tMwWa&1umw4q@9U~qs~!hO8eLSlHG2f-#37n-@H=XI3@M^NL#zE- zpMJRvlt|zpd;T>jwU!XXak1&Hh~fzSTAOEgR;T{<k97|&RM^n+TW$V)lPWQ8?@PBn zdmsIr*Lz&gGjpdL_RHMs690%{D+}1X7J?S<pt+-I*Vo7p^No1L{bMUugvj6<=eSzu zt`jNF?Z1kODZ;oMc&3YZZGJC80u5YMUUA@73sJx*+<q-xj8C2XRHP^!?9MYt)3Fy5 z4~8CP8pV;J625+gt?0tren635Nw;4O#jk*^a%7On@?}SyKoM)`K%4ctNL@WdLskL` ztj&0(khmC!(qdZCahgOmcNIDn^!LN<(BXxyT8u0UO%>2f8oT%#=csf{gtjp#HC8@h zwM!va#`w1+a5TR8<P{oD`kdeL$V%e$5AP;5!9mj5?+5L6t3qIMLpfu!_d9|0)WiEt zT}!LKd7o_h{(;)n6+c*Of7x(blUOAJSGVzOdnBbz()s1z>ZsB*iWwAS{1%*Yn`*6k z^@=XhJfo#2Z6W*OR}(VLxKTK1@O?pP*UUI{?=>&aFCEodeBhW7jo&j&D*m&!aF$2< zftEJIzklYBS&IG(QcEEF=xhaUH>9H5%o3<2YVxRc%b*9!CI#rO{#s@&n<160Jyj71 zWc6v9_*}j^>DKQC&gd7{SGY?)*|HY2+{}MdLbYL^PffPI_K8Cj(_>4#``HvxHb*zv z^hog&Ly@PbgxnER`>e{Xy}-64g;RUovz1)R&jzO-5!?^1>XgdUxU`~<Rx9SN@!i-- zfCcyV22KNYDj8QbnK@ib0jW%>#y8r!1-?c%y6we#yv^SW3_FsUJ=ZMRED|0qtx1wu zUN6=D_t}uQxmmsC<oD{O&MZ_o(R{TcK04$e^kZ7@$N7SH506r``z|_^1m)bK0T$l< zX&bt1c*DSBF^{?d@Oz|)KNJ2^TEn4wzJ~w#mEaGD=f%&Rfk?;Utjd(?FwZ>W=jGRG zqv|KT)(2Ym3oU6Hy+`kqOnfr}6scLoPFK{k*?)GYUerZJ0dlu-`yD^F@5ra9;elP2 zmdi3yqmsw^Pil{`=p2q4Uv$x@`$5OqqI=$1fzD5ZgYJAqsHI!^q*|Ru?C_PXEo_$H z*Go*?-pEXUsKdA^q3fH`bfEiQFbN7kyc@oEf88rP>2a3L4)SGe=XpQ3g*n^f`yR$Y z+}}h0yC{&NSNq2#=@ZjxGg`Fu;O6Y-Y|-)fPXS>U*SJ~H`Nt8oAF_gd4u1=9QM*6K zhlka;k3cgcBHuX_;8~=Mj+!LguiWImrPjc4o<>%>_F6Eink3$8C0^gq>I$ZMzU9KS z72YaVNpN4hrI;F-cWKq*p68F*>N6_wcXZ9dC5mY0zmfc)b1~+N4?6kJ#3i#O_>nxC z)~eRj!K<mhK3uUSmTVJVrwJxcJ4b3lB#2y81{K1mipZz(x3Bxv9%=qcz5~$cZttZ9 z#o;0B1q&wIPR`ffY}7B~<^S1s?c>XW2YT<lnf;*Nt2A=5Z}6g-U;55J?x&$|9$@}{ zvNEbV2U&?;@kw>HZH22C7U1nSkBpThi1ZDK-*saX`oo_V+8vS}4RpM7xsb;#w1@!# zPARRF6L-?vH^-Q~*qW333(;{$cw@8W+QTS(-L<<u%-_}ig=sybN**3vw_nKc`B)-w zO5JGS3q7;b$wL!SPzVmdRnBSw^o)8L;vs@h)7a!ZCmTY9jMIPW#?xU|D~7U}zJ1(( z%lNVH#$T$9l+PEQ7pGaO*VjA!W<B&n{MhK!ckq<N1Xk5E6cRd=%FKMB1(>dS`jkrr zw@##bHRJh#C^X#DMjC8qO`=TQB%?11`a_~>i&)n)xq-mdE|c##dqCV89j1v*#Djd= zVXMGdzafrQR9xFP7%~DuZ=sKWUfX{6vf^CAe6NzQUoQLiT{{e8h0g7F-F<)9qg8`4 z>L4d@`Lm7g3#M$oDX=}ka2N$SU&94kr;Aew)Mi&_m&)1&H*5_q&If)<z4F`z&OLL@ zksI{@>MI+p0sO$`2&EJ$Z+KBrw0s8mGuk)^x)RP#A;PZNyZCW5*0`MeZtXQ?p<J2I z7{~k=aZ14lpc99n`JDDPUQme$(1VFnZ2Gd41!5+2ulD)68?fNOZmc`@)Xm6ut!O?F z?_O`?_~sD@Hk$PlBF9~XhD8sJ4QV?o$1k#DulyEhgRB0gB8lf%LKm+@BIE66gV?*g z&+E*Pzh!IwcVd@Uczr1!X~3-u3|pGZYUJ2a4IOIiKk?4F-q3%67Rrb)h1VFkT5dXI zm+MH9qfih(-f+}Mk!iY8zOjlJR4sTp){H&^3}GfX=Hnx-_LklS{(b|?9?q69m-f8( zXVwLdzr9jhCV6FR9v-+fw_}4aIb{g+=0zhb$NX&ri5dW~w=vz^Hh5Khp|B@3$l$cP zS2dM;*XWJ2rgyX?lxyY^^%G{sR`_fR^WX!BP9$#hg`9GIo5gt9w#VPBI-U!b$s4$b z7GTW+TXz{WX69b!meP390i3i4V)+JSUJ>gjOr}zwVxSJ@LET(uUyh6&D5b%$;CA=j z$=P9Puxbk;FI>;!7vR}-8`GJOH+@4(%oT!y>r~JX1Hc*RYA@bh7~0Ef;k@y0%a=~g z!X^>hdNo_;!I9Uir*3c4vUGdPhePxLd-_^~k&x-(MpGkiWjj&5nvU+6r-!?B=U#^= z(32jIpU~r<ks2KK`1o>SlK49>*jF0`e0>zne_Uy3PisGfw04zvHy`+r;Z$rvwJ|J9 z_oMQTmAPcsrRJpdM93Tjkhbnwfu?@;CJBDMpZ~$+>s`-!>GN}+der$hgDRN}uRY2j z-45V;HR)jGJq_4T{366p)raK@$kW>(Ioz!w!KlVGem&&o#Z-LL_WLLM$aUd}FY?SP zvtbOUoD)I4e)<N9+m%nz-Y|iY!f^&q<tK)TF8bUb3_;_ZFCJf_xyR>jx(Mft+-h>; zkjQcWTcAtAA>+R=^LmStB}vxw5Ck4z2!!D7_y$>^d8&w)-sZG>>|R*2&eMdii^i^c z1sT+2LIpgDeGZupC`d820zSN9x|w9Cb$O6_;r?SFGkC(ZGTnvcR5z1HHjA&5hen}L zFBN~q*Qnp5!YJ`ULKId|p!%No4ibRTxkGHGlLNau`z7?gngiONiQa|T*Q_T!nKaQX zLY%lMgE3lOXay|YHow6TH2BqFQZdHC@qaW}f0WH|exXsNm1K8)l0=c*Zq)2ZNq9R; z!fY8z`u)NJ(Xfr@g4L4o%H}CZbqIf3Wq&eyCU5CD1MBfN`%Mj8^zVtWF12sm>e@pR z6#Ja}Ac6Q^oucm&MrV*FHhk`dkD!rPMFWu6k&hAfeNjy1Rj{2VdbSEmiGR5KA2jEL z<2hWe>^wqaS{Trl5p3e3&eg!-w!+QsyF9x-L!wM(r&R{Lzr;~XbCt7b0ya{Z*IF2` zCQ?ic(wovsc1r4Ue)Z1EZH-prTa%2SmPwM5H^ftm%yLo%U)evOAO>?OnZzwy<MbD; z^@>=LMp<KeO1x(dE3UfCj88lVtHv7Bo7sgWG9pl$RF?6QyqI1g=SK|?c<`PyDNs4= zf)2^>R{x6;d`-MYh-AaDlYO;bMA21c8~v2u*3bS65;U`IX|!E@P?6QDW~aG{F%e+E zcqj!%xP3C5<Pv?878LkP{-RDVmH{|p@=i}ubZNF2?^2Sx?qQqN)jeQYD#7_$tTj|c zkQ&1WzgPA~%uXI%B&3ji(;sUgozl-zEh2MzkECM}R*Ez_!6<s$>^EFz@&r(w!<_%2 zKbs^5TrQWlkZCth(Rxg1zjIi~f3P5<eLLpzD`6>B=!}tIR{E1PX?B3Q*Wc(K+z8BQ zh)=s!X=g<wC_=9dSQ2a%MvIh12sO8$8gJf<D=v^MEIZLNnJ`a0O&j!RNb@tgHF}xz z*6JwVDek#SYaGT^8^+w|<ausyz>Cl4s_^36GeJB$N7Dv=S8!C^fRv{e>!E&Al&?BU z#>wJSv}gm?k6%}Si7La50OYa&U}ssnUtl$owt-;j@tv`~V|P5hj)e7y$tn7wAF&J= zX>)z@RgT@@SN8i#3Ahp8H?@ERPm6qvxW07`%6x0v%=Gts%7cqeiZp1Fz5e*{*VU$L z!q6~Tlj~n^01zAz7IpaQ4nyvg8SJ8kyDhER@i5~}c^AHKzA4)45V~kz#f5u|F8p-G zmHpw=mri%v{_fl)-$p1Jq|IDJEwy;E1b9E(dw*c)=vMS2&Z?Ll%lmhWJ;(VR<r<)b zhtLrrayXda&U9`k?PK{o<YDO{)mVp1Co4QKf$z^DQhxp@E9v^|YL|`06CF{NR1^1V z8?J+tic+(0Og?k>9s7J3MnmJqtQFXj=2t2rSdOg{UxulY4sTx|A|~DGCxGd5p9O3) zg;w7Fn!;$?FC9j;c=3Nfd3LHh1j&f_3)?XLIXU!jj;w5*<g6rG3$t-}l|IBpzLbB{ zLt_1FPfwrV(GQ8KQf|#@=&HU=T5h*QJP{R1MCYi>wER^#ynLN^;i_ftQ!a*#TL=0) z>o}CG<hAT17^OA!PI@2{B$2-NCxBTb<LNwoFbg*~6Jpz`!JoJCxUXNfD$)70V(~`} zmOGId@^6vAx1jl@Y<pM>{U0AWUKJ1H{fD2@>ij{SGJn@a$__g4{&^fet<QtOJy&h5 z2%q!i`>meCs#z9?60}$ac<<CZDpfT-=Xm;_xzgWAE&h+y7e4=(6q65H2K`O{7$7(} zl9Z(0^732i<=M(-P{q^Lch<S)|3=#(Fxd>4CK?aS!E~la&ox*k3R8U4-3>@Eg_>cy zg;XGG1(uOp9$b=W3P}1nzek|oyE*hojKKr*B~0lF4Y-wz+2w<0us}SkZ@dy6&#kjw zyzC{b8vAnxFnM_wbsQc*4=Mjmu*k4vN;cBxm?V%A#PNh=4uB@>{pI^<2Gk|X1$UzZ zH@ak=)9)+KyWIa^;DT;8@Krp2=ZN1Gj46)7c5Q_z)WD@&Ut@YyJ4#=J0}oiQ$^C_` zK|CXs6SWd48fblyGlR3q**jfJSeq7u;u&oX;D7n3*r(i*2GqNP?r)r}RLIXQF=C1n z2{}Y|=~JjOF!T=RA#CKC{mZkJCr7s|K@+`b-m4Fh_Y}J1p>YKx_t>!G1ZJW=Hq61N zpdHU9jd%h9XrQmkO$|~q&L;I|byJmHrl!fk>jID=hzUT0Ca`PAD-FFE$v4o^6vEL6 zx_lhH-wV_9P0$7Linf)C+Uq(DXw%*VC(M{u5lopwkE{17e9{i`*Gf&*`VHCYu?_vM zL8ADjMB|sQeH*JaxrQJXL<~60Qv{vonIwqU5R9shIhRbS^9v^%=ioJX8sO~7Y7FY1 z411eujG6N#s^ay<Rw1x(JRCq+InOKvp^dD@j0$+KNCS0OObqCTSTO<^7E?L*(**Uz z)oZ+C`WBb1Z&OU9S8!L$))Z{5XuN?IJ>3&;^Qw=9CU9rH#B(RlWk~S?odgbH0zGJi zkpHO3MFiA8s-~42u;3vSir6gum9upE<XH-VAV`gu$0w*#^p#{Y=9fSEni;4)N;>x& zrYO3>rL4!lJaVrxL5Ez|zEEpGNl<ssl<(9N@r44%TOxDAJacjQNkYg=0tdXFHxLR? z^yKL1WIgrIvPJ4nW5Pyb&M)f-TS7*?sg{bf2!;_B<j6T+{hMhC8V!~aT(m@<6~bJd z&yI+%Y|Vp4pIZf60lZW{{{&4Qyx?Db7WfdP2qv?v=kp@*)|Qo?(Wya<89YIChhNY) z@$*Ny|B7@^sx=J66ntSqY4PVO#5C~@iD^3|z9PSM16`*ERryV6^2oV4{F$>)h{2VV z>zlbG?)=Y_(ugpPYEX37_t}FA(ZDo|5_I10<OoWbn%=uVsIQT~9j2F{K?E2`qd~dw z2vNTRe~JA-ALBt-PL+O<Crl`(UbP6O73f#e<o8*+(S>J4YgJTr8LAkyRkE~Oe$}E- zuUKg1s*j_D){b}u%^oGfG;5v4mxDJ)lm8Zzf3@bG80TKhUSfXGv%4=ht3CbeA`(q4 zW^4WT>f<GosGH77{*5Jji5X4x6?;t`{&7_A<`Msv_YO@jUijZ%lB}$itbf1Py5!&5 zB>4c^T=!ej4<687;a|fgIn24=L9^fHDe+KmzeIEYp;17W;BKc&K==FIPTS`0=zz@G zy`HpyT+RL7lKn21rhxMO{w3euj{O0%od!+L!P))5(7opQfXDMbrF#KSvP9*#8lKQd z`ypLw7!HQBwoC;MMn*P+b|gpjT9o+w$7}<ix*R<941DH)@GLa&dGx{a_&{o_q;*>0 zc*()|dp`|Q!i$cBo2_;Roq-c22`{dWP1@F@t6GfUa6sS}9N`TBfV3ze32;D#p#b_6 zfS`Fy+9<;bXl6-QYFp)K3Mgb&X3}0|nDi4}#oc=(NX+2VPvbG|s2R@_w`+18@2H(f z$07P-B;-Y>O4V=dEssB}e|1mt12$~?%LhHrDkM^I=L)5;4(Mm;%thjBFTI4*JVkdl zzkT37n#Q~Tt-Lqh8>ttJ%N+vZ&~ROV3>jhqZqO9y_ug&!@Pr7X<<p+IJZc#?542%D zN6#P?8bF>%zCVO0;&$QVVE>GV<<o|-q4icNuD}nbOH=(_`)@DD0YrE5S6_fumOpIh zBJLu(lk?@RLqPp#?FK}9LHZCd7;URIzi0JNE-YRZ^Rn+xFYetkzyqG1%E*r#tfE9r z0I>2=%s09?_C#`-#*G94(lLZG<@)^;K#IGY-@+zNiCF8f@WetJdoCF=TYx#yD1`B4 zJql#C3~yQd)rO!%FTPF^rr}t}f0l*~aj9vWEaKN?o^waTb)1CsSU1J35m3_waux!j z0VW|9sTD38&dEbTKoJg9e(P~zJ>T9@V&1|CLayRb5FTR-QRZW*BzQ3;4x4I!78eGv zztzd5NChf)2!fM{N4W*YPZ554`+U4dMDFG2y08krl*!g8<RpwMsBe}Ae=XX=`!LvF za0}De;xH(Iw(TN0UDJkZnYo1dGvKDGWDVyneXuhA*{S4y3nI?m-6*khwLFxTr4Y;s zWDxcvaM+u%*TI6?cJ+9aCkTXBdIQ!C)Xxh-WoSgtGW3z9sx=cCAdB4JEC^_2hGO08 zudiY^#cNRIeg_?ZvKILf?`BL63OLjvKbZ~1%XK{E6Bh1%$Q#Cu0Vq&n^Oljc0#S@+ zEQL@I9x$Dt%O-8zfC^e7=;5N=zv6K<u3UZ$Nkni6zDrA-#GG|`29S+QA_N<&gKw|A zGo?Tp=%a=G2XM>ZA#M}8`<-|p<}k$x*(WuMfRtR#0pZP(E4g|?V9d?Z8y56qQM))V ze-<WEZ;iNg;o>ya#)lsN29-lm8^!FNy5)QTfS2Hq-8-$|Ssh7(dV&F7=s3mKSoWrw zwQ!I3v(JiQq7BfqN%Eo1&xz|V&<Ytp@v+rb(-@ZGRqtKPODxfPqsRfNYr9ZNvwCaR z{`Te&iZRExU!tD;79pdh<rh&eOMd@=cGLS9U5P)|H@Nt!-&BH`A-t3SwMa|$wGtn` zi$8x+(hm=Mu3H<4>E$IR%Qb}$>P=|n_wUcahJOD*n#KXBA}HYWg@}>B{a}C&i5h+h zi}b44`N}HOSDqU5L(9a$|KnqZl25!kFaV<6aW*=8hvA5nW6$k#Z|OJTZ?#P5Ae5nm zPW%PHiJ*6lq@RR4O!`lY06RVPfey0@!ySZp=W-1n#G6n}3WTV(@X&HF`Y^5i1u0P8 zu>x7Vi(A#I#M`Tr|NC_wN3Tq!nO7(C%_e4|8Y>9^$D>E4hnLG~H}rfrRO88OY#U7+ zY$#6g+izY)UE1Uzn7ru|x;l09-@^(53Hh8`(BOgsb@OG|h`wr_d$PWgJLsThRCs0T zGT%vAJ?<-Sd?JOOF`<kVV>+?d3*&?ni0?-1MS+EuL{a<o|4x3Kn}2GZ#pp*URMbeg zx;2)oHMS<^g?^EMJHq{Xaj#2}z3fk5N5N{o)xAz-vKDBdU8?XZ+MiuFZYl#;8^Zaa z>gSVq@AEjdxix~K#wnQ-SS^J$66n!_(|3KD03|?NZ{BItpKI(UYV86?&fBMGc)c6Y z%K=c7CW50`q<NpxM@=WR-Hel~s5LO*GEALJP=0++)`3J1$WL=k+6$^u8?D&wz@phO z!9dpy8m=_xe4l(U?a|wZ>M82+Eh5_aCF{oZW(6^W)p+>u&VW2x^MY=6zLm=^e$@o@ zkz}bva*7kK;lOShI4YQToPNvfZMkMmacP*4Zn(-^0pItVu~L?PR#)YYAns24?bx2Q z?l>*qYDa<EChrhI&I~RKm+%|46RzT8Nqg7s>4sA+u5(?8Up-5uxnbOFw8+IxT{wgY z)%l$`sBwDje2ddW(A+TzQmeBANmnGoTI3hk)1G#q2MSf0ZSB3PD7F1|bxIyFU{6KC z{dye}znj6ivjq_X8dpA@hq;i;A@(VV3;|x#)aUklGcMx@yek_8v9S~>lKhL;9&6fS z$ToJ3uDt^Io_aoR4A)sHLbZgD-99NMqQI?IMo|kaKR_J7#2rT3q^}&j3|F94C7t{3 za*<Tlk@J|v<T@i$cjC^^$MVTk$4P;^alR@cfm*xRoIU3R_u2XfwY&K6-)l%l?@<IK zp0T?K#Hl+AcidD=!o;tky?XC!KP8ZomS4SUY9FhL-QhT2WR`$q)cIs)o$>ZB&z-TF zQ=X_IqIZ#3#mRceB&f0>@=M}%@$IOyhfm5w>G<ZN31}GMn9#aRo<lm1#mdUlcU>UA zt!-6)*jz9>GFBOHP%tHbTd7oXpm>b08yD)uDXiZ|zW)2$3`XH=qD-Ji0(xy6SP;zf zv-M4$`+fh-BSIAHw@Xol+T>fM4R?r<+yez)8yf<)p<ai4piR;+s<NL9omg%c_0Cg@ zx^Ky8aqTtJ7)tvjJU3)2PhV+s+A5+4zd*l(=N@}C$`BgAy?_@JX}^5$oeNStnvAvm zv-<WZJCT9-*pJiu%2(GFg)36)^JzT-$H|eck(S_1sT#Ba0ATfWvAJ?%o86~BPVhyO zzA@>Mt)qNjE>&uPRVvoOQFbD38A*gXlRv9ZS-TRA^k)rU(AUP^c&{VXNEWzWG_&2> z^@20<YYq&+h)TrI_xuMMiWLji>wGG>WpR;fEAx5OH};O`voof_fHM54FUe%BxTN;v z37vO11Y>a{4t{gOh>g^LhJrj`hJS=gKnb1y$+V>37j}vq+@P;I8LcjxPX8}_Rqp*O zt|EtGpG<+#zgvp8kJ1~t^@T6e;h~-^dwln@V*ZS+g-?8Luq~PmnRVWoE{gA^8tcj= zqt2g<Dj9q=F}eK}(~;PIUl{Xk;5VK;bn+2K+)w@S`#$aUvs<M^R4F_4wC%{>y@;vk zjiCiE(*@DCuF=%jL5F8(zvLf=-(FI8+$UoHMES=nA2nYM(}AmAEc<zO4j2m(Zoxfn zO+N>xeiGRgR4s?VnH2bp7&y-!dRHtI>JfEp6fm3&TXukz`UJutZlH*f_ZdS|zzrut z9$Mc?G`MqlROS1+1Kb1pY%>UrbqT)Wy@&|sbpjoIK$>16G$al=6AN97JwqX;-okC2 zu*^H~9Zz<1T$1%kA}WO4Vu5H}6lFk-OWZp1O}ji0fwB)lHEW>Ccu@aMOw{P@%bP;# z`e3$D!pJv<$Y6k55mdL6;X5>Wlcx_0agXi3z9kxUc6*IEC4}BBglC~{nfZduR9?F% zW;^vbCzCitWo&9nXrWJ(+YfOh#Pwexc&7B7?vMx%x%$Whpc6ESMk}jgF`U-teunt> zsVM@<M(`Y{_fzm)I8mx6fb=sJm?km~r(!&kE|`Eb>R88xjF;3T6y#Rq43T>w<l7b) zc;$jN876%QRipsOcG#{180%#QZI@8p5S4ir)FrN=T*Q;6tS0|ZlX{he{Ba%%v8%r8 zV*eu?Gn2`XlUf#)30P;+K@cD&hXsP5$L73VNU|u(On)9F#2#uvhCNe+Z(k*P{7gPg zgl@mJ``vj-IM`C@HRQA&OmoV{CWzEQ`E^f6ggDwDNh%<=K2mC0AGLK}>86KX6j;-c zLpw}{t-)CqS#7|(HisF=HTc`2BuremQQKXV0Jkm<ZV()R#zxTpaM}K;`P~3~sie{< z%3i7fu{F%=WMbxo(2L`^R<V%9E%Wd-jlPeH4zJG<Zh~#eF10FAq-P<}xX`=mpbIG# zt&nMRn9q22ezD8UAdxvuO|s~No4UjE$Dw9m!8hdfi;34V(eazz?hhQGLc#G0(=ncN zd1wJ4z#5=ui3yd!$vwNX<S19^rPjLPidnPs>Ir?`YiQ~WPEup(Z|0x{a_%~V4mc(o zXVA_$XT}+HEJ}rWz^!^g{!?EMjvpQh+mXm)$k`g#zz*Ncq3-<c63QcHKtrk<5Gn{s zF|R4G>_|WgXVB%i$Zluai{1K=3tB9anLLW$U;szFE8P)=!R9iJKqWM%oIbA7QX`Xn z91a9S;A@pxJ#phFnGBA0N_ZFs0SHn&FR@)^BJgu0aea3d;he#C9HrE$%PBp~mh!fs z8W53jL__h=oT5aAkevKJkX{l5B|#T_C4j3%U~5^9YEUyZu$*$PesFp>))og^QsA@; znKc@T862_eD%J)VKvV-{KTNLj0h^SA|M>_tsB^lwRND#C_7oFR^Q1lPxmwT}uUIMb zD!HOB;!I9S;hCm)q3t!8kYYHYR#%|bu>`d1tB23jLWkiOaG>*Q5p1n^HibMP!M*&( zeet`C+bk5S0zGq#Zl_#q_I9GlflkYV{p0nCSizeR2S&=h9v45~@q}4JYq|orwVtxq zk)TThg=Vc04XG^l2UX@-i@9o9(rVxKl>_)3`w|MOKgz8yRBy-e!4*@rrxi4b&~O7T z-86xUt>(E9MqUN}e|IHnAOsH)5Y}M9&>nD!JyhrdJO_2(5-5KiU1{YHvXtBhu}F_0 zmh&O)9Hs5&*KWXO5KQSH-=B6mfA9khz!8mb6mPVo#=hH$60X0+z-9>#fxtuzluqGA zPt^H8tfiPwH~-LNOJ2Kr-P23IG_5JhD3^`A!})Np&X<(Z7C`_na%5tQD@*q%jApe3 zk|19Uh>34!CbY8#fL;><{?EGjFE-LD+;vJTw<gNwo3>6w-O6z3fhk-G=(-|_14RIU z#T}w@=xXpy6Wp|to|o0qPd_Kc@s@xN@zh$o(YXktphRw{;>npszJ1-GSuYtTP%bi1 zJLg<J-`_R!qswQa9gs)1yz8f*>2ISQplfdjtlKSfx@SaLgZ{L^Jc?%<!IxsGG)^_! z{Vm2@j*?C1S%v`i=?bH#m#$oOV#Q^{*W~RxdlTavKE*4QdMZlfCv=^v6q#{fWAhng z##X%St*Lxhb3v<iAO`fj*o_f*0?T3ZgJ6G3fj`WVe@fX{v_P-6{uXZRauev`-;rb5 zw4mOT+YpuEL*7aDpnv8l*{>u|JTEovER(4C-*y$fr_Jw3z@`nWOnT&T#E`}<$N1A> z$mx==1GwhnanU{z{fmqqew;5^$zR%!COo-a!`vY?1WdC)EWl2!v0n2I0Ebu{Z!DlD zGNY4CQp+;Mhp&gbAP{yBoI$QwKN~xlAx}^waO9E)N2>hgKUdDQZ1)g0`fgwS(@n5e z)HbwsBf}ENvXAi68q#$gQ_evW2MNBzPiSXYv@^PGLXgnY9OU_u(K$(w{br6=Lb$L` z=%t$;ThAN`1u)k@%cERZ6cH%JKWiT5VWubtW^{JE5%E{CE4>h~{JcS!{nktNihzj$ zzW{2v=-6pGm>3KCP^ik-$@DVh$Rv1^j`h+Z0y>O<uT8pB5Ps(OE2X+#YJi3fzV&`* zrg%H}5sY?CTPV+epTJ$v4*zBL!hKB`O$;hnmk?4S)xc|Xl0YWMSj5_plvLeco<{n$ zG2VBh9@b+pZP4d%f(1*Zc{EM8G9CXHWTXd14*HGgYEjs!nX5BZ?;7Dp`Nht4j1Z3z zRXb(!;B|leu|cn75x6P<@YKB2CL}~-jA&04^e4Rgkd*=XJ`|gPDP(2G!tZv0(sm#a z{6!03gTOd#Flc&Cs)|E!Z4M53!vLWI!B33;J@J<Z-QC9;X)7J9r?N9--;clcb&1vU zg^9_4TtwKbj}>0svxYIkun=Gk`dVx4VKZD_LL7f(`}}haikEuo%kk9wUsQ(n_EV|u z3o=-H9WdZ<!7XQwex}M*XG~YSb}${}Fe_d$1#@=-_LBSH1jv8iObra`;WoOHkm;!V zOq}hkx`y|Bm}I`CT@0SI`&iINqi|D)zV(q7$VT%7vOK}UJM_E^wB}ue&&=h}n|lZ> z4wWrKXOM1gV^=PYF-ftiIF`Gdx^z5w_bNRl>XLD+nhH!f*@$a0=n9)8yyxD76{cvn z*Y5NB#3@I3@ila1RMt}8Z0}5X%goz77P#)vUvp}r#iFCz${YF>`k6V9Z_Sn-i+#V$ z@EHuiQLW37xu1}~W8Sp<dD1C07wKC5iF-A7FC%j8-N~Tg$WKQlm5cJ5d6Dz>i>iuk zOdq6k&`+5g-l;yIF4d`aUC}d1lYaloY7umlU*!*2M&>Nf@?x*ce<Ths(<mSW<(mKi z86P_bw`q5q=!&E}Bdp&euocFwMUJs{%B#>IS9|FUp*kn!V8subt>CY4t+9CN5f-x% zl0I}lve5hr2it^+de8aOoxU*FsS@64eb)h~z`#%Q6)C8B&eSsdHPG(yF5(D@5I_OI zo{+#E9pNKwC5J6<%MCJHzGb(5>;SxSAb)8F6(`&6TIH9PZ1&D&*8wld3l;q)9nsGX z&0+Z#xh<T7y)P>x*#&M~B`?qo(*8Yrll|zUF1W(b^S{#*ZeRd;7rwTO5kPG|21Dgh zHJ7k8R-elrgX>w~2P-fX{P=tSBP?gqKLAliGe^IhXlxbLwdHZ=85BBGB{mJ!OuYDq zs@j}#AmYK{=PouN-td)&02e4#{pe_|Hu~~+qSN>chyN!Q$y!UB?ikl6CP84X<rfA4 z)E8Nh!q*~os(@0K`&RmSSMCm2_j1)v1}wZb_icaF1@B6~x3o^bWH&jry}JdFVXsu| zXT3B}p}JJ1BZkWy>!G(0ZQ@Kg0Vb%T@=LFlf==V^cL^89r(d)QTyA8F>Gq15Go^o1 z!1sj}+p_x}RLuUVd>$Kl=O=T{+^>tvWUEzc$x5TkAciJXpneJ&=LR1KScva65|^U8 z?Sq`H2BW_-dT=OtFc`Q8TXyBqSDwE<=$qN_8fG)9WBL5iz~=Y6-J(zWY1#>C!^@7k zphh-$`wkdB{pazAKlmK>Pw$suA@KK?c7v?{*gra8rEed0yX(pIKZef5pXvXL<Dbni z!)#;BeVfhwehW$4jOLQuLuf>~Csa~tW@E0+CFD|bzn5D=m!Hc>QV|uB5V@q1RJwfg z^EbR7@Au<<&Uu~ZlRa_hvQT44x@up*K4;amY+#oM?x`S&2PM=i%wDMbwWl1}27{1T zoQ1|d4X<<I!N{0!1mC85%Ku)X_Bd>h%Akt^4E6|ZNdlnBdI3@Zg)OdV#lpBOS|_8H zX%Usq)(RHkuc*Egs_ze_o>IuZuxe8w4R`|XIjj5tNw%E=3WN>914?F5z|OChK^O;z zJvlW!=I2^-xXg+z=dteI;87bDvPvpv!BAP6mS-pn>C&)MqaiTJur&eTPC>@_X^stk z3MnF$+)VyeWt)H363(buGX=F&@4U~)QHD^0u9jkF=zCC+)%%a3IaU1+L*<HDMKX+$ z)N}GaNwP?L-(p0DRA2oB?rKWM?&&dFLO<0S0Xv}1AB$!}03VQ42<O>)%!j9C2UB%T zDArJz8UW1()mx(^T#Pf30?qyMW<b$-_5HQhT|hxc0fuNF%BezEOp5ll4;bT&4xQ(; zq(U;)4eCBSufhdoq`3NE93`Z}3K#}4M(27FMqE{k6Sw~Wh)83kS_A&hODyv=ewx8+ z#wkR!1nATy3efihDUD9JB`H@pN%;!IaCoI4EM!lHaPM>ZyG&U5e&C@4>;U@`*G27n z(Z_yc<Uq@pa-$y?)hl<4QI3Wqgs>)@pkmtqiM>gKNtoxkwjAC!9kJTSR*Hr8CCxcQ zopS&n4zI5=Bf6`{c5k~%WIMk}(`6TgK-2I|J~*}-adEzUfdw&fcR3WP2^PqVRX1Z> zZ1VQ8OEaO(azM+1<qbk^76(6*@uXbxNa<}{L5G4%`F%^sr}C$GxjYRk;fw06CW^(9 zP7t=^#xqNm(h&Fobu${yTvv0loP3QK>J8*RaNz46jum0h<t>nS`w2H%r?esrR+loe z=!8R%R(Woz1ng(rseiaT0jbJ2(ubR395Fx>B#Og&`_KV2k15U7dF`N_Yh3ZGfwRx} z1gQ5&xwU+lbcLZvj3drUykQ_a95f}nXr^3TP`@i=7|lC#N>!?|NX=CWUtqs|)<k{% zu*+_F&bQ{QcRqS_hM=4~Kym~4VER7b;W`f|*5kSgQbALw<rgp2+>5%WNJ8V2jih0C z`H?qv4;<bVkBp~K<prt>rUhfyQb(?7&#<KfSK(%o$&wADmxoTAio{t!#!N#yWf_&% z{eCZ>JrXu8`l4qHzf7;au@B#MD{44Zx;lcBf*H{i6;wZ;Y~qnRD+GYRhQ)89R&FYP z2i5VU{=82)X>$7ArQ4Zn<q0ciA8!uG&xGr}JP>FPC#hVFfJcEaeoqBKQ>7YK73(Uy ze{se7c=LU?mECTkje)-m!4&QQX?qfpOs~_3^pd_uTC%V~K5@Ad3v-gIxZSkyVHfwm z33o3AFj(#-bU(^l379)`^#l1iTdzqJ1Z;LzI<ig#3iQTHxi-!|Ud8qFmr?9La3^`0 zRveXg)XA64oGv|FRsiSO<fN2U#H}lc_tw&ChHA!xI4HnLR-Ucp?k{^BM@#0=tlE^v z7^>96M%O9pCXzKxgQ@?(fPlJw<5$k%eehr6!ln$g2iguNfZ^=_y9ebob;bYlT5wP> zEK3anw1{!JUeO^368ChihCUfi(XOmc<D~<V=F?PKva-b2M;dU#TL#p<8}ex>5iuU9 za(Wt}>-iC$2r!_l(OmVJH0+mH&iF|ob9T^&;EUw6koyQc8zG91-Ho83;@Ohey*`&! z$ncT)M~_pu;=tg&DQhfUK|s4d=L@SAw&KYKW9j&Uzgdmx`*ISm3zy#H%OT@zy6keG zCbkirP^$G)eGokj36he_6F~|fqcgr{4x`r!2am0n!xN*EDPm`ILc7<}s!P<VMbnOT zA!%Nid}y_9HJJhKP&3}KgJZDFl+{g*fqD!e)*_NAjZXN2odl%m1gP^CF4QP}NQ%jn zLJZ>Cz`j3}@LhK|?Kv@!;|{qm><tMHXSENfgQp42`!8ktY=_fy3oFNa{LWl~Jtiwq z8W0D%>YIa%ohfjm)HBWQ-oJl2qU2vxAJTxRVk~oZt3C??#THcC`vO-fzy~g(Yb4OL z2MNR&TLXV9582v84&+;>D=OOIm3Hi>rI-T>R#bb-om1A)uJ-J)C4XXaF=1_B>Vf_( z+!MKpuHtyrjG351r(Xlg+xv3%tfxJQ)?3^kciX$x`tFGqPZZ<hFkm}(eCTE-gxq1M z)4Iglx=ss^0LwQmJ6%Nn!sPo0OQC!s@IGk_Q%r#m*gB#EK3zg_q?^vzvrKh*T!Tf| z53pHhT|R+HTEE`sq?!^cxFWBY=GOC9Tz^VPicr(tHY!Q#OMHoLEw`=nftbB!-&vkk zF@DRcujn-;k^Ih@XHM2Dvb_XPs@FKbyO=x+o)_o<Grn(qM6_S<#1FY#<HPO;uV@?M zg%df~WEFDc{${Clgtk!#mKw!$H~)UWjfB@3s62%cqxIiM%11M}<8RY4PUnuC1sOvr zGCk&cQM9;#Caws%0++aItrTyklUrcSZ|(37D!z98se*kmfGu!fY8?V5Kl=Y%Y^Hpk z(tB!E)p!3ZX$Bui5Rl4!ayKfQ?=+|Z<U98j6Wagxx$#4Nsdg|gn`1ZmW}(cT-wa}D z0WsRhwGWu_BN}m?#EM8@5QEowcn<yFspcDkw3GW?DhmxQkw0r}@y1D4k1B5+5f6NY z3#^a1twtG0iI;u7duznCS`E32;CJFm6eNB`4K9@s2A^)loTpMNBl7g`;YNZ3IpUB= zvui~?5}~bbLgNSuz(A-Sx-jD41hp2RBh>bF4~zVlk3Lc-krZ#BZ~YI^O@WZl#!J_P zet55}a?U*G&TG%`2E<L{r3{yp-!=a*$T3aUD>Z%L-aGJX(qX~#64Q((v}I?@fgsP0 zb(w2n_HGwcWbq4mP<!Ljl<NOh@Z^28J$+~-d%JW7-u=VLvk6h46}04JK($6Gqw|&L zHnZPdu%^tVlE;z+VIq7M_}#&Wr*3thoE1qu-#=AFlRoN<TbTsSH^f;$JWN9uUIp() zvCZZ`_O=#H`6=f3eBTY90<gjE*^z~zota{CDYEXE7|dNmwN32NGuHl};{k1dcjA@q zCpTjPA35yXLVYy@B|YoyYcO`qK4Blmytc$?f&%mTu42(V>yOn~ZP5=;Pc>#Ys66-o z@vlp`$|AcH376aw*D7hQ3dwN}%;;1xd6aI(!6d&wcK5xH^hwS9bb6-g<Lgyit<wX# zHN1z9O3YK$yHk_Q3*UF9V!DUryVV?wWuB<-b>wb7F-}v@H>KB9ldXdGi+`_d5t(Qf zkAX_G0hsx6g@*sN_8mmgAAF*rfUX0(-~Kn%_~3p$;IN+WnFeh%6a}2kj2m;S9AM{- z#KSdpQ>QXT-K}<Sv?@GI*8O1Cx2|Pw-D2h1I$$1`&UIiNx(JWCc+;TAY$8c^JN9~h zd|4S+4i}b1oKp3;c<@O>($}4$r!TTJ|74N-;ho-Un%h*sIeR6h;noxYSH~p};BFck z8Td-fG#00DdTqS-z8JUP+du3Z%LBH$8lc^h3g*^z){~TOj#;0~9}rs|LbdJ)9jNAD zH4G^l6l3iUaGvMy4i0B<u2`F`UOmO&$O5(P$sC8#gLlkx$HR2?kW#*HSg$lmZ1usH z7ol_khV(oEvsV6{+Y%WB`?`>u>ufEWl+NTTm<0{3NSgOg3><48NGTn_c?r;VlD`Nr zf`e>#{TJ`WNcMzA)L>&}^ESDmV3T_-8B+lVQ%NSpJt%2shH`I~9OBSkLp&yq^C}rC zu*y2SWT=-cbkRpszr6^erNqjB-uYJJ0(&?I2Cf%XPI6?fG{Fv>;4SaxL@d~(8{aRh ze7N5?yXyk{b`bpIJ<C)m3kkWujJd6vP)dobgNAVohDBf3tLoG-3CFS`BP31-<)D-7 zincXcyjl>Xk`#JLsy@RTu(>i}7vCd%#S3<(DEod6>?<u@OIEfkglVc};^hwg8jxSd zH$K%^dN7=m5oG*$z<#x5AeF{?74bAJ`svihK-Ii`OD61~85;~{P}Cu9vuSHFoL#^C zQU}Ra<3NYhT+aPr(eN<NucE7|$(;S`8k<wvZEl<?`xZ_#aAsH-D3aIm9hC{giJ1Yl zQ)-)BG{<@Wn}Bv4(?}~?YN(j>-td1JT6sUb#ded@WsDpSEZOs8p>H}$c1t<dW<zh| zpu?5v3QtN6`}>Zut~;G5yTanQYntr4SLT_|X>Y%Q9=rXqiNMj%e&<CP6gz^UXr57b z{0IQ9EGSC9wu~eZy{M!D03}mH_1;<PTqY|}L_Z#iJwUCDg${QgNoT_3wh!kSJxTQ% zE<=n_y&xLbT&YDbw5naT1sT(`BHCxwfF0Mg_@}8PmLYM7!iBIotlfc&FY5K5?jK7| z(XY>gNr^ocGibG`{K&21GV|QQ#4#OlA5nSYRSEmO$2kerpMHx&0k90E11|9t&Ffsp z+3@VB7>;X&l>N9PJ&id@cM3DqN-Bl+VQD*$rL!E<t(-eJMGvnvTGe33QuN(8UaVv2 zTz&D0G=#HJR!MF$t#HEnc&2#+!YPFCjMK%5m38$%Nx!5Yx!YSv-y27Ylq0uH()P|j z%YB91kU>pvkw28mbJU+rb9v$ZlM5{x9wMxhGvpEGcSi1R?YDJ%!F^*MRsFKd`|vAm zw>L|!tJ5#9u%RF}Yr`SkJkyfp+mX7{z9V8mp=zZ8S-T<l17;UVZf$8%EI!s5!0e>S z(<tF=DC837_Jk06-4kO!J##Vr3pPV<7I&tY<G0`*Um}NZ15cWn;wo+aGi%JWu0iH; zv?^%LnI5$y$mPM8ewR76A&|7*mmj)3&ik<HuFWv-7(fpDct05Ew|<J@SBp$nKOw(b zG}b$r1?|4Xak=PJJ*ujr4lZ*R1+ebQtA$_HMH?we^&gwwO=Y9Mi^r`#yLS1;6-4UH zpB_SePwFPcd+oujosrZ9&diy#6DR6YSFhp~`SHY>toP<Ufm09@OLh?KjntUl*_qV3 znU|5Ax(73d0HCh=?M$^FyTz}r3|e>A?{%rqZp)tZweBI~ZCc^}zP`OD#Nlx2YVz-| z3V99bN|sqSB00G^8uM<@PrvY(>wM2Q`4Y``RdtMy!#Q9tqk-xYRRrMPoehI#x4fsc zv^a6-cOIV=ohxptiGvpGjPhsFLQ6C6XwGCZ(@lwPEd>9XqM6rhpXtkxX+Z#*0-t{H zwm#ZNARGEI+_iSqY#)o8kIIZ8-?VPEy@oC5iGazASJWEan<>`(6$zC9W~Cn>7xi<& zJ1@RakGr}Y0=gg<Q93pHpf=EP8M}1%W8k0p1RZ^aoYAX#=1rt>Xza1Z8%YCIm~Kfv z-ACN{6${!lIOBJ1z6bPPI0fcl#@d~momrnax@Kff;XDLoYmvfDQ@v``;o{?TCv4pF zU&U{Z_+%i5{grwj6~(2aP2eF@3#nfXBlmpH^ZOwCOOEG36~Uz`+-C%{J9VK>!0N&7 zCoR0gT4SQmIHchml@1-x`v7|EZ6u_2&<A&>;{*4tU=&364$C`=!!Tj_usKq3Cm!eZ zl}(j~+d0&1(rP)1d*icsBXClM9-GcktVnvNwf~_DXX6qSZq{t0ieA<SYF6Qx=AfEy zRiWs9DRbmG8`DLVn?c9})*Z6K<tKnH<%fB?91PiG&PUgVp2k^*3Yi%Vy=~0mOh*K# zjV+@7c1~z7TOsy=_SXB#-)E-KRU|@Xb=JIpI51yhC&9n*GSNs+dC``!tj{}H9WK|7 zXu!YymrC0@i3?Ry!!S~4n4gz9-<lq&TW1hDnsx$5Mk1S#A_85$GWuUdYXFN8fTwi> z`W~%OOQRpVJY$duWvaFae;%;rF^&Lk?A3v!%ZD!??o(5IYiAuUlmNR*ujJ^rRdM!> zRMZpW+j9CqbK~V-cAQb`K#6wtdq!SVb|@CfUaEHo#!hnPtK@dl0wjr{&2vu)6-T}= zjSpvt5RyeKr5;_sKD27Y=}k^}X(?Tm-r@;;Er@E0f;J|?Xk*I_^vITf>oxPQ5(n>- zr_7h{ba(x}x%>M}p4+v>w8$r?di2973;V1e%YO>l$l^!$gkKabkvQ8Q;qU(1K`CT4 zweMe!ZQ>H`*~w&FlInDRqbqdiUua;XNTM&b_A9xdTVm;0#XZT^(wu^j<i?B$k55M3 zDYGIUjoc>BaTqt!r#zuA=hA2)n5JtGhoTqyH=e$`oGux0;zs*QV8KLxuW_cE^)|{d zpT-}tipovf_ZwV`tYat-D}95ex6^t#h<gOt=JZg<Pl?&*8HB>K(9UVbB@4Coa!<z} zsw07)AH%{3TF43Ywop`-=elU{OVUo#Rzehv`p4?B-~D=_kcQ|_ud_Kc(q>s5OJC+& z+SFFf{MK%5w3^YmxBA~#(!8FE-{4$K%zK7YEtlj3|0mH|0F{jT(!<hQb%(0*npEm; zpKjvE^z)y~y<>R;!s-A{-$m{&Oq$Z5UKjf1*@GQ6XT1ZYQJ*^!L%MKXX24s$yKyj; zhK+4hU$yvHr#p3}V5T0uSyi-bbRMd=8*}Vbx;+>6`c}Fl1KRZOg;(O?<2N<~4|j|c zk3E*132`4Vp;sEw3iftBmz-dDXv}@)!Ef{B_lHi({<z&74F#E<wJU__wF_dcHa3hw z|AC9zRo1E-)4H4kPYme)w6(e;{@HT;UWaaQtDk?`=Ca9+NTD0)hF`Wgh;Ig`ISve{ z|7qwh=P1V^Iv(=qd(BRaPwl$Fjqk}RC7zvD0z)Hz9^-XqWc%x&{S>)QtHxz*yVk&y zU3cC%d@a}B#PaBOu3j)%Pvk)3fo2jT*x5VwX1b02xE5qT-#`12lYO1@7Qb~h#p3Ql z)5_?DTQbM|DMc?mQ<m!n!@yUd$FIQB3SsHB@eR;#ul{XKr9fae{NAFYuLwQa^}Rnh z5ZSo%Ntk&w0BN$54z&kOrZPa&`d4e*DAys5l2d9`v|K0&{h9E4nVY-LW!PSZD(hv$ zd=LFYRFBV#sQEg*Fej$+G>;_uX5#zE<h!)GNY+%!{OhPcoR+g~GPxb6VKeVUvd?pN zjjllSrQML0mQAAu|BG!**VjJzC%Wie+GDxv5@RB>6<IO{8S9x)@(f(0D7%_z$mVPh zpGw!|;xxo`*g*4bOkmpP8V8C$J{@a5A+|L8Gsv~k><To+Z!SrBLMICf6hi%kp#WGI z)kNLI_OoCzhLGrbTpvx~5Yji_Zn2V`0f|y5QqLh#@#3<sA)GO6QWE0Fn!wlWvgETL z2$uv5!~i{@2RaGnjXY023}}0UfxW{15MrhdL?0qa36tYV>L37;1bzYC7XGR=)e`t9 zm%RgLv<re2u}dw{g5=tL(ZGCp3pAGiE-?cEgJ0eyd0v7~rg6jNcR8^iCUNnnus7IA zp75&Dwk2{7_+Wx%*J`XvQaSo06}m<zCc``mBmete9u9B~DHfMoT-I2MplI9tO#(14 ztfrT#ji~7z0zyn{y180?24?qI<91W_Q`O+h3K74z=S2WQzY-_%pXKjwKj9Y6qVt-7 z81yiyN)&*SaUy?&q%pzR0Pun_B95bBI(7p3wa-;Kzdrv3iKP!gS!eA*7$Z^DY6YqR zXS;Afy-rm?WM}BMELquQRo<=$XAI5c=L8>eglMP<17={lTcB_m2#^KD%&-6mKgn{j zm33jA6M0K=7X6lk=sy~j6i+Phx+P2keF`Qbgmz^k=tL-COpWXQ7PJ}U_mdbT1y~~? z?nf+_SrZu24bWS;J<UYrVRPNWS@L;|+E_W{KM*4sVpqpKSqf??VauchABz%5iytGl zkgL*E%V66$YsIKG5$_7aps^ZAuyH?0HW((It^r>vA?e!gs8<U7_cfd%iieW2z&amh z6)aHsm^g45vWk>49XfbLv`+*OlS1SOoDbK{S0!VC7P62)--`duFA>*?_daD;<A4Z7 zKG{RmM#EV=R-9j!xL0^V$gh>$BLl499kw?G1U0$Y&(Lbq8GWGMaGFw5M+v2pxXnpx zJ3H#*bps59)#0yNzN)XoPu4f=!pmmIYMS~+oF564nTDrpEy8-A30%w1&D0c`6mAK? zHAY+ou(KPa3!2nTQncJ41YzL|$VgaC5xL^@3u9yoyyYxl{JHqDsrA3V?I7Uu9UH{u z1@SmN@(=MPy<U<3JR;F?wij0d!U>nT1IbE-^l&LjmKHk?H3<#5I)BMI%0wc_&{{{L zYHOO1mtgoo%*EK5P-zK1-IS*$B{!6nF&WDOYdB3;K#BGnq>SZTn|+C@V$Bo6zy3Q) z2McUWUY<RBaUjoWT%0irxj+x5ID=YrXQofAT|2rTF4cFDu4JqP%qJ3A{}V+jPm)vC zsJ2|kZ~su_yOMtQD7)z@RrsMM0ebm5B(MaP1IJ-ipmkFH<`C8BpqnRN*Gs)1O+u-t z0;mgd-lJqPEqGrpIPIjuH7yY`$0eg***efrGDw8rZ1=~_tI1iA`TZ2u5y~Wa^|G2l zy-~4}P+uUrhE2nQqdvlbp4tb*o{ySnj117Ls>G}UbPX^Z@k@1x2Uyl=;WcK!-he+u zBQjbvz{yd}1QDPJVF!$RyyxeZ(7bM8QNA?D^$?|};sj_e4Z5z6CXHv>p2+?vzJYpC zSKf>SA{>WX#ZtLe23eW=ku;eO#vX^TTJJE%-X)XAda&bgA#Sah6d0}d4T-!ImcuaH z&Y|uec=5t=b>|TZ7R}wuBkL?u+<whd_Q|)@>;45Z5?TGqOlse0b6FaupCn`@0&#}9 zILY}{{?FG=44-?9ljbZ_B6veB7`X(o7*DIV)LcS?A9Kt++R4DBJmX}DC~nJ}GSbDu zUM0{RVYOT<qBicF9LMMns<s@HBm#8xif8u@Bzx)EYp5UZdT6W5WL(vmbvdeIJyU!r z{}kvr9x7b5gYKECJ|^(^jeo&30uM^V3i?gS=MQ3%_<XZVUd{*Kcok4%mad2;og%Ep zn|sJYVpUaYy(Z0{v0C!1B_X}5x}1ho#%K^1af+>fQY%-#iUoMNJIKZCXAbZ7v0rMh zUWMSx^i8Qww)%UwBRWYL3OWd^O2ea^lVwNeFHlMYDXM^S5~)%df4RwPwC{=V-uk!X zJdr#KIRN;^VTUiipnj1aNKWVz4Zx@*No}Q+qSgao^?sFcY(#||df$)xwUiyGM;)rF z;rJRPI$3MhiNn52M_v!3oGOMV)^y+RtMx{|NWFq$nG1w!dB-p2$$EY~c*B=z4H_dP z&7TTq9-xUb)u~%ZNc$GJ*Bh(#E=B!O6}WGMG?jr^5~-@LAc7qQ@oqn4?PwwaKD>wu z?ME$Cms5&P_MOvDU$Refzq4e*cUBR32U>6sJ!lr=*1iY>u+T1Xfh8cbST6w6Kampm z+6T$>OBw!>d)$Rt3h<Ju0rJ6ftrD77INSsr|G>y~y<9=&0f;`!Ui1uX>u(7{cSr<) zeLwOi4qs*mCm6(dZRYf~)!7PyDQ$udfJ1WoE!8S(3Gzz;w^zsBcMeIe=4etjGr2BZ zM)2F4?vFhO<xnqO_MI**B4ImdKnJU*OQ1LFzFKIt!4i+O_L;PoW5W_As>8RQp)1?C zFm+FC7#T4Am$O9p-+N^f{a*4?-kuOWH+*nA>G*N`<>U?VuyKn|q{Re;k!meG;9q*O zz4}7>fuqJ>STt7?$g68v>kTkpXnLRF;#7Ra8(?$y+zo5X6+wSIs&*I*Sb<JCHFtR+ z4X#$9DE$lSOE)>m#sktPCr)~!a0Buj$y=7(w3LGXm9mvCPdzcsPVmHj^}9oRz6JGa zU)Gc?8u7Axi*Wq1#0wNN1-kHE+g*I(o#e4f!f01Zv>3NIEY^!(w!(@7&)Us(l3YzK zfH5-a+}termRwKh=?$dbL-Ym|ryy)pjGgeHkz$Qclt_1kJ}-S$E%8D|6`Fbf%5u^L zaouWvIR63IKoFP(edV;*ZV2EEt(kvcCj;7gRBsyE)Z2&t+8rBOXF<67mR7q@k*yvI zWiP6G7Nd)?3PYWg=tRUk-g^r?ZbaE##B$3df|$d>ttp>>1+M5;5q^tOoj;zpO+ixM z!OB0XKItC_#1j(eza9;|e#pOA_n(j20UES4bFP;9>vp#jE&K9iZb&xh&KVmoliTK8 z{X;|JJI9Ro?N8<oy4~6vSiE0`Q%)iD_*>$wzm8IK5H2lOv=6G$?wSN3WG*dRORQ~r zQQYePGk_TViTF)6^9jeXj)_BLJ%q`awDX@Hkwa!lEIEA<Dzx|QV89@_&SrCU4t4gb zQNA$X{A$pH)a@)muCf#51Mb6$<au%O@Z)PB8*~UcNdzKWn$!ZiL70ZN?nqH4pFM77 zv9#Y%6cj1F87Uz}wVBH1!MpMl$WcmMiCUeqHy4cd#GwsYzw4DXF3AJ51<6}Ox~mM* z>^nt|H<Xqsmtgz*f~gT@)1<1ogNpXCtMHFH4rD<Q*(DLb0NLJ8GPU2)iP48bK#Tw~ z>pq607bo~5WPW;-p*#JWl$i#BL7ItFX>s4XtHS<4GYr}M0A2wJAqDc3iJc_3@~6mE zRMyj1Coyu!5nGT6pGZK|^Svc|-u*FQq0`xDe;l>t_@B3Uun0s^jH+vhs8^Q(Lby+- z@`jAzv@Tpl&fp15NsL+Q$6t1o)pEK%mO^kdtba`QofH{M-Be_0MM|rrOYOMRKZ(eC zO)1WS*wUN35X|M-qd_X4r^w8|dGdqVi@i>}>eRGSTh|A^6m=Eys;nf8-wAq8rY)fD zgV4oUdgt~&APdsBZpx@a6#q`A;;41=$0<d$125fdLX;zOSc^Ol3U%nj6!`@7Ms`zy zDT?YFOlO$6)jXK|U)N*un38qf<VEdQz!+<$`TaD{8j}C$;(_u0K0hyo<Gmqrf3Q@c z--=>ytKf#VS)26rtm{xBi!>x87lj%7?wM*FWDRHi608*RUn2D`lcW39OPL=)y{gf3 z6l3R9E@2JvmbCHiB*Xb%%L3Mn<4`k3=~8Mpb2uDKq+Vi>_MEA4K3C2h)&wEV*I!ex zy8t*Oxk01)-e2oGQ-%A%Ku+sXwBRyj-UfvkR5O@3LQj2UE-t&k<2foHQRMqnD|sQ% zKQD|P?W-V_E?bWVrUuOED5;R$gQPn%G#u5=R=oA{U9!cq)H2~>bdO`E{8X;k9ULDk ze(DF3wfk#?0)3*0&2BZ}%aI;k-In+AB^`%M^?n~aKl+IDH<#2^d9g|&H0n7?te3*2 ze~0q(T0|0^gI_;QqcAF3OjrXQD-TTgSjfWZO|hSA%EF4&r_oa-Iqyi(%q6=Uu`tM= z;1!B{?OCT&3B$o<BGhw+E6WCa&n(VQkKw9~lnZd-Pk&V?T`Lz~1@N3vK`(YsSqJqA z0=*LYEa}UFiQ;wB9dd6krR`^mUlSWAd0kEXAPhiPkMifple~B1g(nE<Kq4DQ0B^+a z!LIUBOJQ|;`A!sTxmw+e%RF0=m6^`Id%3?%m1<F*UaouXah*`cOBY+tOWS#vcloIl z+d}!nuMcXZ&g(c{O7WF*RQG089=}lR7OyeO0z42@L8ipDo{ZQYl{Y)Jq&R6vf<t~( zpfx@9$VR{yXP=LsoWkoCDg2!F1>2f@+owTZvag8Nz|p&Q<<fBeO;t$7i`D6E4YKp8 z-$?!_iO;j(Qeb@Y3%4ONCztXSa*_XS5;dsFqsCS_L9CB#Tu1TUMfy^&*82#0Hig~u z&6(<Y+YbVuEa0MdPT{jbtkR&%@JY4YP|9D9`j7PsjtzEPcB|=JU8xw|Vz2fo{pDAC zr%iO`vbG+Ds)67?J4*mKC0SwpJz2G9a)(IT{Ta<wh==9d<cLDHLQuMmBqBvJq=Ljc zG4NC_@bHmt1ofgA)pfn`!fHR6#k=G#*c2oE*6XVDa<Qc<_0Ht`+v9X=b+4FFP?o|Y z3b3L{u}@$*(R9Z;k*_<+0WzJ+BY1uXCH$>_<8Xy|rY>KN#Uw?jX;5(-yO%rNViXkr z>3rsR-`ZkCNH{+TzBt@(`QcfCV4`a^DZc*KtkzWit|-GWvcUP(<p*y`{KFJX>3z?W zug)RKoBU95&Ol7Cb&w=Lwe_;{st{Qi8C;{(!9TEI)M)KxyYP-ZTK)RsQFk>e5B$wk zPqWMRYt0)k#H}+qIBV981Jm~J@sJ<CBsF2~qTijea%@muAMy@hDbRQQ0n)*1s7pzo zy=Ie9WNL3N;}env!@EVy+X-ctX3B~_)EHJtBUVyn67b9x_$fuCV#JQ8he7$>|7H!+ zDQ`bVdYgUu7B&2p@`ZdKe7}ui+pqjIP1!wXiPsJDicV>XxqTa2-!h*BV-M~qv7~7r z;P0XMX)a=^g~CxBD%S+4jE4Tx;iF%WUw2V1C`g}X$d!c|N*C`qffYKQU%MC)KCY{5 zSw_LMJl`Dsk#=pJw~%^iN>xALQR1<73U$tuDs<3uTM07r>l2#ar{mmcK=JnxdV68s z^92YPL-+$=_twn7z}1uBXY=IMR0Jj|aahZbs&T6I#p}#lBumB{Z5?EuF!=saLITiK zeD%9;g>);{db5hVcZuB%7BHfwpkB5i^{J_RcW!N$QX!;X3=&HaJP||-*d%v=_3!pi zb1CXO{l1?opw<xcG&LXBrjQ-=HWL^u^eY>7<HBFIxFnS!(tMIaM_liXcbuQl<l|2o zQZNQ;YLLr&Odo$2@hQL{a`({sjApJFyH|v|F`gghCsSU8pH3MJ=2o9>indEo9``=x z6QeEtqFOO|P)?M(XAdAl+b?t&Set!0iZKF~m}-{WOX$~6=xG5;ES9?JXZX`{ezdi- zF2(DR%$S|&J~BG9S9t94tw>?X+83JF1XW97t$pb`P<~My!yU{>ST-ilry{1-{dbNX zK|sENNWR3Z!>WAjYuyD<ZMW%X(n0up7v~*6aM|^`V@g!rXOYlkn{S#Bo7-~VOj)*X zD7IF{zZVR=N~<Zu8)QUBN`r^}Pt_d?%PFK#><mgu!IV53ry>C%NJ6eT)5Csuc=h^R zM1JbK@QQd+6+z$Cz5UXeu?lhWawQW}9**;!>|_Ad;_Eu_TZ9){w}je$1bgeTWDMhM z=XB<DsmJncsMaj)VX)V>DaC7>WcG<X`$^h%B_iW^{Ux}+HQyEySApbL96*Wv3EMd* z>)Ut4_`qQ)?75P8w4+P)+d32uPK`J7MwQ4p+y9^t76om419hn3H+a4XmcyE`E8pFE zlNB0VjeA2oQMyR(;2+d2lewGH5#YST?(pLD|9Kf{(<5|7f`3}z=jjuVqxP|=%2c+% zUAU#5W()IBqq>)N>`>z1>f;zqc&eugHH&e(CdS4Id<=7@aLeQ5m=YhGQtX~zS?|h& z__BStyIB`+KDw@80`O20L`k=S#|Q2n@oJH_c7G@Rr*(t7e6?rRQ0Y{RUsIb!(9<*J zWz(`6q@|<21X~q;%A+A|#$bskzvMZk^y9f>cg=w&lPEpvxepbTcOjIDq1fjm;a7vl z?(g)>mBc#wsWVG`k&nsCT_I;;DPvi)bwB@yf`E2B%pE%QozLx1&sp=0oWhML8(H+| zPek^)6Q4QRJF$+Xc%`P$jZ&@Cv~>TUx?Zgqde5i3c1nf^S2{*Q*hbV;Wk|FUHARi( z`=q;Fg<qof=V(W_{+C&eOt2Q0(t4tN=-fU3hN<-WuA`|Cd>4*Y#o`8<I9knAC{tgO zcZK)0=>j}?G8WY9{JSu!CRd>8m_lT|2xL0*LyiOl!LYEN)sq&1_*F$s&X!$Mgxr!& zv3jC=Q18)2|Fhl!7h1Cae4iU%nLqyKm8%x*VwoDX&0)XS6s29Dw=F~PhRh#{OZ{3Q z1PW*4`fjA|L*+A<F?CoOj*s>d_U+yrICFa>kRnt8n4VJ>n-_fEu_G*H272H?mQ*LB zHqKwvx<rYSCdUE73ObZalf9x4)2>H_bZM6(k+`t`Bt^ZX)OcA)$k8fLYiq&h`)Z4$ z3E|kyd)o1B1$9L#x4jTQTd&x3DDy`|sf$nUj2J=64*nq-Uwop+((d?mOaOq2?(#KS zD4nPGN0yk(1X0WNSn@i<pM1}@IV+M$qTnBVRRe86zfXPPRLRmsG2d~Ua*}y2qYL33 zh9~tte=()TAD6yEnGzg0x;#*s@G-F>H|%}C+31uZ_2-O5#>B*`a8GjH;A}y>7w<mB z*vfm%{8!#Vs{X@~jDt^-4^rR%B0Ez*6xtkGzYih4C$qGg3Gtf$3_dSPkTya3(L6<_ z@QMOtOsH3m83eFE^ELs4$qrIr(EI?t4=r#Q02azC1pq<ghxcCR1UnS!1q><dV3`y+ z-kQ7WH6TRJrT{?m)Dm3^@X)l+w;SX2?FS&R{In2WIW<k&bR84AORr8Zgofd}Lb0_; zWkLxSb>~7I+|j{`r6wPFO<e+!8l!JKKllRe5rS4-GQDrpn|-`T+cMC7ceU-ldZ-s{ zkXmy^!u&e+#7GTj5u_Mo{y8}*9{#F+$F_VRIcSJgZZ-x3bX@5u+12DjgBTs)5(Hrg zfdc!C=ymbHn}egz%kNQzd+k95ieBLJc2&?mB2@x^ry`hMIIZn1k#Fs6vd1qLUd);K zVZ^WzxP!X19fI9W_SgHm&U4Vcw}I`jKoQ$I9SsHzy0nWkbeV*X!P~3)d7J&ByD_2p zNhvg2sp|@sAyj~BZqQt09GY|cklf>|?b%`%){H0TcN=Nh+d?ssJR|s4h3Ff23|<sT z?NU!mHeOui$w9+#f*BT5y?F2oObAh|JAd?M(qDr^OaTQ3od*M)Z&hP_P+>fxKJ&3? z+7N?-O_6S^gC{%6hdfLc3auZanw}8JO~Tr369tY1X7B_J9Gafksg*h79K7v?UL+}n zhr1n;xg7ex^ey?i_H3|t9B<q!VdMb&l>p<ACCE&`bQ-{H5zRnjhxcV!1iE!C#BBlh zjMdCIj*+Era$lS}AxGyG=PItMK4!hh!fr}69L81qq`$1F-I=evn*0pCS8uI{uQ_Kx zHinx7Kt-?dXuq%)el|jWSkF;VfYGu7-j(mFJccOHZV?rEzsYlxldn5oNSl_jVY)-m zJua2<td~i@X?L$4{4_7gFh>PyI4}cCVzD~+6<5JP5zw2Kl&Q{yM(zs>wP)HIz8Xm) zU^&3#T#{#KL9P(5rXW)u&d!eBtgkTZ&H}?S`k|Fh`-S`S9_6o0O?Vtc!@O}G`y2Fz z3c6zI+X@g>Mb%C^#Z&LR#U`E*S*N{y7MLo8;cH3wPAK}max><Iq=_d-@}dFDMYZ#& z%}-vtu)TM=X^0{eU#*V6jjy_I6o|#o5{8A;(Zw^wJfNs8wC{{CcI}5WKw^enZKR!J zo@A8SF}YJeJ~X4{Twfdb@1hF#EE)EN)p8;|_T{d>zUh5V*HszAk9<tr=3N$U!+aU^ zZkwEEc-xzu&j4Q$(PxINAsC)P<IBRf5jkDe#;e#IBwNkW0N=r5$LNC`9PJ0MyCGSK zq~B8{`x8jZsqzDA0*vj?`BLfmQP_R*G--P%kclndPsY(s3xSEB7*sWZuf2E1s0awa zllk`KZJ`qY2#@I=28Mg@?CF*3%Xxwk=?kQWA>^LyTf_lByalfi^izb;6fY#NxOy5E z<bPlSy-MUM_O(9%&;3}yV*%Nhq)ZQj%?AO-pcM0N+T(t`OWQJJG0&W1h-az#B1?3D zdyst}EL6L?d+ZQqAL8=0x<FW(?}H_;oOsZ@pTTvW!#^&$4!|CQu9YghlI+n2i6lsx zbI_R-t_mqh-HxVooEeWGXjTDYXM}-=?!&r*d05q7Wj2)gT=}4?qrwZXwC=3h1Cwi5 zt^H8wFBEiCV<}Ji>+^f2=3Ix&JQu^h*U4kopZ&M?Nv{Ysh5Jv{@!{lc{3fJoF_1!% zROITMeG+s?(<M##;Zo#}HCjlg_s~<&yhgAJX9c>b!enG%eL2-AeIo&O5d$*VN;~Z6 zDtT@An|G3WFG9<(qtIO^T^B+U)e4lV;zeQO@YXWT8d?X$SqZ{OB3TGo+z|AfC*Vz$ z-!-@8MmwF<-sL+Jgtvx^me@BgX-s+8%~%1e0Q}0O$BR6l-VF1GO9mq9z~U=AcBZ|p zHo30BR%PU%K?fXuSk|;VUW-|jjWzGhlI(3KyzRK9;=0bUmoQ|QoHVh}5^+0ZNa6;; z)e3dTq0i^?`;$1SmMbnaIsTAbMDd3CM%d9qxiCg`x|?L|iO1#!9gpsLjg);4(k^VU z$2p3;M_9UZs<5)27P%g(La-3R!`Hcky35RE&1xI0oGF{}$<mi@SL$mvSRi(q&?i6= zOh2g#^gi>x8~NlwVtqwzd8mMbSpg;GECSObRRe@DMT7(MXEsgn&Ax|iegy62bf>$P z0El&R-HWG1Vp2fRnRRb%=Al+4NY|gd2FLkR{<?ie`a_suL$81q*rTf4wd7}J_n5Ow zCzr9c7L`G!AtMrPDTh#HH4!OPrOBre#~|a=<V*8a!I}iY0j*~jwU|K2w)Mc61{1{b zLcTBRg}D8hCO5p2R||OcP<Yx$JJ0oL!6dHNl1L;|&fU6-p2FYsy_E>>M+-^t`_QdN z-|EWB{<yQ;FB`S>cdqc@@va5fNJys6U(S)o3S8{J4Nit8bGD$v<>E<84zA@<=fS$> zBRUH%SG%U#wiIk|PC%0lgSd2qPcWB+>H%V;nS+lAp{we}0yk{Ae!K7`$bkHC1JQaS znIsV*Ec@oM<s-FURo5qyoYl!<eYesT?x>`q5XpnCPOmLsotM^*-uxuOn0;34${4t* zn^<xX?uP;Tb>?d<Ts$|g#bUKQC&_=UCksM+aF>RWH!W7Xk4Rj^QY@g&VJF*9!Ko^8 z*T0Y$-;gTDL|Z9@^T+;vb;zJ&+osaw04C;Ll6Ic3YlJG$#PI`$x3N825mZ0dla}*I z)3`s$?PZGYodG_$l5zWo3q&V2=lQcA4V6Cj5sT@x_$xm?()|BkIy0MnPvy??<P8wR zYIu+3xphM<{jH$nxd-uBmRXC#=ib^?CH@c@3}94q1u?+<uIL*dGp>lMKo*#ug6?yQ zN&gj4|AfGKAOLKdk#du_6R;7BB0z&JS7R;)d;TcY=Dugd>q~MK#3$BDe-Q}>rNAqd z|GR)4jk2X~T3%$YKlk|+TZi5w1m(*kU*z37n`jrozZ{FPi$(sOm+%iP?4RVk6p@8U z-?bTPhQvr#zxs5iNVB$?(|*Omo;~S-TN6>F{@stzErPT687-h9G=3$|(qH~hma{=4 zF+Y1kz$t3~T=CAv%=?89T!1C;1HR=04u^tAcfw57?Nv+rC4OTOiwyV&y7(#s4#mOc z%9&8mL>Ozus?x~!^g)Kx58pt4T6DHk)f*|w$KBaauDaRl0BHyIm`;h%*ADu5E1Qpi zx~rxVSF^Bi!PWVQEUD36N;1NWcxy~dbB7W8d4w2YW4NB7LLZK24!qV51jl^(=N0H+ zv5M8q#yZcdFp^;gD#iEdro7q=Ik4*IdH5<84oMQ%UyzMwh>p=E^g)u7do3q%q~TZx z%F*2{O;~5(nI}ZB-Dw<djhl+R;oE|b3Bb}f1@9ov&;#FkQGOOg{emv$rs%#nDe=x{ z)W}KedmuBm>q~N#){#W2xaemrv-hO7sH!uTW08(E#HK<k0LuGwn#iKLJ~QcgkWhtB z)Z%-g#S!ObBBx)ZD0LFLxC~%xcZC+k1BtldQE>q>vXd^Vnxu4#jCN0wEecS+1wxGM zxkr-VSR4`xLf+~ZC=`XbHLCcEsuq1VU&ZT%Y0dttQNbh611rcvA^j#@3r@JO!CICQ zM=NoxL^qZA_b^VZLc|Yjs<{a6Se6y;FIW#(Nl@9Upe{+_z45({VmyJreaa(^D3^e} zus<k9r%kBe?Duong}`AbSRLB<L_3g%Xu(G~!WCe^a0FPfPfUM74%Ua9(?|SffOYgG z-Ert!NwCpg34EX8!ua>VrIp|B=Xwvt_=Az(I9Sb5eX(TSCf#*{3QFV!J}y9aT*qQD zCOTwOFRW$9f+D%QHk=Em;B>4dhtm3<X-eq`t7_9?$5MjgSZJM!sRFQihp2E$giz^f z3l#r4Kl5?o`2L`N*rRalhekD%C&c?gA8tKPo_VjaL6QIf$-h{{>RwPYn_2oaQ!GhN zbpbAlLrEtgV1j$8J>iw6J~{DzpMI&$IyVAQN3xmw;RO+FxKktPvsA0|BM{2}L=+SF zRZ-alaVyPk*O3w{zabt8r@RUbp4Vpn&t4t2*@%~O!tn@3et6M?Zn%vvn?j2mIGzCS zPm3U_`N51um@4%GR(=%UnPfPCmHxbkw*e^fW2Q&h9;|c(Hfi6_J!54bszc3S&EOfl zqI6gHy%I8r`pizUEDtGqLg&hD2WXqF@S?@-iPX<+_)C36=?}-5jXKWJF>)OJzQrcT zj=VWr=>FslfNrqALc-qe6%>CULfdo>F4n`#sKLUP+PB=DaHUIFa0_1QY6w8O53L{y zA5mVnJ&eZxbHpwQQ7R*_Pqdj^mvV{E-q+N)R4C+Q1A`?DLBMZpvYhkN%$5zyfeo>8 z>x+_-+U3aX2BcK*K?@BOcY7S%u7VxZYaXGW>mVwf*}0^SI(&`j`VtRz-PDiJ8{ZN# zuO_Z@h^6aE_xtDI6r;IOBX|YVr#}I+?(r&0{5aFHM+%UV`p=j0W%l+tRe0L2Z{$HO z%Ki}HudJ0l%J2~_yomnd{{Cbv!xc~HKa%B9%Xy)GTo6zv<Nnc2jntDFFMAuVYF6l= z>H;L{dXZ*0q#W+Yn7y`EpyY5rNmGElev)c+){|&WfeRV6x#3v1J?uto?=8vT1-q04 znsTGoBF@tP2W}pfG`38^+N=CAO|?G}NNb~uThXyaBp8owb$kR*%^hyq{1TUgX-@X> zUKAD1$BN~v88pg@1lII7scbIE9ZnHeO_HG|Pb7wwJR3f)f|LHiJE;lM{&m9bQJ{up zd7wMw@>Y)C*9sxwA)VkwY4rl^Oo7Adi@?G_4|Jfr-kH--ysl<M;4bD-VA$Cv?C72T zL#vP_zbZX^<#xA{eW(atoG^h8DX_XQfd73<g>ee|J9cv{T+R=F9g?3W1)g%u#x||S z)xAfnQ1HHI&^Q?QI|<n&n*5AC;a_27QHe4v-}k*&@*f(-eG<O5abkCi>O0B(v3U7! zj^3(gXadw?&U3cznX-zf?#5!HRG=GnB@pon|9Kn_F*QK9;|=S4G3y%cDm|1#IG);H zptr)JA`Zl}19<xi>{4=DrP1J4d@ljUv()?SAV$KO>Bf_=*JIXH3@1nuiz;aFs4CuM zZzpboE>2mQ;Hx7>Nr-<WO^Qa4Zb*qm|4MceYH}R4i?VSOOs`)Yt`{55_KinY!gAn& z?l)zy;YB-3uZYD*mDQ-OElz7Mgk7ZxC)SB`>Dvc;7O|7*2U%lB%eFUyDn!qY5IX>| zHu}l?d)QhUu1kAA6#p;tz1L)rjAGFacL6Z{R&-xfEV<H&{R5kTvc$`r{YVvm&HKa` z)IbLa2PVO{Ncka!OreV304d8bISbW?>H<lQ&SM<C+zz_ndXD1$NnagX(cw)ru6tfM z9sepJAoT=3_2!8L@3DxITW@_SWNAWDy4f6I8V{xh1%S0YC1%2wpzO1?p0VjV71!oJ zr+3(rPp=*IUp-m42&!-t-Q}HXN3_!BcXv;IUD7<_jqZ<AUq92hEvL0D?w$k#%B3}> zG+jJZx86Hr1Eg$m=&@d;_5#uvt*x}GB=JL=6ddt9w_m#g`7Rf$-I>?Dl&1sEKSts0 zr{rt2?w4Rn`#ML8TIU^KJOf7p2x%Qv^E3~Kw2Rrcy5fMYdLjC*m)4?KgkVYJP||=q zPU)7TRybA@4pss{(!H{Yt*3M<7}r7*%YxGH-w|>8eN2d1oIs6eICG#S2g@fR)XOEd zdC5mSanEkqf^)L;e<P&>Sa%t+6j1kYnxTL9xJ8oANGIOkIOQva`{7l}f8K_RuXwUr zfjyeK!XFa1Do$@tvrp?KQ9(Mpll>oINC2~O(IT`v#9S5VCLcY6tuqko0>o+nAaJ~= zqlVRMeZ)>O9onB3lv>%uCU#KX4}VhpM|R{1Om)Q{(_fTT+!0d&w;r#E__1_$oQL>K ziZuQ7!7w!}7;LMZB&VMw?uA2XCy}6?KR$R@bU$<H?@{?2*g5++N|?Dm<&%nL@-D3A zff8OdXv%Iaro8`+m7sKC6R?~jH{qpU>*7$2YjsV}GkIO_q(_K^u(KyLkDQPB&w@ho z>j!wO!@G_$a5^YjT;_k#)nC6Y(DASax}`so`TYBo5OZ{WUSbb9Dg-j!_sO@W6Yu$@ zqgUn~b^&9!V7)I%fA?5;*CWY(ukPG0Lg<7eS4I;emr+I$?ihfC3Ax`R(LZ$7cSvLT zLUL06o0a1aC9f5>pP`X;qMmDGI7F_oKZBb!6UGh37rq&T_tJvB>~J;MbM+UFcvF(z zOyM=NF+`HW=hLO3t^_#6_<CC0#f0UGoQgUZXE)V(Fj-8h9I*`y#9k-PySOh7l{J%* zQvlFbEJ+IJx@M$<;7I+GcE_<gf8=0G-*k)088!XMJFPHLQmFd|k3EgUoSc%L>eN$( zcz*0Tqbp=H+z{1so|hemkT|a)1iCfUjUT&vC?>t?fjikHyX{ln7gpKR|7BoDmw<|r z*4&iCO1+M|+qa4Q&DS%f>8`ru2b1bU-)lb+90;)B%(moB9()q1SzS;m3})4SI<A9{ zO1z75B$p{Bp>_LEX64TopI*!HB|lraHvn^+O)FokZHRGKO(4rOy}27VJJk4RUKl?i zyf}3JQqP%7Jc)kWX$zULr!PQj@d1-%y+)kF+;Pi=Ih_jOkCBM;-=8)esT(_B<=RPn zMGy8p0}C{Om-ea$c}jP)+4Mlcloe?ZJ%o{p!S%PFI;=2SHT``8UsIKqp4uT%kzwvS z)ngk+XO4bgz!mmjVm#?>z*NG+Pb~9$mtBJ&p8YXWKAx=T-G?$RpS$LJ8_BVG+i&oq zt!Y<L^}@dC$Y1?DqX!qzi4($1j8fu6TGFP-;wH|26OCV#QBs{Z#AGf=HKh|LQObvx zhX14?-qL=n-%0y)2Om~uP#*YU)G=5^^8*?z_Kf%06W)df-}9l}1L!Y*MA=hgM?s{o zJAXPYaSU&;Y$ZWxBu?#ZRc%fup7DF$0{>Bij2!JnZZY6q#AMsb2j83Poc;44R7w1T zWCKVNQjS?IqrK14@#_A3?az%x4OM$ZRfyc%v8<j@%gxh&H@z1(k^jTvm3Bd3hCToh zl_RJ}VEg=q<x!){uwE%(Am(jC{KpFG)OOg&R+mAQx(i@=K~se1rUsP4!|=O1FK|^{ zK}i#1V<_oa%H`jixcEo(GUjQqThm2@yaIK2p%e~G;*gaDPbpB(?Cr-R1dTA47<7;+ z^Jhr$fs6vI1>gw-;sFwc3<oTwEJ0WsQNTdXl}Lj$^r=G1fx6ru8wwWLQ!OqwsdVM! zB%%K^bRKR=HEbL{ARr>@!HF|)YijPC#dKS^NA8KH=1y%PAmR*X&T@~kQZv)ia*M0f zthA|SW@UXg-rnl1{QMWrb*}3?=Xrj=`~GPBYzs4I2WVq@U{#Ma3GI8I_@>1sdqBk= zit_+diSBK_H<i<lJ+?gt#H8r(EfYrl1ZCex^E;m;WC~Xbt44sgcisuhHuztZ7Byzc znlyZ*&m0^+zb`9~dFG4iaCtR4`Zf%=NxUB!TlGgEsC)PlQRuO(1I@*znFz|lYF$7q zENU;Mal}k@7YiH$lgT1piW?9?c}Zgk0D?Wp6y=tb^M}*SX*4)2g+N34nuJLK2iZLo zGDk6jh84jqBLHg@oS>LGZ(ytIuIVbQm<)pgXEXKFeTW<&Xdh6(Zd<XrD3xsQSVb9` zGCif~IvaI0XFcb5)6hf<v902tXI!z$n>C4|LZP+9wC^ORONqJMNFvI7$?+l}d3!;3 z8d&8V0CY||>Pe?Rp{2q9n9k_DDZ5n^a~)&sYX5HG+r`r&bM7=1oOqaoGT;<7k7KjH zNf6V3`B&!<f4sp=K{+Ht(p7&sh-jjoNx{JFJ?8U8>*sl1FzQY@<XnKfIP^p_cNaqR zGw+cBq+c?~<mt!Wp=7R9)9Xx;Kbp40B#_diVu>W#<BCjtz><UYS<&R3@yQ&uB88+` zrHX+O`>Hzev6dKd4QY+uWvM2|iIbwyycC7d>ScmZ7Q3zfym+z!FbqrLQIk*?-lgFx zZRex+$A(>Y67=_x0IrSrf_U~e`_);zh{@h1w>Sa8gk?fFlAgejB#{l_QOFY0bXp&* z5+ER7DM>>7Fr{C`__zb>(%BEq@0b8gJZACsw)BSab%;e%nC?+zaTu;d>d%JFwWl%- zJ^})rX%4lF-Z|9}1qqbK+pg4~tyMBh)763rD8hISMnh{lC*5k7UZ;Fz?w8HJY>EPK z0R7r=J8?qcSMtS+*)7C_!h-fgqPpwvuZV~^(-vTVl8+Npf5<Gl0A{f~$zk7fjYJ>Y za9Y2=Kqm<mC{KCfg~WCGe>g{aGn6gvzABXm4A{-1PRmmCQc?w0vkILWO-kQl?4@j( z`S*U6mH5bt(XTv3zeYm$x!r^TjeAm~`5}~RPlWSvLp#AJ0md^v+N?fLqIogoPJy>Z zsMh}bgr>&3kKas%Ar`!eu4zS!&9oym&{}fp+dHLZ8`g-GMIZ6V@|i7L!_)MDYe2HJ z;n)=z5X6%NU*iC)HrzB60D+wgtZ(CI)6DrCb({=xx2{dtpr-Kf%g<s7$w<9Kb8g-c z2ReuyBgyB`Zj%=E-owHJ-9a`)_@JVyw5nsR&mPh<q?lRsn)z%Mrr|J5JldaQs=VPo z&U{$CP#@08azKiR-Mnqe)G0%{;HQ0&jAL8OWMyc$Z8A$9^Osg~Jwc@1xX6e(OG&G8 zk-Bm^!iuFikG}~mCa!yc@1!<_fx3`?M7zi3QWCWNUONVwjzFRwVE_bu`0&em2h5p0 zko-EsAKfsCO?fC72t)f~m+l#?#;VMt#ewY|D?bQBgb6V2g6$I7*ainrD4-&ta;c2n zAR*;6u9Q2R`)JR_+fpZjw8dI{R)Fo6MwqW@3NqW)0f6()Nkasa(q-26;NbdjIC3r| zm-VAq{Q~dk>xeJ3?C;x=h|IEk6-`!uU~kfQ?R^K%s?HfTLA)J=%851cCROfRX9Xe0 z{7Fzq!d7E*RJ)WPFkjE90ert3aYaN&I(Y7}M3~UVF0$bkXBn@Vk)|XAbKxFR*a_sr z2<vH^;4kF1+JUYn2b(WKjyx5qm}MI+-(okh)NhS~IVD@j5LZ@dTq)c<JSo8TakA)T z+I-g$LwfgU0k0Hitavn?!p)tPqulCP(Ih^7UHo&e?j|Di{z|SbNCrbX@j`7rr>O`n zxiMjnfy>0LRGxl-a9{iG3%>PyR6QIFt9c1!2tCdKuM9}#8?Q7FFYBB9g?D>V%(>TK zzaC^ld&Q=W=+F|OPUZC&Yr#rQ&A4C}w;m>|g|2UFnc>Fcg!Rg=1jmq>Pv0irN<qoW z);sL&7qJ3BE0Uvgz)JDe>iukBr^d&x@!~5fb{Bj_{0!TcXRBF^<Dc;;B`xk-(?ni> zlwv3Gm%f*Ko5P1Mq4EYAl$mBjfDidCM~rzSsVQY336B&SKmpfl;dgwj`AcoWz^;oJ zuvki7ELNvkz_Nr(<6%U^9SQPQx`TC`W=e?Ra8*H5Vu=YW+z|qJf~u`bwLYIVN=foc z6dCnXwYyQf8*2px9Y=L)kF*G-v~5UkNWp?vrs683i@zXF0-ERZ(k*KV0!CdU_LNIW z>j!@8V1T)q>q!urB&5q+B#HpahDDdF2mn*hh3$pw!UKLOhSe$&vJX!uzG0zZkVrV8 z^p@d0CgHzoU`L7g-n>HHY<LjX1wFK2HE41W7A22wQ~CAby3fbTNlVL_p$s`E;+40m z{heFdp2S?&4rU{4ZQD*!{HZqwR=yI)y`+7ln|8@?eMzX$?vV^#5cL&j7vpg$@}Jkt zZ^Jpezi*O}$p}MDJDB}2#&`XfOe97Xv41G{f{^Q7W`_i18M}X?amADwvw~k&;iIE> zcOEC|rt6D#$q$HiBch<IbBO*&cekDUh#UWTWY|zH6;xtBbyK*4J|!AvE?cpE%973W z&OAl&ix1Qtjz}KP=(Vm1&h|r(i<qzJM9YnwAFxoB3!C#<dMOJ~LcZ|yuMtUMso^aH z9|(A^VjYrk_PfJnSU-b!J7|z;g}egKL}AvW<F1(w;&59-oZD~enX5mhmk$j?6uRp> zA$9qdw@~|5?i3lmru%yx6|NB>2|^#I=N#=u<G(8gG3O__B2iOwOGy_^%1Dy%S1eu6 zA~)o-URS9+vq?z&TCu@KO6~Xm%8sUIJsA<zz1;FqSERwwc<mT{_>4%s_ITK?x4WyA zTjH4+io{7U%z@=~w*kk0jPS36`_ka;UOF9-N3Xx7zVVdWKmhZ-QcB=yc&74qK_FgL zbU)n&j)9JP9gb^GiWrVdesnmh<>;5k-~(GQgCLl(ii`-d`!9qBt3Q$9>5T|Zuc`O` zTqJEdj=BV*HtLWO1ksB$6iO!estqY;O;L8ikWY*{-~q}!vEUCeqkcrq5j7gd&q+oI zTN^8?Vzl=g5Tj)z1YXO!Y_ZR#I#Jb(VO{Aug0u%4D&DO)ub_-aqnU!4I^WrGZ+ZjP z7Lx<An2RBx;1J}~s+eu7SWF-0OOlMb9scE4>TI|3-tUc=q1V{R?%^mK@a`fw4~qnm z0I5yza;HE_i&f?jJIppw-ax{|Ods;r@?B<j!+aJhQlvy*=r)LI!wCz^1iu-Mu1k^b zpFhd}Y|yd932Wxy>jgS-X^CmlmpNMUkmH9XwPBk|u0QOIyFx{~{HDG#An=Sx1B~A) zXif(MB@ce^V2NOk2xcl%BF`Ce@bU{Xp7lv(SRQ;>G6n|t^Nt#?MZoc@gnB^|_RKLH zvTH|>JH}pqLckBp!jTeDczN@i@y+`7(evo0d2@)SaAm{ECq>c?so=cJIb$L^^I)NI z5ojX>l=IO4vrR(~U9Ho>|FyYUN+tS=r<<pO$ckMCy3Fs<g?%Cm$4?HOKc*2Aqwbs# zlwl7+$a#Z4$tKT|;t2Y9cLNn8Q00b3?90cXz_R}l0aoM!)Bs3P-U64y_x1?jQrXcX zp?QZZ0{;vP;$_c-5QKP`{f^6#umvRj7G`%7%tV|O%|tabP*;LP82UnYgQ|LV=$2C@ zv?yskH?r(WgXZMYCx)f?H4Uvtdv4`pB5UM+s>EkIMMhg0B3Pm~73?gQ_^}WuZy?za z2}T1z0wHO4xjbhD<gS1Rg9J<n%*ZuBbJ1yqb3}LNR77UL_lGjlu6i$3r1l_@S0al% z#%#XAfxE?C@sH0F+XO4)RSWgKQO3LZthDpxg2eh2@LHE!Yd@-fN9Y+3l^b7jwN8HD zaEYrdM}C3yIN0|<sq|uf=@U}!MTFsUm+&Mp3jg`6BC1h@SSFt!uA5Lc97f6CsB|y( zv%bt0dIJt_`t929LH#Q7_%{AD_<tqV08c0JA!r6(d}VwJ{`rXLLhg54U04xBt4&Iy z&UPar&hatT>no09;B_)oGW|`_?usC}4OLi=Ix3DN-(WlQEAu)VpFXkEvu~_hzW~rs zSL4x(453*-nDrFZmy~v{*s!$;>_|zzBP-62Z+QQe1Md<pEG}&8Ei}e3uC4~f{@eQH zN3mZBxEB$xI4M1ybP)mBWk(7DWCURHB+m2+IGYL{3kNl5Hm{U*qogXn3$n07IU-#$ zAuaxXVJ0v<4_0*Pe~HpWQ(1^MGJ+>m5?nWtWM*}_m1*V|fhQhsRXS{3cFP6Tu7zBr zp{{kdJ;OSPW`^v`h^oBJK_s**7hmrPz0Nm?dOmzk9&Z8h1{<dx)f0@ow1SQ`)Umj& zA(7y<4C&!iFiIb8&V$FU!m+Y}@|j_-E=Rj$A`S_f`VH^Ff0_XhvNx|Rm&ZO8ulShU zyx0BvBm|szqa&$xLD0oyjO72T=aRT)%mW$8({=ljX~MY#cv2PnlxaS<M7vcvJ<kJ- z_PQ1sjJh(vn>EhU=lY`3|FxG)1xulh7aj|%UDn9yy54c4H-gxXEDA0j;!LhpXHAm( ziX8KLk9F1Cn^;i9O3U(=z#KO<>xkBqsi3p5Vsv~HydJLjp+j(ix@9Bv(&(b@$PqXO z0(Js|j9vo@621dO{uApoDRVUY##{9qSQiZXE>70o-+es7R)9)9)pMDbwa0hLs_;W6 zdkc1*LZg6>^_^8qMEI$AK`&HirwBbBJwA`Rwpyk1q#z>Lu#D3{sjU8?t$FE`CcOS! z%RdFFr?g=BGNWkF(qy2;^}OqG&@#HOo9Ui&2SdO*-_RD+iAVUvBghjt&(6cfn1imD zcRhnz@O`#mv@u}1CMxx$YeOnIZ3+B9m6FVX-F^?w*@oG=fj372DSPu5D4cTp>Z#sJ zixTNq|LVKFBLcjEtMgfp<I(g^5s)a{8!tS7?|uJ6b6-Yub4t{?FTJ`ZW3hSCGqmd0 z&nzwq96y^bzJEA-IdMd==lI~`#K<DVe~XAENpW+#gBVv{nmu!Dvf05FjED3{$*5=@ zw;dJKosv^|X_T_ZxOMgg^H)IMw;*I`_~e8jhlXhH^c(3T{Pt8k<r_+`A1Rb+yRi`6 zJ%qYN6DjFLjjy7v?Z{is7R=zIPA(eUhZvG$q-}H*8fqHopGy_x6z&a&7<}8!X3kWu z=C=M3?^=ig!+pTmx)ceQD_;=(6C)jS5uj(VR7N^Di2?-U``aH4JtKjyOii~^Zht8a zld_lSl6TJ7E~>d@6}%#t$3QR#oR+iw{!Pn=nuf-P$v5LfN&)2K9n@m=XsF|Z7P5qq zs^;=YR8BoQk9nQnshLO0Z5qJ5X*)C(6fISLWUT*|Xu?g@hio_b0q&lYc*Y5V3H!ru zss9%qR97UMgN?c!qf*-}=_<8ude{irL9zw0LE&C4B5!XTaeM;CQY-u<Y!XZq2_N<^ zlDmi_?mxyQaykXu84^#t_%Gy?=?9%k4&FSQ0iy1h%cq>|T|o5=?V{#}&<q;dykqLQ zoyPtq;g{9emfsIx!<=%5dBnnlxS6O3XNg{($bb%d7#th<e75gV2>Qi{<r^NNK9%My z5irG&|9tsASt51_8mkW{n+AHrW}m{E@ymPP*f~VkqL5WbyHqZ)TGgNJ2@lQ{`Fs&p z@1Hb!+c&IeCuI^CdPqDDo&cOr&mM<=7Mx!ZWa|qt7|8C16Yzx8+mo$1P7>u|ps0lS zMRI3v(3Ei{Dq>#b<1dX==vcZkI^J30xIY+s^#y+6v5L0Fy&Ylg8^Z9<D_IR=8#5S{ zrY8qB(;^`0^tDRUVFE_Jyf{HR5f=kv##}p-0mBTv>)y3yex{nmvjn5SM&0nYNy%|t zN8m+F<LUr7#zxY7F^gy-SU)U+$Nf8={)dX}q9F=!`EIVS{`U;jT>-1WSFi-5_jz|k zh{6jWP~$j}5*})F6=kNA@Sm+jDaZA+_;h4&`=43P-~0qb!Q;r!!a84tfX;U0uwlxv z2f*<+QJB}0vEV`NR~%~J_k={-vc9>b{SRKdQz3f=AZPy}8`)(^Sf<WV7w}jpZ!j8^ z6<>?T19xmZMf~6b^Ra#oGNGYh2+C$pFih`SdpI08|5K0^<ie&Q)$gCM(w>21gvxNs z5|Z@VI;G4ipXu1UJ^F*dDr%!sun;HG0q$bHyl?+^+hD#ZIBXE3aT|T>{$qf#ajyFV zrG0}=L<^lkk<7u`j+c6<%Ob6}=xew3>nVJ-o<SSm1BL|W!p7x^F^7xcu;PjH`xnoZ z>I6A~A511T)lSR10IAPi)fS<MAX8voS9bNt*Vi65G>Q^utw{u!U8i-pC)_0{#j+tK z5ts43+UnMsX9>}Eq@?wlpU8=3@4A&U65pPHjrREy=7MWg7h*&ncM2}ly|xlPw^ZbM zD)9wuA?n`Q$7Q|=F9si+TSsRzUn~tz?=^(ZeG&h7Tsmi7TeK@({&V_Y3ivA)RPID1 z@GgBd@e+f6x{5t$BrdSQkqIhSu3g@Rs4e>M28oJf4jEalz3J^xHbk5>xufiAe1<0! zQHQM5-yac)tgcjp+&GiDKg(q<^-k$_840|OQ?HyyU$WNPeea;iarpThguQs-712I) z=qubH1cv!K3~n#gMt^pYNLYNi^^9+fU!FFfIehuNV8Z_J!Wq#7NPcW>5N{&oG*~=% z<)<5Xia2reEr?tNHhHEm#=C`T`UAtk*zlFeB0ZnxPjWSg#TyIqnLEGXKqbJtte?;3 zr3Yv|7hEvo*?x{nIJttYse=n&n-?*161`9(JdRUPD$yti1i4~>-N0bB7?5}G?}-nZ z7oKjsde$CQ^kn*eyod-0*zH0<_)y*O5x`6_Y#9VpvoRvd7IeFHDv%_1*SrG3;OZm} z1+mvbAxu7&h#gzq0ea49h2MwO9hC-PVrWnOzRWctKnvY##vQE_0|=tZ!`|b$!+HTg z{_qc*BNQvapV;35t4DDjrL$p%VMU;Fk8!x3RRzds<+R8(7~0*czsl_l(+cfv_31j+ zkA8VOoTfh-fX))K<a>V%1^BAu7QafoA*<xTu~eNKolkv$h!-%zue#@bf>f!db}eNJ zrvTtb*cGW?x{CN8w#H4PL5}0!0_9zX54izqY7OqFp|)W;AcXR5NL=6nQqcd-jgIe% z3<3iC1vaz`0k|OG1Sne6;uk-OKI|}9wuyMm%KZDSUZNazy&Fy3f3-B|3arstGMA2H z(USOj`G;8JWpSFpjq+YWTH7~9Mc=C#0EE-|6`%C;{zs{DqF}o2yZ+i%9#A%P)^+v1 zf)-yEZJ4X00G%R@hk8QjxAH|7x3pR7od83NA;8FA@91pE-4OL1!L<N{cFiqx)e+4) zJG&F(5(|)_9Eh@^*dUATV2`Y9pmVjew~UbXtkX9}3p)}+HNhR!RM>fUB`skLS^Q@L zhLhN&H7rFQ<x6?x7DW`>w{)pp@QYheYY<b6E^^9tSAAsYb`*}o<{T<$8<i2sb<y2j z^o^o5WP0XtuX073+9&tP%BkMNWm)kL7JN$PW|~#OfP8(lp=dw1`?)xvB%1rFP6{v^ zh8av6)1fQ{no0A?zfr^ij^U0FAdV*Cv*N^VL!LE#c_gl4E>@g-gtML0Ci)8K6S&8^ z9nyB*7O31Px^Y@{9&ZaVoA-JWCZ0818WYa#nGY#TAteI!6gO|t_aNY<CeER_KNz%= ztvY_~r{5esS{4Y6u!wmx9WmgcEblh`qs~q#mp++?#;XSNUxF2Q3mYg49i^D4+;IHk zAkr^EK5-R5&rjKIa%Q8Z>bB9-t2ps>H~>E&JN>wBljZ<rs8tPZ1@5w}zR+7bKt$d7 zLy`yv&;5HETlrZ`=&vGMg?}E^<*%&67H`En7vRsURY?KfL0v6as=Mq&*$_h%qf)V; z{wShK%r~OaEve8+Jp}fwIWllb++5B60BL-<UPK(O2Z$$Lsdv_^UpCB>(@wqee5bSV z7N_NqW})7-3Hk^1YcXx+thmnMI$34Z9Xt#KZTGE+Eg~SmY^*%v)|Di__1o1CxOi<S z@IB&C4l>eAW(`S3Meq($H=<?<WOd~U6+k~1U&^vu6jdJN#$QVkT*KP1ZA#Fwp<<JC zM6lnZZkntrN7>a$M5W=5YyDOPqQ90L_heKe7?FK`_{DCBEA&d~Y_xQ-_C+Gew&bn3 zD$#b7uM*}u7;N6;4e%X?d1^Nii)+vX{>UmHM6@epJ0S4;fN4Pn)F$i<Pyum~6F0qR z2LQrtm&nP(dYq2Ab0Uz{LDAw{W?!y4VC$z>6$}Lntay2tcc?mmiVWBu77N4B$i_%u zT2?hm<_;Gr?>drK6R$4ue!}28p>R<MLAm`yQa5~=x4b5<(w>X_#NBdKx(w%b%a@U# z$MXUuOPrk01@pW~(0@ub6lX<SEG}1hO7FB4ZCCOdSmEh?X|a2G2T(*eaEd51IM>^D z<*Kf%SaVhDO>?f&&t+TA?@WKtjQ<SS)wkmSJLYLg+@GZ?7>455k@aNc*`3wa!<rpn zCLk>DDx;&Qs9Fkiwv3~pBu+&!zO9rmWP5Oc)fa-Dt)LjuSGtd8Y8oiN&oT@*919># z$f6<Y?Tnm<v$Rc63CeKRGP<p9vyn!*QKV6!A@MGK9`AH)%vAnM4_oUKjuWbByA1%+ zes9o6b3Nq>+_E$kBr`GT_kX?D#AGPJpqo&@E__q$lWM6`j^78On6kp4AzNiC1bIo{ zP$xHngkf+Icw`ZmayrpgehxFy)P{QmZYZ~9@`&y^i=%x^g?1X{U{LVPleKMS!p+(P zwOtQc+mgMVRQcoSS|z(-zX=8-b-`rX2U*#&O<ZbvM1;XedA_rRijx4)sQ}g7nWYq? z6NmzCuHyGb5(523h81K<w^$W|0#Bll$qSoeMke)uIAqIdK9azR(Y+Jpv~?OiQgje3 z$NR<daR^A8QyUX?IlhCadc4wEmFra%&SfDMeSG*0IT~j?^c*4!qMVqrql|H<V5Dqy zcj`&4blpRd%!kif!eq3KxGp}uM$^awy~$JR(YfE<S-1<iT15q>8ejZa6}Rvwe?(s_ zeZ;e9TSJGY@JprpZ{7^}5GSCPTa8`JWbr0(h@FeuF`X|bmlw=em}2Dbsl2P^W5T;5 zzN_0~7*(m=?JK`i>@wlu2nXDHl=UxF&8wPoEUxjyxV%3b`I?lt9W42fKkn%7@$hBH zSj)5-raAoJY_+JtIMvzSG{pGfli>>dwL5&BokWs*@^@p^fsVS!MeZTnv8bO#$fBYS z%m+CbIts@MxYRviBpY@$wL0gyLW2Z!^{b^3kVIa;ti)Mf;AJP<Ni4?j&T8o^e}@A# zD*b^-3rcV%Us)9x=D5_ryJd}$Z=U-baJHB6@RjAu`;7LNUY;H4+~S~a4X=TZim6&t zZ^BKj*DL?QJk%m4<O;v!>1;DS@_l9-ZC~(CTdKCBU2YCW76;|{>6v<sMJKC-e0T>X zi0-CUv5HSA7M)dW5;|*X)D=!*mg!T@{~Ud5{b@}sRDj`Uo%!tf&<7>*h~OEYFUQCi z_fV^CB~z(iF3Jpx+~nevr6WK|YKM09$)s<rGQ5_3)|K*wg!gXRS2=-xPxD?)?}V2U z4UQVPhMfNHt~|X}pTkDp$(t{K$SbdJ6LhOAc#@?apQ9X}(II`6Bd_9R@D_ZzS`_fm zKGS#0D^+CKM9+NV*hdSy)GZX_fBfyYn`zbksrL`F7`UwzfuTW!Tv1DF(_P`(oJ+lQ zUaJpVCPZ^g8SMH*rR#4ib+G+SCRW{`tCdP6`V%RS+fUG-z>9h6v=uD+_FhRsuxqy` z2hzFYU$|>fdITM+JhwjD$nCrMq0l`=@_1ap*ip)_=pvu9f$H)Cm+e$4+xq{_<x2jL zHb~&sS`IFi)C!p~1XndG!5d!<kfj7>l_j?rFkR=~HWdKk?r<$M4RsB#7Yi^#0hkF5 ze%%P!`PImd%XYcEe;Nlz7{CP=hCTJOJo|*+Cvo$?UOlSCK|8{u>YBeF%dfhe?<{}s zi_yKWmWKyFs2uELN((Rof57v-EAe4mto^`-0rJL;{KKKh-*>qDB&0+#SDc5u5z@-3 zGv_cQsz8}b-treqMt;{5mRV?=_id5W=(yuJD|4hJt~mP(Do0;<+>jN$i(^xY3a}e> zaukrm$ZNop3rmCrqp}vb+yhofe<UX$4IZdj>HP!Y{UZyD!pM|xH3oF6+es1<R;QT= z0L!dZMu4(q{|Yb;NXqi+^PNxU8(AUujcTsSmz$Jw!^|mr_7fxe4P&MShkjd?z@!** zp9uiMFvh<{+#747I}JH^43K6-W-uA^N^|&%C3nnVZ|2k??YSjDmM^1&N{2n|RCfH< z#+hd~V(KT3@zz4P3;OMoTZhixKp6eF<z?4$%(YB2pPOfF3-Il3(hd(vD9wQ6$}QL} zz&sx`FCdL>7ISq*a&2ABqhO4#%M(T+$k%o`amj^Iy8@H_QAjcH05EUJn&(u^^S{I+ z_a`BnKxWE7@$)PBmyNjQqhg1Dwh+?fI<(m?%K}s`?2zLW?KVYIPAi*F1PECgu4*n} z$WkUej8=b)j(F*CH7~6)B%^O`2w7-6T}nd)B$`!Qz;cX`dSl4Z60XZ{g?D63sX{-i zQ+u`1wh~vIzf<7%0cokVKQ^!bcu7v$`zaPO^U`cLXP$HD>C9e|xyDV{GFc;=Yo6mR zklA(KOrVv!+(6_}?EPwN=?cz#7$vB5Y6R2OL)^+lyRPc2`Z@-yQaPHnCune^ADn=A z>TSOw)-(KFzr#60j=;{57uv?I=!wnU0WRKs#-Nl7{~*=H%8whdcm`vb!ho066B_OI z2ZknMBzsG_g;?a|*X1Ky0*oiG0i8SC?<@9}PD0E1$dwMUvj2MXehk_;!QLgao$3l~ z%*gAK{PV@PdV@^PH|7WH9CiI&>c`;N+hs+~XL%_UJ$lL?yrMYMIlfPPzLHTnGJrgg z&tnY<AJZ54<~N&X#?R|KoE;>|x8h1V<@{`t186Mcpl;64#QhjsPA6m+#>j}`o?NhN z(V7=9L4M~iMhQSIXYKQ88l1KV+_XimYelfEbcbPHsHT7kHj7dxV)w%+?NoloseJrL zl7tC2sI55wmu(*p^YoKq?mle(xZN&4xR5ku_rH9ke;6#1TRW0(Icmlo`;C1NowcvD zcA}=BQnT|!u5G><Q!|_kmU8!pU*T>oa<LXHO<>dF!c21YfpO&CTfNWj;h)k2*+CEU zcmhIY4<-qctp@B)kQJJyLwo<wNay}c^u=`fh4o)9MWx6i#P(1BWyN)JtbZKz#v=HA z?t@JWa?S1zSN9c$Jz*gc{%isN7y}s<lg(13E46wihaKi_!>1{roQ0ATRat#D0ML8& zol}l}lWc|PF>9{C_#;l*P*POy*)KT>F-Uk8`T)T*r_H&20Es`QVEyn0UrsV$$JQp{ zV6&`c4%nVyIZ?c8!ChYgFBKvC{wob{LpaUDLsm%{*2vTsj)pl;?u?G7Ud?a(2=`xt z(2<;etA<bd1sWEPze15J)>UrKQ>AGSJeq0d|6Tl5Czkbx0Dz)m8%J~a(mBmJPmH?M z=%#)z7~d1Q@_p8pOVvM$x%#*jMzAKuot%vY^Z0BRfPL-vWI?g^+f#>Xq>$rx@`M_N ziZB@Q%&Ze_aMQXYx>mj{+zalI<xPTrEfd{b<|3JZ2&}9B_q7*(?745HaDI@ILf*mG z-^v^q+}uo){EC~Wi)~dcS3bEs;{+{p`^0seZ7m#x&W(8Aea;9p$?R`mJ~2kPiS^?z zON=@DQFe)Wwp=)M26pl_PQc)Po_FVq6y%$wzRA@mwL*xHc{trJ%f0O>S6|sK7I_jL z^zDWvE8bVDNmf4Pg~S@^!^T3#p#RNz|D1S{=xFZY@wz;^J&TI9wCiV8Fay*?+dCKY z=!JKFI#ptCpEB%%>t7g{Gv6+g{Z(c42O8**VbilZNi{<lfNYno$?5hQmKk_Q9N!zS z&1@?&bZVXl$)8VS>g>@nZ;X8%j6DcXSt>>O=v5AOm6N6`a0v70k)z>7A(_#<_XGE( zgcg16O}Z&|*UPw5{&F1egF@2{rPf@_J{Hqn+S-h(_f=+Xo~iZjf+_O=z$p3G^%8wo zVD4*M;ky)Mfm&HI9`f1D8rb7kGuHC@1_ermpxa6u?v%!x+{g_K70;FmV}<Ta;y%q! zB;RaBxlb?q+yqVfB#LymIdS>|$7xR#bzkhlgYvyO`l2nrw7NnOK;&u&hwd+5%pGwG zmHatUn0Ma19J%kmuD_^m-w*ec8(D{gGVylhrrytf`?U_mB2BJZXV=NsAt4~3nYbXt z>JwZc3ZBbF9w|p2-3+K4H8t7ed&<4x0D*rk-t3bAsamY)A4SuZL@^QL>@C>l3f8wJ z=Y6Q7jBI{c`n~tx;Pf_*M^|9T&XNDcym<Ui$X$0|dR#t-fC%P$0Xtc`yBk+WRV5Cp zlW$xp0-Mpc_BK~W+KOjF+3Ayc@eh+tk=ZFK)14maN^=PihG0A(fP|b&6FhxLCV|Hg z7}{WMMc)1M_Kf+BR=<}t&pg+Nu?`iUl5D9rmyNCQDII_jleFaxW-6EIw2$=Zo#);F zJ0m_zSLbp`q2fcSpw^qzm7=S6jv+313Qr8p1pnX##gEIVxn%RY5bxfZwa_{Ih<t1` zrxUsLKG)=VLFs>tP$<K+?EyXWwu!|Cx1u`_EJ^=6T7M&2d`IvSxf)JjNJSvKHmA0B z^qPKz=?qSN^8UcRjeN${*)!!4c*hlra_&5)G-vQQX7#jxuFme>RSTnY(0OoxpEasp zG&bRKI^!KT%`A{1tK}(mzx=M+-zf7qZfCe2zdqmkEN+A;a2^@fYt3Crjpp=~8-BgU z0<O13aD|r51-4>e*;ES-?K|M%%;K)qS3o4cXA=BSU(JsLL7&<jg<Q*#3Y!sB2oSx@ zbTZ>q+|2*?4W)7?t_P0@)2wvC)&7rNS@QROQt-B$Z0Jn<3H$}2D<2!Hm!lNi%l>@2 z@mDX_*U}tFtGmM6%kk{w*?karV#An_X^h_wpyr+*;v&y6;1%)b=It(N##u01gJJ_% zbc^M&3GXvg9PxwZ&d+mkY!@2a>cxC^-zU)b!L7E0%-y~d4~om~Ud-{XTrb6Wakn|T zzq6R5j(7LJ&ch`d`fTcLCQA<I{bPDmE;zX{fjg6VOEK7{iuO@G>Eq3RE^u}T`X`W0 z*srY4p)~Wa2}OX(K|o?Ty5}>QW9MvkVjtjr>4XmSiR$Nj7722CI&T9;`N0QSe3&hR zveFkcABR+Ee53IsrV3}mJJJ$Vfrzevg~yM7yX$_JwH*-cAGwp9)NwN3J;?s+{V;uQ z4Ay-Hd~oB~x1w1C0K}tAxs2MC)KIxx+_9+v?rwx<VcO_W=BV$h2e89j_^T9KQ5sV4 zyUAogh?i7sU;LrV&kPE<azXLgcF?ysO)L3dxw~mN3BNI%3w>X@6N~=by^}3+1|~O# z1PjC%8t#XqNAi9ksCDcU$ji7_mPfNAPM!0oozTtU{p*G=s`*sdq^#$D0vX_<C-%?x zNi%O&{}<)T9LQ{%@ysCfX>sAc-1EDwkvB9FPG@&`mL)H6kYF6tn!8lWeMkRUtD{L} zE_3VB_X;{!pQ2Dw-H^4P)He3S8rx>ejc^>P(k$inpC_LmHGxG$@jK~lF*uosY{sVZ z1?1`LmoDG>SKIGI$d;`1Ytk2Xa;=nzp*@l!6Pq9ZPbDM8-jHpkk36Uw-xAQoTCVOp z$u<9VbiTBD&>AU0|C*$gp8aF-yvgaD-T2njQZh8`bWUe5t8IGK_6@5Ip&jH$Th~;L z4UFA;TCAc;?D)&+<`Pd%EC6Ht$lBY30*D+4Eg~L2$`O{b2<y{P9?zAk^_gwM03!to zkf0joLeK$V&>^FPE<DsxDry}ykUSMmrWiw>Lui6SHCg+B9tdwD7z+eoJ=>u`?x-pv z$E?R?G)NfGl*?G<4c9}IcAvkv(~nU^R2cwEoy0CA&?<cg>u)!)R?V>#d1}BF6x#=! zF@9=XfgEa}OiFf{_qMq-*%@1=gxI~0m?^y_z4=9RTjlMEN%UXT84y2K+N`Blt?BvN zu3-AesqL-LGK?6#{McPl8}T=DWr+QGYHF8*H#k+E0-dtUp|5HzPyLPR<E*<hIqoOH zS3~RFFAE>lUz&b&#d1S##v*=sIEc$Jh;SMl2D!t^b~?Tb>+x~Z1H%8s_0$9b`3<?U z0~BaZs8#}$kf3i6=0Fy&l5vSZe}2r10b&pYqlZn!D4<i5JxdT;fE~*+zFA(B%a2{= z>D|#OUCY&hoNOddR%)!0SQK_P(cC~Xn`k{~@Pa1daf|2bWS$(D`fLp#oCMs%!8Anp zO%F2MJ&JeO!jLUWl@Bxas6Z@4&Yy7{cm$q9T*WMr5{)-55zqW7TS#Q-LJ7*{P7O$n z0s=ILY_$8CPh*Yi8p{HbdK9fnnfGSsSTXZ&%H-*ut$D-y?8}YOQW*|z9QpU87RU1F zrLE{gzN)H6EM!Xs$tQXiCXz)>qUKASt<_*atgp}z+B>=*MEYC6)PXnss3FV06>jB3 zaUFIGQ56Uxk)vO_XGvk^d=~sux27)Go)hh*=|<##K>|GY?jRcx3(ZPmr|WXA&0U|R z%Vbku_WXej;|<|fk>+UH7^28GI!ijwq|0#%o#0^fC^uY-jrcsn>j2zCcnuK4FuSYd z_2_vFq8&o;Kdv)H>$LZ`#bEfJ?VjXgda6p~J*jcT&3^~>l+A)M&pu`VJx{>Xz%GB1 zm5Pvcgoz)~U4Xg%91f?sh{D5L$seJ}WfIGTw5&V{ka9v0%^eGkl8_kQ(3Rk5eJaz9 z!qdOEg&0zr2ZBQK<)dPF(NdvkLpz`b_1Ul}lH#O4W!99pReqdO-!$rxoT#RCF!caA z;fW-MC%Td`sc5-YSvyDkGaW`A{gvNABpFe9h&J-DOyZYHdy9qV7VaiwFR%80QUUC7 zaM_t4#OVJum2Pv60-f)@#B4a=tujedo-jDCS@o|C@8^FfDCdkQoy1>8Y%S_Q3SYHG zwt&b91~F1RET4cG(;4Z{;zd)-B+ByQHafHPMZ?T*yG*%XI5^p{iw4d!UNGn$80(>J zJpd%iCA!K0no}nqzf&SNQTByl{%0xr+4T$BP-@Xd7!ac=ksnJy;~_zg|1+@rr&ryI z#Vx>ln#oY_^ALgIW1<^Ic9*b*ca~*U;|k~$^}=98gg1$(Rq|?zD*!A}=_=iJQ(5|N z?s3928R(T+XqSOd0I({f=o6G1M>6lC&}_w=at@?o@`LgVldo0fkO^reMA!)K+*Szr zQ&6_~?66&;zBnyJldSO%8gPLPozY1wFWBoI#zP6-IvRRSR7!?}pY&rOXfV_~tZbwq z<cIX4WiEX|MK6@gknXCm@l%#!v|acuy=Y_ayHU6c%(tX}?*v2j=hgDYBFKhs35IH- zK>kCKHNQmJ#AsEv7M@Ks6k<5*u}e1ON33PL5jBtxC)*_>Yyv8o`Gf~Rc!{d`e%G7+ zh8q_~lJX?bBa%t=j;9HGQV*44C!o(U72{Kgm2oYwHVcsi<}VPRBHNFokt9d#h5pWt z&Q<@0O21e}(8ZzhSx!!}o3nPxYHy1hE*hy+t4OSEE+0vAg%v9GQ%w9xM}g&s2PCJ2 z6dM{n%m=_aw0Sl8w(b13?p~$vRI^RrP2hj_-Bvygc1Wd+GBrKQ@t6><TNQ2LLq%Ri zB82gy)4OPZ_u#Zhe>7FvXyhLkDDcQ`cd6kyAFMp0c|*8eD>3dpZ_<Fm%c+K$CI>el z5RVec%@wv2KKK{gBMc=d!Q#Z1`&qLgg}`bDIY{jhzqF&-LK()}u6)F81HIDL{qIXJ zs{R3vmWdEQe32gUY`B>%AY4Syfgd;T1%N%vFyB8t3cUL6kupvB7{xea_UiqT%B{TW zL7R#kmkOd(R1XZ$8Ge;78QG%r^BH2QY4Se2*fe)5YQiSPV5&LdCay@|UD)<m4tArR zzo2`<NcmC4^Q}IqcS3-}5NI{r*^l@<LP|$8doWMppWGSVyBslf?a$*W?kFoo+)J); z&%o%{H>9VMud~e78h);b1@FEaa|u(IHqT3gl~K)5RG>jJ+L*6)t)Is~?X7aIgqrEK zBy7#xb0ifbfZnzIz#;XyOP4*_9~9P5mK1E_CO@<OGm4Fmln#GsSK<5^bZ7~y3~;iq z1LC>H$&wsQa90UKW?WSgZ@KbNu3+#XQ}Vf)m556Kq=9gMdvy_Sr~0%zy2BV)ZtW2D zq1({%WqLi>UBU+S(?F07WiJhF^v)1q&VY9PVY9f0RC}QBEfW-wTk?*lDz|`5Rg?Eq zCvFs4T`79zxpAVcj{i=lTL{=eE?~NzkmRn?S*I89K(`0^B^dR7TSvL#@wdM6@y9eT z*oB_n8W4rs9pg9^z*eCTP^DSY^@C3j1(w7WN7fdddR2u#^Z9*<B56N`7{bn88!?az z&2cb}mUx>QTA|jAdBH@hMV2QKc|{L1Xv*EyzQ`zVqv7f%L{iG8sj~$%Z$6`1U0(8F z|9R)4q}F391=s8b4kkiWUL1?HC{aEyVmNaq>0{2{0OZj5NS=^>6QGQc#h@=<%nBpi zk+z??@*!#8E#wle=Mc+A<_k$&zDabS?kne(mmh4b8pMA*I-#mV^dQ}Njw_1f_sJRx z|2=ajXwH<MY4WAs+MSiqdZvQf>0e)WqI%1$>?6q-9k(cC<|$dEL47ImKZyoVENO?O z9vj>G@9s6M-s%;8(XC$a>wA3_I8BG|j%J_$!l$V~JKy{A&AG|`D%i=gb0qD>Tpn-w zyX)yN$Az>>{pnHpcB@&z7vQUnb?IA!ja&Eg@de04+&wJ999Td{>C6lCmwVHeqru`U zF(_$OihdYpOI49PP*Mj0Hcb@C1SA_*eL<IPWnE5`L;%Z5&J`8bEAnJxFBh6zGIdOR z)t{nPFgoW!CF~=2R;wCZ@@|rG?-4JqUnKE7C`(xiK)~!4{3}EVzg0yZ5?#*;40UJ8 zKKD}Nk0sDo<riSHRM_s;`QO1dlp3G6>0|mmr~^97E$F)U^}*C_g~}fGe<owQ8@e#3 zc#=kk!fkWPOHI_rJ;aKL4Kn1B&3q<uPxtkOeYmzR{Rbf<-PQpIEb$&P2g-=_8Ji_V z%ovvFLwPlL;VOi2(TtM3{1B&FPu7`0XiuvsAmk;<>w6CLr8P$YP>7&p%Z`0mfx_b+ z?sgyyVo;_4L0kX+#S{lQQ}(<5v8{fX0i!;@LNGh3{Ff|6BbnE^CPLm?Qxdfs&>8c% z>aXEKY5J4<H7fI@2~2!TR9|F8Ihq1nt<;kof>J_mp$i@vk4f~y)w^ZL^!1$jWzdtN zp3?ZSEQD;ubodB4@Z-XM@nd9|SG@;J`qKl_^18GfdlxMHBUQUg)B$&$Nd|S?mI2O9 zj0*X8jg11%IcCD1T}U2Ka`X+zTu`Rw=O@rqrs=S4dgH#wZoDlvo=cGK8&(K<e%R-^ zndw-d3rtj(g7$=2>ah=8Rzk!u1SKE1y24V3Malovk-dwWOkg=h*pQF*Wb6ep7FwqR z6KZ#AU@(olpwm$!B+s#I`&=z2L^B^sF{L<u3YW=PGmM52=WPz|p^x~|hMFt`SeZd# z7`3J;D;8FFbt4)OlztlS?z3vsSxD}fB_JI3#l1fAH<<iwIFKi%_zmX$vxK<e)Tz*{ zGaT_bA)7b`xVchbW^bVM(ZfL{rdW!V+?YF)uuEB1C)YH3#)bP~DX$8=kJ4R^>=2V} zC<ilw?o@`Tx-%Qx1#o7hbM?m*ryUaJ!~Xz;HxNKt934oi3p9MK1aIN|CK&|@7~$si zv8)`O2z%2_lGUC!K;><4lYSiqL1YiNX;|TpQDP#<nhq-1fL~@5pJMeR6hUEQm<H!H zw!_<INT_BEn{w47!4US13SjIRW?KU921XCpv2K|)JGN2FtXz&!*sgTqN{xstFY~L& zdeJJJyb96ihY4lX461UkH<Lo@0vq`#Hac5pVx3eGS=jV86FT(!&rv|A?II-NH5x|R zSwC=^r5pw|wTo!2Sv&is#&N517w{P~em<h;qZRju^UA7m!vywzh{E(8GZCM7W;Uj2 z$mWdzz((d_Ik%G7TF2+0gaO6FSm6|31*r2UZwQ!sj0+635uHTH3X<e8O$$Ak`0V2U zHeLsXQ;z-!<>|pDJz&>mVZT)!)H+9$#-JKIPt<pi=P5Q$g9{rjxicP0e<iVc5fe34 zZ2e?@M6#BxnJ97jxxUlrq&~VeZTfhdR^m5}Y&ysBFF;0$c6X2IdLkl+r{#}uG`HW` z1hro3tv2OEJTj*o;X~j$u!amZDxLT}oKoFkA8X3~mgd+j2m9i4B%Ol6$g(dmhA_I6 z(a)};!EZ=NiF<~y-E&J*UY@W)bG9ba#YPpS8Ur<|gX|B3YS5V-OZ6pp>lLUQ&S}y> z8QbtzWIm3aV=Q1y5s0!EFzdIe^28e6jl7}kWDgtFQy7u-i_(A2%yflqN_oGj{SZ!N zci{!E#)n?nlpvqpPo9Nn=uzapy$~~mxpup@xKKoE?a4T2$dEl)R9LI|07eKzbWFyZ zN{+R>?h1Ni4IK*neB6b;RkLhQTNPRs)uwVA@LNq(RXdd!0UVMvB}-AfD1WKAmCCDh zc42ovwyTyF*I61>MM6z^HuElH$0c#^c+>AA#(I^<3@7Z~{?v(8d@*E3371@6`sC=a zRF|?@wM+m0khF!O@+uw+!INAm)IU<<W7so(M_*9KhU8#+_yc_7Ib{Wc)&06}YDHwf z0%DBqcZIjFP>y7t)WqdE;WeSvGo?I3iumo>Ao^>pPvf*7Nxfp&;P;dL(XdXrvCfNc zNn2uiEfmi3zMwe%4LP2%_oxz&WjIthW(LlS2W7<^x6!{cYd~2aAd!P|`%KvZz1z<2 z^&i~dPTFkk7*g=S5ON-(_*{s}jV(ZweD8$2&$hMhNtD`~RX>Xjr(XUn8B>rj=QgA+ zHuA{3{=H3tyKVpfq+MWmeZ3!43cn#=%V|WFJ;MBPo$REfQ1v#wSbtM?=TA6RNzG{& zD7ct|6EKb$Ro%OH7he3}S)q9E+PTEz<&U|m+kTrp4tmce18)caF;k`P*m?ZXGqrfg z@TPeFLrg~5Kbj*dGGhP7JuhRNv&T$nchOPLeJ}i_(`L2!k#FG%y`g7wbyTjVuXBy~ z=%XEvYz~S_={d0~a?z2!sw_|WKp~lw4xfpFYMf3GvPE5V;A6#hW(>b(D0QA<UQ;?( zjy+4(p^Y5u2u8>>o(<4{?>Tc$sbaV-jB0Vi0gQj=&A#0r`iDYMzP?1#F%+`aq$a<{ z@fQ78j}uIU&Zl>K_7;EATt|17W$3_$<)qxT&X3$*eIYmIL3zL5Lr7FJ#3o2`*DrZk z=RY^v64mz6UKPb&razjZ^KeNwG1S{tJC6LizT=?}Wy6IF9Jo<f^RCj9J%VEypBC7f z+H)$#Qqqj<6Tec;$dK>G=Knx%m?za={QTd?qmG0ot({NdSChIt#+bP@vKbxqYHZKh zA-yrw_>QfB(@Qa9x8uXbw}Yr?<5TF!R`v4&IsnvLSU0%DJZ%V~xlKw2JPavKaxtYn zIM=gBR}|o~^Iu5xp1D<fTa62)SqsWDZmRiA+3^vF`WV)La+6(|<3Wm39IQO`gR>53 zU?yO`J)FIL$tL>7(K3Wh&{&%p*2U$B@(UlzPV!rZbddIbhh(jX6P~+)aco_8giuMV z4%Exzo)I<dpG&T_j}wc?#@}<fBEFVvG0iz&$IH*1l>yuktW@Ach?{qqHhG8UZyiIO zr3-(rJL_i*u!n;Ms3GUn?x=pcqbev8VDhoDM{R6Gi8tZ|CQ)Wp-wy@5AFZS0cH+EX zHrL)6K=%UoOywY>4^d%uzI|Eb<)hEOXC?K~uEx0>=by7-GroLx@uKMUkT&D%$+Wuv zd>r~A03u`LwnZHOi=pXXt$~*>W%@7g`!OtKHul5<=5jxaQ+$<bGA7<5?(1{%fVt%J zGHTA*yo!7waLN^;DRvUx+N3wuYC~zfos$tLN$xpG;s5)}ymfcN{NIl*2{UNE)qcAJ zp^?>H!yA8ProPRPdTPk4VwqhVHMt))`?YQq{)qg%u5Ty6Wd}sx>4NqfoK@Z=;5PHT z_46g!^^p|&WNyw0_Wpqp=bL>*@Lz*t_{6O|rIGtq@-XYqKOSrQs+Bw#6d5m`?>=rg z)~rkUj>|huhl$Cu1+WAUHnq&r)i!Exx$F4FAiQEbo?PMkJsskc5<Ymfpvq`$AG^WM z@{7kq-0!-*GXnQNKc?Ew%*!ovY)J+M$Uf2W!^R3%<pbMiFxGg0y!(!6gku>D$r=Zd z#|Z*&2m<#)3md&MvOr1|^{bL>VV#($o4}A1<A}5?Ww%oHhkP*3SqFLfiar2(Q7GL+ zE}%d;Ddoa;)ubLi{~lumyME8rqtyS~&tC#oLjc<E{F{{S<3gy@(dA3P^}q+t3O{X- z0jG7x^eibNA(5)3ByA_A7S1<bB#r8B<!Gl$9Vp3&Uar#!wPkZ6fsupXNJD~T`~VTN zO7LGJh_C?+NW`r|l#v3aK?25T7%g))dLJw??bGVA-IcvL^7L`NWu|Ub_Kae;jTyo* ztB9=1{OD18rD1;XmnNsXh1lfyl8C9H{Tq;}9b2rpkT!%E8xTMa(dt--LCbd=b~<YV zLi!3fuw9?SZN*D3lX;B>SFfMf8=JSK?Ap1p89RoHZlNZfM0^EPz3sXB_8eS}O}_Y{ z?aJFnp`1v6RcG?1zVYZmCz3XORLu?|LV?IyjTkPyvezW<UnNS-4x^R;Ssm!Tht@A6 z_sbnTO`T^((|*`&Uo#M!bb`Vdd+Ab$ej12p*a^w18?$*JgDAL*-G10wKWq-X#BS3& z=Y|ac8@Z*BW)w*SaRIP{GLQgHHVV2kG!Fp;s)4?*Z?8wt>JeSCry231oGJtCFDwe@ zAhqB437hgGp|RE?B^qI2R)lY0<pEX>NTK54ta2U2B=?BwW)|E!Jw)@p)`*YbzlR1> z^u28Sfs8j&>K%B)@rhl|8S*Ggs6KGHlX$GxsggK*zcY$ugD#eqH{ts+5d>L-uyh{{ zRh#_H<I6;`eLCnM{kW=gu{R@}-{S)AKt)7#D!PhCSP^2TAs25cGx88AeYoUE72w*5 z4gOE$khVQ5fPRg_g)u<RL9jO{?Zz5YU=Z^A+l$+NFhK0vKKJ(!Hi)en#>tB&Mz?9A z-$U#5qu1}(UG23%iXGC7jxC~I+-o;v*=R+acc=Hm7|v<hh3c!Es;ooozv9uILv%-^ z0Vg_1r1A-eh~Ozsw@p?CpRLq2VoAC=nMBqtAQ(PRcZNB{=$ZnP@D3eAO>HCPmI==P zDLVH@ru+Ymzjv^cVF!oJscjC;dCr8|=8$vFIi;CHh;l4Swb`aQHiw*2&G`_85IP|w zAw<#XMk<}r;p49Ee0~3h*AK7f^Lbs@<BI$!VMt4{+M=5C#-NMxL9tG6QRYC@x*I>R z_>GpF)ZoWEe6!ea>NUk*YSO$vqhG}NgDz3Ig&8qO@{jOcLK~ngQKkxGy}Bqy;WFM{ zwhsDzzY<9p0{~YLX39HL7D~^7@d_biD?-N_Y0qJbBoO>4hFa*-yzsif(_)F=@H*XA zK;Cs>{G03GB>G!hNauK=%c0W&T*)}EEQyLpz+aC%>~S4uJZ}M^<JC)2AB_5hT`+s3 ze|DF5X;8@Qk}TlgWImZ$94EEU8i|Xk%G`u<_8q{3ACiJVQ#ItPm|e4C<4J0kHQ&!P zO2Z*+SCl3Y4~R2!nLw2f;OG{`P5hg-^-lG;0E`mw)B(CTU;zLTIO)JpDkYnxRYk34 z3ayPsEo`Y*!zZYH*C@MI$$aT2*B3)TJ+-*Qv-9^VGT>vQler>^#e?#{e?0U~y^%ga z4E1S*D20!D^5qV_*zFkn6tHk3TKYwS$??&BxQ90)>YElSzz^SC(^>R?Yj5$J>A2u` zN%0Hmwe@X9z-}l*7#d{g95u*8*hfhLx~c}RbH{DjtC{h_;%%wZJ?agg7Jr}gTmD)! z60FPtnl9QRxP1IG7X(~&=E5DscYqZ9x>!E<Kk<`qgKCXUQq6&nHXeWYQRqS;z9AU1 z$@W*>Q=4@xfHC(`SzvN<3o$7UF?mb_=ASe8WTgm;Fi85;2&*pvO;3NVaF0H*bae<5 z!MaCGBD@IMeZA-D_^N|x;nTG#Sv0UpcR%4&@)q53m$xEAK8BTemwCQnuL*O177Iak z-l+m?E+qqqAr*oV+&`iAB#eA7HG{1RpxtcpjS$ifMHt!2ekg)02eXslR04XbbTZj? z3UrB|oNx&KfCBWFVcxra4RcIIE>)IcV7|IiXe5%4VGi-_TK#yK9l+?*?QLj96a?W= ztJ}|da@hVC2}0^fX6bJmd->b%FK;ai%CKg3gvmCpvbaEr&EgT8Hqpx)KE>u}_oQn9 z6S{}Ww=9MqeB!Cs4(n%b7yxY^XKb-$jF{C64#94rrbr62hthr}TwUrA>7L{0J+XF_ z43J_ydcShRp%A-Dy7@Z54J|uj7^#kh(S)b_$~tcG$4RyqUNigzZdD$iNXLPH7$xr; z=rmom@C4~6iiOGyU{Dc?m7vON-}^N;BtUW>Zy7PCM}Abh3VN|!$=p0clTfb1hQMId zFv~Ojp2F+G07YSc!(;SXWstL@0WIdj?^;<msrPvX-0faBbW&=T?3hv59Of%w=p?Zz z(jl;ePnn%08Lw|cK$~uQwxfZx+-SG(1ORFcr2Sn2(xnT*yp^k!0NuknsD=t`sh?-# z9yc&H={{#4=voFBJ*4`F!hHEm{gkC(Th`_vOY<QK-<oC5OH{gW+KV&S2bEETbB_2! zFfZ4JX}O`fN9$0$1CCtji-rTOPoQSOiMs6MrTHiGA4zp@^7JCxOV6}VH6Yu=-(lFg zJQ0;F>69}k59*sHhhrX?B1rceR6bjO-hH6$9iw7QWS);E$5|uB01o$YH%tk!MuC3k zfxaekZvL;}wYO1s=MC7f^l8`g($Pl2fI6Ifew)TJ){k=g-i@yYv_pe7UskNLYrf7% zn8ec%QI0wt*+`fPyUO_>>9s=l_dJ>iB<1NUhTZ05E@d#;6(rbJJ<L;&8T?UcbRk0y zStVe^9%fzoW8MQZMy$$@U~)I#qj+N5kPU)cRSWc_6XDr?faaU|=}6ixmr+l2WkFea z7zl>Ea{L=ktBMZNh7Ck2^pwuko~UgEL`N|-ZyOkqE25vn*BB=4qBwwwy>BteS~p@{ z9dmUEtI*0pMv1_b720I#5ZXBn698UR*cMet`G!(qwX;L544g@2d#0Q)f~Yn5Jqz!u zRyF&5_jYVR-JgZ=dyyeuYK)*sR$@UiZ$?^{4DHm}S8jqyI#Z^j*qwgi^}TYyPrF2B znXVD9SXWIQgMs@!nbdv^O?3!G)R)0I6|G_ky)721vt|r)Y};`TpANY)hAzxC@%B4i zDGmHxgYN-#_M(YY+iec7KplSn6CPrKGHM~ddPXWW`4oEUK`E~>x*gf1TVA1|xmVJ5 z$U44lxFKa>{KQX%oFJ)Keke~J@!Et)G^Kt6D?P1NG|!Vv7V~gup)vmnl5D@A|2}A+ z+*8sn-C8>g4iR*qAH#JXb*OYI(x5;!P|oH{2>9Gy%M0Yl2uH=%QykrqPtRJTLng+x zkATyNmuOW-JVswXX}<Nmcm2&ffq#+f3SkIWx(L<r0&%?1Ie19b!9f{z!=HlcHe}V~ zknr0N_*20O6V;`87|O#SF^Q(;s<&lW0m}1Xz8>_Mi9c+So42Q|ACvNUW=vtHLD`KS zvPpvzQkt1VRI^L!_vy)AGwIG;=_8*VTJmS^A8kq-);Z%Jsrnr-tVrKUcKHrYt4|aq zU%Oc8V~QX=ofrL;W%Y&b3<q`OT6<npATOJ20|#gw1$8e;s{!Dpt1_IXP81M#x$LGT zSm)5#MVY8NKQy!V)pkW(tET>v-4|DEH+S11Zoz@<ll@Zq$G&0meSk$i!LCKBd2xVH zO{=IPQa&rmF4d-!R}#a&2l8BY^WZUbC$DiAf5>a~{AI;z*KoU^F^@=BNo0RSS>l(% zPvNooukED4_tET0MT#wEOY~IPVZS!}GH$t%$(9P-dj-u#50Z`z?z@0yW^YjP6xnS< zUylw+wxBZ}N`rkB2Okocms$+QtNT$cV&Bmg&7VRtf8uH_jGQTbHuY0F4&0+#MREw0 z@fjdNUD^oMvACm8q$zRZZ5zU>8lf2HEJ>zJkSaj;)TOTXF*1ByVP}~V?N!o&0M6@+ zmPgAQ1O%{lnj*ky8P(=2vavJ+7iaKpWAJ~9;2vpa587e>r!P9VK^c#oYRyxqrzFYC z(&T3PhYl@r)O~N)h>IAo(swQ{PE)OzLZ5taX^lpn)KwE-VFudju3jO3azXME{7txW zsUVCs7yn_4X)!i+dTl2zdO49AlNy*a?D5Goc>oz0N+cb|TN%igapj)do93(U6EO&F zWNaiL(?*_6jLtp6tADHE%c36)mm*V|+Z?MNL6;SH6dWbA=Tg{Hd9KR2!<gJ7y_mNo z(umB84s|?1(v7l!%lI%EcLD>xdHQX(EBzT7tYjbYuy3053Isf%wuEb<&oa0CZNI$D z*UWVPC%#ZK!|;^sprR}Ylg-eVk1nudfCcO`{z7#rFo{w49oLFW2b47PWwXdLqacib zl@i6#)F+JE8EzJCYvv)X7}BP&{I(LOyFoZa``)3+j-|R5u0cnVIP0X0c9yhOIe#nv zX=cVw(`8c2;7*lV%?jY85j*?{=S4C+$7t}G7)QR8KZc{+=CfM~)uuAlzc$XPk1V1$ zMwPLYd1(re6?3*Rb2B{*pJ}fjNVfBLES#M&KjB%OUXx(tOv36F!^l!%23hAER3%E0 z>CTCYPDLRUp8@b#kP^#apWk><VD9c6_swGs$hzKV5+%v0*KVMe5k$)NnV6cHe-^PO zQ|Os8>nfAl@!tPFX@(wsx<m8M+6VM9thuo{`7x<^f{GHG4DZu+S_0%bd!#dbcCpM~ zwmnb;HwPw#;i_NamZkjelm0jY@HWllQNmfKzq6feV-*_B##`Lir*6^II=>|<8&Iiu zb6xiuyB3s1D3QNxDqTZt3&kmWIe+x#Xm4OWI5N92rG3!1(&MCKH0qIaQ}L2?{8c>= z%OXAB_&+_h%txg7h*izy%NVer;?cj($yA?jT2pG8Ghd{L>@+&(S)a>8)Pxy`t|Z#I zb0fox0RD^4_&e1~?rBrrzE>Uhv3x&qR&@AEemrizAB3dHehGi~Vk1^De?*$CPo(T$ zm^GuJ6pwK5%0+>j8w#VLGTCIBApDA%$U2B6-Nqn}U6-4iO$e9i4urUaNYbfIV3{lA zNV$EV!24X(k%D!tQ3^JHyK**^0javY-AUNLcV2NBC9}oO5`FG0Nkq$JjCEFdi@kDx zs*#JqN*Cckr~7ZkE^1bx<`)DYZVyq)@R*ure#kSO$LglNxpP|bfCU4;scjcLfMbHd zDfyZ|@0b317kK<0Oi9NzDrVpnAlG4H;3!gT1Ts!n9i5DZoChhE^lO=|?XDiK&tSg= z`U8X14pK=ClacP8IE~Lf!Nlc}F<(9Opo$U&OFMQTtx;2HkRjEj{9K%pFLh9A`Bw$U z)1r%9HrRsxN%|>Ac3nKEb3T4%EpoX;Gx0vDc4v64F!V4R{lewk<hl<w!%}KZ2Ro<> zOPHKF<nLIkI8MU*gJg?m@fc~`sj<@8NUNYNHH8<mB<n(&a6q23C{OK>Be#CrCaa3M zc*{b*!z8h~A5u9$9F&FbKP)d`@Anp7N#|k%CxZ5Mtf_lgY&V_anfR8HgrgEb&(Cwx zOx;2(TevFyR?ctjeW+8$Nv~>$i5iXF4%zueW-^0^LVTV}Q=a!>Q%$M>Be_H0OEgC( z9!OK-hhzH&>Cv6qQn&7F=SN8+B2ZX!>a9XuK8j!vDr>fMH=nBj^efIUpPug^|Aa>n z!OkiT?c0IMfm(%<C7hT=T)j@Fd^V+w`sXkdDS1C$*mt#sV#OR;#W<=Rq61}nT)^hZ zuw}s}WDk(sr|@^xPu$^|<iA^z_cILjR6&~4Sx?tmS2y~7)`31@-boqCv1WtxGse_@ zWa#rLQsPJszycg=PgTtjF#t$eyeIHARfdVEa0|=8Z5=6!e)Yk^?OX59roAU)4>Xyd zfcIK%_qk0Eb3u!?01GGI9-dc54i*X&ubw$FnLu?;#=0p~lCgdLnb<rBX<IiXN2xxB zf(OCSn;2qOem*G8SvqV$l?yc?8%Q9EYkzdb&mHLKdJ;uRE9jwL{2!^qOx*o*pUg7c zxnEb&M<z-j<h$*?*v`(V{_CGXoqL@p`!fzZ=#!`kP6UJ6s*dP%nb~&wc#J^N-Jf0v z;TSucCx_$aCZum{omEF1Kj+yX{l|igdwQU=9_MI>uf~(dIk@blyGEt`fi>pKGsCPQ zqWl2lp&dEmsjD~?=d)xIPb`&h!R->uOwAr$EsFXU9+5^!!cY$4evzEzvx0bK#@%EL znSui0mKVXN5x&309ual#g`aO@1X&+?@}Eec8_vRO8*GV#Y3Y&Fkp;8Enmb>WY5lJo zhF14FfhSkcZLxy*g6u6-6Y}3pO=Gr-f&v4M?a?QT*WLAvKvJ-`i$03)Vlt}!gBR7z z647Mj?q1k{F+WB<qdQclf}wbVVYBZF$E=*-Dwd3~9FW~mi=H-j4y5W9Nf5a5)&qMa z&)pDiA)SiK!UW9FSyS>56AA!0<yq2Ib0+6=`73QnW45+gWaGD|3zPq|k!FK8%pQJu zYF1@%^oGuVQIr#^_K4;Njn0ZogbW7E{M<xK%AhUhBP*m~KehX(<>gY%RLU;XC7eH( z2=vQ+F--a|mda@|_)x*8d^I@&C?yW?Wq2-#Mh<^KA*5=%qnJyHb3{Mqduy~?jl((@ zAx-KX!{@4h4f=sta*9kVY&8O3O~0IB>0m{!hv72O0E#Q~XQ&*+X^>eKiXVj-*5^kL zo{$dDj>>4lX5?ht^imq^+UPz$yZ`sEW8qJnZE{J-Wg@u~7$sI)T>oJ5ufN~&mP_o- z84?2Ic>GgYn>;z>7pW&m50@>axvAQIea)F%{nn%%;K=J*s*&!8fNh<V?(P54e_LWh z;m^&9=gKp&mK`fE6zfBA-J!DA@(i*-ij~_S=e4%I|C^AxwO`|c>CAS8!PnD{Tsh~^ z9bt|;%FPST=-^7$_S)_gEtsmk=sNdZ+z0BnVrH<5M@apPLrsR{T+V}6qZfAjXo30< z9T~jUM}637J%Xh)tIQp8Uwl4^0%8}BVZfIrC#+}U#@X+B1=W4!MVgLQ`&oUu9#(1< z$6I%7HxfKwq}<k2{o{72^Xz`VpD&V&kX1-Ac?w}8KfqVBG@Qv?nyeoP0&o4-Y34Ch zy@*z9r70giYy9u-C>PwBtS6*t_X3HS8y8rZV$H}x%xp@Gd=;fyP1y0Y*RGO$Yv(!4 z9BEschz4KT)9Ll+o|4Sq!J{_hL>oJEK#52>eq>R~N^Xwft1YTOc^z{(eV0M;6;Y*1 zLFY~5qIo;|0M5Be@m1g>c8b$~`KF0i&nhh+4?0$a9e_mGkxa+xd(^uqIR>FiN?rrl z`hh!dPF<n74~bdG-9-N7>VQp~eJ9rOf4&LFU`rVGpzZI=(M)dXEiz$1<_{nm>NC9s zc$!|)j8y_&dEAs9gcJ{wj%1E8`*-x`uUsp<fM14o<{#Z#fAI|g@Y=dX&cMs4s4ozi z9L9_LQ4|X70cHriKcmw$ze>Jwk&qj*!{EK%)=N@2BTmu4;L{s>rUIFAl&DxGnP|R2 z(>6NrF+xV!@brLUMX1c0_2jj@dOO!BcgWnadGBLC4j#EeR{l@!(x4rNot2`usz||* z$X1F~?0q|hEt@2-`wiC#ud^CF{cdHuW*!>-K#I9Iq$BtL;~<?SX7E(#04a2NC`%R& znzulNldyneAv$(hoh_#m2qaskYEJZ<V&4!d@$GdkOgOf;(h`GnbAy-%>_P}jG`2~n zS&A_t9~U23&~~4b#}j(JNlo|o`G;ct1GkS@mTP<xU)|y!g#R?M=)N*=5D+rLN@4<y z4@T9Eoqz7)e=TGxTb6q)CD!F`66BwX_p%@8bzEDOPbO{N4Q>~tm#tHgbPb>Yn2%i; z)u7mVZlOOJUw6M)uBn!f45Nj!N=>UXR%w`f{Rjw__4t2%H;y(DVcM|^6pA#D&IfuN zztxl!K<;-2KOWI=u>!s*tH+6cGp1k>(!t4XNwZ_Hosh+$2aBqvPjtJ?5y@iD3P(_9 z;xk!}UeMhMA36WN7vMbnMN*O+zyY<14`9pB%NySP!<<wvcl9P4D&z2rhmXAnOJVKk z#*6zU$4nQ`V%Puo?38^P&gYcATm7X7&jRzJtyG{5plhb1zn_i5MmM}<B()`DoPkPE zKVil`TmtY^o-JV5qkX0s=4g|9hjDZo1`ckIigfwkCO!ist?UDWDFL)f2BvFG12`~Q zT<4(Yi!D&t=YZrm&Dp2aG8lL45UKj_=Y{#OI6pN&L=4Z;Xi>fnH?A9}&N66s{0JO) zf#Q5NQ0Xr=w(!Zw<r$mK7t)UTT1*(SMPVLiK^1f7`S9rzPkpBlSc!v)0#l4{<Rm*M z^bojzEd3pk|B7+07|uyE1Ob6+wjLPY9a*X<PNBY`C5AYYW{6AnWr8?(6+LcU39w0< zvg-gXGAi}tXd?PwyOZ@>^rPt6NIT_JmWM4>_K=5E+J^XOB5d8VG}&FTRv$Rp7>+px zEH2ILIE8s%e&cm?j-Gm9$l=%Y%BX55t#N>c(kW1}t8uAUE-BV^eZWk1sYhit^I+Za z53Yp#_d|iz_h$xe(nNbbzP}Uv``H234!abC{pUZs${r$JS)Kvy`mK9L2ofFS*gQ?m zI`Ony{XHW~eQ<+umSg7V!l<w=8pWO(*FVfTw)Bj?0iJ>aiaLj;63m9)79!O*pL;>$ zD2r7CwUEW!LBNj2kN^N{5mJii^Wq|~##(2LPprISwB${<`>b}aTpR<S8#jDjC>HBQ zKo;ghCO*g6I&Bf}3pcd1YNrUvcF%9%j=z9u*oZc7zv+m<og-am&wDz}cWoP8nUku+ zj^BI_)Il(m1$4fBxBg@lQ$cK4R#GdBi@PAv8T?&o#4g-OI#v}pqJBQM{1Emugic1! zK%58^%!qCI@lBQmuM!3{Ft)>b0PqA2-DN!OSfXo=QGUUqbOsGDcD-v`?5Sn_YgM%8 zPbe7BMFVoIi}B2OjEXaQA8ZK(bemxE9tcczgJ<Z?_zvDYH(cX2@Axh6Tj$qT%_~-k zCrt*B|K?T`ind+q9eazpu?E^n7m%HRM?dgpS$;B#hexa`ZFNEA|5=nE^?8~`lsD=A zw{^j3p~MrSgE7)Z)IK;9HMj$I={<a=f>fvJIKU0pq?~jKfyoRa_MpS#Yd}CW?!1as z<r-g4YgUXN?BV){I&T~8T+>Oz)+$g5*!y5RO_~U<yDb8M*%*kr$c!M?=w9llmr<>N z^sHl$b&wpK;#$h#mrffx#<Un?K1JOR4~GKlQIsMy^8<+%rmD5q>H4TYTj?Z*PvsWg z{)c0bj(z|7=wD&(-nGTTYg$TvQNH9WDG<yo0j4`OlXGyYdH=EA9G~QZoDd5&SYS_h zHoEXZIocuJqg>#f8!58>H6o{J;uvm{kahTtoBowbr0$z0qrkVa0tixd%WZH`f)46O z`3jjUXo~CGDGYEQM3;)h@VKOJBxwjoMka&v7(}mljK-Kq)9}xfSD?UDC_0h`$tJF_ z_1mBNTnxiB{Q6@0rPzf8yH5p#?{XndAubyZ3{zEG@5*Ocr|5EJy!@}OH+m#|k1%o_ ziXE%;kvRv|v(Nv<+A7=wqKqr1Jp;InI#;`#?HrqPB19xCG<l^XFx#Y*ilLjN6u6x# zGFSKmk_Sfp!u6Ag$`_5a87e|`G!x;kcvQb9cZ^uQ;=}uNMAOd(A-y^5%j@^Gz!uQ$ z#`sS<e~#?<YH{>}X1^;CbzLLz_G7zzHT&F9{=PTLh=bEx3$?SgOJRE@I4a{2v&EhY z0Igt*B0r57eq~o|xz69IyPg&Er;$+Ufd*K~_kp+$pOvEQ$cf{Uq~r|3Esbp_-mkkX z=xe#Vo0$~l^}M`{&kCoJ9U^<@k}a-)QJCzZFC<IiqrgN|gx}G>MeIhxL`PDS+Nt<$ zrz_e{#-i0OsobjQO<YdU?!*U+Fc5RF%X`3hx^5RpWPe=BPST@p#^ICi9M|7H``WbT z$JyT;wZ5mWb0+;@bez&76(}X?wz7Q&k^@L?+G>MpE`%)<4nDyHqP~XU)6UnqvbJ&& z^O?df^U_{&CRgi=TVzsb4qK1C4Y0ew8~Z7_b<n>?DRzFufMqDZ_k&r?4wMVGxE+BX z%^;jA-l(d>HJ4kD6t{>UXc*zM-f5aqj6%7R0BPa%f&cZrT(5TVAr$00!83u)FFtB) zOSZeKekW0<<GI!6r*sGif-Q1kPFaRe9ytgpsJ;^=geFcx%RCutbk`b|)#B1}s7W*9 z8G4B;`_ugV`zC0R5h|dTEz>f!R^m30*tBy0<USAw9P#S;2B-sZ$|I9`&L&9Ku+e~i z9A>P^=w}fUpMHt(^Q|mE;Kr-zGt#atmw)I2Q$A6~1FDU7o*o}Tqzt2Fet9USY_Ewq zrEpYCX0dO5%+9oOn3Fyhn<nCGY#lk^RUUJ@g;1a*tqvRBHp^O^#k7Oz;GQ)4$FbS3 zz`yrYU}+rahr^g7igs&Wy^bZ?xB2<O4@&#LGYQppng2))eL<d<>a&^bF!q`sEE^~o zO>u6zWEn|P@Zy_VtRug4rR)3Gr`fUfNRwuR@JZ5+N4GQN)V@~Kep9kHXC=th><bEb zd!<X+buo8fXp<z)>t(c5%3A$B-Jw>G3=4;ryS?~Kx_yrAGpU5VOI$X_sM@6n)LnW? z<G)b(`bgdhSb@EM@*ynNvd9+CskijR`oYPXPiIqgGicx>yQ4U)y$R-ejpazKfj^i9 zH}tJC$G}r9@Cw+>nuM(l6a1xP7<{*${y=bTy{d>DFx&>u1|&<?w172Zy@b>ME;)HJ z()AN02gOKZQF<iBGpyb7C0!~9DmiKz=VB|@nJLBOKqKdLU8Zpf-t5)0r|F}F6mP9> zOL5mck*BUBu&_`X1F`C0t?Li3$h3e)VP2#hN`1TYo4g*GrhFBTZMWzCg~eyzrzNt} z01xE@g7~FmjQv!6p>YO$-9pa}-*_MAY;;^>C>o1BtC!$#5p?pELkzqfnZFHU(Lj*o zQI|wE4&-f?h`DF`UKsYYUO_;5vSc3}dX9wdE7ML&*s})?4A7*CFjDteyQ7DLd_pCM zIFN8Lddq>T;CqOmkISs8PSLB1fHU;)eAUlf)ffV{g{7LsVVnx{=db0*?nNktTd&Jv z8$9986eDDf%iYH=`qNl94C}&i-+(zgAU>qT+^>fm53I>#ZYq5R4km$tE5-_ovRT*y zX!_4ISc3bl*GiW*$zm?Tu+iECgltGYW{JgqTleQ+BrVR{Slx?ZSYYl&qzt~>anmAq zasOfWHTW1kSDzg5&;QczZUZknylTCRE9}vFq9ljWoP++_D`!*8iCBlKM169;tPfGU zJow>b;wi{U2p93SClY43&!ozSblo1Zq@H4iBez@m8e!bqIN$xOOt@*=U+Vwt)3&lU zMLWQ0NhF#l7Ht3BcZBP!UsYi2sZln6K)>Lu<9QVgTfFwSOuhE}e<CCGu}F5NszpNP zC#-CV2TJuVf^=+0ZJSLe0(hQuK5?LE@wntD3+@4!GM(_A3OYWGVcAn*Ly@$H_r1EB zB(G0_>OCqG8GOG5+^bb%BODf6toqd)|1Vz;HjRjj^4Bv&*q$$euV<al($`*xH8$w$ zs+SvcOYJcs@Bss0O}J~wGPewrm$}O%Q6_^(_!GTrLKaJmKL|+(NqpnxVG<3{veMze znfd*C?d~u#T$_;qNuXYKRIlb9IU0o!FPSsy{4YggCVYwK3-K4$thdeyV9!aYN|x*% z{6&58g}RO$?YB9tZQv)HivCo&*+WuK`e9ENCHI!Z!fK1Hq9q5{;Hqn0^Yawn==0Z{ z0!$K5e#Bx^Y^x8x$DLcGiZdB{?PuWaCm^8~E0&l~Ft-ooS!<CRa8JvPr%F5mh@AoS zEQ$VGP>N2JQH=*A0Z>nsopFK~M!xL*y?$`0;Ldkt0HA(K!!^JGVG{GpclT7f3)NPA zG0ob9p?Z#95)^n+w^y~I4K>~dzrsRced4eQ=P!k8@BFD){v&6AO0r$>l1!AF#7H)^ zp+`2A98vN%&iHau$;mdD^&&d6AmEhj6|AA;A|xphZ?g42MytN3N51Dpo1|)hqsp!~ z$F4Vt%~U@Vvh}ctZ?y@P7Wl)Ys(lm<-?altpzWe4jdY@%%o>0%YtZ$=z{riN02q27 z0|3}OL>8g^`1;!d2#C5fm4#(+01G_TxW4j(Qe+9Ssv^7D@yL^H@Nt_|-CDK8o4l3} zG4O#Mlenandqn`d<-i)ub(0+XO|DHOsW6C|5be1gT>}&bbS$EcMX<45cmu1`J@d`S zlD7*QWPf;G^bd6249BZA`%nL1E%iq0g<j%L*PC#m7aBB31nfBi7FFf;t2^S)uMq6I zYZuwCb3oYfO_=G7SH{X6nDS`}J(0*T+B$^Fj`*IS?-{z&5`Vm?PHPwDXfdj23RNpk zT!39ri$qmr$o|Xi*q6}h6Ir9bzN2r^V=zAN0b9;YQu5_CS(SF`UejTdpyJ+C$?hph z>J<E8+ujQ<+WN~*r8%<C)oQSY7ZbVo-E+8e9=9yLN~%U9m7n4wD>91S8)651PEmY) z-r&wWQBt7^8;voy+Pkj}T;2k}v5Be0@1n2+rN_>fhFTd&e>ku&1tYyZ65_DVg$Ll= zrlF#)bUaqp;TARldC2_a(me7~KeCi1RYa=&WO$Lbe6x*clD0xI-kUUeqNXn%e95Eu zjQV-oXpE0PdICVq(PCRqVr-P;w#w^jOM(63A3Kci(|Zr+?AOYq{o?IW%g>o>wW%u{ zK78vRc|xq_CF4+|w;PJNue&~5T^kAwVZG4=#b8A5Zr=f^NZxbpF2HzUw-*5X#j`iQ zYTw0`symtD%T8bp*O$W*y1b_2f;F8j42?exAZs}NiL$arUUBTrlQY?}xY(3x$<s#f z(DpQ#vCiQpT#A30q?w;ok$Cr2E4Sf3^ieu^6p*Xk*x>+?gUh9Rfo@^>_jH=}y{IQf zz+xCF4yuYncE0D-AcuAil_Zw9yT4IPK}uvRV&y`Q;=Q|*xJpoRjF&P&5Ookk!0N5p z$=w@HC1SsVsToEXj1_(>DPFNc(>jTZh;c1>Ck$=sQ5Dlrami%VpX&E}15CAA{hm4* zoy~E&kmJ0a!pHRK8nyUx1wQjq*|htBhu}KVj{XtNq>pyQvr)Bl!`LF%Aole8yi2hd zam&7!Cotvh=K4$K!r>E3Sy%t}(SEM7eoFTC_1vt;4ZFzayI_W(4_yFa&Glc*xGp;i zZn*RN+40;g14#QF*t*!U(xtEu7czUxlRFY^eRYrW)de<Q@k-&*N(YE%|HlNhWf^Kz zLk&9I>G!h2S;ypa?qHh>T3s~o?{#(?OL8I}&7n*CSP(kjKhpZ6dm95zp`(R{1HZ6x zdJR*%A+k~jVz#QC@!<|*ChJWvGW^Bc0IHW65C&6FlNAV^(46-%NXDcrC<ToV!I%6% z-jJ6cXSkrWbF4DXt~163<EQ;@yU;AXeM`yhk9T}7ajZTf#9^P--Ti%dU!CjpK}(`m zU`4_$sVEX+0K>K)uo*f<Xyu?fEVb?D=c4JIe;Mi3&oA5n2DAGmN8_(6Sw}pI>%8qx zfA#XozT-%8o0Ei%!n;E|S`=ju9;(~_?5RvLMkz>DA$<CkmYkwgj|Tr7to@v*LQw^> zpuaBGGjzu-X_$D9H-%v!BE2vDM=Mq2?u?6CZN(*};D3D~rliYZhcU$#1{)h^AAuHG zx(Sr9yIT=s8A|t0yu|t7HLEKa(|hEIF|)|J-s<s1RLNS;lveNCbj;|4)2{L&swO&< z1g)`cIh`!&(<8;1LJzk+IwSk!xf_0R1~o*2@1BxOx<}u0<n(RBi=S+E1UPFAS`kB< zE>;?biV~+`hCbw373vq9z>69k58HYvk%;tNrz{#Xu6=WwVcCoImVjs5r`#i&a-wb? zd_OFxk(=-kQFh~60qvI!zU7a~;uC6{dG%MD3X^+CQF~}(FZ{Fz`omKHUQhOc{FINb z1I*pKuhY?V46@H-;1E-;Z4tHk2{FTxyc$1vC^7G@05!^iCX&!5eVzAg*f0I>9s4x3 zMa`~zkDZ>h$6u^c`>sOJw$;y6JN|AECwvSO%v?SCK)*nbbyLkiv>X3A<&M{Y>z!ag zA#F8@y!%bgqQpZkWQn8CeXKvw_<7`p=eqrCEf<rjGy3En?!}7@QO3JW-<GgmTc~2` zR0Xr)2MpES?SEk|i|EN{&GI*>8yIv;{FAF3@47I_&IhuF5t5JtZIvuZ6X%>!742Yn z&572~1Z#ZQt5){Nh-@6D3O25?vmUbk7M4)YcCEUqf^BM7q=0}^1c`MvW<T5B#K$%8 zN0eT{Q5Y7K6;<~Ai_*akfSZK@J-1Yf!rZFdcE2f?@Sy44oOE~m2i(Jpsa0D^+%@L5 z&+Jn0-<w25D~!#XwV6A}>JTZA1pDEUIpbaCS6<<!3Qe{WBx^Yk?SEb#{_J&g74@TL z8%8flJxbI08g!k78lu6~#gfONyS>L=?+&}?rgE%q0cVq>$38}UDgS*L#j`W$aWrsA zN!2g>Fr9xf>vm}Lzsv7nM=;cQussxf+6kYqaXHLDL1ezq4-J$Z5bK9RYHi$AE)9+A z;!e-0$HZXzOqzBktFvXXXK2p>@!iXBje=vGwVXC*^*_g{uLGf3vVbRmRyB$EupJt2 zl;0JOpg++Kk~^f*Y5K9cCBpL+CI_+T=U7NSdXX>jksyv74nEIMi{DZo&jGZbfju6J zbpslObMegBMW(<|L0;XynFQ>+1SA`cYAtI5r4&CfMhgcxVwFr$SqM)%rX&Qk8J1jC zX|D0Ol87G>EAadPyR6mPEQY$h<134KaO7DjxSH-zjo&(ZBv(PXk|p9XFp{1v07fm7 zp_E&t+`_)GKDaC8?YLzsoX*}Y`M5%YHM-~zbQ1M57EBLov`Cu%2NOS7)O4@3OVIX> zJ0}jPtdu@b5&wOXr>OB|$Z6WofJrTWkZqCF=jwm8Pb+bD{K><Sonars5q}ql{5l*{ z=J`q1jD6K8vy^6hBOuNuH|w`&-{5sFYu7r+2S8f{TSKU55fA+D>n@=W1nA<;gT<}9 z8H?52UioH9y*e5P21vl#0I8qi43Yp`JtVpR9a~8tpP2`VrND${fHR0jEsfv-$13$5 zA;F{9$~tL{k~MaprbsfNHe1u(o2$Iq>tJ$iOCiqCaj>v28>-WS;TO@HPuHNdUGgm> zWg>%@)Qjs7zl^mCYpoj33m1!I)B=*R)rG-}l1-EmhdzmtNC!}@QlNa1kKTXFl1;n4 zPxRj7hh(zRO?%3X9O;&}xG$tD`b~TWpqjR=Kd8Pi)m+fcb-YIlQj_BB+MWDRYzT-y zlBNlXgJKQ&6NV0|K+iy?qV%9{?Sm~s;G!Y##ryVP)g3IVk(zCc(RJRg8hL=Su?u04 z*%Dh)Whxy50W2M@o`{FgsBhxV$z4K><V5agl8H>rN`WvwE?!5XwK=<AP-#3`wA{UL z?;QKrpCn&?Zp`r1zv%P(ZdS$?2+GWb{xC{S{4bOGg6!x>TnuY^!KNm8M(fZAdFKV$ z14j_Aeabu{Mz#DdoQUanLxofQc(lo8M%K~aW26_%LMec+pzYuK`0w0P63%vJd4X3g z!3r$AD)^sRGcJ5}l%jxB;G7)Ss5DHhqV|K}@?-suGIYldb*0Gk#HuuzXIDai=Ee+X zpan|T2OM80)Q5eh|0m{d$$YTACm>`Z%}r&-e9d!iOcFjWUDf|G88+o8A@2fkPWU#4 zIuqqCfIJpRdDQAgIs7i-`}$nX^G@nK_h(lX>9q+?dp_pvE>6FozKne1=V4gaAf?}K zpw3WJbdG7hob9Z4RVt(Q%C)0$=(eB6@NT`@gXn-KjK*+*>`MtC`C)L_W+Vn@mrp($ zzyYB*q|eAs@^YpnY}MOD(g2VM_<P-is;L3N4@m}nFPN)-xGDP;j$|57`7MTKMXNP! z{nz%HzKM|0|HTZ>of=Xfsc!|uxZje}w%K9IF6nHgAo0*>uCeL`)2|+jhQ$tnOSziK zAYw?TQ$u|certbmhH}v;-*oIT;hV}t+M^s{6}ryaYn38pIyJm5{}|caivqm3$V%Fi zyRhN#SdGy6fZ!VyBQ2p)aioGQ>19EBoW6Z(LPm(9F>j*3Hh~;40{3kqoY6%Bt87QO zDjdMAN&!0RPB|lL3Pz23E|TjrAN-GZUpK6cmB9yHBW##D#zvee1t#O=nU3yggMCFD z3CdX`QMEN+{UKx<wwt;)Tf~OF`$lpPUP2vi;VXZ9F*}i1axsVQd};~G(Q+)1#Lbfx zJn$=w+G7~Il9d?rQlJLGvR$|ssoNbY-2Na6RaJFZ@PQdA5Ir;G62b(|9o%lLtdnPN z=^VYG`v693!@!|O&Ku+*wM_^GQt3MCI@S%0;Hct9i*?*fVNV=hn#~rbHcBgl`(>tK zN@_+cp}6d+ipm}gbohhVlkD!TJAh35G=P3W&8Pk{-jkVZOj$HRr3yg;ON5%I<O4^W z=iW8}&@h?j{tZ*kl&2rW2IsUOy0%kg7_a$d?9SAW>mno5zp*XiI|DC$6lR7*f4-71 z5r|Lf$RaDB*-Ua;PR9zfRG;Rd*Oxne6KHGo>OM?XZHu<+Ue1>uob86E!GTSfONt&J z+Eq!ijR!bOg|j3tFdc8#*DJ~m4G5o7msXp(H`_myBCmZx?R+ohfMKoq)&RG<GWAfF zr+*l(Y!T0a;XIbl^G~5chfXEVWCvMS!+Ogc|2>j;zwpyjk~wnw?zS!&D7%^V({AVF zCrimofP9{o)#wI}k{z-=GjEIgY+L3i7q!~Hn8$W(>yUe>AAYRM(D4|^LlZ!QLx)X9 zOMTA5Kd6RF$4#%UGI5!aS@qnqFrhv%krxLdHJrRT&2Wywq;$yw%4_!*VaJ2CucH8r zSS!zKDq~`n1vBp%h)-LqRzUV1N&fBX*ayIP$=^wJ_X_hqdb}2O=99Uk<!oft@-uZd zcAu~JP@hgfVN?b_Gk;9B+{^7SkRi#^YkVNwk4lPbmK&vRWvHCsI`D?R-HloA<Q`&3 z)7z>EK)n5FwK{qCQfS^7?+2PRon7nE7u<J}ef941mw%U<hlKuoe?p{^!a*uU;xPpH z?xC3Tx8tBickOeFKBqn(2Fg>E!I%j)-(L88oAMA^H_xx|(mx)BrR8e=1#wdLmyf-% z7+;p}@G4BcQY@KJl@PH>S5yrTI4X&AP*59k>h2M0q}B4>W3BjXSG-?ua~O!0&8`Jw zu8{06BW7NS%FfTN7uf5dPyXZgaHnSs8mXu5TVNK*!)1#cw1Pvao<TczBK*)6=M}Jn zua>3UriSTGY{x&R2pup_5q__0;a+|mQ{51MX=@@=9zZ0pvfk@nL`L;1Ih3mJ3DE~c zELj8NA*h^56~pgYP+Cn`d{>IOYmy`fWU&bHhxPY@XfC(&PQrGc3U&O{eR)Q2$hN`I zF)!;)Mbo`ha{8tDEGO{r+E^2Q?nNf0yDiTPVb@~C{K(sD&$nD1lx=;5+}9uW?OTA% zDR%ff!+DmJpGSqfsb!nzl;Y&eue&cJ*ZKPFHF(hXL$8^o6+U7wWnbqzW@V<MWhi|b zFZqc--113@^n7O2(b)+`UXbHYqtwjRlU)vG!o10=D{4eLuzyIu2<RW^dAh?WW{+dU z%p>*V#9Ej!1*z^|u(EukFiL(^@tkVmR{QXkKC2+Z!fkC>%kVF;vo)b-X;W&6D!pt` z>scldNrx0@<$H)P4|7ca2~+iH6F6)`;t37wZM`{;L_Y-VGFJe;DczN-Q@d~uc|ow- z9~49o6;ksbhTRc0TEnVzGua3`s?xX-lxcAx!$oOMtUrq&$UHFQSwM^&Ntv7NaY4d% z9VEp{crr<2Ti<@*--HsPZ+*l5uIbRHZFi^G*7VmA8$tbQ$T!;b!qwVGzc4jM!pBP( zq7Ks9s^@-@l$|3qJn@bLbC*BTu$7qq@H+HxqlC#~=48!f4%^^m*p5(AhB?h<AV#$^ zsmrZg$l8{C5Sd=AHust>iM4slyI{+=44ZUq<aLU`eN;e+;w@jO7kQYtbkYNwT7t^y zXDtz<Ie8sGN#_*C4hn3i-1M}>0>Hw+1flv{nYU@kLs$W{>&Kh8aRF7D0|kN4ZvHez zpbKq}U(t)T0Pc-iZD&>HXIce4H<n_m2wWV63O4$FFREREHwD&t5ANG!RtHL+na0Uf zUEg&w?|T1LV@9<}mhj83t1XO?C2GE>kiP=(_aI>In|z!Jk;z4NdZ`9X@#X1^w?rvK zn7~gg*rrouyOifGW__NLkPW`PzGkuPiSmi!%SQ>M51;?T9V^=$EsNUKMJ=MH_czt- zI%tHj+}u*YE)1S+!O0PCKAbiO)UyJ?AQ^ulwqmd4c&nnLaz)18LW`XoYXpHUL}Vys zCOfw03ghhZRGHdc9z(-I!pQt((JaBE4R5``a}t~6bETagHdLNOob|tAh^VbV>kdb? zdBs~Y+F*dl-lkCC+*4cm?|8nqWT`b`3nOrElb||6$i>yuWzJ<l4jwOQ3%D1K8n@;m zT5K=o{1V0G3Rh8fU3C46fkKKgBKX6FKE4L8tm8(pRXu@IxCq?gAvr6c_zR`)bngpR zGctWj3RBIpUK9?x+VMn<n#m3|n-!WTD7j0DS4R7VYXtYj2iLUoy+jq<ZEq=JYxpQr zP;3ZtD-+awD)7Qggkg9yx`JOAOE`i9&^W=IsiG_`p`)-S*r1&vaHE4>$B)?>?J697 z^b(C+aH>D#({6Lva6bOxZvR`a$9E5TyJuSP^wG#(tTmA8POuab%RycgB&ICa8w}i7 z+3~rh<75xKI~XnN$kiOEyS1Rj6OzkP<)=WdnX9E|{#D3sF(xO{qtbT+sm<!z?UAwQ z=0#}s^&Yn<0m$%DEsfY=gc6V>LOEbE9mdG$Qi+!E_J)Q`2_)?${H7$3^HV^Z{m}~P zc@rVGZO6G@392w7$b#9Z+h`d&ZuY*S%mZ)2z4J7{FpKT&+`M&%*VwLPEVO`FRI%lC z0>lX>Ld|X32I(GejcXu<E^B<qqXE<!FUxe!J%8bYsk^+M+`m^qw_?$gSwe{HkdS_B zwqWiF>+v3{CT010d#as9UVnrxl8TcKH!*P+LJxaDO@x_~-l&D*PN)FsO&1KtaP8Y9 zuFv!`wPfADReNy+K8}K5f58u;k1PTJ(KwE&+azA;BOCUs7%I@qmlLB}LU&(z#y^|n zIUK+H8HZVjq0mBwini`k%gh5mz*8V?0CSJ$p8={=pc?v>`MY!_-4oCOC?@mY!+vES z!~>SN(ro0(u&RwB1+_P3r+?=@axB>4y{~X|tKH%`=7U;~piRVx_m=&J`ob1!*bTny zt*|UWxkX7}lKI|6sD{;ZTk}31Xdka03F|iQ86%-gL@xf8$E9E&{~7_^g147bj*ZLp zu)ZXX$G}rEsAUp%Imp(4T~4_wXPx+dr!KO?RLmmi_ii@Et=z#*t5189-ex0iZc~r- zvMQbLn)u|XZ^EU=CTmYMSz<W%d)zYt(D9WLfrVB)<Z-iUcIL_xk_5*EWl<wGrUl$` z3M`XVLr$s4{H;Vub@JJxMLwI4^3?vRr<Ql%Ui?!-!~64s=yGSLW-HZ#53_g{g;W0< zytb*ARm*wtt9M7END<U~%h{3ZvbY6(nN<(56rKyF`u><$7;R~ng7T{dhn31cT{kqI zYn+p6e$=~AnI|MLUv*rVTy(bLMJeBg04hrdo;SCip`Atd+!s&_rRF&rVTi^&Bn8tS zz0E!pf+-T5vnB<DYRDQCVbg@rYAq>1y62e~zI-v^Uw~Sk=Q|=KM20*zMz91b-X;k@ zv_>?Nb%SV7Ss>VF>FH@V1h@;v@PH;F1iv-@dFq39KOZa|HoZIr4T{R3MM=0=H%8$M zuT?!hup|eh)@G*NQqq_dvHGog8ubbsuU%YlbKWOgu9S)KD+BsZ+E)EA&Ib8okBd6w zLp08i6aW(EzUam%XUmJ%U+|w&N8y^}Mh?<wt~B^|6<9k@NPU^1ReuF7Y4Ia_C|EP| zn|^a)J-FT54I>C*W!j8F{TBNnHXcn3RNbomsTqIIDS>f(hFC}0TjXIK3Yj!^^XmyK zqYCMk+tylY(>&da#+N5aT-CyayY^{VuUt!0f5Dm)3DxhrXa@{K=0=%%O)KVM!hDJz z&=Zj9pAj8UKtXt`zd?V`$<nyTL5jS5j+tv6){qJWqU=Ne$;f&z@Z_mRf7>_T>GyTU zsTaQBdzeG-v(fTqdO17q=qBIJQ*Umuy+ep9tmn-`J=*xLwR}BCL20~n^E#hA8)@ip za4<#!7q!I?@P9o*6|kw9HXZ`Aj;<s5S#>0x1?4_+__Rx#gz_plpa=Sr(by?L^34<O ztrbn>A<*S_0)F@@87&JJ=gvJdV`(726}ewmdxgu6D6S7LINhYh%Ot*Sz5AXMorn0K ztglRXR7kqZM@wnHuMGkB4E$6WdRSN%5imdMJP-PiX_O7?mV-nGy|r5O<nX=bVXiD* z*c#LY5CI{GZ#Mrx{u{dUgA?5LVY<yU-jDA?%?wnM?E-wN@Qv)*vX|S~x*kaSrH{?5 z@drji+gIo9&4kIPtc?>4*<+X|maAnRlTsmw-o~n|5aB=(jzVu;nvv%Txhd!@4ezZ` z9u@xJSSZk_CuY7EmAw)Ae-iaXL@(rAIe?g61NS<LO-L%dd1iOjsD8m5%Mc-DX)#(O zWrAGYs8>0tmZh1vzf~*1Z64~f&2_iPJlqdmStWeBbNTlJT5a*=gP#QQjbOB`^WT@} zeEWNXgaW5F2|tg-Y7g{Ew^4oD29Gc(bF;#QE+F>vxQ*6KD<SHITy~bwZ$e*^+n#~1 zXNTq*X*?7;w#H_yi5k(;QFjp>+bbl69^19jnat`_b;7dTQ9~}ijHLe>-QOe6tqk0b zPX~9$A3PtxBYfJ?sy}CG);ey?KHYbgQIBXElP@g`E@&0fKCE3@PyKHzWbZuKepFM> zJo_!IxYnN=5GK6(_Mea)LN7<uVH(d<l$dYpQP}@wITF!rwoB0<z$=PJp=~42N1W_} z3Wa5M`pD6+vZrOW<}z7e@WZ#@y@EfDe4pGU=0j1NcxQwb;QvGl_5Jx+t7Vy%rg!P! zR4k8h;~TGZulfDgiZ|u5NCk>}<HKLBK4X4TvN(DUAq)SI60yFqJH=%GbEZpY>h0x~ zc?jJCwy)AH;_k-0ZaICOALP%I9TkLc*?g3jMM_C{&1e2PzhQd%P*?wv?%nEzW$V4K zIQIP&YcbWZ5aAZ%>%$Y9BJoI8^_}?rlLKbhcOO_;Fn~PyRRnB-cX%A%`nadCKh!)n zeu)m3xcoopnKj;&)kJr}>9bk6?pHO}?#2CXcR%46qH5R0dQ4-K?Ryjw=JypIuyT!& z6sg$xDpj-gs-_ET`}<wD6H6%Gk9*mBStPDVpRfom15u~8hnyc}t3Nyt5+{72hcOb) zF8`=1gjE}llr27Tp-HH(X7~yD|8b|U59ihF{q=NUOzVYAcYnLfxtzpnIfDM2N0_?T ziN71`4gjp*JV!quHMc$JO~?Lc`If@PIOWs2uSA>MPfdR_yl{>!<lj$TJ+E(ZcjU^I z>q4-++Ov;-_TTbdYg-J3=-mC#c322-$!n9}3Pu26IPUw_3bLP(0k+Aa*gF?f_mNe* zHokilGr1V^NOh{VYy-Pkv*7wrQ!z7F(hB!!cKQw79c9`+Tl?N?r>$O82+luC<Dq?y zKLzaJQ$+@NV9;k_LsP#Qv`*UEHgddQALu;Br?h4Ds{=xWtPuvzQ8I&$5Xv&%Wadf& zy8W;p`mb)C_}_*cqPG79R}OXpL&#V}0fvzny9))nI05UT$&Y1?@qQEHKbT76`22Uf zPQj%=2v@&H16feBz}d#>8tyqZq)ZC%igkpjG3t=?$MtRn7QPTW`#GH=T7aTS;~FX1 z{l-kH$h0DYx^LJA^bCfpqkFl9YJQ>`U)ws$wKlLfvS&}#bNf;xYcH?=@DN;)kayFY z!jQQ%iT)jDl4s#SIy(7&3MBN+upcA<M3;l6N%Z3guezQbP))|{caTPVR9Q(?q*Ai! z3?7FrLxol|cLHlAA@-yKyG*EM0$Bh}0g)Mp>`XC-fYB<CsAGts#Skvq2tiiS@b#hm zHU;;e-_N$Z5ZA@nh}dhBRep(nA!-o0v!<;Or4-Xf$v(RNW)7K#j;ofG_E??CN=<7j z#yYmhhK(5h0|Go92-8jtX;GJ+7P!$DIzu#S?FMXhzP%rb*xNq*wj$a=OE#hy0-l5K zK<Phts(2V}mq{;6&=ASVIc#AifDp@q(9D8}6$m3YA~^#IO#tXHBALWB+p68v?R@$Y z(!VDhL!W};G0?%#;V%+H{zUHFH2*r72I~Vv<XZYwut%-(C9UwYg~!QJVtTz<%Is+X zVee5|nSs<iY7>$CK*L&!-=<p*fDx3s%794MDDWHH#fh$t!5tmCXFY7s$j?qQssImH z;v7eI%$}m=qYC8i+I4+65%+%-orgcw-yg?6ci<Y=9WL4Ky)Leqy%P6c*Iw61DrB$7 zEEIL`HL_hJE9qJpsjN!nTlT7K8BxeeDzv2G=l3t1$9a4n@AG-RU(YAzL#U2oVwg-R zGy;725%=V3{AvFDTS0$tCr+FGL{D-tt<=p!%}n^I*GXG`GAyCf)&V%OSJF8lvH@{Y z2v8m+BDp0juq?<Dh;G|@;SKz{(PUZ+0OoC*LBW95gHOt5O*E6vnUcJwFzvv=?^Evf z>n}6`dwj1$0mN-kW*zcHd(=+Hjz?UsE8Hs+??>}u$+C6*-5o2UybeikEFEOjE3JN4 zN~KG8pIT{L7tJcF>~ITENX{rSth3Wrwivu4&TT>*7~>B8&XLqg`u!=|$u$36Z@;4* z2wU<V9Qz}A%J>N{{Y1K%IV}kid)*WL4D2D)1}^^O0#AN$mp_Vdo~um^EHHqM+VDnA zg8?YOR`zLvas)c^0e;wq4A!eKFUZg|6kHWqrzq_Z`0hPGI|`_NaDw7rkzk&WGrrw9 zJ1-`>9`IG>cO%r(uoNRVGm#e1$bb(t9rVbMc8F}<AZ*llqH+a2!8Hu*7r#U$lI;0N z+u%ccTM;F|S$6&VnhNZz1p$lWk(;4osNLcPPp;)xArrHzm#ugOBM6LEJB1R9gcEU9 zto@x@X&*-z|0KEtelJsI?vj`rk18+2+KN%oentkgNN@8^gv>jbd#UQO#DI=q-@ySc z4Tq%tS3!x;*t4cTYFP$6)Dt|N(+>IgXBqS_hCG8y(gt#@Ef5=Rgv#r@;w@nHEkmeo z2C{9bCQehbleJPRBW<*%o`H4pJW4_A#MB&1P#qFzdCwu^Otz`jZ1NMqNt2ho8#kJ& z&^e=2DeF=0IT-wCof=f)!0b9I9u7SbV=f51ta+wiHJS*FTE8xFP-I{nuvSRkQ!Y%1 z7!;YHj7;H3=Kv$b6;BDooPk2UfaZDWyu!G^G=<qT@Msb?A=SzgN@>f8io*WY$Z>Y% z9@A{K%>E#qlKXj-!ZDjG19sqXa)>l858y6xEkSHlaRCW3j>Vl#R6<sG#yO8J#KXlz znScrdra_Q>di}BtX_U*+X)G;rv&X`T%<Y`fC9rNU>CT0gy3s2@)c&~X{4~fKpjI?x zFH+%aq>;HOAL4&6%^fVg6>bZ|&OWdv^6s#mWU3p>l~CvgeTV0+AiDZ{hXI_J@le@4 zb`H-Vz^R~m&<O(rpyg36z?ElWsboU}s0G<Tq&s;CRybK=0mlun60S$+=p8{E_f++R z3NT%v8DlQ7*^B*Je7{Zt#ai{N)%=U}A>L?F7;B!M8U0I$I`*_jR>?Ef8vq3IYM~0F zJmLV-8GBAkRZersln)>oc)WyFdW_pT)KZXfz7_)gd&6sRABWv}-cY{@n8O~H?}qB! zsJhqei`OXjuP4<c11m$ODlFbi3oZ4g8cE`ZYJkTqlkWXKT>O_Y_Nn_!)FU)t*d$Z+ z%>fH;b>MEBbZF0i>S;e-R|w?f%1~9sohrf>q(B}0{=y2tyouoOmc4t$DNhQDM^NrS z-sC?BDB!u%pBLgmY1d|X-PE6!G@9pEh)xr`2`ctHiEb@kR@4a@zZ^~syNg=w&4I;` z)9qho+~tr}5?QKS`c3I|%&tw8a2QP$tI#!4x+e|r<-B;7;T#Y7b^bRdg7X&~9iHns zXa`ypmZ?;J0wCp`_yPQq*W=ksJ6sTsW?+?{0O{W)Et-3PMaBZuD!)lJUMU$<g^+k% zagoAZs>ze?@N-}E6#{}Yj*RpnEieAFb0j_RAD&vb>RGYzJ|cVEyG*{bfYqbT|0=^F z5r3CMdrMZuGhJ-bLnsd}ZDrcTL!wq5eseFxsoeAIS$-*}1ab@s(70ia?K*(w#MscN z58SH;!d|!DuFhGZ5$-(bTsSV|BN%7Hl3gKQHCa4s`lQ{Q(QaZY8z2T`$*?+uMF2=x zYWU5&7oNF1=0LQ{)5_*Cj#;vaP>V+wxw_og^tCu1dm?$`=27OoLQBYC3#rY2>dhAG z8no%C`c-fAk9?+B5zS5BN4@DObRGRjm!X47_b9Rd=i`NJx2D**TrzAg>lc@$?a43O z&Uf_O3;e#SPN}cn+D+og5$F9V6Dqzw7Y}9#I;(0>aE}TGc+|wl<4Hd}xCv@rQs%D0 z*54VJ#l16E|G77I;%%O#K=fo%X3o$bwi2PPA{-h{3RN6Qu4_N^4-Ci18u(}iRh}I^ zXt(B-u$=!!w&)n2u9J#AHvzANN$O9;`%vWRf~Qxl9ZOSXJxCI*V6V=J?!g|Sc(<fe zf<^wYn``Mxv8(e1%bHeB`9%^Y82om}!E9bE1D?oSWc+HSNxXb3zTuh$=caO?$s`zS zHk;JuoCWL2x&G=DUk_j0B#-b75|rO6Y#g)!2J&Iwv~X|pVOtg~65+*zcn8xsCo_N- zk;Sp6+<C6f0hWopfAf|-s^><h2v67B{U)h8A~a|q=Xn^`=mPbfR)GXM&pG7!w>=uM zjiLlFMS&t~S0+a@^?fP@PX}-*6bO&AX;F`wE+zV4W169duOcPIs|k@8JvWYb;aw@h zJ%HD0KP-8Kgc=Z486c@TP4#&A5viZy4yJ9dNv;?gJINc%iQ@0MMo2&JoA`P@!HBO? zK*-y4zT1d?nBq|_QBaUbUz5Z;GY;f6Wa3ZmM6Olr3@ow87y6{}ObMtrI;oI{8#@1q z1K0ZY=3vf(pp7XYFr+0!5O$PJOZ_&JsFvA9WC<Q|>M|=u+3-0Vn20O<A#<isD#=MQ zm;@}bOPf|vdWfO-@o*1Yb~6A66Ds245YH@9Nwt+9xv3bQ#9Vgv;kiGZbU!i44uV5{ zkv;s{y{6wMNxJVa>NC)(d=SaO>OiE@PJt?e>n3dr0kj29j~ggveh7EZ=@tB8UDPT< z8kn>cu79KWxp%8mf_bQ9L-ypkWc`LigH}X-(x(0_(bi|K-TDPRzR$XXd#T_9KE=(% z#)0MckPNNtubS?P1D!lhr`>ha6aW$jeysO;srzF2yH}oOKHR~=UECxJ{*To-U_zRm zCskD_`1SA%I^?vbjdWT*dF+tA0aL(rjx|B$<xlM_^zMc`fWA>*|0RTc7PgtiaH<NY zxOkp(A4RNrHRhNk(@g|4JFPC6u;df77u<u$lTJQ~?H#jvB_}gFS#?M-{Uz(F(;B=N z_wv&jeqZQ6K}R)-JjB5Xrfd;KR=7;0hba?BDe<uzoTU<Gz?dEY;^1>FkSUW-F;2U7 z<wN<U6xRgy{O@1sG!g~g03y)sT%2ti$V9+kid)FZY&5sMeK8v3ZK~vNx?!mdCZUBF z?#CV8YTN`0%AE+nzEzN@v+tr#h71Ro1$TfJdOZPpMxuk+B7g|+H07)L0_xrKoPHvo zc;{Q`NYkvsF2|M{Jiliy;m5UwrWx8iG7bet%yM;%RTi2uE&fP}RZ*}`_OY_oT|`Hj zRxtl!hmsTXib9W2@O2r2bE$Tc$&WnufYdQq5-zwa)0K&9=({5iO>*9Fqh-FS8%chW z{&dts=>XkBUEtWmp{*thY`L>2sxD?x9l_(oS~N97<*eBj@r)+t={-`TXJvA0kSVP? zf~Q9~*?X$3I3T4jrrg8q4;d3wz_)5*Pg@&nG(F)f?;BG0{ME_WIY+{l6oKAF+-Bn0 zom!)ya*nZhH?RVdfo!G7etsDyo*=@``IqBg<db-OA?aPx+r~c6>%w5UMLO~j{?vyg ziwDhv=qsvIO0%M5af?cx#7K9O;_I_88>b|UgVXKYAU`TmYu24g*9JO{xtyxiHZfdD zAZ;WV`Y6e$y=iemOJV@9E)W`M6?xbl(%YK3keFF?+o|C8tS9Gvy>)l<b^pv2(!s`y z`%D5HSDVHdIu~a7cM1898%}WX>Cn1!yjoDvNmv$OON+b8D;3<#?cxC#kD953wlT>n zirP&SdE?d$bNJER(uEFF@eAwt_Kz|IGA2&3;lnuhMPJj}A)bQD=c0pR!2u<K$*)sb z*Mi8S*VjgqIMD1vbl|DR;CF6Rkx)3`=rr5wm)OsF(#pol(C71U;gfwosutQ4!vAuR zNe-sseR;~ha3^W2nUoo-%-^_Idm!#tUP-SM5=ZVX-z}-6?0o!aQ|k{mzf_DRL(iS9 zb^SYg)|8-p=3(`5GFUFySc?e8Zjm2Qy5yWZV$+yB07y~EStbK~2#~Zm=mCq;y0l#f zMaI0%8bj+=IS=m)EnkND?3@gV4Dadl{To!rm$J}Ib+mak$u1Y)3yEGhAN1jEwxGPb zlY&z)Eed62wow4plm>+9PENtA+8q7-iAI0AjiOWyIw0Y%OrS2Rz?Q5#l;!A0)&B7| z32Q4@baNRKY}Rh~xh&h_9uK(|d%;<b+#o6DRq&fz@vwQ|t9<k?Xku*l=55v2aVNT@ zk#j_vu>$RonL$w)7`<F^U9o}ms4MV@7?WTN)}n(aE|pDPTy~GES!<kLz%g-3Oo>w9 zt;t}XHF0$&WHMt#k9oxMZ5WG?r9|QA-e*&wv?h4sqm_UU2Vgpf9iZ;_nX?7jf3d-k zZLAv{aXbKG)X}Zy5)2*$r-z}f2r?6Qf$a06q}t8p<n%!2{KTU4U&k?@-7^)Np~}aT zVl%7iR5SS&-uPaSJ4Z|udtn-*Kz%2p=&g26w0i7{Jw(UV7_QVw*qhdx=_IlM{xC4! zwVU8{RIG<dObKnFs5ymIFti8M1gQ9L*X$Q(9SZs+eErBKOXdYtcaIP6uc#|sM_z<e zb9T#KC?p~Pc_f7+U5GQIBhwfG-EfXDD@`z*G*)o!)@V3{$3S#Ej14myiDv27IX;uZ z>PeVn>B<fV9;iJ0oqYT$A0@K&_=uBV(sIm3<iVzWPU~WY?1{6%LXHN5CrjArAI#+4 zEv}?Uj+K?h&A*eFTf#VgB91~%oJ|mEWC-}A3%GV0szMHhj55|c5)sO@E!v#3vm<~Z znVfWRm9<*bnADt-ispQ`CLHjDms(u_=V_&E!?uPso!B<SRJS)V9pB-JQ0n<B)F_#= z=dHrGjM&|V1`wdt_?Xi}16Yq9^rR7Sw1z^`P<I(ZQ=@i><kl$1IONu@d6G-#ULc3< zo94MD>J5_`yY2<o%g)=m$s-qi%0<6k{&dE%N(OWEuEesb>W4x?5w&QXj_d#vT)>2m z<hslYr|y3Y@Ugv&vnhLAbXp9IdVMb8fIT7(RnHyYyz?^XF*lS9>1_k0Tk+CN<6vGV z8!ZQ$snJk_+Cz0kw|+*q;TGgL&|&!Ph@LL5VWMWM6I%OaFStnEDgQ^Ey3A=lsrP7+ zt>$Q*d(jQ;JQm$(9?&lTF%GLgUxsaK59@vQhseSHr2t{Ycjb2tya*S(3Ey7RQDI%d z8+|cekIEjZkxN%E)E+V{QhtvuoarxCzDxVB$T`|RsnX9T=vDo6qmBu@=Lnb%kya<O zZFslv0G*Vsodhj{P}g;=O1t$IjdlP0r1Mf4hx=MUhaSCQA)regOv><sD%3=bUntfB zn<QKLPOCOHNXk2{Y-cVhAP#Pfm@lV4Q{~vn#fq=>ie13RX<Z1f{PdSYKpyDi%kPRp z{7e<LIVNS3p8n|c0Rs-j?A$wxsb?D+uRp!1V}F4fJi&vLhyDY!3!|agXj{)PlCd$1 zWc{wDBG$Av)@bji?}TxwSd3A_W2SLB5kZ$lt&+m%-}Rc$@KO01R1S4(LGOCcb*d~E z-E7b{`CPxEkXCq4c0hUQ#lA#+%*gzR0`*FV)a?<^F?}`iHmgPx?8E4&<JLPSr}h$e zL44t6dLiBlFqd`#aVvGvX;}wv@A5E(taKk|3~QH=lb$Fh3Sds1?K$L6qL(r-R@*|L znD%B~s?oOu{o3y12Z_eVG9bqrx;3CN$6UL$M`M}Y`I%l;4?^g2-26*hUS=SDAn^ue zaex&fZIyv+U}=UJ`v(;1Ox8+OwNL}+f6ot#_dMN8e_@&i%Bb_Kk|U9!-#TSm+uUQ) zX4h|`9!;~jy6{m9q^on^v0m4S^ni}`xyP2Gd?yw!k&lcvUx)OX$lp852c5lu8M^wL zgn3B9Je3X4ZP`n>S^4Ybbo=qWpSn&D=@8O~s|iM>#)eTptdtX4LxR?>J-&VV*`vQ6 ziin;zi~qFi(RVQ)d|hOm8`3)rWBVih{@eTJKlq!Wn_14U<z&r$)-`ahU+Q_C_+RCw z=aGXc|B+!Yug@R6=NQAny99bKYMaohU<4Kv65z-D(-?r`w(_tUDc2#_K3W3PN8xpp z3^5Xb)NSk|C2&~)z!(EU=M#pS(t!>T09)htn{3PRHp`Ye{^MiK(X&Rt@AlYpI{c)k zvD2G3k8yPn%x{P<fc7-DI}h=)`r=fO$A*~{K<86pR(a<qICEY?5d}Mn5)MsiQ$+v8 zQhhhj4Cs*aC}j|5z&RuwfW!gGZ_iT+qsVziWGFabGGNjDzqn9CG@r+IrO6FWUu1LL zd-o2JU;0<#RPFHzF`<Xv@nRa=Tqnk0j+;HwHy)#%_E(>4r9?ZV^=;H8WLk%8tWlY2 z&H>HC7!btsG^DVP&`aBL<W3rHml?%u{<~hObI<Mj=Euz)F_%ca^I{^5a|BPkH!nj2 zm}ygE^^a9?=7lvVHx7~OJk`rkMSeD0I$V#zR&4!e>M$+F=y+{5#|2R$iwhK{NV%bE z+|zaA4>~}-OZ%mHqZv%VywODAluv??d0kaEgEUVx&P1Q;VGlvOwv?Z0iuxcKl6*Z# z%oEkB)(o_PsusiL<M|93#CR8v;^rN@$~Wq0W+hX1JX0qVuS-M#qo9skp9hpQq~rhX z)JPR?F8SWLw23pb)jhD#kc$7Nrg4;u4+&$cXzX@i1#ESRoQxpa(aN6ymU&ReC}EFt z18X<nKrLVHQ2k%s%n(JwsT<N3i~;n3`FL2K>b)Cb(2nK=pOt_d7f{gyXZYDk7`5}q z>6IMYIG{Y+5-sxbH6!5fh70e}_7{C8IK~@J0F#?d+1&b+PfiIvqN8j;Zx;jnJ?woy zui0$D05xls4$`LKRzxUUd&Z*@e13afg3&iQ@osfH@mf`A8?L`BZWl$AiW#=&lGOV0 zc>Qelj|bIuMj%!P_A-3Vq4LY?ZV>$kOC6TFxBN6@+=9zNN1<L@BATt)EV}VLduz|K z!Qq9aY9;PKII}+h-hA$K=3;%rZ0fO+6MfyKDU19L?k3K&-dq)92eKy+%O$6!o|4Lg z5^ObUC(pytQ_?ey6|vaA+T%>a!a{+^l@vISCHq#Q05Nf`h~MDo)jxy%l8k}WH8H>^ z!bRfR&WDrRS$_uWvJVT&*hq#fpaNl#ilW_tZOIK9fOfOPN<x_@r3>KAt?4Sz&93yw zk?SHriQ9YFyghGg!g@lofq6iA>}1A9dxq_$;Gz8g20xq<SW0B^TaQ9>*N<C1Y(Dw1 zE2JORAFawV6k5Wi`CEMKUT^9`^M-(pF1>Pmw3M~UCeGYMq|MDgNMyLk%V&5kkVfC5 zkU$4Sd{3OSQ47g+SSuS=%_@>D?99Y&iSI97(*kJOaR<6vQm_~1J^0(587ozA2#Icr zT^36yWz*zcI>`=?h}8i05VSflq^o`m7*#n0L8QFV?-I1H`-JW8?tXYho5kKSSBBuI zzg##fv*NNZ$Htc6@H^L#>_tSO$Jx69y}e&R^ix)EM6(--EcV}Wgpoc(C|w8HJVU-> z4yKv)Twu+^spkv#&C#sw+JwDDI;RDjoaXR^5%(D@pqJ9)R5ZxwfJlzbavt(jvx*Oa zASJDX$NIhvqzNa6iqv_UZQahv19e>cJa>!KitWkFKj){_GHYteLDy%0!p5nln_XlY zFt!5B+#%d8>J(`m9>S?dmcxgRY?y<R=K;iX6sn!$tEd%pH#1W2J*i6vDdD>k6QxNN z)MceW)CNf4rOHP|8)gZuo>&GHII82@lezr`3$~`9)38V!tn&i6ldJ>^dm@tCFUR#E zm6YXWnb~EG{hrdNz1Nvlya!1lYMNVE1zC0#vjOnqTC={dmf~-#u5o$J2A6szQAB-M zT;yfb^A}kjxvQxVMuq7`hhA~tL=E#h>27l|g`%eh)Q>ceeQSKuJ0wgINKpkL!8<Uj zZfIt((z@o;f?;m>D@{oFSv-l&Va)a=_YnmD@JwF!;MAyn*7J_!r7h?x>R=hwvTB;u zrJrIMMFWH-%p_TQ5O#++;oy3ysfG(B7@&)5f&c?#fkRe`Pz!ig+)UC+-#D-;heu*S zDMa9DjfaAx(^56rtJ@CPaK;||S|Fta)-y(@q>UZw$&<?uDvy7!GdcIxv{gvD!OP}c zVR=0cU7jlA!{%khQ1!=na@TB$SrM24X5vFEC8nG+ft2Z%bc{8%@jY8)>8`0)vJ}Ia zY{^;d1iXJg_p{xsNvFes?<Ite!T4gaE*><ZJTlYwGXNVk4V3Fg7w{c!)#s#IsH87t zd7y!17>Glorin3W6<Q}~&f}q{p5Vf5*rYWOSCNl;Be8@1xu6`8razzk2Sn*#NXhD} zna`;GZn~7fd*C|!7`3MUXfTlu#oHp8+C?b6#G-=wp<|-HWk(R{8zc-YTxf4d=e~ug z;JJ>~_rI5JKNlzaP`DgAGWb`Hp=`F9T$D17d&0oosz#8C8ZtM{CG6`)?eTBqwv?oT zo{S$Uy7&z`EI^65tTq5Q;skPjVdXVBNfbLF52=SQu?}<cs5@S)TR}bj5+4d&vi1$- zht-Oa4mH09UaW|PQ)hH9MMRfvu9~%$gFiB;X8DimABNp+_c=E@vQ1Bs4emhtF9{h= zaAL#07ddjtpY-6eI&%=TGA#9&e2XK3NaFR;Q4uodki{}!r3FX7)V5Y1&+W?IN|5CI z)lcF-aJHmhU6Irq<Af54o|(GBfTV^wldD2Mi>+@6Hc+|)KV|-=v%%G$RPpA|>=^*C z(~Dg($L8*%R*&n&4J(O`59M!}5x`s`L<(MXOvsq_bWXw|)NKApie50CkHWi4UOR@= z8z{f8^U?0ER>ix{x8vBH<#LjwNn%3l!x0xzb9-XYmn8pf(Zv~<)oWB%0)$<a@BZ72 zwuH)39$gl($cI0hIPJ*mBM(7gk;=W#^%3FyC*)&I1ClQQd)o7ygLfp~KlQsfyd#ZF z(;jbEdRr+YH=EqnBb7pDXp+282_7%V8SObUkx=EJf(~KMo$HWK;j0ag+lQ{sjvQpO zFJtY7U|Y`civ|cnlg4paEvQjUShOb>@9=FQPa`#B%NzSiHN~(kA)d8Tg^te)ivbqJ zo{1gCxMq_xTFmuBm-|K6=?|m;|9e-T-7SP1ddd3l?($chdARytRLJzbyV8CmY1-Xu zuPyZw;WszEkbEHYKnH|^g$tFV^b^v?DRq4r=6j3$qyFHS4&)}=$#Qk~%2D7`y7aKk z0h9;WyEFVRy+9u?A4kto&yw~~+TXu7%I|fZ&ugsbi*(lr7G^8GGVGb9s;80+`)P`W znqbitQ6yzf$-0rP!}q*Wd2Y6}pYejI-GTn{v$yQ~;O(Ex{#s!1KcvqA*)=P8O%+<V zDn0b^>n;WHG+6`Od9sxb2?Kbx0W_y)+RGZVhF8*YoQN&b2L%8|Q@sKu+~TXaKVb7Z zN{+9=i^apOAT)xFBmN4==sW%Kui+=IyR=WWp;*2}qaUl>;gyne=dnD)pVXJbsT845 zJW?U}y3<Q+edDq<y~3g6ulh13kFwQs?^+Od3Xx;wVo=J<Fg{7dqbq#1=aW}2g_5E; zr{{Qzk>Orx{D|qmx~P>ja5)OObSMsh#IO-a9BOU!?q*YwIvDi?3r-<@=)y}g16SQ? zdl%QS!@&74E})&Hu+q0DbpIa|&*x?(t!Z1~!52yl8of<BkcP2Gpjk)q5`L2$?8e#E zd=#*LCWDg+RT?%pjpc0Jc9YHBF8Fed)5{R*#n+<pdjGy(qwS;G^P9R%Qc8q>GMCP6 zSU_z6D6dkS+%^4-bL}4;DFi|Uv4!t+AeB}SXez&6*DCEj|F(yjEdXh!Bblk$Ph_wl zz*W^=0A3;Rip3Jm{TRIUAdR%eSzG?Pa)iLMPv6E$dcjcUUIf`5QwOXe8t7WW@~BAn zki90!*lmKE7T)Ve(na-}eLf}x>if5GI~o0Qt0;6txYu5t;v2Dx6$-uRM~gN93p@t9 zUa`A1x<;IOd6#wXYZ3ZK7O%pKs(}q665V-#tnlC<k>ZJ}aalYkM!S@@=}I$T1f31> zqa*gQSl*T0MLvR`4K{7Vkgv;vlq2n|+_4+cr)t?p?c?NsX+W~k(X7CoPQ@R>V=xoy zb{p@sy`&aZ62FmUF}6l}%ThEpV5=x?;D}SOeZUD;wYTpxzbn0#ZK+W0yP5E?c3BI7 z7HjD;Vs0vbuZJHrNoRZj$av^wsP2i4Hl`{6M;J#s06UF^7O;8$g>CRHArBT)D_RgK zd}~jXdAtCq*CL#=lfS(}``EHFggbSBz6V{l5JJd-Itte8wk%QdF6(rs^&HtvEQ!t7 zWg2luNzZvoy(Zgmb$xoxIFOa(^0eNtwzI^JGN3#p9z+F>($B+NO=BZO;1xNRHrO71 zZquDc^nK||n-7ORVX0C4i4G+5C?(5ky-z$QAztF}F8-$p)B00$n`sEJr{otppSwC# z8{q2e;AvlkZ_yubvQIoE!SqSA6c2uIxn7b5$)F<SQmU($GGAH>D}eP}w}Lwt!5uV? zrF)D3iwn!}_bL%GB9jn(x;HV|Hni(Ef7ckaOJcVZ_V_!tZ$;uCXo3$*{)vfdU>R)p z{cY^w#BO4qt7-)r?*xn*dW_1BtM2_!xRvsOUu8;G^SX45a<P;7OKW5P%sNCw6nq@Z z6GVqNbU;WQ2b?qy4hK3!ANwMxgZK3!a&TF3H_gJ0hTW=><G^2qew6>Ab!y}*_FMA> zXD%HF-mcRhD)688hb~AX^TarrVm!kVJnQ~?V2Rz8$e9yZe1o?+7p?qDR1oPsw%#Ye zI>)err-J>QCy-Oe#Avra<jOAk9TwnlR@Ue;(^~$(FQoGs1uEt=U06?L_L-%%@V~|K zMOg68(GinlN^ywIOAnOch0^ZE(yj$(J%vt9uSyr#9sM4R4O?75Z$!;!R|soLJM3a3 zx~#9hmgKL2!9Oq7GQ_thKC`rq4r#Oa4&Yl<E}vHvLB7-70Xtdg&edS=&dY^M`UmZ@ z)X+RQfTjv?G5Lg!)EauF8sOXJe!$<zo&WxoT0UXM{X@xP5>=RT1&UOfkGQpO>;+%O z4g&0DKj}aH+J4S@!gr*<CFknD0%=e9pNz&LIi<F7(%Xe$&@RbMMhm|!L8#@5VgQIA zd-0|avEe~fa0>p@8l5c&G$g{(*zfVV+CF!9ZtwU4A8(0YxTT^d7P1yR!5LGOa#{KN zJx%5%5a}y&g?bBVlD?VxnVua~M7+iw!a04?tZ05M_y9<E(V#5AHv2w1{Nk+eyD<8T zf0>Kd#2o`Z^KtbpUl&LL3|86Fh3#RtskW<51j1dtf1cqb$kvto)+^2!12F!Z-$62o z;zLcQ`R5jxj!7Rf<h6AVF7dFax<{?Gr8$MZ7IY__sEy%IWKC=9PvvIQ+QO=BZ-EKn z;ps-tS`w<GK2CD*l!Ea_VE3&xD-CAnpJZ~&_sDH!rpge2U+mhBOb_)s(hrr~E*GmP zm)z~S{;T>d+7mFK{1yG!3$5Tl6YcrH6>ls3o)2%UFJFyl=GiV1J-6-~iw=)(*yJlz z{?7#4a*DN7bK^KT4XLN+qN|sc`-+(JY*f!zhZ1)|&a&TwC6voj<#6<a$mtbd>&lAO ztBA0<_7`s<?0ZC)_89LZQW)-S%K^T6BSE~DA!V6DuneS+w2sFV<8?I-q%|X~Xos|0 zCB|arueHPRN9NaNb}@Xpc*hQx{-EYcTJVViX=a*oUKMG4yo{cHBc!7Ct#-|<5Ftyw z?X$dekrQ_ESG7!R+?j_8RrxWQ2+Q*k3jjSY9T?#}T6s_Vtv1Dw%S-rbWn}fXE@_&r z2fjLjliKqXBW-r)hFy5)d3KHj=r2cVvmu)5N4-8^5MBk~t@jl>RUnUq@1c&CDzWi( zjSM?!@WY(vpGp(%)WUvzj>Bj%t^9`{OBbD_-e1<*`*5vt(p7g%!9B9f2;4E*;=?Hz z%?q~HqC|2~&frqydP)Li^Q3GGKX>i>d)o_?{LtaY6E{m}Q1HQihtqrhigHe``{hrj z4De+&kBvuE1yc8A!RQd?+>M)$%Aj)1-MdZ7Bhrn<u{bU1eeXw&UhO%Tuw5F}=dN8; zO*$uUl2^GOy<~jOd&>a7N%pkPuTwpPzzci7IcvEo@kdAWNvGb>B~ng7mFT?-V_&MZ zmz&J#jHZ&26fr=3Xp+<J+^^G*1Ca_*fhifpMoSgA>%&|frlP8tlcjLmWPvp7NAF-o z>GzbU@uxYCT#oI$@$8>gJNJ0wjup0uiW5|C^?rSuf4Om+uUN<HxYL`=yJ1*e(is_k zFrL?YZ}oYhF<}xXL8&b;(~**ecRqe_mY*MDjRu}j!CjRHhLBGa!Ave;Ul9$jDebuP zPhPuJ>Pa^&KP-JZ|MKZIEqpIIN%_w2+wk~4&p*9d+&8{kIzSdS``)ylDd~yLb%CVE zs1+MBAKky-IuYnB9W#ne`Avgr?Q2qo#>Bx5Geb?K*7)Q+^HlM+a&beef?j<g3m{Ux z#!7!$r|mTM+c9YcgOLLJ!Szt~hU^L-cp`HedoSE5W_{#1o<yy#6<Lri$|oNA@7TvX z*}Z2J{WASt9{I0sxtoh(xqnW3bHoj4QI&pqZ~{V5Z`Nr`#FzYdcqYD;Hjp^XkV4mp zqfO~MH%a{~Qlp)g8n-9*IK4maZ>fWilh#^umWwo&4`#mTCBRd|kKfo6(t!sg8<qV& z^Te(8!GBM!KF<BEJyvtCcKR{)tGBd!i-qo=@XE1|yZYq?2w2oMruw_|#RMIw3~|#D z?{@_FMo#}4ueUZSIV@WBuQQ{!{Yt-24V<~mR4oeiD*q-jQnWnt@sD)IhAVSk^hIHI zUgiA)*y?}wO)m(aMB-O9ybh05+CXx*^f;#ucmmE{v$4h*|45qhSC$|j3edf0T(Nv~ zSQqqquA~lhINhY8;bXaI15R$(^9WpDXlKz&h^}$m|BHiFZZlHw!xUCFO1ealOYf9h zDIOzoQiUO`&AnUesW1Jn`;(c;XSMWHCHv8jTn9SydhA^TY4JzCGrik;r;pz4nS7Ej zE%_nYY0P_I5~t|}f{7{<xYWcBWDR$BKQ2WbkR{spUW3?z_(ed7{Z*&S8^L@K?#*Q^ zx|RDY<rwq%q_X4aQ-zYhvzPx=gTV9-2J}rUj!4TY)d@v|i;R)@u2hWTX$&z3+np}X zA?Z31z9`I)2E~9zWvY9L&{JSKe$=8D4@rVS!GK(sn2u~8DF*BbV~VI+CpMC>Oe@?C z{dgX&`bozAH_+b6>@&LY>%-q~@Ms55Tn0bz)MZ62CZ>u*`DMsn*fb2(`wzw?0gGT5 zhRsDO2$Wj^_B<!+9GYHqsCoh!2O<`nK=A-D9HqIDvrNu{gNWj7_DWrup({~aap9Rk z>4BW4$=2glg?&UpL@OS-v&2wEY5!7I9n57=q5r11JNj+Yl%cmtxY5LpHpsD7Ed|;k zN0}cg+R?~IKL+^xO*PCmJl=VE>&-34^?PSpFFAkx-hIvPzkjuB2i!^k>GZ743WEy^ zAStfnT2m9Gp;L)az??v)2^=A-%}^g6dS*kKw5CeT>P1?MO~gDeiUPIex0gw`Kbf(D zuy<dJnhV_YEcPK>Cm_9HA-YJfcAJ$%fo>4VGf`9IXQ7GCOc=_|Aw;fF7hprY3r<^J zw=+EaEk-}S5|&_Vc(A#V@U9@p!KaLbMK;pufH@t>B@siir-8N1M)|<AqgZ|egCc>5 zL#!MWZKmRh12Q9=iUdywkaH~M)PBr(pL4*JTp?8K<!3;uQOhQIs3<h0u7ZH91{VG7 zJ+i=NG!zxX)e#<t63xvgZhUYybHcOcV}RDjfz5->({@JdE8Qd7Z}Pv6=nc6mmKlCY z^z5Lbt!ZRVz^4&Z29+O}cZ=CMbY)%s^qqYcEU1G^g1~>)HmH8@a}aFgfv%A1#(&Jz zf$jT5AF2)qRFbN4hfu!vxmy)_p>;m?q2Rzj#9Zi-KC2x3Neh_|toWiD?Ip0+u6`l% zeJwcnw+G4A|G9mb7=4ZtY<UST_8%ZE*tdcJ3Ft8zZPdad2QHhP!LogXrY_|GE)o+g z^8UG`D)HFxz~CH_()S|O_{p$3ZRT8LMxf68*tz?$0cdY`sC5nt^IbNt0c-*T?ol)c zr%8nOs>q=$&eR2}38G2@Kp=a#V<E5RFRpnsP5TzEd-T52`O*PFTrT<YQ{BYrb?i5i zu|-nMk`79aR$&g7oH~EdtUsFUanuyqb)6A&I9|t>%-)7~$J=Lhf7~dlmy>tiNp9Rc z&ax7PEG8xi@%tYoYlCnRPr<$X9m{IlgZ@zfOLdX~OFfeV;$=sye%Qa|zpr=jV^Sb9 zbnn{nsy9*@fTku>m;;g>>1eX%kW=$PMi19?x)S_ehk@Y)p8gu^rEyTEU7%)yIb%UY zFG_k*Sdx-84v^$*TINnn?0%8cDVrxh3mo-`dCGcMK-Ws7H^^cLB7?wo6{8{4&H_Ro zf;EHo;V>KriJ{x>)1j1HZS`}bzvx~q|BW1zbg#$#F{5NKD6tB1_XaGAvl%RdUJ2Z& z^tcB*`Sdb8(Ruzo?1$@W{akR$dFds4ez++MIf%rmx)NM$%~9fdb}^$Zumu>}{A8zs zal(=?k{eCMulX>66bb%IUJ32Bckr??H%SeZ`T)rz01ANh8xAOauKG!*hV`!<8z5(1 zimJAHLbc-qsH`dOL`FzBmi#TBsrxzbI>5p%&ws}n{IkjaIpksX<VU@;jgNNg<CS3Q zvZ%W5m#B1%q>My&W!eerQU;%#C$d5<^fWvU&6B=dtA{%2?4t}Wo*zYqH%tmfmJ0@s z91mK{3J6J%(oEno>>Hr{0~S$Sx<E9Rj@&}_kRWQE%u)^3+MfJTtuWE2mLggq?md^q z-n@NwsYML8bh}Ldk3_G7mR;(rZI7IW48n_o%4;W9YOOC6Nsn=#U@%_Q2$nldUo6CB zMQsI1I_8E`F6MDfHI>L2oByUy=`t4U0=}K$y$J(j56<{R-Ghf@uQxWs&uv#K{_ViK zRXYGa{65D70g|WkxUPpqo}Cuyloc2AS<Ho%ysTySoPF5!t2-E6YkAOZ!^@3LncFu# zah?`L5j(~yK5tlYKIx)aPQzLx{zvnXf!0)UM>OGRdV;jup?^M-o0<k;(8;S+qt6uz zi-3)x<C|o7#9mFLi{{OUqr2+<Y*Hqu#1*<hr6mp=RoOtpc&dKoi74^=>ZaU8#cJg& zD-C*IPPF8@qcHV!mb11{L5^a%jI-GpsLf4GyG@PoNFVe&aVU{F-w<}TCin!!oCvl# ze+-39Ie|U?7-ZG5LT`nUZckT#d|AJX(D-#At+*6pCj7~9nYH&mBNFSZ&OxE&fEP)- zm!-&S<IfCFeC6CY=4FmgJjT%U)Gb^P!#pe$OY5lbY=3dzf~GZ<V&nH>TfEV!c^)$j zW|y4`vGkDiJ$m0u_ar}4>Dryt=5L@ymGRO6i=*m{NB9*4SOn4R)lO4+$OZh0K^Q$# zlZr7=lzPn(W#Shs=~d+c%!dQ!>jYN!`27pUu?rT(ubDzL0n5+F@ew6euLz2>_BO+F zeG1I~YH3=}9XT}gjd<s>=ok4UEiDkBWY*QC+b{3;$&r23J#lFf`IVXx37q3^3~<mZ z$0T8YRl{6P;h~_ew$jS`$65s5cS|1p5*9G}2ST`Bd4vDg##Qjy9zU=YQw(m((~v{I zO8xdaQ1#Vz^NxAm_SAH9zwAI>x%g`8WZqD!ryxr|Du>^qRPA|LO)_T%$Nh!m1QaKq zP7Wb#M@!~n)=hKXGHI4TZN?nXArKBCjh;FUt^8P~7<oK8E8s+e)TZt=qZsF}X~OBk zuwwDssBzNtU)^eXw=aXPLAq%ymuC=esb}=}heN}eq5J<8-Tygl9L8g+V8c4m9C%W| zZKro2GQVZ8kRQm~k0DCxo`!TELxPmOus=IoNAG`>8J|s%nwl{+T+Bhl@BRHEZOwK( zOoZBwHR112XIm5<3=?Zb^Y2L>m~%dQrgb$bvL>%2f9AWiAJ;ohoeCp9uZR4X5><n` z%3n5?&-^2B4~qcgwSkYijf^TOw_;9gDJ5`t&+8($k%l9ebM08>e`S?pgFi1iHZNE+ z+f8;~7Q-exnZ(4z>}-M9=FV54sOj|(e4`CQ*X{nJEF+F3Aqz^$xkm)FqTJU}p#eAM zOHDaJqqT9<uYRbzSR~Jbn5iQHzvxn1DAR*(KJbcQ{OU=*8GmpSXCO|lm=oZ03cWkw z9oQQ+K|m^AFck3giJ^L(I1=#-jaFh@5y&~Q`6&E{;JH{w;bQ|Ru0pl4=u`gD$6z^E zJsv1lMa8DSm;2NLex{DhJdidDhQ`6ja#3DUkZ>!b1jdlB+vEkr!M4c{r0JOfl;o5f zl9nVumoSlzJD=!aU88aZEK}%@O4Oi2)XoYpjzXs~8Utiy)aA#JtGm-ELzl23j>G}y zt8{NqDPz=7IJHI-8AbGu;>3J*MA`eeKqxX<HGDoUUV-Y!Jx1hnO{oJmKNy#GrbtR4 z2Ls0<QL3PGIUzWZtBu+<=ngg!ukLj1+H(I19EihKHKVE5LZyj(4u3{)Oy?AYgHr4B zPCy)Ih8kdq=fH@6WPP4SqoNN}d79>fLntRG9T-*ST9RV#MehTMzaEHjiv9LBVxXUX zRT~M#BKZ$I0^gMTgL9$?y(sHE!^s}^^QOp^?yE88P)!u>ff?#8G%?Bi>YxJwIZLF# zsEc{fBNwm1c8(Y>s$jw`=Y&ImDeC-52}fPzOp_1_02QtY4TR~%*JNcqjN9AR`;JxK z>NrWN$@-Rp{F4$r6|N$LW1*aEYQ6;%AZIC1^=IapE$U$+z9|A^MIkE6IRSd+l&A3| zQ@m3kbM+#|-e1l_qRS+-I5|4d9^l1txiI-jr}Cy(X~QS@$4&&)&!iazD$QVN{9#GS zzL=vrA<@Z5-w#oFGoeRt(EnT%(Ye>aODsW9Cg-%-T}~mJHJj^o*94kkqYp(PYr*>m zrUiB&EAbtGdlEdOn%$>fn6Zxd<$*ZV+`n5ycup!s{_@|Tb1hI%F=i@@x~RjKq=Lo~ zU%djTn)8zx6jq?vR;^gDLP=1*c+5iU+XW&<jd}&=X!@}9@4D%u0F(qW&Vi66xPv(G zQ2O+vM5|vfsUR}N8S$er08Ebesij?7j)CE_Vj{3_PC5YFroUdJVnM_z4B8PQ{Z2zX zKM5J{n1f175n4K~DTuacyzW3Y#3cyWJT4OQ%ms;}@q+Gshv6;_un#kdm@Ug%qq%t@ zyt?3j!eWlhl!b8vT&h5L^R2HM$dFF&2^2d`(B~EETFg#7?S1Ik)fC%<U+JA7OOaX3 zb8@wlW$}r$YUfL+A7-ep*RMSStCQ$wMAyozCk4WV{M-98VIWsR3~Kha1VbL#OcPXo zlB6-A<i^lAHl26T5_w3OWXK?SM=P`5%i^%K4X}+h!E7;*O?5U4?pG8mVLt%tV!Enl zPHEBVWx&^tiIm*5A?yC>zgYF*YUoevq7-Dn2W2qG0UQD3FO?{5*1U7p7{x392(x!v z$-AE_1BCHDBFZiL)=m|uLllr3-vxjq^~jjmPZtuc^ik>$2(BMan6T=~VvmXp-o5p$ zSS8@9D~~SE>1&cA=+PjS07Knq?6S??8ITsLM&2ZbD-Wy&5Dpgk9z02Mo6*~3Ax2I3 z4Nl$KKaG-T%asx?jUJE4SvOQLLn@A5J~wxUa}Krba694a_2&Vec6vy*0&a<?dFhhR z>$wy=1}nRkDbOi^#)OzCgiwM|7IInpDadS6BRjxNV?yvVKpJ1YuU&sXnGWLcNY0wh zeosMiY<L$2xC11%{DrEkOlo!FJ*RZ`>S>fn`n9E#ib87-&hkDSnZ^8hR9;<Q`l&kq zaWu0=G)O+FG!%M7s63ZTEd6~763hY>s+!)5Z5dprZ84;NEF#`@z?Z`iN0UunuGXx2 zi0%o?MeszvUb`%Fq7-rGwouM(`Z#tZjh(Ozxs@K9a4=E2@<gUW3?00#lCyU+2IYUJ zN6t(h1FLZUDy_2qD;Ks@@O)o`cjnPmxqw(6#BFn_O%Dd?O<CL<37AJCC-JdqLP7W& z)IjW!P3CRc%EuVbho_Dia*Jq4)K^I`bm6<6gQrTsBA94dTFaZmF!Jfv>!<fW(9VuW zd+#Db#+A}O)(l?2;5<XO_YFJ1N)8VG6X}nS?Kp^|ax21{VS^p;mmNo%(rKQS`L%{> zi*k1+6Tw0LCV>sgW@WjT%Q&<&pQR@K{Pk>eLoeZE%y{(kzTYK3VCcP~?2C7Vc$`9; z4m(WE*kzF>Q_KIJes>9VMsYW!vyZ70TFU3sCASYudN7?TPomWWPct32sCH4PhLVCP ziVUZT)#kFlTyV`=IR6Kv{g^MpV+&KLosY4n^IcATG;`ThA7cOXjE{-)o!{k0a-P_@ z5)lSHvtk!s?8p@s-qyhO`keB&j(kR0vgC>=F&DE!0gnw1<>zV|t!aH%e^xaAx-URX zu1o1VwMXH{y3qAdxb}L9Qs?BlPM{Hde@h@T?#MOq-l>&_{Js8t#>01yA73oh4OA$Q z)9v>u21hX>Y^+e32FMH3)-#|QDCqIhSM{~dr^PSnJG?+Fj})MJD?Ryn{73!|8)+~` zbdrpT7%ToKXUiq91lj&&*td(DCa8{i2iidf)gZh>m1(%~UQ=ZXJLlqjWbB~~vCL-W zHVjV-As1nAH6o*;|2iMNcD++&tp9~}ex9UU)l!I#M-$rHsRB%K(0^Nhyd%T&P3KT! zvJW1<45cO`18(%QlKQWXkA!gbyuU-8#8lLYM(bOn_<j#a4YZq?p>nWeuY;v7J%Jx9 z<X@*FrZW1XJ3vgWhCh0)&<bZ(O_agSh=?Xl8{CUj<7e8hP#5w?zFNP?G<o4C=ra(A zik6kQFA)2BN4I3A-YFsw>;Ng*RxgU1{8W77)vDl^Huw)VVlVv_)GBh>gXbV8`ob|3 z-o)r)m+1mAx?Vrl_C`bdktWQNoWj9>6W(qewDNKBG4Z~J+2YJuI~UXkzCj_f3@;t< z(?wnRI~^J5*1_xcdXYcn+^vW3=gT=+PXG=iwi~p2Lt@PO{CuX|snMJ82ZhH*BmIuN z5S_z#E?f++m)BYl9J}0@?vl~|@?XqUl-T3<!C7Di*Q5A1C(2v?O|;auNp>t$eDQb( zY2uWmR}36?8NxhH_!V(Iv-^XXM6_%fSj4O`7<F@D;r7C!O=qI*nU{;1vtZ)%a8;{z zyAbq3D|87^>)`$%Jhm0zMNdamy+<67+Lq{Po5)JFpswN!{=2FWPOOWLDQbr7YT_Mw zT7s53H&rjO0^J$*t5&_gb<gDB?G!(6M}zXylqXZB-kKKIB!&%4FgWa;aoK&V<u5nh z3_IvAAg$f(1yAg#yP;=1;@*LAd~S=t{DbF1PA)j{I5TgR<3ix~Q@Rb}EUN7i<}*g% z->~JsW{zQ9TFMjz7q{HjcfFvJzy~<nOVSor<I`WEh?S#Vh(9!bOf_QjFzEUIO6M|S z&=(d<4s47^3DZFiKA|B!^<m+o7T#dFjv>phiorp>cAljXO&_l-N)+CWx19FAE)hp1 z4~x4;IVA#u9wJ{@Wzy~+uKq1kkyM_h^UjuiN~0la_aeb+o9LTIbcQ8Zms{7Y-+pLX zH+DzK(ZOH%zwD@d**$RYm2dfYBxn8ZLi>>&=OLd)0XpR2Vu`EaCxXh2OZwb9>}_5I z-~UY*XSRV+7%{=x!ZT2UG2}1|`m5-U$#EtOtb3w%zi51<<wPx4cssvESuEW^uOQ+j zb|!4yUYYQ>VUb@)`9G;5c&_qIIWQ({BL%+1<Ut-gPHz0>2VPC~&6zFQzQxFLe785+ zg~3<N^PYA2N{HS1cJHn?X2;n~%nM2m6zkx65U-?`{lkq62dnXaY(#u(MDR$##|vLg zoX-Y(wzS>I{;m+plfRo#w{c(dt@H_O^fUPrS5dF3_Vmu9YJ)4n#~Ffb;Sev=f`lKa zgEF@!cn84u`=F8kJpg=Lgm-knzl;igiuomg<N2h6H05&mJG12Wd{pdK{N22zmUKx& z!?L^Y=Q^j88=j?}%$kOcRjRQ#Zx!tiW+TfWh<SkTZ6p7;FgSqxxr2mnj0*m%|ASiK zwOqO(^lsmMWbX)0C8P~>{gvrMsrwlFJq`-8)$X@=_|~c$O62~}-?4xRgnMY@0186> z+Wr0_`m^gJ{|;c(+x)1cYS16PdI)W7*(5_m>-@^h*n2Y;&g9C9TKO^v;8oRc6Yi{l zatq28HKce}+5ozs;Kepi2p1qu5Bl~YGN7MNNMobNWyy=9Mhr&+0ETZLSYD^JZV&PP zzZ}nl-Yl6jueVOM22KUFPycW?ieDeS{$6L~O<VY<j^1>$;hW@`zpwdaU1#1u%~)nH z47QP0P3pz`hcYhZ$oIYQ%zNE4IveRXDDHM|GNt3t#6(Pr=~{b$_v&u)9l7oH=Ami) z{yqxI{^a_ff7~zdx&AL@`Z0nWZ~fkudK+f0UUCy3b&0a(7Vz>ab!}<x{c<i`{nI^( zN@yVpTYG<x{@&Xbc>Ce^`rNPhKfk{ByYsU{j3RqPlA%{#=lGXh+^Cbgmo~Q<Y6SZ# zEdxg@;63OQ3SJg6{c|s1vY8Jdi2Agy-vd1v0hcU#GVo8$WuUYnbD@ks3}uRV<Yc&6 z`o#kXO*{lVK$5zWme?<~@@Hp<EP2EAqv=%uE6b8`Xe25^kugoifMi&x0$}<SMrApz ze3lj>M|@FG1`z?7`X>QZ_)gKNU0Z{%rLUx9UZA*c0Eq_u;*rBUW>~{tlaXUhm<wDI zz}5sz2CVsH2!CCCbP{wF=cou)!zFaQu$5|S#VfZwsZG&y(co%G3vMM25k($+cXpix zE0Rc%SAb;H%fWtSm&ij8)>V39505ylakPR@Z5a*NC_ky6u+dpakqJ5KmFfg<8mb4N z1l@9&9<~0v%f&aVO?Nrp@Td-ulKyZ>M8VK7_vqhK8+~3!(Oe?wen4l{gww%-`3sJE z_{Yg~A1Kx{T^GjSlADX6Vpg9;^q*xJUmPbJU4}>1Tz<8bH$ykM_{$rJ=-#+xRESH; zRvB>VN-m@w_W(dj1d=BJtNn&Qap%rJ6HI{xKoF+^j|>tXcN>3EJy)bs%<aei$3JU# zb?9l7y>*G}r#LTv$~gUbK*UY=u}_})TB8_UZ~NK6XZ;mYRi4%P4>E;mJ%^Rf?kAii z`-fuD?W$M4EL{i&4hi1kk)yHwQeINge<X@RUc9<>^>xUZ@Daz8Hyd;Ng#d11B5h47 z^6iJX3-d=e_a!EKBaTHcCYZgjyEFoGDveuv6&Kl;6#XxDqtbs^%BcJR1qfax!023& zDq|d?A&DXGmv&$19K_|Uec~9Pf{}oEi0aSK@QJZU2Uq^w{Mj!a67X|HC{h>;M6-+k z$Iw{?G}Xpo{4Cih&*)~OTUtup#(<HIQreM{N(zXvu?<EDBScU{T0lWk34?Zo2uO*5 zps1**V11Z;+`bp*;#|D%Kc46Lz1g{R7_LI0=RCi@#)e$H>5c;sD2};FVlN_u!jK+x zFPz-Iu@z=1y&wSyrn;N+$5L3DLH;>Q1humzFsYZFj}DVU@ps!P>E`RWsNUFpE6Xrh z#ld0iBAg((@#gu1K>@<oP(mJkd{K)uq_Hl~RnkG{Ebny%o5;eh#i*vNK&4j_KjAgX zMa~x^f&!(NcdSi@opa)<17$xZ*;u@B&P`bll>fV9gGah>7)n7nfn+jC#U(E*C`eKE zCz)*Rk{?u19i*(CZ0iu>QgC%WNcG@PTS}TsVU<#_x?{4PTdm8bn?b>vzCZ0ehFyx< zs)MzolI?xoxLod858i+7r#%&!o7krmqIa>29J6CvG9qGQHA=^X=(Nd<!qG;0U&aH^ zD`5cu_Y;l?0sufu1<(S-pfD(a+65pe8FF)Z9|I+<;lpjN7)S>d?Mlfl3PXuv2H{KG zma0d&Sj$Wq+t%ul0yWnL8MTS!(aXAlqouZOwU4g~@<7y54Jy0J@C;sAyY{*%)~JXa z(ELq}AnjCTcg?P&!JRGG6uvy#adZB*t|C+P>K0_7E%a$aqZhCSYeOoNFGXw-<~owT zzF+osg)XOx?(oVvbVeUT0ibv(c5DADx`eL8cyu&lZLHWJ!rJzz|7vO>+RK<rhYd|# zb-n3#a7VB22~0g5sr#Fn-geFN!^&gx$_RS1<VjtDUf2)_C#W3}RH)cyJh3{3kHY9J ztt_-f9Ap3b(f4{pJb#x)uCy3<13gGmO?qw^{vNKZ>SnPQ7;*IZ*AH){EKUbMovPr$ zqqu0LRXoBvXa&!wP*_fqC6Os%ytZ@K35g$XtfiSevza`;?H<B8gRK0o9RF&MgNN3r zB!gL!eG*d{inS+XV&pnHpoD+?Gm7bWWWDoA%*7u|ad2XMf4;sL6UwV-WIIKFr_Jm; zffZ`+ErM@PW^t%#>X<y}-#IYJ?Sa~>d{r5E4N1LvF9#1847*XPP+_A0eDqw$0Z|$1 z8|B|+gH(tnVtd9qbgju`KCA)=Bg7nP@2>&cn<sM$U!r??FR9Gb;#CTH@%1i()o;(h zXODuu@y~XZC$9s4VkQqB7Har#p6<KBsd60Md2=<P7I>Xg5zZ@Ii^kY%)eBB<aL(>U zP;wyf9kt1W5+C1xJfGipAg>KN64rzt)tDi68^(Aw-N?%sEyr_>xW0Rm<)UEA|IU86 z?H?ffULKHXZs6QQ-XE#&fe-0&1_Tew3=Co(y2TKRukf8B=BSWxL0I#3plA7Cg#K~p z)gm?0lQb{&9>inpB)_ntQXJV}{j34OTs%I8@F6ynSVzgZ(m=eM!I#H#4)yKH9aWpg zqO%psnQ}?{hLY6>0F!Z@A*j1n+!OdL1?DDM(r64AiOl>U8r|kIr~$yNW=q*<UD+tX zsa>xRcx8L-PKUo{@ymoZNpvrL+B$PPCvLu!^2E4Ydr|;K2sR~OI#osyFg+k+wjeQY zt4czv2*`Kv1yj>a=x@z-HdRJ)I03)Kf;{_%L=EMd(S3gmo}umw0B=luoWL)tYa9#U ziTHZ*#Hrln=ywT+%_gT{lK(A*&a^sF(hyqZh>sgLMRxFl?H5cEYnMZO;<&ac-Cg~U z@L!({+wT*7^QZv54{3r2wy3zGHu|%G;a;Zh=1CsgYb(4$C6>WMha7FMBLgdomv%Cb z-1lC(2UZ$21;5As4fK9fn9hOe4D#rHBRHH~y(hiU97pk7#k*|urs5~DJgK?2cQ?PN z!jt?N<Zs-cA<7_%jUc^r<t9;sQlE<Q;jRctZ+l4G*Xg2Q5A9U)`>Tn(P0&j=99((^ zLiHG-?>$irXZn?=rT08TjOE8Ece*))hfc4X#nLa{<d3a1c6{%Fj9Hi<s)Di#pR?ib zDlM7#5j&S@1w2;?R8p{HoZU_W27O*fzUg4=jl}>G?wLY^8lx0@D(qR6{0Ygt!&c=6 zd6MkuP{Ri2Yag(pFyA*PSG(vUlg03NK?JofTO4YzME%)bL-=##h}@Ipy_yR@XLaC+ zsH0y_r3+FY97=7^E!r?F^(aG0rAmxr3-X`xE(|%c7HDZ@n=ZsF=-tOGkJjrl5H-tU z^~ZF8Py)-V{xXN8U7OtuC?~!q&IDc|XjE(4INY#)6#$OKQ_rLJ5~3uAAG6<4SdTQ{ z5I_x%qj4LSv<IFE8RZlURiG?NP)?eaBdON#tCybQ6bG!qijjAYQK`<4@Kl*Gwx+!# z6p%->KDZb@$>?4ezA1I=#@??C8Eo@cY7Cn!(om{J_o*M5YnZ$9rci;*j_~38GRG)S zC;{q%^abib8LA-7-0j$p_dir@60(ojzIu*tUB^N3crlCCYwiW?D;r81p>f_p)V2}| zW5=x=j!VU7fv!rZpr#v+M53F$&`jFt5@0rha5j2UXIH&F&*H-(I+1TbN^FBvmzV1^ zSShiuukJYOYUIquQ;i=W^Cq<9?b~Qg@KP!UxPC4ql8`b#3#E0aLr!^xnLYg^21kvT zYD*$wy`v8C`)cd1)%z&*zg*Zh0?O_8X1lY7YT_9k+Y^l8r(;c@e)J+GgNfYtVEdbI zjkkRJh4x5pZ1PS&yuO*V*eyKWKZE0cpmG9Dg#8s2Epz1Ui@V1-p6YV~0Gfv`AjD<f zlO8!AKKpse@bVG5$J3G$8LqN`%Y1661kMq_3m0jD=>5;o08O7%G#;cO{|skKX$*Uq z#Z(gU<R(9kP(C;6au<S!pAciCLMf_eq?o%_594Oa>b~|#3iCpcq3ny8b&i<Y^f<y) zg?Pw(F*Pz7=XO*dFdPpmR7zG5U1<$ZCc35$&fS<c^n<EI<4{<vy#^N5;xSkWpUuPV zTb+g!N1VVNq|M$*zENPDwzo+7dK-PNjK7WV4ZZjPy7qpnRXILVEr>J<!x^(A&w=Q+ zx%Rqc^-x4VRKSOdl}8a1U>nEiZ~|OE2?9gqGejp>J->Y{!ylcK`0*Fr-8eDf%XK+{ zkuy#bIEXsLb7n5hqI(LOr{8*9h?QE!>^OB%UAY7}$j86VgDkAwm!F7lAzHb{@jZX; z1Sm`5Z18r%sFE)-rv!r8Iy1YxT~`lvI2N4ji3PIdq9P)|uf{zJ6p184cGPB>S_-aT zjE%|GeOD@HcAFF$LO^_c)%rJ*X`_5Jp9BMTxK=vjk9|iHUy%R{6<x8tB3LZ-gO2{+ z8WOU%NI5EquJjCT#)EG`Pk${tP`&D0H}Zrpe}g4bfsXp!yDz8Nmi7A^)*`9wcu%7@ za29y{T!f9QFv5PDEYZttnVU;AIK_<YZH1S(#h<fYM!?F)?|(YUWL;ag5m)*IaLq{# z_>{#9R_NBmJ`rXw^HXI4S6jRMrSgd7NSh48ZLh@lwBYasv-z(ccXSiZR}uRu)JNSL z7*@>3&&XFdjjNz`Hw6L`>27`4*4uVJ5v~8-*|)yPf1uw9`Q^3l@yj@)-lQzo5<B&g zZfpR?{VsT}dz<ih+x$;r0CLJWw2H#x7V@+RBpd*_Dk<;M&x@OYN6YEbouVHO?A`l` zcI9yRcI4L^;GrSvUssrD6-2LD>50Bv*h@Q!y%07I9UdwnN^v@?qLrZF+cD=!F9KP$ zUcwt^MywNgW6s0;Q-Dc2vV~+#XV~t5z+JePitBzujC?dinghL(?<V&ORJzPag+%zj z#g9%~4;Ti(rfdndpv~P-(KP19Wl$W&I#QPo)pI9Rq<8QD9gmoZJh~zP_(j8=R?h$j zz^2^<@bCJ$=fehn_ZCq`SZIuNh4U#r6;Q`NjnQHbk2&>vI(CrZcq-{ka1Gd?>=z%J z9(@3GBZE#{j339@uma(N0=%e*2cZah9q0;1zdQjp)}6MZ!OfLj^+eMJ{C)2rm8}ep zR}-A}+R|Jc1Va@Uq@8fuGAyqXzcp~yNgqt=Ppdr<hEbz8+R$IwWTleX(3UKhV2nSA z#IL2_tE2BNZ74-?FL{D(idePZgAtcfHxVADfhTpaAU_tW&4HTMg1LQr^fd!_(VVa~ zNEi`}O^q>i)w>(w@I=wEWZmJ?uyFd(^jxtlh-&aqNTLHdMS3Ia_d+^qcM4&q4(@b< z2hqTP5`~0%A@eS<yAyPwC9;pEzNk5^n&d|nu||Hgs;V}os)4+Ch$<K!tFPhu7IH3s z|0_$dwmi?>`2xGug!N5jD<HtU?G(=XSZIByvo-zn-Se#{Qe;CBf0IC)_$*#MWU8(3 zj!7Xb&-q||uE|d(FAm|t0Z*$2@3G6hL*kIEGo~b%L2t;#mJk&%d}cvmB~a?6rI-X0 za9S0*9$MtLt%sY`J6Z_-7w=6#Iznr*VSSO@H~EPYxyB<|=jsbw6LRksJKHD~2LgpK z$T<T7a$=<5zq-<co~7`LVze{Dhf|oF44QPZ?T!6yj4$)<5*+RnozmN~kkEydXPk7` z*QFDbpt|7Akt>8e0tzQDq;UH6OC8B{2V_gmtsyV>H1NYQ#JjunbEcqcLe^o)YY4q! zZb|8cX@$sWsay<_Ck82@0W#3QlaamkbQW(WXy2aIK|X)>SgNPTF(`{u*=}uUS;jzU zzuJx&jyc|&2VN=H{-!Ph0uj&_2y{*Xx~-(Xs&nB-k={JGx4Yu?Pi!NzQQ_dPg#tl4 zkWpXZ<pusj0AZ6g>f1HPGeKz$P%N|bs0OB2A_ZL$2MhD+{SjRL-QxG0u{Iv2s|#}V z^9X0a+Awfrw#sPjfZHQ;9R-)eby}9nOp)Dm-zQ8kay|&GC`3%<&SiijVYO1>U@)(U z*J8a~c&)G*D0`-!Kc@0^dgNa7;W->krj{W6_u|(bu9$)m*3hK<09eI=wrz?1N5OpM zI^C&+oqV}(mg@K&_n&jdJL^OXYz99hMZEa@myOGv<WhiBKVIJmgEXL8kkCE96Rv4> z5fc^N^wJItyaIZ^Z<PCm0Q+q0*Ry85&Y!;90DD(h7y?c<#8f=G(0v9JjZXL$v*$lU z^=AqP5sVNJs9`F!R9{d3sqrZoUT4PkFZ?E~F9^z0z*1wUBp2|kmCyVvxc0uuss*Xx zjS1$h6=*52>7vhO2A$q$*xgO`%}{0X#6(G3LVXgHb*#a&#m)L_nu5O-p23*Y1H^qB zbuVs!+#mE-HTEU5O7>2H<YMcKaPXZ}ldrk3hIbRvxk*P83<w8pf+|Ao!MDP#Zr-c| z^QWA$z;#>L9tyo8#1Q3zt*MB8Z{2>dPeV8MK;NL>pUl(zdj475^L8d3P`&o7jN(9A z$CWe4;Jr_!bct;vOMfGUrn*kinvOpQHTjytuy-QLy998RHqY)vm}Q+*4L17ig;2i4 z^UZ>nNli2})FWpG>-!+KFVH?<p4v$9^c_@CKbn?u;nvQX><^thEm<=q&fKtCXhjDs zraQnKthx$rXkcP@SHZQL;LG=2{4q_d-S;K8FDslWI2#)MWbd#(GhPFXtc99wnVf>2 zU=J{O$`c0cg`@NhKN~slBGPqh^1E#5<~CWgcDXk3H6oc6(hc1&o`d52!mm;u2)49R zy?6?*g0$q~$gwO6nce(5)Dx8vGIR_H_t=buZ5w5hcw^-&mEmiGbg5qHisUt1II8{J ze~C#)-evMQmz#DK92{vx`}c`Xb@5{!#Oe+K&3$6HA(;QrzPzT>RLsXLu$RkJw*XO( z`u&*{UpP#Qa|vjMk#A~bS>_<=1PgwlLl%3HCP_)G_)l+7^J^tit|Y#lr=M3VrHu?; z&1{v~r4PaNc;cFcq%DT>Zw>KG-T$!xKC}gw)$5yn9o5#b<Qarj27y{MEvqw7xyu;| z_k=JY86Be#6$Tc6wK}Bi1?>}lM7}HlVfAorE{qg}^8w`z4*=?jbLkLtn~PcFj^7$b zIrB_9U?v>)&L03k4A@f7>&(^DY*XXE>tK5Ux}EYb*;}L+7-qPQK#Fh-FsXS|S`YGY z+xY>*>f$j_<dKUpE69dFH(R|`=}-A$B=}Fc8zc<D^d6(vxaye41jxCO66aqFcMjOH z4&Ln)O=HEFO*~GzP!S&k^@nKn#u6<x)bp>yA@*DMFok_5tJyh|8xeQU#>wqQfCdpA zqa}?pX2|j6u63y<1;}Hfws7v|BrjoPmLD+FL&R($8+yR;`a8$@CnFc1WEM?1nO=~( zYHB=bg|UoKn#>D!0b$tvecjXgF}8XL|E_muC=DYA4)#}%R>(<>U$!5g)50VGK*~Xo z7&XJUJ)e4T;q3A}J!%1}H-n~6!ZAF4qg?_OU7s>@FP|xFLj`|kAAK`>8(IN9<#ymp ztU_DG#pj{m=jMT%7T3{vkn_@mJkFE|*}JUb%TnZ7({o^u?q1qFGK$ju{OY{?+W3Y0 z7+-$ibo3I}cL^G^G;$9dKMUqsz|Y<va$Kt4k(kQLD6l8hUl<=z+bzz#{PmbA#n&$m zRPUdd-y6YI420gtFng?SUjz%f#=dsm!7MfM_C41$2RXhV>f($5eSt5AClL?A&#$7& zRuK~*!f91FX6f8D9z|_1dmQ}j3l?S7m^Ff4_!M!qju-R36G|B(H1O;%T;kG-P&B}l zA`~90jxe!}|IR+|a~a*2{_$#Qi5aGMnTx8J6s4~wZA~aotwPsU!6}|l;|KhX%c$*{ z!pC=L>|p)-&vqOF&e)NS`@v+Sz^};_=|1)IKSbJYWokQI@HH;UMZVn42Jfm>SgdrM z!t%V~TLmaH(DNdEf&lpt=$pNs=?e~8Ec52g``>I0-u-aAPYblE&UL*s!VifwuZY&R zutpD+@NVrrhj!|zawaYi4FN!czDRW<+XMz&Y&Y#0&Xjx{bTFO4NhzK}pUc#G!1V#2 z`tWcCge(t%BthWeNukew-lm)cqbWRbzyc;_jo}A+m`^$GfS1B92#MPUw}I#{@7@fG zAhu>|&VyBZ;>Zb$ID2qpA!tptadu<_XEs0YJ;JZ|R^%i|Yh2pj#{=~8{5lEl2m+3l z;IEa>KOcPF=l{9v1JpDc71lgI?z{2!_fu3~>C{N~ztT<*_SKuk7+iGt%P#?sA53rM zVb`48eik|YT<Q;<4MtAoZ=Q%u=3$-RK<w<Qecd5{Sm^=Xw0L;0ZDuSl4f$^32wSSS zZvy@(@IRgrzold+P<rWAYFRgRv1ZZ+$uRvom;ChHS+88LPnvK*ycZY=w98je*Kx6l z<p)}c;Elf@lQ#X95?gZ591DBU5;GsixOc~&Q(E}E{?}g+e-a#u`W!mN<M{P6%n#)G z2a<gsAf}L)vnnRkix)IrN4-CN>rC6E8)YQ!Zb^U1Ffrn>J2)Q$WMIJ)kAI-1W*t=> zC)?*nisAN?XB@H7+ujIH4tvz|{%673)$ozwTj05<1^g3n=zcJ5KNz#h1I^<Z7QkHC zx5S>PuP`fq==0*z?XjHBN5f3x#a(M~`_kQ25fZ@lDFuvZ5h~YJ=lDFzmLL84(im!V zj{f#?x!J+uuE)P;w7{~SuW)}J!1;zCV162qAr({Bh-m_lKR*k=O3O?^ob@e_mVK6% ziJvyMi=9{T%s8<-rkx><{g-&229fGm{)G%DL1X9Q!HRu=39wLJ(LB^A%5y}CzXF62 z(I{D^cplgHZVm2@enVH>BL)Oy@j=-H43~flf`~w9q__DhCc;Dr$Wj3``R)U#g6Q!Q zmNuk3a>u$^hN&bhW#IvC%VtV9p1haT{3HmVYw+}!N`56i7Sy(n|Ko9_f|0fnd5>|T z!JoyHh1QxN{a08CyP7(tol0n-cEM9{QK>*RD?u4CV=L6!YER?iYlqY2&S|u#+1KAe z^~`DyXz=%Vumn~g&!+N9?q6r5=f;nT>)G9wIjkvv_|0u8V^0^0e&e;>;bFdt&w^50 z<y`>nChnS$h9*w#>{cI=8D8g~CZ<)5g6|V)=*7KRh3SznHsh$ShBQmA>UA-N{tA`I z){Kg7-ansofFQ*x+(Z3X$8yszussR$ggx14q?Y$1b_|;QS>v&>YbdCGLuRl|rKa)~ zRu;^2$jzLv)WYFjW5<nlCCnK6nL(CZYnC8M%{uK&1c)n3qM%F~idsLF-w^9gClPp* zMQ$FxR?xhwnttZyD6ckeya7(1n>3;<XT@vaz?#!6Y*Y1b$hXs|_#KJ5#Vcit!+w>{ ztu)d=;2%qCzW-#rBuIo-n4L@cH0g8!VZ4xSMrOn7Pf|pluqH=m8zA>l3}fRs(uQ*3 zX=bB)+IbS$6=0Ltu1;2e_-Pa?(ODnjT=3<FBR9|N&tZ_WHtf<R3{dXaN8_Q&9>MN) zc<uKMqBxV7#hkmWVWOHd5L;|Fkjbk{@W|SaJUvh!jz8LfP;aQD0%b#4cVr+)s!h6& z<|Y=G9<OHmuE8P{BnozSDOg5ZtDOK&H>oW*K;KoZ2nl`}&@XxDupv0dulN-k^<;D3 z?$P?ltTC(7)8=evK;o!~=0$NA!DGM*S|qSzer_*wO<(uqCW8`Phh&|Vh&aYPc`gE% zC(H};GJYCVUtu7uZ;LI?Rw@Lqq&U?rV`SyKmqt}uGq=AYU!H!>oH#3rdr)_+19xj* zs=ZTjk_$IYT7x+Pdu5FE#@{*h=x=$u|0n?Ldtk>t*)1O1S($s+z$E!OuSICK?l4Dy z8u2rN{rb=Qojj#en1IsCjH24nx6hyX{<p36*oyn7q5CkGtNRs}kBh>%Jj3l@k}+xG z2)CmBS@%LDJ^;Nm`Hc((TLS7MFj>LWq5}KJeBsIqH`1zUI3eO(W^L-db@#qqXZ<d| zs1PeNz~iEVv+E_>FTp&~9s5*Pt1^E9(FWTsQNBuxsNWAR6@LM+=aow=XWq<%h1#S& zc3tlaa2ozVy;>^}@*Dw_A4rqX#0`6{62-6toz}<41aT0wMlEOa&pJ{AN^9*sikS_* zsAHog`OPjdUsz{7J!6D7SZm(utpqfb_vb4@E4AU*W{WACPPO$&yA=9N5NCI9WF;Se z<F>ntXK*|hP3DLQjO3i=FT}%lOzg7NPe4VfRIAK>PEO4>Hu)*<SA`DF<+|$g0?wsz z)TB%J{8oiRbMC%YEc!4<#f<8O`T-JacVwFs{HSuiKhi<9L3T#Ut~p=TaK9PGgNER? z_VMd_YO$y>>cX5}*qtQM2|FnNfT_wRp$pc0CkYl1C^$M@nYIw56IVY=3s<`2t)X<8 zpui<~)mdhBs(PINR^^U0oAL`8I-zSKAI~YFFjw?6={+yFKsoD=qXA*o2PGu(g9PB& zPC}J^{AvMK02Kqw=}i%WDteNBxS5H>b2VCCfolDO=!UCf@4CUqH?^kIGh8<W2RcM0 zjd?J~+_~-@??D||(oNqQl!vCqr6zqSV8cEl(9$aRgKqD7?Q6wR;(M-Ar49k;3?Yhy z6tO1Dkwcc`gBO(#XzQ$B`}{2|praC>He;X_yji^4T2xb%-8*s`C+dHzF81J%WEv|Q zm)}YKA~{Az+j%_;w-nkgwF1gJ1RxPd1MM-k#qV*GYnErm8T+IC_n&vV#4A~8G{*8M zVuaCcHTUI1`4k4>SL4a9bIF_w05vglsL4_cfS}3POU5;9hhPny%xXr$FCVs0sA$1w zEq9knd$jELf^m|<pgmuUxMf4;CDN^<xC{?C4Y9Nch)eV~Sw$27+ytTWK^?HPErk$G zQR_bdz@bFQX+nh#hVmXhHiD7tZRY53+M8T-Iq!=mNp@doC`A)CQn)qMT?G!`b69^C zX{GV-V|xzQa>cq*z`HRt51@COIJ&#h&BWK`i-f%*@SYx|=g_^BwCc!0Ba`((Z+s-1 zMpM<lEMoGKaUM0OuvQLh!)HYAy)#OIZgNR0oztW<DquO61j2Nx%K#K1pKcLKs6YWH z;$KVElQAaFo;aoUOnqNtFuJcxK|+1La8mr*zb`FMQ5XZF3cq|x%j_ZTuN&a2-=P3y zEZLw!WtW-{LpB4rMj2IN`3KH^ugjAUbxt5K`4L~8rf_%7G+Zp-sAZPYUDUlTrCa%d zqFHgE3jti#dsLl977PqYb5aEPKh>{m3Fa49#PN64GpN$-lFml$vR}f1rPu5mJ(|Fk zBr%2dI>MhnXkgQLbGOTs*@FJ*$}{flOAWjmi4NkTH;Pg#2eIa`BiypafS1NNrq?Bx z4EOUAi!sV@eLMZ?*Vr>XR)#MzFIPqtg37>>0SiSwK`3_i9OutVf>Ej6#o{`lkA-?n z$EAz};!=Ny!dBcxv08{Azz6Wj)hIY(UdKy6Nbo(DeR3c#EK{s?BTXq(M?dUyq~RF& z5I}Yk7X3n1U1Q7MCO&m}DLD_BL_K)^2jhXc+lYf)e^Pkn;KIb6@D*P7pZ|tR+D5bP z%cE^)Kc=DlT)7|8uF3LEM`iQ819&8^KE40p@BFaPtJr-)jAnE0B^1QO>QgvN62o<5 zxS}F|#et@SyPv~8evn(nq;|13=f8<055BNJj=5S;x5Za6zP3-XR(?2TQI~F?TH0)+ zBtb`6Z(Q7$%~6n1yZimx;q$-Lza*z~J2e27QhS-WCe8MDk=)0k+U$1wOo<n`>nmmt z%-QQ>r~@ddE%q*P1jp(ZXZ*t5ICIZ>lznzUlc|=<mwiy(3?=P>DH$~as1Fri@qYiU z_X9@DiaR*ciXX2+-O4C@i@Ror&fTgrW@_vcds!9%qt&!rPGF#$&2)vvQLp0~p?sL0 z=j?nwbaC{>pIyq~U3}8&dMxgPLSpI|%!J)iKpW^>ZP8;D(~xF-xJ`v}BDQL$ZO$Ae zs${;)`H6-0@%4on^{eBO&DjGbupzw+4j_JrO!R9&=|J%MOms{f48wuj;+fW9^P4&$ z`AGI5@KA-T=pD-f2KQE8UdB_;LOv3z9ZK7NMVFqu$Ivz0)BoILbY3+>y-VdKW|uR@ zP=anEdp67k26|Dr{>%VL)7#v<y6o>{?w};<`g4&{3Y%@xNa*F?twQaoiL#TKeXi0Z zED>SfyQL?7MNcWEq=!Y#rc0pf{CghpahMAv3-8oVnyK5;e0*bctb|GW&t7UE`(1#E zhlm)e_y%JmlYxQ+>OtHiWz$=R&JmlIdNb54E18`K&G?6tQW{uPnaHbyyBAFwpEQ@m zGa8%T-=^@1k!f(K4=S9$$N|qj!eJ6anURHRr7_k8zb$=u`Rmtme^uP|C80EF)l82^ zZ6FjY0mV>g^B>S>#!*@U<>xnT&cVfAb7<&ZT8&9-HT7YoiIwEojX-biV$y(pdm)oU zmT$e2#ztj3psr+$I0vFG7YgQ8qxPyNpm;2k&Fr}~_D14fgvi}Ddy<(HR8K+nr)PDY zb|}-mr4-7VMJ;e}c$BsvcnyTA;MrBSY!?z+6fAq&t)Kv->1G2w#ZCKSMybitf;-m? zm>B_@S!Q8k)*l3GQ*U3XX19LhPY2rY0b`7<u?;pn{LkZEJ_Flyu6<e^TnI-b(@e?H z_Ac~6S-4G3Y)No9$|D&~zKI&MLn(T+f6*+{57z<t4GG>TdGo8&GKD-Is2MojK#9xR zLW@SSMI+d4uZCEhOIqGa*pbV{?-UU*TPCM#?o8L~4~4JX*!K8IRvq(I{N!G%{&uJ5 z&4<SXI(vkie;}*PRPj;Ex6U*Pjs`omEFL8w0hKF<lx?9GAhe1)Jr+n{daItmAEDBv zS>*dnlOgT+938AqVb|e7f?Ar#z90*sv?Qn70c^tA#s>zI8y*ywE7mJ+?67;*n0k$u z1-!Nl{4e#2Fip-UtaJJf1lw64Ad=aY{A8E8!Krm%e`s(9ZEG5;)q$ib7Nt+jzi7!s z1E7-A?`8F^WqB>$-!0xhtmv{)IP&s2IY$?6=#ApsnlzDZJKopR-P6e28rUekJrKl> z@MM?DsArlqc@Ls_dj;n5j#T2=!n$;P75i|QvPsR%8{IsC1>i^ItYK-U&$9!tJpD9m z(~}JHfXwtq0;;4UTQj*-DpSq5%9KeneV{q%<;d>4I;NS>wZ@M*+)yz-Ii1p{*r||x zlzvgw!t76d7L1NbD<5Z|pxzGbGZrWT$bOdYkq80IqMqQaPm_7DzQAIeQm5#ht*4#k z8D4b7(0cYj{T;InT=5R$2YGB)a@4V$KErA@4eywHDbwprMipP3Cg^F8p^rI6N&V&4 z#NHps#KN9&v)ZfrO@7L=JZ97IkYfm%ZxsqYc?_J=Yo?--gV{~r1RE(Gx@)a#e8)oK zWv)ORn(cbmd#10~jCI9#aS$}MsGQk=v1|U9?Ju#@BrbEvN^#$(!#xWa#WfEr@BkJ1 zJr#=N(vkkM|FvbJJZOGxUb#4+7)8!(zPbm&KC5rcO3FJxcyw!vQcv_`sY%_E=qOR7 z)Yo}2w-y+yi)o$AiTm&*s3(TZ?pi;3(?ho<9HkC1*z%W|4aG4PgfrYEjl-UY5wEex zsYrjCB5KsYs%TfIx|_AYN!fET=+Yhth)EZlwe=3AZDCD>3LS&lDpTC6?`m46J(yVA z#vLDEV<mIL=kxa^>J%K9WPYh(Z~a{w3vQejGRS6?e!)Cnb9IvqQZw~t4-0^p)G9q+ z4z8Tm_A;Z#U5AN!l1&2|Ems=ZQ`x=Vfj#$pn11(6y0hx@`5DLW%lM`*_-t9RzYa-! zGdhk5p)`G@-V8OxFB!71QneW2=aHyIPX8asTs_6v(0w5F=CMiX`-qb{y5pHw5ArGP z%&w!0-{dK>Iv=nmMb->lnA~>hY18yj(>$vOd-}d{R>o&v6!?!S<b={i=Iw#P#t@$4 ze|vU?%Q9D#+HQAvNV-U+HMb|WF&HoJXGa^|QiD<k)rvjnuph^2)mEUz_K7GFukUL_ zPtL1WE$RBz%Vd~vKCgnaz`rb+9FdMjUdqQtRG!vyqkAA#@s;kO<KLnvwlw+?6Sni@ z%LeL;`cAhHhvA@vin=rY4P;nhOCDX)b&n9kq(FPzi=@egUk5VJlGmNy9blH<+9NFr z@wu5oi#bnuOZGsSeJeMAwL8A?NFz@)4lQMZf%g^t-L2UazgM>I(<jGD;v~K6>jFEc zkEc7JoFdsP%`_QoDr8vr`i?Jv>T&;d4__e5N-{~b3lW-<9@Sqs9E{Q@7lfUBw!0XA z`P&F;vx9eaX337tL?KRiD7|t%igG`x`Y!3U!y7get9>%?z+-~UpFouDTqX{XmgBVO z_$WK3x~H*$`v*}cxR02~JTrenCT-;&mrq##(M`O4ebO8{rLjP+m(QN9_BtS4;zZ^u zGyjf6Q<0jjTHsEoEo5CIeW8TnER;^YPT%Wh!3v#8t90Ge<47R;CEaWd@-u#FYpEKP zSYc6)R2)U|M7y$d3H70z`CCW)?_)M^Wqwre;vSUmjc=Z{!zYM2bz8iR`w`0GzOUa3 zzk`mbH(?2xFpqS;-$;6$yYx6S0ks_PGUHyLa?`-^^&$TnPipN4?>|zzs#iJRpZl{w z<p-kS*jhF$Eo00z@@mraszYpBQ&>qFnvvvNX7BsK5v8-1e{Fle!9XOFHr8Ox-un1b z7fG8c;{ArCH3~)@B2FIOfqzG05?0oyi*cTZJY}^^8Ju>8F518rC0u#2_nB?D-L*7s z*MKAYwUt%+MnSLGW_@$Fc>;UTkA2r2Reeb5k*qeeHx$_TbQASCcQ~9S@$pH~XT}C| z(<~6+T+Vme*0)DxKajjqg6i883;cd+burK9d<WNcX=%;?H+hvuCvy$Gz77C9CVpj^ zTf<P=;et$s(2%MJPk7G@rnwAf|EhX+#V29KuVH8DiKzd6WYjM96&!Ptag6+t7^XdQ zErv?G{$FoQPO8U5#T}hX>&Ko4r<{J1OZPsfp&=SmEW2zJV0wc=US(ieU(d$+oA+gg z?j_n~-3>Nw*6O~sW2)3BnLzN@U}bbi1{>_IGVsU0U5sHZgacb}tYZJp9MduMGjYU& zRktlFIIdYjGFO<Z?5VkXNa3_Q+h2K+g?eI8eT|=7!&FPRxsdb5v76yh_M5q}XzX?? zI{S?Jp#^Bi$;+9TM*(~Hj@w~W>~&seeByDlKw0j!IkD>+Bm3=*ODhYEe+>-A$&_@S z&skH;bmRZT+-OSH03O{rS~t!XS(wUH3s<}YB|D=$Jm2qTN{ByFyNt(2ER&e{OzRaN zcztd7<K>Mn#^3W!pyF)UM|o)Rhf(q3EbIU3U7H(YcP|yq4F5ivU5_7caTC^>w{0j_ zSasYHB>!M0nfT)U`ippZ_pfGCKS56wIJArO7N5wX1*rY#dloyg@-6A6;Bipyqx<2{ zOyGCiW!_5<Wt~g{lOZ(c;_sM><l=}4uCsiJdRL9;Sm73*QJ4}`em3+7N+LyHVJEqS zh<Q?_zNK)VfxqSTw_s59$UBNcnj^}{7FOvxZm}4vHXLGESMe|PeOmb<Lt^5dg}=*f z_8pt#y+`c`KADL{xKREkNwMq~SPxBDcGMJV#n0VozK)jsuh~>h3zW@nSycZ<F6S#B zxhLzhngstT6hz_8tbGy_>&H~1F+W{<;mLL%^~X(2Fp>)Mx~|__;Pdbd$gewDFy?kG zM)zIl*EII`uf{)F?7wNczmtRzM^>4~@Oy(L)DZwFq!qe_?Pv0eLv@2DaX2D?6y1!Q zeA#ctJFolgrB#+F;EW{dsRdI-RFLO@-l;FhJ_(p}se}ZSmM$nQB<F$sBs)+}Oc&A) zH|+04!_9$C(>Q7tLl@F4Lneia0-k(l(83}7G(*^s(AhXjAn}m3fPz$U-9{Ci1CXRV z)GKQ5@g9gW<JOn=GONjr+L1fDv|Z;57z67Cl)ra6O3~Plt5+colt4V{^@Z@ZOgnz4 z<VLK9<vy4mRtd{2e>mED;<mdN!T)hFEUI0`qhovCz#r|W;|*#9=D-&B<nJFJ7s(0Y ze$z}7-PM8G(763-;nccMyfxA}w>Y5Hvk*u-T54F4rh~l;jV4Bq_9~J^D$AU86A2C( z2e5R09HKXhIAREf!!Cssiun%m03LmL?momgiFh001ql|}8^E8Ki6{8B9y<<8fJ&Tx zCc2}LttVyplE{Ep`Z<4g<a!=;#{0_yo)Yn*#Cz%_C_ye-my*iUC44p8S?nkz!d{LE zCF+=xIUq@-4?MSPE)<{U5!7*llO`2bCzDQEt^?WdDfXm~l_w7^VOFnQfm+F)uDlL_ z)-zN@l&W%Nx_hiRfip7##^dHZN@P9=hz{e0(o8ABy!U@d2kuic3-_1gUniiHim4Pn zJ}7lSzze!{#T`&;nXD}iFq@0!e_VmHlnXGVVBht<6U*RRP7cWA)xI;C2*-$pQW*JX zq5{|T+R20^AtlK>u={r<31t{JAr4HGpaksGX@>$HO{04txy1+&S<72YaWm2l1sj30 zVIo~f(G%)~xEZ>PvoZ3uO#F(%=^K959jM+!mYDIz>A98P+k`Bk4))y){DHTT{9_mq z$z7fVOg<T2lf~)b83IKCbv0&RlpXy~%mW~@`SxSD<U47iy)N8<&?BfSmWJL3zZJ_< zZ#CI0940^`AxyuCjlg20j}ddPux}6&b!IB@Pk%`^66E-hy%mR_pBu@rGV1>r2#`xT zq~WHaEg4ONbwh%KJ!X*zk-iA>-c+#V)FWmidhwqYWM9$ICAyyp|MK@jK1vlx*TuF) z9Vk-H(#)f?2)$#@1QF*n${_rp^=ZOA7}c04a?`gM|DsR!?(nP_lXtn+<e}*|UZd#) zgbM>6J4Ee$?cGO#Qo}aqe}7Lv(M}(kSU?EhjQ{q->{8pw+d_i_L_0<rhq-&DFMTo? z1;ZNwCWhvKk2dbWdns?yy2J|%Gcj&TjF2XNFGLxBa!Mh43H*BRM+^s-GO$bpJw(zl zRw-ALO9-9192toq-?l6Az%RuDG3q<)(N>@P9$#`&;wjekSH$lDs}0Eex?yNrU&1{i zQlEnWnqagwWPj~zwIB~ha~=v4aGy^3oCwcgR&BV5=V6pip`H!4%^7pTf+-a1XViVK z)DAurg$ENyq!N2$Il8j`I3sEH!$F>hQex|A?_j|1b#g-;DHv(Qp2cq*xOuaA?EHV4 zBS$%PCCpoE`X_$L6UZioS}JhN%3?s(OK9IaT|2csxSo^%QG1urk!L*aTCE^S25k{F z`;xR!>6>7W&`~v4ugP`%=2yB<ZzL7IO;?JcDiOq#^8kQX2Msr4Ec7b3wq{;V%Rii& zT@fs<z*Q9x>M<6mrU6?Z0ZAy)`r@LtuX+rRmFT0B!6Kl%oRV`_?CtDhY+Yxtv2f-n z6Q!e;gbHzHJ~d2T&pqU{!w*;+m=#TaMpl}0-vR)Xv1AQJU&L%gBLSPrHwS9GQBQd* zZ5X8^7XS|r*+K(6@FyR8>ZMdCKSakb{}v_&;&<q)XC;FS0xfRN2%e|IsZEFq)z?%B zzG*8{)+BaoGbcL4j8ohM=aqWxLWFmvVo&ZG;J%M8xp&1uMM%m>gRLi1D3>eILP6+j zd&S_7M-MwXg>mn2@J=ax@U2AkDNiF_ynx~)o#JlX*cs_#ki{7k3@)||Qvkq6RV<0U zI_+nj9opqke)t|%S3hV<qJQ2S!Aj{*4iK@-;FLjEX|Oe|!Odb$jntd{nqE^uZ&kFr zF|W%TFTM)I40tY{6>4Y2gyhwQ6+$f%wPiMF;ef6w@z>ibfD=S443Qs}R5Ca-<40Tv zv{-B31lwN0<Xek6zVRot1Sr}`e0EW=E}8OlLIBrwYQcv7JX|AwTuWhT`MUN@gzxXL z;AwT|8098xMHe0v?AM_T?MLi>@zMr<xI+q@I`vcl4v2m!^s9w=)Cv!cdg2ZizkZ_m zdMWxtwm}CS`&MvM3Hxz1W6ec_gCiTER=$K><H{vr7i@I`y!>aGBo8q{UUb&s9};Wl zKb*dQ$x(V*y=gp1CE<+}`ahsqUcp50J`x>3=(p!guuO3(-z6i_LW2@Bz|p*0*N;QS z!1<BOTo;R2|Kwlkw*{Gd6IIN`J6;@BY3BaWuUW+KktM{btv)`z1j0Rjz_U&YXwxM# zk1xL+7tFfLZyQH2&Q_1ri*mJHctRlGo2K8QsUZFBkXH;pl$V~WM%hN4!Y2f#8v5UV z9e%3m>cU9sdJ)!IaJML5(-#D1T@$<4;|W*HI73?_qZeaz2s&BsE1DO@nu@-+8l{+L zYW>ueY0*iCtcIjg+p#BRKO{rKz-t24XD1H5z$^3~g0BB=gh2cDy&Bq*cm(o%t9l{- z@hyBSCJh@YcZ&jNcQBaVWiPr7yD*jZzADW9qMGEM=NDUEhy27A%c5@bK|@l+nHxVR zHbr@$N9@FF56;OBNStO3a+)vSF%=_*(XgATV5~Z@DoG$E#501ZuroQ08<QV&sH$JF zN7<7<NIf96qDGK2_t~5$*2BfG+uKLPPE)Zn;~wcp{d9k9qQ`PL0REk|mN#FYuY9AV zqLZLlLge4Irh<2*2PXhFZ<*==a6v8<u=!7t909$3ek9k>uRkW|L)>Aei2(OV{I~wo zH@~HdM3kZRo?Q?ieq{lL%O;nV0|a?bmET6Z$h&Y7`zxyW$VqRU5HETJ(#!NdHxgsa zxHEuJfV9}iy+qhT+V|bBp-2B?(`DHn!U3-8f|J+eQg3_|;;X!EWE#n{?W-xeK%h`k z)fc4P(_YqlL6OUNla;Tpy)9q+23t&-NWx*OJcK`9L~dp>W;#3p;BlKE$arR{dlNhD z2s;1>A9tTT+Kngl#S9&j7{{N@Uz?%#qY6%ZT&Wg?tK0H!Jrf4ta(*&{nSWT2Pcj6z zT`^}ZIha`5{evqo6}Ohn6|eZ`>ruH(H*8<WHKY_GTNEB4L7M+w@>7}laNQk)=5OLs zLnYz8&)l3oVlCC@I&ovW-zT2^5xyizqMl7x9T(EhxWcHBBA6WCa~^0r_$OLX_YyNw zMBu$RcuI+rkOUobuaL0A!@D?$-(V6^17G`!?FiFFNiPV4tD<6XB`H#)ZMlUl{Dd+z zaLSp;|KboDOZ4$vl7S0PKlfjFuC1k@C|31H6rNT}|AEaBs{;vS!VSYdp}`eKq-+Zg zt|kTleT%0MUpCRnD|q&))C2OTcPn@*{Ga;ZNb&Pp2%uB@{D$)2C4td)@-CnHABAjk zh2AGcf?K9@C@-*TBmY+v(1N`Eiy;;-pxZ@L9cWKHTn|xQBQE;;2gxQT30ZEs<-e1i zSE9Ulm*X6DNke@wLpN&`F|@rJ7`RbISb*ApQFO4LT8~<ANFX3qXq@7lZqCH59h#BG zAd<bBP4b)1$d!74)W{$7qACUG%A%69YL!X0wT>2IBq>PdqdFyrldtRIuL`#avMAgp zZo0-l_Z(j<m$Ku;(p<|=fxo^F|GMN<X_R(Mj%n=$|2OhdRwauFt}Ln*cNj_pM?H(= zS3D;7hDgPI{KzYwO$y6k+JW%5H8tgzaIe({598&^Wa0ZPP{Gr?$YlX|9BI+KrmFL& zxbv1E=94huyH(HMHH4(yR|&U7{#W)2DghcQx7k@UrmqNU0?(%;-9?7TdWeN6u92+l zfKh(39-NS>LI_<Sjj1NFK`>ktHf!q(&f|-#-R0yhb#eYLRg$NXg6GA6c88gB5Fnax zbiJC_iXa?6YA7~%LWm@x@EqSPK?t3=#qw8GS;CiBo-rjTpUfo&`4ikO$^kUF)yu~u zNeQW(7g|KO^BBK&6?{Ufs>qY)+}iy)ssUP+{zW%3GF_D9;4}W2Ozcxzk?LuWX_}OE zIfMo=8Hl^~<e4aZLgWgOdO3xHl8p4oL?Y0FB;3sIgyl@ZpwGrZS*FfEVZzo(rpS|t zzQ=B1H5n(v{AXkxWl2(MRU=_(A~XU)&9S59x<Sor{=HaBtsvLpBQE^#p9z<7uaN`V zTt(axVe&?fbD@KPdW_nJ|2JvpcRAx2tITRtx<WC&{i3usj_5IaFQ&dmE={)FN>hl3 zz#;rWFO`h0;JKlc_TFIx>d2qLxccGWkpUl+Nxu<8xki|Zey+LQYy3A{Dg-ZN-9QL^ zSA+aOVNZ{a%b&$CPt}S$ck-6L<Rg-=hj^+0o9fdNr0lXWayC=+o5b!+L!=43Kx)vZ zSRnEIm2Mmp?=0$%ow=vIf?ujlT2F1hvnwGO{+@6)|4e3)G(S8gME-<6Iqsy-O?~ux z2*9&7$%ND?N=o%(&{28eMCxcu?Z%%3o{JVxogz&OG3(&ji)^`oZ2qcy6Pov16#%S* zS@Qeh*gla$y#8O5^Aas@iT@8kTW24CYhoF4r?@?5!s&fArFULQP%`RPt^YUH;>LSo z5`T{dT%n(=ldU!4B!O<^`K~vJ@#z(9e><*3*p$6ul3Lb+8zEmiVvB(feJ`14r=1p1 zB|>|T*Vv2R^ZhsInWtiR+U3z9N#?|M!)+brBOUm?*mNC-M!mTPv7o-Jxkq%dK?X^f zusU8Z#JsfQaBaft;ZB{2!r=J$?ngo-GEa`=D~1~Wmoxk_qwuvxlH6W&cf%99)*X?i zweX{x<!Tit*TmO@&egqaofstM189-Al3p@^h3)TXapxIP0*E;>DtW`hd;FenElNy( zZgp28r~lhzfY$JkgP8ldTiN6&BKOngA#quKW=SgHQ~1iKhJahVp%jzn^OEp4*~<q$ zib|`HL_%*8XsjQ%=vV%Zc9b@$ki@DgKSWwY{k#$?|BY%6DIk!h{-D!K>`*DA4&!W% z!SH1QJ2yCW)v35VWaQLiDS_}pYnRj`B9WP#^I_lMeh^jC3msj7V`<GKRZ->ik+RJ* z7I`INa3KQZRs8604Q9r(-AD=+|Cjh=LWk7AKj<Sn_{Of5*u2$57D;P=w4q|B>_f~* zx^aB2S>hpgv$+5e9}*{XMMCkM9d=z#xDZgEy<F1L;ohpAug}jMT27-h)DV(ni2T{v za-j&h4<%=(Yx75y+o!vTvl55D_?sw;E)zDD^efB+&Qn*dWC!Obwyzx=s+ZU--2-aJ zgY8n=@?YOQ5hHbzAWud3O9nA?+~AMy=M<ER(&gJN<S+R447K1jeL1*@lID_F5XDdx z==DGeF>NuYjO)`jg3-N{mg5Ii`Et>{VcWOMLpu%KwSPx(-^3>Wn6Z4fRjV-m@wJV9 za@xaM?8CaEdGzjU*vwdCnaJ0FAvd^Dgy;%lWXyrv&kvuAb6#yV5sxQE$4MJb4YmSy zJ0a$~+XrD}C)7pbVM^?2&`J<)dFSJiPnhL9MP=*ZZPB+0m)nWe>9AaCtQLPWmwpn- z0>xQH?e&D-1xYCWzDVRg?UCP1|K=z^)gFgq*%^O+eto1CMF*>F72n8ji79^&BeoM_ zO8ahzk@$&`gig4s!XVibZI$V}Uu`;vXhkST?(=vRXT6y#N;31mEg}%@-2TbsNe4kh z>_A-j?e-Hg{DUIJ@BV!``SpBlz0{z`hnPj;5%`uW*|%zntw^j@x6@^k5YLE{1O@qP zTI2nz)4K_JQqULbgULeLX3ES@-8cSgUq0Iu+neO)xSs?!iIWl7#4m{I-_060bo*BA z+n`g@{WI5s&HM3nP+9!SQw^gNpQ}iJ+~yWKLivWo&q81Tt;DYHrP$!@bLhNyLjq@C zgaAqXZZ5oh#fcM5U_Ut+chVO4ftS$?HXvyOG)WU8<44J@usb2*%ozCt$I4<4^9+eQ zM3U<QRNIUR4xb2Wr@txvzz5NAkL}COe93P0SG{?_c^}+n{P^r7U6Bm|>QWhY<>%8) z?j-$~+q$c3`<T!<Ax@s@4URrXekFcq4E-;i*jx<5ety)PJ9H7p)BHZkc3b4RoyKX8 z-sRm7tm~UGrTb&DOfG*pa3$J>z=5Qkr}0%2L_+&&O$c80+xSUCAhMQ-2O?i&EoA6g zo_%^wVb9v<`aM=!Q|_6VT57s5U%~v(I(SZj{9y2f;6ia8{g_yc^dP^o0l~tD!0uXJ z?Q~hsx@3aD)w>-)=r=20>3D6|#IiDzhRe?M3sU-1p5DC`b?4d<9B#cUUW_!<`rY8) zyP^wrJo}gv-?VsU`K~X6`Qx*Tf>#f0zq`!cu&gRAgYl)0_mz$vVBal<=KeY=#b@35 zbW@E-=?bd`SmG&-6p1H@MvfK<6O437Z9;Hw>nE_Y2Y?N}<SO7EEzrKy$VG?r%5GP| z&;H_-a)d1Z0m23WyA?}RHV@$3Zv7x__f>@8BOu35`N8|_q|>cae&0DF8D9OxZQu0( zADuhB##1wc4C$dBX?R}9FXDzdkGlqe{p+E4;Ph)*Q{iW2Uz3Z)-s#bq>7I$dJr#@7 zzf^pV>hvgeAzRQ2E7^|aZsPUc;>`PZi+VHyMhrTL<2fHwgFSkWZSW$%P}zNxPp04- zj!F2=SBAggzv|eDrAP!;dT?OEFG!KJ;pF!TmoCSDKzfI;LO;us@rTAtn7-~dZxS#U z&A!4<@@*nWaUc?rAMt;Z3Gt)zhd$keM-sSU){OC-V-q=2JIViDIv#bl@cORnD1wsW z(r>zQaAP0a@?M6k{(r%7gAYs8Wqp8F1yZ;;{O;x9xemM=IRe>?ybi$&GaN2T4WbMF z)_rnbdvWFJi$cK{=CXCEl4t+9AFP<fkj|(76Up!VpQE$zYU*+0@ZA`&k(bdW8w?oT zU1M}gODZiPNQWYBqc(DMh)PK#jew}Mph$=y0xG3~A_^*EefQ)1{)2nYz2}}cKJW9K zR<gmjRFvz90<bzb7sK+MCA+U~dSm9cjt8$SLaEGJ_*O+X1pR9pjt_J|L@3W|m0RCM z-p7c;jMMryPuOv-_H+c4p&UJjwjtRLZYTl|dr?OG3L8DmXX*oX-qZLz5yNyYH@n(Y z5+9-hAZ&@{=G$l|?{DR^jHrrz2Ku}0xQp`*hz#5xJBwvgy8)DNMb=&$X)uPhSi3mH zx#e7E;F6^pZQe|uK6<&_$Zl2;2;`{ehj%@hONS+bL-wcJ4Q{M-fhIrl^>Pab;Ejbt zjSab^TyT}2^2ugc<~A-C#|{aCYUpaEo(>OA7|`N<ZpgQrcVQ8AuJ<UYsLFxVM|l66 z|3^&N+P%mR%dEhh*=!KvE~K2EP|^qF(j|Cuw_84dY3#pQh4^O;0+--kxkH+O!g(B% z0(@x0HuVbJp;`P2HKy&3Q@1>PP3#}FE5Jy&>Fu@aG#Z4Zx#cb%%1Y?m0YaF7{<1w3 zP=jkk<h_9o-`Nl8KM*T|F-KrO;wpU71$aUlm4JeX)~cz-qZt)y610k)y}^>62XLoJ zWvacbFZkS)cV&+r_%BHI`IK1br;tg~L(!?>x5m%CGiQc18#Cd>VnL$_D^K$pit$Gf zfK$I?=>QyTI5iXAWh)PCNjKu<n6I=l@jRewuTqiaR8RqsNrw&A^D@zO7Fa2U;;Ma_ zDXBcNC${-~49D|%E2U>njS{iaWEFb;R%G>KE>WyW`i3moSdnv)3sY!YlM5?$3F)nx zNB~Gx=~NW9{&9zKkTNjoYCe<(`?oKKgG-<0aP2xLEA-M~&GxBDMO+S6w?8khiLQwS zSx7XvGZXyUSmLT35zp0Z_mfvq+Nr9_1=fJ{@P;+OBm-9hRC^ScNSU<VVpLj5sLX)R zb*7>!e~zdfk5p>}JrD&CkuW>MJ6KX>Myz24&;vJDb_(fKsjYdlRYs|5UEtD_RD9G= zmsF%50zl#cKs;4Qu?I?e{{0@kGd;rwI+f+jG;=y+gA;wE`>{=f^xZB1jUV)i!BP#M zsMlF?AQ|3uFFcg?ym;O6`0R~gFbAc`lF9Pad*IR_zVyB5!d+IIV^keS;rR*_hN@X? zmD*Fb7wntzyGSE{CD}!-TK7EsQYW*t*5^6Hd(BbQb@^Qhplb@9rM7E|Wr~GN>C{c& zkE()<ASriI$nU<K=tsi7gH;kdlDoE~QNk5$%Z+_MPtqVwIrY<gZ$;5_(oFsNt3|ws z;NQ<z4r-@cyjY}}o3h5f)#he`Qt7qKHQY9--m%W@YW5vJo)IBs-^65cU#9IO?u3bU zx*Psyr)30qgNtjooGne&N&a7m-1{!4VpMV(i>N0I4{w;EQ`)G^Ma3k5_yR}i3y=+C z=12r3x85MtAE(&CB=9%r1)2@chW-`3XcjXuN|LQk5Gl9ryyQTIk|xBgqFnf8vD~wU zOjqrDeCrj-hIwF33cz>sG92HVR>=<dL{NY4I#D_47sNEJDd%BkV<cl#kg0%sM#648 ziO_^%M~HG1%;%Tkro^s@!ujVVD`%#BWTU^*vV~{5sr=j@GY!kP@K?|*bIt{YCZkmh zddRzh|8^V^(o+JnAmh^XCNnG&G!#v}v!(W4&MF#V_%Vt%Z(SbxL;CqVz5q%hH=^#r z0PszXCbg2Poa8>H!aO=fmo}cL`~+p#vof6*VN1dzCpDPyEMd9d3@Es9EraK`?sj~Z zsdQLwXsl1Cug*<nK<}8bNWi>a6`+zmh>E-gj}hPwgjsV~{9iXD`@6Nx!%r8L-lbBx z<k+kpbMhD>`E5w%;pim3QnZ7i9H7}z;JfWPtz2#q0VR-jVuHhYh_m$J5k)9UU4wO# zF|Y&J!T9MC0=uZ60RUlwBI(nLc_dfmc3?+;%!Q-j1XepqSoi2{L5L!+&`=iY^EY#o z7SVy0&5_zAp*^dNt!E`rTxC#fXqY~NP@Y_;YIWt7o%O497rdO-8L5x<!Zj~^l2c*- z2A%%Z|K{*m8fNI%t_Mw?pZj9>-gA3l##G0M+L;_+K}3P#r|^d2xZFE1jt}leH&&Zs z*nwBZaEn)n0<DOc>?l7Wf%3o?>A(o1Zp5@4#R9x}XoWfR)y(NNBY=E8Ty}{Iv42ZF z{fTuL+Lv`&q=$j9-^_EhWXt7v^@-P^<(;dP2suOJJ;VGNb&P{=0Dtj0Fl~IN{k{!1 zTSNz+{zq9DYD&xko=L-uAz@Wd(s(^{-Krg%z_<Wws{jt)C%jE8z;4s~U1g>7td})$ zbEi7BQD|r0xR1o57rex`3)ZgBgZ|CRhu^|VkWf|Db8ZOv%YDuU>UF0gO$s`Pd-7I# zDtiJSFHt$0T7Ii^%qH##?<!MtU%68S?ryHfe3VuNotOJO$Uo~cDnWy8Skpatng8B| z%E_X^;Qd^hJ*i3t-Sbt<zGJsI<y(UW25ZPALDsR_HdG4A0m-hY!rPTWCRXnfwK|Q2 zb;U9&)BRc6RM_?<dQu&iqP$;0a4ciiEo^nKoNdDpm9$+B?mqgnhxCM74dt)WJXz5f zF2U4!Z-z?J%(P^D++LlfYI06b&N@A4zO$)&t%nER-IP`=ZAfU!hw$xPgh%?tc|t!_ zeOF`2Q+a*mrtwR6UKnyvJ-#rpZDimI26Vi8(9RnL(HgHt`ITAo0xKINzCV&rkG*`% zZK(8olovfvtO)(&5;qi=W*QUm0+n4z(*43t1jP-*ZK$!gZ)}G@OGwnPeP$4EDT|jX z;SDVKqHQ5=bejR^h=6{*#<4R4LC!cadV)eB&cU*$5~=H3A(XR!#Xg$AEOc&tzeh?+ zgbg$mzx^tC<*5%-Xtjskm-0JlSr}1;TrIqRQXSilE@t)M?dEQ3M}F01^wnc>;#b@! z{^IwvEz5iNL!Mr>$zS;~hDvrlTYDblnCE0Mj|o^diV__YE*oZsKw?MbH}W-Ia<BsD z$3F8jT)lC!#1U9?G5pCvgz#y_uW5?HC&w?HbI7XV8VJ03=J!xwAFMb)$8evgXkzi* z<u$(pvt3!_Wg{U>z3RNM=-xqEhv9ZheDY(-&rOZ5Z<RCB4WoV>Q~TGwm12F=4ZlNc zm{_>bv0vC3aTtSt|MY86kP@?0TdD#7b!;js^~&wrv}iMtZeSzH&gIfiUHrvMEOe9Y z*2qxwvO@5(cuo}xj|p|noGAa#pYq?V?s_o#^v)Kvq3M2Y`-=Mho<N)2Vwv?;wqw(! zHD7KV43Xx0B3AXp2pZmx_q8SDQeAV(Rp*pvC!lW+=8D>hAQY6|q{~qZOL!)|#fE(Y zuzcLpVe(x$b^iS|!<>&m`zqp^+eA~Pyx)tSOT~@AC|0P5m4|KLl10C_A}}}^PNr(Q zJViDc%CbKzwh9FLFQIosCvc;m$TAz_xhVW_(~zP(HTbP;9@%bpRv)TjI|eq6NGe0v z-gO{zb~u!Cr6<$a(5x7yAmza@EbvL}@4VR5*(08<i7nsY=6SL7FqT>1X=C81gqi0g zD<FIKS6>!Vu9LUv!$J@<IycRA-{x#~t(>df;uZ0ee)h*aqm#3+GV0DFT0$PGE9@{6 zMO_(XxwFM~ce1v%iQV+^e=I&+NrysOdkg=uVfWimJt+2GHZ&P^()EO&WAv4-XnfF4 z92}p{G&&$V$K68U_z7cGXrURmF6)v(7N2^iYLtLsN&zS=b##dZgFc1PvRpPPNTJV> zKFOx!2{G;4a#-A|75&~YAdL}hpZlGiA^2{tt4^W2;4IyO)wD92v+T|~63r=dic#<r zZP^mlBhiCf$96&Qczn-rjFy3-^g<sGnQAb>JCD+tGqR;-@xDtSbn0X$Yz8VfIXcI) zl?94!%R{yaQF5_kl5L}3kOlO)8(4}xMnK-AtV<e}BCR(rO^cl!u2d$U%!|Lg`*~K> zaMD3KFoeis&H_{+dv-ZiqLgjuIBn>}A_;H8w<M_Wcgb5$yRx<fMhr~ysM!JgcXvM( zf3}|aDGzD%?qs5N3yK9&6!?UN2d^v@t<j0sXdk_)hy->wVor=h2-a_96%;sThDmq< z$S}~On7q8N(8gig^IWU~_nGQANS;${YDEP-lYM8ojca0Q9{G`=qL*XLY9PuQ4wYht zE?TFh?dEF<&WYKLYU#nmuVgU1+qzfMCEm@s5(3qqPLVaKK?@?$RZ|*E-wd;0swB?; zKDI*2yU=d}RMVb1b20s0ok|<pm(wO$xkjM-za7)2#FWH?F<eEVp6zh7s;NpEn`XO2 z`kmjhG3R35;S<`2VUg&M7Y*)o+Zf{&>0_`PD$7IoU%F5|w1a6imj!vu_$mBTQtN5w zc&>SoL6;SCMZ$)}g;Vy<NF5zmy=cq}l`s+g9iC~C21N>~TE6Qs&s4(7_h{cN7*5Kl zem{Xp+B29nj<^c~c`wv=BWyXG9kmZ}4AsXZx~Ctxus9?pmE!U{E4k6e&H!)p%n4^T zVVgXvMmLdPfwi|;@_2K4>%;Zd)YpN-S2ThgFW-yu4%iqkvK}}P;n=eF``|d>hw=QT zX0Yo-QFAmUJcmOYlWX)ZEQuuq4u^09G=^A>$s&P0=w=ez=PSi19QVCJd+Ev^*NG+7 zH-tB)HNuf!RKM3;)T}!D<ItszyR?HFRZQ_Xw<C=T_WZGAP8efN&sUyT(>JOKzH$)X z@x$ykD}dSXf)ra{O=nnRA%poV`@Pa9d7jClo<C##x}hrn6}wiwkA+8LhuG04MJQ{M zHQVsydae7NACt|ITJdRcmrJ<qNa>X#i}fPE#A9jLJJ*yH3Fxty6BYsIkuPcXXWsJX zj<W{50|a?|cu9F&wjN=9#)nL3Ck7!iyx-O1&`_my%Uo3baGx&J%Pkh|jrZ{AG_!Gu zuiybl=>d2AtgkyI=cY%Td=R5$?rOHiNQ+WJN8%zfj#M;5P_hw0^y+cp5w;1aV92mp zxw<tZ7Q+^Ijx`Xk$ZnRXh#kt`jVp;T;YDvmp?8KkY@8x}EUb2|tUOrIMRDlgJ?5Tq zcHh(w$(e!mTVX5T1&!ikh#Hu`xc`;`2QQmbgQ!Vv+;#kx!$sbjzhmJBquPzjvBBz? z7fx9Hmps=s5)#$vKG{)}w=X#VytS+zuU8Xdw3R3VXxH|!ON#1j`HS=VE)B(^lc+Hq zqA?GauV!&4J-}k0oGUqg)>6qF<<o~UWetGPL0P<;KJtjytNEf`YhqqX%k#ihmajiL zhh6pNoAxHS{fuB(l%_>}APO#b!1GZZavt50#y5d)sZhBnmlUm)>m%{9*#rWQXzF&J z??OEK3~$`aQX&K=cI2epEXOTL`mo$^E?`CV<Y&4@-_;Ax5@d=ZEl#A@d(9Q0FosB@ z>*NnRGh$py`rW*-hN2gm`g8Q4Vg|0R>2tBBny9tqGlqCYzGH)jn&RR68SeerKROcj z_a%>BTC6PQaPy;Ay(u`QEDxl~Nf<h)fr}ZR2N`yO)a6|`$a_6icIoRl3X|i9d{b$A zkyooY)-u-+sx^?1J5<)MJz%r(m@)>UVHVz>v!l=MQ4K~joy#MHe{C8kqAe3HUky^6 z_dhS;otIxnPm7xscj%_i(z?1Ze~OYprzA#9z!RUqr(8-mj{<X!d0d#G@5wD*_I=iu zG%5^y6-6S7SO<ziS9tEdy8g`MzmEv6kzcnetH`dh80Ibcd46p`2^V-k4`E6U*<da` zDvQ5IEBSt_sUMoNd)a7|aJ{B#bJ-lZ8sr&nEcAQ-{eIf@Q5n5+2g}qNVm#a6tC8dc zG62*VkZRveh^@c0J906SX%}~fhZ23CgQ|q$>^nbu**6fF6D_GoUR3C6Q@Fe1T_j+N zQA}ghP>k?IHa6y5@m$+xeGl9)Qer|Z1|e#cNZ7OgIxdD+DCCSc@%=7wD12P<Q_Rkt zM@17u8yx*RxaxF48}p_!xnZ;b5(!};_^sCl)t~l47iSwuEFq*+!k7;!`iVn(yVfzS zzt*^rz)lZh2~F?S%S9+f#yhL+b<i%Ib1DQeH)MGjm96{dlG>j{EgnYIlm=<+J%jHP z7tgD6UwHYn8QLZ0AtBC!txRhV_~S&^j^c&Z`d!4Yn2>L9W6Z<uy{^4yA?WSef2J4T zYvOA^5`Bl_K2WM-KRpJM+0LLyqU3%`hU|LLd<yUMHj`cD!@arZ+-3A#u<-GrxvRD` z0U!`MNIa2bD+y-}sNVl`SvB>~_cevze{dhYL&K1~bV;6z_hry-gRdr<7(ekFi89lE zo!q;~kEzUZOW9Jk)<{zM8~UkAHkAck-*Wr&kK5vI=N`?7nHIc2Z9w1zQyyt?QwNN| zHUkmQqn6^7ayX%Jd`Hcrad*7cpoX+$9mlbCo<UcGNgg*3ZEcy^d$=%dQu-|+(bwyq zHdNYXT^l!;gmp#A1a|7GXU+U@&VEi{DfnQT!-#zkBL$d8*ws9P_%m#-tFDCF-{S>< zmDzVr*{OaH{M<1-XGQ<c)0Lcv<!0TxHc3~nc1>g}H*M>fC%86{xuAsFD)iuDZPGi! zU|zj?dEz8p4IP~}OfiTBINCg;u6O@hy&_lTV9tPa0atfW%fdN5(;MqFrqM~7md>;M zUt&{iKosNsc%w<uYq7Y?gJyb~x#GXiAm|bu`3tT|uRAL1c1v&7S$WAT_?IVN*}L~; z^GpzCjo(A2?)`<l`?{u38ocKEmvBBZasBD*6q>V}A@s2U^i{$-%vJpvDQ0ocOMB`p z>9a6eU#IumwNZ=Mp{K|z6=&I^4F%FictNN@N%e-w)`sLZD(bQhPey&yph*1QVCbyy z-|Cn7<DXu<RG(DNH`?nucbN}P`ZfCLjPv;h0j;fq-f(Y<Q@Zf#Wp8IJKDjw3>b0Ty zCNG-Bel%m@vt@1$QFJH4{-yOTR2f7Nj$jHWZKN4iQqf+wRfip&bHh%>>#H9cn<G?T zX4_nnRQxJ_iVo%kHiSX##TJi1!zAgd>2KpTqiZj&N-yvM-pnwNf9e{)!$VXDL{L3= z!10IcWQE<dmi&rW`guFW@7*4<1Japyl#>!=r;ie&?AbC5IRJna00aOO--;#w)_;=n zW_|ZOxgKP1GX4&e3|zfjEAiVS>P+x;qB6ZGhQ|Q{Y~9*5Bdy!Fv>y&htGWY`LH!KQ z0;fWc86qm?jgfWOW;>M9af!0>NrmuV?=tJgT#g61T2KP*2mIf0$1I>rR;(UPV-eI& zf-BXGQ@FVAa+IZK4=d93g4s}ji69OXp!nhAjO;{>5TJ~<;Jbm~#K6NfT{pcZZo+M3 zJrMvL5anKkUpk$M4r@ijR?$-zPc!O7n7|fAt!26Glqhnd9<kC+deUE^m!;n3-Wxm_ z!Lm(H;E{30Aur*hP#h>cV;`p9*V_gV2G)gkao(A|T=udIAf3+ziXRZ9dcr`ctOqm= z<TQ&rcNg5Ra%8K4{D5Db$Ngm18>0O8fWawx@3g8Zq6LhJAO2!vn<V6G@Er$E7zzOi zCyK7d-se-jqy>i(=D!JVuixiYm5XQ{_FHuAKF-yDaD`&t$@|@RZ5x+w3#f9e+}QZG z&B)pE1sKIWfq;&NBR@=D;C_maFBn-b`OqH6eX{9yk!Q+RVM!AR@2|cp2$|pT{KoC? z5X1D0KxLc=P^^XlPQ$)FK&rPLQA0JJN?}RknB?=X^x*<dQO@WL(=!zR0!x>ebkoZd z0pK-eQTy@Bk3KUF=g_e-4tqlb2t*tRPX!Vtol(?mRnZu_Xh2u;#bx%y1r%VKh@}cy zvO4V)Bp<+dWZs?}U93)bNcAd2@f3NOBc`Q5JN5oLK0q>Npxy_TGw{Y{YFgEf1-pu( z-r!oY0B^xJede963o*4ArcPRhw$W_{-wcadFtNLaLFZT5%~^!ZTdN@BTn!mKS6{=R zkzbo|r3@0%cj$Z&gj}*f53K<gyFMb_(zmM38nS(h`ICSlQ_-g|2CdEwJ7yCGpcIPE zFr*KP`gjW0nc(}}1FbF-&s{;<8(%(D-W8()t&qq#I*X~0AmHzzG~mqIH7~lG%n~&f z)N4ldh+%uth!a)gxZDAMhP!OU+{!5C15FGDo3w7JdYP0fad8{+i=>jLOht0O+ZsVn zgMNMqkUO}c<JB%49+H+)!W21NgOi`FywzRtW+;Hj_D*BrIlUUU58fzL7ml`=vx$Gr z!)?sq8M)_9ZMP~jrrL$SF%M>zs#4@csPbq~VeEw0ujv4C7!@I@YpQ5C>l||w5ZV|v ze-V0!zB^AhVMDW9h-;tK9yC~Mvg7`8<TAe`%N>(|m)B3m#j~B<v-4JfRCO;wInp|e zF1w}M3!Ztn5GD-RCC#q^p5oMxbZXD9{Csm=_Nt*QbDdb7ZoeDdgJUS6{UuZmhuiD? zWu}E66@<a+090hbk+sYVIe^TDUREI=Kg<}0$xmxT^XJI$nl_DMOHGo+qRl)ExPICg zjaN~#%{Mqn<1<e5Qg|9)R2OL@`0OPk@&syBkN!zSdMD&2exFoIG?sMzGrc<e(S)iN zTNQe`3v4*(yv3G)f~hGHqkNJ4rPL0TInKj)S-h^79}~p5>5A7i9aGG-SN%v5#^aD_ zSlWvQefB0uCNzZv28K8mjJ^8HCMuRfeu84u*))=m26s992}k$&g4LBKjisZ|J{ulS z0K3~l1qx{Osdb}3hJyH$6rF+_LcnN|+3=9R6HvBgCt608Pw-(W4qmlqb70)#hp~I= z!jHQexNReR^N02W422SS3%<*u^W7j@NhB4Poh%fr5eBI8-=LEPqV#-tjF1>AedhwI zSryL1?wiqvfU&2wW=^t171t2$Men~D7f(W*O<0{kNpda2n4_!}lx)#AjL(*-cbo;? zzh%@{SmWohI$m;@QNeagD0*`}qW?^#M^mcG+h4Z8B`6nvPJ<cel*VgRDh<nU`Z*Qc z!4TyA85~&FS=mQ5aDf~^yN9_PouPdU6n7K4`9=)6Wu1`#1#W>8b_SU*2A+v0<zAVp z<0>#ywE&>Q9%ujQtC^)<lE)%G+RVj$JCh3>MKf&9;Pz4S?gDj$ey%BPzkbg1nAp25 z%x`tYji`?>k6nMd+vC?4ZbCs=3KT)bRl<RgU*ejDT+aa30!KO~3`bU#ET7;Z`L-yg zvEnrMjyOeHWR`?GoW9;4kCB!p5)zW$B|e2c1X~wQ@>mOTIY}kIQHe`O?H#8RFg#)K zo!I8G@I(Sc09M&?1EL-wZw2turCgk7;}@v3MnwMBCJ$PaHXvho<-38-VVo3nGdq>d zw=;)htK^<6+>;%7nj=4lBD2s(f6<ZuAUd9xxWu2ya*?XLd=^E+v4e0_J+HVw&V9+s zuw)+A@r13+meYLkU|jC4?OD{d#ye>G(avL0Q4WSg1poyhn6qGNZ{ECY=tO+WCz+#= zj3_2dy(ii+)iv)1j{{)WoFJz;YPrDszpkZ6J}x6n?(n97<W$fQiYtL?eQ`f)Ms2C% z1TYN4qCAJ^xmx(pQ}n~~0om{IdJcvO;#1do@y514?hc#cgYn^6REbN`8f@8CDa!#y zB=gIJ-X!kGb`7fh)mJD3lgJ7Yxh``gEb$Q{mp1FG=#^%UOJN`{rz_%&Q|GPjGgyo& z+Ar^<ditl`)M{B{(Sj@R)IC_E13U#k2a$%pbyE-2S}lvJEL9lifHUSU?X~DB;%cC> z{p>$-soHxK+#vCl1W=|8Vso6sAeG8SSZNJ6K_~~K5IK;sAT-6ZruJd@y@K?;t~G>z z@9D+r?IIg+>=xm4Zl)d+-tSM0`8EwE${Nb1YrB2<j>^*17-UAi$PFQJa>n1AD6TU= zPRhQWLQcUvi}<d#m{m|BUCO{NK5OQ2h6IM;%O_78Q=Ay)p?ht{b{e7b3aiVydFEL% z$%j=}Kj;$#%_nUHx&p4-71_(KSX$DwC0{ea&Z=LSVt&T}w1&=g(LuT?XnATZ^R@l; za>=0>tOC*73XN9WpJo+TXM;6T7^IYQk65OO#y-<rar3gAHD8H*q~-VW<gsn5<MC+5 z)*YjOlAfMJ6k8wa@>}YTCkE6xmpR4m#s?h#XYS(8r}FM|w%hCDj2sARyvak;Q1OP_ z#MARe7tfNVG_F&hbU!`o#W{eRaZ&6oUDaP!pPIH)TkPVgi&025FBLre@yhCv&cxZP zb(o{LS8R2+&G5l+G*Vbb+P|6>I!1+h1t4rDd=;{PTw!!L*n4_i&#_A{-^a9Souf{3 zkP+9Ihk^KZLoAEHxO4dUYML?wT0|;FhF!(cnGtB+@;Q}mxZaDv)CYBHTo>#=<GOW0 z3NP~_CJMG9u0P^k;;#!Ex$ycO*bF5KGI+B15Swd*`WUVXkyC<*Mh$Utns`mRNQ1YJ zuS0#jfO$jnQ9l|Zkn00#jJiHnLE0yP)=M^x1q`gkNsN(<YaHCq8XQRt(O$;^z(#~t zP`WM$efBwIFk>u$@`4hfWEC(il20B9VUGaH8ZaDH8OJIh10R=knaEEx^7TZ#h$!eE zA^HBNCA>4OmNNxDqQsM+NAae#$ETN@bL2T)vkN*aa}Sh`;^RiCQx?*9iN@M!M);({ z?YhJt&?MV<8tBX=j@_0gYl0sd_|>^7fFd^+cLIGR<pRUCilA(^5gAmc>5s<}tG&>y zO?LqFr;j}SyIk9g%wastWJOC(Z#&;A1zC2`yOOvB?*JhQa9A^;?IQRoCi~0jS6P^T zjJ7_)J0P9F{DxrDq70ylJ^6V?d%wQ>7G0=Wmc6S;`mQ`v!0F(Pt3CS4)+l4raB|Z* zVnNy|`YcbdoM3;N0*Vo*8xg{GxzClHvQ;r86N6~75E{hO;T4MT_!U(UR2Qkr0PQ3& zY~p%)117uXV5AY;s660q1GqPtFSrs9?X)4#NrkzhGK@|~(btv}FaZ!?IK@z7lXlhM zJE$HE=HMk;jTr*=EIA6fNIb+^NAnLbUrot`?McvAJrGJvu&{`mK1obGckL0HtI#ln z-M-jti~R=1hW|yzz6w}U2p#4vV=u8ud`vpsK`t+-g5PvsAE6MNX;DU$myY4<wfPBB z*R2A0--v_5P^lGP!e1AVP6C{F!v0nUZ<&IDesuRF^_e#>G99WIi0L(a0B;9#zhekw zAQsh0U0s<Bq$j%H*(ru8*;#OgJmx99LlTej4LK|e>)*9BI=XS+mGS+LkOnc0bQ~pW zK<|uWx_@Kk^Lv4b@nCXdyk<l&WeNNbs{4gtY*{0oVnI+v;zw2JYNKc#RA{u1MR}X? zmGWw?P7F?QC5w^6jTDd5j|HcH-QxYg;kZ}{SCYLB=jRylOCQZpcz!*_M`5`uPIcho z%gIXm!<%#q9@}mKVN&+2kyfR>)sy{#x(P8lL~rQAZObFIn;1f(Djyw^6Bg~k5MXk1 z*MD<~%=Uz<ZJ9qWAs5EsW{gO$esxPv`)d3|ipw_LV6YT4@)A7}Sn0*wB!jcdsSJme zqOoDU92{4k^LJrvm$plI-HHy<-1wWpFHV8J0)D9K^xi^lY%sPP$C3Xt^)X#^2v+2> zQnX`fR^oH66m`81Ci#XbO7O$-o%i5gT<Ly#W3alo$%b<1PukUpevpzFn2uKvZ?1=R z>Yw=Kg*K|H4raYURvSp!-z~_UICax3-}=mdp?R=5C|y0O0C~k9%v_8sjF;zn*T_|E z5LA1Sag)O@n4c}hN7dx~Ep&Cyjt^&XZ0g0L=wGdwADZP&+7L=PbPGCtTfo}tX@ycM zZx(iutCn%Z!+ZpPQybJ=H6dOB=XvV|KDHkI4pL1#doq3w08w%2E!U&iwL2N;seFG2 z!R0QkFxUFfz_f!-)vH@gT(vID9NDl#7a!?PKgNRC_#24oR9H1<=crW5bQ>Teoc}7H zfheuw9t}U_ueuT;;zIni;!?H}ogL>Z<<k8i4rvUbN!|OIy~uCb@ybd9lblPcu#fg( zn*yz^s!=@f@n0tJg`jgc5*+;tU>qT!q6&S4$bns5Pgm!-Dk!UA@@O+B;P;u;xN>Qa z^ET+ps?980X5SCfU`=8XHKH^sD^S|rkI)Fl@78Zadls>ZsNd~$`BjL88}}!`Fiv?c zDb-pg-zlc+@J%I&^rF(N0i{WyppZ*6l3DbkTHh~_8WmDl9>)C6GAIkY^o{G|Pdq(W zwuzCicZ^#=S!iteedRzqcTUdxnc!_JnQKoK`06A|3iB9zL1U#pI0vs((GYPQKepOK zcPPzmNjZG!co3WbB|dni<Id$FohM}~$xHKptKly@Q8Q=Xz}zi};CAo^7y@^6gM&d2 z_g03@K8lOm!Bn)t9k+j<9{p6~*NC8-ScG<Jf)$KC+oEiA3z<r!&gV5kQl(n30k1!t z9Le>C_AX$}SlZa$-NL0<{}cEZlWw$---($A3_V0g1d!frwBg&k&*@3UhS10;!3_wi zqrS2MoaW54b^*gjaL(G`f{InbSNzRaN^7-lYz@`sGoC*Y#*4wAiFsYjx9e|t`T8kz z+4Oge)|?cV#Pqtxc6P(81c}^!+D?$t0_T*+1COF+Ji~oQPY?iuH7Jq+Ui+iu?snr} zrdXkSVQPP=!(x2nmYqZT-3>eqm*E0FzaQPLJ6$B?_kF8Es|17r!)9XY#xIIt9A%9G zCLv|YkME7iyMj&<2G2B93(25|OUm!ir_}m9)taX;;$w41-M?MknH-#*=1*RUP7S?6 zDc>2g8tJ;*2X_3KT4D))Ak<ITte88xPO%40?E%r<&uUu11{rXs94~NaW6{D@SuLFF z0q#rR4`Z1-ghi8#z`c}Fd@AlgaE4hz_xtlGa0l!|$FiD(<@x+M_e(hPN7!>NEHY(& zV~`$?boi5`N<O_O{s`uAaLN-e#=3(+sTHwXitL<05aR$AA3dqI=jQbD>=5V_M1q@I z789Lw-O6w@No;71CUfQI89GS7yG-Go6Mp0?Y0rvS^P4XYcM>i_T+O!G3F6v*&^~L7 zKfME89fK5N5gdSsys2xt5O&wf=XuX~@)&oK($!@OuY}0UxmRTQrZUjy=vj}6qMDr@ z<4JWq_iYMX#}&5h(+2X7DSb&=39ip$%jeAwQ|)DXnd)r#!%`O(Z0Ehc2=(Fhogu)8 zX~v_o2rFE!?rM#5gSe;v57`_x^df5U><v|vIx9!{Sk!0+C@B-oXqbEMW7xRmqYEc% z(Me$3I{4qlv}yNpyBp-6BudKeUY+tR3wknvNt}gAXWPV4ma8(QzT?${D{l8*TUcL? z8xp<zK}5Tcrky0##d5gLiPmwhqG#^MT1WR0$N9T<nkp@bf1Y`k_!ro`h6v89QKm!V z##RJxEX?Y0=;t&5^AA~eEa|-*C0HrUtOGo=p1*_4o~VL1F=Cru8cqy7qgh&GixM0V z7kh8|$1^YCo&0wsTU~x;DJNgRdb&>K%U&S^f$E^PyeUI#l+NjPzez?P8ZezTbvG{e z%=;bX_YXWB!Ahj?;~ZQr6UuF=%qTs*N3LYwVUjNrw0Jn<eC&~v^q$wunSr?K>u&}_ z@?%fH?2NA1uCW_eCPRL4)uhy(=i9Au=Cla|>E(^qq@!{>7v#J+jBkZtbCX`!oPVRd zS$aSV*L37l*9SNL=xwtC%o_@nUs4$d#WRPgx;Y@1go|~G&tREkQdc>v{UZjSl~#Gv z(5QBp4-?dWx2=}-UuEKhHTN>1e#7MWhlZWrO@zJ?Dih?^<m^zgKA0Am-+AM$;mrOU zF<t$9DWP1D|Fhl~+{NDHPp<3tq3#OR=U-mP9%HPg(kb16D`Aoj!oZLbMO%A8m4t); z4qA-X<CDO}H`;%MJQ8{)n9zmuTEX=<Y&LAyHnEPu!(^`gu;s9bbAh(b_S}JbhjEMU zYLRUfBngg<M!w4$|Fqt$(7zI@s{8Xku;u{V&`hrVKzJ8^_w{5s!4_0D_!hJM_P<iv zwba~q2!Fs$3w-x4u6$HBvlwhBTYB`}i!~gq+OBd`zh!dsVED(-lQW@6gCAzKLKS~4 z6rg>()E~9ZtK5-f=)yzTjU@74Ils>h_6k2@MU*oOCH@`SuRAVER*a^OOhh}~Lw%u( zM81Zjbw1z3vpUYxqXRm>b9Fgsdo|7*PM@@Gi$iU5&IC*xsE`;pA21YxZ?U&w==u9U zABx$4f%Mh4gekpT0^H57+peq5od?5no%n%2Rp-G0#1X(OwMOAJS5P~}h}WLGTgPs- z{r#9T^KIv+J5R2wdi@oidtvo&+C<V)OW2O@v1t`OI?S}RVyy`@dAI>(1OXVWfCC%B zN>C4Dl7@Y)M-jB6&umGVcg`6B*W~qCVBYg6Vya>;#_jozMUj;AUH@0l-&vI@1<cmD zsiflAu?VK`@$7`T3d1xu?h`hgEs+Dmb$ayyBXDAYR#3BcBZs7$#Kk2FA_(Hp8%3?Y zcf5HOfKh;tjxfUy1Y2t-xiW5<XC|5cht@K$Gp`}iv!6QdzWR*Q>i{cM2rg|rUpy}+ zV*xVFW-d|_1VN=Q<-1!+D7l$bamzvP!#%A)c|wZ(7obdzn)fDO;1|>WZsgJBjgd6= zydlkifURl2hsl}{f*+7|xdKPw76SpVtkWp$GNq7Y50Evk($w2ll`g(8$o@wS_tF8j zUNTh0Z;xf&r@IDgU8h|K=(4R<im04laoK+pX931Ds3s|*c~v-O9_Tng@1Oa|c1pHD zUe+Z#2ueLrJzpr3bF5gfTYUnn*+s8^r6aVz0ecQjg`!mvgLTLk93xLk3@Iu3cIIe$ zqBdt^dTXC@69Q|6XRZA<g))*q=8-nfCAp+Fnq(hvnp?j~R{dtJ3h|VFR&X$2CUWg) zno*Mu7S&M)-qNl{Vd#Ie0D|&KWO(~1a>_1SpDVJrXE~F(R?T5O>duho$2^;AX(@U~ zTh5kw3}`vnjf&B>u^X8t_*#r2q;x5E0M#72K+CAYPN@Peeok`t?5=!4E6@+7=mY1i z_rx51GGPQOps}ui<nW4)5K>}uyjtbUH=WvWCW<A6WXj#B?4(reI2%R#Wmct?;!!9b zX0h5V<N8QBrj;#>drDO%hJKjY%*uBcEq`Bj>TZEACRl?=op2Gi(Lara4g(y!$WW2x zlRLAGNb=eZJU84Es7&!D=08z$zFjbDIMYbt0eNe0n0{<cODMmDto_WS+%uMM{P*Wj zAK*QUDthnAF;fx(8{W&YI2xxqDJBMSXV)&TiswOsoOeE0lLEcyohOegVigA@Drpr^ zL9yndBzQ(XTn@inp#K-F?H%RwW1-22IG8`zc)#JWmtUq&nQ61o#-p&u)n--aV5Gjt z86T!zI=Ic1$0FVBVIQg!9fX6SQ`W1T1pSr@!7)jZRgc~!n0B5V@qA&-bM8+#J|7>) z=exm;DvZO@=K!j4l_?4WAV1`kp08SVCV5|p`0xIH^@|)CWG#OPsCq|yl8N28a2c8; zDMv5BM<5lmxjfwSBJJdxt3m*mY~{Nm-#+T4;+kX-yEW>A89iempOt6yEPE-WOL-D8 zW9H}19C3HxaxpI0xkO;Hr1tYHIzz=mnCl`kJwP7$bnrHo$+vCypF*?@l_^jlCEp%l zfogufqG@`>0<>BwpMv9QPfWXr6GJ)pO+O_4fHHEZnBg=A?*29+Uc6AznC*O~x#7My zqi>p&_1M$(e~M5_;PiZg9DKu)VFRQKYdv$yS=B$br}pHF#bmf;b0~E|*!(4&UW-zk zL%iu$+&WP9N$~ko4zTCHtaB!u@RD_n0y&0Iwugmhlit&b6;LCu<k{7-*mn$)u$?Fl zfFNQuz!ueiNqIJ5>W3n}u5e>N0cwb`==sL|oScT~F2sal5mE(Qt(e=YB_@35EQ6jX z!m35*VG<}Je5N(>*G7iLN;;}8CiHAu7H^gOPF?XXvzU9M7w_-58Io%O=9>;*nE7bN zMN`My9-+m7!?bsmcd{+{POny29{I2XS{YL8Xbe!~WD96=-2CH#iC3(d%_z#i=;VK} zAkhyg+ydDrS1(%BPPUb7)JxL-Fc|EQ48JX+0~mwEWkkM#o;<K(3u*Hz7~VL0rR}01 ze!3<hEx)#NC!P;cYjLw#&A9-^Nb6_ZO(+|<zGEZ|@x6l&KJF~iJfx(Gj=omLT4&dM zLHAxYckqEa6!2Jy{Ynb)T6n<+)rVcW+SB5lU86|U%<$Ku#~Im!_inwx)j+Gy8Is(< zZ{pI%^aH{NNwLWLuq@Z(>d*^%S*Y3K@#5P#+4ieqh95L1HN8W*Ex2@$CP)Y(8;0{& zayUb)?hHi9N5b_yUN{XGxb!oUsOQX<5N)0NX6M8SHx;9~K(H%a@f90`RgFTj%^o_} z_qK<{QA^1Nx_?YuAwoC8=xNb8tv(DT&>Aexn97m(J$fM4bV8Lz%wRCql~?`=qQ2zU z0rZKFoeR_QE}yEef||=M1)dC&2oiR_!qcw<V_$o4?>x-^?s4FBbS8iamO#(HeBCCS z@1rW87*lc8_pKm_^5rHo`c3=P80})x=_w>9H`#5@vIV>U*+}4;xyOn|!RzAGTRl>T zl$)}A9ZUU~JIx=LHzM0UB^E152G`;`pf3#VRb8mDn7CiP$S;GBF){^Hmv8*`*Stqd zg)M%^5v(M@)3rsBf+@AqeT$Wd`tDvj-3`!373zI<dQ8UDuy@o>ow=>nwSf+_fHH7u zMOc)N{0^(sll#EHx!hu^ixUGja!ED8$U8C?dmkZ=*5y!$qL!iH*u`oxba;W?-XD3! z!vk1hs-=!!&X<|Kg=ra(za4mN4Zn)izr80QIelL9D3UGVtD4QJ@BITn*v*J(!|cx3 znTYs$s9Y|?6ct?*c=M7<;$lnYqnLlGxOTZvS8xud6I*d&nWw|Fll!VABdRxDyB@Xz zYkSvZMcC`k3hc++`?HqsqoO%7;ekS*7kH?bY(;#rQZK;FD3L_w(1v=)&@Sm@$o^Yz zI@Qok@Igjwjxf|lvY=S|yV$syYmJ?COGW`BaQ7iV@sZm)YMKY0ph4*nzb-VJHBBgD zRt9c{Sw{ipTBiO3N*<z~N@}#@K!^EWj~m@6-Sc(r6I<rl;El_Ja#IU$UdNm|5<Z^) zyJZm}X4!P3ht9Zb5a(}g7xt6C{)a22>J|Mb)jN|A750I(O9#Ct`s36Gr$oqWYy{Eo zEL}oOeGF%#zWYYK3{pHSFdl4-=eV(>ew{ICLnYo)?cq8m-qTFyIPz%H%k&0+N7Ab% z7299AsiWBw<m!@nbiYAV*NO9OOXTy1Ii(Tf32vUI9|b12v|<~~I%&}`sgwaiw?OsR ze&s&og+!>*-)gOIQkLnzkI7#`#VyU$kGpSA2Ut;j61z!!3Tta+cEOpWwL`Xh8KlPS zSnuA#UB;;~o=q79J4$DU4iJmvX6E3MoCg2vyemO|_^ng5ZMTfYJ*gvhp6lA9Yo zmQ<oz<CTW;6+2XvG#R!SfHI-%4aStKd^-RyBelG+u^f?~$<@!F-T3IXZ|fxV0k*4+ zG++8^58B5>Cx3}~sgQCi*nuWVQ&9>aylqsB@>7R1R#7v_bu8nMF%C<n<C81qdt?A1 z7(quQN8zi=Be4RMCs!!(wONW7M18RGRqbKgg7V%7V-l@DBiSyaO`6<xMM)#E>}r`& zkR7Fd3fCT7ymyp6jwHY1gx@cho9Y_PN3jE7zUhGKQxaG9BJ!*Dc>YG+!?lXl8x+n} z$@J6hfaO>Qj#1dSu+-1sScZ}uG>MjlYrf!c4!$e=N?A|_;Uzs$w32(lh$7ucdNJR~ z?r^(Lv1`ewV!#zKK5fF|MtRlEp-*lp;2TzQQn(x~9h(S0W0}FUU*uqzTGVe=DTojj z6uFzADlOE#prZF(iFH7*Le%krsujYBrSr33CkLmL<$xsJCCd3$_H{*^$$s6#Pdc_p z@`JI;vqZ&;tlSA)`<yR7W9sDbnq+?dqjZ&qL)tVoYK?7yGgAppSF=}Kph><zM%Lg% z$FU5re5)}Lk}4xuR`ll-2Q_nQTX0J?@$3que>>y*!VDmrn(AhAO{)}~?!skT#dRr% zXpQ$-J>pf|MJVMb1sHB?N~)%1$vmc><xKrxN`8UaM%81VUzmbn%Lj!b*~1h5)i(|) z#9Rx+H64ndli1_vjPgsy1^oyFG1LCVP!U!m^P{PEA>s$3vhNA<K@8%pPj|o{6Qo!t zZ)LU)Tx#OiL=mi{5iOds!`WosQ?58U`0;UQ)69EsCOAK)0}0Q|Z#R;rL~Y+L<?Gt( zzDXi93>G%5xZ32XlobtIzD3M=SqrVv{)&#)nU!GA5(zeWSDIV>X1S=DbK~UpB;2h8 z=~!}K8!?-wyPj$#&V7|EFQ@_F%*}P~bw3f@(?PfiAwGXMNX1gDZxneNTXQ@$KlYqE zVrd$)oAEzwg<m&(<TohAa?f)--Q!S=1Z#2*GaN?9^!>NuwX6WUS%jPLO)CU?mx=lJ z^o4Fbc6ju1oz)uucs?O3cXif1)h;1LWb*rL*@}LF)7f(B?bz|UUlvaeRGV&K9~HQA zIx$;q)-V7OLzC4_&R2LJ!|Mu8W@hJ0de)SrlAgLAc2@P@{MK((s7Y4an9Wb1%k@xU zw_#(x$z>DG{`IKU4n0Jgl2M~!6zCT8+BjxND1L=^g^+8)XTWEQE%I5~h}h<yxSIPJ z9mpSF<?970wd<-XhC-D2=jrB75;mN+UX+u{xza|Kf2}Q1)eKQM#!Fd7Mf3IbQ`rJ) z2yy#@VqFAt!EBnpdG#W;TFIdgXY*pFfJA1kFI+kug^nGbW}|b#tIt0zmfigd=`&hB z86UWtgm5-oaBx@5-epWs<8(`ahaus9;uJkM;*J<XaV$4V$IjwgZa)0^nyAB4|Lmjk ziNP^)t|*0z=xlt`jw$WI29+*6_I8vWBJ7_?y5QunC1P91O7+z(!5E98ujjtnKm63F zn3m*{Euik}*Agp6QK4yaV2tVuS6nv}97YZuQ+Hj}A<#K1%3Z@dHyTygzN!<Bgg9GX zW@zc&I6AxKw^$A4+*%U}FS05mkX|L47X{6my>h$suOs1`TQ#sc^nE2Q$fJ(3BJwKJ zF@~ZoL&+DTNJlHXwoFg*6PyKJjjX;T?ea))-HWQ|$k1F>tZnNTLiCRnUp}S#e?t{h zJysMwN~&BT#I>2%!ZZK!->6am?x|~nh%zPA+3k$>P$7E5#cdeCvI5|`y0;w>vz#p~ z<)dX@h{H1BG%uM?vTzwKiTCi=Rv#Bt?csAdMNVFZ`+xHT#3_u?FFTyPBvl-nY&Z$B zWc;7AqL2v^4L(`0G0^+Ti1hEpb0LXWZu8yPK@z-d*QB|?obJy9&AESh7!NwGV1#nn z1))9h7BWQmDtQ@7yx-Ot3MG6IR}6Gyq^G2ZuPo&dOSJtr3II&{sA<8*&_tSW0hPP` z!Dum<zb@*WA#S<lO!@aC?~e(k&OsY^nE%t5@==&Sd&<MKl_ju|k?Bnt*vMHf16Olq z`H3V8Xx}H<x#*3<C7YL+Eup4YJY`x{KkBl|O|`9BWYt<R11{_`n~xH@-ty{G$=rSg zpyhV(>WVn!;`;eHWk;3Q6%I;_N3r89sMhcSuk4d^iBj`bgH=YqoKocU*ewujq7+kp zgbYmpPQq4*$#AIpunm{{giPcMbY${lz0aQ3`@lL1>1djr9#yuzXE+)k>D0i7h^lzg z3c~veXK#B>n2Kg)Q18o|=RCpdk-5l^5SC`;n_d6d?-==+1ajK)Fc~Sj6--&r_$-Jb zdD}_UBf&=>rKUW$A(P?=eB^x&9=I7(*WvsPlICXb^WvoluGrZ{8TZZCOw_2IM^+F0 zh3yOOjw}@gc?Zgq%hwqa+is7EZRz+Seqki%${+~A*I``ndvsYx#C7-lnvH93*ARSN z0n9$8EW>EatlYO*@`&i!{Ma0X@SBU-jpH<n-hA@_Vo)XypUFTsd#bPzw~%e6x$2|& zTn+UR-#7-1e}SHeJ<kRF`SZ-|H5W_Z+o5+T>CVjOC)?%KDU{{>J<+#C2>^oR8>r71 zRC4Poq5QK<@X1pOLv5~$8}U76LgI~42|+d7e|Mo9-@kU_GDba^l_Pq2RP{KZcmtpP z-@EJ*#Ek%oW$nidO$f5zr!ZH=XSZUZ0*K&m^?NY+3^gTTS|`|%JGk_*fGq2hz3b8U ziDj(qoUHbPz?{55yGJ~kjS>`Do{yZ?2%Hn;yA8|YH8?Ct-q&?MujLJ!Y@NhpZ+?VT zQGzGg<3jp(>S$kkJ~nT}6!A1*zH}b{Ao*aR5^*~maZwM!o=jo5|KdAs6kh!P^HI&h zu4d0+aj?+0LdhQLpd7sI_=TYhrKh=P`lctF=;w@tu+rhhhJ(v5^>d7EbGphxjPwzb zSi{1OySI043)>(h7RqgGDGl)QLRasjIAy;xlxbr`Mcmdr264MG;P-4eee4Cu+b_dY zTlrN7BY}t6quhs}N2%iNDbXD7qiMxIy2OqBk}yO*|Ii|YaEDq&_w|rPvb`v5Zx&$( z5l4hA@PFF1k=(R*y5w1iE86|TCV%dr(DlIh%@<DftdZHv$_<_njcB&!PZhu#sVr<q zUxsCs&Gps6nJ+`LYk_6ECC~Q0LixX7t~c|VoEKPpIi1cs?~R<LE$+8&SgbUE{>38^ zAwl^<){Hzh?M$niHu0x>TRK>OxRQ==@gzN#hKe?R(}(T6jHFmkNYQ&DqE9lOoP^l3 z#XMgH_}6abTisNfaL)#8*;FY4)F^N+daHhMfe#_b=#Xkdd3Pogm34fPc9bIiAh0y1 z2rl7V=@{Pb%rr<mxJ6-uD}L+yF&s)Lk2Zd=_3|eEzU0jQe1EjR0fOa9YyaQ(8W~VY z#lszaL$<;1<-kb^*msTb;#UF*JAE8>@9w|IuZ0`W&Nus1qsoVTanaY6F9Ae|;L&l# zB}w*s87GBIhfU0o=Gu2o7k?-X{j$eW3Oa%k3klIk9`GxTEW3R^Xjk@L%mb#I`6t7} z5`_^N4<4M*1~dNj59jM4_&sm_$}Tmg;e@ILnW75(cn{6TZrqsr-CdAK!zN6<JL)7L z+rxs2sJ1tMLi9d}3*s=h<0+M0gM<*Jj0DpfngY(it8|_d^S-d)r0AetF@~giu~)DF zWm9CH0Aue%y^GJ@h<e-}!?yX`+4wJbpp<?AG51ZkPl5b1yL9Kzvr%q1zbb;UtXKaq z<9_=e&J?e6gN7`wj+Kg(J?;Cyo=$olDJL{g9Df>>_W!bAziPWzF6@jU%266cC=qi? zrH%aTsDfDtuh~uAqUm!>w4Q*Dj|If+DfREQ9ZGl_^tdtx+xtdKay4*4_CLmW#Fz*o z=_mVhOj7CB$X0lKSiYbELrc2o>4PEot-J^TDgre^Vqh1wZj3;WrL&3Pv$2t)6PY|B zgLK~Ev!hION-X;*MPoP#Bh&|gDOIe38sQr#zGyT^!n5)4lZ`*v5-kd>Jw=_o3nh5b zq86E7-w#(XT;r;Ao1Yx!XK-Zm%>U|d0f=hBPtWj2NkkaDMyEMWZmlo;?P$*0GBJgb z17?fG^0eYW6i<z-Yi&BNSp&4xn|dLE7ljj%LQLM2^}Z~zBWywf%7^4iAJTRSx1o1R z6|O!$m#Fq>`R;|W^fDQGLq_0#0pbW9_aH3)<lq6}NfQpO0_Y6DB@UQ4r1D5EFgetM zmj@DYoUjOW07;QRhFlQn&+gh=KNl$EGLV{3p(a-@@c3qdGk^ns*cHHh4jTY$5IZn$ z?Ee1$0~nxNstuIO3Iz;g8vqgr#GpZZC3FG+C<K<!O7V5p5&)aE2S8#_m1od+OC3Z+ zP5>0q(}^gqXx()^xmHtn1T~jXVg{|WQdYFlrqEvoW$@5w1EnRPkw+q#<dF_K_>gZ8 z#SjCAoDJ8~O9W*$P>oJGmr!&LNf+RZK9D((dK(IKn1=2x)Z;)W_-4YBeI*oR1^hKx zmVy98@{W>!0vf2GM-7l*M7#ZX(wh_iHl!l}@d;D|RcQi{9zr07DB_GuZ7NZ8Usl9J znKIo-kZ^2Pq-aPY=|#|831xIotf&oItF5=zdO$%;hV`IGh|Wh43KD__z-KBwnk=f3 z4tE@yQ5~e-mRvUV+K6f$cIBj16$EKP6;3#;guW^I<3N0E5M)8G7E~yVxWXH+yhgSm z&;ffA)MP;$@Z|wX0x2rzoC5W@0#-4!kT9~`PUT@tH=bEgmK8bGDO{y)_|j&la=X&8 z1`!KD$Oi4!0fhGfAeO!W;5*Pi^THgn%&paH5N-&miywsM0$k9@38fUDRlu#eo{cjh zm(ZwfQA^Ro88f7CLj%)C&~5_%L8xE80I)j{f-{31w%8Z>InV-U2~^fVD+7>0x&VNM z=tu`qy->nZMk-uOYZ`{JMKuD@G($@_Bvpr1PRcPtSgqiuL8>Ygq}B!9%rXFl5;Q9S z1diRg=bfwO&dX_|4S?Ef<6IEWRV(E9u~H5VpSOh#M3u9J`yJ}U3>7_Gw*)zA&<df^ zcEZml9b_`f2l01M=>(NV>*v!`A9iU2k#V`9TYr?YLh}Xtr161OXz<5T3KTrEQ)#@= z;c#jEK4+&YKG4Smr{H))A@~Kr>SB4MK?gZq^$KXf>8S=C`q&=j3KGDDTy1qvsvE%o zFg%6KKz-{g%(fZ^zxUPuZ&?eoijF>}6~|S`cnn!xtMDR_SJ7o4qq)TO4rs$0!i;kR zG{{|=ClGbztOKkn2nir(5O4t?1;e`^LEe)=Wj$&z6){XidWRBY-A`em5f(v0W&$G? z#AFR&P}d5Q5q}g3hiY77t;#04fuO(uLm~)n%J{&6@C!n71AwB6*hPU*2#HC|3PRAg zutUzSTZueM?4)M53#On#6k60nzS2GKAp|!LSiq2~z{XGd2Oa?EM?XMWktme0BX~SW z1PKx>RS|2F6=akJ?Us_eX%KjBiBc{La;yp!50G0ih`GdQ5RcpuAqb+N4o&IIw~+Fg z7)i*U9#FZ1U|@3pJ7e8I{^bzb2$CYXOc*)K$;7KLk$C#+;_<*pCjfZhYWNYz@&uC1 zf;@mA&yyxU-+~W=z#|{|h-N=8lF!QV2bp03Nsu@o#NEX6AbuPO1-S^vfw-<U!`rB_ z1{p44Ns=ISBS8pM)jx>BZ6Q7+NInIE007LfAT=x~O(EhB0%hbN`LKsQP$NBo)>I;F z!z4qo29_bZvYP{OC&(@;5l1dAA%P61$W-{pgn-W=B0(xaCYKNb4kRDYn`uzXiV&az z03M<oh&ue?j(5Dn9{M;(KM3?wv6@w%Uwc4HACfbybwHlx`U^>dWf1Yb=>)Q*r9~+s zNaI<xsTDo{$m&X_kZe}qo@N`!0Y-y?Gyvcp`dDCIOA8T#3WOQlU<Na;!Hi?@V}Ym< zsPs(xRRCD?n%GQPQAs9{h#EE_0~;At83oznflNZhrD)v-rYa*^Hl_2d=OtaZpoYw% zY_{DlL;mrPn+~KJ-tfje$~%u|(BmBNKrMF}vZqu!Xr&p@+EIV?TcsK#xIGiDMC7Cp z|8`Tq!TOOr^+;U+1aPGbIRFB3*WL#Ugtqq}XgyLP4|%L(9s5|vINA{o0H|ZF5JpH@ z5VQcWB1E(5s%IYI*%x{GkA?en$Yhx+(Mk&OTm<<m^K7ONJd8NV3nAz?t}zb|3xpo+ zXva7I@}UlOlv2nIsS9oq!k>g@cE<?e0GC5T5WoCLzX~ZLnaeDZh!TWVL)7CB|N6iy zLj(g}Ac%IQY-jNPqZ`)%2LSdlkR><y$x*g*o!#44c1=LR4!O^LEQ#j6fLX>Ad2}(k zI!}jW8NmQZv;YP20NbFrAZ2T&orNq=JQo=p``9o5l)R2^*dxNFUdS1CNXHkV4ljAp zEJ(ZxH!ed6#;jZjQiYgffgn|n8F1Ty2lBuGvJE#kJMn{NZEb{%7QFgMbwS!Oj&ImQ z(1X7AK^8%fm@4R?x$d+_d|i-bYdIksn73DeZEt%wJ8}qdH}_uE*OnP%+;1g!sexMm z%5&6X&l$c(hTE}@dRz~!1ZN0?(1rj7m8Gu@YSK`ht?7NMW!dolA*LH5ZH*TMK?tY- z5ISMTiBDXh=QsyD$kC4S%A>sF;Ko2vL(0*@d?CN6wL$W^fCmteU1Xeq1ei{c%mxqx z6_C1KG`p6mJA_>kkoH5MfsWAy9p(ZRs9N)J4{~rL?P(_mKhCkaDAzXZ3K4}tbd@%i z*#=)-OQn@}z3EMJx-~aLxj|lvC4}Tu?gYQ9I`HA$$9q?;_!zs{$*OpPB>pILA-t;| z((#TDBm$}I8U#?zd4kMYAf&xK>j!dEQmWPMYUSxoCEj}Ig;pWvK*qTZ@U?>7oQ~Qo z)h%oIN|)n<+97l=2-pjq``eS-rxWgnKuLKIQbYeJo?H!I5psHb0h}$C&wk7+PkG9t z2I%B}$oL0k`1QkoEz+Mq{o_wPMcY6B5urc-+pmAHt=|6$AVc(D{|%t$WZnTP;6M~$ z{Vm`FLLlhe)C5vs1!7+WVqgXiN&^<4272HJ0*VES-~@tT37TMlaG>;^;0m(fYowr0 zwO|a&pj$-G3(nvT;-Ezs;QZxa5BeZOsKy9Z;13dE5xSm0fR_*&;Sw^T0W#qe5+Mwd OhW|lf6|zx40029M@*-9M literal 0 HcmV?d00001 diff --git a/images/demo_Riemannian_sphere_tpgmm01.gif b/images/demo_Riemannian_sphere_tpgmm01.gif new file mode 100644 index 0000000000000000000000000000000000000000..c26b1fa56a0f177e8ad95ee9048e7ffcf30f5edf GIT binary patch literal 588243 zcmWifWmFVS7sj_(YUz|*=`Lvj>5iqlyH^ARL|j-pS3p1nL_$JhK|n-=rE@7MDVIh{ zP*GH1-~W5gGiT13FZ1EfopbN+nb9-QRaA0Ef&4+g0nz{>00;n*LCMIVbmY_w6l4^X zBv48UN@^H24HY##9X$h^Gc%_ID>EyHxIQO4CntLjmxK|wdLWz&ep@T(Kk>kMcqLT$ zc=!Z(L<RT+1o#C7bfX3I9ts*n2?+=Z32q1(L<tKu3mZKa5fTv*78Mf_6W5NEprMlz zmy|Jjct;~fRz_A<&Rtf=M^Ro$Q6XE&AzdkfpsZ?e7rmjPtfG>Bs2)3~aZf`_M^{@j zOIx#1Tk}9iOIuGz??35N)9CBz>szH5Se6><85kKFn;1DEOwACcJqXiFbA*MZxuunr zjg7UfosFHHt&P2{y@Q3NlY^s^gRe6?r}I5^XZt-@XIEEeH#Zk|cb8|LZf`x^J-t2u z(~ggq&wui@wf6P#@spGe@Cyj?^$7|H3JMAcR#XlS3=RnjL57Cj4=V^mhK1d~cyNCv zJS;r?!P|$CQ8CdmkNpE4KZ<=KtAL__p#+6dI=ZMQ@hDUS3bha)k3pN;p`BdN@#v(a z=H$fW<Q!~DVnRw%dP+)XYI15?N?KZKMp|lCdTM$`)<VY9;>?V!tejj-HYOL7n~Qmw z_cSjrw>&?u;#uCa|5TV?SXfY4SlC@uSX5N>;(1{~aZY7%QSpoCFJ3&ac~SYHGzC>! zQdU;J@hUvxRUG!!%km0OpNjg%%FL|F>e{Npf~tzD*Hy1;OcAwrlxlN}>S}81y72Xw ziZ`rmZ|Y|o>Khsx8XFs%8yj1i^2(YTnz4EL*v96TCTvS{>)Y11Z6C(lUsty`Hg!bD zbhN+g{5aC(<=fTS`Qd$6_w$PGuI}!hfu5q`p6;IBkGMWue}8)BK;OX7;PCLH*wMzW z(czKt(Xq*~vB`-^d}Y;CLE+TQ(hPojW_o6JdUmeo!>5d_`PokkpB5IDmKPhE*H~_S z85!BDtU8cWI@sO&>fwE8WO~^3;Up^N`}f~JzJI?=&G`H0-}UwN&Cu}8*Tb8utDCEv zn=9hY_09ivLnK}iiPyy2L`qW~D@!d6gpQ1a6c`8q0B-+*ka+z!i~TnM|4$PD84>W7 z$^Ge8JcxvxUc_k>`)VMCme;UEUwX4IgOyHsGW9<1NCwS4uAf4!w>6)#-KsFILwbV> zn2n0HZ&|!HEap?%o3Hy`jZcyYElB+OW7{;7$`D&5ZRFZrgQzqtHEge6cw_fAV12y( z%~G@5fNnKQPU*XVjh{@?8gA<G??4;lrAF_X);~o3I9#82*o5juZEsP*6eTx%(KM7D zZ=&w652w-S38*L`cl#eQu@{usKk%K(R84_i+lBkj#gf2BQCfDrPp&;C%1l0VoUC>} zINHE}c=zoK4o%6;^^f~F?!5J}kw!T#et)Kt`@ra9*TvED+rTeVA3yy5Mi|H-a(`RL z0T<W;#E$eNU;g`jwmtFEtheX--{p^^FVnrfL?Ymjw_NQ8TbKn3VWPz)z~udwfMnW= zoY4<e^){1OeQGz8IU*0-BbiN8aFCdvc{%rmUPrA3iPT3qW(Y4rdDA7QIxB+YH%56f z<)(xxvsAz9J7#NiTyAHcZlb5veh%`ZK#KEc3HcVLX=o70_`nIB?Hz?n;7%6aEAlGv z7f4AUKSMDd7uA|&BZr0eOTriZ_e-Pp>h{Z|Pb<ytO_d6!s3f*p`l$qj3j;W+f?CO` zfySh_K@Msxn@)MALbns28Funh+j}Y5CX$Vka8|$0t>1m#&~bS92J1nrQK#CF`bzT{ zyjM>X2l`(Brup<j`DGJ$r7#ftf%?U9%Z0RPLu|iHhG@%}=7*qm{7vzfdw;qk%0LVA zXwQ2yeC0y2O_<qaeo5^^Hy{W?+uR){7sZACkscrk0@j|Vcl&RBsQw7P!+O+5CfFeL z98!fcx_3Fxd#?7+*!X;i)iLvYn8UT<{s{NO?wm(Fg--WX8B=1V$2i|kwhW0_9)BOc zlfm(JMCgUncf9a^L+hj0P^`9!@z!>ZijKBnA>ci23qj0wG-Kd)hCZ+vWMNmX%gHbp zq0W#2r`HDX0TM=;*yn+IU?3lSm<Lsb@dh{*fyYH%NB^NXGA4=VI9ENadLl38`wI{} zK}>VFKU3lKa{Ke`vv^Tj%YVm@3S6mO_m+7A|Fpdv8Bsb|abW+u_dL(E;p=?8i}GIG zi0`4}TlGw{d$my?!X*tzr7{?Sj3_i$gkr7^fT8G)(N@OQV;p_LJlz<jHueD-Pd3Na zC<h59UY|3D!$Y&%HNTRS#~3n$;zG>>Q@Lm$gmn274v#b%U=<;iD@HvRx&wff1GrNF z^w<Q|8^zKChnj{3IZS**-Xe%8Rhd-xEP`neek|0fK@~HF=FBfgNim^V+UmHE_2cLC zqcYt99&{NPM{?lp6wfPA^e!^-{h$;unp1=J0U0R=5sAqFFlw-o!sBHbXEN<afwaen z{)9pGbdn)T@E&%M1KyWS13@v)yJ-NjQTG_&nzT5|4ZzaquzZ0*7-=ReYEOSedF4Di zYLb`JyMX4&C0fGOK|AOtR<jGDehZ&EDBwcd%m@cD7Ss-lf!yMK{NR8q3j{3>kixiV z0M<y3qA#CCG0JKIN9>aM)q!a=gGR7g1XZsTBHKO)#2DemE<B1Fi#pFB$)+EOUellS zV0)mF`-o)l@YRTq@{i{;nLb>96g7>>aiBe^kuNd>cTxOsK&AtN!AWDxrwEWY{b!4f znJ-n20B7|~Oa|FuGoc({3m_aszV(a<wUX6O3t~XgFGDHhv?-K-!~l3YXR1Awf4-s} zGLk72#-}^{tYD20;J&sil&p&{WRA&{DK2l5{DY(Srv*z8(tts=SS#1R3B055<Y3$@ zQatTSyd5eFI;lb9gU}KfWJPh=CBTqK2QbHNQn}IF^s2EW9ELF_a<TbO=<xM6?aH(K z=U?BrQN6JnF<fk6Ce_LG2NXanq0$8u5;|}ap}A@`rJzq%uIfYUF^B|t2#O?3A4LLs zgHkTvVvsv42Bb<Ybu$6L*~lbbCj*5m1Cb|TIyw^UT?<n&@+f4LpRS(K%3LwC8vC_p z<bk(-LW_;WkAB;;EfPsNBE_WRxAaCgm!p#9`t!FqDhc2{+L6ck7oDRfO<{#^1Wytf zEeq!6(G^D=>r8~k=Lr(^-4|>7#p#xB=$oQOj_R9aezYB!G{@8^wW|HqQa;OSj@_sH za%d=`J+mqC_~`Dd0|-U$KPoJW)R+Kbzr>N5ViQ;<3DCQjeY6Fpe!HC;6pokuzhAvp z+Zu9@j_w?Q-(XX<jJN1sbPfuswWM24ZZUo69FmG_$@DbdzO~vptk~0%{a|vN^IzwP zsss)ipyv)_|1+w;2!Q5i#tYp2Glt0io?AKTB@$RZZqe~Qucdoe^r6y(+muXU4ac5L z=<{)p#n$|fuwCgFe~5T*t~)O_k9}lb-kQ3vd#9{V#aD3Y{nVqIw`J$B1A#y{uq00V z9wK>1_ioHbzSOoVL6fhBj(_KhrrKUB;J=za`unMzy1iD<<j~^9-}ze8_Ilfo{tSFE zv%}s^4ZbEv4rsaV9ejJ!L;USA)rQd=>JF^9!&49Tf6Jq$9j%4<W1qYKKF?%#wAGlL z1XyYV1rP$*6#PlZwlt6o+tE2<avJvH-`aucyRIcFIucey+eY@gZlYFw%<8|5%c*xg zzwzJV{{8y`py|Ysnw}-FUlGX6I{R6s&XWJF^6;l_NAH`Qr>~A|vQBpnD@>hdKZ+%g z|LGjni$kUwt!)Vr&Hg+(#Ge+tg8(7=`ja`TKZ?x;_sEOhYayF{q?~c^-2450GKK4D z`L~h-)q62hX-(lJ=({_7IbHKVg6Zh}9&L$CcXhMShZvqLsnAh>h-W|oT3=i%dDY~v zD7F83`?9nrMDkzkn8fdQ6AGu{Ig%Uu*}u95*1tukNUm>BJ?uaF_$~6``z@w#r+I<b z=WD-swP<muamSnQMbq7T3e$i7i^Pv|nvVy1W`E~i-2ALHQ#}+^M>UyUUs#Zif8ZU~ z8(rlZ%XJ+EveL$H{JZ&$qv<(IF}vDgCtmhG#F0ppU+vu?{+Y^A`}sWQ>d=w+cX_(! z*SqQKE!Xmkyp)f`OI7OgH(ze9SWLwygugu^?Id2G<@8?dn-Tx65^pXaq9D3B;?2MR z>VShM(s1B~ZS0?iD6%3{|HCH(dQYf|P_zdqy0gbk3USQK_jgI9TYLgJmgBh&;*VJ3 zPg#J}>InjN2|`f`B1H*eoe2`l2~trB-&nx%2()|@TCoVN$O@)}C#YSb)malY6%&8z z#S?TR^rGSo?U2^KaR<K>nF}6Kv^?U|PqZORv_1e(s-tCQl3Xs6<Y$uHg}|PQ$sVj= zd&NZmsHC9f<Pba5IBA?&3hibA?Wb2k5sGxtol$#xAuAp6+^neyim5SSHp6rYlce#I zovG5xshPyfR53-gj5;{qF0CLctw=x3YZT3UnOt_6R?eEp=a)zhl>B@F;5!Qkk%lY{ zg?cTe8>QYi>GW&XNbQKq=oAtZvjudsr1xCL*>@(%W6}ogGUaK(LPeQ8c1hxA8B>>; zWQy@&sQ_j-5EUSV6$L<?QBZ8A=hXn%%IWB2q6v!tRt){4qQp&>jE#d7EHvq?)&&HL zAS`CgT&DT6f}QO$ul&+RmeHlPsls;TZBpRhQ5dp6ak{mD?>}g8mH-TnL=Q#TMiO!K zJAK1LLimjGypoOZT3C_}V4_aJWS<^78^QXO!(cR9e>v)mIY-LgL97sf7sOzq^0J9V zc^F0Xz;cdSbmmxRGQ~3K9)U{pIYys6opMa}yE>E#4tVYc)uE+QM1jQsw?&n*NoD|S zZa`*a76=1c#zM?10Gq!6CO!qQuMn%xVB1@_8D^gOynE*S=NZ#z?r-^wOy;~;C5I1w zITW>d32AwWx6&MHbMg-It}b(MtnmV!q**hhB+v8nzh+S00$5lhfLL-b0{A<CY5_$d zjEMZD8_8TwI)Q{OV}wW$pku^;>y%VT02Pu9kA(Rkvor^&=P*<lq_ZM{0uO*0x)q}^ z#mjIg(Cxo~hTcl0dCyupCtP}G?9oS-qNL}g=;wJV&x_IxGSxq)=@EtF`Ikx2NMMjU z<+lCvW8w7sesmxLg%kE33GTTL7AA%Tx~fxD*@wampco`X5d&f^e>z713t&Kcc3=}E z<UN3d5=1htPRoY?(40~FBOn%7*vT9;8(uEv2E6`UQvHXXzdZQy^9t6a)a>`AD}O4a z4&wSRONTns0K(`$OOIffGF@6=7J*7)rc5&?Y0fUC=MxDPib96}S!X%i2oA&QiwxUS z#ajdHazPU_T6rG8r|MJ_a2h)-+(L@-Y>R`+jd~Rcn?+E2Q~^^ERKXYk3FaB!;Y&JF zX_4ZZxxp~2+DxUx3KT`9s8HI5L1jT_nnoRp4qJIlM8P%)ROhr5TFP~rLRrl5&!e>{ zB9K-(7|N@DNS{=Ng#+L#kPHPV5C%}OBAxf>$&ph0BRCR|70LkLR|_~2$r-Sk)C&+6 zs5qlWg)EG4NIC5+jEQN8mW^KY&x>DakXk8CE>6q5g&~b9y#t5%N|B%mRF>*>8(o>- zZsoqkDEwuhaYaD-&H!X^l1@Y<RXl(KnI%9V^EqP?M#6;40W@wBh)T95i~^4mC6yGG zIR=*b6OaN|0A~P%Y01Y87-NO#PCJ7~9a;eW6<;V49XoSoV`?{*5@F@gHcSiO3)Gi~ zb>D?0F*7vw1n@D&uyzJqLD3w}OEpeJ!m^RiB%hM>&cJGC0R37N@5ZRj^8k-{VY5gw z5C&j`qQt{t0XTUtIMoR1t(a8JfN~x~Mg;R}`}KL@k$vmsND}8!ONn0*j}TBpq$B7E zrK>N@Ck6B_<f54Y$f3ZhQpHoz0PY!Z)CaT8NWj}Uu-w^GVZuAPGk~}6tEd;C?V>kw zfHs4jcdA&R(TjG6M-`G^+e;pCzgNgUUh1GrE%JVp=C@p=y&M<NiF(5xTSpmdd)X0o z*hG<QYNK7_;4h^|7Gh(S@+YC)>){82yktZz+%4flL_pY!)%TMVGN+q*M@t#*qFrZ# znaWWgmmg(9>=I=B5*h-Zd?MaWzy>BYt#)lY)_oCuqSN)^!y7tyOQ=puF7vBwL5<#U z{f3{HJw<QYZQga`|Mi|SecUwqc%}#Br3I6g;G|JF*d&hh7)RCp5u(!9LK*k(QQy=b z`fH;Wz*_f=Xf+wUXI-J6FDMr7*e_JlFVfvFYMefr(Kq&{Z%D3G)@gv-FZ4rAjB@vY z%G!Y1)qpz3pvKw*DcC^FXBW<r!9U2*8M>&)f>G3agJv*yQ?Vh?ucwa$A0kSIU>y%_ zV%=OghEO#_woXxTOM}~&{W_V2Z%6wKkK4H$LTHb|e8__zbVohp2##J0dK45CUOOB( zncMm>qW$+U(+h{~#SwAh{h)M}-n1+F?Bk#d$KFWTSpHQ|9&9Y8VT^8dtc-)c_-Ht} zq=v1aaHk`M0u#Pa(C0rH5wRRfV_tDQ5#(QzJtZ(PlRPo~dg2=!lDY1FFUROvU`4jV zIDTTh{kTLh?ZchBc@_b}u#t4UQ)tOtR<qb>0O{zGSaqLM*h(gHJ#!LXlO3>hKaXef zq_Yp@H*mZ*HJTJUBX;}mFTiGM=-=_seOU9qLuAB@>EAxIrz<aSx)XmNXVK9=m_J5> zv+h&k2ci4ZfB)j4EVBnCQ>K2Cla9q_BH8C%DRljq7#uamVnp&bz(}3K&T)dk+^j|i zkdvZJXAd*;#p@H7vmzBq`G!jJ9s-&W5U3ko%;eLZTX9XX_@4*kM+YxG6Dbb-=5Mn! z9~1!syz%<Z^U>tZOMag;gU2=T5u&9Fcf{u{AJ1>Xx-{?@#WRY&fTuR4eO{02Gzb*t zC$nEi@s1x8gD2Zr*V}&$W5T3JjYI)XSh5N7ey<eZEL<nTSeWM)tZ;RSAWPaeAgPFj z1-5@UstG-24`J?FTot=Lf`pJV<yrv9Q#V8H#ukfDO4edSVV@zrQpThIUZQAKyafSl z1PW%U&kqf1-mXhVxUJTcb-giJJ7mp8!aq;lU)b{?H*#D3SQ-jbB8`i12GT-CQ2aTM z*M=HHVZ>-iKMHUk*gs}GRgWK*IqrRw)qtVWI-P^wSTPQkQl^_kRwn|3XDACl<ido> zYTbas*i}VZDoF&0`z+l1A?;w}EP3`bQdBzM^(=*{aKAcqLGcAl7}|dZ1ghaB&u4Ga zXzkt;{A+p>9???bF-Az3fE$PnOQ_mfdW!`LO9A&ZLCXX%w>rq@IYF5-gm-oZenP>D z*p`;qD!%66xp~S0ynSs#0Z;=Drf+Qu06L{e0bC9AWs$!)0NH2c=3D?Z0F{^<h+QgM zje5KM(H5_CHpPvJ-V98bu;mv=7f9XgqbF=4(ZFICLCPm_%5jh&VS^DTD>wtN6R~R6 z+K~4%uqGVnjH0=(e0g)2WPS#=R}RZ*oWH#eTg5;n@YM6_RBz7;SOMhYaG1r+0`p&T zLv@ON0$5fQdW=yEkAn0eVRKTHb|9)f0M#6lMD_*A_j1^00ND$d-2@cX2$IAfP8Ik7 zU<ild&&c@^kp)t7*)!lnPv{67HU}rIHwQPD!<rCa@b&ul8Q3cWP{M?S89liotz;mM zdJ03ebz`@8Ml}zB(I5cKC^9@2=7GbgVW{f7$k}El<M7n@a;ms$fa(locGFu-BP3%6 zl9r!EiUZZoz<S|F@RPF@fQ1~2a$KFFat!m)jd~WdJuyaNP0Sz*Gpd0_lTr6ljeiDL zm{K*DzhjpoAE$+xNUcp9pN^En-lKrPa?;Q0CxJNm1ud!t0)+tJHXn+78~`)IVO+~e zZE2|z%A3f}=Js5`u_5tsH`zz{_ZTW2yxZGjH*y9kN<$Rb_Ux^xX~~4JVU>C(im)ut z4M0gz%Be&46Tu5eh#ZFGo+u!%oYZgz(hOgjtb0a-qn@29uR?&P;(>Uqsoi%_6Yes2 z#u9{tMIgXxC<<*_NvCp{A}xfOdmD(N%tL_731o7#<gOS{GXkQh4lM_S;NAX=5FkJ# zNf8#Jrw$Q=16ZY+4B^nX*!nARLsAE@KM_lwz)p4f2{4X;oP$XF5MT|dViMH01>%`q z7}*2VyO#hJTLhH`3Vf8i1w@c`Auj<>dDPQw4Ut|N7v<_82o;?W8HT@%pCg!>+z%x} zNzLD6$4CYsv!&wUr{=)Uc%`w~Qqhv(+Ec5N047e-N<5=a0m;<tn%X<*UTFZedZxPb zr2GWX^F1Md8Bu)zi5dfA5x_8$o=24pqE1q;OJn2#5~|a!N@hjCG{($9-UT^;2Roeo z=DwyVs<%BtbayBRG+!oBaqE`YwJbm=46%nPp<nKeKNEKyF0udNGgYek1j^~~({HZY z#M2a`ET^sUK0)YQBOo`;&y{GY{}w@Tm*Teq$3`>3ak(xkx9USUz9RrYQV>BA`c$Wl z6j=Opf+@3<v3|5!t#-ItJ)TX10kT{*tnk!x-<2Z}u5L%S*V#!*i%wTEgKU61w?JYV zAa(5=wrmZ;d!PDZGXP1PJr9Z=VE;PnoZ=Ey>Kzk5Ttby;NyQ_81g52Wb1A<j%}fy1 zL;-fNiSLsj@K?8BMR#cm0bsaJcB<3;^HfjjgXz1ehySrFFeD1dwu*ElQ%Y^cBqss5 zYBf-#6)mmt-bkc5X1Carg48Ll?lngtBr54{*_kIPtJ7#-^<7@Doi@!L{ZEae9|5%{ z0DoMc&W8;~L?f~HrhJryi9YrpAJrxgaHqkwWWc=--1=F7#eG?+qREr1oj^h^w==^* zrT(+Y+SWBmZqb$r4wQ*K922y4ez@Ci>-vO5-p)ORzr)TmM@Qb?yKvq2rPIZ1jZ`Xi z-TaU&kMOHoln^%!$8|0hS%8F-0U~`X<~uo$dZZzBinjo5d9rssgFr5S6$*p~&zv*^ zC<~<f`t~eDQH&Sx??5%+T9#Q6KSv1(#pWQ=+cl0|d74QEGWZ}H-0RU??|EPeDB7Ub z2U2MKM4*O)=KQwOdF!`q2VET`JoHKOzurbc?HEn7P1LLC*cd8cglCc<MHHhVPk;3; zKkD`z5z8xnAG^zvAOCKZoa{e5DS_B*MuEBP_DIBY#$*7cQ2|OM7Oi$3)B$XE-=6`P zP^p=I#VE~mwqNaR)4)FxhVIEEiavDwXYDBD8)^iBOh!GrPYFSwRY&RnwBjkcq;IOf zrEwaZ@LC!E>JSBTG94g)?(fnNxf=S=PmbQ@YYmrgA&FYlW{O}>)OOnM5pMr=7i~91 z0byV<Ip{$CU5fFq;5Ept-OxV~n{lT_hXH<jKw#Kcag=OKlgPs-FWlo7AP~SVVX)W1 zsYvVo(@O>0@PQ)hTpwmDm>*q)B5i*K8uiqCmn8+12Bkf3W9**rjTkk-gK&v1>U>0B zp~KJ94vYXr*omTS0F*qF7ho&a2zZe(DmFEc=w=lh9g&&{_{)G|k@bvm0k4`3>NN2% z5rBB91@Q77kGgDV%JbZ887|B_0RMhie_ec%#4lPEYl{2i88ibFv@jkiJu1a=3J(wp zARM%%Yf7mORC`$9)|MF#)2;*%5NN<WFz^kXI!VnE00yOdn4--$%w`GNSU-%)N%Z35 zR~pmT42(|Ir`IN^r-Mc}nL7R4|1lDz>fQ8d%de7Ux_qC3uyFdfw7Sfo8T5COa_F4Y z7driON+-n%NOE^NN&O)A0vUiQ*l!)YcSd2Wt;KGv1ZAk5qdbM9APGbi|Ndn}nSIgb zy;L$3FYQx+>LiGz76SrN6ChRu5X<pF7JXuThP_>d4i$VrEKZtIaYiD@*FEK~`7DIT z;8p2+H&SQX|C&KuE=<`9b<5?P5;0gqR*n?pf#fE+mei1IDNkD4%^=*xPJqZuFCnIj zX`CI*b9;P9bcc`&>i&;w=kJ1dq%!RF(Hs&=IGyQ4T?Tjs%SZJjdRSUZagPP-ns9<l z&m4M%v7Ee?uzOn#FbS4*E9`{pu-9u*gq3?RXJd2e2@C)pzx2{>#zE4*ifufq+Ejmc zYVI+-Us^HvD*g0){hN@IT|e_8b|`T1ZN<<yV=Nz#R4AUf!bbb{xv&UOZj@lHhLRK} zsD~xd)iE}ecaRcL!qtuAz!)TnaKoVo%p5>{7Riy)je?l>V>ous(gK7CfTDF<D(C|y z`qag@t177Az~TfOhcOVM6GS(olPIcwJ0iXzggF3<X_DBaFg!a6q>%#RoNtp+eYT~m zpGXuQHfdXZ90blsCh=D>lQyWX0HqM<5r=YU+H+TmDpV3n(Ft&)^t12tu6P#XrZ8JK z$q;)fH|CNZpa~{{v1;`tc+HlA9qD}kznldm=R4YVYF-JT&?6Ncx7BJ-J6!(J3V3yr zOOOMEvS*W(QRMt`ZsX~XG@XTZUIPSbk!D-OBj+=bqGmHF(le6f`B=&Dxb1LQL3_8i z#FN+D*Vs(=J-x{#RU5@X?Lq)9^4XmuTAW1xZ0@gJj)juwIyH?ues^oUFt9-bBc9CS zoKO3Jp!<_48*d*Z<`pNGJoo?cU(GY!Z80MfGn*bJy9xg&XiQn7j~s5KZr<`4404z+ zcr7bxAnw1ZKQ+%0*_L}^jJ*>&D}vk`%T*LR{6V%qRr*U-TW!-s<KD0N3R6t8<y+r3 ze0Qf2$&vZ~3;Ir+iz`dRksS}8Eyt?Av5rukx__B0B%Jg}Zo9zRlXl@{go1!}?45^i zMz8C6S^@NVSnYe<JRvLfFMKvWKg8WS2_*`@da-^G_q)6IBs3}K!}`9wLO=ObXk-oh zhEDEfKT{bp`rg_m$#2DO@r{t&2P!t)DXF5rT2Iq$uhw=Xa^J|5g%mHX?PXMTbVT$# zC^M3Yo`uHD{BuAtP6BDYiW+C0^@P7xSpRCKw_}a@9$0JpSi0*-=iWhlPT9ltBiDO2 z-$T?QTMHi_Ul+IW;CmuF-mRa6raW5PrG9fG_2~5B%YRx;!a0)LS~CA?_1yZ@qWXWV z<=W_}oRXDA4J&M%=Y%Rx+`ji`p$bRp1y54?+jHS){o(8-=|^|Ldogo`8$WCG9v{Av z;AiI0ppbJ(+~a*4F`csU>)pMw!-(ET8^4Jgzk5TKwb;%;Lb10gzXT`nPMYV$9S?l_ zLy$kMzIW{j{PK5cB<@$cYfQ2o0q#oBWX^7e2+;Dd{k;6XSl1i(i`1xjHRZ|G?!6~} z_f6#lgh01?;K>q+_b4q;>GHUwDE)g)fxY0MdkjV5-JUpTIF2+CN0yHxufkDqd>Hir z$-%)gwBR#_UZP_H&t-xuT)pu}iiB1lqg5Z1m&UYW0zHy^82QYi@*SpLL;8cpOtA*r zl{^<jky|@k=tzT|Lz8n&gTt%suVp{KF^awx$d3TuSyrcp^qzT&lkp}<0+Q)t)gV7L zSMR3NkD{Q+P8r#OJK6)XRs(Wg14Q}o0foc?#ry%KssZJ;fxCkPD)R%XJ6f`_04n`> z7DR%a9a>f&EL_zu;w3)2MImuOB2h*9<g(v@qdN{xYJ)-Z7say?22Fnsnn8vTj6>#p zLl&|_mfAyBRzucaLpHJTw{Y<+7#;ftphMe`efJPct&a1gj#KxL^O}w;<FGrUt{aE0 z=gyFq_OP4wusv+pDOT5)Z`iYBIG}Afa8Ng}1jvm9iTR=B5nwr~L19KT^-jVWLn91L zC4qxPy7lN+4Mxq&`x$UOzLa_FmJ(E({CH<1?&ru8$S8_&G@frXL3R|aJ(_4Wn&dSa zoSKY4CF-Rn>J~u^un?jl4w5;jZ@R2+NJz|SfS8hznASopY9R<X$<r%HKBGad>{y}L z*i#q@f^{sn%^;7@05ds;ff?ldG{~MDEg#f3pfxmx8yeJ(R^=z^7eUg)$Mx;T_52c3 zV-xG!4E3TQI-}!_R*6kN4V%Rhv5ZD7$6yVz2{k}soAyN8JXn1O{Vvf+wHB?6nRq`> z`LPJBG-|ZIWu$}x_a>tM!z-bX5o8crHdRx*MDzL|=+2oDE(oltZLBReBEs0K15poY zgM7BU7yWZ`z_9GevhtJ5R%TiJCvE(EH!RW*>aLjV?U%fqnEW|2*$<PvT9v$3l^iz+ zjXTC~Fpd(x{4_y9Oi^q2?FQ(2x5-*JekFWrKQsAr34S>!*&93Mjes6mC7-Aydm^CU zj;B0nlg~M(-Qd%1>eH@d(2F$^x633~#d;^CU`&Ns*;bt`Zu%-b={lUm>cGqjFoRGh zu~0Wa5FnuI(VW3V5@&=FHqoFcQ9l);UyjhjBJ>W%waJXANFW-3M77k3t`hY7Nu$0* z^eAjZXbm^6q9^JlE`$W}AH?%xA<<DI(}T166x~h+WwGU%v1cC|D^p@<En<b{c;)8! zbmsW2=LEdx1S95zlIDb;&52aciMG#)4b6$_+>3D|^~RC7k(qs4n>xxj`I>0D>NG`^ z^Zq0s@oCrC@*v;TuY5|mdg^G<QUz~%b~PnUW%eCn^+U|;Cj|OCak}y_$q6(4$II$p zx7qd1v_8p<0e=#ZKgsB$RsL0?*>a)@F3}jUV2p#1wnJX$BPbeYC?gVe>>%3eiCQRY z4UBaM%>2XPgwnDRPGwe(Y(y5W_dsQ2Vvt494|MBU0&rd#JUQ#l#1(=raPnvF{qf<z zb1{IEx#^$G;$-%znB{VnsbAET0@Koc{-v;I$%>_x%I%*HCoNTXE$^L}E<xrsbj&p6 z<}a<RbiA!%!sf4j+WKrw8*t9V4_SdoNDzd1Q)@eOPHWO61bHdK%G%l{!kTES3bDVK zX$zltS7qclWW6pk8)|Gm?qy8WYH{aZ<iP=jFOxuRi-mH`AxGv1fy_7tm7*bgm%fxI z2PsjPP&YDYh@9nT*wO=j+jZ@gDr<)-Ia`ItrYo6K2Tn`NLAEDXQ))@J(WSQTwYHBQ zo5kXnbRq=xN|T->&0qgC`wzYYRhQB0R!JvTh+qV1(sHWFg0=U84r(Ez)H*B4$noRC zN7(0nM!m2r5DlY^5VlFc55#i@R253;v0N;vcJjL}ow34CF0A4Cvz&l;9uOQt@TNz6 z4sx7J)jI3*&MU7~mlU(6!kw4u7c3htEE`LgnoOpDtIT89Z6CxW5nJU}^-rdWRaXC9 zbnlW@O~@9KAJ34fE>I*vx~rFMcULp37rOY&ov!T|RL%RXC#l;e^PYh`f<Xe9S*}`e z<behE?%J=2FTbx-#-F*C;%x$?%w#SWeE>@p!IldbUx?NY4|Hso7hLZ)uE>0Jh`Ro? zI<&4CVTN5;`XgHtcVTM_SVr-?0K}KKP3$_KIa)kk-cQ=l!MJ?PTIl(>kxk{)1G9HI zu^xvkZaZqTTBq?N64(?$2=(6B@|4R`*YVQN+*6;Q;8G;>Qi9aYu2d}#7?-NON8_y4 zUt3!$m42#w=KRK*5XCgz$Z18|v!uQ2Ox|JkcF1hgWOb`?o@gAr`p(+rz4wMil3iL7 zgnnxEYoklnx?T3gvJ<Bhi#*uXd3HeVGYh}X4`<MS$3X~}^z(=L?Z_RyVe_D@lrY6) z*C>;@g)i4~&TGc&g3P1yyIui8wyUuYAbGdXCT=8q9x)dyS|r=COr8`?ZU%UQY=@Pc zn%%DR^7|xDy6lZKyyM}nqsq;y>fUzWl`f0gAQQ<Kw;|)BR(F0>7E3J{zwOSQyc4vz zcOkkJ=a%AmkaRk@vjVYIh}c36CU5;53HR~cyz(M)?#ec9Sr)86wBBtDcGFs4mufPz zm+;)gyBU4-rvBxY9K1~1;iz}HOCPep(6ONcbvhxjC-xcpxH#_#tE`>z?|gse<3H@~ zF60s8w-YSzH5Yo9XKFD(YI+vGW8!1E&M_KU@b$UwemJ#0KwwEY($uo&6Bs%zw&4-m zw4{0MK$h(mC%&pz>J8KNG!Ax5JRx*4S*Jv7keeJ(HhN}o`lxK!eVE_KS+MT6+RJD% z&KhPpl5yo%OyGrsnDt%1e09$&IC?)UA5={mrtcA%g<m;#t)iNG4n4*d_@gsDfUi9w z8ZE7E{L6csV<HF@)T@=c0o7`bZBz%ckpb_r4&{9|Qj!wi3<uoZ2=G|kK3?CzW*cV+ z9A#45+!|&Xc23~8JL0X4hbtyy)HJ#lPu7#Gh@}^MhCN<~J4c1Tjv_Yn2#m)&%*O!; z-)+e5eSU9|GKWa~r;{Di6;4Zusr`y%g6>e#7m|(fj^o!o-gr|N1?Xniv*nrB%O8jA znv(sRp@Gip3og#V8j-UsNx|(dM;&G0NWh(_ofDwonV0ZZ)M&CRE%eU%m!1uL1oLqa z21y>ePyX&K2odr^KtC$ZvZrAGYt??taEQ3e?yE)L%2Vej(1Y_1?@5<!yl!Yp*7ilm zOhcsKrG(F?Q=@cU^ZQpWi&Nj0Y{+jUK+jI%J>7Odw%_@`G4*bL4rTtN9AUa=?68sV z59>V>Tly~k4vCXLePOy{9<p8vJs(sf5WVe=SDd|@g1txg_Q_udoi}-JTYIv;Jp8F< zJyYP)7#G@`W%Q>kluK|e!&G}vrzK1NOS?oEw;NCqJ3Hm|U0?8wXE+5(<{Mg#m$P2k zZbFLHAS3s_BUmnW<Msja$4lZ5?)?5r$1+_`J>SG1P|575xGx;zaE@ZKo1C%&d2c6u z{IS;<pwx8k78%Mo<#~L4$XVmZ!mOumI=HCz^X<krUZJpdGLWDCy`X}h!IJ)83R3(o zlaA-VY*O!%?uY-kQMm1IF~JBanje;W5rd~+t!=$+?@ga<>{m8LJm5((gC|LmRKHc- zZjZQME8&+s^neb!XCt?%*1Iv+V@>q_=As!CsSb6`Dsyk^*u2r*VFM)Uy>tp0k&nsO ze!BGjlFI*q)bt_8Z<8q#vJohZ^rFc1cd^;;9kq}rVnO%Cy`x|Ljx^c57aVbt9I;Na z`q-MpnviUcBz=g5Mj_B@m#5bdyY`P($_mT)>{WErVdBlMa>&75pNUIoc$(QBBma?4 z<SdMR@%#E^fbUO!KdA0vWF9G=A@NK1(!bd=r)X4iIn(K;M93H8ee#^>;&*=rd!r?Z zBc=P%GQXn_p?_rs&*c>EpT>E&SjV_ZCHd<oS@|WIvXc0?k=Ufp|C=XJ4SP2dFG%qZ z4!lDfxlR~$Bh$+KynKFrvwlRpRpvhIosi{w1SbQTu0eWMyFTjO?0kWJSduTZ{^NOR z^Qkdx?=*a98XCL|HJ!aVes?48do}F3UXmOuY7=Dh&KXJ#t%%&6<aR9Mfu=hpnPZ`W zQY0bjB%dCV*uaytX25y?GMie&QxQK5qflbGT5!O!6oY_qfq+9gBl(<;K8EA|PUitH zk9LYK1wG_|&rmhyu%W@ym)clKW*1jSUV~?oQ~p#Wt(BZvB<b2oix1naWfVdb%euE} zk3HqpNxeLK%9GI%cYUyXba)}UjP)4F6%YI+w$c``)XIM}?Yi0-wm;Vx_)z>~<7%RC z;2w*Etp8js-D{f@sSe`cXJ%i^$xCUk;MG=>CgVS?-V+#w2R<d2KlTSIXjmjnOr#Fy z>ndBap(pKMmg5R%n;L_jw|c(MIX@LYF2WM}(WIi($BJ0j-k6K=T@{w5gH9j(c=ZuW zlTD=yKIXy@u3#A<@H{{c!>Ex!!4&DREd1%UF|Dvev6pnEt{yw*V~Emsgn_^-NUEV| zJA@(O&gXfksnYq*Co>IlYeowL@r6NpGYvUwYdI`7O~rBZ0ZSTxanzP`=&Mei4DqgI zCbjEPUK6P{Ik25u0-eB$Z-&yMz5I%syqAwQn>`;!J)yu(ZaLE?%Ri~Eqgb}_J@iEo ze!inRxa;EAZYXhp+?OM4OnhnW!JLU+>BHvQ3QExiB#WTJFdsNaxTiD0C5Dt=8zJ~I zd<zpxZz7xam}PT`?#XqMwuJ$hd3nx=Z0ePp39PB5j?Mp!@l~SMeRoC+L+NUFD~`W2 zS`>)HN+wlex1wlcds%gkTE}76Q4{g!z*J}pFxkO9_2OVVC(|JLv-~r;e`0O3h9B^) z`U2#ibB)z*@w;1^`tJtLcqy?Lw(Ukr6yeg8obLB=)NnkQ)~MMN3vB(o_pqr`(^%on znI`NdkbQ8BHv`^JE=WD3@a0vSL)B~?=Y{Xtlc%q(;6@VmF~TO4GPRa9FG2k7=2eDI z^BHPHfX}Rm+K^c^jbs&uyrFv~_D7n?R`;Fhu%Syc#lD{r+t|BoN38N$!2(|1xk`7% z=gn>J?zERhGq2=T-G5a4F2O#!y3@WOgFVD0Zfv!yAEL$a{H)?@N%5??f<n*6S9af$ z*!m?wkvCUBa?WTTV?S-i+kek0=<YhSpmNy`EUKl)yewZUoj^868R#SCnFL>?Z;qSO zZHCdP5|Gc79RKhJPB(s#Sac+gs@*+lUyZwa`u?cr?zfNsZtkA-eJV4{{Em2#iB)1= z-DxSYW|#XptEC#TP!eCzzGxnq#n!o*eYfMiPtA*tmEf1cp=%dY>(1-Jhj%fe`xj&6 z!k?<<Oz#rwGV{m<&%}fL9-pFLW(kGd$Apy_%0S;kOr|^welYIo>%O9ROl@r;+&^Jl zn7~F>$vw!xMW!XxPnU~L?0UpWVOd1u+5%=9{XrQB^^~0nPxjA$y3y9tLdE%=Hf6rm z<^oeKKA4&8xavq1*exi3_Ub6e-O%yF#;$xcK2Z6WhwHze7d@9$J1QibiK4MUnyAZu zmTRMBA}py^PBRmg8J4dP@RA-8MtE`@*}X=BWS)APT2*dwj2CU?&oISny*}!rln0R0 z%z-6DV)^)Zg$)?4d3CR)NL@WDyKl*VleYY^`8I}Z-2bsmYK}equZ~FVW`60QFYJyC zrL_`7>Gla{pLCYLJ3cz6ZnGiHGh58NzO)I*3i>QJ9bR=HMH16EG7mX;o9nho>PI@h z`}x}_vP9`o9cs(y*z(aqcpn}pgF$<JKCnpwbIg}RGS<fVwuPso=iZ98rqijm-G-Tn z<mjmy+F;6<#W^+Kq^Mj$HFbo=lMLVFzYdzbu&6U!*r_#Kf5cxHf^J&B^l=W%sCYhA zDDbs5C&V5iAksPd&Rqn;Nd6C^wN<HWq*wv-E*}u#IZwUPpDfOtcrDNEt2efJE>J*u zEAc-%VD24nReERN(qdO8qV*0*Fd3cgVV(7d<H|QK*CKWUB8x4#?F~Mvq7I+x7u#Ej z5!^BX!)l>byaOEK{uy*a^SD{DkKZHMA78(51yfQdX441g8d}WJuT~8ihF7e4dUs+I z&DVq~TYX>fGbRBu-3~ykT{9$1n*#4HF6dnyj(NV!=h0fs<S<NR`o~f)q*)(G-WtOW znntf!rl)yjvoIVY*!}WM?i&jF0;~~T>QiANyX2;60k`Wsx*`hTWObE#sw?&DCt>eC zY+Os&-RIvp&wbaurz#oq>CMJP>${JqkH0<o@rvoe4m3Ib)sf##^wI%;Tkp-aBnr6J zK-`+iuN~y_FZU|u?GR|q-OVkS95NS-X^ZXX-d(NNpSx)PR#>y^q475nQxF2`Aks+B zi#WJv-n(*V%(EMky|qxQXAPsxdSS&Ww}*e>cNkBX@5YRU@6<Td3eQ+Cgq!W7kM_Vl zrg1X)m14WXZyvs}@tK$&HLqkJ!sM00gj^m9?V+=ka6qmf)a2<}DQt?eT9X?IADD}v zMmF-sjIMfPwrV@Z_p7>g&J57P#uu4(&neB9(`YVIbqO{#@3ZVGuO6sFK<{4k@7}-9 z4XLk|C>%93uuqnk?SdniNX2kKS(VOy(YIX-O}{?dw6=Kr(N4TfYd`WRV;Ps>p6?}G z%3;ys$9-(Fcn=pL;rQCB)R2jmjladBCr%O*rmV(H(7II_<7QE)!_2`SVuuEOg>ey& zgWAu!)C!r3m+Kape1iT?h@;LH&cJ}2m-OIUimD<tk*2~%x4i15^aDOE07xa_@w{$B zUAA|+H>oALoQSOkj(P$q{-#1LDUIh@#Fa^MogXcgLq3B(qJdL4i#md<)dBmTE0>w; z{0st`sh=oTyYPi~js$z8>TC1-GMML`cUC9H^3kPWr9n)J-;6wC1UF$!<~RBpLRFdM zqN_7j`X5ar7YX15MCZVO#IMFZ9WET*lE7EP0Vl1-CDwh#HKo(@8^fHK1+Co|OdP)H z4*65t>1S={Yhi_}GOO>~c*>7#9z1K3-Nz>7#LC>S{j1oJwQx0ho5&%ZA{XmUodJhb zzrXeVu0_*V<*#F}ub1cRY}XU)YXYb|LKBn*!DXIb>Zd}Q7g$@+3Sp&hR`Pb+lGwse zhl!!XX<0tWnxQ)r!^LCOvPCBvcUM~8-<g<=4E`alx5{qX{VyPUC6r-hCg(}&4h>V< zxaE(mH2pyyUH9~R4a<y`h%o~Jox0g?%Rfug%lGm#YpP+%oi55Iw#O09bouC$uNx}6 zW#C~3waav+vtjJKLx+&js`Hw{U@2)FyydY|i%!lDRqljaPfH?lE`Tn&<XkIm%pZ{4 z5`R83Ju66g#TY<tIVGN$HfA+&wFYQ(G!xe3wgZcGg2jpw3=W8Wp(ih^C$-HNUVP$b znm=KOKQ^^YG{qS#Df5?;&*R>BSwl?eA=$V2ObGY#(KE7IvdAo$G)+^>deeJOvPE}J z3cK~|8E+wcp+<h5tc^e7B}M((xHB^nM<^<ynM|`Wc%HwN_T_T3<j;lMUvrm=wx=P{ zgFM|Y<GR`B_&KXpHmjvmxo$6*d6~`|tXrCw!tH11GTDxYTqp>*H<_uo)aaY?H^qBQ z`7Z|U#STc)Ql0g=b5Oeq(Jiiib|1O@QYM-3UCy=1A1x1OR7%uRJa~rTOO_`%zx`Uu zUcph?2>*|MUC!ht8JPbze>xfea=n~!Th7JkDf=BJ>RoaoVoTq+@+yU+&#^m+2h8;B zYqTL-NrgpSnPqe~1Ioe5V8QA(fpT7*qFY_!(xc(n<G;tNI`xQ50$Bdo681H<B`R0_ zy>qeL_ON}WfdudR30s>!uTnl*!3r!Bgcc!76s_%-{ts~%p}D(0a|;wHP<WtQptmgw zD7kq4bUP_?x$v&QrN~#xPYAE1Enj){vwilAgO&FEv_W|>WQ)(-(|yHw!>w_++H)&u zAM3$PKX=r(LD>zUv{UEArSp34;KQwL4=S9uCUtEF)R^!vajI77N>YbPcP;@Bw$}zc zo}=wM3b-AY+J4r}X;~y%q_$rL2fk?o$p?X@Wr${UeV-M0%oT4qe>pEQ(3LTYdoaoI z<KKJoB{*sr^Hk_S0Gv~g?KX6cjr9kghLSKL(|FW#w;1WYm<-p)Aaf3_lcMrfT0Ogv zN#ODce>1^b?SMbx&`@$qOAbCw5|#_ym_ePhtwp$blnKUg`P_*tzau{(8>3}xD4=4e zrGV5@UPh}{X({9O?{=eAy9Zcrp;bqB<gdKmo^U>c@!Sr`r+h6SF1!UB=GaoI@ZWS} zdHN-YZN-Y78c_EVVE!q@)cC`-05Y8m{ERE-84pB9zX$kyOh}NSB(L_VY3>5RsTBal zXt<=hM}9XvE~3Ri>oC+`RWHDL6a#_A#I=?9&m4ap$aokPojmhj3qBKgjpgJX=FgYM zpcQ5kl<m-RxB;b|8r7)(Yzn_TuK{;BS^@K)r>S*!Qd4<nDIQvZNH8%kF!`nA$HVOM z@{hgc%6|<P&9?gi^)CXk<i%sRK~>%2DiX5p&E<G2Lr&vtyM#|UUsn%JoJC#MNjTx4 z6(P#OYI-M@r)47buSLH7Jis&N$VU0z<J29ZvU>7tKi@{UsbZfq8LW|nR)P;GW)8^K zg5zQaq@wm*{B_^T4jUiV$Yp{Rr3&IJ;9o8{%OuPRC&D~syvh<In_0|B9lU(<Wu0F+ zD*l6ZQkj3H1OEB*aF{qS6dzQ#5rK>rra8{kOvT=oA8Q@TJ~2}})oututJLLX;cvJa zz|7M!9N_Fp>*DksHvw1d^ZmxX`k{KkN5h=%?R7GV!Y#RIm)ir)suRx6CZ5L0#WrYF z)`2^d!f->^c9Gh)U~+Uopv8FkZxg@HbkSGCdm4kh6~!;^RI{gcy)kpovlT!HEdn_& z<GHIqCImWRE+%d!FOiS{2YR>KmPsqbP`%22ZJas<V!%d>qrWV8K!al-uEu@vc3!q` zW7yizRO7Q4!f>vZw2ElU@Xp%<rm>1+VPU)nhpuurTDW#V9<Jrd`1IFW9X-Aw_@M6g z_qrA2ktCm9VgRfE$Ja^8#G-wl+V{hHY*fJ^J{6U7cDBhb!;|q`RUk1wEwM=;r&E2- zt(qP#zRY9?t2S8OP(^Jkj?_+_^jv6#`I`+>or)~_;o{0b0D<Fl=074hG<UK#%-I}* zR?64fm_k2cI~uLOHFmn$Zl$Fdj+Vw~ZA5#%Qw%A6N+~9H(BW|Ud`GNvV}e(+;#GnK zO@U*|*4{wd(N`Jjdj&!Y_?JgeQ}*Sf5k}ucF(%8+)0zm8r5=~B;jgmBVQ0Aj`TWN7 z4zj4nQe-JoWJ~DG&KVLzE&a0Nwlk(RegUO!DcA@WHZ4U}vu|*SQ79Vt75UBdZ{ru; zj40}~)z`=4D}p)NMAvuA!oS-rysk_C+1UIV3f&DU@Qr5nOIrMW($Kl*Ms2uzL!Umg z==oK%SU?%XlX(CL{e-9n&G!S<`+@iC`q--aZe0%EO3kwnwyoj!eQ@iRqXiPTaR9Bt zLHCo$xMg?*!|Wr@(rd-D+uT>D0yLc025;CdTw0qVov^`L)RtOBJp*wuXxA2`C)c8n zB6KrsK%_IMv|mioMYKa#LaB#<|0^8W#Cw<e@ZaETzGMm3FRus0(lgU)L#eUyyUX{w zT4c<`U$@qR3t_##-W)}o;Ox&FTh%GBC}@#7Yq2=*lLr*LI^Tq~aw&8vCfxI=nXxVV zL;YvbHoO9r#46=~OlAqfEyZY|oQ5wlFI(+t@>mD%mi+f8qktlPyVT^gBY`owZu{l# zcgvNvq;$Ji=WzbH6rz0nY{h*x+hSz8w{Wiap|kjY1CJ%^XUz^+t;3J3;a$oi5ygq5 z2#0;6X`QF71N{X*+)93|T71WDick^5Ro?8o_4z8;4Q%W^aNT`%>45i?O_Q%eo3q#Y zHGO-VRH^YvESQ6T*P-a8kAy^^bdYXaP{%yWUF{U;4C_%rss*eH^lWbY4F}TrtH}x1 z^|InQyC!{kZ(IPa)myoo!&)^QB^FFN-RAx!Q&IBx+bby#^&kyz;k*BSnwdpXxgIO* zoGBUqXL}NbEr<&=Mp-^8+)9~R3Q_1gFuL|bGXE|Aw!Yk*ar(_oG0R2xei^gmQK)@R z6RYR$uEC00S3BD(9phZnM=HKB68NG+s!Qm}X}<@_gY|DdKOp)*wdf!2l_Zfa@9fXY zzD0cYVA@uHR;BD1)@0EUJ#seW5vqKtDbuZ`M4Rs`%1xf!LF+xC5I!Iq<s)htVU5n} zY?HtAi?|Z;PK;~6wh^+5nVk-(RguW-a`{Q5{_#PR;$9rT-NvlY#!)&*hg-)vO!RkM zr$@N8PL|7At<M8+QD1m~LgW&EMkUEN;mFz8cb<8^So`DX{Y%Q;2a342`8IAclW3(X zu#y+?c(94@-fC&Cm6m)rTG|h-XdL)I0B%5$zvEKW*IY?7<mqddBfH4&BCaF1-EYs{ z_Mz@vq4-=d|F0W4YP-Q}{ss3FlAZ!nE$TJ!?XsQ(?{0KSSE&9jHmAS?z=2jw;ERt% zJ=8;2;EJjyx}u9v@pLyxHn#J^EtFdF^rEMZUplUS13rUk_j&`b%JVvt8B4Y#eLIgf z9ERb7vNP<rYJ6k&TzM?FAj@qvmlt?LJM_51BZE^S!$5ctvfDKwZM^y;Q4ME<;A>Jn zvjBP;EAI8bmRjsxbDyU`0|2_LEIPJl`>GE5cFT@5{N;V|NR4ygcvrd$Upl%UW;L#R zIAFFh-2byTEaR0bpC~b(lKaSJp!zC{!+wt@l{4{;K(4H#CL(?mgwk&fI^{!)IazNg z`T?^&3bWDDn6Uqryj4oQ&b5m61Qp(Oaz}88GiROytV*AF3Yb6xBpmT_dp=lacC-8n z^}{!S`x`bdI`g!!RVljfJiD(umwH1wJVP?r13q)I#`;(EEHzU%bv2~Jle6+vkEW}a zW~|e!&6?xOoewTZXrP9lF7I+w`iU}~YcrWSRst|@UXw9fI9SGY|4E@hc6?A=Z8Q_0 zA5U=Ce(lypJ7AxD2{ZsI7%a?t#mjTMuY5x=u;G2REkF$)4<#Ru8z#?BzBR%#IGBSr zSpS2N7kQLge)KZt2tLcbcLw1aLpty~;|}z{v$nv~Ec|YtE!+C7A2`p3dDtH+|I#B` ze`qF7_-|9%{t0)+JCMCaP`)8I1YgMA2VCAicNa=~3Y`1~Y(O&<_TV3Su3Z0D#0VxS ze$6M=&Eq_IOTLd!zWMKXHRkX<SVQ+3{b8EflM>eSlsf4*{VIq<I;^^Aq&7G<F+f0T zHn7<;g9i^PJErhh!-m3+36nTcVla!qfc?_gt5+_Mxp0LHIg4b;S0_=rQmGP^D^xF0 zk%}3UR83N#aDLjflP4yhmVjD{G;}B=qmCdsQo4vKQ$&akMHK{yYE?jbu-4I2hyUvw zuXE&tg)^3H8?$QArb%OlOj|Ny#C-X}g>IHCSMW;F3&ly3CQOzrQF4TEks?Hh1o6?M z2M)(IYP@*Cf<+1wCM=K$*N@)6e4jyw7CoADY15}sr&hh1wLgEXVaJv|n|5q`{n#B_ z7EM}jYSpS?!<LPBHf`IGf7|x$8#w3A!$p@)j@)$W*Rhi;mz{fe@7TS0v**j2J#x>X zOGm#R9P{PMk;j*RJlnS7_wi=~{%%z|aliqrhMEBh?9IU5c#B5CXrO6OAb|!#D4}H( zV#uL~D9X^HU@+3?mySLHNu*hDDTySMQd)^6m}Zj6CYx{qMJJv%$t07XEdQBg5~7MS zDk-HLX=;(Dq!MH*tFFpwtFFEZODwYBFsqF<(lTQ$x8Ra%uDb5ZYp=fk5^S)-4pWS= z#&CcvGRji0tb_?t*sQbK=&aMuJMqj@&pmDHM;>96;Z2$W0UWNl<C0UZIp>;_&e7_^ z`A*VFDLv1eZLFEcob$W^=R8NlVGlj#NL6$>`L?0YzWWTtZ@*Fe3lKO03p@}(X%=MA z!Db*VNJ0uLT<Ag!Go<LEj5G?-Baucj5ycc$bm=7*TdXNY8E53lMofUxaYr6~{BfzK zh&;r|Bdx+JE3WGJ$}1<K9Lp>!)mZDwwz8CqE-viC>k7T3;L9(-l>aE0OvHRx3{5p9 zV>5*kNO-^mb2#&i&x<j(bDw=O?$~45=<%~5Xaps+RpJmmwN&QP12wuyx2u%9n5m<g zI&aKTCz*Hb3D47(qhoaC=7x?BzWMB1H9uDOOC_CjqzUjhTB))1z+4^dm7re@64pY8 zik)af4w2<ZS!PQt(WH}HVOzzPV4~JVYh(N*+nsLYw%c#PO-fuL%RLv#B-drKNqEbe z7p;2leJkI6?dtO1fCUCjOu~*ZEHQ-_hOFVrQXqkZ25MlZ9(rE;SoPIeZ{79LZlkA} zV@NJJIQ&v3RaBR)liBy~Xbz7ZUy`w>9B;M(+EG!TD>^w;Q~ynRY5cH3W}A0Rc?W8# zskZv+1+(UL>tB@tcG!m^3VZAhKQ#Lzv`w7lS+}E&yG5FAs{8J|gX)&YNWulAAdw3y z<}%XY)U}l*xeF{$f|8ULrxv#0iws)Y7r!L87brksV1hZqU<`AZ%`wI?Y4Y4;Dr15V zkU#-N_y=cF_c|HQkcKscO+UUN43hcAWcNwgd)l)o<vr?mMf46h%%P2TXeu2(D@UYw z7sR1SkyOw_T76hWJ>mc-9ma?i_h{uk17U4f1o0Kugmu2KiETsd;|PeBH6pdG4Mp{n z*8N_Tznp-AMm4%o|M*6fqx=nUQZXR92&X`HG0=gDoBvV-%`id7S&&Oz(jb_aK(H}s zZiHwuVPsI)rV?!60}bFpKmIW%8?KU-t#n;K!l6S!4GK6X`=Rd8v%KCJk(cH0B{{ZX z4tp3w9X;z*Il%EmNP&uZLMxRO<D;tS6-PML*v2`G@eOh42S8J+mDLgizA}!_AZJ`g z8ixguHLkC09Kpr=<QTvC*^xzZgOUFFxUHb*=zjtH5xItB$O9rtU0PYByTl@g2P!Tt zjmy`TFz7FU39N$!+azK-S;7;B(gdT_Kmz7~N_@DIq$M?Jo&Iqfa~y+Lw!7VMe)t|C zwg()%qZG}2nNywG3}(l}88voh4xIh0I?G(%O#hoF#rHrHIntbFHmV7ZZcO7F*Z^Y~ z!HFPoHpq<Tlu#Niq|SA=v7K-f(TL>vEP750k1x6wjr6(CKmu@(KoU|wi-bt3B#>S0 zLa0I&x=?yCPLdUj3q&I)(SSJtlbSqOCp*_Lj*>tF7yxNM@G;VpZkDs170qqr!O~`w z>^H*kq0yED9o^aVJ3Qqjc65p}br^$ZLM5tEU53<And)fJbLvxpqm6V-qZ{CGhE-=p zwW^5`S7a0)Imw4ku%)k9WG!om;Fs1qzU_|ogi-!J!AH2_$bWr1id_qtR|G2QpoeQ@ zl%_;42}<&?a_It>6uUu+2F75IHPgb<^#3`~sZawJIDj7ZK@ZO^n8B_DtwDA;sM5A7 zcR<`7sEW8#o%-&0;9$oy$|F?jc&ezp3tBU)XsYL3QE9|EnTv%(j&T(CxZUg?b91FD ztwl&e%J8vtr#n`%wexJuil6+{%3b?;_gZ$#C;!ST$hwY;Tu~{~df98Z2EKP*gT2=u z{LlqDWFan)%b*7R5+;k1sZ0qY;U@)b84_#&0~SDlB{<VyJ@46d|Ja8#L~A?K9!frn zS`TYwreQ@_YCGmI$2hE!j_r73J5a=JO@pS}<|(STR{X7t^CKK=Xu}xi;HHfSG$=9V zSjRi|DupNnWb~<ztR8Y7JkzG#w*T$Ae)X)D9&>WHO^`RrQWn<$t8C?grmLWRWh9pw zN~JW2fef&SMIK-=7sQ^Ka+nm;m@+3qH+yoU4l@B|E%1N@G^1jCe%;3Op%2%%dzCLN zN1%BqYC=B`m(M|Tb{4H@fe+l5IJ1W-x?vATV+V>Z!*r;c8AO#aHF{XgqN_$Nj%mEZ zs>l^kftI`Kt-6|gvHn_+t6S@hnDwkA((ZOw0=FgO?^@V;GLHCZ-eUu_fQK9$;S8$f zEyqhrgH?kW&Txi5<YDPuD1#U-hy{O5Zi9{e_G5{_xyPK)VGsKN1~AY73s4Mo^p@eg z%|1hw>SnYOF70ViyQor`82@-U)egaPded;2BOS?52Rpox9TW3zXu4Y&#Vg+8=?O<0 z*f54YoDm#Uf75$pWKdUMZIEE8@fg9-5IcVXj5ih;t#pJrOYVq2w>DYWKG9o_<{Cis z5>VNC-D{Tp>fU(4*UM>W3mul8hcc9*3-_&yME_OwzGRZWn-pPU&h(f7qcDXXr85Q) z&;-n;{dMvF$M?Y>e({f={N*?Q`O%+#^{=1&w_%4c1_BKO)sn)f>bJjL=AB>uvSxVS z4&Dupwv36ysAKRPj(MC%#aQgApvtPgp%`e(<B|)jL{34%r>nTe<Ty{r$R_mKhxA;| zS>{Q}W^VO@?dJ3*=l_gt=K!bY1c#t-@2?Oian``gl8y|{pbW^M476lR5^Hk0t%EMd zzqHPT1g!c#puh|a&pLzsobU;uFbbt`3aPLPt?&vx1GHvmAPj^WL~YP+X&WF8|EA+* zVC(KS%>UAG;BZD8tl=FN&SngdnNW<k3Jq00ZSlD18J@u&kU{b$kn+H3t1vI~&S~>5 z1R^}|^M)++MlU4JD%V6X$zm?`ybIWz46goYZ~AG<kS*C>klAAJ*><n!AgQqG>w>sV z`NCuf!woSMLt!)ulqh4s=F9@pO#!x{Vmt#2eeoBkupdwf{J8Ix<Y5cjj+VX<WeRO& z$j}V+kEhfy@Biu!XWl^o!vmRUW)9V(@QTJgm?{sK2D$8E8i*ksWaZ;1@M^Tm0=WwF zGSF+%iMkjOBQhc*ZY_=^(e$7N^?Yq^fX(J;gxGTAf9Q$@)60N<j<4EF_ZBL?8j8N^ z3$YZd+m=t0oKJK9YZlj}>&~sREI<KRKpwWQ7(WK>O!8x1s2YM{AOvmDn33OBhVIT# zJL*miTPqyc0UCm8;kbhvGtC=Q>{P-LIf_H^n5G)8@fy%E9dFE5!if+uFdk2C)@ZE} z@sZ`Siy!I7A4`yK@JU;?<@I9EM+E4u@Jb=EEa-CYU1pF57l*L0qzBC`FRnnpI7kTl zi<2O07XKxKqpVK}3m~L4D<v}qB@HuU`eCJ9(l=@ecjAscXcFLD3k?a*9QY5mjwfe| z$Cx(dCxJ2?G|ic+s3?^NDN)9%uE!M8K^tVnn*{Mza%`NS>#M4gSW>PLR}KW{=tM@a z6919rSPyUf2+9hw69woKouc-zOp%1nNdil-yeyLDl9D3IOM<W!`|B0^a_eYuz&^6h zCIA68q1_UbPZ0Aw^CYDf6Hs`?G3n1x!jNTXN<DVTCTpf9Efep6M<<sd#Bk>SK$9CI zPU66kDDe<A$I+V3p+Ek^DP!|{-0>aFC<A}&Hm~wnY%L$-X%bJ*B~q`gFj3h2sDF;r z*#D5?EE6&mtAZgLa_EQ-A{ob_9tXeji!Z!w&B9HDHqtMtuT4Hu2^(Mn$S#J|^GG)f zw1NTOeuMs?$~f+jK8Gk$jA$CAaWiMj9z63qLQ^zROl3MPK^d?(f&(0Ufg84=n*uS_ zaBSq@vB%7(D#a={?QtVM1iOsPL;Dd#SwuwjC=)f2yvovVR5aOq4h9QH%b>FqWmGLB z2w&i$%xn}panvuG58OD(OmKkQJf{}h#4?hw&MY7Sg5ZS;6G>5(q&Nc_gkc#*i#G}d z4DC-!9}dIxv$d?$W{`;;njxrg=I*+qOC!!b4iuWiG1RI-xQqc!UsJi-)J-GA5dY&; zjX02fJ`hh!&o?R2E5Gud099LFuh<SUMQ3k0)eBJ*wMk%9IvYwYup|}h@-Czx`50^Y zu8s)b%sb;u&c4n9Ccpv&pbqjZRSA}rRH_$Tb%&ZXIOH>FB6GED^>=bL?+T7Hc_utI zB{LZgC`t1h5!6_vXH2WXKOzu9*AXhAHCi)J1J8#Z*~q$f6I(-&E4xzWy7f;<bSycs zD8>~b&Gk@4F<sp&I^i;c9IApS=?DKM`6^Y-_VW40jU)fkBhk%Y9{>T4!8{9gYh4Gl za=}&Gj!+o3{)|RSCsSf4wr0G6SN#s~%psX7vj8zHiiY*@6tJm6_Nl7r8~?81@gnc4 z*t7yC^i87+LtXY|JFtDUvO~4?Lqk+VhZ6<&sS^pcT+@<8Z*LSG@*(BxQ7MQnF-UT# zu2L;WM>7YbqSi-$)J^(z0wzEKUVtQ3iEC;1V>lxkTJ=2%WNhIMOdDnJD05<`(Hdbv zOEH!jgLQ5R?@Kvt;ucV3N0u29&KaU+@&Xqsn@cKdQ}bAM9;@}buvKl;W`4SIMS?Sr zPEc~iRrV~`1(&Twajz|*lW5_q4UE=Z-_<&m_L9792tx=KixAE}=Tkot7boBW3cv~a zp>`SAV^k^^;*U2>M&DE=QHbUn46v7Sl^i;S9hRYOe|7)7!=~sK0sjxLD94mct6`X! zvU;tTxw5y_3Xv*X_Hd0w<?>M<d$V!(luzRZAi?rm@y0j@_1KiteQmFxmPAqCQeMuY zN*d=atn)f4m2@wa2xU=U2N*~_%4#1#05V}<8+eTI#QkzN!kSdyptL?@3S!Te!zR`m zcV<h0b%gWJ;YL$5PxxaKFNL|O9IwGOU05BjcMvDk)eKSABEp6%;#fK)htXz-$#<=$ z<r2XwXE#w?d$xURFNvG2As019?YCX;B~sy)iYJP69gEF2Cx97db-k{@T=xMKpaIB^ zjBy#I=z$vG4~^p!rtB}Z76o``MtA|x9KHcSF>{%bSMWGixBujBC_&bbhr^n<!HXW$ zdPB~T2bXYrOp)i5PTgp6C2@{^6F7fZ^+vRh{D>?Em0YRpXE7J(mY9j5&FCEUT_>_G ztGEfkr1>z1JO7JQzti02OqL(u0S+K`OEQ-onl(bk93c2TCCo`<vTWt9RwEXUb2R`j z7BlfPqzBXhY08B8c$yhd)U4?lx<Q)+WKFl3n=i0J$tPG&E}X?i7+^MLacyRKxO~l* zt$;Xk19fr@(ku&Ap5Hff*|IIy^?_>eez62;^>-CH=$~Ctpi_72rq<jbMwSn_0Rn&w z#Q32<BRwCQJ>O3mUR8o8Y~T1zGT)fdIvSZlIAi~B!~c?Z4(s-r5RX1my5rJe6wYBA z{t(q9Y}I0zHn&&v<S`K$S*JC0<;*IQU#^Gy)K7_eh{II{d!%xe^KzFuk?Ps0o0#`V zd8&JG+bVLguzEYWGwZTgi)*p^x;U&A00D$SYacq^%o=uh*(KfjG2yyY4sEXKdU(a7 z)b3#$C{2V#dSeN+uZi`f^YFz~dSs!2wqBEvVYnR`o5u>bWpVn3>y)Q;c!!Z}TYb1& zn~a^?nJkam6OXu)o3p89kbdhowe`8Gk?%|TS4aO>wxf@>J=HP@OgtZ;0S+JqNb*$2 zxE|^u-q1Ri*|QvefgoJ!b}pLJMn$8ED8r@^GymDa8oGfUw!t!^d!$La4oee-6_lE) zsTv+|8k$m@VVI04l%~gf1F!PDuNBvtMNiAuW`$Zf(>GA%n{we9EqhKagBHJsR+LA1 zM%`kP{M#-mhoVY%J2Tal%gx-*EeWl*0mNDic)Nk&P2T)rW8D1B;XKaee9q~-&h7lp z@x0D)!^c|6F_)2z;{zO$N3QSlI;<2k%Ym5{J*VE*9-d(udIqEgRAVWngbTDik|)y< z&*DOD#?!$S&S87hRJooKSEM0pW_l_U;x;2&r-cC+I7AnKK^JIUS>Va1Utzts%g8g^ zt#Fn&Z6p&+G!g;{sgv`r+;<`4cMftdl>eb*4Ipw2(m)N)Kq3#z__*K-L|22L;0gYs z%Q2M*iXaGjREtB2i|0(i&Ab4zHe~Yr-Qhjn<^9ej{4;#}xAWnJsG%kMTx`|2!tM{m zLmc36RSi9?8%{hOL=3tmB{b`nkHb`&l;#T!CA(SJH5b;qb6k6QyvNgNjU+p9gIvf- z!kj0$5<`^9>IS|u8TKgGhzUrvJvmYBS-(wjM(K;HS-T>uPA|QjN4NTu3L4!v0HMuX z07&4$9h$<8)S*@Cj5qw>XBDY3*wFLZn0?97))vGR?zuJ0jybjtofpPaIJ?!s8eAHt zzgx#=*g_TAWjn8tb#vq+QIby{o&Rt4z1i7DEMdt})Mu4?=A~Q)8MVsgGJo}DQh~7N zeI9fEm)yY|lvejL4qDyM9EKjc!pYcA6r!Aln_+vG(`Ksbt-h!H&l*#~9u)q$SA4Je zdNiv$OvN<DSp~VgVH#}Q;|L`}B~-_}+2cQ6LqZ<NAvsTJ_7y1k$W2fnhnVjHiOB(9 z=GU^G8R)5<_>pj4B0-mmN0+f0pOss=z+ZXt&#mY!UjYQ5-7RK}nI7N&0ULq=Y+cH< zfEmz@+l~LN^)>S{vz{CPBH250=E{{LXONu2g$&7sdk8V2#BkuieY=S9o5hRUzIFWQ zahphy+O}mgnJuNtmD#Yl#Q#>U8aQL>w85-K4JS@&)TH_R=`)(NXhexZJK8L%(q_w= zI&G@#Sk$P;s#X<-H7nL&T)P4T_A6|!Ub)Ja#f5eju32o^zIqGyt*g0nQMp2e7ZoYJ zdP(^O1sK$)Pn!xG&XfrgCQFPbO^O5=QY1)}DLcCCXwf1>h&CVkd`OTWK%`6SIeog0 zYSnXEx0VANHk{eB+t^;CMok(sX?BzOE#`~xFI<XeIesO%lq*o0J8{ya36mvDlqflZ z{Ya4_M2H0O;iE?n9OQA-sPQ8G3l=O=xHnPag9Z&2EKGRNpn-r7^7_&9mrsBK4oF~u z1|EoDf(kCkV1o`m2>)S(66S+XKjr|V%rebD<5N!6xU^D9BY~t*MHNj1Q9}r+*pNXk zz6hf^_89YyJ?40m&_OG*s1S-inh2zc8F4gXk=vAX5=%<9<WfxHh%?GN9_qwXl|WrN zR8dDEwNz41JvEh7R#~N$R>26<RWM(L^~+dhorP9fZOsx_Ty)iSS6+MV>DOO?4QAM3 zi!s*NW06f(86=oxrkQ4lfEL<lrJ07>YOJ|7M{Kgu28V5J;Feo&Y5WFUaKaU5To%bG zCxsMHJO|x$)m?|(cHDUfo_OV%cb<Cewf7zg^40eMehnxP02%%PIAOESJ_~KM(oRcZ zKk-zhOj1Ni<Nx7H*rX)lNEr#~<3lRy$Rk298dQ*r<d|cPIs_G@F1qQKD^Za84oReu zB$<TLk}JIwQ##BTV~;a2QCVeASO%r#mR)-JrBh*!dDSsxW|iieVv+S`oN>-cXPvLy zc~_o#^3^9Pfel7jpqnH%D4~W%mgu64Hu@-NqDeX_YI<0D>1&#D+UaefifRU_Vwg%C zs>rR{s;kdMC#!YYX?H6TxsF%fdFZA0E3hUAy8(Uo;imwy)%f=hwQ|o*cinau_)kCI zV5s4?Jbeh_x7mmo5=KFmn{MI?<p`rU-rO_II5v7?PQ5!OjxR*|2FdS;A&rP+z$$qw zIKkDVGye@Y=~UwkOgT0D@J~fWvn4bWGgWbhVq%=}##?y>mRN7XIWoy6pM0lXdEvEZ zUw!@wsLY8GTBxCkTDEATj`sZXq@)Qww56D4dNik==B69dPD33v7gMw9>Z@2&XC19v z6T#hg;(^U;uj~C9EE1#*1NJc%vX-!{yD4yi3~b<mD#VUiNM%Dp;Z{t%1uk)Q#Be3T zm*PISxEH;v8{;rXI&PE@5N0kSo8#P&G+3n232b2Aipe{SAr5VLs9`*bo$MmUrKMC1 zD$BUon1rFRjh(4uY;x1^Mz$8?nG9vhTN$7H1ihFYhGsUq8O|)DD9mWjGoR_6_rMpv zqW>9fQ|7Y``k2<VQke=>siIn|n$v_>O{ad@u~m1z6CVEc&sXeu4}3_V0RpZ~0mlkJ zFyQ9ENJ?^&&x%`spb?A=HKT&v5}ZnmWVplm2!x7joH@ji3>&rUAojY~3LnzK6Kw<| zo->jRXP6SwRbw0KForh75tG;L#9^_UUF~i+M2qe2h)FC{nz+KIHi0Z;X^CQ6j)y$D zRFQcsYuU@9C#XzN&oPiGXU?)W#-2qAXhBO&8tZ^5P00aiwP^$T(&rmF4u_8KtD1A5 zAe}vGt&jQBpRU5zEA#-+kOEX>vGSt;0gyl*^}q)uFN)EOKCmC;0LC#i1PxAJ(EpPe z^xQ@Cg}8LFQeBs;myRfBk5QcC9^1f?yFU0zio~)a8Tp96MsiDBGO0<`(1ta-@eN_V zu7^I%l2IhqrDPV-h|KgInz-_n;7Rj|P@EGsQI@jhHP4$_l-bNM!9`1uvz&;+o*2{V zGtqeOdzBKOYvf7K^DV76aU_En$S|Dtxo=fh@aL<bBOUq;)K<6p8vn#Lwz4raZS`5( zu^JG7LqJlaob7A_<JJ#(00W8I63X8I$C7Yuup<^}ZAw|RQpy#iT`O`|IdEhSfmH6M zD$Hpp`8CUa{Zxjc6PW4Jkq(+<V_`fbW-)<?%w&d%DpfU8$FkZ)vf#ojBL7p1SC0qQ z<#F?hff0-r1BDoIcJWYc4dYw2r%p4Tv95Mq<2;e(DNu<jpMC`_)TE{=__->N^P83Z z{D`alA=H2W16B&omNvCL^jHO$06Y3&QO|04!*i?9Hh%F@3UX^oAX15HH&`MQd5}j2 zf$21~QI2X*E=LP-oIRc)ImcCQalOslPKETspZ+UJ#a+_3ZjugeOyeEZK!)ph*woq4 zE{IBz>N3Pc-QHRCs#(>l6Ny*NYkoC(DjTo!%4=S;rnOLPZL1^PJI2j$Prj6LXMOFP z*H7J3eR7;*ssdbC!y>i`iaqdlykk&7ij9yCKHCR2;7|i1%MAYEu>S-1f$2<ZdefZl zw5LA}>QIY%)b+4XFhU&C5ijh>x%3w}wz0X0B#xB{ahy8TVU2l=LL4Y0hiuCM4s)nu z8tGt1MbNcUQub&fKL#=_h3u~+&5&TuNQW$*kuc^Cv$;$S%1~+t)!X52s#(U^mX`<& zH335x?AFEbh(|IymCR1b6R%jw`c3IsLcMBT>lYQ}-ktHRjB=f8rQQk8yT*o|a9D%G zakGXrsNoE0IK%p$cB<lB0nmZIBNU$Sgv8E@palg_4ivp;vK7)jB_KgV3uwRu2ml)X z>Bp#Vj`N)BJk$ZwhdwOLz<>Os8K>@Bhe&*6!4=6PCk4`qTmN)hZ?J<#??}e2=Rpw4 zCHWiWFkvczy^wN*qsKmOHZ7ShWa0{Ss6<VNDW1f-U_$x1(4Cl6sY<41DiL_WbK-V$ zA+ohtbKdkOvsk-HR&b)XX8mrno8g?!__DLk2v0bk^X%|9@^yWIjoNVlUA6cPy3i#5 zV<1t^;DtUoKJ<Y(M3Gg51OmNo{$SSZ>sBFi^r9*v?$Ag{dSa%x_C%RuF*xkO4Qu53 z9o86#P2n*PU)aMQzEFofblmk|j~%D4G&|Ej=P$Jn%*Zvw2ClWCZP-1mg2oJYm8H7O z>h7KI**y!qqi9X=QnAcq#kb-MlNkKg80LgCZ>BSF75`Ur1qebzG?sUHZIpR?)mIo7 zSbt_m9(Of~HBhy3Xx;HOy8>A%w{j*xf&!FC1@w9e5CE=FX}2dWnAUSY=Yn(-T4;i5 z6=XrE6(UQ=S{k7dE5s1!f+OBQ4#hSP<B$&5=MDBi4BTK3t8fp-&<(~mW8bg}#Gnj{ zGlb?acI5&N;qVPC#8biLQ)ve<YsYpkAr0Oz4&y)$)PN03WhLw9R8M6)c9%?8#yd!K zZopH2TqSt%rhkTKMb3jo|94i5=WpiZR+kZHk~evDl^S<OJ`0Cmp8_iQG=c2ndHp14 zh?O;4gJ52BdJ8r-4dxyX24N>?S#5(XDbODoHvfap0)zQbd$Tw<9JPDd5>lMhNjqp# ztmSkpgd!glZ1Zv>?C=cgFb?m)4aPuI-cS)qRwD=_jja?82GI(mfDK~zBVR}nDF!4Q zAzZ_ChHIxwACe6;kyKT(ZFDGQ$ApJN6o2MsRoB&be#c#MGI)e17yEa3{db7x1%T5t zPF_?Q2KZhBM{tq2fb_K*@l-w#n2CJmSDa{p7w8<(A#!}gHC^+8AeedpWC9N+Ec4-d z$C3al2na2RixX0dxA>CM5?UH_gFn$pz{i74r(!@@N+D!p=`auK@D8ScT$Q7B+|Wzs zaD80ZBH7Rl@9+-ea1a#1Y+tAm-XM-Vh5vSF7k=l6jx}^T=P(NCFeP(GcT+}X6eC^r zctrQ;hadB9fX9#DRVU$9W-Mcf`KD%yVF`oc7zmk==mcMJ<&XzQG!n^16sdXqMS=U| zKAwnyph$Wj*&U>)VB`^kBG_mr*?RYpf&%aW>`)K?F_X?Blc(t{6@m@8FhQH-i-1#N zgR^v@BuY<*IS#QRvo&?^zz*qf5H|J>@GuYT&?5|Sjobi*zHkmE1Z-kxA_u{1TiH`( z2s&q2WaL*v$dC@t5S2|Pcina+LJ^N^Nil5c6jD)cSFvSRrEXpZGJh9%Y=H}};1+|Z zP5g&=18G*9;Fo~uMPH<lj<^{N8UHB?_>e<`aN{$Pv~e5yB`TzHkrkMc@UxKx=8^Z~ zfg!1xDJNM0L|G}R00^LhSKyMW86iF=bSuiDE$X5#3ZpS9qccjQGFl<>;F`yf6shKW zBL$2i@qJrKe7K2I3gI|W=!D>aBjgZll*0};0uCtzOWuH7%Ey$B0}f28IX>tO%`gtu zzzpdijm~DBF$9)EMLI-Pl;^-?PWFyI)PCkUZuGdG><O3eS%2FlpIv2_cbT8tq?h=X zW`{8|G*dGH`gnwCpmZjQ3QCE1b%_zUUlRJ58TWY?D0-A>U<7rUi6)Z%^P#JUHj(yv z2!H?qpbV8(qpQlQt?H^XivOa`f)D$E4Y|O36eLozSz_T5q(Yig%C<PcrVgo85JZSB zN}8q1CTj^%4d#%g;0R0L=ndOo57WSuqi}t&R-NE?okWI)Vi^<JfNR^ZL&MZmP9=}? zm^*IChkb~rV*#>H2>7p_pR;bm_ESzd@(sD8<2Y;`>Y8hMaXaP2gSk7|i+go*gX zUlR(MkqLUAh@l&ZV1RT`9XgVY=4g;sSr64VBpLudAbYV&vI=ygIjSMO_ct%`qa?zU zJ^4z?c8%#ktSqv93{i}W^Np>w4c#dY#DHzn%9TXItwVOE(^h`e01lCpRNE$=KtY~B zbcgB+CT?ky?TJ+$BmYfb24?YAGWL3}^`<g@fq45$kcGNti`ZTOw+IBvGmvO-h#8TJ zd0z^fdHdy<>;qsCJDC%^SRII&7rU9Ln2Kj(f*l)k2yg%aFbgMIvX3h_vs$aS+KW9Z zn<loC!iZAEC$md94c3RH=#q^MkyFqqt;fd=?a&V8Af~WZrnYn>N1_ei3a%Gq4CfGs ze=~<^nXd1bJIXK>b=scpscs*`wR9O~Vm3tpS%@uji2a#f{@Qqll8^!Sh;vr3l-Ga^ zny~fspbR@IocFMoDqzl`sr5rEqv)v%#%P5LACK00D0nO*y0{h~5Bp%6kgLDZa-+R~ zL@CRor=^3mx&M<dJB&oCIN-nz-Czyuuno@IO1fFPrYj^oRSx#R4j%Dp&z5%I&}1V4 zE-j&*rZbkNkT9)-mg5<x<|$o8WVL$dJM_1;({z7Qw7i69W`Zgh(3`danlsiru<I0w z449a7n`cUcx0I^4sIqZ{bw^eMasg#v>Dz%pu)h5Rs;YNL@<Bi%ng9oIs+O=>`%A_X z!kW9MqZ<;yIl;0m8>HKyQ=99PEJB37Ru1BTFiPr5T{yuz1xwi=Bp~s+C-Du-&<^lm z4fYTd*_lhG;}X)~4Al1w?|=;938!_~yXZMYcz3n#id}!WkKNU$VM|5LduDuzUWU3} z0DDeu`~S9vsenX0w??e63!B8^n{g1E99R%&g@s3cTY4KBNT14Rjn;DV@tG6$v8UPt z{g4lqRL0TlASa7N*@CN<JDUVtOTyPe6PzwKW(qZ;V=6Mi`O<7WMIt;nA}P_G*4KvS zPz|HQ66tso)%JF6YOYZxwN(2hoNSXY{5x?emt3V5a&n*e8CH5Cko+k<({rdkJeUi) zJqZ}gb~eijx0v30xBC@Gf7N+=>%>i<1WW)>SCcg!S+U?T%%<4B3<bZ4n}Ujqs*Wqo zHT^*QkPT?u6xV!O7=*doY`|k!&f8}%!PX7(;%iZgvqK%N-baqB1#Qb!t;zrmOSTQW zME_EaES5K+4ZWm8a@QenT6a;^!v5T@&V-NAG?!g9cw>gcf%-iA%EQt-y^Pq10>>Gg z(U3zdw`%l&-fPPi>9Dy>zPua;RgedH5Cvht1WX{s=*xj!bH!L(%nW6MiUgXada5ET zi)CDkHeDe7t1%e@Qn9IysRb|^WSip%t=^2B$YqU7nnDi2)N%Y{<cQm8cM=_O4PS~} z%e4(zorW+$RNK&o+n{POQB0UDr*jG>E?lPoy%hod$!)UM#UqF}TyFt+%Fr{{4=tE? z9cOa3*A;!ReqD)m3)mao8%n&yx~v?2Pz8RV*o^JiCv9kw?O4Q2Hvdz&Ew=$2JO2Th zJ-=VPxXnP*pl#D}^AD5zny`t@tVWx=t=d5ivqNp9OBf|eXtP6o&cW4FMQgMw0S-0d z62UFuT1~<igvaj?hthxz-0%#-Pz`CRmg07Idbo!%OuWUrweo7v%3FAU+Pu#DGSG`w z)YEU_J)i<N(G6+d=k0*$t=<~FR}EXK0A@#B5C*oe4pk5a($SG94Y-N+SScrh|9z5O zY+0He0Aeu4(yXGdO6PTM=PL?9xPTRDT)D}OS|AcS+l*rT@`JU_q~_3u>_8E~CUz3c z)Pz1HTq(%V7P}&%65$%p<Cli378B0kj5Gqt*-#AQpbn<M4K<D><;lW19{=5E%`pM3 zCc$95G~8YN=#Qj~C)};WXM0vX+-5&4(d12VQC<gWGzU|DH0qsS6}fr1ELePd1+Wkc zQefX>{<r$Q(ioeuYW~tGS>OjCnim!zcTVo*PNNDQAow5+Xl%_q>gPTk=&G%`oYUIn zOr_$G$f3)mj?UCh-IbIse!E>dB0M_adK0JP3##J`o^A@;Kn_Z#L#ZycQ>)4S?9ZJ% ze?I=>faqN|Jmk5q>w?PbhWgOI9?`BWXOc(k?=(K?eZ-O)p-N1lkx5v-%mglQ1t1s2 zg+|5ty+3D;=33lxm+kFslK`d~04+%m&>YP^w{uSq^--T`r4~U*6#rr(Ccx^*YC`sE z!{^5m0Yc!6T;U*%I7_-Y_2I+kgCg;2lr9q9il!~`A#)#0)gTUUhYbsVL*vj5QDRyW ze-vuj+;a-Nz{@*tsYGa!ZeO7b>*j9PZR@xG@%E<BBCka;gBbhP7<K(`2Z(^{1PGJI zfGlr$a!`qIpzN3kaS}IiWMFX@`82`N1x(CwtrBQYAU};=nT*w`J#ccUcZwfMg2x=- z#G=eb5ALJc5A`7R&F}o47J~}@5A<*hdR`SNyDjey@2OqkLVBA(7_H_&LcgiUS=xoP zjrM6D;yxwfu`6x!EW)LebWL*b3nQ+?Mhyz{B=ay2=Kv7moc~FaMvb7fXbGc1V+gI; zLx{^HPNcX@nX+RTk8R{A%;QIo!Gr}P84MV(UnzU7%+<0bE||Dx$(&Vl)+?Mjak}E! z6O}7eL4}e+MU>Q0QlON6V!Fxc(@aq@VX{<p(xgaPwL;?R2$CbPjuwp_iwMynw1U(E zV%rvw9=Lky$gNXn&Rx86^vZ$L*Dstlf!C~2qbAMaG-k*w7DMLC<HuYiXQ6z>@)aqW zpGbKErOD?dOO%XOa^y%6)I?Mh@zKLI4%o13%&zgmHVfP=Qlv0pq6CQ#8Z=n2@W6P3 z1`3oTIFKNKqki=AO{ZSn`gQEtwQuLHec!(6`t)@tU;p0x`R(}nnVaQt<3ong4pOUD zAKU$G*s|@{wk_K>0Jr%@z;C_*=RgDzEHE4f8+7nN1`kXpon-9s#v5|T2`9r1A@nf9 z1Va?DKoUs|aKHdl1hBvV_H%JR{q%G3J{s?<@5URov8J1Ckg3L?YKHM~AZiRkNTGxp zf@sN#D#A!3jygI9q>x4`$)uE2TB#S8a)}8hn{3i4r=H6ENhmapLQ1KnK6&a*OfsRW zDod`yN~=h?>MAU;$XevAv(j42Ew<vKt1i3nx@#}J{_0Dx!3skxjl~#q46-jI<ASm* zF2gJ{DWGt|iO-r~LbTCLI}NoWR%`9G*l?h&w*T95+pRYffZJd=3nn-YIpq>K0D%CA z=m#J4l2vwD>%{x#S!kn`c3Ntywf0(Uv;AkfeyC|rm}8cK51NAty0JzXvtjW>0SOdQ z!EZkFFvAP&F=fJXFyv4}4dr$4U4RcPu-yR*Zdb(=S$uI}hS9YVNBhJv<sE~HEb>Qb zswtNsBo}gM$%vYq=*cLf1eZ!HOF9W9ExGK{%P+&cY0RC<1PUlLgHm%%Hk*2L6RD=6 z^C~>E((@}m{roe~L(~$4(6-{53(-UsWt1;R18XBv!wyrdQZd5DR8vkp1r-WWNi{Vz z(n?#k)mB-1wTIYdr8PI)ZtYE14KV2S*Z<@c5Vn8=1ZXBYZ4*~~@x}Y;Ct7ABm%O}w z<e3E+aF2m6A%ZME7r%7Z1<>FE176Ty2*EL@n{n7lr^9_wZ!qA1!x^|>6mv&--G*s| z5x@Lug!o2h(s^c@cQP($zH&K7vZ0SbZbsyhGb(wblc^*r<&(1fWy_airb$eiU$Ob- zoR2E1sH4~fg()|G4w}w7@5J-yq{%{LX|$Rilu$!W4N;0(6r-{Rn5`A2Yl*288Nwz8 zOl4|QmATB>()O8Cp(<5xOAQf%Ft@tR$~G^++irN1s}JmoI1}&{asrnC<`C-$$C_LX zZAcw|_~V8<oSb^T(VmTns~HOE9RGbj$1u^2jzA@1A~;HPAk=vS91}8zJ+>i5+5Jmk zOypwex@aO4AxuRIW7v#d<S=XuuRg^yMlsUi3}+OnhzH@^kvyg(=}k{$%CLy_u9rRS zagSv!3t!A+RzCBY31>rLAN$&ul%@R4Df6=m(Tb)guY|=<`!h@boCdYGNbOKn%Zma3 zqO~?CaDkKpo7f;jHVRtCf}<+csYs(LR(0@$uA!T3L|Ci5=`B~g^4s5Bs2l|_hj0Nn z96fZ%Lue+8anqz`H6a(BW8@-p5P^n#iuk#7xhRPQ6A<k}ggS6|!ydjkM>?bkMcJ7X zVBv5g=}aWXg!#umW#lIsAOB__AicvF;&=x#mbWp4G%rbb1R3=tauJR|X-ZT22t`G5 zC6f#id|iskOk_4Qnw^g)Ia}Y(AlW8K0!>bHs$bFagvtDEl4+lGiylG=7pe`glzYjV zU=p~>uQ|{$5R42gJ0;6m){<?v<Y3%B_^Md_l7zO>+i!xyD_=d}n8`dq0f?0a#933U zW6f4H&1xR?m;)E?k;vxeW5jCsZeimjojehQx^0+4pyf!1Ip8U~(%Dr(^}Jme@fjfA z@w1E$i)$JoMvZNBV;bL}PeF{NP&?i+dJT0b$^J-Dl%<R$-6JGN4T+0a)TDeOJyZG| ziIkK2On!2rpC#`HQ~ymWt&{%yU(^DaQ&L{dQ3zZ^DkbH$pf=_UM3vxVVhO5HiAt#& zbXzW+>I0~Ta5f_>VO4=69KU6Ct1w)q2INr>WSv#L+aYUv-TM#m<f9+b_?G6H5g%_} z44e!TBkl~8#VC^F8`gM7Imq!>)Wr+H4f>*r40~9`E*4#JRb!FFVGVU;!?Ks%SjRNW zkUTQ!p%_`l^*U0~DhZOb8+FN-WHLVTjmZ^>^oeUt+P<E-DJqks?a*wy72Ikv5&8?% zC!bc+0FKgXrtE2P)j$|Em?1G{NG@}m%PA~m8L64MAO@*xnj*Z-RoT@pt){9Q6YedA zef!(5kf}^!9seS%@1?Uf*L!E|RPJ)y6k<2uy5G6#lU=uSqB#}pA#mjN8Qrju6#Io} zfeAK5w<G6a$EeQ;_fB|ftPeG`Q4DL?1CDY;D94`1P!Us)WD-3w%0!}Kma+IH9fdJS zL#oL1-PnEai=Rq)%+i+T>9$`%8d#L}Cr|d)w^E}T0q4NvQ*I5)Kn2^SUg_MUV&+rP zrRCbb+*H*(6;|5iE>%xxRTUD)I9d&y;JSK%09fF>>BV!s?Oktt>?0hma1S3h=S|B3 z`bFa$U0o%8*F>u`8Q*Xxf**A7cTpO5mPRb5_nGP6O}N6+aK<~H!HhR{uGFSZ(jD{Y z&_1#nd;g$y^_5mE>sfd7kgK&BNlW_LlfEydQlVe4xni^+ADe$_;Vsk*HA+%G8`^#m zj4BaB<!VRJsAl8xsMO}|wt+d9;l}Q`eQ9RAp_w=67EYVljZ7GJHO|qwciY__&224X ztwHQ_9X)5CaEepVDVn%}Ag-Wt7(*TA@H_1a|MxAHh~oKd(Zw;&*a~Z`8UnqBK;p>Z z4l4wDCr7zwPdw4kiZ-JybD3#hTocr)b|+-2`63x<QuoRBO+06*Z6N{lJ>^!WX(>9A zncZvxE**i=Rv?ub81=DXo9dx*LYFhhRB(H+>%IKCna_;o-jIDbENmgL1gA`Rzkr5s zC;xx>m!%$dxI!d!|927L3cNu7hwn>#BE+{*j&oG;LWq}igBQ;`$ICP{;<O*B24|>- zYZ!%e5D1Yo5`a535aX;pvIvMO8F5jD&<hEd^PVj!J(!`jnUk^eX{|KDIUM7)o$Ikm z8aDjVJt9jsWxFYy0>0qmsh;|&!Z5xDav&?ylnKhVZ9^OB^0IHUF0LapS)q*)y1q2a z6%rt(UST0O`#xnNoN7QE^UFdl)Q*3^hkB@n`U)3r0=T<ttTLi2f+;MBlOlT<C@b=Y zZJ;Oq0~p049d<b^(ZRSg+B8msD;?<uY`DCU>zK`x9+acN>sf}P-~^WYh*wjYLI3(5 zSreZS6u}WBDP4=LUYos@@-de>nqupd-Q%qoOfni=vPQW<u8Fe4*g;n+D(9-8Ahf#a z%DU(iH|k5m?JBomIw2DHF05L&V@iOu^Qr(?g6MdrEnLQBtelkSx3(H0GSn|KM54V@ zBLAYl!#k%4$*XZ_o&K0Z(*dJ8thC*+I6a&ZJ{%tUkRx%xhGa+{L3F@`g1`t2na&Cq zlMx1SXa!Sv22+>@WhjP5gv6I)i9!OCT0^7}biJE{t(=p+UlSTnyriJht=%F;qx(Ib z+No5Gwx&C-<Fl0Iy0#w#LJJx~tYfOJJ3_CMDkjvMU)&Wo%c`>rmMSa&0sp{;WMoEW zi7%gw9Q6PP^<%5Ln?`|)zr*69IINv;kRmFwB5|a{FB+Kn!zTbtN652}$Fdk{NC##x z28t0xgd#*#dx*}05{VLqbC?D<>IP$ghGHlNVVKLg1O~hO1-$%)T#&?Gh=~@HIge7k zTl0xU!Ws3^HI$kyN(#1N%On>Zi$f?fn({rIQnDJfL6Drbr)!`GO1_g^J|Vn1Te8KL zls*uuKCm;l?0Z7+ibBA_$*w8@=a4gc*p{G77H6q5-b@^BkvsPYm!o{E_scuIlfOH( zrzR2+dV)iCn1*L~!$_OTE+P<f#6xrpz<$!W3cDC;fTK2aqk%XmI{z}udt?$m;-hH% zn9V{4TA&4JAO%avg;9_N_k2(MRE77{PyY0XU2r+l!UbX&%ovj~8XGBxd`O<*wM~SI zPOL5a!M(01Hr?u<rtzPRyv$Sd$l=nOX<MM65-QOAL0L>m(p)OH;h=EC#aPkB)$GOA zysGdLM(_K+0$3&zkcVUGO&-OT++>!1NWWhQ&L!z4q&y;iLPO;Qqky?0b(n?;Nwld< zJpYoogTYF4Y#0e!$A9WH?}Q_P5(frco;os5XgJDlLWcWvPxsV?T$q`fPz7!<25Yc} zc7O+WK!<kNQ+U`@cW{S0<<oYs26z|;YgmP6U<KF;3Rh4CRsRqLT5wcH)rHf$i5WAW z105+$EU6P@&=jP|`iW2p4MkCuOr{YO05Zjn^hm7POa=0qk>o+<^1)crHZB`YrLsj8 zMNK4hQC<|g7%e;4WVd!JMq`8ow)@fZ$RTA_mU@teS9rDe7|spD5xKHP<iy4_?4pP> z2f_0z>a0pI8Z<G=%5)5#t&BX+!3NgR1_q=@`G6jBfd(I;1vRAwVbBG-G}J!5Q)@_u zQ5Xe4kb^l8ghV)mQJ4mJfQNZ#SaoPvh>ci@ori}VhgC3zx8Mso0E9Yl1Y<~rJxvC9 zFotO;3Q!;gR*+OlWd#JaIi2Cuh-^>?1ywt-$O(<9vj4D9jZ9SyT~(zMJ`a7>DGSlh zgvAN+lpsW#Zd)5&WtG)<s$P|<?m9QVDJJo%QFl84tqlMZc$Q{0j~wbzv7Hw6hzGu0 zzl><B_#jSeg+FY)O1@*Fa)PHsONX|!kU1<z|9h}=Y`hlHLw};M?)1ty5(mMnn1Uc8 zj*|u<sRm>K7j95kc=%UGr~^P)1csGZbvOqGT&QL^hW8W(e2vu5C0$32RQ{CIT{wna za1Te^g@;{O*|i3{Py;zg1yiuoWH?k_P@k10ir2%r9819mbxa^5RiT?qL5V>bl#4@g zHsR{fkTeX%AX;lP$+D@STUALWD9sHLvm=aJCI18_VD*ivU7^@SJMg<vZJ4vMtux1g zoUiQ;-0X*MP(QSti2L%hKf^n>Rm%CZLv96!=G+E*7=?3av~Bo1aUEAXEZ6KjSATLW zb;THI(1vRuFpevd1N0GOPzG^$hC($4V}J`norlcD265mxA;C{ta0Y!`xy%VI49q}b z(58>j1s(pt(^FX=b_v$G(>^tYR7iu{HHKtJhE?cYQV0b{4TZ!!+1UG3U^8Ca<C9V) z3k!9cBg;_d_1OaYNLK|>qJ72YB2n$-wkA-U=Yu|{UD4@lQK@B3^IbEm1)LW$R$_sI z@tfc4_>S-x4?m{ge>jHA$zQeQ-)~Av0ROf$D=i&*%Byp*26G?>0D(9M*2XKPICDMM zj9W(>v6yz0qvBbGX|M+$F~AW1MnWJ2W9Wv3rPx4(BQ~W43LKe>$Yqt25*zjiZTe*$ z4rVt^NSJ5|RmcTZ04Y~U*+*U3npjvsH3m9RgE_$6+(imi2n9|c1y10EO^`^H>Nz_R z)t5rvW1FeU<XHh)RpDyYM+w^Fg1T0+vMcM9qcYJoCPLGEV_x+-UnO4?8oQZfvo>>~ zVr7om6aWQahdv(U>j>NT9b5Esg<ja6v{l<Waz92MxNF2G0d^N~AO~#_OH0P&M<yq} z<z!6rWObww0xZB$E)pMULvgr<<Npx^J+OvxSlDwYC}&Vp$90G^g&t*?o+Z)cT>hhz z0X>xY<r{u#U=AN1CQ#L~wVJt^WmZ{KP*gl^2X}yjGoS-gFa=}i1XS2&Zsvrj*s-<F z1RwjcE5=!~$Ve^*rJGvky2wm-W;#d_S}LnDdWNOtQ)5!;Uhl204suC<o?|*5=wM9W z@6*~Fg*Q@g--zx_hvtrch=x}H25A*eaWPW11t;S?PLFmldjb%9c!ubNLn>`xl)g@F z#ZJFvX>{#UcKngcN~3HL2VxipSTKfF;Ax-!X^vY4X_(iBScWrY?xGf#hr(q)Dj5{B z;gk5~To~qIHa)=<6RW=J8vkn~qF`oK*ycX{Q#wfRIxvM*u!N)NW=`n26?Ca`j?AU$ zBrfjaW$W2fj9yjr>*{T#lEmKU+TNw@UJX)}Rap(x<fW)$Y#99w*TjGsg=}I(fEzVN zC+Nw{?r`&{oL)HO%u&zw(`eFGEP`9g*!G5ZxEFW2<k<e`k6t_ou5H`CZ3^bJjM)bL zxCUa#1VLzrd2ok$fTJ{WhGtmY<d%m0mDi!B2t67xL^Ls`cHNJ_oFN_3T)>=`2<Dgh zz`-0JM9Nh3dA&yx3P&Y{M&N|=b_ewi*j0e<MhI2<#vi0PXXPbD{oZfjO1huj>vzUM z<SOF`s^@G=N$y2aT>nb!27gHi2UZCurV1xkv@=$nT<C`Oa81XKv~q<lN952JZ4=*U zj?Pw!8<+#}#&ICL1zz9=CdZVf@fFF^#Zs&R?86-ghifQ?NI--;rPv=4%XppFC3o`s zI`*MP%P1eQjo9U-w&9HGp6vGWF9$)?D^Q&fDTh=OojJkx-sbWEoj_v0&ICyK({_M` zz#xQC$b?U@giM%(NBB9QgG^(?NEqC6KF=w=7Gu69zOMP}DjU)4-LlanP48XwxZyfp z%0;{RRY-U2JErttv2=Jtg=F3I>9}mnzW8XMXw1nR{ast)gsaAi5i>IF(+(qpiNle$ zq9uxPm*?A*|36yyWXAvMQfjyl08s`~(1SZ22X#oJZ73dIs3K$_5`%DZkJ(=lLrW*g zh+VGo42<?j%moh&%$caQ?*{Ldbv>hi*){q09Rmed(B?+424h$UH>U$YKm<tWggS|Y zcW=RYuh8YS_d?;wyw>aC8opH=bkCH!soS#XQd$f;Yz1fZU2^a;d(jAYc=UyM!Lf8= zX@X?L_>8xB`H}~jsOaGQctv)<;{4x6Uc3T<!_{tWS8p%@j(J&Uyp>*<($+NGzIkj2 z2Wi-aM(9(9{f}?J27?#~fhvY~fFmY%a$^rMibzk-`z&Z5Ez<JKFXv$}nTgc0>KSWD z5`0MEb)QY}W~cw?gg9aMOaKK`=mbbWgg=FaWLN`1a0GUr1Y*Ntdf#HZSJk{{RY2!^ z&YUvj19*VQlI03PDF&rLN$8{r!zN6YEKwry2*n~6iC`oW#7B>gJ#c`;QDfxD7baPt zM44ix2@@npe9)i)g9Qr{9^h=CQvuHe2o4koT0npTcKz_>OR97!)22?JLX9eQD%Gl1 zuP(*c&zvh<zk&%nCU)7fX3d~MizaQYG-__CRf`)J8{KSn@8Z?AE!(!fe*XgA_HCQD zcc#*%>kDo$W5JFaHx4X$vR=NH@nX)5nJ(vQ*yMWthK!aqYwhM8t42<nG-qtxRui{M zTr_8{(L(=|hC3}<v%Z^=4K7^SGG)h%i%p(9tgz<Jn+J;?4A^vFz<&Mer9Bt-?zwP* z$2Cj*tn#nSze=y(6?^umT)jsn9~CM3_Un_%PYM*MPyRn`5}<&Y5NL@dkxXJqE3(Mq z2q5hw1B*Ln^pOaHkT~MVA{%nJ2qK4oc!(e)3Id3UCjz2}ih9(+VjVBe5u=Q9&`2X3 zH{u9K8#}JCh8jPnk%k#&kWr)<M}CoHl3Xy!g+K%qWKcp1E#%Nc5lvLlMHmIKkw+nk zBvMH=oRks^E2Yp<2{6e-lTA21pi=`pDc}=OLLCr*EB(-em7jkC8mORy=F?9!uH-^p zSjYd7Wfod$v9;D)pmC;IUVC9WSzzXj(~UWUX&S1inpTFXrKjS>nW~?~wbwD6z|&4Q z;-sSuHm<ex8a2*fGmbUdP{USQ(d0%fvA_K$oU&vcr<}9QJr}KX)me9)cD;D_U3lV= zSKch@f$K_o?YRdZeDmdZUw-_t%O8LO4wwlhm>6i_B#}Jw$Rv-fvI-=6w6hK@$*fV~ zBam!}h=(7BNFs_TuBhUR6U#VbjW*_}Bac4*s78=!6lo-qN`BF#Km$Q}5JFHm(K16< zVo8yfMP#%QM;+nt5lAGFY0?X3p2?C4Yksi7Of}sUr<`;qV5d+B1i%HK{t#NV)mQ&x z4OKt#;POf?U>y@yaE_)Gsic$6RTrwI@-^x<;b>!wJ&L(qH)W>cjjG<Oeuj-U-q6yG zG1kl@&NsHY2AAT&z9!Bnw5b)1<dW~!8?ws=M_h5uI=fuh(LyK8wANvV-FDe(3*LC% zdb{4ZuaFy`x$~(@pMLwb+aJ7}5J+#m2~GlhB=|a#?<%c~0!T6u!ZJrAeLS)-B7%VE z@WUoX+~UM_R2<{Qa%7C-#vOYcWXNKW@r4*9H|gY)DIY{-l}tP&krFZ=VG+$-`f#(( zA@R&-KQj}W)C3cwX#i<CSz1q=7L)@B-~mQKO4cf9!3$bNE9O82E_wlsMIHZRY-cH3 zq}~D-xu{BSY|9j2K(!5fJmVSm@J3%C^Oze(#%(LK%wF_{D!zqg8=~;lG}J+kZ&V|3 zun899)?%A?5W^VnK!$53M=abRD_NK;jxvmcoX&+UjGz;p=%{s_?3^xJ+v--=&;zb< zk!yD6k`I2=rJr`aYj?bpm+yiXyx{>75`uh$BJyR7Rg9tz?tld>QlW=FG$Ij%nB*j{ zhrR5%2u2l?!yGOaK8>}3W91VPk<ORC^)1O{?~BsPSXL#6K*WCd(_hW{cQY{YtY>9P zNdbq(CYdNuX*+4)PlQr{JmF$$7{s7IsJ6^yYDF4|>IK-w(x?$aN>~3UL}8_{u{OL- zW-x^@24ZMPLmQ&gF?QQw4}F-b&8Vsx+o%R9;9-q!yyI|d0gVYu7%XRKqZQ0}hi%qE zx!q*ZH(TT)=fKFE&q=F{W;ES)aN(V8t*$(6d}FxcI7iym@pkKSR~`eD36svtcb53$ z@a`qZmtv@R87iJJjA05oxWgS~Fhw6KM9C68EMhFmB=@@az3}ZQl%o9DkU~a=BcU>t zOgb5qt`I*eHRMXNlo>7g*FT)$k|Y8IS}%##reMlxPIN-RPwrFzsAYjq&%B^M^fA{9 zB848oK-338D8ff&vn?j1RHeSjLmmdE9MkAVIrL(;y0P=H?#%xT-{>MwZ1}<&(>TXF z=IM;Mz$I61F`Ho5@{Ux9gBp=LC>9gCP_lUOi=BfO=)f|%YEcwhYFuMR-S|e2eiU8z zvE6=f*B}3w6kdF+m%RWPNSMY{Lm7f(hHRP&It&aBeJDg9Dj8IX5j93d^`4Eum$C5y ziK(T0>M7Yb)m5@`N-ldDL}JF({dx6EVJ(Tz$SO3m0@Ef*V_==^<W>kuP?>kVT3r`h zL9MXE6|?wSbCUDdVfhnneJiYC^VULa$PF8PaqMFy6IoMD_Ef8?hBw5K*}|ox8pvRk z;;Lc7ChCe;-FOBzipAPvB@{SYB#sxsC>GjAbXwIZ-L?Nv$J=hTj-#-PV|+k5T#>Tt zKP5#ebM196=SBjij)?9|5uq?d^b``KFh(jO^oL~VfeqfhBvCav-lHOwM;-eZDbEMh zsFuuqD1%=s=L^eN-fw0Z(a2Z93P7>;mw-ZhNlXGffdLP*z-={Vo^l~q2Mekm^+-yC zL47r?WP^hgUX<p_f=$v6mYW=QXQ}>z4SV=v8gnZ#sXTm{6kCdK&S>!}2=|V3AOjiM zV3mz;jAPP91H{}=trZdK+Shimp|gc(L?s#>(xFke7sV))ecMqg2REd*%N=sJya`Om ztII5Pu9(T(p+zJD5rp_qPivZrKQwX<dJu#jOw|9Pp>EHpovhI(liH*73dyNYMN(8% zIcTe1wPo|G-&XUtrTjX2XOP~dN+$iw1PXY8YSr`s-1^o4Na53_{?k78G4lua;}{&I zW`!9wwnxD_)*DvaWLG%PaUzC=ydJTyQ4DN&erDM$4ydt_jf`#3ST2Hn3uz-Ij%%2L zpw2LswXeO<A{!aW&#~=oOBe3ls!nyR`<9e}TV-^Gl(@z{t{!=((v|uV%wZPuOr^Ua z4dFWxAey9#%)Gom_~8#c1+Vrfwn>IJ9KEAlugFLyRjL*Q<MM67#<6t2M0XYB{}cJh z{hKCVRvP7(hEt~N#MV0jB~K-gM?ENbb3p%<`uBp`TGw*%m7ce{EPxF<Y-CMzU^_M& z-q>+tm+qGnKV8Ku-i9`Kk&MD2@#>#B;o|z)b+_0i9l4&OGltdLEWQ@D+I|+d*AAVw zQ`E`ip1ZllW%uA-8F8_jyAeq5FjwG#S-lnBy(P>c5Q2z|$RPj%A@qSBtXV3+f*+)U zz=c=$EF9+L*~38`=RuX{wGVu$jC{?PR&`wJF`EB?iJ0&g$py{p0hpW2o-omg?X_I) zJx~A~gMtYkRy5NP28ssl+%NQ%SR@}d1=iVYQ`*ehU3imWX+t_lQD4|a(;XHU_E0<R zO%(>)id6$R978g|!#UW4j9C_FEs_7TbsbyShU1)rIM_zz1euUw+x&UX7)i^w;nv&1 z9Y*orZ?VFZ#SZPz(Usj19uXkC{T<*59^pk-hbYX#9Kwf?2vF$(A*jeCwF4~V0W81) zA#e}H6cs0dV2(JP2$oM%`5B-EnxIvc6kGum6xs?RTB6O&{@4r*?w2kNP|5w*$srA< zty}`|pvytc9LSszQbk=AAvF4lRzyP*E}_p|6NZ^htVv-CQI-#-!!_udJU!M5u}zAJ z;TXnK8CJtISc4jlhOICgXf+!g#^FA3gE1tL`&kbB#UDe-mU8%E=qOpWoKcevqTChY zdJw}bc$6Xv7k*$_mLb>f@X`O@%^SVFRN-ZaC1Ro`ZXzIXVv4j#9~cAk?39dX()XAb zD{7v4IaLWN$qAz1Rk>1D?cywb+%M|a&dA_cNty|y38l$|>>;CCHI0FBS^$_pJoE!K zUPbUpWmWtGJ^({kco10l)n82x^P$i;KA#FnojsVsIV46GswFrvoi=2jI|0%3C4)M2 z*41ePKQ-GunjiD+$~N3nkFi#e1>`au$3PNf{nZvAf?K$W8+U}qc$AxONf<8d!5*+e zL@Ht(>0KlKN8jzyym*=54Npgs8RBt>nKg{{SdzrV2qBmPBXt2Cw4_U(S1ayWkia5) zsgHXJ+MwB@l*rG^ups|0dK`Y)j7O|qE(s+u5~WL!00QA)QtqGv+@8w?MKcItRcdF| zK-hWYLN6R&S2haJJ>k}YhFFf}sc3^+dIL9DL-oniTFR%>y`}cW6Zd775qU;EE{<N_ zSUySvq(H-2QUh<4ok9g<VH%kj6{NQzB$K6)V?HLgG$icIf+nzm8@NFr?81AvM`qdw zeSpGyv_f%_lxOx1Xx_`0O=3qbV8SE}YC>R%0M#X>$cnTG2hKq<#6slB0r%ipZ7S7m z_L-5Sj|sll#r<Y3>ZIxMqW&0XqlKJuMjA2N;By}3F{+$W+TNx;O#nC}J^aIVk}08R z#Ws)vco-j7TG;>34a*aHW7_QJ6z&Z<7=sbHB^aidp4O*kv?DkuLn<&<-`FGhIoq>! zo#eDeGrYqyOv5`ggENd!9tLEQ876}k<UuZGgm%aN%^gS00wcshG2nt0Xu`Pwpt`9- zAFzQabV4WWM`vOrBw7N!ylN+~C`V#QX~L+65W*s)=7^jKAyAJeridpFm3XO0C}toW z)B*UsWNr2c#|TN08mZ^aqWjb$POji^K56P5XUNIm3=U%rzMfH9nshQvbv7jn*j$;y z>+lIfSA6F$I7geh8eqXG+MMT{(y5<TLpl_L+*CuK8mtf9r#d8q8h(~%MB$-w9e_s4 z9F9UU&_@6J0U1E<A==TOA4-R}Q456X--K4EdR(X$?1Cm}0VBM^-C0?Fv_dC%!OVI= zCs<_P6(DG4f+Wa68%Tm^65dR4h$FD79y~&@jtC(DLLtb35img;6oQFN!4$}Wi-;GE zumSV<!5MVYCuxi;%496^CM^=$%4nQ$?&7!hq?E=Wm69BqoGX^5>z3}IPk8AA2|xp| zL+{1wQ~bl<0&d_6?%)z`;TrDY9&Vv<O;>b~qKKz&yeVHs;d!o#4^;yUp(URl?B=#( zI;=uFsKYkQSijzwUP>%!xrRCzgE)vor2gaOY%Cuh8DjpSbS$PIj@x5uRFu7ueC$FX z#KHd-gn}r@N2=0CE3|?rXu=fSLNCNwDcq{NeP$+DLMK2161;&GSivMfLYR%FAdQ(v z9^M)xfg9)mA57AWCM_ZCfex?%8wf!h?7<XZuMx0;<#o?Z!9pyo0USi@*Mco6trz+r zsVY?!#xW^<?c{xJNtdu~FbbojnH&NkCEYfV-CAd!2m_xWZU=kt2ZM0mI)w&F*o19m z&xO!6oyAvnW1M=1^R1(1$kRI*!+OT>=5lUlfP=3f#(t76#3HK1M%y#^0yc~gGzccP zajZkp?%LsBZjEf*eJZG0Xno8=m8IJvDz6Y|0xOuo9%w@J;%vN4LMZfs7Knl<XhHuS zRKiOQ9{7syBFwKOgaR9A!6H21CJMqN^}!VEK_zH`7W9D-^pqW&;v9?@dC9>|#R4p- zf&Yrnkfzs=kl@Hj)qB<AEf!is9Gd;8ZIt@Y>Wymz^HMLp1O;oUFePKt+-*=mjUzmx z2+Q(Q7z!zj$9Fm|zCtdB?W+q9U3y{$i%r8c)XK8i#SP;yTmn(R8bdiM+Ydvm5JSpW zrp29J5v4ZDkS%e?X6h3&W)zc0xk(uuO_|FE;JToKAq4LmghD91>KLo&Bve8pOhF(7 z!W8sD8$(xVW{AG2Y&{1uBoOOJdSW23!4wF=6v%HIOaU9%uhklrjm&}m!ovR-L~;OI zD**$VO)6=|y;3K4Tyb)VPfn@ZmMh%)lH69XDl-i$_h3^V!BNceOgqIt&;u?^X5-$g zHMyD-o?q$qYh?j!I*3CS{#r6WU1hP#HYCG1kV8G%m|OsH5J!rl254<SgE$bwY(Rsg zB5|_l;j(DXHa|;)-k<HB5o3y52lWEU_LjM=2WGx(?X&_bghC^@f|kKEb3sBUxPccS zfg7v>A-Gh~eq@X;LJ}ka8yLbQjpT_u(j34+!M#Wl@PHP?!6|y+#k7I{(gAkC0vW7< zo<Us1nbL07q{VG(F20htGB7BANpc2Im6~fyoN|_?97|ttTe%#9$wU8C(sXd=1B8jo zEi2(pYvV4nu%v8V^98j~Q(-o!Mln1?Iv6ujtD{oC@a3+8uANZU`R9M0u0c)C6B)xZ zOwlsD?qFIf6Pq>2DyGPGsxY){G3@RX*Ih&!FGb$YCx8Me`1eKXQHuJ`@NhyqSHky_ zrbn9QhDbsnC_*6&v}z73!3|YURiJo9ba_FtjWALf&;cBzff}sA88DS8(PXxQ9-)oi z{M1*LFmTO;t0<ea>%}c9=XP4P^z9iF-XefDWM`R5qchF4R(t~}oQFjnHwp^}<XTZL z`!ag2<7Z&uHKaq-VK>4mbsHA!G>pSHh(o`I_g==KqOMkXH-rD<Ttn+3!&zui{Kb}X z$d=mG?ro(t8fD8QctH{j!Y!0Aesk3SNu;{18-K*A^ycgVa__EouL8d4X-atd>hWr3 z4=N_|2d<)ycy=n}!58evkC?b=U+YFEDatJACcF3o7bhqK<D-pSxz_fYsB|jp_`0^T zD+d56#PW95+>i(N-v$FIB>9@6a0;uizDh2?Qtp<Qp*mPYt$0(kXF1euc^gVYIy{5i z*hbb(^?0+zlV4Fa2o5&%G=jo;vs@~jC#LO&Z0U4|F6aVy+=3RALMg<7CgeiNo|}Hp zHGemvyLjej${W2s*RIB~B{IyUQ+lQ2ulHcO*ZRn3$3p)sh(U>)cy3Ny0h4X$0jENs zt&{R3Z2u(d%^=X!wsYcm4%WJ+-TKS5L6F1iG|u$a$cJ|(3Y+3<xxXotyD(u@7K?QQ zH;{ukVBI?*b+wZrT{y!ws4h|SXH-Y?ct1HpQG+p@Lo~Sgn`6#cqq}>XwUV`a{&mMJ z5Q8YN!7wyKAPhn=oCoWSv!H)e-iefP2{=X)`0wbdVK?|`%4qcn>%t>k!fiOl2&o#h zfhqh!BbUJ%fQ+bH@+GghRf!%}DX=HMwpYQRY`30`8xVBTI)Slr%jXFT&;xM8Yt1Ev z%*!$o7Iz1QXBc&n2p#cqXBbdRp})4FHi$#mg=7CRBmK{_itf*4Hf)oj9;&xrb+vVM znkz%tIf~Y6b9>L$dmp3{-nl|@$AsMiV;h1b_&K2e7P^@;q3_*s)%}2g=I?A|!5h5L zG9bhF{ogNq<q7`f5x$W6h-m*CBXPkQ00bE`WXOmyDCSGTFI*UM$@1_@#4A!JLb2!s zW0NLKm@HYM1f-H9Ba4(QLWD>VA1iyb#PRZF4Vf}u)O^7LXU-HmQ<yM8g2V<58ZcO} zFk!-j2Mw4uQ1Dbi0t5&SR4s7z>Hz@?*ww?A4{TVmW672^dloI&ef!e3b^8`BSbY7c zZF==;R<2&Zf(a9L?5{Gx%Lq3!3=MI#Xwv@_OLOd)T4c$Qt5vpK4O?Ywn=7Z|Hq9Qg zYTK}7E1eB>YSpV*r{4S;cI?crEoXL?&KGEB&Z<$K{QGfm;fx(CHm(?PGiTy_`FeNE z*)qe130Jo+Snx4r+K+Yj?%i*A@xuE04HgU-uwTE_um9BxelGd*aqT+Brq3=`vu5G# ze;2?2T^W!-R9ry?!30quWx)kWc@Pv*K$-B93P0Hd!%Q^XBoj<9u>{0PM2v*Q5=n#v zMMxZ3k;O$^d=U{u4w+Gq8fydu#~k(8k;gjpr~^nK=NOVmIgB(CjwF>#vW+I&SYr(} z&N$-_Kk|TuATbI;NTG!qdI%zkD6;?PA}2Iz!XuAD5{aaeP(n#1A6n`G2RdV#sRo;F z%83P@dh!V<p@uRFDW#fn>Zt^zqUr#w94#OKVfvvbu1YN>Yb~(!(dW`mJq_z0e1ak6 zuDtdt4>0YNv2HrVpfQfP;C`FzvRX0AESq$uIVT-lO=}HU)?^!&Gg~v$tg>y?nI;`^ zDx;>iS%;gpxZ;jOE-`125yup6#90OzWvH``T*9_H_q%if8;@P`&O@&~_uz|fKKXFD zcb4?{!-c;9{e6YNfDIftK?V(e5a9_Gwh+UHGwcw=5GOIw#1v6vam5!kmT|^IY!oEN zka6Vk#~*_v66GW1fMew);c)*F$|%)HW9BuIi6xIe)cE3{E*o+v%!nwGLJBf7+9=JB zKpN=?lio}z&N*Sab0$6c?2{*-ehO+R4G2wYsivTcYO1OleH4KJ5SjF=Pu*^7(@o!= z`>jb`A$1m9^h(dKR0pfB)x;X3c2;O@t*tU|)G<aIakkOSG-4&6T((+gvsIdEv@u2< zY@q#IT55$`%-Z8zO|BVfx-kZuYgQe%TyoJ>x4XaE4X?a+;f;5_dF!Q*Uw&2LkNAHD z40u3-6*SmEge6oMlnNboSi=t`o|xhjQ^eR2ja`hfV~;()QRI<#^fAbjQ&zcUmzjK0 z4K-w@Ss*oFiNy~(5<>ro%b&rNXd)9S8Whab1T%3&O(9{L)7}&Wl}OD_RHKPauI4A7 zlmI9n=-Sr|B{rxm$|{d4K-!wnkG9bbg=E>(KUmm87rqdNF_hs9X&A$~umcpRz>D5` z0Sr_HW>u_e)p0~uxWm<I8`e+<X)qHx$~|#dm^tF%c#{rh7{eagDx73QN3Cl`<8;uN z4mOO@jp#(D8L_L*U}i_VRNc-zx`UT{<V7#w-79$fBHn+Dhr9wEXn74f7=)k~z3DYf zLmjf7#IhF&i>U}>-s4#KK2|;*ozG<IL)jcu<~}9CEPkP+nHmW4hd;m~4_qk2Ld4Jo zSAHpI0wh|QGSdH%1TL*jCutx{q&77?>1j_o*@@OL$TgyHFl<cuAP7a66#+az9$u;8 zG^tt5X{HdHW0{LNKH-WT?hRGm2_oPEN5p9v(OAc778ZHK87RK<SW}c|HEv^yb2zIv z)sO~ox;U+Cg%NepxP~dz;f%w;u3X&NjvL>&u6D_BcXXUrFMgK`JmO1_do<o%{CJ?` z1(JCQd!B?YbjS>O$P$Yb5%wr%G46Fwl9T)x$Sg@R^rdf;a^U2VJP9+I%`6RO2r3!U zkcKmefewGjLmm|J%7$Da3jmbm00~$?G~JR-O>@(mRw5^tObrKk$`b|oG|WF`P$(EE z3R1v!sImWn@NCT#z&9r4k8Iu*ui2zWKd_MrZ{`i0efti%0{1F&3TKOkLtHhGk&b6L zhp|qCC*>A9&st?p9oEQ3KKD79em;hDjQQf}nt{4^_~IGw0M|00p~hukN1+V0okQ6r z$Mi^aq7<#yMKQWZKKiSpe^ihlokvLMNzbI!L#ZWJ+R{ftGGpFzQTWD3zVg{LlbRe7 z``YKSCP7J*K@I9a2114}kfBOd_=A_a;1DiA6@WyWrP0oGRi)ultGY}{S0M<K8iaL% zWEJM0w)TOv8s#W$^<bjP7Q#mzAON43R9-1uVYl_;7~TA44}B=u?u=79g+1(Wws^#J zjDr7Hnu%v@kY!mHAMta&aRxZLF^$GKgP)%r-9JfN+GZf*81LwoIF8}k>Zod=vV9{Q zb(bFAO|+sGy(sZ;;h&8H40!_s<ZvI<yh29LLM1(<B2~)Lin+8!lKdXWDrreTU^jhr z*yK)m>OLnu>8C{<FG2WhUY@1G4pAsW7p~x5_=-usMk^o_uDT|s<yXJ_bx8!pYPAYx zZEJ$^8ZzDb!3M|GQE6Mlge_cZQ@7<G^uPrv{>sA+d$>D7EGMi8S7KYeBN@%Q+>3er z;#q0N7~IgtK0B*pFB&I|he?if&S8pgAyjtRNwOPf3rBaI$I0!<t!{Ta<%||@qaFWM z-hmk8pynBuLJXUpa?9LON1{2B(w$^=X(}?3l`PJ3&S@vTd*`3Vuc+niGeH*8g)+dx z4q+(6LmVPi`BK%YNV{)VO|n%YNIHTN9BWN3Jxo9ubJJ|?pfaH{6-I#?D-f;$J^pcO zw^<YBF{fre`XLVn{Z&4D0Y-RI^<l!!dT_O-m16a|jT%4haFSCov7~5OBT_>e&Ugp6 z-m#l#89O*%1S4sa)7msrV;a+-hI9aDE_20}p-X;f9N%@@I@<A$c=T<*u8d_rBFGi9 z=tL*(*5%?pFU(?IH^d^wTr)%B-P?n1bT`(qnb!2pJ<6`Wi$rH6b+-*K!*l;AfjU$^ zYsnx9;ldP7X$M$j0Sj1=sw@?KCR<K?fehTQSHJ4tUkVr}7BoRI1yvMeCUcpeZst`G z(3N`RL*~g>ehXdhsT*2iKzPYHUwHl(pUb+mh7I~TfAcJ&b50w*7C(#=YnkP6V-!`_ zC)BYn+R*|Ob!kka61~o<*Peaa)TZt2n(V`P`7X+MYwqYS-0qItSiu-l!5F3iVb1Ni z)NRa`D`G~ZL{LO~RAljBDyC?}M%*m&Fe%^WjNk0cr^3q&PVfY?#Jsq~AhO^K5H1YD zfD2SFzNo6IT(2Y6gyLi`YI@1`ss{J4#^W%^z=p#2L@t>S<ta?gY=-|2!jys3nokN# z4Ik<O95z9R_C+tKkLSb*#HK^p4C}Lo?&{K^7>wZ^C}aG@FR=>88Kl9nrlIP112RM> zwA{~hdQ91-V;RK370~c+<S&iZsEyR6+N`br-0nR9u-oMB+X%3a#0^1Mff-gI6`tW4 zOab}^>3J5$q&UPwG^Fq-umTb9k+?^?zQ^%8(BAItrf_QCMzG)DC%pFT^ZYC!+KVB+ zpbYXL7NFq0qH3zj#P!m|(PD3_9Eg`PPJ)1`taOhEd++x;jloV1<%ll;^k7n2ZVJ0G zulA}LFd_N?>r}+!JN~9HL~Q$nj#jkA9(<u2-hrOtX$|G64HN%sH_~Ah;&C@3qy6v@ zpukWdf$SZO;TgWAFruvx4N>j*ukD=d?S4mZq|6cLuI_>hK|+BPh+!4zfEc*J6uN~I z66VVUZ{0$%-Ad6EG4Q2Q5qvn16<ZMmwQIX94@pRH^J*~#RWS6r#FeHX3;e(j@E{hZ zU<!n0zHV?MUhfzoZI_l2tSZgY225+v$_S@%!4&1wu5p9{01Bee8^bb%S`HXCVI1!z z7ucgbtWTVNE)2DA9TAIG7)!{`K^{dTpX$+8?y(K^={80o9-~g5x@a-94*moZ442^; zkU<?x;Tni6b`~l-l+4<2=OGnw5$#1Hy=`AKDiQ_8qwxQ3L0n-J=pY$PffvqALORiq zl1l=wCwop2x;6$zWGW^@Mh`v^-)OQ(ZjxnY5xjI#;6RT{6rv&8tI$wM;T}%WoZty0 z?!F$)Dd7a;qVo2F5YvjO2sbUklp+a(&l;Oa<@V}?#L_JM!LH1+E&3rI?&d6ULFd*o zT|g`yvrlmDu#0{p8!`(VGACO25<mmA4Wmx#_HhmeGwZ6Qbn?(u5EC(#K^n$k8pHt| z@9(wHj&^LPGOrEWFq08Cv$rg=06|k=5~LMSBsGhxBu(;R7AZs`!OT>WCDTma*sRU2 zOY-7O1a)d<y6b&PP$&CLOL(SByrdzpU<$e*4DA0P53(T9Xh|bFA_te?2&fbp^(#(j z&pNAS<2vqwtkU<obL8F%uDG%QwBiA}qCC}eEYOop(c*?a!9ZF~Z`88-ywEMfaK!R6 zGLlFg26N~HR8a5nF(M-$0rM`2ZFKOE$Mn!a<*yGpr#lAmIzEgtne03`v_o-=+Zu7o z2JkaMQ+WzzU^o%oAdq?pZvtcV0%w%*HgFX^P&Z#uNOsgWm*mc95#aPp;I@Q+jPqx( zAgY8Fm8zf&EJ6yNfEYPK3929pqJU}GqzLj0PLxqged#)bDfhAyOcAV5#?;fca`*~B z0Lr1R-jpod6kW?=n=oNczbP$Wt>@Y@Pw)RTE<X#!JZDh%bwEjs8uAgf-T@it@Yw!o z>*DWG4dWP^K^)Fd9e`{Q|7Ic6MMF2V?XZng1CTTG#xp}zxVCJ0n8yJZ22~O1L&}U* zU25@CaS>u<-mFU|XA&0Ir_Orny8y29dev8p^k*7QXtJOe6YdJg#3GjRS<xU5svr-J zAgidgTA^}F158_m@K3Z;P`p*aNUj>gQ#=Cz8qO76GbJD7W?ji*F0vsL-W9L{s|)EB z`|R_JKI=BPVHFOPU+<QSYAqk10S$K}LA4HB95rF5;~1Dj4v%3NBz7{>u3{1KGXL*G z<1Tmx@V5XYxI%Nd%uSFYge23=BoqJXWLK3{6VFvOaARJQ-rUR;Cr<?F%#$<^&*n$G zc2Wh26j&JoOoUN@tOO1GfFq#b37nH7j@A#*pbD5^2Q4m3eNf|GV63i&YI{OEuM#Vj zkZi=YnbJlOz>-bHR$a?hEau`E+*OC*wTIpX*0dvb3JWgrvryS@H{M|yxItifgHZ7{ z$M`hr#6cX=FY1N^a1V2E6LK*d^D+P8Iu=*|5RvV62XZ5qw<h-y1>|@Pa8w0}xKz}0 zlS@@$)447t16`83ZZu|hlQ-Gtb%7M9go<`|)@NWTXs|#E!r%(>AmN?>hZpT=kv0#C zKqRJB_GZtk>I7SXkmEY;tTO+IdXW(L!j)@9C~c%*8^ISWzL$z=E*@q<PS0}sGPQ5m zl0NGbZncj4cB6m!m;E4Pi{6)C+s{y?fq$LNZ$Zm26XR7H^ihRqF;_<%u0b(hOWG)N z|Gro}Y)cWL3`8q(g0JjyN44Di&Uq%J6HB&5U9`Dk6W(66HYw>ganlt;kY;PP--0t| zTiAs~4~FAQfS$lgjvx#;;yDrMS)DZsrj;bL>S=nAPBKm^kN6pTq9?5Km=Y{&l~60q zrU|n*0D=H)-_(24^NQ!f=5mOOx6q4WEsR5Kh_-ITNC)a7LmO6S8^#cS{}HkFNgKj$ zoU5gM1?P?t7BNGNT&Vw{jH2Pl6e|C|;}F+QQ|G965ZP1nh-1NxqXMR&F%qN@L`7MX zk~xIkR@J#kH-zPFgkd&jX_Y3qD}`fMIEQluc@}qL3DKTF3i1FAlJyA?D1oFim!5J? znDM`|6^W~o1h(@C!R9*?MJkZl!5%CCQa~Q|VNK1m9*!>`tQdUT_2ycwi?4Y;vss$~ zDsF{C9JFB^#$g+fp$^TNtKB#nsv)y(tbGqQAQP6Hj!Yat@?m2wkT10|4H-S&4uT_i zpb6SzMU~4iIFbvAl0ny!N0)RRVP$KSlP&s^a&%^UQx-=#&v><0d**gST6dAMBAS4A z{Xhv+Iy$cuOQHXgmjO&_XZqu8x_Yg5r;&MFwL$^Rp_#8Zn)^W;CSj@lV<PReZ7tQc zz)-4bE$gZw8Q!6*gZm!~6B-KAu%N;H;7^POmr~_fIttep&@k3iCGBcwL;KnPB2r^3 z5>!Vt%RpA4^;&~Bc<_{~@C>h!0z2La8zv1qHxXM$V^Ng7>)*yJ;06w|QCYGbPJqZH z2JOHOq#(0xsVS#(_9hLiKs!&mw5+g(ri(C4zcr_;5w*wlD#)R=T|22U%o6bKuh#Z_ z*ODzitU}4@E$wwd#epN=0l5`bxL=%6NyizAdlh^k9h5`+%6fp^k}!hIF|VP>FqGP^ z8=^cka_#?RV@33?g^N@NNj3Qzxl;9^A==#(Z@nd{qU-IVS=UzQ`;%^VS7-OJaWS(0 z$KjZh3826a?4Sx>8F@E5my)qMqjuwNLR&Fy_X6c=t9NY3CYdcfZJL35HN0%+q8DTv zK}uz9)zYcerNp&aAWw&g{#ELxp%rfY4Pji<sl|*3s($SgkD1%ZdK?*62Rkm5aR<4O zbLVj%xKky!u6@h9zdLh7>hJh^-K5+_(Yui{S(DeSu(f>4<6FLO^+#i-7K=(CZm~%9 z8)#OK^@_F${yPssLTRKkh;<pJLE9O<^h<+c&&9Nf8LYxB9Kt|h&<TBA`ym%BVYc_h z)zJSpeMvlw9aPe3Eq?7u913;QHJ!(*dK!G88dxjYL_N3f?--<^jG&>d-5OI9@qwd^ zB0qJJ0S34*61;7FWRL3;GXWIOn~^HekrGd^QIWmdTXo?qu@&3ckG;MfTS$8{vY%a* zpA-t3017z5hM!djIr}NE^#?=y&hec0miSw#F)9+^&&@pm>LA_KolR2>72KWGJ{&DW zywT4wi0JcC?|tj2fg6m0fB(1NgBx&>V>g=ZF_pu|n7g?n(>ey~9L^=5^;y+%r-2<f zV=F3x@g>$P_u^^2)(>XmNtQ(&8l_SalS}v4TNZUmc-V=3yLi;ged^@{?y+Uw+0FkP z(dG*yFoGkB7ipWa;^Z7^{fpbXbm+O2w29d}7cA*}n(4FP>7iaMrI{2k;ob8l-miJY zNnDM(-c^u8F*c_gvH=;8+kMNPFwfp}qT?OL!4#@4`wV{6d%SR4LAot<f$x6RI}{@S z`PC)Y?`6G$y{VDGJG^bZbHVHrL2=iaE4@{=B`MlA4O=%&xK@kZM_nEu)Cd%qreGQ~ zWD=4QL*|RahhMlz<dUW0m5W!TWRxNW3KS<Gn=oM#B@CK8N>VC0!m@}<mqcO)@j<hP zO&mCL*4Vl8g-@R>f(A`Nl&FakB}kCaz!ZZ83lpL~c+j9~0|i(WBuH?eYk~i-V8en% z5CBI%dj9gMUCXwu+qZDz%3b@fuHCzM^XlEpw{Kmw{p69#L<*HFSFdKx!o|4PuV9dc zNtS#}*s;r(l_^`sxijZxphJU(M!GaLamLh1b4FU4>({Vj%brb}cC_2LbKfovtr;|N z;*zOzcFdXR<DQc%=dA3qxK+fiVQ!AOy5-5(B}Wzp88Wc%z<!Ar->ZDC^XShrX1o}e z;`fSQ$)8XEuzmZ6QRUaKzp#H)qyz{GDWDVx$|neJqTqs?Wa1zumOyBUC6i1N$%PnR z2+4*UIs%C!AUd+hh$Jq8$ccxfD9DN{0^;I}fanpU9(vSKV;wl+ILH5vJj&tYk8lJj zBphuN*~S`c45WrZ2O*RYLtlsiQA86_lm$i?X~dC7Acgb<6G||VhaE>mal}eT6p`jj zF%dD74>t9HgPc0?RKrg|3B^KDMjfTp2TW<;6jT#TMU_=qX@x*n2Z-h9R|f>Z0zLiY z<JYB_X1dp0oObHzTmRtG4?C88QrKaMwTFvi-35bPWz`*{*=EWe7aDJ*iL;C`?=<6# zZnXs~>}<Lfn;WjAHG_;gsr+UuXv;09nP-=&W6Cwu#fsT=*=6TytHFTx-FW4hmmYfS zvF9Fq@zLk*EBD>EAAkJ)=O2Lt8i?R03^M3oCK66ap@kV@$YKA7ABI>WiHIE1u!<}S z0watx(r9CjI`Y`#k3J45q>)D^IgmkSIQe8lQbJT^MHXSi(Uu=|*@Q@7Mp4B{MWCrB zn=-u_XHIqUgy#!-?#ZVKev$xaQ%^}Xl~q?|mB6B2Jt|hD8?e(4KA(2&_19pBJ(sBL zEHa>BsJ3^Wc))b`s%6zp8||~cLF3Fa>G(2DufG}_jWmA`D>&eOAB!xq$Sm_tH>SLE zOyZ(N8*Oux7q^Np&=iyHwy<{VIk@45Hy(NAo|{X$?ybA-d+)j%uPgJ?+aG|m2PmL{ z2lnglgAoc`VTA=7%wdQiF3j-5DIUVvOt<Bb?=yd(d|a(Mi4kw_{@vdJflk@7<m zv3w<#FMGtL6ElmHQb}l30cJ})%S02LHvwG(4tC;Mw9$R~`N0N(8kExxRh2|djZs#+ zS^*Fcj<cjiY!Hl#KJ?*_2S)IMalywv%;5-70LVUxVa$1Y@ty5V23B#K)pF=Y8sfZT z8qW}iGgwo&zzr@oHPp@Fb{HCGC<8UdsKzlOCpl@!>N3j^M=I2@xz2UYbKLnB=)g0& za`nP=>Omd5;M2PKyzVfut5@v+WV?Lni(md~5WoP|y9xb{V8I(+!ir}+6CqD|%VXY* zDt58xNpE@_vtE#ll)aG^q+|*?S(K&}zLt>>W?cVD-$<CSgq4gb3Q^cu{M=NNpV<$8 zLi@@7j)t_PYyg0QYFeQT1vRN1uxbee%K-#H4F_WImTajYE_b;WQH7&}{F#qpM3@U! zx$T77lGSEtl^k331{uy!hcT`p4qrhd8obG&Hn+K(9VUxzp+Uwwk`cqsG^2>gp&WIV zagAb(LOQX!PGz8oohee0Tvjw)x)!rV)^!nH@d_io>_x`gnejkq?AO0A5isAuv0w)a z(HxD3B8Wvyk1ldvAN|;)IZ#iKM8clP2y#e7CenM~b4Vi{nURfjBxWHI$r5Iol0398 zlP`fu&pJsb``PJEqAXfbkd`!5rjk&rBw+v4v~s{$I*Kf$I14XvsmrP2QdHG|#Mw|G zOts~LZQtouGN;8%&o~n_$lylfbXB)(a`UaY@n&hjX)DeE#~9oo4zwn>jAi!qh}02> zDfYGtT5yh@-U64nL`S-OqH8^~2p2#5`A>l22X?TN-R$gD#@ihzce-0>8yy-v4GoWY zbS%+{9u~0{=~1K5%h4Zw<k9L?PmqKh>5@vC$R~MEWh=!}mde*9^rdg6l~e*I?U09@ z>eNj>tDjHv7gRkBwUmDfpemEvN~~;UQBD;LSt4Oet46S@=Di?RAz?eibag$B`9<5Z zgTlBebA{(z#$KC&4PQKi8f`5NTnGP*O>febuE(H-I+DQ)aU||D5M~Z_Dz~|Fm_jp` zfg55I+nvQ$v2?i5=X!Ecp<Gb*pI;QH81Gfa0i7{Hx>F;-8VbBP9t>d$qiFIhDlv@0 z7GtuN-bZiivD_Mxw<kpz_*TZ!mO}D;lB8)$%47#J<&+3Th{^ms`AO;$jcC@ruK!Ru zC_=HayNUvDc*hceE0j0AUE9Y#)Pi0(i%nF^h(vo4BcEY5#xW&y)d}G?o%<G1G{3>? z-MraN0n7DphC|kYk)vPa{4hA<K*kWwnw-o4Hp9r6hBcHy=y`5f(5>=tW3PzC^vnVn zZ+OEV3=xbida-o@&1@J6+FAcI?kl08Wh0FrnxPxdk&Y)C(Q1>|T8!?|VnD9LA8QLF zkcw1$W<at+pv1_Pj?c+Y{)i+gncOMcv`kpeGM3*&KcEFIlwTIAnEyoPr<nO^h>{ut z)V$^bL~03dwzJpjEby<13Kx+W(5d+B=Ml>Hm~YdT+z!2r%r$NqiR;Z=NAu{8^KjDO zG-rM}li&ptLmZdM?>T2R;jt!z8=KoOheOBMRk!+d>$*iHv~Y`Cut5{IK*cN)Q`r>j zdZ1(MwP*Jg<9`X;p~N<AL?^1_JL0j&ujONGGbZFfTKn20)%HSAmeML&>D$AFq|9bE zl5(e{2sW+4n%X2k`t|?x-8}&cn1w>hq$sW4O*52I4Y=<{_1oV8c)`{R4z>w0UTpnv z#U!?hs#Jy8;ei%wsWZd!BL46hyebYjd&6;$OB&H24>^AODvoOyV;aa9hBEStVPz&$ z7}rqiIVfXlncH)8zp&!vv-nuW+=3Bm7)CMXP>Eagx#+J`F&S&uS==Esp_x#qgCZ2L z-x*AJa?CMBE4req`&gquo;Dz>Z9R|`a<_-<EtJa6<R-uDr7=sNOx>OmlT;xOIq+QU z#$|X1RPn}lMnhD7XH)`|RD<VTQ^Rj-7AYSf5B0z`kJl*^L~t3{DgQtZs9*_{$8cU% z9uFsI^tE~SRaXBZw+zSd4#v=6mBvD(XL^To92=K<BUdYC^*HKa4Wn=l$RG?7=4r{a z3*s;e)3AG#A#+ibYWK8itd<_Avo5=^3tsRBTfhgqKy)aUVw$yC)K`5k25btlPz)t7 zZd7B%c4HnwJax2eJC;XTXE9qhZPa61*7kl&l5O#qWQ(+95+Odqb${j)Q*1|WDzOr3 zax(xZfIQ`HpyXu-I26}~6!gY4_l9o;q;C=!UbEBy<q&WkSc<q57@#16g@HDG)^NoH zXl;XnO;}%mC1IbDUz!Gk#h@#9ql3PvgSSXT=+sQdkVNNT4ara(pO#G9Vqx5H4!h8V zP=soVB`*ITHihS+MeIQgrO=I~Fm&yLYteUfNXJ?Da!?2Y3NfZ2n6Q1rR%~tfA;%^n zaY%j_<!o9PZFm?+MAm+M$RymONGU}nXNPw8hkuCJ1jyxfEKw$7fCfeofNc_8a&mV+ zWq^CfcVgyu|D%Zm1T{;gD28`<jY3OOWr`?yit-R43a1~H=ZdeGd72k1%`rF4kyggg zdYkc!JehjK*i6zw9q;fAOSBA@QG2)74C7!7%`j+)RgL3<Pv&xS+Bi(J;0nax3gP%J zUj#;)wTkBGS-1mZO*dm|I51Hsb@GT>ap*8SMu*LVenB={AB9_lq&)^f2HZ1$Q=(FX zXn+6ZV?Iq_T>B?wXu=XVg9a`U1X(tK(uH?JBX5_;k*H*EADM3u_=#&q7P)YeDfyXq zwh!z837JqJtN4;$RZQ{~i=IP^oTow}R~$>JD=w&V=hTz9`IEZI97iOZ$<PTXca+Q+ z49#E-;{Xk(MvdNKjZ%q?SOi(A!!D`93Rfu~AY@qq^_59iP_|=zWEooRXqKc^S`h^z zRA(X#<CZFNb*?orKgLmA=XLD|c41dCCc~HAR*=HwQV6MkZO4BN$r9~@Wmq;pb~h(o z25%W@iT%ToOQQj*BzS0+W+QocWMK)O37Q((HDr?rn_!wQNrEL9UnZ1-5~of(Nh|-T z(GAg1Y3PKT2c}=UiB2q6IhP>~*N_bDAPkyj9i5{L#IQuYM^8{0mBCj!tyYz*vlv7- zbY0Yym?b;BrgYYaQ0w?0X{d(YXJa_Vma0`z>)C9~<2=v?pVPB`aL|v}L!a<xQrm`7 z!1b5*cLh+OcK)e|DiNSAfd=hU1x1hpK|qm`c#--enJJ)v^ael;$Vvo6c$yhrWB~}I zxS^C97xb_}h@c=N_+G<Dq9r<L%!r~j`9q_SSLQ@<Fd7;%x`Q(+IiH4M*`f~PU=7ni z9ET+gyKoNOunN1k3q#s1P-vt_3SuI*PwFC_PWq%qC#BQJV%_PTX6P^N*iipySz2n@ zA>yZ6>dBt%Ii~rTessxxMP_72b`ZTac7aHca%zwpVLthnh{%<vdJ1<p1*m}<1V3Yu zlXxcvI7*Y5iAQyrm`S0B$7W_Qsg;_rY#}P&un3wOAZSB^#1vv+1#zG%ae!5mnG=M~ zFhs1{svsM(ol&E+@~SCB3kqfp#&8bJ;Hyt$VcpQHzxsq7#+){nq*WN5w)TZx89UCZ zbO%)+-?=*sHEe0=hHIIv$1{ib=&j!ht{RhvAQe&}b7XG1ZDc2i1^I1S@??leZpn2f z^O^%UQw3FUulSm;(<L-O<*%3cCmoqeQNdjU`(3bPp#h)<2&=FPD=Pok;IJPGvDc{z zsWW^P+bSj+s=Y}K#1MMOKr0_BvXUz~u-R7>wv6#48RxJJ@X!vR5Dmu=4D)mh-7rnX zU}~~xPf<9mQ<;rbxwBrxXZ5kH<=9?SI+oG8AZtXe)e4VOcWiZJM{{U?=Vyod7@z$3 zbw{!!eVA<liJx(LcKd0Fhv=X2I%V@(1ZH~#ehR2LaG)0XQ-vC4|4IU<#58kzW}TRs zciV4dp|@zkxAMEN{m=}HkbNzAAGk0Hynu5dh6}pjsj?Vxit8Mgv$@4Mxe839WwlHu z%Z#5U8SlUh?a&UY;0%*doYr8Jz$!(-Dmqrwx>RVa>;b!#g`NNMa&$lYvsF5@yCa@j z3Q>>{2~+2#<Hu}bT8GbbyirSS9iyg$M4tdDe+%(j(aSQ^t9IfRWenMnIc2tTcdwm< z6XC0%3(7x-id{-UW=@g5oEVbd^{7ro7HzP%r6_0f+ZK3szkz$2tUwH{kPOK<3#X$C zx{wRH@EEZ;z!y7Km+=m!Pz=z(f(u;8%0X7jRI*LPj7N#93N{YOU<|rIYQP|*pHs7{ zcC$DOos-2y&<CYqxSeE(ySaOYywiPb$fXjcwCTyT-RhoXx^>cqyg#hG|0s5f1U`N# zy@lwtUwgePahN&Pr$^uefNFP-d65|DwppAs4{DhL3&#J2SE24308n7YDanBe+Yh<m z2>1)JhVjOu01NF<4DAuXcuYc%VX>g9g1vbT#!w8{vT24~&m()eunNJqmto3KSn2=| zsW1-Wzze3J4!>HY!WzQQ`M+A!PswVXv)i+woOGl7V(Tbl5Q56741U;Z!(ZykuN;@g z3$;-zpX17=ZTh@QcEs!&nCJ7$<;D`i{1P|Ay*Y5qH*t6S+7taszRgUTfdb8|1d@*0 zzMB~UMX-1YyMY!YzudeC?f3~>g$mRu3$OqWzpxmm^NR5mXnfqqvC<5_Fbd*8VT5eY zhfKNn{J{F`que4H#lWNUkPOJk4C0^*(Wo8T5jy|g0eq~x$?BrB(#f;5TaFanVr6*I zqNSx9&Cv;So(m&~7KM*wx=~zL(#boY%UiBZa-S=$wS?$0PUf!YLzrN@h}j!}d}_8g zowgOZwhGG3SxlLVYMFx9s0Q>(1q&$wa0E)Nu-aUy{eTNloe5HXnuswATvZIR@CV$0 z3#xFW!FPgRO~BiN45eGvEr-u&O`|5e)@_|(P9%+{RvhpE3#QNwExXsk5Q{eZVK?W$ z#_G_YJdWBqrHC!GOsCjSH=g7fesEZi$kVhsY}uEM*&SocN&<hK-91JO+DKf88F7fE z&BTj1)5DAgX%YnAtF{HGKMP7qV;0ogC87W8>s`~l+lc4e7zo@=&9}q72$t}$$o&ec zzzPc%(7O=bzo43{xyNtQ&egFD*3b=uoUz|6D`-u!On$lHE#C6vghXhZ@Zb)K01V3z z89yF{AuPg=#mP(R$%LK4{6UU~{j7<7rMz>N6k@GNi(2#;*&vN|IxNcvzJ3XA%ev)< zO@g(3sjj^2GSmxG<7SwLxh6D?26n*VM1aihc0b}<T^iXxCIGMy8lmbNk_4;bk;3Bg z8{8Xua57Hg5$g)95DL<y<En7SKK|p8QQhNBO+w0fy}8yC2eM3_<cs{|hc&aUDGbVB z3f$0?oeK!XunfBp3|oGUUY<o@PT&70jKY^S(fA#-zt(hTIIU;d*c|O4^C;jr43|!8 z=d&EHdZ^iK$|OYm=k<qn{P|LA$99H(=sCr`ir(4>`sm`@(>_g9mHu~4(SUS&;$ck9 z{nqKft)Xa~51_uG{XhybjtOlXqNc72&+rV%Fb+HZzYgc>>>T96AkU>L-imAMx_<H| z&+Bdd)*DtCyKoJ@U<&78$3WV-gg^|E@e9RZ$6Zd9RoEU5{m|k_=4Ni#x2xYS+#nd8 zrE8d$G#q~O80W_`;NmXQJ516D4#d~PhYWtT4DsL)egy{U(&A>?z>K}{!<hDN2RD7w zaiXvJ!|(l0Q~+CM1N4BIDaQX!6)7x`@M#R=vk>tUPw}Zz48%Z8=n-G5`SGo}3;>-# zV!ynw3gQrr`n=sHU-^lw$VRC0+7jiyPESa<3afApcB~7QK@8Ra4}(PussIedkj_ZD z&`Nq@V-7}98p`*=ooIgT+Golc&Dii5kKX?6<45&X|00zgZRJkOQ;X67xtE_E_PzXM zGh<x;*~IWu1c3_0-Rt&`xzqeQz6{!+0Pm4^k0?uJw?++$0gwWf^64+0um^_-5wZ!# zUFHmzDt<P6YqR)>i&y|5Zk4fjs*W8*m{6fYWycymbQlrhM2Qg>Uc`7zm`07lJbnZj zGUTpZ+){D7mdm3qlGlojOO|T?94%GCis90gGuKX@xp4gi`g0bpp|gw{eU(({(xk4O zK7ESH6)LJ#sggp4mDJX(TS0vV3+mI@O=ZoR&6EifCQEEBy`2;{(p<W8A>F;}2$Cbd zd>8!%ya*AZLxl|sLM#Z-V#ba2Jbqk9PaVpX=Um1-N6zNWa6Eqo-A449HEK+&Nt4>l zYBH@`iy`ynix}BoxZJ*-MfVlny`}ty65NTCCdG|2S+YdQawSKcA1MO8NRA?C&{Ub8 zBS#PJIJ|$yQA51=7v;;dK%YLv`V=PImncEv!v+l+Fj&ApVZsCc4;uXcPXPf1OaOrc z4k#c&1s7y+!2<$Fp&xwz@}aOo3opblLk&0NutN_&1d+pjW<jK_O+EpIE2^AI>L{av z+Nqacdg%oi8-WQX$6$onQKVhY@nxEGILfF<BadVV$%8gxk|U9xgwms9d|5@AVuaBp z7+r+<MHO9?QD&Z)#!-cqS%~Q=&7g`R%0;A@dc_r{pn^)OsjRxHtE~3is?V^*8tap@ z22G2twcv_NuDa~PORv5j4Ggfs20J7%#2UkNF~}yHtg^~7!;CXI;20G&&qPC&w9`~e z!wfQ5do4EFYO@VDE_Un9Hz|UHVz}XqYk~>nlw0mO=ZZi!Sv$}mf`}lt>#hgz!V7Oa z^Uh0;g%q@Huf6#HNRW>{`|z_szy2EVFTeo_G!VfC-(~Q@2t%Z|UVHDwx5E)jw4|&Q zv0711rH+Cz7nXL><(FS>)Un4W&oQQ$YnoKDVvCjB$Vn%od{Re`ax6v}W5&U9$Ay8> z1(;uQsY#h`j7cULRdx|Zm6d%83Me++oCVINmZG!HJMq+t&#t^8B`mVe%7oCg)N<=B zOA=j_(Y*HBtFK7^nv}4@ELAL1O*iG#(>g#6l`~RJ{S4JMR9&^zR$U_lHZks=wKiLC z%_7$;r1*PR;fN!yxM7Jc_PJz>2;vAL#;{{LAAI0WT4})>kGvYp%N9NM)_V`!`NX}i zTyyyYP~CO^3p5a3*AtXi!hC0^y>{F8oy3x+KT&bTrCbb3muE&nSz#P;Z204l&PnA; zDK)0}V(Bw#vigoV#-7I<c@!oWQ`E^R<%EmBSr;#b;l`R|tXZX)UA$bgs26$mdCs7n zk}7|qjn=Bqq?KOUpqTcwLrpDFldu{jtfm*NL27G+q14yFCN@BjEiz_9n`Y#onYFR4 zZEq`0+*IQ#*VyfDw33ajaFwgy2(DL!D_j$nFf8U6OFGEPfpw~Y9qm-^a?{G(=C0K_ zZh<ZZ@DZK3G(fJ?p)PgnQa}P&=dRbi>p>rgM?Y-0MJ{%6LnAsw?sk_VtFY*IFZxL? z)aQ%;V)Q~6GGf^FL~@L7n8GE{!{hYys1WOY<a*iTp7yq<BZQq}6r;EXOUS1%g&8at zH=CI{V3Le!JVO<#2!_t&=cfAE?|%6kT2+eHKmVl&fC6+{p`wN;1Xc|%S9_FSwk8;_ zNzhVav!G-!m_ZG8rc`W872Hgd8r9IPZn8pQt#Y$M-T<zJg9BEu4#%A49P5VFiJY^Z z6|HGi%UVKw0TDmf9`}HY1WGKO>H3o{06{T|?W!WY9%KP_$j*!R#OLhr0mev7VvGO_ zn7{@`6jc<17}l7^D$aomRR9ByHcH+{g0YNoSOXfx_#+-Ema#n^sgF_uB$OKFF&n-A zPaURUMj~^9G8(lsO^&>zI=Z1gV@%_c=HuB>><6d&;V+a{86}@e`KJJ)aucd7-~s8P zz@=U-FR`2@*J=s2usJ4|W;+`%Mb$x5wE+&nJPm4yNkY2eEt$&HP2c?1LKnX9I5JEQ zHLH2U##I3gdB{N!f<QTLey0ZBB+n2#_c;@I%be)UPZLwu0Cy??0qvq<JQXz0dQK>x zm&GiI_-P^(_3kN5LE|inVU1KwgBvqTneiYh$B&6@8W+W$Mv2r>*@hH*JsN3lQ6`LM zm_ixE&{FYQ+KZR+BxRTU?L69H3RAd(81HjYi#n;4pxH@(c;esD{PZV48MQ3`s+5}4 zlv=d~X3c?-nv`KGbxT}cb(f&p;8s2ORj`VXn8t+7Y*4tjw5~O9f^$NzfF-QB)=+WM z$>DX-FrB^jU^_VYAz(Gfxp1ndi0(1Lx8_ryahYyEPHZO>r+6UA#w!5yv}a~jykZND zNDz@|OVj=Z(9aI+C|(-JI1Ks=UF1SWs>P8YgAp=gbmNb)?PG0~Y(41NmSefq(T#Qy z3}76?6eL4gPH0rzo}_Un#W0E}RG|)dm?9OUu;e9M)U!_Z6qMM_(<q1fKd=PKyM<~? zQsZI?@+QzxP@QE2*UR2a<+4+r(&|=!**5yV?QLOg6|C@UR$AdEt<3!YFK~PnLjo7r zz|mP89wMjLz48^pKn&swz$s3`W;lr)PN#l8jIJk&xIhPrY>6qGVit#JAHN26u!TKr zVi()k#|E~G#h8iC(%6jBC0H&<lBS$2EK3l@(UywAjZttz7&K!NAZd#ckUBYg4*OWP zwUiTsrUHBoU71d}+-08(MHRW2#U;7%40t5N6r<n;G1T1VIK@e5*M&1c{kL$U78NZ| zON;KrYrs}6>XorPZ=k(4K?;&hmxw-FRxcA@wJrKo^d(Jc){utNoWTrdAOp-xh_@4p zp$lBNc@}Qvx4&hYSHXFL;W~}DYJ$2t)<MIw@;W&mqB?We!j^jf*n?qLpK}BB!9c9n z`9#L9PKvk&d)UPe_5f%=9`&dPvemwJwg<b{`Rd0jUOWj*$k=~Xsj-cP;*;Y3_+-HN zwlJ>2ymNrt+=sXAkpYQrC`XxL;nT%6MqvzfyiaAs<#Nt)R+M|^`;w|qZYs_!@Jq_c z^rt`gPqQoMp?)P$g1WO>-m*%n^%<7t)moqrA!tIkH!_DtG}=UEa$t@ogu@&wS!1Q& z{i;x{x_agd1$><3#PtY?yQUpR&A7Za{fB=IA~-9|g7HtCoaP)|eM;9vcB+m*QhaQ# zOI&~h2tWbl=m$Og@%9h-WB>dQk$nmVK<FpkIguFy7&@{4v7zuXdZQ7A86=W0C{yq@ z!$Z6a3<<?Mw~%N&$GZ`gDF$FLDPw2_W!Q-x!-dS#JWXm7p3%2yXoq%~gH>n+((9?H zn2MiTxE*Xg*K@c5f|>$irHZpSr}{Hl(!E-;C0weYO~I;9fv@44FSh|9NF%1XDJxmY zn-t=&=WC|_dLdt-zUnI$>_Zl$TQKT)7QX5$?+8Ct<D9`Vzp4ut^<$zB12OlDBKVWP z`K!PC%fJ5vzzg{`3h}=|1d)9@20&0C6WN3rE2F#vo`T_tmNK4M__iMzh;yhJ4aC4t zJiHF1vJbQoMrx!j>4uXi29~**F4H^))R`8Hu32FJ1yyhbR$wSqfQNR78AND>p<o48 zuoL`2I8j<X9t0rR`>uz>v+zQcK4TO|d8*udAoa4POX)Z#e8LPOIkoX1w^@Tnvo9=+ zl@n^dW$G^$`Ws&P6;7)@Pg9&Ch=MB6K4c-aHT0qHlQ8ikKRKMbs{4Qq>o5;Hms(q$ z_?y25*)_{TL<{*feb5L0>xYS?$cnVci^Rx`)X0tOhkdAreptl0Fu-PWHi23|qDVn5 zGoN!<h0>}SahN<#v_Md#NhjNpkvbkK(@7k$wk*pDTo8sL1BQ81lQj_vg5ji|>6u_; z1y`6EVnBs<a0lk%1XRF<S7^#NgR_L=K|1sQ!5@S;i3_jX=_evwsz_j<Y0NlDp_Gm5 zJ*$F@kHesl8@XO8IkpK$5K@(uGmSGy4Vjxcnwu4zvouWWxm|IgCxC({2s&Xo9AYt+ zA`rDII0C(5oHb;_?(i!KgSvk7oN;=OZ@D_GyTh$B$N}NQu~W^l3xE=!hmPdP*p$uL zoXCH$&3|Y}4^c!$6iG}tKu8RzXLA!u+=)v%hbyy&_qm2u@P%_=2_a*xnv_ma^uP}^ z#TjX-_aTO2NQG`NpW@oQ&C4mBA~>gbE>)-~cW?(ecmz;*g;^j*pgP7LR2uI(D%o>J zimMB}h=fLgrSn3Bz~H@WtSU_LIN-DYj6{>K;xoRmLJcz@#}d-Q6jCO1<T)_>xnD7y zcPy}DQG#W;E9$sRe9T9uvlciEr|~Ny&?%>IA)PzK!^K*icY>#cbPx#9qTD3JeK15p z)X@ytO{Stde*w;6G|BfQ7~;G)Za_|&;09x0hI6Qi9YG#Zl+KP}Em5q}93jP0yiSD~ zE`y0YU!XiMDasX$pYdd~>57x4Y)XOSgnm;`J!k|{P=z?jlReRs9po-MLnWlj&)hM~ z{d^_0j4G)*jKjc2-{TYn6}iml#!(@@MytYM601nVFJ#i2z2O@#Jj}KV!!bmh=TL$j z(muMnOr~o(6WyFuQ_&SACk?y*Iy+3Pf;>$r8ZjHa(Hh9nAEl5&%m@Fw&0!_hVl~!d zMb=~;)_m9}VbBA;fU%J*QX?(6HA~V4WSMK|Eo-P5CS64=$&yjD(km5-o1{*L=~9*X zQtWgoo=}D3^aXDC&YeJ0O;Xe7@|hdNA66g+Vqk?vfCqPo89GIUtkf?0tTR7lMgj`d z+H<8sRZB;RDnTRAMTN`X!zx~~%g*>la6G<CjnHG7jV<Itbo5jVWk+`;L&TX!JBS78 zu*@JJg2_?U%IT(5TeZQuuokVufs{2{)k7L>9bKKQ08j$iQP!kY+NCX4U)7Liebz>l z*1HQ%(3-@8NuyRMhMZ9UhvwPZltG@Ag3iXnK<aF~biI*v9j<nDS6z6Se(f=wS;3vT zS2nFy9K=Dc;8$Yc1xJv|nCXK$wMAr1#vlAHsA&slbl8V2RE&F|^inUX%0`UMSZ*A? zN%bm}JH9K7H08@Lk}cUzeLiObjtq^VVByeWAp$&zg~hSQAYdGt&CHukwK()gaso(! zT)&^q!>&8X8YS8SK!5-s176cnV1-Dh1=4<SR=#M&x;sFsrPedLR-ot!l-UU;wTWtD zq-@K{D&11E6<;kyTkBNYwdJyzu?Azf24c{K6r5X>oFDqJTZ41690aPZV1;LR22$|b zn32Ijuv4mN1=j=r3r_fiPB1EnTcu}&M!R4j=UqzyRl>I{w77KCM}^c#ov%g{CXiLW z<s;cHytK6{-7tiqC`gVdxW48ff>^)<7It0Om07*2*$8t(&a~ZZX*D`Tr~BaD-u1c> z>%$ToUNtaY<yB$~fm-K<G3b57X@v@_MM~@CiIfxu<}3ytOBhoGymYe>unphwC1Wlv z-*q*`wZ**RQUzkThAY#F@Z1?$#Mk=0L9N8Dg;RxR=!RAR1od%;c3^`>AY@g*idHxa zWduU}9Lqr^)CO`~iPb$tO$-WZLJZDet+Gq53XS?gz7fhoO54=JOh@Q5T@4MED2M_j zFapPc;V20I1K7QxW@#21o?Rf);q!P^(B#<<;IIx0;`UPj--W;UD`F!KfI|qxC9V*r zb>?S2R%Y#oV9<j_fY#jc%_#1ZNPM;hoFC1j*Pvu09~+;9VYgPmgklJWDNENf7T+#K zV>DLdHD=>n;07{1t$V{6SlpzXs^6x#U;NEu*5ibNR)tFPg;5Ya^&|vBAY@YD1XAdP ziH2eZZeT@$#*4!}Bt$QY6@)=6Py=<sOtxGpoWjwt!m)alEIca`#x%A{*%*2PRW<?_ z$OAiI-6M$Q=$K_%)~1?0HO#@;9hN#4r9)q)Re}^^uQTRjmaO63gg}Jmsix|xwrZtq z);h5NW(C4#BK;RUQ9y5Q6L9v4pybw+H0K^WhG{T{np!t6{=iWz-?={HcuwPare~FW zS5sI8b+{yYO;eOaQu4Ip`z^-(;fjSTXijK^J@$nhqk}q7Pg5|4z-@$3i0A~ygic7@ zhJE11#W+ds=&2&m$;IGp6u!$XK1%&q&Rq@9jg4e-X%mjVO`GXpsp(kIzC6f-C_t8? zOBSEDWi|}z9IjmoyIl;E)fY{y7(LBBZ0g`mkm3D>{JZMwPF7~FkbR<tIrs~vim~6^ zW^V3gYegd%sfn5@hMO=hUAU5In1*ghhGXE~>!j=ZhG)BGSG>;ad1EMCVA6h-TcM!; zV@{ebfzns&QoT6S)5N~Jq>1Q8;DlFbg>is~MW6#S<3&P%1VUzPiS7itgNwQtREQ1j ziS=m7WmL)yzSLH<lNQI6##ELbVdr~k(tUzmnduy70v8B_D$s4-4g=pd!{8R~8^+;% zM9~yYZo_&t`-nB?4l&d$W)hQb;SGRb$Up7o^6l=2?*0pC4e#jfo!~sulO*t+_=RG) zvS4^A;t~d!um)>52AlCQzXLM-rt5g-Z?+{$!2XGunFdqnSMls;!mb~a)K`Jt%Ao4X zt>}cL>63}>1P>>LZkPsZXa_i;gJf`rR4@iacmzTwWX_I+Q8>#-ZWKVPMkNIQ>5yg& zJ-FnuLG38)r72`>2L<5}rnz$zT@wzR#gu|Da7-n*={&eASU?u%sG(&y@>-@@?-S~$ z<44cbmJ4eS^g}ErGR-M}zg)fY0uTUdSmrL*?$;y-IS9~eHb5dBZ@io0@&+CTY-46H z26@$I_@&q76p~qZBQ@6VfIr_p-?B4JN$}J>U>F&LQU$s#@HM5bL{D%=M{NFKI8#y@ zP(a{KfbdOdgiIi0S7-%z=(kj$12yn;%2tF?C-tf6PZN(=6i;!BHPBg?3`gb0jm6wk zNfjBFw7`^YQa)L>5}cam?YpuASb$|@VFGH3%xC{;pic6kjyfLhVQq*1wbDc#VIE?H zyz=@>fN&^xX2$NaFV=lB2R%51t%d|KG7FLf>v%tN7X)x-pukIN#V#WWJFmpG75Kj= z_&--cK>u%IV219@w?p^me_r&%HbzH3SU>SfA4DZi=!CQ&^{QNj7&L}dxSN<s24g4$ zmM7##xIL&6ZAsa^uUSG%9-Bt3^|~CnyX-1Tt<(oqX=ADz(4FnIf`Ta!7C+$an~sG% zP<9u10wrjA18WYWD*~U6`c=i8T(0`hY&BW^WpXK(Zr8(NhODm_fCexJq&55U@A7?O z2R#r3L|~vNP7CpVcQc=RH_<m@I0^W%;uzsOF6(nG1BhM%2NEp*Xz*aJgbEij#O3fI zM2D(WT^nWW+{9V4aB1wQ@fFCBB1eXFW%A@nRIXH_YU$D?DO53M%9Kg!=1owbIFZW4 zlhY?qpEeOKTC~%qOq)7^>XhkGrbbd5wOZw_U9x0X#H31=%Ge@Djvh^Ylt}ENw1^O? zO?2ojTtRZ>0;+4*uAaPl>*%TD_pjeMf(Of)Bj@m8IC9`HZp^q%n>CWvP^O&bvKcdE zG?VEphRm1Hp}Uao!sT?9)K^ktnc`ZClstK&REcFL7Az*Zbw4@sL<tim!i66xUgSuT zB1D!i58}f|kLW#cP_K@o26pT(YP{(Fg2i_h;#s69U)}`&`Vu5aeAuAjJq8Q%Cro%? z|3QQN`4#ZzpWr_N2plkA0R<X(Ac6@NaDV_0u(J<7`A9e+g%w(OA%+=hxFLrfdZ=MP z@i?N#Az?uR$t0F!qSPiqfr8UZDxpMDNFK4G3OBx(!p%gvJj4)?4J|Z~F1qAmWROV) ziHnj=`WVqe8%fEHDZX&S3M(FINh6maq4cFmEUgq{OEj5@Q%*U7!b=@x(9wx3n{Z;( zibSn=XC^A@ImwEXO!7!4QjyikDD4>P&KX$HK}T1qnBqtxiaer7BZ*k*7F=-^GM6BC zc?!s0eF65@V5J&{SYnQ;3I}A9RdyMyn`PFSXJUx|_C;x@b&&-Zt-01(7-7gp#1ZSD zlSgj5J@JIH!3{SYa>ga69CJiC2VHbHOlMto-Fnv@c;k_0UJ53ZtKNF;!6)B*_1&jm z1O3ShV1NfGc<;Rj1Ym+Z{e1W@z!dJYkA(jC6EMOF=hF{8km$jdBPT{;2_`JM2xE+2 za_NyOtZ=i6De6oFk&{mLQZmXZHwooN5Y3{?G^P}z<(6HJ<jN~xekmrIW!7Y-O=!NT z6Dr0e^NcU4OcPa8M%lR{CYDG&wV#tj;%6jTPjVuPjgTd%F~+!a6)a_3v1lrensSIE zh*(N#AC>|_*Qa>t)t9KF)?un(s3Nv%W01A~x<+M|!8$9gwcZ-q6k>3}YZiY9n@4iD zt+P(BOvJ$K6H+Y8>~6p<vBa~*MLR9E)?SP4blXx_!*$+r2X1)dky~!L>#^tFy6xU) zAH4GVM=yc+8gHP!EcpA6!p&niaKQ&VKfQ+d^aDyAB}SYz#TM%XV@xjTOk+nkax=;_ zJgOoklq9Q+i!ieY#H7maGub}-`8%XhF;&h?v(31qGnDYGXF!_?nsB0%1#SWrUulIe z{xA(raDqio%LFDesKKdO!fIK|8YDo-HLi)}5hgt0BOIX!MOY&l?pVjz%FqQVq~Q;Y zN(CKE0SH9AMJ{~+L>~mv2R(pFRCyWy)g1Q5w^RLXF@O_XWF$j4!(|3>iK`W8K2wG; z_#qF%N=__dVXQy+0Sj2r%@v>k8`yk~bD>iL>6CB;;+PI~)moi&T*s|$&CWaG5>E=o zRj%~tPF)&^54-5|J9x!Qc=QsGy^eQ0ef5B0%%dJAC!`O3WU`YJvYsolhX}ERFhvz3 zN>IR;F&UX;W3#~0`BtGmj<nBxD8t1rRxyfEFk=_=tDlo<i9e1=X%?y=1~F36jaPak zfHWE)0msxcpPeazYFgk<Kw*uqn1T?#s9*()0=20{O=>CX;0Hq(33ZMT5)nI*SkNMt zM7V7%Qt1O+2+@ug!q6REC<7G#rf>!~nPO1|tpg$IA_yYhjW2uC!xB-Y7{EDZa8XPH zWn6{P%xqC|l8ZtVl9LB9UM?1o!@_E^aD|m#!HjD3TpO3g8zzj7ICPYj9hvhS*6Fc2 zeC(qi|41(Mn4kpc`hX!3IiKI*M?VT^WPcu6JW1k9UsAB7CoyTTtaj3R!I;A#M!7vx zS}>KWe8~Vsq7n0%;vzTlh%h7KBw-k%8^#z%Fo3zFxDJzM#$*LCbV&?je#Ds~fo4ip zB25GS>}S@z<^n0`3tx;46?YQnouXDw4x;me>1-!F-5Jk#rbUHnc?%CSC8<XQ@rZJ8 zAwMtY4p{tw3u-(K7jU)zsNL=s4vX^bV(8E}iOOLObT|VY+*F3;{^6g0_`(*U-~=ZG zrwLJ5hZxaeELiyA3#mB`79gimmacS-YgFSCpdizkjxLUJG#yT-#T-0l%Q~<7>9@iq z)S(u&ki0u&BHabN;0aFw2|&Ps2NX%F-U|T%Py<#k$<=>BFCUwnFed5I4{XTcEhge# z295Hfvx;wgHF~AT>fqM(X@r>j<15J^B8(mRVj6k1AB_7-%VKiOW2Q)-D^&4{Ss2z! zh*d00rU{eAJ{FtU{KO~bl!;HY#DbX3AjLRaH4l2$vm}J)XwwoFNGXDzi^x<D1(8rf zbP7~3goQg4Q3yi+ECLar+S_3aGlyir`EthcGoW7x3s{iGR-rk~A4Up8KpRWDfTk@S zxL~W?mSLb}AcGhTjayz_feWi4Z+XoN1@)@;2~7YUO=}7*_@XX#^sTRb@!LoJ+D?!} zJ!(=BNgn|>)u{zOaJ{C=-~>6i4p_x7!0J&C30)Z3&eL!><RA#`sq>ttY|-~fEG96C z1WUvig_Yi_C0f3?WjO}MII_}>Vmv9w?k@L^Tg+pcJ;M}2F7ja!TR_Gh@Uf(DvQD5p z6gnk^P8g)vW;tjztgZ92BP1o)KHIj`vMpj3uk*C&riW21Y8A%#14HlDP`?lYp@1L+ z%IQ$@l^cftRjiUC%+~;!G)Ts`zO4gqF{%d6B<>4_77cDu!x~UuK?+5e!l;uzY9}<I z>Fsszs*lrZS34(<t&24uw-Z#M+Pc5#+5qpAy6bl_^4G)@_OK6B>|;CoUz^-&+ZCo^ zbJRgDr7fk@uDywD-=rpJW#vh_?PFPD$*=O>G2+b~ky#Xj6t5`8yW^_A$r~Pky9nE0 z@qJ_@FLtp9bgVU<EO010t@KaRtire4<q(1v5>kW2A>>lrGl)SAi-I#O*71i_oZ$?i zQNtSM08v0#D)yr=MHr6n2SS)a<POc7UkY;=JS%1~#HA>!q9{c*^uCIk;W?%=o#`%& z<_kgp7w>pkYF^kVeY#9%LKB|;teZ}KzB|n$b@Yhe{MOEP{6*L9z=zoJTG`EufdLyN zp<UV)fP;Mk+r{07z#RkzjP<ZXUI@b7;hl;U1(fk!-~FA5VaYS30xuB5D`d%#!4=I! z9xmtt3&L3b$Xn(4)sXQLk=e}VC03HPge#CjC6EFuAP|%J8^Dd8>0wr8VHwqQ5SMw` zI!TNrOo}4-79GfzI{?Do@C6}^0w9b6%KgP*6qKL2Lm7xc@DUN8!9p?+g7ZONU?dS7 zA_fzsiW3D66vdon^j;dA0r=6%XZYOWnBVz%TKcJ98nxeaHC+?vMtjX4tL0R4yqdQE z*jMa$3;*rcc?{A~{g(y=7y%MkRQ(6ADcAxkh=U!&15ThSPFMvV0uhPXSmhliaNxzD z$trQ%3BE$T-QbX^)eLq-;<*gs<=Er}<1f-+3c?b|aDywbLYL$q=j|XVsKP!a!#IRO zC{PmuDbT-(p1>U;5*}QZr5?k9&=XEf6!t+IWQ98<17A$TD#YVE#Zw_%N+N{CB3Q~O z8G|mF0%MF#EVu(11YaU7)DamGV8Ee54wpnZMjb*%_G#Y~?P2fnAsL*(6@5mg1)^ze zT51%c(Vf@QF&)!29V0^BO(BPT-4T6FBG$=He*KXk4HA0z*Lwh%?~t8SLDlg81V{pw zB7)dU0+d54u408$m{B4O!$3mam57OGV2Gj80%;o$0v^t|!Yu5f%^af&lABk)V7$p7 zS9XLi!jdV-5-P9)&g9HmvZcNunKY6DG1P%IsDm+>!YlOMHin)z4jec_%?4>16E<Na zJi<DqNF%TTpJjz9AVNGsf>~V3#H|HoQe2w(kRJ3w5cR?F9fBOB!l1c>7_dQJ+?n3+ zjo<vuM6C)GMbWEVMnzg=;{4&y0p0n1B+-Q=`;DX`E@G-d9ek<eN;b#+;a{v(qIPT@ zCgKhukpL$S;3xXpyqw*F0cC;c%LcGRKj4FeC8c*_(soWl-3bE3NX*s$NKKtcr3d;Q zTFpo^jzcQoLR-4hSRNkx)KW3dTYZvcmxy305Cbz{i8HQcE4}5u!2~JPn<Ef|FN{L? z>}3M=CFv2I!L3N%k)t`S9$7@f9L&~Ntim+dqa&0SKB|S7twpAAN}CZ;5#<GEnnFRP z&7c*=5s?aNre>;8l;CWiWn@N0Zbn9mUmynE<KQN!iR4HoqDeMl>C{oH-BEF7OHaWL zOoEF{-p;Lk-A&@81t^kEO6Tw(ASqfW@&rH-SW<U>r<x|rKUfbaNE>;MS+$WB2Tmnb z^5B=S0(_dFVeO~k8RMVsXN@?ME8v3B?7|5WXb#HA4wA`DxB@T#B*Qc)4d_K^5q={$ zUXTVQTsdZq31y8`i~?vTgE36Q)<DW=p@o>`qovfDWyaoIC{#k>MT_di@tMLO4B8)< z!W^)HjS|KjI#C@~RAdN_8ni*-WYika+!?3=Mx}v|Vj5_G2IH9D6cj1Z72VMxqLMBt zO~KI|y;poC$9!E2{^=ibCZ}@xpLt|y0QOFodg*|HX_)$?0s^JJ=mDCpDZeU=_4I-q z%#BlSkJjW}S=FLm_Kaeggr26tEX=1f`KiQ?CBBhFkV)#py5;5_=rqy9Gl1JO=%vs= zmQY}7reaXVh$A@?CS*2(sCEU2_CX_zMG3{zS(NCix@uhiWE@>|N}JV1X||{m5s@)~ zCU+%6VF(7E1*>W{hV`Y2aSc>*DOVVD0eP*T8jac$TtOH}LDdEe*pkK-><Vj4fvC0L zs43!Zq?%2M>(o)p>adPW`jo8sQUA>(O&XP!!mGUEN3WS30zwj*s$Bpq0>kvHh7642 zE-vFXuH!x~<VG&z)<Zu)L%`adoPH2`)=3AB*awEsEv6+aOsah5OqUQD>h>b)Zpp+_ zEJ&p84W@2?0#?#6qgo!8k+CJuEEc~7jlc1wgq|#(<cVN5p*y+kA7n*5HbNhmkj14C zY2j?nqG%7ns?RD^-H06CDADopnIHUt@a38K`i)`#7+2Jm1{rX{5bOXF@PG*L0Q(LB z3>d)_NZs28K@bQ*3&6no?tuHYZw%}}5lq1xEeqH_K^SZ;Y&5~rH65zSpAoo#xSq~% z;%^Z208h>Bb)+j$-7Vhc?RtQndtd-`erde$<N*T60VJS;wXh4n@Cye(GxS3}NUjav zFb+d5;%12TYy%t+5qUxk!CKq3b#4N&CkT$NDLm{|LTttQV(S7>jZ6dzmPEwDk}-_J zGYF{0f(ggI#OIw!nFx(HmaJcz9-eHfmZb>8S<P6qLLI2#Ds+MhosejyYFMnrs#fOC zT5sKWN<-BsUz|!3c?Gg0Eh5jsqO3usodFX63_<(4fDl};5*Wb{Y=IS6ffslI5_rKD zY=IWALGMkGvqGyG3{)Fv!6zdD5?BEbw67NEfD04>b{Ihm?0^XDzz(QD{mKyn`^K{P zrm87H5rk0{gcJpntNrm*Pi=74U1F^TQYO~q-g4>K0Z*^-q$rB%y_O<_I0(Z?&km0> zhgeTJv;h!@Rpu6K_ZWqXc<$$kj}mur;61TD<D0j=LNZvxD-~HQ3Frtu12d#$Vugu8 z7ZC3zY&HGvrA}z3CI!kS9Mx2f))XdGID#62+gPNK^WHH&j_CAKCYo6<-F!;Owc)5h z6rSmUA;Usptic(ufe^4VFZ;j}baE#DvjH3Y&2eqfa)rTi1vTwmnvmiO`EfxPgaOxr zZLlD4X<Pvr%rp<Y@(Q%T3(NovWc3ah0TUDlNF6~O(MBxT0vb?GatLR+M(NdY3vz0m z9|cl0w`+5@N7%7Tye<+b)@!hJ^8)IN320}8kh5S{Pd~7O9MnNwco@X7v);AHJKG{n zWK1_WtW|2vJzqAL_$NHL11I2uGa44dqQWf13^8omm~dX0C>fItAsGYQ0(IaSA7L7g z<H~xORD9fzP0Axc<{gt3Nat*wp;l_mg&+Shiw3eAmdYDShB4%U4){R}Sn?JmK@zY* z9KeAhBi9*7(RKshcEdDy$L6K~)k<xSMi+>|d6$OR>LzT20Z2tb0&~F>Ac6n#KzFpj z{=&c<1;G*I0UrED6`1vt66bTAD<x8CcDS{8%zy)Azzj$;mKK$I&~;t6OLXpsBaPyi z4sL-sSS1DaI9Hei4t73N;NB>dI+M}|S(}x0E<86@jMUpJR5mVRwvC^lDom;}d>b(| zW4__yNzB4NvjQunr7EN)LObeei?IR?jcc2+L!&VUMKotkG}icu39SMhz`{5<?-N>_ zJAE{8pVml|bV&oU_VPt?CnOxO!4OP=5UhX@oPrh5mK^Ms6fwpe1Ru;P>voTFY|dsD z)n;zt*4P%^4CSWhz?4k?JwX%{hocX{5byv9)Bp=mfD5#M4&Z?u*Z~>{C$$uT1*^3N zJF_Kn2YxRA3@ktkz;%Rg;(rYwUel{6+UtgMxV{)0JqWgli!+HY3_UEu4=1+vypslQ zpgTXdDuHfH=*TSK>E_+|WveAKpbtM@$!8;$#<oITVTntyf-J1UjH~vNg)u`1??c;3 z%Bn0mcG+%QLL{hRCb-jXlaM_9_Lx(zAVdm2spuaAt@AmQjsAreXaN%#K`SG{8}L>d zrb1#kQO)6DWx({G2fAlqS|ExBX(08XuawnZ?fS)38$J3l7YBXgvMu0&5$He;C;|Rj z3lWHV+)C+j?%xalw7>$000dmX3q(MxLpXEx7hT_^Qr)!)XE--kC$0y;B!u&?k2r~2 z4=JE?I%i<D8ElJV)3X1JD;UkQCmA$0u@g)CNH`-g@B%!*LkapgJ?jiAoR1)sHj%Fc zDeN;LFvFuNc^FqJ$v&A8raNE;W^H>GSxiG7RLNM}ac@WOm<M<4Edn8=O+m)0ao6hh z0!Cl3ffh^w!drnB#DQ^T;i)JFEW|<>)Bzl<fn%sXkG=}`S^UKp^{o);X>>fun^))L zej6=86pT)97{?J*LH?=$2!Oy0_`D0myz1<f+#Yzkc1H~yzg1@d1S|j`%_LC?{Ra@e zUH5G^Yx5)j{UnE%sW3Qwh!adcK>c8A*fF3pV#@_vtn+zxPu6>2!pcO~Cj*gJrD;PW zK)ez-kYGWB2NAwvrAiemRIFS@lsJ(hD^AZ+J$pvVAt_>`rgbwliWMnTCr_GGiE5=v zQZHeW0tHIuOq-u@Zqm7vXU|MOGhwnM)Kbw&M<+#6x)jo*N2?scN@mFsBuG`SI?}pz zQCF{D5rsV@sF1Ng?$*&61xOGew{PJB(leK?o;r5x^pP{g2ofG!-khmZXHMZcaOB8A zjCe4tJZ0vrkqk$&WHpyBr_roNvl%j<KZ_yrMa&n|r@5p~oh8c^*RQWgi7kaT6e&+` zKY{Z9g!hvrzm*(W5?o2~Bgd-*F=7OSh#41V80irtNRJ*ktmDwW9Y+oC-)p=OKcmHh z78k;^NTEJO`xGYNlOXZo!v+oaF<8)VVZww5{~u^TKmipfu)qWmL_om<7-X=32O*45 z!U-chK!66==?9;DIPB2F4?zr3#1Ti_XCDsz@rT3}S!~foeEKOzjltX!<dCkkvP!8* ziW=&tO)}Bx6Psdsi6xd?F(w&@P(sNSRGy?r$|)s!g~}@<vJy)uwZu}Qhg6v+6=F7e z$fHq4A;uU}a7l@!mX36(NSJJ@6BL~A>`6}`feI><p?b6gsic-F^pQrafyI<*a<mHn ztF5^D%B!#tImA-32uUT9MN%=P5Vqoat1h}|1Vj!lh8O|~FXkA`FvAj4EHOA}g`<r* z=x}TeIohDiGR!#BEDbY=1uZl&kS*=BFH}>FHP&Erjkal_s1^z*u!W)tCYbom+ariG z?zkh0C^xy~L=XYJ8H&gbJMOdt?>q5cV4;QbT3|t6_S}0fzWFw=PXi3{)2~1O{%at> z0S!Db0R<O4pa6*}tk~j-17IPZeKvH_<BvfOS>%ynWJiux^<e9euoh`_sU9%_O2{GY zgej#Ymuyn!D8202=bv5aa?6PvdL<QOSP3O1k7P-v(`Q04DbA_oq|?r;@yu!eCrmKW z)6bu{4%DbY3th^oqZEbes;pXu)DcM~70XgY$TG!`QA|-Q)VM~yOAtNCFoFjw<Y0r4 zS6_{FR>f*<Je5E4_(KlK+W0lt&O9?#v}BhxtywOfZ7tf_YO@wwY@0~E+irmaH@M@9 zAh+DvgDAp?>U3x!-4trbp$K?u=nlLW!V^zl<Mr*gJ^20w_&)p$?hn9(8E(M91R-wF z!Hc<%5P<-i=!c$>$qzZj^3nhJpLiUBV=lG?K?FyvAlb1fu7lhOr<#pK(wJ0cAvK*f ziDy7F-~q1$r7u0{Btc8XI7$K~H<5x9O)`>8;#4G>T+L2d)6+?S#1o+Z;4dgd8QW3H zX11sNVNp)Wk=q~zx2{mCQY$+IAo}n>SSYFwdy`Aw<N^mF2muLO7>ui01*<tMZZVB( zT;=2di&*@j4r{oK6)%T5&5?m~o%5Wto;A8@m9AQ+b3*Exu!L?EhmGJGSGi<YgxXQZ zIz1o)5qeOAbhQ8i-nowOf;TUE)oWibSP#FJ$2|Es4|>s?-ohBxFzg{fdlc*5CBG*J z@pUYHo$Qc_P~?w)jFOb4H03E#nMzfz(v<mt5h>I_7nRM=D)mze%zng^{qc_!IC~NX z2k0aTMoEDPG-gDGIZR>_GbPNxTQ~YQwKq{MgL9h6OR$!;Pxu7?NMg9cBRJ6~uyM_V zCnQt~l>&)RBqJHCxXL54l9jh<Wri}W;iWDmi1-o0hjRJh4+T+&GpI@nhI18R5~sLW zHPMN-YD2H+V2V7%;tW<?gBgUS#VwM?i=PYK=tw68YhCMfXxtX-hQr3!!LeL-yrUe6 zKt~@~r#d}o!3;zI0pi802J7+8AXz}jeYFRXij+@%o>wsb91K7T8<6!R`7laW@{(0O zKmbr7K2~m(t6lZ#SHT+AQ_`a!&6v?$RCc4b)zW_V%ccIVW-}#45Kh5tU^16k%wrA> zuM)hg1zGWokp%F9(=05U=A=OmdXOib=tLz#!G<^lLI|G!(8MG<F+#ERh-~O|$|?u} zi)kd{QB|2|%VapIO5IbRt!)dad{~!4)S(PWK!O(bfEOepPH~H2TtjKqt6o(!6@JJ= zD$ZbrET+L&p&5;`mi0N%g)v%V6lodFXi}7_^mVYC-FNR81RspIj(?nK4{)lk7u+<b z_o|oigql3%G0y}?6<8yeiZJR$Qj*!DYE>^80BvYhtOYi(ClM?n7@1=YD65fL8>OR2 z@W`z(%ikvUN3#v0LP@S@NnP!_GraDVB7J3Gh%FcjF+IZ<G07k`6RX%dX>*%<%4{ea zp#@Rgf(>j4#Zfv@PIIEOY=@f0-BzK9M{Gr&^i1vlB4}7CeU3$+{p4F6^ht&tAb|~i z&_fatia1#HmZ494Xyq!i1~@=24HqTWo0}^dj&`(Jp%Wc!WMiA_VpqG~N@*M42ws<l zcf9Alj=QuogC4*D0(|t&O@oTOeIe34@F~F}>mx9w9!$TGBv4c%rab^(QUD6b5GNCy zYE`e=mHl7`W8P;Y`LzuzOQG;kNT@$NT@w@>PQ@z>i`Wn|)313owuw!QOa?C7uOXfV znml|#41PGVL|QD3^|VdLLY57Cki-}IaM?~oLQrDsERiDt&q<^r6_#kS+nyX{*1Gn! zR`#bJ#E_~!^nox(3^Q++Nao)*^vslN!x_&1@VLmWfef9AGZ&FXXE0J1&!ih^NzsVX zKX;d0aV)~1sZ;3kzKc8F>5d2%009VGpat)ZuYCJuRQcFP)B9m+Q=i%}hlRR9qvqaK zUmy<+v6|>bPv1Z2;fOZeC1q2VACo1Fl>1pY+ZratG)(a(n+aQhC>}Plk4<c^2h&Kc zNX0bz_hGHaxF#IDlh*cRV@qfv4oG;zxW~<-TMG)^OlitfM&So*JVFsMbaK2YWhuqe z+ui_`!wz=P<$mAgh++=7Ld)#LGe0!VYC!lJQeg)=(4klxg)VA5`qAoA>*A=(IB>W- zE|1U7rPL8GdFx2>?R<v?Gf1z>*Yk4!O8cvMNX0Lwo9gMPO0|;P^LfR-=LGSo$mrF# z{)_rS3Ns8QWodmn)OU32T!(OGpx^{2u+Da_kDdMPM=^*8XcA1AVk1&Jtoq$P6K%#l z?wPo8C_+IKl%f;LjkEZ!?;^n}oWd7aXc`nj$ztfqpp1s{iQekX$_Swjv|tFdz!3cH zp#CkPFb}wbtKibiqRxN}MlTj%K@G?tbDV3=mZb~oO!X>`j7aK?&Pa8<g}cOM_F9V2 zL@qo2X!ii=JACh6761lF;CR$y_?YL?80q*r&C{Ujda$SYEa~|sB$GDj`p`!o#BdDB zunf)c4AC$R)$j~q<QUAr!Qf~AW#)-~Z0RUq27juK6Rs{5)^1K<jGEjp5CajIU;-mX zffp<&*s4t?7;%I2kH+$Z|N5jy5^&ti?cC6bt(?Lb{J@=H2uJE^0=q)-7S94<D^$8q z4+udEgg^`4AOk<J-(H0<PUiB+47fIra?}8eh6UlsKn+siG3ek6oGV$n=!+&U3$S1r zvEVhVYowY0<G7^<0d1weD+uq%2X3zieBfP*FkX((J0h(HR=_+UfT&<Dk%}*1@PlCT z>ye(ydaf`56ktIp2>~W%3%O82z9*~bVGRK?AO+G4IfM+s5PcS`4NeBFoX#tt&Xy+Z z4&MsHaN_*LBqnGg#;R%m{kl#N-A~w1A|^0`7Z9;(7SU=th_U!@PbTqCI^os^1rsw- z0Uf~-QXv^8;S(bz6e*AtP0`BgfDrm%3UnY20xA}F%kmUz;5086J1;XdBe_)Y5A2`? zHwWUNiwjJH29xp5obd|u47*T=H<;iFxP^68O7?(|2w*DY%Ina8$K>Rtc#a2O7Jxm9 z%F-^)_y%S_-Vx{c3k!L!=k~E;1fUwG?;sU(G4r7x;-L=U0A;$*Mj$N03Pt>=PM0h) z6&kVaGO|dhX6yd2BRz67rAbbb#1vkk75We*^Y11iaV5Q`Pr{~0UQ+L5vTSOpmX>T4 zM&S=etMCpFZla9;6id;yVk>3p;1C`U2^66ZT7~lb&GHK4WO|D!n-a~QGK+lC41%!? z=zt51v7@+hx+qRsEY5UXPj#YT8kr#W+{ohwEv9ZS2YMg};Kc~%@~41GUl`3iQh)?1 z&C=}azBWyI05dQZV3M@3Fek)96hI#80o53@LW@p(7NNnI?!i`Oe(2{iG4sN90{v2f z6JApz)lS;h&NMml#Y|EoQQ_=b6PtMLHQz2aWs^@vNXX0yDKfE8cGFRwf)38^0e3RB zdeQ<fFt&n{4RoLb`%SkhPbrr&^Pb3|Dg#)c(&0km4~)wX&VV#d4;fd(2EUT^uEnHO z=PY6G2feHRr9STC=u^CMpib*FKfzI62I;*f?FArU0oLO^h))Uw#z3P7LHCP5u5dvI zQ`8)^LIMB>$jU-l1eEe2MGP!c3yiF0feZ=*tvJ*nBMc(#(5+<V6M`gBJTtD;Z|m5O zMPXG=Op_%z!4+2Ff$;A&RWe6)LYzv7oH#2cCoF|_Go6A|0Tp2t)M6D9K{$~#@r?5) zt;{YYK?rof5CDPlq%<iL#};RW1WS<fun3E?2+qjh48YSdN@HEKvIe0=jK)YkcQE6& zD=lHC<7iJ#>2tj5^p6lNPlu;JCk-7JAOcL_JxJhRGA*fW4pFUeQ5Tf?v``-%^m~+G z=rlF|W4($}L58fP!BZu(=@f6)9uh>SE;BJqO!kKpcIiY>^bce8NMiOyUqZ0xkAi5_ zMzM`ocS4-V30Q*_g%Hs1YKeZf!Ym+xv>bu7>}hVImGP!^E`kyXhG5^g4=JhBTV(}Y z9ZFoaG@~>sG`;|G!eAIX$6enQq~f)V)HHSc3_kBw(8A01$jeS!U<GPm2D&30iKlqz zC8z**s8V1CBA{Rs7Sk5CFAufT;!)=qwNVN4Q6J>0B0+pOmP9O73@_JX5;8I+lS9>t z*4U~J_s+t8L`+!r{3x<z>!elvuti~aBVG6Wx*-)<Qx6^S+IE&#eYJ$9ZnK0H-Hvtt zH%%*PAA#K<0kz(SIHA=ik+bmzqY<V+2t1JKuvRI()k<r{Dan;HmdgxM@LY{$^zy(D z#6UbzuT0bS2GJDbUXL2x^ct}-rV5R`aKH$3M+9zaZv#nB|Mul#&IHQC0RUA4=Hmkx zwqY5!aX}4oolkNFpa8xhF*g@POvE57xJAT=R~8af8&Xt@)z(V)CoCZoQ1|>eLDzPT zRb4l+Li1&57XS3{e^8+nC`fnrk7q^bSAUjA1tliWX(o$yZA?om65)7LVHLU}5$vgX zm2^q>hAvi73%m>|r<Avr5<3Y_TrFq0nCmmjKs1g;D;=W@%76yDfLYYnEAg!VeWP(b zd2r+6SAIcm2(M!WBA^@ZB^(3xZznAs1vLd!P6JHfJ`i|d4ir)2aZ%|pL3-}LBzJNH z-~;I4L^9ZdEg4fac9U7@Qt`nN%%B!GG!9vYme|VH#D;_$VH*CR6*^%PQn)8p*zH=l zmTj5sY=RS7!D!GfcONl_b$B*S$cKM8H-$JzVMr@F<+N0*d5;rnr!_C8Knvo4`@U>S zLvYNllWV(HJAnmk-^>imm<+<0bEW`tBIgUTfD6jg&fv9ub&y``)n3=K_Owytx)BFf z;9hQO1_J2_iAP`uR(Vq31Dfyx7GMDm**@ISk*0@%8+c+VwqgSy3ow@dlQBA@HM)~w z1Q)&_F{1N*(yBv6_msnLvn+v?SHTy~&;Kw?mom&{Z+WJ%$(riq{93{6rs4cvBExWW zB`30Xe-==H*GGr;Sc{j4wW9DwVG;gd6$Bv>n7EnmsRCQ8@#-QdwLk|H0WY>SYqM92 zv$Ko06m#AzjIokk!7~r?fDBUaJV^%&MC!WWcw4sRZ2|2~X|Im$_&V@c1VEsF=Q5!G z_m5*vPzzZD2KWLj00Zp9FCBJ~9oLZ^HIg4R09=8<Hd<r*p&vH;vq{NgzW^~7Ql!0) zWWf(a_imL_VH8-p5kBFS<1TA#^fPJNmN`f!&W{-Cz!<ur5%duMm~(U@dv%<Knn#0I zcy$D+<*CUY&^P_S7@l)^XK1ya_IZ<&RQiAogkTSj$S$rqo3(kN#M)NEHA}x)Sj-hP zk_F<#G&PK?48lO2%`<I9M>g<#uHAP{{cPi8?;7V*yl&6XfM@sox3CTSuoX!IG610$ zAOomyfpadRE8DUm1VYW>qCuOJFPTLaYz=y)gGJiuP`hMBxKta#7kb+lWJWe2QNv`q zg=_mYQ}`MFpc7`oL_r~#XOlLE8l{1FXwwazhS*WwZ7ZZ2O`f_Cq`JC|^O>PoRNNw~ z^<WQ-pxZumI<Ys4xq0)@OiM2Zqt=^?$UNeri)_o_3e5EXOwlw4&xi@`dY<Q4ZuhmX zwc{K2({JG`!2{R?q_6}AreF)UKMdvp7+3k0kLN7>vRS~hJN(hnr?UZp3`pCWCv$GT z;vpgOq#I!pY<y7~;U{F9{AT;bXZ+Mr{YK4?6aI%6S^<T5yl0I&W_}#VjafGnaCnP2 znU`1*Mu8BXTB@10s;LZ`qn1<%K?t^BwysyqvbemvnTx+Rqe^d!j!})dK)&+;7N!6T z;My5k&k0B>8u=Tq^SYj0s(#;6_k@R!_mocuy3eI>J`y$q5;_AiV5uJIVH15Y7u|aT zKn*Au(h2@!+As@fMZ~-Bv^|s#C2YbbVF676)cYj=)>qfmQ(b3Yydp_qBv7FfJ|UKQ zT&RhnHUlNdh1^(?S*hX8D-xj)R>5who5>g9$!!F?k6mi>f)xXygRdBis}$P1nXJpT z+SwZ`J1Pszn60@$&DA!f=(?^oPL4Saz~{5C|JA?`9Ki*5Kne7y5SU;JmjM<41#T{3 z5S_vw_}?++7c95n;U4?UVHZg|WNU;nOSz<%+tv=n7b5Bz8lfnB)#5S!)HnXcDf0Ye zK^A}$g;AAfdzXiS_7a2msE4;`lbO0*z7X&xi3_0*h`rcxzMuN0%3Yw#qEpL7FzCBn z+S6OTU-02JXH2o(+l{LW!hj2!@tyZ92m8$b+|PaX=938Q{2O^{uz?DI^U|p3gP|<| z-xE4Nst}?DbE+bj?JWdDhA!^8e?`Pc56pm8vRszp5YuVR;UQAu>0lZfp%DnMgiV*Y z3IFiv|EF~cmK(ul$D#c}VblR)lfX@x3KArk36sKw3N1N&2yv3cNE9ntyhss}#*G>s zL2?8#q)11LN}61hC{dwNbWDvZB<PS#nSyHC1cWoE&YXIB`s_J}kPt0>`plVAC+X3p zOy$gx0~IP1op(Id-yg^C9_GDVT>IKv*B%+y-nwR1b;(YB?d-05ZQ<Hm*H%VkM5(To znXDqIkP4NAM9a_b@B829p3mcR&Ursy&zFE!@Ex~DOpRGD)vvs4I{u}W<)Y#{N0Xqc zw_=qq4W}K0G!%IhFFcs~n=f@!Sl*@W=!cv{FiAQIc{XGYqLe>k#dqe!4y3i0JD#8E zqG%}I`4Ok5{qyJ#uNk{Qoy8)<PON*I?~L0M()Y6DpjR@1i|UE5jgcJUdT~qb22>ae zr@XuiUSx>+VUl0-MjI~X0D?r}G|7JniC<S9#-6YV{YeC99<EKM>OK1P<IC%ZH`w(b z|2aPRJUP0^zEFI}Hvi>pe!h*0i2a;7zw5!6SaVC>glxX5*SI*lk|WU&#+u}r!gp=V zGgT<^9#SexXMa?7UUhIhrPKw)B*WsFhm<KdN7!YtTO_>~$9{D|o9Sh%&RG~XIF8AN z|50Ma#m|JB+t|G9awyRGTW4k;-(Ec=^jD-FbDApRa&mOZ>U-gQav_nc$mMeVh$Qco z?hno$!Ou+mxX&k{O@$Jy2Z}4nNarQbR5b&C&YN1?rQQV>Od-By0jK0BJ>9u1psBT? z>`KQoQ-0>2dRqCl{=eK6!B`iP0gOlBCjrc<`qKkEXJJ+u@hX7lV%q~sDghAl#VAMr zkku-v<EhXUdELLHuw*AQi4UB%AfeE_M7U|*DkY)fD9uRKu#T9_6Jvg@?_*#IQtD~l zoTU^On<Gu4oE|#HV~HO~<~_Y&P8O^4-fPW5e;j*nq8GYhHz=ImWo~X*mV^*Z#so|V zKRw7bw^n~6UT+JqKfY8Lc3=RrdtUYBgPmuF)<-9w&<M%0lfW_`=W_o?yp0u?W?ZE% zM1Ra3!Q8M2fznf0wWX`AH4j~CEQyiEXgjN~{=Npml3R7PPBAhKEdfmYja~74+t(ib zm0SsK;`j+@zN<bH*wQIWxDc_p_Tb9fXki>#^)DndXqCcl+Z*?HY#zpY)%r)!7yu+n z8iuF~<mD{M`m^LAO*a*Ki{!<3`f75jJf(K>@-mcK<M!GJa+LKkE?dTTEy-KwyiC!q zNBr&gIk~3Z4+zG0;c4vpr&Y?bS<05_6o&EGQ^8mkM4{fX#;A~K`)sO%Ol+U>q{5RH zrzz#;Xy@`PeTAJBI?qpqN0G-sRURWA1rs_&wBexo#KtHxsZl{T&<sKGS9VBh_Iw7X z^FDhi8^L!s{+XH=fB99z<Z`>h3CE^;j8Nrv08E~t6+)eE*^bnBbenko{Qy~K+pZTo z5uEaLa8zG@AbG?f*-Agx*_sXA5$JSH?3LSya9l1uea2k0DmJ&*@H%SF0xgn7OP06y zWVLl!PnQ!N5s90D5y>^CCAegXF%(3RMiJEnUEEE&pPR({EowAhz}nQ4Ngr#3ipLG- zH+)k1{C8MCf<#3D>{7oejL67cDHWSs;JQop@%2`sK3iGPt9+Eh{Jrzi>>qN9@{s|P z3u=m#{q)H{rDp-4mMNd?b_#bF0}AbTtHYjP%iu+(6wW#lR39o!{NU^8|DFUd9s-~g z0Z^v2!j_ND&6u{}vbVg?xyV0qZp;Li|C$+9e^Q!rLt2jS{0!6ks3lI}f5cG94rjE3 zCzF-Vx~P_D?bkrKn4)b+22R#o&e{%s$)yIp<A%sQASPjvH^Y2cSfs-@o(c}+MiIQ0 zEF{mH;VfBDQ}dU9{6m;mkXxiqM7#wd)lh{r>s%5j-%()eUa`qu+~tnCXTc4fT93{o z+!z?d>{1$K2*4Z1)WLuD0ZmTYtbq<<6tr7ANN`v=@qQ34ApDh@b-*1pu7iR`MQQ8K z+(4>e7a^pC(-5W^c5S|c>unQq@#Lbx`hUw1zqJQj>^Ho_?#6v>zI4L0#9)eSUmIpW zJ5^)!%|Nbljt^xjqhXvA4yvjgOEcN-o8kG8pIITe*r)kfG4+VTR*TxqkQF~;h5@2g z+?tF;m5}xx)rebUe}0KTwB|%djW~MlvXy9GseqSPlFP8Lb*_>$Qnc=+TtML+NUIi$ z2-^iq*Q1NtkMGd_YX~fHwYhrdvGs&ce#M3iY1baA?*U|LH1?VM^Hbl%NixtFK|#6U zsf|7K$4<{A7OlkwS|in<mmb+%v&1>C7Hm5TR*<QcVurA$7fDiG{E@2}o;&{3wq=2q zRDBjN)a!`yPg|p+z3s4nswawWdYEgd*GP^GH_AQQ((Jd;g@@1A<|Faj9XT=!uco!X zcNG!OQ{9x1qBj&dn_FA6!o%IoHyaV<X`9BnhIVh~X7A@^mIPnDm*!YEh)$w8n>TBi zZyGM@2jMq_8uH9{FYq+Dj%Qdu`}C&l4JQA;@vZ5|z_)S*d$uvk60vWZC+bId$i&Nz zsGB4Rc6AY9FlO-b&!pN#rYMI_pf5f|%-No|bAUbS1z23b&{Zq7H8S5f<-Dd4_i(MS zddufD_~JA7d7>+0jKat9(Cew;v_*Du$W6iTh^RJE4z()30sLpTXO^+cr{Opw<-{6C z@u8b)8LgO??N9mFj(Sd}B%wUn?dg1%y=y}1q{VT}92+8MqQ^ORti3>KhH0fJA3c?_ zTMs|xMFz0Dp$3IEcOQMWPo9oc6uv&6^!T77AU^(3g%18(eD)QP+s6N{9n?wML?flJ zHC*BaWroVt!a$g`t15OMz61Qc*L+dpbz<~<Ijb_(iOtux*)5_1qPkxy75=&T_A5D+ zKMEBOOke69CRTZ9=%ySgneoig*28M{LlhKyI&vQ=P6Gd1X?qd!>Us8IYB<H<>1I;z zhX{mhPC2PvZAmiY5E<dOF|qTu)#N@)$LjKL3w0%!e9^;|Ej5i*$x5)mFFZ6q`kPf) z!+xZ&-gw%#()fgbCt;QApQQA;6j&~twx=~Pl4|&VycaniSi`5=Jqa05c4|8Fl5dky z0(W8DTT{i`pq#yAT{L|n+HaT7%OdZVz2HvxJiGr=&i;>$i-X3?`P!Xl+dOT;|7O5E z3A%;jXNo@0=Z$AtaO4?#U*mG&{@qzRW;|UV|8G{vU#vkX!x4uz1eZgk+wgFwl*{Om zpj$JLE4#?AQaTBZKIBm!s#%mqhsV=ZcoLpzP+fxJZO<Qti6=qa=n|P5_F3N1G;cjs zCyUhxl`jq<J7FO;#UaM~D)zLPUsOlY`~DI<vBinJNN=k%#jy|W$6|&9xV=dlW+0{> z(#T?%o|K&Ei7J2vU^5%;`Ml9Et`_hSAHRHF{@kL?8;qBybjsxtn`63sCmDJP806l_ z$^YKVum+JsVr@qunW7XRn%BQe-8j&=k-v+W5B7Mzi^w92-3mjvl93RsPEjx<hJ^g` z)ZJj6%<xG#l*I9OdH@DFxT%RJ>h}ER=CYme+@HQT>w+bs{PL0{-_%EQrdm|qx1gtn z{Cv;T0EgNDpyy~<i_6lQW0v4ys#7N~GbF6E$f*>h4t6H_<dYb=>Sz7p^v)Y{NP2Ra zCOadpoTBA1PFK7)v)*l<_b}HyGGIFfCAeuMTy;qxEZEBAYSHjaIdnXqr)!1_`Um7{ z+(|D{H4n)$$JD%wfOMXM-0)jucjpvjFded$f_LRkXM0bE*#AdOO)pu3$B+?RVTm3; zmBdD(1U94MageJYqr|Y1EX5hkV;QZR8NqYW+D;eg#UVzQE$Nuks4XPT(@{h!R2&{V za3t-_DKp}K)9r<o$&$=zae(hUKOa5JIx0>A;yLOG=;E+hOw5v9kPB-MU-y@fGKs&K zE`OT92*kmj^rX0(C0uK=lg#CKOb<$<Ble^4*C2L51*yp;#j)v^bJ~#&1UMbwPLveM z42Gop=k&cm*WsY9?MSA5+9S2}L^Dp?dx*kUDQAH=?oD_D!;5m@L0^&xIgy0Z%rK6g zc@Bwrl1&+?`*|FnBs*j-DkAiiweoM+t0t|%oybz>7?88CVlpDnSfL2kTsO1VrS%a> z1_%SAO{*t$1qjKw0HZio?m~SYIRwrVObj<IE{qWaEVL(ky-FsURgD?4{{|r6MP{GH z1bJu#4L{9h&F3)9W11%-_7J5z#U&a~i%%>fX#nPzBxJ;Sba^|>o9J^G<zq!gjD!WT zYL+UaFAH`cW<aizv*I_qJ$}KM(*b4TKXRAE{2E^A2IDDrkPb4p^WN4|0@3AHftfmD znfH;{qp(a*GVD=$W^$fmnmt&a47Mg!jPe%f1;;ukJ2i#eynQkd>p36r1RkjQiGRVh z()UHu)SC4)+Hl1}BRovQ>8P?#SxAOf^(mw(z%72lkkuZ?eT8ncxv9B})H>u=nlwU4 z<RQXb?S>tSb@NIRABa&kSx@V|9+QKLpvYV8kT5bb=BFuhFTR8hJ5NHgYnAetDDc_A zgK5x`SqO9kY{GzA6Cp;wpl;Q0@s4WUT(dvwjUr;fHRG6&!zjZUSkP*e*S+9oq)Kb4 zWPrVe!g#cbWi4Jazo9_inv@^ij!mD9v1-T4{&X}ULG~jm2Ac@QrZOgdd}o3SDmeHd z9|Ig@<Fw&fi+%O8v-PuyfbKlO%Maupfe;sNH~c(_x#B&}?K@Movn8xsm#rkC6|2qE zOgGD6G!oVuZ!C+^WSgQkQ*&0CN4sz6DkI4ZNG?;lU@ks)CJn`uTk6J9&V)Er=Jg`N z|K@V0CzW}Tc=ZSnR{%VQj>rHYKJUS6QO)8KWg*VZB+)#aIecw2czL8uq0H|LU+u^p ziw@09jXN#YGZ1xNSjrsa!KS_q38I3B8tyte%t)UdlO9^SRMKN*!`EhF-sa62$LC$Y z#a9^I>5K#<vycR@eTdt0vjOb_z7Vb)G4+b2u>VG#^$N)j)ouj-HX7>YsHK~!l_NIc z|A`J<6R^w47{8WLf-8N`4A=^q@<qm+0HD!}?S&6-oo-oz0nmKFWl?6OR1}gzgX#gG zVK_v@rccsOpHu=zwi(QL25hnmH84O_%GBssHOrfDHH^bT+hOaSHNK&gfjh9GaM)rj zEFf4VXrRmHcl0@{e5#$JH4W~+3ioWsTCbLC`a>LWRtf+x&6HruBx7M&fLf?4KeU2I zCRw{$KliWPe&8I=>B)ivz)5m3XYT^rAvgGY+52rK=2+|rFdty!ACZKuUe0-Cr77^a z3{)Sh1FrwWwbIF;nCq$RzY#PVGUdS_EFby%ds^Xdu@UgSTskCX_gWjX$9U)IuTbM% zXzK2@RMag2PKg{b&dd`$Jdgp=LP0%u;kQYcMU|Qtg~7oLm>V7%g712?-0U(?#whD5 z@`iZ?cYhvw)Two`8~NDy#l;lE?k&0Q$4l5!Pl#1;tE3-qPECdLi&nq0;EUk4aYUu1 zjI1BE4JdH`vn9h$696F!dfj2HqXA8%yQr4&q+0neGtf)K0sr&?tM7L!m%N@kATn^i zIl+zT1g%Sc3aUYUC1)ogM~DOxD>8IY@H^6EHI1LYx<nfpNP`yP?p<*HFB2cz&!0$K z|4$T(BhJCB@GyS>+$VBG?=&nq2X`YuVrRG<(NCQ{ZReO<-V{nMW^$X=@Wj}`d}g2u zn~z2_T8JmjG0C3N+8I)F+xmBT2olAuX4(b$9AgiS$5a|`&Tc)KMlf`W>+NMU7J$jj zBmj&CDDW76GoZn`df)%S_~(##;j6+&9Y~A^ck1UVkGx)>73Upmcyn;$C}-(C>v^`b zO&nL4ex(LQ$UyJA57Br_^P(VRTxodH)ObHaj|Qd9Oqox4P#kri(%_egP$B?liO!HO ztT}&A*L76*{pIQACds=24&ihuFK){lyWF>Qo*x9&now(#4X}cKF`g*sbJ>bK5nlVD z(Lw)M@FO)VCepiKb*XVl=@nu8b?T?y$SWq{2*5Z5)xaw#^hgxW5S=R()SNJ6vv24A zbF%$n&1@pfve9e>j?rYA$VZ%!oR5!rFyt^_%8W#uWt}L(ef@;UrNb`~Q-{C{xtfEI zeUQc~$b~_l3%-qHA~+0yH2bpP$6aHPYj&FfQJH~;5p}cjgC+ZdBk-8))C@ee>mBr> z7h^hs{PvqX?7INZtv{3>LC^2}gt%B?KQKeXZ%Stj`a2F$4aP66{JLblU2!+D;7Y8) zP@MtGqc9h~`=~e8^VI+d13(J`U~OK#RuY<_jhD3w*^jR6h}eb(L%kSxrFElaS=)iJ z%c)Wx`PhX*qv8$)opN{4FZTySypf^pkn$NkF7q}y6_HJcTdpE<l2=gDh&w0su<X^9 z=PS8<{v)?{;Ym2S7XzY8gAuCxrDV9m@R;}3)34RuUQuqj77Fu0!Oo#z-#lPioo^!z zp7%tTr${c^5*_Wyu<2hda}WIWkp&6XHz9&y{>@KP;+Lu$mV)K7+%3cBMApD~Kz{rh zpCI52BV0IJNTl+7$&S!b2MclcRbcQyt<G|tf&_)86@h00y)I%qT8Hf|ckIw;_{-xn z2z(X3Xa;6RL*~m>yG!PdcUE0xEKuNys_3)l85_@8&CflK%JO51Ccu-35|_wec&~k? zsvolyJO}`O->=E~DOi;&q+O<5or@>lnI{tXN$I%D7(5zUnR)I61+k=kY#4?7%v=1| zFa7uHJ0H0vknLFVGno$=Nm^!=%tBdi+hfiaSul^aXscK5T2&R<@!ao(Qum>*sO{Qm zO<wtCVNMAaig*kWQ8;Gnez@KH_PWB!G9Qq69@W>#kBlHrJ<d)LDZkBL2D56l<Fv@7 zkP#7NaN6qB^DpU{_kBfc;VEVC1^}0?=U2;J;pMmHo)yi81XvJic|AK??zUuc7lrE+ zw+EdkY%Tg7^W((a@=)D(4y&L}4AhPUpT6@=Z1kJg>rwK>9_ZDXX=FY0`4h9Wu=Kw- zna(i4Uv^(>0lsT*y~zc9Abv0Tm;5UA`*xym?kePp0W9DIx4l+1S6jKR(}4)5X<LRO z5>#>eclYGJ{SvE2G!vDMO4~)z$RZ5#Zp*$-KVskom=ONuXOBmAJLE6rAaNtN)3PRv z4!;dx)^nFIBZ6(nm`1Ea&`fs_04@_5-Rk<(@^^;fI5f&YKYAA)@^9z+&LI&G{VE69 zISc(5d&ZLdbFcpAzej{g-c|oeJ{36Xj0=l+3B`mdNyb`Q)w2eI<Pg>injxaWFlJr_ z>(wL1dn!!CMAo0qs2hjCVR#ar#7G1~y{GG3=Rew<ik%_2Ird9>bc19z3Acq!yE=>X z?fIY2w;Y=6>TT=YUTizvIr>%laL$B<S0(V|Wmlqub9RN6|EH<j4rb5Ydt(5=yt9D? z!Vc*GL2dE0Zz9Ht;4`8gOS_)K*_boFD@)(KOfsDRcKkNaeQ%OaPb=*jLwn6sL&e-M zC3kD(t_b|~d3Jv0%9DsV1jsmc=juw|*3<aUJ=fh=2NoxkKBQ*f?hF79$k<aeg|vdF zP0zRsPV;F8Eg?KReOW8i*M?#*)jsV%R^570E;9dCxAg9%^~~eJ51F@g!Y4M4hemF2 z1Hk=W1khdDIzfg`3^tIiAbVwS-y{=LW$utDNQok%*J=0T?#z&=Ato2WVZ|bf5RM^+ zm<Yr$)=aP=O`fKFesOD0`CU<IbPC6beVRxrF3%sFq1tO+o2C8BTwL;;whU0()k}t4 z5_)gXQto<Ly>LwX-kueHD9KVrc~W(Ms`}3soK0r<NS1Yfu$fJvdkLi2_WA&~q38hE zqN0}E-cPE|8LAv88KZ56(U<LAeK00Mt_2+?IJ8mDa~7_vs>T2n)^;PD5;fiY&o;BV zV}N^|o>_R9+Wp?Rd^OFrZI?_1hdpx%1?^8WMmPE5Tx!`qXLQ@LiF5(Z^{bDaJ;(Z^ zMveOD=W6F6^YKdEw@m%PU9p?^e+*G(MG&N&0j$UG5@1~6g9B1EC4;BBf-x{_aLyQQ zh*e+5a2RbR{@qxZ>7v~T_vMqg4jAv1F0@%<<i>ZLFwZHJnVKR$XMR(8-Jg=9<E1Pv zWk;DKL)`+$0rKvVePl4ipIjM}V7TvFG3zbsR~74=QI(M7IcU?qDsW|b;~Fd5xjul1 zc%eSGNL|nJMb3im0o51Uc2fe0;)RYlSL0k0PEIhYm6gA>yW1VSk@m>GkRN4y4|j@K zU;1Ffe&7Gc!&djjK)F(#WlKdZ-8M#bx^|OFkNmx!nZy>~ak+1<{)@GTkM4dPIt&Zy zlNMu9-CJGH2z~Yp^d=k~bl*U#iuMR8y-_)sty7a`Xp~U6`|}bx6K8lNO2JW9DGuIt zYsrEQXs>jsL$pYy(g}Com}t(z=6jl%;_VFxhI|hI;|{hU7ti14NCZ4yofE$GzWAN+ z(TDr*{94xo-ZRw<*;C~^1#E-6yvl^E4R{SV4X!yqT&6P>sv|@t(dk&I2+8xN8Kx#E z75Rb-U)a-wY)HI;P7;g3!;R&M8hZX^%^Q1$Z^ttJyHV@38dS*bFata@U!5(mO^1oD z;#h}cJU;ZOB=5Meg_T+jb=`SUH9g?xPXBGl^MH}880X1!0e61e#S91O$Tawt@rJW( zCW(2gE!>m{;*456bAt;QCBk>{d-iovj3A5W)a8=>i$w6|mcJLg8haX5rlnbn#|rLa z#|&Y4xrI~SCrmCDRuH1Z4<CCep#Rg~J3lQdx4;FpI`jHu(+mmkOcqlx3GmsN@rW19 z9br!Q2<jv_cxE{yFV~ZpRQQY}YEaGQ$uiC&X~-hq;%pQZM;Mwsm({M8koZg#wjjH- z!Fo-hV)CsQf`{*)Lh${vX@P&M@QVW?3cjUOOkjIbrwg2XITy_DJX5I>^~rTMu!ggl z%jB4d4tMz?+6Or>iRf#);H`7nNC}f7yK0LJN_zi|BBjH5YB+$M#qN7AwDbK%$IQx^ zi`-bCap06i`Bgabdhd&yt0Uuxq67&zS<mJp#upd`)ca>(NryQ#>CRhf(P_{iuCF&j zy-q&Kc_Mi(ulfY`4b-cifTj>BrX_aWnJ~`p*5(8QR@!DgqSbN`s#wEn!|;6znN5*E z)Fi)!`2F{VZ<;?lOfz8Z1@JqiYkOghMGrB^yFt+U9@WSiilwlv;)?cnJ8zYTo%_@! zF*9>))(Oyl)8|r5Ojb<0Y3nb|C!CQYy-|JrNx2v!MWa3I7Y;5MfflZWn-kW}X>%$v zG>Uj#x?^3vV#G#Xzm&!I*>C`}3!pH(%;E4wqLoqowTM=COsnP~a*2b=J117;Y$+80 z?&o}WV4SLteXr1VM;6TQ@)90sQ<4KHzwnDTbs=Sf#Xc>mQ8VHtVQo(>0!IOz?3-#R z39O;Q{x(GWrJZLWZSTfrNx6}LnNelX(BP&aj==VmA!Vyuel!8zC1Q#SUP*U;PYTmo z-zsBo*IBN{^I+k{gPFX;o8PqGC$B_R%hCsszxFC0uSd-;a<k`1PYeWIa&*_D97Oj$ zLtDU=A8l73#PH8w%qtLA{ucjV1DwbU2JL#-JQWA7?QTT8`QvL3y2@|4`}{nEqj9&$ zK_THizX+Ru#*fFA3_mW%Glg1wo{C<WErldl;nuq+ny1@XGNgJoMi%Hdk2Wr$UiI*Q zc1Au*gLQ{LX<ys(@g6NT*gRQy7vy!h+mr1|(*T<7Y|-~9Gd71_sf^?Cll2=HKi^ZX z`hFwuk1M#<>gG;hQ}%3{sf4izOH>*(<>u6Krq@Cg<np~e4~P%;$83&c_7X1k^Xr0Z zuDyJOyyAyE4teRXEM$}j$IhaFikf4ev$qq^t^WCsJb6xT4@bp(+2{I3x$p8pKq~l) zF`}PQUk<ObqT?&AtcumpX~7VYf5B6R<U3azU5C(?5#82)ZW?JM5HDM<hAwWM$(#1M zDgN?Bhg*Cv!q<<(hbKK<HayvK9@@Gh_ys!(KC$?bzyjeoh;{|gHb1_`C-rN?^V9N8 zcy|c4_^aYlZV|HKf*~KZWm)v7Z44LM%E(^az-{16WCGE>Lkb^cPK<)?>nJ0N&J^u@ zZY|H<*?Ai>&<Fsf<xG84QJFgUt9;n!^#Iry_u)B2l_Wo)e~Bm?wJ%TDJN&A6o2IGp zrYzKohYy`qWi4wu>))&mYLoJ_nQ$t(Z`5Ug%v|-Ie;bNWGB;>@H`O<NeOk`R%<Op4 z!equl1dd8AaSd|;G57Ae?6(ZCNc)15H%KWMjgD=5fgVD4mG<+5m!FvhTbITkSL-Yp zTsPJW-L-Vo>HTDvgY5j;YZkb(r6uzjsWb4p>I^4uRQ~;ZO)`X}_|Z+V7z+S1>P9Cy zfbD?DU5&}t1U7jlx@W3HFDSG_<(nng<1F{qs$4y=Lfc>M#1NNMuA-aK`N(05xmh&H z^!**XO>pygy`w8clL#_vf7Dm4xuOYC(*&6zx~}E*s!LPshWaXux*1!28}5&_a<iFL zT54U3c8OrkUJ7QF^35nmMH;M$17nv!mpJvOMf6V<hpi5RNqLlzaSFt>2`1Cp@esv2 zD|nXn<jQZ9xLmG4Nuo=8va!xEj)Z>ryXo~{E8*Tfz?5<!lj0g*zj$;V%$$%{a(`EZ zTp)96PfMkwiBa?lN$~GvyD6*`ZQ^osL}?&39tDwH(mDHEal~-oJ0I?n44VUa0INDU zKdEZXS+M8=Y2VT`kcQmMFE5q@>Go;@#Y_(arA}PFOLB*{%hVY%8R<FYv(^002G14x zmNrgUP*sP4(npUE%$4vMkcdBc_bin}?U1>b(^5V}b*lu~6^jvbCB}@ddo~Ff)k;X8 zmFO*=v!ir1Kk1RHTIZ$Wnn4@`i2~*&W*CiBw9KR0;kOS;-dT!g(9<HtblwMYKrzCW zp#&K%l~E%T=3zz*9e#smQZY5&OxI~ZN&Fgs)9Xg!>9^vS;Hto~|A-XDyqub2#qX;l zDMQuzbZQSn>utN~9nrzQXoHEUtUGpEX6@a@laejsPfM<VG_iUQ?tldVNvCp8WapsM zkYUY3HZAiMmram1`SC;ucZ@esLfYtLpOm9H1C*puH6TscN%;hwp0<37hzn4RHYJl* zNeP$M527Rm)e=~!(pcl3D-X}!8<Ul`$!G!H+|W-hMfc|q=Rg=4Kn{jOUBs39U<mS@ zBSBgTS?Ge?4@pNRA(;xsZRWtvr?ma6QnH+-+7|p%+;q(bZz~<H;!mkJ?)~O=C;9V; zy9h*38P?S_fgR4jw~$p(o@rNdN)N+yk2sf!eJ0WrTe)+cUnGrD+}$m5kE6@gqwxKE zPi6ZDnK(xuK-j-DQR$Ov@f3OgfkYmEs*^oc`Ls*2y-}ouIC9g->&n!D!xMQtNN@&( zD5WeX3Z@#431{}C*(;pP6o}2L=1O*gbr|5Yn?R}8wb->&>(~9z_X<zul_NS4ult|j z^TnkD$a?{b1p(=0e75T?=_Q(g(AB&I!t}-h{MW37>s0EkZFsbKYIr*w|BUcy1@1Bh zr<W#+VT-9l(@AFs<h?Zq#<}J?Ih*U`epL)WKuJx?$#(vH=O!(e2}x&Y6q7NBN9l%8 zZHjuk*28sv0~bL9G9K`i3n(!IYR&fT%T}2Y`8U%z>Dr-6qw?lb>#v9^NmCVE5@m>B z8Br>Euw~!q3ESV%h*FRU9wg?U$Tb6c6AhAPSZi3Cvv^WsXDd?+YHtK6+?;3<Kv3r7 zpDq09c@boDvbdlicUB|U@phq`_`0kj<fgdT1)W&;wvRDLsrb24lCa_`heG@*8pcGf zy%n<wk8OutA6tyOni|eXjcH2VG|o@_O_4+ms9$B*9DlsaaVBM7gg{Q#Cug5^<<l{7 zd=oWr7^HXmwx*X3<fDsWW<+%_DoM;=^4h^U!YW82*lG<h^B-pBLs-QF2>ts~yW<!Y zznhJ5r%H0@YvL$EM6guZjQXmYf;9Lp*=gzyJ6o$09;6^s0un1pl)%kOmQ)JucO?BW z5|tKw>E`^Kvt;SstmNd_gZ(D+1M?uky2s5WPaYZ<@%0x|WI~`O!z#j0o5kZC7Ui_a zp_;ZQa%%ZxCtD4<iFm+LOi60|Rrq!P)QI+!SUNlgutZklq>m?wVo@GJIY|ynUpGV^ z%d&BAsKECnA0S*GoE~b;QwXe%2KiuV7S{)ZoXTm<_MDAEGvKr7`2V^Vtm-GNe+-5N zfz>pr>U6Nnn3eYC%5~L?!cD*!2=kFNSiuD-?GILTnTnTJ*EUvfazef814+{a{lc1( zRw`MM#@-UfzE_<)Y=r)+b?$nk(A}yGP`!Qik+Jm#7A!tzK4&A1CPT@9V)N42NsY&? z$jHim#-mbly|AX-#Emzpu_TYE5;#jr>eKGjvI<gde}BSQikK!!e#s+AH>c6K>|{eO z`~6bqlW50zR#*MnoA-m?fQJf1U8u#A^REgEKe)Ie=D`xZm|_X3U~9dQ0@s?$-004V zJ#%o=I9MMA_6I(>E)LclOXP6@OLI^aXF$qiGBYdq2-~#(`J(&Zi_*9;!7v)9pfjry z1&;-<92a+Ax%5-8WTRT)MgQ4ffAwj@$|->UYppixF?A3Riy~{}UH~#okPN_*A=Ahw z&=nY)gl6rc;%(A(2I*X6s`o01eoU&^O4Y`CQa>pEG<SLK?&36Atxw42Vv)kW<>#Sj z5wK8gI@M0|LW|C%db{UJ$%X&&s{eXWaU~1EWz>SJAcC~lI}<MnMdFF1t^DM8W1J|} zc7)w!vrPq{uIx|cLr~Oaxa*vpuy~L<4Rn`LB)2|u#<B<R^<;K^2;)SN)CBRdg4tcq z^02<Xxh$=B*!1yxt%dh%+KO|U^oF&Lw{6n>a}X103vxLJxyZZ}fS9&$UIq9sD)wzu ziL89iBgN23Pb*WIAFr|&t;9UzrO&2_ktskKPbWRkWFJ|EcBb|W*W-I!4$VGZzJo!k z$zEk;eaeQ=7{j;oS@Z<Q%WP}};;A+v>CIKwq1!-zy;BFxTd&)`eu?ryDWh?NRx&9? z_0$@*s6;U$HK;=rot&r?$tk~nakR_HM{JA|q#yg%T5@yhL^gO#)WMmojy`(x#4Kr8 zKfy*g>)8``|K%=3-=k;7>T?^000<5MMv=^l7~yX=Wx9E3)4YfT6&v*}+p5$^fA|RN zhq9Krieq?d2^H<k6Yp&~ZR4VOL34{R^QoD$rzy})?^Q#J2ozMVgWl$kw3287n+WbS z9zMTgP3?hPd;6nM^a%7uu+jgqq4kCJHsAHT(|Yw(?t__+D!urBQA%gQ);*D&ay1vR zWQuCZXI=-v8(kd_pMGwaYxUbVV)dlp@|)Ozxrbct8*9=@T3=EEYzU_Q2G@dC*YAn^ zxKvsuGpR>rW(R;1(zANfp*`a>kLRLT^Anoj@pSkJ>os^(`)Xm;N<!L5+ziv{mQ1R* z<5}m|25aq#=|Qa-5wV`?`z;^7%j@dC3iu(qv$m6E;twig4&;rox=-8jyY?z%j;cyC zW#Yu`z}{N_*oN9@Po)>tcba`urf&S;R?-C59D_LhIq&YSD*~9YGl{d&e!m}o3(x&D z!=XU!cN3nkRL=mZB8H^^HtmABI@ztdr-$qAm#MR7;n&>}QsY^r!NE4(09(MMDH)6> z$K>agXN<GmLdwM7LhDDk#Mv$?uCT)_BW4yO(ju-CQ^z7gsuI5@1Ve-gG>(^M9F95r zn}hO6VD4)I?_M^qhi$v8Wr1ZI#NYAX2S84gi4+T`$hDL`>08%&Sp;-<6GaU5S`W1p ze_lJo{!Jo}o4a%L5TB#+oGSf*!oJHSH^>cebrPGQ;8#Tt_)$8G`_aDo|4hXWd??aQ z6qmH*<Dniy)!g^42Ok0sx+LyDdjAj(x6hMj{L^K;pEzLVnTE6cuxm_bKe>%Mb4-_> zNLYf?`{1!;IIG^(=-tH_37?8%hJ-%_Z1JH?alp^w^fCziL^*k6n@e{1aBnZ`Qo)_a z=p7-LR6yLd+PfmUIO<m0!my`Ei6F79NNQL8=a{8tK<?X#m<}29WS22;g#uW449Kks zmb;fTF9KE|1F`L*3n9xd`#vkpeLkTcC~1gNTu{bALzjQP=^2bPreqJBJx7PlJ10ke z>FqukbQq7eQnX1;k5O3!^w!bNuRei><g>@qr7h!|N@E%DSYm37!uK0o^;JssF~P|= z0&4nK#ii%A9{Kssd0_n`@MXBJV`fZq+>+x`R{f2gE1$}Zq$%>mk4=|8-oBgY*XAgE z2dH-Rx3%h{3$-F}XYvgD{tt8Z>AzA}mB3ezsT*0zQqokR-9(i!&}lKO90IIx>H(wg z<531l6aV$M`H_Ry>nu1WVWk2h9CFUN(q`Gxc6-6=xuV=>IL4cD%~8Tav1FF?T6lJz z<dxN?>QJ979tHQuQ3HmOnI~oH4(;aE4vpzml9mNHk%OTWR=#X62FY_PsexTmCylQg z_~H&zo0kn;4G4n3*|09{BnAKoovyKIj#PNv6NHA4=5pRXiHrQU{;c`>nRky9PC#t( zQSI+ye(VZ9_51clFD~-uSFshIOZw6F1%%vC2`g^JOM00iMo(F`R09`UT<3k&D%687 z4*ha4WBa<?{b_Z&^Pw~ucu&d!$;D|MbmF|)J9X$2DkvjJs8aoXQjBEsFzaT>E9 zuJi;fjvIQbU)2nqdSZJwAwFiY`CVi7jhKI1s)yg+Nh!pf{F|YV0FK^icO+FCV0^*{ zk||6VXQ3Q;tie;RG9RUrH7-ue-0Bo!Fd~^C9Ai#1u#vYj;p$id<{Hbk9nF}W;qE}2 z3C3eMEW}F-E?b_eN%M15USYg#HNScrGU@#l#~_V)BMM-aN-qiu?46wIL9C<*ClFKk zj~74)3xfdy_Bu6``ZY)p@L|VdrRDz(o}!j{Yt-jw4;KQKDxzmQbL8}b&8sQ5;?c|g zzDpXn0>5>`Qe~oNJT3X(&AzOxU$ih2Y-l+8o~jfoUR=>I1vDJys|gIeeP^z_dN`<e zT*<7ZGeHB+<}sD>Hu_7)&#Jq-BgK622WzRf68`)!GbJY_JWa-WSc{|xM=x<qqKT?a zbYE{oHJHWI1ADTQ%y(_6Iu*yZQO#jO$65)YWjY}J3eJ$)n*z@^?XqxLb(bxqzc1BV z={*(SusQpEgOg~foW77xwB1^8bh3}|DPjs5d2t?^X5s7##{iVe#BL$aqYJcp8YkpB zSMFU%v5WMp`q5=w>a*zE^NLRYo+=%m*^^r)bK{Resz833UwMnw=!5NRy~paQLbn<A zsWQZzJ2E(X4EjxIsdlSulLx*U-deB>8x`>G$H~Q<c0(=SZH8tpw~sU!l)W7jWnR5E zrT01+djWCLl#QoFh2CxLA8CShv!11(y=d-jsihYZjydgGGGTn1E%{*1@6-HflOM~m z|CtHC8ap|Y{SPLOA5i7h@y<1soeCZ@SKz82cC^3wVZ<%+_yd3$Pvjn-Jac18@1R%U z(ZT$0DDTwou`gKf+}nT7-D*3Ssm8d3e{`)*$v6drn-t2HuO!svy^Y?N)BQYWd#PCe zzfer^RK$vp!WGRlzNNvBszezev+u)8(R0pK+DEIWgCKtBCvMea7Aw|68JmPDJm2GV zN!5hkuX%Ldmny0@CwWByIUnFfTsDA$n+PKeg`OnRLV`Ik1~~^!6s0j6I7<ZRp_j-I zj;}79LrKtt<ei%Z5y|+qT>SY@VV+=zHwgl^|B8B=FZM%R+DIe=R#unz)|FuSB$lw7 z)Ob=4!Q-M?@Z|G@%G~!#lA~jSCV?O__yO_sP*Nu}^(9Gac&5eoFKLu3dnT!3Ybq{z z`CI^oOMagL;tq8gdcApG?zh@Aawr}u_=l9y;5k9|oTp;wC_yJTrh?KtM(hs&aP5{g zmQ$~$0L6j-xE>Do)#QU-x;*f}r`<(h;q}|2kGIgunMA4^ibr!lS+bqXye12t)htNW zX#op%%oudvBqgP*)-m-Uq&8;~Y5%{OIww8WzaeoZrf=+`5=AuYKq7B(3qk6bud(*` z!=K?p-n8Jew5uq<NY{s0+IwE!O)&#(BwL)OWUE|2v{7A(qe8I3h{v|_SpLbc5#fJF za4Yxix#B_92Ia~CtKW9)H?a4F3%1}kvDyw3^cuKLFi3pzr|`dxtMQF}t9<rAncCZa z2@eeU=M^I=?FPRU5UKUDAv0EOgWC!23PYSxIFOKdBHZ6ej=gSXP$f!AH|&&w-d-)c z=t{dbI6;ap=+j`Q5R=3(Myg=rXV8d`OkPa}Y+YJyf?n0kp1VVsu2nd;i-0_beY07x zniTa*gr&x3(3gGAHOfG|yD@D2(Vm(K{}1L!mkqQ5v)kF%To%<{9vr-aOm=Fv1vQw? zk|I8oWCxy6%S<MlJ-^pMOX<py-{iE~Uz`8zrSWk2nW80g*nGt=qmy%rwJc}p!4OGQ zcZjL(t!f<?i^KX9wi{zqnd#v37o+p;IQ_5{v=`z3QpeHqW|qns2S_7&nH6<W3YUB6 zRKcJ`7E_Xuz!Jez{UDKb#=aSqgo2&&zicMNL4lpuRhL9mN~2!mNCsF#pW{~ItoKV# z^kk{L`2b{X5X3z!kt{<HVX~VUWD>ugEJeyTGR3zV6s>N=w8^nJwNnLel5#WXJL$@K zHTunn8G+m0J+il34U&z;lSBfl`y=x5XAmptJ-NMDD{_cPu$j_`5&#yZ7+xz!zEsfl zkn%Fq68?y1Xw^~haC1~|`1L*0pYO58I7I4T_uKs+EOwSBAL<0OCGLA!a$POVbE@Aa zTDCG_iz1>1_(1*dI^*GN@g*RZxA;`O@M?I&;|~g2GJ?!^MVQS21DGTNTzd-0CVym@ zzR%aiyw`m<;c7!B)M}8o7;ljJC?vTTz%hD=WiHGg^c%uKup1<%a-&err8nME`o~qb z)$D|30J);xecb}3HSDBVF}V!aNO$=#o9T+zD@qGD*+0K2zb(F!(PwAHgtOYqzHSCg zYk4k`Y{d<_y18TcR5AIV=0&DxsY=^(!pBWhXbLJ>N~b!6XPLJ_=5~Nd<-l!%ic&&E zVb?jYAMA}Smz=mf4r-`oESmW8SreObXLcYAoAUXDGlNjI*W|~F>uKjsYNv{XdlswV zKTiLAkm7$OcqIBthe{#z@}SqlB((;~`|(pC;Y|0H)}Rj`8rs2AcVdzIEbAO4yWSF} zBJ7$dWpp+QDq5F)>+WAE2Dr+k<WJhF@!-{Sj9&a(S%DgKq4aJ_Y=?pbz#4?g9A%+@ z*ZcV${Ds6h&Z--l=l%_UKpfTG?$X^EM=GC2)+>M2C36!Dc9m`oCQqaemSr~N{T%NT zUM=P`<>D+kZncs1^4xB|vA1bs_CP3Z2Ga2E>DGtYAxt<b)#mVC(fD*s%qC6f!g>m; z;psF&{EO3zI_#yj)UFS#5`9arM_g9M-}Ho>yv{lu!M~a4{Yy;2zQr5~LQdUxH*F0t zRcmkNIV^_LMhs7<n^(T(Z`h%;<6d!%OqV>%zA9KSAmeyWdOT0H;J-dzM;&N|ljCW# z2k48dz?<B?-B+KL*gb*<Jr;z<LZ0s`tW9oK)x27`40u<C<Ir88YNV01?3Rx_fXDKP zYJmCkmC*qI3qo~+ydJ`bKJT9Y<+!?Gpv=hlHR~z()RMIYcsqUB@sX)O7ofd#lrM^F zr6o}y2*@%9<PWwF+~hb_)1g=lAT0#J0wAEO5+G@5-zwNGxJnv%vm#>-c24Vc;ltDc zQe3k8P)>V-iO>u(0t1{9G+2u#Z7rNkYP>QK+MF*6aeZ>?U`>8S@Vq#H61et;Z7`mo z{C3rjKD)U^+Hy4+_8BSmSSVp3hw*xbLmA97;0fJo`t60t^!E|3FnTjXS_c<(zYJ;q z!qk?E>7G9DXX`pXrrhMU=_6L&wj90&ir@^;p~I8^@zb^igCC_7{$)?Y1hc4qz|pZs z)1#*XUoN$kjB-H?($~&&2Mur|61f?|bE=~JEC$S*WbOi>;)V4%Y-UHW*Sr3b8`7js za*cFe4f|=N76X*stCVGeOmPi!hGSXi{OMCQ9Iei5CAc%TLLbJRnI8``B65|cSFgPy zZT>Cd(|tc=@_y?o^z()HRX!(T;fXiZ3ovKPKDgG@Tm60OcF)KC!3X!p^_~kuJ8!_c zI1Z0>ACH$7l?Pz{egYaJG&NqakF?cGdCH4x2&e$^)(v)*P_T^RyNJ3!43tcAnW5Lm z=!F4JbCluJvOg^V{-#lZ0|3t#%a^S{eixEpdm_4G^oPPaZ@~bhm2kDJj!%}WW0ln_ zZ@^1Y@<tj8WXM^KvZeUH_Pm+`e!0=>ZGdhkaFenzxYE90#MD*pJV664hy(-!G}Ia9 zsL0OT$Y;iV;N&tuO_^h6%|AP$zi5774$UpKkl0De%?lzc^NkoOc^E^_R~(bhi=Nvn z8F?CIk;u21DC$p<J!wjmBmmL|Jn(K8EjN?w{ga(HHS9&ER>0ppt7|)~Yj4-;te&pe z5jIUoo{#x{A^Wqewdx=m-;99}gThw=jQd*Qy=TcUz%M`i{Izl6p{_U0P~3RhfYoCF z!sQUCS%V%<3@m~3tOAtAS!>1D#kLvT!>JcT?D;DU_~HzhSO(Zy7*_*PK%q(CgEuMz zl^}|jTKf9wf9p$QX4Xm684x(fVO+&GJQ>mu$uz*kV6b2ljhfP;US@tGzKY(-k5QCx zfMJ;DUg8HyJkfT8aaFAMT<ulGwrrA}z0y?!p`lq80F0;0ww-V;;Ovx7Imy4ds=$K} zb|JD!+xcW|f{>y!2G-pLK*)f{Z?;Grk}DtHC)5FXn-U!=>m)j!-;G;NFE!*sRPy1T zdE3ja%)r<@2L7PE0wV?aSMB+iEKl9qu{d9Wpi^O+0dJFM`<KG5qC{B10QVO%GuB;k zE33n?{Pp<K<9k~xkG4X8(NYd(SZLxbs{vKpTMw@~pRW1)h<ds@`tgON)9;=90VBG` zPycxRj9V@N%2H}`r_|}r;Flt0-$1su*<qH&8=~jT`l^acwx2>7@;dCz54NA#v#0Sr z)uq>Jsk@E!S=WB`(IEp6U1XHzMLKaTD_JDA+y6kYT(EA9cgg0(N2eH!*N?Am-Jz}B zJtqUq=0H=9^_GA{QSNn{>4B`k0R9SbFBmSq1Snt*WUi>|k6cnL95{W~yDz-HdE8w7 zQjn3IX=|E@IX&En0};LC2PQx}5&5-&*SbG$i}5BRNJVJXi-s=7m=g0(&IYCjUQ9*9 zO#d?RgMLcf0%cpy<BIR|=|RD_TMBz~oe^s#{Xt{HE$a6e`kE;gYhNr}{dYh5v>Xnl zysY<Nx|{TI=;Fsa{As6}K1O=Y=3Lw64Xosi79dMyo#e8AQO`Lc=Sw+!4vTqr|8ynh zips=F-$oa-{$2o_vGD!vfpTbVe$$d@{|e4Krodch+P}k?J^c3H1MzokFUt~uOz0Cf z9;}~qV1B4#V}-M=uPTtIf&nTpz+e+mh*z8}#s-9I8x*NPT?nUR8={NAyyA{>G>9xi z@S%W19|`(D2y9)`=CroaxtCj}5{5P(uu2vQRd#HLjg6L<za~tbCkeR8Z*r)FaK@$s zqyd^sj!BaLak+ozy8A(6;)8Cmk@g*d8NFps)f6qZL<E_@I>rq5GtF=-1L+GN43xxG zSHmk!v;J8Z>G8A7CSDjAnC><^w*MS`06-r}$5jCNZ{EJ&X27a5AQ=$w(+l<DE$dsF z0Y7P;i;?(X;`6MiFK^m_7wl8;;gxcAdi@LU3{!ln`72C61L=;NQc8rMJt>6`mMip( zrTKhfD+y-CB%+%>o%tymo2OXULuVWH+jib&DFY03wKXVLIC%T;n^cs@7n`90pw(+T zhCCiki5&lSG^}!_UsAvG!LX^FJ8M)e%vTWZE86-KU$g%Y(DZy2kcBIYH$0%G#51nM zRAyxDhmFh?7Zi?X{=zYUEpFh-AY8D^_xDQ%S~HZN{>Hema@i@An?}a80D1lQPWZ~D zID@SxytDo`uWoy%NGo8h2Mk-N3Jfyri9r5rr~;K9*jmJNi=TzSU@7?YIKq|nUGP>y zi;}~gZBc>E(%gh!w$Ar*8!w(hvpJQ~nDdw%_1~|+CE%}#`_A`IraZXMX!E5^K<BW} zC3Jg%kbbZCCcuE!8evBRosbkte+RY*X#V@WJOfk{Ow+qU4BS+*)Z+(ezb0`;dQz`& zFAzAbuP6%MLuraK8xKfUUa++7T9(Own=!x_4rKNZ_h0xSSuRcyUzN%WmC<-7Q@h9R z1G7ta=4w)9b~M2Lsap*pDF{~~G|=0Q#u#1$w*GbIDaJ@B#N6BX$qy@HxnkVgB9??% zyUT&)YPBkZylA6tmz(3jx~lV-CMPP!1Hg9>91-;`T{B;$wQRrk>bdWQ9kW&WXN$Sz zmw-YWKpt9-PG&VC9(Xyyfp_UUZ}7~kXT`$e)Ytc}v|~@y4d7kIw?;XP?YNinl)4!# zQv@ty;DP<2-uZ)HE{Br;3Of{EqPr5S!v}a#rOZi0>z><L&>gT*u<Z3Tg1M^@(I7}p z9${vTcy1MC*<ymqtvQ|2MKMDd1f~T5dKCckXD}}X2PKw%(5(;UQ7aQcIvsL<3ksaD zzYZn<Ahcv4mf;+i9O)-;{S3QDKUpK=KCWKEjnbsI`$c!`L)oRpi!Z5K0@qGO#OZn* z@68hxmIj4;JIl**#Ir<xF(?m@5<4MTr|Voe33&1Rk@qLx7u>zee24Y(&+70Ga`lbb z&5tnBUVm%eq+CI%bX<6c*Upv8yqP<|gB#$sJpuCef2S9#+b~@VY+TP|A9gbuVBR3R zKMPk__8Qhko62vSu9A80GeD?lR`1gYJ~@Q?D%NsaDO27sdG=gd?)duZ=R-d*u>h1d zUIYgKy`fIA$tC$(`vL%rm67X2bpPbpNQLSj2Nuzb)NdcZcpgzNyftJ-9JAbHo6-Vu zS`Sp$rrrEk(la9H`NLOtbdcO%vF>kQd?%6b7mJBeXnk1R=yjbyTozV!Ebm_8gNvHL zbyk%RXUZfe{p*JP@tN>PF)i$DodQyC3J+Ry_#+a=Qa83%)&cFWd+oNPI{b!_|L&Qg z44!l|pqN(V6oa+^Agl%Fm<Nu*ER-8hO3Ng~%5|rl8d?g2jw?GZ?gd+%PdhHTd$x>` zETD64qE0J@{oU7ikMbZTmqn_}lfcS9RGo03o3O&;)`*8A0xYk9@=XU^(s;FJSkL&- z;yDAgN^jxc_kR_5E(i2W)QiKe>U?tO3fSPd|9~)V6?*Aw#Dwr<DXi!*Y>ZC;h}2Bv zMM?2=C30`>aUyIpUjG7L9<y-x)Q1=*M&REQV)tgdIF!)ZynknFr8Xz<*{DQhKY_gh zk4PiHqyb3C!l?7v?Fn3bp8QbMqt8qoY_@>jOCw8{7Ya{7JvIig?r-E>-LkHSpe9+} zrJxnFbDGl+BZ0<G5`JvYUT)ku5i&?T!K#NJp}dUKK+v7nKiS_s4%K!epzJo%@}#WG zR6Ru{tV?tp+PwP)lbDMYm7XkM9QK(@&v->uX&ITa@GARGmx$!U0_IeGX?H??VFDd* zJKT0IeDKklSKZgSUFN+*mVJlSvjR0)%vHB;Ln`dexQY~p+l;)vkyoFE!iu(~Z7Hkx zPRUb|5Bo#0N?tOVyjF>O*uBeA`7*_-<Hl|5QdXL0?DlvMK8e*@@F>MEtD;{tJHbP~ zf+N{q>4vtOi}0uBa;x~Jk=yAeOx$WNt4*H$rdd3brJYd&pqPVAnI;E~+(F|*4oOSe z?mtf|?EAVBsXh4ZAIOgr)+IUeF8?3^$^ug*(s963%9fi&nhpR$*swGPm<iubhH!b% z24I45s6i+@0#F>knTr@=QCp!6vFZNtt4`VD%^l{j(Ls-3oTf%^#WCIago{D^kEFBU zin43l@I6HhFm%Vz-5tWvD4hZ#4j>)Uf*=mvjkGv~lz?<7@C+TIk_w18bV!4Upw7p; zzW=b--q*VJc^*fL`!I_SZ`Me}`E&wDgm4nB6Bb*umc*wYy-z08h~wr{Iqec@D)ehf zsuo^U<`JxD6ZNVWFK!{5lq@r!5Rk#!Xr#!^p@l_Tmu0;g6c@o{f~7%4E&N!A8b^V5 ze^4<L>gXvha$HN-`&a!m_hiR)SyRZRCwSZId9(BMS4sFaA!59I`YK@FIc=AQb|hLQ zSbo`WM+3rUZzP_;Z0BAUMT%T7h$X;nu+d$s7Y`{HcD-9ERrXtE8&zo3E>SVZ@?(G< ze6kfEMO60!1ENOZGl0KLU2kq((=efdD-sf_`(PgX{BI$g+DL%yqC4wG2Gz^>o%XMX z)b~h}<peCp0kuFGbKrTWZVKHB@yp1KFfjBxN-;W7umHK6G|KXBfKp}P5|X0zY9A~h zHF3GNAst<AVcfQ2m@L%VQ&PCq>|{Ohp(hsW{Gt4#C-Y9nPDF~k>VNn(xJ<6T2C1~` z-Wo!srND{on+;ioq%MU;z0?RY&S_>`upzgS+uYr0woRQr*z&Wz%+I+6^Wb^ny(fP3 z-5Y+A{ZY2}uukMme!X}Yfu>HxT5*^1!LrTaogGTmGt&Zm)C4OIdG9+?9~%Yh=|$LI z??di`0zlddIPkaoFM^2?R9L|0s;rtb*5|*!7i^FJWIm>Zag*o<KdcuRT1k6M!Woe} z%@)mE#B{KhEt>~U5ke>NA=HUdvL9xrbp*IzJA-J2syx*=pEgh4)q?ZjnaGT>(=>KF zopn6~{tC#u+uh<r_%%c%YE=0YNa4a^VRl`bOm+i;!@RX#4<N;r!dkT{QjVmiij+$; z{6!{Fbw1jH;93XTPRnlxzCm9BxOr&F2HPl<LQ;d?K{B2JDz3=fg(B0&ic$6G-DSSS zJZ`A~xq4t#w+I^CG_%g2f9F#QSG5e!RKJu?S*6@6=lS-OCKH&WC(&r2<@v!co3bdy z%Q<SX&a&9Wwfq|%D$QckzgO0zP_={p-K3v!(S-RfiiVjfMrRcq$EGTcWD5O;eAXO+ ziHf?C5n7Y}9t+6+ezj?|W$@r?j98}7LxWgd2+kZyBdZ)`B4Bk@I-Sl?P>|^8p@i3D zZoEl3R#x)sQ$@k6a4<ff2D6)L^g}@#4Y*U2jFF%Qwd!o`R4Nhg6x%$>ZJpT8-#AMF z`}sQag&0OdKq)NTkwR1wq>Arn=s@=S<;p-v^zpY^XUf_nsW>Q(iPa+QF%Y(6;HTwB zFeR><!1>eSBM}w_`rKmAz+5yX7IG2<2Cp*-?TLrdmvN52Th~=8Y6@#ke8B$dF58c+ z^v7d~At7|T{{hw+@#8#X&+IYOsgn9Ua*oobJ1hoyLzTiCtB9E2(YZFaZ>!jzW{bby z5X@hiyCij~wQ(9GtHQ;L=W-dJt9bIA-JKKarm2_O9iaEi1oJ0GdG^LuG6w-MJbtTW zCW@)qZ?~96sb)zPKfH!X1U7#Rts-^V#1gC9u*^XnW9LMzr~;-IZV24OUAN0#n_n(a z<f4fr=&A$cZ<;bEdrF^}t;zKL*jGzBlp`U=a11TTUChgtsQ_qisp0r)?OR4p@rB`p z5W^`^WpJOKUOW~b2MK#f$0=gvt9RCA&)S|F!vAXY*mBRF?I1?)Cq@@;j~W)jXp<@o z3q52CWD-U9Bf@YTXxyGv1-D%7iPih!wR`d6xSN1-x98=KLfdtBXN@CF#L+bjx`V4U z>&pc*pS}avi|H0*MAN}WL;B(Wp34{_LDZ^RHl|Mtd}__Ssp@xQZp=$$&M1HSjzy;) zW`SWvEEqn5E@7O+-<_!Khp{w8G3yhLbujxhCkvJ$&?r?wWEA!2;LvHw_RD`mKJ864 zU#GJu%XhPDq6QT0B?QJ$AneF~{XJKimy0^nw`x<bPRwNU1;Y|ULF5;+U;=k4f1#q! zz<Dkd#;+sB@XRAg#A~g$-1;>4)atx^94jr>RtB^Fc4TG}Mr#1Ec?J&Qi=vjv;ch|_ z8y4I)Xu?{E?ZAi}Yku74TaP7WnU#(lZgMX<j&7xww?t~Ek<fb?(fn7{?2dvYk4h3* z^<G-Z2!;e;B;#2bukTKBrNi`_N{|&7exn1%9!7X}nq0K4QKWRPk3qN4UE5B|O&`X0 zm&5qT#rF_06#vId*YNLOL;Uv>f@)KaB6vSJnk`T~bC9ewPEx2=jyrY)hsHH?klp#p zx;NB2VRhM(I-S~K&KlGtL$K|6UC@|RHE74A!>oH-MoE+M<|jqsAt9>Kj08dx)CAVN zwc2Rz7yR1sDRU0GOXel1=&WLU2i4u#FOOvAlV1CMl){3DmHebuvMpf3*c=!W4g^1z zjNbr$D9II|Aee|HE(LLwS3l)j)AdXJ^S{2_8fkdm(B&J_8UFr${4c-N;MmkF*5h-} zb(Uv(RFSkt+%f7a`?>jGZc!u{X9f-(Oz}Gnp^y^q*JLa=jg!R8hsXcpxJ&!(`#*=7 z^H-cK6Kze=IsG~t4t(8cL*D@6JC2ffFzGb-w@f7lj>M7${dAR?Ql-C^dGkR}WHP91 zC}N>s-mb{atTJ?tOz^+3LO~v7K4oKFN0Tr9s{i7pNVHw@ppC%lj&Y|Q?Hak|d$6j; zon5Wt+htOCXg4H{=}G)0cErBI&kI{vO{Mz;ATrYc#M`}9cH=tak|9X!At%5EOGQG~ zZj(F#K1okX+kcps{M6Hk>~-Q|s6^HSJQvAC8`hcUD=DwZ8sK)1$mXyn=6)Nl5|W-0 zUTiy2l$*0#;9qNdq;=I>$!IcikL}E(0aqj0Tr8<421;gdwGe+*cNBZbZ_Vb_lDcj+ zQcJ`QjJg6afEW=vtfUR6Fv5cj@%xGUHeEdbh6YOuc2xI|I<_dkg?Ocq;Di1g0aSPt z;CBQ@vhIl;Q&LkC_|O*z?8jx_!EYRQxZpMz62i**t#TAZBPR0>_bOd_V>T4th$TP8 zQU1XrZirh;B9gk|Fxx5m2h<nwb?_zRe+#%(O>vx`Byq5*S!kx&jxb3I*4GbDVz)+G zjwXvm!_XL#H8Pozsy7dPJ|9ow3~?5BoXNDtd<=KUJSv*sX25%=;12*|Q+&zP(Vw7U zc?V>?B!0hf-3EW8f^(+aZK8ZHHX&L)F?TT0G)XYm3x;MLfdQH^QEJ2~Qfy6!#V-W2 zO(j;zxxhuTHJO3L!U~W@vRS-}{@be4W^CzEOhOMSVfnIY^gdL4KF1Pm81ktNi9bkk z<M<joQsS`YiwJ)+wP`ObUa|;BOu#~jivajTW0EB@qVyBeh(>c|NR0e&RW2STiY3a! z$7qVm>DOF!`O9~aKH`5LCvWh`!QI3h5Bg}@=I%|t^hy3nDhyA3knO_pgF0!ispR-% zxqctSggxvU>x>i${%3+Do*}+k<)oUCr1l3H33J9*b5Nady6ds%qpeZsdj&Uq)bRo3 zlT(IGaovD$Cr9==WDW8Vsw2T?(puvh-4KM%A`&E<K-KG~%lZTm`v){`kqyKrH5TBk z^a0{%Jc%nMku{2>9OslLIjFoZBbi8=h^@E56gEu@zo8LnFfF#56nSULHY&8_i4mPX zR+<8_*Wk!&V_<VUUkPo4UvpuqMc(4Or<6x6WptS29Y_!juCq_@2pou1zyLWvBq49Q z{}^$>*Vt$JsVyd?7y~)=qhPKW>09MQYTgz@25-14dU9jUoTL%Tmf^^B*$Qob5(+s3 zI-+|L^ru+zf5>ppY<bc_c}{(SAD#o1dfR!pVsB^7$0%qjnyeg`nJxV}`weL_-d7C? zb3iIrj0<Op@3sYqWKb*)_^S+?D-}V=1W;`=r(ZqsdpFf;8*Bg@vG{ft$Efr2zUg7j zjeScWbUG6_5ht-|r2aikUBpu}x*rLVrT)bShDUQy&QVh%xPFy!;sFR6pTv!W2@+jV zemqt7cP7ZvDLD31HjQRswHdRv+?D6GO|qX4dCu8=B54D{2XF|M+70g(KFqkhTTnq? z`~ZK<lL9=+6THTaK+7CU)Hp6zGW)p^qI@`MtuD%1n-kkKuDtEKhikqwOtU{_dcz!m zi35I18Oq+PluOdE5nmO&r1%dhqXTob*$;si&cJ16%8n)K;><V>?!e#}qM2-hm^S&_ zpaa%5P0-_{%I3Jx;7CWpmOVfr09e*Ewxsq{-uw-3uyY<%DuT38`i<n_8X1*~g^abc z#vAw;3QkjVNkpOTA*1_j+RWN0np?+v$W>q6G&2YXTdBCaK&9+}|5B9k8?|HeV(trJ zZG^auG_LC0s>YJ7Ld-_<y;9XrB{hS)=2++$6+#{l7Da(Js8tJGAp1f_^XKAcruI}Q zwTm}|Q{$r*t5kd(jJ(}}`qbe>>_N5H1JY;*#EBG7w&D{c<c}+?UZ|+VgH}jK<_B4H zo2#T|GhAPipIFS<Bf#11$g~knHilgnzi@Icw+fq%vX_%WKi9R$+g5HGxDzb{6(Wnr z@C4x$^U=JSNy2GAZD?PUHIrIlI&2?I#+Az1H5`amRFouEkayFol;)|{qCM&H5Tt<D z@N@BlCi~e2&TzQ8S%UWm1``MdI_c=}rNd<V;saSO$H#sShUpJftz1$4P(r#^0^M_x zRFs@r&8ettwek$@`xIiW6KAp-vOgGj72Z_X8i#K552jvY&?gE{a+2$O_=uLtOx{Ik zeI6^tl66L+|Crcym_*W?teVy~M^5C8UvbA&$fHj8H+1_SKgGTpY;B}OFeIqd2alKo z5OKHhq4s}W41^uyZyd?@zde5<MCK6CPu2d#;V%djR(%YXV`pgzO}0s6s^S#og889| zq*2x^7^biT3pJiWCiyqAfsw(|QXHgk<u)zCfQ;8sPYd2pjGn=?`Pl=ybb1}KC1N8> zA1B&NdG&yKUPJ2?k2jZ|LiriL-8~h(@L_cU%3&R`uK6Jvq3$n#{vZVWihb`(UV|-Z z3$`)*;V+K&I6<k>;lSyJ%X#_sKcxtvuO&`C8i$9b;&muRW0Rb1^TLRaPun>*R@n#g zAHahh0AGp-T4HHra)V;?m9-<G!|@iCmW*scv=I5j!*oQKA7N7K<;K~XV)}M6d<+>i zfNFH2OZ}y2%{P`2{&B!HO{V0Og)|Hnfy%^sxV<=+YpG=|v~t(!x)aFgQKrRS#sdqA zBb)Iczv%?dW-E(}#MPo9BmhLaJO1Ekd0{Th?Dye6X)4?9@+oU1V3|nW>~qxc%J(<h zg5z7)*nHA*#|1}^8?Y`D%9;ZpP6nD&m1H|Yz27pKOPXjA)SKnQOwSsL{oiBEPZV{# zQ6zSF_rxbrzZL>-WYk<tg*JDUil;0Zr!5lkHEu4aYu#ijp}x_dvpAU_-@bHzJ^$z9 z^ym0t`LUb;wG^^L9K%>(jsiL~3VScz+iRT`;a^ZLa)p?8K}o(1=C1@zL`^EbtpGjJ z`*)rfXqz;uKrQAJauvmvtCh@&xl4~FPF@U_^G{*6{<QJyG)Ota=Pb)~9&!G-CTXeK zQJh?#p8jsQE{|bJ@lpntVrKrEn9|*t!&DwSY?bSinC2O`|E^-<<k|XX?(qE<RZkg7 zWc;f58!U-yo!O;4#Hbn}!=7*Mi6TM#XuH{pT%)jZ!nNJ=_ts5!w}UBBEYXV1-@{*d z|K`wrV)~=(!H?%5Pc$GGm9V`@uph3dsq2x~k|yY`Ij_E-`pM074gYA6YOA8FMV)<W z053=N4~LapU(RPrd=@pVn+@wsF(ykwk){Gst|-#WjxW~ES<Fgzyz=*Q!@K#I$0j6S zG^N>;$irj-Sfk2|F`2MkY7%pdDk&Z`bp3CP^;^KDnn+Q?Y;h|85DgQe4-t^3P<gy{ z&2i^R(wpT_hE`6f2E=BG__E?ZHylX>O3s)k<rZt9%2bM;N`K%P4_D7aw{WsP?ABXg z@b^N;Bi7Dw-As*$&R0~WdRlVsWMFG7afHt>;ocuNR_5-c5S6r!*vFlA5Ab^(^QyD6 zHvGu4-U?fJY-#!=*qn)k1p_)S>d_lD`oN03%RKSTMRN)5(98BE@Gln~RcKqud#-Cq z)+){!9Q3jnw6YG`PaQHHd@9#`itH-rtNQdS)X%ZK@R3P|z<j1!o@ZaEz%|p9EkoV- z)*zv7>Wx&)t8rP>E8=Ku0|SaU5&O;Mst9Y@f>s^jTAV3{%+hazLj=Dj#;H^?z*ONR zcaUD&pHv4bMvriIr~YrYoz?r|#w~2s-CmS?zL2DTH=z<)L3YkTwe}@W@zwj}$)6q| z!2W{{%rc}{sDhXUu^ia@bjfRF>!}1eAr?($ha%|-lL|^Md2hQ6`8N1!dRc3EYSlL8 zZUqTB!-p8`H%G|c=GO3_@^=^e(E^n*I=wNQOA5|yfAm5tP3asn8dCYHgb9Eps?L9r zMbx^3gjd$4H_N3;gK3aJ7dAw3W&K+1vE3d=*D43m&%X9f-+nIT>_KZJ5(4y0e<}H( zH@K<J+O`@I?W$J&$l+{Q3BEK@9OJN)wwsY8`+MSPUDnE!*5;1QpzOn#stBGvmzcfI z>=u6ZmuH3b!H<8$4gZ~@wD0Bdib7plpdmN8`5HiFZ%UN|{}z!vv1L5}t3v&}LhZ1% z6C=`e@b3_UA%U)G{#lU<e#%WCD(BEt<620S9R41<lp5jyg5>ciU9b|jS<2g26nyDj zY`=Vi=IGSoL}E$U^qa8#F{YIyx#gy18bT&m)g<Z4xGW)>7w*er&CWR)NG*9s&6bVq z9Kn1++wqpo2_8x35z&Ck#1F-aNjuB6tt43-im`1N5JWGdLO+A$esV?aY?Yj!c7sN{ z=RBiaQ{TeG^SCc>(7jdYEGO^9R{ohHL9^)Cd!3x}T`+L$5V5c&#<Usj82z0Xb7l-I z<27OiDd;58P3R~PER##1pacL#LkbXdQ})=_?N3;(6b_@e=WbAtTGJ1`qX&J@nw;O4 z8olc{_}UftW938mV?y6|TnwDkxaact>2>7M>(M_Po#B@|^RxMg?vo!2tzN{wFC5hM zXuCSPrY<#8IMgDbq%%2V9}4cIciD$!kJDsxYxw@@q9)Ue1-R*^X&qImsWE2ST(PE_ zyi8_#Y)M1f`WMe1KDZ<Jp}NdadU}J)7<n}`Yy6{u*pgnmy$Ni3XS0dU)Z~`Vb4zR6 zSM+xkTaGnt9u(?)wnf!Fx4!r2Db*JuR&<jF848PKbg)#N`hq5>(`CF5wM?>c%3;Q6 zg0pVR7rGP{x^5M^mnPXkHk-DVLi|RAwo8IOGYbSvZrXk-`FD9%{PII>U`FXrq}z)Z ziJreq)PJ7Oeqv)F?Ar{IBT+~&l$yyu_sM?uFAk&Q5Bb?~Je$>Kv{Y4fb-D;&x?x%y zrm|>iM&?UxTCfLiW|X6$hGmq=em<u@1A_rgynx48cEpLlBCVkUwV4H#QkuR~(k|cp z;43*M>gVQC6N2<<a^}H2>GyWWDr_G9C3#4uNqL*sUe_0^Vb1{cgXsmA{SzE8Fx@yJ zL8dL<{(Hh0n*t|m>qQq2T~YrbV(2kW-j~1bWQ6T8TS-~`KV8AH3BCk&wM!(i`>l@} z`2rJ{l8<Xf*$FWj6@lm`9=He!0Fl5^XiEg&1(Z91h5H_7WL0vTXI;mVunwj0DKJ3B zz?@}D+fPt-#5bC`J5JLXYIChFG72|jx11?`bu^OG@fsqRVKRfZ&!yWqQSG{fTT&S< zLi@=K<9^JgZaO@te|!I+r_uIkfK}q&*%Ey|QGqiSluc{upD+*uk_VCQECdkKL#d`J z|AX@8F%4#!xh}dC7<peGl(8c*V5Uypvm+d#5fQv3rJ#CpPX2voa%9z`rsBg3Et5%U z8OA?H*UNtdi5wh*Yd;~#joR8@zHJa~8M)a|&vwXjMUz+<uHtF+6VcRk_FwDF==2P^ zaw$ojmh_W@Ion;_wS3nz6V`~hxuH>lM{rGqcez5}&kv85l9S<fO_(z#U*V)y>UEaR zMgoV<M`*SMd^0(Sce2|wkO>bb)6dL@8e%{QVBkMv;@ANy6v$W;L}pL?PU=>@VV42- zq3Idf=gZwErm1TolyW_5Y-A>XL(?ic77z=PM~d%j^<J_CBSH$MIlk%ZG4D2KJUib_ zF|VIhXZcy9{~Si71_43XaOHgs2?B~ytTP|0JDi^1dCDo38JUMgrns+?7=(gpdBb7_ z_fb%BcT+lkC9d1j{iNEqOU*O!q8)|OQGRf<wnWrxLnB8bF{%Nxpy-A^4}*J#yP(hF zk}(|Gn|?^c<?etsp3##U(L+rGvb*{c;XWVZSa2xv>zRDwP+u^qI}UmtO<^xLG6P z;QK7`n2Cq+GItE!icBkrKM$R}IHpVgc{*KvFt_e{E|{R$#6{`TwC?)kt?|nOErfsD zI`+VCRGDTeJ*=MJg)gQ0MVml^e*2GbF*L?pepm=a6cF{1<~hjBoJO0*Aluv~iW2Mh zvT;*_%p3<c%SFbKN~L9K`uEeV(Zbq=9DOEO9)cNbCa9D$NkWGzsO?ST*y^{VnTGgM zO28HLqWJuNI#+83J;UHz;)Md1T=$Y=dEJy{ill}xr23{tTx)#6@u1l}szBiFACcf@ z3*5eYf^qQGye$2-Cc_EW^uS1K=>oIh`|RltBjquyGeWuQ_)CFjq1)_)!?AkTFJ-om zQ=Ls$7IPebY`lo@a|A!|01@BIj3&k7bo5WwjV(R;T$A>y&zWmy(&yE=>#-VoO+uh+ z0XnARBhp{ZCUk2GxdMM=`KlhW3R{fh%FU@VG3)olBtqYp^$O}*N=19#Go=q8&GFxp z-jd=WenZ#jQh)xIP4?9|BZVrdgn1FFkLWWX$?V!lW`P0GU<Z5BlioZtYVt7US%{<x zX`>n`9j6Ls&%I5|k?vD3wnF_P%&wVpu{c46ML8pkw{7UyFF|hK46*xAY9OGcFs2pT zdT1N0N){T07)mHje=^5EXM_%V`A+`ZfVLoG?L)4Ez}VzT%q!+-!Z?kvrU<q);O(cY z%wQowZZD<GTT4$pEnj&m9)AWhga_`BBovDOjCK({ATzh+zuV2AN!t*y$e-g*66>jk zYp^s0K$MbS1_kk-G=pfU%mq|FoLlv0UXXj1;03?;U(Rs6F88NP$q2s*GsDIFRn)#w zewHM5t%<i)JDwJx9;_HT!|16vyjTnQBhyk4pQHY;B!eIOStRIek(>z!t_zqOZG9zH zlgUuW^|~S3rZ}3q9Q9D-zYP*b+bDnAfNUOTBa#og_@MS4mzS3B?ZR8JV((O}n4T-W zmg|~>yEe_gPMvzqmnsu(CRnMQPk&pYg#W>%=J)>Cbjc?k*<b=C6@I8D{eh7*#=-Qs zAW-*et(p{|>~Y?;5AQJ^tdR6S-e5PWs3>DAC9ZWI8P0q6hqE#Mr-s=+W#~c-N7>)d zkgIdVQPVn%h01`;@~ej9C#=xzlXcE#_I)mhfUybB=sQO|FCiUJz7^kox)RD9L9`F4 zqz7qh6M4g4UU<jOin!(I@}V@Ruf6<0KY2veRzvxh4~|jxnU}qWmjf{T8GYA-KWt4g zj3W&w8*&IyQvv6a+?r-3987dyCG|ms(bibOM}<$-0(SmNd`GSyhW#_by9OB!oAi`s z91${kgQ>2$#42kV;Y%r9WpC638>}Xsb_-I^zU+pnPeu`9C?Z@|)MEO<On8l>5r)M> zDZ51I?GRV4V{Wl2jV^_`dT%YvvtuPNbu5j6t4QYC4e`4C-k#3(YkVH7SjpFFCx`IY z@?f!@m9-wbNt(U;g(uRyj~taSjD8RWzsM6tP%9?RpDE}BEI7rKMh)al19W;Sb+cL| zl0b%Q*t0kmG89D-aRhIoU}(0$H45=9$aEJ+{>%@tllf%tm~ziFM&2go3=^ZM=vf$S zS_t#v2?^}ev*o*FQE;Y2{o)aw0#i?Eq^ufP4m%%JbNtvA(i;r6*`kru5LslT^>Tiy zVFlHcg4`3}lyZb(p^$Y31y{HGR{919+mXi!1iJ5=A%4V<xE@-GN<wy`AB{q-Z<?3d zPP{*9Lcs|b(i%+c$pg|^;9m<<>RsT55lCbT)U8WU>oLM`QN>Z(90l4WO)A_A{yH|v zftmqVD8$Pfc{z>(gd+JRi4Yp|JoiJi+dR1u#CDM&;Cx=k$0@R%PGZ)ARW@t`2^9S3 z2v>hsxStTaERWe`#MBp#d-0L;2|jCburEv@cT8bcRMc8rksrXc+E_@P983eLzgZRO zJ{svic0bT2A%x`d&rVkr8gDAxv)@&Z9O)$>`iXi0*5|>Pu)IV#lO#n~M7(PhsasNZ z8GzRG|EC!h#H9_wCA};#Mk*#hGAE>RDCs<jMjTAptYaxbR6xKK;sg_zHSZ+)J6kay zAw}%fWbO5<DLeHvYtTQH9|Ic81<Or=ZyquBIq>=^_h?nn4@R-i^bc(keVTZoR!wPg zCu+hj=_VbhnSnS@L9yLVmq&@dhn>F10?*DKCvZI!56P!jF1J%_&Dd{wbjXLvvygxl zC_$C@h>|j6r-78_h!hZWZH1O*t}+D*Af1vR%<$4xyAvUSV(LQnf-Ki;0E7i*@citx zIVB!!44)Af7{?s|!7l`WrikjNvxDXWW>*oHk~y-rPKTM~y~Iv0gxFT1Qdy33v>t=h z1|vj|4W<i%?tBq4=q9A2s$49vc3McW`Mc0IFhm6l`LA6=8B06mM5~KVS3*OrYwkGS z=JpeGb!N^ul+UoS%1Cy8%+n@gO%IZ}IY5kwr<!0NP-ciLhPWUxIWhAdcT`$GKtjcw z^_b6CGbtsEj|l0X$_%{a0U)SCniv)aECo+!F_RrTl2%vD6>)}V69~)p!)DJ8vhzcv z(*nX<w^IHqFg^Cm>B}#}Wfk)`75m9EXpw?gfHaeS?ims*9f<z8wXgr+ojShf+EyXA z?Vxusa@+u9x*I%xn^xHoDv~MmIM8=>oc39zZ-Bn5g<QsYL7x18)#ER>Bybu+$6&RA z;&1^aJ`^GU*{?^B<uenz@*@f*pLK_l%M_r{%0XsHU?f2F77J&oiDmJ>!4`J&l)ca> zE7VJtPA(I?V|w0{T}K5}g=GgcAw+(o(Y)+s<F=J`rd3yz9X573SFEyoIet|<634fw za0WLd(rLjslxN93PfJ}EgN39Lno7vPTZq*ZWMlh<p)J$^qj$iR_u|yjfh;4C>6t6D z`0nj0&v93u3q?aF**k*yL0gX=7b+#x<P(o#;`<Zhb(!DL@{=I52%7$gJzkJ$(u;m< zNH8%&QdYV!OAR&jwZ=^@v~EO8mHW)3m8zVpC|l%rc)yhG;7x*>)JtJB0HRXy7enDa zPjGPR*HD|)_%v1_wN`QaMjX-{r1>`YP)cF(E^IEkM6#b_c!FbU5iEX8tLRTR`o!`_ z_5F3`25-Ft$K)WVJI@yC6b}j=GS0xE4>@@8RS{nvt=U<h(HmVSRTJB~leK0Zu&9tq zx<hmsW9)z`Az)j!2A-Tm*NJ^0RhXX4qK)$}4r_ifu1dfnE^(CCnN7tk<*pdSOFOpb z9SCHer=W%4{d0u&SYgvD`}{Eok;yO?tI0MLp;lq%>8i+kT`|mD>EKHHqrXM-SnvKt zyljfXmM)zdo>ul9tsbsEG{@JI*lI_r;pB0tPD-9vN8as}$6*Q#p2A9j3>Ysd0wzSG zJt{x{Pgvvb6D9<f&yEJY4rShaXbjuKre81<VVRZBC5WiXQm>eO!^1#0SPFM-kV+E) zi8#+}qGJLcpedI!DORWvSYZ<<IvKVifyTnV!BzH6QwRbD&W2luLJjVjISkxxE56sl z$onq*%w^4mdfnOAQHb02iNY<(evv85uru0`iCA5vMk~B+w#Z=q%Gb24)Na1?@0Vx4 ziQGJ<8{nB>sA~SCY;~}(Q9@VG-$hLP2ooTDcb!+I?W_P~nk7gDytrhJsT%^J09TPd zBh^0A5%hEU&VR21xvK@kt`Vf+B&5aQzc|V*H03_7uk=?K>t55nR6_G921bEr5InE* zCVL(1MlYh;@?EFIIjn`B25P_1uU+w)ai1f+)lwMTuV)68yt(-@A<w+u`6#sQge8dD zS1sMq^c&A`IRR;P0+-bwlWT`yhRnzDZg=0mw0+%}*c_3nz)TL|&-Dj#-2D^kYBH6E z$+sn{VtVyuYcg%am>vT*5oM1ihrQ|r2~8}GNTR<;1T7WNjYQ02M)t2+#_Oe4rV&0^ zAjp1nG~dC_Ox%~4hoW9AKwnHZQ|KA3D;3)(evxtgd9XH4C^CqS^&z#Y?zkXZTz>sK zy?5g!<oRdJybo7pn9+kHuLo7^8{da#{;O?Ygl64`XHj_&j7t|fV0gYDF0@5SP2avz zhR|d#i8fhgRsl5-j2FDb4u55HOqdy70I^PsBKAcnPLU)aQ|NW(NECclib7!E3&JlG z2=E^qgEFL8JlgVp4W#Afsv6L;-OK(ny1A=B>kZYV9zW_7(wUMGSPn6J@lG~-yvV!C zZE4(}$lB}&10#w9jsjP*Jy`c_hcZvoeCvsGb=MJ9>HOpF#tIm(NxU8Gedeirb;qA# zhwtR=P+m1NXv+At{2Zr(iRvip8xU*D7sLjV!ri;*D++OnXX*7{s(G<g*Spm07@M+2 z7U{^C{caAuDs#C#N2Z$bTy&l_PVQF;gfex0F`FQ!*z}2G?!FvGt}r_2UD`VkyP^Aw z2JvO9>xC)-S+|4d48Hvu)Ks7%i^N**>c>TxhUG7CrC#P+{3C{w*equK{e{QKVS(C? ztj+}v3aEp*igkoaSt!toM@#fB*5ATI9q>dB_`q^Ri`&RPit-YG33ekEy%$-XWmZ5G ze3Cd$s%ke7gU4ID2>q%@cU`+wti+=s>#zX}qwxo6ax%yBnkojNyctec8m3VR9=E4< zhCllXyG_tlFByU1M!C$HAWn?Z?P%*YpGL&g%M|w&ZQ0)WaP8{@<^o6HXI(*UMbq7K zEfhKla<PzMyGb3xLX0Fo<ej6VbS~m22vkzcxyDi?;3zA_n!G+rdACvUN{+HNtwu01 z$WVb?lfNcvJ(CkxGm3g{e-QC>dFNdkBx4!eJG5h3wj8U~_UY;R^tS;|Bh9|z$C?6e zW~`V;j$lp<$p0IYRM5soUC+k1jZKQpofj*ugDW1=Xn`=m6VCj5PomHFyMf`>4?2JX zLva|it;`tkzJ$Gznte6~af+t=XF9Tl9T{ts8epUp#RB3FUk2~<jE*YmsjTrj>}IR& zs_pIUMV79$FQ*<>sNrSc-s{fE>ksWdLL1tM4#wTf7y^Ggi1KbQV8Gf!6F;pQxArz7 zDA3z4?gA5`Uky|`oc+N~Sadc)*}+M<0}X#g>mM(?@7}`STe0=U*Jh$rFwbS=D-~ty zs3+g257UN3WN1*q`u2CVAZomfAOB&P_s3n2^@B#pe;d9ZjMg2OZicg6)PHuSp}96N z&EnF}vwsI71z+y-?d8l)fyVb(GC}-POnSbcXtzvb%Au!Xy-ixc`!7s4SXh#ayUzEL z;;(*iB0RXC?MuArlVL$LGv@HV{584qApipu1xi3gyZNy^+DXseC^OhcHMspf6ERe% z<D>uhbSHj&&1ngeVW?ot`SaJx?o<7r^B<0Y%OfwBo{-;<^tp|U7MKJjS0=AF+&DLN z+M;~afn4HKT6HuSlXS^W=!<ljyk)c<LV3A+&*W3z;@BgBTb+WzXswyKZQp4JA*wH4 zb_~9xpp1+oJ@`*ckim2HqXL3PcB9>tdz&oSfISvs1G<u1`zv0b@xuEXKKUwAFA>v8 zP*pt!n$a5Z<g^@yDEBEmBp$({=uKtj1cA}f+Yg0GMS*X~rbv_@7N?)hXH=?PI8zDS zP-K{>YR#(*p<pm>{O<p1^|zk>gR)ren3n6Lap)9T?wVH;O4Q<5toG(2OkW!h7g_zV zZoJ<c`PYvA`+t#n+@3h>>R<v5zhNb&I67{bkx?7vHx;d&%p&UW=cyTwAH_f%1>;Co zmu?D!oS$OIAHt>7!-*XF2YIT_y0Hw|T;aOp&KfDq2}X>RC3ZJW|Au?lF4Xrf_7?-T zC(?>l;=XqFe9HqIqKEuwywtr>jT*lLHW^A(KHW%<V-v_&r6ZWA*M^drWu8Efs5hbt zWInu<5JI7%PIo@>kW3-({`XAfP4w`~2ZYFfe|x2^k_7-_-X;{Ja4o4cvPG&4L@qi7 zbg!;V9CW<p#`#4tx+Z>*n>Ut8llnl}n%YDoQn4??#srxjn)fRJMUU9=ipn7##U8}5 zd93?4F5ur9b*_Y*i7BooiX3)r6x^eXA%0nm1IIv}&`}AEgW~U!xc5G)qz+sQR)UrS z-%RF=$r1vqAoy!!N#qXm50uh&Wvj8uQ9YT-tzT_9rB5fhRx#VT*Jw?$C}=i}TARtJ zgH_%8rb^~sDLcbJR3R(RXlH|tTQGf{)vgEn+N@{cGb=W~60v@uzm{qd0O6m0a;mgV zGjJFMt8vD0J?LC+d4D7iex!Ojc2B~{C130eDE^$eZ4_}?*<t7PM(hsCyL0oi0PI5+ zIEuI=P<lW!%%B}cBJSSbL8<pQrRjqmx-6bq@qm2xj>yxpIFiF}Uz(Y<!$HKMdUA4( zi+*rvD{fo4etq6FE#KSxUhQ&RY3z2`J0k6nJOhaY`cF2pg*r+uId}_XcI3*wylbJG zE+Nyk_~#$um-#>Su^=HaeGyG9gv+YwV~<%W4|6$Iu{dV1v*-#&h+==`_D?zT*@Z*) z12n?XqDyaigyD3RJ4Q=-+{Wz{y|W<oKsFa09X2~Ev$O3T2rO%kwaGEDR`PRQokbQ$ zR`n|R4`-ad@gL<(Pz|WAD<6FsIpA1^5v(xuiqVYIQn2ErH-78DT%F<*2fJg@@N?ci z;e}ikYYL;oz#k{?pN!_0Z_k^aLH~8c2eQ(vb;Je+ciFhSn7`fmXg-unl*b9@jFw2& zM@A8$u@z}3Fu|sO^lo7f5RKk8D&=+i@9D4aUqbwUZy%9z!WKQ&0a#^fK({7E93f?z z=D8&Mc%0M?ipf4e@6A%!0Xo((^#NNA&u46-#D6OE$5fk=WDOIcxZ7Wsgg>j^>lJ(A z|DG~r=W{d6JJx`~5eF#C14q9PY%n|zC_g}60>GNfIrae+<2K?M$#i0}g{itcbxn-+ zxYESQGC|W#c2!7JJaUz#mse3EbU5CkezDw(ZIiLfj{?kOUqCdz)daj9_HMXSx|CVL z+o4n&JEg)!_N<*R>YO~BQ3KE;r_w))lHlE#cI5t$ivc1~OcE)x)O?F#+{QE6-|9a7 z_4C8TD^k0g*~3XAXc<BLd+z8TnQslPl&udFpDR0ooW*fvl-&XH%BPHn1a4d-Xokp2 z&57qEL}n5Z?dRm>=nyNu)kEVe{=~0%B_#S4W{-3TU_F@u6lv5>gl3Ajq`t!!%4lB< zA7yV3<=j}sjYI5GIDYOV@IW&$af;1>TP&1*Q#xEk1$eLq%Qqp5%=hrmG-<c4;Bb~< z70c5aaU{^+xB-rW;kNQw$@ztDku)a`Q(KQ2@&}guQvK&6>ib{z)=x$5Od?5q(bFGa ze+|ric=TD8?;{zC6;CQK)IM7sWG?V0R@t)rLLh0TMgwSc{)E-ZQuJB<5Twg9LB_Qw zpX!KuM|t&*!hb8bs;D2vW;zYWo8PCxP8~<@j--`}#Rk;d=oddEjH=|#RZh>%d~;Y( zI3%qEhW1z${M{{z2eyI6OGh*McQzyPpPMs$>i=GGA^1s9AcLpIQ`~J)5qW5_lI&@} z1;L&q&z;xzbe6!}fPo12-UA=YZ|=)A)=r-<ylLQE^=o!|*`>#g6yvWQ-Z^I_BXNKw z3ji7j)Gwm>+`Z)-Rg8z)?pf!nOSDdyw1*2+_q1|iO#y*7K~(o(6oqlZmSo!9pB%Sz zA$$uI)iyUUc_P`+|JshMg59jH(;FOhM8tfdW7A(pPOOma1^OOVcU9N+D#PbQbP|8O z$RJ0>!!hHA#Xsx^PEE;nA>~S)Dr+FC>>+_X+L9|rN;blfo(j2!zH7ck^BUDC^oNT` zTu5-#ye_K!;O7z1S-33BS{BT#69D{>e$hddfn%3zI?WrE-;_K{mx|nqv0!p^d`et3 zq>Q^@!ez4t6by2cVu&10wCFm!hjfAhOF)$}VQpMDe{=c*M>V$XOxv}ln;-7;7J-xU zq{rFL?-GSP-f1z@&&9@Jh%TH|X_#a>x1T?^-=4q|aSqK+FB{+aCG03c4L5`}HKD-B zzWyRxKQA(r@j90n_4~!oog;FXy)$Wh8x%mhTPg7Vb)H%^#clq}>3gm?44pluU|8g< z-KumEf_$N)BbX;Eez11BW>aBAO>$Uw?B3hYa)b=K_~W1Y-(32BQ}8-wJCcj-?@=-$ z0Yyo+$$;KRk-xqQD!uzo4W4RMB~}?hX~F5Xciiyxn<Inc7){3G5i^HtQ>~&9xGZYI zO}!9DTVzbceGIxSV&X$m6<}9Cxhq<s(#7TcSjVs-OY&*uLt;r(4<i*&Fm*3$OAE(E z2Nih6_-#k;E|r@8GzPGQE=a0fVqJS|)j8jpmb}Hm;^psT{P#+X5QKvAYx{#)$1BQ3 zqfpYOC2FI=okpHtCzzK{b8b+qKR%A#?9F?b9B5Ua5J<QYnR_qRd$!d$IU}H^(82j? zfp)bg8+^~!c#C4lkHZ|v=xKtna`OlN1io&f7V%6vcf5kTR`{3i0ic<?*XOQ!x4Miz zULX|1m1zY*XUmkoI{cR!|7&<x6BGB#(Mlp-#y*Fukd+n!#W}<AD?oN!Xl@)YKzlii z2q*hJ{`mX#&QQWfhPGIM4hRq9crzmXqmtYk`<II^j7Sz&OJ0f0b!SYxcgo!Skz-e^ z4i?RtBE5KBlVJ|0@uQh9qI~JW(fzJPG^UDJOGunYjm!WzEKJ|CZD(CWZP5bom>S_# zr7U;3JuOljI3Nx*mtOTT1ogkn7JX$9Rn<y@W|gQ3OgA=HQk%t)jsc(V0h+bF<k%WG zx`Q{Xx81q-TbKG`j`X+k7JfoAz)71J`xO&V{LXDjHJ`R`HKki3NhrNb5`IsOQkE3X zszoIDAB}8(PE8V^ALWW}Wvm=j)~>!nrbO64ipNM;$>rnyfDFgF05c`HsmgDI6a;nv zhQe*u7PRZbc_x*)Cfh!J?G@}{qQhbCGmFrL0&S8CV!0fo5#8^Y8?%JkvztjF=nTpp zp%OS|r?qL&Yw!#s2djy(<xy7I7<P~?hlUmUWkv%{qNxA_-V=x#!|@AqZA(RwD{5a{ z_ru+Vw`{tgY$TpTLk2@bT?UHe1who!kpJ&nX1v2e6*viA=1qe>X$#tH{dT514BB-% z&qKA?fCQ!U;irU+(cibZ?@C6Uo>7uQnD?nj%(O`aG(cMRK(n2`!0yXf3&{<Dh4Z>U zV7e`rRY-JFG~hN#JROON_Lx}@<+~KgXiL59=_bnMrb3jKm2<|E$|Q*UTP?KA;g8V} z>E@E4)~hMzCw@@4yRyV0O#&*4)tkG<fW(iE1TL6J8k(84r<z&_&^75tV=~i%P~V-E zx{{jj*Jg{<R^vs6-(B-qLI=~SL}ec4A#yvjv3iAVeZXbY6P#8lTl3R}gwloEJ=#)e zdno}^MBlDfwTS+MUEcUi8q^%eDUJNSq;v;=b)qhy9?H_Vap$L&{_qA935mfi>G7a? zjkd~eCjx1Xbda8l6acEBIb_x-<Rv{L#jsq$dP~IrTW)+(L);fDvm7KdzL)R_4RRt! zILl6!Yft<rU_Gz}vgQU*m4ZzVG10imROa#T+_#zDb9|aCZjsf=;xe+7ZJ&KOKIhF) z5@<jXODfMRx>z4&k4(9LZgenX5NuxkJ6Gn3DODH-N=^c_pOX|Qt4E(}4Ove5*<<`~ zPx5;LbPM!bK_7qQn&NX%@n}pM{#}BialvccF*N5y+vv=mp+rkgmMy2iTZ^tf%3(|k zIq+$D`9s9cdq$mRUMFJFCeq%UX+&(2MC5in6^RMYcuzBsku*h`h9l#9f6FNm>SuaD z*v+0)89x3)^PdoN#*|8lhzzw6?I~IZoX90-f5X_)fG<Gz-x{&}73$qEl1r1p*Aww2 z%CX<4Jw{GYq&2<WeQvKbf&6Ci!*m8U{8}8EmsZ1(%#ERZHG{bIVe^Rs7>Ti-<dSeP z+M%_$FszhoCWT{S-A`^Sd=r;{KD`39qKmPJ;u+C;qQJqfugb1g>scmJTXmy>F`=_G zpQA}c&gE=mqs%e8_|n`q3rRDz&6uQZ3pqo%oEvy4oJZqjxEA@&T(RgpZSk}xpVZ$7 zW{<IGV&n+xY3XrlQ*UkJE&$TjQNMr7Fmv20WYdbwUO}7-C_sM%;rJzG+nop$)0u*1 zi2+7-Y@At%3cFgWMpktm&l$X}7UEvfzKkdgsDYHRDV{D&uk~0|%NV8_HEMsGfBe&i zl22}p)ktcCV;2L2Q<&<>Ri28rf)eFqOVm!oNWqfR3$m>WmVlfj@qzO~=}%k8^yhK1 z3Cmk~EKc(&x71aG=QB2~QYjXNUYUdBra_6u<nOAEZPmISzAv!MD3~vEO?!Vav?#w| z`}BITRp;v~61y-zD8XLNs$n7g)yy=nX|>L6q2aIZZVi*B*bOYR2JlsuXld1!mzA=r zURZv1Wya*=-%%UdyGq%>Y+_pGP0WqHz8|(P1B^S2K;a^o%&9MHxnFAtoA=rxma@#| z`qG4SbpU-BXHi<8)~!YTr=&Eg?@xh+yR12dKMQQUhezdd<jTgYW*0f@N+xwyHYmvO zl?iui>O0w!%B|E?D6|GFzx^0?09lPAUd@)XtNv_i`pk<VFB#4+7?mRZN?ZT!F`Mc| zXwr7zqD=T8fCedImp%G#Z_a;jZRc#+A@*?x7hl>_l7B;p8J$e7n9n-2v6+0fGFS~B zrU_oOVbiMnMo)t8p0_u0^UtGsWt$}l=s#B|V4{Uz<Fi7OmUIC0^Uh(|3Z8w12pMfV zMZDg={CC)Kqx~iCL_A<T|8)Lth0ENY6{eTj<e>L1BY0MFzKV$8YWeu}g6OM-hO`xs zAW)1~+IB9pDyBrIjV~EFo+_$^89EjSu0v{Q(7jCv-UUWoL<~JZgNgCqONh{)W$WWL zd#d_lZC&kRy%EcH@;=@-O%6o0vQXmWN3mwb?j+zk*K4LrZfvU;?-XLVL86=V%V#xz zu9OgKnXG)b_H^=vjN?IJ`a8wNd_xzflD<>@@41Bru$?IM81dKo67`Wy`;RWF{8AvZ z=16pcJ`$`etR9)>koVldz_<4P?@!sb4>QKPg_&D7!aLd9x1Q^`ivPWTzW@55xyfd| z`zKP><^`9V4)Ed~{=U?-O^QRYW}eL;Mj5+qIPt)tw9<>vzWs8dGT&CpuqJBt*2CvF z8Ut8=;!?L)x$BmBA8CA&j`(Nq$j=J@Rscb_U6ti?U_142=_fiV^`rZO3qnM^epLtH zG>zwN;e1xJ9g$ag{m{eW@8)~k80J*DOjCxEJtpc(oxEYYqqv>Ch|LQ*glM{ZuAn1} z@G31^&xZ1JRHKk~ayuyiRW@G8=a<Uw*kk#Yl%JH~jEq4DZfHr<ik4brAKNuNbxG1S zD^y&!)>_WdpjGJG?Y8f6%_Nq8{;7UNoO|Yd-^Gvri1u*|`~Cd;1M>TWy8A=c`@^pL zBO&|4pGhOr6Yi3LVS*b_D%HfBj>U(q_NvjB={qt6wVXXi&q0@Q=XCtb71w?(pQ(@o z=ielL9e|$TSB2Vy(UF7Y&j;VO4puIFRt`z)KmYhnzC<4w%Yod=i~W#=#6Yl%KgBRq z96+LZyVQN(vHP^)DRLBJ(axE~p)Jk~Y`!#u+b3$x>?7iVKx}25M{~T<V9Lf9Hd1(u z)oAab_>1>Z;ZaJ*hhJ9`dgPC2X%B&n)``t+^d&gyueCG3#iav44S?M4oBRaatb2~m zw1ETTR_;V-fGO2IhDTt5BUXl!|Jv3k!k9x8<CT!$_u?BEahsO(;d07d_+!K>pC=p{ z<E;NOU+F~OZkL8JAUu7S9zvv419Eck>n7+j`*fTreDw1(#&9gedKSp(*DZ5>ITibq zz}~?Y$)8}4jNv7AyFeccbe@FF`B5MtrZoo&AV2Z^Gp_HBgja|_Buq*l)bejxMlW#B zBCy36!%`FD+I6bT{}%c3Oo#K)-{n2d2_kcMFay$SD)>m9z@L1JH!Tu#0~t0!C-6p} zQMsL)ZwG)h9*wUM>A8bxj@>~xSN_o;qm0v3<0x)Ph&f3D$Cvkp-2N8CA-dlkPr{kQ zaPda&G2Hr~s<R!nPj-fk?na|RLMBl>m>Bzo_;*`w+8Jl)Um@u2B=(COpM2s#T)YVo zD_R30$8-6~Z~WK&2u%4><fA)`fCdQ^KwKn=eYV~FN55BJUSJq6ucC6+RzgB9i5wN7 z;-NPX2Y~qjqWur6A!P~W20z&^_mD^oojX{6>aml8!{4FrxB4=wm_lFt`I#f3?9cey z$HYG{lgKhNh6f2s9t(YZWH*-=nn39^8N$H)W#@ehhD9)%j|yslgSlYiO}}3l(u6%f z>H{TQ9i2Tk`yLW_8E+53H1N?ky|DigSo}y}iQ~lz*R7v+O2Yth<dy7H%xxgvW#Om0 z|L@41;H;yIT6N{xFX43pp;@B|5^t`RM-l=Q5<GE4?gcRWf;fE)R6j9R%jO0_{b!;x z;(Y={4+FhR67Pdf;2>~D=##1IJ-h0w*6LGu>hSRQad=Mz$=@#tfBO>zuJkkKP5zc> z|NT1pe!7!0PvCF#(NjEQ<af8H-xU6>>;2ncoIf@GxAi!Zhh~2H*}vWDf5Tb-_D28h zfBAQ?{qOMCzawJ8F(ctbfN-inIMXAX-zEHXBV0Tt0ADsQ^9jGJ30Iwj>ruj=g!*6G zgacxdXa7#AMct2)1F>X`(%w7ATtkU80_OGZC)^{cED8bpJ10ChbauUL(OT1&YB|Dp zTfBEq`6dgb-Dc`NX!$3Kl^>t(@16-vVKo!d>GaP9XDaXHOZ)8QR!>)(SDQC@{uH(@ zR%#76*!wB6&}34POc3+B5M65X{L<p{<3en?D`0!3!Rwd!O3#yDrw2cNN#JqO#I)kx zmy&Dg1O^%3{Y$Bhv1|d0M(^L!Ta!f!frtCQWp<{@^>W00u4MP->h89dmR!p1FSLkt zH2Pf2A1=Rre0F$nt#FL*b)%K=WxM#iK9Mi;DaBmzd}pTG;*IZL<%|9L;=rTBzx#bp zq2rMfkN)+{9<TrPcy#pd)}PDM?b+(|e`^2!sLyZnydkJ#KpniMPhl*f$Y@gGF6^Vf z=d%SE>N|>Mx~o~E$arSYF0KUj89lB<uH>=IILPMNr$nJT{W8?mA6gUjOMEMLnq1N7 z1NHL=t&EskSC>3*GBwDQc(Zg^!g#Z93wQJ87%Bhe%{9BD#P{6FE{reF*0Y;0|31;} zPxABngXyX+MPd9!9(CRP#XfI;^OyKfC<(j>UJ4T^4cqG$c=`0|w*WSZ?8X}($KvU# zdWzCY<8bohB4P`iG}B|xv9lAZ%J(c1sxE%ABvkV<nMJs^qR39TuDY&B`1R|zOTzVU zCRjuoT9@oZ8awxjMBco+S`umckBrs(RUl47m%(X=nhN0h4TU`f06>%kFa-F)8z6v$ zaFg}?|7bD^t+4%AQ`ukw70;djBk9b;q59wdf6QhUrZZz-o3UkY2qD#s8H_dimNbN9 z3n7(iW{fd|H1;KA4^c>kRD&UVh*GI2Nu}N@m3sTU{d}+Ab)EmuKj*xz`*q*X`|&8F zw^a|Mn;J%JN0VzFZAX(cl<nJVhx4>O{PRWjb)!Y3V<Tnux9Yc}$#7dJ!Qk5CtK?L) zibF@kR1G~(_sB>`;}iCH1-nDzcGK*2-&=T&R;!<9i;R(9HJX8+yA}SVsr*l33$<NB zrK{ZW?u}RX#1AgM8ohh-&AqeYF)v_*JWVI)xN5#5IQ8a{K;6--@wZeEJ9d{&HVvF! z`oCy$wy$3+rRj>Cnx#qi?a$A0_TXq%NrVq+nSeQW{NCMvx_I#T2m2@YFy|pTTY(cj ze-63BDHc~<?w|E=Z>W^Yf8g2{n>unDy2XgT-}9$_R2VM~`VtnMdf}y}Slr~Fe>Z;Y z$$zaXJm=IQ^Gx9w+(L_Y0jU+Pno!GZ52O@{F-uQN@~<tV$s1l%p?=d5$+O-OVLVlZ z!tl388vsGIjfesXj?a`&ew$_TweD4hRGk(h9%{gzXPF{&mcpg)Y`l$=eX(~b*U45E zb$&m7y@u>ycH(_Oo*$B2;G6VO)B7&&11}RkXbu(~t#1tT&py$$d?gkQ_o0Ny%6}+N z_D-Y6#4LaOa8+|k>k2iy1hrDd`x_Eoon`hZH$K}|_k{g<mxzzGyu^*#2tnYd#)2D_ z_)p~Li$jx@SL-umOlKF~XOPW<w|0HDaczpwbDIHa&Noh_{cR$*hxy>r?#h0yYf!@- zkK(>edD2XNsjt^k_mcLn!cCHjx`e|`r+tmLFWk0tHN96_J7zQ@U)w^zB|T$6sX2?$ z?mW-e6WrI(k(xDv8q_#-e@94M^Eql$5Mwl=|6@?8S;E7~;bEWRH(Gn5_Syj5zTe9S z5-kDrj&Ej;8OHeHhDfi&+tRliiPdBMrUl(q)~OSIxHIr7{x*E}CycqrjiPQs2^0gI zb^P<+jw{to2J^H^qk4x%fwg^kV>%Nlt^;wip9B+D=|^xrZvjHKG4<kR+z>F|huj$x z9*;4ZmgwWok3=c$Nzzr^T4&IXU1$IW$I-QR+a)J9XL8!SUwr4ed3Wc&2u$rir2c$& z^zui_sXMQYike(G_%kXvK2QC|M*CdWt1+{J&c#bgC&Qt!p0HE1Ssx0oUH{#EE)%O? z2U%<e`M_A)-}c!KEV&Cyd6Koaw5OM@T<7^Ni~KR};AEE<)M<w6Zzp<QEdGa{qujLn zqMqqo_^l1&A%aJS(%t0LtPSz<&lf4eeZ%+6AXn2mkVJpAvVWE9B>y<qCeBO_l1#*y zQC79PCct!a(e1XcGO!e2;SHI5TEJM~Bs5qLMStoL%A!T=mi|HG4OcXEzK^vdj=QJ2 zP3p3O=;*d+p0Y(>k@~X!h!|`<kz=g^!m&%SL+V4yOACFwqt%txGlmE~L0D?OwbB7S zy1dl1EC;})Y+@ED%pgI4GE7bm<^4w+f_gmp!R8+EvXoqP56jh!5DSo%UbJ#`ryE%2 z3G_n^i;{<;f-t3PwkCtf9Ah;aM=q|05^IDppWyiJg9!1zR|E%iX_5fBj<~x+k`{4H zX@MSMJuL>DQ+X#ZTg%&FQIAu@*2+aoBX?Q+$rGYrm+>dwNbi{DdZBfcM+tDV2a7#^ zF|LHUp|I;~HlTxSNKt_liiD{i4jO@(LK<iB@OCAN{0?9{`>b33u`Jf)vmf$=rr8*7 zi?=sf9UKybQadehj%pgbPv7fypBBqH0(+t+^%9wu&ja5J+==z;>ifTW82DbG5?^c! zx8?*74d$zryJ&PvQO-0s`IH)=8A(-faLFV%s+;XW{uS;KK#$B2POZE%-g|auY*dZ% zG9mpIzWvh1nRgdr$O=G{pEJ;NOy(_J-1tDSYwE`12uY(V%Ah^y`~sF=pE*r_ZC}SG z>~4SzYrC~TvriV+$Y%=>7VW+QpZF;y=1*>ClO=d8oT|*3rTZM@O}1tvZWAjS42McE zw=U%Rj>Pk%-gOBMD%J`brFja=mZc~2-^p@aZ8Vz}FI~Q{PMB))rr?!wj%-mb6EijG z$7VwX46CH(hZ=fDdTi5NvV+B04dn6nC0tG{t3&Y3R(*`JUubB0wJS>3%-_=MLtVdo z=waUDC_T{OYls?SHu|I(C~@=`yBXMk+d0|fydZ>Jdo(LaG4xM=4-wwNxKU44VH9IU zxyp5Ph&u3@{9r;BaCRQ@b`CO2$+><-!~P$#$ygw30}rg-UX9hXJ}PLPBxKviSa04F zgy}9}V80yA`@|NnwL@E<a7Z-#JxR<v+F|AYTF6Pn5SH)LdZWcB7fvM!e&Jw3akuy3 za5XMVXg+xE4|gv>#-1GdMa14=m<kpzUB`+PIxbb%na?k>TjRC}v7C1~e5K~1T6sDn z5}Dt&c_ljP4Dn{viQrqrFxF)5l{p8V$wZ_{p7fvb?=o7za#_B7&Ij<IX<446S~}UG zb|mG3v!2o%7&W;OC>>;CuAp|H71G5)oY_NJvN~!}7*dXVzJ784xIiaUYzF9zZ}<$s z0_LB)ThG^#QA$*{Xa6I~poE$;je>;#?QU*UrCaPe61kWID{%^l`!_)n2*kt_ekc#+ zH(EtKP*w^^IbTQV#JoJdOJfS<_tQEU&5TA-FA2tfQFQO&n#ZTqJ7bVt;=x~2O@2!t z7W?G7C%-=GNg~MhR8wP%mp`28QBzGAdU$YC@Ed(A&u&ZXG;QgHz_il%737Rzs~%S2 zkE!4_me}y<TQqptejkx|k)9)C{jr*PrA2YkG#uxS09?!7n(RfJ54mN>%WtT&o+2h> zzGp|j{+BqdN1xoA63rX>E0<G|=n=?CC{AHvTrdB16$WKTNkA3kZqj9;Epc4YA;Pb@ z3hU$>pkwwC!adV}$<sHI>NQdv@j+eIPoo8$qpx-?EqveGJ!bOUPYzfdI_I#uh`E0D ze`j8%=uj@i*yfTdUb=|oB)|A7IQX@T0DWNP(bJ2yooA~=A@x@deaUSxrv0=M13vGF zPfh~@h&PKm-YKc$wq8FVke;1)?~clL?_qIgUd3;jXN=?YAH)*7tkNkl*H=#3!t#`~ z&IsZ7^FXpY;fsR>OIHRzxg7YfZO)n3Oi%4o$6DY3LhGzd&Ji6OUma6)7!(+Cb>?$Z z4u88KYm|UA3bwU7udx^m`*soVm0ogX0}QOCw^U28#LijwRXJQ&o#AFZ*aui@X+-Ww z1pnNXiv<|t9SQ1l(hhJO8W}c61HEig-nHYnMIe7y0$l89>$TJiapzZLIWcjE27i%X zC2~AW@zJ={#r`l&jf(_??4~%5ng~i3o%d~!`Nx~{BMkIPlbo+TCGqXl=q@fQhzlbg zbuR`xN#q(L`=qwQ^ChcUPP$yx$)YV7&ijY2c_&!jkqR*QjJ8<CMBYRd4^EM&f5dCD zvsXH1pJI-S5+&QD$Nx#^Cr`yf#W-afiXAqRvf6>!NFe?9?uol#BmE+p6`vb-zTG^t zCWi;l!A=W#m>e_mvx6=x>6tzkf2UvkWyiD2;Uas3uWa}Y@?@W~qh#Ei4;M<jC*k%@ zN!`oOeDf|vV^_$};}>HGGa#%>5kU^#+8}5BlJ7Uk_+*^HtmK3i?ru2#oAzaMoN^)H zU@peq43}9-$E&1+nNN*W)lF7c@Hd9Qy)sf!J~)M+cCEbgJN`&l|Bg|P^Zk4}XsR$< z?hO8+sS7KaFNNE!+AGl7BA(fw3|7A9YIaHEKH@q$&@3Nt%p5$2lrpwYQw)lfX60q( zfF(&_ZaNt0nsxBG^v$1_@l%#Bgc1!&6uP~wwwOeoX<CF2A7+I4)hX?928?$tNbN|7 zSjh9!k$xN>_ck0i_-NlR>tyk^6hkBarPKV_j#MSo?)CTiI#W7wZUt@OMW-#K<2G<D zeLl?Rxle3OuF2zqZHkq60{$7i>lrB@i;}A>$-%wYB`~n7FPHI%dgZx{4OME^yi_g7 z2%h6-Ml5OgDBUu18k^&MGc+BVqgUb=IGmnum7miy3!0jP50klU?JN_PA8N4}l@I>! z=as9tvcr2_AzQt=!#cLd{BR-RU>|}1O%uFNj-^$}TUu*7=R3KJVs}u^cqJqX+&Dh# zSMlE@AVDdhk^Kh?{G&?NSAHSYt+Z6;%x@I^H7b4IQ?Twg7Ec!-rb-IcX%ab=57NLr z3esUXRFE3}6(6iO$we9Y2a^$f%LgbQ6|r}~VZy;*@%cz%G5NO_HpqGvRq9(+j&aj0 zrGxuEf+3_T$KKP+yKqlQ;OLMZ+)vQG!l`(EavCLJ{X%YDz6!Z0a6$tgI^~{LOE!vM z*-;hYy2x4kT?3h_OTpQcc2?g#U3%=3T>TpM4sSaI==@=z<~|K1`pfk2x6#PgzSZWP z-YUIzq3S}zF2jr6Wnabfs6Ll2P93%T)PM`ZdKH~<#8n`TBo+KC%-bra8>H_BIYHYl zMz@DZPucxRE($OK{qj9SyJi0&p`XR>t{(v>J}T>YgC~c<TW5>xL&58laxHu6F8+~f zY-$1o-jZ(3WtO;A0QkhfY7d2CaoDBF7N}Sgm1y`%fPHLhXi>WRkTx#9RC*>OSah~U z@!N3-rRftH{51mp`>DmwO;Xa^@ixc6yBi$;EwAYSrvI&cM7@b-v6ltdU%(Dj(2mM* z$@y6JYw``KoAVC__6@1VhA8>kvvthqD$v?`SsZx!sTD!NQiie1VBMf?qWG2(Q~7%H zZGq%6>6k60NktDox<EOxB$t7^8IcH{Tdy;81eG1nLb^grif#pjv7w8S*UYfPLK71a z_C+O!BF1tOtNq7cs+J0dEmoQk>rdO?cuHtH?2RQwCSFU*Uij1zkHHE*Nd9I}368fZ z-<r>CC>?)^dpgpAUA*$f_j=bz8{>0J;sCZT7R?eOR~Ifb|CO5R(@j06IdIk-HDzaC z3T9j>@V*BgLHLqAuoq>|T1gQO5WC@GnRTQ5E(ctRPhx<dOpr#yX|;P|%jK{9v6ue^ zH~(-A{slWemxn51@9x7Lh?M?NnZ-UXHPs{y*T9z`x|Q7SrEA|v+G>-0OR_zmvD2as z*Krp&`nkO1vuxg3u-8(m_^i~2&$xsp@R0-f`eg@l@v;TWSN!MoJ;X?Lf3SG2P}%P| ztc_@=0qTS(VXlJ(?S8PfMv3ETX&nzY4}(i`_jkK_!7RZSu>wqQm2{iIsvmgsbja*n zA#Nb2p9)F_$hTf;#kVQKDM&UMY2}2}$UTnhtyY?so~79j5hUL-B&6&MP23WYQwGfd z;5LT#v;y5$_3%dhP>QTs3XbQB1eh>t<^Rc;c%Q+~`$T8&rWw0Q25DgJQf>l3Afycc z*#hilCNa$;JDHd!;Q0Af`<qORh=dWv4yC0GwQP|v4P=R-@4C1>dkn;Y$tt-kYpC*t zo#Hun5Mrq7y1jhzHZ2kvJBjpQZ1YuM=Ul}PSmE|-iyCWtBUYtmz-%kG`#`Lu{3nS- zE4;>fnB;9tHxtv%hzDFHM9i_FP4tb)vGFW)69L6yAmc#sldj{>qLAA|wR5fFWguD- zf-aT-TA1kf^V<)ql8i1BqDowi8oo~`_bOhR6t}B{9j=6)0MY&e#HC7chw8?&VFgvD zqc~i<nxoWIHFl<T|66?DI}54*>i3qyBnAi)1F=)uySBe3@i_9hKOi2t26qv_kH;dS zD&Z#=;4zca29jRCZ@~ir@sKStB0vZ`<oZO{WBf1!c^*Vx5unN^Q7cw6<+1VrKxo~E z<AWm{2GU=MC}@RKxBG#W&^X|bKpa<dF6M*Q==K`rjYO$AwZ@=7ai+a>$h;{bL86p2 z&LtzF0r>IO?N?66R9f6~_3IMab63&4tRcX4NO#)sCV9Xu3te4_N`5u%UkSHcgGEh> z&(4b%FlJgvGofw|C3BRltdQ{p7)yxoa5dh!U%Yt}$543+3o@8$FVb!E8fq*H{~!KA z8tEwlC?z4!Pa=Y25y=MVyM!@0XNeKPSlCZ=x^rIIeoWTbkWO%3zH)zd*2GHG1a%yF zQUHq~&$?|9;8Eb~RK`q+zFZ;=+;<yf3y^UHm_GyA?1XG=d2n#(g<{YsDbA~MNGemL zcfSYspRDy(wZvW5?O7-y{>yY7C~-@G>5H8|yT>m@@+v}N_YD%JnTh_w9;ofx3lT#% zfNzN|XpIR}Ib)*a6{@OLJVpQu+$R3T!WUbR1q@V4O7Nv1qB#_KV61<QhK#N|A-#Aa z*&pY_c;f^QI`j!Qd(U069ADgFur)352t-$r#6yMC21g`rkrrMWFQOJRYKDhe)xd|= zZ~KhFX$rbrxU6M3u_OslkIdANkmm$2dlJll4IV!!o*O$O-Hyx_Dl9Fk8@JD<ZAo<t zEbjf~72x8Q=rN#+KfYuAjq11E)2$LWn5d{pgu%G@T_$FPEO|y<;vqS<s}hrPNf6m+ z-$g1NaRyZ^KqdF!{N{;OB52^Yr<4fNUZHBpNX=AOU@R=OQv4DV)lU?6auvVqx}tv_ zBun_<C`Hm@A9Gwlh$()KkgWA@R=0Tv@tN-^L2{ggDF<Kcx1g%Qubb`?(b1oz;zDi; zivMX>6EuSt)#bH0x*<lgTrqSZ8JWU_c{5>0ViDpuwn<{JC;-K2Me@Nf&M*-~#RnC4 zp0gDH{55Vt?W6|op<M6oM}TB)Hu}5}VXz-r-MWo`sq=qvGGMEzQYpNA`(LTe{b7^> zrsjYv>&Pb=2a1KL!b<Uzt#ErL%$k7G*}sig@@UNfbt0NoF5}w@Bwxlz-}W=L&C|O< zSoL18!LP`y1%_zY^?~2|0MPBug9*uRLfAKC&KlBT37H9?@)#)Aq&NY9fUVGGWmGmW zn0)8{?GJc&#+w@32p6OGv#t^?<ngDcFh5fz6jXj--GmsU?NjkHCN5UI>dGCXmPa${ z2Oy~Pg6~lbxK%9tl(1jw@(SfYno17h&e5NE++mPQooW{;24%jF#C6`<Hwj9xh0|sn zi{1U1CfXOJ195ZOx|xkXfYyIdV!va9suOaRv$l-T$J`$uCJY`XiTD2JA*+nLa~1KI z|8J+-rp*(HiP-sS#(1R*=1|4nZdEh}S1!9~4;W#DWHt~e17o5W$?h0&wr=O}A}s?@ zwxD^26NuKi8Us^o*l>xZ@=s4%NiL(*MEA%8j)KRsQ>kh6Yf*{E2bT)%#@Q%YlLnJ; zk^FtWN5mW{d;p=Uw31nA6mEG+vMfzc&%wu(h~Ml6J+y#Aq)VwhpP)g9@5Tq@^J>)X zSaVSd#-W$($*@BePCDYmvJ8WBs<vgm-+~7(sq8J}-cn#5n<-6vEA_}#=j0F|9a%qC zWgY|E5CfMJ7!mA>DC<y`Fgi9b1?fIAL<Z+ULmjJzU-_isl56{ERU`^mtY}`ot1F z{IRMAmD9Soau;jUYa)3Nu`_Tp`TP6vegB^DP%w$8cpEjf)S_q_T74bj`)fv_$;IW2 z<SA5B+6A%7B33LhOg0#K)`sv3{oPs1l?e^)Of$B3>3XlKLvLXzvz81pb@3sUxr)!< zNvd$>sx|iCc{gFDaJ;t7R_WyWiOLAsYOQwuSEcZFmYN4w(I0Upb;m?FF0AMXy04Cq ztQ>K?TKCLhdKJGNzf#Fc`C+W-$)pbTVN?|B^6Xz&594f*)=L5wtV#;72Ef{EOIbG! ztV+kEb@sk<5g+#{@31l1a<e(Hsk0xbeI8eupqs(1bWj<wDGpV%55)k>CG_kECJ>>b zYou{lK6_bSx+<xj*g!PK1izQ@>7X@K89mC9(FYE&hI0+>tkmGm#L?e;IkFT^B_3Dp zv19*A$}tR)%Sg<&a8eF`nSngTtFw8ec{kvc)DO2ucF%0WAF*kAL!~zL@^2;C^$ENN zR$+;gyuU1dyGHf=BWLP`#)lDRWfgao;3X4z1?*T&_%rrc*-Gavpn)T~dp`Ww<@W$1 zlh6%DBvn$E%1%{1@NG$g8!S&s0rI#{F;%7@{&&FDiwMh=v@)Hcis5NELuu1RNxb5O z6ER#hW${evR?gv`E;yMjplC7J`0U|3tOR@WB5joA%c>&@IJzAB223bzBs7o#{Ltw4 z3?SqP(zjs7n3n10|B;&Mtk~7Cw8KVOI~4Fm)OtO1YEH#kZ_ZQ=T#2g)mo!b5wM>|@ zJD4BNe%%-*Uxx`+sEPuL$CTV+lHYwgRu-XkkX^|>UGH>JPD^faz;LC>FMH=u6iXxN zJ%P23sJsprYnYby=#(Fl2ReMTPquDO%yqK#`7pfm9M~ryz7>k70|voXE^NX@SrV{% z@!JJ!PZR4*%6&Lfd8JTlmAHg941#==?j$3!!wBc&c*k=QK&U=csjH#zOE&IOlRkCp zw6?{d5#G!?ohg~@GYlv3>_BPTEVYKtS+d5Ry+_<m5~2xI-C(vdTd*6SGsIDv2gPl( z`fw3$g*;g!!G{Gt0W6!hkEu_$K-%sIoa>dIa~1D?A4QDzMT%tm(ja&Z49tRIQ#eUB zyEAqCx*l>~)?KC=R%ge`d`zk|E*W0A!QKg*i_nH-&FW_fbQ2Cc^{v<G<3z!=0$*)9 z4xJ%^l`g9cp;%Ta1IfIQJi5o>8MW#>9W@-_`}UpZA7PPe95xn!DG6Gk`ZJ3KVhMZ& z-(W<3{!|t+hwYHRU>hu(XR81KtXf%FvldXrk8Fe>pLOYQE5-ihmN~*iK-6F-g9jh2 zs5l6<hNuu~8YgRfE_S-d#?08er+P_ZS8zrquuDqW8mXbxrgbPAdBGte;BzG%_ir2q zU^et)xohzK%+XA#sXF;b=7K#C!X<1Rgn|!u%1&ChosQ*RUJq@wlWA0BB}0!_ixq4F z_=BpR2y-3diL~NVWqp%r=*Suj#3IZ`LWlRp+(?h_Ijl0Q4ehjSvse8k<(F0Cs8*Zd z0Ms@o>guc{-GPdmuTn7k=EQ(q-@8~Vcp!w3>Qc!Rn4X<!IcczC8gSJKH-ReMqr00~ z_1~QDTECo+y5_(ZV=^S3w!*}?FXx|PpkjdBiB$WoeJVOcHhoD-CQ?MZVcE_P5aq|Z zD>$LM!M>g#q~2Vg@`?a|tG+<X$M?G8qUGTix>}`}E@`uk*0k%3$B$A<QO-fRL+njR z``t6!IR619dH-g$qkmwnLUE=uougkKK5*01OJKILh*MNo;4K8_G}hyZ(DT(vwvHe$ zU4=b7*DC{<3t6?j5@Ct<HoGIH(n6#GrIu(WJSuOfHdA{l*48ASD0y;zK<O;(hHGb+ zKv++cXDF@G6hDLWV6CGs+x1km@sUr#)#gAlP2Fh~bF?g;@Rd2BxL%2D?+hi>M|n$K zoo!dy>3Lt5Mcuj7TFst(_FzLLHn(8Qs>Y$@hOTmRq#2t9+nY~~#K}4wJDbrc^E!+u z&Ii?{zE2D+JW*rDrtd>n^Tx0te8(|lV{%F$XYS;w+9T8<j=;jAObpAIR{$hVy{Rw> zA~*wUxia^|(`kDY(NAr4I$}*jlJ{s+N?RQ`#J;uU6S9Gp^cIm7_~BDiFqZ#ymj)Z} zSgDCGJ5SS4BxZWe-&AR(50d{fAKT~$hhjb&>4|@@{)rW3#;!~#F1Nx}=oBmqyIy(5 z0(aC~<4(HPkmAdc@EDIJrIRh_sZZ}N?T=#Zx&Kbjn)YrwO(W|`pUe^&{aGM+%G|-< z{%eukN2L$4A=~a05gGDTu(eeDJ{@UcPLX!|oVG4D&|n2C*HDdGzY#&Sp#GA4CPV;2 z29o2~KQVOHo5Q0>92MGEiyJ!u(p4|#x$2!CGImB2-uD)%4b{oL9WOy6U#A;<Efk-| z+-d`(5BKhMV#x0=5}>3T$OF5Kd-={1R#Ni1^y?PS?Qa~kq5-a=D<D2|wnBu%-`ueN z8nq`NKARB9+-~bLU}j~D5*1f?kwK8dMXmGicZ;Xkspl=s{p<yI1YUMbcof62(2(yN zik%c!TYuZA@#agw*(bkk1ukGPHit<U9@^Y{?ZV0+_F&zw|6D=Jkb+jQCXdlG$1NWY zLXyI%O397foE=*n39V~pHac(Luz=$C`a4p-i?>TgN2x1Kr2qHh>Q2jQgBr!S1?W@R z>Qkk{E3GD`$0?uA2keL(Fp_%lQY)YhZqPu%IKHRFMQq}~$!Zw#V?~|=fuJw>OPr<} z>;we`Oc&0LDv%GS?ji3isY*3o*uTA#k*~yqG?@X&dN$#~mKt)&;{jGfYx{yW72diE z-9=b@P<{)wsHSl?70)3YYzFfVqxNtr<tH#{**b8y@YDm9wJya6IW<U-)wDhTmb;f1 z424<bsolB4({19J5hTpbp_X$Hc>?s+zSI-yNMo`Es+nBk%Z^s!sjmrbjy+hR_CF)4 z91rJiMJzxM(96G!nj|Xm(ARm7PVo)*2}UEqQghRb7;MiJM+eEFn82KUbsdWjhCupu zxD~R@HEFSJP3V>b<{X>J3f3g?r~kfmLF#iTa09|LYu#ry2|>=W_h_f;>vyp?`dFQ8 zjEGEyGPNe}n7TuZ_4|)_62e`%(c9Y8HSRG$<3MTuo2LHawFAJMF{JVC3o`%w%S-hy z3o=S%+ySi13d|j;>>&YnZsoYR(u%>pZzBgM9XQvG`FSKn!#C)$&xP_jyhCNY`NOHk zzW-<GHQy-PvvxnDLA#)GAWDfEm}2qaR88m{f;yKPA=u`s8KCx2ENhWBb$DB6sK^ne zhxy5ANuTKH#l6M8x>2<-?_y4!E{6S1|4^{h591P#Pq)4BW|RhV-!-VEJp7~%xqM9F ztiEv{pbm6CGG?Ue_==fnry6fO%16>M`2#E_n`J_OpJ@TF)(aJs6FcF58#0;%L&rQ( znLYiC4fv%fiabpT;a8iTuU~(icLCbjE(F^<E#H|N-I}{LahAp`-B}`%Lb3_E5M}@r zIJl8oD#nCpw4|#cVIBKS8Bmo;7Fh~<Umc0k=hZLWW5q%m%N!KriXMBSOqKC(y3@>C zRXD)tWF_Hd8#RMx)t5V7<%s%mN<V`!nk})Xv)ML%1HJOMU@Og4#EvwbXh#i|AccZL zw*UQqdo|le%-MikjylqmJ~C8$&rlm`qzxVO%z7v_K7brwOF&`SDkn*M(?hH>c#Y+} zaR`xj_HY&Uifz*L`0Eu(_bU_wF>I8`mM4$J>menKFsjBboQ8*?K`P-v`^n_pbJtOy zl#!;%PG-I=Vr8l!$-)SrlQbT$HE>lF9`7hen$;3cB01({t5VRh#J9KN?BGad^S@({ zUo%Jf-yWkIK>%>g7=m4*WJ5I-GU#=CuQy$fR}i0tk~cDwL;89X(yfwRl4(ftmC1t1 zx{eoY*$uYI1_bLYaYSQkP=3nD1{qg_us@963imyf9_}%-&{2}nvvzC{!k=2oLERA@ z+8nb=mzUbwe9Qt}7d0{o<(%nrwDc8I8bkKcnd%3zll0K(_su1nXQt0I^T<@>YY&_C zKY7NJlcXa^HF+L^<WU+c9fO$~nB&&E9twe7mI<KLQ2CEW_Hrhl?3c7xgn4dHBvdZl z@KTz*r=R(DvnrKZeVaaMGxRX<@Qitvu6@DN_ZoMud=wQh#@K}Gd*r)1`s|1x`wPrt zthu3HgLf?p<*tI<Y3@}*pEZttM(7<OoA(?}cFu3@cRp;JUhMUPGicC@4hVNd{K?(_ zKl}%GWF*W}rA5H7;dR5@sr#SuooBYbS!*7*frT3&PZW4Y%;s&j)kXdf>dS*WOOB*1 z?5Em07)*-kPg=*zJUC_JlMeQ?v!0dFXRm1ThSn+%&#~)-JIub+FHCoo`Xk@kUlH%} zdcAh3{>u|iY?>33(>mnFy>ugsnE8%0LoJ`<+~V0KcxR<OJ^FGkyWG>k#_4Y4J~r?q zua5U`w@b|o+pzNRKMA~X81we`-N5zdg;ZqXtY7iab76~g=p^C*iPMzAPl=wQG(8!1 zRDB6n$fXD_!`k>I6dzxX1|4#$|3=d*w@*z-DW$9D-@Z7uUv|*wex^-b+m|+#%$bLR zLd#@a%iqF7oc-GKB?3KUpjyXPfxxLQK|*+hrz&I#(@;@NpC}>X>WSBBYq;dws50n{ z7<WX7JlDPkae<{$UB_S3a~#Z=8a}Uoc>j&M^1*z0k$Y#_eje0k1(pW5W)XQiowCoD z`sRLnk;bz(AD%1Vdl$L6yqL{{a3_ldP}8+C@%2|1X%+^)EFA*0yIhzd7?AMfKlFH} zs*S|jzSeL|FRSDB*71h`{FCQJp@h5rR77a;5b&qe+zVxS+hg$WGpNqdmdg23LYlYv zRoA&Rb4IF9EBM!d_g4NsYlG<asdoAbFA&Ojn6T|dnEt}tzhY%p-Z=61Z#L>H#DK)E z>0ui-EU<Y4|6@CBl@cHxKNog*8%F{_2veF(SS(I9Nnfas2uB=U=i1+cp8zFWB^>jG zL+oO&Z?_j;$X6&o4JrzE#GTThqto`1THKLG3O0H#DJUF@4{oYPYFy&$O?Ve{?rxv9 z-ktPNc9Okq9XEb(IAMTMObFb2Kw=ukOqfKNrUV|=x|}|PJD&WypUK^Kz++Rub)RET z40V-)Rf7e4sTZcI_JD1~qlfob$a!}2k!kxGaOZ`oV!&PUdAHWDTG-EB|K<%Jx4$Qr zHOc0|O_2_JVhyl17RGewuvO}A(ld6kpQ)J_!0-V`f$Rp>ySn#m!E1i8G`j&Ya6czH zmK&A)ddso`Rl7*2_A3T!x%(NgC=ic2Hnoq|Og$T*BwO*a`I7Q-?h-oh$WIT&5M)DS zS~RRFeQj!Ii&4m1aF2)gUDqQO%<YsmY75HLnVcEjgmkAZ>?U{VFF;IO-Zj+oFV-Vd zZ3DYXk?*~V*bD@F4iU8w`pEUQ7o53Vz#U3PaO;l^7H4(Hif^xVZi6b}{U+t-JUDYE z*4fUdUKm&JJCXljuZnHO{187<<97bgQnLXTI_|jV^EC}?)RM&elN5gVEvF3E2=$e# zM%;*Ns~?JyY^EXd`hoCf1e0UCGNX#*V|OgS%K0#WkTx7|G34PM@b^8fM_s=h)KI?_ z)VyPEvHs0dlj9c-`572KvVKvsPifuj2J60CIw6hXjOxkaUwy!jEJyw=Mc#t~_fp}$ z+D<@&6T9-TDF~69WRsYme6vtktCix`FZsyjG`e^TBJ!IM5iyB~o8)dD`0~L(5~$?< ziA82)^M`@l)5N{DYhUzJi+=U^j0}C|GkboQ@$xR{E5Giytw7Pe`M^)N#oCyB`Vn}d zXQC}C_*SRPWfVMy|7bJ&AYCuN=B3Fb#Oo`YRLqM^WoLaKD+0f;2w#3{1<k1PPO9^k z%TGR%Uz{Lu%r`zImQ;krawAC5WtFdCyLfTOQa4(keM)P*w$g>#O{9kPZsjNGe|NO3 zXs`_w6LDMh(|vC@zv9~_dJce}NZTHa*!QD7$B8TKi6ov@rA+}8_^pL(!hZklje_px zr3ZW;tVG1gBTnh1nUm55mMTEQcbwVxGBEwvkO=hT1~H(&>MF(MV$cqQ=j&qkT;nYn zJ{;{IX9=ywF*8SVzFv0>)(qs)TISfDr*>X>TNG<uJUR1E>pqg^Nuw1=z8;hq&N3^8 zFdS;;zJGgriWdYqv{w6x75*+QS<LpJwEAy^^CTy^K`V*8Er#SiDddXXZD~<J`Yx&f zo$Kb(l2gbk_CmRE+DG959V5=X5K7#?Zk!!5S`?Oig&|^Vmu$HlIButsw5tgzbBzbR z!2d_^Vb6lAp>GRo!POY?PN$e{xDhp>kE9+<;H>@15V91tktMr+-wu?HTI22|!Km`w zBynb3=X>0P@BJH<a6j%}^JRk#{;+T2aoHQ8`XRmtljWTJmof$~ujZz@B8#$RqG-HN z_@{f$Y-G?U^G=jCMaa6|$g@;OzHmleDw>G(<C`#S7Nnp@tD&o1-*j3J=aWq`fJ4In zC9$-=5O4l@;Vm7(M4Z%y@6}E_38t@`r}JI1!l%1#hyh*}mq4p!b3y$zUgNXc#`Bk) z*_Q*f8_)K68w$#7y#%Sdi`jO9Yjx1<tJbEx2E%mu%&q)d<n81rnAa;RvLU0PGx!|J zO+p>mD67EzBPo-r&-le+GV*rUJbwN1K_ar(ju(3{r4r|szR8UT(^YWkr<s9vkN7n= z5$3kG;pXE7!9RaBBYiI4Ef<E(dm?S=Xy;;+^=;xd1YWI{7C``9Au?)FNJ3se4^VSf zUP0!nb25$1Xc}t*8s{wH>6FJV4W>mr*e5m_Pbf3P&q_EwS;GKE!La%fDZN5j8QTsz z-**NzQVUJxG_#H^WGXuR|7h~lW}il{C!b8!Zu4flxrtA27q=x$*QUWIf9dswjVqc- zJsXo}h69D;X-ScnZyg)S7jxB;uWQ{p#&_E;i#v61ux<e~S>9(EFYo(*SBYksm+DjN z5!G)KT-B(+)dLnHlgZm6x-?Nz)ZnH=2iWZsl&<d)idRC0=9T9(clF8mR}gw2<Po<{ z>{V<6+G{(S{NnDe^Lm%|&ED|1X9-<!T=;$GP1mT(T$bW3)}tlERBv5uM=uw1NXGl8 zkyn?w=X1~E`)mc>>TtJVRsVeJF>N40{gqZp2%E2o3^hktw@*EtOwXh(<=EMaO$+SR zy?*9W^=%Ud6~YJ|PqH9iV3{fg;bLTYh=n*HjU;M<Qr@_n{KN&F?PRilVwzLlT#H;C z?G#G-D0Mo&J<a5izQ<h9)=@Fu<ZkUnH3BQ|L|O^Cx%F+DQWNL91W*(7TvCVF#>LYV zupL3^IVrrUbO?XWEe2a2K5LKs`Bac;{~RV%$j8zKUCdDl%5vo{-^77q8)AU0q|B_V z6d>Ig;_2D_S2youZ@1SOK>kP8{@c~HMS%`}3T}IjnwcC8x-j6T8uZAiE{fJ`{<)YO zs%t~ohTl}zmjbOHC+|SIAi}%1#^MFxiM6>-ccFEKuI{Zz25`WdYDPf@kU!Hv-mqOi zT$|&d@s3=oxEGWIoQO2l3mdpWX<wMdWIwdUQg1-!aPv&Q+-Y&9$wz=RPL2v~e0KJJ zHSCgCpnqdl+g2Y$xa#v?+DvB2%Pwm}-D_gP4C|b-`dd`=m*=3CoSCS~eQi+Bt=hXJ z-}9v2{}4LL|5=70ggAcOeB99xBRD_`$7QP2L-?*zPWn|dIgTeb&E{WPs7KBt7vW4l z{Q079KBED91g&~{?<AF~C2lp-`n11-B*`g#-0kP?g|p*(cNKiF{@kvFqa|WIcYAq2 z3EgBbOoy#k$btq5IN}t<!3Q`QrDX$iI2(Bz3eE^PWKty(Y2P*w?5I$>nBxA=+Lu3P zuOn+CX<Clr_s^ZvF>@l6ChyU*<{J#kGcSp$8vvJ&YIb=QK=-?9!%>_wlXyREkoz^b zZk@dK<5T@N#Rd$`!?|4xoK?7n2`OgB`;*`X@)WzE6&%nGs1WPWKx8HzC%D!tX;!Nb z<%9Wxy_#XnG2*#A-g<t!L{OJRtX}?Ol1W?oVH2u6=VL`MLkkS;jdGg5m2q4Di68;R z;W@;;AuoudH|#^CAYB4Y#=C2^bAxKwsW)C<XTkFpoCKU0!CA{xefA5-_DCmNwu1yU zBe+U>fLExx<{F&*7Bo>oRs2Uo+ilm>n6t`5;Unr5J+-d(mMIDVHx6SEbtudss4y5< z>*op%k&$h+UfrRz=>VHk$daS<`Z@492X+zr+}W#x2O9Q;x{KOyVz}wFEx!xBNXu=+ z?6x4NO8Pw-elDBLmF{6FFJ2xrS^l2oM+YjM2;=J+rb+U+5Lb0<mf$r}>Fw1=S&ea~ zdA!?we+sVJ!}yrtyj_~X2U)!Md|4gOo_z0WeCQPMRC0a-AYWz@;w;goJoGf|kEOc4 zD~oYzq7gRD(Hd(z4Q*uOjkQ6(>aFS<4m-}m`Xqsn{>zCq+#y8uC4mj~>^KK8QlXP0 zXGv3d8@ntit}c*~r7C8TIKw^SfZcZZ^gl6#s~Gt}3*E)}jpC5j@EK1R$b!j7&x}a@ zsR=jqh??B+&i|Gz1oM^Ob$`?Nvx*Qh2PUq0%c>I70doDgTNDgppsx{s7OpMfL2&52 zj@MGmeQQtCmHpp!pT6KrF(EZpg!hcWO5CN8LK8#ZKki2E->{(u{Uk&6EaMnlI%~yK z$4X{s1L1D(<l<snSR!$|x&48LZ0&6)7_j+kN#y$AdWLrboe!Hb@f}{$4Vm|pOZfQo zxrH5uL@*?&xIg1cR~18g)xW`}p`Va2@e3^uXqY=hX!eo&oP{vc{UmY3p4z4pQ17)o z-N#CPM(m%X5(HJ9QD!i5CiIKz?Ogwlop)~gJ{LuO+*@EB3ae0|h=@std5yJnosE3D zl3Gf4<A&6(eHPjB2|D8H+giFH&>DmFZTjE|25*fPxa7jVvjrii2`_DU2t=^hSBLbv zX}1%`y9=GdH=BssHYdFT=d!@|y-qJYxoX>_m=ng_Yp-h^B5rDmAZ~RJozELsbC(6% zfW{_BiAaO~aiUg;!6CJ1wC)W2WLtZt<i{`M&1=%-lMRUo$Ipi2gfzoWGV)exvGo-o z^ExQj{c_uzaex3y5SGMDzA7b8+zLEq2vx}V*>=;_x>)sxxaQCt)P)-V<_rC~any?? zR#Wi%*)YG+PofOgwOj_P!B6eb;kx~Pcs%N8-NYj!=$8c2z2_fSP}ef#rHVl~-#M)s zy7)QahNBD(Lz}w%+T~mq^?qlI<|CkWD|grvt>3irNs%;qhn$h)XP}(=08&!x^()f9 zc3LUm&5ICP^E{}3@9(TiJl*TQdt~}bklWSBJ=ROiL*~hG1mm1r-tAzo-nzD=o~w&| z#X=d6!m{W&b;G?lSNfCL5?nugXjqIK4Wuxj&&-zZB(6qtc+fiSXm01j>a0_h3c2<= zgCvPwZjf?~{Hw^PUi6pXx&<v@HXf;~E1ozl4<ok8Ad4E=9Y!yox^}*5Nl>*CH2(Rl z8Cx-;_jwgG44|O>V|!OM{;RpQpJf3IQB_yNWpZ}ZiX+=%61|mk^RJKz8sYRT@wY2Q z&kTCbLBD^iXBCB+r#^XiXXMOQ(u=FdB#y}+)=o3d`da)b>WAMSN&YlOlyOAcTGCyc z7UAa%rcPeir`-L&VokOUAfWFH@a%LS!vef?n1?0GzBi+K^dM#_Naf}|>l)WPH#g4f z>VrL0^htLA-5%neu$~VH)S1VW%R}0Uy!VZGV%*T!t9@SHq<lBDfyq1h-p-rq<?ow! zT{*PxMr@jPxV3UVTUSWYZ0IBVx_G$33*82!#n6BgL?Z=hgA~~m<Nsr-ILMcIS^4${ z!Rt5k$gNml6KQz9S6XA{IYA^fBQxYSkYGBnAW2&^<%|Xif3vQBOF@m~7kw+cO6?qT zRO!ESJKd}D<?%F5JFvCA&T)jqt5_Ce8q(cK#XJ72zaiHK(kdTs!KvFCZ3BIGbzYyI zAkUqFm69Bf2!O*ZIqCtGN=Yzl4Yc@K_?o72lKfHkj#pwbhw1snO#$!@F#zj%l}uLx z0-pUO(niF{l4>H!<w~sT<sD|CVB(>c$zcm~=uuK$lG6+ISL{7eV(J`KYpdsZI%%5r zE{#>9yF6=BD}`Xf)24AJ^u65mr^u~?5$n|t+n#uOrRfkkgcaEq8(J^LnJSnNkAS28 z!voS|G6B7xm7OjVJl#3H?PBCWXPcin0Z9Vp?ZpL+2-gWo(T3mH8`_f}t8i^wShvie zX_l?@*Db+sS}s-kh*6ZirbPd4=~NOhdrL6<F^vWW+33jk0pI&5+61rgi3$nlT?r5% ziv2&BdNEN13rs`AFx+QY4@_$M%T)r%HJ1}uSRqr$PzOx%$x+Al2E)z62GrxPQpe_C z`86)x4j5ejs7b0Z%*9=P@WQIVd}GNX#T%<xl_LL&#Onj|`;4WbB$L720mKmH5UsXh zeGqzO;jL%o6GK}OE&jRXeT=pCcvUjZt}ks41^Xyi@@mbtcX_wkECllx+Nv@{`p+;I zY_4kzjQG8D`ESZX^>V?c^Iouo2CE~(-goI_x`(A*H0du~?K85%dWTiXx+4r}TZkt* z@CS+0%j;LjP9fe=wO>^n)HEPHOSXq!_}fc}d`xLGLd|{)+DY6|_etdE)(Mj)H^cW6 zmtiPreNVWi5&=S%sbsAs52)GFGWQ1usXhr(d%VaT4IHv*9h0_}SID!69dJ*33s4Q` z*;?jwqb0WCDum>;s97?6o3redGP-pHE@eb}igQ*qm5+X)>BX7#OkuesuwMK@0t@c) zA(WRWQKLD_(M*JkQa2I<RKJxc=%jfTD`yf#i(b2U?pZ|y+8IyPg_K>ztKu4_{pKlG z5|C7qGE`keF;q@v280?eS?^|49lub2nJabPJ#EHf$+MPwA>QSK`IhKu&hv<~BDK}m zUd(J7ueKk>37B}Ukl!0;LVMZRYlusGWf4xQL%TOSw2KLG(jI$ldvWGh$c*qE@^8sw z8bE9Vtz$0fd^qpxiTv2(YAD$5Rk(Eus!G?<O^tIbDYby4=>_ZGJ!UP@_(8wt_;IZ0 za^Pr+<tzQHFxuQMU)hhIs~?K0IK^=y5}Ni8?%hCuPTK7W9EVj{>L4f48`oGMJ*M)4 zlurwoB-2<`l4`(EBNbL(9(FXTM3||mdR2|KdlS;ri=O!36sFfH)0*#e->IGV!D3xH zz_W@(>I2u`9si_#+@<95e+`|r*L~)8DK0yGX&m*Cq@_u0(LT@$u0|cPb$}_q9o*jB zP-*v*<7YF&(hmBSfw9GfNvvl9y<)vgEZvn#8?&|_!%GjpXm-AWg(-IGc)9v8xExgT ze0#jWq3-DXSQ-wJYu=%BX8G9uumM9DHCuNYBv~7Q)N_IO6E=wY`s+`sXicUfHv<`| z`+C;39!$+fu4`Jc-&A^;?rB1q`+8wOh8qp`OnL=SQjXF;LXl(6L2Sel7McVE(F^Tf zxP@F=d{hGba{^<a?L{qZDTJ;8ypvfPa(Lt@!#z9ju9XI>aT)M(STqFt4-EEB+AE|i zH;`dCLDT2@w@TM6X<tkU$({s2+M&4w&lcMPqKxOfNXKH-I8Ln*?g=a<1&X3_v#e9E zLRDqFP=*Z|?kB*d$K2opAx0L5ancm9HM(`WF~eTz7e5LWdv#O{u&CxhBsi~@4c3Eg z_QGtFZ8@#dp$l3^45j;x!k>a*Drrb5)I8?4`Kvq3I-E_ps-$}U_t)O0&MIh__=J{y zhXT_-4LCCLO$<<&Y{E)V6!I6I-4H_FyNIwbjswlfMLG>a#)g30c)LvgJ46&Y%SaKJ zj9!mf^AV0&)mrO$4lE7ZB`t;TPS8C2bk)cglfw1TQxmb2ht8iJy*BdtLCKTr^77GS z13=&U0~V$$#s;Oz=#wYuu3L>U*<M~_?uvC&&_*#{H03L!mnWtO*+Juf)7@(cgF(q4 zEmmSeM=j8f#%ZQ%s3I^N#3_=Jhs`-kzoRB}bWM84`N!cQH@zfc{vc`RKCwypY`Ip7 z&ityr(;_BwR1bE-Ld9*iD`UA@l(&7;fAZwNp_7}I9GoM^!ReB+@1;!bHm`(U|MDDp zBrDz|3k~u3qC0@oCn5eY%g}lbjHA@zxN5)HEc@!Wrevkx@uLu-m3+TBDa=eE)qItm z%a}fX=ZX@6qE6_q_a4P44SCVZ|N5uBj}f=})>^gM`hgwuU|uoWB~7l4_mRs{kO`No zWnm<2216+_JGN-LS6Zl@?RfKR)Ft4ka}f~|xZq_Yd8e!$&CxKd*uAp@ZwcEAJ|_kZ zH}no<o6*i?WU3K+l`7d&Rfi@WXzsX1cTr^iTC2C0F&H`UKZo?$2?gne>DAV9+Sn~? zQ(9n`u?<VPRgJ$e)lN34CKIlceOtdz6dNj;SpV};^1ix*{42@ZkP$1B{So5t9BA98 zqb^9*VSbjChDyg{!t`ga8OvPgb9gr3L8E=QlPIf};N;iSZrrBR%3di>(&UHf|2c^C zC412c@-IVKq9Zmrq7WxDIcv|}ZS<^%^y34VljUk0m!i1aCxr0N@osiE-)ME1l=s_e zrjlm1b{g*xCF<G})qfl~%aVn$4{61RW54)F(cBkE^rHj0pFaCW!u|DXqF)o8!fpQh zyIh~&`!Xm%e#qtMK2e~WNVL|ZS3~>xr#yI9uy+cxeVO2P$ZWm)D2=Yw?T3GD#_wEW z-zHRgiMMNo{9~)mk$g6;z8CgEm0e=PpG!18UF@bHVBv&9u((%lb2|31q0?{87cXW# zH-J{Q`tbQEFKz$t^+tfx-o(9~<mAV}DTinYznW8)CmO6tCVP}B`)az`T0y4<7&oFG zE%FF3V&!w6G85H^bQdsO!AeYGRVXJAlihHK{WQIyCH>F(d-yA_Aye2vpGQt+zg%`~ z!K$N+Mm0}T^;J{%b>=;6HoJditX3_FUQ(bwtH(LHXOyB1>(}4h`QXg@H(n>J?Ig9q zFZ#!z@!9qQtpUAnCtb#p73eJN3OT(z#~w?2X&O%L)Q|!mdxZ#?j&iJhqC{Mm`U?Ue z@_qZh7V)E<MiAy5`s+ko7-(hRaoUFT^%bV~=_k~i+QGhjeAz6Ns;Uk3tD%)1gU5Kl zPpXOZg3wzPVh+o<W%GOeLn#&eR$7`Ef(?txtx(z=tMcI&PwCH|8l5!qS*q3Ux`&r8 zMY~FNja+aZ4B6aCYGo^}v1C^%YVWR0EDbm8H6Gw~dbzeYxexg34Tx9l0gAW8vU<+B zfa!&$@#%|ypPGm+cnsjfjY@R~pz2A9!|~n=A2SoLepeGI+Hqc4{(H+~80{RHfkq7M z)NLkZj;@!HT+JK3{(TZUdUr`%J&GkOZ>_hn1j(?B>Me})%j&uw+LSJ8x^4<I|7#ow z|HN!3GbDw@VmC0X{?}&}mhO>bDUE_?T623-0C*F9kG2E=^9e~k#T5s7W@}*O<}_p4 zQ0}T+*yM-13w?&9KBcH$*#v97CH8s$S0kDG&i-?~is8l=h54u7n&FC8x_|cD)9QNe zDK1#HB+b2fjGwZ5Co)a9vP+lJxJEPopV!6@B0iGJ(+7IyJW1!MCR;cAkM7S~1HU8t z-;~)IB2#r&``!>lhLdcyi#BKMM64yJk3|rrWR~2FSg};gOZ6RNKd!s$kJ!&y1+1Q@ zH}_`#Bg7{7Dr!V6*1)FkYJ82bc}ZJ)V@i{Rg(ZYtP4YTVli!9Jk$<2?za1?<sGFqp zT_ew5(w$^8JwN%tPBaw+O^mU%B_KPa#FSPkdL4a5nftmz_K*Pp&SX$h;d@j(I|Wq~ zI~a~=tldVW?w2u|5CiP6{bu6N0HlKZrP4j26J%W5v5Z3FBa9?5;1;7W&0W`;Wi7Dp z)r4J^w{i~&l1bZ-eJbn~3}Cog?$R2pxISw*LW(idU9c7DbMt5~S7u+~YVVN|2?(a% zQJ%zrWs1p*6a1dH+{C{1TFGEs_r7PM5S%K)RCzZ5o#?dAw?gMD9l;O=pAg!fc}G=O zyJ69$HQpqc;~`jj#Eu@}OhJx`;|-$1GCrzttDJ#57>BOl*bfvf#|sc-j3Au46LC)8 zxm%h1B-Kr<mLw*m@o(%<B#lKBojd){o8I(ix>=QtsoelfeM44g`u`|87k?)I_mAH@ zac_)`jS+Qk&d25$a@giH=TXk8IYvnc_0ef3%&|F!RCCNJO-V$B5R%YI#}7huq;q}x z=I8f6+>giozOL)}dcJ@M4Jt1z0xk{wKBjV=v6$n~6wtg=FZz^G*z3rWfSB;Sk_>y3 z*kS>=@mm`;)QDABrOL?Q)<9FQx(Cm!90#eHlXPjLhH{E*1*XQU+Az^<8S^q7LA#)H zZatAF)=GanCcPaPfpH)?zXGx9b&WYhhN0CmH&cNIa1d6l(_;qhf4uE}rNLa3w-PH+ zc3<B&Um}~yJoCB7XTpXqg}R$W<r=+Oj>O$!1&b8<_HmLLG`4xQ$5}T76k&;<Tg5iL zZ<z&C!1A*A)Z^IO(-z*-1A}A%yEb1hEU_PL(Q(<x1xSl*M4!X>)jY}&m<yReK_uwb zP^GVnQUZBnNW}(9tQ$b>>k~J378Q*dRvdWzbgz8K5EP!gR&--GFrpO-B*JJ!e!z+p z5E2t!*3M&&Dz<yuBt@6`k-{BiY-HjFFIm#(oc1`tI3h9H2wxI>4_vo-$ZFU8pg(A8 zuMW>tye8DJune1|$Z0e%5r8s!K7wp`^X-a`R@kmaE4~oY4FHN9o1uEyW^y19^Xe@h zYf0L_J@%iEPxr2M7zsTyIlrRG`>*ROa{?z@nGSyl?%TZltX38r0$#A4WXMb7g9<I7 zD^CA<TCE*69UH$HU&F(Zf3h=h7R;%(&0byNspX(ZtZ61G0;M53f~YqI9r*dghVs`= z<yK1ruM6&kT)j{vZ}Th4JSV7vtd<bnxb&vMY<a0_=-IC~4}5*jwwUC<(vJn^YwnVO z32bgDfAwfO8TBat*;Zfkq}%yEZ{9m9G6!OmO}X87SE2D2>-M?{D;F+BCh$m)-2JQ> zHGDbi>E-93#t{jxcEFiXIH#93QynpUYXIFU*45FMt{DcPQ!1u9Ba4(`(<{oW&5$9- z+mZRE?qa!jDmG<yrN|^dvSY&FC53ryCq4Hc=mXT%^>SK&x??cjd6$fhvYrwWAY8t? zwHZ9OX$BHJk#ObD3I&hiXR>AdW3t#uuf71Z!ey`fkW&=%yOW}x4QWEQ%9JNlBtlw_ zRLh=Zo_Cwz4Dlcs`T%s>qnF}vag|A?!#FBv(-!`pg9h-O;3dXk(HXoG0)qt7#7IET zPIT&cRKWXTUT!d`0JtOitOqv$=H7_H+!yP+9H*~}3Hnh`ghs|p(DLa3D&t51cw5o% zah5y4Rxr#P)FZ>PT>+@H$sE)q6@eMdx&xJXWPctLXE%N?ooOg^VJPb5_l3(1BKsaU zumwcfevF%l|AUn*<+<`f7HRFMI!=?~3Au^8fY-_ZFu_ag*S=6WMXwThtNSDK9j%$0 z%@3DkrnEulHAY|=7OlwNh3EhG^+Mp-BO?ZUmQUhV(m&pAXeyN)_H`uRq~U#mW4vAO zn^k*U=s7OnL75OM25AO2ZD%#GzhsI`SF3ghY!{${M1i5ap9cW)%tD(s14|8sHt$Pt zd6kap&%`K#N;T*roUdB%y_VUVfs{*sunF*F;7rT=E1xd}(Sw{sJ1pw9S=b0$+?Sdu z$VKo9h9MVI$`5HDXI7a_GpZOg{_GC&@b5Rf)+z(}vMJ;miHv@E!|7+fMP!8!#pi!N zykwVcq*&1ys|n6$YBH5DF0%v5jIm66Pq<=P`JkrmgR#<q%Vk+sPR{`vweoR^uxD_E z4#GGy3IkWu0f8EC-$t~E4C+(&DS#SY^~s-n6Jy`THliOD0i0%OGM^NyG4ae$(;vl! z7o-$<2f(0KS6c0;u;Ve0gpM(}@@8Ya!uPx_z3~Bi%6Rt=^#JOJ&^=S?2D3nhJ<X`- zp9m0xHeJW@qu{1UZeEn?{%Ze#hML+V0u5Pwmaco5><(QXp@9=@InKqVFY`D1VX}9) z4AhGfkrbuEd0~0kkddX4*MEKC7JYOXdMTVxFo__yLOH(2uysp)cKMp)O&Y&&fVm6K z%={X3UyGlj{Mm}fhD8CBSnq{viaIoU53r0s9O`Uc4Tw(~A|U#UeIn(JzFbUp?a?{4 zy=y^K+bx5+2AK4Q!AA7`kXgQV2Mg^B1Qitz3OUMt?9H1O7;S&vYgpnfJ!lblbECmc zos+LO|M-CMCB4IoskH{8{?Q2CZ^V?EVl5mObQSV&DU*?#olFwlGZ3|D*LU#ONryGI zU`Aak-;x_C*4UY_%ZIR(iPl${GLP=%mtG9hFuL@%rR}#dp5r7c@kdIpzpi4;9NXP! zJ_vtT`lWm7tPS2&KopWu1|8y@U0=z#X4==2DuW^co1$1`G9pL5>z>io0cmF<V{a&B zyU~>Jc8_lR9J=vfmy7L_Ly{w++`EP6;j^qQj}b!}#AGHt$Gqq9ruq|JBJ;XSmCuhQ zq@dx8Z6lZN+Pob-egEf6ikSSIt}m2-2y*Isul8=O4ThOSoXv#ZxvixAe(=AMoL`sc zu+?n7w)x!o{u&uW^vbncZoi0S!-T5_sZAa`S|fPnX$|HFw(rNrg!02|*Ry4V5y@_f zMf-}}n?2L4OQI7*J4Su--XS@2NeM1mRi4pEJ;ssyYFBb(ac@hn*;Zkn7NoJaD%P*^ zl-=hVGJr1fA9!D+96YTJsa9W`Ix>S*uzR~W4L!bFR470HBhzXEI(5jhgLv8d%qC<j z3hi$Aezh1PRD-Rr)VlsnPqEk<^&%|p_hS3`<DaVTzWg^`O5X*>xfdEK&xhXAWRD-* z2+}clZ^IpfZu#;0E<+M&;H!Rw<YL$*1I>Re0No7eME<7|8K7h3QyT_Qa~+GSgC_KT z9@DUDJwU$c@!T(y*_)p~#%oimar+p{1tWqx4kFzqp?!OOqzpUPWoz(^xtFX)B9aH$ zhbw+vghnzI30MHgm>L=Q3o*zq8XATNPA^R)bj>%3b4F7>E$UNT+WMZRyoP!)KqcoH z2La^u`L9AsN)gYYPX>?k43_r=VFnOrc(B~OK8AtykYHa*$W~;6eJpXO2x2%Ar?qNy zn|(0j@m5^M^wR&jcz<Q*vq%gO4aeW+fieT&|2`#<D5Io#;1=!rAP07K5~^7>aMxA} zJJ6cL2fbZ-MH;pxasX2rF}@02z75SxLQbpL=&8@L`Ov;MFJB>~?$tuz65n&{H~26^ zU*rAtT9zEoOd$GhHL=|)f-EpvWM+JljCQY!4Pcw*e+<HZHTOMGy99Y_gUohv%_T}& zG}$}pe2j_uqcsC>Fk@aqPQwFM+<lozrUVA=_5cn|87gQOmLzRh@1HQd4f5_f`V~NB zxy_pGqvCfE)x>rZk{!tz7v6^UIU}(1&-H8W$=3Xqt0_>L|NXfUs;dJYuW7~=dM){G zzBcgpw-IUU!WCoW<;~&!`}_>WcStW?)@PRtE=!y9nkcq)*s5lzW=*3Zr(2dGE6#&$ zVv#SuM}rLgr=w>FG5MseYS$PsvOJA9`)r!|(DzZql*r&as5PbVA2QyDC4#K_eO?*a z&yrP^#n5;yPH8{^YRO{9^{-P0q(9v!?REby8=YWZuuh5?>EP*N;pjry=CN7Kpm@<z z`{{5t>}(NKBU%L@*+C}xGe=)%HBYz5ph!alAv{-E%aPN)QDPhf4#?`zG_TGZKKN`| zEl2PZ?)yAsw75nG#Q5HNrTQj=`BUW06g)de`Kd7;%fQRjTqU&|Zcf62IKasXJJN?L ziaVnZH&dB6Yf8lE^P)<`u9C~}TetNl-a+0;1%&zEt3m@gNGa)%(z|z`RgvFpxLVs` z1XT|<8wbpCq3hzx7yY&hbo@=YS;-;m9s56AAGn$lXG5guZd$`1y=ank5%T6?^JXnN z*eI7;a?kvabxXX=7XX;#K<qh4UlcVyl1yUs&M-B)2Mn+bH-(Y5<{HDeFOUL<`|*qY z%KH~FtI%(!e|j6*ZO8|}0p-E_>b4yQo8d!BWIT>bKUGLoT!hlI4S4Ye0&KINcclGJ zutAI!&_K~=nYLyH#Hp%tIDnRkZXSoaL{QGDpUf{lJ!?>(?>T)&%*^|IeV#0_#xS?T zm&m&$W$y5_g$P#5%(96gFzH{YZ*mm2!aV-m*LarRtUwW{b2iYekq2maRk|65ju-iM zf-roBL~c(DV-x(z$ovyg;wLBMXbSsS7|*h!iEL0P6UF<%UU*8ND0NMu8jH~D=?m!e zd9Yl3mRY<OmBG?DrFZ=^)HiLDAf-uH07yg);X_{!(Iqek^5fcy6WU3PZ?crxG^V!3 z9G>Y}s@lI*WnP|bz#!87(KYhoVrVDpV`WC5GUfOfV7jGKw(>J{nIrRuW>EKNtWg25 zEJKeMo2Rxxofi!fABGx4*m$>7CMCp27MBv|qPKiw_Ap|wjJOcj(B0(w&+aN8sV4uP z+@q_Zt@HW{NSSr<{0q+ai#qXYb9jaRJu(zoiMTSY(ASoKRkl<9Nb)>kfHBHYEzMhW z5=6G?!?t!}bfwiF&qdrvV+KK2^Ww+~cI0UqdihRIZ%x4Ue8cs$dW*#o$h_~xcqtT= zMxMSJ-F{GH%uJG>=ciasm{#M9Qu<U|uKfM*KT3ZoQVxjqi+ghkw*|hnSP4+r=-T@V z{RQ60!A;uVyk44}vvriuo75oG_!W3!i{9Iu{3buZIlQ&Zhscnn4JS$Rpctf1ou6&} z=cN+B>b;U-yt(0o0m_QXh5wKZo`O_oiB|?J@qwvGy<>6Tp$=4NiMDc1H7Pm#_>;in z+4RuO$`h(}_;YhRv4+y?&eGqmK|-a!Y6F8DVf_gvrK2Q;*dMpInf;aK==0-n``d68 zo}4{TZg%!)<=VQt955y}#_|%!giu7dIxi3w9EDjID9ena{gWN_n;t>sPke6Rqg~3# z=80;LJY8QJMo-}l<$fGJE~U(yBbCgNgjS^Fe$fCDI6)R>aEVr21x>D^K7Egkhk`zg zm`*40=F~P4-D9ZiwH!him$15x^*)JQaAg+6mm$ly{7CYD>OzSxeGP^?#(aZ*LwGqZ zE}rO!o=-8MD1{_E1!g0Dq>v})pfQe~#Su%{dEiP8tbOfA&=GwiW4yO;E#^o-NAl;l z=&b%yh^?rh3NeW_S;uFBlj$U8xLh3#+eX70hAS0Ri{xs;crX$ZrZ6tXw$d(Zdmc$2 z$1Z7N2m1)i;tdvCIgPGtxGY}(sVDtk@g4<Pjfl@BIh~NC``e$>TkvynZ?;-%q^K-T z*bW?2nffJElk<JsXA8`|e#<WJy5N~*^xB5U<2N<g4}Mbp+zbY{?2A}6S9Ar_6YR?1 zTt@MYNoi*Lb76wo^BsYjHij#W1;{4_vdX}2lTx3(*m9cu?rHq9S@aU8>_A26e1v?* z>}f4Bfk7r^&XF?1m7V5D30&bp7{DMa=vG(MfO0miyH3DD75EM>TK-j~kfzEHUF+WM ztlT^@OIs%?y&x<3^#dw3^0+y&r9ciSgIxLpZhwUgKb}@Y0X$E~TQ!=Afz2YUMpbgK z|IGDQ->;W#i*)FcS%1(-_Wr_*{~7vb%s{Vl`wXts`nP)woph5eS5R%lBcINgBhHG^ z3$zVjnIxop&vWnv;mWo>%A{<Ea+i*Lo6xjyVpllHDO>?Vzr3tj;TwK@Z}`i26Ni-R zMpqX4iYiZTfgRefaHfC49QZ{cEuQ_=1qD4(f6O(#6MVXphres1yPa{7UI+MlN2d6Y zE2ksNyxJCjkJZug5(e+~GVEaNOqp+&3cUjt^l!Y6sNMEka&|E{gDWdnT_(MfyN9e? zFh_jcht{qpx%Wr7&ykX0TbE^HjF@rb3(Z46qYut0v8u2B3nebG2{B}4+t_z<^I?qe zubvX68yfxV$jpE2PnQPyIOg{&51h)EftwNf@v=#Hb{ruuoM4Co9?v;jyR6Gy*?%(b zBPSbr@8T$b+0mnBrt%#Scl%*^viJUhBTcd{ZR0NUWl+i>+BD5-Mvry%-pT2s8V*?q zG$RbwSK}cK$cEk=dY!9yRIY87RI-$N`*dgl3_nJb@8n$ZuZ~NuRupo@vS_cmhe+RW zr5HLPmP`E2kr%OLe)dsuc6%Sxbs8K$OmVaQld;=C@GT@8hlMLWtCpJxCP$6to7J(3 z@ZB<8vw=$fOPJCGTW)7*>Q=(VBs)jtff4zEnV;RxBt}(Y<hI7Vv9@EFs~%C*h}MpX zi|gM53=*_zKCRpX0DHHmCGrDDpQ?FCp^0VCt=p%QWCn-=GJ!;s(NuF-<;A7V;a|;S zb?0(@Dxtv)W%%(pHMD>Q+j##E7*xx@0MIjR`9G9cD>a}z{Lq=9e+}v1*q<SA4Nn?U ze><%lFxTJpu-^NBgRJ*M7LL^1<p6BW!#xDU%wvw-@c8TlqbFVh)wW~#KcGRTZTpM6 zT`!`>|GV4Gu(&OP-ZyRBe^&@Zjkc{fzs26W_P_1B=SV!+-7@gJ?jd3(2Y-DQQ!>ZL z*@bG7aqeWfnOUW;h-z?vlvv$CUnY)a#KrEV$H2V5bFi(mSg>00WBlP`{iJoPk>GOa zLuP^XvIDk|4CCEFip_4aTmXm)ca+sWhgR~8KI|)s^~6S`k@1VIJ2Z1XTn|3?(EUTV z{toTyK(L+5SSRMEeepB7Q@t5{pYx~5RiEA{%|FfXwwS|&bUHpS{_DP*E*BPlOomsO zK$nr7Q_6wKP0*BY2E9#$O_qe?=f#9r*SJ+#WxsH><banZaN-}h@=h+E67MY=P7qc* zfRrN4%f0%@Lyqdegaf`(DNdO_9DU4C80$!I*4XTg-$915UYvr#IcfkB)@K4rd!NbJ z|F|)(acR856j)}OJ7$inm`2zX{h}=8G7H1p%f@-8cS}nRWZ<H8zezNpV=80Zji#YF z8tw&Mf7})>OjZMle_Gdgv2-PdmxzV&Z{nSot_iu3W6|>XVpvbYP)2jEabs&3-k@HK z6coN|qZ*jnV%QuS(i)`FaksRkF@0AxTzp!*r%xb#ZC|QK3E3#L7odD=CK~vmf|EYy zJdLh%1FRe>2`f_?KoeU9G3oAG>x5K?adsvaYPjYGDLM<lJ~ADJf>C~MdRN62U<Ni$ zR1<2zUFpBJ<<#_nj038Syr71A1Tyd}cD%g3_Gba5CuJ`AucmvML48;ud=IAN7qZ$G zHtE#pUE^Hxdv$GxybDp_h;>u}0U5W{46c+C;p_S=!pVaAhy|)8hR3KTjD%-xR{H8r zO?|j_*8u2^n9nx8r;w+VIY}v}29A*P*lmrMJ@o2@mzC*y3Q?GCme;@5vK`w8+;uoj zewZzxvHh9aXFK44ehEHxG0QkO0=@Sv42RaNz38V#ZxNOW_qXM{Oi~V9S9wIv`ZIWj zl|F-}sRJ)6bPlDyK<92jVKt?zlbKn%sgJDdTx#>r6=vdCZ>brFBLv%aGxsF6H@WFu zyi;^^ZFJifg10$WzuCd4z1W{l&v2A?ARZy?G^|T(VQGbF&9N}%ELKK{oJV~7@UZSM zxlh(2m)#RPFl=NG*Opb}{F&AOTE)}r?pJinoLSp|)z6Ch&jYN>_t@23ezM1<Mq#Yv zTI}acrI5j?QG=7+GJq~BIxb$5krePuAJCi@?gy+s3kPJbtx&W2H+EGUWZ*S5;0`uK zS4~|*RXz2Ib-I*V6v=m)uw#SCRZ)S_&XIt;hfV3?-7wnGkEJ2{UKeV{oF-c%oSjYr zNa7$1aa{n>ng1Jn=%<IfYCu<w4GM?fNw}B#B<S9Jj!K>Re><*3wM>KR7dj9$9ri&F zC(SM>yH3BAW3}_tVMK#5`@fh?MExDjH94D($>LqN)Tp^&bm~N(v!9^2QVYX?xmvr& zzRo4dnQpWelMDcU7g)E}R@RHoHNJD3R8zTI?P|&$xIBC(i=lIN1Zh2Xbkp|t;@fgY zN1bpg4uuPG?$!tnO3CK-oh$d7Os9~F+l+h#-m!-LNLAD?O#<Ex0f_yiEU|qL0L>xB ze;;%}B6<su_$?D;7M%RM>pnb3^#)*Evguntp`mNo3{1WjoDzX<V-Fd8T<TMd&fNp< zEbP$+`*`nj2?1}}rB+AEwGV`Y@gye$<mp>XuoY^OxM&#bsNS<PJakBZ<PGRoHT}P( zZS@8tgSt{qPmJ!QCPVXTQKz$Bzc98z`U)A(W))spG|NV>!WBf44AYeUX!VK;kDId! z#>X&w$M?Vb%vQK@e%<SS`jZ_Dd<_e=9RRTZP%AxztIccoa^gA^-2HZop&usE`%ora z){-ku7L0}mcc1^e89ge0FGA7d=N_p8PRal&4;shGQWp|4+GF22=}iX$h})%d$s#^7 zJi3&{C%N>7%j}!EEnT{B>0-u`$ARaI@gV$6mQnnnz&S7MKg^OX3QqE^8Y4sH8crHY zNphPtgknO3NPDxuhT-d|dUM4~zw^B;vM^ZrWP}1B^!+E0`r0F`X!txTKi`AJvpdyS z95hJ5xa#s8{!=Uwm&gN`DY30#e&TxKAZ_bLHvXkFz)%<z`4?{iEG5i~V6J}Q`$pG` z^EqyobL%JF*F5w(S-IYwd{S-e^wx1mnqA&fuU#|i6V{L3uNg@&R3Fp#M?aLmUZ)sP zIgNg~TDP%iC5l;o3zQ35Tf3uFPq79yAiQU_?m#BXw_I<`{QBm<$W-^K2f`A?dvk<+ zR;bY+=Otk1qi&9FTw;mJI8<2HFKci<2SccvHLGkbL<5Z%?Bw4KpVa>zyAj>rNqWZ0 zy1A9Ekm`m$_nD9vQV+Xv+1=kB^K8;oh7i#=q-8Ri$r9F>9;M@f<U*9I2<xOh=BERj zbqBy~>P1aqX%|C<#cEKjvm$SKTaR)UFcQy>2-+chZfAC!dHk3@FdIdj>RyoVTgSgM zHF~V`_$={aoJGkY@nz9R!UEaR?e?xwb|$ZUM@%3++r!CUbZbIKvQIW7{9T12kF&LX zeNbaFA17D`M%oLsgp8BZEV}7pfG>hWhOv0N?4tLha2K;2#%^t$oo}#j*4q_SoikAK z0q+XrvVf&rR#cPKHT5SxNiq*N87#V=+P|o6GnMT(u7ExS8H>(tH*~1d#+OIVY>nja zYJ50KNDayuI8y6bV}7Vtc~ecOjK334Z6AvjAG4{md;7&OOkTh!oF0<A#}p1=O!Sy1 zKt>R6#;ormMW~KF#zrZ3^vfKVcmOM`nsQE!KLVhjKSQTe0u0XE(blsZ^5U2`;Tr=n zCWrM^`MQ8I#4u6TPlidGEx_5xxH5~xo^8CJ6yj)Xz1PX+*C*$cu9d(@x|Pq+ti%X~ zI-E1q27*j6PjTYvU{=voc58w5p^!PREgg)<4oSaS+cvqEOQ+(h2fyj;PjpiSaQ{|^ z?YmczbpQA}$CB!mC<k{~2W|ZU|Co$$GSJPOt{*09^8YZEoo7zh#<sQ`D}zo?blleZ zk>isXKIjPh7WV%uV8W=@$qJMr)Sd)<{pwC|%Fs$*aF<_tre*iBopl0x$eVgp;Udmi zqcv8_O~i038$lMC6k~v&jPOEMdFn-q4)6VN&jquWLHE{eUUha(Xibny%B%g}<p@Ht zfYr9^w-Ritj|pyuFO2Q^vi<yanTrzR>cjNBn1gG2<>Ft%+?OAA8`KysAMetSqD%c< z?US)LxYYOmm_A`=m@Ps0>A8U;CR<~ix68o|wT;og7WljDQNWxnJvkT$ounk6i4E1J z!Z20WVdyB(Nzz@S5>!`1Y?;x&EyzCFI^L9$__<B~$JbpkE_OZ%XRot{ZA<vAb1zaj z&YQdBI6|SF0Ywi~#>~f5i}2cvCNzD)j&Mx%-g%@o^_P@>OVG=gA1xZWzRzyiw=C?d zahiJ1!fkF9$e&oR9Cpe*FqU+vU#dv5?R^BN;K{noMocX#QmdzwLi-jPR_IYB?GLch zjoZ;GjodRFv^t2Xm_;3gkV#bZ#@42{j%c*gU+#+aLl=U@f`a1fqyPHj4pWZp)k<Zo zMZ@t4PWXhCdJ|;0)U2jp#f1>%ii?jSe$*zUND&jHiBbW$^aTa@<r5#DoCy92m(3t* z)0p{bzS&4(6_FTn`{dpuhK;M3iau1aH0LG?u)Kh}wz{o%Q6YT|1q|+z{_5WHm2Uk# z^MBJ@Zv^1P7YO#(&=nHyh12LVT>QmZO${rI?FEAC6Mu&}9w6G3T$GaRXTziNExL5l zX*tg_`7zFff74R!mKD%ziU-7;9>luyZfPJq&|8fwKqeh`C+|g)^<#JLHJelTr(w&# zuNBgez|J7t${p8WAyoM7pv+~0LsGalkQr2ck`bO6JCZ*<kExqP)=^2>Su*+5tet+z z4r>_RD(VVN<#43z;oDnpp@fd)ur95zb6H%5Z+exOTQ1_N&u}M{(1VMbjvI0b38sD< z+Aky3z=_~vNjOxL;(m>2S+28fMkgR?cZ(H)7KB@TteZl^HQ~}+tO)M0#2Y`oU%XLx z<w{`vv>Q3%8k%Gu^3!#dPvl&K1@d81*ND$&@*RJX8>uo;iQv7<TQ7B#w2ILoVss!( zC2SQuN;ke<cEo*dtKjFlVz+s^@7$p(4%+_BAw)J>a)Dv`Ml(r*5=^2ehP5xz2@gct zrgcZDAP_;!>D!hwKIpk=)Mn@n@pV8#&ug!O`C|mKATa5;es`{8zrX=j%rG%O9&ivv zW-+Qy99u9C5fbp)`46moOBZ893-gWJeVv*rH!(2XeW+Agk~<#L1C;i3mRwuHh!RoS zHJa-K?k99hx4uyz#uBqZ;DU~5FB;f2pb|bEmMM|mK3V3T?4RsLI1UwFOd?tcP6yL- z{tY%EJUDRY4mn@p_?|%AUPx*oCHGB=t^3b%hq)r}@;%5T{oBl-Qa!dY%-;2jKJ0Q{ zW*SsT3}1Iy4+h?3u-1xq7ghqZ%ocQYFdfsiib|)3y02l5icvkBe}FGL0^llp0FZGR zyg!?4cr9|EzNRkmRCy8?-dz<oA7AW<D+AE*2k1(i^z=$uabj(4Qc5k$KS{;p9D?|A zMZr`0*uTHd9t+0JJ0IhlmIF``$~O?7B&GRld$cImY{&6U^F<a(dw<gN4m>%3{QLRQ za`s(a$l1hT`L#I`AIx*Ym8OO}grCeo0<@>ZABV^?%GKQKk(U54Y!&nS=Rd$|Nf+mz zGd~nHpMYPpOSdZ#GrNcmhj|t@wI<iK`jF@XQEd`+L!&5tmX(sUq7dqj>%d1pd893V zy`I8?fu6s0qDuL%%80GZ1m6;=D2bGf7;!>^a+#FcL&LM{1o2AeS!=n60=9TJx*Tpe z&*0`ASvZfDf)I;rC$9Z;*Wr!({ns}N<&VgWl?%L_wg4E$E3uI^wKHW3%&$BWSc8cW zNBMFa-RV^Ub79IsIQ7P+GwwKCFfM3OI}d7R(!i3}3R!(Tr*;s(oggOhgQe6i+^##Z z;;A;Ork=gw%}qd=BrN^%T8Wc7Ac2R7WIM%(_(>G1y6EvXf}!4dmakp>wu}F{74Hbj zNI8A*pbeoqIQ*lTg&^gE@fz&g6|qA<GZfaig1PFrhW=H3O8p_arcY{$vA#3s!argE zZM#TAvF4J)^a%fr5dj%Mr@RSfAkjTyjp~tr+mVhE3Bbl6!#B04>M${CzSYuK+*|6p z3NLDuJNR}jJLAav>)&OlZ+I#<<dA71OiyfX7<bRjpe^=}6%I)a4zR<EuJ#MH2OW+= zzOck=ejWJK@Y9R2Uurv!*~Ix8^r(Ku5TCWVhZ|RmQT0@<txDXX3`{H=b2PHasPYoP z?#!|xOlV6?ZE9s(RP?{9_G?lFR7~=AWG(wzE!#gE+SL6+aa+mhFj&{@uhaLCUZGQk zkOyHhFz{We)Xu1_`FNQ$z<KyfJ+OM&w1+quf{Sh@%zo+qXXkpxWj_`sBg2>6(Rc=q zjb}bSlJAc1X>2;lu<lU~vy72QeH=+{7KAnrNo8^{;#p(hwee}X>OZvJU^sPjKR0yl z(j7Nk{!H)v=ORaLvvZ)NCj3U;s-_DItfGT${i;<*Kw;lm-}ck}h3!QCM(@VWhybrG zzj89-%A+Mx!Rh!InsYc#stMA4@lEl+7H?nJ7W3_jRBNA&(qS_<!X@5`fFp;U=T3M! z5)_pZQ{VOxzA375e7|YLp^_>ARzE3z#PAKK074z*?%y1y)hZ#8FKigVNYO0myPXz) zo2w8{J431&$d<F0*1*R{F()L55CANafZbgG^R4TQpj1aO2r9J@yuxyPY|nMMr|$TZ z;}|{^rh|`{s5`RChYtmY84fdG=cB7oK{VXG2ex0j$!E_r03nCpx!zepgtIgVzE|$x zdc!w~gH^>B!ovHr^7>EC6;%crUz|j*>R;Nrq%g<<gK_(f!<&$E17ila?XFb?k#D%u zCBfgCP$sGpku1X!xgjP?mPox*QiuVhhc$IB&w*LAyN<APtfa227IIji)Lxve8vx(M z*88X@^<rq3X87jo!sGW^k55!~BTX9i-$`?#-}7xh=)ygmfC*1jCF)6HA2Z?3MiT*w zM8&E^Oyb1yvHnYtRH`J-H|eUXKIVqUI>C;yGh!BO1pI&X-v5J<?0Y`Sz)!N0QuY=3 zD?CRZ_K=Piqo|W`BM9ZQihMVWj}s#UCy{B=C=ZSTD`ha3s?&MhbE&1!*tg4foFC*{ zK6(1wULe;6kWQzfT>7M-Lj0p2DEfum9kjII)$$3oz2DFWP00=0u*9=RUDKobq<T+y zARc~xb2v9G*jYU@5HW(9>Ij~C=zX?LyoyN{NqH`|0g^DsKJa5+4U%qra#gm1gE`cP zYLlSP1L@(ra4JIXdRHfM?d9&m$LB*PyMBNhe#{gWDqM`*fs+zQNQ^!y(Iol`*Z&HP z&k;#|sYb4oQF~YkEicv`J8ipIp6ApU-uocwKGi2XW-n8>n>}&GpP=p8YOvuX0uml8 zym%u>Y3M!@P?6wz@NDSCF(&TG_zAe`Nn==|1Nos+X1KGFgIyDBVf;Bj?RQ^$-e=Tv zJ`t%A*7Qt4I%E|y_{cqzNi!Ws`>gIqRlh{`zeFXa&)#cVe=!>EMVQ|HssQKdq>N7P zL+-AUe)b$Jn*|^LC&h&H@E)L8H{eRrR2@^wGZAS;Lk5ba668P)O4p|6(Y|w2jCQZF z(=m=F&e0MSvkwulirOW4y4%SNfLx6}Op_*xKCiWY@771P@BKO0&1!EzKDr{8W}o@k zoD)Snoc??Zv_4_45_jX?>-M&`#y%7WSh%rNy<Itqfdd0yo~eE#qxlqbnv2=2C>#n- zpYvK|a2Hv4ZR4rMu4|x(jZW;dOO{|-Xwt)z(xDk(witYTS9;%slz{y)g+h=s0Mpr0 z9yFx;BytZ`nsj!C)0PwFTc7eMb%8KFZ*ErU=N<iC;ptvtN?Mw6wf--Y21jzSQ}spU z<%{6A2j$h_t-D_@^mYJLSn+q@sny8k6C-U@>3y@9|7^qj?NHa)=-c*$ouB^^v5>#i zh|0{exZI}L=S_(H#QVmCuyfYAlj!tWgzNuXSex7DZe&AXY}-;26%%dB_rid=5ST1p zm-_33jG#)tn@|(HJHY+OHzpT}UhZBlONh#9-O~~HVo^F`u+@u{w-IXwUJQq>tx8|L zc;()FV;i9*_k!|zv6S>XD`O(`>0t#6S$l1x2Py1aAI5m#1(G{}oWh6`xpj%CQ-vyJ zeWSjxu~@8jy2q;uMf5Hfaz862wFq;Piap+^nl0LtF}sv83+|R6cFg`}rxH)*f~hnq zcMigtRju;!+noz7H#~8_Zg!!<ZTE4C-Y+>bxSKyaKND?yQf0%Y^q`dcM9>BIY~Ne` ziF+)vZ~o)A774JGtv^vyYsPD9nWy^Ca4^AQ=|)z%=^kM<8+7E1y2Ek#A?p|6ED2l3 zvvEO4&lsI`6ymiQRpwKaK_&naQ;=efI$?2_8kewwtKlJGq<6KtzLXLaiioUZ7M7~- z_zg}UTB|;1llpbJ!Yz}D*WM3&J!U1%d61R3(APerU8Bm6n`R$BvgCQ%bT6hzPgkn% zboQ>xiCh%qSz(}1Z(AkPmrd6>EMscYxDbKQr5_`y#kWhzozIqOpaxNDq_8AI&vR55 zXOV~9Op9M-aU&+Holj}+diFK$Az)d^D9L!(;H6}p^!8y>Ntu1+zP<Ac`*$`c09HfB zvFIH7%%B-@{Nb^G)_8InA(xSCKj+Cp(`3!4j4UO`S|ztI!g^eG$y*(mF0VZH!gz%| z4DYvd1S4yd1L7l^rE!Bc0JyKuS^!7N>GB{(PBo_JcE7OE&r`1rm>h#Fra=!G^&>!a zuKA$uYZ;T9G#N@q*DNJhZy9qh`}J4GMX(Q)sSyvj91S-ghA7n#R(1g3j2hoI?AUn9 zK^EF)Qa-!s`rH)|ifG--iom|tnuJx_ir`w7Rop_cw|#}5thMU1LF*-Ib(_spN3NNM ztJ0JJYvi8oDC04lt6OAPCq&kl6IO0RkqX(Ls-5>z>Iz(DXc5w8-`{2H@dXNrePT@V zKHUx513A~rt$4K>V}$I><Cz*pV#$KO2dH(+>&pyTQ%@&+jp21_Y@5M6oQ4U{G6Hj6 zzc+2n&Mpv+1Oq_Jlo(17Y%~etJmOuo-G0(2GWu8EbMKkI9ybGu!c5)Mo~J6CuR!S^ z-TWFD(XX;QWTSm{&I)3!mY7p~89!=Lo3*DxfYn@fn;COru;clJ*ct5pBIEsglA_?S zJtPXxoQ;hrDhGlz@s6%Ah*%+qU%;LJ3Tfip4mTnS*Ja=8(Y&Pzt4+MOfM&i%8M_8+ zw<KaU=XwuOTg(HZABh7m;CKbPg2@`$Jw9L2xz}U|cx?s+Ee20}%D<sQ_yvtg&$3$Y znT!#Fjx^rMI`Kz|GNwKA{?q!zE8?-l0U2qdVjpd5_@3Ms9Zrfb%-6QvT>xUeuWB0x zKTyb;J@(~GmV~cR=kl8tA!9T%lTcWomUIK8t7W4LomuXKV&5<+_S8$Q`Ac#P+3ZMZ z&Dj~<<$B8x)_p=j(Q6qsAxndHLCYo;Tfcc)A8XdoIhkiVHUpQ^bfP+9J9;gd$N85N z9ZvD)o8LW&JhkKKfm@q-WiAw<ZsW;yd;>Hy{kZeU!}2Y}1;i#@VU#SzIJwY(f&s&v z%2I&a(JX#-6PUVrpgW7|Z81oe>t!WnSc)i$SKFD|hEr%SS-3621iVR-$}s>V6cgaU zZD6*4o7aFsO^a}S`53%N*ioQ?;tp<5MAB|Y>NIjh>YC>uX(q&DY4e{}1FIXv6<z*X zv73|9)h#f5gpUmyu?iRHoj38J96G{MUjk5D48zmy+cALTNpmZq?x=4l5$Jj>Wwdc_ zfByyDB%yZN3g+Zl8+g#t;X<t-!GS*r_WI^&{vbiJ(Q(x87}RGZoH<~kt;<9!#NwnB zR=B0vvxxENLd^rL(>;WH3nzlqSA;CefB@9RwIls{C5lQ-SjP8yR0PmR0Aihzs$OgR z_03@#%bBUoht5)LJWWKjc?E0UV6svaUf<Elbu&EMn$WKq;xy={1iQi@EXeCWA6-*e zFWx}yPsyuAIG!xgam^m-*OO0oS1(xQ8jQpA<yUIye;YG*{&I3+o8&qjdvx=Ap*!XT zKqCN&D7`QRU}WI#?#dxcVdCXtCyA01O%Lx2=WK*?>ghq8Z9pBT6!$AY1W@a;b~Zo@ z*R{5u{rym9=q}`!&rH@2yzMFG$)qx44waz`72uG9$k9pNb1EnLI@KoO*&vy{5BJ_G zUg25Ae!8Y*AyZUbCGQ(y{UBKMynDx4p>R-ngslLm!DH}b<lW@X?X*>63g@TKL={E2 zZJCXUhn%>_ET^)l1j^0|zG^xPp*J!|_qehVbFM5e@LrJFf{LT7#o^X})|*pCF<8$Z zIy)+#J=Dp{X8O2RxQpT6N}cmZx&R#g-cDTegZhu>O({0=E`qG7mGHx-4@vIYAr*%O zaNS1L0Z+|V%TkhH%M3N&f9Dte!wRHsfkgObgxGedbY_r=$UbE?e<}MPG$kDX59<d| zt`v_(8qKpC!qSfIm_ew2(Dj|nN$Zd*bW|VV7+L6E#Cjh(5Jyr8-JQ{KJdk!fL1)92 zKqVIg<w<*>c|%oVcmq(r5!E*+^!x2pDy8z)fU8+2ZJgRPg`(}%{VCGaLh~QhUpCI4 zG4`m!;dc4&KZ2e20us?m7s{QqRom6bQg}je>}_qz+*WI^_10Us+rpFg^w_o@cnVM5 z5ZGNLbnW13QVpJdj4>@9(qHnkzWuO%c_zyaf=NX!^EXQ2%HLk4SNk2IEAIU7j{Qv~ z^WBP$O_6s;itQH)QQR$x;{muEFYec)nv&?R_Tkj;cZ4)H!SsEac1&6gQ<$YAF_kZX zD8#H8t1bD;*|&T4Ff^YjCyi(;!7?tnFZ2Rd8A{7yG_&qk*8JZ=wJ?pnJ&(I@y)6Kl zz@G&BmM@f(Cj=@kW%o_pA46Y~Bok$R!Dr*%>LiN!<c*nFJ?!^hnxfaHl1#p;QwO8z zx+r3LuPAh?tP_uaJky5D<T2@wy+nodpN#!eDGILZ7T?^wwLb3$WUVO-BW591K~omD zebl3~KBeMAy!h7L2_<|@>Iq?`n+T3cgq&j={=umCRue^>VqAX(niiED5qM&x>QiL` zziShKuoS*i*m2*H#=u0)Ug0TvfOG)9<H7rF4M0kh@GDXdHa&pp5GPKm)}`ZB*3@pY z_!=y&TH-crQ2f=kpUzJ8k%&IU60LVvgOMCyHR=>hbn%S+;9}qR6`3e|e6LpGK^LR% zg{J)XQMCrkSN1-c^fCL89W{XWolSSz%x#QYrGr&sK~Vn+m3b@z&70|T>TvXaeyi9m zTX)byZVuFYIG2|5NWFI9@6gUhS;}9N^?dd1f21^*X)<o1T@kGmvPB<EF3Sy}2F6ui z<VXzx5`Wb^wm^@4K7tFD+9*wTS@1z9dzm|_h<#15+W~JD>kAj*Ky9*^C*kCB>{dcL zW#AmWT06WsRwT5aT!voM3Yk!b*-toY*{&-j+d+f^x)jO4wZxu+56qid0McWmrM*Yk zJKb`5Q~oL6ywkedwU)1q=Ct}YA{?lwt=ENT+rjM5g!|3>Z6n#1$*K+Q!v12u0h_BO zLYQ^k`lyEuo#K*39eU+(W1Ny-x6pP3p$8&Jhj@iYg&_z4>DkxS)FfptD_piXhrudR zFJrrCSOFNh!<4@s3t&PlqmK%4YIILz{;l6Oxe~kWUm#Lzfln;YaarxfYh+v{k|`3f zXzHvDFF0S|1tE-Qke7?W8<YXb74XUq*%HY7<C*Nu0u{RMu;aV4JjwR42*v^)*OLo2 z_EBy0MK}NB*^3;oha6h0_?AqB+A6Hs>b5^wW=cXdE$1n*`IbK&jE?YNNUU9zP<019 z{a9J33`AM&<&Bgv)a(H8a{1A|>s)Y{q|Xn6$aMX2R&zEB$f_F*8*|Dw%)j-l#k#%4 z=TFu9X961$oJH;DK~2$cs>_B93EU`(5&XMpyT>F#_opDV1I#tNa6|)}&gfyM2q^32 z2q)@rM3~E14Z22jDjUdIh&vZENcBJf*2@S>nw1$RM|#u+NUXH~t>Lf_LFt2SC{~j- zv4{Tfh&Z@LEEkYf8e+qXDlP7sb!Un1q<dOxKW)mIDSU7SR7}h}_>>c5)9hj{bd4X$ zG8cx0oX)oO^pYJ&J6b+uoA1*Fx8{uIvMc`8(D7+Rs?YM7qzu;)FnK^=qkAbCKH9FK z1M3m)w%ra)Qa<kYI-P_hCJ9Dzwu@Wu_5PO~bxb2xAl#?~e-trh!QtCY!smk#He&ad z#>U5E=NjoE<yp8DlzWMgzx^vu9e^2td>xMM^lWZ%tw~qi9Sx4swe@TeMSyhYl>C3| z2}#YpNX`vGURJErljnW?o<J(y^M7hOr<U(mzHpvi5Z{lyIhZIYO+k84k?JDBzT|6( z2!Xcvik-psTghkF|M=u~xjjiyiA)ig$HJesdf`jAH;55C8V71Ury61%#A{xU(tR(m za<-A+-_G#g>tRh}`36j`MwjnYxlw30TmqII?iGGI241bWv#RE!opEMePq=Aq%YL*S z{JIjy)>ufraW3Ni_juW#?>+cGJ(zie=yWEk?>>(@{=bL!?Hd&j72WiX@@yY-UViN) zoH1Z-9I~z8p;f}2EVMS9x+zL9?L_&4Ly{H@ZeC`|9N%$%U3{T<hIM*wvg?pwYY?1C z^2Hy(*#NasvZ{Pju#u+w>ey6M>liPHZ#~1%U?Z$oeYac{%ETc|XQwP1MSe2*S0O)R zQ7&aM_o|bh>bu-kg3mR*`$$>wt_QBr8SuKAR{0f>j|9RIJ94cQ&YOW|L-&QfgBEt4 zrf+@1)OsEud$tn|tcw+G9yx12LmK~tkE-?L1!>!iSl&n$Fjob3?N_`;;C9T1P~J9| ztD`)&*GIFC2!YVCkxwCw9j`@;)i4a4gB3hyZ&X)Iim1ulAA2UpLd37EfD3Z`cV>g8 zEWTwUce4oou|v2Ug=LfbG}Is8C~r>>n_gQVZ_l#w(HkoCQN3Yc0lrSB4MALIr~K%n z%mfS1gZ~T2?%lvgg%4j0O$zNVUAf{qg48PKdp1sX_BlV{R&6rxX^rOD;M9Q~<Jpo) z4a59BJ0)%zLcup7RE{{#pQ$J1R5MWyM+i&ZK^eLK&yg#aV&Z$xnawDYX1JytM9`2s zFoI*aJMvfg`i*cAU--XV@JF_-vWe2@nc!@epTnSqa8*+`+L}+3J#kF9<*wfh5gWe! zvXsIDUZaojXWjuX0J*&D!mbC7%jHvjlis}{+mB9C8igq}{J0>ub<My4HJ(u{iXlWg z{}i09Le6W+r|t`#3~FUph5lMklsM|1aX#WA{)4{olkZ?PWzBY2LfZ;Qh6m2(G%jNR zA)mb3V}X-d%zMG>au7m#HWI#x7|~{(TjpibO)Z0W$mqu2)ddl^eop+8q9j|Oq?0;5 z(4`j-1H}14u`~8yH%+!g>%3^NFNvApU-a+sx!l!a^o<7}P*~Ryfi)W*p}*Z0At}&x zvu+eTdLekfIAl{e_wj$EPxU0tfSJ{^twJlL)iUh(yKU#fb8M+n*&&<rc3J(3c5f)T z)nBXYZ`T#@4fB32C!2|A7lQg$aGS1D#ebgYaCtqF-tG~E%I)53UmZVJDLt%LicxpU zJra;R>j#uSewqQEUH53t8hKpjZ~5xO%Z7|_kH=cB%Yk|`$nWLa*~@b_Dj9SUQeDV* zg9P5XaO>IY+6ACiz<l;(jc&uvSK-4^PJ+SQp6nwU=YPo;%@brJedW&lTaS-CPn|eb z+F{H=T(aWlRaRcoyhH7R+pu9PD~}YcWu_bJM0~L5DEw7&lRc92r$YE8PpB47dqBN0 zNQI$gvGK=^&-eNKdt>3YIm&5OXEJs%EeYuv3x6V{Cu;?6`5rFPb7Qs(&Z^mH@r2L* zSq!uUgFC_Vy`i~QNE2Q7iOsj_b#alnNASYotx7K<${Yp^zzcc^+u*R6v=|^Z(zM)L zSgvZqgz2qY@eltGZoJGp?Irt5udMqBym~^06xyVO0B)}4CV!8dV!iaq0fo1n&Yy`w zT5;Sv_lj%zJE@t+rmry!I<(T1kw!e7SQH?UvcGF~<Q>QmZP;}ey^rv0gn~YWCxfhr z^v~I+-3%iQu{4NhEs3_y`ImULR;Gv1oPyg*h%7c1u3v2otngJ{?UYy{#w>!9>zvJ~ zJc1Bj(P>nUdKoz?V;5C6p5Gq6>+PoPyK-53w`{tx_mSU1I_R7UK6aeD%gWQ?gUvVh zwI*1u$<(e}nLn;OD>)&|&n$B5d*Se52y@^e4?;3$5$cV6y`S<WCOxXg73uDV=b_=8 z_0HwqO&F)2aKAsHdo>^V;r&H&OM`zIB{A{MB-@|^OBU2fOK^+n>gIbxrB4+QMa^)1 z5aA%cc+T5Gh*Jvh*4&;3ua1FhZzQLMn#nP|t`gz3WWV#I!6&IN&qchMrkXww4GNbJ z{QLLA+qa05Hb~-|caM67+1gc3iGn!NhOit(^PqGt7Iex9+SO1DT18@NbhdF&m8ZGO zoO&d(YjE=Uam4#tf>rF!PZwCa1}A-~ZSKt_2Y>D7=kUTD#?DFliq&UeCW$W^S9DEB z{KMLbMpU>F4Pk{#wAsL%tXC=D!d~vvt5$kTDqhtR!s|Ehy(i<e`L)Rwc7XbN_uYy! z0hqd%&u<F*;!U5vd)aKCM99+r?D1Llc(YTv_V@vT%C?Gvr%5syg6wF1N{QgK8{?m& z!jC7C%9HN#Xvv>KhbI%0D{u%(kfGkcUJYNPzMpd`uzS?J`g!a9b35lSt>6~hY>pDd zqt3cyLkJ0uN9@bq2!Kx*BetIuQq=qGE}iEc;q`J7fks}DDabetc6Arhzu!3!p2Dko zyk%<BO>%y`m$G~3KF|AKFHG;PpbvX*4N|$E^e6~!98{3@`-+B3L}w;4STB0#VdQt} z5q|8wV5NVxk({sj6}>1NeHCVk`(z+{(VDH28L3-v;C;3jvsIe2zRPyw{kLQWBDR!s zRj6<!E1qR0C@J6Q=dD#*<x_D<NNJA$gF{j$g*rkLEjF*#_~qp4mKJ$&%4TDnahq7{ z*#k3X-GyCl4$7~L!B^jYoRt2#D`HrD47_$%oS6wa$0GG0_)0)UcB%mKK?-l3)rF96 zWB4wR;AnH|r-oR;#rcBspv&`UX_au%?x}vF?Ev<5Q{t~F9wO=>f76g|BYxJ5{n|pr zQxoyY9Io~VOlcNgk#<Pn*mco2*hFkAByCFg7!%}prs!Ry7IZ)KkRMQVrn~U)RF{X7 zw&^}%Qf<!H=U%caV_J%VN3+!uLQgaUbfmrwUuhC<CL$WGTM1kzkKVKqxZ&`wB7wc` zVvgI#GV4D%Z6_*Mj|ls|<>IX99G(UaIXOT*7wpRcphO6;PDYM#YZJ+8yu@c6_?Z~2 zGqBHC&eJim)>+SDELNo^QdmN8odA|8lDkBs9U@3iG1H?=+0RO@m$HZ<6nLMrjoV;# z6anX4I88$WPBd)F#-Zo=8gdt`_V><=z;!ktxNQkPuebL<K_c*CJ8^*F^Uj2S2l5TB z9Z)Z*-PpFa{Mdiq3HVzM7dPJ5uwbSM6JKj*i}aFJ)hQht<S6q{x)mIHDpIn_2l0%B z09+g$0IX4UA>U|^Bi=nG>NZL#(+(wUUq7qiy6ujo6s*r0tg0U163Bi#uejtpb5)1V zRqtvTS5kNBm~EWW!k#vM<)4Pu$lQ>zIwv0MZ@SV{%w?b`>Le*(2jE%|-+I4LNc&4i zdOr&AM}|93%7n&c6bHgfsjMJmICT;U_xf2D46n}U3z2^Rs5)y4k5nU6H=aLDYXQHH zD1~e+AynukCOO(k?<J^MxU=aUnbat$5RK!@xI2_>e%fdJd95*z_O+eu^xd6mTM@V; zc^1eju|jXVLqiW)x;ny-KgBuXeLJLpsNE$?&i9j?hF$il`6AtcDw9EsO}iMm(fBs_ zMurvDKIM)0rimkXLu0;*%=KztX97Yme9Q5GHEH5Wd(TBj`G7}k{{V#g&!!!E<y010 zQxXmHmQSn$f)QGY;hFoUY-%oEo3CtXJAkK*K=EKWNclg8&cvVTKaS(y&BhF~&CJa< z_kEYUZRS35-)W9qQAmZ*HurtxPMR}Uq9jTEHbzK=R4NscBnqh{<>z1cK0e3y^M1eH z&u5xR{X>+YiMEwIYXrrM51i4m3IPk;g~=Ed;dyask|jPRc8TrP(zK;?aZ=(;`d800 z0Qmad(_;a)(idsUb3{&+AqoibDGd?dKXihd6r4pG5z%b?bOjsC(xQkeL-1Opq>_gg z$d$VvId$KJZ*z!+U}ShB<awryW0@tC>GkTEyb4ekdk`U2jz0lzbFdh7P6tdj+FZM< z%UB&fv3>1RR<c+0{Fnj+h(s#wT$XI1$sZ1iw9h|9=ChRhk`-QTVQDRUVTCGNELmlV z>~m1heqH85w(;zD+KHC8`uR?xrW|HLagq=$Gn|SAx3-S_C*GYc#OA*2oF*6=_vtNG zwTERXpxlB{a&+laTd`c%$Cs{H^6DLz-p-HQ@+9r?5Su$st4z`$H}ft%;u&;T@iV^D z1OVL#hm#;%q2mLacMD2#h%OKDX^J`a+%#OBDVQc5JL4{e%a4473QOYGPRGC1&31hg z;rpMszvswLk3V2g>}{O)*JU>{D{A|&`3Px-`%K!6&(WE>shsM-uI-t5cpz|8WSq$* z8dt}oP()7TE`dIdspGMjoD=4b6{<<wM*z7IgXl#rpfLX+i10?x4J;>YpWMWKOV;UA zuqE=~Zam-5#o~c%;rOXU_v4#Yu1ShLJ;>|8kg>GT<rPlv_6b>)X|kNHdDW@#5L5wG zTw<JCoE#S7`v%-V=*2-u7>0V(1<y-!y=HgU9w(X7z_``SOY=$DxC<8?rJ*j(9~-ly z!FwX0$3*VK-XHlw48VLp<%(3}NPOflHnP45tdO+;m#XnX`Lm!()(Z+Ua@H4K>lPK< zJ&`UE10sbKrAj8r8|&`D5r%<a7xgfl4D3;A&7g6w5)nk?dj~4r;RF$MtGpnr;Df1K zbxwd+xWp*F`Qdd<e>=W?I*@;tWpLjpIs|$F$d_&&E0$}`&j%;G&phXvDH2S&5=iIz zk9+z~;@9@*r($v-P_#7z(?R|Go1EB3%n;WLIQkyM66pa_73}LEuM^}*20Y_V1=Gs8 zXlsniY$>6oB$(1db}8AqDm@Q0DJ9!|veZWk&7l<~;)}R}BHb%&`7kTWqEC6{gy2Wn z767K=oNGICRY5l@PRoJ-IA@tb+AoA%mJTPHSK`AKESqiKi12Q5i+0ta&H}P;UaVjS zyl!0a>32XfnVFjMODT@@EaGzdk)&l;!&Esr(7qv(vPj_%1OSm<7ZMN_3lE`zAjc<D zHK_rz>BsgN7$(*G5n;UaEB$Da$tw0Qr%C0?YnX?nagopRP36Pp?ha5er3TR$8YQN1 zG`E!!L^!Ky`8LWd_VOExNxbk#k-rSUOf?PTR&08O4c8m0QjT;Ld?yL(2ZI{b^XfI0 z<0S6BTWO3VwIbFyHj=|PJ%C0gZwtG@@5-R2(Oj<V1Zi#oaI!X+*7=W1OwFoaOZvOX z3x?lhBUb57x_B40t1d4R8$pEB`eA{r#6qG{Wa$jAT%#js-LkD@+Iyr(w(o;=#Nj{& zw?N}<z-iMm<u1ze{?2(ZLi5q&_KJ(Zyo}L1?ZWesL5*mzemH-5+_P-)=eTU0v=%PH zer;>IImR2eCd;|q+?Cl~@I~*N&-*v5dybn0=W%`A;|Yfsn?%&=1_D3J_&;@e`WsB7 zrB7&H;q#FGXIp-B%6U*kqf*Ek0pfOHf!YWcE~zTjaeGgShA0krPhWAuo$E5s*i4lv zirrD(qn}U>I&3aBUL@NjYzL39L1MUYYS&M6yJzj(x)Na>-}krMFaG40hUwkP;B=MP zYxj!fQGp2Su0fIAjX6@@SzPe3Sead|G<=cn^-o);Tv-#2TK`!*hP86p4$YM&cC!8V zA6eJ%C}|y@N{IQ)z7?!GTJlOj6z~Fa<dk1=xt~~=w2Eg7iyjMjoG}@M7lPTCH}69V zM{I@;vR!WfgqZY5IHwN#gU|j;X=hQTtf~DE&y>%r`F>fwx39-^zK#8I>BDQ4KeJZ8 zaBGuTy0xAG3LJYsUBt#dfG;oF2almYH=kkag{4d2!3Rhk4rw5`NuzWvL+E7a8};ZG zb5tVp@`H~DIp=I$sd*$HP|Ch|%4jI*S@dz88qiy)Y$a9DxJYBe26qsR6tZ0-0k{CD zWhJ@xCXlX*q(eQ!$RUOdi~?*<x!lo*?#Op5?`enf{Wy3#_cU$%78GP<zt~}SDz^0M zfVq@g_NQST_|9Nq2LpMn=c!Gnk!UhJnP%?srO2Thk-P$ke!)^FGgS8<I*hNx8d<SS zcuosJPXAO*5%MbHHVl)x=n?as1&PhjYYBL=`{UY?R~p<5bR5o4wB!6z0aSZ_9$LjA z2SW+zTJ|KE>LeSb@rq4oWTrMl`gnOd$u&xnR;(g_ueo71H21ArdS9g%>{8zI@~ARt zKU(ee;dHYVu15(-xnh6FVp=I=q>NdN5Cw1E9*M{+!>-Vf+w77bH6qXHChPuEdSHo} ztauyVe(Gh{8Fp0OtNyi&t+xVJ6Cg|%Ai}Yf(TARCVT<|6kdi>Q%(pd@-oKLHgXvdo zF>X6!SFUPfIGndcD*I13`^Cmvl$X7LH9ejEkf=s~DCfW5`1|<a-Ql5DH&+bPeFi-e z#bGe3iAlth_si3qvK}5#RCW*~NdhoA8&xdHV>Aredf_``ZrUMf1`rPcETPdWvOZ8X zBtseF>2rY9<FHH0$|7jRa(ccob$obH24VuVAwcP$sK@iuQ60>3{^N*KY4MxP-dDB~ z6C{ZlB8?{Due{Lrm{*O(klF(Yfjv^7ZemI7U-b9-v22mxAV-cbPZ<OVd-B$ljj;y> znSyvFN#~M~PGJNgoHQxVUN{Y8Ex>8|nCWg(<L5RfkUuN%>Ma69lo?5HXN!(16EZl} zK3W9Dn@~CNGT(zDhg-e;&vIheqEIn&-ya6{5uo4=9)G2yHm?gt%nTP_e<m$?MXl4d zG^--S?cuk#8MpI26aEJJ;p$xVDDP_?es|}X3P3Ei9@c0DSO7%P9XdYdJvBkb{22Za zn!*f22l7HhOz6Bt4;}e!d8RJEfRW%-7J8dgXTZKtigeT>q15QBqX8E;9uj-xIj?M` z|H(Se+2_2S@lC2BRzkr5kg2p3rM=|4JxfJ5du<N|{7fZEE}OZ@3Hdb=`=rcwL1%Ag zTmrrIjuE@W8Sxrs!_yi|Z7!E`2nS{<``y4lK#&8N^)75oFcxy*?NYx1h|ijBu9aEk zM=_Omtl{Oy97-2;`k;SEeqSV5HYRXVr2jaii6w%~Ar{F7S&+CObPQmz0+9qn*+~FV znnJ=zlHdW=s~EN~g7O6*3U*+!x`=jlFD#j}k6UJsjg)&Kr|=^=1ck;ZfupkA3RbY^ zPKHaq9dmM>lBO`q7eA7L&XSV-vQbppC0@pzkI)Lkx0g8ec79@Ey|q8qxL=8aB#;c_ z>&yKsmf4*O$Oj6(xH@r32x1<{9ZctFE!0GEFg;Q`4j)BWQZZXfq@Jrh$sms;(wUze z2ZQFl@O<8R0Ao)_o3POo(*6MmD!#nYDJKC9$y!L`+)Zzdp&WZ%dh$BlPi~O}PfOVf zy||cWZYH<y=S4M@Y_8KH9o=iGK9r8LE-`$(c*(1<qV<u$p*OeES27kMc*!ek>&%2Q zrJQ$merL1xF%ZlE5!C^btOWhMK1Q_Wr#4+7meMb4eQ=wmN24(b@jQk8NC)c^uF)j; z674;Rs1#1Xn1GZ{u)!=MpBfReLc}ngFm7}y4jDz8*!OPrMN`IEAN_mWTzf(hWkB2d z^b#-ODOK80lt36CC&l`IdiB|}tJQCft7hEXsPc=F0sKmes?`d66Uu<!WPjBk-Vl(v z2j@s~=!iY(hMZTD+aL)OiJt~a<sD@tW|-gbvSk{t)qvO;3WN_PE!hYX!;~aHezkA8 zBP`?y0$AX>i7RZRVgL%;Hcer~vN01xRAgkwD&%M-4ZXoJdZB`eSL7$M;A;REg>{hD z_t`y;0@k}1A?3?Kei-Xp5f%|3IbcSfciTym7e%sX-3AL~c#{L;_(a-ElR@qq<p z+T3*RAdGJQs`J24M;4v13XYn;vuvT3vLe0a@bxia#?T@LIwr~V=Py{PV1uMKK<HA3 z%GN6OR{M;F3@Oj|E}JbpLlh_?nLDYacth`jX!)noUY}zV9Y{<+Cu}rHsrUe<2%txg zi&9=FY(n@XN&kt#lhQy3Q?wW&3n9wB%_tpf{OCzc2XaQG`e*h%*QRr_l|P~&&qLZt z)ymZo*ZrNCe%8UJ^Ft=3*NuD3jce4UIfIyBx9|Qf*n=E^nUrSrtE`)J6y*KwvG#a2 z-E*CV=^{z#aq8dYleV1)Rn-3dTUs>Y5wqtAZv&`G`VtsRY<+Wu*W--<L^nmMu@&Or zSL7H*=Q99_g|YcLSI;4!_4-+uJozMRHvcRIvjM<ZH0<2L>UfwescKp>;R*l=E*5KD z!)Ao_iTKZ!{HK$^G^B<4Q^{{$rJubwK33JYYBz;{-&K4$4y8|Xne=g)OblU$xQxOy zv3hhy=a;B8P)5$_%~#ivt0U5BN0mxeW`2OsS+xB!uk^p;W&eyQi|7+)@+4ScZDKtj zF$joHEB(c0#TDK(>bfVcf+yzGso-QOBT-PG4QM681#3@#(L+NdvB!7AP+i2MdUPcz zHg|M2u?OIHBXKVQLS0>cdps!2y5E|tZ|Q4k4Ryh$YHnar@aZ*oj9dpyfIRMlR^6<Q zjT-MBrnxK%S#4sDb{o%<)goivBGgZ<fNmviK0{ILwyu|gvavIupIt)l<}%34CBz!* z6pNHF=1#_B`i^cMHA<J_<KWqJ(H%hMTdo-FrjTU_?w1lI6cl|9gw<OyQW{2Sfw0JQ z6afF@jH#PpK^$_VoIn7FEGjv-k6NL<u%|<}X{Cpt3H~|6NVotOtsD%rWLFdOUL-DS zk>*^~{uB{s+>rXv=Pv5NfUVY4`SAlqx*bmF;jrB9kSVbnGn9(CXRgL!7&Gdy?aHMF z4tBkQ#;pqa5|q#vq=As^N?}U&JIlWN^ed$btI&s}rKx{<&|_@q8S6Z$H=9Rp(@kyx zC?ef*qXLWOEa$9oHgw-i^X*k3jXF}Lmgr~<sd2?h4d_*$C3m1fMqprc&ML@07HQA2 zyku`(tT;s94!Oa<0Z(f&k@j7A(i#bAx45qUAJkD6B^#oCG#47ME9!?+s1d*AY!_pU zyKUUIaOYIBoPf&y*4r<7L)_%;19Bx>y7YV2Kg*Niou`y2Qb}dcR@99uZhL>y%v!tj zNQ_5Bi_N!}ovb}$SsL*>ig4uOsSaDvFUKb09y_@0x^ZtEk@z`D^n@^yjj9AtChXCk zfb-&X1d)~;Mnn!Qz)y%L)PEu-Ra#fXt<O3#f+Z38hrB9(5-IE8kxJrxkJj}=R50=6 zy>qT<{z7(|X2i`OmNCX&-@3>?-%o`+AnR8-oc#??yTuE_Pl8Tk(iXP*NRw>wtd{{r z^a><TrPr@2ij3L9^M9u}O+Fpxgl-P&kamC2NH+Y1gwTZZPS{9v#e0gVxbj&Yk`le- zga9<uVtgN?MFT6*m4|<!mFQzTEKz$9!k)%&46Qx$v$mlp?Chv27hvCnt!(zud@CRE zUWb67Xz^Z}q^h6H-0{te_oK+kKS(w1FmDd(H=al}nxF+8T&2<)WENXGNy+1q(kWo! zv=Ze(8%QF4tl-y<*P}#p4jr3yhJ>_=ku)T!CHVF6mR4l4wLaoc(9w<Wx&OKjN2bX> zx}p&7vMMc3G9jJtHg?jYugtVzmH=)O4ZgKIqp&n|+^3*BG$~QK;6Wri>k~alnbd)) zcwG?s5E`Cp;fmXh)K4Ve?A5d~()#wopI-@>Of_wZcRs&sx-%qF8Y|@Wg6H|?LePi( zY_L^~@2htuFSDyx-g2Dva$U_Qj0O=_(riyj$ZKTW+fG%;v9Zk?z7|J>wMKS@YNz(_ z`Xs?F0D+-nB#{QO3s|#hg|}~coIiazWxwL*hUf@Id3m&&E)z$Cgx%N{o^;gQ8$QK$ z*O|JO;_c9f_7m|I5zi-xGxC}X_k5SOzO^L#Z2$SsZWq!!JdQeJnznA*GGsb$YP!Q! zbI3d(^ukft{rsxI3J%KQpmftk=fj<k{WKz|B9rrij$8o>BswbdOhzAykmuXacCp3d zq_#~d`xJ=J(-`Ah*(}z8J4WlC`vg9jF4Xw`;1)nRIkgfz=FKngKvU`_R`=@wsO5pI zvXs?GCJ9OUxmVMk=S{Gseu583Is>dnBU+9SSn3zqjrtcJrCu7mau3s$BaX6We58?@ ziCb;=xgubVseNy_k}fB%YZZPuzylc0a+yw=n;-||N6h&o*_XhaONu}z5)zFJAgA+* z9g5p=LeymPeOf`)H$ADz=J^;`%7voU7#PiLdvht)Qw&t4I^(=U`S@icmukFUg*Zsm z7`<$9*3}lEF?q*|Ucp!^B<(<Kip@^CeYvWIe^>m}2bd6Wyf5w}!QFN?)oD~3BYJ49 zOx2z-LuG?A(Mmx1r2ff4%B3_*^se{R;%KpmLIK3adWpFpZM83^8O%0-4x(W;xEUJK zJSbfNqvuo!0AL6Y0;84OMGJY}?tQ0rNATR*Z0Dcn4KJV88YS+m{;<qCYMm?WTn~u0 z{Dfm)KB{t^sc$IY<VznR?0K0sQcNQ~CgTz&<sYR-Ep>b*f0~dyWPQ%Q_}Q}k6aDWO zcK2RIudwxgODM?8F8|k588O<LcGJl=udAS?PNkjUwU{Npyw%pOrUuE)Cgk82(=qRI z+If|$y%-dr)Co-MupNEGN%I46JW@WDbWOorYyR%#IFr$|Q91K4E<od!8lDf42mo?| zTOHa{mZ}1@XXk24Y+wGoi+-f$`+Z&d>{{zOE*Vj>&jXw$A_G8DImXsGDrZXzw996M zzy&J+?Gk>~$VbTpc->;oqdsoe@^o{_dI%=+pyf0Fp`KY#hVrZz7qGkH+Hg&O$9VLb zE*ieduS0f#v0N_2wy-kP)L?)HXA}%qC}1t9--&Jk0fMfxXFa)HS2ofKgaL4lVx`xj z7rMd#H7r}JRR_6_ffHcDK4EN_Opek*x-5EY0T*3$0rWCI&RyLa&=N)C`4qw&Kv0A& z4m7=Hx&j>j@wTEaY45KH^`hs!n}-wMC0Jd3xB5y^CTRmilLl--^gziR<Icw(zug7o zN7_;w3YF7lQw#LFT&<hdIA>Y}3@mr|8TrQF)Jo+ImV?Y;z|YA*xWW9%xLm1oN<+&# ztG7-cshiOHfNQ>N7NOiEZTp;<Uc^O&t7&Y*Jz)BKKIVk96J&K|W;8=1xa?TDcZfq| z{los!zD=Al0$q?Lox@^gNQ$_^GV{kBvPh%lL7sTI_wEk<itA;uA4Y!*RBl~7Jiayl zX3g-E^hHc3PhFxkH^7Soyr}7EI;U*6(v_Zf^y|-38`2H@k5tudYy@W&q<Um=4P5py zvsSDfJ(=nV#ED`GbXKy0U{Y~7t^&O$8{z-0J+>C7H9c0!>27KX2}=SH_SV-kI7Ui; zRVNdVsPzby^lJ3KKJ~^IsGQxu{Vz3;EsO2ld4yu6bMeiyv=)tEh(u&xwgD2KZkOdQ zeG4h0t#ItKi|4%qMX$WF4StK9HLxNtK270`z3#eDpyFxxc)M9<XT#+Py0<G?vN3>< z4!}aR(iKcV@UN~<;BV!4Od+<iG1JHFmYg#2{3Q9|H&UCgH-rpCNj#BG=EACHGjvKp ziK>%iu_w_PYvJE6{ENwIEf`GCNE(iiC<eC!M67Y`W8Q>=Uh$#W|Ae5+Fbl6i-vM`M z8WRLqhS3k8Q>new`O~lfrg;QFN-N6sD+nKj9`NDQMR@@sq&!(17);AT0-Gvzyx)c8 z2@hheDldJENKD-?j2rkMO?4R+00I4}L~7>60CM*-Bc0*5kaQz*D7Jho<70S8_T5{r z#2353x&xVJ(bG0fS-&ow7~ugnol~#9AX*-xI>Y2u8-9&;_2^`byLO08dh|yZC2Gi3 zA?g}dm(lG3;Hd&&GM8M5Q%_?mSt#nDaQZ!IB9TO|3<ygUZ73_NRb+lZKL*Q-jpYYV zJIKw_xCI&X38mmtD;0V3%2HeCWUfDK?B#u`_p=v0S~37~mU7drFeNTqYMW_gy1gK% zzHV;M)5;@31VE@2oI?Q8dN<P6BxHmH3(oQmax2j}@;Fa1pD^?-uh;&F`m+w$tNO#= zf_ilJ|8e+F!m9bww5~cu-B3z+-cEMWKe|=+4fmTOV?GyJWCY*F1+*~SE=Tt&n0PRu zQY$2(Scv?RrUe~So`H?4A}r0{8YD2H6T2#LNh}B{nrQ`cvhnjSiH5hrfe>T%bH9v6 z{!JX<F+QEz5?iL&u^R22>iS53<nTX(*;8nRX4UmrnVnf4LkeJz@;lG%DGDQHz#jG7 z3^6-1IcUEubZzm<;p-;aRa-r@OSaxQE;r1xl70-C-Y#(MG-kFRE3SVzKp4IuxH&E% zaj84Gw^i*7h^RK{?4)Rdy~*?WJqh``10%m=DTa8%P(T_)fM~EBKa#MdD1@(zwa;@Y zc=Y56<Guz;GXq#D<~8C4oL+nB))spX_*Vl{NRiP;?C>DiIf-*EAEfVrfO71jW^xv< z%$+b0KQ;Q8Xa`P>Ti|Adl6>YF_^RBozmDclF1%QLd@Uz7oqgzo-SLc_V0<*<+5rG$ zgn63?JE6u!%L#02ap2_V8@@L~k;Bp{eFrV1A=DQ02>lRAwa60o22($o9&a~9F(3<C z(^3a_XvHs8)&pJkXsm>p+d?tj=7D)dVn-;c;s(kmDWe~xGeaKTJ(U*&>P20Q@09*! zkZGD`>(;PUf*)vgkO+%AX1$PrOYwq9err9c((lP<*p5lOdmVXdsKP9Nzk1MqJnPaH z7<dxft9fmHqDSZEpWO3~pTr=P3{99dKP}3gsh^tu6>+WrP9I#AP9D|5H8P>cvYKSb zhk>~)7)o$3U#*BifYkL|tV2PLGwG6A4^{X#51K7{#a@@=@Pe~Zr_IB@RAekayx#M3 zLWCf3dEZ=@cPQUTviW<;z_QF8P>f(k7Y!S>;A3Ao$esexv^uhv`R`UC`n6g{dVaf9 z!p}GK%!AcC=rwS$oaC?HTOHDGh1=!+LTv0=G-Q3_izzfF!y8ZMt8?D-^TxAK<PB2- zB+5P-9D}GA-Yr|fzZ+Z&Al4K~Q&|v;u=(R%>0H7UI4HaZwr?%C#duE17~%U(B%4$f zy)B8gsadcekenW$p(HO4Jo!vX$#+YN`)sE_Fn#Ij+|tF*4Kf^S_5p9v4XXu!jidDd zY8^7=*+D&!I^-2}E+YziT6R<ZUb5cVYn?%%Z(~Plf0%r{-=r*8>&QhDeS#E{g5miu zyvv#UypPE+k-;atyjKV9q|(j9cx$PH;@~<_Su1ftzZ@D=k449}Ld9EpM6J0@Zuogb zS=oNILIiGGtLUoDkBBoqiW4EmLm%CEe>ythV<SeB1ZMe{r83$Mmqf_^8$Q%I56xn> z=5<1`%uLKz+!l^+yKve66aT;(VKBUEyi+?R@Q>F1aBdB6$f(lZSM$H++)0vyO7EU1 z_0#yLac`(po?7bDQ5xTpW0IRi*G^&bjs|{D5I?^7?WYpFfXG9o1ui=cay#j+C@i9f zHW@UiG?N?C3e93|iDuD_zTzTSV2S!(Nv;tD<5D~Xe@N??)01r%gbk%g$SV3r<n=UB zLb?-j^wig7jZm4Sh%;aDGSrn%l8ehfNn;UAo;X%3js<C>g0L)DGZnYR5-k1jJ_Cub zO?`|eKbTv4JcGMn)Wko_;^(a7&gC7MIQsWMZwHrqUs})iV1@5Iaq0=~>&^M@Mw)8v z(XIl<<X!=On*cAT&TT}({aCOxoYwY!5gz*uhd|=Z_yN76w-2<%(oTMesjYJ#J)+Z5 zzU|*J3<jkDPyU8e-~!C3+W;{&WF0prZzIi;J#tgXFvi9Y(JW5T_b<fI?V+9<_(a+M z5SUE-QEsWgYmjCcH9C|)fyLp#SfCOIa5qwMX+@Yvuu!=sevi~6Pr{D88?Wl2i9Ms% zEQY^TSUl1>tqcVJ{nx?w^*aAehp?P^zJGuyhzZ}D=W7P=PpnjCq6PTczhTL21wQ;c zXBcA$mPfN>QW3&802En9?CHW_6JBx!EDHGge?f{BpFVKCpJc+lXe5)T-+_5`jWd^G zp<E!UjtZAGg3J}Xf1T^FOX<6hvZgw6z7Y@O)tW`g%Pz5xf=^$=GN_3k%45R=_7=u! za}`20Wui40Tg~vCuUI@2IuomO5eXe@5$GZ2tuXl$7ax>59Z6dZuZ%s?(Z%0Oh4v{a z4}BIt%uxQP_P!_PFJe&n0h6!4IP@G5vc-h^$@A~w_#QCc^9vk-I^t^p#P6__ciM0U z*VB3$Y?W{k^G#_7#lc_zCx-+{K$|ObSgjCZ^jKRtf`5dlqx>Bz4$(bx0)4`MWTPIU z(nD6)u_n8|Fe$RIb1ilJ4kE|OnYYLVT*5d^ElU%GGu!M+B3p{0r~p%@5yX>3^VvdI z7My`%_ldkoo4n1m`MKCWlXU(UEYXXE+R|z9x9egS83O&Act@z|KELwH>90@D)UIZ$ z_A_zuA#;&+pa0SLnu#ingI&##L1aOS3xzx)Pz1Qj@O;PZM9X4es0;HxAvi8I8d&UR zqvSIk*|YpD^I)S=hQ@bwVyWjjsHV|viUY>tFwsJvX7RR3&mCb|MbS6>peqfQkJ1|r zKJybx4%iL2d#*t`WgQoP3x96ab`L7EOG0|hpDdvA-~jDwRCwO0c@M>ZIwRz{=)R=I z+`d%)*DU_&Z+jd>ey{%egKJO5S&9W;b2&JZ8!oErQL0m}_}&=&i)Xc~xA^*q@V@;b z#2!nKO60-h^OX!$7GyiX7*c}m0*A>y{Dm5TG8wZ-lyP+WwYhKz4jh8}CDCr<He_xL zZ+TI{_N<a<DwhkuW2A>yd2X)#L+5arr%@T@NEyV8+GzQ_(e`Yq0^sh;rH256(2MQ? z?(!#Y;Uj}&3e?7OR$uM~c+$7=HEIEfdfwd;nf5ORpSq!OK(dEbS3mfm0$euGVmExy z*eDZ|7~I=ySL&Gj?<?itAW-Vu!j;s2oqYBcvsl}APW@gWyo(sDQI9xF<87oJ|Lm5v z^E7hXHD!A=oUe0ZYooA$?DVIIBm)i-8C^Lwyme?EWO9z~GS3D61XbFPsMnzNk`IiQ zx;h$JC+dbN$ImrVe&~3VS_lo6+Gm$KDdS^3Fv%V-gU{kqt{+azpG|QKcON<)-6>PQ zphD0ndcsi@RyXis@^Y)=s|B%Z+@k}dc{Sm%^05oZMfl;tNcJaHPbS}fsvDNTk_7u7 zt~b-9Oko`O>O-OLG~t6xzGWESth0{@I7TLlsj!v;{xI#bbil;}&QJm+>Um<R+7Sn{ z&L^NsZQLVFcm$D4fyzbs#ii0>uKEK!-lQW#fZBE*xQs$<BCO4{nveubk->9TFd+JT z=!v$_v%f-pTkvtN!e>*Zt54dV`hfJp!HDXdJSq>C3NF|uwjGQeC(^zR2EzMs{DFAE z#nX>CRAWzO=qf*c@R`cco!TchJg;%8WsC2Y%keMH6Aol*MMLjv59rQBSOyj90dSW- zG59$q@Ch8XQiAVUWA3%wlmst|YSKgJizL6{5@}fFqxcQxZGRe^M&+_6;zf#s%}+7N zGtUifQS^}^c7>_LqH_U#?lBI{$oh<^+2&x)@Ee@-BHX_MTYhHT>3i43ofU7s6v!>g z<f$jZ%V{7D9DF8FgF}AZXdrbwJMYCMfo3Ljc0QNM?eN}1863=)OU|1Y&cAX)AF)I% z;5D3knEbB7^dA`L5jZ(v$zI~Qx%;b|U$97Ze_|RUiccE`P~aIaJ^;xJAhoqafU^jK zxnMnfgoavghLdM?OiSy$=l%TF8Md@~A#jM);)rA69oxIQSVCxMW!X`r)rnNRPxRf0 zGTXfK#ZsS70@S%UCms&~Y|Z4ZWkw6s<1#kOx@P&)=5rq~1sX#IxYO*1xA7b6PhZ>c z<jtF{y})nWFdRuJ*g>Rx5(Uy4L>9bokO+<5Y9{tD-l@^MQeKP8Mi*Uqb&6O|2<H)Q zy{!_D;;XJZVt_Z%!z(xwEJ}5>VjGEPto#i!j)*s!8~uz|$H$*(@j%I>V8X9)6o#63 zl8BKS2p|IhC!t;b1y+78Oa8jw(>6-v$zV!fDlxuB%j1JwzL)TK0;Am6_a%qHS0j#R zChC`DD+vS^%qglxiWfXi;Q1E_&6_`c6$kHq<i$z^_@X<+P8EreNv+TsGyWNj7=RSB z#A?Gr0I<ualD0poM?~VhY4twqI4$?3Eg!t2-W}=sQZaCs-PXh4Rejz+8QwZ^Nwyge z(hf%|#oF5W9%>}kv7n;F<6KSsIxN_n6?-=Nq-P7?fKy&=kZKR`dBnQ+ap~=k*rAuF z2l9w~GhX^(#s@S0us3NnFU3-NtNVtC-U&oVXOnd9<vs!UrjmUf*g#8)K@!@Lk>KJv z7u{oEi>HXhnKr7l?JpkWSzXVcz;C_Q1u=CF6=}b|U=yF~el(%WIRW$eUYnm7K0*kX zrk{y8IJX`<gq$tT?`aYmgK5lzM;stTs)*}6Z_i2m{MPTdM5`A<pTFL`Jxo=6MC>gD z4}Hsbt@%Fm^48_sz1n;0z0Y~nxjVgchrOh~e5NehhtMqZs2VSpG@}N*|83WvF^QG$ z>=7@$y8rt$E{rE#R!2QNdTvpD#b`-X9H4l*YGz$h+9GK7H@Xd#T5hBtN0fo6&3z{2 z@!6iaxv_Dp$K%gfr3#EuyJRBo+P08_{~E(MBR5NN2Hacy6e<rwi07QI(x#2*VN3r0 zV*X~_)bBk5p?%Zj!v`B%cz<R7FRWhmntB(dhLfoz#TR&%`)9#Mmf8UrDCZvU>ftMA zX@R2Jnq@@I0;Z<smqJQ1VK-XqV8f}s(lT?zJ6>tPHb4oqak=pCaw{lapO;lNBjiGY ze%Fnc_q2&wLN=4<VnpzkviN0*SKc4aq)l{z=3j0H$h0NjmCk7K`6MjX($kWDN=dr< zy4}Ik<KUmqxAfFK(LG$Ajr(4*>`c7r%lmxQ-&aQ7=`U{!0`r22idQ`6?Z0PFNf45y zO$$a7sDEx;{i#%#vcfBUlDD4dgE<LzqXmXQc=R|hNVNCAnGT718ma+CP2yI0T0%@I zKEvd;-LD;wyx%FmQlj$%*FqdafnOdjI}ucSBOTJ<?RCzyp~<B9VT#?S3ua{(AL#F~ z1Ae|al$81^zx^6EBkcT;49zuG+7eM+NzaRWb6T#beBSGlTX4@C#mxE7z3ty_jx>S1 z)qgbA`VAYt6ymsFc;Cn5A7oC6KQ?^(Hl^b3<X(PTzyH(1dWY40+)h^E73?5R&HI24 zRBGZpxRhP0WR<f4fVeWUMa*&}wQo{*frF%_pWI-vbumH296Z00YMpyY*GH61{}3n$ zm?lE1oKv9?n5sut->l2hu!w%rzhKh#qNs|dhCec*zLgh{PXkZle$+#Yh1zl=Cy8{= z{Tm`eeiRyY4Rk&1S=+Hky-~gwqyLOud2_?x^bX-WX!PNo8}D=f{Csu){1a)@d%GJd zKVJ#b&{(w#J1{h-At=v^N({rx*;nGVuxgb$&__bWo{dxx?Sw5B@WkHx8@ri<l~V7C zdzD|oSE2Uc{Iy=wrt~UR&pw!iG&=YDr%6p)5bnfIT<gnLW8S;>Z7!_?EUqw}2fUZQ z+fA!FyTq7YkhiLq<P8jl!ZK9ti3k_;8FG;f9YRFPLQ$^fgsk~gJF{(?xqxQlBp5=V z70p<XZvO!DN%&J{9IY%W$<}UJOBh~};tdcWVSg6oZg%YK6c<^a*l_fiGR|!ue4<SL zO(Btcto+FSjO;;I-ahED!9b&|2=Gs-x#D;Vlv@N~{0J&E+MW;cH2nj+JIklGpe05J z`)_m5#zd`DlnW6LhVTy*rDC49ioJ<wKM=xHlF#C&PadnROGTXEESJar_j}p*z<}J% zz)n2Rn5%8?=6-wT(TPt&7#~BBbb?5+I6C1IsOVkWx4U=zEv=9}9E>F}pNi6*JOAE> z0y;spKVjsxY++_%?FQHMi$2aEegs&lPn*jYoJ2CV>#SwLMT4${C?_(nN(Lmz-TSf9 z<pOw?@U%Cr_e*CW{Z&(e`pV47(}#B?UmUHBa{heUY*Rd;(CAkjuju}N-)zgC9ufJA zMkBPHu^cM^21`dBzW+PD2C2pzLb-=^gZa%VG2)TWPON^7@E-W77)y|-vpCCW`=}GG z9=Z@3$+|x2Jx;K=)_SJJ=2LmgT;0bjt#)ZM?=Bp@alY7sELN9>vV_s~9rRbI$J6^W z)PLU8od8O0bqyq@dm_(z2@40ManymM$B@rOk0vu0c~rp(AAJ0a&!X<}ik#|m`YWmM z)aYmDkbzO}tZU(eQ-6bgf2{P?s5rJg@coJDuIQ`T1^2(^h1U8+HL(*S;lWcK7QrUz zSWDXECciOj{`Q#Jv5M-VaS+l@y2ByHS;VsluTwv^P<G}~%IZY=K2kL)An6R*y!unL z5B+s{e3L&10({^*QQY1MZ<^YbMWHCd?RIY3z>kFW+bE6s<L^h+J0=-?z$nQ+f=H~} zrpSo|N&qD;*NgJ9;O<(aUX3jbmNE>P2eYK?yXc5hL@rSP;3j946`9PR4s#}QrPVid z?<@gYa##4%gXJ&UcS`?k@id;%E==fY@L#o-4BRGBZrgu8PQME??TIV6u+%QSyJ3Y6 z?W<5e)+pd?BgK)!mgqemhp8hS_O)Jg<JX9gM&(hAThVPT6Owb=g3wujm97;`IuYsY z7TXbeS(pM!I5qaFX|G3IIjj!aSocKA94+xhsm)Ml-~PEpwL+QKeYl5ss~4F}PMgRA zxCu0y>LlX0H0uUDatNg2dX0D$@{tzt$|keqrqK0LYdJM0S^Y3Eo%fs**9WkR=j5U+ zgi{plX5SoHuXp#!=Sk^bqE^PD*9sIF;W8HXkNyLC1s}{pWp<o0O?T;n1V`<vi<>sV za?gr$VFx4s;S3ui?$kr-OsEmgL8x{E;<KPojAsj-twm;NnBe0hHfLl8krMH?c>cz4 zHgavp1Tgug??P0PEly3JNu!_Bu;!}GI&`HZ_FFNLT-};B2(fk4F?Hp$QFxg-me<&N z7NF4(X_H`?iA*A=-rhcG5mzB9d{&Urw6EH}co5@y>?2)0-<!n9H1=yuO?DlJn1zAF zKukX+{xSHgX)>@4tAZ-gbYA9&uqQug8B!i1e#I2ZybhEmrx8%Ua>}Cy<?Szhu`;Um z64C0`mrDu|U3GbxDp~Wnxj>t2Nf-y<*;F1mDygOxfciWaD!vS*A=Bo;cw8M`NPz3) z+@RC+lHAD$pvPyi$|axI^!Oi0ED0MKNom*zxIDQ0#HJk#{q`FY9&dQ`H<_$o92^_* zco=3Whi2waUW5HL=KaS_nW;!yl1IS5xs<73n82{2WQjbmSk6FqQyBzhHuO|B0+?SQ zI2XfVHx}K6PJILgy|wjj+9wzUOaEj=Wxw=&ziIEdLYFGyTMQs)Iy{K@n3aMj=zh`e zVn~f>z_7L&S{t@mhUaw31Fi<iq0^P-6~O9QWVqfNDdi14_{b$N>GrvnMCtJ``Sq5g z;)c_+MV35w!bxKMW6!D_J{5RXBCe-tL1g<vE>yH3tZuQyGT>ExwI%Q!4MLlC#Y4C8 z>u`k_72#FxmB*A8FBHq`Dj^!ug7+?Z9q;0Hy|JJbISuF1B&YxJ4<2y|w}mT&xwins z({lV{5Yfr^JrFNds<tY?FS+P=ZTR|bpVj@qO@s%8DN*0KoY}xBpSbHI1ALb>-77BS z#QP|zPuH(H*>~@M9@mp~rpfRnZZPC&pLm_4Wsg)unY^VdocH)TBkP=4ti%QAX%Pp_ zyIIg13%$J=ocE{CGM!f&Egy<3FrK>QiY(>4npjf3Dpz$u?5fEfl~XC-tqcM~3$hyF zjloj(X=wkgK&93cvl~7dPLHliRx`-q-z>grJr@aQS~$vYd$tEQT+ee)_aV{x$@MRM zFV87Tq_i93ULuY`aKPohhbEjDLF6Cvp^na+<56KE=a6~Q;%1-5Y@7n08>&9}ckY_~ zvkwp@3Y&Laee~v4r`On2TiEZ$Eri<zoezT{xASWnZsXga_%IOs*>9y&Jw&JH)>R&6 z#Nb)G97Ty6`!qctF5=64g_6a@D--iEcdRE|AIPhD%1v3AJb=cz0%tkzrCam<gMNM6 z3rR2IKCa@6yb{K122CBHz=gF^ijj=yG(3KRYusJ7v+td{w#nVKWVF@=7MIj_*6<^) z$(+QEF3Ds43Rxhny#c2&+qw_Y0q@`z%7lq$*UVRq<aKdl4__Vmb?&oV)x5XV4i&DB zxG3r~@wCKN9v-GGKx%Mml^vQ7F1y+Cq$^cXG1yn$#38sc`R4RSX@a`euwV8kzhBEj zGw#ARFU`KXib2R?jc&roO9{Y6s8EZj04C-(<T%<*c;1B|hqQ0~<bIwA4S1e-Oxr#J zb>Y?>#=gj=eEk{0Uqm<v2WVFC`qU#<S%@7c5&gz9$tY2e5_w;+W7a~F;x!Qfi9q~P zd#0#e^xO!#;^)x|?yKW^<l*P4h<Qm;Rat<<Ok?-l&h0E&k~hysOnVRGA;Wkb*GVyj zpbT5x`0y8cnTKtBictmHv>D;_??X0)=R*Z{Xl1{SY2xW7+6s|V(LN|)Zwu&s2qaA* z#>`nmNe85NlN|IhQE^Au7>zb_iB%KL`7<ea;6+$-60GUEplQV`*(-nbmSG}Fq~Q#z zvsW{JQ;<v7(TSsZH1;H4gBLJ)Tn!|oS$C+M9WvPz-&(JK{*$S-tKYjig&HWdX4rM# zoXKSoZ3;e-G82$u)EjBu1@_1|H4~6=eAGL8TOqSCV~Hp8Br3nHJ~^QU>%yfJqoCbb zTF6IsLm6Zdirp|u7^F_o$J+@CXtXn(fZqhEZ-JENv()N^Kk6`i*upBM;bdof0w||0 zKGqW~zso}W-Qd-2$+<c&xE(F{4d<A-Am~p>I`3@ZP7nnq4Zm%a{Gq1Zd?-R#aEJ6b zf+)C`hmZWis*<}QR+EA1P3OO3&GsOG6VsB~$mQ{~lviJBZ^_4K-ZIS7kGy&D=wuuZ zJxB$VvbS{hJ>4&iyKrj-Ti$5KlSMQ47T%r3nY$<agVCq!qoeAw?6pbzVi>g2O#;6+ zxWM}0gctTE$qKRnRZ4NiIn?E>Vi9es*<iSoSfDE;ZI4jGbSi0s!2l;M->ox$Xo3Kd zVv;RilTh7~km|S{(5nzv+pDz$9K512{fFGhh85?Pj=@M~YVtL6o27r!GCpiVmIC}j zR?a`OmNt2Q!j9!#4~Fi4y7=5C-@rq1<cyAcx1N=9;g9&tBqek>Sv!33G65AT7^b=| zCbaP?G#sQ3wJBmKU{b;fvf$%{slx&ZiDKvNO76zIW`I=(0U{CFp;%QT8vCWB>Q;p# z&xa~atJLE-frm_fU{Y{%QgELt_`L|B@99MkaGZ~;_Xj)fFY4tUP)|LIFB6>=kRNLQ z%!WKUVHW0`8Qk1((mCV}3VNl?*hQq=F}nQ8N`r+slnek_GcNB8YnDkhkK_y62SYx- zieKgpEwrj2bQf;&UY#Bky54h0Buw2Q{pz00;XlfU0cKI*fiZBJz|R64Z-YEZ*VsyE zk6}Ow$QB_1l`Hj(acl~yE)mHKn&<k<Lab2{TR6ep`jYQJl5$Qpo+NUn7;*Is>JOpi zH!?Y4oOnb`%+$Fd_Ju|Gf=iULu*vvEyYFpF#aGnJgMGtw-UnQ91lsLxK@66`S&b^! z>Ke9|g+2$J&UqQaTiiiL;VxFv=H!Lfe;?zB()YpPSw~_LTw<DC7Ak}vHWTWK*ch^0 zsc?}s10c$RRXqGaF<dXQFCS`A>#I(3uE+BN#Yl-YCICVTtPus4S%{)t`5i4S!z{r+ z$mA^~I&Zwi*G21`vzIn+9TN`RClmW$2$g-hY~G4G>|X2MUApk>A{kT|>e1*xOF7DN z)zyMt+m!0Jm3~J@`naBTCT3<RnsHiH9L;O3SnY@UZE|0B_}b#8R%>0R3hk8|OpEc` z-v0Dv(V7bE(S>IG6ag2H`WOiErdNv3SDKMz)whA<M4sZR;%e?2$nk^O3Bkf~#5PS} zvx^(Vg68hFY;MTw8&)?d3+BfN?Bf>@>yro?Utc$`g?n1Bm#STVLif9m$M{-8rY$-Q zsvGcAZP&JLS_?r1ViX;^An(`^IaQmH)D-cUTULg&tWPRcJrIf$ml+kcHH5XkMw4<D z>m|G0IobB^EYVb3t+FEeXfE-H&S9k0ZL^r$PAK8{)oTLtx5=R1Aa{bS2=-ZSpHx-A zE>4hOgV^gA0MP(ILhv`WRRksfCsy$1q`*%AcqWJb8jUIly6=OR)pYs~`v#rxigy2Q z$IqYTCAs}ksI%i1D$mB!Rf&+j9u@U;Y3o+hjviFZ+3bTDEqt^547a686W6M8MY8oh zi4I4#Vy>=6H=W&3b?xT;yV--7c467YirQ;fb#kK5!nF<_h(t8`OO9-rAvMtX{?>*2 z$t21qPH=hS#z&f<DH5QudR;aJ0~mt;sDj@%9uTI?H-J9!W>RXR(X}9uz@0v}OIt!l z+j3RMQLod7tNU+UYHOb!F}Peh^9)I%wrjb^JIx<~)k#Mz{1;Ytld8uBbi{?4pyw=l z{1fkq)QSBfDR3zY-`G~ewh!{9i5Pb`BO1fPi``p26BCTG@l(eQB|QX+m?^eY9#-*@ zwcLHQV4jNLCKa)X<Byu}E!q|QN0vJm)Aei#u@Q|j#q<$kjBdehB*qx+booi#>;oxZ zmsk*z;lDe&<FX%R&o<M3oN+$>Gw7i#7gsaq=nAPEEsqkOl7=X`Mma;RqAe@rg~;7a zF50Ed5k#%JV<Jp6NjvMt_NZuJx3IyO{V+a<G!Ox@504QRbqaraud~>DT)c-IxFFj) zz}Vjs{JrI|L*&FxwcH+Xc+b)N%6bG$nh%%=uGuAVt_^FvuCKB0mPC&Y5w42h6TJI7 z#(iw!`>=<vWPYuazHv*1m2rf3>j=dOs->;t^^7%KJrdTPDNYjeO4W~Fo>-SeJ3C~p zmX0C;FhPqepueYB5_4h|KURYcZ&TOw6XsXO;FsKwoyg{kuv1w|#EGEK7Xi<5$5Hn$ z{R@1wpF$GM?-y8LAvS4()^eg$@&ix)>Gh(QVa{A12Jt_Q+XO!pHb>k`t--FO_Gf&O z?p`!<yA`t50I@ZK>N-Ix%5WlcdR<_dk%*2E{+{(UGwG?5J~7FgbE6PNbl>!me_?~} zo6jK$_|#>5F6j7gd10LaQ92yR=FJuWS`4Sjyi5Rw1MqY(IC}is`0SNlhdcIyuO%L& z9h<$IC-_}!dSmk7dp%lxjF>wnoYQ_8c1@UX%j>J2cEww^!K!rSRA|ky4j>6~WhSs* z-=|U4bz`A>c>pVs<oeWPgxrmbzw6ejM@JvfbuZwJi~W5z{eRn#Mx-j?Rdb_%Ztp`9 zJEiUjD;yvWH-yhQ06qc0>nk4NKi=^yzfBH!bo#k`&&bP%5380<r%mNBxsO{>k7mV- z)Qhf946UGbRnU8zeai`%7ep(}==!KG@adZ&k(;k@x-)vu{VLr)PIX`(7;3u<JUxjL zGu!~5_@MC#iWk$ElR2gCY)1m;A7>;CEE33J_;If4Au{L#z|{CmK)+fS3Qw;(<Y-~= zz`^W+1AT!b;=JS%AW(8<I{)9So%Gn$mRh`F)*W@+zjGtbJB~k|9dX8?4D+8|Nj_LO zW*xPscmK)?jM}(syK$#+8B!ryFTf&NTz4MZMrs$OTG|C&$$Gac^qx>TqKe)x_7GNd zlPzh@W=PA$zg-#MUYYy%p|@H1{v6^|`#Rtxpo|Q^kA4MR!t!lR{C*sQrmLRT3B9E; z`kf2s<mEaRG4iSPwB6(R$CA&$is%I1Rb7=e#f2m4tmlHVW1=^SKdY|GxO|d+f)%5H zpFS8PPaT)flC545etJw;X?`fYczx-g#@m7qS?Ou&@k^2HR3)jYDe3oLI*BuhZqKd6 z)_ZDCY2TBn>&XB0dPf?!zbRv@82Zm~Rj?MjSNsL~G*ox>m@W&f#SQTPcj!fgKjP`M z(0>bI-C=VjpG4S)HNopw)Yi*Giig~K&58kT8rDM?Nb6j23D{EnhE@L0VL!JU;e-0V zm3vvIeyK=cuF5lEli$t#e*B}h)6bi*dHXxT1K-mkm!H1go=kj`xl?%eFZ$xod-+lR zulmzo=xpl#^uMS)neeq)XW)f4Azb+LrhqsaLVcN?fFe@gasdF520pF%;h<Z2TLyhv z5XepWl`dPSGq&!s@XH7E{achFEL&a8^wZwn=ZP9DAEDIM^dpWQm-iG~`2KW}V$b^a z#8=nkyMJWw{n-}IiuTsrH7lNw`G?o-4J(_#grPKCQTBg6?gAj<Jdpv2n<&i^nG9|? z2ICh`1lV8z;noO40Z2MpGXf&!vSeK%?@%jQr71%yQ$O|~PVDBsG%ZE%mvBesQRb0S z)8v10Hi2X~LoM$CakqYCS{#Vhlb;R36%?D<quD-?FE0o{R_Wfj{@RN!f1Xo6c5gFZ z<8aB_U2wf6*M4v-Inu}cGv8gXcO#&t)iuwMCq_(mk#O9AxHUm;XP!w)=LTsd!E{KB z0w|PUiHf6xAUqJb*8NRK0F2cRS(EVnxmK$cbq8|yn*xxe%J;89%Flpyk;QZ9fPoqY zZ+LuZSvcFg?QM(VREhjak0|Tgv-caINXp*MhFM3>(_${7A7hQzw!**b;ob_sET6mZ z-#j07@Asu(gchibFFTDP=^BZ9h`Y&RjN*i>bw>BanO)=z4b|*hfC4(KC!62;K!gTH z!eCqwB$Eb4P*F5t?ZhYpu~5qALlVgi+E!8)I(b?^UQTE0J?>SIS!=TpY^<2EgHZi4 zO~@Tv=hnGl+ulK7{3jNoM802~19@isd%2CS@)x&gr+MFLQB@Ah?V|w|TGGQC=JW3X z+OHMtV7i&OMSc*;Rj36(fS3$j5yA8oPEO#Qwu=qEf9enrU8DC*%x<MyiT=9hXoGG8 z<EZSf*Q%!ndI!I>Uf=BSD>PMozsk<S`b^fP3m-7faoU$4OzYBdJ>~z3_P(5aVpMVc z)-yr4trMHusv01e{qa-MWniEHoxIOmo#h;D&X}4+SeQ7to(*lEaj}1ye#er5q1xk& z`4WWyr_ET~2lx-|DlfcmY%6!t1+WHQyGebw)A_QPtJd0Ok~Y?ObNO(${Gzv>a`mv? zS^p42eJ3VFB(24t-lm@Q@dKo-0~duKpYT0>OwHQDnvbC8fAzdxLEmDALchUcilxsX zw2_5wt6nl(H-eVkc=mw`A9mDsSIHyZOfq^lmRojLptrxIcJQRN9`AIY(!No~%8jCu z24CC(;6>szfXO}AZF5+5bh+4#Kir&QU~3ff`n9`F%)_H938^K?dsE?k?^FM$=&Ylf z`u{&Z7#mBxqf<wRfTK%vbmJ(c9i_CCN*DvSG1Aek1Cd5aDbdj=;V7jA1O-IDsHk9k z`0@Myo^#KA-}gE1_v>|@ugAkOgf5lQ6;z|1r2FzPM{#!KwB*X~uNRKYyfg5$4GzY{ zT=siM#xsipV&Xv5&9SBcctqGHCsq-zmad81zw%%}4CX;AxTOC(K`{UM?}X<uPn+UD zL@l4GKm>L_w%eA>sy)!XX&Lw<-S@%wyS*s>=TG7a*#4u_2H(}B&d&%)9sO3b7+E!@ z$IUl5#Ego0^TN(%S`*m^Bwtc2r_^#9M`G9w;_<FvZY*{pw$=^)e&t8+iBJZ|jb?}E ze-pC0ckh{(r@nq``Q!c%i-yZLzY6~)Yw%T#>;++8mfUvrmtpK}M*QBnhgjyt(iN*n zH$`Cgzg6HN-grNhD2(GoL_@yNHSCFS*f$O*;ZDF7yA=y-S7+xqQp;+L)r#=hPvbeE z0$NQ851J^}g_fqpXXvVu-@O>QVPyDiPx;*bdo)H~K@AgbW|_8#Feq1KTR=;^HXMWU zI+&bh$42uUh=FP$2AM>eD~k(bf-mJnk(y^Rp76plmLQ|U>8y+=NW#hU5M~zsk@Z8> z2dFqfQLmK?cQ1F}8{+P4noZugdtM=ViO?rsiI$3UoZ*2A@9X6^pd_-`ER2M?vm7%p z0jJCT_Jxy*haNeEOBxG-Y+<q=HonS%Rm$-T{9;`N_X=o^ZXU56IaPa2XUwEV?*48! z?le%n5s@HfU`f}a``gF0?^npSZ!<#KNzranepGf10MT_cU7>?mn6&+^_Wr<>?F8$? z3W(4g*EVtgp9SK;x-TbT3UW88f@@w_-ncvu9&%0$*0evIb35UJJY39z8}mEca$)p_ z#CEaR|NPlFZ#d<MQwrOp<XRHsu06V1nxiyXt7|)JqhnfgHFE!lekZQ&jODDXLv;1@ zv#r^}z$saa``d&Egl1BUWU>jouV58Ut}EZ&0UJeFK9GA-5i}SaHdEwc^W&jtYOXvR zXTg)RAF>OPe7Tn?4_z~HvyXqf@&uO3zkC4Xg*s^vc`eop^tcD=`bF-WNov~`%Hz|Q zh0R5Dx|imH^E!_SkKX4R)%%TS&V)<vHW9md|8!_-AFT|YAfjWrr`fm6tj9usJ-sP= zmTlF=#n1Yh#y9*byOxwd`LPw_#{9>hmpuQoarapcvZ#Z8upw_c8!BBj*3h`_yu7LG z_zkWg>H0-#+i&^uiZL(W8^@mJVt4cATDvT5Txvg9-kiBbKYt7gxdI7G^DD9C(vgc6 zDNvq9RIklnjPAAlbZUvAwn5n3tO*Rvj#i<*{vTV+Wy^uaD%WAJrRTP--)78z{^oX1 zH>Vk@J_J$+$Gkz<Cu-Wo;YG73E4KG@S=akQa?6r)9{%mHaZuu?f8XuF4qtg?b4%_Q zp4&VA7L)ZX^&>u3#FB1pF3y**??=<S5(-a|&~rPAtkn3|Vx7ZuBaVmc){FXmH0P^o zZE6fIo45Yo_P4&b%Q$K$=VVsSZjXQ;V66L_2PrS5c3QK=6xS2rEud$wYcbWx6FK{+ zp}iK($3Pr{rEdLvJp;eLXQ;%<yc)Q{eD}1<wBX<(SKL@5WirGBlC?#LX&btq%OI;y z1*r;1%>ipqntt?L6Z-r?Rs3^lXkA@>64#a119tA5KUsU%o-8bC{hN#zyR)2}M1CV& z^TCO;*&@9$&aXRkpWkeXu5#7XPSWH{<6%!k-sq#!Hwq)^;@sZaC;VF*QakFd@`Pq> zaX$_l)CrLd2>apMcH`-EbKZ&RY>zmhnHSH;3XV9-hyH!&-n=xd8&W&i94#DMY30LT za^iG>vyYax?lp<Fn0hbfUum3^hN3Z2uABY3yRu@U7NJ%80|&XuE$`y}S1sqF`;s`! zDp+lDe7?>8Le=vZp)Ms$j}7<jV`eLIeNTR}2oK2m*RbzsOZ>9=rhIYSmTdcLUA&y_ z@Xpz<5;4cq$%Eb-kESFj!?(ZKWlfRgR(^4Wr<KWSz5cO)EN74XGyXcx)Bns-L-4T9 zhYRe2maf-#%QTaR-!6X{o@mE<D#QJ3&RutU%st*^cK7$~DI3&)Lqu%<H?O)2VLA^v z4u2$#gnTk>Z!BgwNKI=e5OkHM&*jkT-=zYH1xIvPdEt8tlEJo6ufq$t=(FMxNT6No z5KMcJpc_+O=?7N_thqi#Xx_u1iq)QX=(VqZI)9|sH890wcRxQj`s7b@d*L>)vBS^b zN#ieLo~ppd93VvZWric_fAZj$yTk&2<GVh=50UD2r)is5xJ*g)qs~&Pr4FSTT5NcG zW;BTBk4$Fw6XCzv=gYcYNXqk13T?9YX(^t)o7khQUdXanOkfp1E0am@ILE$z{z|4H zt<i8j@x1hah*4agn;w06{+zyeQ#MFr&xg5Q-V>p4J}V+!b4Eye!+6;W^ud6J<4ykQ zhSmS7Yy7O#aiCaVD*3<f_@9P73CvRCsG~DB&4VV!LPBYsXG-cDx#8gwebq=wl>`;9 z=>g5%0bkK)A%ukY1w!_L^#Q#ytJ4+Rh69DorH-Po{^(wVipsT7?XywOM&`wq4b&Bc zO}+#bN{Dt|-j|3=?OJe<j*!psF*b!e4&BO8i4}wqn0bdgmFf2Ske3yKimlsSVr0?Q zC!>Azy{?22F*i|_U{|{Bx{0Ez89^<%>9}zahj&^(W8O4uHaVQ7u4!$Tm~R0K`&NzH ztqt+UN>!MDmN&D>QZ{~O`m4{vc!S9`pz(l+db22JDnd)Wg`%*`vq7RJorNmRT_r*m zTIw%r9Myai(KwFBBd_FE!vR}~qrm_&e+tKF&$h_2e6p>=t1?HchqvhTu&&I4LgFs{ zy~HuS?0js!nQs*4R>iC51Bxr7+VhD*Bh^n<5hq0wUzRzx9$2=nV65~fP15HoO(GQw z(iBzBs{AQOJ4ncOsaMTu4|VU4PL`<LpUb<8I?XEr``u@qZaMb0gulSr3fWk`uy2_5 z7e3}&I2!d*u?RhpW5q1A+LSkC&5XuMjc<&#zULn6b!3k0)s9ACMZn2zIW|wFl84xJ zl#zpd?iLBvy)i1VRbKe(vCL}6iT&L(D}Tx<2NLTkDAm6*`7@R;TWxnabg~5>Dc3zo zgqbJ{E9XWrRTohq^0w7~kCLmGjDPqNG`{CO54w=CU;S#e{CAi2$ZzfK;PD4?V->fA z5SggVKdO8p7Y;<>YrHg08#^x~S0CKwc`!@xdX*xGS3nJ(w~@Vy82sPE*S{SF5R_JP z5xdU4u}bx-8A4{2ak7o5h0t~T54s6!SnK~;Gk<d{uYF@><1G(GJF&NEAI1Q1TPyEB z>yy6yDUDX|jbF?9O^=mBJ9c|+mT0{K$pg7S-bNd2ehU5>IWMV$>w3bkH{NB9hMk?( zw4ai0Gn)*aHhm;rCrSfF<CP$eL5Iy)>9M`mwCmzJUWz(}+uhl5DuQb0lkPKX(K+v< zW}G}u>oc`-aCUI+qp9ex8pL4R>hCkSK$Wg~hJ(p0>+f-u_$DgBaR`fvkeG}qRKFbc z@N!+xy^`U@PeN)vts4tgf)E5z>`jP%-74lRuadM{y_1FHTcpa{aQ(OAC8JmW>Cr3R z1Zlv7Kf@upmZ5EzoLxCU1+<w)tFX4obX11rtloIROa^W`(Poz1c5&mc)4n?^j^cbX zkeyDrPyEx?6Dit>DzV}%vDbHuRmx9-z@7Z;1VW~0Ci5+?pqW_SiB%^i#!(34>}Ys0 zUCg0Ze&`;=C8=k)6zxK{nP*5}jAua&Z_k0H;To!Hq2VsSqF!6NyIu&n@UP3bPR-@P zpwNTa1(V#POJzS?9~^R8_fnhtgu2zy#X79GIy=v{_N#oesv@v;McbCrw+(G>-5zs2 ze;0b3s^VA8;tM#0<j*sWTvhpa{d<IRrh5l9+_TK5gO*)KdKR-kyFPDQ+Uae%uRV7& zeNpA}((4Lz@ZiEm`K6a3Q?WfuGa5CT1?idlbGP32F6yaeGv3fQM&qOeF88S07`MD~ zT7H*%(hCQkXI;#doX-xk%VNFBOuuBkDD)1pvX%bOrGR@p*JA>b{8qzxp^cXKd1c{; z=YO$F8YPTNVwbl~-nC6RZ|lrX*}VHjdAIz-36lQqx6^s^w)-zBo_{vq(e#%CKfeRn zp8q*^Ig^ircoP8wi63%6d_f@4@ywnJNQV6_8whp;VuOjAH!^w?VLS@%BaLPKNr0qf ziFs4GNh(X#b7`dM;qX1IQHrQVbH&SSIfvT%j$o{M{P@LJB^E7}<Hg#MJ4>Ca3#0i{ zweWN(Uh?%r^K1o=SFJVE_ZOS(z}U|PSpDo2;oGm;>fSyf_NP$HLw0%tFGa?5w>`>{ z(=2}`c3Su8<K^z??>lIDn<8d2t9sCDBV@EOIMh<QvNHJ7$}nBh>VAFe|9bORsAx^c z6xX(~!tv)7)?KaJ)77%}qo&Hm228`IrXr{D!q+n$k)Kv<iWaoouU`q!^XJEF1{)_M zax{MvM-yJhSUs@q`8^Ui<bs|W_#pU{`l@E?$V70u>+t*5^m)ZkO13rj*DT||r<Qs} zCyYZ(FTH;8;%Iv=`hB{1c#I^Sz`gnFT>?r|`^`;^&5v=dD{!X=hQIh6SMYyyw$_rc z<*jIgxwHd-{KF|)9OTD$l|U6Al6#*fQ7A{(TosiZ594++Uov<luT_+w&L6Om2~F2t zqRsiMrODiG6d%`|!;b)D1<j3o10#v;&3sR;kLXj6qQ4K}RvdjE83sMCq^Gh&;2%n& z5~{~b*;l59`P&P8yo)hT?_CVSBH*C3>oT>~F_NazEX`Gt<mAmjRmZIe!;@WGl_jnp zi^65D`1qKdwm0^zs;=Cb)m+N~PiVel9@Ww{(^p<f8pHS<6^yHDcRoEaPxsGI8}@xa zUX2Vf`t%Sy537D0dPfM}ICGz$OMBtg_xmEDjgmWB+{s;&k1;=9Ew;{9>bYpI-Fld= zwHv&KmV8w39^KKDFiLM&m#|uI0eb{WN$v0}+CP`sakJNEr$}Pk+oO@7ZuYfL^oAie zS7|2n=5CWA4>hWx4`yS|rS}stQai}M{KrPKU+g2$2@UCFQMur1Z->ton?;y?E;6zm z#P;iock^CQM;R_gM}8^>vE1q7h&5}L%Bx*#`h@;Xo8{LcCV^ZktOD>)1D=!P%A-6@ zs&qXNqxpWSBafq&@u(b_w8AcS^uGNqN%9b_4bJN`)7UVNeQIE?W<9AlUg>iW{~flU z5r5%K)Gy=FsK=*3k%vmZRopp4W78H3B1ca?iWbLCil5>Q=pXxC$I_hh`d)MV2aT<b zi-%*jLf(hW9ey3YTKZ$_PQI;>R7Qz%kJ(0WOR9{#EEjY41e)t{JVIPDpxQd6*5)xc z<kU)tu*Umy2KQy}X?!1lEj{MTy71)4WMltYhR){JDFZ2K`Fr>sy9{AkQ1hDbqO@^f zfojg56;4u~=(TGx#i#z2$O>&?g70GMX&|IMlcJp=Va-nZ5>?fgga^zg_bg0h4xVpC z*$N4{pWHG|D%zs#C833ifFn#_;~<*j7T2L8JMvp8ciWyKUve3$%)sctV~=_pS&G+& z4Jd!1dJ%I*;1KqE$30CaVkD8l#bMAjh?5Lce??8JYOnu1l;k<~-hi4%Z_`l@aEu?; z2H|wBurY6JES4JZ9^wsbl*Fg#-lDSAbkV?&)cl!;GOu~Mj~@_ZXS+NNO)$MXXq}Gi z&7hoh5d8r^lYvWqWN?<VE77+Z%j`&%JlFBkQ*(nXtw@XKGUv85v5`~ab~aoU<f+4O zB#jn4P_oKCPZ90QpSwk?7nD#io!Bi%2%IzoW&u%!CwbsCZ-azm@TjOSzvtIA2@r`E z9H?5*ytpECYU*fQ!xdJzKET3{6w<jo21=oY5areFoEU`f@j%yr#^;wcVITmsxiz9C z`j#s`$0wXF@u9w)n-3cM9oyf;ttzyh-`zXH;PLusaK{U9hZ&b4Afp-(13TN?e$nSI z{mlo&fm{3>7bR7_kCS9mlxLD+6U2v-xrKDWiDoHvC7KNzX}Zz6wJL>uSZl5+X&~As zP0YZ%8OQ@%uV>fDO1~5li<n5LcBteyq<97e3K(1O*AXGvCMFn!T1>y_sh4uU__Llm z%WpJ<Z3==~Gc));r_^#Z1sZ+3f$6!Di*-ZS`%Btq#O1!{55<nTs35pog{4BwHOk$r z7G{=@<W<Fn%#*YgQ?o?RZQOw#?&1wa@?v#!svbhJb>@1xqL+hYR)Xs7Ef8-nlt%Hb zlXgsDDZo2TV?n0ah$lwZ-5n56Of8U$$PTJV%e#nQJ)LyRiMs|a6e5ytIKnO@^fqaK zP<2!urc)|U?-G`Jwrw0{5TQbMCu>&iriU4R_~iM<+p*esm*)Jadpwags*MWf0V`>x zL^%iQfF=lcU}?bf`5#OW0QD3ZTU|4S0^Fwd6l8+exmaIAk<j2i{^oa_>{z}57tED2 z>+21@f*`d}oIjj>P1G%>Pw*t|9^4x}qVz_*B|Ee}3xT;N0nQci`g+si*Tyr%+oPdN z8Q)D+5htR3d7D6jYeoYI(oo(Z_T901I!q7Pw;(eDZD|SZg6;{pg5Hn0EfsvKhHdPi z*Z+{5I_{t7wld@jj;~j8xpV-0&mKYZeW)3Ksna*Z*r`h^5r9=S*A0B&bjOEQvnz}A zKtYY$;9S}p_xcu-;f_fp6kp+m4mv~-;+7jt<-V6(_0ZyQZwfhGosUpD8SW!;-7SKY zs02iY!=i5dRc>Y@u`a3oSw1<~_~=aOM|Rh4@p+jAJCmNwRk-skw0B_^Up3()ura<# zY41a-jv!Bbek*41MqW%}KE8EEBKfIb@2U0GV&$kc<Zxr9#_cTA+tK!%N1Yw`QICma zK|S$NsE(%JKcMw@M>r`>`-!A|_}v%g28tI~l!Ov45$Ts+sS1ST1=$*xT-&(%YT<@L z?(dN#P|qNHzWL+{`}Y-bx4n7#JEvdNXGNU_gSMTg9aTPkkN5p6(OD8<bMEU8+sP#f zZ?lD;)px|=amPFfamz)&!^JX5sV^_@TgdQV{<Xd7@xNOc9o!D`^dP|jR=hx%F)`&O z1$**qMxLGpz6tI)qQq0|f3{RL_E$3L>sKBT_W?*mgsJOG-faCVWpIg5lF_gP<Fa|K zks-o9jGZ?~J5kcS?DzDxewvQZq=I$uyu+FA;!v62M&4YcOJNlUW2Xj>PR}u^TG%yA zS);LR(Y3A;HI8+3Q)o4(U_+|A*e9DWi=$}nUs{px{)kM%8<;RRCODJ<2@XRBGa%(e z_|8@M?pv!v!@xCm@79}=Qj?-3TEM)34|Vu%SrvEb9>SF=6b^8@twKCkVcVSXm^rH^ z$`z{mU4(BOkDXT46gRK20gTP_Hdwbe3}xUS)(xO~8<FM(<Zcqu>cDnyfB^Y=Y_tX* z6Jf46SOkl|hyiD?;K~OH*>4<&>;fe)C&M;w<m8wzjEu(VTCW(WK?Z7ofm*^Q4TdER z;!!aLNdv5;J99~WbR-jm>SZCjn26d{%}^u2K@NC)!~}+95q1)sxd0*)hbRG2k+OF= zzTW(~iuz9mCnO=oqKki#G+8%r9N0rt;}H*tvA6c1p-j$DBIN0aQtKA9xjJ>p8)89( zcrsFNF`-37cm@$(!a{)dk~$fL`n@#B8sZ)dQ~@An=29S&@X91aDGUC9o?KKACCkTa zmm@v_9D_^H>kQO74*3{|ta}gj+=E`jao!GtUS)7zXL9a;JNe(iJ<#^OWN~^r6B@*X zTw!p!0h~|G?-k?V3+AW>JZev!QpUUmVj&vjw4j->ApFfWxeQ5D;G<e}ycw?w#)*aH zTF0VV!cd9$RM}`~P$Or_+P(fG0{XUr$u(ybXf^x1JTM6IG;%>PS!tbndhD4wtB=%% z8<C6OPI@*%Js1#IM#8ZmdD$ElF^wp1<aFDE3JPWIJ~|_I5!0<E(Rn@bqRFwO7ClHp zmE%(*n9wk$?tj{+MzQGY6<RjiiF&PC<=^vFE0KM~0;&$s#Xz>O3XV@B_TJnUJgSq9 zTwI4z8zJs2==V9!T7WZ{AsA){_#9?p;h;hgs9=xcE3fbS784Y4gY7+F{FQs1gudpl zZD)8VC0?fIq1LB@(3GcYcO!$DkC43}RB8<}ciVql$FG)EP``?(Cn4@=XLe%|ONMuJ zaU9n`MeQtv@DUueDhHg@0cw)r4RFI-zc6nE&@))B`{AfG;_-fiF4@c24Q5Sp@C0aw zU5Y&KTA^WM;h@@9;K2!c{n81df^6w^dQ3uG@Q)qU&TJqcj`fsS90VrF$sUh*1;f;L z-ango;qWPDn;3dvfS$v0E#gp#0Bj>)uzeN1<BV4RfYOD5&T0dvv@xhkq?J5y>X$88 z1<9R)SgER*hJhYq@4xL=GQ>fG0odShdMV-lmPPrSujiwG@_v@btg51ODJZ#hp*(}r z6Iet#1LEg|=x0f-ucG8F1Xy@0Ctpl7pP!Md13?a0`Bk;7Rej15i0Dtp?&MNep%zCt zNEj2E$jDqSD5};ecP|pY`Lp0L>FW6(4wiQKJz30LCYOz_M%P31FafTHsLK8!Cgdfu zE{;|yE5B9^oJaUU#VcTT6<{{f1;KRD7+@?3!Jt<cF*!Yn5C<%0I)G?syrW!joHzsM zIHm5WntNXzHi%r{0Bl1(Plli5)d0+oaP$I>&u>y{F$`6~;5;mp0m@yd&E6AIQJk7l zYC~0K`3&eJO-q^rwyO;{LWt-96)gB5C!zs|_|^e2B5=})w?HK2JY2(^rSQLgu3^H% zaF#nb+)fXZi1o7Oza+87Kr!~9t<DIW1hie7wb8mDR66SLW4znZ_Xt=LkPr)i^nl(# zU{C=Vlm$F!)n$#G&krCeICupeo(aHRdaVSC8`wCwc1f<GtM2b~g*pu@w;R!;03wX3 zG!k~kUPbuT%()izmhTQNf3$#Gmd6r3+o`Pzatbg912OQe9N~@2bMQiZV<{okkO?KN zQb0^Ad%d=pc;`KCu5rjY(EcOOrpO){UdeA<>v+_NrOdAcu{)X8y;rDX`*9O?MBZN8 z-YUT9C%J-EFs)6w=iDBi2ncqzm$E212+;Bzf(me&H$twHl9SzlXtG(F9)E+@HFg6o zwhG?7KhEGxu5BV>nyCa?M>qZ!aN6XCNMl5f1Uzf?0JD6;D^s8wI2Ln4rsr=rry^{M z+QCij98K+276330Us{8hv!K-h&tBFE<XCmWo7yB2>}O{6ZKpWRSD_#*wuc8Tz<oAz zqvxzH_qma(PGg52!gEJc;4vLZrIRj3Bg4TYj6x%#sr{o1P@@CCPz*Oq<uC_vW|QDs z$5|awej_6$*z3d+4h=24sv(}J9vxq$z*P=#R_#GQGP!0}QGRRYErl@<11YsdZkJ); zt`5K$?md|XJi#HCFsM=nM5ew18(hs{)rd!el+ucJT!73~SSf&rKbFQ4?`4yoakce( zsa%HiaxD=6qn0Qu%%yinWs2(rgsd~-ClU1#`v4{$nz06mnClkK<RHSMmOfTghato1 z92PiOcNp+>ai~|fH5NIH`bwGPL8Jqm7v<rZtAxpH80jzH#4%gvVR^5rTgol-btWtk zqXP9t@p5Y<+VjhLJ=uX`9*jB7AD--Pq_KUXQ4p=|RzOY{ygLp!G=k^uLG?hK=^!{6 zq@PT<(48jmbG6^wPGW&DmdJK_0wg{<X89%`xb{n@&9McBY3INUd0el+E+JZ0pFo>3 zAI*=$GT}Ril*<PO8I7=_Mo#r5Xcm1mWpCm_Z!B!m{o7x@cVE$St0T3W=n>$-gD9>9 z>SM>hz`)V>*KAiW1^@K+yan_ypX?3Pp?>$GJZiuF8G@?}!@suP!^0lZCyf}8>j3-? zWXiM5`4@HoEPk0b#+yP$e`y{#{jb@<r*g>+qZv{sVg}UJG0e5vv43g*vzmDn1AOf4 z-mU?*zQL@PXM%AYM)VE}W7P38-y7!fZam{wI^t7pm?Qm)x~DtBa_j+vmWko@#>Had zECdFnnpXm1AcK|}Tx++jYWvPDwu8f8tOUc?ZUOi3xY+R-4sDKO%`KS@OToetaCX|7 zb7#dPPMU<cPvRAFxcUK@ulJc*oWv~AV>b21emIt&Q|i+04bjYL^xEAorhX5`SdgPN zR<GrY2GL3LabUO(c8|&FhUG|Kg^@uZ%Ie}-6|Oxjl6?&s9gilraK1#JQ;ZteQkZ_P zsR6#itvUpBG%h3k9Q2Tw)pQ_S5oov#=-g`H2#2MxV1Gv^NqZ~bN_no{Jn=B>M9#AN zV?$=L4cAIz)GvPS11IzXfvXpr`m-DzFXK=7fRZMol@r9)HBT1j19Rg*-{#AHjayQf zwWDre%l;Y18Y~45BNJh9jbQWDm6QLiX{m6bZ^mbNpRla)Yo=aI_K+N1x0?b|XGzXk z8i7M9(@rH3{MIKSZG$?~fCj%SYGoM+@7}k%X}JQNa<l=j896_O8y*ok;;@_KMo(8| zp4@()6D3>}#g`|7z0A&XvCXWD$D=oxFjs=i%HI2qOCnFg<)04&tx*8PjCH#xEFyJ7 zRD1>1R0J>UKj8;_`U^F}a%M0%UH;pWS@Qw!2E**8z-!2lM6T^s1&Q_9l}65REcOw% zKLq1+FdoO{l_e0|RrD_rsp69meIEYb@dWv&8$k>28eRdRK-$$$;CN-5$H12oSTc6= zMK^mm9(Enr?NjFA5VbySYq;uzeiO#^6N_DC=u2Vv<_KJUEdH7MmI4WJGjHQ+9s}?0 zzv;+v+7&)N`3VDUs~?^Zu_0faj{{o2yy8?@`)=D1y+6!;v^D`E{ZE$&jc0Ji?)^_K zd`_w=AlXRUaKm-t=?CNqu2?N@JIwnXF_rK@AZYyq*g*W8#7U9Nmwnq0Mb7}cQRG1! zvS~!gYOa@YorT)G9cIJLW4neChuPm>yBNdAX~%i?f0)2WvwiwNhEe2`w+b<rBo&Oc zH?_W6w*nr@ay)5(<9F_j)}6|_aH_0>X*HvBPb!!s6AW;+@BMfk;|Y@MhJK};|HKmi z`YnU>3~q32o2DF#tFJeH2OIo?i*vGzbA}OqJ-*81WQ$wmspZ4GA7%0XG?cht3_P+w zb+$a4C-dt!$qmtbWP2krm<gjPBZ|)>J>ITLlr6X&r2rlO0ZG`++bqsI|30yc|3Mi1 z0WtpTIB{hKKY*G1g+7u?TZLeJDy_&sCm56+@)u->X5v9J2w|xL!kQr!l%oW0w4PV- zL*LUtRqhFp+&k|qtMXRys(5$BvK3H*E*j+>hmeAWlCe@|D2((omueQ?kc<kza97)w z#>cw85~A^bu&=Z!Jx39C+HtIPYUtXBJ{BcKY>Zf-1-|U`h0Kfg1)0f~wtKx3_V#hM z2{pV5s;~%o)4D!D5%7YJ!cc<4?!6ge$T!IRzFdyWn5fMTd3h>BFw|8ck|Al%5!AH{ z$6t70=-LWM=wAF0_@=?*1@)h6koFVDqu%%+kMWZvhpL(D->=+Ygn_~e5x0btT>GD0 z{HKhPQS@5vg@=2zpKA;s9cjvsxFPHsRf;zp*|qrW@h|r0=jHBq3qN|M1Lx-glHZ3g z{tF&RR~vxptXCU^GP+&k<jU)6!K)QiM|+FrU#h)ih6RWfEN>htyhW#Qtkq<kW1oyq zKeRPgG2y%9xOJLeXaNdZS||FROjy{tP<F(t0FXjqx?zk>-mcRl;>B4b;wg%*=DO6{ zKZCvGh?iXX!=5qLWnZ`r{WPq&i=>QDJUhW^l+bSgNu3SgFg66?mAH<@wH1$aJO|V+ z=>L-PKRp+ks$d%2`t?eZ+Z@~Kk=V7^F=(-vOP^^;JW%^V6jb6XXa1|AKL<<HjD_oc zIgTyyjym_DNC?iZy*{$~!<sP)zg;#%!$8WvT7Qlu&Xt$5uIB8O)RR)u$o*TUZoxg$ z%5>>|AGIWqE;lHW_{@OXv6kXijSncX;8d`wv9FY%WNha!wu)SLHD1YqR~_>&di=1; z)BY2DkxP%G$p-%)rKMk-8lCN&c*3-xHY&}|U(@IN(iN7Wl^3T_$Zs{INDDbKhjCmm z5X7(2W3KXs)F#j#<#4KMiAR-XD?G~K@8Sk2wx^-^E_J!nc<=N5<{&v9<4HX8eM_Cn zG$DuW+wPxm#+(|zJJgQ6>Yfb6mfZxg&WJB~M}BfCXq_A?(Xv#jDr)w=H7Xr|7`U<# zKg7n&xjA&ZMu)oZS?EW>Y1CWnL<w2v%j*RSJaXZG%Vjlu>gHhXr5h_kB;~vR34x-O zT6VK-sQkKRXOu8J{i>Nz>}3$Y3rD6AmrK!hCEJ_abiSW-pNv`_drL0uX6U&Cfzio8 ztk0<-9+Aj{xrg2z5;C@nW_8=q$L*JsW+LGw+jgSidyi9|<S8puE_oB7s{%jbyk0zv zkLdiOTPRR<^tD)W_(6o@&yNpyAN=EF)Zo9u+3#?vJ&=UST$}}5CM%>xV#Rj<YIN&v zrU0&3!A5es0oQZbk(PH5TKoB=qJM58hPp?+^WU^wh{~q#@*Gtiuop-WG!~9dG(B*A zN_RtfpLhgf9;&jF#B0x3?tX&g0s=1%XJ6mR9zFHnLHmoNGIml02*Ph;f`2Wv7g;Ds zlOBM9E;VsnhX*Ww@|M-B`Zp@ak;w!4&FJNNGnpaBof_ml@U%((0#7(`7{~vuI@Io- zcosV-!q*=gh^-LUk-Bs_p*l@#uNUoEK*6c93-$_PlEv7h|E^bY|5o~vOh~id01-O> z3z$f`G_wxs-Ws$an8!anEosD@&VpIe6Kvuho}@K%Dp`A-c+u^nn%gNH31W)2zVwMJ z+RO`~)3KN%$sB(B5v3zwO5UV-v;wuC<F}t~ao6arSJWiTx4?(1sDpw_VM`<4dX@bd zxhZ$Gved<0UNs}NeDkTVPQvr4yX-mAN-zAatZ9?n*&TFi3A-*TOF=xa1PkFY%$eLz z$r$AbFfX2Ji(i70R|5D?36!UYMEf9TT^$Fwrwl`W(4<G3*3j1kb0aj3C3s^pMxhdE zJ}eq0956YXYIh;-@sr#C12g4#^684`jXSk7E+1lV5ZL(lQlVpHC9&TuoDJ_qa5&b$ zxxFiX_w<eH>;?W2CIB8p0m97h#WrK@pYPNZf@qcZMK{r=sB&+xU5%luf6q=px<;%6 z?dU+N&^CtuA#a|di5g8DWpl$`K*sBoRb}8TCCV(fP89aKx}bABBs>qwfp-?!A<&9u z>*>tT$`0)pQw?$A9TK#YD=?BSOdvy7FeUEi!le(7X`)iI*^Cjp6#ZbHrWFpByK}id zwk%DWhwY33myyc^!bpNeH&xLdb?mJ;kt|!5WoYatomX-Lo9i(0dKIG1PF0SoDN?F? z73j7!^a`U9&hd$N=_17uC*Hs5Z~q$yQQBt%ow_|9QQYmt^@98ed`LB)G6i<u@G9R^ z9YNHwTY%K7gwA|$OMt3+3g_oLlsG+!TBt)3l>A!%1=9jrED3qcRNj9OrY!RaHWaTu zV+d{vkwTO#f-kxBHbi<fK-pod3jtgMC5ER~8@svk=f}QJLN({Y4R64FMS>+ayoILB zGfg1P7?mo+EOm_Vy|+V~rChR{Q$G14yV5^HM(+GNeWuDd%9_WdF23Q`Cc36(R0&gQ z_W_%9uF(J{BdlgXkGW!>U!;-P1rf3LpN=PLWk#CX>Q)-032RCVp9!^iC)JmK?lQSr z^S?zvLqfXNG1m$)f6cJ5fX-0yjYno~xdf;NSpHHK=elAZtJ#p`$ws{S@X85ZYyD8Y z(8S<*=abeUJ3CdPuv?0q-|^VRw1_Xl)we(Fnj{nf){~Je@&uRF(-!F?pZ5YXX*ZI4 zoY_zB5!`wKM@dkl2XEez#fi!qF!g0mct-n%@4R`7R%ltWNkILq)cur4+!FmJ_7I65 zcg#CumC^*x_`EyT5D*1tu-=y`5r@*Wav`)X<?J7;PSNQr=dzz98Qls9_j@%+p?}S| zw7jFFqSa*;p6bMtwTu*}8=(4dAw6;OKZYWEZlXPJpO>AtQCYGV_6Z*GPZoDY$7U7l z^HF6hWP%{1=?CY!gLx_f?O)VYKY4zT@xRRAm92i9<(&xb^E;nLFi9#iYf3HM#-AUY zx!UP_AMoExz)n}2cg;Kk?txZYzKOxePp5&d>=bO=B^brg1fZNgGQP;EnQgMTqnmbx zmw3(ECNSY8Res~Tc!=PLaAhB4=+e8u56=a?&|fb-Y2O=o{3b`AZqQ%zOmtuMqgu~R z7%A$nT+)v8$l1t=*o^(?R=W`E?km@37rKpK{2A0wfYr^}GjK&ICfXctw*@qd#NG?j z)`e+0a^Q7#kY^b)9@JiY!2anyv;L5}6RRP{22>N9zNL1?#;N!_Q;Slmmk-3f7?1!g z#7Z0Pf~PX<A+8{j=tjG&#VG}Gs8Nt;aam!tvu00FGCN8#4wDU?Qd)B>y<Jv!nOm7t zl%|hM5C_;NX^DJ9u;zi7HcPvDj>)CopV$k{tW!2J)H(X!cfpG-_v7(YihpOmbKxe5 z>W_!|9{2iIjn2(Locsmc0f@LZMVkca3gD!WI1`))Zuk#S=T3FU(F^A@6osnu_JpV~ zCM8-kp|K$!^o(N8)4^V;!25WH2v)+8m0)Vf8L;*Ueo(Sst#y!?EU2NzVY){RAsL-4 zdzMG+w+^65u4#D?o`g3-LC(h1f<!Y`f>Ht0)BO02$;ViW7y@UsGo;f{=DjM#mjDYQ zQli;N5sD3tT~F>el|RVLXNc?O3*yYbr?n>Z<yAAF^?hZ6h~qEUW+j|CFchoCg9=PQ zr03OgMhUD&x2Ta{0B_(P^xSIKP*%&)rJ#CkclmIMp09Q^-!QT+h-0k<LnToI&D%14 z$ZiEqC#8-HAPQx~z#}ZHA6s7Rd+fdhYY-9k_~CeS&HFKWc`SW!iCL_*SY@}_qq4f= z<Knhx${CIn)#}sY)r`cF=See`d>CHC`Gm)kG=6TFk!r?KHM9v?MILF%CnaT-B$*%P zc@-EXgi(FAioFG)b~Lb2N89(9<R}dESNN&V#N-0Uaw--~#F$+cq!oz5Y?*oqv|*}t zmt1!91n7CZ;2@Vc%-ySqQq6GWt<<RoFBd-41*PcXWmK$bWDd~w;;Xr{f(C3P`_;jh z@AJqk<!cH34FSmsW&KB82S%=QZTX93DaRhraM-4l!q>noci0&7Yzd{~d<M2bG2A*q zZg^e|s=NBKiwzVsQZ9yqB&?EOZs>y=1!%Pma;LM$+{NUAOD9BWuX8#oZ{gQe6XbF1 z`t-!5&JJ;cP2vppE!n2Z*_@g)4!Mo)z;T*lJ5PS?!bDZn`9t~0R1^j3$7p}XY<nT4 z@B*-Vlg+h7p7=H2Ie4Hl6it~grbPVhBoishWvH9Sl?Mat7ngkO#Q7<O8#9(nSfwj= z=R&(Lcx64*6l6cQ*E*F04oyw0JrqOf5h@Q7I3T3cSeQJKrQC)vn}<f?$o2=+C#gts zHH(6S9tDqSpgpMQWmdie5IL`rFKAct9%h|<=93idPu;|PUC)=j2Mixdfg{A$KiR2~ z<H*2q((ZyP`ygQ#<+7&aDrB!&b|D|YX!^%{xUeC!6LsY<E6Hf3A5#vGQZl|$TjZyS zsNPCqb9_NkXO32YoWay6i}#j8s}*chRKKP=L;nYifY4r8JYQ$ndS4tiO3GJGwy^c* zpbAp#KqS);@=9X!q6E*l=%8ZVYwM8Y^_@f|7MlPuv1}_*6G+fzB-(W2>WyckoiH88 z3H=TV(~_1}FP<HT^dVP>BC@(!EO!bO=~1Yct;5(!{lHrr4?@WvQkWc6ci5Yw1ADuh z0mC*Mg$^-#xaP?lB#Nf_h&8Opx`VDZ)o|dBQ$M^|$$Coo_gWiZ_sJSOa;Lqkv9G~7 z#ca-3!i26hzP%;~Y!Edzw1x7BZR%pQyGnEJKUlN_Lc)Q(bT~qGE$0vn_1L0yh>Yo9 zPqD7otK8xk7os)&BOjwDzXikOE95AQTs!M*t7%8-s=B21rFVxHTq*|Z=H~DJaLXsm z=FU(Nr6+}wQ{%M@MI~N*@m>;5p;iuRJm0RV>d>KX<<xIFB<#5!?wo(=LaS$AG!}t5 zBnz-ya&6~0Mz=U-T)+ll99BftTVGMR=(AM1Tj#3_ALH=Hi--pq9X*>}q#R7VkY0f< z-&2t;1BLS@YP(XI>Fjo{K2o&!S%P2?*Y{#~YPEaioX%UdlJT~Te{pF(kMvkh>5bm1 zv}W=}I>co}!1>t5x0PrtCzk5k_;#{csr&WnD?X{~mSS@WY~zco8s=LLiEFtjR7KAZ zfh#dK{mF`yY@yNhy~>-7G8rW;t=6>R+wPy7MqAyiYC!5<k;ywbbn<~L!>D0K*m71* z(wvoe!#Rm;PBsIk7Sb6(i<kdfmg|4mb&ka@sa+|bJ1D{LlIf8M&O_|Dt#X~_jO<wD z3C{@xEgbVR283yTGvi>m9-0c@QF1<Ue`)tREkC-D%Bnb`Y<cb|s{48jProX$uCO~@ zo2C?-Y@yw?5=l0TCOi2<lC7w|BuczL2NL-Vow=CY@3H>v9p~TI`g?{rUz-X!Z*6UF z5W(A;ntVEBT{RUGRzSJPfHqku{$i}#!#Hl0ihvHN4<GTee_hXW<~keYDkuqyRg<OB zRb&DtiY3>+K=}61mvb0TehbUphcC}~Ctopo?G(UQ(ceIh=AedKf@p8<Gp|&|;PS93 zp-_YofB)=^o79l+ee1+{bFdmNF^@TA%U^R1r*(X*(FZ8_J!m`4+u=jelU9C$AZIjj z3_3x4<Oe&;LE35aYeTL5(916xn6~<w^F`nKh)Sd9Y`ys1Rq`m>%=Hxq$ieVprd%sK zY1%?egnA(%ED7G)Xw3Yu=tNsv5YyRuY6sTZa!b^7PLw*g8hH|?Y7SEg`xx%S83#?~ z<=#3xxbI{Fy&?z;#VwU`!&=jJ9u;h&^tW)fTlu(r>42=yVhS23(^%#H1&nTM^^W}2 zlEqIFI9+Td?L$T8L;nW219Orr$6<5>p~Ey(0%;`f2iYYi7Ec6}LP_e{S09{&F`%Ry zP}1hkBIEf(b+?nIM2?rp41w?(UqVt4h$JZPdap1=^p#P)Croun<94=Ul%Wp=yS87* zO{EL*c&7VhOF#Kmz8sX&`VD0^M?X3o2ue5rhwmn8rJP<K=UZvRg;xe_8+n&%2KPfj z15nW5m0$>U*H^cYxA`M4dnb<yGQKe<ynyO}=M5ksTk8><KuCRtt7@KB5}kLOxMgJ_ zn|H8D5wxzBpykfV*6Oy3^DIw#ykU=3DmxsI^<m`PUTj+jP8@!&5JX%1`BLUu&zUEN zE-sQAH;T`#mTK-^zX($y?0)*vII5g<&x-c&#=Wqw?5ZXeEd#_F!MXapg`6f&FA~)r zuMoc%IO_C1-r46jk2W?Dp?gkq+(L8lrv$=IyJGQTtG(Fxl9JmRd~%NNYfgzj0AEAS za#nQcHHm35Kk1Ax-&u?tm3-Ozs0mi3hjO3NYKD)ty@cwVNu49^#G7-z)Dw?@aVJny zh8z4wRL{o*Q6n;;PTC@-APFz$7r*Z$|MUh90^u+V7~aFHU}WxwVy=VTH%eB+(wl}C zJm*|>I946A@2dFvFg~f^6LAl<&m_ewRr9Dy63MOG5f>9b+J4ly5UffJ)_RB2eem7u za`7)5GXE9yvoMnUM#LT5Bj5n_!qyY^pglQM+ru`sQ103O|Gj;@Pa%q0KS+7|yBwht zh6?DLw<)FIIjnl%@&kOz)1?nckRYsi@-$czJFf4~rWBnh`r|3;6s$NjQT<Y+=Kp?N zmZc3tZ|IfR@ETB$1k0%Y*m{lq@0BA2{MG+eLG)vIdc25`xRp`2@f)Wu(SGjS82{{$ zgSEcnnlcic0#0aP7nL+Ov3!>ru@>}81o{}kO|IH)6{ICPVn+-r6T1`Gq?mlFe?C!G z!%n=rJ|F{T*b-#k;HcLQbQcP|%`opf^1PyJ!lH|72pNgz{7?M1N@lh-P@y(Na9q!9 z6_I|D=gJTX-g1SeFy$QitS8?8)6yS*vlhhboW0}buhP~pZN{f~*!uD1@?F{WcLC$^ zcWt6Be%H7fsj~NjN?a#*uq%)MzOO&(@FDS<VE)ADYTe__%0{ac0u^0~kkb);Vk2sK z({4)FYlKyMbS1=#g1_M8f|b1tTfPF9pLzG-3C}|iSr^MuRg<WX1)panoZU;*E87qW zp}C#eJu&=u>=bP1%6jR)zbv!aCUsh1qf_LZ)wPb))SJm&u>I)B<e3jzW*=7!c$BI^ zZl&SLzF?R=2zrN|5Qa4*7br>x({Ncv<P2d6c0!XlHi@*aUhj}Z=NAnA*^vlAf=YD2 zYsR8;P*M>!V61=*|DjS)^|I@gfbH+HEQVncw^HD~+*E~SzG{eY<^nTtwmkMbe^rjA zKjEGw81y-)rO_){!6;g>3<tV8t2(|32=uvhTtQ#oWbrAKGk`CU6gZC|HCxn>x2t+x z{HQEeTcYG)QaT_WPS~-7Gfyb0<cU4MC8V}yt)>;8f@zt)dZDWJQcLLP-x|AfmXCD6 zgg_)Ia5B%3M~@%hQW3yb!T0oHz!Pf65?79%)tA$Z8$9KGdiruT&(CZ5MaUI28k_TQ z>bka8d#zIwNN*;=<`Wr8X_!}q#{)@y6X3VcjH_kPAP|>vks#=n9aaD)4P){(>l|Ro z7)$Lndj}f`8nlvAPSKk1_nW!Yb4Z;D$K)0eaJ>gP?p9&w4ev;>iI(H_Sq&+Iv9|Ec zluR**4ksG$nL5V88{V?K!M7`t_;nj6lPrrhjFYS)8ad4F{u7tNf;2GE!k{B0Rfmws zTNEQx6i}Ny;|OzlKc>}g*D_1!PL|^jd%-49oMO;K10q3V5J^KdP2a5x6^!!g3~+z| zFWtx>fgWwZS4c1w4BxjCJ&p1j5iNUTaM>urn1l1q`E*m$fXdrnAp+i6g)BaM^Cp?c zojb3DHM@0<(dwho{pO-#%0?eA2x>-NwU_0}EjRjqYP(gG33&_uMtWeYJazp*&fvVt z42up%>jW5mly;mn$-lCI5x;HS)GtCJD{SH`KOi|pe@o=-;8kwRV1>YWKX+`Ke|O>f z(RybIPfW%w&?W6UE#sje^Y6KrKr>W8)oXcvOcj)KE2qWy2ONbvdeL!~*8}IB%DRpZ zw?a&4^K3pe1g94hIx#w`EBKGc+0`r(Ov3cm?Po}4wbJ(DH6ss3>t$gOyE6_1iA@iy z2S3VN==UqWtr_%=)-qGl8>nq8Ka-<D80tm0YJ$Y?JsW#zI^K{Mt{}VdZS*cX-HLH; z+?rQmS+(f9-SR(_I%uo>G_QmJTUf<~B&G@ncf_uW*$n0oNy>!>6arQ*C!~Z8b;Mvl z6MP@u*89?F#v5)pf#nG=<~DK~$IUPCr)Y`aNL$l}DSZ-oCv#du)NYE)_Mp{x*19Df zw!GUgVf1wgFfuq16=P&98x>_t0VIY2y)+JzWm>MMqsS5HS`77*`_0b^pLr|0*|>4y z8^EzAJPS=zu~tAEydhL$(Eg5t$ZP&kO`JO5-zqOW3PRpLHU&QvOp3**cs&3Sd;0!y z2!u7|rDZhh|1Sm!O6Rt$0Qn?;i?52<j-Y**iIn=);Dyv<C5XdRYX2->lT(a;$-@Rp zRb3rMsR<F@qR2RBcq7Sk#zT|;02g5H7d-<zX<yQmb_MlGVO<WXD!g9YSdw;a(kKO9 zr$z6RPSPO@I~ox?I%vTs%vMJ;9s&_`+F!pUu+W$hh<MJ7@%k(VE&<AUs$<9!zhll} z%!A>!WYjA=)tHY65e4)>5h~U$TgjiF%Z(mscqQKCsu|J@?&S6OuR^$O!_TN>^0fL% zKP{o}1!}c+DcX%|{0nkOH7Iw9&T-ckeCS5V$TUj|cA&rxP0sYq55qPg;+xOBjEA%U zF~k*IW^|R5yvhAz^sL7@jIlTf4>J^HzhkCO#+JW1Df8b()H%CEVMn3V$ECgEZfSf1 zo-eUv^D^s}XL6Ll`78)~wwxF`#gV$5y=u@X&!P`$K3k(|q54GNE)Sh|otyQFg30G6 zD=%34_vF#0Wg{_;?zh%cgsxbfSrtyvOZR?FTb;iBHLxEzPD79~6dXRYk#2K)6B0Em z&Ig4p-{wwuz>bz8VFu+~Cx1@9Jvg#g;E$kbdMB3oYacs%_lA@NduajI@6%(lYOEh! za(KGITcrf2;;P#nl4v~PV0ezZH*bzmAX47Ugr<9{(D4Dm{`Pr!vcn$+<XC-*wg`TG z3tB{%iO`U!LkfZp1l-8vGAl3}*7$XxU5dm2Jm6mgnI`1kPIdHYORgLS;i}&H6MRk$ z)MXdgp;5iOl@i7yORo~f$^O%g7>hM;PAz)a$qA)oa4jM8TTh5|#F;`d^P3=skvL^o ze8<Z899tvI5N`^TgmcLLDwL|;_R6uGoVw~AM5S_Z@Z0a50(G$<v>{bZeULKM?OT%? zroCU}r=Z29>?VKTF`=W04ycxGIQsNJJm0jF>Gisryyp5%MQKZ+6#FgN{X7A2QoWTO zkD+4{sr<~sww;x*{N)F1pe+1plr&q|J7bhFCIvenw_gL1#IB*^SqU{iEog&tA8XI| zUb6CRhQ>=rV*`j`La%gzy3ME7e9!rgF-de8T)dpYo`F#qea*nkqyw|l=r~f%B<Hls zd0<|tPJKlMfmZq3*No(-;^^*)s7AGuBPzBt%gpc==@&Fu3{Qloz#G46axh$1?AywH z2psf2Le-e{mix4%xBtVre*daHsuocw%9WMC4WB#~>s+}WVme}j+UEo@dhs>MasrR( zkdPKC490fUdLa<&Pku&XHLI(WUpc3%*`q+qAiVpjfu?8TWD#a2m3jao;ZZ&-INOmM z@WthR8Ge(vVDnnGP3L`ktLn#3Q`4~-IVS&YoUy(UVLTAoX(A<o$q+P=G}b$FW+47V zNfcRhghey8F5|jAqA;UtuTUZ7tnQxr)b=<bcy{X+wkb=_<YrKgBx+z0d>F|%lSUUV z5NUX>KHVj&Da*-D5?S!y58U@{KE6C*Cj_ZD@^$37XYuGVZD?cHOAq_^&L%Opg!<4| zR|F>Y#c|dnr`^${GOo6`xYwgP0<+u%Uh;auvT?(iFWF{GH!*bJgvdErj?*1%quw&c zl1D#r5KRt4*zLJQvz&q8azaBL=I{i`pZ#<3Ed$x``?*gg1MSKrE8wv0NGsY3P$BEP zWOLM$$dLGP{pO}vbT(C;eB}RT?(>tV^6<ut$uyh%KBT!XM3rHe7n0HSdD0T$@#Wln z()XVKZ7yAGe>N=et1|l~{BYuMj4yfO{#E;I0*6Q?k>j+p*NH4aN`YA4IX^NsIG$?@ zFDm60^o-vhYiuKB9Dgf*me_mhSRKqX<UclLxU+rUEaX&$beM2(;l%cG89|Eqlo_a2 zTAyBlvqse5H=V&}(gV%WrThP8RYi?Nla1tYeU{s73MGzeaz?#u88=Jm-Z9hB|BeP? z22r51Nm0I5hqExdE%VD*7o&l<h8$FB>jVL=q4$|dQZZhVjRrzz<N5aRFTI37qJ6Q7 z2_g~$v4r_7n!Od7yQs#NFf#x)B=RS-@sA(`f{BK!h4;5zj1+tA<(Bbj4EVYA|D)*K zADMjrKYrV0W{i6bb4c5q&vVSF+R2$3DQ7vK$*EGQ_cn7r&H0dOLvl*a={!RYsgO#g z-Uz8wsJx{<`TG6`_Yc=~-S_>vp3lc4nq=c)o%V9+;Vv#DN;l2iS7dZ9;D-s+h%}_z z$5d<=QuKuAr=}Yz1-jOFZ^DW<S1<WF2fhdR+5q49u41bwtrZXB1W?omJpxQ#{hGO= zmQ2ymWGUA$F>4H&80Kg`<UMK-uY0rzAvoJAVs|$;>bk63qnFbJj7^@Y1W5A9WZgwF zR@J_0t_n{`pA=44p%C`B?L5qk948Ipj+j(<M9`H`Fg3!U^ZMfld#IyI12C-tJuF14 zmyGYD5M!Jh$xc)Z9%vokXF=2F+i*>Mb;F$U5j2zMLi@l0Qan^+5drufqX5CDr(aur z;i$z>$T5R*B(jusuoRi1s>xDO71$_c*wEOWZ|7ICr~WrWR{k{q@!p~Cx5xT9WlS0t zsJGp<uu@#euA0oKEoIRcDxS(iViJRz$pcmhVet)kpapDn2A%I$;U@$2`(mqgm#L^q zR{SBP1r8X|sK#uC1X#nqk655RYu@@8<qtM5Ywu%o*xd6V$^_YH)laA9I3*Pl7DsV} z2NMZ(*F$#%ry1%R@eoZCOX_5Qgc?~Y4@L-~sE`KTo|hcXlW*8vd!aJXv9{5B+-dDO z?%Tf90J7{B)AHEW>*nk)zhEBv=^hzZlca1s%m=(a1#MW+Op<LLt^~WqczTtJkMd`X zLgdUIyBGp|A}-B%6`}%zXjLz0-lgbkrfte7nfG6sS6ZI$hP#TsTN?BZBglt)LjvL< z>YRqTs$nJj$|!H9+_(^)&C&=E1n8E93%eF+Dt_3aRh?I%W5g}gVXb)%tq}oOcK^{R zH42UZsD@vee|H!|rm(s6(l<#j8tEZkakv3bGqz#q0x5Z5*!`Jy+ky*<O)L#J!R-v_ ziBmP5S&GC)x#@mFH^gv}Vz@YG2piCE9I?F(=BY~XX5ZrW*jQZJ`{c)v#t-|#JarAa z;C&wCuoR1Zl^2yUrtD5pGl^8K6xpB63-6(2yjVVLGU;Y?^>CK$-fddkJvZ7<*i*w1 zY5RU@fN|oLvNW+jaTi1Ky76nxfcMqW;Vl8_Pq0%&xLYflayRV<TJ;+0qajSGv5cOL zp&IgMh`N!Q;t<7IwY_UXIFO<-4l#6(ydL#TU+HrPTqan-W^f5nVB)B`=$y}`=;To} zJfrv22q`x9v%HyQKbY!lors*_3Dv<Xe?M+3IdCOxc<}Ua8m-oLu!X)eqmvMDJ%st( z83Q<fBCWk5(a1-LgllHwdhdeUCPt01X=>`ULR;8DDVu+135^!)miyWTWz`8aLq*7e zmtL>+A_RC6OD=^h#qm}8)2u@O*xpMq1gSx>F$OCv{dSi2gs#ra>f>cy9RSc_Lv*;5 zr<=L}TQDIZqtge`xl4IxdPv7N`k6MmdDj@)7<Ooky!cp1h25e)w`&SkQcDlCPLQ?X zW-8eZKD(RoS9K8D>DYhQ(MvDt-fJD%?m=l)4GNd6?C#^lkDwxAzNyhr6Dxd)HtL+_ zfv@n5TMtJyS55!;oDyRAr7Hv=g@5+>d3QS#C!!1y1KRI)SXawfnyW%eD`cg?em}Q& z?)xG5xe^s;h*6uaA-!q!VcY7lFr8Wbugh^g&26|9^7+1D#TcRI-b~rSeubKTrFOEU z5k+fJOADuR*jAuQVyjsTo;v3&rIg<eaJ%DMN9EU0yQAsW7on7ks|?NAhk7Cq61LPK z_DjoK0_`1yA%$T|t@zVmLV%{9<d*WhnYem^D^2N{p^VMHnyVIz`Q*fx+K2QhrJQU; z7#c~<sTW>Ygb+O=&&0L)or%**jhB?5>>25o=acvT=$DOQD(0=Smg}R=_9F*~;y2?D z6|9cDW61tsDz)~@H8PdD$x0Cv$#Rxr7E5z(XQ<XUT7v{JvMl}_q@?Qg#M))BzH<1C z=L)@d{_xCjY@4jIQTiv-!4nyxv#+DCiw{b#eJ1%vDeOd3X#Hr=4?Sl<-}<(*ozt}7 zxUs+5G#UEMSL0xT=Kw+Y5?jN}t94O%c&IwP-?hFQNE`QGdqkSo#Yq?<bby$zkCfB2 z8SNT(`bE-=5V=NLnHwU;C$u62dVK<&amv(vh;}N(=$*b1Ay|F7GaOzQhG)w?+<SPe zWP5O#goFI9iKQv+?y_&nIV$euaLRbJ{KfU{uR1n1{q-C24H7h^;SRG$b^O=sdosTZ zHghsDM9O%;Fm}jm=HhquwIQjdMWdY!f(pAJaFMhE3EK9&pj@!4JyCmRqoeUfT53S| zwxHci!qDW<`*Di@gpGf)fRxOd>)Aale>lp%a$FGCm~+;k*Mx895f2#{jvb*y%u0H} z)FTaD#W7oE@Xy^ar#U;;`3!CH(rT%U+@wz0%;)RLb6@bVNxcu~H9cVM`rjO5H%XhM zJ<lH27#~UbK(cQ|^f!B}ZVVc21YV^R+sBnJDddi<rpO<vw4`mVuS(zU)cK|hBp3QM z_IOLuwryxdOhH5#KGkB~UNL>!olS>Np2dE*#U?pjL3*s`Qn{C7hYAk$jkzx;*EuHH zpkSCrP5MLved`M;b;(10rziicy%T3<KzYcMt4+yD%dg5>ELQNTG0UM7>3u;o)q<Y8 z;JdPudE*eBfu1-!+P3KBQ1wCIuKM3v{tsO`s58%Gx(=(Kzd^06DrSFkvODd0{vqFd z@E6NLFwtV-gSl)dgxMk!AU0_5r>o?U$NgQE$mU#aIBF_@KI2X;6>pLlYSf}W(xjdt z2*-%ngcSWetf_Z$E}fcMDARkKl5CecT2Bq|{o}x<`y$OG*oMK+qe9D!cG!Qd71>LJ z?ql-z;x3v<!Y*HrkiKi+I;heYc#0O&dv@pBsENn-9$4y4Hryu7?|N@`DQLuIDe%df zxU_;MKWZQ0g49lW4`ONoxXk!&c5}^!7N9<qFkGmrY-rTi_EU=v3NEZ4aqXo=q0%4J zA95P${wKyE=r>K!SG@gVOujHhdZj9N%7BjDgC2>Xx2NPvu9{|1jm-zXx7xlxwdd5^ zX~USWMr8uM)qXuCY6^Z3ne7osP;wm?XS_-0O^+1UU8x=EDbaB&y*apO0^8<3y@FiA zb8FDf{g@y9%Sv6bW<^Y9hszf44J4fM0~P}1XZ<dh-g@zN+23i#f<AZV^2-(T<V#mF zd#U4n^zo!tNSYCL7Y3Myk6@jb9*%EBJTlpqx^II!Q_or2qx0R5AvV;o!=B&McbZn* zcBwGDZ0Gg?v_KiruZ(5=qs4l4-!e{pP-(Tnbx_BPnN6MBK6IrcOOkfOikt}1Rp63q zPJjQ3XXo5V>5$Yt7+3ki&*KRHQ+!@Eae@_T_>A}?yCBvo=G#8{A9uQ@-lK|tPr46_ zqqp)+23zwBhinF|stO&hm{8iq2+7JgPeF%;;Pxjg`VT8QZIWlpHrAlY$^6MuNu>@N z@W(6waZ^f6)Slf)oJZ<@vn!p0eF(#Iu5(zJqE@3YR7>BISgK(gXXUEfFt&G$*M7I} zPHI=D2ldY>0tzN;2@9CDHpskA?Y<ME4!iK>2#)kH;tNwb`4=5*eqfc(m$c4$({kTz zhkfJGt!xe03n;&#{J*~ofC|g_*43LYow7_Sjobdbztf~`MCyqe54SmW+(!Kcct1vJ zdr)8l^Zj$-pPgMX;=M=T-p0M5*8-<0fA#}g2;yt+>xL-~haaSgCCQ2feCriiblM6y zc$(_l=fsw|3m2~BPc7M<qW|!E4kcYd_Z()=?K^$`(-jBh76&iQR+FVs`uG;23_(Iz zsnc;lnuriWT2>s}9w3Q_LjiGKzds@&a95rjY?F4wS~*#mf7GF*QM`a=uU$`e<Jxz? zfU)-tE>-b_!Q_eJe*1%H+o;G1S9@9}D34)tIClG~=qF4hX&1T}FWx4^4cpPC7zW)Z zJx)wtl>yw^?5l3qw+!QeRHaoWXqVr6dVTr%or)93AN(T(jmub*XM|>oC|<t(|8ZB5 z3bK{?8n?X{DQ%m&LSN`VE|Roll+_aaXzKLQYFcCGRp&GlzrBCh6JbM_WAR7F{SsV9 zsQ8Lw)89*PxThty!)2+<xs^OGZlP&({B5!({F0KdK-QorEdiP-ckpuRueQnYisNB) zB_QsJ>_M~En0w@5pkR;nzSbLqSty~D5#tGKWUR^*1)`-^=&2If(-f4O-*A{z^@aOd zd@MwRtsd#nn5Oh9zcEc#tAjvhS!vp&Wl$R>_J1<heAw2k(2TlQxs&u2rw`_|wSEG} z^sRtufMEsX063%-_pDg6LcIOqF|DS0se9T3bwfCRfVA8mD&;iJeW+b5i613)ebaxe z5cR!c-@%KH-D&2poydjsDKSj-##sGT37zeD8jz#Ve6yVHJ6R_eZqhi(i~6x*dmZ4q zquK!b0TrYBkk7e?_p`p*eFASw;CF4+BvJM;mrlaBm1?m^UXkg|UET?M3JuvDA#T-n zs!hcH;jbl!EB*7C>IWZ9v!i%E@=?;2`}967)moqhvJ9_X9fVKeSMjF)QhI{gQ=ab| zV^uL7!36is21}JzC*h*4O8R=XTkX9>v$k7WvDJv13vVY%Vmha`q(HZ)jVN;`EoZji z`q4u3l`PGGpZ3Rq_!;w;g&p;X#iC!^Qh=Ti4t|ggKj&OE{IzA}K-^+oj0<~~Eqy53 zpgO1SiVjlFp!A6;LdLD&z-_{TH;={Mm7gl{pi#~kPrj3;5)K($Xxcul?TjKo@rQ=~ zPOmDT|Kq9$D8c#Jc$DMG=Nw<tmFxL+s$SnV4&;`EL=4W}(J{Uz#CUN0QH(=nG&pAP z;6d`=^zi5&wf0)CzWpvMZR4hLfP0Ru!pAc0po-pdGuT}36#|n+Z$w_VM@#EKU?ApF z^NMR5s+y|(esS$T{dOT@U9HmNzpUJ)io+LMd2>7JQb%`*yOeD0W>Q_w(QJDo1mWw2 z4X%PeIQ!@OHKec6k2?xWHU80N&+3Lpb5l3`DbHldyDr9vq#{SwwW6Aq2nQc;XKtrx znkEQbfRH{l81=lxe4-<oxNZ`x8%@M!!rjk)KI*2J_pxIEVLq41eRFryy*}V#sUuR$ zz0F7UL;;J4?ADD8@D6rS*ec{-NhWr%t!CiB8ouO@wV-tkF@ig>;PqGB<l6tvwD|nH z@h{!|NYRs{G<CSOoKrxp9Aa7R6hcb{kWIkIoV1Zt_#vjm2`*EVXQ#->&(An+X)T*R zwS#-Tc|EgCRCj)AFT%qDou@g3kXFK;_d8-@Y^;Mr=ixn%17xLiiYr4k4Gk`>zaeXi z4E>p3lDT@9;9zUi_B0lacT|*wUO6S#R5pnYHyJtcqVf?ho~VsqS8&%nie?=Ru?Q3* zZIp^IFqSt63^oLlGhLQ*G|!RKnkA}U<r3RqcVH50XJpBgi*{$1z;7M3iTgPkwFHr? zWe0hLC0v7-ZTuq^6{=%5Z1aj_Lsd{v;ZinkH<6cE06(<W451<?9ER#26f-Kj>Fio| zRqas9GMPRE`y{`JkZHL{HiBPHGfzylsL3%s((Y2$W@7!TsL=eyvjRU{+67UEtjBAK zPXLsr>Pr?OlHoW6+f6j<HHF*nY+$6J5=+tzEm>Di1&KP<OVIa9m6AT#V0_+5x#o;j z-`{MoTUJ{=b5$Y7_Q+N3C<!$L8Ppnvl(>~YDQi2^)I@&B>${^s!=L;4)Z%26!US8r zv3}I|(jPbexeJGqZN6t6p)T<61{|gJ{Kz68<`EQbqn699xA!(T9x?WW6qHd$h+<)& zbb)E?k?aO?t;N3EOM&99jgaEii~;4!?zVeBua^?fNEnuN5rLT@e<}oB*w{r_)zzin zISKmS737E`18g=HXI3vfQRxsO9TDR5%gu==JH*F6Q-Zvtem0;(h%EFX7xCuRla}-A zIO0tysp+$Wm6{=X$=*{ty)Pv?34886@=?r|lO2)4t8RTs!;im=?haQkd8Gy9p)X%X z36r1x&+BB5xs-6zR7b8}Ldrud9SA7f=Wc9IkV?p+-X)8jLkwazNm&iuv}hn@lJak5 z*`KiHl;3(Y$`xM6R?e{XBGVmx`E_r2TkUF`!7z4*QefaJOYnuBZcIFKh5sepJ7xVv zm0`v5F6FzCYO#Lm8{`$I9?Sh;lQpf~`P@cHfQ|`BBdFqGW-EQeDMBr44Q{XTCqAXX zCnuwRnU}ZGzV#&ee5P~7<<e-Q!7})N>8+8R(xC59FEdl8LZ)w8)_9HE>*F^k#;=<M ze{F1J=V<c;-Dx`$^_0Uu5$c!2-lZW*>Cm140>FJwieRF=!QJ}`*UZQ2$=VNK<9j3t zy}{atTeVbWD1cYdONB_Q&U-(|opx+(7+&O1aqhK~p7(p}xiAShA8rx=iU9$TYn!J* zk;FVduDD071?p1B{^+yiQZM!7<s20r6(@b%)<-%U`sckZ7L$UY{nsFPBrn*Eb@Din z`#yzJad&^15a4K=YnNg2H8E+LuS^~wzm6Sn`F5(_{W3Dm1?M4BVfpWF?C-(OrQ{#` z+pt@%B0%xH^24JI#!Qs6?fp<2Z-bi8wErEyrIgH(HbCK>OTOPYQ(Mv6yBOs>xnA&J z;>w-z$sL|R_Z_*WWH|2J8<mJ(D(<RgrAg2^gzGztyE=pu0Q)vUTz~gLV!=9{OB<_Q z<DIpJlI+!>WB;pr)=LtcJZq`6ih}rgOxYw9+HW4#ev<SMUHdR+#S@H|99Q}q`Xy(& zL+z0e--B~&gVWlsV_b;0i@gA|y?@a_3t^fjL}HCV1O6?$`B&1gDeAt`pTxPKu9f3~ z#Tmi-7MxBxy!w^AnYL9zr8c$R-DExbvGPu(E;d^}Ps8j`tksqV4Z-<Jsne$PathZ9 z7!JUk9*cA=CC<8S^<7TecALQ?|K-pNBSwqV1G7S}$^+$E+YBaR9<!EzOAvkx8ssWS zJlWZGA-R8}Tt-U&6^#nGrne{w%p$Z?BDJ@KEmkA}il%Be3K)Uc7LVe9yrl-hS#b&w znhT(7kp%(b8vx$&`mf732n~hX>hWR*0}Z-$HCvSI)Onn{5K#R!xbNzVL+!pZoI8VY z$ys5M$&Xi~Ab8J0gWl$$-8NNXrp*OsgF}bhoOAyZ4`PqZffdj#);FBzS0sn1+BV=G z)Fuk!9L0>{id7xJcx^5Wf7X7zkBIRRgubqo=i(LUt_tpk3iWsez|L9ugV;|3R&y1X z+;7w;1hnD@#^MiYi(KwigRL*Xh6+)Sg_99kcO3Ixo{GH^LA|ShXwF!m?%;R|-&^(0 z21~xmvKg!E?q-2qD71wQ`l-5sz-9L9LS57du6Y8N`c?W&);b8;u9d_$ABNaW{!4%= zl=85pOsr*~lx{zo13_<&qjmAp-aKp$6T9sy&t)1G;IZm%207#q23e+5Q{I_J=#$hY z#b_32GjckTIB5C#_6~ayd>B;W!zyzs?Nn!nT3q`ncG_ZUw)R}3ULQ-xL=Ckjxg(K) zuu{{_p;x8U6Q&@*jRDc>xt_lFTl#2xgigI}b5Uwsraxo7=J2#KQC0m0L19kFn<BK~ zdX=COYBZ0Y<-ebuLyLDxq=xJN<bulcsCRr+F<)#JklFDSk;&@ctJD6xcqQS*fRO?P zyIjB5)Idg@qH=J`I$rNi0a~rhHW}dGar~fPk5m`pK3SV6msr{-fwzg;*gV^=_JWZz z1!#`)#WUP?#2eI#jZ~)vRfE^3#09h31jNK{ceg0GnR9b7R_9vnI|;(Z1`5w<6Uq?i zK20q4x5X0YQFj9*wz-(@E=(_8=IFYWYlnQ?ylih5Mkx@r%|Kb}OJI4@vKyf}_=C+) za7KAI8bS%G3v$W*4G-}Hc}$rYZMh40qfAIr!$RZCnrcbIpCF3y@w5da@?GEE8D*@t zw*6D_Pq@WzCgExUj-TD8xu#4hv*51EUOm;FKTplBlJwp!$6l7|?XJ_y3J{MM>$lFh zX$`^rX6d2?7MTPg01&E`&hl@-EX>*WBq=uYAipOY{=63`y~pd&6*z&|?h^DS|EcvM zDH=~^dvdSb0^tc>Zc`c<Tg5TRa_;ke0u@zxnr~jwAKB#HX|-BPzTfPUK1o`V8l-;9 z(IB9HB7>rRN(xwgN<ZJuJNDg;W}+FKg!uhPC911xJjli;YierpZM+!pI^kJ{z+5t@ z|E?6^IJYhl1O);tdN_7E5KA<~K0Vp~=`}2ujG383VdrJ<@*JwJ;<W43+^!R<3-JF- zz>YjaZIdM40S;ucNnW4~NRivwd`1EnjA?1#C4v-?RG9;GgNKJzCqfT>#;9-BQ>w?* zXKk1!^-L0+xBT?<2E~<ZLR0+d>SE%i@)O5U)$?4z&B3*WpQ^CBf}NZ7G2<$ZGWZP_ zsKD*m$FaRdfs(ykOoq_-lX#;_HQ6swq2qKcw)jBrchsL%%tC;Il93#nEJvf7)IV2A zo>vk3pl=)F`|t*;Xw1|z$oJ86-={KuDj2_$gyuo&y$Q`taABXx$fh{tc$AdJe%A51 z75a&KRAVo1xy;{g+FxcJCjkdIYv`vzmc9{uq}I{KrsWzMGB)Cu_2c@p2>c=%e}4+M z=5q8G#D34Q_|kc~o!&WAMj$qahpWbfbsMOD&GBN8@d!e^eDSW_UDlC_?q#4BaT1R6 zG76{VPR+|vDF<HjR34nvZgXNh)W6~#6n;k5@94|${UyiRY=`UhUS-q{W17=0zlbh= zuPrVk(byX$Cqq*#qh)qhTB{iVoY+#LYHRp){V&TCIFZ*bsn+PYlifP2n>ddC35}0f zY$CRsfxa6kR~?5dC1a);sJK9Dwh&3`KRL}HJcfY9iYSkiNYcttn{%>|F6@0Zqim)R zjVv=Qq-;%*!3?_m@7fE&$z-ME@Qa_MkG)inhiEWRaI0rHSf|0p1UFt3y}j$1=Ofy? zcFB&eJ5l?(PyMHzQgOPa7j<DD?J?KX0rRc0PU+i1iosZHK=iD*sPyOM%p%%{H9@8) z_pA^@`Qzq0fE)PB<y?;gwv;Ru7l>^?nyp)beiv~5F9BPsc~FBzV3Cvd8DJIMtSX*A zr7&e7(l2VGO+LYV`gna33qko~G6I9u?vcmXXl<n}rb-G+qfeuLObV7LB`&Y&`QhY` zR_=uTLx2ln$YR}maDjw?FhOK~q$GiUa(K8_aGW)K+}$(%4I^E~^nw0WP-sqE&~c=O zYIl}xSMXBh^2gfCI8}AHG!=p}ks&U~208>lJJ(h+YK45CXaA=z$6=zx=VkkD5_V7@ zWM}41{D<?rQ|ptkY-|Z7wLiyYMaab&$}xC(Z*dacTuHdl!7UHiE-=@f=`+@@^EcD9 z`!f#vBSLkNd`6Zvpu<wb&NM`EM1OIl&kQvt_~%`xVSnKe^WZiYU8yIvOhW9+U63x( z-t{FPr2MHCDYn1rZq%OE3H3Kl4+t=h5vU(86veCer~yqjSF_iALmSfgN8eHE&ESry z653pY75k%sM|udIa@yl=_L5wHbL-fjBJ={+@oBslD-gTDklZ9mm-l}v6}vcD`n>t4 z+=4ui%ENlg0%OxSh=<H9A60oBeQMri%DK_Dj&T3Af%f-56IXqmuBq)9)|<uEG6Qz2 z5;GhPe3A4mg{$ztQB9i8yGNM<T1gQohZMgeAylhS+X3d4y^;HGNti1FX0J~#0{>a= z3Yc%7_Dj)m^P*+vRaU<Lk6U~7e~4x8A2t{Hqh`%&i8zNC#I;8QFy#}KziJyxEIq2{ zvGsip(K+}NOmt$8!-sI|15lq_rsA@t4`eXGi77eDM=s8xPvJw~N5b}&$jrJcc05YL z{6IbaW*SEEyWirc`sgtClbQaOvFOG27DF0^<}dXIjlI}WNO|a3(uLrmXSgTo@<BkT zE3>ZO;&(s(PZwG7KOpQh`Z><|jYy_=jCV=T1B&k76PD%0u{+8SV<YaUMYR#`4m+^> z)EZZxrDR>x5xnze9Yrrx3IQiF?;N`jh*iK##P#0_wUu{X*PoNaV+o^s1o&AGxvB2) z<q#!Z>Ob|5WRsY9KOW|8fMhox9WR8XQ6qAY2Ea5{#^hf1@?b!kS|;nK5x)GafP=c- zt`hj*`<(~TA0If;9>M~jMxE$V@V*ZSmBe1lS4cI-3JWY0{XZCW@BeMi7SSmVMm5Xg z@4KR&a812l>6o9tdK$(r?Od8!R=P4*?!y8~V3IK{6(~xUA_!O-zO$aJ?vuKxOxz#> zP}Mb|>hBNFWANY{a4Pj!PX9U6d0B><>O=X_e`LgWCX;Vz3r^IZyp3Xguhj7|BFGWL z59abPkbdM{Ktk{li!fOw)!wGACLMB9OL8&eKT`9fQ|FY@&I?ppi!`^aI)2XL_V_%M z3Pdk+B^<w>LY}|B{CUE{Yx3al$-?*Mw$a^Z|C>S+GQ!PcoZamL?&vwIW#)#=hGYR{ z0n+EXhCVFVHmwThnX9(N#JQfd&;#~npPh+RJGk)7{!(=dlqRb|aIvPeXb@EYG=%3c zotp3Ik;GL;DlxC!#1^>HS<IXWS>IPNn&Mm7BK1h$QI+v0lsP{Q<;MFu)BoETe-PS9 zQ}P+!4nP*;M7v4%F|(&)z^{^ThtIC|`_$U*L@m<Kcno|T(eSvF!XjP`^s35$07Jd$ zICa}HIeZSc;@lZ?UTs$9f)4Xy<;58l%-qWa-{q#ky{3U;&16FS<r^{D2|kotrT28s z&Kvt5JJ`4M`VEDggU6cmgROw*53UT0EEh%|#CV3*)S~H3nbrfUvv1^ozmoVyTn$~r zB|`t+7WgBCq`CtT;`0v|fReKEQ<r)dwNq1M_1?U$jlTB+LEW!vdD$M|N>K$8L3nBD z_6Dy@yLy2Dm4og}+QMz)?yfycLJ%l}DG67w&LRo{=?F#3RD@yeU^Yg_`)*c372bBZ zKp2X1#*Q!rr_z<QItj#_drIm$J7)BkeBWCN3lK)M?32tJzDpRHv0ORxbKdAjLt`=w z4`>-AJ_lKA1&nT+MA;)r$LJyl<!65or2%K?s6w|1dWzfwDEX<v9CFJY&$HX{H2cG} z{U?csVxWKozz3$qor8(_@<6UgF`Bw8CNL=76K1Hnlta}-Rf+pTNZA7fR4#1Sh}P4u zY)-gO+S<nDrl|v!nt}8I5(;8q1Y_)CN#+N06^9WqOYQq_=BVw>rq7Hq`3E3~Ua@ln zi_cJhJIx;l=pWsO{{$npSW_;2@O%7PE$3;u-U-~E(42{;XG|{<BPfvLBZ8vjXg6}F zkRJX*BcmFZaNRo&?4V2OvXmms%`B?CtQ%t2v>cix>x1Cg;7%@va+J?r^&HL-dA!b1 z5;O&3fk@mkmcns>qvb?G6ROA__DqhnjjbUaW5@1YB)LE)79*i(S67tCb5IfRvUGn# zlLZ&)(BXWCu&OZRe`3U8@w#-)A@ho2>eD@Jze{gj?R*VKlfO^6SS*<+X%DU@=Bl3? zw?k-uy2V1)Nfo)_fTz3vB#KbeTBH`j7CX-hkT1>ltg1X&ejK8l97R=vFh=met{qt+ z@rNrS2QD;4KaT3p;^d)z<$!^x=UW^sG&^vWR3^VzM<z>{)E_?#p{GmPm_$}b0`^)v zXo+L~krQINF&2sxH4ZpgAtIB^sT8wF=2vYzak^piU@=k5$a@x&pA@Mu`1aK3M@qZ1 z<o`A<rC`v(IhJOZc5n5z90tdjU2}Ja6@A+ANW<$tFwe>Oy4uKp;0Z<(#`giv7@57c zZz3%)Fz8r%2@sF3lDF*E2H3#HJXOE9@iUDNhclE|rrkeCgM^Ga`H&T?e4+GyA0_1u zjO+ChxG+x-?Y4=Vya^2yMT=>fv%iV}E6d=WpHEy)zrC>JHcq^W=oltkQmPv_yr-($ zP8L?QraQ5r@h4nl<&z4iAKsR}(*>Pk&_`}4Z8`E126^fD(nG17QPpVS9Y9+%Ng&z) z$_LXmYbvcL*dj+geVavkEIFC!2&0K_0APTg1RwY7Jd@~|w0$N}hMNYXzL>uvKd!E_ z!_=PHR4sGMdHjWH+MO|Rb4j^-lcbgWYKeR=upWqq4k_MvyZP^NUwy$i!A?Q7+%?0L zkC&b>hYP?{8tfmnYMV!%l9bGgvWwzyGSN0V5qKn(@fB5CEnM%G3A!*RaISb^kBIQ1 zLnGt5MG<%)ZkbZkF=UVxP}TxZM36BMfB`74ODqs_*P<j6%@w9f_i;=oRwB(PdD8&V zG%XeHHFg&9f^EXl07U`&9D7U-t~%1?BhJk+-=?=-EoX=8L`ZD0|KF#~2j*jjg#M8s zL(2}B!z>H+NBg0!IS+0`qF_&^BA|MZ{%k%BXeQbdP)7Y3bHg&f6YLM$?#p!>*O17b z5FI`AALp;Nrp_)_7Kx%D4|vt>F-o*EDi&fWO0cD?Dru_I#l|%s6A4yzSvUk<WdGa{ z{wx4%g9lmXV0R0uqT}BqLcoDpd&7L@0=coTmFbK2rcH?h<|^q#5=^$9DOJKwgLcY? zq@uDP_Ys0vJ=Z5=;b-;&>ZBSdKcV2y>NO&LQrJp4STX^0AhHwkoI}VG_dvKlD2uK( zr`1Z*MpUj-^J*Gv6QRr*67e*6l|Hp&?uED2TI>?GVMBmYWEIufKIagFrQ`dN?P2Na z*kJ-Gh4P>s`ocx>6jf^OO6WK15DpcDpc5-uV1y~UR(Ksx!yHn45zmQqGtO~M&3X>B zyF}n&$Qq_S+INjj)Fzvtd2UqCBL_AtLVQ1@jVK7U3-#e)SD=w3#XV9=zht;q*gvmf z?Gy66FjVP;h==-T$<q8-is;3NjQ2{N`~&;z)%zISvwciu5*b$iFw(uQn&l`~PD%3) zNK^NWLJM0UbgQ^(pDhFLyx;|ezO){}C+|bw#5`}@RfOPRJcLC%St?<INl*xKen2!P zJcWuMLj`3-I_8Vd?xY8KXeACspxB}p0FttDEn7orUUVsD3Vr)O@T3H-4Io~Of4vX9 z`SGZqYzj&7tuO%WRc%k#YgbC(iCc8@<Sn$|DqEg**$WHU8}Se&TA~*)p(<B(X(Yo? za9Ln`Rr)%ZuKtb)GZSAR;bRaQVL2S<c;xN`$<R}oZ8h_0gh2aAca2T~CFa$@BOI#g zCNcfMkNIQ6N+a&af3z&_Cj6cr2{O4D0dI;u9W`xiFL!^Iqw6bVe*`;%=}iHxxG!;b z0iUU37M!)m6$BrO3NZB_2Ne^r5AmyoilqcV#kMa9Cen0R>w8L~nDh_3spWWdo<Ht0 z)_inr$42+9>ty+`++d}!PKwmR?OPZbRWrlAt;BSaQbdF1dz(FD@!+9UB*2Tx^3)B? zc9`2vFG`_NmC0H;szJD?F6@rrGYF4cjw5XP2H3l{dSy@jD3H=g4p0q!0K%)yqH3kP z#@~KbXfZnel~s7V-9^_tWKUEWD;!v3>)yAzx8`4baVP@ZTRDmQ;rD^;AMkI++%MdR zv2T|}f(~aPw(!4|x(9}*rTkz6yE$gKeh4McXRu$o^!_Mh@BeZ`r<vmXts#}n_x$gb zK}E%Ri}oLmbvEKwNR8${G2%jkR&1SOi#ft0$oX@p_+r>?<&pHnNT<4e3uupQ#2#>G zp;<wF;TBZ>)OEx>TxYN!JZX-W%pI+bdKUdg;#KqMTh2CysXxz38M4Go>TJ^PTA6Sy zvMxT3Y_M!u$8VOt`3EiafVA(=JbT|0!)0Q2={N*?lL%AH5NZ^5^prozVb$e+w?_yD z6WOOfk|Y*0@;m0yMh+P|mjgMr3`!W;&OY7$#3LUFLyyB>65lf)eH=Q6E{tar8Vfl3 z_Ckh-MM&#qNQU&18k)5-Ffk}`9te38A$=<@zftt-*JXR7C=o#BX)fm^_q}Am(S6d> z=hN}A>!L{_e5pz<TdnWcR|(N8sn0&jot|nq-*@XXb!I6XUIZY)gX!Un@Y)@*yL92? zc$AzmIE+Jj(~%dF&t#`54|7HQz(|dKXr**z$pmHmitE)O%`yz-in|eF-i;Hqdjl5a z16aZFVx4Bu2&SmTGROg`7IkR_^mFhc?E>O%dCq-w+4#!@7>W~)`45~NA{@@JHYA`u zPKNHz8(xO0<f7sKfba{rLv%<u0v{F(2i~!TKbe7U;0cj_Sact3;~FgXMVK7#(8uW$ zsKDb(ZXQcPkRImo6KV1Ab+uGsKqvx)RRRwZ7`a)A&?2Osw8kC2dUd<~-fMwUSH(Fv zVM5UvD_7-9M=kydvZ#4!k64ey2C@dwNiA5k7y8I`u7fwYBl3Ad;(CB+YjCvL76qPQ zY|$snSMwcQ_8G~D$(f6G%5Wa<mVlBk{2Q`gQb^>mT)rb!<fthaA8!&qaiske_)mao zG~xu%F44gN|C!MJFe2;=9s?L*AwON_Ds4`rfJrN+a93EMIa=t0oF7Y3gy(V26pch5 z%o)iN{wVhk2dUj94YZ35^F_|Zi(fL8R?HB)MHCYNh!9XiHeLFXT28Hb4!#N53V6f& zkzI_vMWuTs`h&D9a~j>zZ4pLY1EQB0$ZC_lMH9%@(_noNp1Kb-R&|dxJO`ae*zFSa zNNk`TF_r-y{BAV)!N}$(Rk9;bT1d<f0K7l$oQEg)d)$gc^{e=<3AdkuhezuA1(=c( z<zvr)5f2M$T#v!gCoWH3h%wXKG6y$=fz(K~|Am=-V}sCr;Q#Cov&_Ly0uRadct`}N z&_ZdKulkSye@K*oPfB&gi{);5N>_;~S4j^8BEIbh_bl1-JT34|)y==ePm;uM1X$p% z7Q@$zSJuV4<Q+9v&Rm5WL;Gb~j+E@8b`#cOR9}diq@~@BNWO<HjapB`@MP`FVjv4? z&R)JRZ-pFwnKXJ$?uFUWf#g{B1i`@=>)s203I!lAk;r!VOPPEds>r^LBYqC@(IV)I zq6?AcV5nNfztgZQuBQ?G$6h9a|C#Tog?1}Q@CxNz75`@riu_mjDG1Cz1HweB<h0Qb zCPeM%;uWDq)$$_eiQ*;DYGth|UqIv$Lwa?+$fBdVC0qGMyVygHct4|9Dy>c{+rnVD zxN8k@oFm#5?|nBLO<Yduc!ATdr*Mfioht~dY}vX*@Lr`8d_9etO@(*B!*Os^h}c&^ z>@(@Y>lKg@A9FSkc{~ENp<1Wz5^zeaozn8*Jd<ZK=x`uz3W^>TumetlzeWq*VJhJB zuyjk%1y_h7|FdasD<R|&{$6iKw(`^_D4YqNwaF5S<iQO+v7ee&@Zu%$!efA;X^~hz zS2UHae8sDlHzVdaw}TJ>7aMO?>u=ZYH5IGli}%eTEk3nK4b-8~GUvL5C1nwglf@w$ zNkBUe!K=T-_dN7k^de4F0!=+;NgWj}?}MlaOpq?eOy)mG%$kGK<*5c#MA8~8I-m{8 zj7|2YiR{X*pP78jKKkVhJTksKo9rS%wh7Uaf4revE!4O=1E#-*9a_60%d2=(%mo56 zQ#8>Lv`VR>c<I;rlIVyl+fBP(=n|Z8=?f4w3eTH}RQ7VMtrTmFht;p~ntw6($V6?; zyEd$0TKUKaucb=|yR2JS*W2yRc8kQ2#2eqswIR?~xZRJD+T|0XeGf$^6-4S7KKcBb zgW1M?-*>E&0K|L;vTj25$u0cw!_p(y5Ri?Y2KtQ`A-+&DB8DjJ!xfI2Xq&G#F<Q`x zjs~5Qj(Vo}{TjOwvhC--82V)6+Q*6uRe|kKBEX$ju$?m%Ctfrrn1Ki4|4Ef^8bBXT z|M(Azd03Lu^u>*_E}fzjeOqK5*$;}+Ii9jVl_kw;@d!=OSgfBR>a-?CyrW!`SqwL1 z?LVF4G}&VHrfcX;7d}bs93XOM&7zfryg^UJU`izWyHP^2eaD<iaKUa)i0d5DV`9{M z<;K>(92)}MheJWDBks_S`{t@n@JW%!FTvwcx=9neJYnHNKK!su`l;NTi??n{;&nZT zc4Cjs(17+EF=D`RQ}94yK}K#LELR>HsG5lcI67#%iFQPP1*+)Q4qN~)f_&(@H9+QN zZs}i(zHKQaUR&+S+hi(eh~D928gFq{(Bg>!@P1-TgM6{YZ45aEY_t>K5dthO?tOUf zZYjpdYaVV7BCf9Co)VFD@ydu|OHCO1k$0L291lfbt>Q$N@I@7V#JHa`F65@s;bMAS z$Y(gV(;4uySV*fIwau;U<uB0ea~6~*Y}k%S=I=`+ikxz~23V(ykaZ8HtN8uI7EPWX zXMr!%OmnRI^Uw9mDcwTw`ayg+TBx!EuMZhE!xS|Ez46dn9onl+w-`I3k?lnyyBnq5 zfRZ|J|2I;AgJ%Nb?Y~^B>$>XSV@62>{W@;Le=x(otOirJQa4TWi<Z~<V%m*E!+}=a z<<aDqltYgY6TQN3&*5Fd!S*EM`!7M;(3r#;_X*QjZNjOqe~bz%k*5HNH6LEivUat< z?52Kg!W?9{syI!@!skb(kH{CJ+cR2RKATqn0jj&aEV18lPNc#*bjFq0UAH{?q|F!x z&%?MfE{=`KRf};a;F;54bG*1uh1iyB&b7wszKKq~|2^uzi_!XsZ03kRBZ}S2@kV!y z=TVZVZ;@()L5+;Fv>ZoUOYpfBx+hHbWlVC<OVPJ~VzO{M#(Kfx_a_kN=c1!{=O7ec z*-0vbsS}Xte7jcUS^)AISGb)c&T<tQ9dKsxZl>XN--M-mmtBhy8x>2vGC^qcQEil( zkGm|Skf5pX-^0cW=y*Uw5y3Mf_*P0pp*3m*@QyK+^NflTv5<Dr%8Zt)IM@Tyfb)7J zaeqr2U7W!ezCHIyDyhy=2W|f8+1{U+EBh!-#?#bGLxjP-^>jx`A*A=+RuKQZoHGjq zh~8X8xW9R<N|C8pcz#oaZL@?3zT}>w>lAu@Scmmuq?_PgjvNKVfHjd1dgpf@nK-@& zA?$RAQn*v;jcrGGNHc%TC=QheRvWg*j~2+(?ATO^1JZijm@tsW)k}EMzjgD_|KRbp zx|JbPx1l@$vZ*M_07Tkf)x<KY>mG61&5iC@jJ7m)q8?vaj%=N<zeBpoC*Ixnzn1&w zz&g&fz4Jxwk#W`JX%i2lgA%j0(cmx&H*N{~iQ~I6WXtDDN=R2Np5-2`LHcl^*LFFp zbF;QprT2`{D^{^Gt|s$QTIY+9bD8KT!8g2yu&?%+`pVk;^s<p+UI|(PGnyND_*>A9 z{ubV3o2!S)|1&~?^0VkhUxwD~ymB1J5-lDAikhz1N>Mev13JIXM_R5U&3{+Rs0r5- z-*DJ<qctD3RJ492c>fOcR;_1w^L8#8+8JrhfV3ym7(@I4(T8JaoaBN;Z|_4r+ePwn zh0hU@93bz7#qgH#OSUz*bo7Q%;>*X$;QDpH82z}TA*LT!!1O(htB49n0Vos&_L2&O zn?J;zRQP=g+#}v0XDE<N@DQ<6Vwi!<=S?|(D{tWt8nG;kPtqIfVj4{rn0n;10OT4e zx}UN8))X7CdVlcVr(2KTQ1pxpUwz^Pt^1IV_$4gb$K4CYCnNf6ZY4Y276AgpbSfuA zPcUGIpNqPVmgeGo?=9lLU35P%-3Io{oi)51neY74Olken(bqC@^X0nYd0$?$ZDzas z@^-)WCNI1wwy9;pYbV>u0Xw#pxghxN&{}Eu+Ox_H3E*ekx7@#?Uch^V&|qV`UFu+6 z)qyp=Bi-X%F*l;f1MofXFGf0;ML0P)^#)^9aj_M#C?~09Y_oWUc*Gcv?oJn_qc-M! zuA(Lp1)%7ww-oIg!o`57!F$>ME%1;9cwmr<Lcg1h9C5d~%%94ei13p%{6c-|=eL<B z#q0z8Ro^Ldb1e%cnO`N>`y<oPYZAcTSTyt%7<6zmcSZS1yzu_~P2S&K{(Mz6U$gS^ z$5zr1wMNSZXx%OvcPYw|>AHw<eM~N}ls!JHPCLS#ley9^n)Pk^*2=nx@l{Fk2D}3q zw_am&RFnyTKBso-BNwwkz%Com^@RbGl&nku;cbrwX?gOdVXbwp5;TjwhJtG7HJ67a z(Jugc7n-DC9Jaf{yV{p43>1=X!{V351XtuQnUBuYi_+BWOE%c{s`i}p1Gr6oe{x{H zoV-`SEYfg@A}w|>W`f)Q=@l&ed0Xh47hin(5=?Jz{~SW=dw|EkytRrhZ}H0OMm+nS zBcl^^AK<?i=9lU34^p~QTeI&*@VLHfkz-gsXxvh7Rw(O&WJKoGJC{J7zcy_=+;K4W zHH_Q)$XP52+8!eMzTV-kvF+>16*L9lD5+)A5N=m(k8#GULMDm`nNsrl&R5$PY%1nn zK6z!o<F8u78EtKgX);7PSDP-~Sb`YlKI8)RBqpm!lTr7?QlLig74S0i;v30rc>>5B z6c`_ifV5yD0D>@fI-V+F^#fG#U>QO=zWP2{1_OU7OXcP>eQE|6Kf@T_qcB%O@dM3A z_I8JGXTx}pai7BQ$8eM-6P%NZ-bg;l;_>Lqkc;_d+WW>}(haFTn&w$Jre?8g!2Dyh z5guP)ZlLJK1}WI=;4J)d)-FF&R*Oc+A=U;HE)S;J7h3)Zh?XdlWkCr)MjoxuvtC3L zUaO9QF!C<FyG_aYv+2`#Ft0KoC|ga|d#o99z1gu&_-)X9OS-2ilPz+lc0z9lW}-bu z^-X$ybl`4S6+3q~<C<VF=5OIz=F=SzBI}-YU7Qh?E)2-o_3?$v!i}}3>?Uyv!axu% zYH8%zNURuU8i<I+Yc(a`97~TFKs?Gz{f_F(D}@FqcshS<D00>vb&+I=`iB(Tt9QW0 z&HkGS6eBBHs6I_cIH(n80GjNlU4Trt9tBnQexhhTV44me1*x4~pP;zh-zmiq!Xcq8 zNd{e>t*z4h<ShOu;J=cibK|~Ie}A3{Kft5m;;HS(d-g>FPf#Z~-5}6u5>onLYwU%+ zZ=boU-5z737g&H|C<k~IJB0G+Q(rc9HHz3$b*KJ)ezEs$`?OTu&O6yow$rjQ8e4j3 z0~aZ(p2(mewQ@MViTZ6RwOPvL97=)l%3N?RegT`#$pl_iUeC4cbo`mOh>)M87_tU1 z2XSYoH!FPIyh6*Z7Jq~_z(XE2!S=avw0K=pV=Z|BWjX`-QGSgKD7W|Twr>(X8137v z@ALXtoG2~VE${m3xqC)MEH97t=UJa(U99s<dWuXsyVZHERw}PHUs#ps1X38~Yl?F? zfto!@Aaw;`D35?}lSRC^7bgw(1BW1~23eqmVEvHL3?n6>M7IgDm@hxWhD5Q#YSH%Y zhV63^5VYKSr7h;9?2noll^{Wuqh}|_#4|Ls%p0*ImlaXQjfleUmcJ>GZcdG8p`KOR zNRvs>P)}=f#N&aHDfN1uPvGIa;5;$ycp-%8xZqr<@k{-M_Vgg<<<!Rbe~aRI@QsOe zdppO92loBQ=~g%)$ww@@rc@so%=qUB3-Pbg8MWPkgY-X&68EM0vYl6$VlH%nqwG}9 zY^4^{Ux27`{+I>RZw1+7EQw@3M6HG_akg@hK-}tB^PNY;0yOSo?LdC_ylMm8_s~>( z297c)u7HMqn_lRwhztn>8oeGv24O&eba<4OjO{7)GVM56gvUIGZD!PxZVeDn3}yMZ zzn(}GEg)|YU;bJYsSo){#w6Xn7Hqa-h}*9`D)Y}Dbl=%-&J@_G*Wl%0yQ#6;$(3RN zeQqaoqYMC0KX6nOtHcG_W|&%;f4#F#zt{jRMJa>=PqqqS9if`V6?KlFpm)h`D1BH3 zu%d?V=BDqv+MlizxaUaFHFRK`ki-a#^u<32ZmL?Mb#EXG-GX$<^Ucw_!U}p~k_gk< zfYn&bYXI#Fvh}fpHK1#_rNJQPWB-x1q$SZk31m2#=v44w0I|m=K@3l1VJ~U={N^rU z-R3CbiTw14@uT(bCU9QzYI(8l=i=wH`Mcd&Zmjjii}!`sYUP%s<}nf3W}0|0#tKa( zWkJmi5`dOZ8l@s#5j$iA%Ozt5D#gKNn(FcpZk__A-H@snvRUH%$^a5FDPp#Q1C!{O zlV=j$8*1t^9c7LfRop6iy9W&%=Qn#tg~{C5s7GKwsspcc(Ylbi6nU*^UtB%!6a?3n zykziC0x#2SMaKJ!O1y2s52UR)6EmK8C3N;f<zXe>c_FnS9cM#iFuu6ZiL!{}h1j<w zA5*#6fdVwN`z9qM%=@!p)g&Q=y8S$OaiaKy+x$g4B@vabOJCro8(`kzCN4(d3P`ul zGV{eFXfrjAR#Tb#oylTs1XW>^@ive1Ap`dcK@^HFHn#sM8SNQX?@M{!8!)E!;jR5y zyB_}r`VRVjRMWQ&T=9!^4nR@N;>hirV)VwTKKT9R1aCe&hY--xpVR9c27veXcMrB# zUK)~HB<8ZCLSosg@ln&EGG}Zs{y!jmRXoL;-P1P|CSYR=xS5CDMF_cbffc<}^+g<H z#CkV!jSxbZ4Uxrcv!EA2yolEB&i#p|*}Y@Klvl`)e4ZqJzMI#X9w7&;dJV{1-?~;^ z6R2W0?r_Es(v?0QQ@#Ca<ezR)hHL(qT5)tvO_f{tl3qx}c39cbt-Rw@k-HDN=uq4= z;yPoaUZ!hq0Q4`a*bWSlcAUuzHr=DD-W2-JUdx0g*Kx)4t7o4VwX<Cv_xR+s3e0!j zkP)#j6SHJCreBI_4az2yG7f+g$zJvVdRJ0PA?}kn=Q*O3lY@?WAFrZa6lEJm*_-rU z<Vc~kBZDELof1xa7Y_&SU6d-@&AQz``LJy2{z~~LA>0>8`0t;-LZX^<JuZ5$YJE?9 z?xAjoH;X-@J3<t3Zdtag!@)IIo=7JL4mw=A{^sE;BUjzY+-Z@;;${bbm{FxVbC4`S zEAOhw=$>Bc^kcW}Nt9h*@s*0fvLrq+vI+ne;kLVA9O0^|2j$+@zt!v1eF<H4S5G`S zt8^?y>Sy|3p2mms3zWVnnJWhM2;qg>_k?h#u7s-o3(9*xFibq&8L=p|60+k6!EhMe zjrYEMe&C;e0=9n3IJDnqMi8jsqwjY2{N-kcig(Px()=T+zx@~c5IDDschl*n0NvD{ z&sG7UbgWt_l;OUMYYay0eT1-_%*xKT$XV%u6WD}{odqC9{F8-JWtD%TsO}pMu2|HP z3$<bhn?|UQl8gc3zQq#tEL_fV8X=~5Umil|Mv_5e`+-$4jr@^)yuchxJV%O=wcjVJ z$5G>^eeNeOtIanQzb4{-dleyP^UGkq8vw|4@bepq#w0eAA{<N<HvQC{9&bI^q9}FF zIv>Z)k1(v5Ve1gnTu4`4#|-oM1zs)JpE=Pg0CIjKl#&I-?^Hs}%(D)n*_S^vYi6|G zMw9c`j1Dhko0vnZ?9<#w(u_2r<!FNj`hovVXkYHDI-M&<&;&o{8uZTG@0nrzV|*tM z(M@_!2}r$$W3t}R^Y;r{pGBn8L1Dcah_AV7Vw1UtCtD{zeHV6kQ;2Wz$Ao@opr^8t z&#TwN*T7b#>}O!6D?)UTwiM5{BhsoLWlg4K`Mo!7=|fN&p(Hx&;(*1aDJ@b2R4aw4 zzNVI!b*acT_i%Fde+)^(t+az9X$MI|>r>gg2=qSyGH<R>ZJVq)m32K$%%_#PwJo2= zw>f{u`101xB&2PHwaK3|!gGS|dy1$QqV;tP>b)IBl)5YAP<;AP`}71veV)CXWofQe zsdeH1QFP|fQ2qZOzq2u87-Q@j%rJJc3!#}Y7((`4jWvl<mbB<I8^%8NC26ct6eXc; zW|C~xkfeRGl%$eW>Rb8w{dfPm=bm%V`=0xHy`HbfBQ@_N{(kl<W^M^Y;Xr3SaL3Zv zfg2DY1P1s(Ef9{!>+kpTTkUHg@1{Wb1fB^}!B(HC#s%*aUU|K<HhT!(k)LN-gFrVy zLPl6;M2NtJJR|Xl&J?GaYI;p<{}W8_nd0iEk*nLug}7Y++$uxJ{d2<oL80DJ2J>N9 znJ57kL>o5YjV3tA1nVOX0f2vI4)OW9qKn()Vyd4x6ub(7k2>?Oi5;jL(CuO-kpjQS zhRRsv?BYPPX$H@<95pN*r{@t~f69v!pe88{gR9#)qWjkROofU*?}b~g&-z{*7|Gcz z%yX~JGpzvwBM@M=JezvYgP|KV4HvG<7V-x>U%>Ar6%cN^w3&gvK!EpoXkgWnLp;AP zf|D^e@gT`Z#$2Y>Q~S>g?eQz_Y(JT<NxdSoB3B>gk<8xwa%WD8!{LB}7gpx4(Y(GI zqUjN+=Elv15O{z^aR4<tFoaDJ@kH}I&!(=O7?O95MJ{To*x}eaL<|F*JzKiM2F}#* zVHMLV4&LZ{aU8Mc39-CN8r6qz_<7qmrq=Rnd8>$XwETAkE_gQQ@5@JF6z;zOWW=;q zpP7$jm%oJ+#t-LOxYHQrjQQs;b7>N6Q<Ke_a}5$RuOH72!oj@JlZBgb>%MjwP+fa* zjMT%ECZ;`Xdn&|}s8i&_QM;#tjr7)Nm9JshIgOeG%J>y>9_}(2v;&|vM5a0&;>d-} z{DL=^Gu3F!D-p;~YI}^bN@_CgEg`@ty4+%e^@eb{-N>I4vSVZtE*{nOWgtJ6n_i#_ ze@)$%889vC2CmV3cA5ka0I*;#%ZgmROGbvMlU=U>8}cpEI07T9u<%D@W<-jfP5RU+ zuYR14+XmEtr&GkYcAJ&=^<uxHur(Y5Yr+Gi!O;A!*@D$_iLr+g7g)_Kj-!aFC;}60 zD_(|kt^_dEwl-c}40CQyMYrZvhSp-I#|nL%7RN^#Hn}qzY|cR;$12dj$Y)|$dZ+F8 zpoUCxcM8J3%d;WVNP5yVwdi?&0(dvv7lgh0*r&)lWH`R1?qVd&sz$;)A>b*MAY*Q> zpon^ncDqRBy&X}em_Y)@_?ObyzAD+fLSUqkNx$?Ef5*W5QImpeAq`ElMLuUSY|geO zmOTfeZU(k#huF?ql<BaPZNcPUjz#Ueaaa6mIVJI0TBEb&4z?`gC1!O;$#1%<dEE5| z-k=bQZb;ATULGt=xQqkN|Lb*W4-Fgh6cyrvJJk0MrEWFFS;4fY7w?5-JlWYb3HAa2 zBmuTp1!iTI<C6fL@oAwL`d%NAQT%QT-5jch*ca@s^xa*<(w>D@YnM}e*nujrU1m8> zKG2+GZ%+1Xp-RL*6O~PvLbZ67#oiufJxI2r+4(S)H+FuCR`@g*fwO>YaAfE2!p)bM zZ*Gn(oK#I4=N#~B+O(Bw;&p`F4AQD-`n%3JTqpIqsNge;qhCR81NL5|?wY$5Rh>|@ zCo@|IfCdw*hn)3`GG%5%l!G%Nge9ooEL+1o+kT0u^%gq2x>p|7<!+5DN*TMF@`81i zZ5IOeOyKwnCn^0eZa(mx`rnH`MRs>zy~%&VLan_ahK2%5v)qkYE{r~EB5T11>5D1V zoV-V^i0Tb6)&bd7r~3|~v1haK)pH$g(kIZ4R@2|lZ!b)8E&-w<6=bLYem>Br5WN?x zv3MH;&Ho?!DbXPvKj*y!^+nsbCd6?vnPM?ClTiQ)8@s0Hw&u96nm$$}s;0KHjJnxX zYB5%a9{Kt}S7;s94Jv_=@WO0P{u2W`35DWM@S(_1awE%*15pt%omN|#%UD+JAWfB8 zYbv6RoA<3kp=|>^{eUwTm4A+A*}OV(8BFg!5zFCT?K$E9>q`FaANg5GQ3wdAV#AL- z;q2){bGoDabmKlJw*;dhmYLaJ)VKz2+3XT~&k{5sq2GB6UtN=}Zwq~#Qr%xexP#c& zAey7;w$9e^sayL$VRMs<RCXg6h%p<IVTa_Mojo}LFBy$*u?cO!$%YqgS3x6;FS4{V zL9KoeO{rKQWj`mSt*B-{Q1gC!&7;ma1)DRGSvknCn@)x3rE9ad6>Jk6UT|8kO^ENo z^BR_XU$dY8fqLpQ-RUx%3lCiKW%PQ8US?4BEn;N1gkKHI)VAzcDY9V9S%T5U${Mqy zgJa%JJ_FMg>m-0Bmh&t>n+s0}3KYJAd#&rV97<k^m0Hh~SLQ(M+jo}(fL%XWNes5N z)vaoua#xMzz$4o>9vG(>3R+aJWN1B0{(Kp1)R16$o-XCykZ+`Q<LauD{tzd7n3MD4 z-k!}FPA?TnzWcG=WYWuQFXHh*&hs;ry0Y0>sFg#Jp9r)|Ea6Qz4_K9<KH;opA2<>9 zLec2{wb`5Jv8@BG;na4BehoDDl`mk{k-fyaRm3T*3Hg^ikFr?)FCekFbvydM<X7J~ zp;KUWTb7-uuiUo6n#*!}_sPnK<;FmeG-7|*E@(}Ov-#jZJk>_p=c{|+OF{kyb@vKI zksnD**|gD|420V0uy4g{g(J}5ex@}s+mlz+^Qp8aZrbF_xsg8hA+zjrLZ~+v?3RK7 z%Jf(7K|Qh$wBg*g@@Cg7iHiyMr9JUmhh=w4NY#xl@=K25;H>od5Zj<ncTL98o7cCK z8*SFPkf>;g37vs&hwQPa%}%LsJ`U2SL)tys5N)*m!XriEscfG;#%O=*i+kQ(nkj0J zym!iUI0C*BbMVyop{*ic#e3;<#@eb<oPlh{ZXf2Ihij)@vc3CX1nmvTKT+-7UgQA) zA^O=%hS_HAEFISuFQyj@>EDWKQj1htPYrzY7hVg$$kL@lckRcM#ACZ^Bpg#3Ymg<< z`;voAN?c^~xU=xmlnD3EPlsYEDia_UG={ex<O}9|EhjYgTK@kw5Ow#!--oCp9gqGk z$p%ZhYxPPI_P<4y`Zv@Fy-^uu$B>>l7%>EFSj+B8hG=wyO;^E$Ri@o$!lJiI_^s1F zUaZ6R66bW<AwEkoy^BAts?@J7qWy)bn#fzZK1>rM$D$9`lMTmC>{#DS4z%~Se`P64 zMj+P37Wd*Hcr??g1}xXjv_xO8q_S+xAW8|~J^SF>a-UK0-!BY;xAVaZpYzgQRA|aZ z_34vsWD>&kjQVGH6jF_<7F_y(A7%fIzM9Rr$XhcVVFq_Yz1!LNS+MKUpNIP)qDhud zH{Vmt_Dq0=a<j9x=o%`}-Xs`OL51<Gi2n@UyeYHq9b)`Oz<9AQTmP8f*)HcAwl){y zw>&u&3O}F!Zj~2*ar2E`+x*8cc-GI~N)ZryIt4z<++hx}+0<w4iC{60ftlwjzOh4V z9Sd?xf&e1RVijV*XQt0ny$>+Y{1Tk2bSi$sNp?ii+rKtR(3z$o3Z8Jfi&Qqkt0JWa z?My~uG_8EvaWP~VW*1Z1;3#3VOm|O{XUEajyPoY;od<L-c-8wg+oumcbFaV?oE3WN zVh#LtL)lWOv(x#$NRvtnmn-bisWEpQ?Wm#vv>%yTOtk+!nBYskQh+A;rNXB00O#fH zPvxQzO-BIQI^BHi@L6`2;zQr9frYv~09LNhmPEx2W8QW$?z%!Tc6->}2C4BfbgTGj zZd7UZRkB6w5ce0jtbjZNTmkyQz?dcw1$b^Uw06dpmwHqHz}{|-P-|%S4?ez>M`jqi z`$5eb#gJ?jFD)QNZ1?l?>pLu2Q*(K}-4yJnNz4U5fj3}(B!9XiU<*`6O;=m~_(*?W zmD<~d5ry!CQn-Py?;<)dNXKfFP->g`#4X|ojIJG#wa5*Xx@BFZO;;dQg(DDCN?O-$ z!2leri&_>5Ecxc{Wlz?KupE%68k?Tf!$Kc1Q&Pd^TL;CGlL6qqYFY@0fpR`IIjpu{ zKXzDcUkg85tu=2b`yeK=C!8EeKgM<*R+RLUmD0K1Mz%G3?^6%Mr}<G}$+)RBM5JEB zx&Odw?L2%aSqkr#5CzvmZ6-7Q^-7JeWuxmtEb`1ddcj0pWQL!sHbc6{#fYp^!*dR6 zWLHx5MJ*|Y;EJqg@LVFuEeCN8M(1et*-jPMZ3!!j?#{uD3lmqwE+zlz1o@N}>C_Tp z_jfmD!*`DO4y%Rh#!9Fjj1YjY16&YY1=AtHucqZ2oKeTPN0p`E)g}GVq<#ZTJ?_@( z%d;pKy~zel@<OTev$!4YLZqd!zHe0sMhYwEQ-}7YzJ&sM?d!9-h8={v?z%1B<b0J> zx)6>DORzu?0(6#e7xV+$eJ&~=`d-R`rMDmK+^;^z!Ft#-m4N}J3J%$o1?5EEd8ZOn ze0M4{hQ`@6>B~iTevg7~OX7p*SSiQxkZt>wr*q<uEQ!hS0T-fNN$0PThL8t&IbnnQ zR?l7<BxHZ^x#^=ou?4)>gQji*)8m=*uVpGkB+1%XGFfxsxF6(+^~-_x=S&^)baQ&m z?&-ngD)Y#GURTNq&O@d7)@R7l#L?hskd$6ak~tJt?+}7!b&&o3T-171=acVLk`33& zg?h2E1>$?_Q+PX><{v1M*Y~1ab)}l<NH-A~X*8lz7PJ4{E!S<~-UhWO`%d2+wIfD^ zVKrN;s2r7cgO<aH(BPz@3iPwIMqCID3^e$l^#I(F{N3^}c?=X-*iA^a7^&CYff-la zT=3SUQX8yR<sRy=wRz!qWOzG9GMg!rB_g9OT=W44A*NNt&`gZV!-nZ#+G$Lzt?x}A zDj6P@A{!j<ikV+r$%|7(x}Sb`(-|(5i?<c#N@>BHM_X~tvwO)WzL%<yWJ0ofo<A81 zLR+uXWFb=|nI@my9tJz>69m|Ao0?-W6b0M+c*1Rn%QUS(M($fJJ4mxEGqasaVYA5c zIJlq`8+By=g{LszD+2aV$37hp9{2|X<ny7~hG}@C@DF-=HVK(p$GJmlf_%LVx`Os7 z!qT&cW#V8+25|Q<3#)nU0D!3zG11`Ca<?>{I)uRE0W@9deWcup&0|L>a__n=b471u zhq)Y8-!)~M*HrV|11wpgYp#7g9&Q_Q7t38R24=5jz3{uM_8URBtS6mzZr`UyD9h0n z^LU^Lf_A7g(M)l{M(PMn-mnghh`w?p!H*+*3IIxU33j@_V$V9k0S*^k35Ebtpl-Wd zl?gl|MaS!)ntrEos%%}tJ^6e<DqDJw(@7f3z^^ecQAQXit94KDU5Y(GY0B&pL;9?u z@COVDMm9Il!54p(b{DodkFzwCzFvXbDKr-B4Uofo3eH)bZZS>yj=U<|A!+wA(0r$% zQ2DcMi=7on(vL6qym;vT|L{t{Pa|j5Sssg2Mbe7rZ!+XDq1@Z%)4N0IUSjN2D6j#N ziQ)?7(eL?eGc!Wnsd_SJb&^T9(kU&EaCi3u`x{aqAjqg;q?$i4G2JFq|9q@TP0Dfw zuTX4Oi?NB?xjO-7RE48pUh-fzozaR%L}1+r3A)!Ql57onF9B;V<s}V9P;nGJ4Uo%% z&ei-k(xcx{M_eLEUkZ$m4q^IN6^Yo^`jep1f|i`Jo6G5L!TQYNRm3B;H2HH;yQ#Z= z<%L))te*ywSxP}>qLGGoRtrqB4CdMOoTE`!&%pAM=5$K+%({0-#|kl+rctl_mh#Ic zoTG#*rn%CT3SgB-Rw0+kBmt?4103>ZP;KdJaCN_5!%_E6zngJCNb>g}E^54PgIJAH znWLF7!0$*t1sjNDaV`wv8Wnfk_$BAoxTn1V@c<DS=rg|ax$^gmP0oN&GM%Qj7x0CP z$V_x<QC$y~Srg5WEkW${l<8OOvsqb!o8lm`Qd^s`hCfapP)R2}=7*T{((e{JKHcnP zLv*+d<SFMP`GL}xnf<m+2)pFDgov238iV_YJd=`Lek={7VXCHT2$dJX{p4f!d`fAr zg}R)SN$fx-cY~r{Md$1Z;271<-Ze-|$#>qxlz)+3qfz%_D0c9f;YwgFT4EB>eJJ}P z!o7jgPA&Ugx1=5SDK&INv<Y$JKT+v!KS+{@QO?;BrnQ{byjRs<Qpc(h^`lo#IT0se z*S`lpzbxJ1{@2Y0-Uv%tB7;HP?G{!HSWjDe*Hs$vwaP=hVx0K$jrr$WBnM#RP;q_y z&a&q@(9sj*(ZljKpU&_3HTLug`*@^;lr6Rq)uP{^BNTGf6W%H;ejoEa&qHjTsPxB$ ziP_k%aGy*N!oPipkn#?F`XEQ=A;kS0qRU8k<EIOgTVODx|1{@+I+w&oqq8~FHEI;s zxkMU6e%NO1p+d{T0U$wjh$~^cM1;pB47?fgff#TYGlm%pUGiX<aPh5n$6spq?zym8 z4@wIGZ?K4Eu9t1D^x-DrJ6!8!zR#bb$mQ{O-gTABS3Mz=3w>q-)BxG;u}zun7hEi! z{o!~dMIqhL(7-0-m!I}cn6jlvxf|fTop;9w0jI_rkW3fM_knu1lO#2zuf5!nCp5S# ziC9-8uKdjxV2wi@lk3@tNLjJ(JA(i+7es6Y9pI2+J^%{60_EQNK`u#dgFm1^dGHKN zT?ixD`aJZSPEDGAB=dsGA1z^&akJT_tx$;&wsWt7`yZt>P!!cn^R6vZH$mpffU33K zh?0QR>f>UVNj^miBqcD>)AXZu?7jgHk}>)BCjmMEgfA>r*mA%QYf`z2Q<-wO?kGEi za1(ozj)e;&%nPQ85s`}HKRJ|Hvm7iGq&fn69`XFyh(K<g80AH~4ooZK9xD6fsd|E> z6F}poG*YYp$zf>sXcU0x1@2|k^@v9uTO>Ij>RY1dfR9HF(Ycc%TRbESCW4@EjSXc1 zg7B0<VQ>HwdqAjVC1>pd)&qo?Qw(iSvZ2b|*-znmX)^INp;o)c*Z$zIX^I4#P+x`o z<t7LyWNPu>++I}Oy;S|ZovL~b{}ao^iusoT@;-%zeJV9H1stesh;3JZO%ou^aL?-> z{2c+wwa`_28810(O*TWb9;w<Q_*1x7=P2WYoj^HhE??b;wBmYmXna%Nr;NNHSeeuS zrZo;)qok{v3>t>?+@Yw3Y3Fvf(bU}TrlHqaD1|7d(h6hzkCt^PSdTBz<S{e>qIQMk zk7Tm$2uWrMq`d@e3m{wj#ZZahTlWO|SeFp-S<k6zcW%tKEBK!{u(Fu0rUdoz_8KB# zX{XrpE<DNvNe&Ad`B1t`Cr>`seOt&(yKi1{MX2Ed34ENE>%~w@VeE@%2w)`L9Cng^ z8^xCN@EJpa!f^9oW7sXuXhB>t<xB-ZKZ`AMg)UQ!ITT3YOP|}FMe&3wdtQh)vLovy zkgzrRN=+Wx0ADkJq<D&<`f@~VYnMU+g!d%tK$)B96%e6NsGXvC`}-MFSK&5k&=K9b zY=SV&P$pv4^Y2;qzm5?*se1Vh`s0xiY+<Qp4Ok<rsM#8MjL(=Lx$gQTpOdAb%#kQ7 zth>(LO<E8nFMwi-_HLuh5i&@F9FQE8@uq@uiA0KV5*!HJm)IKg=*erhqyQ2(+I>rB zK-YEejwbN}4xPog_qTX<z2gjWwL^pl$I6tn^nk*0(?5?D^oLc&s5I+R{1RWADqIWI zd7b4Ff&=4;)ru=bwH1aonyIZ1&M;($6hrL{p}~Fd;I%^e!gEE&bw#J3Egg&0*>dcN z-pDPz=vI(wFX?_9Bhqk4^DHQd3flZnqMe+xS2;o;=^;Qm1W>zqWNHQ3jH~<PwVcDl z`Imc13rLi-I)L5g@q2HM2StkOM=JF3=$~`tCbZ57^ldxdQ<yXT_k#x12_e}A2`;)x zOco6s;9082tJlSmmBVzDUwfqIz_yA+0#vB9#K&gB@C2roEwntbl}bDikrgLPe;;)- z=I#USsyVpkrMNKfnu<U3;cbkXpo65W9F?1Zq%O3Qmvf*V`KD!f%LcCMDLB}UROVn@ zblD0KAm+p2j}M055(N!P&_@PChk4NW;_1d5XtUvvq3&7o)*7uKz%5{TcbibtlNAXZ zysN@g%52Wggylp~H?v=c<|M2rIe~T2@c$?D_Fo8DdC~B|5bs0Q#0gLnprdPv>Cygw z152DYYA-9W_tyLFg9|b1yX{(;8ZW8p#vk1rKDt@qG<Do%VnNt|gD<Dwx0f>1PJtHR zdXfLgUQ8z~s}qzXNZUI33JD~Y2u5`T=}rXbM#kI&yP=PfehL6!tO80gV_-OQwX<E6 z2p_jmUQ=R1vfXlyA-hbGeW;ZJ`J-g4yYl#xG;ZXcuR{{A&_(eINq-}ptS>a|e`2+s zNO~!C#{`T|5TdyZJoZEJXQ>dC4_XOitTbrc2HbUYBs`#`{7Te==tmDeyQrBL;HV_2 zc92L7xj9V{gY1W@@`on1^3-}6D&73P8is17Yt~p1+1tbu=a<-$GoD3C-XLi#2s9G} z3RW&PDWABZP2~QAQo59wy#XW&s5U_J)l4!>aflbz?mU5WKh>7Q^g(cmV#DyvmiRgE zZMecl6EHcvg7f~=XIwymE?T(5QMkC~M%pk`zLc+x6>801Kn;-y*bgQ_mmUszXo;4W znQyT-x8oI<TG;3Fb<hYImF}VWD7f%nCn+2^tciu~mHQH7oZ~V3_%8t=uOJ|jO*@Vk z97vO>!U`(;>tBzA{rpE#T>$x%38dhR`lIn4wgR084KKC}RNkoE>J9o_G}QCKbd%3y zZ;}%m^dkjpGXmWqKt2U@-goQnONH44EPln1t*vrbvr~8^x?5YnXe!{67F0$PPSSJ$ zuNyPrM(ogueI!cvmQe)P4PsEt05n+o99#NPii|uja+;2TclDSR$d(sn)-dcbAgq4N z0pp$n^*Ng@eEA#oKeVPaHw2n&lFA=}!YPpRppml5++Yh1dHSoRX}j~v0oDK5e?8c* z*HjGahW<4TZO$REsrTP1u^+!W0y2W)J2@Gsu@Eb!mZv~tqWYB=S=n!Yy6%Hu+mb2K z1;|GLy8p_zQ~nbkL*t(<$9fnVr!Lu_q5P1>?W@<BlXFFxsYDSVo5r&-VM@tiRqXx7 zP|3M9xA~*wD}bE-bY7)Ekw@D1J1+N#Kp~c-ybj2vm|q%r4N-si7UzA~3IthXBm^>I zi=hWw*+-Ln?rf1<fJ?bKxnLD(yXtQh4=OccF9=V;QuYRGzl;tpWNL;$((S=oKJOn{ z?a?t3=Ai_H-o$SsE&7{F_$^^<Y_n1V2=}Kw($m_5C#UAPjzzoP1%Xv7Y9gm4!fsns zGoc4=PF98Fsnqb-nd{fvhBsRP_wnbQfi~K=j4m*`6w*K_EJ>-wluAe-g;X>svE|G_ zMT+d(_LNW0zI;l@P<8Gb6bIzQCrE9W09KS-56bE%-llBgknJvOljktp%WIh{h2Lz2 z87@cvD!#^hzPG-&k{09t4bAiul5qUb-#F~aSUIfO7Mqh4z66Tcov$>_(7hZ;6}`Qy zs`4cE!`uhbwoIFSyIei6CYs+T-M9ww9OQt*j{_V=e;ZM*Mi6INrX5LANnjx9$qEi2 zqv)334<+V^T$k@TDL0XT3h2nIK4)9QTzg83($HZe=+*CHS)1=yWp-@63wxtpp=}8s z4#HWH!xfkjz@ni7Ij!J($(ihLE2+55)e<naTur9S2E2_+!X*W3My$3DUqfv%fpN^p zH^!<R&?gRQ(Jv?E7U*#<<1X)gpD)PoIv%!3j(Gi&FNoXz#ciKS{9jq50!b~?eb8p= zMjZpGB2eI`$)u1hjVKLeedL#0UN6amdK5O3ZGC6-DEj+kRzHO<YW5g9d?u50GvF(O zA|!?vum+Eb5_R~bCed=R!fTc9jFQcbw0--PUCll+jg?BDoH%DWA2hB3WoCZ->Ra(s z_r3tN!dLsFUl`G0_XO_P)M^g`D=h%5LEqkkR#=59c1Mom(eZD7yaCZqxpu+z9HaQJ z59sAYIW9xjkP=^TS!wBq+|7##+fc3@8Dus|!OXsybzgcdnS4rjO6QvM>W|iaLwwsa zwh;RH+!MmoTwO`#Ov2C7+g%3w<V{V^N+{oDqAhCp9IVT=Q;7<uFIIp0XNX@HC}gJK zvCn<=!-|tEw!wE|rv+=+|4{=TIQ&kzIs?K&1;{@j<ChYeRd!{#zF8FkTAHN5J$`^= zx7aG!jHv22ozm*z%hjLEKWloxi-A@FsV)G>G|){a^a~HD>(;0}cB)A>H?#e#4J)&` zj<{LJc5xtbv{u}3H-+<#9=IYcE8)SxbdpG*zuun}_joe)&)f3KvK_(_QR17p#9%NH zKQuBX+q<{-<_Ry7dcSp4@5tqen??0{wAkL+X@Ocqyat~<-&%CF7jzAo^}HUGYofEQ zm#<_tqc&1RmWu`QhBy1kS@9-*QpO}5FtC+9QfqmsPy_V7H+UQ2#{%>Jyu0|x{Nb&7 z%D+oJzlxzogXZqi(yt&ut04tEQSsO={dMylD*f6e-pjL3h7Bt?Sx*MvYCDBy$%TSu zHI|4AJO8bKp#TE{lhSI*6%*NT&=P(f4qyoW(<+1!v#4Qqs_juI&P|(So3b!+AUaoy z9-BOaPO@BGRI5#%>XnOT7b&TSJ*+rTt4mNdk8No|L&UqMOsVBZk1VevkvjV>0sTxE zUBMu%urq<g##L|;wPvB@RqBXV45%}18^*2ZIym&Es74F_nnA!MqL+f_p?y+nv7TJC zAmU!Zrs|H2KPpFKN6RHOz&H-Ak<13nrp(XFk%-wSbxgouFL9a~a?a+J+Eu=5A{(le zw#|~qEL65xG3l0Vv^$&upY(f=b1h0=X0O=3*PgdK+AkJBB>CgjW{5tAt2sqn^_|x% z3{qXa)GSrA%YK!$!I6y~FsH1#>;eTPuYO>J8JMrvX4aIgI+&?N=z%9TA%Gg%gh|m+ z0H+il4Wi`?Byx-hHzY0`+<wb*WC;QQmU65Csc>U+Mp%pVuu5Eg>9Cr!aKd5+==Z{y z^qNt4zQBR5-dVU%x{nZkqpL*YS_&IYY^nDfySJXQG`6@*Oh6KHh)k3{N^5gOyRU7& zopAp-mxZz#ZYLL)KCkh|Sx-|(ylqEt&PA4gJWU&$p%`bMjYPC_hiL<t@AM}>x@lJ@ zbZU;N+RFixdRj(C@)#;s<D|Y~j!&}|lZ(#P@Jsf*#14Uf2n777Q9}$5^b$+f8;ZNf z*5H11*_N$dH5*;@s+8;W8y#J;Ys(iu+7r!69>Ie|T_|U#k1P+vu7E>4lQWN-2k<{d z<fiTKXz;;z0PS<6g`{EL>tWYAZN;4zwz3meAX~^D=4UJIBIbjTJ<X=YVN!If052BO zMRL%z!1$852_e5RK6XJhjH@NpWt&4L0rolxc@o;%mBY%3tD7mfnq3n{jp3k?bO_UU zWGQ%*>8P~C%hm`pcbTmr<A}@~(xZhp&#pZ`1Orh@9A`y%^upj1uj}kV)Paa&iWrWz z<8PX?7Jil&Gu}fioA>Phs1CoeM1JngGv7PXcwzAV7L^S^Yb5BCEKisQTGrR~&usye z>yf$}gIY*~y&*)7S;K5vEHGqm*Qlcb<w-FrYA$lF@xiq3D*L#q0NOG?5GTJ5=0R^u zjD_;{9*@5Wf|2bDm*$Fgy$(5uuxrhC^8Daj(s4_DWTd71^@%YS{HvUtWB28wxK(+z zpOK4vMfm5d*Hnc47DEarUl%UvjGEhqf%(rI@-sI{2=gWEtT)1LRt$(Va?~%;jd5Vr z)pGQG$1MuInTPClB3m(H8KL7}D^JwpUS&%G$B8Ureu{n7t;GO91)p=24guEr=G~9s z$V2DlUcHjGaP*h{%6;mr`ES*{XOd;G#>@7PMI=VVjQ?z>aFUV>5`9~yes#v`uE6J# z$V4Hk4Jfml#vc-uYHn5b7~7i*h0hN-zZ&$((VpN*`r%lAw}1yk7gyhXBV?&!T#hlk zB|7N%OWakWgpw5?>7T$rw*lGGm=;!}+AGQ6W6<5GSd(TcL`YCInc10dZi<xq1SMZA zTsjn-Klzpz1O;I5M=r#Q#n`pd&60cEs4DK{1ATxdtv>YD=4oBncPru0Av<$)(w02B zM!VI>(Q>!NZ!MAsv)*=yk>#u}`(lXtU}@+8L3<LOF;;W-KM)-Swu7j*a9J{uN!|yk zcN?T^(T%t`W62>s&F}8qg1EPEV;&xr#$y?H3J@h&D#1}D`+Dah8(|kH6=kcfT70j< zCbf_zu|^L<L95h$g>HAZSM6Ls-%>1qt9!p~rbO(?i!py!aZ?ZNB27YO)8JN(c71&& z5`~AO9;-c6YQU?cCBLL-{sqtvQ*@z+@u7Ej`!#yo);FHrzEi09XTP2$P6}X#jrmFk zYr1~dL!O8gVA{(R$2MK0rAX}{Bom!uMWKPJg$fE<dAK4KJYG(R`Vnd|$p}!e=#uhv z^|Vud1ETFO_@xhUc1%_5tundRyGVTfe9y#K8m`041<U3c=Ms~*d!EvLg2qUy13X#q z+YePEI^1&}5~n8-hV~!PxjWz_NwWSUwRgna53>(C(hCx)fCSx|(>TDYGXw^G*c$DL z7bDDA4j%>-+RZ$D_5U^pc9wy4ja^DS;Y{K|5wsu@BystZK(S#JibA#A1`<S}H7WL$ z2!aU!Pm#0wrKA~42;5#j;o?smd;TdKw@rL@pBD02@oz(I&90UGb`DAp-mx?QQO<j) zRtL(+b*uLXXDhXFud#R;d7W8phfjELT=gvvM&H0BACCyPv}-$~9{T>-U<=bgoOU*~ zy}7<({46`u4Yy`o;}NhVneJU_=+Q2yI^qL0@OfCgW_7ng^a94v&-RI?3ng8@4?a}~ zAtN%$Du9@Y+%7QnOJOppKlb?`V$-79nHa5#Q8s!eB%?Hn^`_~@Hv9NW!T;J<ndx-- zV;gs`K>;TT;lOUwwu5w<Qfkw}t(vhPTA{yX_G|-(t0xKa7RE5C2{M-l7J{@%Gt_!0 zrp<P%MJKQ>R$3yy{9o4*@2@xCoNbbhi!WD=I=-RY2>gsNu!=&YX4T5tP}siiAmrQ4 z(-CqU-UVf`I9(>hNPbYP;O2^w*eNzrsG@;&h>Zwu8h4DMXAb}wI1lv32e@B?Kx%>C z=*byZIz2f%Inh&!FQo3un)@%}k0y8^)5%tbu9JptRn+4c0JQu|iew}?gk9LtUYgKX zH+-!Nf|~;%g}q%fy}JH8S|Qix%e)9T|8cN0d|mrLzuR4Z$f>)osn<%gpJgae#nZJC zyAY_45WBlRWfm2Vzucw$LYO+W;)fbHlg3}{B`+8A+1*?H)7{S$veMD}@U&$_h&~gs zK7m7T$4j}=n9h<%p*qkIK2%q69Db5EbQ>+mkJ}v?yQ3;hj&e*VdiQ3moqZKo%XLBV z(fTg?hLn_CC++{tT%Eb{aQq19#Os50B=P%s4YzL*VYAM)uPeWWeY<In%af*tm3f<n zL^%`&yg0TbPGc%0jY0C9Q~_5BrjD^e{Abz5A47jl71|~96R&59mZ3^XmA8#T7^oby zgeQ!H2&uW)@ZB*JKs#t}=ta5u?cgf3nZ4C8U9*jK-Clxo!tFmQVP@DV^mzo*oWDz+ zn6IOK)<7q94sVgv?Aqb@luM9<<M)${-d~D?&C-ld%WkmqO_ub$*|J#;NlRB^&d$(L zH;Gy_KD>}`8%EZh;qO7~E~ADUpiR<Ha5cb30XXR~UgzK@f8yb?R6qFqQL|lEbK^pu zL_Se6jQ;nf>7C_|Ta-<yW%5d$nB=6dw1ShGicb4+*#!Ji1OR|yjB~!uu{1ZK6|NG~ z^lkeDc+(8;w4%AxsPX?<?D(7HFQ;C%%J#a?XqYF3?7_^(ok}W*sJVMGjcjYdoM~__ z^z$(v$un7^;F=O;R&tB~!B9)QEk*`1lP-Dbpp;67%rsH=_Pj$e*YWv$JzO|ZBf0?< zPW19&3siU*UAj#ybvwyl$lJx^!)Y`SjfQL@rrPKb`CL-ImgJ=_(gi>kPDVV`;u{;7 zpf0(ppezzcpjJ{KuNK!#INHwmaUw$V_a;fBMf}=kv4s5jacANCm-nt!WY5@l+a-0G zqpsM!qsg`rk-vcrhp%=xR$&;|d}-nIa{IGWT!}~8GG%m0E)mM%!BP2Ii9LHBHp6R~ zI;uK^G2X7|HL0>mql~%nL9tYQ3UTYpPNYi~(xeiB9Gm^GmyuFqO~ws8XwZFBbmJXw zH!)PYyyc1*F6<7u7h;tUwfbVJf!v~Te0%4+zAQKNL!fwy_UQHs$O|Mtx)5Q()jou@ zKwbH1JC{_5LoLAU32Sx{T$4X*T3_OECsud<X)*h<p!7tn7$pY{a6x!t4oJYOn~XY# z=tyon&MX_5-;JC~G)Tc93pW9^c`%g7L!P6lo~1)ma7c^x+qN7;9luoiuyi}11O<0X zY@MYf9Cb}*(G1SSy~UN_0(2^-kEr9Nfj$hNn-pxD2o5@s3ngpZvuGVDn_rcas=%3C zoCAFaHsU`&NldnQxmaM|gi`xz3zT~<#M{sMpT@-uc$Avd$T<Fi{+_1O5_|OO!H7)0 zp34<@Ja60sj^v4Xy<lY35mn70C4jGVln-y=z3exUJT;}qC__Fky3Mg50%BMTJr)on zn&=|x{j|N3Qqrb|@4=Jo$CB?-a2QYE8Tb>8a128h4q_~rxh5$7RHtQi_th$iN#iWs z8y-CsvpIP+)&M7m0ovSUBarXaSf<Gz9RwVFusBHqyz%nt-gm>v@4$!0+_m4#dH<t0 z68!afMlvfcGQEHSYMs{yC+?OfMw#!)Dl?BVSIhu_G@b-UjJP7^{fkjmu1LMoqyIx& z@+eMed#rlCSlU0{x|Z&u>1->h^)~0K>w94w*4xzzfSl61(jpJ&j#paD?Uy1_-Seqm zd^PID@E_7#rTsosDW_(u2rAq)Hfwh*%BKi2G)#1U<L=-c5#bMKRvTDRbE^<-b| zW&P!b%TaJL{He3@txNxVIghO0deupLMu^A>YrTm|X*SOLfjA<YA9<d?h3OkB+!WhL zg4MSZOwh7lMN#TFD=DxI4FvcP`=%Asp~W-=N*47DY>Y~>{U8c??(3#kD0?3qXx(Yg zSP$Hfn0Hc&{Sc+;1Il^GWKB;Y5c_eL4p-gOzy2JC&JgwyVoXPe<v$W7XKDB|PeL0j z3)?C^-FtS1Y0<5i%RxanI0rXY`B6A_KvGBVh#x|7bV6l)ysGpe4=0V1VgmdvH?pjU z0!h~ZzeW`K@!$<a#BU?<@FB!eI?U{QS=*HzG86vtN#<DZ025Q~j0!hcldO5tb`1ZD zeMS|>YUdXLA{r!{Bp@f@Wjm8_>!ZK9Zci6rsW7laSXZPjD|B*`f?CEcW@NwwqaDlV zoi3*@tG!DopMj?z*?Oi2XcvR}6v+%RQ%H>PS8DC&9o+Ir+z6t$Rm4zoj476vjB)Vk z85a1^zIH$cF7wp~zTL?H4>voEcW#!5mIYlmx0<NLXq(&4q~ul@|BTXHZq!&3D2N1E zZ=RBc^eA|%`yOdRKRHBsKDl_@@woM&Ikrp$U1pY7*i!j)S$BYLgQwf*wmeKwgk+qv z=}gHxeegPR8mD%hCKbe!PMKm2@S;yWWk91<<+X@5I(IyWV_nzv%h$Gq%aVUCtU~9K zZh3w6(U0DR$Vs%?u26_OwC=o@FHm4b-zP)VQgFXFMa>wY8!10m>iVhws8<2;T~Rgq zlR!-*I1+>3_bM21&PRJjJ0&bQ;RnX^ze7vE>3`u-A<gTlk5q~uwS+cr#eU1^kJ5}s zKBQSkJDuH4Q`1gi`)H4hIimFbH%LSV;iM-NRc{&Tj*jpAdv{2ycBrBv#y*>6@l1NW z=}isMz+X%|(4Pjb%4y>7_&8%IA8q?J1GrCKgGL|5-!-~V4z!%BY?lYn^i$2VxoG9A zNo8OORPYqPPy5N1+*P{X*AK1}d@b-mNp|vHk#^$DA&;hav=YKXrt$V;Plbs6CCwd~ zHuaWTjK|cS7IU6oXNv=lrN3u(!pY~H{39-J5(&>9P1wt`|FX;}Rz|kDmo4lXowCax zMPtwKBs_6&vvia7!;qu6bd9hk-Q|E&xZJl*sBPL+`(rClw^osszcDMSWp_LlU9Xz@ zncpQ)pJ_Z|G^8XVNmYcZ+;2L{kWlh#L}gfO=OfQ<K~RHms6yltjS%*pmZp8TzP!l0 zkEN4|E<v^>^jLqiAp5k{8I+N=2WbYEaMFFi`4Ql#zNC@F0WLJ}W-mFGD$!+q{LPOp zWANvH6+A==9h%7Vr|QTiZs9R-@R1@ox~R$Mw@JiO<w^Y%byj93yu~@Jil{XIqfyg) zQ2nJqDJZPqu2|Ol@Xg;br*pXp3Y)XLpYnIl@K9npI%jKQ8;)~0$&e>6@!e6+iM73e z{qIbMyh_KT(6jPjeQ0RPj5GIKXdLqVh5O)EKbzWnzmL2|4s<EKoCq_TQsaG3euHh1 zaojFe2tvfiCA;hI*u7Q2oxd#isXI-j!s$a3>DroBGv!ZTK&i@BWG&F&+8806iU{mU zMb!MKTJyA8<1_xsE4<&CDWw^K+EuVoP1@-ri0V#MLcom<F-|Xsj|`wC&(LJKiS>AG zuh;Pe{$1&5SKSD-*;%P)EARWxZNL7pWx2h$a8rl*#l63Eu+u^-F4d1)v2CDsa=;}m zbMpE9j|T@eTe=*Jd6KA02RDh3L>wRc9QJN3;JKEq^%mS;RiMkt$?5O;ZG$)F-+B|C z5_(`x|MTq!$~(OV@7%z*KE?Y*;r)tm(iK)OF-@mS;&zTvmzq{0D-875wBGmP#Mo`^ zp=S;$IhT;YdauFH4sFvu*)92LXtMQk`hD9Jts0!vd2YA`;m?ui<t=vop@H<516lR4 z>qV@YusauS9KYwwpD>3f=tz3+XRp#rm{%|FPy}!pu2Cbo-!i(@?`CXKB~_ix=1xwy zJgokHLv!Z3#-EewV$y>cfowDgOrx(le40QdJWO8j4hSE*PJ>m^_a<;<f{3VD@o7N* z{C$IZj?rTLww>?3)t7I6`cOYU`SI^0<aiu{GbI_?`5GLIXgYRLOU|;%@TTRoI%3fL zIL=2sF1~+t;s}CCgZKfm+o6;aoGptE|5s<58tJU`xiWiWdrpY?;7@b=!P(2-PW=>Y zjfb;7;?<`G8lMFk648<r031dveZRd-VEdxfZNov>akL4V=e;qNwS6I0W{w7{3uMGF zC%+86R#*Q$l6k%Pw@JJMf#9lb<;W#Re|C7#=^oIy{_zfR#C)P>bBQUH&@OQSH-GqS z)2{TVZ@`~ob#Eb<lN&*^2y$+f?V^d#o$ukeKcJ!C0*&dn8cTSMxyG$Y8x$a_xc~?y z1L>+X+_2&~_U5qQ!II$3VmooN{nLACp)+zO$6|mrdE9I)>8tnaY43-)T_4qd``uA4 zN->AR3X@}f@raRg^tbot(xglFy@>v_i-5G$aDDHDcS<)`C|Dy_^sLQ2eZxFPFj{r~ zG8_JSu{!b{t5!pJ4n+ahNIX~?Si<AzP4BVJ-m|zR@iocFf91CcvC*=Jgf9)Q6wc+L zW&zyv63ste1^^`FGy<CA8}DXIKWTAKO=)tmRCxg4QoEb)m#E)41^Q5mR4xO&PfV1- z78MPG0jiz8i&O>6cMYHkp^Fc7oGLerk9Jc_aTFE~#+%Od*91;bKfRTAlfeeL-_B%| z!A3R}ByVY0P4=)u&n18ys26z*W^c;;*xB9JFTJ{v`fU-yyZ+_&o&PO=zj6P8#;p_I z*ME%%d%Gd!c51;9sj)Dqj{hL_!%-KV*MkSeorod~3R{*8)Y!agE5h2?_X51f=II|_ zbiD1;kjX8Qd$vDp*Pq#LZI?1-%lL(ws^ej$Y2i(0KlJFPb9c!8AQ((HmwnMFQLvkv zOpw!Z+v${bBE_&+!`5f`^4A`TrzNICr#;^)8b@Fx51^kyH5^3%HMz8czhByBNz6j8 zJ$cGL@ijYS*G79x&92-<mMrl1rXNerA4qv7DK`Otpn(gd08h!|5>Xo6`myu-lli61 zo5crv<#JK}-R5;E1XV&9S>w}8j9PL6o?R@X82pr?*xFdC8XMcuT9w&hg>kpgAgEJK z8(}UP`roIAyfr~E%yIQRNx)ZAE=o_1WCjCHs{1bPKcx=JugcPR<%aoBy_O3O)u<#+ zNu;U5%fjV?5<j%oFe#1u=y=yhJC|QR-s32Ve^;{WFJC}LJJje4r494D0qH)h6-+s_ zp3tl!Ei4;j4XAHzNn93~v9bH>g9zC8Q%CAZ*L4PlRre?LFc0{ZRdl&2tFtFv!*j+< zQ#HPNOjRc={`OTeI}I)O{M>|~%dcrH=mNW6797r$6x1r6J@y>&#NXc?#@{>{VqNnl z*m&c;T(c7b{xnQom1-V=1k;Ia*kdc^9-D0AD<h1_$0d%9zge?R1Vsi5S&|3v!CIWH zBxau&L{$8;ECmdvoMkLLv{q{wR=ckgD@t(3d?+tV?(`j2-6dhLE&_aR+(Y4Tq~t_T zh{z|QO`x<eJrwBPdPG%y0h>A(Zy=!>Jt31;9ozRp&hyLOV{LBUX$mlab$Ngy?*+6T zK9(?wsP-eFBg_IN@zP6yPLq;lr;nIORW)mpr0}hp)rWq6IO831fwq#sdE4=O>DyD% zI$*Y2##O*$p^R$U?<$?{?LOJ1qp|LyoN@1p_oO6VJuc!!{wKN3$If+1YTJwwKyE35 zz9Yj}azalo+O?aMJPVlRxu7ZC=J$yHmP4P89K8O?W?<XEt;v^vo<{y`U0EAVNBNoR zK~V(GJYvsH`RcE9He7#HUeKgf$qp4UYapXY`1e{D1~g4mz>hG_7{t_}(>orI?}Mh6 z9GZ;@(2aTKw)(YX47NpS+cNaf06MalCUqL#^!dW-9n)T@eaa|!?TQ3Y)bc1ip69oI z3L}?Ym~0i%J=)tY0l5g<PbC-Jm1@I5)rX=Iox``%fIJCp=_sV@EEtelE4{`T%1d}# z`3ey4GUqIm{MS-YIBccfkL}jx90c!KtGvvjzxUGI{95gX3(@oVJSthv+QUOtnLU`i z=aakUjsRi@3(u}rw6~0p1l7t8O*?C-2_>DN+ILH)yEP@h31li$p!g68@K;cirU=bI z646qw0i&2nznnjDMcQwcIj&1?rStrIIP%A$tzTBQ0iPt(X0D`uDWmtm-z2Fp5ywuw zNy21_D3csQ!iE94R`r6q*S|-qe4;P0R!d5DL0X8VoNQQ*!S)bpUZkj37a&+L3S$ZL zb8O|^r-vL@Cu6fZwc5#cBT>3$AOqiM5YlYPMBO~jFnG+bENM9a*vLKq@N4nO{wq~Z zwL{2>a%XKiEgs1sE3~cVsuO8OncdEt%Kf5C+tWxTI0NTh_wRM-X2j;-ZHz7l#M@HJ z-b%-pvm77qD76G|J3=ZUs+j=zS=zTVm>!J6e3RSY<b#M~{|hC;PGGFCP?`U5v2NX5 zQ3*Oj*Ps4O;mRtzAB!nP#4;&&APsp!81sFHe*=*`P^i129SU-n8SXawGjflmu4({K z-phj@=#Vr<L%;#gr=B;MWuF)@XkRiPKhenzQ19Tn&BQ8Tw+rAx2oX|fc3yqykd&G2 zvceeMAu`LoBx^|1!|aMpKBc_#fc!S+hdvTN)4ODXv>@089t$sOlwSL$bZxD}#H3pw z?KK5bczp3y$@=43{0C0x_s!+fU3Ei*(<7`jVfO?pg47M*Iz9V=Y^Ai+!h73jx3E%W z4aOGxDqw)AizjA{I@KikY$e_uqq%V^!zr|bQFu+Lcsb?LcHJ#NsQX;lwTRAWO-8au zZqf^_b19YDk0qm5ON)ITV9q=Ja{JWe%W^1^%yov*QCcD<e1+fctnx13!VF?w0dke; z+x?>H{;U3aP<;~DOHF0%iOCWl2F*L?mOoE%@NSW&OVD>d;N^TNTex$I02%x}Vsu`E zBsJ}#k(PEXp!|<Ob}2*>_`@%&P*4KUIZqYZL|_X~fh3`f93#6nTVgEQ+r1YYr)e<v zS>#@(ZaxMvN$lSI5rQ(}U#fRox?4F}JYy6C&_fPM1C&-6n;;kE=6Qmv@ie>7^`VVa zV886G4d+okq@p9rU-myhV$4b4-%!jS*M8Y@?CKO#DU8N;SV;lJY6zu-*HsrBuOX+u zb6x_54{|E-($k6CQrly9aqAh<^oEhla@aQYibk2tmdkq<#-1qhjCL;?RyWE0y;JNE zh}<q}L{F!PRenhaduPLpFKr=wX^lF;qBE=xZJ4o@62kfg<AUU@h^27WtEaEJ^MDKx zvBU9I#e_WcTW_@JD8`5Xg8;-%e1Fh*?^yzVQF3K1<{VD}XnR@H_jK<d;%`O(>qz8b z*`tRl;G5UAsRLIqu_gfq6JoG2hl!%4TxBF3cQFxxS$55^B`rZm>imS_*s9KrD!f!m z$~+4ES8j0ws{OOqFLX2FwRIwXPT}|lopd<pXzlT$eN@)w+V%T`MOc&F4g<&qUd~D+ z{=u?`yHdAVqVV0Hjgez1ZqY}x^(X@OxAM#K5;bkEuP^SbN`A(&S8Lyxpnnv<87!2s zmN3-+9~jU#iNwM_mB2aAkI7k3ryu_Kz0WZFj!t1zMCjccqWfdE>*~AtP%pHEFAcgk z$Wn{vT$Bqn>juy?s6Agbc0Dc_ClMing_%LN^I+a_4zV<-QTNX97--5WjAP?AZDG9` zZ$|sstfTT4E2}4w2!*)fB;#F`<Kt~)qE5mjFvnq-LOq7_>b9uWlLWka2>q1j2>S~e z<4dFanq}?jPIP@Qcezi!dqz(DHVqZvj`K}#QdAU3B-xrl0!4De@tX7ZNy@9>rRvjT zN*)@FFi8-u7>tX#zjg7S(<BhL|37ACc!#s0${OkmKl~Cj;+()Kc=*ssNd-kXNDBZv znZcrbQvc&YGH_tD2yEGX_{L*~^st1P*n1BQ*i$KS#}dlQg&OfCfTw%nXC#_4P9#7u zb90`4_s~lH5;|@ve+UVLDGB}dghdOC!IHe5oJ1_zN#iH%&Qpvo2(yW(^zq6(b;@5J z;H5eTXBVYYyZW-#8%>?@8s53l0L}e)8AQD_=S*69h<S{pFKo1r^rK%<QlOY41TR08 zn|Nmi0OkNM_mnLM{z3kZqRJJv?Ela^)mh=cQVa(IWzS&@FA;WbS%9utntJwx+HO%5 z^#f|#VX|;Yi;9GGbb!%Xp0gR$pD0n^DB<4?(c;45#j4)X#^IK*11USaueshHI{vRB z;fV8g?`tq;nlb&y9zX&UO)JyJ`yBhq2zmyKN{PQP5@1o5iknQG_=z#?DGJO)2PIVP zk0u7s%DtGRM(8USf0IjND*1es8<ha;Ry8UiNtWG~k_^esW52-mS4qHtnRQN#Cds2y z$NX`Sa!Wb)dOEsmTDHQyR(?Ra;)6Lg!|-pe#ZOWAQk61r9Gx+hhOagC?S}3VK?Bhe zyMNJz&RW$!<IvrJH8<z<Dov6BrP30yZv$d!63)C#kRCgZesnE<t6ndhx7gukP-qb< z5&oFr<-P;DV~1|=-kA0B=xz#0Mcur~$DJC2`5_lQS~P=)`2$8-2*76*ny7kio@06l zf$<EEK8hzP>m==*50;ewKZ?#WDvGuN!$a<}u*)vpE}c>$4KCeC2_lM=0us`#F1>U} zmz1=03rKe?-6;(!E#=F{_iz5qInSK))ZF)VaTz&Fc<zz^w~G*)5gfiiNNgi4cMua7 zv?rj{0z4Y0S<+)C(!WU3Go*f7Fik4UOGj!N<b<Svf#ZKp+(={myOuLXO(0qa9z41e zMqCN7_M4%^2$Y>bUT{KXd?2DQ{HZ$`AQr*xCH)Ej{m#exf#bAg;d|?9G-}TO3Z9`_ ziT6V{<G)Q6j#+}Xv(J5ast?v_SHsA7It-R~6JZ6e!U*!G;^dG030fw-073i-5P>%E z#V$a+Jc()^MD41Uw!clmHIDbYU(I(ww~H|J5uk2>dSRlQ?aCYrTIYh&$=jMc#GfEQ zEICDP%!dGJWwvzH8mt>hnwLw1n5WJdU<R=A0*a3G^T=Z)YYJsN-$L%1_=i**d|91G z#IY>YI<i$Lf@f<Wu?9t>c7M>i!EoAJ<C1W5)aT#}|GUVGC)3R;j^qiy@$odx2$#d8 zF@#R*mharV2>jVtRVk=J1gu>Rek))BHXH&ylx*N^vc4CG^@)y;kGw^{#geC>k=%ov z^DidrY8F+3eDF|491lwzDj1%8;$RA}7K);xwpOvqNaOyr9!up-T8xGv>8tAj(n~X8 zhCE4fTSwqXoo<7)Rf(tOl=kk3`9Sr7%o^TTTMOKxG)<?%H^o_m;0Jt8>Eb2?d_atZ zwW}l=U)GH9;d-VVxcvGQfmdf_c3tLY5H7#=QW>7P+*J0;EFvr!^zrDMMqQZ;g5yg) znRR%9OB`bf6~Qt-t~6Fl7hUn}Qb%T;BRr7o?yoVmKTnbS9)j*!Q7~O4rj(Kq$17VT zZG?)-Mve+uivzksuz#iEsw$>k)T<G3+y|-;)?m5cVMsfDUh+~B+}w<K(tj$XBJ4b& zIi!ec>N<)CLHs_3WK8XdIwWFNmdK+wWtDGm^b?;xsTy;M?sUz4eF+|M2UMtF}~ zN7KI!FR;B9#mg%obh9*c-UsF1;J?v{+V;_5%;DW$MDTU+3+9SBHv2L8S3HmlKH&)# zUB?fnFpj6xMG4ulUHm{FAYxe?k%$M31eV4^59qo>ZW`^8as)(@v0=CXoS2LTRrM*Q z*xng_*3gukD;z3BT91Yu36gRw!S0YZCA|9FWLMN&T_#mSos2jTGsFXNVmT)=^p!lC zlv4c6f?O=wKWm(fWE&*81`01MFsCCEpeEauZ#7y(tfrA^vlB?S<M9G`M&r1=m3XQE zu?<#JD4zEX9V6d*J)*w;PXyT~JTlqz3T01}_L}+acefhCu=&tvww!3M2BwrLyI%;( zP{|k!5B1;U7(81p_Us4v66!I+LgZ!+DW%2KzHsYM2PP6`_DRxHp!x{lIRZ$zmq>rk zkmh((lQmgsdE7sLN|vwjl}>JyLQ5~<6DkT^LK+a;iTgxA6&h5fBi%S*o2^{1M;v5G z-@~N)YJ`W}(Z?Uzk#`50amgWkcVL&L-s1YEv-h_eYTo~c?7I04y>5-+=&!eFisnp8 zId)%ZL$uZ@J}ZQr*n|X^x!?55g=>VqVUERbdcjJ8@u$hDN*rLQA<Z8isIP?mI)Ysa zl5$1D*wr=oG?@!6gtLsL!klxzDoBVg3N)sF$M+f{Wc#r#LEbI)uA#bq&}ewthWd@< z$iq-F?ckudi%|y?1Wna#-7RF6@lgwNQM1QEbK?kyrIB|{N%qFkTQ<@1a>mS8Q$Nj_ z_UtJ<T$sKN$a=Y`9g*}uR~h?q{>7yO_rKlto4F!*29?DQf-Hh6zKkl3p4wIgn`D8l zW9{6<!ZzAr7ubP2xYl6729m3k`Yx8#38ZncR?SNvm*Ea){D;uG=X3@BsE-_Sk|LLw zb#1DCeiT6#JWVF`FbEacHhFk|O*7y1a>QnTlBuI$?h-*CLZ<SIe0x{*VsD&Tf>ZC| zG)~Rp9|nnl7lNi*V<v^|#4RzVoc9xiIwXRuguRM%A%!$xz{P=^iU|0FhJkWm!#a4E zm9PUO57j&=9dz!4b2G-7bjOTF=upU4j!b)eRLf|zHbb>hb6&I~>Zm%1El%f+83>34 znZwQbt;w=l`MKk01yy<lKMc<tk_UD3&z6Y|%+{~;`yKnNgDFP+Ani|Q*W(iw4IQR& zPDf3kOLtjY)5kW{QA103#av8s1ZFuniPty@^hnub;0Yn-eH2;E^v{%+z~n#LR3gAl zi}Wu*3NnZ8n*o|mq^Gg4+CU9BnQ#KP@V5l!FmNf7Wvig;Ly{t=l+<cH!+gTSifuJ= z9vM}0>?ATr@j=e~Oxfft3AM0=tA*Zk&Bg_C?GIBbWS3CtoA6)<32JeCGF=(YMy>mS zi#|}@VE@h3@hYTCnXKDm=>ap9C9)WHP)R`ocp;INDnIQ;EU9i%Ktd)qy7%UW&7ura z3J4G?N4k%NaghT!PWb;SP4WVozwxJj+f<)n<jJd+bn_fc?HoVwvU^FhT_-)y8dY(( zmzrfx%Zl?cNWy5%W*r1Vtfj?Gx|oi*t|xkb^t0*|`+czBf!Iare)+h_s68vZt($iA z&5=#JQJ=a0nLib;sb#1!wZReY7gsnc)}9LKFt&_vcqJqiP4zy<19XHS9or`nmMV9n zxj9O$fCIR2K<S8k=_oZ{c*ULh<qnlpz<MfA4JL9|h*6EnFh@6#p2=%iRa$8K?Boy| zy_z&KM5_GT20?E3{hKP1!0x|awsc9G(Y@BcCpUg0W@#$K#&_5dyDDNY<KKKqqO@4B z-gT{BJo>eG|DQB1NHCkS@-A)3i8&=Uf^2uT2xLxdfCf$UhLQl>EN({teBcg=z({8a z!B!Cj@ME$&TFR#Cf|sO+DAE$MgZhv7H)f<i&6@KkR+#9h1rkpHRBmBOT;eBnLQP7s zmlPZ!eR1OGv#1{p8AH|qS=%sjwI|fYf&q5<Sr!uO>M>`6dRc?XQ6e1$Z^#Ir0=GiW z<Tfnl58_m9Sr+RUIZbJj4>T!E|EvhDa$5aCbUTc_Ym|#he-LW>(OQcD%~?zh$k$CE z9`Os&A1x789I-KDZ9>Tco?I4x=O!G1{Szdn8@ptDPs%UC1L%&umI*iq7!*?k&1FNb z&h}3KR+#?qT|PW#z0_G(j%Jkkh>z9iA`TMwvFFpnUq`S%Oyo1}47yVzPZJ@PbjDTU z1Tyvf{=*MHf}nX7BrKXv@WYcRrQB$6j`DX6N)!uUe0|}Trwiznd!1iBW~Snj@+iZS zZH0}M6L~t8%{y<)rD#Yt8@LDx46^b_kul=}M{7tqKQ3wS6SEj54yl=Tob2A8)Stzw zy*hBwZvn3&q*a`J%{B!{!(P_rAo^P%J&<s@mi7}rw(bdws#p7k<4Ws?yNk=Gmq(xe z&7G%HqOML@{v8%;sJwsO`r*HeU#Bt|W>38L57)a?;J!aTwvV{pI$^8j+d&Zwa&y)E z!>OV;A|0u(t)Ft=equ@3$OiD1`Z<{kXe_||u_xgrgye%fycKs8WD!Mo6h0OZRu7as zh`LgImniFEQGodd9$y?5bGTt6u%^e-SrLTc8V>CO8WBQ$;+;6c{iFJrV4>gb3bjG% zydxsyWGw4}XRyw8R$@Op6izT1iVJ7S39nj1;78fR2LRomiumu{R08xCL=_3}?KY_} zx&vIKz|n2T<d+zl=HHS5o8BsnJ}1Q>7U>GS$)R&65?p55bv&Sg-P8gX`2Mbw;t3aw z1p%oCv+1<g6Atr4mbbaU`3%CU;m@8aXn~8K5|9XXalh~?3Fa>FlJAZ-aNA(zc)kgp zh>G0eV*hLKjufrzEX~!o%%Wf;{7#BxPiz#<<1oN_hjU57JP%;v^FSQpv-Lcb)h9?k z#D=i0_YOh)u<)t5$`=u0EE4_b$UKzMXU$+I!?!cA|LK0Ee!ppGfvfgCZS#DGS#j@Q zRK5}^Bv<AQPAr0%>a@C4R`Yy_o0H6Y18kTBb2%?1dh?YMRWE%qFsW@Ey&skl;-!ue z%w1~|rQBNpbHuzjDH5<EhtTG{bx!ce>!tYV{Bx!LAI6Sc@5qCdyk$8Xe_oV}`lrXw zo<@fTZ&ugFpD&4!G`6^2C??mo<KB$G)l`+NfNOIv*3jc&E=Kp?IVxX1opk8uHTc_; zyy(CU^!XZu(Gt?XJ;8gGqos0K{7_qru@z-}_deR4^{LvQT76ER4=j+y(1KTr8RC+3 zXmv`LV%DS+$&EdJDUQzG9<NA}gD9Wdaj|kSVKOuuDI|ShRx~%jA1a&85=>!}ZZ;^e zxTV@KFl&8>+=yH(Ojd2QWCrv$aX8n!2<t=BBli85QZ950gTSHM02U;};t}Hu#|M1m z!QKm?jD9Ww!4y1W`AF;H6t~|tA~>%qf!NQ8`wm^<PqiYCfabZnSXRCu#$C7gFH6&v z)^%6Q+bF%34QH!Bz0>}hj9_@L^q+ULCzu(S9&Nl8vFbctd%SiH0&25{d}aWKOl-5C zF)Dr_NV#82dt(C=!le3gLWMWui0%fa0vT`eRJ<;ZGj@S?B%X+BSGQGPSoZ+af5;eA zSyyF5Se)3@zTEWEB=v~QH~zNoV_|T;&+roaH+9B2#QL1gnV8CW=CXBiHX^lDEGYhm zt~@E_N!DL4MRr|RDndDz?!ga=VH)^oa&OkOee<#8Io=Km960@~!FV_bC*ZznS1!;x z6am7?WB%&RBpf|pegdBptv82xh};t|)?n)e3bEp?tkF}>8C~W2OrWfvjF*+HQq+e1 zwoJk=M#*yXXuRP`iadI3fe~zS;+<mzyiZuA!5{C1tIHoIJ~R4va)K6WO#eY_>7B<X z0{W5-o2yxaX)PQy1G;yX@AQO`1Df~L0*x3Hf|(8JZ(r8v&y8bFLZ1Uo6wgKTvnYNz z$LDb>@fNVJ?qWFMQh72A2W0LS+=(V_*?e-&KnW)#*t}oiR*uWBs4HVVhejq460h`3 zTPWo-J8&_7AN-o~Y#lO}|Haz5D(>dV-g2Ovu_keI_B%l+jEF7lO>vO@)VIEc5ni$Q zr@>q&u^c1pR<85uY{6P7Am$E1oV7Hl{aOmR3Z?xi4|pFvUHj{EiS%aG4|J*}?O7}c z*gcMsoo0=`1Txkb`Vj$GR-M0<mYvsbFHX%yKx1iXFU*OGyBr;foMhNl4%24$M9(-t znN|gUoaDhGIsA8B8(O9*7YbG#6B?r?Bz3B3vAenjgw6Sf>f|nI!{HI(kCr#&nA(Aj z3(qp=uD<q-BC)xouHv))NhD`L%zyJ;(TwJxK<ZEgfSLZ$D)-0PXpgI|x3DSjnJTP_ zm?8bBuKR&)fTn@;XLD!%%46D8W&I{O%YRszI&(gN%(gCWLAiRHDC*qab)Hw<Rz0@| zfbh3$`bd(voC)rW4dbA_?A;$&@ThvRyp3_S&u9E?1Cs8=dFdx@->6x?CFfJy;>*O= zluG>GbzR<~ZG|(3!S>ki5Z9uWqO?o;Fegfkj5P*}VGUJ_l=m=5f8dG#Xi{qI&6mwM zOA9mHTdli(JSOy8?TWF1m_P^npWqH*!;}~b|31m34uoem9uslg%fiXXlpv9Jg0fcZ zM~3+#(iJJJF`H|wJ2e)Re^QlvvM4GNU(qv_P|BhSMR*CI@eC$WLXouGKJyw62ij&? zkF>zH_IUcyepG<r@E>b+-WO|U1~Y%QF`sG4%<y;cvV3Ye<hFD6J=m<6j-2`=DJ;0W zZr-Ydk5{JWaX36Uc_gcL8ebJRV%NF<M$fAXdc4^}X6sptwN+B>gR?xOH;+m}8rN9O zq{E#wDp+;OD&F=5!(H)E1CV(UVD1A`J>}BQNi;ZBJl6~uww(U$buPD!gMRj4bH)2a zLgh|yGX0%vZKcnAQRs2}`72I`4Z(Szxqn10QDQHfxaEBN!5=K64VGQ(M@3<qFn~>Y zTP4b)R{eu(Ym9hU_@+9Tus+2V5J4Zc>7tWz+q~=s7fl(PMxXp%h7JCu2VQIY;4`bd z>*dYgB5E3UR{H(+<)0c2O}lZ^&NiQ!(v#<7<yw8oi5@?eu33LM^Qlm<damT%=JS2I z=R%L1sQ7lP#{Rc33*VSfn`Afw4RBw%Me}Dq=uZFo%kRRoMx{)WmhBD&mfqI&E^rO% zT==A^0{@ujmrKdE4LzFxmd&dlJxm-8@i>0|WxQHp#FkO+`>NCT9X0Su`gh!nNILXg z83$dPQ)v{^S0V^03}Cng=W8=GIL;<fi?I!>&zqyrAdnPBTK>oFg6L3VS{$*&Vgw@A zge^va?-|*5*~O@TkC=YO#W9G;#0+NCc4l{)@i|OZ_3sKP<w-r(M}1c)j<R7<m5Rrv zFeP{L1$o7j7Bxi+KFFM`jae&(o^{IDN(*naMIpgQQs5!|=AcT#d7nywAQ8@Mp>Yj< z>f5MWyy&-GPoVF_3w8NcbfgyTzDMcgFKfspoW><8fH~f^D`rUk3`9Auf1gch544dz z^#TqxFoa07z@}m>jlzmB#y2o@SRdm7PYFaKe+`8MqHC3mDOgByY1ah-zPr}H==xKy z`V${HnKS4qi_9=ir-J?uX6al!MO0G_)!L<Wu>zT+TH8vBMC@Es*H5tKVYl5Gbo3{N zl%gZ-NZwx1pSPQR1>X4sBXeiRt~yW`qf_Rw#Q9p2&&vSJTphPmlZGqOzH);})bD<S zPXvzawtgvl&q|CHY{~5G4Z@E;$Oc8DK_b#%4?*yL5r_S7k`Z4i3w~?tX}r-1amdfE zSk1mCcI@8yO0h(!MXyJTT;1_HH7g2=NVVb^t|*l=cCPr^7%tVoGUW+ez*E0J`z)$} zwaZ|*O{OGd=O_4+w0zEH6pkjwMOuQ%cF>zP>P@ZM)d`rhxO->lt|GImDR2q=#ci<q z3=FP*7z>o*Ewn$qjWS~EEh>9#qOaDG5|?-wA7jk^+3nG=MC8&?D{Joed#KxElN!g; z$kl^*)kv0J1I(Ff%qT=UxW6-|vNy(wqlRzDx%#t|@Z%sInh$XGclk)hM_MeBwG961 zBzjZ}t|PPdT5GEOMOHQDidqj2;u0QlbKsJ1;-z2hgDoUEpm6EvqT!XI_@Sxcty_%j zJjkn)eA`O?Tt_o;GEGTe&S3~4Ny1897Uxr|5`*lH6IPB^?Ole;7DNgJgVQI#1yN{C zZaIvt2z6D$=uP(+zi!(eL*KhFHGy?)!KUokQqiL_m6EDEXcS+2RO9!%vZQ`>%@rs4 z)!5FF{j$_Y9Z_?gm24xM!(*fb<1s}#3NM=)$vYLvyMGvD3Gy`g@a2-T_u4sQ<4XqF zHbz?P6c<x;g1P)thRVtn!5u?7L328b$cNb^<80HKkKB^quaE5;JZk<vx`-e4gRjq9 zPK3oJ%kJky(V@_D3hqRyVp@V|#yTdhO$>X-KvYphc{e~@q$%Db0bAxKUB(O>Oh`Y| zYkj0hBBk|Wa)S5G0LwyDsanTim{g#hz-M)o(v<F_I%r#Zu3APhQU>!AAJF_2&p$P( z{c4mOR}WjsnLuuEMrMFC7GRM!NRgfvK(v82Cqejk@tntHX}sDofX2anpsHQ}>G`ys zbo!8Z4B>|?19y7zXV0u2hBe(h{q8ywnKP;!XaKT$TIsBLX&+_7Fd?xO#aahl-fenK zIV-?dkYcC2W?9i$OTzwAr#Y~v8)f(++^A2r_QgI}*ujV`VZf-BeKcj}(KoeywKg{I zr_ud<qr%!56BYYIBK$9tqbuW`{uMiaecrps>WvK4q@*|8lyb5hOwf>6jZpI=ARDsL zc@Q_z&@z5eWjK`9u6Dr3rw*3T0$*=NZQ>7l>`jMn8UM1J2*RRMd^^7?&VH!X_IOjR zAo6s@Yq~s#Z{pG@8qV?J7dSQZsr&r&7X$4e)ZIkZ`NH9iG0^|wROe}z$b4)jgN2eY z?jh7^ab#nN{n0P>-rJEtOm~15IJJ5~V18jGWv+tY<vl;g?FKz88P&Y?l+!+U#ik<R zu}NQDQh)H$z=x&2W$3FHG2nBIO8S5*rI_lC)_dmXfy-sQ!VO$iXoqu*28BrsFqrvo zu|0A5P#?XnNlI3P-Agq*AD$ITTpIkhe5z@bS~jZWH}PK?l(lJQp|K3&*0zA1iaIK& zIybRNTRvDuX(=t0Es-R;be>tYd^A9<paoW*tt7rMg;2c6o(2YL4ZeybzkD2nuZk}3 zS-BZ$%WPF6V&`4iTozPs&+Vbvf(rlscZX49D7fa~2(HZC9jS%ASr!O;b^F!qjQ76s zMW&(vUA<go*UWu~c+K^%?{w`eE|u{2I;Qt=os(YkuCC@9lzPGNZ$v2S39DCI(t39J zt3lXR$i+Ie#VlC$b+M&Vfy~N#;x#}!At8LhiFgj(v&I!~v6B7bw0~M7(rnd<gMU4q z=)ZM=-z~`BX{Ii<46TBXeyy==&)GhkjLNR)vyU=&Sw)WM(5*;ZeKqADj<?1I1PFgV zp;CALJe|F<v|(p)C9fZAW8D21x(HX9{$N%)yiwIX`~`ng<6=rN3%ketdNh*{_E!F> zwx#1dRguhO(!2SU=d1ip7F`D>!)|v4Oud`Ny}hDTuRs(~JdV|Y7fYtwTd%bf(yWTh z@L%~KV$L08kx}t3658T2+E<Cx#syopzq`5VESRaRv=t`JMP;q6HvJ7SDd`d<TJ)+M z6W1A=0z^jd-tIsdlF9nBm^s$in%?>x&+2n*kt@qGOBsnNuSIbcs6+LvMdh>{-t3R8 zukLPmytNUyE#vgxS%q(pAb)Z(Z7?!!hh^!o(LSe?HFsLcY8#rdX))lN!j`p~V;(-d z*#h%(qix>prfheo-0Vban^J6BAK3QdQoW^`dke|jSh;t?;}E@Iw{;QPiLNxiu}TiA zd~KVwSG3Z8`%ZQVYU@<LhseBRFp)LtBT3JBYc4vn*!l}fH!4E6^2~_IB;ywp|G9N> z$bp^x>yd@5>wsMLoE?gSMNaiM<tt;^j@;y64wi$#ycKB8jKJFyaDgGlDEgppbj$^@ zYhJP+gnf6ox2rUII5K13zOCEx7>du)aKj@;ZMZDuxO}bYF#BQax#K;7+CjS;y)M#l zNikl!vY+E<sdffVq5HMnmHXlu2Unaj%d*JTGdlt2UrPYm%YSb!#PLkym8;$Bc+;&8 zLWjed-@ketV|IV997)}<*hSA7c9$D}m9?HJj~YIl4m<z38}i4~vf+((dW}T7n#q>a z#jk(cfBwCVzlB-<u#0z=yPFgLO{V!!@3fLk>J9bv^lSd;Kj1%#l^G7v&&`MvqXxAT z#`#~V`^9JCFZ}J9MyOc#I@*7GW6PwCY54e_$n*HW&W(`ixm2y?Wx)dV$A@boM=dg9 zmJ3lXA*<2oZK4eWPyc;9)CslG$szqodj#2oiiMq?qdX3~`&q!G4!Yp9CT)0N#4%KF zh;es3X6JOBymkp{@1`YuxbpmM!}0MvKecOtF?0($vvtCtJi)|tD!g;bzPK)FJ$Fh7 zW9~UwZ#&6vo02fv$A5n)ZRo`7zbu=47L;LXHzlGXmVcsqmge9Rn{E1D@>Gr59ezHe z+3mI~6C>_!CfNX$^1R!c7FDg*biTj-H+4VI?Q;*7RwWN@BVv)35`7;y+(ff;-us)o zZyWRQH%4ac{H@r-CG<P}inA`$GmVNUv%VLO&yooQ++*7(pWL0wjzX8cY^}vSMWoOV zt2Q-B-1pd}tv=BkJvmq0%XPXlbb0dE&$_x{dtoBLv#LkdDD-@}z1w`YV(-=5it4dd z!{6w}^C&OJAdJ_CLa#5DN6YZb$klVL#mmm0m)@Rpjtx<aNn328)E_G@6aLCegU&y3 zo^*Ddy01cgRlE}$uCxy&Y<uUE3STifUWS5*KL5DNd8+rRp)F59I)BIei}Y#m4}HEI z_b;TUX`I(34`vTEs;<Aedv`B_8w##n8m=q<cFqx8hwO;dtQzB|JQuX^sPeoS)qn6Y z#%J~e{fnI`mWn8+%*%!y-!pO_=O1J>tK1!by*vM6obEj4qLy3#-1N@MF1P<ZI|f%2 zUVHmr)Oy|yd#V?H5@S<28JxYve%Y?Kb{rS`*JGzTYJzv>yEg*@dY}B8yORhK4~cx` zJm2@P@ni7P&cBtv|5ic&tx^A1!|>mR*ndA&J_@-EZ5mCW0f6}mpTG*Zr^WyP7~scc z!v(;101lYp9^KOs2qtHeRy;z}2E$p^GgPZ`dm?Bay<6(9x=)NE6~Y<Rs`J(2Tqs1v z2dcl`SJW*BGt_DdM$-9=`S7wy3dg>n0wIj*wMFBx4$(ZX25XBa3w843hdJPM@+d17 zdE8j#lGzHgu5d<;&%|=%)M|0BhU&j9HaHPyNCW>5jC!5cE258pSFLC~VkXVYjn$w~ zVqVkX#;Tuvv8)<dFUj!;2U8x|tqeES?2KhAL@;SJ*X~Ug>6e<0G}j%>R$2~aY0(Sf zw$-^BwcPJSfz@^#<dK75<8e@57&Y}rhO0k2ZK151s8?nI5wkc}W93fY&x2O#6z)jI zmXY2^t394iU$?DYo$oJ_`w7H0{Jw!hcUONrK!5bVqg{LO=@x2(^d}(XLIyzicaeec zi^5eLsIm=n0G=$^JcRZ||9bEP(@V2Zk`Qoi5L2#~MKI0APOjVq&RTn<$fy@il-NR1 z9-hQSV_uB(Z<@{6$7HFjaZ3NCY{sc_>}^Kr5YlcX=ozYQB^tgB+e&)jF|d_v8bY+4 z@=CHD?KR!%_24~$DoPH-*h0&h@qR|4Fw<kydne0hLyhx`%k~~80TVuCC&x`Mdp9?{ zd0;m$mM5Gmlj(NAIwO&6q3~;(wt8_+N=Qj@PEfQucR~JJpLfNdl1fU7g6r?D_lv4l zjCacta|ibdoqX0hQ9>ogChi1^@V%-C$?(JKVbO!bJhDi5SM8Lc-LJZ7TtRsd85ePJ z!%)D@VdJJUk7Lt%?#*FSgmOFjWoL;ux@v#M?tLp6+D)P1@5RBN9{}jk9)tk0+i^~M zOib{Z!G}&i7{FF|0J%P&5Fo6XA=FD}WFJTZRNfr*vn4Y)fgTAWQ9h6{!{ru^z9swa z2SaA3BjP({kNT0W$m(Gf=;2v90q<<J<7tWD85UvLayt2xSR^3b`MOj-N5lHt<2=UN zqa`gjW3x&pmG6|S!zM$THIp>+eCK07oA1la>V*z}v5)*-=?Rhv-O0fn-!z;HcX=i+ zxs4!SCtObb7XkoMfZ40dP4+uU9pFc#Vxkfn^qXoSftasj!SQ|fWh)N}%OKJ%^mlXD z?{X3}P)_p|XvqqE{JyIKZ%Jg4-g&L2m9Z%6{Xr||Q@@oq_FG+2Tt*TA_K~_)6T;^g zEA=v)_x+z;+~o`e6!(hcZxwzY4vM6>;?KXEt!Cm1pu%rGUZf9>--8Ns5HL&&3VhwF zT8KFLb>P=`f@<4fhPwhN3NS_XU+H$~<KbLlfetx2C+3WcH6-{yVvWCSs^zPRFxE}_ ztXBDULeXv%#Wn_q$eM=xDvAw?)6NLcWdng2<{)=khCg>UmwdR<6@Cc&sRlMUjwmt) zBa)xJBA=^(<aryUqeykxX@p`c*8smTo2{)@RSam=U|Vp_qWt4h55x<-q|$h)%;C}e zRxO+KSO;0d_E-5&s`H!KxMe#1z#duIeNV<Fx&9gU(EGe30ohs}vn{52r^q=rZ+@9= zgz_6r*`Lo@_+L@dwCZ{v^-OMEsDKL;u}n8Bq1saZfkmj=G<Y1Z=_G;Qb708y`Xu?s zCK?o^GHgM2n$pL>2!cH;e(QlW3eq!UwP8l9baxTNb$=CYDAqFbIZa<9DHQJ`8ZO2u zb*-a-x>t9x-TT(nerM=PuS$%0OBQGS$w$bZ4&04>q#DTl-7+psgauiFkw8@ATa-H+ z)~|Om3s$+Ka3i7Xy`ukx=Bu?btB-Dk4@DMzFqaCe&!}4#2Mz><!Xaa0!6C|iA`pc= zG~3TfX|630p=_6PADqm(J}X2m+dk#apG+_31FZX%0oXOzLlX(q+}IjK&;kF-G?i|0 z;2JmyECe{HQheM}f7Nb1(1%1hi+`lX^dd84L?@EFBHT8PmJe3B(11)N*!0R}76Uj| z5bc$AM0&tG=q|)O+0ho%Lvy{7GgaP<7~IXkS)fd=7^lCCebXNY=j^D)3wk(5aWvnq z>``0rc+Qr%^hMw+>$>=74z@}fFJ|wezg6Dj-t2$4G6oGyyC%EEC<RD;3D|URXpnI{ zOR{51Qk$us>o0TT?1+ZmoATmYqdlha_`<p=wbuSEda_q9|C+IGp%8j6ht+^@{+A@; z7FFT5<*R)S;cPpfhP^tFTK(^Owhga%)Z<=RgJahq(=jnB`I;VhtZ3Anx*Q~}>a-kx z?cR2~{O7~J?<+L_{&rnb3ap_tH(;*f?Y2G@;dXjV8!r@bu&;Q6@N__~X4##*qgBzY z8yk`BUeIau5h8$@#QaQwNdS%t_Z;5j0MW2b`B%{;@DS+WqY3_@2#}lEq3j0Z17<K+ z6|<#~w^M8VRN!`@eZc&0_|@HrQwTV+2}SCSVy2D-1LSj6WQV<1W9WijR1z{)D_aT2 z6|MNB(kVzHArHXeQh6MNv#V}G2k;4Ea9`qt@!_K>WQ#&*=<H#;udb)w&t%Jel*2E& z$R)Ix3!#`}juFYbo(bd|dq<0lmShV8<6bEtAjlXmKU}!$bE5L(Uq2dWw2>|4s?hEW z0L2zOKbJJCSY2&O^Q!_WgAC?1jr-+7tl>+k)^P~O?F>-uATkncXxY*F;}clWM{Zux z`Zv?=<IQ6J^?wcRLm_|s>2KG-Pa8X_M~_0JZr9;4joqB1X?HA}-JlNf$m?`?R60#N z1!+^iiuOr-`t2sy-P5K)qtTP3?|zRAy_<#!$f5p<tlN*qn#`QaPqS`rcR0Q^$*19* z<*F#{;xadnC&Q?6$TN2|W3F}b5zu@*)UIK2^Gu+gyDiXu0HBp0Wx>wBr89Dx6)Hc@ z$GNC!*nR-<_kBq45NdCxK!+{r6}pbaSS~T_OF4gEd#VSu4zi#g%vR>E)d|--?4Y*{ z4Vg=ny&Mb-qMJg8h=(9RVvYXL6)u7Y%CEys3|NmW8(Q{-^q@gHUGyecMTV8Ns7dNP z+WG#L%^nyqSn=Oq(6Ntb$@q1kc-~RPWshh`hsV3M*8T5KWsVA;!tDVR{e(`4_`PK8 zr#>G2G$!Qkw3sPsM?-dR>gf~FBIam4!A__e^5eax2wuN<_umDn@BHN5%{#L$`V}}R zO$TBqNV3xY0dL*iEg5b9*BwvS-MH^lsS31z4cd={Bnpx&qWn@g5vE42NG|_d6~DPk z=xXK1lUe@&LV!^m@p#9VCB=2o%oET21Kj)rTS@@#cz{$2+<`h!wh#&k1}?<H*4ljl z<R>+ZH*XRA2{=f$0Scg@3p$YZ*+eU`P*E<#87I7_FYxs&8hjk2v+J^$4V_29YOr38 zI*?5>Pm||x=jZU(G=3htXrs`NZ~9$4tYMMups(oQMZv&%9gHgm-t#wDs|b!r32nUt z(PRTadL@zXF3UnT6qxhc*1;_5V1m5@O~D^Q<H3Y-A!ZGqJdTMH8|ea75t+Nt)g$OU zHY|$^p8gr}t^wnf0)HGDUi$pKo+^A58%`ld*&!a(Py}~Y^;4rkSlPIm%|`qXcdGJ= z1ax3qC>Y1{$c{#d0UAUPb!amNAt)YoMiqf?4$Bb)b?Cr$#o>!K@CB!k+1W5^xo|w8 zXo_*nw(9$JILz7xhW8v|-wvCHN30{^GvbthQv}TT!#{D?Ri~i!HRyc{(cg)f&^BOI z5OFFVv9e3PMH6>I2wOqHq>rI6{D>~`AUJan9!@+|;xk*S%N-4@>kjjo$T^5SHLB_o zDn1a0Uloh*A0l)W7AlUoe*XF9A_g#nZLdY+j>ka|5qwvl^;8qca-c*+z&Zf4R;8Rf zipuK`AnS;k=}Iuah}m9)d<LNRJ}Lm24EF#0nh54~6;16=(vKv`X@?Xc;a%t$qH!M$ zW4MhP+`lkM>*Br{kG9Vy+FpZ-(IULOQ>S<1X>%Y1$M)po!5XP4k+g5UjA4tF1i2ve zDhj5pmJIPvr86hRTZiJ~km8z?ek)8Y7fU<YhHfDt@c=quFTqtJxtu%FAT<L(C4LDb zdDIk~AOWv2Lxj$I<Vw&+S5meRQR*1O#I7<;=M%~A5DBJ4h-qYSUs&YKP6ka?!V|B| zxVX$kBFZvu_$qhS)<6amPEx&igiBGZzA7S=C<-6vOKe<bwBQ$QIT)AimrL6(WI11` z<tSHE5{QJd%W^UygA_#bIbi3YJ!3d*GrYbi9lH1BQB?~4wJFzpE;Vz`sUW;xFn6*2 z3xQk`wRw)GjVo9vJ}xJRcQB_SH5u1G`N{@bp9;fcPG)YF$Sg{KQG^Jk^_Qi~|GS>c z?-PaV|MkW@!@wL0HOP0f4LDYXi<cm#D>1)~>0)EE4V$Ul)Y3sXxg2ShC&lo9qk{M5 zc^p;2Gz&pvG#<HCU|fGN0C(_7L(I{@w(j7GTY_Yy@8HJV$z%&;H0p4NKG!x3ts?{o z8H5MK7KWwWL(ZWYYb5hv0J?xsh5!Rd_+DiR!SUxrAF|}MP(mKMFOntHh~%v`XzdQ+ zJXb057>3JS2o{QDG%gf!PDzK*g$$PFmk>3ygTJ=JIMvFSgmM*~OTo<EBS&TFRp4=+ zk_jG!o-xGHiTD^uAfY3J)k6DuD1KfBj`Ec6?9;`l!*m8<pHsgXL&z4c$yZ9?m*KQQ zgLas-3Xp%)oOmkbK=%9~ZJG}q2L6qBsFElyis7cH<hnd2&YhAM&QntLZM_mUl+Bd> z6&V4?`|irY%ZDQcFWs+teHRDwr>l{ism3#}!H*-U-h&SBlS`x{K&3Uu8>nA`q`chl z6=NFqh}w4nQGhz!WxsU&s9Nk8y5UryXQw2~ivYyoe*{yv0oW$G-q?;p^16<<pgQKd z6v&44!V8ckb+Y5owKWn4U&OQh`lj*fy|8$j?_X7_8a~{6yFF{s>GWnLC2hu8n(K9R z9gTW&kay#aOKLU7^u_MF?mlr%Kz4ZA4Vk$HqI<td!JKpyp3P|9^xD4(*B|n&k|^J# znbW^PiktFJY$G+!cO4u^CJK^)1x3Nb8o$$BtYx&7HU_+)E=NO(vWZ^A;;UtYa$<=x zV_Vpq@A-Hntas*=?TZxUmEbqogud;B4M>Q+AoyEl>ynA6s#u$fKO`Ru$wlI)!NJb$ zgfFrQKENSKSfcb;qT}!1UP#i(H~7-Z*>)VY!%0ZUNJxHQiK*;6n$X0wesBgi_@o59 z0_6zthhzhgh*{88DNz&_lmb9L+qCPIHkaarm|@^75k88^K7FxIuJUp%cSzP3NZ?@q zwPq5_1`;Vh5~X_L=1OAiGDzc5$3z%>GXyez0Le0je?vnY+wqE;Am7@F_@%=LNV+(N zYHD@6K;xL9N^;9kl94r%iAoP_B}tD{U$+iP_fcCkwhyfXLNoLSNQ2O5a3~5K2M~R` zLy`Cn_t)r<C=rsh0zjD{aa~}KF$rK43HK+0OwmDdutb@Hy;d1Ssc51U!IEyZnl}m| z#k0+$?LmWrLp~%#L1y>J55lZu{Hz_q_iF^vN8nf_*ymmd<~Qt)1V^C2@mP@Q5#f<_ ztKS+y3>M^53C_g!cMB3X#degnL-5uiW$?~&WHTZ2U^WVp|8lT+xHNHI*bL)ozC+@Y zQ80mo4WdXg;gG~NZ^I++kZe#87K}&h6GiPaE$E>@Qm(SpI~d#D=R_POHtt^p_5naa zM}+UqTJ6oi?kMnlOMm0hNH!Ma3lP<jr(Dpd;QBYQ-x68990Y07h24D*c&svZ(D!je zkoX(YH;WpC^9xJ?MOQ_7*7%XskN`^cQ=RaR4pax_67g~*aVwfwH-oqbJF=K@|7E5q z9KiNYgsy7@hLr@4C~zJc;*JIRV+nJzskZsx?9#JefXUC|lOoH3Dd8#IoUo5kkPbM+ zagBgu8H8txb{qak`j7<v5333t*JPYWkWAAojVzZDC&>_}$q-jK4fuymH(|XZ&A@g@ zLc?~v$UZ_BfF#Wio~<+M@nP1>fo?fD27nJuBVh}%V}>*!XDsN06Sl7J;}H7E2)5V3 zZ%Orb4*sn>?&19Bf5f^D^Ha+sHSnJFe~`50`3=9G?z?PANp`t35?9rXK(!r|2cPgC zAbO`e8!Wn*FZXG=!9%TRaZraO@`%vB5`=yZF}Cqk_9GdsBpC&usEj4(KWy~!QsgTu z^@ng6!?NzfY5cejqYumTt@DXx%N0i>8=BvL7nVofI|#E0Oxi)QSfX!OND6Q7(Kotp zg^SYW!S+~?!|rO65p)pfHUdG%1wByFOY)=S(l0lqq~Wm9DfsPFLR1Hy`MMz#NP7s+ zVC*z>+)9ZY__hX#XxXSe3Vn~ncc>(Y6ubu;4rU0#6TAimV6;KT2@6PAgBf_w_vaxR zx={%w<nR05hedr{0xHQB%Ga(G;8zN^>UUAQeqCa~(G-AO)@_wzl<s-P)S0L~Y8>4& zVfQ1mePa5W&;+^dyVjPwM3h>2&k-cT6(Vvdhi@ah+&ey|a6$aDhd@y~L=T~U{N7$W zKR^H7kt@#~!jePeY{U8C2oj(S3Q)Jm;R)>_H60CMK<3DD`o~}C(M`Ea5FoqUSr8vs z0v90%lgtM3JNB1|6Jg!o!Vx>T>m-2~Xl^CQ<cM&FZf8E$(=OE8zTx0gpRbyVTL6<+ z_b53-$3p7qCa%yPR{Pf^cjr{}9xkHwp~H_9yJM=SkfWg<(`<srOoN%(`^7L|_jkR4 zZ`8gxD8?yj<t9P26lT3hHFF30e6a?lDI##NL9ZiW-JzfU_8shi%3C=<C}_h81Q3d% z@S*4<#CQjDBs`g66ofOIVsf70bZ#pPF>JiQlp;(zTKJs3&qA7C)#30T@~!O<EVmt8 z8Tt)Mm#8a|PMGsu*ZhOeF!6f;a|iwCdU)#g*FT!8?Xo#VC1w-eaR!NjKPc;1zO|ny z9~gVvLxf1-*J|nJZRwICy3r&uMdQE5f(jjpVk;@F-d7tC!w%t~+`>4{)OI)yY&*N! z?Gwc`It*xsdarp;BWw9mA~gFy{51Mx;RSD-?S<%Gg5%EA?{+Dp;f#^Q<w%fmHu!sN z&nDFs&^`edn$5erA<DoKtyZ-D83L)U9Y@1YGOz1w|3DqU5}QsZTu%zE%ss1$NJ8MC zLMO;xENmW40_c9DdmKPetfl})t;^dIGl~XYVskp*5XWeBi|amDj;4KYYi<x8m1A5a z+3cbUNmNgwdE(&Hq_$n4nI!DK-_11|`!Gln2R)^`tCOn~#iW!*!A<*BD^oU@?%DoS z@JdT6Ui&D0lgq0i_rrJ549}|7s?3QCqiFKPA^|sg5GteH9}mibkHzMghGGSkGwws( zRUNbfq9cijSw7(F1)A(Fm$sl`1<+Ex6qnGM$bn;Tdda;#td$~ZTrFZt1}K|&UEgcS ziw>*n?i^OBN=W|xKQSu67fM+wR`DDM|1La^VRq|Bj$;=FiWYMyTJmaoGffY;uNIB} z(}n|eE#NEBP5N(^HPOLB5UEI^x$f66a@TJ6tE2+4_w@;BJ(R-~@?nnvonsP_NR;j_ zIiRYK;m{P6)2dT-vG`f{#VSw{0Z`<8V?|}KR*8|RD+(!5hN;8ys5p77%P8XlwCRKM zc|qxhmrh-@t}V2LXuC*n5N-25%TwkyLG|}C(fF*x+-5*gMbRw{o*DI1#}1`-oLAgO zC?n~cNX=jh`=gFXo?1AWs*B6FLR}_r#T+I1j9qx%SxVK@C->rdrLy=(g}gcKSNnH8 zs9;HA20+}_j>fe!hnMkfK@|vS?$vOSj?TRwsvnUPTHNNMoki5azq@RbZmE2}Y7D>q zK%hC=8_7c+%!h-ln_>yWCsR=#P$SNwA}Y~VAyczrR*c_p)wM1BTECEEk$}kaEeIoS z{8{GSue@7{!<nwWFcD2>UtLU?>K3`qk?B!YY*!JT<R&Z#fFs@)S#IM2(^n-1lz^d- z&$Aq3o3GO|!NXRz>_vR|hR;=H%@v86=P*_YibpS1V{^}nSYJ3jRhD=|nLK33?Aq*) zKqnP1bEG@;{_9QG!PcoSyYG!`Gd9&0_fBe`^6=1|$MZbCPc~<Q&7xs%-S4V`aGs~E z3o;5nV%4F+Z<mV{?XY<q%z}e_ZqB&Z9m^baKR?Mc93L46E4G=uY5lwXy?cw~85cv- zwIR6Kp>jMV!`N$TG}XTPD%Ersz$#}1M`wl0R0rXB4d#^eo=lg~XZ1f4W;Ml7RQ5zW zan<+}s6SU^JMJcC+eBN%DWnjr8Mi#5i*s5J<uonv<xrV-(rOS=NqM-W+OXX>mfJwL z$w*gJ7B0;5tl=YNz(S6Gu%s7rDQD-2@NoSo_&ndO$BMaTl5h<n#^`N@kmsSr4`asn z$7jx}0|U1()($-MKzIX+@V5hBn4W6AMSjt{S1}AzYhCo!KcVmD4)2^}r6N#NC($8D zHE!&4x@XY{*(k1jS6EY;d^tte*(*ZeP)cWCJdZ5dDagKgP*ulbr{D$=0GFKapuz>C z-_km<fbGpFzV?f~pZiG*LktZUJeF`k=TVrzgP#FMa>7~ctfNl7;Y*h3_s0zl(yr-L zj}*jAoi_9F&u1z@yI|RiIC$P#7gZ2E6ky3Uc9FW*C=|4Fi%!H%yCe)&>PDN}`;!_< zFwi~#0sCqy0+Y{G$3@;y_{nVfDiXaGED=c%g%Ge?cIGfp<JJeqI<SZiSi=2r0hO{5 zM8tDNR=VR5#wliWkPcWl^HTM#sH<|fDhP<oi~YqF6cBMI`ErzSJy`Fyh%PN7%Wb%* z*fUa|KbMVkJ4GapLXSX}A?`&IgWea@r9wa8c_eQrnGgYYQ8e*DcaV!31vBoNc9>u; z+cgmQP#iaPG{{EL2tUTTOx`Q@QK;~WlbS0EmO&h+ty~``<Hn<yc@O_nQ9e)S=FX$} zn^P!5y}{F4d%|_Q+5aR$PsbE8#QfuB5DRP_EQ|DqMgiTJq&>K@`c(1L#}KIkXP9qU z03$I@Up7Z>kL>&*{kJ9pDdAK#;T5j@j0|lqEw72_+EcFEcMG~`oXAhV<S07(dw8fj zdD39PABr$}x~Lreujt|I2vvL*4-nDAUBH3#mFk^-j->IR2R_3El5m)!8sckTn8pvG z5ba-wYFudgFfp=n&L+m$Q#dB5v#3LsuV)^!Y*BY!V(6E$LoGLR{rq~Yp+aOs(QII? zpv-<YLdiH&?I3ihQV;@~QzdhM1`2xq?oHkISJC+!B@cz8ALoCCI#eo9sO}bswGoZh zKzcGJ`d1Xy!$gXwJXm-S`xDZbQysVhp$*7hML(&@HTkdX+^Jv}U&<e*as-HRrEV$@ zBv@$|r#kK%p6BC30~JI#V=sV`EJ%%W@$*n#m{TUqvwpOvm0$OZ01yU%L7g@au9^>I z0Pr(bKb$lRIC{ywf(%o?ZIIm}XOw+(_cH;{SF5nT7C+GU@sC{Tza3$T{PbpU&;gk| zsm_v9N{$byR|iIC=5{8sGOkAarC#e?QR*42uc#(X-zIH;%5RUJlB?$#Gw<QC{83tj ziJ*K#t~epTUwTU5Ii;bZ|C@cbnK67<#lco}s0v9$oHb)ET-gtg<oZ6z?MK^Xq5SyK zYpWQV)aP%zo8F2yswce<DrM-u9E({SHm&8!uY1>u08lTpE~_c~t~N{)L;_yt44)fx z!bt>ubjOs$uKh$?nCs)@_ll2dxkBOHh3A4`(Xw_pn?kmgeybyQyn+*L>bd-L5Bklp ziwJWi!te*P8?ov;vkLciS<3_X-FcZCi&PfoOHbe7UoNY1gWQYS;#QlNZ1c>|S$^x< za3{)0CUcoaSHc*Ca!FK@mN{RWu`vd4y|cxm-)`)oFVl;9Z!^JMlnIWMd#6`l|I9!| zR~ei5OC;CpH?>N#SDmY_^QlB%Qqm}RA&UiEf|m>P$97U&=!C{AdBC_pzN?xoQ7)B! zN<5zZVr|DKdfgp7U6olGViFX46j}-71CM;pmMA&^Gr<c=5fz=SChmXo8{~f-K9+x| z4iKeg9eak!Dq@<~#X}L}vo$q$wRykGVPu$&6bonBb8+>uAT~5smg2gOCe5vDz4HKz z=EwC0_tWqYa;htZFkR+K-`(y4sy=m`E_G)QuPW4;`QSv&@Cdn&Tmdu)B%eK)vHzZ( zGAq4PM_R5H%%rsV{JVskMWRhf7t>FgP>J6kUGv+i+vGclm7VS=s30%iwau1x5NewF zk-ZsE!yyo<s@<Ak?RylSA6_QI)zHYDdbrpIx+SL-`i^35)p3$4tqiplCtN6{bv~(! zE((dQMg&(fwCzgBPC|ogz#XMe0&rxbvx|ce{Lw&J`8t?jzA>y(#56}Z*GcxfGiD73 zU%&+a9ylQ5-_E9)YWE_pjy1G?66V<y;z-MysqyXJ^W2y%<68xNgOzFbrMp@KQ!A!K zbkX&u1k>I=!4-nsVK3=&8byF?;r9n%T-?rJRQv8^pbQ)r*u~3<#bc-Frbun4C2CCb zmCzNJImbn(6+iYpDr!pqo&yi9DIv6JCv==kKGz4Ii;Gr+n<G<VymI4j$;0XN6mp#& zFzVe~xg^n@dBOd85(XI41rci^+WS}ZPXx-M@tEfVD~7=44BZxIQJYR;o(G>_uqNvX z;{T$_6Q88$A86u@Y}Jtu(G()^o$K`1&-sH0L1BX|FlpB}3}-?Lk<S%!D&<1GltOi6 zuhzj4LXbE$9<B{?)NWu@abN|ngeAV}4o$??eJg03(6uN(^)!3t;4$@$*ds`B?!3Hn zN^3qh<Zfgg(<n(|&J|)#L!>MiXae*VRMHtlLc)w=b1+>@x5d$o3a{{M*2V+nu{82) z&FF5mAKncd`3w%oZ|0TZ?%ceXZt&a?=G|IEQzNy<M9q~6=GXD}8wiaJ7GD95xqBXB zu)#3K9R5!MGUWBO7@qExppxg*wjw7lJ<P8F$9=RL_-S~cku7432V~5v`s6r7?4FZ! zmMxU4{Lbpf9C=QpS*fEUck%A`NShFoxj+*^d{M4oD#>tP7mWMMzKsp$#n|R7y71a5 zrO36<B#VJ%i+B=9<zR8GCIhW}n>Z^G#bis676#7)6(YWvA1X3f;6$ix#o2J(-LRj0 z=edC=3!qJC9*jC;%#in6l-hiNuUsN__%@QkPX%bluVxE3Q5@1f)x;WL4kqyK-OCcl zv1yT~UuhyTZ$G~{VBtConXFFjJQi!tqwcf<KW!S5u`65^3D*yxd*f9fg&Hkx9L}{- z0s7@4+qDBGMw5rr!vs^~_wXK8@=KtHPP?%=D5=0RwTZN*^suqlLnDPnA<Nz0r4NX6 zP>qq@U=(o*01eUC9o=FG-_F3`QieY}%!x*}doPKAdKCWDmg`O8iNXUuN{>tpV@cd8 zT;{N{{#puN%I5)NYWDqRixN55ZV`EP?JDZ8#+cQY<H1LrKkRgih;(S5jo#sC#c|wI z6x>yE%+#)nl_U=tBT@2#fjYr+c&uiDvVvOduO`^tAEV-6eU;%K7RBr$VSEgl+I(_Z zr%l=~F;{_u?MF;Ga4h8p!)WTbx3E%S`*^M@HX74~D-y1-I~s{hm5dD>pTb2^D$6lW zO`nBu5>U8e0?(?mF3;)^GK0<=op7m+kh!t1sZS!iF|x!W$N!_~T>P2*-#>oufNhv< zhB<a`&gVHFlD3&M<s4F(Q*%g2QdHZ_%&|G<ln|mM=Tz!rb4VqrBuagdq*5W3`u54s z??1R7@5keP-H-Qmy{_kz{lq)(ve$(|pW~>DIMgn0|NF8z6V(~J$~n3Me?aGPu;vR# zqA|CBps$J^dgS`=#i4p{h0OMyo9a2G!Mx8m_nB%+$*u4SVywMlrfswN1El9xe#IWm zd+Me=3alHtR4R&;J+EbCtT#O0O6r-$*}SkGMQ?6AlxcOU$JG7E`6sX3cvjgrYxDMN zWt5Uw=SzZrp7libC|7Kl&j}8!WA%4W`XWBxvnTs}`hDw})KIQwFpiqr`@h1$LNfwv zN?*Eh&q<y>lw}^nFGk5-=DJ1h;-w#%I`fXtsVL*BqO2+qu@=pFsrN7Z=aHz%z5XnN zN_t%9kGN_0^475Q`mLM;pLGg8_cYzf->~k@VIh7rZ+rQ~XJ9P%U8okMcpH2_#5X7J z82YH${+790))=V8=AiA|Jxb53$DgH@*Tf?dcJAr)?EY=_k715~yGk)lX4(gL2Y8md zv6HF8vt5QWCq_jU&I&%`TW1?_uLQGsEJBu7`(phwVwinaLLfj9`Cs7M>cDLXP<ss2 z5Udzi-8b>>%}a2XXDIh)$oXe_ZVmkFT{N|;!;+1<eg90D<e7&s_%Mg*49ck6>ri6Z zfBTe9hv1^`S=qgL=ZmO`Ie2N#_M!#!w*~a#JLh!`r(2)jAOdoZ47{=e+#3I@{S|`H z?=iXM&O1T&nEvb;@s2P2zLT-avz~xo-87Dv=1=(}!dE4?(yg<~E$1$c>FUi%h}C>u zajco(7_K_1PG@9mI$5(avR%ReCaifBiqzVNLTCAe!dnB44}}L4x^})<<e#u^nK_R7 z0eBsq%dk)IaM+&zeZ@+6=J8?&5J?*MegnMU<bLHhZQUVSMP2u07_fxM3`=k!TZ~nA zAS{cyaCr`@(>q<MD{)xLO&UFxJr`D=z$?6VeaK>#k-(#_!t;;w!fP`#m$|=JGZ~0? z&4MXiAA_ukspV@hdpcBOF5qaszj_&rrj<(%h)5cKh5w=@6MRiN<>hVJfc~m|SqVIi zncJ5Ug3#&A@M*DlvUn^@0%(rPVoEfGib0aEIJ7Ir8P;mwYLiNY=}*|&)Mg-up#Up` z(jQsC%5Vrk9eDGOdfet}D7@BAk{5wLshRV0`?6V6TLdtQmw$L*W^4fJczISIITM?B z_^NF0mR}$umCTFg2Q8ZmvOdTPg5Hfj9A4IhtE*<3VK@}<vHhy=zT@wy@rO0HdHYP% zsQ|uy^ZRc@;@}Ky%~0Rq$fU4e<<x6QCSh6D2f<|VqA22#wVAnIV!;@mSHZ{n)TIN6 z{`~fj*({0JW#@XZ_{h?-)d8%XJgVs1l<G7)(Bjdf$c+7J!HBXP<Gv44J%wGX;v<XE zXLu%wwoAAFSKw{x5!u*ux<e($6!j|2En<2!d~WivKCkJ+f&T>}4orwCnxgy%5Se>2 z%?A(%z4%@L;ExdVnIp!OmQ74L8?SP1RKs>n5bP5}`vUlyW$$kWELPvmoS}=~#Xs4q z&UN|U5TEITh#<U<{1GkhKijO5mm9jR+4J@D;Xi1L8xFlS(fcJ6A?rPdI58o0H@mE8 z-gdneMwvKxqvlAK&f-gZRApQAt0=7=U+ht9-r>BVt_Pk*_Dkn(djSaC+3^=Dm-uz5 zmsyaD(0}#&QRN{6`hFE({7uUL`t~ayD1R_S9J?EzXPxmBa-KO~9B|}_4Vkl+x4*mw zWfb~VJLRZ2G)wLxV)fYC(bTn1x{|YJMhYu;>M!#Dd1H1-FzQyyD@}6SF6r{8Wttg% zytLK(BmA^VA@cCOd|pxzO%eXlw(XO%ecp3w4eXoK!W+sOUc2Tfkj45Wt8`to<@qwU zk)V@0&0}o#7;?qmp5aGMRDYRKkV~&T1GyJAa8=2Y@PHSxls;4MbwMSG?=;7~Lw%a` zZN{cN@LSaTJV7-1MZ4U-nr?j+)A!Q1)wc1cYgn<5ciPo39=O3jYi^|o)ik$9*f`?P zy@M3r-50N3a?cY#yQ&hO^L~gwwzx#!UD4+7$f56`y@}_IvJ9h(e64_^mp7B#-YYBY zy-mnUyfpmz<9c(~I%SWPuHr>Lrp(yw+GM~{-j=1*<-{jvE_~12+_kf8MQ*0A;x)W| z?YrEs_^k2_dmzF{_J!ez!x4x0ktf0qYpV=Gb_2~ltSXiGf2D7~$?UtCvZ5Qc1$aF+ z_}-xU7?GhYC*1Sp6=vG@%fA{wi#^MKUR*A%_%6FT1zXR9sWM?f?@rt_jK~zccU4Gj z<|G~~$7j6w<>Z0AJ$}R!xujgNPi3novg{jfBtMnpIG9F_#lGr7;;94<anr#tYoq-9 z$;{f5&Fvp5UsPo{i@8jQdmh5x{_##_ZQ#}?KC?0+&r9a$zxnE0CYNMURkWLFkAK#l zJ~>nH>)O7YsGp}wZCo5e;ZD<;KR0B%-e>qE+~n^=D1Az4@F=Qx%Hg+P&o@5dowsuC z#A@g0a<Ndk&>LL+d&@eI?ey=7@WY2&ParDa$JLY92EHnDtt1>mvwWt-j`dY+MH{D8 zhL0s7s0|32KL)wN;URO<Y{~F3%GH1J`*tg%cdp>zk{K}dBt(e>oCk&9v3hh<4#l#9 znTF<Mf*Hn`jLguZGkX;YhigP<VGA`WZ}wq7fY&~3*F{q1wW-#dF6wLBX;Ub~MVYw@ zinxd>2(v6#pnv!tT+P?gd!E8TWI!fHvFbpGxFf1sY+d6)iQc|WIOu|@v*q#PX6l>; zLYw11mM1!$(JUL<djLQI<5cS-FInc#aCLayy_bEi#eCPBY7K5V^(khw%I4^+k@#0H zO{*x;Z#JdY%L>j990Ph?uUZO%dpJ*<vF7^iL1vK;cpWDA%RW6@x%mJ7u7BE0bf>c9 zpF}i7y4Bhq7l(eFah~(4bIc{}>PxOw0-~jCRb7^H%ef(5G<MwoEWga&GKqR-d7{d) zGZHKQxc8Cu`rCVtPF*_wG2nLM0x)gCKmYYh`16I5b*Ie$bM}MIGa;@?R=>;Ql%h?- zv&TwyRat$lSSV&r)KSHhESmAhY1b4roZ>zxrh*(~lz&;GC|^@>^aJDBdF%dxq?}z} z0hUzo^SR@=l>JD{G0Q||k+fc=lq><rQB2MwlfxPcDZ&yfFJo}t^kD(&w>8G#G(tFt zjze@R5>G8-B*5Aa8h&U0BTkMe#cI%bG_f;v0zZA-L@(^t?i?Gf3e>JtEiO=-S;p=} zBtO(06j&31>CDvg@iz$T;_6Qfj*Xf6Ceqb`9Trhu1?tj6;S~rqD9Z$BSidKqz9AF` zxb07#?WI3A@hkCB8p6BpM@M}0KV*4J?`ovI4kqD&=3$liAwu^QxRlEDI=&3CTp%}= zaPmXtRo{j=o5m*#@^vprY#YCODwX$~T7Gg*XB!jhu6BR2Zc(1A((tcqqjw9Y42Er< zh(jC@7F~JvVCVJtt_Qb5;@?VhrGNuR65XxS{9k-xKQwU2H+_gtTgf%qwwC8ZA%jo5 zHfTKGq8B)t%g*-ACs5$(DEr^y`bP}EXjG7{SIicGXpU$5+pxX+<zJ<L^T(nax+?o@ z%nB+R`x8}<!!I9BFcX&yzz#}><JTwy9&u{p1~$-v=eZ!KFrvr;>7rUW0u1Ovk24;O zF6N+~J|JYT1;?344msWisV3hj?zMO=H|t3+i@A+5IsM1C62s3u0r=r)^|aLR7Z-e8 zVUK*pCGpH$cdH9NWSPAeyy_7qN}B<PBqtksaz^V0<>Oow#Z{+pnWoX<mW4mxG<>>y zn>~}>l|%U#PhZUfhKQJV0gke7C{mt1$+@FG7RSTyaE*Q!$bCEW^b(N#IH<T{%47(0 zdZSJeIF(-IVQ}UTL`j7*eAee7c&Eure#=WUd8d2&(XHJ;4-U<4hN;BW`z|)m=UXwM zz*ugzTV<i$RX;fJJEpwT3)%z3L}F1w<Q~(;mKp-hj5PrR%*`ZXdj`Sdf{Z_yqRw7L zjRWLx1-I%6_}{h1poJ^~OMVJN<2v|+`4OIY*m>j=WD;}+s(!blh(n0r1l<hHg)g*U z#$E{m%BPL5T)y-~aSc>c8U1;XL?eEflQzNfqwY2q*N#GbU#>eSl1&F&YGc5!ZmzN$ zOAdMPHPFF8os^3}bG<GVrho8Hl_#K%0)P^R&Nq|llzLzBjwE}3&Q<DoQAqV=XHC}z z%D6R##x?dmT`oc|fE8QqNc!o-p>xG}4*r;h7;*o{x776$f|pVeQ65aFYygc55^$yC z@X+fZffOB)L`a;=uxt?8<x#>z%e$oWDA5>(-HH<fKl&XINOH?@!Ti~mR1}1DUxy>L zb5+!1S#1A(#<XA=cK=TS38U0DVgXW1$-ZG8fQGMTruiuGqOSLwHBGj7MYXkjbLPFE z^`iMYl6mh3!iSbcuO*ZFT@C(DsWoUI2OLu5vEb*GhJydy_6-~(2}+QQk{&kF{&#^f zF0|HNA{zQee0`8hK32cyxKtG``F<`5ruar@SU#cf(Ongd;zzghtz~F?GUx{0Q)Z*K zvPC{mZML8|(7VwcooHdQ3LxWB;fGs?_nuuU*^Lx7Qdl`fH@<r}6ADE;&gltwR~lNx zg;e_1R1waur&GN0qhsNXysM--{PWssv$FRCJSn=$#GFEfWgo7TWQxrO020a@LAQot zd?`@e?+N~fH2r#-KXUIpS;FU?w*}CA$o*p(CJY*y1^rM*DQTai*{0~1^cbYv_rvtl zVajh32LBo8kkW$=TzynLSMKL-^3;(A3Yb@^Dv1{6_A%H?shYUp8~gD~&u^Um{OL@J zo&)%cdQ&%B`ifLuVZ#qE0n7$U<IKVGCIJZp6KaZ?omTX6X65LFlWu=|79&*MYim5z z#p+{8Z3mjGuI!=j66kJw108X9O%6fAuOVo89BJC<(H$us4^KktM^C*oWJ#EI7JIcw z+ldV*w$l6r6f4c=jxL$9>(I>5&09)ZzP8<o6gItwuTrC8-ap8<PKGL{|7tP^23^Hk ztVWQ99mCALp3Q@v*fzONd0uU%wRt`E)b#X+oVZ2xOM-uViQB~XN2ZHmbfJW+0gybp zTg#e2#Hfvy%8`PAxFE363BhxvaE#BlC=FILTQ)M<kHX(dZ<~vScYi&fO)gZ|y7NHa zdKuvuas<y09F!M;T<S6d%@>F3%Uxr}HX7f5t9PENBh8u-%tz`9x01bcKg<?yUKhwT zu4Y2!A_H=xm8W&O{O9iI37j0N-ro7B+&drz*u7P~NBR72;#>PME%=BoviHlIPY2m{ zVR-H|>{qZAVlR`52-a~R-PJmx?!eOxuyu%C2LRJ)46*EBe3KZ*N{cM7p1$)$fX~2} zfS;{;>vw0?>)BGmximx%lV{#;{eCue?M0ngA8mE)wzGLUzMy<io)nL8!f?<T7#b*L zB4())_BPkvWzV%;0+v=pWDGM%>E(bu@P{fr;DHRIKAlKCeG2^hX}^2K-7ginAC^?` z(W$k>RHUtg;&k7L+SC|tKi@&I1SUmmXO`Js?b2%_BSc&8hLfG?qWQ#W4u&a`aHoWY zD=QD-f7c=|rv3;18A9#7sv$6Mu6t$p4W`<wAwJza)cn|j|E4TPaNF#d2;ehm8V@<X z%J9K-1=$Pjw;wUR&`Q(f5$pa$NvD3|nh29660bLYXp(PNVzn9UXeAiaAH|`B`T!_Q z29j$q`Jox|&;z<o*6HE7<kQ<OV9$1;8vWJC^QSjhs+0?G=^l^INEfvPYN9m#wnqhx ztl%{Hnu=ksDgH~%Qv&i{u1j;rcI~JDLLxQK&Hd+S#vimO=hzy+%p+i?B^+hUoY6L# z#2`-;T5#9pVCTfBcI1$6?Z2)%7dW9D&AzRRR1YX%2i55F?=`3GSUj}1kFA_X+d^{H zK@o}R*<>J6PCW;z1b_NoHl086vgGylcTgLtC5l7;+n9V6DU_R@Co@9Dp#b;!g`1g5 z>$-4B4LY*2_FMwrEPGoA4ma)3F!pe8(0DYSJ@{jo%3yNd$_=G@45b3|j!dpLmPm8S zr(mjsRpGe$d)gXwEdpG24=ru@qGrTH4ISuTBpVY-)QsQ^-al{r_u`a_h=>r8b0!q) z=Uokg+$IE6d<m<;U2ZJD@s9f}gr$b2m#VTY!|2UHf$P#kpi<aX`o&19n)#nsHiV38 zf3o2g4)eMK={KP}q(tPvEsQxnV-ZQLlVUilz;)ZsQ)}`6(;TA23~RTNXx${hpzeR3 zG;O;@9Y0ZH2oDp;R`w7XL_L)KO#+yn3PvI#Mno13jZmu8T$J5_GXKeQHz2H*297E~ zQA}o2A|MK^SCkNSherC%13@yWZ(XZ{iMAK5wGfsX<7U^kWpHrQQSj*>R|`JOBwb-g zKULM7lY`)iCJ;7}6H9hu3a7E(|GcCMp8EEQ-pMUeLJs<~MA~*5Km;cwN`$j-IPiu2 zDR5R^gRP99Yv)1p=bsxJan#cpWYk-iyWAIvAw4aR-A0AQE%f`yq1Xh7CyGu0SYp4i z_+^coGh3?7HY0E3G^3-2;bJIxT@MkZM)=3IWBbBQ&nbft6>FO2EUhCiOF@_Gls@ju z+{;OTYL7;02hy}zH0^F^5|8tXDU`LN;#M1#DIy)ahV=V~{(P=T$1ZKjX^}t<`7T!p zJ7aS94W+rk)M(DtW2prgz*lp>dS;6AmME06W|KqFOWN_2H&l<Ts2;88%tP@gCoPME zCPSB$lOaSdO=qz-=3{RDG$IfU7hWi(RXgjcaf3-*T?AY=U5Cbk>H-7QD3KPQsW0I0 zc^uM)P%W8_pMW3w!q%YE^#8omu%j8=eUWzmg?ij!Mv`{ikw-r<6%m5NM=iFR_H@uA z)VQqf2KTAOS9K~b$x7~kX4!|!Wh56fFIWf@N7EVW$ZP5Fqiaze;$ook@of1~hz7YC z1`*FgWK1s7jHjau7NJi+jPOx(D?1qA0o4OoIUG(MTCcvIqhCu?$J2I<Q5Ec{osRF- z{6r)=H00?a{2q?1Q{Cks&Bo%<j0Hj}&kKQ_v1`0?Ntf#eol-(`8^rt-7pVrROMbH# zDBPE8bwdag-8x>k-F~=w?ee$4!F`VuV}b=@h0zrveyF*FFAk<x0^KpDqg+B&jezRa ziVWZxLKR6Hqyza6&3KM>t~{3439p9^)S}?EPlXgZN`GwYlR+O;_fNCBhDeDIkx!>4 zJH1yo=cp%(>R(3ICh1*vqG>EIU*^O#N9Ct0(hHM#pX%nXEIIG#|LE4hR;1|ClD8$_ z>>ZmBHF|V<KnrE;vKxGXQXPC<Ylta+b*u*NV32W={bBP+y(9f``S^$GBH#Cj3{x<} z%o=7o2i0ZLz&>_zjIf92sa;FkKCJfP(Wk(X0zUmFk9!l!(i;;Qw9}>wKI@kpnOW!G zZ2DXPsu(ngwCNm`W}#vTL|GvGM~kXLfD#R$x?@-M33^Gk^E8ryfnJ;jy-wsbe>|xn zzXR`1q!+Te;YKag4d>!8I@P<0(w}cEy#@C?2vHai`8OMkvAO?t8(1&AA8Y#(Fxi?K z@gz)&u46m)n0K|0SLmdXS3N5-;X)4-LFNBmRhFWvOhQKQQ&lNd^=_YgdpY0ik0v>N z&9^<ek-~`@p#Bk16<Q&GUmr<6_-xw^pw8v!G(+{dP`z}fcBlrBEYcc#hqEP$l#Db~ z;s*~tN>^-BJneNwjjr#n{H~4ODvn4~8+zp_jMSt1bij|#AE5Qe5j)%9SBESx6aVPK zv_D8b0~k&oT&L-_&rUjIxI@i2%_zB%yz+%SD>Ce(X$ErCRiGN?P|beGj!@z=(`!G! zw6D5dR_JGc)T9+5Xr$>To!KoBHdoXiA1i$M&Y_H{l`IN*(1<gQ5Ir?sICUkz(Z`uH z)S}0|bXt;Cr(L|}LraLee@)UU6as`m<lEOMF4V&>Ke{c)xc&JEf8XJzl3}KC&K4Y` zYe)m!iz{K=JUb~wR_uE|nY`Sh{upYq9af{PBePbGR*fXP5_D%d?Qu!kXV<l2lW@5r zgLK2`PTGw9*A0?30A8+BTcjq5wBtm2@igsFsL{R-Ifb@)y;kb-3}rx$h6#74esOIe zx=>y|h-h0v^JfY0*C9%@i4KR8p!-~h+Tm{`G+YBUG_E)_F27FYKI6t<^Xbj`E{}|X z3?uVSBWqJ5>n&5ejL$F2KKG78Z}f7y?}{cZukYS_M8ErMFG)|g;cFJUo2qanr%05Y zB+{}or|;ef`Iz+QV2APH_caxT<WJWr)gQOCbfE`Z-8#9U*G9~gR?XDuwEG>@?hyBq zHVb8XSw$s{-fsDCvO~2)mJb*F2XVBX>)cInZazln=rZd6cHx1U-6j27PLk917Jj?G z>$41ljXu_sHYf_+RPBwdl<)dGBIphq^tVZW#6LPdJCqLTqBi3QXgb2NZELFJP_<-i zgsWQyTz)PhV5r*z_D+&jOPw~~^KW;@!3;+@s+Qj+AMI@|{PJv)KM6PxG7G;~m->8a zdHIF!o3ZuT@3F}5HfN^HFjz0f|D0ujf_cob<NFk@>>p1GbWhe=G<7g)pbRa{|4qt| zOm@B%aF=uVXL^Up#UYp2)@bufly07Mq40nVSL`6$Z<#0)Ew=usn*vxO(UyC{$F1S7 zZ{%D&A(;__n$K(A7w(l3`EQHuHQ(UEBA13Eerdgj&!#Z<T120>47mKYxBf>=uFhPq zrNKWxwB|Y~B^Lk9^foR1$e$;uoSuK1vf-zpnAla9cv~tGR|YY&a<`+FUZ8(K5AFTY z;}QPzWOizK)VO%nH?kD;1VAwn`01z))rH9XZaLyo4xdKRXP^V=RY#%^)trL?`+N1z zD45rAwwU^7zdI<y>5}v~$v#bMhQU+{Ep9DcRYaQ1l1~>W4oziba7!>Z?%kYUxs#W) zyDRC4mJ4DB5rTCKw90l~n27E&?ni{d7-j?~-9Vwi5MSrV&D~H+Ue+GF>sGvadb{ea zf`6dQbG`MFHn&eL3(|C)Sl_i&=#4On(KAcg8t#7YU(Y9|Y86HD148w5lZ1?J$z4mu zYkvPFwEB|G%7&!P!&BX>TT792IzyNC$HFP}+n6c6dT)E1;*U-e*QvE#ewJg^N82&^ zRwDO#Cs)&!Jyi2XvHopef$~tj68$zB9wYnFb-<KHf@_8TrkZQemKD#fS5Poj7?&-m z<}w?ze625Z$a&Bk_@BR<OQji!oAmFtKySoh&BCQ`rD{k23FZHhK?fDG$Z$hwDCO|p z%h9&9v0gBge+eFp9$N3zblPZXP=@Ph&>Ih(iqoc-$k0m$6`UplRNB!vfJ2HvIaNo{ zxQV7=a5Gc0%-bU+Zf5c3a>6W7w8L(R<>%JDX}H3cCyP4ZpM5oQF6g0taN$%E_nsuz z|HSPZmyH`T`e_EgDCNyJpIN%hrsTJLr}RyYv~EMh1THVrJT*a=yp0hw*B8Iq3cC}& z>WK-dIF063z38T3BA>*zn2tJ%-HWFsyfc|oC$m=L3rO_{_*4Je&o6C}oZwaWj-IAT z{kn09UUcrineZX`tEcmiAKsF_)Hj>96)^l#fHG4$;r_r=b&sQYaAw<%p_V&<<-=;^ z^6UAd(UhOz)){ott1qsbP49L}D(b@bNA02|{P#ZNw0lXKEUN8+3_Sml!pEw@qw1X0 zg2TgTF5%FA_t7)TB>3ZVvyYYGmEl9O0L8<0l9D?2MH&9>mn{I_O#yTutWau(1Xjzh zPrz`<k|8>kSQmyl<|=5b9n;CHC7)BvNVG%bk&H6B66#7eV~AHW8oY!hABsR7z*3U) zyM*jZbuUBh2}ZQks=E|`YCd{=U0(`|F!jXua-B*>!W<a)mb~?dY7%kRdW^G*a?k=w zRP2f@Nd;=+v0ys8F#f>p6KhM)Z{KL^2zyatG1-hAa2^zKY*zfq`vyz2v^!gKeZwAK zw1?1dr6CHRI(S~7m0I6pOx-&44<DQ6<u=#_ziOvZgmE6m8vx}l!t*DN{`-%N6U@H9 z)*Rq!pMqoZY=ld|8O@cRO>mLZ<yBwefi2aq6#qxR!6U)<BzKn?qq9M+i}na!s1(w@ zilI`!SLM{W+^Vg%2_Oc;01G?`Mtn}vlVnZR2J)|wrEEoYH-P23UQSG(pikOn1#_KA zkussnxZ3G-2ry7yLq>CW9I-gcRmUl_*KBm>SM(N2hUi04lwo-y9?(a3C_>$IxNqE< zcQb5184&+NLFwmidAKw6Aw;Mol_LsU&Y1$3WDoAREsZvl-Yftm=bx@-_9?x*He~am z_1T{6Hk-EEaPGY9&1}DrLdTCu(NcByqPU}_+=NLJXI=udljx!5hO-CwKFzNGQ{$M{ zZxOEekW7cBiym_EA*&C?kV&L^l9mCVmbv8SGQKnMk^c+Zf3ZCIg5TXPUZM34%v<u1 zf#F*b5U&rl^w^N*Cp;C+Veo>+0p^__IJfoYj0Fd-EAa8E@q>(-m}c}9sdX9PFTjEg zaOnAbKVLaFIhKFW@#oJum9<PuZq(K=WY5h6{pG0xit*EoJ7qR#n?i!y7)Y&4Tl32B zsb_lkw`wxA0jB`IPlgucfe*(ta^_toCi^6DuPWySSk)2Cyb3|OUD5}}w%g7beU#^* zZh+h|57r^~(J?NE;^M$TYc)@0b&Lnc=CwwT)Y|I?=rpuT{%#Beg3a;7p7V}6Pq_7( z%T9p(p5>iBt47U>S$k@hUnN4UTrh8v+HQabNH~~ZtNd}D*q~5C^UzU}Dz9ylv^`d5 z{>*?G16+9%yz#{K&}d0~f0>R+XQTRLUGLs2%=nBb&Ie6^HdS>wgO$`A>5;F;blpZo zHgEPX<-bT6Ota)Ca=f-+z`vZFD1=9bfdp_Y+xA2=@2X62-^Q9v+{mAAk0gx#>z~x+ zf6o*hOq}jI@BhP*5Pp&QgA*34^RsF^To9+b=u)_OfLf45an>MVbG+!JFs&}3XS-Ds z;~?#f69(oVVSv1;2K*H(v|9v#b||n7n!J-a2c%2Rc%qUW>=l2DpSIX|WJ;3nxJ?*T zP{qnqp^lg?Id~B2<g3m%DS|#o?M|bXR}QW3)QiM0KuOrSuLF$(bc_gl34{ak-u-WF zBJ_M?5Y0+OU0kwJ2KK`otxbXU*(O3tb7=IZS{Rfg#f1YC06<O<NRa6eGxNnZ(hu!h zIzA*eZp*JD$E8q1X;IESZsC%An5>#-gSK?^%mduIqXQFyJPHgbKoTxym9P0?yw%Ha zox%~h#r)rTE-Du=?JF%}L?>|m08SiOd&fI>hU)@D`HVUk9jmbI=l>xG6t0l322HbH z;XXKFRA<n}7gnn1I6kI<5{5`jfZ={)5VZ8fJR~Dh@q4G)t>l(dm}riQGA=VG0zr~| z7LIhIaO_QsYa1n{sAxBVzZcB-D{P=$zTPquM5R3S8NJv03-iFmoAp7lh<fTh#yPJ` zhYt>czd`ukhy|%&@{sNDb4;a0YYiGAi%<G>U5m^>0?WG8k^%Xh^$>unLz~=E!`UjB zM!?`5EUI{rSIZk@mYAy!tvV62TTBvYnRvEOmS)MvMcBf1CtpTPTE?0#W+(Z&jD8W< zEhv%zb_s{%AQQLM4Tp5rs4nUnLUGF#Dk4rWWcyiU#M8JAuEPNX_A%d;M<z7dXMvg| zjU!{;0P()?@$lycm)PXNtjzghYCs~Iv9i!D0SWkX#_T@NAm%I_8T1)#T60rru}c1z zGU5DW!?suqkw~EvQ8X&I9S5wM^TXsw#@QNsNEXNWPbo~n#lOi!X0r&(Vfpb^zY%Zb zFrus^M=wJ|q2g36=DehelPy;{$R81{+(HUBajK6xJsKR{y+wZ+)dk)dzTj}md^oe( zpdrl>p@HV>{*sabv<`3;zQU9)(=%_vD`3g8qyrarm64vo29${;=P%GwqQ4FlIb4NV z4?fZY7p_q7PY?baIe+iOlX-s#h5&wT0Z&3H`rL4ntl-7C$X%mB7oT?=)-5c0a%KO1 z>1x+pZn6&U?&Mb;4}s%ooUYPH?rpSaI%B0ZUxAwF(C%KS-e)ag(v(j>nEIA&DF^%X zdF|pi(})}co8#lH{9<h%Zy>Y_ETxamek_Ze&3u0rNOsYtK8P%HBoG-|E@O6=7}SP` zM%KQ^`lX;V|MKr66OBgqme$&24s4PPx8V%HgtPtD4*EUTj~;qLb6&W{M(sE0tF+|A zxVw~-;U^RE4tl$W_eu#|`v2FI@k`0>AFT$nnqMAgYD|4IJR(U7)w1~boM+rtg0-PJ zAL%i0Pi934`1JYv^|ePBhp(>FoIMDJ^}^AgYa<%}^|<WssYrNflBgxoYv?%9g^AOS zctut}zh>?cgWdrj`j5z08S_+Wa4iE{oe-^c;;d;vqDykkjQXbPXu4z-F(Vr>-TMHO z*c@h^?bF>I!d`Xvc}d*TSL~5{8p`_<UoE%WrF_jSCh?W#qN-l*RZZwsg%d7ap1VdL z%HWPw{O{Cs<kuS=I~KItN$}67PL3V8bt&PMlkyg^<k!#}9A_hg<x@>hw55gVS-0#X z@B96<g*LA7iR(9i{)EYO>e2xLWh#wmvTtcRGBA##lJN})bTYG-ImM8;edUny=7ADM z$1OsLv8PG`I~<o*5%Lf`aarGCaxl_UU!!{6+htAsgb_bkg=p#UeVP2zJfplFp)Wx} z=hTXBcc<5i{Ze<tuzqcCsa`=ocQI?AN;3f#VMvGfE1Q@X*1F@rC1ajx12Lc3@TFTN z`ZiT?>G#`KdE=SFb+?738MX0wT$o+lULrXkOgj1%<UCU%ZEA5gbIx^KY1?CP_&kF4 z3llaz0Z8YBimw=uIN4y}+*;BgSm_4a(mG1SQ&tcQK=<|J0?41*`9D+HGQ9)RMFXhW zT8Y!`62+ksX#(l(3WTVWeem_axpPZp>ZGD;?@1ZgQX0;-Ha=Z<IuZXE#I@hhAf>9b zgF}u{H4XRL?mhpTd6_^v#-Y&oIYv$bIJW*>+hbCvv3OS$xj?8`!Y1g|$rKGpE7f83 z7z%DeWmE^AS%-;c%S&}&-HCW5Dn<o@xE3n&gM|qe{waYdl`+U0GQ^s8A`MIO;MCVR z_98@2G(-dS*H9hpFHsAZ@EDyG88(81OIQQJG4QXERB<lJc6^gm4^<E)YSl~0aggI- zX$G-tZp~|7R!9rdz}C}TFkk{LnX^<$RSag!^n+;gdHHyuvH+sg&-=zZqR5q2wK>|u zr7D(Dl`4r?=?>h+048Zd@<%P!)LSv9PO*SU_{$}XQx&Yk@Q?vQ5ko13Dra49Ql3vd z^Tp~)``IKCan<O<4-Ol_VdLvCLl~$gP45ebU@@u>3=m`%9w9h~P|%Cz08F(Wb|4R| zT?0!{>1|E$9W>a%@vinno;61)WM29W3p>)Gl34I<s!;X9)4iJwd+XO#s~Cj%I=ovQ zc4I*DO{gS6h@0K3xS~&%dJ3|s3dsxwU`}a-NJP@`qvwn<1;L0sBHZh!={nfgP9o*8 zw+MVpKOZAc9HZk7oN}m9xeC@uF!e-bKO&>6fs5Vm4JxrQ9!yUuj%R`oF>v5D8ro&~ z@KYNWuzT1wWCZz0);Zy*$Ym(M9l*FT2v?};zZ+yP7O6Jk-lGTAo1Ur%b`i=TO6{F^ zDdM&`L~<6y@rjC@IE8An87^@qhyDIfA&4(}znM#dk6EQJe%bf}Mqt%@4ekFHVWb!c zx9AH9VF>Ej?DCM*%N2b$$5RE~R3*B{mlm*+XBgpm%%}^DPl_q|2)-esB}Jc>q2m5# z`?yr=89=vj{=ZGQ(w`39SBd20V#^c99E47KKQRCgqW`*9rkf%`VB@zAGGt02hLE|| z9EgIF17T7~n79IJ;r6BEYU2dPDpVOBOJ);5=C%8lxkEp3ZlUTQHM~FQu>z_TQ%jnV z>)(>5J=cuFC~{%t!Ds-}4SvZtmlTOf(x?jEd+bDtG=`)b!}660c>%=mAV3b|n`mSy zBscEhL-NRydJgqJzEF7&TZTYwf5VcYKnPQN2}<fSMTSmH2yxQK(A$JWxTYDCg*p~i z3}+H8>x!R-8yknc3TwjpJdo9(N_W>{F|kBjDU!?E$rX4~pjaq6EDf`;+hoBrX5}@a zUg=>;1(%^nr%G-ooO2+mxez55-sNiX9z$qgx(;E>k4|6-)qndbOcLd`M<2Kj{4Aw? zfra&A6MhIBj}sO6Y+@2y&Zyo;le3&e%emVHQY`$07_5C~^#VmwX}JVoMQwnghR^`@ z`uvD&(njVXd!5?|QmD=|aJn9m&|`Q-{M>_wBjP0UV;;mXBM1Omob938K^4uZl5SL` z1T*qRZQxthQd!(*x2s@Do(<E|t69!4b6(LyxZ@aA;ej#s^_(<3Rwlmg4+3gB&I60s zPBvO76J6t^4J#)%B2I|iq)7VsyZN{hgXKsQD<sp=!>hD_L%2_BVV|@Xj!7+uIjvfz z4u&5hN4PH%rXDNvYVq+5#e!}ASsg=$z_#B1(1@90BfifOr>;;UBs4Mp;|Rgmg@4-D zx2YO3;#4_K9U+RS5H%m?$Ch6bD&bM_(|XG_KS=cfEJ52r6PgqR;7t1NatOa!nG05b zib@}p8k-A+uw1MBNTe<XR@8|*=P-2GJs&ApOiAaIVi#DRmpj3Dwlpv&|FXj<@NmMD zBFATPK(a7N@?Bb*<uSQZ>|KA!-xS$1kYiPmr;!UPP4i&yPvY!zBQe33&_o9TEkuQ# ztGDtD&BnkP7a9tp8tA)6KSzC>8(g7DPt`seXGx9M5>NePs(b@$09d91&}wdM_YM3Z zMXdSgE(eV-J`ul_MMS$%r|n64I~QoXMMQgVqDvU>=8F(%nrge5?ZA!0l937zzRHij zK#hgU1X8^<V|;uI<wDq+OI9TQmt^5LD?+pV?*T+!t+WcY)O1YO>GPpA!|{ktqE@fb z^c47JB2^Z;Lf~-SryW=ff(8-Yd}HtahkvcjTT9+XvYEu3c>~FMxe}s+A2myQA?>k6 z`q{caqx&SK-0?YeURoB4dFIBeBWDtavAj8HCs(u*1Or&V6+Oz$`U*}kc_nMlQT3)L zFJ=7V<i9H4o+cCa1mbz~CkK}bu%x)KKCoUlJV}v+atz`sYNkLGa^~gDh0?7oDYZJj z@>{vB5Nh@zqSJH_cz4;!P$YL;Gem<S(*$D35Og=?g1wD7E$Hnyg7_!=AO#&eCSPh% z&R9BvK50lC+9=%>vF9kYAWimM>02T#?7Z}X!k<9m-w6Ek5wB3ZW{Kv`_QAsk>Le6{ zut^X?ZRF|VYjQxXst-i=7bz#jF$7<SZJ(<8cOzE|f#IB+Y%(I^2t$b8<TGw-s{`n} z53OcXh(4>SpN>H5Q94*r_yNU>X%6aKGqivRZUqs`Zjr0s(n+LfS?Gaha#{QRNaq5| ztHiubt^V8on-&7-V2DDIVP#NVrFVVhO*3IaB=*O7%=Q~-cJ4T_z452|qt2xhTXOZ6 zr}M#=69qhnJqcsK1?Rz+?p)ch=Iq~AEQVr^S<BDKp4!SNu~Qm2+LikcTF=yZwbf-I z!UTu3omySHJ77EYbdMcl<4b}he}smd{L-rWNbafsweOs3-;(x}(6D)7x$wT+dlRHQ z<EF24(;i8~y#0nAqs=jo@`&}n?-qb(PIVl6r%=K^NmLHThIQ(vo!dbwQhK}92QdsX zCQj<fxhq#5fb8^QWBWrT7eHJvRbkTBE-b=(PN=H&R_^$_v;Hr25!A+A!)?g019;8_ z$E?27dc-gxdR!x>ASQGptX%wmFmqN-no<XLVZ9;EnnhJK7h(j&&Z@z%EuGuQ8?T7u z+qS9WgfU|UaPUl%ho)Deyoz*X(7c=%Lw=$Y|6>5v%EGuX<O3mc$=uPaCyn$MdOtUq zQQrO|ag^9l{}$1&M?dUlcrO4FDtudE^=35y{_5s6?|fz2pp}Ys^DE2`Krw~U+4U-n zxmm|?;nxqwHP{xFD<!+rddscl6pmEZDar*><>J}6{sGCCp_m{2%XkugGWh;idXx%7 z_ildfpy%!hn+N-m*Og;q+wJ66Lw}*6nKUorEcd2vz5ByIj1nP6il|)l`w@}kwfqMJ z?~f~s@GpIwdV@zgg0l5mib~2y4=@zyb^7^cvZb5E)m)qC6Ukds$k_kQVeJ&n_3nW1 zAK)!ZBDdp01yW`s8}#5KhEzqD3S;aKYd;KREF`oeU$qPIOK4gJzE)t@i<ShRuZ20L zPzeq5cEmavgSx#X3_jwg%>yl4e&$?$q;2I2v7FeQk06~<txWtQ$Lp8lFcb(3$=(4; zC&m-B!H;+ezz_1z_B^zA>8vILHBwPnNMb#yh;=O@h1r^Pji47QkocpsGPK_fQAfUt zMA+M6Yj>>Ns#^;na^n;P7eK!R(BnXE#@Lix&3NOjaqMSe6I*$-3JhD^>OV-bA6dv! znFwOzgBkMX_Gn(Hq(CIsI;{EI`O8|9EP^AuMPsC0+in045N)Z)Prf}XK}BfPRb|e- zgH-25{k@s9_nC5-v|xjAg@p|J4CYW~k)#;wd*Eb%5mSnYYkD_*0bKIBm)zP_)DjLE zD81jk{Gnc<5`yE`%9_`mEIuXgH80t~(y``f_=JofK7B<Us?ctBw*QT75hDA@;uDV1 z@-5hxYmxHt44LV>GDZg%krVSPHL})qSi!dG{uzeL>XH1UKI}P=<&6#tey-;9D~D2w zY??xKgJH}K-&G|O6(B^A|Mm5E2$VIzhD$1`Y<>#VFzPCK{gM;=;`$*`S>Y|3_zRN| z3CN$1F75lSvu{!=;pEs*w-Rm1TcoYckEO2rnnRw@{bl7^_FRjPe#vP#*A#HgOAamu z;C<K)fVt|Z>+^1Q@*Kh=(i1c31Q<XF&rRcmbO1ptn!GoLw@gDIp~;vwwGQ$3K)XJs zpqdi^2|UonYnu}?N>%J=fh&^oV!mYYP^c*jCuW5hBCoRN-~d|Vuas@~@{?q?*u!^k z{X2qgbT6ZtBw0owa^ER4lOBt%h5cd+dcXFEx^f10%BwfU$hVcKNVjnneValn&Bc_4 zvoE|ibV%%GKH*-Gqx#g2o`tS{@V&gp6_W6B=u9ysV8zp(^xDL`p2mXPB+(JX|Aca7 zYR9`ZBo1o#cuy$B%t>t3QTe*;X;-QW*Fi>X-fNIzJh{rrI(LB{#D$%V3d_-J+YB;# z)LQ3kb`x-TsFpul<Zkp&9`~VXAHIV}zJuTARiG;UVwR$!IOA<~OXI}TV_Hg)swp!) zow+*cVBIk2sM&+p{ZMy84X8?3cvAsPzVO~DrdccnWX?J(k+Km<qeK8fav}b?6FCtA zdrs70reTL_55aehlA@heI=B>`98n3aojL7|k_d{LfXhZW382za4ciP`L~_ifD{T+- zfPpd6$WdGLGlcRD{H06rZP0L@(mg_ha&Z_|F`($;%!W_keI+_d*LI%1L#MTUeMC8~ zoh_@&M8mfpXs=^64rzUXfbrT3oW+8whC=@dVmf-$2!x~jnkihhWRP=Ox}=$MWaCv4 z0h&!*bqxUo!*W2ViP#yQB7KO0y?!M+8x~E*M8Qs<@@WAQrea1(RXS3-u{z&g83_4d zu?07mp=Q9%ji-5F1OOXj4jJA1M(IqrgmUQ`)p+gkkh2u$>uT(oliHX{ge!OEJrz^^ zek7@_;$PfiY2ShU(3E}WQpE<;^V?72NT6J&HZ}dO;q`t{HSnt|3Z1M|FD@n@APlp} zOK@IZ#40t);pjt|;?XXGMlFWk1RrzCLyxLckau#4qpB`J6pa<VH5zOex|r;^)4JvE zdXu@$Fr?vl?kf_mic<#NFpO`Q4TPfU@>uVhZ<i=T^z7N03E`OEVoJBgOtH1`ghnBN zas6IMfo4;pZfxA6W`p&7>gtH96>v<>t(l$u;W%ahy7t;iQ8kh1BrkDdw-=@ZQ-J<! zVrNp0lAA}A;9MY%&xnFN9aAkKfod(z^7bzPt05IjMto|W?pstbM!bl#jVjj(SGby? zm>_O?J`{h|QS0Ub=YyR^_0kO|`jy9g#Yz29i5%_i;MNYQc?os|Np`<FLJOWm2Ry=X zu%LyFCW-715HJl$pi^5BEV>;nR|4rEKL*;<m!m0(&rm2CdUN^~(g}TP<^^Teg}~09 zmjo~wf5dTg^JH(7PiUa*rcNdYNC0J&N3kemQMMd6ky|)RF+Yxz#B;-Ob}lUj<wB2` zb*nx;N7o6`eW0NMA3Qy5<a4iKE};R<)+h_D>?(Rk7z%_I&U++aQLg6q$|ma=)H6R@ zIkWBi-H3a;S_|`hQ!mS8f--6L+uN&J-q{j`^^|(VupVj%I}IBkwYtdfdg2QH?}LjX z0Ei7p58;mhTqT(>aMu{M=J;Dl6(V<cMr}A4G(ej}B#CAApjm7@LbhgrTi~T*va21h zE)BI|)6J6v+y++-Bx`T96Ii-}IPBASUl4=dQWyXo)y5fl(ai}q+tNysWv2!MxkxzP zCvw6Knkl5vFH2<KH?W=;Gu}>GS!f`R+d{`0ey!_-{)TH?uStdX4XRcm=H(G=lo#2X ze_$<VpIF$VSf9t>Y;`?Fo{Dki$^bFG$~F=lN4%b%;wOTOX=tHDpa%n$VduIHNZ4mP zN~E4-s7Hr+@8fJzr6jJZ3;&)h;`}%cB1<u6tQV~X^vQaFr2*UD>0RuFZXg+c9_2pC zHc1HAv#E;K*#<{GAIh^fyD%tB)x#`}nL6Hd5YyFM!`Nd6b&OBCdJ6R98+62Wxw^_s z)qF(xwARa3PQ!2l*7H4qB-v+Md1};F*Wq^2_trNCqrp3q5I2C(gRquZ^&cSDx}Pd( zOCH)Kwoo9Pzykl%lu}jN&%0MvClw($6fP#pG??BCB6lM26S{)?mc+WkoXODi_Bx&= z8bEFc_#UE}3}#+<o!EV*XKq*_5{64*`C0)3*pTM>#>znHgfM4!0Kd8KuD9!+w6gHG z7%kiW+hWS*CbxD4Ubc0vs_QD!$22s&w|hS`R6%CHyBrL~KYuRr-|4OOwct6p@EM^| z7HA19wiv`;sF&+#F8$l807xi_1#a)w6IU46<OwSHku`Ga<}v(n^03NwV1PZFPu(K% zRbGbj%)00A0$v$gN>c)Hb~W{01Xw;Wj$|3F7K1^oIEq|=7eb~1=}CCB?S7tN57`<N z5cy5^k~jpaVW<Q)py?~M5`Y}UMvi921d6a>OpbI@NP#}`Dc1pUDbp3TP7RL5R8bD6 zT#tms<@%^{ymVUz@JrG+Ein35Up=5N(zQ|$falQmgki!#dqS#cr8Fo_{KIuh*n9!_ z2CKnx6Kj4LhO$I#$4WyTb}Yx;<)|>*p$zrmYtSsq-s@o1n{LWzsJLl_l14qchl&pQ z$POVsmr+CDYk<rESZycffuL2aC<t?U8YIf|htZrT?Hez_^OC(!9L?f%%^gzicDy!R z*cy-%Xhh39mJeOEF2X4+l!3FOuO+MgxL46>SQ{a7`a&4Kv1UJ+vFE2&yWNln_u8%f z)1p)TK1<FKvOqZ#ep|fgUw)PGp=_-@Fcf>)1{NTll<<D1=9%-wv$6$cZGT3OtE{tM zt#ycfv*JJoGW8qm4EDHSd63$9=?bn`F1uQNr$|={eh1X-UA#v=xiOoil_F%(6$<K9 z%A_<1*Y7yGrHH>Rfxne?MBMFYy+Anfw(YVJbyz=&ky1@q9NzoH)wv`Mr>_i;b<lW` zB9wPL8B0VLgg(|#!wwe=$SeS4aUj4u;K)bq^q6Bqq>T(jV(E5Q4Bat-J_K&<{su*G zF?&CnVNUoer1~bF8f50;2xXR-C`^*tKFk?)%ptENox>O((91{y@SKBRb2@e@@l>-_ zEI^LM4xbWRBj~bXp&gL2I*1YsC^CoiIP0luVvww~TZg&rW|9M;$OKTTH)7}Q1gZVC z$PulbCQZ1$V^YTeF})I!?i$LN8lmkS5>R9aP^82d?qCN#gJ?9H85t;USvE(%Fo4*P zIaEMKRZJj$PaSBVKpzL>UzH$av@v1ZMnES2izy~5!U_6BBA9^^HxWCPU>^-<{(`bo zAncRjnD|NYZxVpIgcI=vR&DvD7IhoAnq(+(M7QV^$0P&)eapoP0igXbT@nB#5aXE2 zy|d}2#z014q{ix0g0#&V@aFrqWus~(o{emGbmT{dcTTV2n=r`3E{OiQ(^F4yM^510 zC(+9=1&K`Li|yx_H9Rr&uy@v><XXFP2?v8TSh=hKi8^gKQQ_3UK^T^wYPMHADH}75 z<@F>203nZrsVIw9YChD^lmz%=S`k3wVK2EBJyk7l*xD(eogyyORrL<LWzD_oQdG;{ zMp%ipu_R3kk3U>PHLoVek)_%|&FE!44-9f}{&<}bmHZ^)wnM({8ZO%ky{C@kh%Y$s z#D7onF7FcLcAwoL0ro>1(-bOIF^4!u;YT-adA{;HXGlb3zQCqH<eOF{+5yS4q0Aq& zvxWOGX~JwV2>IKIlMr8LSYnP$%lT{J7`zQbZiHm9%E3h9x?PmOVm-%wMY%KB>)>`( zL_XHS+@4U%OW@r<zn@tySy&4npqSSurWhyVUUcNc>+&6k4Ij}ku?XC|EV?tiK%BVi zsqZcU8I_MgJ&2HKAxrztpExHd4XOx;*JOq29u^ZGJXTwMYC>WpVP89jp7^2csK$k( z5x9yGo#W9MHN>gy^WM_%YKg*_p5VBL*1*@uS(AFQ{;|-tAPq7>bIO~qi;<`;&&$3D zn=kjmR0K-^cLpT(w@cn<<c&;k6+e9<9=57)`AhMlVu}s6a%$c{2nTlEOc4!LLg(|v z3N7G?MyfCAQ{k4ECU#AQB7!l8iYbV5z}cuC&o_S6p^6Ggj+c&u5^-cy6Goe=kqR;r zKfkp{a|AI1Y%Oo{fdMhiEOOnx7)^qUrj85f?UL0+vUSENpTz9GkzrS!yW52z!2*6( zT-2<<wPB>f<`8!VYJpYU{?&x$(49JrJana`CmE?fqjN9P&v4Bk`X1ihAM?HguZ+Sy zrCWl;UC<|}<E+%H?Whb8d6W#Nc_9la2tV_KSf9NxU4hJI*+qy`y$j}ollUPo^6amZ zm*i{oUtkw?G4d%}HF~6SF%xg|=^8;|ES!;h0jj4><%XkL#n(`GScot{DwLpl@Sf8D zLofvz1}8DM$VkV~I9+HR=0TI?;$^?2I+%%8av?qI_W_0+GC9ogJ{ffvIG5^zEJ`?V zWCBrE*#esn_{k)3XxYy`Fl*TY#mz*$qL>9;Oq=a7t*2gj8s&svL?s(<gNb8cM}`)$ zh`#Tl5Y^g;K?Z?RZ35n7?`{6zMf=hUiA1SG6XMh2MCVeHXJMWD6GOu%JSefvR5Cz| zfx0UwUESBlC8M5a!W{sKQZM;})e~=$&;4*y_+H|a@spL}Edh14u6Bu57`mdk;iVFQ z0XbWRc2*>Lv5O=p3~2^%IDrX^>CnhN9YR6vRFsdk#a#J6hR*$;sXvb6XE%0n*<9zo zjhJh5ZMn5E%zbX98*?f58mV;O4I{aeQ0|Nnk|gytmL!#1Mc0u^k|>p~zW##q!{>3% z`F!4=*Yo*mgH|x=hqxw9P6s>=qt%8@1HQLt;mt}UX&(2iL)wG%^NOav>g4uS+uOm@ zSbMoForF#3@56#Mxav7Fn$6g}GKtA?LnCLUFP37NR!uqAN^FiA?$%K6qK9kY`Snii zQFitHxv*^DlvEfzBt@Zz0S{kBVM?iYA{AZ{P8;OWLUda#J<%nl$d*y>^>**|74Hl* z?(h(+>lpmkN>TiT&4oCHvf~P|$y<&=P>stOf?3Co=L&My@Vj?kJ~x(EfJcYgsn<E} zT0k|o=Ax1q(gyb`&8ad89tF~(bre`6(_4ew+XlbxsV=HL@>X9Z!A%HTF?Hwf<9T}H zFtnFw#9OjM&W4V>msY?!nA_LAiwRwHgRjmTeAFxcjm7N?LwkB+Qxb`7>@5Mt*o$fZ zp~KB}5WpUf6Gc{C5Ybr&`}(W72!FJU=JS%xKNUEYu--#fE<B{eR#YVpb`|JVEvyRL zPQ!7m_5HdfZ{Y>FqZiwd?Ep%yL&|p)W_~x;iw*M{g|b*ud;3z-C1(oIm9eAJ`dLxX zJm1A2_<kldU>TM!xpC31SRpu(?TTi#Nqsmg)>_Hj;)ZUr!%{TG1(EJoPTY(7ow}zD zame#Jct)(;gW6rWKKxAI`A(5)^>4M9sQa<$M_$G%9FJ3Iy%z)%(Yyj30`#&gS@0y5 z)G@YH^s@9RJt@|*_rD)H>5O}kESPs6%mW9bvY<OiG27c9k)!Y&rfV(`1r?PaQ;|MV z35(pYfj${JXV3ZCOf1gQITq8t9jPGydq8dAGC%RZ8n1jIAQQ=gkDfPixL|UMg?c8f z@XQstx7kj<+$y%@dhg<O)j!ueZUl`NIBb`K$FiVaqp&E(?G`3tN&jfZZ=LlphewKt zY!>`4UfPodb!9?P03@o?;7l75V6j&HrBn7pIhF9(O4x~IAIWYs*ge;n`{))q?rP7y z&(E=tu=NuCsyG;an6?AhNH%xlHlC3`yg~joA+C-huZ$K*bCBH(=~#xsQ=_p1FO`m> zga#a?I~u1od&a!2&=X$~d4RMF4i*l;bCzY2naByC{Ke!rjGD7rVvx>;Pke;G9WrQ6 z-k>0)j-gSZD@FUL@Kb#cohhNIBvp>oG3oXUTYGiCixuU)hj4k1G5*Q>QBTw+?^xyK z-%8NB+6Q;8%zxv0=S8%lKY;AW+KT;jL~5n#{@14`pJF<1Ao7?}o_(;xOa#wV=iVry zhNWXFdkbPdU2tl8mFT)efS*6rXn=&+QlLS7(4<P~aJ`g6E764|SH5VfJpQm*nzP<? z^QFSCUToJhjLKJ#j-fd0`D18y#kLGoEDOFzQzbAQ?!-XOtmIoKw_GJjhvP07Dd?Mu zo{oGi)u-BoTtg(VprI0Y857ZW1Nj|!CYaxdOPm%6_b>TRhuwhh9%n_dpbiXZc%`&O z%Z<YBIpChrUymMih@@r(q{j0@cRton6#Iwl+WQBI;+(3Ad0~}@I!S`wjXfg8QM}Ry z%|#zT=Rf7)b!IHkI}e!+mx*3&((&wro+V994ODBb?AIUL5AmCJcxV9fhi6M*c70Mg z4C%PG2aHN7HVeKInQ?xoc+Vwwl(Ap%FS?@vI_Ne?PN_Yt?5#o7^YYW{)TdR$;?$P- zQrP_m^~v5(Gh-unu~1J$$Xkc@T&a`}Z95#^9{9HXer2Kvhi~<QA`erbNy~@=w96YP zaF2w@dr&mDX*%|aSpsAWpCNr>RQhS1w6W%*8yd<WNgo8|mfm)3K0w%h>ycEuM7`~D z7)s%a#^~~^vsWusyComB&6a!3kcXdYR((KTpBd$0-d|S3zi_$QaSUAsNPD8+Oig%i zXqq<Y^mo6i-v;H>>=i&corzuSrCMoxE#x3WIx|Gtw-V~Yl=_Rmm%RP!pVqCNr_eSj z=<nHIMZ3m$Gsp@6cHCo;)CfC83Dj!uI>eMR99w48m+Jedj!mxb?Tbg}j?U7S?WZ<` z&6RMi*F_P&SM)^&2WnEl)i?Nk(sq?me3I{ZA1Ox$G?pa&d+jUnT^kIe_V*+@_@Un( zZz`ny^Rd@P@>!)gD)K7n>wuY8GY*-Emfrp+@>M$0KNo@0$#^Eb?^U5RCsN`yRdL6v zj$SIneBSHDM{wB%<7Od0K&Y2<E92!ZbBCwHs5rKhW8su^#^`*&DE$1CPHZlW)(1U$ z#WgnYBH)Pi%l^9iBmIQDLXa8yhZ%ZX$pWkjKvV)aSbb>1TKeZ1rB4g}tH|tJ*p<<r zbQfex)hd9~_DQol)R!@=yPo-9>B9tl?#hv2IWz#Qdnp8uO7z@3aNb;{4|x<i#vD-& zr}$Cb&O&W1;7kmGlWuzi3azZAQrN3NQ$WL`OB*QshX2Okt){+p$<UZ?)SPd{wp2M- z+q;}TYg&=nzGumi=muIGHgbh4%uoV*=K{-Baa0+Y0lb`~Lg7hkX=Kq@xP{%_iEkg) z*%eOu2G)LAdi-29h-#R<$K^4~sE`OG?&o|tvEyJp;TTB9Z0-C~gKy%Nt=FuU4fMP` z$Kx}FR+xZXfTnKWS^B}lfxkK;Q+o%l;ba;09GY8@b?MUKvP+;!*R{mCp`BQ-_VOG4 zDB75jckYW{hZm<|HeE8zgZn<$(r=AJ)|pRUF45MPOzY}$h<7EShe6_DTOqgP{q{dG zjh1Zs>0z4OCc2?4p~ngg<W0``Z>Yc)aC+Iw^-~eq7Z!4BvM-fvNHa@cadnL>1rtlO znR*MM)MaGS0bz6DIJ34h%^z^lJT%#^%Q(Jawf)wsn1AKJJv*I9)w3T_fIlV7rO0%a z<<k3UDG7!#3!b@y^BL#GUG26|%lMB6$h6haahzs3Puz#02iZQlnWEg_n#=l<g_4>a z$J{B70YDPBZ8B%|QO^}1ksd+}C_2K8o*0N>H?<lK@w07Mv8J2@R>B^-v+^}FqtqT_ z_b;{ND~-6Xv2_kM=(x96)&u;)`tzfpvuTR{<mn|-QmXEuTFY%$Y1x}>5}`iOt?Dpf zzvXPSUY<JNc&vg@?wq})D;S?`J3ku0kh?h_mT^ISQ`4B6+u`f2s`|?FE~=?UGsbnX zCy$1n)^$*}2eNBN3|9eoYLRJI%ANZ=By3(;BoGY)LUr#z3)Wv5bya$I2zfYq{Y!eK z;HA>BTB*GO-ekGmNyp^K@GwZ4;V*Rbo~<@~XM{>OF{klJ!NSq`>+@QOiMr~uo*>_h zBfnz$_3ij)4LNf@oAGYP52H-2sC9~gCinS>h>inaLKnroDW9q=LYk&Ft&%4&*(IjY z`F>{kS9PUYl;>L33p-lgygUDXv?ixSN<R5{`7w(cDb22g9mFbG4@hjon^UM5p5tiX zL{I79$>i}f$2XmIZc6*u>LWN7A?>qA^m&r>2Ya{OciGNdG3&3hSw3Jo7J=}bm;2dJ zgL9Ak%$;AP@1s_)mkDY2->`(mlH38b)*dDVAiqNs-!H!>S4)|TH=p`jF;_P^p541Z zkEy5m0)gMZ{+C14DFVZk-N@9#mp{@BXnq>5oz;qKcvr12%QEI4e9SJO3;fqCoAb~# z!#hd*O(WM4Ff}no6$EIx`oXJ$?^CCYh8`(xWE2sRjOSpnN-`zQk=%@v<2h^9vU&O@ z9%pK<X0HF9oxQ;wp&OR}$^b8Kp%IY=mK*xIrI4^RH}5f=!|W`5X<XNzeGao>gEFR! zWo$=RZ*1>j29&BhLdGbr46YLJ!sfjDJQa!U6i~eIXqVNQ$OpQ^tJU0wJmwINT;r^> z-v(N8&R0$@ZlDWy{;G|aoS~LEk7B0kqIu`C3ruYvH5>{&+~<+8&D>MbE=d>4_AfsC zq1yl7+Y)b0yh4L*8T7)c=cb}zb{4i@WzQIbqZx)dIwr4aFl4s~_!9F*A*z{AF?lWE zeW+cTcssCW!Jozbvwt#v$q*c6wwlP<mh}I4(ni#N0zz7oc$)k!sguaJ1sBWfZf@|O zHA*<sA`Ql@k?i>JX?>;G3RddRJ$`pXt6DOn7NN~(2;ejdQdX8xbRqVSb-ncFIZsdd zOCg5HTdNPAK8xCVMOt<6?Fh?xl%qK>DX3)l%lYF#N^{KelmGN&FU~bk#1tv>jk)%d zs;Apz2@K$cafZ_|z$t^!Q@8)IA^L6JW>|RbR+$l8MWwFR#Tazt5w0TqIfvqkPd%qC zU3&CIp1hs&7LJLNF3~Dg2O54gM@jFvvErit5W+c8+lD~_0X~P)9&M2cgT<E&s0}l= zk~^t#IR*W`MNU#JPQ%f`=7PWi-s4dtrCN`zmnpvta$h9$ODo&gEHP$~>o0o1$_aep zPV<QjF9BE9m7HqK1rYwtN4A|T^mO+%$^}frba^J?tH=)f17OKPqnia3rQiLBkbZK{ zlS;HZ+rS$7Am~!^q`JjU$R>DRL8W&~c9s;oxz_(Q(6>=?)uY6?Gj96LTd4Vdd{^KQ z2L%vufX&K(wuShsdxa2n-?}^A%rwOd%c+JwRWKVSRsLR(*?)^&)bi28#MYI1%C2(F zWhsx_U^R^9@;xaV3eIC-pR?mi#v@hnQ<*_E#3>jzP*;&`*Qg};Bl8S%3e=5*Z0|5J z=-)G=8D=4~#Mkevgt5lL<abfHs_?N)(z^!53o&A=f2>UT&+C;aVH<SkjbEMb$G!E~ z5`nA#KyQquncjru+*$YP!hwezxwD#~5vtFlmsi@-?bsak5gcFJ;LhCyrU)a+jpQg@ z!&Sl#7rl4d{4nv3G4xatwK_gF*q3(a-ZV|NI3~j<I!wNr=`zI-A-xwth}}5xQzI$; z(7Jxrj_8frx|Iy~<Z#8{rAPFW=gSq>=g`GuuI8evff7=T%>-x!I5k*RqbF7OSj^V< zZ0NRQRY}{%F7>Eild??-lg0s}>h~>aR>Ck@>OU*LtUs{e-Rbwhpo^64KVS3R_7FFv zp^R495XdkUb)7})wBy9>i6h8437kQXhb68`waV))5~zMMiEm4{GP`=|en;iE7hFxS z!Vc0vhJ2oYg{npKJ_&kI{Z3-JefmjQr|bM>Cz*TK{T7Ud?WQX~Zyv!5?|{11C;Pzq zN_!09=Tr9hWDIi)nKOUt@~GN<;ynAj;eAhIcfyjQs)E7FQ7KM_d<nvvt=U}$n5nB( zr5Z+8i!MZ`+O&ue9$wYTu^Tvi7lY!toc#=}_F)ep|5M&M+Le=sXj+Bnj96>p3pewO zIDnd5MeH&>747_Bl?AgQJ}j5Kak%xCIbG3DL9xgK>H?W%d>IGkKdSdKeG2%krdRxM zhXt&~cZD0=uk72GOoZor>`3A+UkF~0i+rt!@LUU5;>C$|ZD)`MfRj>0HpIv^jQL5E zP9(qI9r8{6dVwus8x}^T*jBR|6EoYn(FiP<tu@8f!g2@m8-+u9Ke&*CAM|EPa%_zz z>ou+t3F5aK*->-*#+qijF}#i{{1A<V5&^}+x~v<w5rkB=QEr5KuXp!`JB&}?5M>JT zrFL5Z^Hl#nu9LvVkpebF!(xW{4{zE4D>4m$wwyxM8$<Z0B^*ZO({Vf#a=R1!df=#8 z0m+sJG{9sqK<=$W<2>>x7$8A4&f2=w^yFdlY*<&U$-Lp+psgm5D_?7^aJ-AhILCA| z6|$&3(PU*M!H)F^+QJ*%(vJehC|3n*&V?6y4cP;I*T4jQQ#fpc6Ay__EsV(D%;x#5 zi5OTL8byD8xN?J`$RBo^q3~VMd;%F-?6l<ubKr;~(xH)OBLoqITw-v~^(kl6qBEJi z**Y46S=Gbn@obhsI?<3i+a{Mn@!V*kT9r<RfW~1vb~~H0CXLo}oj_yu(h)pLABeu( z<ZIIJlg0Oer!uC%dc-mxr2=<cs^t*aKU$HFHrr6AMn5lcpSSN36z6jI=u)#f06`=3 z>1?ivfd2u5$b;J!Ff#jYT(AkGR7(&9GQ@$*`+AHkDbZ^f?X)37wu!~2L`d0sZ+V;^ z<ZS`>zPnLXaNFT5q{7r@4$cjr2(KG^1n`D#Nce7Ou=mE5TM2)puOvHVh%wJ|s^l}B zdAp+TWDY@T!4MzHf3qK;&Xit{Ha>8SE>uGP)yT}~yiq5l+wDYC<~dKIWvfUO4)LB# zX0A|@fg?j?#&|Yxux2o%P)XpmAgJtb*nrLJCpe{lYISutz-X>IU|JQQX)?q;tk=@r zW^~8|9t>vRIOOr&u-KjD)*u;nU_!isRLc~Q=M+>p>1Kll<FWi0EX;I`M-f70jkK+Y z`1D-QRY>Y#FrPs@cOw~@9b8<1QTz8BAq5(7Mnm1!xW?;kWlt5o2EzM>lyqRtJQD`@ z61>8;o2woTmd!v`t=Qh*)$p9ivygZJYhY^}SC_;)_y<u91tv^}v3W*%&j7bYczvzh z2c9>BAh=QM9e#n|8p-n*b#ow_F^GnlYA)Vr@D`q>7K!f@E%0t@_fGNA@ltey!`w%? z8(MOe1OXQ}_7}oloOJ2|9#uO-bxI&KGNOp$`#BTkl5{=(MKS#{#G1&(^^LsK$fQEa z_x&McHfN(2-C|x)Gs{(_k5&aUrtCLOgp)_d*llFub>7WGCIW*}M^sUrObbn?8S0J( zJFoHgHbFE;A&fqTX9?762&(z@X23eY4$4g>W5FKL1wP$ir#5~%+f0H`^JYS{m^`g- zep+e{35tl7cpiZTjc-@`xM3M*=zO;a=UmX+-NMsO;Vd6hvacPfCOcY>y4wiRHuGEy za#O9sC}El7uZXmU-NlAk$O;&U!*<;%5A0u_H;v5vsF~qA3U=No;S1&undheS1q`9R zBMBCevau$CP09T24DMEz&z1~<6-e7H80I<!Muov|PGft;a!b$dJ4-AL*x+m;VoN!y zu)KXMgE!P@zTBv1Ed&{$D@;t~c%<z6V~;G>I#ifE3(|IAd1NyhV%7(;au|)*%BX<? zT<}>T1DHRtbLV=KXB~M*Ro^HbfKj{ybw;3cGT5T~Z1*aaFMtM<q`XR??(kId$z6t1 zT{~saG1X%}EQlVPNA0e!;%I*u3xeUH)8s9|M5z9`vnxgo+TC1wwfTczJ=&y(s6{vc zV=HWhSh68nqaa1<PV<c%#5|~GZ`)?p^!XyApb0iNbD~rkX@6(BYUaO$O+i*5w9hEm zvCT>1KB*tgeU)4Q9OK6@cZ7Be1Z#mm*jyC{MdNa(Q+xRyLa6at0k)+q=7SF%1f}Kj z)X5o#zUpoxUmxP1U3uo<a-mjRQk9L}OdxW<D+s8yA)c2*ESKGD6(BY&kOiH$c^+J~ z?zL0iuPHla`*4soz#t4=MBS))F??$W)EvHF^x}H^Mp8)e(chgxMH>__|NGa}Z6sJ| z3O`){bzkO_+3c;Op_Ui!oJfH8H1b{h#&T}lPk4;^5H{t~&DG9TECSdaVGf!I<b)kK zLNmj|maAGaSUn$1uoNtQ8;SUPNoACqZ~Yoj=Bams?|6p-WDmXS={hJ|TF_C?f6Z5) z%44dKW8nVZUifNS^7$%)At-f2zk%j^M{nbd>O-D9btmyv7!dE0VymkA0t%GAAxFk` z-IxyaGp9HNLk$>Qm*9+SlGL~MOKCw!Lu<kD=Xe!i!z*LK(O9k$YbI}97{Y0D=U^vp z!zRqFUvHLxE#^Ul=<T?{^Nj>lQ#E7L!-@j1!|#`&UIJ&Iz8yb<3fvhy+z>b1xXM?k z5gp^F3+LknkY00%{-xqas0)7cJG|}-Dn{?q{Sa<Mu;Ea|buh545>kvcm{UgXc4#mb zl-sagaY@;mg&;FFuh$x0F$X3xxn|_)%{Yi@H{Jps%IS+F%!9tVOx!UQ1pS_iJ)CKv z{<ey`|JS}ut5-Xnv0%?=e)zFj`V`bN+RJbm5|`3u&9fmB!A@&b(_DxLHrU|R-Zxcc z?h+mz3wCDnXJF$l@bRra2nv(4nJk;gP5rX=W-gj%yS@xEObMg;WLm9RY3734PedwW z1SH&oi^d*PG*~wpVn&ZLqrcebZ?(F`HSXK_&05eF{krag#hKO@OT9Z@Z8F4t>u`j_ zvUBUTQ~7R^wrxW2wmz_l1Y8uv)m|%c*{B=~9=rJh{!<Ilb7S5o*a_9%T44S-GEG)< z4b1M+o@sj=vT5%2#qwHQhYb#*!Ui|pbma^|coMK}aGO;LSZfsA@diBcZevgJsr5id z8ZV&EK0NLkrhezA@nfy=S8vF?61a5JY=|HHT^j?jsX@U!6Eu$tg%Yy_F41rB(R^2U z9Ij5IhycBI`l3jmkFk|qJbsCLE&GC$+^%(R{sr;}{kpSp+Q<jL@F$X#vg<-DgCQ1l z&Zb;Qg^5ue!6{lrko=G9qs}$=jshfH6Y_+R4Q_}hx7dVtrx38U3BiZ>eptRE-5z$s zW%hBs`xFV8$<NttnDQ9vG%85=WO?gXoKrN^J>_ER9{!;K{#)~S<)rpEY_zI>h7uc` zCy`YvJ*yT`SY5L5eeQ@U-*O4sjZ;)V?cZb}T&R{}C;LQMpt;J#og9+)DD8E2H@Do( zqcu2_UK=1CI@>+^@K!7T863I<9ar>};<EU(+ylLt2Y?i)yF}fcY#6h$ZQV1*g|u7g z^~N8EM<G3TA)mXghOml9!q+jH#gxGr(=u*J#(<STdp*O;17yPHVZYaM=VONaRQ)Hy z3{+pINCCPfV3HCGCd+DSjqPI{o=UdhF+7N#ZY23b!bbWn{(*R~f9O%ZTP6R`zHnnR zK@70pSn4B}nHc_M7i{cu)DQUH^dpKtCdgA@@)YE%H`E32Qq}ce#FpDP@|=Ug1fapi zQ|j%-)vD2f18F>y;JJmrdJn~e+T=oi$npj~W!5H(r}JQ@4~!aOd80{yFcz{IZUC@T z8ywxdmI+;X+4E6*&YXWTM32iz3^72`nLJa;GWn>Y!tmBthl?q2=!U!8kNlxfYJOjX zV$V(}C718GE^z+AOa!n!%Sy;8MLAX`nj(lLGn_wF_MG&9Y$bzra(PzK#{q1VMKDBD z$QkxAy1c{agbKV)ifyVYz;X^7l2SPIl+-N({mPpcv@*7rj@FgD$UJ&}Ddc;ff?SU| z6h9;=eq_95v%n8HvQ>1WP@nH7f#6vO_Qq$@D9}nzektj>;+3EHVESFvdy0vT#Q@(p zW#cVH*skf$NrLS4ENVZ4mVbu$85^BwXgB}`s;ol)bjj+Da;tB1%~)L3zAvWf;0|fv zrS#qHhpdSwe(zjZ!WtmYhvs%gLVU3fw@jSRcEfuKE7@ysCoI2KDsl11Pv@iUdKbA< z>u2~*0@?RnOXQM2`SfJ0h9(90q6q*Wcm3!dt>Q+X_uc`qNa2_TLom&Q*%TvoFi#iG z=7!6G*TA?eoo#-|*qA*1`^rE#YmFGp@VLWeSaJVs$fWP(>-$!FH70FxmsK~9?(FLT z-7mE{I6KmK$iTOd>!Cf~EsUbl0Hc^O3&E(6mXT(b8HmnzbvxS{ehUeFeBzQ#+Ef=C zblH`b&IOZ@6u%0?(zWQY2?6@0ZT#!Sl71=7-fH!aljQ*o+4<@$VD7@iAz8L{l!WAZ z!&L^bh#jvrk4V!~GmkkrNm8pH9#VGh*>j^Gb{Au|$py^bJDTzOSyxccIuy7%2R&yM zpbxMmHY>A(InV!OycpXKoKr`vB-{86H|wQy_aqDQ&<;5Y_-Z-8)V=52_qMPJH`y`@ z45mz|b;~1cJ~mxjl;fXsiOWuYVxArjLu?;XGWkPwqb8X|2WV`V@6#}@N}@{FJPyrO zBUMBl+^@E)HcyQ_S()YpB>OQ`!%ya=o(*lTbcx+b$#aU;O68Yl+vQI_r~fyd4CFW~ z?5xcr!s>=}cZtJ_TxUTf54_X9pt{2V8qC%^F;CJ4e3bY3<JsuyAtl@BD*DNdqGkBW zFZ({+QHcg82~O*QzPvsStVWG9^&a5UwUd~0(g54Kdt=hN-q!AP+zBqKRF4z-jqi7p zEaT{fr$jN-*o_#hYb&P^2JG>g;i~x4$6RC`St37=POY6EJ#J1z=jaINmhzVWz#7e= z*<w(io-e+dPCY}LzU#eXYd##G8*NV0i^4bN;gT^)^s?v3@%pj@Nx!8OoV?7_3BOjN z{LdU-oi?b<#3O~8;3q40u(hC3Db1umCxSh)+N%cClk{K;X}G$vgR&l3w4F{06{Uly z%_qtJvHRg;T$QlV60i#(A*Q-_ZfqFaXusg&kRI?T8?5_4hQjJ^DZl#AF2`yT=LCEi z!k=ZFM*@Kv()*6+dAn)h)5O+0il1FlI&f)r{oT*dC%Y%E-Bq!Z!Ou?;AIIghi7zjg zX#N<+z?9noi^{%DG0&z%0nL>>OniCbAYJxMx0+gHFXeK>rc+geD00@^GiCp1b370% z5IM=Ub0fdRd$TsWnC&6Yzd+Q_{i|{Bot5cXxU3OVT+E6#AJ-Z5%DCt*z^2;KQ}q-k z4>`4k*&V}uKv25l56H5g+%MQEjejWJFQs6267N=){^eNoO#=j(>HaFN)28omE!S1~ z477ASEWuvrs&VRiRob5~Jf###Xf3YH9qA`C{wDWkAKU`T9g4h$IY$v8%HzN-rF}iS zzSZy3=Uf2C)?-2)NIdn<a~D+-FBx{PzmEpi28>RBDQuDWm>OZk_(7V0Jdaa|Tku>d z+%eGdn4x>Dqe}bIQ)icXJi?yI)m&h~DTU`wq<e&~^-1TSxfUk(7vv<@WFUPe1}azD zq)|tFoMts7Zy7%6MICB0w2Tx%;qC}kC2;$Q1D+5t3YN1Pg*|wH1iV<x1h`YKY(7oj zI8W^XGRcxcu*kFBdKRZym1<f@L$^k_cfUGh4^T{PBmK1vjt1v9pUN*d4$y9{4OEcv zRB7i*$lkeYil}q6lK?x*(BE9jegud5pz9v_?)`mIwt0k}`wL7kbFgTS2&&#Vq}+q! zE62Zs_@<P5lvBzao~6OpVPo|K5N>E(8Cnj@Q-j@%d3fmATnsSJyK3bxsAyy9%^;ud z#5R`ap{wPWL^-lA=PF90AMCBy9MOb>1gnbx!mo0G_>I+dwdz5}PAJv{Kesu!Zx%`J zqpCi6g3S+%JsqyuxPOE-vXR&bh$TBk`$QIGvZ`RtWG;f-Z&bMKmvg7x#UviY)~qZ@ z-qbE><;G6d7~MtxHKJRrIccjrQ8eJr<7K8TY|8a=HqPo3Oo_{|O)y6qT+93FU)@!} zP;$~8t2X>6Ne_&yk|L*Y)s+GoQ<WoYMNl?LddHyR1rA&dl;LR|-ZVv21QM;da@%vc z2I7T!{fTuQU~LHMU`EY3_##7oE%hNn@KrzE-YDkLG~C8(M#*m&?^j>HamJbTG09Vn zLycD)y@d+dt1N^2)hA`Dr{u<NB=VPn@;fhW$g1eBCd153L*fj~g)#6Sz`EcYQyX?+ zEGyKn#}$(&^w&$oxYtgn4t6o6!bsDRbvT8>on3n8-)2N9f6zq~^K)_Sl4#G5p%nE_ z`Ew~P3C15(E#4lIcNGkLZ8c)}6w~C{d2Qd@u8Uh00_7GX2UKtCLrn`gMH}ctIQZIq zDN)jaUOja9zr#{qGZch6*ST&8&Q7~nYia1<E-PS-=jW;dZYd%qTpK|6^XL}grvSXZ z?Z<0fk&NEoQx-)*KML4geM%98heXsDDJ}l}BFw8-bmE`$mIaa5!3v>Tqcy39I1nNr z7;;O`)^oPL_7p&x)Ok|rVg{XoIWV}`sUMYDvP*Zv=`riBUtp=i5$oDr`>Dk7R234= zH7tdD;-#HNoI)d<0%J!d0)c~hHp4+7*0`bw8LMb<<=|ECGvJkXlo!Q?r^5(zSIx?$ z2Ov2XdxvJzCcaiYUM9J3$C@1P{WY`0vS&LO*tw%^)^v~+ncc6fe@&{lIB_i18qqjH zjwwmvpnR7(Qo8`2Dj$Sw{xx*skZt~mdQ{sx8B_OFI|Z2zTS?_d-{QcV>(aEnSGsJ& z8ssulH<>F&iPb?icivOpJBm57PT2nTf?M$&7VzSfC$n^{Zb)$D{9x4bp}K4|UwxH{ z@FzL{nOCiLYv{Fzq;H}7*J4b{Gf{gb{R$xuxv)MaGLk7mg~L)C?hn4QAHPocnb0$V zu>WW`5umkSnr-U!jeH=JhtA&6>*0_g${~m=RHv0rSebc(+4sS*&Q!C}nde8g->Y>M z=6P_&9>o!zRk&!VW-lA=!v?F4w53^<n2+t7cf#sFs&=~~#JQ1b6bjjEN|TlCI%(j@ zfLw_Bu~I$n?s&ywQfSN5!Pj~hEEeNJ^>$=~^*Y{WTyout-M!As%|IVKQTo6p|EdL% zF&p3*p`?_)C7KG$Rp?h4W~KE)yzWTM1h0qMNEWqKzxBPH|8%op#7W#=YbI4TlMORu z^+cGWom2{CVEQEdbJ-NCFqXw9!a1l)_ulqQB{CI3<bW1(z%k;F)7m~XHNPTgp92#n z=dM-KuPx-D=}zZgN*R9OTm^iKy@FFes4&qwrH%a5l)%Ic-#(KHO)DKOu}CGJgT``@ zGNPAzUq`H|9q~i{*eVtJQ+9Y7bXDe|S|K&cq%?i#kt$uZfT31yWQY0ynRx)JNyQ8) z%e95(SaU2cij=L2jS`-nv%h$+1Q3%(8yq<6uqE;RKLY4889D=}Ia`$oExFo8EuJs! zEm07+&??aVad<BO!UbHD_|*k|V$0)aP%k~OSLFy(b{9xNiHepHq32V-jfsYTJ~)>* zmcHsu%w|+qRlC^lQk2X7R#hxtLZ!((tT_czO9s771*wf}uyhosRMGKG7v9l9nA{C( z#^8Gr=i@#V@$%W>IlK>DqUHF;>I+S4j$^)h_l)Fjpy3{$!UvjA@N%c(cjBzVOPWiS zE*;3)rIprpqsDHyQs%UV)`s$Nh^nBsL2>~YtVsVzwZeCAHGutE$Wh~0RGZ`XX^N?% z;XPHE>ho+Ab4Jw*^w#f{k{4$k*$r&&>XZ93Yo#pdb<hID%BVe5pRJ?&w&DP>(|f-+ z?nAFUha(d^gN#c0Ly1KyR!#^7mkM0wK{e2`ee%=LwC5M0GNm-ThvOzxsmPPhug8cD zIz%dxh=>^q#;Za_&u49K#kX&=9z<I3kxVQjM8k_}>JP2Oa!{QV6b>ZM2fYOWm=}Ke z8}&fe9Hq9<eJvr>?pO3buQ8gU{SWk>D8CC+NrzWo>~Gu~L8$)z2cc*<h>oVdsHGtX z6?Dx6{!JyBrgd$~;_F-A2DEAh%0;U2vB2C#b&0OLAPB|eW4vCcdvnmF9on_!*`~EF zOugE9K(34O>l1rDjzFdU38!{Tp~{gB(-qcRqvB7pZDvCEKRB-?cEZ?0!~AQSVrbw% zh8AIe3b-)AJNTv&S7p9$x$pv_IO57*7cC`EtyK_BZIh4vZkJ>GsqFgGvC!Z2=REAQ z0NX)!@qWYa=hXSwSfjAI<-XlL`tpDFZ*-+=NvNsYtA0J8$glP(_vpiy*_%T|n-7%! z%=2<#iIr;sIhJUze(s@hDJ4ygltkyB7HEqDjY=8OQ0BbLh&rmm&s~kqy+pHEb~~0o zr47hud>AVG1mZEV`=3EiKY>Oc81v`QUQ^%hV~^EFrg4nI_LWd6)%#VwUI_~g!|nNx zWcTjbHMf3_6p&HxO7HMc?ok!qh*q>0DNv|#wSDIXo!q0N!d!7F$i^1EQ9m`v?GiPn zB>ie7Gm&2@*9Iyq4e}>E^;nF$cWQWZM&ZVVvHP{^Z>G<xi#S-5Fm-rj&0$e@qnBkO zr?Dioyr;2j*ifmk7W8FoW616L0<_UArqJD|2;X0oPqR|EoJZ$aYAatdbj8bv<j~yx z9sD1RIIUh4giUqE*6LrAX)%|ek_=2}9>ysDa(4z*C0C$C+SM>RORX)#dVxHvojpTT z++I|lWza~Odbjpc<)g*DE5v3H08$1i5=Ct)P2j?b2lO}X3xfZ?U`7)>+y&<!l9kp^ z?V8dgmZ+?9#O>k&^|~LLt|*}!%1qF8X{xY^-`Do&dMWg8^wWmzgCh%?M%rSDP(iK> z^X_GM&pys0q}Gf($Yc&=+YA9{BFtQ9!#$+6viN69h@zxVnkdSSh1%BED%gW6)E6}j zFMEC2U1+|TW4oB!=IqitWAXFF!qjwyCh}VKU8I=$i=FdaAr-SoJ>68(lJfC&P<+Tf zS8AcsgX%&L7r7HyYVY^v(XDfrXN_+sQPuuXu}qMnq~5ier?o81#hU_C{bSY6R0*Ic z98rAndf(w!ij#d2Ti@(I^~wDY=JJQkeuc+JxipXxW%>)<VU=ebEmi~$uGbw7VAt+l zJE<iDNDYoZdwTJ~)x^u*^DRZ+KNbB;2))R^p)an<<H#{*kRyIr=tXC#myaBm-Y`W! z!$q~$;?4RI`}aM;*o&OkK+g6w`4>82X1a<c6gi0oy|?u-mxf+r&-m?x4B<VX>EO{z zOWNt%)|?#xwml8xdyb~f@T!5`zv^J*4#=Em=cdvxd&|I2L(9H)y|Mj5ds!&{9uz+a zmz!y&g*A$l^jb~p>2LD&+-E;dyn+LCj`&v_WK83h=rx@v%DPQKG>23=LJ`qWaeSBu zD}cHd2Wk+HyvWLxm_g(b4z>J8Erdt4+|DD9ZNGs^Q%wA77uPkv-F?B|lOSA99WuY8 zGPfVD=s|lW)P9(0udZ4W`$+Dhvv%>%b24>#b8o~S|4S3oRm2OoLPA<!V>W|s&+Jyt z0x44xF}-H)URADvE0Ao{+@zI<M1CBz?V(;pVo|UbT*LUONTr$0=d|s@q-riJp6O@y zNoblm(9QqF`_jF_UWPl{w65iU#{ZVjw*NF25B-o>`e9gVxxO~khKeo(<g7%Z{9V|! zICMOKiLdJLX?I17$Y+xJ?nDv~t`Idce2*RQHAShE48J|6@sULL5A@U;<+QZ)X?yKC zwIF`BdT(cA(brPi%lQP&^%n0J=7JLF9kk^en*(lv;`K1Y4)>|hWebb<ZLh5U+x+2n zpSrrqdljhmnvO@|RU5y(Pwve9*Zwte&e?Hsz_EmHDxp$GjMqFCN7ZO;b5slBhtqnn zX^}{?jiVi3?O0*r2hY+R$@qay_LuYW=!?(3AT~FAW~fRFR=N5pe@E^)sCMeNjRQKQ zO6H%k_@uW*w#A0+hayX%GGh5!B^1n*_2NIw;~9#4<*uT~2dGTO(rv4p6mvSG&6IEU zHeaT3@~S}7JrDxK-r9M5?&aWjPz0rG#nEq<`OxVOYSd?om!0v^Tn*Ab)$AgSw%w}7 z@{7yIt%K9AP0V6+b7=1?#Tsvg3RWP@NeWUEw0>KeqfkhZ3r<*+5|JT&9@6FgN8U%v zrW57AC$0|AI|u0e1Jt3f!Yo>p%p4_rFng35wObHnYpAKWgj%51#8dbCeo$7X5xz#9 z)T!(I_T~N&Oz{E3ALnR4J{%R$Wsa@~JLN*()DMkbK>q9zSnTec$iL=Zo3JZRysJ!n za5Gglmn{r51@-`m1&6juljs{#_vLR}&#Qb=-=D0QVJ{pQixpRZDX5cFB`-ynV5>%k z)b_K+Nx47#_m3f*3DN&hCh}!%eoFr19q@<+|9wsO$5&ogZEO_8M`aZ~PF{0~%K}wF zTgYnsZRX6=EecQ&s<02H1XZ3A?TrdwUo3`(o?UCYW|gVv?iELKQ2I_6b5#UvH~^gd zQGVuiw|9JK!pH-=FJ#RPLuYfJe+SNPLCh2SYcc)m7e1{zzTNy9D>;2#V$<m=A=lK= zA~c?aiM|Kte5;DxSmavBw}a>3%&*5LJ<jyFGRT!@O(-?pxSdBX|9IT%^FT5La4Zyq z=K;6?P;sTY{b{Z(qOqmV_ANG~c8ZJ#*x}?8$k)@dJ=d?gT|xSOe!X+YxeR!9yEwZM zD%}0k;ynLe`D=o_`7ka5Qq5=nyE2TXDFupdmF1)xTz8EWGtZ@z?M}ph_?0`f6_|uT z&(khJ04Ng=%=alyzO8+`XT96}gttUli{$wq?Xy`0D1YhP{w>F&!E8*)*mZ}Y7s)5? zC4P8g?YfqVaW9$u)@l=WL+Rl~WD?>1jS6V7F8bCns8zwG@SrCigLceP{?9;;$B864 zi7h~qD~r?8lCw`#vWNb*1=b+$^FL2~X3LG}oVfKte3`G7S`kSad_nmYMoL5ePV(p0 zn;xv@HbZ%Uu<B0xYl_FwE2pUQJ1Z-?QmT%Gtndrv3vR@Dxt!nV>4nmBrIb3u5<Ios zaq(1u<c|HJgIT_v1DzarHNud9C_g5D(7fzO4wU7sO0=*E=O?OSxxPNI5?`vX@9cd# zb`R&_RoX}nt*%*f-F@m*k^ay9S3t50?2t~;v}N7ZD<DN^T_;!b-tga4=*;zJd))bP zv3Hm2qrZ99@h$ES{)lKbP4<C^PI&YlP%5KgYLnkRn$zOmo_{*%l_R$MbKGGb^5i4L zv70L#IxG)}&#F5BCPKeW9;(0&0ANg^34jI05KM<qya%je9+p?Z8^X#q(wy6^rqO!t z`3X;eVBPd{8<LLzFdGu};DV!TT0EwIaNiy4glAr3<8Fdt%eY-#_K1~mahB|Zk_*I@ znC&gTS0l~ujT*Zc%G3!G=ApBBL`)eFjbbC%o6tq^-ky2z5S?TAUxF!!H1j48p=xsy zn;3rQ?7G^PBbw%+w+sF*fJPgxXgdPZc@*{(7=U7r2!XZnT+e|Cr7Qk_4p|$~a{Mcb zlXq!^Ym~;$%|+JiLzdN9U-&22dWWu+>+N#MZ~%gksc?N)7+90mI5QP2eHMRpSNo1D zGB@^wt*xHiPK-7jOqjoPK->eob2dr(^6!*@O88YLc+(ERUM#Rdvi4{ZRO4Ax#TnAs zXq|%Pj9h{Cb^w5)&G-OVtFtX4OC=kq>`l`?P9&HUkUXQze!(WS%TI;`gK4cdF?Sa` z!acGL(?-L{Hpy77oS-D!V~c6>GCJF465S}9Gld&Sb(jjq%V7l`5k|0EUzbqkVqjgq zy;a@fioJfNq}n926>D5=QxO}UVNfDKIS#B2psw`(nLus~dbJ8ion)2UE)DxM8R)p` z7Ray>8n&}=ox&-Q6dH&Q%M1>m1_AbeSaiIZR{}lDOk7BpvFw5XnH%}>ysYdelBBlh zSy{qb<AzCmw#Bf(Sz32$=pNnREv_a@zoNGlpCdt6PZ`cei|(DXv1q<l5U2<765PgK z_X7I4^h{D`Fy2}BcJ3j3yCfByDJbvWa{0#Mvx(ac|Ew}9onhJ~5-#k!bl91Bzs{;u zwR)k>ArNua(c_qe0R{Tm`<|Ga4ROv|4AH%fZAXYa+LeFNyzE^MfOW~+1apu0Cd)}? z1d_RTw3=R$3>3*Vbeu?XHHccY&<l7lzhVG9OtHRvz_*lG!_s;~K;@6Y`rxXk<EUp1 za31nNig)a6OT+5p%+~_qyDjj4myj~;>LDcT=iYBN-4%jw8RS`*MpMJV7H(yUz({>O znUfa0>I{WD((!P^p%QSAvajNyprwZlKb!Ma)k4>s7NzYnwp~C_clJYpvp{)@Q6m%S zyG=oN?_=_S%;GR}Kv2O?J+jc!3jQHum_6?ld&l4InmBEEoExBHe{vSlVcc`x0a$iv zcKq#{d@}*~!zW780L8^N_3x*3{;k0xNfu{}s?)VIvHW$CQ>JUJlCx$wXYd^uqSed> zp@dG@ha`+yma!LrEr_}8oc3m`?EaXP3u?AsEY32;x>|-_K1`>=auXNXLsMXxAwZ$* z)H1>1vOs+tXR;L+h3fCPAgu^#HR}x9>&)&yx*cMBGukvn;qp*fJt<Wg8-|Qf^Sm{@ zy~GXyPfQONy_|dMviY>1@oz|<qZI@=VU=}8d0Kj(PZHm7Sqw)-gJfjjz=x?s5E@5S z8qRGZv9kAswlPb@de-s}_aF6aSChRCyC%PjwmSyxtVZT)m0het{kId8$4JAdk4M`D zW$bj@C;*y1TqUDDQ?<P`s@e>AZ!mPBf1}lPy~LRRb`RzrIQYO%ilIFfnNVGQYw?@I z_4qo+uVcQahwe5sLo>~-r)I50!QOF4R&-=Jli?>B&>JAOzh7mD_Lga}j9MEEHAF!l zY2zi<x#IWca+}n_W){5*hYC!1DtuC^&7_B}2Bwba-C^oF$f)dp)~`5SInYRhRR=d_ zPILm&Z69)rnmeN26A5(U5=ELj2hQy5Cjd;*p7&ss3PU|_3rw-zzfzT!c1-1arECIg z8d*2ErFuhZzZsLU`-~jKyMToOHc!o3Uw9VCanbktEp+=waOzIjpGpn9rGZ(!3ccb= zMFy}$^;zgNE!qL;A&v<AB^r8ey=qbBBe)E6GZ$T$SB1Jz&V}bn@LKRN*~XLV(qZqK z)TpNU7SG|b7bm2);;7Jlg7Nsy!wT8-?I^p6u&*{A_dh3F5#;rFyRR)%{HHg`oPl5d z9^BNP+WEnI^WS~bX*aa5&#memi+#f!K7an;zsvY!%UBwV!JBd1*GNCSkaXb$&Kyk9 zmL1F5_76We6j_&*X!u%Ta#Bog1*8D9NRHJ9GbI{=QS1%26(`mHH%R&-l#RM1Ozkbk z7dTPC3jACpEbgq)<}$e2J42@ebYNlY<tpqfz*dHH<Qn(X!CEZxnpXW#N!`LW6CvR< zz3q~w0|NgV(P}(bv|cOR>K<&I4>PItgqtxFcZM5HgpOaX@7{O+Vr$8DO5LMVyAVk( zwT&;{X{+6X<hyN~ACo_0f1Pw9V`y!zgWsmkajuLNsZ=vk1F=-;Xu%$6h@>iQ#Gl~2 zhRI!i4zu(ENjbqUVX|=UC?{xg@+DD+?F|pXi=Bj{M|@OgcQq3+yNn0!H>>c!g=J3W zlin=!(+v`u0;tdobWDs3_vfH@D-)()XPEuea-yaAoZ~+`r?rkRHc`l-17OThKvsF= z?$^)EFvqd9)x@Bik&41&GqFuKJg*S>A|i?1mr^mBN}3Y|lxCJ6zupF;9*2?7T+4*Q zZnPQ-XChPA|B%w3kA{-5Gqw_=EZFaoG;0}<)L{RWA)j$KYcDFCg{yVg1g1W?03B~S z)=-DIq;7dp@4Rf-ht=(9n1u`{pv?%?n1I4`9{yZ%%pZLDc`#o$rJT_EWEd-D2^pA5 z80y}BBSKqQ?If=GEsVF&dO5R=W+>I&xF7ti9-T_;O_4^kC@7n)MswxXRzXav%59Rr zS=K!n-8)w@_-_xoomso;`Al>XvNYpX(=_m(?!e9~=qaVAiu)3nTnx6w=pnxT!=r+m zbpgkh(=_+gJ>$_;BwlV>ZE$4LF8N*Ku6bSaDvu?T$f8dcliv|P^&rh~lt1ogQD}(q zsR;CXq4m|lGr)7k<4>WqFHdv+DQA=V99@zBtm1!7rXu`=1&Wodcsx-9EF%C;{5Roa zCXv9Ru@_?Mms8KTYwe53?`#^{)JkfkqJDcTR|Y`Cp8(IeVMB8{Og8LUVv2PNjI#e6 zH}vhcw8+`58ONp$9!<`ZJwczM`d8y@{B^#@+nz!esU57SDAg1GB5Yhs9smH@CQ0`q z7nZhoK#2INy-ZSg`%YczjLP6a?Np|)sR;)g)*N`V-P=qO{=UsEz8@#kM1k+3Kq-|V zFQ$|kTkaooyP&Ug*xCKxf>=Lc&%-N(;wv)P`A>xE-2^%p_i1;zshp%GxDzMCUw?c1 z7hLKHQ+Da>CD$yPSptb=IMXrfU7J3UZ7Q?y`TQjyl$1^AU65&LZt$92zcgDmo(>%9 zn^O-5)FMiAhlfn$!9UOheRR*OFwMa*?ZGOI@v1YnB<g}RaKzj1&rA=Nr~NQ>8@I`9 zb(3$~dnEe<6r>A-RwEYyc_D6N{D|sxl1&Mh9yPVb3B1a44vBFUf;PLXXfJXD;?d=c z^UeP)e`4oXBks_~HJz*jO(xI}1G`8j8~Le+d^HX5T>vO)i;}s~fXMpbAop2jjAZ)j zpz-nh*MIfvNwvx0`@6H^EOFJ{5A)=o=9&L$(4OOHJP~Ql`Dqu-XyMjp@40Tq;5V@d zb$F}K7)4zjt2X=}rvpn7j!fUXgQOEvzQ|&Uqd+p%CKZ?YC|lF#&X-}NdzN|W75E)m zkk=?Og)L115GhRQX3B5JyR}|tY4+o!q!0G154~#z6U@|*$jr&5I`xZ`yDuOsMqCYp zy6eAE3AgX*fq6La{_gQHv)th?!oDGYw${_cufOhUH;c5MfwX%%v^Iuha~$d_wd|xR zg#f{*CT4j(GVf^AK_yMCMx0!RZeR4RAJ#8vV<NTZu@Cl5jDmnK5_u1E!b6`u{1yDJ z71EJqWvW8aX+|*ptvmo|Jqa^)iZgz(IYWi}cXYsHbW;g&9elStU0tJkx!YJHD1oR} zBmHj^37I<t=)KKu!ei0EDoaK<4n1(y=qKw;Taxj65J3`V{F!R{ZH1x$(}BMai*7Zi z<S0!xgsw)s!8wHv<vJ{ET4pw(9?jW*0qp;>NxQRXUJ=$_AFY%Wmwaka1bPs|B<Ra< z;6I!^?Ey`p#_}aUKK#Buf@iR<xSnhx`__5IsQ=CBrjuz4p%OHJEhLQiX=P+-RuHxv z4fwJofeAbC{(VsYO6c)`4Y!UCp<a6tul6EL+dq&j`l4Oiq@6oK`JS%b<!(9h#XNrU z<l3f_t9R7vq`PM8OzJB`7I7-fs(Po7VjSVlrF8?!xS~B{1aIbjTgnnu+=(@GvaIOW zj~UnNxhpeWjaN9hzP&*9YQJ=nSvS;0-jE9u0`l=y&?AZjM<rU&(mj<i?b{YE83p9$ zBC>{)&Y~Mb`<-@q0JSnBT>qWfyBbqy;RKfZ*T>|9jrVyYYfpLpQnk|Ykxkb9O#3U# z9-j{wkLz}!2V_u>tng0P$!3m!-meoZ2)8lby!%wyfuRG|jVYD{vr58zr_YWhAJ0`< z(5mtEeC^^13xzSg?^S*(7+1ww;7qKeL^mN@$tu)nn{@)}5s%>f%`rWZ(#wq`DyS*8 zUhAB7d!TRi2^<tuWTsdnt9*^HHn8o_`T#ZVv0RnK4#Qcnl@f6B+m0W(+Dlcz&qd6a zAmCY;(-*4Fc!$;xP7h&L+ZYm#*r&th5XRFtueo@|WY&+ks#S0u58spYIQ{KnZN5VJ z-IhxV-kxFAQrE@U{U~V0MmA(*5ams{+k02<3-ocYa>yHH%>sqcu`#{HK|M_p;g2#w z=)dLfVHtWQ-Ui1k`}p-AhA=my^@0=kJ}+(t1h}rcfPio6&RMlc!owj8@cUTl!Oh$S z$nGN3EJM4!$S%4vYN$T&yPW5JOTx1|GGDsvZ#~v~2#b5@vi}Acg)bVs)IZr#ZF+mP z<k>YmyEtgu5=qA2);QeImoTKT&a#a4{!*Oj?OW}<vk!WtAQnFh0VI&^*JI1hT6jIu zUZiTh0v-K4qkZ5h`Mf1g=lhLu5JPp$Z`gu594%X`B3<b|r5^5!{k->PLw$3R+HXbc zJu?1V3iK~iq+hXb^+=HL9gIThLze}fiQA)0eUgG6L(;!A<R%?j*EJp<GtB8CmDmtG zAOPLxi%<nFthBP}1FJhhNVp@HGftBkO~f}YD<V$L;iHejFlF&y)pg$y31?dUnG3vQ zzTu9HPo~j14n5M5hl=sR3jvtc%tZirLY4lXqO%N(;%%e&z%I*DE8XDIB}kWoG)OMp zNOvP0vc&F^Qqr+>3DPCt(j6kwBGU3lr3A#_<^3?<pP6gsp7T7{Ilseb5A70nq;h;v z6>X?e@kr574ppmOQZ~lF%sEQvdN20jW)nO1YuDjzup|wKa;rV*1s%I2V2cMQcz}y$ zvX8!l!b;t<TNKsjpGSVSV=ennw1*yuk`f7O*qaYQ4B9DO?JTkn%B{sD)=24gR0(ra z0e@`Uu)HLbF<M@HX*%paNTTg%kms<l%eUNIe*4t=V`0=aAAXZCuq&a*&Z1~4u++v@ z6TN%V$rhBkTO0$fxr9}jB^B}Cr>u%<;rCrs6r9LTA>8Sq-nTm&LwrF$oRng};5zLh zG~wU&yT{>ExiwP8>oKkDO9zUaQ%St|PPFOTcQRAaW+>oahh8<krQO*XZ)4+S0GwZS z3CZxWT?k7vu=Bo5T)vCaPy^p_wBMuIZEri-Tcls*9i5;3I=^vN%5R<cSL#Vr?z6eT zxn^QJi4m4>6r%LEC{XCElVEqQ%loF3r*Fp4?vmEIpC@(mm|M1^M&_jO4%*1T-cR_9 zx!s|4uz;r<iereva}vnzVsq5N3;n1gLj7W|jjbZcEtC;32?jMvvvY41H@KxNca`v* zu%t@pr-lg#b+K)hBIufzh39SmcnS}y6YbjzZMIjau87#zc`k5>kFkf(<(D&E33rI) zV&SCua2|nFL0=N%!2dX9X``hZ3vORRugl)V*TEBx9(I&<;j30%Nw8<pHoxz7<0}JW zrP&Wxi`ne)S+OliH%Xj3`jlq)61O{oH1QASR_dA)5w~`A+V|@25nTMKWV5lrSV~l? z=esN~3$0c7d95Rgn->oW1chhyL#G@0$|y_lUGu&wBues;4Z8`xR95U})5Mw9UIyaX zwuo51dKs4DmC6c!#UAD*K)<_BTUD1I)<y(b!F}P(Hkhm;-L;t$_DvL-yb<B-N$iN} ze0tum*JB-?T(3V<Z_p#8rjij)3&d_co6QPH4;K>;t<rB4rVm#>xahX-bgKpKlsbL{ zBYPYpJ1ef|okq!3_kDSvl$$D6C8lhFSbdu;tiZM^S^F^4AlCSIa(h`o$#&?EFkME6 zTpGu!!w#NE%6^uQ*0<}N_P6VOei4;>A36Vlb!Z|6*z`nBI=k~shB)vEG#Y!J6m~bg z-BW4P$Gxq~pVlYWSL47JGb%J^bIK-krohN5F^M<fML*f50l)ks*OOK86V=%sBOZC? z>3@{i)+~IM|MAj70GIbLVvCG|S#jg;u%l2Xk2Xsy8r=9e(T<LQAAj~dXG-k%RJXJp zdkj|MhxwT6eJCa1+ikbpJF~}QYvI!w-IWtCHRog9aX<ECYdt(7<3yvCotd$pVs3ow zIWI-uM}S-e`&fiJ{Onk%nyD;Mhn)bsGAOV<#HIuSuy~C41U-L0{8Vf0+o+|ZkL7T_ zU^e@7ikz5s{Wx)^`s|h^c}cy=y1n|lwO3H1eo0IRP26%PzWhnW%D3$oC$SUXl-?(; z2-#3QbIKfGDb(r4G}js|w8pr1vH;@I?jp9)KWss)@bv`QH70y0JO0KHi_iF{TDMdd z3+A`9&B?oeBi&O1(p$*tTiGe^b=AJ|Kd(AiR?|+8FfeG){xP_9KelkHJL)B|TM0`u zU)fnr<SySf$Rej04;M|gf-i3Sfhnd&uYZW>4)=)N4YfGdFSa$3Uv$y!#e<Ku;$KYi z*6IF@B)|EZkhIE!%4xMP^^@1WWxa($sy7GU?b+AA2)d198Y?mtq3(Z@#xyDMt0^<_ zIUVQ~howME$oj+Ex4TSb>rC)<yu1A(aEx~s-30LF{~^ZzCaY#e*)s$S*b7+qvQA&; zn}k<+h#|5&pY+#yty!MFv^u=!wAI<o{%7+Aah8zT$F8>&g_f4yHjFx%tW|nSOWaSc zID7=;jfTFOw=}aR;bHIY1dmba?o{f0&Zc<I=BJZx+p@F*Cu09i?NaiQw%4XtTG3&G zWd<1po(<4z_+m3+38?U;YgFt8*zd7WK2S=>C?|npH8#eZ;i;)`WlHTYO>u+wh(&;= zt&;(T90I#UZFo!7Oo4R3(Z+;G$=sbMENDZ@m!%h}&UN{FqP12xg4iRDR7qt=A(@>? z==r2Xslsg$S-baR{OAV&hMBKS$CaY|BT_DmGwVMJPFSrqRh6xxfsbJ}RWzx%$owF< z&?p+KQ3HRoGnU3dcd;r~A|LtJdud(Wyu}63aoijZ3-VHIai(Kcyj~4B%2!QQh$xyD z{~BZVS+>FNYG;=2f%NxJ^=ZO(sZ4;UhCG5xD;{-^Dq<dM`!hAE7AvgK+J5z8%WG-f zioE!31=D|lupielioHaB7uOo59Bv;Z&0B-V5w8vZwCjU2)OsR$UK#zLR;r8><fV8P z@ym%>k$X=ZPfK_r>x&whc*kcn97Uh;i2eJrse1qWy)+Bh#6J5Ar&k(jCYtlK6c#N- zAN6l3R4(o?Jq&)kvC8K(M3g=(d^K1V91&fiG7qJSlHz?Vb;fgMgM&15a$t2DKu8VW z$#wK^yQdHS8cUV$badgUbizgy9nnwLy`$EQH?c_}si|UF@~AA32~h0a8!9DQouJCN z3!PLH4E=gF=tpfLUFkm^7{>(^NMgAZ$*jg|@vZz<_iJl5cV8-<W7QFIpyoVx4TK-K z#0NBCnwA*1mQ|h9Ttxi-jm%eb1Tuhc(zslzd7e|3Tg45(5-_XXctzkv99_f0l7_&q zn&toAMKl94c+!+1Kq(1Q{W@<Arb(#Rh|PARbq_r<Gkp1z+lUvy$W|Pe-52?td;6Ay zB53=rR0BtmEfm<J-*seSbsEy*?MMbRU1m0q$S`P=7l8>L&*R#Qh<W?|^2bq3a*av3 z=$_!iTgD&tt$Mc+7}t;o<keNAb+8ATv5dfZboN8!D+>^h)Z3Nk<xY9MGKUDh9=~t! zKV=jH1pliSe`iN!#EYcNd)(5i7IW}=iKv;p)P~p)imN1+>9q=gQwUn<Zs6HQe~d#P zhy(w1WnOP{)+x^^Xwmdjyw#cM6nG;nz<HQE8dQ1N_&n^>V$4fX^US48-8%A3kO*1= zFnfDI{(gO}0>EFV$O^}^$EN@k?KOoW4DSaR)ypf9&3)_z#x2uYly6RaZu8`OtS)uR z4%{8rL%F2WV*R9Yspi<bZRY<2dEEftfIpuobi^s(*9x2X@aVH^s<}MG*UMPF2GD@I zGcbQoV$TOYF*HiJ(n%pR@jxGz$GXxV(3fhvhfr2pnh?#Y?{U1R$~KU99i$`(kfQ>L zCa7<qqIi&)$w;>J`#`UF8ZbU@X@`HOF`*e@cdXGJhPk?s+_aw<a0H7H=6oMt_)Xsk zKji}oH}UHM>zUV~rA$<mQe|RidGm2xoErWnhr*=|oSenmOA6HUrE8J(a3Y21PVmWF zB=#;H+*-o=qk0H=A{0U}&PGA_bUZB!p6pwfG(&wxk)eptV7Qf8Uky4N);Qu6y2I8q zHjO`}ep>15l}KBuX-m0eP7)NV&jGAp#A8B;@W8d76{wZpnaQeXcV$)HCz+VCF-QQ* zE7PkhFx>ynH$!OMnsnJ{Hi8tcbCwRs)Yz{g5B{Z{Oli(m-3!u6IPr$ZYGHC|Tho8X zx4!Dvu9od)r~52C=bloSDWZC&UC@`QsI|S_Dvi%(cW3MVr)^htU4<t``^`}74w?Gg zO>2{=3Larqt-`~fZispqceQA9C|XBO>MzWB-*|gX(p@H1t<rWlVw!e`7V+`pE(r9| zNSm^Zi+(e%lt@P5?@>tRNLm2Oc9KIC?cRK!J5JbFVEk6|bL)7@e0&9`n43)o!$VzJ zf5!{$TFoMfnP^#XJb}5cwv*JO_?73Dp2r$eUItG}DTjf_IvOncK-{B6M4HM>{mAPJ zq}ER^O#$m8p7M$DM%7nd2-OGc`Gj;C_U}Ut+MmiPw=ACcwYNOxb5c4%$;WCAS1lq- z-!Bpa;Bg8-dS*gd#vfgB^s^lfLeooaiB*gWvgHQC%N3vuH8!W*e)%74Uoa`17@I`o z##5@N4hf^N;Hounv`g#9{`{sE*}B5gppl78kP0;bMz|`0aq69em%TNKX!;6)%Aj^F zmx1>TcHf>#XRT#Q4K++?9#~Sni8_53tH`M#e7j{n<ja}j@(B~dHuUy)<T4w+@WU`3 z?W$cGwVsLEdB2)&-Y-3^IzNudUcB7xOA+U-CH`{a&lMv@J(`94P+4o<YWe7Skjp^B zfE$8uddJW_*HGj;bOZLB^Gn#uctdS9s2txao-+qdq9medWR>P7IPG0uPpj*A&_A!~ z*k-9YZt*U2jkQ3=_!a=TRVtBW*kS2^5exEE=2Q)8Y7+#RuMO}J+o^>ivwt{epCp}| z0{3?FLA49*2JDaM`kOdbRb3J|Bla~j6D%3j+QNTY%7%$D*kD<`Yf_Ty$M-Ad?oF;` zD&r#_+RLydvW^qS9=oPBQF4A_ZmkSXvAGTKR2gFHejr~^*K4e|s;E!vU%|<4Yk-ei zy{ktfes;i2(p4QV7MNVyWA1Dd{(C)3PNI%7?r0pWK2JVLWY$orLz+gjagur!Y*vPs z#k{~~gc2?B%b0`lObko@YR&4_V2%?Bo|k*O?p#f67&Dyu+HpkERHJ=z)Yo#8zS=dv z`|V7|;c(XlXJ^KE-w%Sk-d!!(P}{3WcRQxvB?nO%!Y?_rwY;(gNL3EAjq(7-ZRs5a z(}R~%lpc+}UMBD-LB2MrzPW@(c7Wh)>zh!%L-*)p(`TjaGj-(P1C?HnZ$a~8vs#oP z^-Bb&57pDgFB%J(J0JK=wy@Yc>G#}f;SM~y=Ao}^iMr+ty|tltdlGBw^6X<wH80G7 z>C?ZPU*R5ed5-q5^R^Ft`Rae!%LI?e-Fd*@zA^pbchf#a(z60tcWuxK(ztIiDj$Sc zhyZqR-?ZW2%dU5Q-ve$--^RuX&$B{_PL_O)C>?t!gC_$!hbx=zNBx|CxcfwM_UEj} z2hPVykxP&a?~U?A&bIroy*^nsWgcc9<GP-q_rZY$k8LBZJ0)^y7U&b(C2p>t9Z*jH zX6}C@blunyX}E9GKE_IL#SIN`!j}{zZS@8tDZ_`NgfG2asHt2CLY@VA5SJpvpTGEZ zg;eHZEOycdr0Mso=|l*l_@%>d1*E0oQNDuEC_~y<CJHruQ>A%`Ny3usfgyQ>x`%Qm z7vVlz-7eb`w1qukj3)16WhoYd0m=`?5!22}Ha|H{#v@zlo_!gMvC;_d<YK<%)O=<X z^{&e8QJ3qt94W@8Kz6(r%x6wZ&B#hAayfPK+0M8S4VA@CO~G_2DO0|yB?_sPaD8=h zdwRs3OV1_O)wo59&yFhUfbvBwl3wG*Ih}JQftGqMy3kBxjXkWj(ltkv%aJ#n*f5d% zkUqYKszRKLw<0z*mt0YeJOvWQT#CFfMHBdiy<JS`AJ;0#B|i+%l<m4-6GAmI9-72W zF`KSQWJ2ChfvC=jduNt%`&C7p7B1fGDyW*{i;fFUrBLH8#WYnV?*~L2#|u7qPCsXs zknEQLS5)qGO}Q9XK0YCUlA9t4?<goCZ2HNh^lA7qX{6W2Ig}CR*-D{2@kENq_*3t> zngGgl6L!0hbF-K9wT~}+r6t%NEpa~*SWKA=aitMWO$f>0O-O@_WVBq$rd;`o{tWHN zMY4#XNu0u}KdLiyXI?uPl^7?8vOW6FZ7tG~5-GuDypSTBo~8XO+MXuqaTi4^lm*6+ zj_r!*#AG(d8P<+v+VDMovPkc>D79v<_OFv7&z?&!flqHWdpbR<1x2Nl87Se$CgaB< zF~VlXM{(Ab#Pt5v?K6g4S`c;kwJi%C6)Z3H5R<LIVPbypQsfnCG&tfzU^XQlJ(C~3 zOpe+|)y$J|dbM0bhke0lzT7Gz(I=2pCJK?ZaSCDXWHYf>kDG%nb8^YdO{Dx@sVS#l zNTKOM^Kmlz873@qHB|KQyw$rSD8~XykxW6w!eR5wx1m&Ts0)|!Oe>U>9ez>jUWex8 zMSLmE+v0QZf)<tXP<D;yFe|1kuNFUUQ(c=Vcu2u7gqN5zQCR$?@G+a4FZfAN7vlJ9 zF}{VyADNPmudEr*SYEWs@0drvbS}v?ONW(eeHO>k*6BK!U`6mkm~Vth7nR_|49rJP z-=PfDnI7+I4R7gs%3^o#H|~bTjiKu&@+kS(>CFoLx^hmhHQ!B?$!i)(KTldGqU6vl zC!Y*tktJ8FtLP53K4W+ZXVWscDL2y8cv(&^<3^=CNo6Bdwr)^jTPK8~!x~#uT`R+2 z@5_B$MbztToo}ih2UP+95jB1CkKE#?J6t`kVb7t}QSNRn2~@ga;_Bs8micsY)k#$n zr7zZM<o2Pm6BOY`HCYz5%mZNNEBPQ<Zl1Mj%RIwMx7xBvhbpI#0)7r@l%b<+-RntZ z(|j_v(z2kgnq8&(<gm<!{Q5V>WW;P*-tBepvMNfv*F6@mGg|!sM<QX_$ApMFbNAQt z7L|kfwF2)g8mI_po-9Hp%MCYfB9?9%-bknbaMC{F#(noH#^;SkH|5nmjh|`nU}<c> zzyyu}06e(6fM|Rkd;oe2^tn-#m0=ZWIEYb*am0ucnw(BkMMI=)B;g*FyGobuuo{L* z#3D{3V|OT%Og~?H!oO1Mm9XV#1YaxnOo3Ry+G0Y$9aK#rl=!cVIIn&zKM8T3lE8fc zxG2^vVx&3xP-j?a@+nNh!?fPEFKUlJ=y<usu{lx4a>;Y0-TVD$Jc)^yNrzAMWVj}o zg1n#*HHu!ltLe)ShDw0@7}+#5k|-yRdTj0woyz2p8ZD$h-=D_FJxh)Fb#DJ2t6ZQP zY1X#CP_9>CvSBCTwBBOZ%9<P|<*-p2_?fo2AmDVefTVt&oeYqVaJu~qf*0L9Z~oY- z_omqR?az+QZim~?x~vhQr#3^+?%%RRUY-B<VMyw;{6C|gpWpso&yhe8PqBtl4?;n- z()36|R{E_ND6JYi7Ecz+U`J*EWs4;+S;=!`o*cD9=SLp0VVEo+mKe^u%hCj{suf26 z2X%*KcHD^=`{ajfE9^e~r#0otk5e%mDFWUr`40TrU&!Qsir4B{BGmZyvW!gJ_FkDe z*Y0H-?C<Oa7|8A85wIX|czJjKSbJx(wd?Yid`o7INROp%Zo-HAX4S<W9V<NPK{qlk zc0n-n!({ZC3@<iZ^rpJZC!4k=`Q<-Jz6uO&qFbd%W9~d$NAl}lP5F0+quPq9{JGlK z-^=-H8+vYU>T;U%Wd#}<HhbI~T9^1e-gIvs)i*X%PSrOJ;QwBH&Yaq$N;;=T(m;!^ zsfh%y_~R5`W`_ymCvVV>DiShBB&~EZy7PW5J?{AL``eRIfgimWOCCS^uJ`MI^k?Q@ zHxPRcbMWVY={!#cpggaApX>e#uqBKg<~SWb1%xrxJfun_f|ag{$nJZL+_tUEe7V@3 zSbgjWoMjQRHNMBcVjK70naBBz^ug=%*~eGMtr-4cTiqwui{*2fBs>il3))g%m4<|2 zTQM>hMqcew8Ie<^B%AZ1m{AeZ6}%40WNbs;syEYMJEiNRpbocih087u4Xoe#I;C{* zT`&3ViJyaygGbQJ6FTqfFBqQ2>p6a?-?ZVJ%-+RrmZ`VQKyQkIA~PU9;rQ6|&!-0j zZNtch<tPufL|#7)T4iPt(z2(dFIt;rnJ9;wWRJ^8MX%xYV_Oa2@TS&N`28^<VvalD z_uFrl5gSPI`XqbIRFcb^zn2@qJ|X)ga^IKtcJE9Dzkui;c%r3C%2SE$e!lpEQYu?Y zU+>@3{|oPCdKbob%Ygibqis5BNTpx}SWh(B9&d*_1WG}Zxk=5WEOH$J+fK|#dpl%z zLwChCNlKyW8cLLBysm?X8@2OegS0(Ow*QWz8MaSl*f5PEpSKwWRhpH*gen9xmJ<-% z#$EP<7iK{qaY7DBUOY)#LC7XTaXFf>$K%tC&j$zfA1V|t={2HhH&57^e5)VnZ$#ru zJt$>d9v_vwIR^8S-<Q|^IVih!n(Fjr#z~wfk(+Fg;C^AUy2cfbGz<%3+Q^lOgQ~8% zeNVGo$>m)UflBtyWr##?Lwn!1Z++BpX#bUSntGtR_;lYV!E>0ckEW5R`|MRya^(Y; zr&AVdXW3oTl|sP@Q!hr~^l2WHtmvoObWt@{7)L_DK3Wdu<q=gy!bQ;NI>F|A;zP4r z0;boWxcY=+&bt_ex+33lOP(aIxpQ`Gr|A%dXn8CfDE|1@At<$WUVJ@$P`br?t8Pbo zUIH|1Bz8DS?KYn&JMUO9^PbGY%tT>|%=Yy6G<!G62AN)6KnQNg)k^VBJ=$EiAn$_I zXtK6FY=4&#a>Z(7!D1-f7OS;gG(UVV5{B?aXg;~2m@mE&cZ)nT0SYEGF+_SE4lTQ< z7GaCV+`j0Gq)+6kr$b2-t!TV69GTG<3F0_~U^$f?xIMXshbE=9gigK1a#&Z~Fopl~ zKebi|JzSsxKF1&$OLW_%q=ZDhxz8gi$uaS9!yd6ThaOsGvfs@<fk5qRN6SsKIP4_% zxI*^Gv6I-;>P(nPEB2eG>l1;sg^bI#a-9Y@<D|8ZJss^$P7R*V9<8t3E=am7f~s^w zHJ3MUOf-XTY~^C9jpCG+K;v23-SW`Y9rmRzjT!f)dB#sqnt%4J%zW>==6luk@AB<d z<fQ$HCa>IJt*)z}PIo>*>1%>ci|=wZ5eNU-*sNXkU(dXWx|;g@??y_5H%{QipqB0D zj$<5Dw<(5hdJB?M>!d5kg{EECCd~P&O*`9!lA8Vk3%?$M!<sSb+S`-`*TcN~!URS* z`Gb&7obaU^w~O`;<NEce^lWo#@bnJr@9QxISW6mOdzYQ**SLmmOGeJL<9!lEn%P?Q z<mx{kNX$YZCjCHm>-3(0OX!rvcmJGD(tRlA*Oa+r>#L8<&JP3fZfEQvV)>so_GPC+ zrvo|yiU%TGgw8|fqN@T5K@BdlSF7`J|5~x9$%krmH`9qx&nxbIJA6u&|2{+aB2S>f zO=S*FJzLsR6P^g*-C2$a0bK1p+>yzB>|(u%M4ho9VA{%v_qwsY*6W))J~M8)eLt{X zNA5pk4q$mOs{OTP3Se;`x7d@~-lp&6VMh0M<$da9yJ6pvJ5|B@O4McJyS`(m@bI<m z*^aJGFK_2e%eAAZtB$#u?|$oVHy4B2+XrU8g_OVj^!;CFU;B(t^gD~qzq(gFB%5B5 z92=|iHX+>(-)JUMZni^=06={9G$p)u2Ywr3E-vJshPK)P-)@DB$qBv6%=xp&c3)=N z<@;Gj*Ps1|IWn`sv;NH|e-0$8yXQ^6pO-Sp9V)yDeV-{GP{CyV)n*{n(kA(|uKXdM zz1wAWn+<K_!|DIb@P8W(M{%`0896pmdIT&AakaO~X?h<}u6>4Gb<BVIj_3(rJ{Jmp zK(=xeeXn<mQ15z>>E8)PuXmen?t1i5u^SOi7HHD_HKAv7W?tL7zupo$?egy|`>NMe z_TJ4HPybofGYcYvxiBHFM;~8DX&&2^c)G9u``KA7_vXCl_wr8EWzSXLiS<nQ7rGbM zW4CfADW8ubmivDVE%%+r7e#zFeR0(=*MIpYH53wZ`+Mu&yW8tAy?<u~w|@@x-rX$E z-M!Yge@|Y%`}5@qvi*(qkM+5C|K3oC8i~R20s3fs>1eQ7G$bS%nj1~r6-~+;4ch|f z03?O06S*0Z$`wf!f+XugGOr+6uaR&}G##AgZ|4i{kQo1EPw2@D;5u69I!2g2R#ZAx z+$>fyBvv{%_8u=D)Q?U6I+g_+t0Wz#Viu<s5+??Yrc(f}(J{K$aSkqV6kC9yS-eq5 zyh(1nSy#NpO1#x|ybV3dc0ArN1W&{k<eH0e??QQYp`>tt20hwe8vVQ`mIDJ2&Br0S z(A?KA0<Y20yzxTP_;-kwcvp;QG$t_wlbnl*zYPJ2Y(*ob6SB+_gv?OdAwdylT=ks^ zwZWbqrbuO8RE0FEG9<AoH__%g+VDD>LjfcX2Q^72wV5S#<YL56P}yBcz1L_b*B8a~ z$;D<s)JoFmVUiFOXy#4oSV``51xfjW#J2E-e3O?#Qlwm+aUt?ED7;dh<gIHxuCAaF zOv-*uY=bmLl00d4CAArvQb~Sq6G65$4?PHZc_1B=dqvzED5E1xQ%0AHZ?2Bb1<H8i zYI4)+y3&Xf5?@PWn#PmAUnff;h%W;0gwj&4yVColWArG}4l>>8mJ>h|A;UH4GAn7M z-5LC=8K&1Ulb9r`&?He`kR<uNh1<If<9Pbx?j)@mw0Q=JRR+Lro}p$gPlSu%b&C~R z&3f=Ft9m6dZah`YJn1F<%fbp`*<TrQtFHpCli&%$i(4Q*;m{cq&}}ZwBo3cX0bl)B z_QN=UFd-FTo}(L@V|kd^)Rk)dG^r&QC4~S-!ijwkU!k6&pFEXcY$7#eBQVehd>Qig zK#9N>TFX2(Brh+>Jm(%gXlf;gIurzk6Sm=E(4qP2A!vhB;%5pn5@|Gj(eAd(AbEIR z$Evu%N({6+FMqXw<ZI%8yy;jsjO5cNq_$7167nbWGRQRmyQjj#+%)&d(;7kxmO^E) zyg84$3z>f<8WH7}xPh#1cgX6n_#2_cGBtOikV|zn?B_}Fa;P6qLh+S!ya-?6R(I;W zG=UH~(nO;KIEqQ=E<QEK_DiI8Ghh!6i?&vi-<##$tHt8w=gvU#AYr8<+1MPu(pMoU zuj^9yT`R^-3G-ypT1^anewlDKmMbjTN!i3v0$)V7oK>-0n7`crLm6{^E&*`~|BdzP zL?WAXg^EQ5$#o2QSS)!M(#W+!_of1&S#e_)_Qay{iE7>}qA2skD9cH}S~kl1rgEFE z>Oj5fe5`WQrD~t2>hoBY+gg<aW0d7lmG4be5Px;xQRSXgb!c5>=uuTfSasA<C8q`! z-(1|p!d7L%J?S>zC&}F-MKfZ0IpXD!dpdFCl6u6eHTQzan)f`ODqkZemTOb*hy|;) zxpm<=iM1^`wYcTFj-ZI9p77VQky9?=9bxs&F7-86>8Sh~+?rClX-t+>Dnj(N(PU`+ zP2sR6cIGBMN9y&0Y{Q~O!@^ns+^yk5j~`zSK%D09R2tgHPrGx}pr`21OczRwZ9G_O zWIbp&N(}sO(*Kb7O@>S3MOfpN#q$;721fK7&I1~=umX9;*NJpZ1~E;BWlbh6Z^nol zvgw*R>ABW48y>jSyt}C{uWlxrYBtMg=Cf#mJTm=j+Pr*Jzs}gOgL(bF=Qa25mIq9& z>%3gB@P^S_%|_v*P^qa<zV#MqkLEGrHYS0#FPd$Dd4uZPhQGm{3NkIamVr7R!rD`9 z#A59x;qCgr+brI;2QC&1I<^}pwc9^xGTd&r3h!`zEAA-Je8>SXst4&zwWSAp1|*>u zdO8djJg<(L-PSv!)-BDBpm+$t*)qti0Bu@8<4Q={GS=~eDdfkmE*C9)ZsFGZTAdiJ zEGQPZtqUrvCUxTLE_>8N-$}Zrz%_G9t$9LS(iBEyOC-J3kvb2;n+KeINe9w;@TXb~ z2VgxOr4>xQgX@;bPr(4tYe3oKuuQ5>4iNj2BFF*LG@`qPfzjVhhRxtek=~8<zP|Wg zgWI!w8#Yo^U-x%SU_1r<Xe_B00@$kW%IBqxpL(-t`R>wE#)c;>=7c(6o>ujQ8ixhP z7U1i`p<%ctAe3uR0bC6s{2ulWkRT!dQ*JNp;dM%E(EQG{45+QbLn{c!GXV}#1DsZa zmW054W-e#pFdIKWcZ)^~PTB<@ST5jtcub>cJHY)%kFs~@v=+eM%GNvWw;#X<;Dh%1 zLk36!L>hqs383j2`YMS)K0=+-e8jA9#3*RQVxu!+eWc8!+xAbV`J++ih|%ox5mzhQ zXa$<0*3kirQC}<Dd6BW8h_R5uu`nxJHzGi*X)Ky~{P-))U5rKj1ROoj%zi5{o=iG! zyG&p;Kc4Y;;)DdyNrM200Ym-qtOuz}`E7EK+DZ#UHAp6Tez%ryOgwai<i4J4+!%lH z8qz|_WeO*Fu|e?WPn%fUR8~2p?Ksykov8P5%c}6S*3MMhW3KOZ)6?36x}-qr*Iab~ zsDDKBZ+?2^L9Z7%m+th0ArchqH?#V9)@Xq=;RvTsIbn!L0N}uScm&Bz?z@lY?D5F- z-jnWoRvwaarB6?!h7Kvtg8*BYft}w)#Jpkp+>@TUjo#Vp$27{Z^OS$v)*sL|m=_uP z-90#v)(H{NG)~2`K-UAYXM@lS(%?u5bWg^BlXtiW3&Ni|<ELjI-cB#bFn^Ga?3g13 zj*rJsg&!1BIt+Y=9$3$W0W^Q<7d2U4fBZw;Za%NY@{zypz2Paoft(D)+RwBv#ON>e z2U1|t_P(Xu($d6&f!#;PqNUESU~4&=_rCYt`$A@H=Y0NB_q^=`5M+LGT-Mg$+eb9; zzU4U6<#jEx^&~O_<Vs8=m&Ea`0oziNU`S8FN+Qdum46?r*D8vKthRpnmCkBO!zyB7 z5rEGFO=M*{Az^YfBY&t@(#RT$)(p=+>iK<Wkqap$Tkq^!=b>K*fc5?cvh}U?UOAdJ zGN9dUZ6q?JA!Tjdx2O8;hRvsi+uw@-4uA8(Cz0&+L7k1Y+aj7a9q`iMPxMk7H9DL6 z{u_rgeIY3$k$*n4|D~=H9Gz;}B)BBgYbLwy`+W21^R*z&zasHf?8>HGS|I?Gq^%lO zEx6T!j|4y8xk`R|eeRE6+iD`CD;~i{`yKxQ8+_S%68WJ@a9CFL3yrrr!R!?2_gT0Q z4Z9FcmGv0+cf;AgpY`l^jLyjLqBhNA)_P{dzx54~Zh{{~ZKz;34ASRB<#zz%ooYFn zEnAsSUYone;2&}{qe;6D5co;BUAe%`Yckm9=pC>jq3PgGL(#UG0a-oSXzJ4sZf;8k zUqEv3`R#f<8zEB%8`>}AFyQ2~1M8t<l<+4qV9-n0>vncrqd)9|d?i#@<}qw<iyWpe zMDq%^r^gE0w1w>}z`g+cIkQ}II(zB5Tr1>jp~oxcr`vkSrI+%iF^xL_0#-D;+PX!& zfFRo^he`L7jcpy685|jx?JGu&`NKxu{L_mqrg2RDTo^_AL742@JnRJV?b{Z~*DW&O zA9YmYw<%Vxxxee?cpFcIzUyZk259frX?=3C`zWCRLm=;^6&-7f9frez$kZQt-monN z;uGO}i*VQ_4t9xvU8cbfnuxd4VA(=6pLMxrb-oYje1E625ti~j<j>3025^NSt;r02 zGvC}rs(cjeaJCpWY)f_?O*TAFw6I0CihH_w+e8NSA-!xOTl;r#)5t~f<h1GA`L50P z(4ys<#xdu=TO4}Yk;OmgzLW93Is1y$HW+}dBYtjek?q>Tj^@es;m0mEKWpUn6rWr+ zv8;WJJ{svC9b@HsV2k&(MBL^fm%cY_9{71F{8G;jYM}Tv=O3&-4MuvO>q?$R7Ita- z@KW)1E#bwHYRMS?-+2S%g^!+0DGbOd{$XPW+XU`?gP#<Ff!&D%F`s+oz%`xCFB{}% z)VmwB&nE6Kwd0em<Too`#h0$rOIvck1TRhi;736t?87|SCH5CR4ECz=n~cv_-8r(2 zv~LD2pB-jzP|psZ*i85IT~~i!rGGK@^7h4E&kK3`)SF!en6%Hmep@nvC+C|0Y!CMj zVgKjSm#iNLOPM=H&fZj8|3npkZua^M-~kGfF{@21!`z53N+>cG`8az0ZIwhCL7U-R z{T(%wrgRjT!C+S-gG;AaB`;%J3V1Le2X=v3z75@5K%PTVH*}F-;9=*^FW33QH#-Kv zS2|x8eAWy3AM+#DJ3RFXoSCG_1r*~5>x~T=OpeW3_(~sKn3;UD=<xc~Z(M(|r&U4{ z8YWgfyYeV}zxNv_A+}H#K(fTF(_R!l3|dJR1=Gp!8CI_6OL|GSyDPsoB@6mXY<l6k zP^nX*R%G$>Fo!hq2JAj(+S0FZYYD1(MB&;KphER9i`h!r88D$^%yB&lP<m5e^yGdx zt>E*cj}6c6hpw}A`$RR&IOGUb>lW{EY?DsTnCkBgay;{%IBPjAU*it4NhNy_^zZLO z+0%y#c!X`bk5J<ST17^)eD1ye<3wXk7}6m(rtmNap62p>f1j30&XzZ2v-w)CZ0=B% zQyD&Ld|_3(XLpDa96kvla}dVufaM*I;WcwfNFB6~q}q)<8pf5RC!Z>7h>?k_;}cO! zvPw6oq#?*?)D-O8%_w6a8>(mWSa54%9*|Ue*=axgNK`bQ*WqhfZJ7}U4ix`!e*#<_ z8^HP5l;X1#^uM+ul<x_O-%4SE2B%nUUN@szu+v~ZkyU!IJJY?)I76(oU_Mn@Bja}K z+>^g5dqygzPVFC+f<-?t2lP|bPyo|1nG4D6=iEhZ3wGynoLo256@M;vT8&h!pMEq> zv3M?N;ii`~L+|~)JN_PW`m0|#&cDSaD|lhGS?$Z{HnF&qwUfz5x6koXHVd4jXiJa9 zPy{v7n__${*?--OIy{DKj7RFDK~8DlJ)KtwjE3J&;!vKd5KcHjkF?~o#pVOsJBvF- z`Epp|(;~NNHt9n9siPx!ylG^mJ(|<Rb>xB5sEkXzYnE?m*g!Yk?n|15pP!2d?Wzm> zL_KG0J1k&crSYA~47UhHf{!vD4SU8}rS2jlQ%u0{=*r=8*Hk@I0Q=Mot{J=ZaINk> zBeh37TrDf9;cE6~tk}=;k*j}~#DQfRv07oFe@`fSv~fA6V0IzZkCz@D=Eh5xnqLIH zGprF7O*JxE$2(w&OZ1z{R8dW~BWx_c{o+0rSyVb@%cwC-GOhKoO)(r1oX3mPxzbwE z=5v+zu-$MzKPb@?DIAE&HVzXry*k4cO%p8TLOw+?&Kc-YYXyG_ePhLLwe-Y>Z6`B$ zoW_``80vHQW9;+0H%!Ac;YpleQrltYmmaUjB)1BROv^^IH%fo74I(gmK_ZI8m+bTd z<f8<4ee_n(({3ZXgg0-TMFvfq@PSfaRbE>E_P2P^)H762(sL<g#_Un1Jzn*B`!ZSP z7|!VR@C3PHMbaQghsWMBv@Hnb?oA?2dhN$3;lxr>d-8I6V@?RatYV^$?I2~|wF<qI z$f$M}1y#BN2Pd~(f^J(G&2Wf=0HE*$jU0@^Zh?6KtU6#@hI#?!G_M;W`<K$dEOqfY zZt`4N?PntWwr!?sQyK1!Mrwq2!nTO`QyC}Ta{3VkRbJI*LaE*X5}&Oh+7%o`x)4cX z1qU%Z5}_p*7qYF!m1ryA5E+~u)bAvQu44-#NjgZGhKXacL?$|A#88Ls#*u<#blkHY zg^zFP2_JLr(OG$EaU?rBdYYuC60(u|k6U0ZvYOL2_Zl;Yb5(`JDG23H6iGaJl^Ir= z&<0(lC6&OTa9r~Q>0L_nox<V6m@5+7KkRf}UGcpCzCvE~E0S27#W1g&pah2%sa!qF znI5I9YhO3Bzw}j+FlLku5FOTT{(`#FMJuapH=%9tT>v|W)ZpY;?G7Z#w*>}D*9R4u zMPQt4re?P@6vVjAi=t+*!$=R8k~oEcIR2O?S}G_rfd1~%#4C~lxQC$}V4T2Woe6+= z8f8Sh$LvBeraP_F&`KW9%{z&fe#}N{aahB~E<%(ZG)M{L#;LHLVqQtorb)NGzm<87 z6gB5MW0#T89?)DOt7;cV&V-J0F|m_jHed|Zs)B+DlISv82YTd+GV`!6BoXqQL7fZ5 z^9X~m(-5H>oR3$EsZP7>e#zz;sXAn4Hz=c|ojQ387O+x$Z=hL9!tza-3%Z^#AOxl) zwR^2(aAbDoKf}JMz$ntoBalS2kB&#CrBh460*}YViL;oMRo;@jX_VKf5=4tt=##l9 zI52F4pd_m7Qv8Ik89tH6vr)651y2S_#=E?Dk_OT?i9w|Rphg&|_&D8H7amB$RobRO z?9{QHN6ivLJKi*@cvl#l89f|KK$&oMY358&KCTsdB<CM^ZgPKsjRSc*RQ^1<+(9Ot zW$=64tem3bJK_Y0N0Fkf8@!9AJPib2!+RN&)y?wVcTCnc9n4x-Mm<7~7LPkMu9Tzz zSRp91B55)OVKC=(-F?0eURT}c_<+~33J-5jJX@L~StPwmS>UmQ<`hZ93oX&kj8j<9 z;?y`Z-gGPw054imsbZxf3&0xf%^yiITK?0-V?km>hLl+*S6U=p*@)$uN;}#@2&Kjg z6Wsu8Er4MM(`C5WMz8qKERA6346G8nNanx$=PJpTstN|-Q*-ECa4X3s8i<Aw`-gzJ zNaZ#)JJ*f%ZJ;_cezj%3TAY$JKWl;^Lf{uK#j$x9*YZ=ETX*tusyO;q+1YdtFC%4| zv@~U}x0-8#+l&lH(dzs?Uy`li>%nAh9m+Lw6do?W**0e{#pJ5LX-72Aqm1L2GT>lA zoE^m&7{?AC^bWpytRL@&$@9Em2|D&=>$-Wa>RBg!eoU&kX^WOf)K_`QRVla)ni{-N zA@j0TrcdD&i+smU=IJ=ZPy<&HX3!^g!VEFYO7k1c9VCagDbsG_uq_<9l)(v(Q~+<e z68kAsi#&)t+%|yjLgD%;2%wNh|H+PK{-GSU!}=+WZ&f~K6_EYJdnpXzycfz8f>w>7 zWD}HVX(oM^jL&-RiZav%XPX}nEPIoyNwgqIT~}@yYFX(}(v9h)A@lZhLH}4()r8Xf z)raj|e4$KuCs*;DK?gGO;%wK^U_sYAWrhK>!%nZqbMC91e#-0pX-{QN0Qvg)Pial( z`9<)bM5~%0twC0$HPi=u)(PxGcOVIG2xX5D7chJ4gM%#CH#qw$l*^V>^oZFZ(2ghZ z9@kxoX8jn~epJ)_J2*Iwi38^W{qMJsI#8=Hk1wDQBL<Iq>Kmsl4L&bd#Q#-L3`9T2 zruZM0z{8=lZwCf(3B9?flX0S_`7PP$jK~^@mjc8X-tQ8EMuk7}jE3lR^{t#kNG(y$ z<QPIDOri%A>i!6@Lhbw~97_zbwH>;R+lFuFW4it7lU%_%!uV<$uZQ@{DL54q&A{Sy zad$-)oaC{x(f==sP^uYFt$=|I3Y+t!9E4eVn;sNS@?qCuo`ZCM!b#@G-`quZO`-`y z;Hc*~i2I6YjXgMwpTKhk;&!Oy%FF){9KBvU;?$*z#3&#!>`wHA4rVBOjSf=&8VOI{ z_-!og3{Jj=L)`@~4WXHqP$RQ$Y3Vi(E6h8w+PlTvRr@ML#IoeZ$icx%0H6v6s~L@b z07O-r`8X1KZZc?CYgJSSU#m_i`fow}==)y0&3x=e31CrP<Y<%YR3{C>)&Nv293meA zQpU#n)S#SkBd8GE?fSs@x=4x6wuW5@p+gsLlTj_!T{+%>*U3tag0Zw!NvI=#6!yII zl>ou-uVA+_`NU{&kR|xkBTgNv&UOe=7ao&08!NLS`SUv+J4F<<1<}Z>4SP)fwo65O zv6zXHkX>f*y%{W;S_2V59TLsyqJTo;P$pO&eSml~Qx$pr@Zob@a@<tP@%UyB#925# zfPU2e!Ba<-3G@y2mDNPMg}|=_HP7F;_>&G{dyEcrAVnk2|9GP0IMyEwD28Buh)qtD z5_O*purcKxCA_-*l@Z=c{|1k6^APpp^ucom8c$z{4>{p8SF|5gYtuv8NSdpS8RB@N z<c5KmgLQ8Ssdc-iHM%)#v<)CnH{xMaa9d$DspI&5$C4{N?YETL0}%qqL(qRzP+EJa zn*pX^8mjIKRz-lvk7ET_@YvvEvch91oc2tXUPeeEt0>wLK^SycS|BT$08qk7mEwUM zw=H#l3@Iow>FE)%+X}?%gunxs3SNOYrlA^@<6rj>U|mtJTl1g)%xqE5c5=?@PO@+- zb?}~bIRQ_t9CgWL)ut14XWkcn1+(FLb=&>pT}Ug<b3q>3u`>7uC>)arrQYc-RE0Or zKP&F8YJtTyc485P1md2*j^!<y6HrZ9$wfUquBs@24&ge5D<{$O22sajMg=WMFyXCL zG{UwPWd{IW^C%LDIMN1)69)C~Ob14wYfh?9Avn99f%{a-+!u>-6NXqALHjJBUnrpO z9v5E{O*2K-8&MEQHh~?R<gB3aLq?ca9#D=?m@%z56#%T{8Yh1e!-9xCUyS7&Sum3z z%C|=olfDd%7`sJ2^o@B#_)AeEg3tqc5By~~V4=^47qU%-4hEv_q@liuJ0Lgcku}6< z@dNBHf}CYGks50CM-B})@)nNwSP@1>W7CqLmu}GiwCe|q>JbL<nhN+2Z9!_#%6h-5 zTrhyJ)=q~%nbKa6#n!Q`;9U)C%VG2Y%$!WxM^po}K8}U?=>EU9;oDl$`IglO{-X0A zsX1Mv5fC?%zw;2+v?YTRl&331&e+`Zo1yFVhs5FWq?PypVFGVy^j@zR>Y5<^j{O!_ z($X{AcE=Qd$|^-3Z{1WL9?0#2A75oW9n}XdPJ$}UgTAff)7gTQFmnyYP*mW`8?F!7 zTnOX~H-h9taBp!7+lPTX2+Qh9bvIRf4Wy19?Fg^<powX;RL%T(H?$O9eS7FRW3rTi z@nIR_E;IM;f><9mC1X2Etf9gBY_U{XJ?3jwfopnO%JC;<@mnIv<WEr2#&I9zS#0Ni z)EmT`nKe0m3Q^AY-g=;XM0dSo4BRAq&?eLvAR0_-;jM+-`e17P(h!d0DEF-%OIwgU zZ@hmr1V>=yIf4n~*RQl#+{|0mhocHcRvoCJ>N8N8VM#PHSHaw(YGy-3=^65bBeNxL zt`B-<iFy8DO!g3@=sBRIVU5&SS@N>R+M)x-d;dO%KCJ9rW0_gF8)m|Ue&fCN5`8b? zX7s!04C5#p&rymYu?A*ac!uWgCtGqqbpTKks%gZ^ir;!y_`gbX{~`sab@P;5rudqC zSRDQD?u~QRXQF3iUW?FcYv@$6!IdZY4yP*^qW5?2Gp9Ufv1ojWMZtea&7AFCkxwuV z3R3SaNYFflke1{V2iimf6$(eA#BAJo2~EcNZ?S2pcgE(x;X`D!4KOa6xMh-<yP9v! zGwRh5y8wOb4joi^<(jP4i=>|>xT7B1u?W?^Jo&<4gz>MixY_`*(T~a4uKd;6e$zmA zV^4^LGilnPHBSbttt+Z5sqJ5pxnnA-YazaA5D)sy=QW&-Ly&$(hz}Np6tjUmhYoy% zJ_^8k&=YuL>h=~}>H4AjlTf`+rqf&o7ZMx~WgnavVn(MXMh&6&y`cgh*KSl}SWYao zy<fc;cce~8zMbjSBO%qv#dynFw#j9NL}3`e)Vj^1a9d^$=1|iM$h4LYpn&p{R`sHX z2+q^WKuGS%Q^Z%HBut>69dR-pnA=3KGirsvP6#y;kKIx-1y0105&LatnV6<8krH2B zgvv#4*tK|jpK3f{O#(X(Iwz9HJvYLbHpI#Zg9Xj-l+!>cr<IcISpOw$qJgBB+IPb* zHKao}$*d<rEIFy2giRbBz&lv5wVi=W{QQmV%U_7w_}vKH@`uKgN)krzW=aVqtn=%m z6!hb}9PDW!g%U&x-U9cmSdm-HUpY8LC&6ysZsIpqS4CevM=>&Ya*G@vMemM`jveK8 zSIbJvJw)BG=b-2d6QG78r7PAVg!Wq~|4H|ZTuc8D>Oc(*UPY*v*+`qC(!Ve$ta3*d zHU!ybQ6q>B&>$!<Cb-?$UroF=&sAxDbXK_kegnnJmksk2$A33B^At0`k8W~{D+1A2 zA>|IakkOth6tUy5w8~uw`zgs?OY5bqDC=`f<$t}4GH*UOqIE$0EjWm&v#?Zrh9?#> zHXkE(g0kzXc)hb{lYO|rZ<iF}f$ZA3TVFQ{OE=0)xek5njrrmYJ-PcXAV7AI+rVi5 zpflz$2=jGRTgi1nwkGx)3iKn}Qx5`E2xYeEtb6&nlzq+N{H>RQOL$IB$nyx>l=k7X zaoXZ*&NnM4_Z9qp9l0F|3e>2mj0uLK1Cvr=V{`G%o}R$}TSMx9hYL-<DCyTvw@z~Z zH8OL|6@HMpEdu#XC4c^E0+q?#_0#qPY*(aBPZ_CO{4k$Rvk&Gk=4z**C%QANPZDZ! z*Po{mXrybz@!G@`n>4eP#5Y0{gzE50pnSm|8{QBVFGvqWB$Xawg0V|KJd>Y1d3f)f zSvjzX8hRGs7>_u=?)&<q0CY#!y6Xgy!=B5&8Sud)#P^@fZ+XqITpUiVGmMqO@+RD1 z4DU38zcfnt9|}d{5i3mTDDCeLO%X_fevUXx#(qn1g?I=<T;?5+E9QjvSuqL%F!AO@ z`apvxuLnK6Mf84V`Nyf^f{Q=^1GP0q!CJ<2MS31jdOmhE%F`O%I{_nhxaR9kbEyOk z-X_~plQg3SLz1)RAsqRHf7;M*axamWD8X^Wz0J(O<bqykhg1Y)V|4_R%kFWAaxj}k zt@;0mgu0Ws>Awg@<~o084iM#;3ttXKx&A~oxy7r7MSlhrZ-UIvEaLP+^k$R%;DxIr z(3+?>K8#F0hkW11U6Pw#D%~ewHT7~QByq%mGWRCe(xHIi;-J%id}yei!EA~oSudYA z+O<0YeqP8q7x5$@-t}jBFy<oxpoEq2L)`=^lULZ;hT}RD0Yv0)?qOlHpILr^biz}9 zLMPnZwjA`4BCXE~=+T~LGWG&}9TboGop>EjK-5U0<lNGgukg#L_Z{@=XX7oF?nZ1Z zIO^fel*&pYL3C*<h(0=2=Ce02{&VCRpW4@-&4Qv=N9Xz+LA9fv*vw@A69VT?f1G|C zINFkL3%;cgDI+y;XuI5MsE2lTj(5LtwQ+>{nZ+AR6FwnnTy=p$O^FZ$Py_&>d;rB| z48){Cl>B$+-<M%1>F}h*=k1k%FzC{%wC}8fOn4P^wUv7ZC+Uu8@%(zmHJvN!vhdpN zoO`xVHu$XKDGazv239pQnZa=SIlI}S1h|U>gL3JCP^}zqV_EDMNYr|*j-`apo|<|1 zRf9!`C$NZ*Q=2I$mD;S+uXoOYOT>mgQ;UUQ&DC&1ubdv6_%6%bIy5wXrR)%(2dw3& z%KVMVY51mdsbVO{DGjyJ0P`J)0!pEl%__0<6j}{q;_y41$Ak0O6-@L5pMU@MTk2%1 zzx1C9F)p{yXD_=|JZI5X#{Yc@ZLn-0(<AS><Ir_UbIT6*z2Wv)Qy~_Mm=%cqhaiE} z&hDV*)yhX=jEe7GP!T(aCi^N5GIMAv9poyJI=qE)m@9URcNIA2(Wp!+;77K6Py)Sj zW^_kGMd#6w&_#WZ`!tJaazlWfIZ3eRnmt)$vg@P5?mSc>;`q7@7W`i3r<K|Q1?Q5# zs;CRIkz}ALOk~6NfJN_Fd}XT0<F)pgFt6s$6e+(A_Ggi|A4xf#^=`P@NOd=I{mDee z4hOelANS!aIMvKMesN3%5NmF%_;3tdfU?a(3BC#em}IkfIm%OHZ+I(GxSztL_j(<Y zWxnR_==g1Ih)pVdBNf-x-y|KL)_X5_Wu&*2<}k;*R`J1FZ`IQfCN|N#LngYekhiDc z^G!do7Kmf;R0>xOOMW=YYe<R&z@TY`K41&3xI!sTA~a~7%TvNq#Z9HrFoCDeEQ=Ev z^GfgeE!2BDIc1Om<cg)r?&m7+1bj+%pGzaqi7l7f*XS$^0MUd~8UHX-o|QrzfmtOt z&BSzNe_UJ4hy7>Vs>62@YDgDpzgFp~=Xz<REp|Jq9grNehCiRwE=m<g(g{pw7{&$l zXA$X9f1CKirV1j)U_lhbxUxOU#W8A&3h{>@jV=F2(RoKD^}liaqKK$~fD2cF6KA+l z8-Tb+xOa&wEi*MUGb;pC+_*<p;7ZL*P0h;6o#jZ=%FN7Fj;z#d*VmuFbMF72d+t5Y z=X~ySpZDu^;Y`$=TLRp~(p%V{`~?{-uD7NDp6qsZY|o;-44%I7l6W%T(S0CRaKkvb z{<>;*O2L++|BHhCYEJ>l#>@IUvY}jth=zqjVNY#^L#yEH2;}J7(IvYOgA4Y^F>?_` z=WBZ|mTZ%1j|J-jw2uMLZM}vLnty6jmmGE3d>!OqHlveho((ST9W@Y43kr^2jXI40 z1YP?#9{jo}fgqaFy|eY7)PBt}o+8zGJf1r>;ehQ=vGqK%IwU`Abkj|v6fdMv`D<ib zka0R{=jsDC63Cx%Yh4vcHYDq0VNVk#`M*giuWr)epIQ{b%J}ZHLe=t%HeN)A8+Q#> zl^|G}`mjo(@GC4>ZU!^>FpMH~!=ZPVAyU{Ex^P27)<R*GHgxM{ewOy#et8xt<yTMD zL#9Hbb2ss^W=%B09ahQG?oR#?({6AzBE<lhqS_;S4(+@KGZ<*>bJ{|#AbQC-g2qBl z5xRF97g^ex*|DFkvfuH+*%pD;(ChiA3+K3Mvw-!0&!Fl@Tr%cK6y4`#pw{<RRr}AV zQiD;?Vq6PV?q}%}eK!aIyk^T+#tS8BS|g9Y)y5GoS2)#|<UT_MOOyg5ByGL49h+e= zO0J$W-bEylBsY|ytyz1fc|yjM16c$6)$~v5TSrZ?WF8B4Wd(0Z)HjG`Ult%aC-!w0 zM^u}S#G-e}f$&OdKGxrsbE_j5e!@#NH^X6RcEuyzB{*mwr3&&ieNY0>K&V!LyL7X= zv)ud^<;*KBH5!01U!<Vw3`Ny3(Mny!R#MGtn7RVdw=W6~GlcM=Ru4Put8UgPL$n7^ zN_yo%+Qkr05;YvMWbfe4ExJ6&$T?i=x{paae9~kSVqQ=p1#~XD2;Chw4I<t-S=Ae< z`?rKV*(1$l9}^cdmp=GyRX3y~LUv3P5)6FJ@bhcLihoL@ep}AVyt*@jZ5`%}(UhL& z7PS_)Cke_Aa;<<qUFC3&Mu6b?wu8q%$$x0Fdf2xxQM@v#@n%Vc*cmj@@H4O$pY+@m zG^Z7n*emxIc<%OE|HZc@_`yMfw8vN3TY-McQfpJm%!{Z}BE0Y7BR<!@37UV$xT<oW z>9lTPjo|@pO<W^O(f&WpsrULOM||XSj1rgYW7?_L8y4WEqk35<5a2zlCE;ZK8?R*^ z_DY_0)ogm{g1i@RA(8p>?USZ~gFha8*L#Gmju?{DcpD=LaOZAb4Q)}n*O=0A^H;UP z%O+u57+?GZuU8OWG4sKtqeoX%IIGh%>qMB{3FEw)Gkb63-)wSB+j-yhmSh;>#EMnD zGKGI^)asc%;Zm3@A|h@yg%WlIZwCKVsW@e5E8&mf$YgqRBS73><A*O$yDBR`UwxOn zH9q4JTksy6;aTi3)pO*(m{aW(spy{z`!A=bb3_EJKmIq+G{L?4GAuc-YIH<?ZLDw# zK)$^nU{UX^2sP~N7Tz<_|JeIX?gH^wUQn&FR6os1x2s;v#be0lz<ha#zKe57la%Ty zRZdvNa31ng%TssVM)DF(*zo1N@m;cQakutI@8v#s#|x?53MZ}@-Z1U!Y!^u}x{Qc! zSg-|FM2~r+^^SITXn)@jvU`46`xJp9StIJ_A+EEpM3E))FkmM?h^ZHD?`vjNMbol7 zB3q_Dq(TMoX9|UxYnH2IVV|F>4dFMxTo|fKh;SWvyWm=PODLSxaPM<uJ6$~T=Ys8} zrKinz#vdpBOpkQ4v-V8n!~U_Y>z}J}{HKS45~a)Xp8p)tM_*q7`0U-;SBYQ-Nd4ae zc!Ds#SIc+d(cxo#cYvl4hgyX%>;fp_LRhb8s097d*8Nqd!#3YK>Ef<cl?r>*I$WkQ zzg>+@RU9Cueo>jt3wcz633=jc6&JS1Y<jPgSlidOYG8X4v6N?SYv_=T%Jgs2kX?>~ zB{f*Cx&(?<Jlq^skBLOucg0}$FQ0RCGx5t0r6OWDS<*WWTX|lG9_+GHE(^WZyRr6f zdJeY-no=jW9`Ytg>Pt!Clt@b!=gGzIFOYWn4Fc6`rTqhY)&1UC9kkt*(w~wwHMJYw zmZz5oN!m>&Yf5jcF}>u{A$osLNnWz#8C}J4k8$#y1-6SD1}6*l*(lDDpgJo7%F7Ea z%ZrCUb{M@#7JqlfJ}kI$^7@{#|6ak1J9~vJGap%I#)lV$hFF;H@5NR3yXZXk*+ANl zS@+K{-9vnhYy^!ZdmZuD92yh=Z6~rqF9YZzH5cjP2QS-L-F@Mqu}KZ>o2z--_XEz( z7xJR;tSB9qIpuQE)jou7(ykm#q4U~bMgFpef?n&+Sg*6_f6d?>OZraT5vO3TS*C@l zP5H~=*>$o)e{w&O>gnMiCGeR${cq2ptQb(@aiNy4(E;94Wp9bR4&bq+VS-88P6iG6 zo^^AgqYh&F>ECs(T7gLLX|T8&IQk#2vu#?g5s+^JDG<k=<M^thWuG@j8)o)8{G5ht zrqB!f564@#gn)0~>>*BB#7AVV|B`j!+7=fujco)Enz9Unsi@aigxlE_X*@E4`4$BI z<JUX%>Fu`O;5L0!4AEEK#l8~kb4p>s9?J~(19NPy{`wc7sNnVB?VEcYld36;%dfpn zIJ0}t(aOd-l6L$ZXPndAD6#YES&qyn#huFuS%L#IV*^}%*b}Z$q{Swjs(|hz36RLT za%4;jMYD?hvqE}CfV^>KUkT-c2y6IBx$Y7LYsEb^&-<AKwFza5M=l!A4lu*Jk<3Lt zN7>$I%9v|m*2*<z$e7$zHovFr7~plbiWPU4JEb@muUEK_>N!hFGyW^<Xu~p$eL{#A zG#pa`h`l7uYLXn-5U?^Jv4~;S9(F7uzSlEF)eD_MjCk&;+3S^EjU)6BV1mK|1xfpR zP1l*4)D+fVx>ay?=SGgB+ajXg>I7G1VloK<17R6#er>S5u3ErqRZlc4KPv6UWR)Xj z!eee}ZJu*re{UT4@ZK{!{IkKmbUOcF;1gqoYNfZ}gXb(X!ny~MDqEH;RcAqC4r}-F zwdr;BaWR}>;ya4fFamoqJwA}@=ixoka_Z5?1@^9!PY-~UvDeku0wO5^Cd8r217fXQ zcipZh|00IYI&o{A`+ioB+DBCGsr6B40PN&&K@XQ>&RDv~vfR6}9Hy2+{(Bc3o8Obw zW7@SRti2>O?Xf{C_s8Va>>#_<T~I$!F!mx#mCo9Arp^WT>i?}#3+ur)bsJv=$taA; z$0x}bFy#ws)ADx1kNEWZ+O+oCw1?gDk~mpEGUhKxemhBRos4z3&IDKlNkOitg>Jyn zj15n#*rP}P+j)OY1q>1jRU9Vcw8x~80*b^1k|ZuMbk)8&ix}1G95&KN#$DXH78xvE zZ0P=l8#rBRVd7w6&Ua17owpAzgdAs?M1YVddv*WT;I}~v9P-{Ka>nQcfofr(Ef^4{ zY8)SOGM(j;plTFf9hoi|nNsalq3V_1TiNZQhh&|*TPwdShw&rJ4w98&6s#K){})fl zl+s)3(K4)bj7ZT0b=`%7wa)nXeyXQ*vd1#*ZSM8uBgk@}$a+a^dwN}w?g{V<<&?rH z(}G@8P>9vs@~L?4S*TDAHoz)?Wx65YJiXhzT+Nd0^Zz^L8P;o(*qdC`BaZ>e_mLIK zckuebc?MNl@f=&jUAGQEdRnbe1JSNQvk58)Kr#X!B9=rF12`-_Os_duyH&DRyR%1| zz)bT=l4&4gO6pZ?D0nc7J1X$x9y7!%rC}6|pObdjsJ3Sxbzs{lsX3-01>~WiT{I0a zmh=b3ZuzZ!8}jJ|2Ac+#kLk09-DS76%L)_;2CE4jkQ;i?Gy$(p*1Ff{Hj-*QJnPZ* zQn_I$EyY2v^|8ZK|0;^$bj{7J)zqUTK_3A*dZ!M#?-PkSbSN21x-w@JyX@sJb`~Ni zBFdT@rGylOp*y;z!$2}ffnATR)_TuA?z+}6*4|C>-aPwRe}od6&1>C(;0BXWFtWlh zxv*&Pq{@x48r@G3g5TmNG#OXAKthhQP9ZPHo$JQ>9#nmF&tY8657W1ZeVx9McY+d} z<{xnq;>-#{_9&FE=t&A1+1%LQ+&wtPC%c3MY(Ks@#{V{YvQ^t@5y{cd>^0n<QDq7} z`?BcUFP&Bu1fheX4ql#Di<H%-sBs0n-L<a-vtiQUQ7N|82=zk`^|;L}2`MnS&X5}J z&exB!ajRIf+8BfIjBGwSWUkt?!yPtsWl~tiSZhjb|EIU5?qkAt+QCAhteA*ieP}O! z@I+dAkDj4L;&8I>{`U`$TWDaD2*IqaZ<f;tszKO3a@ZH7#18u@Cc=R_gpck0`kAS# z;{98o!h3$WeArgEOL~~sgC{U$6m(^~K-k!xwqfRzJb@t(NjV9&&q-!3x?&O42Yj(5 zmqQ#Pz&M~w5(YxAkoPJeWean`;w|gcOjGR~Q`!kDH}P)`LF9Pa41UWYs^~1&F(jPe z5+xWz3<yh?mbI%5EoB+g1oe<TyLYS~k#4d+_GCP;-C1zDMGgHIZs?cyR!YxaLC>Bs zNBX(2fE_R>=`pREt9rto_tpkV*4w&X>NHWX+euO?yPl<Pg;t6>x8YgSy5<Y23Te-9 z3%F^Ew+GpS1A1iEyQH_t7{xK;i(s&X{(kEnyI}Xj|6YJgnBkBw;DVp&TaqlH)0tQ9 zY9y=&-ANEPjbITwqSCg=8tWAJd5g&GwE0f`gHqQF#zy3ux(Q)|(*nSo&lQi_*_+L~ zwjXd{2@_q{69hYAKPLV}uCKgFV3{YNIozW=)1wp1)HvTQ-AR_sq=X_PljmOEL{!+v ze^rp65+%SmBy*1g$m~xv8LNhUeB1q**rC&c5(&bgabpLbMMjmc;=L>>T_ug$FJ?OO z6XGq1i7frtX8BIChL<ngTrdme{3JwPM`^D<(ZZ0xlrp4z6Ogm{Nd2J}Y*Hm)NXj_- z`;$XwEV*xuG$o?Z${gh|@oWmNYX^_+TfvXDhD7xw`!zbme!YG!*dBO#Uy6c53Pg~M z(A!B7kIFhhG1#L<k%yj|P>Uv=-!^PtUcYFh_SGsF)aA}K8hq{j*<FWxyWc)tP>&6> zkg$ipN=~RMKI6Jwc~#+Hc(ut4Q$8Mq@38c68o1QK4pOk#EeCy)6@@EhH&rx>tZSII zT?R;6G-&9LIvH%Y^afcmQ(&1ZpuW-<F2fE(Qk7JgM$$}W+N$)fud0*07f&ItbQ#Fg zu#dhLerQj<BfH{{TyFy(6#EhNBjxOjs7a!9Mm4LE!TM2^|002P(%1se{(&{DHUXUC ztE?ZZ3{fXm<CN{)uI|j7O<mC%6RHp>Lw*s~{S#<4NFmQzzh8fA>Y(zq!SLk!kkK*r z2nrnPby{nNqG3qc+X+JVeZ;p4XznJcqjpPI?*r3^tSxZjM>i{nqR1h$E31^YlTMuI zyKg&!B)|ppa}_Y@?`6R!FLhM@=)0%XZ_sH$j2KQU{&`@CW6Tu{ByTs@B_F6_<|k$f zPTLWyEMm`h@9Fe}zY*SlQ^u}yD^6zViD~b^1(V&S@xgQYB$k1KvHgq@K=Soy=rNLH z(V@Ej1Mf|jDBBvP)zQ~k4Yx+AC<8UNzNc=<VK?<yfy>2AwLXx1Y@A}exvWgb&@B6E zd5RLgM~S%8gC8R+*!)B`CE*m9uCK^@u0eqkP-=@oplA%6{<=~o@i0vOg}a&8p_r&k zZ4x4n_s^EaC-?Rj^uA2jGNvWtm(2Di+MXQ?En*8l=Fxw<ZC84z+D(~dcYKr{Bp5}^ zka%gs>M8)t0&CMlqKz{AerXa|L$vHU$UnVUmPYIvb5LPqo7tLQ_>JsbEDp|9GYG*@ zcRud}O3XEz1e80Iq{F(UF+KR$Kk`2gJ3t-po4>|SHAutA?8n`EFw7I?ZRD_S1njBt z^mn^GqN(!x-@Rh@{9@)$9fO$vO{?sPHgC|Z_jH&Y(Y#tijC~?cplED3JEznn_}{T# z+4<J6cd6jbJ^d!Ny&eB_GDFnh(P}!qdaX?aTCbj)#R7MZf$ydM?s*5d850{!(CV$a z8Ss4H1zi$q;~M&jM?}LBJu+!ASe*@9c=<F=K<=ynzTwxY^!k-G@}09iD!~FW<XPq5 zK4tAbd?qD9352d1m){_}UVr2|bYag4(5L{3_1btgm1<>}@b29qhw?hoDUbQ{MkIy= zlo3E?38U29YNIYcIQDSeU64Cc-WL77HRKJ%$+wP}Xm{?bw3A=kNpN$B1wMLySNU4i zUm!v%>kb1d-h+XgrG~*z3(no|$2*mq+$~CTg*d)$4tZQoIiTjC=|*?EBJ#%Q+s^SO z|5sN_&3<T=H2OV?`L<S=aq^8{$J}U-QAXrj&s%<PAAC&TNA?u8)q%kPNxTcs?2J-! zI_etEVhX%ws42m)$%P#h;Qbm`w&q%8J)aO3$<v_Bb|h_cXeVAJKv!}2H&{jBJoIJh z?ellYrcpi+nS<r=(Tk6B)jc1UpF6$$j4wZ9)%b=OvkJtU*G2J2U*;+#cC4Dp9)$Nj zKW9<&*}H}FW?09d^|7PI>1ox-pwg^I<TP#n7?GM%Se{y0NsJw`Oz7P4P;y97w^f;o z-D@WNAV$MVHkut?Qx{sFCkiySqalnNtpalju2)Tk8U73qM92SSj98=m`<?m>-3Re~ z8MpTOlPzuBM16*Bl11$^^PMy=H%MBwk5MuXU{}F_jq%4}eZVR$xZvQ_R3JyAW}_#| zN)tyleC20fivR>bfCx}C6@&od7e}yjJs&5Y9Rk7K#>gTe*-9s7MUI+ws_Z!LCU z@bcMAl=_vEYK|YS#18ZOk;WAL)bjseJ)so~M+6vh?(T}TnzAE~G!KYu#6Wjw(I%nR zWoC{AH-_A`EP)q-cy&Qmt)kw^*{f=WC(=PyGX7%%SQ%ynIH0j3w!HfB1IChAAvTrT zZ=(c)Mi5vB!(Z6}X0O>2W3>4txC(nrDbI;?dH6Q5LQ?6d$>>gEu;eSGEhg6jfurI` zP&63On(2}N-fn|Q*$3dqm7nL35#CF=wpQ5+(H^$P_Ol<pt_fi(T!`gyZ<J1A3WrPw zFz1Jz`?*Al09N%sH;U~_A>bG0&h)z=<pDmHtX2j&d2{-Ba5mqnJg~DaC&%#jRHbA{ zihDgTq}T|G3CWYSE(uQpb!p$0E)!xz!WZ=XutSPlHcW&TtRPOJ9tNB<`dB4pH9Kg6 zG+r2Erm5kLPZzSpt=LFw1yBHLL=m@y1h5A=#;nhM2G1tNroH$^cG>>lUx(j%+p$$c zAK0_`aP^=37rPoK#i;gk>V;=V&#`iRr#4gMvVQMqnGs!4J}-U?T*-F#5IWIzZ!M%q z16muJ{h=(t<R!5eX<>M`--}nEQNs)9bQzFwoh<c`3BS}Vjq^hU-eGp`npU)Jj{c=^ zqv0C<6f+qOY*<M*h#^r9Fy`l~JNgJ366b$P$)^B<dl*=eNFG(0Vo*8)FivON^x>pI z0Htq?m=HhFA6qH^4%v66PfrjS3^2zbaygc<*~X%I+2K`!<{3(Zwm#qW0qS_jLtpQz zpOtXcdJFk?P0+owB(XTRO0_pOPsY+y;A@3;xK}4$*dNI|04D2@&0nYecqq)+_|)tL z@g7JiaM5ONc8mG*SZV^!X}*jvn0}X?6tm3vjMKG&K2y(=+aukOAk998@ZTZwK@An4 zL`xFM4!CzP3DesuAa#=ya8I)vBHlw6rEw`D_Rw2oa3Iu|YoWIPc8|0Y6RYP(g<0M~ zP6ItDx4Y-p*uB?TRUjY~Yk?Hs5>k%Lzx-BG34Pl+J5qb|EHwJHX<f;vM#a~1_HQdQ zhfT!!OeW%bz!4*d7R8DXWmRhnDFu+IwJ8Oze#X$|1(ZoUpj*HnJf5!n1R{w*2?F)R zYx1MW6f<fdlEv-6-N<hUl(fJo8==T+F(w6TLcn>8IlN_BW05Ym=JwBAE(O)z)I2X1 z9Ke+1&LyK0lEgiyJ+*dz3Z*>@Q$kdi_TKlJ>Isa?E`ez|8GK|k&o(*X_Si#>9>{t$ zXS>I}8HAW3&-AlN&FLQH6<=Tr=EaJ^<}MD|cF%E$6H|+lK6oK>fV(#h`6=_C_hOVl z*;LYORkn#K9vCd9`F_$%goFoA!=68;KlqZ<j~&oXSx8aI^bn646i`?qq|)3d=sYhS zEiXMW$!JSVH+OvBn2YkA&SagL3NdxBHyo>NzIe|`mfRpA86OK0@kO2#S>%aWQ+v>I z4w<TIC=r{8v-VuCKD=Rf%Jac_{VS)zdb_-)RR1<a>l01G{2)lvf82&|ZC@_@*@lNV z1fI<l0L)&=?)0k<oM~h}KWx@9{>p8tSN_$871^mG@50sN#Gel9$-+Jo-mjfoxZi?8 ze4kqnWv^6;B&8EMxv(>}OsU#<%OI%n^jGhB&yz$8>6R#=U1bXV<i@5PqXB{wKL_{b z_T)Z_O3`m3i`nv~!a^cysyxmXEK!EljY~xABhC%wmw@Bi?!UE(S3}S1z!eJa9Rajq z5Bi$<=ii-IZ`7rhL2~zzSA3CrbH&dteE%xf#)tnaS(aVRo%MNhynj}adNcFlsBJw6 zamr>@@=JWGNy;X?utYSATDd{qu)W&lvDhP!Eah09vi9i=2AAvalqS(4=H6hFcaL|J zP>`%uyEDv`YUIqR>7&+r5(6drjg6aFitFpgi|^&fgYf|1dw091=2jH%9%JOa10X*I zG_i}CKfWI#E$9yq<Sk>JMV=3f*o&B}=?S4uJ#SkY@y<GZD$(^Avo+~3#dt9BpF&iU zutJ)8bE<~6kwTm(@rqNh_h~04{A9d^<n<}0`6RADScX0EXM3A&dEmHMaYA@Zl?b{0 zx<s-xII+=c)J-x_NkXR=Gr&2jyZxi+?wFA7NoV_g7x~gxPTlY|TSL7A)H`~S5ZvW3 zGqUFGkW>3E&nzLn#_cB4@FH}v;}ohA(wW05XjC<s)Fgjs_%g?Mfejw}&^5p3$4MpB zj{NN00P#6Fdm)1LB{9dXn{SPXsQRGzaqO+mo(3!anZ#@9Kg7>%$ev^5O(*E#21$n- zCBh{8JT6wGM_HAn|NV5>M}%%~Z*1CCq)Dww(ks4Op&U6>Apg<sA8Z+_Cvq^142^*L zD@o#-i?|OS5L->Ih%LA?yFOzNIS3lR-*aJA##w#|W4#N1*ht>KU_LDjm@j}C0sF7d zQM6L6`@&!+;*}M%m$%1NhW9?MRN4A={jdG!OTWq_m)!B5gHOq!GNW{<OnTn;>zCMq z3@8QkWgrs9VVJGv`z(Ab>qU3M0X2}|u`g>rwSvcNe#DWWFuoDHGInj`=MoIJGl>9x zQh#m0fU7y!K@#kH19mp@cN9Tb*mB`H{n*yxqnF3i1tJ=2Yq2f##l9TVcJkPN_6wbS z^ej*EGhHr_zK5W*@HcI7>2Q|9v;Wrjxr<gTHL0J61%4Inf$j8B2{*8<6u>nJ(+FB_ z3?WK#bu*Q1m?~z3L4kcy_UOR-W@9Mn?qupRO08Qgj)aiI1*$-hfxXy4U6b{!8y|S7 zl9aNNXQSH@kp4NynGFfD-u@;~cg_3(!@xgsk^38=`(YK5<%=psNZ=`7uD$DECs{EM zv}YCs=sV(OPi;=(Cp&3MT~Xnp;1@KV7YZM-V@<Ti1!^o=cJi?74u^b6R|DkyG}7gi zfGYPJEYM$CK%(L^RzJ#KR}g1*tRA9=@(DtI=NXFPPyi3P)<uscIYq7nZjaB#)}D#0 zy#Zh)ETXX@`m_xV#dtoZY~>N}@t=-of1pYVc$kQ<KsmtsE1<K`#ivku<jcC{Ch4~v z7XC@*Bsk=WrRq)2)w+8L;k5V3qS$c(I@^<UnE+~J%I;}0$nR?JDzA}9sKh?cP0qGO z=7gi<Qg$WEKc>2jmYUbI5AQv<vey&>WNQ(L&DgdWtyBy7CVsp_Qd-^zY}GPOIO66* zkTMr<S`;PH+^s;Ri%|nH>*Q_hs*9BikvaaKz{ji|uYQb#!0x+huBwsU35JXHs6C@g ziqd4<aF`EGku*(H=~^N$3(NbY4;Nq|deBT4T)|Up_VW_y4@fZm^a4qEv<vl{gkspB zTQ&X$v-XN9?S0>czP2c~KUeGAX)V^c{M97+9=gson}nx%f0!)d(Pp`)Nzotj%<RVH zN<jNY@M7YD`&^%ANeAxyytNat0JF8y%EoCoCSj^Ve3T4uF>Fv)rG6o63c)lGQxZHR zp;)*!1EbJ^Iix5b=~IdN9srHw8GR>-aRKlLo_KI?N(K5;cCS$C;-?OtiADj|(K5qh zUcn0mm3`hYd|YW5t;APen9ZyEfbQOrURU%WE3}f89P$>4aPtREsvy^$b_0(nO5E`b zY#iCbfiKU-MKW*)#FX@x15IaKiH4_f%uh@LNCMg;@N5%%@T&oWnG%SnTL}XTH}@2~ zK)(kVy0A*uvW&geKm84+XvI37p=Gs_Z>@LBN>j$t2Q2<Ynj%jAaZ6U<1nQprps+qK z=P~bi!vNQTly}i@N{=R%tGzGL3$`0pyVWh@=J1j|uZ>hXkkhKVwP4zni#<4xE&pt5 zKB51#8Oz-IF0Dj|2HMM~ltRf4YvZ#DDaQL!(9!vhXU=$DKPH(rFFQ*<L~SJ=+Li>p zSLxi9u;38XiqJujw0@)9&L~~ZDFtgIq>3<7)yY%^<(mtBCBcGw1CRY}43vqbTl!F? zhNVEx`*3C&#Cv+gBEy4X0=x64;$lqk!)Lxj1?*Gw6;U{Q|2Ax2_HK0`TLXlmf;>RD z8<_1BFLh5)9`-ro6O00z`HY<`@HCB^tLF>z=jH2@u5C|R@R!|GU?J}9IPaGhG8J+U zyOlq*;7a(C)gXn$B>9K@YgNlMl)LX+DC}gbYLC00NDtx4Ce<leYoHqgFtoR=iS4=A z*+N&H)5Jvd(S1=zMHUP;Z<p*(EeQ)d^rQ%@pl7Tw4-c4gn$95aH72UWy_*EI!kdCV zd3<(Yx@f<*+<6kC)UslcYtiE;tu#{mIhzhGGcv!2(|*+LB1$`C)xIxDZ;Oi9`g}Ny z6_mY#w?28@I-?si30l?+r^P?V9{FN3*^m9;PTX%`*6#MR!|(=-F6M(pK<S9-jJ;p` z0*%!o#RDUaP`_KYBGWwQ+IKzQBF;G<nkpVo9L&<Wb1UirT@1OeX?PGbOAemE$rVAb zC3sj_eA+~7k=nm*!R*vrgZ0E{{&oGAz}52OA$o2mI7*u;Z}N@LSzN<55o;A_LlZ~P z#R5p;(uOy#hTkv@)y(M)%(#>EFH?1pzPsI++v(%>>xSf7n95MHIzeF@mHQo%<kvy6 z^+^gl9KNJ2#up`}YVA0=bt>_}H|%$Dzhl*L3!yUXBzYG;rlZ^MO)*VnBPm$ZpHs5R zUcC6Hi8$~Q+uj<Xj6#CRaT3Nzm>1e}*;wi)wo{ZMru0nVXT}$?YqN$|w^^s)3(T*R zhmnN~3tb9UBk}{FJ<q$f4i(9WI>vZ*{73nG$YU#OH{W#U^m%T3@T`?=P4~%}1-W-W z<PUq+zyxt?KZ2%*BS4@)&AWL)7UD>{SS&9V<~16>XxvQ1wPP|Jy+1$aW4?>Zib^dt zyjYBjT3A9)Ons4?VI>@lv&^lP>oQ5yDGvYpeDa7s_wKQ;evQEu<1$t_#Q0Yok`-rX z`3F|X6vvG}Sjuu2qs-#(=6&PEe!wEZ14tJw9QBv+{9L&V^H=SYT>?Dh@UJUbgKkyb z`#W%oElH|=uTRlUX+(_0(<JQ6Ah}VT;>M~9K3VRievXCXIn_H>H-&lH;#@I1t_+nU zIU!lYPjx3-aSCX>yI8~1XHt8Iij?i)ltA!&p8LJLkGUPOScJA(P~xJ=nD@Jmk}G;~ zCiCa6hX_08l23`4?eqV|)X>hl%wpw|b^o*|)xJ<^xFg@dk2Zl{bLcPLQ9f<pfRkkR z9=DcZ(-mCkveY}3wm&K--n)VV%6utDD=lVSe&;QZV5h~93joAz*+DB>bLZK)TOTts z&i%f1KU}_pF6W^ZLq=p>yK}fHNp3jl!k+b@(r!s5W*E0yzJ4+Ib7}Df@5$qns`NZk z5$b&m(?fcx#1?{y!(lv<<VPp82hC`5-WM~#Rr!l<kJ^u>x)2>Cs@?Blovg*<DoI&b z<XXfilzD6XwWf@~?`helE9Sw+W93WcW#x*sGt~auKT=z{sC6pI`__iy!m46t@u7!g z=7`Ph-eT1Om+*u4cRJ4;59{ys8*LR4Y7>f*1eaZSZR9dM%^`mycC=$hKYic$S|Yk| z8d_m^)_hjev{Bi4ueF8n6i@ZyVu$xe`Gw5Ke{W{I(Y<~~4rpOu8yVQ0s=2$4<)&T~ zIc?ReJ|$U4N^5_;R>0s?Qb0gYw_L-<Aq4trTyF8Dc2l_*&N)S`-a34WnpKonY8pRv z+#vY3Z`n20eJ{MBcw*YPefOfyuE%WsxC9U^h$PA)Rg5F&=N`Wd=#^nY+QLmN{`S39 zFe}F?HiDc1K(_V#W`Hc~&i&73n9YMl@^LAJ>I>NG?w!ZBi3HD`U}nYQn_i;0i-<s5 zGU!nbXt_hf?Zvcdr1^vW%ct#Jk#U!ib3V98XvZ?vXr2LI3n*t*4&U4wPHhOhp<!xO z-gn~PNc08b!e90$zS?gQ+$8>)#2eF#x9`7Dmd{jIggwB%WMOs&a84Q~Fkcr_bXA!3 zd3C$X4_AF@4phA_%W|Rg$~2p*%Ag7JfA~kAk&@l0mh#wuJL{i=#cKkf-+_#*KiHot zgMt1pZ>3>pOkaTxnhkOebaaoslE<*#p2{MarPqW~afm69Y-=~>9=|EeD(xzrePIUE zcG?v4;Jkx;pOUK0(cqUZyMsx0Il2?-p!fJ^2T*@cqvisP?z#=hRQw#%CBN?4U8@bz zbGG=@yNNE?Mb2H&T(984RbQp-pSR?;JrqQHEG<WlsYgr|_MSVThD3^Y$JHd?m|o2X z@pUpMZ5(kacN2vTtZmKTfTG?AzOSlzkE!XFe0uxI-L&^RSAs50L>uO`7%c>g0&}oF zL^_<w*sE}6TI(njgy;}mp(_HDyuj3}4|!kSNmPu0=0vOJM0uoD&@ARgw`>b2uQM+T z|LU0d3!j~;(C-15E*FJ3y(UTVYj{<RjC_f|OGOULV;2_U=d^Ta!0&*T)J$mQ(fh%W z%8Q$`*!o{YGwv4|9BL^SxzL9MNYLM1sGLQoZIYeSb*#r2mLUV7b60MKL*61*4_x}^ z+audfFP}aYj*-i`8?_0k4s8#>bau<#>%I!AkOLwBu-%)1^-|;GlVD>opr-_cqqTf8 ztu~c_F!{^p{{D=9tq&;aWVdqktL@V6$6hhmG5S=l>3`Q_x-)G;Nh9r=OX$;r+e#|d z7K*ZGTJd$yscBdUT3`jmAhI<D1X^PdeP$8tuq>!G;;AwEMJ*@*LMk&1d(t5#_(Kf1 zi@)vGi8j17`ylbp?|)*%rn&BfI&wqG$doBF#ofcgfg5EvFx$?#A3D58pOd?HcRuju zW#b5#d+7EMiewmu^)-?3-cqpzo)*})LnB`4M%Hmq6V+l}w>U=13-_`l-1@E_&<RX< zsE_Wm$;E;ghOM>E)fvb$$3&ZR`wlX-*PcAF67~WDb@GIoAn$#E$ai_Ue^d{>y-ef& z*%1$52q0Fj89wJIkK(^zT^)l^=R9`Cf^sb5<c*~%!CoP+O183zk{;}=eHlh>a!Ejk zG&({vJr)M&+=Gs1phQl?vXCNzKsHk7cAoBIl?g|^e!$Z?TFnQX9s>}rqiIDX_1xG= z+cf_;Yh1OY5}+;6h4U}+bXQ2<CPO_mU*N_)k^S?9WuI)p!qnh?;c;(dwew!tz!ec0 z>d`1vu78}OZ5TggPkQZ9NV;q0z6FO#9#z1Sh^uBhnsJk5Bk7rDueqVQ2CJMPJF`(5 zd-c*tM4z0E%DL8x^tQWUm-Tg?5_iW@XECT8d|T{@W=(BnhNcxIRvUPXo1RcJp$p`y z<~w*Q0<Io)Z{uc8uI_|T-&?x9C|$0blmd=7ZXdCWB&!Vg1umJ$0F0R2eqP#a#;J$D z(Iumr6IFr?19XMTd=>H_lwN;6_XEs4S|#Wi0U_#^Wmpjtlzw0oy3V_#aBgzVTBZNq zg5K>tEd55p+E1lyGl<~Vte&5uB>NeauTQz%Qr_dyw};UId3FN4CAHBSuug1|jro%T zC(mQ5R4+B5+_OFjvbunme_`I9GnprHz5Mwi<Cn?JmPe@<){6Jae0`bm>S4??$FpxW z^jbH~2mF+sdPH5<UcdXV+TyXstf9vSwc_{l5%U)W%v`;C1xB8#-0gAsW_!)>ubaBl z_|vz5vGo%KLye%FOrxH^FHg6y_zT73ErJ1t)Mq+be^eX~om7kih+F5WevzeUoYyf$ z)YOVd^PZ!jRsFhtU)Gk}-vCo5&VHXhbtx?9O9{Hv5CI}YFP!rqd_|tX1aVBHglEU< zRtbBWx+Ko*FR{))jQBXHoD+OGH@@*SxGI-`2+J+q3`;Vvf32HN&UCA_kkSH`rNz1A z9uDKiwS1gYyU4tcT+2TDP+4??ZN0z#jEK_Pt)e4qB;)VHID{65|9UAlf7v$p(53pT zZ`P6zd=`o3P&*|}GWl8Qn9wwic?pAh1`*U5BsM$cKo)(D315MeA$bGn+{#BB2G#h# z+vR{iwQF=oc7qWyi4w5Bqec7>YC_0O(@Y6MiD}yF*D;`)M3A|PWuNz+0)MrutTd$V zNw#Z?G_~RDpal9<9{QIDbyx-Ea8V}(m{U1FAdPCS8rp^ZL1kT@_pX8TB9XZQyOD(< zuct0XsI&oN%57u@As1JTQiv(vd~l*ENUVAcV%U^hpHkb4ncAq3d2&_`=oU2&Z5Y%K z4Uw0P9%UFER~C2;y&VM+#604qX=dxeUCS3u%q3`8&_-q?(1mUU08N{u!!A%A+iUo$ zaYS00g(h0*er0xBRes)lcv><*>ceT5q8$XfPDnTN71nskxOf+(%2w#M=JQ6*`tnX{ z)cqmt!|5)#?=f;SSVzMrkB3V1`-+otxd!dy@DpJc3U|V;86YH3;Q=i9hhZP6N7k<8 zI(&_}oojQ`A+!Zk*I@N_J5;`3B(ot;f=IEmG)XTM^IHmR7!q|j0E&7^<1%HhWO6is zuC&C@u3`WFUKhTUH&{I~ftJceQ*Pac+ECcX-A;$y!HPO_Y_`>6xV;LoJfQ>Z<O4+d z(ASr3z5jmN7DnA?9;-&?{#O;-TGcOOS)Rmm-fyR>U#Q{mj|Gp8O~=m0_v&_{;Aym8 z**SuheI1>L7U2Y|o2GqG3cQ@ogT+R-)(iBOzBp=AthSG?;q_R~!!Jw*Anp8-J^SEK z`bN5EXV{tKb0Zm|o;;-o9}k?+&zn#8m~n0VU3KHoAq<VT<bDgK7e>Y6pdrIO4!xC2 zqQ6?kIg|Y63jr+D6!K|$=k-dIMzzM9YVWkM8@I3Zi%4KwzyO}#s-n9YV62A7d=M10 zG!b%QQ@u1j?YPw2CTj!kJlwJMSvn@q%Gk@UY(_4O)O@`DeV9b0&rPbe6n$}}&(tX< z)LrWSij^i7s<0mFdH;4-|FegGZ*Qjml3G4+Dq;No>^G)>`Nt9UgUh0#@Ru*RV*-rl z-+y~P`tB+IVnrAa;B3>hC6&@FMW&49dWCNB#VN?1Ju6Kq@&h8Nv3by)Y2ClNoMC$< zh0jq=l>LDyK^|01cNbS0Gu`hP)IW%9j0~#pvp-;!xMtJu1b2g<>f=jJ(I6JmFEX90 z1m*nM(Jr>qs9Y5ptD&pTS#D?p1s%fE=Q`JQ*#()=k`_b0FLjH%|GwADzdIZfdaCTr z@DY>y=dQ*47a**hH@Nb1Hz~nO**}#eN~)|%*2xUpdRSDGPBcb{hxS&@8$PwWW|@jM z4M{Q8!9Tkw-HMN9T2^2el*<zq74C5Q8BaRSf+G^`mQ)#PmZ;bDm4Qgqag8Zj7Tt|C zH5mWcUU~^OCwHFEm*se~K+(OBa8?xt1_*4|lXKt`UUzv|?*}`dLiU}N9bQ1}yL;>6 zXTxRJkLKg*)RdRc940@roazmL8dX%c(xh1oR2XQSJ9fc(>A1AUHudC|R7*Fg(hPV5 zSJqbtrbKk`cXRB(La0s~`lbtma;Y3RSIE7$Sg=eq<mKLRFApMPm>-<)V`i?14Fs;n zTZMAzhdA*p)cG!*C~+$6;e$POd1>$#W%TwNg|{o+xs94`-ItF^RyH7CH@0*Q`+rW6 z0Tv(JE7cOXzjF59N1$u@RiW~+j7fxQV%y;Kt%*1qn1|Q_lJ_`qpsC;cPdq)LRkk!H zY}$oIL?4f^d&!G3s+zAv&AVD!`JlX`gc`v@S<CU<<sGnN0LmRe$;qG)UguCYKJvF6 z7Lf3xlQF#ONv+p?FFC`%a7CeLLNysqlorn9BA${GD!brXMW?+B+(O-gP5Js16EmN- z^C+A@z!iJSg$>YHQsW^{gi#}}5|^bUt2UgNyMG^hj&6NFdh(742nob+#V<$gSv?!T zjPkk&vJg`fHtd5$lZ4kd&mvKKV`HTMoVA0eqQ%uwf`jqd!a}*J=s0ZBxv)TmXw78; ze3I)c)tuxniG2~}`jUWHjY`r<vAmW9=Fh>eSD3uw5xb<Y#i!5T7C?;@p&jBR9_FzC zns)yN3~eZZ*JD#U5{HhVj=i_mj6RId-BFPqR~T*fMDfjMkD;b;!tV&l0<`2EMsmj3 zsY`q{Lf;;Y5qL51l7cE~7qM!(88xMx3h_!6sb!$((bO&mzb5rviOUdD=^5d4v3f9} zI_d1<@ry}5CMHb9Ues)qSl=#(t;u0b1wM}C)Hml`az>;1N;U&&dK9Zm-O5y@^e(<w z+Xwl6rgh(A|Gpoh!=6W^ypJ??u+4IFwVE%WHYG^(W8+MTDJ9{#F%b}u>E0n;6tzbu z_^bvf3aKZ2P6l;>AY`@?mVd@V!UH9C%nm)SE+>s*1fnv8QL)f-jvL_DQw#?lc$Rn^ z3C(uZFxl}!jnLo&SUGv}4(eY=l0=e1O0(W7udqSQ4>o>$lIB|&fUs_bW9ZnZQaL8Q zu%r^UQ)_y+n8X|x>lu&j34je?RnF<<YS52J@sF&998OHS(6*A>emdjaxOo(SSg=lZ zBMNU5L=rY=;%zdYtc_)iz-9pSG$5S+evk2Z3YlDhp0@+W;(;i})L;QpFA#|@G<6mv zk_sRE+B?~&iOluA!aVc`njp~PYY_s226BG(A~)m3Y`UO}0q_wjhf<THP$IKqqhD$v z-%$bUArxO;NxR4w>!86J=iK`Vm~XKjsj`@C4b&kN>a8`+1QoWcKYPf@D>l8jjTBi< z+K+Gc!YA!yMg`=XA%%gcs6e{$Nm{r`vwBo*I1)v@RhMO3n#Gew@jbx#spx}9$$bDy zn^f^Its<e@tziK+!VPqptmqLbjut5<f7`oDWqY!LxZjqIPD+@XgCAi)zA)e;+?)?k z_&+G7>#mYhwSKu*3CmggMTj*zTH#2$wds8NXAxAR*M%RF8Q<At2M(GPZG*F=g<a2Z zF_6rmmb$K7E0Gm1A_(_)$nb5Um9K@*Ak}N1I7g%T|B<6xe#Of@1>1M=+eJ`Vv*Q{` zf(N)2xd|#7?V@5WnzEo`13S*0B$JB31g-BrcxSmmMv!ll&?^G$28i>Uc$FPpth%|Q zL@trhtCXn+N@^G(eXsnHr7}m>Wd2bx%ojB~mZb~o035mN%SNmRApT*+FV&!h?n$A^ z#>S@LZDC=b=%|qi$Vo!{pk8f7NHoC6N=>i5v&u(z*Gg^HYDQP&iQf7Tk7$|0kIcao zx>3Jt>m<8x<&D?9JB_&TmAS?VoQV>B#Q^uKAT(=p+U}&0j%i(RzM7aT*1sY4u~hr5 z5ax>r#<~*yT~^guK;%*gC0tl|K45nffi)t5eKhgQO;C1#NG|p!xj7)A2|^%%8AywZ zWo4JheChdkBt6<Op!I`XpfMRN4XQKQY}^!WONfT828hmJ5hhml`t>`v9{<{VCm8;& z$)`5%)|V*icbaG>R=Af3f6A>YUf%mys+pnJY@#P&Z78}-5F1cJ&3=<fOG5{hNo<8n z9IwxK;M(GH`&tzs@~;aqC<lLp6*}2;*67W}v&CvMZ9-aIkn>Sx%V><mJ(>7up$b(W zAgcAlG-FK@WiN&zBin9?VIO0CbvUq*rkteOTX!>1gY=}AJjB$7D{;JHp-ZeYKy$YN z;5!EG9Xny`bH2<~o_0nBnkMF6B>IX3L-CubQ!)xSa_wr_#`Dc4pqBIV(3mk;<_X9L zp75>>cZ(pLz>o?F+*6>H@24m9>M8H4J(jg)Cm3HK9o@>gw*$T-a$h(?N$EChl!urA z;02h@zqR-8UT%|f#*ETV4|KuOITFtq=SE0viOT4$703~W*hniZ@}ta%^n=SR{InE# zkzt+C_kfv{n}F-U)8jfYlA7Dl7%Y4XE9}}O`hk)6o*;Ib1_elalCjVWU48FC{mAi) zfqY@tCPAC7+aJ*MybpVKH-zdF_e5>F4*x2U^8_P18UbttFecckfr`rPI$e&w(E=ME zgAdT)8Z-5~R1Wx!s&y~8iTZBCuyZsDan^Tmkbs`0iTZ9pZjt1K?p~3~Eyi15<0Vm# zWGvUV&l{0@<%f=pSz|&ykKHYab4QEhbUnSfzGFxow{4*bUn1@1W)Zuv*rF~(EMU>; zC*0{E+yxsB+cIKc9}({hngh^H^?Xy*-giE9Jj&$^3UzBc4n4ltN(;4od;n20kRexr z9B++wc>F#B_1gk|uJiFvIaKkn>>Ihh@Edp;KHNv7^ZNK>%|xXaBsaxH*kfK%=Em;R z6kWi=3ni?KqaDe@?j;R=GlqB0j~7ch-?`KUp8-6)HP5gs6d30v_KN5TwRzqP5;-(3 zVnc>%z@f9pA>JE8$D$xjfY`@5#K(Y%uXFHvlK3iZ;(+6XF?^Ez3DHc0gkXiN31!(H zLv%f1!nV{gygKV__=)aI8slXzI(KA35(n<SuFW<Z1sH-x0i!{mqF;`|Ckf~}kpAbH z_Fwhrt#UNW1~o~8AuC}&%4AmkuG~;E1-b^un-WfKK!iTQUa=((3*9OII_4%du4`c+ z&3_^_E+&yB)&r>A0}T6{wL8=Iy%Ekk^HSs){rMFDNQ;7|@q|w{U8>s<Haa=+c@B{r z1>F+ctz<7QK{T5uoPZVofE0-$L6h2`m0Zbef@ms1ltB<}zbU+FE_@6NHtT}yhI?0l zH;0iBFDzts8j>Aid>k`!j(*^kgyf<qDp))4Z6erD5!HA?A`p%;+Gq`i-yfMf@q~xC z`SjID*UQMux1z2b+<Se;<QW!G^6IgcGn_Mp`F#QQoB+#l7<)>q5)7BPoUgybe<E=b zRo@gVK_x%-OiT{EFa$zn|H`$R5V;13mUBhYH=qna_{12b>Ey&GE-aZR%w#}sG>Nt} ziKej?tx@|kx+IfnW&e*&BOfjEg)cO{Sx!=OgrjJQ5Su1JpC(~Ku;`fpQ8q8^7+2Kb z<U~^!c=`(DSl6B?fPb7G4geF8*%F@qBP<`(>nZTwmwexmS@PJxJ==F5W?&D$x#Zn` z`T4IsEJ75z)onsw@vcL3n_t}vf@_up9hnnK<G~E>yt~Esdm?oMycEIa&r8A+>$+ew z8|P8s<Z{OyY*78e$hgQA;2|&u&BA)uaYc=<z&<s-$!-#T*tK{iKqP0(uxoK)&UreG z767X@vUhqUVWj)%&UJdg`-r)v<pmx}FTZYMsLc;ztSI(50PGh93CAv;;6Vr{y@4^^ z5G3XwNXY7PmIGs1xn}lb7CQ0sz|!C4f1i~WNHCX4C3@8%Y`2^geWexz|26}+Jf5Av zcM{fR;U!Mrq4i|*M4xWpM|J};1;HH^Qwe$oXz~p!nRGN=W!d{x{a1g_^nDn~kGwIF zElbh1M&XzM(I=#dI_^w10sgE>^cq(riy(4y_^FE^DhF%3qP{;h;JT+XZ%Yi&IMC+} z+qopEilQmnWhH-%qCqZg2pcOxE)s-}1?(O|A)g<r8<PtrZKAEhQvt?uMd)Qa#+Q8S z;|)Wt(zwUcdhh-_5~!XdfmcS5b`XN^Uj1E^ljc8@%9O~gsLU8$NrY|)h@;Xj{kqxR z{yGXK@DGwmf<08@-rHK0(cMxNw^rNtvr;!*;j>tc4Y@9U-+^&a-iCFXlUf~ZqGs%U zB>^#k6>Aw2v3U3Nz89)X*$bJp4)HiEH7=Y?f}Z9HQ3zn)fKMa4-!>t}$DsV5>UX<g z-{}Dp?sLLXn;(uJ8qw^w17_@a$yw4r=xM(TfT$mtcHji@pPRp@Oh7l1#gUbLJBos1 zu&!?Ah@`GtNt3K02de5+#i7lc2My1f8pI=gEYly)9xy1%4xj)-MT)^w5vBI@p?diJ zkio2Cr@H{hH!fyDkJkf0h2|udXh657fMCkTD`%iSHrl{4^RlKp5K4YO-KK>HZqoSm zleM{5gFofny<rhHLp=JB7_D!v@x0p!P;(Rj>ME3PaR96tn}(#2QpLaHsI^YAIu@;A zs}sUq3hXmLSP|zJPvO=HM7wwX+Oxffngf%68N7$d0!K-qb@=z9mUwh2;6>RS{G!yY z4%yV)w2WSQQn>Hf?98vzD}(1%{Sn)54Uc|d7ze*@S)_8rl_|UVKe!S#cyO{5{aB*Z z`qm&dP(~OiZTSLquW@^_G1U@Q%TLQ8wg<2=AqBryuspf_Hkir|mo;7uK4FdL7t<}o zhk?2*F|L`Q4~2g1)0+1xX?3+yz<_9VE)^R6Skcu*FQo9!2mOy&d;Qf->_ZjiQe!$6 zv|ei|ZCXnJN_NjHBtWBzJMe)66M3p>VUshmHWzW%=q0TZZlsd%DU;x8+n=*PFv(K% z6>_bj;tev7sidwp{fRe=`2FedJb(>U+RLlwr?9f^3xp))&ulx}C>O?>hNM?mD!7)& zt{nXDXAtK`cE^oD-q(XY10|8Q-r;2DoIG*YNQjx*qn)%OTbioh4?!L#q*J51;J|Er zCE6oC*{YO>jg6!L7w<L|uM(>8Hv$v&EEPT6UemNB{hgha+-yWlW>~an)dI2_u1fLj zQf+Tpbj`UG-P^>~;C#o#VU<BFh@)cj=&x$a4TeZG7)3=$P@5@|xL`@sQIdeY&iAR_ z=Jbc_!#9k96$~&A&@8eHY!3Ej?yK=)WxH)L`VoizB7;QrJ`6L(*kR_HhttZ4qGL*G zQVC%d8OHZkz#`};l98jPA08I}?EN;eG9Zy!5<Khu;X#gcdF_jea?{5JCm=r1dOr!b zKaYag&X<c^1n7%!6SeN-S5>81$od+l$iV9z7O(InrJ=*NzxYPWv`2+R;b|e2=>8bX z0-Bj@vcH)_(kq$3m5Pi4Co|BMd<UeaqD>>@`%^Ir#6I|Gio9}FrcN9(kV9OkZOAtD zImEGFT4GdI7$3Y^>%blc<}wZXkSsAhr}M8vi2X!Ph8cgs^srjll&g{|(oCs?lmnR) z{5s)z>0f1j&HHla(OnE+-RZ1*&YW^oc)_vO(-7d6V*jC0UOKT6Ro|!r_ZC&LVFJ9& zK(}7mN9nyYvs@jpyPfPsbIAWFIv0PY+y9S$HrvdcHa2IPnVIv*S%+<gIW1=+X=cun zQ>AkEof(a!Ig>-q=Y&)$6$?ocQK?i;Njj-iba&^s-#@U&<9h7cKG)}cy<X4fWrM|Q z8Gq`iA<s+9b3=3432vG2=-?!+Uwug+axehT6c01AId~mR3RiMhNP5nra2~n_eqei* zz?O0YqD>3!AULg&o5nH}ICWN}F3yxtH#&_grW`c6$Iy@PdK^Ws*R)DWz>HHX^FOYm zR`5@VczF!PMDQbVA!Y$dIhTP`lbX1<hYa%;PPWdN=XB@fRSuoH!CwCF{CA5Z_zbmY zbg9M$lxd7_o1tOo<O`u6+H;SmD%A^S7U7MsM)PDsQtx7E`IHdtp^TaLV~hAY<M>S+ zW^KTA>8hnP%S18@zNKUsVj-*9BvM-!w}4<%aPI^jdI~ZS{P75qp|PAor_u5KTa{!D z4zeBKYQPp6jpGL4zG)5`DipY#O_SN7DR*V{@c#OSTHMp*kiE6r&z!8YYNeS2RL7(Y zq~4|sUQDTXP(^Teea^R0cn^{zu%{>yzV+%yioDP>vSGeUdkv$PPo+Q=f{r(;wRrnE z+T6#)47jOXc70FL7_F&`>Y|V-0#EF+6#y)$jLm25B&=rb?n;+EDR9t_NVkR~>JMLz zQzE5+fI%<31Jl;opeeua(83}nNUBNtA=Jc=FH){2LB$!abI~bFj!)2~mJ|>oc0$** z>E9{Z?Q#uA;vzl2i>5h0a2oS*0P)I!r#`2DGj)s+792OTj^ynER(){cG(lYFvweU& z2<W1FXjOAB+iNZ}BzFrmmF@E9KPGx+)<re!=>l!%t@vMCJL73Vc0HT1+;+<JpH{bw zml%#9Lv>_QE-iRb0d&e)ZNyXZzm5uW<!9gMy<7VGG6oGp{u`4`E2FCM9kcf%9aQFx zoe)P*7Y}@_GrSDs>*s{lWdoNpLsXk&{7@!7GpiTBNAV5RyiB596;q~$44G}$pFP$^ zDZ(ji1^sXEJ2oQJIh%rmP74CB-p|PQGd#Hz62ux$QAme(?+Vwm2hyg_6hfCG=K-}G zW{F{?qu|Hw$$cL{HPRAQyd5DClE5Sk!Q_gn{H1|sr_SLh8Br*XG_ZrSh21TjIdtsb zaFX;x;$+!~MctIXmqA$m@S!{^7bo}Ea{F2n(GuS3otS5P((&dCP1l!21R1h&CQ+6@ zPx5>Za~N8XP7q{h!@8v#y8`sIM2?M#sEaKh*Hmu~AsjazXkbDcF>#F!_GzmKiI+(2 zsbCU7?w0Cj?=(I6DL?Z#f9TZKTNG`Pgm(&6<`0P>x|3kVGFE0q-vZY7RQH+mW=Zj8 z9T^_%K3nYLv~xWbS6!?_?VE%W+|$n<9hE>ARR#geS&@iOImMUUUmAyPU~S00WuN}} z^2$UEULXkwj;#uoOKW{&3lmh~pe)U<OZ)iM(PKrSvPW#fbpQT!@%lM}{dBaH$X&7V z5`wwyouw^EJZx@mKFd080kNG7r(u8AWC#B_bnDY@K{g^lGOSW(|JLp)rv74bPK`Jn zn=njV6FQ_e7Nap<>yJbK%icF0j@ts02?QBD4ke`^?4sfQ^OX-<)yc=r^3?dqOg*f< zRD3G`?w(yaG>iM$7bPIM=gdDX&oS>Q3^tDv!Rl{E6B!BY!WfaPGyg@R^}=`A;#U{% zVF%Q;zro12Q0(JxqX0l{0Jyz-d#iKvIB|?LY#VoDz@lQqYb;@8XSMd(4}^Pmx687Q z{`Dy;mht<Az9e|8HuI`FsUOFMW%+`tq{$ydht_nnOcD~m6<%9FgvD%OEf#XZNV>}R zx}3~iZN&%cf9}9lx9uhm+n(|7y`uREn`M~$ye`p&bH0K+dZ0bf!<|Fj_TPuIKC}5h zw^fK+4P>{cfmIn#Pr!TG&BL#Qt-1WCATvIY>mWdh|J<Yg#br;D>F@1@lUBmjs}=XF zZ3@8p+)QQ*crWQ{#tEJt$qHcZ>J(ml-ex?OfpDV8J)GV(`GK;d2tE~?b>O#@thc&V z?Bz_w(+7SFc=qa@WLT)!9VEo8Mpf+jSAXGyjS${j?Y##WMTU+dm+z{x%Q6G{pdQ>k z)~pOGE_i1`sV@oU&>}uSWgeV_vL=zTQ>J^;G6Pspj1=wH2WiXnQneTSMmJjaDu3TV z={^8R+kOwh-Dqb-L8qdjo@Grp&o{XvZ+5HO8<p{NQhCN?9zKeE)m}jFs-&xAI@%~? zGa-XQI3chsM_{$ua&-mh&p=9;+tg=lf=yPf4!fB@0dw{Gz)u7`QYyvf1SQiOJaUpK zD1aL(qH%)$Gp>0W8#$VPC<z}ahPm0C789)d<$c~2(@VQski}tQPA99gc~HJ99l<&7 z92S-Nd-m4b_13+y6?xL5+3PhZJNT{{=z-Bp{&?oDIPG9~)(?d&^Igh*EWWX)y)|9W zri^FElvsG5;VOh&7D8NV_?~d+#TE<ML@14ZCUQP2&=b11(&c;#^!$cHow~H|HrB=2 zlRwrXa{(`5z6sX1;T0`_V7rF#Q5JzI{Ot#4xY>@fXNEJ@HS50Ss>jM9Hyl~~9HYr{ z!>+R#EFLMUkjdidt(U(NIPqEiWGS`hIlFeun*%K^odf;Zql0L&K%oq-MH5KDod;zu zhizs){;>O1J^ZM<T*iQaU3OviWQ{90d!JfGav!X53XA^Q%3Y?e0or`xXpP7r(|t6% zOIL9)GuSgTObmzY%St9@u?C=FJ<8rJzKxA-WAM!iGPn_UmIRmBFUTZ}@=WO&JLws5 z`zPLVw08D^^|;{oe6Sf&;)SYM+4&G1%O^7-)PXL)IOt^eknZ-kQYo5%dwe*@Q-NO& z&kW5Y*&z<}TLJUK2W8B&*E?*^>)3zQvZ7?{B3bFjUOV>EDZ6iQ%tuavykqXXK$0ww z+zp482_P!&(jFILnI_F&ZO%-04i~vUkA=mnWJdMryV}BnnCBkQZY@ssC2HI|_rd0l zSB}(I^`?3C=_0sWyWk=b7DCUAUxik1psp2}u0EM8fhjz?V)I0%Co9vb1;yl^cAB+x z#u^<~Q#d^K_~J`DXL<pi0+F32xeFn_HZFDFOA@+E-A9$(yShw%7y_w~7Ovx<XTe~Z zU<i<si_6<ekqhA?*p-5pQRaXU9QHuM9-cwmtbV=C+QqNw$*7?i+k18nxbat=g!2?> z8^J)401o9!-SYId+)-<Dx{q{AINMqoQzQA}R;@u^SOQG^ZMfX%OP|IcaaW51TEnh8 zSKB$~CVO34b)STIG;`&G1ulN`FlrYpe%4k<_py|v`C*}9q)bkkWcLYZ#fJZ3seqU# zE=iiD(P}u{8s8l`;L<|cUm-YU3%{eH!YqOhv;+WfpTPtLpl_gaeqa-lz1J^~{3D0r zD4_aXBrs=5>k{@|83a!-fwhZ%QP5Y^-|1Q8EafLudE)&a(^(s_bt7-{IdtlS=Y{!J z*rIcwW>zvbD>fPyEUSAz82iQt7PC#<S^nhK?yx5m#a<=MZPltNby@AVtHKPiVI~wB z+6DU;2lHoT_Sof=_iBfY)+Wv(9fNPEcn=+}g?9}o=MXjjlP1UCxPg0a=T`}L7L4VT zIqEG0?0Gw|r}64LBC}JdqfjZxh%u*ygP8*o5e-f)sr_-4Zu}ZIVQRXXC;IFY3b4AX zGYUB82!{ZH<C${#j!*Q9Ol#L~v8tYzR|)nhoHma&Vd@@WLZ8CKZ1OVL*6Q=BHJiPP zx6i5X$x{!i3r931lt@SCg}*`sCuI7L2H`#-F1Q(naWjJ+LNVG<6@^mO7}VOuy^;>_ zwA#HnHGADxUr&40WqZD~+rILwUa<e|YTXUX3kNmEI!D0@bNl(JU?S;iPa2aT^o=R< zy<6<|;s)hJp<u*OaBp|c?Og)cZbV+O0P!#wmX)_@CmFV$nJm2Ixz@>oW=~zTd605G zw9f_>BMcW$LWo|W^I2?eAG_>&xgm@lW!f(#zc*uaLIZIwgZ@f0hy~Aj{o~caQG;ch z{BS?0e@#y1OWQx-?0^A8nBZ=F8T4@a>m2ydB`yu%+GQj6PwQ*;LJzjURnjg740tMh z-+eHrrh9Rne2IDRKli+sec-1BaAgbLlqkahE@7ZEM=!o;^x@4-4VI9Uev1a*TPGO! z;|sw3piuyyIWMst#d7|cgOKVKGf3Gr_(Dg)iz}kFuIKxxS&5{qo%Mk=^z&6bSR`G@ zUWGV!L5keW@bePZEQk{~+-cH-v){pkUf>^P3b8Gb1CLIiv(&FnX|9Aup)}T~z4o`+ z%0EZ=Pi88PL0fbmf3+8MdoS9I2d(`Vv{lH?nSb%yUf{e7VY~-7vw+Y^d|B_wcVH># zeGTaB(nC|0<Y|I~ABQa&c{5^ZNGe5_<&-3?Mt^uPyTEPuqT6yR$iq?Y{*RfARKRhM zKyZqa!;lj|xRQhlws?v-&3RYT2dOowXzPR7DkYLLy;Mv?qh%a6i@j~2CljI%ZWWjR z#dvK;@omc_OlPC5qaZG;5Qsi3iU|va^@b86So5Kgwku&yLE#}0IapXQ;H@2^{at!* zM_E>!*6VKU4JB2=d&__%Q1%DS$mv>mJeYf|_!&2Q>}q&k-vgqix=!|FN5;VZOOvWO zvynNoh3j53IszX3iqohx_<Ci3#tI^HB?nAMr@ZdZf&mWIt7Cp#vB`G4M9}b4Jv4RR zH%e{mo79W{T3>qPxuUX?YjTdwdlva2!=s>1>%2xb-@6Zbn4A?(dLLb5lG#^$E<xSb zf2V+3aWEQUOSd(h&u|@5uYY~u^&v!9e2iITd?(ZYgAzNwCgYNL+ENVv{y^#CHX|#s z3`&O3(ANzwH!WUn>N<8dAO~A;_3UAo|3tRu(yS29o{7zdKL~TTCbkRKvv~%<WK5-i zlHTv?G3Ts5FHhd_PUXpihjCKMwYBRX*=6(D$lHb3r!q}&_i~tDF}xfD^ZCi2tNj$Z zp4Gl3I(HWyf|P8eKQG*DsKHtECq_H593*=oeo+fvIhR<IP|c?cjS*`hW%2lD!s!j+ z`TZ{r%pPKwMF>YrBC-5y=b>yYl)RxNM)uOTUT2h%q%T`OsTFMAezusJ@gP-UWxdX& z_Cp3h`FG??#*@R@^RdtB1VjPvv>&ggcBF6l;0i1K-hov#k;R|vAKhMIj#Wox3lgNx zrQ}v4nq0KA%NFWa*Cj#R?gf~uT5s5VaVXY)Ps^bwY*y$jxZ*|M0p#hlhK9#-x>Fv) zAK$X}*I<oj!F$M=0a2!{Ii_1wdQ-$#{3E2BPms<<I2+(DigkVocLKZk`u}7GPJTP| z^V>?-Vh)ger9^<$PZkaYbi$#olRl|(_c9vce}5j{?yS#Y^7eT70?0Ui4aKN^CdY17 zt)?H?1E+pL?8T+a&JT{3q+|r-;a@>F%@*A5ZLoi=UV45gk##7XoV6$Qt(aXcSk4hs zUy;M}Y)sZ^&O#{Z`ktr^n|TQZecc1InKH*s*Pcq5?K<kVz4I~WPNVkI&r!OM+np@E zN41BvGq)GNnUtbQd#m8}UCWcCBTji@;(YLo@i-XJ`aWza*JBrO>{R^4V|xWSxP%2T zsWBRsEn+%@H~=x7`=&p8b;jW{lkdqL+nt(oDyQTPw5@NwM1IdpSt-f`&e@wOQDlr& z1}uQ3`|@wa9Z4Vv0IcYEcx_H>S4z!WM5xo#jQJYVKPJ9+GQYN!l_oEgHpeS9Tb#eN z6<!Qq??glhUSuci_3MH$xqWKj$RGOea)4vUb>F<R;qQKEJU(XS9C+-hYfC4qMR)ak z_c>#T^+|_(!T%o3kp1%@o$%{>;q>Nzoj*hQ=&bndu1n|@cjK9z%CdjLxzCel`)bED zz1CrxA%8L^A?_m_;SE^)<i>cjLGxth!Sy3t<WDyhfZgbN{dryZBcsq^!Q02hv22rI zCDTPPH&N+c-eo50WN}QTfj__imqEG3ZSk!I4}BcR@IXL|=i+#)SmfZ@a1`vAt*=OM z19G)?+eUkP0(k)W#a3@LgUW??9SYJjd{z_vxa_`u)_7@;&Gj1E$#1TnL}2cyW4Wa4 z1djF@yk7f@Bd@W05zNZ>ApwejYtcX}s1aHz-)8^_0n*#C64S7W4%K8+;6{p6MTAG7 z8E+7PyLkw)Yn>flZKoo~p4rX}6usJh%pTp}C7xoxH9FEWV_x|%*Td)Nmc<(DQaWY( z$5z1mu<NeU4x?EQwY-2FzoACyfYfiwK8xQ*yYbdO?S0qlj+>wAq~D*v6_lM*>=6*` z^4}1KsQ1q|7e+-~Qh`@_Wzl_n$u1Qa&wO_bCO{xAMQiJ!dQ^cU<Dk0Ju`S(BjOa=V z%<o`jab}Rs0d461gv2XDF3x}_P0O#w%Ms-W@e*VHA%g*OdRv(iEWTy2imOW0q>Agg z@J2ERo?6yevOnp$Zomz6vP{ywk4fjt2Wz&}BJK%~=jqSQTzz2P5;r(Xy0!_MGZO)) z3(OmC`RCd+xnCYP`DbNAE!lRvHrpp<0044L?$E7Kz;&QY+6-2_IINW5yBKV8nZ-Y2 zpw!4OIAP>bh_D{o)Z1a$ftNUA`lu^u+9R=60qZIeR3ha?*B>p;v@<q;!Z??Z3fG>f zPAM*(K3WWAJYB;NyLk4!g#@^w2X)RlYGgkP`5%azQ9ys%_1VRA9<S0*DJFwm&w#k; zMS5N?ew-PwM%RGEJ2c8{j2V_|ezTI_bho+HMYRIZn0B`wu~^!_v$jinjC61FYLJgW zDfz6~D`9rj5X!or=z0erw~pW1sC&?8^)mN`QR9D$BkC`2C5@XlRJ*oK87x>Bn)Nq4 ze%SHn);ENkNnpL4LEHAn7jHU?KyLFcQs7Li>yS6>zVDb_vES)O;K>EX38aQK<HaIv z$;D&7Vd$*QN(&9`2mB2~u7J7mH*6L>9T?y1hBz#{C(?kF`rOUK!P{e1*H<czS!#(! zgwM@M^44nTIuGNWV>_Q}D~=%>Z7xT~6zMzUnymrD<}8cvjLS6QTbVx&js2*5N<z4V zyUC@NXI`$Cx=M4*=El{282)`ODR0)Yx^^()fCLM>DNYzD5<JYHMSQ*TvsSKWEW+WZ z58ZrteZ~Co*@9Pg?{E2_(&XRcPkaR}rYxF_sYK`%J#e{`#IyZZ%#KsQkC-VC<SIXc z?Iw;hBgiE(M^?9~s*RH(<2|t4=OBX0m7R{23P-5U(6AKqU1u9&Hp>gsR>ZKO8HVST zyTNl*#r^A4%^>YuFU!M9TcO!z-d-{h<6{_apG-@ZnQZ*{G9l<?Zu+SoSJscbrMQ(N z@kYz=U&d@yHZXuAp^M}|RNl`*-Yc=igh0|J{wFbjI>nK+pAAm{8ELrwd0eDSjMp=w zgIwK(;GxQ8i5<WI%!&&ta-Rn&+PFxZPtvvJnHPl^IGOo}%2ZCSD^IFcJqS`PJrI0X z*@#mp=bD}y25~rgLjrMLi=CVNk!nea)=l9(z8T`lH_%YUd{60?_U;2ooe<N(>PAp2 z`WF?qyH-ci8b%QD{dhv{>^Z|Y(XC2hUBH@q^Q9Auibd!aa>Xi}At)&Pt`8;cOMK%? zS{^ARfyD;q3&giD<$e%XO8lOrpq5jpv+>p0uIKLj=S7LT+O7K8y}7qidhS2KSTx|S z$TTHTawj_$HR^5dn;bQ3_3P{@=GvY%t4@>)>Ka5|OAy3((u<#eTGY5*1|wyt>id?+ z=?cvwz7PxCi<pQu4Hx+)-~2N=HwI;cqWCT#*2BQ-oD)wf*yaWK(iO`H%*wLX{zTD4 z;l>(%DMN2-OcD)y51|G>Z`R2h9;snDq5vX<@zm-u_wASX)G(@+SC8`^szn`@y6tc- zEv2DSBSBC7p8!vl@<Nwtn(L0;M$v9J%X86TYR$`z=1qwTtWlXJVS&D%%G2uP$_&*0 z7Ff)QwdtxZf~E11=|L{a{Qx>ykMv=THo7#^+2E{aHGMHY0wumfukW~YBFL@b^sr~c z_sTfUFZ-vn3oe2N0`5?S2R@v5R3$VvjN)H-!Qf#4`h(s;*N-lhtZTbo5cQCmaXU_< zJGE-HB@rtHONfj@*A-5otjri^BQ|uJ0a3ZV?np{WEX*D?8fxQ&%Tz2*N3<xZwoQT) zPrUSbRzqkRNf@>yPq)nLA8Dm5EVvLC=iIyqdx?X?rX^D{i|<DWLrh15?HLf_>I7bO zM4;w|H*dQF7F4Z4$id0xx2yY<fz&5b8H*<ietddz>3@z=xTkQyT0%EZ`Kf!ZC)HXn z^??*ToOd>^*IAdQ#MN6sg<~o+aDiEgzKIID?>??N8!Gw?lNqP~cg)@O6Xd$Hqf7P? zBbjh~n8sbfU2K2%Wm!8Jp!Z>RL*;$hFyvk98!SeW*^;kYc*AM>gLAHxmwkh2Y`Ivb z!;VoBM6;y^>Zjs>%o~6tfYc;IH#1Z^Jx|+JF32PU5W?^8h~WN3LZFuQzPZ59>-R6; zBI;l0BBk$xo<$M8vRw}zS=`eJr%njPE})P7##JAWOP%_>qeilFyHJBKolx=+1hQ;z zI2-@de3O?ek?hU=C#;e+wcEvvdP}<fr;YNxnfq;iRV~2{iyGIjL#uOYDUWrFmu=7^ z!!dd?%VU#XX8TP7;x+v$mw)43HQ=NZ3poy>Ah}>B58a2v+0LXR``|F0#d%4qepig{ zeMj>SP`rPomwarL1a>ANQ<pR-bA)+U16%7KFfPJ0th?-6`OG->*yokqackhQ@|PMW z{b6k9_&;8CUvlpfO-{nN1FA13dFp@g<d~}>*|Q3{5&B8C*Evxj(hI32jycl~SajP< z^8V-E(ysm^k*U{$vleL6E#pNd6Wuvp0v)+D&k;eWTynwo8>Y%5lH(^k8MOPcrgx<V zm^MZMN|*7U@}K~MogXkZ@2!<fcs6SAzkKP>n0lpVI!s}65&>|(b6VhzX=RZp-OmWc zBjVp|!=$I}C`CTT(Xme&lCy7K^Q08(<bvXxw}ss^74zjGr5pP_Q{DdeO7?=(+|v7p z-2dRNbYBbr%riq4I7$F*ZZR14&f`AAVnD)}g#f#sSPn9Ae<XWg>>@}$<7K9}N#P z2h*-W<FtDn_n!*xKmBMa6Xkx_g6mFOrG5LPkzDND3a@hA;E`&0I-?-8FkKB!o%zF? z#6C=$8FKA~7*&caRj3-PP8g|-r^09Z%1Q$oCAST@BErm|vH+xH0n(UB*C|ufmtpPb zdFGj`%4paZOsqjrh1IX}AtoRw`26yd;d8zqRKk2X$~(g7u}f-6#v!e+b?G}P3VO9z zSC$lj2HvYK>a$^O{n-ZO;zyJxjhjyXD$h)~g*KHu9M-{P^r^|W#irx1vfvE;+`DE> z)rUZ)8MRb#&jnW`1TV}~1HcCJJQ6X~))Hz~Mm0w|7<LW8RR{Hv4t8Hpt0kQ)>8?FK zSY;^VsM$xK2Jv)?mh?Eh9SCW!K6P&<&ud8iJjn5uUzSqMVnl*8Ft1u|3DR=G>L@VN zZE^W=^LU)p%6l5ze}pZpdHWHvjbPs=!Z^;}PRbLa3IH$+8cN2<JUW|USOt0HD271F zm`9}(WF(HSvpqV!KfVW>^|@I0%`~htNB_eI6y>;bUmDp+8jMnudMWsR9yxV^v3&X$ z@gdP7khqKhe7*Fs6tyUkQ9{@WN?<C8UV7h8xpCTvOU17aV$wj09fP<Ob^SDv=bzA< zZ<h{GN4;xQ_kQ;Cv2nu!+?<r*h2!{ZWC~?XHO!;NVRwlR7(i7*@`=G1BW8FPw=R?& zVeakxe&}|tQb63Y3wmJqI49a_*clB0%Ba?>U>EZXPBN;DO7F=9jtTKD(LIAOG-xRR z>t{0spXLsW#<yu{S*D2&CM~>gWerXo+IOk9PBa9`hKEiAVTDwZuj2QVVdoTOQ<6k! zx5$Y8+<1nkE<?H3pbYTA!Drw0f#3|8(d~zY`})8{tVk^Zgr=u!F{zj0c)Bx7yI;Tc zUJb{qw4{Rp-XiVa%_p}O_<K>lFCoymvWQpM2)03;gBkh_3D1B~<N&$whXcHD|C=>5 zS>lWEBxq#PutXXTAP$`I7aJ9#&Kmeo1o%<29f#~Lcr7AbiJ^(?C0jA4cXrMM-aHP8 z6kMr}oTnOD2F5a6eIUA?7J97>r@deqI%yzPvS{Xbae!1{z_O%S$}6K)gp~r=I)%60 zmMs#mM|<5_Z`1i?PvOa?=HMSgdU2v%dAj%+5SnyAbK~9r7T<D}R?`h)@I_vXIrV?K zpJ!=+adC8Qq*8!q)Ijgx$|xM5gESMR*;;rlsX3hY{Ml8$Q0Uf|JBU|%tnFC2#Hk|? zCSBYs!#3O`ERYEQGW{2;msa?${i2xjIa4+ZjE|lQzvar-MW2S!2^wBB>>D#}9l*2w zN}jXXrpUAvoM#DjVzzdlsvsHh&}D;!fs(Qqy>eGs1EhpslH#u}YWpVGv<xCf8xr{< zF(puk<ZiezR&}HKRU+@iRAE`DNUy;M4{1|KNY^2L^ipx$qp(`16}7Dz+VQ;ik!sbD zZ^M)eR<sv1khM(HURGuxBT5G-!3`9K__jj;axKaXtl?kj8pg~UO;isxtF448EmH`- zt>$7W{aNA1q0@Dg_TPY<MmFsftDoa|@o2<5kYn!J5HShg<=<jiO-ohCXfGP_)jXRF zh8f<FI@G1&$SjxhGW^19zk>5|>?K(Dg0H<8?_Q%NS4W)a7fn_kz_TJ}e6z$XQj0$n z>-n+3CZ1(VsO=T1VG&OoJE#s}S2qQe{D7FwP*f}VMgXAq5kiOqb6GsK*@NmfqJ8dE zd`IVSh|$Q;C#v^9`!slcdJ#XG_t8azx=;)G0v^!-GPgBWhsIVQUl;jmHIQ$0G$v%l zML5Xp5{#b$DR;q@6Vk76C`!w56Q^Q+{rvbyi_?0(%|R+CZ&%Zn-SUnDPY)Im88xe{ zc^YEWfYH?w!MgbLZ`-eyv6!qw&fNC!@r(K-2?L>LuYsQDp5n$o!WV5|xg>{c-ori% zkTt0TB@-eu4G{(aTdtg*hXs~3L5xW8&rAZRTi&@q;D#w+1LQg6M@rxBa>lHtfr^9q zt_;&SADslzE<Y0h?MT?*&te8KMqu80IL|yryv~ua&QGsRK5J3YUrhWxzus318H;yh z0EhkYuNW$qvH|WlF!=!ty0J+6QJ47xOy2$(@#W`Y+%H~CiyD5?Dulb+|MVV$a25(I zb2W28oQRq1J%@ZaIGu-UE1`H6$N2Bl)v_kUc2@I=E-ds8``jnmHMuvWN|Dx_s0Du4 zXuZskkRYQFDbXx496itQjc!X>fW!_N0(XrPK&myOy43ag9<Y9|vw6a_YXaEjB6YF4 z^isz<++z@%+F1Si6`_W=vB@+1Gw5PL)$4tKQghfl4ou|mREZ$f(ezcSBQIyC>p<so z8%IU^M0J;Lv^3TJ=H<%aeC&Y7X^z3%Dn*kMqZA3%z*nuW3^i3l$Y;!4h26|urhs5@ ze4^urxrKV{CH4QUT^;SN*2Hgfx1PILG)=7}a_WY5Tz`N)migy1?Z0Y>l>Z2Br}<xY z{WLA<JIg7mOho!f*&!oAd?U`BtUn4g*FV;7*Ff#CJs2)#KZ5V-q0==gvvl^uJi3N# z2Eb-%?>xGAmVbKRCOs#~j~cBH%FUz`Yp4~lQEq~WOFyTdOEpXo$>|AZ=lSIib+Hx{ zRPUfC8M^oUlx?$z-L-tXSUURV_k-6iYXM*^nx{2N*&#-x5`XT#`|!#EbpSZbS>o@l zhlF3?f4w@`bY7sA@Y5x2IAC&zs^Dsr!(lOXB#^Z6qqF<rgzPI7!sepKlC6@H1QaXp zf&?a1YCzK`Sf2fdx0e8JT{s(TrUs-9fEQ?CX%Rkx5ZC5j;dR$Eyq94!qBure>lq_K zL|PgS4wW+ZWSb3fhDo2P*7&;)y(<Roh&Z*g45AkaOGN?kl7^NMf+3rPa~`RF2JQ}3 zFoEr7SH0y}V*j8LR^-98WW=c;BEfp&VHXyQZ*FyA>u7i;m^g4HIAf>l=F;;@$e$S# z^}%!M`9`dzQmhz9O*_E;_5TD+WN-!B-fEBiPmS5lvyaj>miyL!CqKSu^i>4X;2c$# zQO{4diu|7yGxujy>Cb3qQ-|c?*d<kTZkyH<C}VzDNG!uIk}<if?bSp-8%9PIf8~(W zS-WG~(RHPh7dJYHsPC!#w&kFc2kZ5B-8Gis;papX9V-{HieS^`@8y#2&+;NG2>~0% zxZrg0X8xH@iWujaH1n#C8S5K8kGZYKJg-ywK8O2;igoYgE)B^^Z+dKm-hA%ESY6@; zi3qD8#V8xXuFR36Mj>ZX)wD%|rT8ykvi+|cx35bW5ve->G6Td#LPWW5zUMA&o?Uu# z+2N$n?Pjn1R#*OLzMk!W<%0$7@bT)Sj2g$EV6wy-Bv@e33S)XkZEV%?dB*DJa-;m? zN^(SBT<C{<1pfY$#PiM9&m!VeE`t|>6psX0`=K3nwg<aEwJ>Yo=zdvEZ5NreJl%F! zFMG{MN~zU4cfyZk1V%IY=qJCz$6Xa~@oq(^T2;&Fcf7O9*R_+f`6>g_@l4hO+%7y` z>Ow<ZW$HqD_T38-=>Z}IWV%Kgk3Vi=*PJ}+ZD9Y7Us*14DWe+9({LT>NV1hH=c~Vk zJ?D!}uf#yF&&dc0a)kWLd>z}U(?_rASODWjFE0$8Y55wo`f=h!48zl+x(X6z3Dx?- z$H!o&4YFxk-u;5!TRUK9aM!|u8N{C_GhfqYI#!rcy9Sdp4HE7e^xrq$^}(1=Guw3S zyhV7vIMfj6V76<AbPQh{Rq({yp@V%!-<Y%JhUlZ3j9m@}T;AWhq5V+kwmt`JKmsdt zr4z=}lpii-=m-vItxd=;+Sog`OHff3gW4R?lszxxn%8LOcl4cPjdGrTzhKY7pIUL< zdz_D6ewP|9!ChA~WdIwq7x>R3?ZpEj%H@AHoJ_@?^Pt)PUP(Xzz#XDwA%3P%a5M!l zRsljjXAqXO3~-mQTs2i&B~IuhjiR6_yT>NVJPe$U0I)VpF2}umXY|wF<BE}tDr>L& zg6OelM*f!sN>H-JQb&U;sKvX{q}Y^wZFcU3Wvr6Pf$MUM-+upyb@Ce$G@dAND}Ki7 z1G)|w77{x>Xu%JYpuZwoJm>yyo`7+S_c7W!$`>;c+<g^$w)Y-F=#EJ%&^wJZ=Zd5X z$?g?qf!{tJSKv<8NjrgAY6^JgJRAkLB#~3^B2cmoN>TrHh;};l*NQP6iCwsxDZ$kh z3bn`yW8?32k{J_L2``3xbx3Dbffv#RD2Ekk?z-7!&h>)Enj%B9ijR=VE>@m_;?#Us zRKn75p6Q-b=rYk>z@471BMUL_YB;ap*{b_XBMm8n>sAUIs_6!?YPBJ@2>o=cp&b44 z%C!-d9@_gbWv?WVG`FKjgiuy~p7Zr$Q-pSwy3dWowqY%4M7K_dU~D+sftT3WBD>r7 zTW9Whi`Dx99qE}WAyoZQG>~hSS>`W(`gWI-QQPn$1_7mu)Lx8gEOfWIFV1cPqj5VQ z?zzk<*rk`ve>B68z+Rcr@Op@H$KA)lZOprkt$_pw2=InmVbM3ArN}9=Tcb11*~vWK z!0xLzq|15l<Sk)+Wxbbfd;sWTgI~;I9X1HWG}Y0EJida}L&VhWPA{pE+LLb320p!I za${eOTEgh1=NX$j1yC@w*9s5NH*2sEP#IU0FsxZRm!y*d#jta`oiO+_NpD>$eW$`J zeJ8Y?igq8pZqTk0mX_$GdT?A|<WpAei0Oz~^TY=57N~hT**x(8qoTKrkfNv)fo86F zWflhR!i<)2aw(-nq{QD1g$$$j+e1j>aX6&N#cmK^=ni=tSo7%Hvf^sZK55@8b%zXl z^K@&-_yUKd{gB6W+n%Dng(3;sIR<Fb&Npva<q6g=GDt%2%YgbNo&6y47i`G!w*stW zG8cZ<%%tZFHd6KkC@8(Dv7|xP4*YCRB)eB5v1)*?aNx+<=u(Gz8*o0pIZbtVXb)}6 zy8SA5WA4pFv~Nx^J4m%r#s6{LAFQs+dEEj+LZY>c-l3#SwEqp4aJ2}aPl4+ka(twy zMZssQY2O}D&07XtN;gj%NqM`odZ#FPUyZiZ`PDjTCI{ub|G}cb3TumBD~Et;`r3*g z*nP0G`;@{-Uo$1zb%D6s^}c!Y<SVj=m=ez+i){f%hT;w)Gbob;<dtp@f~O6=E6Yz2 zm(U=Y+T|dZFqt8kTZT%u`cpbEiZa3mP`1wkBCxFQ=D0}Z+!C@s_}7g`Qhb$RV9cxK zv0#5cn1=Y*>kN-bOULG7o~dN&&ny(-o_Z2GH#1d%Dd}U56At#;!$#hrGX6{f2cW}t z{hgF$&{h>I*K>(7-5JI;qVOYQ<58|*=WDJsoy<`4rNl200cM??<tR^AW1+XK<B|<D z`T}{;dhb>=!gtG_zKy_LEkh>wb>Xs~LvXO(R#~8?-=zzfgz$#W5|sIHz`*;O!OZCl zExgp55$Lu_(KufhU<t+64!47U72I>S^39wE(PuoykHSK$)<)S%K+U4k$<@1NYoZ(C zVvBPd3wkeiQ1%Hlk+84rjP8(7`UNGC&@x#@p$~TZrevT+5Wo~5osFb9R?DwJ9@u#y z@a`1FlWR1m)ztI$M@>C}1U^+0bNi(R&e9dj!y=9g9Xj^qe=N+_c`tdN&UlPX>RN6^ z@a}`PCS~T#;Ci600iHz{_U#}Bn7NCR0uKa0Lq!bPBuF}Ouvs#YPT@_CnT<!n#tq<3 z4VXeyL<2-_?5!)L$1UWqLVKWP@Gie56_pd+?0a)aJ8AQ$NZCfW`t>Tqy1?T4ZDz9m zyb;`xnP2ahnoPV5;E*R9o~bM0RRSh6ObYl#XD|>Ki~FxEet(l;3{7L($c~0bQ=Q<4 zc#0K*dc%Go!&!*i2itlc)%Q$odd<sHW;gv1L_x|74MGYBq8cEH@N@uIFFANf3~^|+ zoe7mIDB{f0Tnhjtnr!T31Eu7pCM>U6I(U`m-kFejO=`JGAx@;|so%jPh7#H#T=|hM ziUy0{3O-(v(W5KO7jnRgeU0u-FA5}r{o1#le90i2HAOa!>+SIhF!0T{Kcjh-Em=ED zSq;kdE90rJ<wop?|LWgoa9QAfJk#oWKB5P3!gfp=1}^z^2Z{rJh|Bh*k>1rpU*-}< zKg^L`ecb8brU;#Pr6VJ0WS1KUr%=y==wu;JGst!3lJ~2Be(O`ylg6jXV(2q+sBGIA zK(6QF{U<hcr+KM}f<er8joUE56~Sr1n_-WZ7`7LmYHqAvhC>dA7giz+<6VI-?j|Zb zwkDf#s)42qSEjH9!I9t<B2WE#8RhH@cfZIDHTRt&DHU=CVYP-k-KRWmyslFSn$67C zeRg9M^AnTu>Hzzhd65`%s&j{%p*4P;ohR_Ay1s|LE4#V=jizb%L29OHZe-x`-@gdu z3FQ;!AgMB0igW-E5-l^fyh~y1zVs2Ii-wn^24@h(-R?5}_vp*FWw|oG;QI#??i^jQ z2uLDCbNyW97gwM+W_DYDqMtM<Q}lxk%7yh|U&|D{=FMRFr=*edQ9O|J5Iz%}ZQ~~^ zT6I3CvGm?I*DlOv$@IVrLdqwSslcndH>wtWRMjl7*mw4NTb=s-mIu3`3g!WYnC_~f zAw#)J*3e2&SXYFeI0KCUQl(}kzd}vdx0nwM_F>Pu93>QV=((q{rT3Tp>^&WEXm6<c z%l7D~qMcy<mk@1PA@P{=(+T<(X#Ug=ziS#VUhVz+u)%JpSG3z;a$nz%{d)h?l2Btm zAIwmxB<$NgTD$XGg47^>DZez$X<#$Q7&H60TrP53aO7PmyN}n|N8V~(;Kkf%t6ROk zIrr{x-uIhA>d`fbEo<@#emRkkUgr&4B>d9No7<FM!VZT?_w?Hgzo!(^J@k9A{N2c; zeJ=}dUjTHGyX~%fy@Ua{KGQ2N?5I-SWmY)bo}bqae<Gwb+i$-<B<z0!d1I^_(8VY( z#F1&mogF+!nH`G!llX<Bi+qUaE1FhHkOwIuf7wi+tsrJ89;@b}Bfib6t|miA(`9AS zje|RNM%uc3^|B)F9YgTc$>&1jWtHW$hy6Q-_$C*O_~_5~Rc@q@n6o$Y7_igl(7z4W za1Av8fPT%AluK8<s&^8?{vgM$Re2k&wLN?lS&K9>KnchQr8aE8ksj{@wyu7h{`P;j zJ>&j5W4}!_a2D-ZW5H!LJm4_lvpg=13%3vi%5)x%qkipj#P;bDRtyQgJPI0#)RWK6 z>BI;?XipF-KeCF>cA&+%<<z<`LzNe?aycN3zuddAH3>iMEbJ6^^*-dd$^YZlHUMSL zBQeEUu|r#xbnllO_&7{QwIEa}2$X6gdhZ$P7E+6`8SGicZ&B;baoQGGZ8V<Zkr(&- z_PgIb7p0QJtWDam-r6Vx4#ne2D}kh4*r#l$(k{G$fpuw@I+;UYSv~$=fF*mVPCM^y zG5j#>M9ubj=vNvM2;Z)|wIKw4O%c}GDPR;<=Sy|`$5doDb|#u2<dIzYKbW=3;B;B5 zuA^-5lQj|AoUg(#?GU+sXQ5PX*T^xt-^uXQ#pV-(hghDz`-^Cdcc?~ntInbeiC)VI zu2udAMcw6qrN&12>L|!i#3VKae~EJt-IxCLQupGm#TM7PF6=4*{3gpoLQyAJvIq)N zrUiL5k?`4>Fytlk{quii4>Y9pG@s;aemxw&4#@vDDv`S+_r*(ZBY%e&L8&{jL!N~F z)icF^pZmEL^Ox5i|A-(MM32;>4uVjJLlLwEC1n0PTvw<~LFf5s4QBe2#o?zRU(31L z(kt`mBipiO5!z{GVuCKkCEj#)qDB4BK($eOJA!Ja6|3f6s~B&tC(Y~adxr{vNeKrO zz~SfmCR8uv|BG)_%V@?nc+V}*L&a6up95H%oNG~wpC{w~cYD1LsIePMButDX(C^=j z!D-J;$<0qm?rE7{^W@vG7ZA7|huDjpMF0Z+wyCf;U{w(vwrR7V`gdM64Kxe)A>0<I zer{Fw99*h?uT<xO&T}!hEg-J0sg~8|t{R-F#E0BiQ|<#S6wQVpRC2fv7Klsad>_6M zBbomRoAz~YK&|^veL}}+!pGIT%^{SNINL~;wn#^IOd>9RQQe`dW{R)@2IQTzbvCxS z$fq?>2wPq&^vmry>4i?hL`MOb&V>v7<_~AW*^ho2_4BaWA8U+%J;HIM^j<3hU_6vs zcMIQedu`|54;!Vw6-iKwaGw71<3`Lljua7R_KPeRUyBho=o~&oy_TI?osOY~j?}CU zAbZ#;7ajJ_U{PU9oSn1o=m8sT=hsqz4aFy1q<lOyyL#asf*0A*d@q8h@~h!RpQM6T zsBe9<&QSbEjhuh;zFPye^10fWybL5<JAZ?PY8rrFCBsXm4Zk}74^sE44&!F{{(s;o z?r4)+EIWN7F}MV9zuPMt=(1-lHlx7RLz)rvI}5sOu7fyB_}qhCnPz<0#<c&5-Aw4f zq}A&6xt77vN`c<abV^TkD<(eF*^y$Vc!hjnVep2w=NEQWHQ!s$2YX`BAyOOl?+?&F zb?v^7u{n9-{yFS>tD|i#hO;2wq^+oy9uA>0%)=t%L{6Eob3u1e@KEPW77{DI1?$At zWqqt6c%Q1jN`Rtrijgf@|1_CPM##z~w4drz0P2eIVy0BjQMYGYzpGcUE1w?z&dVH{ z!RFM!d272NqPR0yxldg9i2=#i-odV`w*Zzz|L|8tLde@EA^-j?ExG6D6N*lWOWcKF zeZi4r6h({Twi{)`6=dd=L{NB!o<Wds&)%Kt{OSET@d<!LZ%<>l+kO2W``qCxAKe#D z9^}a5&U%(8=Sb$+;3AWpBJ39<<7YnH{*3C1hu64Y*`)t__0hk1N;dqA7(tl9TkNgs zC)f^uy%vf6*RRGtVO<}vio12CbX-YWf#?2ishAnvDtAt2&QfQtNayoUGHmke@&kg= z#Njv3f`faLj)!jkK0=P94wMMgliq=*pvsFZ>At$3Do@#zOI3Df)orxVL?zd1DVjW6 zX;W`RgIP`gMT_lxHZIuozowJcz3M;ccGNvDrc`H><L_Z}Ofd!pPe)xHfLefnQx^1k zqp=fy*oY6Q?ISV$aZ*LBxwdKbs%tvF;r7kH{FXhibK4!*3DRE^6F6@kP7ulEjA0-9 z>8zo|%zD03JXvP(7W(1BTEXFk(%e8n_;M*S#hqX{n{bHa4709Q%Ezcsq&>Z#MNui) z>B!u4Rqz$>FJNt*U+MA+81q`GIQfC~RNp{tRqs$G-%@l?Rz~2p@SUK0NpT7jg6AX& z|9vW%*E*xx<fWQr6<?Djk)cun(%v`D;ZtV+nZGB=pLN|?_bQGm;}&zGHQ;s6U74b? zFXwIUOqR6daE;&9w><X2c9iM-H6<X7@$;A|*lGN?0?KM{?xjE~EJsnTR^2^aZbqdi zUZnTgMM<Fj>*z&_E(Kj3ot$Ap0I`m77F7GT4G2~xLZ21In)x5zJt?+ebZRYzMcK4c z0ZL9wdRQuor{5tRD79J-qgsX>RZkv#%(*-&1tS&4jJ!4gmkG_()V9rdian(QkPz2` zRZrPDBKx>f5YVgjW}U7LyI7H5%JI^CX7(KinWHzR#1Z?X8hFF3Tuu#67+4-lH31D_ z=a1mgpRgK-b7k3-uJSg0+H+Dn>cm-<6hbxAm*Agt4D4P_uf@=6QEhb?xgVft9Qw0V z$j9qC3TCrWMtOJUkqP(0-q{f-3%MhMmQTvubM_G;o_Ta=V`lklQN7rLajd}&Y^Q9! zEDmK9Dt)3f>#pQK@l3+e55>2($1k5D%VDES?&^MN`qgx-{IwkT<UcND7i_fGu}T_s zl4Xus-y_nVUoLmV$=ie5ym<28d)hMgQ|I`KCe5=)6AEla)T5FIcP@IJL?4(BBG5yR zArtpW+Ok5s!gQE&giV4?dVXPO59veq?^yRdd6lrb+LMQ9sulQ{r!`vYp8V<GGQ5vD z#d(=nB)jh%f_>G(-o~7L+ULas!~&v-j67xdiUw`c=DQs_U;6%G>5hxcoH6$)Kz86* zKaQ<s$==JMwz|OgTp4baUgRT4Z7yJt+`#$Fm%}d9$mL~^Adq5e^NRmWyCMD<-!DwQ zhZ7kpy-3!#QeuS{Vq~@}*p!)r%FPF@P4aXW5QM%_S?Z|+kCkoHCI5{*9<%5%5rt8D zp<+JhZ%f^`Ch#v7dak|1@`{iOp$Y~sBQvjI8>a5;zaG8de5wm6m%}|Z;{LzeW`1#X zu{)`+Pn65Z9moz)Z_leKo*a<N3Tm|z1<n?hh(A`=WB*5gEQ9_JbP<$xauHnvYKm!_ z`!&3;>IL&iWKx!5s&i!5TunNuYQR1#W-7s>C~vo%d)LWlOzkX|!hkzkNzsAeXq|T% zK;e36iWyd+3nM8)#Ttg*sob>@kdjj^Caze|Z8J|!bh6Wwpwz~cO_${lDCS&gXdaoE zl7D26K<05}Hnv%>Mml0{Cg{nG#$MBDMD9-KmE%L~mHeaQ&8g+Gd1+s~z5?@)UBD7B zA%V7A$6fP@*8vqvoyb#h7kH*4>JBfCo&5&XPotBM{DZ4<TtH?Xxc(0hV|P(0!(}%A z-P1t`Is_zldp=(p{9F`hC2>OS==vCia{THa@!=k&HK?2$8m@lAVr*_aouHFTc$sFc zqcDijZtF>YdbKB{K7tpsBv}AxOC#qV4R-`Z+UblG==59J7pP1<>S_i7hcbYxx^*}# z?tt_j9fMbg*Ufb3HA9-Wv2bU?--Jc!JKgrYH7k(f-x-y(L`5|n2LCoKfB!qsT~1uj z1;u(r+BQX@myGU*a9r4L-S7i8N^e7Z?muI8RB@f;Z#Wv(s{dud^aqvqUt5Y^^!uOD zKCN`cT#%ARt)lyq<ekoaPlIclJ`t~6)QQ(YDTK~tlBHqkE{$0q<ax0t+~gn6!`C9m zXG|y0x?%g19~P8-QiPZNFqG8Lyqg_#wYcqSG!EEuID@%;>vb$1iO+pIz5eTt4p#{a zz#+nHEWvZcJ-uh9b-L+v1?1Fki>^g7qa#-}`N<eg-?sshr7%no8Uk3a+Md;^VyA!| zVRgCJ3w%e5fw;9^DMXQ>IVaeQqmM)bjD`Z;?{Ci(PG>u0yXuy;)(p55YVH0OZcyC4 z?R1VH%g2)n0_joE0_gl`{=n5kAfq6>GEkRu=JN|EnVzqsohbG=LC8Y#T^gvnqrN$B zz)tvKd@7^<?67ST>A`cO$Tji<;3?9tK1;Veoiild!mT_YKdTOVP%S$z7|@8CobC3( zJEPKf0}x3$;NC}NrTqQw+Qksyo!YK_H6FKa{P-|?Irh!OEqgCFjQv06B{@a90zj+D z)DD9-xTM#-XweY<)Z;wO<?FZNwLnIR{qtonZo@{=Yg7e)$a`O<#kX-{SMKzv58zG{ zI-)$FT4Iql+XY`PyhhjKT!fOdqb^=4(cuh2p9QDLHU#7<p{R7MN!Jv78_S2YRoF`J zLs4O8C|0U+2{u;Fj+Kc{6;VJDp;$G-H|0e%o3jOt+n=;>AkNLVVTgPc<mrexI<&YS zMe(($Oc+s(tV;539MEvvL3?%peDLS{cNe%Y10ql;K5ZPAPArh3sdid>`qHm_du>q( zu!<tDMS-LYKQBnm@4WqIVTYcLENz|vM$Jy^b&d{Z8loJJp!B9UyIl<#F5$&~Z&12V z$w3#v3jybZKSr5R-J^@y@!dagxfY0qXWFM{QkS$0AvhJGk<@h+FQ+vxnwq=$byba3 z(Sm9e#^wEU@pjO^)SuyxCU`lb6KR;#Asn*eklaRueBy||#C8?X#U*(i+Y^uvJK=Bf zN<w}n_Uo`pWJhAEl;7{{I+SJ1RHJkL;~dkJU4`w9_|wf}T0w%xu3RI(v6&sOd<~wo z8vR<{`JnYTSHQ#kGbcq1$$y+p?ho?yn=YHodg6DE$(A)r>8&fy(LX<`&`Xk|g<X-@ zA_~vy#n(!_c!g+CIg;$|4?&+uxmtexecesXVsc=w8gTL9zffhq^s;WvuOMH(f-7?B zOL^R1C6e3Vebtwuo>zf9@`PVNw=W{j==W+v>1~9j+umEm6S(~bLLa>|H+p!bYFAQ- zZBZz=!Ojo9JAv_B_E?MeR$RZ=J$2$Fp=GreVzA~no4sAvKbh}pU1ISq+X3S!PoD8` zyP^%``*Qrd+8YYSHt$n=K0aeT(hchkzf7ZRZg`;Rn*94Kv)3f@E6{6C@xZJH_P9?e zdDgMYpw`KfJ6+H(F8bXK5A_VQ11|ydeauQ1seDC&d;{AyeZB^!WLtKOzMh`W;u5D( zqwidu@2b7<^ehC<`8Rz%?YD_LS;egSr4_E-JQt_I&<<)tSO^)tJX8?bk(k753*3Dd zT|Zhr5ggen#LFKaNq*I6{uQC0Hi+?m9zw98REvFp`WM^jlo91Cvqgsu?A?cV+!obw zhKF%qE2MFs%|{(%dT?_|>Mzh{5Rc;@4q>(v-NX7Vk)ysGmlHPNSLbI`fz^kFQtqXW zbGpbRsiAZlN@9Ldw{H+MpKyu|_EKr)V;iJokB@=?9`d@CM<-6#h#|`$sw?^8p(8~e z(x7!wI+KMp<G4r|iJH}ezMr4nzyMlPaIH?Z+S%2~#~Q;0*%kst>km#k^zPxDj}6+_ zSQ6^A1=<^ZK~*IdrkOjK`+pRji$Bxv|Hj`tZw|AqZO+=952MK;r?k!aR89#Y<V-?} zO10TAb7;=T$~lCbqvM9;keWk6>4Q{~`sl2~_v7dHAH46!<9@vE`@Y`S^}PHD+{^=i zlr^isMKBl$+o;LSNCA;mjluZWF^V&H3ySSRR-#Uj^0JnsNA9}r91t>(<r4v><r*s= zjGfw!P(j2yRHI!|*$Ur=1$TRv8>-0lkq1@eg>F>yg8<DnQ`sqt+J?MCx7sEERZhUS zsS;};NT?T%J+6L=B-v&EZU@;Hh6_#KF+>@4Im~uWZRUcP)h{_Oi^rZBz{y7yjyxXC zEU2&1Iv6SIRN0v68o|Q0u0anKCgBfKAz9j1Jlwd0Xt?Ill`Pj(hK8Z!O^ZQX5%22Z zbxn+OT<@V=Zy4adoMGcVa3NsVQM>Dm-lms(Ffr7D|L%Jtl)Hl*V1GkwL}}9%okN8e zyYiy~2lMp^XuzkBbSB-gP)#8SbzGbAAnunukeyi)gBw|Wg?DCExf++6huKti9WHj( zD7TKJtwG%<pbCPP&77MLA9qf)mZqXlOpyH^NLMtEtRxnWeQ>?F?S<!x5yP5E4>eN4 zst0Of2$?p#7Vg~KA!-!&idvdNF<%559FS4;DYT)2uA1eZBx%^*2!EVl*L^#b(6D8t zji2Q9iRyh)IkTki%9yB$Fly?1HnE$;Ekb7+m$tCv;wosS)E%%E3v%!|EwrhQEZJy1 z;i+y<e-nTZBWSJDhPydbhv)2|#!s|Vfm3mI9BJ{{K`)O$Fl*-Q4QxS<cm0=uU%!7n zy}%nnAOD-(EPRH$8tOpbTc^1Lvb<Tz6-z%q#dnXWmTKJerXR2sYomDzV4<UFb~(%c z_6IvPHop4asnOXy^!5lx4%t$lzks{acz@O&M#--xY%7VYUNmnTA*T%K^7Ya&>E0mu zA3)jg-=`y;We|njs<yI)6OxIdR7`RpP2)Vy&@&weFwJ8r;XXz_`I5`|6)$zXGx`CH z0r2TGRC#EC?Iu&O@})iud%xd=BCCFeADL%%Gz3D3R0pp5D8gE#MVQN5XSxSOo-GVf z+_RhE`dG_`(1DzW2pe@Jv!E=KdU83Eg8^P(4*JR9Evz4=qQ-8o<(1D+gix)*xOC&* z8Y|a76rRprqmP<8J-lS7MPQzohaqFfWKNrbMcP|$m74SCtzya~KdL~0h0<SUMDFH+ z)AiA4Rih!IcB%)fg=H8eNYEO!NvAy6w$(nmS0UlW1z6Hk_+ubqU{?)^uZBO2vgI-e zpIo2==HHP~Z`CS#%=woJHt%?xWer$Zg}08u?@bpv8o^S5%!>cMb<X>0{3u1WFyDQ* z3imxH@r-A-6`a#qW<T!Jk*3?nu&8L?v^ExI`i=iRKKNjh7MuI^jS&>cS+bG&LaMg4 zIAE;tpL>)}KG)h>S+;$Ptrd~N?N<$c<aJVa-q)$(mcG0APY<n^apoCnAwdpe5>@DK zT85tUvOzIfE>1e>x?yaXz=Kfj*ldj-dZV^6n}jiur$2)_w?hxLL)|bi+a>T>(VjCH zSm>AJ9y-*Tp6d2pJ+4@xbRTAW*#@uPZu;ai2>I?XkrmJ>)TqxmXV%B2fKbJoLA!CN zHakrXuV7&FTq{Yufh68$EU)n#RZoRxV8on`2Vq#4H`o-f<Wq}-DQiNVU3<~(d_;qY zRIx<1i@<ujC9V!C#&%F%{7hd&pl$#cSAHTdEFry0F3#+YNpr(817l8jH~{TCpgj16 zcGWj~G4?cMwCJ?DD&|V}(W6wTg#Z#ximm>9#toNr<V>jN0B+Do9$gB<%q4Z}vj9Ge zb&J&zD1MfYIE;b)!ugZ!q3W9Q?xz)=Pg3EJ7^p|M^TX^R?`-Qy3OEQAAPg=bagOAr z6XPRVnJ6+MaeHPGRlrX$6C|KNW6Ee^t9h;gCb^huv*j+-ScF6c2^QUsQ~a6T*>PbW zB<=p3n88OTA}_8_BXV|Fej^u|YqF_ZG7Mu_W+Rt^MOaZ0d~bxaE0oXGa~goh^E0a^ z;jZp-*S0dNO)zV{%&yN&tR}&oiaE3i4J5)`1yDT<JWE<U0t4qD&f2MAZjIm`K*Kdl zQ$a@*@AsMN7HWX=!ofjoBK91(BcQ&7Jv>*4kw&fR@2HW%-_)XGG%-0#w!QmMv+v>$ zS>ek>m@7+S@l~)kATcW#RmV3xR;IL1BlxXM$)VRiacbg;fnw9t1dEJazl*X@*voH6 zR|gY5TXxZ<7vCXMMTmiXiQ91TziTQPB9)X$6_&SR{*cT$5rR<#V>0>fLb$a)!m$co zFmfiY9UkrqPi%+FILHw@@*<hc7u9~(ku3M6B(PgP0Ko2|k}0y{cY+WdTgjm{CyliT z1&?s<gmCN0RF7&?3RY1J0oZEEOCf*@ZwnVt$3E>s`F9xQQH#2;#nfK0w)BY1A3oX2 z*emT~#j}WNSHi2l;$grI+Yu4#5LG6KPcSV}HBP7$l-?(a7l<%6B$!p+h19e9-@1^Q zRO!tA9iE=#5<>iRJCY|t7}v;T;^ki{s}|xBW^wNEyUq|;(5bg&+h97}&b6E<JX*1J zChlkX+u40eWpboQY`ZnS=Pc}2Q$@cP=I$ueb}2s+mlebhBUaNx+_C+APQ{4uI}zB& zqp1~1in?_gGJ-e=*~=aU9E-vt_*Y)|G}I3spZtOx7FpeBH;SkZ{?<d@A+g;Mp?bsJ z6g%V3i4_N#qN=G#vp{6<dvYaTY*v6;s*Ok(z4oW+`nf2S&!iZKFZLQk?3hJ4iy-fU z6#b7Ye=#YAu(GW|D(APVQbj76ff9ssB^N{pivi<ItSUs`!6_JNMuMJ?+vf-dj#k0? zeNRBh9!7z1y>of4>T-L<lCGIxJO}n6O?cKFweD^e+qX<H?j%^y=FYTeb><@mWV6l+ zpd?lGVIO&7UY0cmsvdE6yo?dwOMMa<{@MuRqmA+Ny)xyAtqpJZ8)fwk0_;eW)qBNm z0H}w12{Cj3&;Gl#B<|OLt^Hj|=dJiZ^`}l!p(O)5+mcX}n!YsIcoo)(`OrxIV;E;d z9tOmB=vX^7GI>m~Xjf=zJL*~#Hp#PVF;Ck3ZB<epGH<?ln%~(jNIWG%q%P_H&wx<y z?R3cuA_kDTBIL&x$eyAhs79(JPsE|OM<1297~F30h2xDE6dRF%Wfaym5V|Or6@l3q z5Ot1%R(Gs_2R+qN(B^R%3x2K$*C1?Lzn4AM9PoSLCg-RXmvkV8d>X8Cahjiq_)|j3 zBLMB~#9J;M!g%S_;_F3PzEvoWdwg0LL4K<7;x8}EontqXB9>T$Sg80cK>Tx<$Optu zF(J_yoKaSn-E~UM@93G&m!E;l{*wu*rHT>O5iTWVnl=u*<=mf`-zd-zdF5W?c|-P$ zibse5Z1xa0vXD7;JMVCCEe%A!O80{ZVV}}r>sc_!WKs|b<{^N32zp<w_g)m_AHv+q zRyo;Iee!ogTa+#IB(eUnPd!j|mLdfE7-1?@Fnf`}4hF-05*YOEBc@m-VO4T5?bO-! z%uQsjDENLp;c|QXCE(!pBV6>e$?T$~Bk?4Rgqn6v;00_&wmkS+^Z5wll!!o~RkDwf z$6&BVYOcEon!AaL)W?V~u<wc6&vYEW;4P!5jbxHkTOF(Gz9ZVHGG$sfG*8Qdu?QW3 zOqttorJ=`OH3WqQua7+Q>$zT=gIwSp5Alfm9W36u4(5|FY;zoXk(BkS9Pu+9_VQf* z=Y|K*KGy+px00MpJ<AoL&lLl|13_k9CdtCm6n!?QPeI}MjitT-t7FkDf^bFrB305i zFa3zAe4YrET?M&7MNU)2l1@`P%n2--GQauuXsMOy3~KieugfHkH<`2VJm;7z^aLR0 zE-T-ACi+5x^!5z6tTjz$Xjp~(UFG8v`jTj(iHhJ%BA)ztn78V1o&@!1N38Gd38Q%6 zd>}4V#33*2%G+}Aa%NRBv(xmxPkycYawvfX^VqxuV6u26>K%ai%Q2{i7VL%G$xhF< zH|w4hH-FyW5gC8%o+<_;zP{^ome227{=V3v80>S0hO)}33k>574sub0a)~M?-$FTA zO(bF|(Y&!!>#|+M{=6zwItj`a5VT%<nXbzEwj)d1)15z#?{`LEl_R3<iz3p9RV3to z0G8X1a!HBqomFPK>kit+K&oX9D{wiR#v0Eaa+c7aHXkiMK2T7Nh*!a!-uYp>)Xk(L zwx6BZx0tTia~L{hEMLcY`s?mfuu$#{g|K!W=0Os93t-bF2)j6FM?3mwG3?8oR`iAZ z7r&vOjWI#)l~=1r3NlhX!~#Zz)FTgZk`{&5!g`3?&PXh*+lPTwP2IjXMZ})g$QQdi zOZ;?vn$SU9J2lYcml$oI=uvRNrH=0xByl1%qEUy~@u8nph4Pr6nJ6XX#2MXZjs?XN zJ@=Qs%Y&Ja5M>zDM5?dhe$6nIhar-H0&n&lb0X#Q-B3v&_9NorCL%Geq(EPmNJgBl zD)Zeu01G*B$`yJ<BzxQD=|`Lzy!7es6nOBRnj7>z;7OQ&oF71iwHsd0GtJumz(ika z*;y5Ap}F<WsHp0M|6g<Y|MmKtJ215HH^J2cLQvdIU5xzZtzA_8z{697_$&1#FYer1 zU7YmQ2cra%1M<(F!H*6|ylBu;=tr7IFE^p8M&Sn(4i3dE5<6h&ODNA1#Ja!8{HVr2 z{l`&xZx1&SukA#U<6vA2c4F$8k)pir;*@pJ#E|X7P(^Nf?Aq^-4-@ZAbS$CWnXu-_ zo}AC8ooY_xPoB7VMb>gt9%YC*Y>RJz-VYYXhw@{2l7K%TA20xGo`C@v_{F9Cq6;e} zIWQNJDC~Ue^QaLG6s$^eL2Ca=+t5m~raYuzL4cPRn_h5t3%|K|cpFj;l6VwHpkR7V zV4X)-7p^KoBBiqgrRVzGVnDM3_W}6|iAw$(kLtJMtwTwM<d`bREOqhD;~7E+dD!_` zu+U{`pI9e<OvByMbH3^A6;v<=>dr(y$x+OhInL4}a1Z{Ip~NkOI@rQ%O5@$(2N9pz z(Mt%J3+8=d+>^rCdpljD(XNnGNk{iH9wW_}5H~rrr`m6e`%OZR8<S64Ct(h9@Rg{Q zwRZG}O{kiK3Dh5J{g0><x}m4E@y2%pzr&fBfta6tJ+nO7F?kE4Anc?IfAK!f^?wY0 zp!hQ3vepOWn-b(DLt^F&N>Gqk!zQ`doM0kO;m3)Y(Gc6!G~&aT*$ih*{?gB7hi5`C zd6qWtR^`r>a^=`bWy5jU47`auzIp$LThV)C+@a4JY6NTWJ+*}xMuMK=o^Su%12aUh zW}hA8E5c_Jd<^hND$tYo_C^0vXuawqg)(@k;A;>c=8u7`oZGpIf1_VRv<n_7q3cEt zV=p3L?#%qujC?@wt@?z&?P0|edl_zy-^ZF##RoUQ`r+V7f$q@v<Cp#md6p3^2Gjzl zb2o2RFDQ?diYe;<<lh+>^z-q>AWrc91+WfFJ4&S(8jqwc)!I%6)|bCs!vZ{l4r8Dc zTdR^qFhH5PLvsZ-SqkwRrS5MWi<p30qHNc8uruvkj8{u7f~Ht}D)~#dw_T&FSxom@ z;A=GT_UR9z927gvp+LvIEu?=yO;Xk%Y$S!C0*~?Ddu+&$wK6oCujW{~Iy#M4oc6xd z8S)EU^*8`H0>t&Nl&INgx?iQyUqZ#08qRQtYt7I~-XnTS`^M+el`J{pv3C1WWt&Hn zYT6fp_Uc*~Z^!G>K1b_%2<bZU&+wI_KVx6ryRd!nZ$iUEMyl8U^h2HVYOK|yTRBi# zO_S#p+x_KSYBht0)Qzf(pb%8*ssX&kWw$@)cylVPH3m_*hijL~rnfI`tJ)Pl)tx}0 za#I!PL;L7Z(;?$>zbO<@p#&Z4MQ)qtvz1L0HjcxLXB!9cW;-HKuF-8}l^la9Cak!@ z%P(H<x_68=(R*!arA;pS?`tWuAKI_Qci&k81M)g!3^k!PBSv2ne|!bSQ;^Tz3oslr zxv%0HK^eIw(<cmh&QupQ3GHA>6F`h=;9~SVq|0TW<i>Hl$A6`^7#rtvpZbfG;;k*d zxqo?LY)^536J4|?$+-u2Vl>t4*`reC$M|1uY7Q8UpFHs1jG>yp&5L75&?w}cJ%rKk zse#02jjAulj5P`8)i)w?d3u~$^iCU3U5-jrUohHasd3ZGY>f{=o4K17&ztVAdwtn6 zaYkQ4L(9ynWl!G{BRh7xe+z6Ms|((+&#LoA@iZz;S~8<6n7Gc|y1O6u0vj+OL+M)& z(n;6jT(yb_?j+>w0a0@}g<~mQK^eQ#O;+}W*4twM0Bil^K=yl;ytg<IaHzm@@7v36 z%6TLAd2$~$%?>?0AA++@=d0lV_8B0_IfmuX;t;BjO`hF4`_tR3A6B<(-eI)tFYh_W z2V?%ax}2`J!u|b7=OvD5X)f~W<0OG@%!)X%kZ+Z1oPMHKk~iCjVeSxOUuWNb3J9_d zMgW@RjtBjyntqDJ4RQV3G(W!y5sdkHpb$#Z)hMs3OaO`-?K^pE^=rr{tvl^PDd)wv zI`DA#4)1FF$gw8pxid~x%23sYduLvp{P$zMjjh8&{ADRnKW)ENuRRuU%w07r<X+7= z3s4;DZ`)|gs=B$qpFSIIuUd3Q!A7os{_F(*V0khRQ)VWvmg~xPvv0faOZPfGWj0&M zaqk*1TP;-vt1OhVUr?YK#@rLJCu_NK_|kO4HA&#i4SActfq7Iw5XZ5qgpI1zJ@QVA zC+1c9Y9pBHetK$GD<neeJUPmVA&FYQjyzEMS~lggny9128qlthE56&N+!^Em=FH_S zEIr}cS=W3F$mgz^u3$W^tR37F@~tg`<wj8DHk(}!|3u`evG=BFsplzvc`OW*o(!<P zFMV(OFf`}TFVoAD-YW`bvw67y%{ujyN`~4uKrF%AT3RYZe;?gm%IX)Y^;}JU(66B* zCK!hJw<_aXl3C0XI#n-Us`tXnSuB4LP43GN8t|7ac5%eYCI!ljOMA12u<VtmsqFO9 zkj^R6sYbmabWkSXr@K(oCsIu0VL;#+f>toDsNXs4ldTCsWyq<<j%!mTcG+|AxJ_dz z_i%EATv{@8#NB<j30fT|FR!B7u#Za~3c`&$sa!L2%kY#ruAHL0`_fwz3-ed{huj~l zT!fP0np+(Vjs8+cq^W#aOiuK^d6e>b2;$mfmW1OP2s;*tROAO)5riQx-oCw+OWmdx z2I#YG?lbZ<sBLzw7B71>ajIzaur{SkK~HC(csxk&R9{E7<KBWY-j<WWwX&Rb_kqD@ zuB)JatuTXnv%}4wY%#;k9k4(401)`GobcIOnbgtZmh2olsTFQ_E-a@YkfWR}N>zYY zKQX!e-SQu&^xd`{JZ;B}lv9Ss0-bO+=8QaLzk5#=+AthtKe}Xw$*8g)c-MrXp;`uq zpllSaQ#=xcepnN6a7x6H+u7-$kU>0005^l8>kutmu+EeNu8CtEG%9X$8>1HsYqDkB z7T0|m+Lrs${kp~B%(pRL89YqSz6UMHb+KZc;_n8KTWi$+x6Zeku9a<{qo(g(@!+l` z_e25651OQ)y<NfU=I>blo;`Q{+8;^{Hb(@Or+ik(tdjtE-ZqMXK{<9ZQulvZYdXew z*lD`w+#n3r?gEkFYWN`3F`!O`7>}gW@cS|(cwuVie8u96l}~LtD2~LzE@0^rSBvB` z8mid)3t8xsI;5E0UyF*oI447^xwrme(oe+G{a%-c9&=CdNW4Hzz?UhYv>rj#+tYN% z>XF4pR?zdN&-=TY=#pAs|4IIEp!TGoynWo?_}1C7b22a=M5O-Bt5TPh<R5DOtx~ug z*{3o%h$kDTANp;Pfn|tN)sgY})&IMNO<RaomQd(SF|&&-m)(v@twbI;c<S~I6fW0+ zGXUL9VIlo?e5HnWwGn5%4QN<>o{MuZfWLu0)$SlS6bHRPpi7v8<Zb3Q)1I|0OO#}H zfQ$A!X4T;Vi?=Vjbll-_^>w#8?q=niyBDdLp4A7qorO1I-uR!XON(94cARo)FJeX- zOPpVq3g2bE@A->YC*A8@FrQm217r9BZ?rd8oe=h%(;nLNM#t>uE@sYFQ(Hs3&YYog za^g4@VD&gMrRMrY@NfOIyqY-Ihml|M_gy@F5tVU8Gb4*wjiT>_A6H!wO=Jc}@_#6s z%@SPo$nUNLw~7vZbKPaq$P)MaL6_>J!LNDRGXYGK()I|mu)mf3DAA+W!Nznf!UIb2 zfBI4T^wF_sgtQK;Ny`SR0@FCEdcDXhHbEyLw%A(>Nqu?5uCx0SFRp3dCpdtz++-O- zsx}p6)d8kV#rb`&KKD#R$lqdk<r4X7Zr#(BUf51c59@1}il1y2Pfr}!G{QQZf|8Nd znYu_Jrj}%_EQh^!kI2BH8b%KMDZ@oKaLO4th8%t}l8(P_QhY7O5u>_p*j;^@U<uwe zM2ZHG$~=YPIVVlxB%*)yt(i}ST=5cHWeY&i1x_~Mi`b415MVDnnyvd~v@rI9T8M~f zli)O+8yIAtgp%m?$n0hB<q7KJUu#X!x2yYKS89WpccS%brb=Wwk@r0c0_E-wLV$FK zyN|vKr0yzSG2vura;gVQ*N<mfYeHMhIBuF8jj@~)d*M<(Fgug|d6Rg63ki^w%k~gX z@6srmyO)dXL)3EVR1SHKO=~PQl~)}PM(w9zpjsG{&0@ZQrA$iI2~1UX1#8U}@8S1! zlLy1ccUY-lbrRU)D~lum?PjLlu{T<mmjG!)047^Yl!_Run{#KwYg(1WJ0ECe2}fJ$ zbx1=bdv9YE1;~yOr#*-;?>(C7mx|Mg&caW1E^d|VfiRy`(Rl4NfT_oGZ59S<OSW(k z+<h;+4KSRC!@Ja;cWxt}lpFEhvm<%xyHeDVH}0?W)oj^w(gq~uq3u+;v^Rb91GUJg zDX6hGOV>W#V#I*`r%%|~(5z3%@@DY((D3MC$mf0KeWj~MGyiS2MDJ9mupxUjrS~TH zt5A(}Ra4KYrYf6&mFJ2nTr0g&(}@AA2@=T*%v7eP&M0g3cW@8X9k{v1Jtl9x8+&JQ zJ@vua`UliI_b~zxw7O7}42{VeS*wIoMjowo@<t>sPTq0F8!Vc1t>X%W5jMj|GedX} zD?+*q?MHk%kRHsm5tT<JB-<>J%yCVQCBLSyv9{1v=te_Jf0NPjl^ZbQ*pV)K%Vf+H zpud$F*0*do<oz*hX)-tr0vG^uCm*XzgLZY7R*c_=okeMOb3YEEKFL4wipN~BQuU7P zvHDH%6Ap%;dJ8dmeI3aChP{G$hu<H}ZtfDdE*v>5R^s!eb%{4*e^-lFWgT}44B2?B z@m|aM<<LK_4zGY5cU7A#DrgT%ofp_VpUiw%i-hrA=F1c-hDKk`=sn1+5R-lE1L2vn z*b(bCW6EfYDTCS#_Nzb5FOQ-wYjIwW7`%-@H`S?J{#;f|+F6New8ie`QNykNoE3BW zGlTIyKg~YRL;XXU8RZx=3w^OBBOYn+x2jbznfTJg7?1%EWgnOyt7zL4i|}X)HxU0{ z*7oCEzS{WR$ITIyMO%+^`>b_5+P?ejI+Ri{MPjWpB>$<JC^AuhIWvI`RS!Q^as7Oc z8Hp324?m(mUfhTrJx<KB6236uta!r?P}2_YU~#&;HNTX;mZ4hB6`62%+^NuiTe$G? z+Jjx(4vu<>>;7tq-0z;5ZFzj*=ESecr+*Y47kbM#4id9y-E0cvF1e{yU=}*~K<SUs zk#*$m_qxiUwyr_v6)<_UgX<?Y!Jko}4BDwMv{|y*3T8REGP{P(XCLY29ye3RrOkwX zsq^tuE!q)n<_!D{9u;vLEH@oSr`aowZbi%*o6XW}eOc*^NsXFvYv8KQrmVfpcA8Zw zXWtyifXk7T&o202$dn(icHYTv6X0k06-#mmx4K-Jjwg<p-NHjow<T{(XYDOz%N}PN zz(j`L?18?l0V>;QPVA<EI9IhK`j0L-QglDCGtn&zc>(7vF-kGG)r8AAW@f+>k%dl@ zQmrn^yqQZ^v>(tXi<VGFn;`pZAq+t5qs|kz(_`%Kw+2()Us>JUluNVmex~XI^~7?l zkvBcPVT{rNTUV&A2;2mk)o8WUNE~qU_gTc`mWwQZYk56h$b8gig!e!_{XHcZdK%K9 z8qvcIazH`M*fYMZ_uA#*%IpiDS>J`M##WHJNGu^V^A%3dTv9^HY&-v?RsK^7+4AG` z$ksHW#=Lk0^mgyAI>tn9-}C9@iK1lY^T1509^^T3H!N)K-hSo57SC&?#Aky!ZjJ2y z^0$jh4LDyh_Q`Jf1!#~{`dYip7x(?jC$8I2$3682ib8$x&hsw=F-6omD><HU&a?<H zvmLPVLoHM(dN;mMO|xLv8l~3x`!=e8)kq|G6x(p=k<v(hee~lj)%<KqKK#3J5%NWQ zJ@Rq?-cFayE=38XX9Eto3&%Zb<C1w1#x#;w4w*W7pKvT}#pjB7tLdf#A%`%*wb<{J zW+`G@CA$?pEKf7T*xAFpmkzE#pf)4Ncx&uI?Qux8x~0r^sv#2k?6}dJ<33)|-lCiV zuRFW3I*apL6kEq)=3T;UPhF3xn@jKmgf?4O1TsiAyN_in0d`h?O?xy`m6BO1TVkpn zuH&9}##3Ae>`_TQ$amj8^6;aJrJxC__ObGu^Cu=YLS?cxtKp>%yrqESHMc(32dj#C zfW{8#Eu!#)o~9(I-}tzY1ieB{w-ESsR_0iFb3*K41c~vLQ)3_<;h_)BMThVG+mWis zhje#yzkc(J4|)1BuIKg!vaNclvTNyk7hmGX3()!!|Mu-G_zHvlyxz}s;YWAKxT#k> z)flP}Elu5H$5Fst52@dzp=61Ude^)<i8solqO;oq{YEekxbjFdc-r&Ivu^JC*el+e zU@>`SfmWcc9+p{c^Lu86SIQ>Xps%*ik0)quj^z>S#}haVRsUj=1>Z)*&OpvT&6zYq za!lqxs??_m6sN--Q!h&AqtcB+)K)7NTdKbH`#QWmIvQ9U=x_g|F4Sq{whx3XVwr9Y zy1BC{TP4Q(t)T>QO=OqOlDysOf!2G|r#}1Mbjj3?4(JShBW$z-8sGTF7SMahYqy`@ zI-C;_ka@A^Xi@S^aQgcN)3?4KCW6aMJw_lNH2uFqif@_E=y{}6#Xq^;1RBlVo0?`t zT|YSS4_nbJE_S$66$&|s|2osx%gH<)u#Gx0X_<PV@wn0ARgVMLrss9<h5Nmq&kd~L zH=BiieK%j!PY{94G_gD?MBkMyw*|(-J5405lAS>c{M6-p%fPDd#LFN^3)g8wD>q%@ zNp(JNYfUH+Wt6q;iFC;lF|E^@3%SiDx$i|6W#-TM|9Y93G50<xJ$zEP&{QTZ>a8c; zAf4w5z20*DG=2>6<E4JF#U5I!mi<z71LZs3e@;o_bpWc<>(f*1!LSn{6N0+t5AwId zNbvH-83s?!#3Ow0gOWGcZ9Te3v-2(qylahh*97-K^Nqr6kRtJg(tpd}-N?lzFGzjn z>k}mkNSg&z0s5I_@h7A$;Ug$%TgH(vUENybxd};Y)%<$G=-@+7kJ95WNYJ`jwk5{! z+OPXC{ex-w>y{B53uB1H_3`i7PFZuF(+_h}TM78r^Vhnbih-OZ15o&!#XRMvmWmkz zO^9)$zp?03J~-6CJ0jtG>w_)blT9EZGj&gdYwU~1y;&k;n)J1?y^qek$qzwI?kENn zmlvCNUM3%1lxdio$qp_L1|RvluRny(*xV|FIM=f)UA)43-$fdxJy%*~D81fq4mGjI z&fSTtDnu>5?Khia?-#KYz2EBF#s{o!?wg#SUz(Rm@~Tqv9gJD+?ch4&<kyMy>u5E{ z0G6@q&h-SccZ3*e4pB(n2H$V8_rjS=4j9}01*;=B^aS9+x4i>_CvTlU3B*b0XuN<` z;)?hIJl7WsvZr`!u9AMiysbAp%;wX8uhB^bzY87+nQT)!`l+M-<RS`Vu50?4?Fj%| zi(gxPprG+%b;fDv>8J^eA3+joEMk#O-UaH~wPJt1T51Vt<?6O3Iz9L{tL8fpf|?(@ zy^j8VAO_N}<f^nQs~yAEXk;09*HihayvJ3YU6192Ea?%kw$M8Tmpb>iaxc%+Zx#Q$ zcEy}$a%&WxTRfDrQv|U+o2`B^*fysb3Y>_MKKIIG$oK)F2W@XAn(RhxIqV5ZxJ7W@ zpXAh2YPmUcfWMt*@l$Wtq0c^L>$)<jx|o*{Z9X@Zk{mKR0=pu^ZMJ&fCGPua<(ic2 zs?D~@9=^vk&N@)(6`s0xtA`K=x(A%)p|dH0V4{f;LM>ZW81ayJW|wd1+WsF;9Dd|t zBD3a7#%z@(zg0(Go6u~?sh0lVKcX|xbDu<JKfC*V&gCw(kvV_&|Ma=h_}3-vb}76y z2%}?^SnTRXPiB)vAYIovYMak}XtK>KpQEgfD;H*alm2sB`6l@F4eDFv(E6#3blOOi zdM|mJL8<H#fJhGGx=c`9ymgmK==b7O0||pfEeXSrzfb(Ku~7k8OA)_{abt}sStRf} zjH?8|ag^<dP0|2I3{~vi2wH})C6$SufmERof+QwvtbJA);VawaQzE~pIvSu}C{z|` zU%qMzgy8C$T%~~hr`G{T`1qmH1DF2(-4RE9_8xCq!!)x`k*XR^YTaQ_rna!z_Xb+k zdTjzjjyZ#yIZnL(<oaprHbt#>RSG8XH(<W_JH3FrJ4D<QU2p%D1ESzk2anH5tPF8q ztcf}roMrVPque~o+wl@TAXf(D%6Tl%0y^VH6V$Ta>ogy^`8Ji!$*1fXx|%-Ljc%yB zp!GoQA(=QeyVR4GoqR5R6$(4k!h!_lNNc*d`$cq+Y_lO!&i{V;pZV72%A-r3TFIpC z@zj%`7X2awQ_J*AXz!KGO|6B>3wL|1%AG~DQ`uh-inS(2BA+d_(rJg&$%IFku=Yt$ z--B;TJT9P~(T}C0cAThwkjc}o0T({P=Hxg{-laiNbu4c=fHs_t)oI7d%7&!qW5Ue8 zAek}-GGuFUGtAJ#$cFmi@+fzE5FqV*mo`M`qAw4f@Rpl_?z;a!cqI-Z8}5o7#p10o zfM$v46x{UPq&Q_r*4+x42M7?*Ak5V>tG|9}RI$W<Uzgix%?mgObkh-v&?lc~Gj=bR z6gVHkhK%iQC=H%YHC2ls+7~M$1-=}hJq_*AUTx=Lu4o@+7jog-TJ5rMJ7|S=sdcB| zDE(K|aF(EaA5<bHV$w!BbW5|0KJsZ~0PpJ@1Sh&G?~noJ8FYEz$X(`Of%mJ17qr{@ zlW$4_ar+t=)|%3sJHQqu|CG_z*>^P6)n6Fk{HL=bsIvb)O(9G^WmBkM{^%-~2PPqE zFRDT^Qj|`67hm7~q&h?EqKW;r>)~mCn;K!uiAy)?0+6)b7f7t3ZjC#)MGAQrZ@sd+ zwKBHZc2DVtPO#}!a=M(KpdHqkcleCYWtZc_52ZaKNU(gr!r}#5^XV6L1&3l^=%Ohz z=@qf7;P#`pg;=|nVK(hfn1oQG;U3^Ih-oF2yqm+m$G*5Jgrj`6cLYBWI|OShPrhsN zI>%hkJ@=jBOuFCc)x0r(lWX09&ZqjWH+c}->ZfV7M;rO?W%Rz`$*1miu(7^tLC+LA zXI1kj;@q5ZHT}4muA3RCXt?Z<^qyf^-)`odwBw$S-=@8e>cV$XymREDZV*%-68z15 z_`8lQZ3?l6iv3*|Vos_zgeTm(fq8Y}9R5nu7P>He3D`6jEpaXzZob|@!+>y@{m|-4 zg&n(~k!On<WYUkGAWeVzKcQ!{xc||SmF6;Gl$p_=F*L_jdg@sVr?2Y}V+AaHkLOYE z%Z-Rj71XZek@ucp4ovm|stp%d8T&gIXo=qCd!Q_skLxz_XQyq&Ld=I~7d{wkNP}uo zSx)bNyOaW$29>*#WE<~-a(m?mv^OZ=*Xv^p2}Hgnp*<%yMa4dB5G$fQPD*zt)vg-U zl(+00K+UoMKB8GNww+zC6Oz346|TAyd5lB)?>?%G@ZC>I!@pRx!=>>BOjU27lpIP@ zfl9a2CAC>fVE|_Tdw-XV;5DK6P+S_@B(fM5RCA*J+mIT+3hC+%-qqIFt1DNRbxfkR zTwroVTJ*1Z=r^w1vgSmj``1GPW&6OXF1T5pvc%~sg#gl4vBSXx^7p1IO8)^_rFdLk zy-Ja}OG3wOAW+IzB*fe%A-W7PWSr+ywQU`r{Cjv#0jcRVZO9e=21OS)TlJDY^DQj{ zJn8#<@M>hAh%M)LgVYNZ6d?1R{EdT92VEIrsY{$at-4t!Psx|%TX9ID3DVi|3gFlG zJ<Mv3`Ln-TuDdlJT~>#B>pSLg7f6U2&IoBGMW$6*mV^+lNa>q~Sag_moxN!77475n zQN1a{vVA$!$plhA1F2#1LN3F*U(?YBe4%rCGMpYDUk>b?20IvXjEmG+XwP+6yrJDt z1hH{=-?S>W?od8>S4py3d{HaUiOP~Hr#h#~ysKA;KT<x`y>D&vL^dR-A@QKj_05f@ zORzGgoW|4+ZJOHHdrx=ZDzMFrQgkyI1Lx2szIvJ5wMIwxiSPd~<!L#q?RClip|f!a zgSL=yTdi>Pz#(^oUmH-g7i~bSo9We-uc=Cz&pN8ui&>Tn2{N!4k*x#R4|?h1RSuUi z3vojOO7E+oqpzawFR|rRXV3Rlw)EML)t~xqi!vgmhOrIQmod-=F|2MmCc(p4tL|j8 z%SVQLU@BhI8e*pF0EwyqjKPBIeHZkzL20lX4&Mr3KBa9>L=(<UpnmB5Yq9NL#BsIb z>P7{6XWSwRKDh6*;Ggq+_^mySyaAvNRat$EV3d5fKTIw+94W!#R8sG@CnNQ(WCv)J z4wCpzT_H`ntxA@?tx!zr3c)?wfj>Q?fjSYk?WychcYsQUS#nc38M~%aHM>;n_uD60 zY+!NHoGHY7$yL7(3#k@?y-E(um0-%cTapH`7hpCaRuFp5bcs{&HafUA-5~L?R3dXQ ze%kzCZ$o>3;^q$Ru|*#*#~F2*{bW+@c#u_|CK*O!AbVWX4Pxx8rbokSBz*Y{*z<{3 zmR#8xewg+LrsT*}woIVQ9D7Te>?9T}MXloKq?|a4QaUp4SgxlV3x}8@A#xjh#801O ziv~rMI6#ZURWQj&(^|UmL>^v6HNNh?$?&~`vKnyU<4Bs0qF$0_@tOo#d$q^I!6?H* z_4u}>gBS8l&VHQ)+n%>y&sL=*D3#oK%xVcM1>=%8p?hPx7EYoJGE@98_o>d0kE?$z zWu?uYJfJRS#yu0VU=c1$&wN0)h`Ay)b?;MX4w9(JDB5VPf4Ta?$-9uci^l{R0wk#j znQ81x>8p0Tp+f+-;2*-?m2^neL9uzQ>o*|GOwkz<@u|tG%I<usOo&gx{14gLO`M;! z>b+B@zr<WVf7lXPG(&~+`8V%u=v^1BN=^T2%ej-j&>{3@AaCPu(=z7w@vGjysiTY6 ze~djT4}_ZxP6y4vM?!>1b0!NT_6&9;df3iy&g{-lb2*L$vF=sI0HK@@RtN#@OW2P2 zLp%3czQ<?_8Pu4XSmO!<tc3=IFuwt8{-spR{UI3Lg06XWMGFd$1)v?3Pc3kD8Pt5m z_xVR+rP@r6<k07d1=m85;#S(f_Xu1rvf(dXQSj=cw>;f&MnNDvQ>OGJZvK4_$<8%f z>53msR=THyu3(>q*#M+M=wB;^pRNS@FFmxkSo~LJw{O{eU?shLKd7jciH-m{RaR&# zT37VQ|A@IZm*#mK%fXv~LM{N}rBc8uyc*^EThgNxX@{kPl&FD}Rpu)!>s5}Of#T4A zl2CE}+<%g<>X$SBOSCq;0F@_Kfr%>*dmz9POR-80Fd;?JMk{|I>D!g884#`3^;KZD z-?aXs_^ge5q6Bh)^nt)ZXM0S{KhjLMmN3rt{go!Q4w8=%5}jFJ_1!IhRY|=qSJ+IG zYaiM~NeBN$XQ@`>8p_Iz^3jHcL;+ozLl5nir+53%EtCzz$n%*q&nqSEzthADrRe<e zlNf7a<Rmo*MaUKk&RV;$hANoWOV}aB9UdP6`X7Ze<boi})mRRDQ|cBBuMXQW{gnRF zd4C_Sk`(=BU=7qUR9nV7E$g>ye)b!aYH1^%HY%sII4OVAq%3*T$t=uH2G$uQHK!~a z2MP(S!cEcN%GR|t(&<lp9UDSqoQ3$cD)BzSt|%dKyUs_}`B-S+KbK`V=*WL)7BzM! z$kMTyvG#PSQks<OByIz4*EkW!$rO*Fp;s4aBjlF=E#iNfl|w4P>arqF#%?n!6SPE= z2(;4#{J_jJoCV9-H(5Pwa|KRBAPes~Zl&wOVA<xTRLa(+Dhfb~bs+yB5BH|$3=v&M zL|5cYi~Zi^XCI<%x$3uS6F{-<)t3mNI)3yKCP}jHv<Sp#M~fm^81C@*j;ZhOxflsn z)F-C63@Em^j`-4Erfz-)%L#ElW_UkL8ku+HbQT>$NQgaTAHN&FQwwb<d|v4!m-{*l ziI9#D#V-k9kI8nc%tg*4bEP4RAIsa@9d95KRo5>J*^+3WIkgn{v;Bz>Mim>+0pXoN zKlyOFeGT1p*lCOYsEN};5M!uA<KNH~MIdMp&Tc6iGnM8qDhNAc9ez&M81zrPVhJ|= zt*ooFLJS?J3W`JvF-u|CRRG<x#)H$bG9XJIA=j5h<UV&!7k<`va&>&oka;t!3jJvq zeu4x&oLha8iATrKq~bDhjmPMXhhD7uqgO!~(IPEn@(#r=xqK*j{aXED-?KRA&=n52 z<+|UnMtQDpz*{w7j-@DIqAi34FU!z2EBI8~Q16x9ez|U_YpW#aXlR9kMA{CD)qW0E z^IImtrO_d-;T?IAwGAHroEGNTxq9r|!|Ey|{70C~(%Lt=ZKpRpu=6N`Ry#}LB%rPD zu`cJ~tf_Q5woU+75blxXoNhaWEp))nfs|g-7iFwne$kRwW)fRw?Xu@+h2i@XI6%1; zea5TY_QQ$y5c=F8jSE0Sbdc7pN_8yl6(Q~|Z}%!)ey0NLKdnF@%6O9Fyb)Z>Lx!Kr z;0)`WBVC~n%kdQc`P|C79~SVy_KAl6xayA^jbIJe{B`=)T0-n)+}VHJwK>IAhfY#K z_-rY01<<azyahbx1)h}!7W}mVVIChN2$s#z&{Jy@i<Q<T#i3&S&}8aWI_*aH>_*n) zAdLb*w>JQwTY#srDx)SSif&iMD14~9QXol|^p7lN_+Dz6dJoG*A>!y{bV3od#vOfZ z?&0QXsPAW;2TIpIr?oz~UG^Dh$#Ee0UZHm?SO@-kN5j9XRGhS{*Om@Yu@5=U&=mIb z0ncFUgT>v9Y!D&a0gd5EA#b=WP81KI=s<waLN$Fe$XAbZ^kVr$Sgg@6_5lkFK%t4t z(4mzscoP&cP$+Wuy!6SnR$^5|x)yhjPgTMk<GkE0^ZZ$ZU7B*^v#U`5Y=t)9TJ_)e z>a8buaTO1Kd^o9ReH9$;D)(`Hs*F*${!_;Kl)DmO!BUWgvdNtI4O_7k0R7kY)%IyO zx*$k0@!g6XXN*y9-`z4mfG($L(Hr0F|NYcHB!i9@oR4bThGU+fp{A=b;voX4CJS$o zCsKAeDbx+CqbqH(<nV`r+n@LL@LLp*jL?rfXS8OL>T1Q7dzR%k<)F8A%5Qs1WCgJd zBqj82Tpt+K*;oFYY<*{5*FMMp6x#YH)|yf^*#B~P-#OH8{I2R>G%-GawwGaWys$Gg z6rL`{^-3N-^cu~%r%=hbdt6Bl>igx|vf9wWrpY(u(Cz>B$nDPVnX<B+v3fUUb>J~W zQXl|JKp`?9;?C<!hQ$QaWGsT?Q*Q*x{UdSq<=MCwZP4MH^$c}mMf+`z>>JH7#BPiq z3o1JTawe{!&O@_lS3awzGwP1sc38=!<Y-B$-6^si&}*4f<Gcz!DYHs1kr<*p{qmbI zT?$Nl+>gNozN7VND!_$1pDUK!Li5z`xSdHnHDrFjrC#?XjnhHjxNJ8P^LjE=F8u4t z%ph$80?a`6{Tw_;1AxE}V%&5jQWKH@B1T*bvsMlXK=WOLVUM_e1lyZ`%Xil?rsep1 z;I@dHL$p$%KXCFG9_m}hLY{?6$z<XZaLOkW9<k&<m(4Q-a$gxYU6n>J#ar{W)ozhE zMPJhCoY#!L2`ok^o;`P~+vSe}2wf<^?-?Q#ST6}TO12%lmN1-UXiZGKHP{<!9BtsX zOTtpZ`oK2`U7%0zW<I(2NsJ2sT#VTqLncng-OIDHkPa;oPNw1%n>aU@y1+q8Zf_hL zem}fdgFJfR#5<P+nzUzw+-~|eA#ny4XrE~3H=UTRO^8jTd*Yj?rsi1ICD2{f<e}Dc zdDz!9F|IeNohJE>rgTxj9u=os*txJXl*UeWE@aYUfT4~zc7>5{*Ln?Mo8p=*sSp8n zO#tRHk&gw8N2vng!291vRPS4dd_sCp^WFaED7T?iJJR;=ma+pEE+0Xfj+ECZqAP-~ zv2dJZ^0Q!`H8p{wDIW86VY46f1CpLZ+_v1%Wj+0IHD`XK^`~5ibo`{tJzAv&0=r6c zi9GWs_tE&lPjo)>e|S#jg`q=xpjp+%ECm0a;D@OdGlpFl`(|hAf_FW}NmE_o6IiYi zb=s)6CpCr_u7cvbLLSvq2Zv6l>+Jzvj?~{@Jstk#z=zZRRkqXG4e<qtZ&CXyPZ&mO zQXDIjhP15<61*6tCyxv}{aKA_>(oR)rlBdn^iQ5iT1|5Jn?!$k(q0t9I%X>THt1Hn z!KVNcq7EdJCXNLC_zwgKXwnv=yP$h_`fg>jb;^JB=1lN|F^A+aHk;pr_uyuxOvCJE zG-)@s&O*;&c|Lo@Y&W5Yl8`M)+uB1`gvfz_oFHrwriDf?)YDzef7Os=A2;bhF}->F zy~JbM;n#GEA2WZq-o>O2Mj>#2^Cvw5h^*ig9q(_2I9jd_?s$gEJz1DF3R0vm5h2`# zKmR{T4iV`f;|IEK38Jim(#16zpVUotf7;D$&8FF&e4^?!MRyES3V_1Thbl>+;6bH- z`tNKp`dn*{#@P#~-=gT@)}$t)#!I=`K$W3ff#wgh;^uVd^+Sj}`JwzHbV3zKPUM1C z_)F`q-U&=LN?BJZDEwXgRw={rIryo>>r-I{^x@$l8cE>#kJ)IJo#kIP9eL{Mr_YU6 zbdEggDSGF2$3m_F$nBRF$V~t#1CkRYiFX50ZGh+|Qyh9vB>(s6_TMLOEv8>vJozdh z{w3fwg}Z3BFr^(0yQV)Q`OYAJ|Do;yibQth$CJmuImn<czdYa6EEn~%{qlnQPiK&O z{yuu;?!yhYbdxyOZ%Vx?Lox6vglv%9Dl;DfEWgeXUZ%@03`qD1_71-OCnvO|^R~3g zkiiv=?Qc>sikz;Cf4gu)BPDm&E@v2y?8AD3^rb=KOSBFtR(<V-C+MLRm?APl*!Q0> z@b+2xMi%i~@V`mU-80g%TNiPKb<#1Q?hB@qH)-~cEZkC9Q9SEDk$1<+|ISkrI<$7K zV83P#CpQr)yWQ=3`8PEkk(c0=rOWEJkLS!+j`u4>9#*pcrDR=u1+}D-vb+ZY%m^e5 zEoj+7_Vr;201>SK-DCt=Wk`{2JsX3R)45V|#sW>ZYH;pudOF@TKg6Lx!>z${2m3ja z@(aCUK2j5e-DTvgkO`(CvK2jQm~$Wi%%_GA378<}!K>cKMkL(k(xPOv4pmP58iX;4 zx|V4G6<j6Z(-1nw$#l0tE0`v%AR~ouAD5*^%@{gENG``7TmqHqpKAZtN*IDJaC3&& z$P7y<Udo(%SiQQ(PbJuLOT(E+@iB4i$9-<L(g4a85)<TBaC}Ew;#vD045BhUVYShH zJJh*I!5{%x1L-fzu#y9)erwdU1i(<S(;n10M8~OVaAQOrp-KP#Bg~LKaMfbu!k=}; z6fnu2zu=tE?m89XxQonaLBl|)!fd5OOH^>GV&cw=?|_0?)E<@QO?LJkP4kFGcDe}E zYB1IqonuhQS8k;a$bjLxb87>7nNTM;8-lC{miZ{a&w2PEIyhTGKPpDTE^lbb(SX|r zNCK30*Z1053XVA{&;4|oxGGBdE_JeJUbLn!0fOZ!r8s+gr?hN&`+jk`U`^9CxqS3Q zhBL5amZ52egk+J%KGnkUb8UC`|Js;-dH`gDYDiCYjmVrS^j7BCT;m3Bi>dGd8Wc<P z7MPfSSqjQvdGYbUD0-@frZQ7n)3QgkV7*EU{Gwf4E2@#qrE<IhxMKQTO$*UYfif%` z`WNXfxBCTlrto46(vVC5pD@e}#77#XxgXD2P%mBD;c`}GCm1h;6-4yC0tD_R0IqqZ zT3XK}Hrt!v7^}{mH578*qxV+d{$N>ZPnMwYM-Bo?A_EZ{d(eA1?ScF^(r&Q}?v6ll z@&HP+$~%##l`aBjDu%V=C6Tdd!dx)ORV7DjXj7%QO-W}k+bDSjjK&O_)WC@Wjr0sf zPt3q|-7^A=Zb7=FvGPNO=-(ZC;_y~c`neYx*VFs#jkoJ4efLv+GG=$(xWO;i{9~x5 z7L{L@DOJ<joBk>mnUfwTpjRzB-VP+a9!X&}7!k_Ro9WG`BG?&VcvE181y~T6PQL8- zWmGEnXti}$+Q5qDRb=f~>WC;fL$Ns-1U?$ncU)rWi(uw*&R}0nmPXtM9Aa9U38c#Y z)k#I@bk8v;;EA~pReNJn+<v7iMF(^otB8GU+ju?Jem%eYqUL!%|1Q`8XwY=8{+FCO z;G5A2BmIvZ7~Ob*TNU!cnEUF75OJ4WE<`6NmIq1j7eW=Z+s92=1qZF%<MyO=JCJvq z_*LTb``Gpv)tuUwJDnPI$@~!4u|Uv&>a)5t+l7*1fav9}It;9m#YOurp(w*N7*RqM zM&Un^&=c*(mD0@i2!#LU^P#vrHHpag40(J)4SS<e_28+MoGK)9-Q`5ok?7IqN?#~x ze)KE=<6?D{0MD>yrR*LpULXzV0$dT<F7Wt^RcY+qWnJQN8k>IRxB^=wsSN8T1Dk>3 zK(-Jn9rpx;9TBkc2gy=}T<E?UOb&M_Rla*wP5&%iS%Gfs>WGhWUbETb$SU+<Dn2oR zWO;|M^p9y;agsaJ4QJ~0Olrjr*QFPJ$V<x<d;iA%s*G$?HLvtxol>)9uuX2r<><wE z2Zz#jOCV<aLJ9jH`wfk@jJok{leMvY1}*`!7sM1x4iw5H|JVo24OAi=go&GkybJyB zA!sNQu7nh#7<*MPqtjN}WezNKVbw~eUFYi0(atiAgFBO9buS}r)1NHS`jx$#rwR*m zun`X~R3y~T!t|G>&MgKh+vk)`1t&b*TVy)&qkZ-<CEeQaAC=u&1owfwz^q`Y>IO&3 zbv`M?!(=OZB<?<^O>Pqo)SGjQ2YzASxY9{U$p<B+O9fEd5J<);<Q0Xz?H4Uq;{jJ1 zO}yNzr|q!nUeo6DXmEXO)5l<$E*-7UV)rRa62R5|)Gd61?7T~8U7z7buI++ikzQ}9 zzX_4UM~xQ+VqL|zB}e}#e5uoP7)|K;Ot-QW&$}&4@b?`U+~%s>JgdbCzo;XmHJ$_6 zT83PeWK~&8<zLyb{&EoK032n>`z;$=%W=xDSy`f(&zzmE{~tr={ZI85$MMfy+>6V- z*T{D7b?p&luUva?vO|(tW{K3j<~6%yk8D}lgp`qNvXT**rIL{PqU7sOIG@iC=lwYE z=j-{}_-RkghUL27!1-K+kzBQvGT<VY1(GBL-&KnZco=UH(ogk_`6C<SjKm1jEfw(R zF?Q6Udet_B1hD%;Kw^#5(gtDn-ms2(@}`Ew&{!O7K#dGsHzYIOo6)*OZv#-?;b0pQ zciCx49~rY=^O%SUd!||WzsZO|cGwCtX}p>WMg!t((~l~ZS+hmwE+tySYk)o4v@u(P z?5~vsE(;w>!>9ZF<coi0xFq9}vQ?RwCC;)G4g@xY2Nl7YL*%mx!D<Uva)OFpH)9Ft z!(6;eT8q@i$X66JG<)1{rRX&rR%fEo--O-I)#Aduy5KX=6@mAd10qmn3uIH#e<f5y z;Y~`Bguub6o*9qD$GGLJmZigbO%txv;LI;QK+je1MKcpovtsCl_K7Ia<i+|l#pfvf zAg#%-9(Hd}B42+2IllKamYKFn=iJgjv>v@5KGw4%Z>_UN_HU&9ogYM*2kWyhQ=P;% zlL5WJ_IaDiMHX+vU`_9G;sJPro!0n^%uI!9^3dJ7C1`2N=PXczH+d>|<rm}b6<#-= z|AH^2)amo34t}OixvWiqvu@EuoUu4%vc&7r+U;L3$9zw>QhtviAO3A0|NfUZLm?|u zuVUj(vrNa#%nx76E4mA>>)0m9HM~KZ!oIh2-rkS;brhqCy@Og%`7-qF#zil}fw)E- zsFXH-fAeIAif>fdCMaG@<?6Fc&<|RiedVE*J%*m1kgm#1sn#q}+68IoZq}&kF$@l` zLNkl<34jKoQ}mO9zCx{=lOyacr%&#Wf*;GhTKd(mCNXmILn03-I%uu!Sm3vdzA2(# zAaW)yy}=jrkP=SR*!Ou<W>&m>)S+?k%TI9g_VOWDkOfMU%i^6g;Ig`?iiBp|?!g}i z!(rD==3f1H^51=p5{+2PYiA-n9r|_VX<OPIZ`d>sv5hb4HZCjX#!D{~YW0x^S<oxT z6CB?T!-qZ-3o%ny;$T+g#W=ffU!sa2@adcsh8vX^F+Ix#>XheK1&oMsMwoF%{hl+~ z9V}`U2&)H>RD!p<;a=<#Z;8X=%?Q!A{fv=&X>Zpk1p2Ou*O{veYU`g%Oz;zxU#W@x z+~Wip6Py~;2bR7&7%Kn3qnna0v9;cUC=ugb*tNY?#yt`px97E;M|7QZ5YKv?I5t3X z2S}AdypH0w+2dc|#x}wHa#wv5k|5ntCv?U*8(<K?`U>tX2%E{OP^U`tq5OT1^PvLm z?nwR;*x(OrSj8EMTSM`mF6{-c{9UPDgPzgasB2vbbVjQXnI1eK=)ze9632c@F~c9$ z0qJ|_)V)tD4WI}*y2o1jMRnlb$~S6}Z`hgW^}#F=wMn+VB1#QInKct>PyyiyM940V z-7HVt4Wrqo$il!h3E~NEm}L{b1{6W(Q%0c(K)mD$MH&wl{4w#B@bC6(7PoQ6J~S?X z^X?<w{QhLT8)D21-)DBrdn>(6{eI^lo$mTt_IP-jDGN_u@%@yElt)vOG(QJ6)+J2@ zIvE8R;&H)JwAU-CyXD4<?n;4_d^0Sp%X>@^iw5<88O?E7QvrXgYFT<X_#%O-ef;q) zvuT&JHqq}0({&k@J-QAGGqS$8Yn!_pK4h~lGcV1cX@Qe6<u#<{RvWw7Pw_tzWBXI1 zJn-XCC&d`}!stz+b06LOy?5aX0NLA964ro#Y2cLroJ0a)EI{Xf=8zH3+Q(76j}^!8 z_cr}E@MA8e24h#kbp<TJ|Fpv~kilA->#0889?dnl!ONs$Tu}-gxkx(|P1ajg>J)vq z?q_mdewcuQn7J^JT)>qFC@}^=Kx9rX3IDq3(%m0is6Jc^p<8k{d6WL9MJi!7QH5|@ zX83helQyr24%D?&@I^T*QA0@V*)6R|HrUvR9{Ac^*{qI4EStU*C<xN;Yr+CPgEI=D z$ygY#3s?{^bu$4Kp-p)sFM(FYBz`J=M}90}fL%uu+RSkiu~Rm$>xAPvW-SP!7jriQ z7C%rV75n%TNzIu%uI#7}I|sN<t!gVb{|e1(l0~OF$Xy%B6&mxgRV`dG=3I0D=I!B^ zSr5Rh0?rbEh!w7uSy?)LjvE(1=h@8yo|ZFxwIUQD&h#f!jJbD1Yp_{4Tb-*F{nO<- z*V3SBNXlcE$8i6qVY3F>oySPaKBEyWLc`b1)!~BQQnZjmY*)f>x<DEsIKLT*P6mJp z7P-`38b_&faz!dh$Y{Pi#Qw(deRVaO(Zme|KRdyV_$G^ANnZ?XIU}fJ1aj%Mg&y&n z9Ad|GI<{MIBmRr)h7SK^niUX)ujZBhCivYT!g|A_5lMXPA#S}&$zT=2j-B0gnO!8f zL^DI!S2q9`BE29;@DS)cz+z``Er*8EEPMmOd>_8zMp%Fq5MY~8L^Fu9np~_#BAMJ4 zGqJg|Lipb;DptX^4q!P0srSBz#)|9EE0Ntr)_6<<jNi@tGfKd@ew2h35s3s<u3GE^ z5H&11kt!`@R6DtbWhVg|@1*%kfOaeEEo*^knP<0HTbinrpG`z)u{1l*npJK^S_KI> z|77s#TQ|{wF|%Iz&vIsE`~ptn8nii8uSlx+fDsyhhL<Wbs5!(+-eDK20%5SGjQcoQ zBY@Lw+#tkxtJRsmkB`NT4<PY6&ZX5#6WD%#)f2~Kw7HIFF^%=6v&`u<cL*y_RdJDi zE|vmnO!mdKD!cD?xFeZxc&QiOknJBJ_EpCA-;4$%5M>6eV~jIf#kQ4#8UoK<iU1=C ze=+@rbc^$MBF`!a_)yHV!*&~|;XylcV{5N6kX38#>7tgDER%=l!#P5V`YX@iYj!1O zuW!Q&<*sVhvz6Wv;NA9@>j8V$*EGEb7frMIf_Qw1q8rvAI;`nI9gfcB#@g?Y_aOWn z?#|6jkK?wY2I2fy(cSoQ#Ma1HmzkRjwPyiKmAG3iezqE*vrXra8FL=DHf$fBW(v1+ z8%IwAo1lYz$Oz!172_J@S6K&Eeur4MIxiD(pNemNUc)YudA41RT;-nKVq-KcG4q>s zx#EU!V=;T+z3v!rq|oO_XMJtI#;Z9xkSo&u&4zh%LL1%Z-p%j7!Jl!wMUg^Y{D=Mg za2GM%-?hLVFrVo+EU$Um%Qq2a!(VcXwU2kY)MF+A5y(Uc+|_KJaG}qf+x%?2aaoN& z64c8iV7r&szd_=)IrXGp!H!)^No7w&ecIVY30NrcXaItNuNi?Gx}nj(e&cF;aVDY9 zws&vGMBQD}!MT^lX0gg;$(d2^o|&%4+Mxv*y;AwTDda2b##Y~-{EOKg3F*rWI-6if z-~vBm004#}KV}yI1SB?R-?wH57D2pocN4#@-HG}ZNPhcAqfd~T&hF2DwwK?Arrt?5 zcZ+-5{s+JQ;EA|>x$I4dZ%^0t8k5}%b}9UaKTLKf0*Y)yAl~i>5&*?!)1q!zwx&wU zJh)Plc-^|)nS`I~S3LMx^=ZiLMRRQORX4UzkG1g+ysZee9Z5_Y(;9ucPIiRaUpUTI zg8M=*3;3O0NhH_$*wEL)wnN-57Kl_VeDgm0Gb=Ce0&ej==O5Rct*gk#qSyQ&)2}#G z)@zD+7M1lBi<c`1ot7B^8E21rG?RL-xBUym<Jkk&JNiZ#iuSZPnB4F}O$ukG039~E zG_|lhI1v{a11d_36XP;+Lk=tCzqwa*XJU~QcJq3ap9;ni-oAv@cpB5bf$GcH3RUT1 z2uq!BQ}28ynsoM8pTp7~BsY)qkODDwl+yz@5R*UxM}=J*uVePOl;UGt$<u4-d)@rW ziaB*ztd(oF_&W-OOS_f(i5mue$O2CJGiX@vP8-`nflx4Y+#COb6CkZ>jQ+NSkbuQI zQQGX!ULF>@W{hvwWsu)$3Ph6bu?NP~C?m3U3qz`uCy*jfjoaQCryu@fuzI8jelqUc z$ge>xZ!+ZQz*SnEfmqUg=<nT^<-#nx@}w={R@QhK`zn-cIjgN(wBF7!p2R`20}sN6 z*9YqP-!Iv6m>bqqm51Qq;fzyAd~6FvATrfVLMp4h8sUM~wI{&Mi2PruOkfyY2LK0P zq#l65rOD5=spe<xBW3Z=&v_5YKVC`ZN-N2YPA6%Xz>UHmM=dIUtx>jiNa^FM;s^JQ z+qov~m&T)AC}xpLbMN$&iojn1l47>zJYd$=4Fh`aIpB5yxM*H2^L<VUJDhXIc*~3u zFUgzP_HvD~{bM@vMebWrg^_Z{5$4>ICC&W${K~-GjgjN3F87p;7?t@Y+(CQW7p=2g zTf9c*89}gF>E)$pheeGjjvg3y6V5^O_|Nl~2ZP7?f&Yq!5TBH&_gnKOpYeGpG$>DZ zEhUGvkZ_UHJIsgqcb?vC9CcWq(UbHCE)fpeapLQlud4}V?0Bm=F`{klMpwBx+aRrD z4@|wM9Fy1`2%L1yNyBAQFd$XQ#}Vm2V-sSRJ*Ln$ON+5`(WiefFA?{$rk7CFS}JA< zp#|D~{Q{w;a4KM~x@3N88Soc-=l;ZgSCe1F2YJ0oWBe6~(<yEI!j0@@(EAcyjeB-n zH(zU(+SR1se(_nZ&nQMJ>Vi$3C7f{@OXfD`9b!Ox8*Yzd&KxK-wl+lPe-L=0vO0Fg zUl!JBsIfu>Pn~TxEB)oKb$E(qztXK@*u#x;>9C(U9@&{MkUJ#^<HvP1p13B5!}d5p zK<|di=Qo{7_3YOZn<svJ=n;CgJ>!ireUMbxmVf1+si4zkUFXXjavyHZtUR1HXQJGD z={wmAsag2@NmFCV!T!EoSkL<}SZ-(0yC42B+}}z5_x*U&gRj<qAfNE0;8v#7W`SJb zli!5Mqg{dZ{Q5B=V&uzTrxgA5=42^6n?uNH6<)XGv-v6DvixuU_j3;vd_)d3$GfX~ zX1d}I>DgJat9kbF?;-KQw5IbfyK6sEzmgoT{X#|%py7EQQ~C1ahsg?VPct*S$IjTz zHJ%TNW`XGN*qH=#jU9TspXTa-=Sv*4>N&E5dZqiMyL9OF8Vu8;{`u`MDb=yZUDJcg zznrf89=*2Ny8Gh!<4xlg!mZ1M;A`GL&*AFNxYa)e()drjR{u$f?|{Ih9x{}kQ=HV$ z0|L>Qedu65Z}SWW%-B)cJw2c(ZsoAQ@JnSwsRYAZmH12LBN^fjo$ghj9-6d^3Uiy3 zQXLaO!TAK*arvg{6ImlR*j|awbRIq@&>eIsCZ2`H5Z*$!s@a<jmG*A|fZ9P?elGU( zqvj0|1Y`!><5DN72e*L%VJZLXi!bm0IXR_QXmIIumi3f%MTz!aNYH0I6A<0oULEEw z5cKfnASALRBQ479LyG2d?6ngF6pH!nQs~BFjaL8b(E)+MT@eocz}9kC_@95szdx=- zIqHW(Ri!RZrxFogp?_7vObe#X=NzjKuYaDvcbH00xEp(?!17}(+p^+=vyg?yzR7Y5 zy^BcmB6eGKlJoK3KYz}cT&^7hE{HI2gbTL~6eph+r~twixPv&OdG0K_4mj!NA^LN4 z*I5Zq0$@3`z*Sg*AS&Uy>>kOdmLnbTh2T~l{6O<ClJ6hmq3e&-{wd(>zu=CF4H=be ztjzQ!5jkn#@BP!}hKOK7hPVrjdMxLq&@>7-)&Gf+LrB?r!Wp;hq`mGXa6^T<GEG~m zulj`k&4N30HYsE<t31_;+dD@<&-z5T*nkuU70!Z0Y;Vz~WC~hl3wWO+;ld_Tz22}^ zN*egm02~0ztmu1JRXj2HT*)nBiz<q<uuHelWmUpGyBIQ*Q<7*<UZeY2UkOE%!DuC@ zE8%T`%JnQc6s(?5qxWkeb;Mx-f=f(xD9>W>R!uXT`!^Ta7zYlkdbKwKcOTGM5r_gZ zbRrEvnUF7W7qqATil&kBLw6s^!e4nALwMRk!<XdWM}xGbI?@#AYP=vgAzW%jUD-YF zTKQ!QzYxvwOnY@REv8m|<ewO7q`JD=e^j!YK|<|}XW8djmN~*($TFcI4`VIp&XwC* zg4E)ScS0!Fs>@s<eW?)dv_;*=w<3bx*<3UJDrk^L*l){qHOlF*a})n<(9Sz@<ArUb zQb{&6;0Cb~8ov`f3@J_uSqb}5;6KfyFFx6!Y}xK;$j-a+z39q5UCRrg%cpr#E6A!U zA&~3ORMY+26Zbx=&drn)En8nK!~%!*)nE9Yg`ZT*hHE)rg=TO(C(2|Aw0`dVG4aQp z;jxxmHah%6=gom1PJN4zRCRD!c@AyuM_yO&=gWUSF<$?%c>C>3Ln8%ol--V(3%<-3 z0)*~&(4;6)Dbf?2FFrr~@@+{#_8I4_u=#St+1bCd!gHcK!L~#snUeHat<X!{kjn=P z;Tw{s)j>sm%X6`MbvX?hpru6(TzWF}IdwGTtGoBfg;9Xg$KqX2OGC72R60^fxvz5> z<BPSLxYNn?wIPJrsvyoJj>yRRHiUQ0<=!T1ZCJcJNyLtAMdh8Kd6j>H)#fs%2U{AW zjtS+3_lMhNS!#zd=-5=zRHA5k|3VB*{J7KU2<X9^6d=O6k6GTC*uGKuiuPzXOZ_!_ znVRiMl7Z+uGZ0(E7+LknqU4X;YCnhOTI;FYxKfVM>)kCwsj?^6^_zdgN6a*8;K0#U zp?B<h)ZyESH9=)!d<a8l<Uap-)>e=EOrRqbZV~37iRk_mI+D&B{jfy5LfSPp^9n|n z8kLU_qrY^eQ0r&FSdHM$`mcsU%G=~1dO^fHs}YWZ2A4tcr;3FFSu$17c<q)7c5}C( zYL}RMeEVrrg6Hog{>&+PI~1Qi9TW_Zxd`nYRb)z-RP-tp!1lXm&v*3t*xks577OWD zFLc#HEeHmiH!e12U-@t^I$H)WL}X5wPX8CjOHdRTmr_@=c0N!qBcgO9>@Z2U%*7rl zts5!2;n5G$38&EbPdaoBWRA_pqJGtu;fF21rKYg0OEbD28YS5(bXgAHMJ3<3%TU7l zwY>7PbT2+Py-$?L7K~zY*tk4#mco8m75q%B>i50euzM}V(itMeq6;GWvcX~xWaB?% zv!#`UxfikHJo0zw7KSu38iTm>t>qII3TF+)d0Tn@Ssjd~ooo5Qy`}D^iHp5MJL1^J zrSFo;nELdLK)o72KTwC(hg$|Y!}vry7A~{4SS@QK<7WYnlsW!Avu>RImi4e7Z)FrQ zSNQ6gq~3?>i8lrWwKDCxyWM{ZCl4}>yi|vSpUS`MfnUuA8<W(f!7E22cjX(r9yk4N z&7F*#y;v3S=+%L&^J##0SGnVl#8n@ZNM}|1PrrsJ>*?jxJ+>an;yk@-9~Togg%|u= zg*|ibi?oU73gluPqK5by`R_?u&x5tB2bb^5D@^Zqen{RU?rN-af1Ag?!`kYNr3sFJ zD+<kd_TUgv4Efc6{C`~cQVP2^-c`E~NPy~e4}CD~cio4v=yxMU44<UJ%NSwi@ZH_f z($-Gv7E#T{?2imLe+h~W1!gwdP5yntUTE7Ju-jbtFsP|?S}{LbC$Tu@-Zdp}#iG!t zWUqq1pY;qo`Nfwc4aLuyp&xHv%ROm%dPNmO#vNZN)3yV9Mh^x|u+G;0J9IoAtFUG6 zf7yeWk30Tv+vZ!?dvC>kDb1~mraAp{Aj6!rrKK;A+H>BI-TLj5pvqwtcLa<MG&a{K zf6pK+y?;G^=RO1s;Etg%cK`sy!2lhg3%&$CUk3vqIJaIyQEwC+VZp99>ev^D;y1|G zYb<$_$bQ-T!%$=C;3KSN0=Irs+3;ho3+WoeP35CmQrAcF^_wfk^JHnIMfFA@6NTzg zbUX$vl~bh(%2M3I)kVVRdp3gtgVySIHMY(8LlLt`D4Cu%@SQ<h?LxEXOf}DtE0neo zD5)zjd|tQwBGh<9U?{|QrJDqy=k=8p2k5S=25%Q-H*5@2`3;{Kbu?{_X6sL&6gD(I zy)DvA6chu_=L=eRlJj_H>$faAnrfONEYX+T?AN_A{^I$M6!-&rK9jEY{f(i=g+^5M zj-Q_=zu@7#FFUoN<IjAuaw1;*_ha>S;u)W*v(m4F?U|ZuZ(qIq^WWaaXrXEMtJ6P6 zKfir^+ui-peI@$t6R|VOVd6vhv;YK<YhaFo=4qpzfWe!WFmecw>`Ww(jwzy-RFHB8 z>a(L0V};!WAaUGE&~pNevc2rbuMZ(1L_XQFB7wbjOGbcUJtqW%Vd)Wf+OBkW=blDE zAikkj-GgK#y~<rwzzvTX@YR9jq|=;$t!$kss({4GBz}^*WUl`yPnVo?L&q3Hz-P}D zyhkH|ZN%q7?6MTK2#ls96~{@!)fqz95!<EIw9U$($2#63Cj9*_W(?*5)m{}vVPRh? zscanl+Ab^lPYTO+2fS+<2F|=EgS&a8QlCLGVjY6I=+d3)d%!*4K)q~YJB<T^i91ar za-%!V6FTAIjqSgWt83>U%sT1NjnSyz0*m-R(^}&7*{%P4Qhlp)rzEfL#a<oP?H31g z;bt8RpTciv2=4pTwGT~g*T1S;bFg?`X#8}qZ~nAX;x*mn!TfrJx=KMm`&HllHyoFr z2MqE$7zGUSMTuW}2K{(d;%>izZ^o#|pwYYb%hK-;Mrj;;I7cr1w=>-jLyA8Jy>x!Z z9iqaN&NHqik7REoZZY(b0hY<9Gq$CJ!5R;Eqc*fS&)=x#-1#r`5c>$hq&}MAnK5;- z3uQFGq^ITY<sn5JN|5>ZtSUO084(3piRQZs21cnbc57)1oT#%gx@x)4%&06zXz*}j z`(}Q(hb%zpX`HI*ytQ)tr9^~?`otj{KxMjGDjDu`mE<n=4e}-v479%8{qv)T_F|V! z9MkRlAwpoYxBFxKS$b;VE&d3#KRf&pKj&X~XrR5gU#F;_-)yRf3t4Y-F^)!;%*g-D zuAQoV8hn_u;;4t4#DAQGs9!nRoVjv*K)>peB8U=)N7Fk3BuxHftaE=UA23O)`WM$j zr=i0D=%uOGHAM5DYr!Q);{H|N?8VFpC>v!v(9l}E5R+Mh8vt60P&^R;CZp5I`7`Ts z^3tvi*sD}9%eh|(%E7o9t6+q;k&~jz)#7k=s|BZJX3_ZVUhNUh5=^26BsI8^#)(A_ z=?svhGgFgbM1Ej4G))S>33H0x;C$^lpp-V1a+8I^xg|V!sV)E;5WGR07uJhv*cYw4 zOvz?Ui&^<H9&$h`LejTrS6M*_gGJ{sEjC_H56oOxcJ8n3MHm1@n0)mu5q%I~VFe}> z!L`K|i70z8DYHdpOIUX}-qa>Cs~EZ^seP=kZ=`|ARIiZc>K)btdU6044}NT;ew1(@ z_T1(pM{hy#;VnafL0ZH^0Ij-R%ovt^PM=koD30|O(4<1RW#mz;)x}7#eiR3r-5K>F z6$E%?3la0-W)YZ8dRP@VbEJQaWB>Jt_ciX$W5r2i0wd?tkT3w~CX*d8n!u58ta?In zYHn~DAS|L!6r~!{MVCt;zi9drkX~9*SQ4bi7_=wnx!1y>4ijC^OjWqS4FPmnhom!e zXI)sJ?0~<wRAeK4q%9m6X4bP|UZ(?sS%G48n3z6@?!2A4_QvUXt-C(T5KxbRko(n} zswh5eB~0h7nz(*NR4}-R5mqb&>{XdYu@T5!5cMrNN+RtvgwH<R(|&J_Y6s=_V>9M9 zg&oKha1u(Dmnk~hB}vn{ZCL%}p&Kx;H2`c}=sw>pSLagC<4`?q4J;IUP{W+@Uh?x> z1=0R|O%!bg0(uqNg9Ccr`zJ6rd{d!pGp5my|1tyDjx@lf3MgT25a2x@OTdXOG=Grd zv|^@s$mXHF+y8sH7gDdKlt7)r^gm^n76lIT?8z={&2Z3w&kQ}u*){~*JnyaDKjK18 z55X3)>j_?RrRu3$)`1r)h>VSnpX8onCkr%{k&$nODte3Dk8m1AMe=w6oVaB@YK@q- zi{7-t9!C7o*{(rPp0IS&xLzct6Rk=!=dilp>mSB|T;9{Q_t5B2B4O(Z^_YIv%7#lK z>?$@E4F|o@h5l&i{iSFZTP#JdIS|=*HIPp0tbpu?2aFhi2i5Gr2Z15XeRU|%aQ)s% z;=c8sH1#^Sa6s<&FD9Dw0Pn`UpsXsqlnFl@ng5%ewH!`@{oRb(bQ@^Tj`7o0rPgIu z&cYU&s$uI}QD)iC-FbIom`c{-S{BA9c_=Ql%2ei`%#>y0O^kmJ)C$T8u&@MMm+jLV z@z*u8FMF2Jmuyh1Hqzd!=^H<NW;r>1gwGMwdraHsF37d1Zq5d;<PY=~y_xgQfd&v= zHMRk?La}*3Pc#hUNLCN3gP8}#A*Me$>h||1T1mShz_9nyWQ6v1FKd4FPN{mm`u^m= z#b|SL+{fT0d0xtW`gM!Mp8s(CXN6u7e0X;PAII>99Q+M^+N~(UqgfX7R$DusPfu>* z+x=lZIXH8lNQN#f--FBf=;_#w<1p;q6)Z8k0V;6F0bH&NH5<CHJ;z4ilqrZWts38G z<RWaUS2$477Uujv<o)5r_Tz|4TaWJJKZ1+>1xNlG6>F~dr6~MVPZFb+GWU;9MO+3d zUW7)n%i%1xc>oLonD5Amu%{gflcz@(nsiR3NGfVHMNob6c$W~;$~u#hsKU9Ur*J!( ziUKE;t1t)fiH&0EK)=-C^XoraujgHssz0LAS$~|!=}k&BeJG=c?i;>!B<|(Bjn;KK z0PB}wUO7bTL31Z_;^NQP9;LQ>h?h1On%-;GS4&NMHG3-USO1kZaAV^6zh4Ni7wUZy zyGt7nurK6g8>~?dA^7%I^fM0|Re98{Up7Rc(El`1lpa?&IrNLW|I}cpX}T$dYzFOh zO4PpRrbV+g$&}9WK-!g2SKB@R^F1g!3=Xp720cXJ!rY$*%C~y{zUq}9g3@Yz2$#O) zbvej#%N}eS6e5JS8SqBxppo+=3>gl?!Py#pX38}@{GDjcl{Lz2VPr)u7hmCd%rRD9 zr_$N`vmIU+CC6^Ds~bg|iVVy~e$TRCB8JhV24168NMu7QAB9QiqQoe2(x0!H$jQRw zP<H=$!S9fuXXhUL3%6;|uK!is9=d==3CA$Go>!B&`M3GN_kG|~G2mV(#2ngiS$_0# ztoT}p>b#$iZB#&|1z0*Rm^}_nOyuj0D|(lxe3Wo3AI`p(@G36EP9D|wA00LO#?QHE zNUs4rARdLg%Bd5IAp20RqTj*Lzb#SK5I}oUdywioJdnU0pgD?S(8}~wcoQoi6m^Fk z<F9}cia~`@u6xi1%5EhV&>~eR4>e=aET0pg=o>+wDX_-qH$rHa%)1CzSCnh=sCEow z?LJD{i3@H9Z*&4ClcD>`AK!o<ctn1JV?L4Ww&EV*E<C&l1D<cE1;LqrvZGIIAIoiB z_d2_2?)&^anCaXkfTE437br>6s!D=3QfbWZ|Dr*kelj|%FlM*$8Pz81-9&Y;ML<Bb z(AH!wMHDXrFxpE7lND9ZEohc$Y^hAELdYI}hELD!%HPLIa4=uAL+x#wXURO2>v*(s z2Tiv1jA{2W({^bMaVU|a*Vey*Do#i5dz%TP%<p+DSvgvGhVstEL&zDhfSA>c7&Af$ zZ2&Z44sy|jW@nNqH71i5q<-4N=oR!pWy?}bBuh#^F60YF+RN{f?45%fkHG<tVX2QF z9;5WxvLQrjE30>$UHW&A8#ZlJ`W&0O-`>DpHlo-y*E44v7D3Y+3fm6_2i&wfo79`v zMSX+;L^Fs2^;T6??xv>aego1o`*C?(;&U(5BDU}Z0UUh6%zK3Kl!wV4=k;*dD-K8f z8H}V&wfZMdeR2miBI2#}g^pPXHAYE?fjp-53N93T_|O0>iYB-UA130>k|Q##SRPWW zq&;~vN|WYeX)a>_{ChEd*$z0`PJy`Q1s<V}hYSB6mmYY@-+`2!Dq^0}79CjML8V5O z-gqcOL*<YTf)Zs1Dc0bCY|3!{HR~I;u{RuJi>K}4xx-MVIq?f3C>$NIP#KyhauW)3 z_9}`2uaQGPWdKDb-~ec?CRA+?Y%G<3$-wh?6;;J*&wV3HnGUUS7FNg{P{y&JHcu^k z`q^{0H4Q<&M(eEzCf~BXi#ng~F-qy+eL83R8$SeZPYwk!{YKn<j&Nf`n|h&g6;M8l z71<&Y$wH|7DjG+Qkb8ot-=!rVhm?qb@<jkHEm{irM;@vpy=EAuGAnttA0>4b(l!<@ zDxp*C(U0ws9~0v4d0x*pD8x3}Yf~sp=Wk`64)Ik<PfyA#rEb?4pl)teHyEI@_p&e0 z7?ZPHF$x*pbm$J6gyc9=+fWp@NG(s!Q<|xp#7PLlXe|Id2<B(F0K4-@uucm0Xn|U| z(164#qp0@iHZRn280s>I#nb;hZwjHWe2RnN$}0sZZD(;P#$1%$1#kUOZ)c@?J&|~i z5St?ZyNtsQO#8RlJ(A}X8dw$4kuj;9#ZSc(P)q`)lR?ePY<CWCL<t$9u6#{{nm6&A zmvxA=?N=t!m<P7RR~1^L$wLqIti!+9qn=dXlA}dmsiD^B*l2yLzWem<-vJU+C@T6n zoY}L6b^9u8KYr$F#A$Sih(RlW&D~Z+iTFbwdT4$Zu>+#**l+MV<)NM<n(&5Mc%MX( znznsCKU(RBxAS7rxaSyRIV9lufGyg(A{$y9<fLPBlv@u+2RC~=8o%)H;WU8+nB*Lz zR_tz?(E>f3wI-|3ic0lWVH8mcC2j^~Bv#s=#WA6@%pv;$T&z`W`$#_5ysD*A5udEP z$DK^B*AT?!+jp4_74E;SOn(qw-;i)O^gZe8bypL`8o<AuuexhAF_b?SRiYUI2`HhF z)@FPGWs+79H?x5SMn0*za=3@=r8e#eS(f>9vNaZ-8^FKj^<f&3cbJ=`YCBaE5^0E0 zEsEW}UUiwV3OMtit8bbWuA(Z!(rpD%$hM%<#Cllo-M3mjC`1N2v?s$0otuLab$8;S zm~ALFvWjO~YeAQk&x=ikbT>O7YjXN9q`X|GvVE4IN*hr0O4p!mo^#Nhz6|Z!DZTS5 zq!PVlfF7N^qd)hM3*-&Yp|S<obe?70KK`2hSI`kE9t<bu=w@||F7+@qW=tl&;ju;W zR>>Qhg*=51+@`xSWvM^<n$b`IeG%~*4Prb&FkWaxHmQs*`H!}b74nA<!iaIJbalMA z=3?z;*$TVopC6hFFtF%m!vf0LrjlNMbNP=B;POUfN+B{=`wa|H7W$}6UsMV`Ktu2B z(~#^I=;XFarXTbN7b{sioF5D&;2$#5tbJ0%1Sw|l5<;rb#64Gdjp!Za*hfN7kzm!f z_WPsk=x&@gvgC7{DJSOn)3G~wl<``$w)kzw0dJQ%>WPiVoC;!*0TBozLvS&X>M@Z3 zoTa1SDo2DlSHj#D8GiN#)+>q<*SWVun{riX;G7IzbJ27-WI8otG#+S$f+qDNCYM|$ z!Bex3>`}%q&+&J(WKtV#!K~<LEbUsG_fQ~PKsd|I7x1+)yA#wk?|!AhAVhC54w;&o zj~aYYA-UXz0`&qRPQjum`DeC|W+yW8UN&f=#HDVZ`TK&k^iNT<+yCYHGCYRt4-kAN zt$79^=A$U$q^J=p{d6`Xd5};uXs4PLBoelMl85N^yfTNj7rS*K)g^As`b}K=RQzq4 z#`<?(NdM;UYTZN)Sl5W0y275LpX9jRZELuuc(4BQyn>Vt=id0frv4!niL1554O;xD z=`)rnv_4&6IRi1SB3A+&Cq=sYN|A#rxnZ!icfB0pYTI{O<HiQ7>bO$7bvx!@XxHf@ zhg%`zlPm~9ClqDWRpjL~ZEx4ZcWCpwPaWBFq3E{&c0dqId*DAZg?uo%n)zKgEabS+ zGw&G;w?d0sY2{v7lRydHT8F({z_|7qB%@M9!;az2&#s~(!_Za+E*?&(M!(|Uekhka zw}%ElzK{r}5np8vg~M*8CL5Lz<ZhZ=bqeP}*YQVQM+}Tfp!iVGO@MgR)4O1~mY-q% z=yVNDTsYNV5x%tmYwX)FURgGtTs50qQbpySq9nzeo;si_K6idAK#5horY*ikGqt#> zGna6djnZdFyN01OBvHqovhk`YQ}N-bn_b)$n_@`#{dbN@hNul+)T+qK`Bpb@@lz(l zw{GrWS?s8Hyz1HB*U?1=<r{Y{PORVAnQc!&iAavVT=^!v@+~mwQ^7K(QWw30M3are zTf<S^{z-{-&xv`clb8Jr^CaM3|4W`X>5i*(+?Xc_z`lKg!RJciuNbCOusDFwGG=mN zR7vn-+<9aEJ{A`Ux409uf|CB6clzyL%EGH#>o3&yLQPN%#)}-OJIBv=T9(kmubZJ{ z>Xm;<vnJzEqU&E|jEO!9W$TzzH*I8sGL)Zqn}@m+_LSkNyw&rkw7A9(KA^9&Oq4So zm18rkjs&XM`iI+}G*_{AG~@+8$<J9xV9o4s4Or1W`vFZ|H~o%YIDMcx;K$axCv|l@ z;3^t(hI+M>Jv=CnGe(hgQPH1^Ki<mVn9`&zo;Vi+>-s;*-hfD6)bS|;`D2;>s52Fe zD$1TQi7>b~{Au*s{rM5Qj&MDUeRvdi_5&}uC&oLulH3Hp_L{rb@6wAZBF#rRdNk;W zey9pv#fi=cMa}sZpoyWG!xa%RDC=7E)|UoIZv+(mA7mfQPJ&1t>=y7ZFPu+b2^Oj2 zvw->$#PtY9J{l-I>Ph+Bf9o@kd6t+mI{n%PhWJZP?4$XO=*}YgMp$w2S=gNC=`oY} zcZ^(nx{1$X@IQ0MP^^JJZQ}_|BN@T<5*`4{c<naAGrvkvj%oqP0@neM`l@;)49TmN zZMLQni{w#@W;b8gN<jQXqzj#^o5`~@ZerQSOLCD*uX3P!$oxM4HHJ=K4$DtQfCO#i z>yArn@=+=vYIOFvi(D})twCaixr@wsP*K#OVkf&Paxj|5lAQsNDup{0Tj&|A2?9BA zlLRdkhN#N`lg+;@RmZJJ`wq~%UQxs@4ens?(wL0z#RGJZJ?Vzno(mV{W?gjazqyZO zNL(Ap=UBT!-YIguLDzF#Hc~r07b?29^p&g@!kf?GAlRE<bLQ9VF*Nhpy#%4}BL}w@ zeMhnHknESG&(gRG?UpOlV*@Ihy=LmHDW1i=(E*^)EC?+=C)SKX^d4mm_9CojxjT;U z+AEETf;>NH(V@KDKZrKo=oz-4C!h+O?f&?gAS7tS>s6Eyq>7UYJ*dQ$X;^yZJWb%= z&T<Yc-sy<yccX|m!<$Ts^zh`eXR#}s6lJnI!ISX^r@?jX!HMX0LQfg{P`n@u-mRE( z3|*;4o8{i5FU0EhIs3-$jHe7$@B>2NNzcBQJeZyvPK5e^9~Wh^-ybhtX5bXb^E0x9 zYs85X^s3^|g$V6&Etj@00O~Tr9b4R(#$r=U$*r>@7Fut#auj3EkPg>3x{Jl!=o5Si zKaHq3Jd%xHFNz=5xvg($s?Dl!r=-L}2KX&zoHu92EIe)xI>O+jZ;Jga&t{Jn?x|bt z4=nl!FL_+-nQtImU0HEys5<Is$G^xqjOb~Wpht}9kE_gsl3K(eWy<<rs;!C*L0D59 z78d9xMa~2ORdNCrPvNBtbHy^~z|@DWXa(C{Vr|MrTig?4JO!TkUfNTa9*)+(n$zx! z!Z}!$yc2c<xy%>2%krCGy^tks_COtM^@2KVnvG;9t{hzKPtPe|tj!QPRit!SsadB# zrRtd+eT3hx7so5@VA*Ve)oTP~Md#VqYV-=FimqmuhETlPAHwAyEjy_m2q@%nx4!oX zFKXt>71@Zj3fne*(M!|uEiy%0*v@-<7G4#Z?Nqr*2?pt8W!U{@zTgNXA7|uTh)lsY zFjVIh=W&EIigA3S21^28E%cHvk74;k$f3|$tRPTywa6F*FVTC-nz!h^eE0SxgB!b} zZztT&@<PV*SlqqdXAfyP7d?NSlsx*uf|IiIb*W`VRax3y?{#!-A00lE9>YS)E@<uw zjF(ePEoS40l))8wr5hF*ykTY{$?aaEFuXcB8C3^sqJ9dONvX|esrv(f8PQm^W5Wq5 z;F<H#Uxya}j5BmDzjRoxK2w*R(tnfwyvw<lChWrNcun<C3>%v}*Zg&gnchqxRT?U? z#0=k~S%0~zZip9Q9y)?I<^MFMVL{;N&jp;Q3yO3&s_1*-r~jybkp!f-?S&W6v?{VV z5`aJfmQ7hyII`c80rU>~u6=;AS*muyF`+=626*{P3m1I3*x0R4PObC%z2S4@wla%) zVeuK3;ajr$p^YXzGCG`oin=DquQen>ds&y85=@hZ5Mb=b<XIYihL`Y=`!6QYfb37{ zG?d6zXx!!+p4fGy4Rn1|fi^A^Pcp!OEdZe0uS><~Qy;EEfPGH`T^*ZTyJgWB@nZJH zqjtF#fwykg&n(UZiqBCctK-;H;+)1N1;vBkw6hpy*u)2Rko`vs!25H>G6>Q=lZu=E z<^q7D2vzpOmPHs&uL9gIBZV(Zibd<aVs|570D`iaZt$z=L6A@NqBt?RrT81=xhY?0 z9x>#2EU|;7=ZAE{m=-+pF&t@{Z0<S8HD^UMemEA8#$|}(iOx7QX4n#&LuC|#xy46! znPQcdzp5L>zl~)##@Ze7akwpX#-fV#+6;@-r{N?PsbKH&NKe~)Lguajpm`yK;=`HN zMy+_3OK<MbFL+1S?@lc)>3)X#UNtp<G1{Mw!{o^OD=K7UO!en1!CYd0I7&ve3XCg1 zQ{PpjT7pRr(8K0zj|EYYm`x{5{16d_iSFO=At&L6pqzBTFy&n<P0)2U!C8h1+u)RN z*`Wc(gSIx4pl1)QCLNoHrQgA!0<6dES|<k7Zb3prxB+FICepHC+6ZT8m7c)<%XSy+ z(v(qdl(HB?wVTE`YjR><rkf2og0VFWQ1xzG7cfvc$9?Mg-RIYzvWJdke5)wm2P#eP zAFo#1Fj)@qMJ(CG^~)NuBpUk!8p<y-9AF6|1j8J{Oq9xVTwjBThBHm!7}4F)<bDZD zX|_R3dlQldeOsOXK#5GrY@v(3sKMJ4`Da?w<qxbW%9&Z=WuF(}&3CMi-kE{L>hHPd zOvN7ljrXQM@V>?M9S9PoPEh44m+;&7;gnMP)M12HMCH+lhSYI9hA+BOftg~?jOqS? z*$iU1x35u_TUEtNa5gDwBqnTD^?S171Vh!4o8)T`p$k*{YesfrBSz#Ts4%O|Flmf{ z%2JrWXOa@Ar852n9;Ad*nlk>4PjejeZ;x}~_0`lFL;d3DKOddo!cy_n-=NiT;gJbE z3T^j;4ce9M>O{=^Es0G=-+?U57NLJuMWy#Zk#HkvzL(#}{0D>{7EsMnlH4KTUNZ=s zuHx*owvfbN{F8x-s(K?1w|$9vO#Bzi3e0LuG`j;VM|P`kTH?%+X_MmjPlU)Oma5&) zgd^DoOybwAy5MC_5o`DhSvD)tl;2nf9z8k(buf%tH}yg1-qkLNBoBqH@=QTJgKGzK zk+sjb10-~1s}#M-o7{D8#aiDOV1mM!p<KToR1t4&>qTx;U#pZQ75?K9HoTR%N?4T5 z`}SoxhGLNp6g8`-sPe~O*wmpPMyrFcG*!1!o1d`ifo?Cf-~~RlRI<X)rx|eCZPl%Z z7i58v4!)Trhra45KVyy4FH|Md+{Cy`*^w(m3%*xj^!IS`IF_ce3(-S{UMK2Lo;>B_ zBm{J3D;={p&5(oWad~^;MD<}d@_n8iXopa;t?zGg!x`pspgi_FryKah%>_IPyMKUo zGa`KPj|zJhOlmvi%=!6upMgeFqv=Y}n%h6w`eEl!9bO!pceg|tK|1Sd>GZ$5ea#dj zVBf}*K2dyMz6a-=YEVz8O_$vZ(HvN;G!qU4OoB-Z`oh3a`3o-iO9*gsLZZcz1GnQy z=CA0r;P<i<Y=~l1Tm#Kz%1TMc2zzntq~OLuHf6i(RVUNaAjxSl%1_N4@@m4hJ*tn_ zmES?!#GDx3o!%oz-%(Hu&NrprMF_wuL_q+j(x-xDLd~`%e}mw9cGV+8d`~;m_wg5h zHkE_L;pc~sp<b-Rz|Z?UX>6GotX>m(<IWyT_FSh{NhnjmulaL=x^jI~?uJt^VGT|> zaAgAA52Y17bSWlO<l<;?q<^c*KJL6Rw23ZO&*%zQSLQFDZXPQ}zQ4WL`!GDWhKy#6 zS@ij0hRtF~X+Eg$&+G1irkA=PU{9%hnIHa<pCVeKFm6EM!xi;<M$Rize!Eeau!<M^ zXdCQbcmIit*rQ}>YMsqjf=e$!9zXwtgQIu&DXW?miO*ZS;lvNZG1=78$MDU^B0P~w zszi#exL8P%mOeE0nu4m~SPV}vxABL5>|y_B_?w6>S&Kbgr<qn$(#!eFa25!##4J~y z%kc5f6{Cf|NECmRde3WNnJ8O^GujWzz&wd8RdN0Ai~H>qe_^pzyX^X79hQEixuLw- z%<GsT9eAD!v6?}#7~ZQ$2~?p3U82;O4L*T3-pSW8NFTh{uNA)8Z*r(*wmDeybMPU< z5Sd#~*cYzrpMEL^kGo!Ntwd4bhf6rZ9U{RUi3L(BNtcx*xI@WrLP3>l<>bk8ELt>7 zO6SoBxwuYwjcTcUvv`d6C9h7!%$8RPd#{xPnR06xJVc(}Ff&3b4qo>k8w@sjayYCD z9l6`p%XIws3a(^psGk=~DgbK$>>5*6BW62;6;M4hlwPHKp~;D?nUZw%j^u|ZO7pju z_T2EN>wNF*cqHkHo<EK}6BEYX<S&f{I-<@a{*^s^rK8v=S@IEb2K!`IPyf@gVo#S2 zhJj#WD58EJ-qp($o|oit&e}VU{Vb!aC5;WHj}7|{y1+*ag0J|AG`~&1a#>6xqKo@I zgnkw}^e%eDXq8}OD_+u>qYWZew-~sIwNZdak)A_cE*H+w5VdcY!I4>Uq4iOohU9q? z?GdTUb>b64ja)kI4>FA+=51C3(yLa-+g)YHcR0FTQJt>SpP~a)O+@!Rt3Rf&hGZNh z(p12ap2BYrRNfMhwZEW+x>_9iEbwBZmvQZHkNGJxEcBKPdO*y}bGhh%ed_nL@!h78 z*rWV^iHQ+S+Gh{bCTG_YFOp{HS>bC8n2TjuQZoE8{^}<fIMR$H10_A?H$NSTZCd2Q zp2kOo3buoRkRU5v9(bWo*YLJl)}G0j)Yz+Grf6y`y&an;C6-@%nqWO9;AAQ!Yefz< zJ@Vx!ZecjFY(C@G3v=VUcuHuoO?6zZTX3h0a#H?<Q)Gq`X9H&FVrIw(C9CPm&WCRz zx6|WRErC!&k?pwq!UM#JXMrvqrS0<mc-|7j;zt_tZQxeap(0i3>a_)vky0duJzkCs z-*>DC_&RICGmR@3=4Z9Ga5A!dgRP|!BRzEi7i+FAVkBH4vhwX)arlX{hK2jn+0AK5 z>yk5Y0o3tEDytp6kmyVTVDkq@k!#n8l!DBP*r@#(7sm=?(duL=^}Zq=zRL4$Gx?3# zD0Otm*@6^UOiO%YLm7b~&9f&qgdsKT4r_{c!mWgqDfvrkQF>Q95{50s;7@uQA{8$A z32SLjUkccPm)ATF`!#F&?mhq3RbY}Daos{FxmRtUIZAIny3)ed82;31+-{lh)wVWq z{GDSAwA4FMd%ioRpf>u*Hfq&CjB^g5%?WHbM`9SraG67eq>AJAqf7A1{Qw{gSpQu> zbW$ve>CDQh;op$2e^wg4c^w>NHCNt|pSbwsg=Tc+R5VJGJ3}#!n7nM(%5G71CKgb& z$_j6M_C8#|!Q7AL!7tukCF=)baPLN9bObl0(js>6?Ta@K!uO4n-p%U-ME~IV5LJ1( z=^JCjB??@C@=8xG_I$f&NcnHE`T?Q?L!CQml9E69fVfog*TDR0aZ5ITymrhKx=XFi zT%JO*>aCsqfJMCf<+RP5vnsH{)p_-Ak?^L|m?w_%$=I5_y-E&sAeA~(+MRa_tgE<1 z0r&-{(<QcJXI<0>cEJyQ0+iRS<B{#!l+|{!di}j)?O5uyBo;V>CyB-7(ch7e@J`BY zF{jeRS07GZEq~2W3!Bwxb>n>I7OcFQmLSjV1ZPvKi}q)(E2ngeIC*Egob^ht+?Q}z zReW2GW&D*i_83R8idl)GI7C-EM{j3V%vvz(Xn&8n9N?PT9pTEJx#r3*M=Ww3RdS43 zHF!9kdMFDoKgNsnY%(C#qJfOWe!I)u6sQa6US(X0(fYFV4PGAj>*faN%&WGA^|+z+ z`0ZD@L(A1$f<^Q8QL9{+|K)Y-U*CB1o?g<FJmeB<_V%~YJ0=@SmYwbE=_-4!RJDKC z-$5rMdn8$P;1_f@*>$2dk3NxI+#@M(bYHnfQQf;H`+mVlAB`x2p#>gq1mgUAn5c7z z1^_fv*r9Tx+BMF36{pl2dkYNA%EteA+_eyr_bq&O-kK6yL20(TdM4Y^QYgjCo^Vy? zfO5^`dicw$a+06oJuO14tRq<|8+w%gYLq(0O}{<!c$O#hmS>X;eAN2qp?5Daz=ING zl0}69|IqMRJD%r;6v^6Z^893;HYK^Xo>l?)!7=r~BqJ2y_27_F>hlIx($1?T+b^9* zU$^Wkwz7@7s=qrW(F{JC=b}5lk+QojYoZlN>WpikYm>E7BYweJsFH2HRPUt3Nl?DU zcty5%|K-Y(Ru#Ri7X3yoI{%jYiZWbQg3@Bi)0Q|>lJY`|6aL@J3ovm?EjZ%=Vx4wu z0g(;B*tf#A?WzQ`Q<7*DjLeq~m~LB$1#W!x0)J~@`<B~0b+#qKm5i&isiRQisa@Va zE{snQax0Ui@Ife0DDx#Id%A9Z@Sn{1o#|;)ASMhWx&V=jn&-Iv>dOG{=f)^say#1I z=tBYoXcdDeGZ(F<gMUgfLDFwV2}@8W0dh9*^M+qFj#f>dPAHc7Yx+P27PZ1ij5TqI zt8k*&3@@F!l_<k^7H%*_n{3y{BI{!}Xgs!lTQy@;OW}Omg0|0GtfR7T{gkGB73d>Z z-s+KSce)JE`FCs2#C^cST_?6ZM&ZSw4m`o<$ID9hC@JrF0_CQ*w`zp?Niru83IGZu z)Sn+h(zKo&{;ej2*>aWT5w&^``2_(uEng7)sngkaOWuTrn!43Jx&QW<Os`M+umv4R zJx*oY*4d{B^F@(T@GQosEN`M*`l1{5cc#1dR|1HncGiuQW#yY^yp-5{illEOZ*1Fy z<fy>g#tre;$Vt+8@&Ur-k?0lH32MThN(p3?V#=@#^y9NDfs1qFZkMk7jEP-r4)6@z ze$|vodF)6*cm*+@-IyW;HOj&nQmZ<29IDj^$qG47?mJV4s-itpre%yduEO8O7{|_Y z@O<3Yj#E(eJZuU-oa!BqGE=@INC60xEbW8HY`dr)J!WB0_{tCA3xMgAoW-@Ye_^by zsKwS@WGWn0G--J8nv>dy-?DS4!}I0cAeS?`!NnETvQqlrSNHc2pKKH_bj6z8xq0OZ z^P}A{Jp+E0HxA*HzBv!gtMIbEFSlv$Ueo>&Zwcp3ow3K5tcL$LajPCV{-W@rX7~!j zgWH%Z2+wVYDlNaOam1tOhfi#ERs*GI?H?{O=c+h&H{C4{W!ijHy1_I(zbF4=Hqvt- z<;N2b+IviL`zmjJ&~kK-nS$R3!Tky;+BS#T?_b_mx*Kcu;!djNP=@l|`U^y5{@i3Z zvVkOgky0rbHntrX`aehK;YjuO|M9o$y6!da<>DHbdoS7Jnjz|5d+%gtXO>xrxYxzC zuf5A&NeD?Qbd4k-gwn^%NTO7<{Ct1^!h4=`p3m3g(UT^H)yr#f+IjxVD0nNm$R{NQ z>Y9D_Qaq=~?A=z*>us-(+JE+yxzN$lvj!?92}9u+77q%Vx(@F-Y`S_a2YRww`lNiS z#N)Yk2<MH^XDwm>{cd2{G5#P6%&(AvdoSX$L6T&afImn0`T#hj5guCjRp9anPq_1b zz^-WB6Hl;On#!G!)cgA_!f7pg0@K&RGvdEd`m0i?ViZ86>&l3c*!&?Q^fa1;$@;;8 zR>vL=rHCQ;EYYqOqtxPu=&w!Z<6|IrTfqSWPJc(LX>++eEldSuBs!VFPx7WuY8C6( z<dMx-q&;AjDg6ROg<C-70C~Xte34S{&Y{#yqYdjvnNuO33NQ_}_bN7b9ti$Vn(Sqi zRX*?_;4Mh<?c6<LkHCfj`<0*aA4050+-ADv%JlmeAYL*V_na=B(5X#|SIu5kc8)qR z=+(G5y3f_U%tx=q?iaUtfs%4~dD#eUGYuqIpC(U&ObW#38H5J2C7Pnx4Zgm}!B*0+ z3?;Ju_%qK7c;BKZQhD{LdMl1S7ZAbtHCZ1Fk%G=#VFARX)heBTYyCRhsrpy*kgfms z3y=sO9kLwgK#FB5R4uzMmk<oI;~-rvdFV!5-zq3_Wm4^#xy2T|#^(-UNPeaElfm7= z!<C`ZK{ZR;;EujCKiFKQL~f`=iH&4$<zHJ>C;+seJK?%4`ub%AF6$XPabU~W`kHL$ zIwC|AamfZ9Gh@vRjKV18LLss@tjw5l4)lpGN)buO6Ts}o6oMymWSW)j^xI^^#ABs* z;RK^DQ4wizkq7XTdtl}(w)k)*&Ygi)bt|@D_P=;$reX;v5U<g4d5j`5iyX}Zo;aH; zjKl(7q0;cAcqTQJM{*q0lPan-oSWL!<(Gr6De)~0P!pI**N4GWSnmUUt2257ykHh7 zP#h@1=DZJ>Af_*{ZlrJMgmf_ySB3fHn>sE)fN|9;aDGU1G`tv~NLg7h7r^?j+qApu zL>YLvPcn|PP#P+ZcOEMM-=SiQO0UL8W{Es3dXl<-D|~XCvUM~oH8%8Q6^AxecNz(~ z_Az`wX}}m)J@m4jM{;~_DZ83vL+rfANn?xyJQbj~%=$<N%w+UKq`oy1t6vDL`8V)* z-zE0Q)=p0K{n!a4-tYM;12pdYO=g2~KrFgM7H?y5U5-bx4`@)a>%?cSV5kuj)5s}~ zoCRE$5A;`+6GEci1rz;yBCH}HKA}vyn>q)2+&e6tr#4skK&};2yA=(_i^eEDD{#(o zJOABCbo@3`m(yh;<O)?Xp2u}uGQqEDukHEy3b#oTueIjmI<#`v9S2B~G-^wVyFM&M zK3#Hh({v+t>Ol6Gjo?2pX;PC3UTMymK0O-!8$BdYW=AY$bA-=Z*SR9P0Ilur{BX%j z8wHTMoDH)$M!Y<5)-m6f`(zfDzqDdn=V-kyI|z!|T?>O~E!%EQDU!kCm~2Hy{ilkW zZ!20o)}tI;#zF@SUA;ZnzEv97jZ`k8Yh}5FShvf=lx%pCW#n0N#tU)$B$s;J3uU8N zX|B>lm23l^5@8_B1CGA<CB^^=&33`6-tprM<lPpq9Uaa+P+S*d@^?mmtQ?Z^r#MH; z7!}G7CjD|1bA@PtPFOm6$jg<uOl70KG;)3nwk_-WA?!TR&v8dpRC(wD)j_=R4w8kQ z*u*+HC;(}i=i$;8jfIcMh7DS5r{q@sPH&X$)ENwF^pVpYkF~4IvDdFjW`49nbfDAF zgMRkSj^=?tg3O7KqL_c55^hGIL$8ol?NAwl(+$ZhTf)C|^!f(l;q=r`)G|(YmW3{H zbR<89d0&I-c<Ikc($oajGeeN0QPMUE8%yowk-N+))a!6g*s#K{7x0az#8Is?&`4_M zCWPP7vN55}D?1jhdp;6xxy_N+_imkqX<EmQolPmHq-vAJb1ZRvAGa<$s&D+wq-uzZ z%4<!X4taqTF{fh|Z{kd2yiTFu^i%))Wu>Cjd%l{sn6Y*)-Ns|Cr;6SgeEi(H(~ZN* zf7dY|!2N41I%Iah-3=l|um%!1V@n=1U(e+}#bybN`E4jtkMqQokyX*n9CsRPu3$Nv z3cn|u?B4<6UhP4`MJQvlczIn;6)Q*UbeF@+5C#FmdpOg22hN)dYi{^wR}@GsNGG;q z_FVVoaq_rI`h?x(rNy6e>67<y1RkT6C>$*kMuF<d1=tQN--jV<8JJ3%FM2sQG><+v zh|RSeAbjlY1Q{g;{>^sctG8_I`R)aK18wLZeEjIDjc&ysZ=!n??Sj)VhP%#|Gp=#M zMUmddR3Z?QA6E9oe6U#N2{iY7?zoJNnn_WTxJBIy8eXaP0b9vL#D2qt-QpKg2Ot7$ zPzpW=>hA(owgz#>-j3B0PjOb9ddYUZ%>wq-CNIElCpO*wWck6JtWKnxijL+OTCDYi z%pjby_Z$l!$iPB}Kl@nu=e$xs^SI6X)kTT}9L*QZ3wd!SXyQSt_i?S!tI{;goD9vU z^z{>`e8zkQC3D#vtcw*x^DTv3^*evEu~JY>G*b4XhTOXLTOO(lCzsK`(LAY?pmiJG zy4y_JVcH8vtgag|*vC(IwN$;vd^O)(LZ9a>WIot}N6vQc8PqvQbV0=_QeuhJ&wb{` z9s0!?a#yD1o|eo?U16Gb?7v9QxDsn_lhZuY*xk**0;gs+YJPNlASQCOm7<jungP+= z*G-V7R!Wy#B$dkdgzLOK1z5T?nsLoTh92C0)3VC*_TvyFr=8%S;-{m_iP||lk(A4U z03yntF@#pAas2w0o5hf$O+*lpBj*Fzy*G`=_(k5O!KZb_17oh9)W2hr@J|_P=RSk_ z1>!1m<nL;R1^!Ba$Z`=J-}J8XG^MHCIuJ%4(<_)1XNVbP?Hm#vIcGLEKgD)n;**c= z@xjE}i9VAbO^zN-28Xhxo;6AJOvc`n8@;Jjqbsa=|D9?tG;1`IRxjm>+4N<39Cw`R zr9HF+B+zloa<oHXPbmveXhY5JHaVg6DbSc|Uahk@4Z=Y6HtLC}TQpTgdKVDYHT3Nk z!kMvO2(TI+4h=+PJLgs^TEd-ojlZ&g;a!MiXm3-^ef)G>tBPrj7I*T?rMm8PDGk~# z|C;<^EHmae-!$v0q5mVl@YlXYeYKjBjczndv_jgcBcaoQ>xcBfz#Dt%$Io8NLlllx zmO<FaTMX_yiJhipfK?B1S)OKhiQdFC@R(_RMd3;KWz0#xp)#e4jpWMLqI4EIs-Uyk z0eSe>Pg{d*pl-=}dEK@^q9AE9<M=|fpD+1_qHdIMtP7<(4kGjSVpYLy0%nnzFatlP zaFy8gDpGcd0(O2&#AV@Q*#)Be%Y4GZ(*tMyc|L&V1Y^<rDklQ8n0~_w9kzqN^MIH1 zUG^gHu+KqXZ@s@?H%{TF|M9u#gmFvOVEGgRXLh8J#NIInpNzZyskF?PSJPXmFvtGW zxYX2X#i~d-Ar2GE`2lxl;yT7wB^wXux*t=rPQ6lkmHL0E+~%%KEPAwv%sC@{oEVuP zM8+%&FQW90)l<z%EKNokd|zeeH<1MT^!EAn_)rv>0N85dH4(})s7Swoq@T0_&r1mF zZBAwH(Ex@3I&#%UPO?upT{zV3-pJsa-~qsbNiS?!uw!G^V`W|c$u&=WikfGBVZlvi z#COow+bLm0XC48zv=WgCjT!wv)-u(G*Jq*lpxMk_7Ta<`K_vv>&Yt5+@zhRQs5L*f zqtyGP|4MNG(oX+SytKeWu|)qDCv`__k3zIMskRln*r#WqKIN{T4-2ZOE?$8##;uID z>6Kwk@S4=m5vXgA?l|SRjG3qXN}6Bcr{hhisi9n@{zgjn&pi$oBW59}e@op6Cy+Eo zRjsmG!&P5vi3m>DgM#PU1a%|U^ikYm>SUxg?~_>!b9YgGWzGBjcet_F=WZ_(#qJRB z3<IvrWC}BkAOtw{gD0nm-pLn$+8_@eAR!sWRWn)+uNO)?lT_~dhj({*Rad}fHPWh1 zwwCy(T2_a;?o-<-_x9hhlOzM?vVhg~=yxim!mazoCejr*m=+!xo6oxFaWnMKz$iBJ zwfY2d9hze3S4oiMzgeZ%UFoIy>qPI_K|Vp~%p(HH1_an@)@dtI4&{;({K4guy7mD+ zK^s#9q@D=B9tGxAc3kPWs_#6Q<=lA2x#vzbzH0QC8!s>6np|)hRYO4|(=JjzX4<GY z2y!6Yue9VE&zWq)d=;XQ9^GPG#zV#kRv<zrX4peNzo>3w-NK3D%QEsVw&FNy858qy z{v!CCK%MA^Y^}7p@>u>QelRHx5}dXW#k<a3Nb6YA$33y&QuE&FyAz5NPLvgMla)xR z{?DObXfVVCnLK9DTg~Gs9BEHa&#|%lBlN9rOS;0_{hv-$+G#nGOa2cFjdY1<XKv<3 ziMbBC$wH}pw5i`$MjSs8w2N}TqO)+zO%IhiP-sU-X;%{)EA9H1tce`DLR;UN2rP8n z3xB-Gi-_CMoYzpyxnsJ%iP+0+eZAfdZR^JJC;k;u5-A_INA#h03X6#wyoUCp|4Qye z9P9ZI?1)jf(}z=}2cX}A-hDIja-VA?u7f;U*L$!zL1MmYgWkp$^(3H8!J{j|W~Fun zUfq_r>H%~OO)1+p(E?!#(q*7{ozisgBhh75e-y3jaEB<?e^=451ZQ=A*;s)-cKiJ# zFC<OOpAJ=Yvz?LBbsKj?7S+xVIee4~zs|C!cUwQ#Z_5Sz@#1FS46WK;Z_<^{&^`Sv z${BAKpdjlfcYHFIr3r5M1;+DGVgx92$Zb2xCd+w=Q(P(Z>xVoRJsb#V`GKq;+-YT@ zpX@gi_iKtk1Q4{Ju`SV#JrKQ-DD7L8I7GWt<(RZQQhB)C5IbH`&zyX5@|tfWXF%ZX zTa2$hrabf=-Sg%$oxhl7lJw|Txjqted1y-}P9if|Vp=ZA^n6mIFvUBW)70G^0+G!V zHXLv=j?Hu(bfWy}5w*D$oFJd1R>3Ris>hbad_kB3>J#V+IWuC<@svIWxLvxlaC-dC zGDw?$IoMLs<1(ygGm1_dmzQ|;Rlh8GXiuH#PEMea{LpI~q#f1Z@<Q>HynCHf4PkQn zja)D>>SV`r=abhQ)~>&SVDvdRfO3nMGAAD7cYCQY;<Mkadj$dXMIO5UfNP+Do(-wQ zK#~AD9Xvcj13jPL?U`P%gDwvl-lelC4dTYzDb7RNDdt1Vpf%W3(B9T(>W=J-G?_cI zsX%q$WI=7~!Q|ydmR9_7>y}BDZ$NNtD*?LQPQ9vM%(t*57E{8$_o`vfHTVm9cTRqn zNE4s0W(6p`rr-hA)&A%9VAej<KFXT_M<3!Jd1QuvJMaCC{o<1CdL5pOu%slgBUtVq zx68!B8tm$KwX!qpUdX5Tq#2i2QZs4MV!HU&D$OL+tqlhG*T+{cp{HuS<{;aJtv;X= z!dv4)BJ`8~X~g7PNW`pKr1~y0S=__5S*nZdDN*PavH-kzX$cKF;sM6%A#Y)qR*g1Y zHZ|L~p?ClL??cn!c_zXc30psz_+l&lr~4Flu1<}&L~oCMZ{YzytX-5a>g%{ZY526F z5nv=r>`CtHy>Ae5H9IOme?5>WnN*A3Cc2{m_e#^ISKhM{J1iS{;+}vq<q!Oh=tT3Q z^&)QfZT-FqL66nL&?d`2d*7B`^1m~_*p?Vbku@#eJ$KQ&;`9U-KNfiO*%n+g4#L7& z>^@vo;1RAd09$&F7QP=$6K#OFm%5qovVVLE`D3pq#I<l%ST6?|+6kl>04KOBi%4hy zMLH27qa3tsM7*U+^xJ;T;%j>Y(BEUB5h#WUFpBL(*$<H$3Y#x~>L>Q`zAk<GekC&r zmi}Jo_i7AVYw45r(t-WI3}4ya>|c@^PRSTm`iQs3d<~@K`5|5Ju~7msrCDdd_03h; zw*odn{l?n9bFr^Al_`?h9RxV2YyXSZxdZN-h(S>QoB$>N7Q-%xP%v17^zQPX=x9>i zNC2S#q&_{)Gv4~WZUghVWsuB<uP!Mo34Xinm2JJ)H$Atz4>TXx*(t!eOpuGRB0mpQ zxlLXufls2vB;^byREIy7OyBW`7_*>FDG>grGFeL>iBLq=vZUSqiKHo;RL(REd+NBb zMRYkJxHrr03Q!uBz9CJ&KXX)l<gI!^m*J8i<<e#P4ZkKvL2xngy#p(l>F2nksL}a9 zy4pg|FVYR|gOVge#Y(M5>l4`2y&KUZKGeVB-^DZBYA$mMk6-5V(qaF>d~;s{+ue+Z zR4*DEJfVgtTTb2D%z{zs?AN0I_|34T6Qh1GoxXjUU;jPL7jd)B3(3iw{Wfr3^^?i> zPfnD-07voo_23IkhdiBYr-dFpAzkN|&maPX^F~Z@Vm8A#UyN{S`RNAknydk>VP;~i zsk~zr(#|9Q%F|?})lon8ta#*oo&ac-xIy&u460WCfu6kgw-flyY=cSlY=1j>-F=5Q z8cCjG!x}#i;a4($#%3DOuMj(txIZ^6bHn0RH}ls82eK;oG*sVONcHC+Yywn+Ux&qn z*owzE0(JL@eNLc^0|s#aO-WkH+vIXt&MkhW7lpDeoGh$GaD2Cm9L`E7;B1QL7uZ3U ze%j%S<h$Xl(p9at%~WX2h5W7(E|rWJw~G|q&E(fxrLD%@?}x|EGJeb$yJ72~<YlpJ zGkML{FM0tJ>ia{}pY<p-2odn@HnIFTR==rKA*n39OAOQ>>`bR9Go8P_N^G+a5lJ9K z<v5-^vMo*&U}Z~_{lfgMGU~3Q<5uu(w;Pe4Ue@F>t%RN2Rk<9a`t5+S9gL~T7(o7D zjqWuu%}>qGwYAGfHUDZZ8h$-)qJBco9RKNa<?0)44O6?!8gq?~SaOVsZy_J--`9sk zS)C%rsF0Q&8wdLV%^`lhCWAlb%T(Ac?E#w(Jw!wbr%IcCt#KcPxp?82m~mhib~89O zNS<oIQ93GuUaJz>s|#uD6`kzeZ2vAStd-d~vczvIS;PLA<~3^OmC$QH4)=P?*2Jne zu|9coa{kgk*1LjzX0~cs=-@szCi**LntSYDUP`NFaDoV3L`mxDtX%^SrTsPEe|D;- zL6N<aHI}1&c7KXU9rmceC<gb(qrdxX{aSPrg#|ZHT>j0Lk7DBNxBcI2vM%dru8j5Q zn~YMQuEtd!+4z0%WP9BlqW#+Ol8<*%|1#U&m(;y4Pj$Jq1{$7Z^xT-5?vzcE@URHe zILm$-o77kz>wAM*mFH%8D6`s0qn1xGZiP>YOdW4H{U=(Bi=6`8=mJtttyek>#w+i; z-63EI>+y=`GNd-nF`eIKRFkD&A2wt^PR+V=o&dnrX{V(IW<)ZpA?^Rk<6Ngd8$rE9 zfaBI(sKwgDU>?|2?xxIIHDICJ=Or%!P)nX|?h=AN5Kt`x8X0KfAy+K@FT@*gOCz1E zYhKaRoRcFQZ5zh2h}voeJBl9mNj|dzW+x8#`vVC{e^t9L-FE@MW}!2=^A2<e!=8F> zu@uOVYoXNw)S@%>X0oE1VNp;#Q9JSwXtZVS7aGahV58Woukww7D_nSuzyvs19YXd! zTJ?aDd0Cj}YfB;n-`;n8#v*RDpai^v?g?#u73(elI)fQ8F3W~%NG9@g>OL-Lo|{4D zY@^khAq~Tv_MSI(<66H=G;7B3q;GT?VTuv0IV0IwyO$>&sVUMt(`<V`VCmOvpo6<t zywuAUmyj1p{aqm?K5`G21K4?NglE#RR=^ScQ3^O*u05IeCYw^SxL_mu7#*|5`VzcK zP9Icylkor(3pF>`6b32{$Q&n<gi4gc?$n5g;9`RiiNa9X{VwdeF{Y@GTe4?G=X6Xl zO|!XCbW7kXWHhxjJ*!6gZiLa}&lFRClLC3cYxTwBG78#<b6)qKyelPTHysr=ne#X8 z)<|FYd$?vP3oxlnTDidWBMMIii!ZT{ARXygD0A*4mX*Qb^9UPE#~VXr(KV~&5Md-_ zjp7(FdL#qNXhyOX*j=C8iZWuEr$*%%0(xr~mATHlHx3KJrV+p?u~Je5Qxe>*`pz%W zzS2)%^`7zaScVNIv(U>zBcm;X7f2eE8?Tg3`qWsZXwC(FH8{vvDG=mBHg+psjQD2m zUkwX*@*}rP`Fwrp31}IWSjR<`PGpwm0#caJD*YX7s(5RCZtu=}m(&YQ<&9w=4IB$I zXoK5KaFC8Q5+GA-0ioz)ECE_w;tOz{3u@QY3i7)+HwxEfBYP%6SpcQLcDyUY*1)B= zMu2-FyRc1vl_=1E#WD2JUTIY~hd9+KK&1D_3n}eEj+(0_+>P&jC2Y#-(x*9;msXR# z&c1s&c=v|e&4X7(rE!U+*Bg^VbZyR)Si0{$Z9-*f1(DNso1e7-M@#?%L*r3@x~f~} z+LS9|0SmQ$h6M8D=qlU=avqXgfH=S350b;vkmq#xyOJv-P@UP$<Z0mRR;_~9;<lS> zP45ng;{>Qo0D+I{MPmLOINkI;K~M!;$QtwA^vE~C#y41h`@KsW4UWf!mAGzc95v~k zeY`sS{&CyhR^1J^AU`fbzzkU87sy1HW0O|RCKhVUZxk$U2p@H<^8lq5$E%Dynh1si zsWw(yz6WXWtUaDO8CO?vpQaQCKkm{oy7)gFynvm~_24dA*ISLI52f4Q`C6rW2&Y#_ z)hmKZp8Gg4C9DplVI@lo2mz|6Q`eaovjii=>Cih`^&VDLG6N?01^~neF^nE;z+t<# zs*-8AelG6<ChXqtSD~0q9V6Y|8PVf`j~JvP$3vamvr1L9=l-)cKKa8(U?^=!NW6LS zhA<2<JZ0`<r$K~)3?$E}>bf*X$*W6$7&A!uJ{Vp>qti;Hq(LezLR=ONY>`<UcQ%MX zrJb%7B*Baxk_>+2;STxQf#!moPViF|nROnN!$PV0LZb-LTs@$Xh`Em&oun34C%<O_ zM#6Kx_Rhnnp%f;LDFDC&2{5xtEQ|mURr<4TwdCBM*k)Gq)`goI(1UzI<7fAd;6I;a zpZO~K_F=j0*-unGGf`}o5I<SGz?(5A&1KyjqSM1T7-|78c}@6=EEqMO^x%mt-sr~_ zj%#}p1C9k`&JHVHnm$wbpydo;H%~J!mo4huJrn3TM-!f4gC{^&txw{9K2G_QfeCha zE&$dsC(%|)IisryJyLLK>C7{acFZ!$hv5oYz8ERYsWT&FBBJ>lR%6;jdu6fo7F{=- zZK1(peTZw%OzPZw6K7!sWvc<5lsL#zjc>~u;xk_F+|9qQ@)uRDUkG<p^L}@;Kz+^o z*5|Lywk<h;f6+6dNVh}?Q7>7g4HSg!=QH|G5-?28CA}T;Y6WNNj0X6gws6>LqoLxS zo2KM-4nSVihy$$yB_X>SiFO$iyl+ICG{I%;kEDT~XcbAxS81+H4T0ln_M}>FRr+8~ zJ8;@VSQTyk%#@+w6d-0KZfxE{bT0Tsos92gzxCOR8b1<wGM@tEV*H(Dy$qG$`6{*N z^6G+4{J0dThhjCvl}jqT#j>OsDaT0@AtQc1n?~B4bbXzWq~b#j(%~xhex|9e8_d*U zdb+#urqxwqju*=*d-H-Te=^M!P6Rwh$5o|ms!Zw2){y2mLR3}fJXaFt{$s>}bVg59 zm3y7)6E#o*ieE_^z+iy-@Gm6=1)T9hL26TB)MKac@|_v;XRd;hdO)h$I@Bik_~x`R zYS;Y*F3g;5VAm|)&O`k>s{rcuda$JbC7PO#W$AmdTW!<u)=CsmZ5OKdVGy3BT1&|( zZ6|p9zjXY_JEE!Pm?TSw@$0M?fv{I~udBoLP7dLAWK>vA*-dY(&d-ee9ACS;u#Fv# zT0dYEgyawF6o=N1!5=9(2o7qEsb^!|yBCX>1hi!X*k5h<Dx8~}{`kVb_zYL_Xz0!r zbU$x$KUbAVylB|`W1bO{c)fj$C0TqA8dFWJz2x?ZHAnYKzC@0g$;}--8t3J&xt8sR zaV9N1V^tAq()UgQio3j|o+In_Oe2cJQovkAOH#RC)n(67n(<6b4}X|mYh)%>clZ5U z%6?Z)X27u6xd)0(HnX~wi|Z2S#Oy67YW9I$vn0FUSSNaz!-Y4ru)>cjV1`q;0RPo( zxxV*)ABF=9h@oRW=WsZNyx#7JFN2htlL-=X-IISzo{2eD@F`Y3DvCR5jOH2yP~TWD zuL)~vBs!(Ov^A2uhc{zv_GtQ^O*o%bI9J?<Z}jTA8~rP_@R<<M#y!d&$P6pou)vo) z(K#+ZgI0X`1Ap4B-IjREu3R;5Yv8vdSH&V+(r~?(gZP0^=pIaRam6h1j;cH2CsKlr zqd}pciWz9JKMI$g{G}O^7KISw%~Ik)@kYJ8i-?uUd$+^Z&R#ya;V!`-q#l1`KNoyW zq2C>e*D3L~-Vr;WK@qU>;H|}e_FD_xeeS-mdqIVL=%45}%xa>hBu@Pc7Dq2s35krz z*l^ln^zbW^9T>q3egupD@Vxf+#P7?GTYJ7)J9v&nY9$O;9DvE^z)_MHAfEQOKV!4* zWAhWRolu~S9p~1cUY&iWC-dGSj3L7(28@x|BK=-Xdoo@nH>l7lfLrk<f0!|>0#g63 zn#3Jm!ARrcE4}Y0Coccl``5d_++(!@{es1hOXAJ=8;L^GSNWSg;PVOWIv%J}2J%iK zgE5PYbP85o4&=zlw@zM{7j001AL?;}o&AdN3_Y?Q-2R5wvrI9b5T?u5egxeAaf@R< z1o9#`4eJZX<#H^rh}zrNGV_zmdRU-Ir*+z^nBg=`F0EXM95DK_4}#l8t@<|7Zuc?+ z|5i|#gI8Z!ri2IEPgus)x$b_LX*6BtG#RI{jfh>Fnfxct64yNRXElVQVM79nbH}}c ze@H+y6ZuUB;C)rd)n#4?g1r8+bFe<lL|R5(GSOiSyUGffj8fz$<;PpF1QODyUPtzT zQPG;)E9D~&%Vqx>;UeyP)dK1N8tL5DSon$Q=9Mc>2)&G~i$RmvWKJNhp0#ru+ri=w z#T|ojP*G1lDX&is<cdWpLpmEUF3rET!{V4hMtKHBts1`HW32;Mj$d`AdP#q~LbJgw zL*<t-tII;GLJ}Eg(r}-T5;#o;*o_zjRY=0uh^*jHOC*GWzdEl2Coh+cFiyozdxAuU zu)H?2Cnm`lt+oxNGho9IZn>)KzMHsf4LvHkqUX4nE`~70-NU-UA#sMvS;5=Wz!=$g z0a|^OVTq}i`wam}V09!|y*?##-G-1Ws8bd6afk72$ugfnwl6$dnQAOw&PXPnn;YtH zeU9CkQ0-q=tp~H;%cY6G#9{)@c2CMkn4v|g`O63RDgA<d13W+a1+QY^Dp(Gc0l{kA zXK^DB>beI;$4b*YTpWU9nFe92734Os{5rPwUPVd+cusCbMI|ob6`ZTDsD=%aZ$&g6 zR)X>@F;VJ8;m)`sfXaYgwLFa3x@vczN?F2=*#m4E4HI*KwR?b_FvhspVx9(%pO9@Z zTwW~xwm17Yt;MWXV!`b3Z=~9-m75a<Ut1aqHn(>_Z!gRn06yz1XPg<AaR0|C@gac| z<-vN@1C?8cyjmrYg|(DsU&D-em^6D}XjY(FLwPH%v+xEXvbTy4#)Zm#HuNLXR`H_c zcOhk@H5@PsRYF8Of($Atd{YVt!K7U|l1AeE5I`%y(qZav@J5^g18x6^wfd$j<@M4a z0^`QbkiZ3SU;rC;mf#2afp3hJm{HwGV_|l+#)G}1ooqWE6YARM<<?tnJpbAl#k$)K zUr@w`y@fU!H7fGXI<84nR*5%~mcV56&vo9h4rHf?WvPcmp{Mk(_46mdhKL47;^?Zp zOdFOZcikZK%%SH)amqu`n+=x<1<9}r5>@65NG@Rp3l9jOH)VT0OI0rkV_~C&^Xzr= zNyStzKqE2LP-Q)CoB&U{${N&hP(@yJmz*23IAr_iqsSH!<y+NCzw(@}P+e-vzV=!Z zwaP{czxcrCT9{qDFAu)k`Wp0wS-!2zeIFs1j`=E6h(NUw8YGDHU{Plf<Z7s4QxIq) z3evGbwM<T55*bdsoi;m6VM#;MAM<tC@x7`xRwNz=kB3V8@<O=}30RzmB)9SuegO&0 zT>PH)$#v!XcTIh_FP*;m#`*;rRMeWCgQwnA8peqWXl7M8VN`Qx#woWLS)&KtnL(;| zl9l?6Y^)Pu{A3UQ)eKD@&$#vXE?7R#d@TqFjUH@o4inV<5q^;;0=?>eIWfGzwj()T zD7s5#4SpX7@_X_|a24QdUU^RauJ%KZKZNnDq#PMP;hx_u(;R69_9jfPdUmLKd8Sc% zXDL7e%ASFXO5(O#84i%zkemusv^M|w#{4ahg{x(7G!&r1@Gfoh>(?<tNIg57qsDYq z-><y)x3J}3l(;ToRNO=3I<T^;lF9{44t8M``sxlXdBQqpIX+MNhGSyC?cs3hh?jr0 z2HCJZXD!J-w$-!`OmTf)iH_Bgk%PY5GVo*)`eYuX#VI~5ef9bI7PU$yd1hRYq-0de zL;uX5R$7u?`9;yrO%Xaoo<%J69SMo_KwkYcY?l?;$rnUo1$uwtm{xCk`HC{>#70x` zV-JJ5k#VA)ahIkoMF*7`p7S<v@WIF-54S>`b^D;6@y9=Hn8-0y(VO5So!(86{S}nk z3ZL(Dx`0mjU8d@%?FI^Z!G2xX1l#-aQ9g+gMrGkzgd?{AHHyA^4f*@IHFwV2b^?XO zB<x_4<6r{1T3)oxN{cxn!hxcflH!`mV?{zat#I~`cn;ms?+4I}Bp&sZZ>NOk=&`_o zIc%kaV)`d@wDOM#qfIa_T@b{7Q!MpFECSQWqPF@_oUcoTY0!PD7+R+A3FoQG&<{p- z<42)ccZ?l(dJMZQiJlIt^+S`jidv<$iAzIf>#zU*foeDw2!8ske((ryR(;N4ZlJjK zY&qkpTSSw=akX$jPz9@n{(N0zP;IYS74+3fd&E=zbbKbY;L4|fk`;ca2Tw7H!-k0N z#qv0j<j>#NaTxX{;BDOueS9T*s?~4cr{`9YKb8wD3Q9^UydY2JuU?~FZqV?ne}r#M zDD(ZQ)Lmj&+;B_Ovm6Z?Piv1qrDC}y2>-xV#CsdD9FfE<a=UYdl2j`HO2z%qh&VC& z>o=ncipgOX@Ld`@Tm0tS;WgG1#65w*0kN^?H!DL)G>?Sj6#-4hRdI_ue!8^=3)z;e zfYo@ic0(e8nG)5L637Y+V|lJFAY%vkw)**;Jj_H^3T-_E)T<DLDsJz4hbFJ<uS{GI zOX;ac{m{#a-Q+3hR42Y_Om_|K&4&Wxn5J{K86vo}+R7#-oe<_5%F{>6=k0!tjcEw| z^kO1sJy}$p|Mc7-@~rZWKQXFVZAo5+Z=YIyH$-V9ezB}(*;d79NVE}AA1k?eQ6%vf z*G(^eK3~!<wT4>ExM0(q&&)ORL&@6;3Pdr)q*kGGu~a#qqPP{#;VMBhEWc4zm(RVT z7^&-A+_(&xU~C>T9*R3rqq~{A#2sAJE0^s#L0Wm$vAUP5I#FQY8@dd-&DbvNaI}pm z*<<P@byDMTg%__*YaXtVe^hg7H%Z32oAmPC)8=W73BA?_T$778BSmz~!>R?!SI{B? zg1PS_*{@)<`01UKSodP3^V?yl(0;?#b@yGYUNW~Yu`?Ara!BS@U*R{yazzdBnURp1 zB&^#Nj6fAaxC&8y6qJ&Vow5IMJ@`k&Z{Hxu6_@Af!B)*`4~FU<sRq=Q!Ul&G#73|> z_b7FtzkiN&l?oSHk9vs8_2`_Pl^-8U)OaZ_NM4g}@3X%&o6V&W{39qn!d1-T#uM9z zt!H-Q&-XYy8GxUtV1;{a1*<)({$4}N_@9^Tea7DN7+dE5NqXI>rEB>ch+ju%pUf>> zj*KPp<_-wh3<#XZe)RS$62@}pRt@A~r>?Ohf1;IqzKCYN@J+Db{7|Ti=hm4eG}p^C zF%4d>sIx|cRO@~z&869#^1EB__q(9g8tdwW3~oqqyii@E?FqbnsC)0gz`m(N>Se9{ z@iuwD`blKurMTxyWB1PlJ)O&|6JA*6U9CjYtM;4Gxqhzg?SGSwe`AFnzgy_b*Ogb` z_mp$Vc<+%O;L~C=dRT8{Fh>~RGw@it@gfOT&FwxQuzb2`cz1eDeT1}wMe{ae*tbeq zubTEfB=zA><}fSI)vcI8;uW8_apb#Z53I3Iv22%a4$8+&%Eah^AD_K_=Br0**a}Yw zDSOKH>7ny@T$huIeTUiVw`io{w`khCEJN5fxr@Y}ICq8+|E1bmYxmdkjvzqu5Y%Bn z>W~t0JGRiPTkYDPr~fGRt#<18%bu6psrkpR|7v}!8tVsB=#Mn}Ue0|z6=Qad%ie?M zpF7WaBBz-Lk8qVMqbP!lh(KZyIJ8*k>(K~K$mf6M*lKns{q2O`rAKb|5KpT(nrb({ z5ikf&AOU!IEKtcXki^UZNVee#EHS|ThBH;MW;pYI<Z<eO2+@v_#KeeUTkA-gR<jp8 zIr>^R9HbKH`vwARss+CT4tHTnYu#14+W*Fl@$b~?Op4_1HL<_zzV@MSs@deFkXjJX z=JVXaTu{|#^(j|=Q@cQy-(qLUE0mnmBuR!r_Hp{91tlNhY}h$9{KjA&KxSf0M$O+J zdZM*jnk2J!H}k$UXGGH2MFX2g^}Mh1sd)xwfYI3iZ}!5+-hi-2M82YRwKc{4jOol3 zM71tCh7|<XQpaf1zXN!SHjV_%@O;MNH|?1Qs;n>UPH?_gN5mNm{7xp?={kub2z5%2 z72yHtU;pEH&UnnE+cS%Luo<726Yx84u|)%JX@+JJwj%g@S0-4nt52GrgGHU>sa<4$ z@KWou3-q<t<DfNmrK@s!uhi;LT!vEbsEoGpC~IAIAWZIX^=8zoV!m6k{x@<xG{w8; z6`rVcTX}<FFn(fQXoQ$SDf^6Lo=6;dO1y-PlIovrwwA6sXEqHL1N5eIMC)sF7lml> zFzB@>u#x)EQIB;Y;$)~88VIyXu@>;{yTN2+3M{)?Y12m#(ZVG^tqj88V}3P4e|0(W zr5m1H#3O$RTU8gI!`XP_6$*m%A3g@zsI2W{>wGp^IYV=<MQKdy%eZp3W~+d%ndTn` z_c^uEKI^ozZb7}D3}pk5e6cDYm=cuE21GO&46gg3vVo(<oKp{^+6k+HaSSUVw^;6x zRo?AjFbiPC)oJ{=)=_CvtkB`>=&82|l29agW_47$srED`i_aiaF^u<Kh=*MBoN+Ns z52HvJ+&nek#hR-t!nv1TsWuuaB<KxBiJWo&z_3-toB%uA4bQ2O=T74Uc6&hlw8Ha( zGq<Gw8QL0X9n+Ud`%>!elYL*u!qq-_zsXcwYy4)R>EPk>`rKTG?JG4U>*vyf2k!?B zE>0jHuNun9f!S5U<sS20p1NiD*@OE1Xe~R76u7Qa7`^Uz1zaasXHa7H2wt2g3pQRA z8h|87#XIDUi3}sBnXv$>ylrskiN;7dSletfLMVq+aox(Ba?(C5IC6<G3Y%C92gJ_h zOOEZZ&wPE^`<QRy%A-S_dBVstn@#$as-cV1+6spcY|m>yTehCo%|;qde3_AYZ4>+^ z;@&z%8L9Nr4}DAZM}*hdIi*njSAy5_w@xd{g`cfEC`y5RKmuC%&y6=bl4pnT^?Z*2 z!cwOy{3-)LLLbi={2J!ZYzf4aVT{D_p~PwUddTI|%mLYuqpyxLuR$@%+E@>sN9~4{ z2u^&|Y)F}izKRJ4DhzfylQo+dEd3j^P|^l8h5i&+ywfNGVgn|_JurGu5TKcynAABT zD%(H$3F6t9g#oMu+E@0TqVi+^h@$eO$8~<CAi7S58bxR4Eq?@ssbu`g@H?04HnmF~ zIcM|wf=Z~VYF}uUb-yn9!+i3k*dd7Z?tq}eRH@puV%Ak5s=(@gvS9Nnj)$Q?YSFl? zqqOdVPoEtA7k7q1V?i;AZ89P96B8pdnZPXIe~nY6=)X?oo@qb4=r7Rey(r4jN9rKx zvUC={T#Z#WJ&t%NBO0oxD{u?U0d{00{+M~52|dt$&ycXA)u9Kd9HcU);&@bZK_qvv zbfJaSXtfSb{MZ}O|MmW?6iZzG;6&+(2rAT5%Ut{(QP5x5aw}?t^3mEacGpX-!yxOT zgO~6}cW<?BPYzu_GCBjEq<<{RezUmx1l3zTTpy8?p_Utrx$=&xvb)*Xn=ow<ZVdAP zN%jx1)h000jdBhRN<t#nmA6>N@;~q>aD+`J3L&sW?{Fx9Sq<Yib_hMy4%!wEa@GU= z)vN1>0DEQ8m@z2)zeL4sp`27f#Vdx*#W@imf|f`z>kE^@#=}uPv2VLF20uKqUh6?n ze_TdmT=EeXVPT@q2X+mbIE-!FX1m~&o9ZAo)4M-WXgvyM-o46x{{5g}A_`(<F~)8? z?-j&q-IP{4Wzz%q&dlVh+kekU0QMUV8QUEVsI~XTB1}a)$Jq?1JGEcnS26pbezC$d zbus}|oPK0vr^pN}d%sP3d7_vsvV~9kBEa0jiU>4pfhDBY6=A%ORvgbwOU(F)SsB=Q zI$r?2&6?@Lh*+PBHd1qTK$si1K7Z1$B&9k2$!bG8W-r1`X@$apSmy(iO8})){Z>Qt z4ELf9!87k3KtK<x8)^#2<fW6Zqi)V8POA*vDWZy^UoQ`<O?+JZ(vs5+j&3tKuhfTm zE@AlC^^AcVf4*p{jIx*q7r5-tLy{Rj1nj>T4pW^?YJopygk=dQD>L8w$iVAZ!5w`e zOoB$cDt~YWiY%wucj0nGuMUl})))VmjoM-0o`=2wfaN4)m58ED2<fv%3GQMV=CxC5 zqAG4>h@*CpC%NV%nO!@t)J{}z+hIuk!$D?CQcru;2bFm0P(g5rmw>f#j)B-KL@}s; z#P1vR!PP*ildAQ4{U13?>eYlN?0nZY1pb%tv}Pq#lWPV>SNbW4I0jqMj*<Yot`@{+ z-YXo#Il63$t3w%`#Fja|`&yO{Y1hIsFjwypD`2^snY(Ax<K{;1Fly5P2ZHcl48A_H zD7(0X@y>I#4Z>BiHw$5Ub*QQcucDuY@m}i>is}rMh8Yqff_}-kRUIZtn6Hr3*U-aw z|BOq`UPa%zo#J68_njAVMzxYLO9DS+`IO`(MFkf&$(G@)MF>CU2cje6KSI-NnYCv; zwx?nzbOui{pOcEumCZ3EL>e*EgXP6ogT<*x2>B|YLR>-_uNr>1mlGA}{egK~Sx3c2 zDWAa!fYMs%H*O&Op+B4k@amG^&eE8_6=!l-3KJF0Tax@11$T^wHFk4sberc_9uE%x z8s(k#$BUxXCyauye~$;QthWiY%T=-I(&+1*1y6mJ$Ky;~oIdusXgxav01`e~@V!lN zDrK@nz%@Vu^v?Ce=*Pm=^7X(5i|YZ;1?sbMezZD@x}c1Bd8faVYP-q=Pl>4IJ+$jJ zXdvJ<^d0lp9}m6g714EHm!3hJ9A#6_$K5eiIe#bTAM$B?(bIE7FRa;K5R9rJnBRu7 z_~aABL?t^N&;A9&uE=2Zg%~J^wT0a<==~P<v<`8Bi7O9lit;eki@Zs+CcflRU_7{q zR)J?#D*RT8B_4>Iq{O}q^$l-_T){v-b|c=Lh0iiy_GpMZWi#o|AoTDS=sd*QrCW?1 zpok=W{;FH71GktkH%_O47JlB6_p-FAw;Tu$fl4@|4x;}~8Q|u4{=DUJoaY^N=UAe# zeF37K9%wb#dq@{Vc{;GKVmOBPIVP6b*d#1#8xS&Blll=v%?u)3neeO|&a{pYk+d7C z54RL2;~M3G{vh%L(<dXTf>UHvjt@9ASdanAN{Ve5#lJa>ZG*G60jyW7BKZ*~>EM+_ zz$%?Fl<6`v&>N-sj+x8%3T3$gZCb2kF?tz=NCGP+g)swMQ=G8{Neap#=TzYoMUz?y zs_Y8F**f{^4B`gVV4lE1$0RJb`ImOY2ZO2iApobkSL{}bLa16>9lH7~pG*;gT8yYi z60}zX1-5MOdxyv9nyNE%)ndp!n}}CT3X@4>VLG{AB^bcC@2!Y89-$|gnIo2&PjZ=k z2+TV}ZhJg>oqlmWQAvyg=^+O2oo;)d5qsh?<H|#X?K;973T!@vzfgzU8=d>X%Q4k+ z?(&q}GcSW*&;1y&)bq*lhc#Kg#Zlpsp)M=zb2PRem7!abp1AsxtSxF-8JK&om}9t- zV|G8KZJ0}rnElw6T9qGoE!sqq2$!g$rbB7EUu}DURJyMV#^Gim6i8S=)V8Oh7{sNH z5Odcx^e?5M5Q#5|iAskW8<D!Fl+;)GEF#9tKnP@k?&g$&cu38ahFwQhX?_R=9~L0i zRPv1d^1?}Zn$d9n9DtE@O$TOhOyeA(x%afW*EQsW5Bz8!xm=?IO2iAk%^2W(*njME zar`WIImj0pFjm5{o1IFg`;7znli48#zj_b@dA27<2qWH`Iiq63!(u{JG?r9^cn@)c zCt^`CtuGWmd>YG!rYX&6tcYK=X@E2>GjA<(;P_8O9yKCD)h?q~^zNl1)ZOz$)`WM# zzz*LzU^(yeL&U%2vSkLT)L|1rQZ_fr<CxED_)(VefE9*0>!6A~{*Y~$#^LzLpXYj* zYe{t(nB=#@_TG#AKMco@Q5%I>ug=0u;*?siZqb_K*>HplqXzsY%qOk}vA2C2MS|^n z`eb<q*NpmzR0+Mp)=#e7;rB2PATUSlD|q7-eJkCxju18pl~;#zJq@o5wd<`#Tm~PM zvgUxI#f61du7@!D2`pA!rgOl+02AH)VG`A_S!CEhSt!){Ka|M(Vvd^0^4VpqhGNsb zr0N7HiFJi-p)Ft=Q!BesvCn`?g5E|WPP8c2MfkT=Lp7QzGqBE8$6VrKE?$gQRKGar zA|dH2te9hy1bv(%{)7n6gw>mk+(CJ``ASCyx<f9$E%~Gh4`JcD{4kfL7oo5n2TWEn zk|-O82&uN~=z+YSKj7n0jnl>QG(`vSR9J!siREnVVxxmZnpPomSlVXjonL6iyX+Io z>`U(K%1-RdRxEC9tRE7*{5;BsaQ<9BQpA$kC8rVZr2=Wc5HdL-)U6vU#&SvRG3IHA ztR8|;W23+dORuKg3wt{O>={&q9e`K($}cXQ)8gOJGG6LB8X+V!AoRykH$U2KD-sgU zP+GGcX|o?mQ0H6GYvm7ZT^l(;fIKordh#eSW!+K$cuM%-7y7#%yVY0Q%$WP=16+V{ zg{%(y&b*WVd^NZ|KBM5FfMV9A1%nTjuvjaWbPC&hqxOh*2D6WFva2a#H`pat+1|lC z{8ivh%?QjpgdFqTrUvIUhqJPR;cX4*Vg{~lkoqMSfFgQ^U!~=e8ebdHbxfdhe5d8r zFT@{zU7s|B*-JO(=Jehk`1>kFJtMe+|7G-4gGiNyhB5rmzN)jN%B}}7F;M0E32~CZ zS+5dAnd&Y|M`-anhdH+kggykH3k^T0&M0DAtvo;B&JhZ*FT<f90PYdphwe?h_tiW^ z&$5qTICAbbGiW)B?VLOrTwr7F6IKsryE!GvHe8!gET`K6f8JfReT*=Nur!t-KIbCN zeWFcWZ>f}g9MB>DA3|cB;p&@a#0CVo?H|dAg*+HVI8YIhCU8?iA7BL@HidKiLU8>8 zZ8Ws9wli27!4uOEU5<_Wi_cGh%sEyrJ|d@5I%4TAqBA)@{mjGg-v#U=QfYjloA2VU zw6l-xCs#q7N|zzA?$E=#%C4z}XEfm>N@2qUUil5n2lXR@q5U<6d^bb+{w8J%W7+EI z?*ERmnZUjK2c%kOdCMPXpY;wTh7<o&bY&&FB99+D_$}D=8(pDXBAtO4Kc#k;y6x~h zx4er`X-P+|oun@!z=OpUp`6Rds&vNo%Z7it_;ad65SFv7LxMSt#9Y<^+YZ5lZu3V& zFI$ZLr^Ztrh8$mF7gO_^YC_h*Wzk_N0im*?E^4>@IA4T}v?R%*NRJW>No?;Cw^sOs zLdTmssgK%57rBDaJqXR8MGp`8VaJGqzB-Sv7huHW(xBj{Bs_mRp0y_SHI|v(9A0fU z#+qaPwiI#MeQLh|(f?^ounMdddwsvkf}{x-aA$b1eP!w$;)BpQKQ@GAyKMLm;uAvD z{E_iXmp8A=lcSs+|2rsOpt0=ivx{F$K~&@3_l-+ykIYQ=3|pN(6f+nGb|{;$a>s@E zhwymP$*dq2mFdLwud##p6=5}oIMRaKnarUSeRgwuHCZF5Qo-kCF4jchD|Uq^taUm5 zqJ8S_;WHwe`w-!aW2l_x&5ue2LR%5Pgaz<$qo8Y3FX{G@Z)KJcin{DPcHs)H@n{c{ z^1WxyE^oM#rG68mg|MEZ7@OBXv_wGk&)*A%at{w5^emUNnVV1i_j1IxBIG!YYd3a0 zsXT^CghzaPWN7d@+vBzg`MsS`@lghiHD~TiD&l0^^v=9pZz$B!7q8=dk+mv9kO6(; z?__wD1f&=KMIZk5Ct^9~dDJ4psSH6!HHui#uW!r?RVgNkF9;*pdYJi#WUE=RwgKKJ z?{uZvTPtRamL%yN>}z<A?Y4q{y{h*=FIKWIwrhvY5qP^?AIaN_CT7g;%F3}$HFB~I zqzmvDeeT#a9@;VH5<B33ad9r3M65eNOb)Bhu&2G1OI!H-VlSsN!zQxnR4lNBurY-% zoAe34vR_?)t{&1#$$iOaJ*{O7H;ENKH4lLB3}3A{k1GBXKyYfNu;x^WhWJlti`QQH zwy647xaJpng2wT5GNCe{T+VazUffKX-W%i3Y*U0Vev80By?*RVzMY`i-}4hI+wa1o zQE!z9Uxj+TI7H+=csIIl%iTuw+~|G%WKQKN{Izd!c#cn%5nO)+vGfFf``c2K+zGR^ z?ASS@4~)chuwug(#a7f*sW#@8zeJT_dmoBK=aWtXW1k3w0t{{Je+isEzc<uOxt5eZ z{`;IHqPXSR^HIM2oXY?Y^d)-}jU%oYw=;@U4Bh0Oz=fDr0FyoSz}7E;D5bE#q|wtQ z&@7P@v;Sx7Yu{+M08+_$+bnEb<uP2ZK)zgfsZ1UA^rwFP?K_K8cPe$wKYrg~Y}b|V zgF9`$-TE9UT%~x}W&e;v_(nbYQtdooHI4Sz_|hEoY69`Mty-tUkH6~OZKP<}lucXG zx0_d=_2#j^!X)Gt^cZOG<@&z)>~|=Feb*_stUre6b#+L&HEVr=k5bU_i{oTlDD*w1 zD!j-dH78?EO|XTZVTbyLjBP<!pLx3&{P=xE+VspM2Rn1`-9+Sl2=B=t-xoxfW>-I} zh`ni^u<fm9xAYI6(1%(PTd#IyFC(rq+<DsM{Kf+Qr~)BolC5$7+X_b^h0Hz*06%Cf z*_$cTQir!Ij_<`C@3ro|+UKa>@9`2nZT~x1a4u8kWv}INiTs<GEk;nV?|+@QT<6-y zs@Gk<KgYYiedizT7!=!9_Cg@XC+9Q5<RPB6{o~qyI{^ORjp7I2F1QP()b(v-?CYuJ zTEu6Am(FE~Gn`ymnH#`9=#b!-W(gn5VuiexJn#EW<9=o_mk28dd~W)Lq0v4Qqe_7? zh}l8=S9JUlqMGGLleh#wl&EH)ufj#eP(J-EG5^q#j$DqUx;|8p7(V4$%&Xl3)=RA^ zJth+|M`^V(mw2sRg;)R{X&a-QH1Nj%QFJbjO#S~KKbv8j+srWc-Q4fDT+=oq_gmy% z%>9ytN|MhoW`+z2QLg2ldn)yvYwjV0B!pBdl}cAXzyIN!_wDt3J|4Tz?%3mX{lPS5 zeGMaDfl1#(<W=1jlwnggoDjC`1e-~JljD=#Kn%da-XEe$GQxo(?Ep6aQh|%CaoBqF z2$Er=Atv#*-(QGfh&k5ioHy8y61UG70OA9a!31tozc-6}VYA|!Y$Q`eeUvd_NscXY zUOy8C#Jpd*@?iDsYA+u+x^VKk_GQrq?ZBH;)Trf0nl>!4GxyG~KUtCI8qwCbEoixV zMG<zOyQNvI7u&>38#{W5K}zE}YNMwd!LpY#<8D!|AGFu08$~us&xALy9w6VV9+!md zAUXi+upGux!h5pec0C{P2;huiAIl<Bvor^yw-4t<JxYADf?Pz{Aj$+xldvtZs~)v_ zU{^g(nJI72lT=dfcnUaiN|Uxf^O`BF=^iJt6D|$c%$Bg5j;vHR)Q+(D+lDcL^@|Q= z7wbtpH_}Q@oG{3Yx@`5pV6o$Hbl5HO#6$xGb#y%X<l#2j|BtkF(Y4y1Vbi_Y*a>Wz z>^gIrl?ZOEt(1M>Soa5*x_a#37gw&zGZdtO<Rar4Slu?Bu-(`pTW@~VSS@o7cW_UG z9$_vh*Qc5-WbvngpkeudOi+>zuVnTMraEi0(6Pgd4269DCUK9Y@k%)h<V?jG85<66 z%E}l+3;Lq>qvMQapM?$UBocOn(VQg?EQPaj42<L|x0V_3J_U*MJtIw+@WOy$>=t1Z zc`tD~#<KWgmat`MaB1@GQwrCNECb?Sa1*Br_&bM9fteeyI~M9CHO_3=vRNh94K7+| zbrx=Oi*5Gy?z02wUqY^VxO33F<{_LYjYr(stJ+n_{~7^yqU0JG2!C{5gSFIMYmTr+ z_75;p?86oqkkm>K0B(E1GdPU?y#nJ=4`Q(Ezu9qd9=NT(VDzb5|L-7iUv#<hKWVSq zM8HSmr+92b?6UolHM`hX>>j=0F%4M#kVMFicCh5-+;c-1eWAw}{YPGvLIW6v2_d3E z1IpKr%&)!ZCJ>KlD5Kc|7EiGjixF2huZezw=@-lNIaY5P%-ui1(qYSr41gBGkrf~( zr^~Im8g5~`W5)V!0LD%^oN=nGv#-9Pu>akCJ(P6>u(LjA4kVoqrHCG<PFEf>58)~7 zK9QTNxzsv)&oM84>nJ*&wXuyei5c#cZc8qRdyh+u&3I*{)6gg2KtC8ht^t7*u(SjL zI?nnDfYDSnsy;R6@9|D;U0T69K<YIj!?0T0n64j!^CFiW^eOS8LonttL*15-!Y@h& zWhlxgCqRc~U6g>`NhbmqaaZlj&4INP#i7{ZYMb@UB5g<IANQe3M>=)cL>N#Acv)w3 zJ#s0AC*F~SHB9|Lboy+#b<}%#FHjry+0_E!tCFW@ro>shpKw%F*kZXBM-esT0eDDd z<?LDmJrlZyxqbqtFeH}Ku9rN(;nmvCo%G<~Bol{MI2MFF!(ME%NX6=|@U5F@A;1U4 z6xBqUhXxLu)7!H%m%LyeV#W(BAQ;-SYypg<8W#Ry0`YQhV%cfZ*f9~Rr_x0^r^i0^ ziisOuev2S(I$TVOxo%zy;ZH2w!Sx0Rq5BU!dV19dgAcU|%15~2+ZIA1F%)~*Z{1J| zT?nX4Sds&UIeWTgkWc2@rf<B-y}B|OK`04a@W62^XjN!Eu#-}}&go)ElL~;07Z$fg zC0v&#ya2yVtH7VMJS6})%(j97K+@;b1^|?Mo5e4V(cbX`!5ta!HP5FnYN{pB-U|I~ zkcrUs_ZiA-%O-Zc*>QiSY-e+MynocR7|tP@Mf~62@VM9-N=%JiF5)>d%q)!QZFfwX zS<vQ>unTD3b^7_oSN!LF*&8i(LHXb8BvrrV>gQ070lDE%Wx?|GPEUzd>dfiK_m0<K zQxYBV))*PEs{5ROm1L)+FZmbZ;9+fV(nA&NgOeM%2S)Tr0BSCpgGg5@&xUEFO<Pf{ z>D@=CaMc|dFFndn08R+?HajM`$9A?Vp@s05Ru5goK5;kA4AMGx-Lw<lAEP0Hm(ZT* z)o^)`2KX_C%5Uo~KbUwXDr~S&F`Rfg-;NbHU^BNpq*sg082~GoO6jVZ3VHkgc;`T% z$GDrxQQJz0^ZLp!M#89tmMovlY{I3RA)88GY|Jq3g*W2R&@gqha4=E%oI2pg?d>%< zO742lWVJ&TwmL<xCj2}d&Ap9KF7Fk(L^KE4&UEEb40H@CKU#G(NHB5%v&*XC@ne^_ z@>;l5N!EAGtrCSBRSxhiV$3x@w$bTdREohR4d#{9&{yf9spz^E-Z!PG2%OoI8^Zp< zM$fG^&Ad0L18;f$yQ>{?>CxEX^YucSfK+Y5k+*?3F(&#&tYkfWvfb==q(c4iybtFs zTnz<pg$tdFm`}Q+o)*WKW}K=2Gt7P=V))G6f<K+C{gWO-_sO!QWxPtJq#D3OgQ@`@ zWg(Jp1JV3IH6ID+SsgoCziL5)&|u|*g_fdstq=%WWVvVbMp3aj;k<}a&W6p&rFVmQ zo@Ef#6NJfXA9KO3yYzzds5kM93L%+QmfADpL+TYr?l0v(ktY(@1g#@=j^-(Sw+{I4 zi(aky8DTbap#DIGzcu3w+4F?lUF!(xOk(WNJJz4$#JdhtQ$1j@R)RpMu*E>rMShyk zZ?w9rl#b6vw6`Jj1$N+LZtDpVAAtV{Y_b{LQJgzc5aUA7kICo)0lut6@8b*hBRsno z*m0-ng%thzkOld(vHtx?b9S*q+zjh<%e}PM#b3?gj++1B4WD*N7z(CBCw^N7NIh#A zGN?R9NsoS(zEZHCXm5Ta$T0QptYM;!;ZPpmjncH}N!;jhs@rwGyFqO7N>GSpY#}Y> zm|5zKt0gXg4Ydy?iqB;`^G#R2Hhz1@pJmQ}siJ#aGvat~;PXFU^joe$-h+F{9W@A^ zUGoaqSj|C~#ggUs$YWdDaW^!ATwagfyAgbLRbRmJ^S`pwUySCovA3xfE(vz;?`1vH z6^`K{>84*KqOVw^r7EG!%bcE)jyz6LP;PoybW6m3H_H&lSS@PAF+V#!%5PWX_}wpL zHL?J_|2lFx;3jL~C?K3$2S~2IfLET&*kS8`FcS5$Ri7i%$p{G6^%`qiJ5P(icPZme z0PNSuwLA=aC!mduDGvYviZpN^=2(PnR-V?wj)%&(Gs_v>8XVd&)~W^rP{{-C)=*(p zNPYlXaflsFD$lDbS9!i)Hg|%_potsdVM(?<$8QKKEM9LjZb<)nm+s%NLhNSHh|q&^ zL&X^m3&99;Vi?;pjiih^5F`yF((so%C!{QnkL26*qBcEmGCVpN9!d<N^i3|>@zu=M z7U-@uokBFLiY>uP!&qK&?j$m$uY@&q$YU>gJSC??Jkr5=(1wNCCqUKAj}<zZurcPc zt(e$Ys2&9HYJ*l9(~eO1zI*2x*<~kk7)jgQ5E8fP#<7EkxTjFHBtFX0&jzp*)9N8K zWSA!&kzo};8MfBCQqVmhLRl)O^xx+>r<E3)E0CsF8pG7OT37kZ>OP|!24p-c#SF5X zO5Jyve*<7{6xIX|_SV0aRb;`4r%OwVdYhVg>psBlSg-&HKJMDy0g3#>9~RIk=X(jN zJ9Wzn2WuTk`H-s9ehylQgdL*kHRCV})}S+SCf!_sJ^@xiHSh4KM`bXQ_G@BI1&mBB zOnt7NLiDIqRtoA#=O0RmYL6#fu87IwJhPISv{pP3&pXe|d5~$y)*4Q=GreyIOSj`b zPfQP>4cm1<;pRubEL5^{k=G+oh3rO`9_UFcn4XR7X2t!Ix_ev7u(H%vqrTo%smFJV z^s7is=2m8>Ob^!v$Wj4f$<^5XT$2Y|-Cu2p6`Fd>w2fuO6;x1tD#7NSFcY)gmA9?) z40DgK??$Ayz^||TAVVbJl-Ft}aEYkIh<?H%j{V~@0uE?n0v)>dBgaVuSTbHUB%a}n zW~7_*SV(DsOF6v-l*_J;Pf(0-oAJRcD-O`PEYXV`w}NCJ{jvKHY0G3wGxO|P^G&Vm z09u_=E|}eFwJ>GXU1c&_RYQXK?2$@PeT$9us6p$a9?o(NT;f-pZ^rRG4NX0Qa3Gi* z0hCfr&!yb9gB80tumN*MZuton<~VI~`%lh03JZ)DPc3JB_#<eWt8%dbbu(H>xgswg zuV!Xs+8vqR-FW;#;L`#pg`Ww~5Kg+yZ=U(OZe~@^asF{rli_%4M-zQ!upv)qHxGkw zCm$_TP(G}nEhL18341&J=$;Xkh8?-=^z?wjm)ZtJLvnBRI@wOafmJ8_Z&SzPA&8@9 z8A}!-N2gJ4)1to4-!3_?=v8;uic-~JR1w%?j18bA9HgrZL=S~@kn=*NHXt*h{>Q>U z^Sk4&$_FvQ@dnT1>y<26Nq&qI)|o2jGgP@{ms>N~s*k>)o@M;GcctJ2ZOqnebBuSO zUH2RRf2mf+?I*O<pK5ah=ls&c;u-K*clKpFjox9l_N*|U1y4<5U3mL5Xy$Qy7(58} zRswNYb#9uPwg2nH)2dyJnp;qtTQZ%KJK-iSYMGN@eDznYq(%1K!&~DT*rpAtjMiZJ zDSvsGak{Lo05Ol#7dV+9&&qiC@gOGS!Pl&dx^ls1<_l_hqqj4mof&G^o;38GJgWVa zlVW>E)G4pUwvC(~r<H#Abp#W6mS~hGMgp<*x&j*pcVu3u8u6S9O}iwT?hm*o2EoAk zQv&9E4e+Pmh_eI91s0;rzpC)3uG+4%YNcO`9g1(J`7WfNUl8~<l_C0|#^@TQs1_;X z2DEs{@ew+wJP46y-k%q));I&T)B00<&BCMq^B7|6s@u%C0alAFqEz9_z9Jh~M|<5T zCwW2;^Q<1SOy)`RxG_WPc)10u)rQ$Ii(?DV_DOl4DHH!wuoM%+1FZ4{>^hp(We5E- zID`W2E#G51ooY+7ZU2_`=%CRZ{+oz^bjBthWf{(L`%2L4v-RG2Pjwu%XU`t&3jGnt z<x^kgA}tR*>K%NEXK@DIB;1Z=O1>Dk&pz)={?geU&$>E+kgRd84<P8TiU#~<?L3_0 zIC-jWOxxSQiUekOOQfDU$uqW<JEm@UE&0xt53L5lLNg$LF$*~;Sruy|(lx73*Vbxf z#ve5DM0h!xicoNcdWw~0O_h|d8*86@dD=JAI_9(-2(WH-W<I`n$OiV`-{%iym_23n zv0?C+moxuNyn5RT|98}f;f8Q-wP38`8BXf#mXRBY>aJ;`=tt0cW#(kfDtu`5IF5^~ z;oE}sWbMldb!AWwNH_X2EEhJBZ+eE<Q$r`gz>P<qY=jD<MgB04Q|M8T1jcS<uRU)# z4Yc@M`CsL{E@QV;zEBqbbZv9fBHLQEA!NaJ@~0u4pjg+Lmzq^^_5Iox*HisShFg4k z?5@byiRVWf>xW8SJbW>%Ay!qS%4G9f>sF$m6KafTyv}^V9a^UD_p1ffvc@_-JJu7B zIt#OuS|bOu+WXL@0gt0e(>zhP7&NZ?N<*+_Kg$HdDTz_?<gGtzt9gFDknlj+D;tcA zz{1+Pj@L+$ZeRP829H5O9s9rqsO<?2CP#T;#I@qzZ#@$1YVP|rFCNOjEP)UYT>8f5 zAL$dPhl=(N)R+oMSkIMt)9fPZ@Cl8hufX5<yUV;GHQtoYt!E44G*PCAiNHMYMn~aI zjKk}=$tgS0$BbdwkM}dYdNRCKVSD#IPRs=W9=8_TGLn+!3bu3khWt_#0$-bED?Wt! z&QynXK+$Fo8Cnl{+bjX1ybTXfzoD$%AJ{!+!<pJHK+t%U7zEJD)vk=B492GNk~4n~ z`Mh1%j(J~xyXO&84kGycATqKgJ!~pH$$Xu)Hs3^M-MHYzF=poKHeR$!iwM2LCsh#t zU_F;T?h>0_9Nj)lp4GbGRI%?M9w=MK^XA+NMAz)~vjMo%CH-a|{#hjKj;AQ2#Uo3m zy8Yn7V>2;Wl1AH8?hQu#`{bO6f5Kdp?{dMHp&c;)Yi(WEKSZ!wEJZFHV{k0@Ig9Mo zK!#sr9<e?=V`t<s^n4(1*>rK99)6ra>Hu7)POcnyhizqNiz6A-g|Wq-UNbkxX422J z%6QxJt1Uoh0}Ocsl+urV>*)6y8!+a{qI(OySPx4tsD2#$3_8L>ynXQyb>qH7YTmmy z8gFWINe$hZ&wSq4eakG^?k(1n``Ws|I_mb!BO;f|oH`FB2@0qDlSKXm>l}bJv|<6n zMT_7KRo2Up&-|S4I?p&5f$gF0v6pApFweAhA#%*qF1mIZ@cG(;zhh|~kw?3Og5d{u zqZfIIcWVT^x<6bx%Jb{blJVyJ#UPkgCz7fG6aQ5d>`}?2f1c$kII8FLY7(as)+l{Z z_w~te{{*MYBCuad9#e!bTQ|cA3|WQ$EN0f>)t(cqP#>hIn@DHOQKk2LBl)*__^c$i zQ|4E7G-LC*o7J2a*GkT^hTng^3=PGCH3KIZh<TQwe3w)|qc-#@u<MYNVR{?@Yck^< zcTel^9;bbLwy;i}X}RkE0)FrLNA7q|9*^u7M~S5sA}ZMa-t(#8{f`!(UsUXcX{CpD zr+>zLySLdQy58dYA5`6v@3~dD%K*1E`@H9W;kKTczd7H0j(z#lIptWMNiV~L4@ma6 zL|{c(*1&LUOOB6=y|da=>%6HLjz{$#4?8&t`nULkuEC<8^UJv)X3uSQaPL`0?zYsW za_jH>=ieY5(tmu?dS~`@GD(YJQ8c^w_0Ijl;fs|m#|C!K+rvUVc)|g62wG_V{@V<~ zhkJVGp6<u_N2fFI@O-Xqxu<_V$MKKfRDA4blZXqi#v{X7P-|37xE_w_{XYpOr5FRr zH)Y8;-P$u70ke);3k$<57MwxhCjCv3z9oWNmVWl<@2?q#LsFf_tfC8d-hiunzU#~J z-;RSSw4Bx0`_8VdGZc@EQ-s-eWyG2rbnJ_@I0{^mxqSIYL9uWcQtD~-dAt6D^`hK{ zydgF5bB2Nm7U?r0C(hB*9iQx`|8JKSjqSa~6RMPc>4D0CW8z<Np4aDtXaL3u(~|tZ z1OYokgt)m+yEM5}KDv;Sd=~|d-V9%DV1b>lxMsjbmGcPJ6$EZLP+M4T*0fBB-MW29 z1NLi+6X8@_n_dy5L*7nTmFHkUG`;Y*F2}2&q%^oyt}HR3ncBovJIT4@^d13rIxb|{ z4Bi~KhVtTH(8GCdJ1eDU6(yhk7z4_^Zd>@+y%_-biJ4?Y^mQfIzCtJs2fy4gxL<iV zD`RV_mST2Esa-IwfE6f4ZhPjoBj3PtAzGDV(Ya3bqFoQNKm6+2!O27CR8-nTlEFj% zKR<K=pR5$GE97*2TAM7DnAtO3JDW9DDA1E5V*-4HUrUY(-tp88>H<xfDcBta{JUQE zUzLkAyYh=e`}>QV_&?66`$XM6L}UwySbkhqxmws8Q-NEu0<v85=*qC_JX_7)J!U$1 z<nYjDB(Ra60VB<fC@GNFp#TeL;g#|pXyrzFNA{+Rkq^bQC?``;+EpjRwE+=ZJMA>Y ziO>peq&a_UnpkAD{&6n=;lk@4T$aX`4(|jVj-UkeuKQkmStEY>O3-I_zhqJ?9&iHu z7Krv*$sXRv`3KOJxiETvP=04nF;Tf_s*ndwsFnbP4k+Ix!r^s>OI7(UB?u$7ud6fp z{$7gHnaDClL{vAZMJi!A+2C!|Ok6;g;d6+1>4kQc)GR_&H`Ye~f!mY$^Doce@eQnN zvuM<LUQ{`G`9s~4Q?(xi_HJJO=6v~d((m(2b;SG8FFugDdA4)Oyi|ghw?L9!-UH-K z`V3K=3MDeW%nytx6a|701B~`aYsH4R8D?f~w-sKB?9)mSb_vy{OIe#{H4qbfrmgS{ zwUmsZ4CxpvkK~rMH1Q}8Hhm;2KADcP*oYorTX*#i5l_yr=e@2C1z8pWv)|Hu;T1ox zPq`qrf=grI19Wn{%exSAfik4CJhDd12?jq1!{l<a1P7EX;ZQoU#u`RhS_ruzW?#*A zrVEq*6dzHE?UDJ~KwRZ^UphNg8jxlD(5T981uT4rU+><Y@Kx-!Ky&ZA^Ox@Uo?Z68 z=Uv}ZV-tD#d1?Nr(Zfb@<5)H~KKIP*QplO4#o!lB_qbDDAS}+r&N`=n!vZxd-+hU4 zv5xf2SX0y&IOe2K933N)0pjH+D&{Sqc_mIrW4V!d#WilZd?Iqh*~W-_PAP}T4PfZd zyvG<?(b;RVes0Q1*JA1195)~%@=La1cO$oi&e<?qU>j*UPh;y9fs&0ypuX>1u6G5J zFf<9t=?joMhOlZF7b&X@wO%x6ckqt;8q;o0tG%-;&Js&)a3zeUcZpNeCBGn<7N@iy zo&nKLM2lFxMInv%vTR)6YKvKZ`QDwpx+POpG-Q&K%s;{1ATc&Iq4k}^P~V}VH~m?{ zsrn74|JoQ-{hqwj+$(URwEyUM!bxu%#)Dt0ipOFC%ijAu&y7C1kuJg>RzuJq9(yNv z@evDweQ5zt>mXnymj-sjad%7ODn-ix3q{G^bX&7E*z?o{F*LToN@<g#90O6dErz<_ z$QC)P9#2r<j5>ZgA_2;}R!<O1tLC;%@Jk(ur_m+!NPH)VW5juYaYLS<5$@Cv7LS*> z1>3NLIX@H4_+EtpmBS8}X8m|IPtb+n1Sqg7BDfDR7b)b43>8^5dckC$86MN;TFg*2 zrkaB`caNRrqD5+n40O#381@M(>CF0PMyT-uSM%3(lFSFayDL!rM9Yggp)%<+a1Sn! z5bBB&|G9mt<QtFIVap5VDa#?pVk3QJ?w>!NVMxbmm-)*54t;uK%Yn2vZe^LkK=Swx zkX8Jd>3XxU=Yf65d^KyOUsJqCI!55~vHf_WgqAbhLJ3f^QMQHADExufRKc_%2reVJ z#S!~M1nSZ4atyGuR*x+=m)Qn*rHbvK8o7PqOHPac$z63GI|X2Tb^I1qEHuI^U;i%C zUO+_vka0c8A{Hqij)I7#aOF3*PGu;KS36;Dd17l;)+e8V0Xblp2Pa)zp0JWn)cE^U z^CSL7eu>7>_Y!zyaTUK-${S-bby58+ZNaeW(I`>*Nu6?GfiS;RNwAC$Iqs|Xi02QJ zIIiq71KRM@S#jb4{p!ay;}OPDqcs;%2>Y;6_>BvYuFn&`mN84^q_zmMvh_$><}aq* zVfTs<Mv<G}g-DPZg|dqv%HVmCj{-H9JuNbcN~H*~R_;c$QG?er<Mx?>^R_1{`z7-@ zTr!O`zAI_{lJkH<ay3>UFqaP))yvgrvCx9ImS1fto-l@0r`okQl2cZ>lBIv@;R5;i z4s41LNWY<oQvqY4Pb|^14^DJ8PEhOxnI_qB^b2i&g~F4dQ>zLCCbJffdYSAj1*Ag- zcyY3EYp2`e<(aBQ82)ABi;&qJvUCHYuGZ#jW0Fc>&C-%9nFpd#+;tsyq^Is^Y<QUa z^2OZ8Ce{y~z?rKf8zM^QxD`+p3>=Ign24b$I)O4bzNsSF8RvhfNTaHAT`)PEX!2+R zR6q`gm5mznSQ$N;h7i#WWv5ESbGY!BNP#ncTi_ADblnyUej&ANRQ*qdCsFONm!{dl zBGgGUk~-G*v0a5$UgtPJp`*ec8m7qYpw{oy`GN?!E_2B$msWhc<x*Kv_}GE@m&!Mc zp1J1Dco8+f4_k(|k?Vc`tM%z?y8obte05VYs=oWL6Z*Nwpl)+A#i{PI^P<aPo*c&p zS(IGet=Uu6D0^rZVJ!dtot}-}-dlGXRXElvZ$!2N>d=itO>%J>)%}@C+P?FFws04h zg39C;rT2j{5iKIZk%C-)SI$U$|2^-w;~lKL2zc<BaL@1rjQXovlT)BKozlg)X#7w+ zs6_eCTKI#yCk_j@12xSzk|7n#TSMb{o-I*Xh7tf_pTh(BvM4fS@|DY(R;A>2Ht~%V zFhhhq-Y72D8Y{pqf0<1}kx%Wb^>|3#`g-<L7r$aXUi5AZ_3ZaQgV_h))2rG^LZ3e= z46VDrLocJbflT4w&vtS*1BdKn8}1(OT6MiswDS12933u|mm(te8uD}SY*Joar6A>A zN{VMM{F;*EX)M^rkq125AZLN~3K7QfRJQsB473Og{B3zEJ=-hA4?=o?wEahjwK6)& z5D<vt-9Z}91-&GB|9|_r0K~;)k`Ix3l&PFc-m4&3Zls9F>_}jRWu8Aouv!Wjz*yR4 z&$SGO6c2^OtyCw<Zud@UOM@RzISEV%QtVz;$`4pu^CeQozD}<U1qq%drfSETUotHH zWG{T-Qt9ruMbQ=es9gA$YnBQ8l#j}(U$gD^eABzM=wlz)2j8Y0LOqtQoPnekKvc%T zDjBzA$CFJu`i&dSO`w&SzJB9!bCrFN5P_t^?E8JCkDxU7*{_eV4*B0MWwvu_Rwhlw zU&hkU<Dgj7EBhreo*!#EA`9&m-|H>V!*~-{4`r?_Yj4TY-mJlwV&w~nf@GepvM%2t zXwGU7WMs8w6^X7QDuIH0)7c;zpRv97Ea$ba<y--0&M%uBKhe`V2r9J~__exFTd0$J zGveCV(HdF7R#_o`dcpt$U6_8pcvJ_K`U-OV<!tt6CVSV-UHs$g9j47dHny(i$+prf zQY&|#0EAq^qY=#_n^KY~B_Dj!LzkDo*Bs(FDF;e=Dau7DCf)rmjbPn4a|2T@T~l+_ zEU--OxN<4kgpjJNb<0Kj>1Ti@zhP@{Ec3rWT(!^3w9iY6x!m5qy{J+zIi)^v{$wmC zS-Jz))@pH`zYrubB~c6Fl@!rv<{;=GO)BM-A4N-$#}YlH6`l{5tkO}S2l<~gEPkQu zV3V&**FQB>5QcvQ;($<`1<H!S$;@zdE`Vxz+ZB?mL?M;Bz8&BdX?AWmW$g+JC-n5I z#F>-rr!SmCZ57z;lCV#Vq~mGWkWu^4^xNC?(S+Sxovc*tQfzFu^XPq9tpdSHb%LcU zWqc83X~`40=>A|lMa8x6M0dZfP4Iz1C`E}5wu<YM?&;0iA;ra$<>>{=)qT>#Df{}4 z_S8E>j}&4cRpDe=bMhU>Qw#I*kcG~{zqG;ZLtL9+vh;9PVQre~V_(-HT-PIR-kT(; z)k?w8AYK)^y8^^R&{E&G_|VTfgMN)9RPo9~g5_7%&&=~H&<((xS(FWoxX4T4@g2Hh z45EP>oj@D%HAS@W&+<!uf-WR@k|XH?S8NaCof??6#M*$%TK=Qj!R>yQ^|h(mKB*)3 zUq|V=>&7XZ@yXfB2+mVcj@mg%RZzH`@x-unEok_5WTB<G3cVYZVKg~uvF~iO<YU>B zqOwOa;iM>|Q#IqbQ~}`NXBt@5DvyQfm1-g3Gr=5)9X=YY97xvT^eLH|;|(1ZBkvGr z<(|n?oG~iZe!lbm9z)S~mnyGa62y3#UX$1%VeES4C6fOp77+(Tfq^pBwn4vMkE{>t zFV}GV{3P)>l5e+4xKC~}dEQe)2`JxO=&m6<Z7=F^3N9%D1OOcUI>RNCyT$xi(Kgd1 z^P(%1F71NxhZKT|nm&9$w{RDaIkg!dRyd?<+K(!eMyhjZmG}K;h()N^<>hVF8rEHI z!S{SjiMQj@L#4iL5k4kBKhw(HX>;26!J3qfWYpGH&F2D@7P2COtV2jWC(NZCO_m3U z);(lZ1o<E<v{zOuMX4P8mH!=aJIuh2OAT#qpET^yk~V8m*0lL*sl^JX)>jo}_XK+A za1^Rpa&!Wd<<KB0!xZ6A5{5I^+BsNzDjlLi0qf_ZR~IBglLgVeC@u9I0Xhv%xhGmn z9Iq!YylVn;)_mu^;1r=~v6{VlqSFe|57^qow1R1^4sagA`!=2TVf*sH3c=gzJu!Fj z-KEhp6TJ7fB63O;ETO478L7%~sqJEtFB|(*2)ueNgAX*q9v)FP8G8Q^ZmzAAsvX@g z0q3GBY*@cNP8wD~rljA7?g&^DzR%@P)RC34Qk1oJ^h{G#c9azX;6_&;rlq%Z2y}qQ zsD0I2NXLi{$Moq{_u)FoE5UE%dAOO8mH+g^ah#olX*C9H6=)Os9X%+u!x8Kuk$sq4 z3iN5}fNGn?<gQHP&0a(!O}O^35{;%QQ0|rSPzkS7)<+)AH4%$w`X^<3lt+X3Ra@6L z7cdQN|1`swn~2K;Hg;;5GxT>~n%@8U&^vv6dn-bur1<TE65x}niS9SS_|%tj8B~*v z?fUgL`qq$gn>^FRgoy20VUzWSY=td-#Ni*#70DB|&69d&WT?|p?wyVo*`sCLy5wl5 zMa|-M)!IIc(peP`bL;w)a)%wuIPfq(X}1upVl^|M;Nq?2V&9db`KR|lB@pc7N8uxt zIVZk}|Ftnbvs2|UB0JD4YYSWI4O#B=C1aYx>@iuLgFfB$lBOTvyIFH8bUz=7Qj9>L z=*mCYUU>sc?`}*@4`&e^{m}O{(T)fT7y=dPELWxjN<_m$x9`3=*Nyb>GFOP)Oy)o5 z!u8zuwX@q%yT-qq?v*&ai8hxM7}Jk$)<<)dz}fsaZf_>Rq2{*UP_FIjmNz@#?dqH} zbA^}c*7!cNMFQkd0fDKtU}dzq3ZdU{&w0PK&VoXg4(%1&O;*VO+n7OZSKB3o=<<;% z`qgBDUy9VdL5D55-~lyUpxqOtj$e^?i9IglTno8pBqx;{2fzBL-aQ^G{+8l&(4jz? zuOl2C4HEZB#xvwYm+O(MF!swE>z&;Erz{1$LSeoWyw&PJDDXmM^lkzVm=#)6tE2i* zN9_cB)S*%R_q1RADVZ?VnTp9X-T039_c|SLy~N!}Xul4kANg~_urb9DVx9+f7I-gq z8MUN&dPx6tzi#=oK0`zJ3Hws3gUK|iMtPV*Jm*jcRw<3u8BbM_)>oyI6|FwwBa;z5 zB=keC2KK<sHi*&W6tVlHf?kSd5m?5wA0MjixKq8iUJ^gAjU#|n>z;a+`TkBsdqU(r z^=fKw-nH=FtAkT?1t7kAGEeyjL<@SwI5gpE(1BR(h@S9-b;uO4u{_ZEq|T`?!ii48 z8R~i2ADY3mxEq!g9XHac5an2V$6H?<9c`TMeNh!TAGX@(3EOMWGccz{pD;Op#V*QK zb8PKbpYBfjJ@|B#e!o#siedF<Bg99l@z;Fv*C0%A;&z{r>Bl#<DO#NKKB^`Exx(e{ zAEy4TSX=rkJ>sYPQ}q9wS1KR)-6^TMmz=*#Qts$OKOBPy(cg9s+D{RH4zdc`93T1S zQUE<|y7iy39yajoFZw!A;uxOlf%)H*|K}_;9RtMmisphOH~@bJX<o3FOeBfy7X@ZZ zH7BXZ{`V|Mo^I=Sk<5wnj*B5z(-f;F4nP+TRBrIZ3w?{f#Y4DxE-ZdPW{ypoJ$X6g z{jU1*_HMLFZEDWSP?R>qxFb_pk1xNkVLLFYLoK1UTGiVpc0ENL*y%&OX4o_d+Flyl zt7)#XH?&M?x9|&en3KNoAVoWJ->@ZRAc~S|eNIk~sZbQJ>Y8D*5EGV|;V>+x(2)}N z?qkJ@VMGh}-9feaPM5IX-B+K?xL42pcGB}n3!kpnggh<_8(bh3C3kk-)l?V|UtKu8 zdto*>8I@I@!`$RK=R|fAi#1RRx4Ng-Widz7DG(TV=x^ClZ*(f*M|G${>2=FzXHp;y zhE^Ti$+fa$9}Xi%eF&k}w;00N?8yU-J^Px}mNNzVJ9G91kOvRpspqV|Rb9VLt+ZVI z@=T*PCFxkd(RN?Wr#5Nr9*yBd+rJErd(t}|T7cEkxcork%Vo7{W8;haA02j8TT*1l zp-r|f4KO<7zY;Um0sD`?E_h{09*ZI<y~}pgtll|21f@SAkbg<{wW-oE1eo+*?{A8w zkN=1?;?l1!5K9??)qEzg&ENHTJnMXr_{N~q?PS4iBD%;#%<qF=<Qbl6Ybxe-;eXF~ zn}YH_kKC`w&R={;jO6gF`UOH7T5wuRYFeD@mWL}sh2S6J#)JE_3TDE=on8@19Q`iK zv0eLS_(5&W)#-=tqPLbTwR1}kjvwXw_<ZQo!`o+2knK`oU6i@j;bpE)P-Z$&W0@_5 z`y+Cq`-2svC=8-fdw6*GcG`BQ{V`Z&ytgzxMal5#(W;BPJ&@pyfzQhu1Vq}GlEY2a zV(-*YbJK8Zh~0SC%mNo3Lt+3Rge&53CCpsfjc$K!UuFzfROpDGUYBOYXq}3Tb+&&( z51T0xUTht+&~UE~_4E&fivjLxW|zPmW<JYKP33L;hLv!IMFxr+u@QJR9~Kc8__?x* zi302jTDtwY00A`8!DC4ql)}aPxX>QW8F>8P&o9O2e~W3*y4oS6Ob8%Cv&T7mCSHr4 zALMjLd#WurJl7oj-vLcODpA{G(Ql&BKH}ugf`xw{5cz%l=hqP6O;%@wyPapqgqZo+ z^hoWPkV)}m`DOV=Z<V0?w6`|3w$G^p0Gw<1ytI-3CLIJB@>pJPbbnTN!qM=h+XeSV zz^*Dk@@Bmg%#)4#HaaIwNF+1KbE7yVpv=m*Kxp;Zb32&&=A+QJ!nTPLX*q5{JOr@P zh=Cw^w7oWZEf7W!HcaTg6CxELDq+dMf;p6I>EEAm{MQr|kJ5C}#^xBOa0%YC(}Cf& zAMaD^)Y`h&GnH@C{GrMkDYy!Std0z(ys-<Ji3fmirOGULA8%H)Rzn^AW?yJM-ELQ> zLdb0D0E2B-OW-s?`Xp5~*kG#)xx|I={7K^~k&R|+wZ%{Qzk%APjh?0WN!$R!JFE4{ zy4O%al#6$L=ak0!5bAQHghi<@=G#v70<uIM>-b;4dhs{_2+q+H?kkD+7kWpDZBj+8 zje+_G4Xpc=`BPC>*UxE!7gwDJO+Wsd{f5x&simL*FKo?SmKBJ5ivHz&=>P1$gE9F% zf4KaR|72m$uZGEzw0h%Y28M-!C2l`<yn4?rB3Z{&sh<U%4iHiwJuG{x|1z9zG}`c+ zZagyIt(46QjpKVl@7}gzi6!m~Gw~ueG1jb7h+l1GhM~&g(@p}`7Vy}wAIljYI2cxK zpAXDeGjYplSHE%oNW`tJckt)PM{1ehaqg8Ojapk8Wc}_H8f@#Wlcz}7_1K%*o6>+D zH^+4zCpv+%nUe^)7TfjF%EigQANsEAR`Un(<|gf}BDd`J;d?bXwpJ%SxJBP;dY|nS z1U~pUrxh9JwFZlw%-|W%Q}04kQ0_PXo*+2YKH6UT(`6s};^>c#;k;;21|jdHi#9ir zTU2dK7`m2yk<F*r@na>`c*b0aynrUN41g)CtD=m%To$RGbn_haOBXx=m^I|0>D8Ww zKPgZfrOE>>xs~!*uc^M<^igqZYar3(RV8joar8>H&Er~zsz@I;h*jQp5V}cs*_H#8 zwR!<ZssdmK*aKFp)(A{tnLGvdxAyokS&!bDKbyYG@2onqw#3;)hTDBDS1Rhnjipk$ zZtudN#(;KaNU6DN$xq3Jj$r)=kJr+JME?i?k%ji6IEypA$uSlDC$h}Z=6Vhd%azjW z`}R)G{Nty2+{<=$!%f;bbd#lCKC0h_Y4t*i82>pw*EpQlm5P&{$aTev^MN8S*Tobb zccSd7aiYcXbUbeD!CfLW7g-|yk-x8^W*mDOT?e%kydeB$u!exJwHhe=a#VRgl-n5E zFG3F#E(6M8(wAAoIVmVP*SD(Qy+{8U>s-?Wt#Wx;509zs9*A=5t>ScTttPhVKrRT7 z6GH_b*Qza_zOwFR`_?ZO!d29V3853zurF>aWCcJ|rRusZwOy3*?$+JLkM6IB2cr4? z_Yq}B2dog^E@TB}y+;3!IO$$6WU#f0({h;&X@a;9_I)08ueP$(Ir-VbB@W^AH`82s z65SLI3XeUz_|)Al#5nqVAL@1y<bls~%stnPQ{Rvo>HJ~r_2M{o@HuCe>`&8l(5nAJ zRki29^)%%L2;6BHrUc4;%+h;Hz~RBy8UuA$8;%4Z%jWozT^-%IFEm*1rUfb&p${Ue z1uD}f60JoN_5+IgBga(vnarp6TcgpiWp^)bd-DVJ+b0?q2eqTR`J?_J^h|w5g=)6? z1O9vye?xiWH&&^%imE~nty*gB3{md!ho3}`+=+v_Tljv?6s^~?R6#woJ4sJLwNKH- zx;Po`oa0{K*Q9mWVTH^Kkn=LVbY+*;X?oB5^U=Mz7GK<EUe@U0aij%nFE24&(=2`} zBGpP^UbrN%_c9EYDwegHqHMLMV5C0dcsWM+N3vZlsT`^DDZ~}PTvPU<)>wE23nP6t zg0w_N)YbEV#$S1AJv;J%8Tsmebp1wcy@*8Q7sJEU<H@{E#Tc|{-+6@rIsgo5+w}@W zRem_ZR$-lrsA2`|_o13I6ldc;7m0X54w{is<B0PW@F*>=h<d-d=xx2)EmvWa>w~z2 zM16tDoGQ~t@5V@;6|x2>o+dw^Gdd(iZ=-N6tk|QB6hvUwu|}%sn+G2(0z-tC+?244 zZYU=4a$f$0KtZT?okix2T=bPd|LOb{+mTf<4LxySstjgtyk7O$0{hS;dDX&<r|lCM z)AL$iMKCLK<&UyH4M;q^0`k!s2Wsk1c4{VFysw*|D9Y)twv@s6Uylx2kLA8F=2cd# z$D=#l`d)7heiuY-f2k0DQ*x&n-|x;JaYlSJ)IulbnSg(&N=BwI^QG4MdV?sJc)b&~ zJnu-+)}N+ZhPQK?J6@}z`>E3H2gJedCm%AuCW2w!h(QhFbmlo#3H)=LPOGjoW;yqS z`kOC<*97S0{Cy4hHgif52(v{mFv2EaV$1lqtbmS=30vldMV@VX@de1!N&Aeee&wl3 zK#7&9eTJiUOelr%qu{8PM3rXBF*h*nns<yXjH;YhG{}!X!A&daixEDun1wGF?Bs6H zW-o`2;b>%TDealwPRsAi?ggm^Cp)R8x9idx8$<9b3&N+q8f!e98r1jl7r3mK`M%ZY z9Jv5(uv%L$UeEcZa=SNM%<;xa@m@u<AJ&WBZ{wqvoYUm}rUj`8F0a@BB2|6-p*n?q zFQ;@IuK@Z@^8GbAEutd_c$Bulv8>8hJ4ov^qRLFNbfUS8XM7(BSYBfWP6!#;mcGhc z?%wqztTrgKCqsnu?%u^KIsW{s<-+ynL!(MdWccxDjXBo#^5e3VnxwaT4@w1I1|O93 z0)5U5{_i1`BR;?CO^~X6110a!&RH54NXk?nF2h#li|4(9*M~A5&404vHpmeGdc-pq zDV2lWr1u+9Ob4pg_vTNKLF0~z%r^5wx?lObNmHi^cOMYS$zOcKkI$wzrZ8$*;i;)! zh}VX>S+4TjsfLkm3+|s)YMA7&rcco)Ny6WUasMX9Y=q3e1XVASg?v5{^vD)CLA;pd z`gr-I2Kj#Bdz{8WlydYZSfw9aEf`+1st`{m&^}qKk!y2so8#|mg8|^wN8C;D%;@?| zWYpuB5nMd;*EZzUKfd2_!N14-1s@BE^a;fxQ{Fb?n;?v0>foQ!Z32JV2U==#mcKy^ zNxVG$h%^_{E%F1Qu_c8h-u+g>GFkirmtjKHyMiXQjgOLcz2e=y!1PnMW_!dBn7e64 zW^JlyODf8>_emZ}W}FLuNH<gg!B#M+Q7*546o{f@Y$m(2$d2$J?XbG;V0c#akDq8( zg)q{eWa-Gui!%q35pWz^tuOc8D(`e7UXnRMNr4{k^9N}BdAYFbxv>9%e^B}qRCp8` z5dh`Dnvbt($|1@o{VA@1$`kCzKU5AMqFr;@;(sxQYwUB-X~HLc6nGJceB%_dKoUaq z3Zpk>T@E>LccV)uPa+zNOU%QFwRlS<ar#<WaK8xF4vA%#J?=Y^R3UN&FTQ1iMo){p z4nA9;F8)vGBhM5nqZj4o|8CC#B%XWgcGcTL<tJ^aq8Z6ueNCDxO?VShM>+>#Qz5cE zQ9(cFWiy3#cJkg5h$Hj9T3^?=J^huaDU9+Ti+0K-kM3E**LLXAGJ<$B9Cmda+VBKN zRlyEm?ypSaN}ULymH92Ia5{(Ej|z*T!s1glzH9GW2KOWa{KZrZZ_K0pkVi`gwls~( zEe(PCl259Yj=z#7gTcADGq+{cz93dCMt=o{)^qoIG~x5o4SsH^3XX}k@Q6DFE&0tD zz6PUwk%knd618>3#j9ejShO7yNa!_4@t3yQ1g^xM+>a8i+Fp8$i;m%EWdxOHk`9NR z5Nne7FF#(pF;!*Fx0Wqv5P<S%Q2Q$K7P;Q3b60Ij9y>XRE}uple&R8quEL{uKgeU@ z6;g5;cpv(uC4RxBRlFJs_=nUI=_BMtYvm)f$H>|uWUI<(_$ex!Qg=tIPe)|^VJ1%3 z?IVGw4O0OQdJLX<Ovj2)f4-yWV|8$^z##A{z4?>=3xXU~R~T}z_S-N-=;t~Ixnul= zNq9eE^kTHtD@)IEO)@Y`Sd(0W;C6mjZBRL47pAt9nJkg#?@`@^Pvk=1?nPz#i%s3t zf()AU=7UVggxJC8a+h`&f5`{f;o+w2V5}gWD1s5nZu~;f<2`0ZI;N;Ea>|ywW`_Xm zb;<gR`uU?QNy4i-!qHme<WUTiiOA)}^D9fgq;?m*vCz^p4>|8I$%B_2()vJ<1pyCl za-PyL@I)0k$8`(Fy8^uvmc0m}U5@Tk)u2<W{OZ)13wn>$!1^y!o&hxdx77fICYj?J zvV@bxfe<V5$P@*k7tj?~b@!sSKmRNd6J$}>HEFwpHHpkN1L^lp195h*alk}JuNwJd z8%%b|U$p#;!R29e78cFZZ<Obf37#GrUC-1|ZEsc(rKzEx<)gevs0AXQDZ)%z6#wxx zWYb<#sng{azoy<NLX0X=#2?ihi89p0i*(@mn|XyQ5%6Swx*wdpv1(ZDHb%y8V7`xk zX3rDNZTn7gJ;SYNyE{_dtx@>sQK*+6w34Hv-VTLlD>*pyJa$s{$We|i*A+nG1Dn+@ z=m`iw_2r0fw5ZQKV!dBf1MqT5fb&1jHHW1XSqw>NJ?*O6yV&~8a}*Z?ka;Gm1%JC) zcyqST!NLtd$lnnxc}FPOs&h(@6`wu8iWZW@RqQ@aofUJ9k&eTLfwdhK$BY!jqW{I2 z_<+PQ{^x?RM@{mU$*O`Khbpw*mxX<S`i#yMrJ%7km#@)5o?<>~*sc|@h5;XvC<@dH zlg<_11N@|Z`w5-IAf(U2!4-n0)!&rJ-F`y&$!VNkocUE%tm&TW$8ojl@^BDG;Wh`V z^Y%4`EO(te?dq^OyxXGz02-_Ndw0|nKHxMa>=ZbvV%tBZb+C!n-Vq8`Yn7n!3OV}Z z+1EI^Us%ltI~rbM$2O{j4yJ@&>i6!A6pstxX#rxHYw7e}d%25D^tcf-)G&JAH8L;u z^asNWXoedo?qM%F@emh!kQIBw9PLsel?1xg*Z!#lcEN&tK{ukjC-iOMh|^h+U^+4I zS#987di+StF-@w-mnm<x<m?ySagV{l+Uvrh4YSK>4yJ*AxBY}rB!LbLBC{(|6n5o_ zGa*nP`|nHGoHJX!QVYb<`XA=?GHxS!J*oXd#MM;=XtsxNcK+4#y6WpT<e#;x>$Z8H zRMx3cbM%zX&J+kHHMuVJEky1Y2-WixXKAQzvQ9tY(R2!AdNsZHCKvh;8p`iPpcxu{ z3|98}dhT@gkOuV>D;eDgk`;XF017z3MP%N|aG1ioC(0W{PMapw;N1kg*8TV{fa0Ir z6;gj{_UT#HkM%6|gG%q^?rcTSEel+Z$c8Thg0xE(RPc9|qmV=@c^MZja~(d30`b4f z<6XWb&pyYk^2=0+;Z;7alRNOn*0NXh|2wJy?`To8f&q_r34;5zX1d8BzvF9sc+5Vb zIWtAG+up}BHC4GVf*(M}`TnX3{5geZS~o>*UO#5#$EpyuTa$dZN63}1^%u|x<<Gb! zakeP*lz!0p8v&>8g9b7^MSaBE>e12FdydW|aaoX9Bk1$!gwu;qabg$B_y|Ptlk?|T zmt!H`3MxV$ByKss(Xcf1rF`-g!y<RLg^|4puPQMJoSSHc(1M>3VO=Bp0-j2_viKYq zDVj9L)+#&D$`eUBu12;pOvsyfQsqwMqfuchCkTCo`66IXN1nQQ7B?zS#cK)Y@U`YT z`Pv=FUvXPp3s{Gk5{GDz#e*H^pDk~l4%IfTe=-A3&Gn*ARw%_L8=u{uYx%7N+9gPh z6<@A!%M3VMZd}AYKS(eD<Hg!m)|Im@O+5U?^00>lSc!M$N5}4)5!Xcd{kfA2;;%=c zizl1Eogn<l&+ZLE{_*Pl1m;<b7u{7tB22IZ`YI)5T*F7|N7}dw82Ue4*lRFb{Q<t< z{rZLhb}#a2CCmMP>##yUxDSWwdKqT66<{Zbw@i;bb|3$RR|V7b-vdhWWxdC;`*yXN z0-q1wN1YE2+Msv82$V2fM^Fs!CqD?)pc;E5n^3jIU?B!o6N6h1AIQ8fE-e|?PN`oL z)XsbDhCmeIZHF@bMHMR0I%C(@9y$a*f7ELvx&j*$`SfyTSk%xTx|%P<5O%Sj@*;d| zc6UmRkpKiueZ+ivKg5s8LXh8mgbB+yeur;jQvKrIYw>T!9qRl4mjW$gXoh?vQ0v*+ zDSW~3LH(#fkY8Ta)Sx#9N^Z8e=S0Z57AcX<KhnZ8rJ8)s1Y5465#OAg=MysXL~g!v z<aMQ#D8<oI(d;80UDbi_`g3xi#L$Bze)9t>aEEYeaQQmguDHoC+TShy8MFC!l=Q(p zlaW-ZcdHT^pye8_m8OM9$6PKrS6uM-_c)cj3}3-{RfyR1UOfw1(`KMq!Y(Fn;wNG> zAIOVH%baiw>9uW|mF|6IOilR9L6hD3A{fuy=bjxa8>f_Qauv79D6cP-*UZww&brC0 z-D|%ihNnKV_wq^f11lk^&mGr2*qupB5HIgKwRPKjqDuCXN)27%4YF232|SIJf7RQP zeNhCY!-Se+rQ=<wd(TlUa!m3<uRn-Od7|t?-PiGJ_dlc-+awzyxC=$w-bxgaL}mTU zPgZDUZL0D=c_r|~y%8k#<>vBCy9$Wgd66hW?&T~&*VjB<)GOED-sgTlJS}pte%G1t z+GORb-+Y3<|AuI?s~igJnsiusy6E%RZ@jWb>&3}AjKKW4fopvDsKCpQQ>rwncYxK` zNlEaO6*bEtoSm^JclZ9DB38SvAjDeW89}Yhrr~x{$j5%G)_;WPrAsY8E}7s)3Qd}_ zhVEOWm<T>)R;e4KT0Xq~S5%j+6)b;>``o9;xb~RWyUoFpL%pY3r7^%bnAn0Lx!>iN zjT=OWss`5qaRJ;kQI(WhojhDxCJJ!BkzVj16oINuQLs<)x?i`ckfM1SJWQ{<Ee{l- zB(th>6#*+^s&PzpY%QJ~cM@we;97x6rNO}^Hln#V8$8}`PkSD}<9+}{KTdJ04HoFt z<DSd#_15C^PICebvHKfVD6INzG$^{-@AP9H7JwmZWe5Rg2}(nta^4q`@Y9X<q$vtB zMG{JNG9>wP-96OY6KSioFn}B0<J*+w_js-)U`!!2%3;<#13+*i!jO|GIsz96hwu~C zH0WvhJ>v+Bs!wfRT|mt!MkA#?I_%Y?uL<y}9d_Zz${*tkJ6rz?z7-4?ZwR^FEowWM zC2Fzw<XBz_H@vXZ^GOh4HCoztc2wPK2Wz8Rj<_dGQUtXiZ8a`k8}WMle-xdGJ5>Gq z$IonxvCYcZGGk<4#@blY41=-nvNyJ@l|4y4V;06%){-rIM1@q6G}e%6ES02hluA?& zrPB8J`TYs!y3XfZpL5^u_v^K3SL9}a!p^zbe7LCq<SKR}lpGAo`L1pt0wdqu;|9(* zBf43r*ga8?*-<=#oojTBo=_7B^bhh7;ym#md@z9JCKT({QwIT@bchO}RuOG}(iDm> zQp$uS7eZ4@zmavg`V=mJCI(O|V?>cn3l%UW0t@^WxguSYIrF@n(2IjQ90UBiCwKrf zXF6dVSGK4P`Cu&6`JQMrsWq~AKPYW6@_ic>y!^WDL_^5=TI%ytyFe6J&98Gw&;3ga zw4@753Jh9OY~oH|=QT_kpLQO8XeT4tx+{Y!`ZBpEU<r)?>e9Cew2N4Jz0>?7`s^{- zOS*fu{89W>T2Xp*nMXddoIz}F3Y*l(!zPUfu<3iBcxTM#<90JQ#-eBTjg2*)1v)~X z?)bN#TE@wW+<seL0v+9Zp5{ibKVRmdxOv`>i=)%e<!U~~hoADab4Nsi6D}N-!EaHc zV!O>2suCNXs?$K30x4j-Kke(|xMc`n@fX2{d)!Inx6;NlMzw9+wVM`Cl()<{wmdnq zu-Mv`7pwHFC8<y=;~{VIz4iz`{NYs~2%)7drhBV0aipSTl5!R6N61n_(ethaY-Bld zC-QiomUV;uyz2iaQ%39!NrdN;O4rpINcj;1aIdjHi80FBHz~(xWG$@Ey}%fsH-X9H z^^Mlo*5~Z}pnta;1K_3gMfiwJ;#ko=OjAN2G#F$6IN0eJ04`()A=(}uI<kYXj?Uzk zA4+vbqOyta=6{&eeBC8W<VM)8YA3%9ibQ=kGXeu67vzONztGKUd-mGBgI{!ZO?yzH z<86r~4fsz<l46WJpa(X|R$S4Z`(UTVACw4ai;BbRyf~p^qUnAr*7L)}($f*N=52=~ zGHvN&+MgQ{KUQ)Mh8eihbV>@a=<s7o4unQ?Fv4StCVp#`&c!l%-Fj3#a)x}>&M`2@ z-i{E8Fb8QA@1mF7XpPDTK`Ot5w>=6PkUWj?RmKn8NnDd%yEy*iuenBLIjC-*5&YlG zef`%cQ|ThbY%HR?|F*jh!XuB3GQ8RK1Uh&!a41V9{44vboa!lHhv83SbXswGItb+1 ziAo9U%I%3`uBX_q4t=?G&-1mka&f05Ft&~PpRp9BJ&~6vzm3AnkKpbZiWnHe_FZw& z;_SoJi{K2MyZVQ4*T>6GDcTl=Kl(&zav!C5h8Bb-Mr4UEGNk05<hhnvi)RVx+K7Yb zI8A7xbI*j!(+`v`_f2ggqE6;u#6JD+^(jz;aJk2D){|6TYS)F}Pw*r%0Cmtwh6-fY zde6Nf{;Tc$g#<JJ0I3H+*sY3xFRLp(lR8BX2#`2GpgOQwe$DOE8?P$!6Y}oaXkcf{ zU(?Cq?Adf)5@f_d4G}G92`;6K<}T=>UL$_@vhi&d**hoIOicVhUfe<KVVbjsCNTa` zWh9zssL3um?5dmHJ@r`IYWbpn^eoMMBvd`1Ud)thjjbUwZcMdd_Rch^RdjMg?v>Xw zc6D){5_LzDv>Mn`$*5w6t>J51r0=7aLm?pi-;4<IylP5)yIHNx55J;!(~)8>{24?; zkpVk8-h_zz5bL-wUJ53hQe&+I82T4I&TMu$s=|+X_v1RnHrmZd@~UC9x}U})E-U0V zW0qm)BpUGT+<YQWbFH!M@FTD%IBQNn%R&8<si^0CO{lG}mu67nuFe3tZhuDZmaP2y zyC=MOCd|!(qg?A_;Dx~MJtHXJ&QR&AWHB?39qWTUa$@c|YG=q@6EP78A<rAy@pk0( zJ$l4Z>}N2^>i(8nS4xE&Y%lyXJyXPJcL`(Txf;-01k(!|423Q0(3(2?)sanNK6#$v zJyd9+X1)F?%^?)DvFMDFTEx;<G~no{{v5pm0T>@D5)=-+oRK~at+zkGR#-gt=W!=# zX2Laes0SjmqOwt5@5*fUIZ9b+7x6e#U9<L*@vx;Wx%O-7H7%1ipIB_m(%Zlp#iwVG z9OMLE^p#Za!@ox(NcHehB!2o~VJmkkn=~H$HCD_uFbq8qQ+)_#a&=IOe5nF*eFvGf zt0ddS)A~K@7epg7*GexQDvqb6JUq8!+S^4qEVk)C#eB_{$URe0BUus_k5o^;NpKS6 zqgs~2*KtW?1W2yrPE!$?cfa^hmSJT`KxEZl9TV6%=KSp`sfCw)<**ZBW@47i@CkI4 zNIm1FU1CVD$CJw^q$q;Nrtja&^k0bcICH8ZG|$KVmWOa}O1F1$K}6kaTy?L0<@FN+ z`@l+43DB_j^<*ym;Wyp%hZAgBiP+lyWSd4Q=G&1OEIa-xvXKDQX{pb#LWZHZaC4fe zgg-l_*-kmcX*~sP!Ta;;86xY=XYQr2%L?4xSy$pFP^T*AG<DXQIfSn31mh{hM#t^0 zZ+RW1BdUiZ0D>H?BIsU8_YT!i-326G{Rbx*F9P(y3TdtJk;#xk=z7R4%c<UFLG7&e zvmkFftaY{H1u*7<VM|g8WS0aV^XNaRZN#%7Brk`ppxGg<dHIgOT6CN+P{P#eT^9H1 z&&Q32VP|zD^V~Wcq~nEjb*|qRu`6%+l$gayn&g_N^v2sO63KmOUSAhG+LQn7b0qcD z@rc3z^}y*%h0L$lS{`Keb_a?F@Pp$yMZ|PXJ-AI*Z7NUk@j7B~6P02KU2h8xr{CPa z009U$_68YxiqMXmgN~|)BTKmH9;Sh@VS!LudaCt-L{G@}hIH<&13&AeTUAAE?e%27 z;B4q<3Kv!OW6w?t3vqo3>DwGqqn?rQG&o5nqd_*x1kd@tDS_FN_)bH+e+`l5D%LD1 zUlWMmnvs-zFV1VEp2p}lkuzV-iN2<1-o1rBw29_79Q<O3%y^P?+9X^4brQnB%;=!4 z$Tar9WH?V?dzuPwtP|x5L~NEsLI}_jY7QwH+0HTluUr2851iYj)8;69-}C%qUGd0B zWLlQ&3<gFA_CK{lvT1la6;CJ+I72+{^e*=sNug_0=AR!jRXs9#-#iVUX8mf6Y~3K~ zmng(#i8&cZ$9$t+PeFap(jF0rKUmQSOHDB9<&Yzs;_Nsl-udjvaBTOAH+E9NNs3pa zyrRzO>~xSN+d2_1nTjn-;+F+tZ9+*N#Jh>WdrQfLcZ+tAGphw+af!qiUw9$J?C{kj zw1^7kFf!B^=~Aqavpck6B2F{iPLW}S8*nZecG6vxizFd7Ljw&&Q#agpC1cl#@rdcu zpL4=AWd4EC{vqG=_p4JyV`Lvd0B0l&cO7g_Wt8=%DV66!QJ$p6h{Q`Q#5My_Y`B+| zUN&NNsMrD9D<ji-V53p=HvlM(=TW`9u7KR$pkvLtjM3IiD-%U3j&PMF-oli4_6;{v zQ83)gfrUm@<`g6ipJ1Nw4sJt~s@rr&=t%dVt|7%bS^J6(OUy+ex~US?fcK7Q8M=;~ zdE|*`z2J<`&oj*Vn3rF4rQaoeqhxb^Y`G?<075==5X<XS*<oO7ZQ!gTcpw3q*a=xm zN%307y@^6P*dvpe#o>lwA@#+uX^TB=82<!&sYs-ILJ7=3R>+aX+d#Py`$7C8$}mHb z`Mq`9II|D9##Tc_qS|S78Jjj_uTNPsmS{Lyc1p$goj||v?E&x#@tDCuaN1!p?y;YP zh<=v$EECmn3wgsk!;E2l4V~alih69DAyI5P#zaNQoKNycRuc|6e3JkY4s{46XN6K5 zEX3zlq$WsLlU9+q1b>V^c!*XWk4l#J)GN`%j;4B<6Z5aD!FRYz@PC*HUR?uMAR4$N z;!p>-I<N1$dGz*J+|?K)2d@CzTLq<6DgBfo#2^dcz^M^S*s`kq2GqPr){dHc244#G zV}%S=zm&0x2RT@tkV9%j9-0QE-H`}#SsXji&)4XE+W*tz0IIa$ZOwsUsr^Z~cJ75k zwEWx#<dc%xnJ>`_$EhQoh%vHM@4kyRZ>f?I7t^!P!Jbh+n)n>LQ833x!4vm=JFHXs ze&3jf=<(Z!%;pY-5SgeF^phE}27yRPLWSa5{bn}i#9oDO+e9$e7_odHq}U8rtiUcx z?qo`sIl?96QtD!GKTGug&beI?19s5<yK=g)P???X6Yg=F7PsUS9N7OP8OT097cOJ6 z_Yw?$Zr<bI<?39lRoyn&`CY)Zw=7tfA&P;#05Xp2I{>Q#-U+3X94}Ex(y2&`#!|g2 zBSa5XjA7#CJwLqGZ=<GIp%@h6Lo=pO%X>Z5IoPC4jD||&M19kYI*V3t`x>ITqET&5 zc)o=&p-Uh#T+W&vo3XCH$V3m{y39i&E(pcEC%l-gn3FeT9?N2_Efg{k8pkMzB&y4) zI#I0!6-u7|L|=#JgUVDv+|@T72;vnO&B9$>0Ws_@&PffpCI4tx*1Zp~Cc~_K88+{5 zmHex@5v7m(k;g9~GeiTSU54(y*Y-66JF$6@zcK2n1nF-C<Nq>@wwI(Ugd$3&=5IgX zu0b*5QD>r_L{ET~|J=-I5+bi1?DBYXJJF_14ck}i<TN(!T#<ns8x%jzIr($CZR*KB ziSvjxfmjBqb#~~G`5;<*TCB8AEPz=tEDBV!I`4Hc<3J5jt3+#q3#OOaFWgoEip;9~ z<5*<GKY}8byEzM}q&Sj{z+Ocr#pJj8=DV%CtN}<Q@(BXyZY%ybs!H6(a_hJIq2(*i zj(a_s9yUl=+;5qR-dqs|GHLyYS~F6j6=NxuwLW~yoLGiPY?=R{R^#oM$cAinmgT%q zH^FJ9cHaHkaA^$JZgEHKpIG#czIfq09f6JzJHgSJ*<G7GY5nFf%$ksC{%x$^)JHRM zn(%BL+mMi+X%p+IRi?RICA-3w6E!`~aKq~b)9C6AF>ic-1375}e@y&ceX&!l>b#?M zqMmO=a>q@X9I`$O$ax%%Gtbih>zxukB6BVG1}yQ$nuWV4sY!&^WVb*LpQ$>%)s$Wj zv37?&d&55xh&*4BTg8tk+?4q&pBHA3_r(zzhDe8cwA_en;mFEs+sd;}MgpwV>^p;} z(2^m<Aq$XM-pnPLzRo|*K~``?KbbkR9m0J#Z1SgX+oLZfDWjzmzHbGk!BFg8*Lz7t zU?xXgzK+aUQ*}4RcFYvSj_ehs1m<hzh#7WK&P*r>qiXj>V%e~}Az2C?+_BsuL|ajE z2<V2_??=$V#(mdCj=0P0a-GdXMflP2H^pu?E|R4hQztM6_u4Sd8&Em`(G`nWS-V*= zzMt@I{A_%wND%U)<E=u~383?M#L#i-gv_(tn$y20>I<^kBPM?tg%y=6tb9lp>GB%f zL>s*r`Q6O!U}-xn?ki+Jm|e|?9eZ%hfXfpJzLnYMG?maum4KYn={r6$v4MDlZFP;0 z5wg*4nMvg0>orJ3Apv>|5Ho*3$)17d3gH)!wsK$KA&F<%Jmate+ZAWzf9Ydi4fS=c z;W@&F^o6mV@k-n&#(igXg#%&aSPy@X^CCTR_n0T+!whbYU(YiKRl95Lol6^+3})m{ zjT6F=i*}wtdDC#6Kut*2)-R*lKUPWTUXW1!Z{7^`>tNW3Op(#y5{p@vk5iYKC;iJ$ zPL$`<=aJmBV}}e{Z<IY43RZjqKhd<r=@xc7O$EuR({8_RJA3$!Yfyczn3G4p*zhy4 za_a7pf!C0eGM>O6!NosOT?&Qp!r9C?7dAK5cJ}>&#Qk^MSNwjKC3lKE{+VL;Q2sIX zP25Lqne|)6fY3tXn?*3wo+$Pl7JSngfYAgc&9DfC(s7Z&aj?!UMAy|6*$D~0VaT$e zLIT*S?3b^t4ulow?IQt_okmw*s{chwvyd`7O>W<UV`0-`W+;rBPQ@dg;IR!vCWII5 zTNiZ>HRQ5rs8eW)BQQ=6$I}q=<KnIrzNfA$+ixpl)}p69>(vv{WA?h?dbfuUiq+S_ z5`_p$kN*u&MW2$T(jbV7rV2##tG;5}ts1jP%e(o)_vDf>Mls^4FgZm77sa*P2}UY? z??`D7$>_h2K-u55L2mwliR;NYc2`wLmei&SwT0kWwFuatM@woor#N@9@ra{H-a`lE z+vMZ#lRXuK<u-psm~S4>x-Ww$dW|cP*LkF#I0N~%B>htEO?Q|2g}RxYuh<pK3p>FD zbn@Rf)c>6s08q1?8qSTg8ZX*P?zeS<-h!>wPc<S2Hbh63#G_km(7&`Ten@<(&`}>e zIe#kYO3*>QE_xjj9*}?{MLiuTLZk{2jqak|ortqb3Lem7h^%(=uJ`>~c2OP3R9##K zQ=-!je)2Cam^P3Vof6w~<9Po7?9Bi~@5Aqo`H(?(;stxgOltr0Dom=ZZYTKf$s-EM z)t9aC;0~ne1io%OBK0>zLc?L!A9<eZP!*3P>dIqv)cczch$ep=*HgHTv^Nd2gT5f{ zU&pD%4`B>vN5p|E$c>l6Gow1X7T6Q}3RZ-?zH8!lhHDnfew^>eKS2zN?Of|b)Gxdh zCcQjV%ljwxUsxg$lc!<vEk^JH&e>o>yL>+{Nlh>%&kErK20d|IXJfbf|M~BIhv_D0 z1s*#0N?sp628aW7o5o*o2Mvk~rRMLbJwB9m`g;&EhI!?N*#|^&m3Zw3ayD%AdX-~< z@KKu334oB1BIo~x`>YvU-UCJHPMdG8CEMSUzdM~N3h>pBenkMf*VkQ+wTRWVxGR4g zI^E`@yvO8;L_}Sj2Z(fMGxMeM5E}g5&X`!oydzzuy?GT0&=5Evt5re@$|4h4Tv16w zE*|lk&X+=IsZ!jR?7W-Q(I7k2MdVutilF+q=adu^iU?nPkExzhN+DR4qEX4Dy( z81}l%L4#FWsumO0XzSJFYA1K*`pwDnjrOI4U>=kZ*R(qoHEW<uPpfnT<F&S2xC+re z=_x^l4j0mC|9FnV>T>Es@=}30(8ql`%<QC<DY2>wq9PCn^nmI_y2D5FM!A2%1fvlh ziEBY0g5*@n)Z793i3Z3JmT2Fg;}2efkE$T^vBZ)pMiId(lRIjFvM*f1#`QDD!K|cd zq?7v`K;?*tW7Rc|)=@wJRN{`ThA=2IEa}a|i}tS+m4W0~iJj(F-;`&$6=Z|OvO_y9 zRph`z$7Y2JON6+pCk1_^k>{S+T<#m>P(X$37#TVk7g)x=#d)<5d6)v~iAbDZheNKQ z(zQRASUt3sORVQE<ktT-2i29h_mD@loOD2h5<B@5E2t}-DkUmJ5FoC@mvPW3rpq|& z8jf2m=_uPC=8-(BUjPe9>r)(+4&PeJzcvZROj%M^q91jc{x4Ia!FWg|T*Yvt_ha|h zs}-vV&F$({F`$l+lB?bl9m*qKPWZ&1$9pyyssKV=IFR|<rT1Mdz?#k7^_>}DJmKpQ zenXs|#V8hFT0r~4;r$yk7+n^2^?8nO@Np%#T9c>Mq=%DbT>gLqFpnyA{{BFk<!YYg zaL(K}CXx!qRFQSgiWsg6AUnY)RL|_oSc_IEmFPDmo_PwJ2=WdvXvQ5ATTv~GVQ#+N z>pBB_TYCC$jo78b!OkE3BTmG3l`5$(t4irIE;MO7$uDcQljIPF;lQ56740)PlBpwr z1`)2<G+EM-w!e@=NS7X=3etLfE*xvllq-FA8-LkGI&=pt(KW)gI%|-p*r-!zCT9p? znd`>s83Rp+8F{%)=_+v=)#CwqBwto2f)r3u4_7-ZzRq9354qfWd3v|jshENMx7YPN z=B)R7U|ZnrjXBA*^bK@b^5I9+lt0Vud(*J1wD+(~8vXh+r`C3gnXJzr@a|~ukjfq( zkUcOh&2sTxQ!97gF<+D|E7e#V4=k8_o7M=iK-r30Ef(2e#jcqYy~x9QZ#14Y|JkSj ze2?Up9yFKh8i7P2@M<$(XEn!iDTCY+=iXb7Q~soR_LlmXd)Vfi1<5s+et(to>hF); z4QGkR>Tg8{d%jCkk@c@1hX8RR+&bO?esa}DeyKCZe5&K{KV+WfRL}K(XRdy-fG|xc zG0W?Su`CLOM*^KaoAGKoK}!WuLt!Qd90p^3N#2-l5e_|O5RMYEr2@!2Qk|~Bt;DM4 z49q@Ys!(M(Mk?958Gm<w&N1bAz{Z%B_0^b}AQ4*L&gAuuIJnvZbvd%5z3m}E*)FFq zh!X~yWOjZ=^N2yA<6Y_8j#~KJj0fg5d;Ml|V+XlJXy4QRmK^j#{YY9Xa&%Anh{!9s zvuT4bWZ3WvdfBWY*><>l4g-{T>ZSIfS1-=rJNo6?`m(CV;x6wCSR(j-={n`TJbzGe zns3!f3p$3(lD*l<qr@*u22zJ4cg6RipJyuW6xb-v3$phsvXPn?x^c4u94KHT8#@o1 zzCoYY9CU`q&(DNxF%bul*6ch341KMLCYh9=Vuz82+rm*MfI!0Kq`d7`86KMrb4PZ` z10mx`bu!e%nlabVKsN3A)R_bDu|OWV>P3&sK8Y*^dVz-GYwoBQGE~Zjft$fr><|n* z7RxUax|Kf1qY}d`sUWDkWH$9^!9JWD{+@^Wantw7#VqJ4mBbEVXc&fSrsYBDLU^r= zoXt&qnME~VjHa(pKY<1Mat`%ruz$}UvVCmiY=AhG3dhwjL~_4BsjpsK!8|3^IGPUH zi|&uJw^-ol7Jul}%*+yx@*2YRkzuBUQ1Or@8+6H%$e3wb*U|Kk;R+W1`h-w;JOP5e z3czmQXk!0#*UMzw<`Ls*JrC$m(6>%QQ~Xfn3st%n(}Ul+-NF6<4G^h%LmL%fRN|1K z@^j?H3^h9mHzT6WFSA+}7^~7cXpLfaax}buz^%z(314JY&P+?g&e1BYou>6IlH;SM z(C2{T-EmJp5G$W735dN00hue1OFxddTJqJ52Nc18dN{l*gRY#X>f}E;2`!YTA-tLz zXb-CR>sn?{E;yepS?E>*@XOi$T$R9owq$5}@q1h?Nx1wa*!oA9_<2E7szH`m;o3rO z6?EuaBAJ7nOyH^~fW*!m`A9I{?3g|E82z~9qSiba<`OiE+8kCh9W+F!dR(ad5eW79 z{>;GNoGpDUfg>x^?zhh`6mF9~bhMIivq|7A9$zs`92qG(Vk*?{tr<5r@T(ZvPCGb! z_tGr-EANywSNy?4>u4*|p7zKih#AQj*s@OOGvh(Hxo~IDhU7S%XE<^MNmMzpZdxqM z^|o|fsmd5O%vxuv8}Qa2fflvftJ3TdfBmFSr@Eki{|8A@{qrDbWeB+=lCF|a5Ps_8 z^~T85FiaEK&X7TC)W4ZJq+UYydAN6++tW~j?ON-fG19MSa@DGihH9yy_E#j7V0O_K z+U8jZckb)4unI7yn+emWo|7&BM%50pS3JgFoT|ZJ_UiLA0GzEERb*XF`Q;A#6qRt9 z$9`jHdk*mF6A@kuEu^bvU*ggxF0dHyDoU9=)e53S_&B8MrB04jQJYgRLf&S+jmF<L z+b=j85Q#VvoyYie5!i43v^If95>TObNNeoQ;bE>?g`}x;jf=F!@0W}22;iJ~L+jh8 z)47>g6(?tB2e~k?w_8M>L`-Tsrg0`W+Q3(T^h4KBZ`^=UQxZTKOGgf>ZX)q1h`?qY z&rk_Z3ET2NG1@n;m_MN%ogtM;Cq@n(S-yPuf0xyF2Xw7Z;68qw(Z}0+G#)MFxo;7# z=^1|vdn4etSjLUb`Od2r{poN<mbYSl{yms<f934{25m*7(_xfHiFwosom_Wuq6{d| zx=5!oRuvkwwh@s0i->DkZ4Sd(K#5yRa61BIYDSP<`*W{f4Exe!i)dqHp2$Ux2vx46 zN)97`YTD;3CJWKpoDcpK0MacorxouM;)Gc$WbpIxzK(Vc!dl-oh=mFm=qjyJoviXq zywjP^5`@D0+9mwf?^IZ`;#cqBpsY+k>EzY}o6)3w4RA^&_s$U4bsXwc1oPj99Ks{= z=A~!knky+{nCGTP*DYy?rfc$DpNOzS4Bl}fjKQyUVIl)cAbRu7qX@41QsZ&6_LtY& z395PK=n{ujF(-0=XD`B@&voqVXz9%(p-NQ5I(1(dUME<FSwKrd`5K98v1lmOon!-r z#?EjqfVkcpoUq1$p$g7EDtOcytm@9*!(?klLv$G&vyBV;ZO-DW`BZW90Drx_?E_hk z5}JIllJF`K4%rj918%Eg%Lzf;Nn^gSFSk!J7kter6y7x}7@?dwYj|Tts8Bpp^)-yY z#fEEvS-#@5t<F0G;w-VE9GM8(z;*qMR>%*kL@kFOW|ZGa=)6kKyHiPOWAI|4p+;Qz z;brMtm14Uz_IM-fgxUKi%gECV)bZh_7zI&3Jnv{-vwjhHGy`In!1b-$=PuZPC*$02 z0>a5}IO6x+uiMq?7#>9kvckhU$MZ@g@>Rw1yXUJPo@m(tv-Fo0>BjWfhU?x8-aD#< zpyI+9i$lS)RhP1ybl8f~U_+#ynV-588*?J5;I(5xi<xb9Z>jkp#<HIO*187=X8kiH zue8hm_wTr>&IAML?DYjA-2i-LeRRREiaCY#sH%F6l)P?nXEI?ITW3;MV%OVPKA2eU z_u<a`_>H5BH@*>I`=4LGxU4umesPcgeWe(v(*_L4x^K4)jje)bblBf&*yHJk;;-I6 z*~AzAv2WFKk+tECCc_S~co9V$P4^Be9?GZl9<1z-B2~!5pt5`0t6o>QrgMlwj_Yd0 z>v*fO>cQmdl5#BfEfg?ePn<7vu$dE2o`i_?T}L#)N5&P0R^{BwIHnYcNhf#@+3n+( zENuqF(2p}*1R3+=WW+*D>Iz=xO}5UdpLUd<g>%&1vt+g>*Q^UWV%YQPU=8vP7!Fi9 zdp)>Otl@ZDBXo+oR42S{WFezrGTrNxO~x5`0{5EudVSX(cj*t!-5?KTdwW-3l)uca z;@WNS%*il<YQ>0fD&x;hcwD<mlbEoKd}?KCbNp;wG%UogKV}@Fy1}N9q0*bq@`EJK z1?|Re2GGfHt{_b(<ZW&%zQLHe%yX3H!A|ow;p@Z6*t2DckIrX03{<$TW!4=aXJ7n~ zKS`F5u7nJ?a;%Ct#u|`{We^h2cFt!TQaIna5K1)1gkt+g!Z@3v$B@j|TV-Rz_;fGZ ztReP)b087ugN_qy5RBCY1?B~X&)l7qzw{t_%3iS^gn1W;KiqN8Bj1SZC|F~`QI=<Q z4689^n$hIxqgY}+tuaZ}^x_QSDx<e>6Sn)P+<2&b7vmEVF*`l=U-YfYg!UtnGr3Do zkH8olhvJN%()%o6;jO#zkzvv>$#Q`!`vIyYsVt0<YKXN-p_}Hd;_U<_`}t7oqGlZq z927??3Wx91^H+nM`7AF(qPka|n!BR>=(yJ~v(zNCpdc7C?AKzl3f9Ggzs`Y3+d4Kb zbK5<a>MTavxO3L+bCUvZRwerp1&m`-cMtO{;Xwz8r4|iVBRrXBN$w>qe6HlX#XSja zDwm~>`NK2=Z}{+6-9HGP#9*uY;&7iS)y%g$3%`HmoCct^i2R!Ry1{V16}B_afkNEm z!N2erg7KHt_Z4(&CdX?Z{(0Je<7r<r|A<d+#s{w1eDhOdo>wdErA_zWbkvCzm(h8~ zR`0<p8jm^%;*4~N5{1J+-tJ<EmwOkyv%DZOlwTgf=QYdKbU9ocG#W&X<_ZY;kp;Dm zbI)OV0E=Vhr)Ij!Rww8pm$LTsfo+00KMN+!Z<iX@@%1P@x$e`s0<d1is8YJQE*vt4 zFT0}IdQs_#XE3<I2Ykh=z^zo+S^D6P!I)cOfZBq>bdkl^ZJ~DTHJl~*eplPo(Q6?L z+a#SArfb80Kw6Qh6nrzsBmG70o1NU>t6~q0rTcIf4~H`Eq@Igu=LD~Dy!gB{3eR`` z;qm=8^+=`Pt)BOr`S&B8i(;J38@X1!BW47z4_*#x^(DFde5yO74yxW?alyLNOkAt9 zHj7{mli&7JuYmxjZGHv1VOCWy>A{mGWbc)i^Gz(aCfs}X?Ilw<HmUN4+w7HvOWyGz zIs!1T#8!uc@hlKY2yPDr!=QjV>&->jLjAY@@w+8+liWq$N{(v0@@w|#uZOo51_1M{ zdu<E1XP=CWtMK`U2HH8NI}Z)K5YZ#p?u&#YwB&wLX2ZRFiJ@Zlez5T3Vl7)He)+{a zCNuV>bR15yyc7B~e1{W^HpFmvC!(R{2{-YZOys*r9m#wpxzMlU&q5s}=q#uUpM%@O zvqwVJV@RfKaX<rV&yus5hY*V{*ap!lof9@fh)qvjY|==}n)v<~W~1YZ2WI_jeZ0rh zOD8(j4K+B1jJe24wi=bKBz#YTb52-sGQ;@iPd(3t7w)oG$Z(Ek0?7Dq;eRXsdC_ck z7<hj5f9C&%i1kQ{;tG3>&sdqhTG24+QCRuLgZo@R^Bq^H&4&9MO`{7Vg2M}be6<>U zu@bhNN9Ync;K$3hId}gC_cyX;R0&VKJAFI&?K=k9dzC|EdU~vi#qnX`>DkH#6&@j` zY4meL?K=hIpHQd%=3R4@=uY59n?g<JL8=v;;wCf@m=BKS?ju3Xk!(tW+I|ggqA840 z=a7e2KalV=CFwvK82GFcR)2f8HbY(QG-eY2zeW#^5gGE26~{DOk~IIGyvjbY$NU`( z&>07>N<xT!AdzY?G$op1_o?=qzgf#0bCFk~kqUY6YhUXgxcWClcpvJIfTIZ!cP&>s zqgiyRd|OiwP&$xSckTRue#WZku(*t$hI*f1g=*<g(lKn$%ne(9_&;w`<Y^SK$+z+F zxtA#iGn(K^E45L?D^z?pg8-u?h#vQY`j5vJ^vrNV?LWUmy^5n;wX+YIwqe8OY0MoC zk-FYhfnNBc5BtZ}M#y#=L0PX}pm&NFa|nEfx_w!~5VEpn_KNEN>V9+-9M8rywFPIW z=$&-r=sdcow;Dy+XmNe=elHwiunNv><ZA*fauIlM#Z?(3Tb~lWjw|a(WUDdZ7i+@v zvNaka;XY4RJApf2(2d1*`rbdQa;YD-m>+Ok*nbjY-kwvGh4zo)Kbo_6e!XVdsS~-v zl`N%_jtXcv1NJxzj{e_K2&TrU!<S$5;;zXts&d6fcJ4t_s1l#!8O^)8#Esd2#4$wd zsg}$~|2m2uu02iKaV;3HS$xMFD2vGN{$CccmD5Fl?qs=wwd$;vAXf7`B{f)X&JFP- z-%I^0p7+KD!M1qVsh28;F;W3x(*Uuhnr|kj$M3yVXEbNT;-5Zh<eYEIZJD#NS=GdU z3Q`2i=D@A8z%<$?Qq+;Wo8gSjdW{1Mn#%fTuYL;d`r_q(BNutJ{LunbLlId0f`f(` z$dZzmz?Z5y5iFir(Z>5GTt_<8sndZQ&i|8$Xy{Hser8%do)T#Z{Av{&bph(3kzhmM zDV;dSz!&@0K~Ai@IK40aYnoT~cxy=Ea2N7y<r(Q42_<oc(2I*;qg75Xl50&KS%*Mt z$`VB7VP30Ie4NDHc`Ne`h?k%Ge)zddufAFCia;_RKmSA+uiLqYj4c?Wq-Eo;>KsmF zynTJ{M&jVm$0mWE-y*$Z`aKTGp0SJGXDX@T-bXpJnvhdCN&b<13oE&}>o9ij5s%>a zI(-{r-5q(Ndl6nPGJVjDb@G`B6b?jI@c$7WH%O{B>y_xpk!DNh^ITm2ZsNK7VDeeq z{OO~7@=vqw@rzP5_1m9EuQUdKej9n`tLy6C)KljI2hMve!OV}r{CjC;m$ww+d&|yN zoO`u4{x|RZ`N1ShuC+V2xAmv45HyVrzO6Aruf9+-C4QH|y^WOFUj#||H83o^lA3hy zkotWKm$?!A_c2Q1wI3P3CGr_K&Q$B9!aWI1fUg%i87;S?Vhx4DZHl;Jkfq%=Jz5>S z8)KZnXt<ajjp$x^gU$oa6zDh<^T!D)d%p|1zU*bmnrI9#H^FL;s?C$NfFjoGEQm$U z8dk^(-Vglzf;zIc)#l|4JYAi$*%Xf0@R1HdPyx!1aYnw`@vwtRQ*|le9DDM+j;(Xj zdvH<galIDjj2~Z~SQyOGol5C3(+v}zs!puHLC5Uf47Ar3Uz5s+58X>QE7flnt~@tl zF(|gfDXP97pVfrizB)G<&_KxL!eM#WBl$?(jKhzgLRNp!+gZRI%D><BqW5Vy?&6z% zN@8yEiu*re_EL&9M>IUkTkRx)ja}S;flcw$&d>6&zD{WpJttqzqKNQ(xq*)&N;cD1 z9`C5wxy7&0G0tQVz`!Wc&<-SAA{x+ez;Ye+zX7w(l;=I32<(NTQW5v%xmmYe6?Pe4 z#k5Nr_>Ww!vWo<?l?I*!ZN79G^1!~>1)Sd;S7By-V`#N>l*j;#ye)s#$|E8`kc&TC zw%q4Yxr1uWNIeWF_nVm@6<U@$YQ3=>5>skqcKepP9<^JbJ5T;Bi)k}cdF`9S<oWml z@Szv+`HEje(ALiNwu-46B7y{8kCf_0^aqfW7S`;zCXl?uRZ^@uY>!er5--YXUC!F) zA>WcGN<D$iC89F0sUF$XfYu!*SKLCvU_?gJqzQ&L7c327kq)3@+ljCd4-8z5;lV-M zD%5-Fd6X^R*yj>~5m#KJv+43&_$(A-Lhy83y~=GUpx3KRANVwB@h^QF5ImCYvZ{<} z(jLuz5=TRrITXh=pKGEwO-!r=#07uH9!A;g%%~Q34rL>A_NMu&N8AJpw66RKl~6xx z+;Jf)o-J}IT6|ZwQFHvAs*!Erm63qjQ(xc!ku@d4AaV=B7>eIqh){+24d0wSzW$>< zP2JPWIhv23B&I4QM@X_1(Wwu=r2^>-ny!ttd0Or0ny#DlcMhr|a)&afdH6`-!stoc zDPTDBuIUyOKn3q?((#9!v$$}*4y2t7-hYLQK_8(P+Y>#SxNH>^v7TYok+OW_sjD}~ z*{ykF+40S5@6UYgU3MB64z<1JYCnDYPXEpl2`<~_2+eugwo<Q|@}DPEwJ2A$<mvdO z`tpquz2TppWphrMe~0T`!uV1p+}FOOfjQ6vN}+Lgo_-rX{B+bs-n;*t^lTa;VniSO zUZ7j#)8UOS+U8XX9b~SObCyKF>hRGD8^sQs{jM<1rnoQdhEwoboc1#IIsHppZb!Xj z+^Q6i`Rpdjb;T#G5hr)11){vg68*MWMFoT~y@X}N!QJ12_;KZ-Cs8nM{!mwg5DHF( z(nQU7tg+UHx`1VLE_pNSy`M^7?h+8#h;g{(JH(c9fTm(VvVav8CE>?Z>1Z5>1Rd8a z{sT?>I8?)Mp5vYt4l5`0H+ua?BSkZ4+%O2$Fl;mDGECicc(atz+tBYpwLW#W74z_Q z8TtI(W9lMCe$3AE`yUp8J(`NRkwXy@yY*@L(11}5&rruwpZHKACpYSy`h%YiBgQwq z3lAoB<LDa4&hs?5wIN_dyHDd$8Lh(_6&L|X3nU)Ev{3@;TiYGzW^-jWPc{6MB=e5M ztAL2dtu%_gi|-#<)r0_(2_kozX%g8(KH@<Fj%xI>xa5Z+$<16hg)gNS&9>aIJ40kB zzJn@i3s(Uu-|9@c)Wh}2Y=??o`Xdjgz3x*q*I4(_^M2EsAyc`qNlKQHDWMR1qK3Y} zzhBcY4r~T!Iv*c8)7wmwyvVj8JYXWsqVp=yW~wTnIvk*CjcUY?D*JZ9Z3z<RW;l^v zi>goZQro0$gwSnskeHv}F#7CvtoB+F;t-?h)P}f=E5qo)&nGeJ%n7lgUt1;nbD^!| z#0Bs*Qw4K;n7G4I7OH>@Gl`~2-PyD;tZmd>Bd1l}gH-KPH`MYhcdUM+`QH0!TDElB zMzmMOkc9OE&a}$lQOE~2-M#&>_M9-=fAx|iL>(o7ZAFt=AXMGb4)lT2CY($emy+R@ zitbNTSGaqQZrF6Cx`LIj94sc{YwcO;N(aStTy<0PWK}q>0N`}Mb7NEGbII|&Q4T($ zqlXdZ!ur_18DeL9Jo#1yud~L|p<bFv>T`9xl5<eWQ9UysQ<^pA@f<gLYM<l*e0X^r z>Y^5Cga4Qc7R*+yIL&K4xH%)Ol~@k{FX4;AogrweuLohLV(fs6e`u|xhBZ#Olw%5C zHa}>g_B3O`Ydj;5li&w=K0fwb>L$@Uc3Y>UeYZ0FCsouJ4teQ1zDMp6Sv;sSDello z7!ZBp0k(K|_*;Sk=rp)>?-5ijl9x*!gzJ*Mp<wOlnjOD6QT)SPCv!*h$~k&ICg!v2 zctxpbknEj#-D3L92f-NKtTSmk`c0ZDlE6rw*0br#6qU$>dp_x)2nsOHg|(RCIR}Th zD;vCG<9p&3sjl^H343>`1CFYiP7&bJ=z&Tr(y4L>CD)m2>TLO&r)?S5GuOP>Vz2rP zwM>6uS`uqT0DCigPp*)o$h`%-S8`L#b~Ov##Nz#15!$)p%xRsuB9dA~JfvC8UTmp@ zlCVTkipG#s8hK&5JLhNwgY$A^<MQcz+EHW6beWJqo4oX&7cpH7+dX@Dh6;l@bU+cX zoMCJBnsruG$=IrU)@yhssvC8^PU_lzUk+jIKvj{XPwufQ4Dr4A;(^=rFZK5OBWNlg z9zF_d|2ymQOb5lI#Cl45@agm<mESM_)tOdt$`hj1&en}juFT2UJBLXJY;aZg+(vk{ zerZSlTr>W!lkek9LAQ#ebvm4?43v2>Z~d!N?}$iglv@NP^D)Y~PNq#M*+qKNfTvk0 zVrtTH<i$U4LGYkI2S+^iKrN721I3-k#{WIJ8%G<GxJ}JY{U=H?f^ur`{mt4Z4~`ra zeGfi=d+}>+{>TF~$Ox+nHXC<2`g$k;Bq7rSRqL&T9Xn%<Nw(%9K&%x?^n|-1H>tRZ zkgu|-g7>+UwQAZ7(trWE%$%=AuN7x9c0S(MsiTS*WhQjXRHr2}`bmJIQd_&9xkuGN z$!rI1e(1k%bJJ*6y?m+jh*~^I!P}Z-X{}Z;qt*G6)C5}?9IDw0@Y+9mZFK4-(M|7z zCwVhBNKX1J<>AS~3Wg#kQE~R<749A?@)^_qS#+r)6{D~PQkWuypP1}RojkrsP!P~& zc0XgSgYw9F`J($Dib0DS^#ZX)S-9fMIvGIlKWxYa*A=1T$NznHd1UV#gw=U2fgeN@ zicuXGdX~6c@+*1|bhY47Vxj9~qSNFRu53Br8vp83Kk9@nw6ILM>ACnoW>%YD9`wl* zge#p$cC6GGnn@+NHjQ>h`t9s|fPy9`{uqNb;e&ge*(5(UX#{MU=>x5ON!mrsDT=Am z395Zh4sINbp@2ol8c1w>+-h$3&xuz*U(!{FR1{x}eRkU9(_v3QO74hf&N;AD$u#V9 z(Z3axztgR)Rfn(4nzxn8RnyGMz0kFL0Kr4dq>F6N|FC%@AE*E4G#^4=4OyYOTH~g( zik{0_v!sp77?f#uXH=5ps3Ms4Z5cY{0u@Pk<y2PYn)xbsG013p`Qh@gmC!~hUM}NA zp=%L-2R@YGJ!!m3JH7WYeJV_sHwu%oeR8+tw>w@n{j8eR3|o$)PhmgLwNoz%RxKDh zSg6|lyyWZ1loQ}EwKLw}mW}uDYr0NE6Z@YYb$-z!nG<|hHbhR;w!(VP+@R|qeZIgY zA`#hEjY!8Yqe5hW>cNAxgQkdT^nfJL6S6)nq*uH#3tRq_OJCuSWZ~g}#vmRIx=&+C zA!#^`EHoCBILLKuB?44s`zv(&!4a9eBRMSb-b{f=KV8lN`tuWgyZjJP1nlqRTU#&e z860`mf3fAEG9Wy!S>UXUEI*jOk`qICIbHDI6}pS>%eIM<AFC{42Y9dvtnP}>2C?o( z&pR%9#$ToD<Z<1=6MCS%-di+fZ1x4SORwK@^$$-r_7HTKFMjWTn(7xRa+mv@RrGIx zJ-kb@d1o(iF};yc+dO#XeSqPjBV{pg?SD>K{@b~?^!a9Fhd`p0%2fm<I*fB#q3??p z<yGFfZ#B|&-q90^>GSpUKX2BYp{Wks)S5DymVDD7?Lf-mCIef`BARSP*1rXlX^wQV zN@T(=PZkhpY|%(ymVKIS5qzrahRWV|bge!mRW?s`Hz+WYr7z4P?MK_vm;5ViT_4r_ z?GH<oe;=#zSnqj*J8bsVGS_Z0ODdX8j0VXyy>lc>rgRWYcri*VSq9Ee=^Bm4Lz*jH zM|`tIPh`7a4kG!T*^3#Nq}S~=8+z~5^d@uWlC{G~mY>wSpfhxMzBCo<%&lfDk$|24 zWnAuv)l7Xd2;gStw@l_cf>_xl2SIRwVfw1|_hEGgD5FfnHa@D!IclfF`eY%Sumyro zuEwURewlw6D0%7ch}teFRL5j@c9liM+w8Hddv5lUWVxhV{jzjzr1YJvvvZs7=_U88 z+&>O^dni$%TcF+END5XIVJGQ95h}YEGTiNt-_(5GuX$YX!LdSg-#Pc%$wK<Z2Z|#! zaG{m~TxP87vGC;9|7vD1rBKkPM?B!RSWu`Zv}uitJ2LKC=h|YY0mM@yJn6R!yj|0k zUF*g#ojZTG=yDVoplq){=c?s-UfM&zz5bR(_#@7r(0Di#t@BxHYJP&WbJJ(4NoB94 zmw!T7*TWhWO9ICP>@}*?_Tl40%4@y1^c!OxbFQDt2k6Ak!TM;BJ8iPi#1;}+r7Q%c zw6^zs_p2Jvq!gAa7prIVN;WrN64W#=PU_-@p!dK6-1fSoAJlFna*P<e-<6I+X6;t! z@s4z+X$O5t@YT#VYzRJvhSBoq^}&Z5csj?MH73U9#t++Hwvu_q{p<t{pY4pUoYEq~ zhlnGxg=sJqRdwx#>}z^4v3Q7l1z5jeq4RdcbW4eW2D|uk)4|myFLD(BdBb&&Pkh~D zH%$?L&7z3h_1<^TWq(BC2v`TO4j-)ZNh`h7R7Fo0I&FKL*y%yIQiuVFhQYV=p>ONM zf7j6)y3U!3&WeNY1Q-c`<%m4U>j`Z#y=vvj9r-2q;4XCRC?FCoh-mQm)arEnL@bD@ z=PU-8#vg5(W{}CW4wilK{&O%F_mt?k2T~=P60;AN9<QstuSr?DUQ*dbd_k(-wLY>{ zs6!ilhgAe?np$8l+ufC{*5+EtS<6rE9eVK$-LGn!LePDpl0E#urla@2t1{t+D+H0$ zQjunb?X>&Pxyam>oEJmfyA90&=C=QP&9#e0VCav6-bMXAH^N3{9lHVC{cug`8Wi}K zdvhezxpnbkqK6o(7+*{k;nP!m-g#BP#~sPeU4Ye2N-NC1vit+ojn~GgxN2bRGUclM zD1qlT8I8Q&aCNePRA8-?vaSiuoz3E@tdNUcZIms+`ZviQ39uVaV{g2B{AaI${yxXq zKZdu@wCl^9Z9(oaG<TnW3i=VUDN^WCd}Ncb#{KEaMUT1cThKl!AN2Bj8{K$OZkUU) zq#>gr<ZZxC7#Y0hau59AJI2U6te(>KqDHMI{1Jg@CY7p3R)J7?@|C>2SGjaD=}mF& z)?A})lC#06>PpCh^QbcK^KYMHPmx0emnt8>CfD9E-%R|M6x)X?QL&4iR~?}n^6Q#S zyIip$l>+drT%h(f>*9_fBKc+OU_sBqn$C`IoL)Y6ZSAp|xR?Ifd428Loh7_Uj2>+7 z4T(n}9l=ma$GXTBdRlx=E6ZKBUH4~pqRGDHyJrk21GTt!+<R+R-fRITTf^Gh)U5tD zZ#8H=Kr063E8YR1wpfna`q`H8cf8{xRLCNkEHQV`lx_m;v<_5yYZn`CN|CodFKeok zbu#;3M`uZ;j*3Kr&q))>1g7!a!t3>ct7j>&j~To#me%3vLwk_xDoC*3#>$5Lurj>x zi-w!-tP0{_o9nf!YeUc6-gD8AA$RE;6^6(}PN%23N$M0xX@zE(@;;ZHHy>@_gI)GH zi?MY!YA$!*mq%acy%}@~{ayRUeTO0?#e!&7K*(FvtPbd3>j(6@5e^n4(E}tdo47Kx zfRA$C)l#nUf(ITT)~i7%lX?I%>ZU6A2v2De8x<E0A1F8&e!tAJDGS@Hj&gmP2K5YA z{Xus&79$}sKa||w+;n}B6nzisuBIMyRw>q(EfYVep(-s3W~mg+Xi&gM+}7>IaR=vL z>pO5=+pivV(v4T#^r}cmFe>zrJ$^>%mZ=gc%~D7>k~8UeL*`&A%Fd`}tep{m!{3wp z>vUGYxh}u2+BUQAZ6fHB6%bhsmgN%LX;J<3J7}UoytLpts;B;L@HjSRE)-4vb^^Xz z=7<ObkWBy%pfx~PupR8S6Fwp>STAh2IJZ-TYfo{Wa2`m{Ve||_430lrrMdaT4y)H5 zi&zi(Ng>DBUXj|2YuZ+cH~xYhB2nLZm{=>1WFe_w{jo3)If#xWTK|azO4<jt{=Eou zqPX#wYf%NlT(VU8Mk(odsz&1mvJso?)tC76c*>pBL;J*P{&gxd_{dBBc*@_EyjAB5 zl`4ZM?iydmhjq3D_6+D?m@BjI`qJq@>E7o-FZOv%g*H2KIlsbtnXLVd0P7Nf9M5;x zNN*AYz!easyV#cdShJ=#?cVZ{H?orUi2$9n7UTPhWxw=|e)Gjo<gUM@cV<5Lw?s#V zO)|C%n95e$Arz|q5ffFjzH({E@mBYP7ZS;zN7URtxrG`}dO^wS^t>>a5ZkU)yZ!rU zNTrCAm%L<d9k)0$)pl@zo{<(l_zC*)Lbwbw>$#2Xb>IwUj%wCJ10q`b-%uH?Mz7h5 znMTvR?K>#)(I#*vju!g?zTt$;O!m;Rji>UV5i4MUoY^l|jW5GCmQB0a$U~XV4?%%D z3hBH1Km^J5(vSw_e%lVV=k4RU(@Rq=0~^0Gh=MI;KZvvin8>hJUOHU2p`wp+(4v4< zHgZXyx4hi15NWnvTBkO>qjKJGg${rJtyY8XKfZk$an9@3)8l(DmzByTG!C$Sy2mHG zE`Fl#Z0p*_k5snP064Jtn7ybRivn6*$;v4F#rJ^a2;#J|wC!j}hY0=XYjIU7fTYlv zkStLY!WjT)!w^vfy{w`r%r;*ZgP<~{!tKv0)3UKAHlLxh4nZs1G;+df%#xkU>%$%0 z9##TdOlXgnyW7PaI1!vM-XP@gkxJG*{5E&nmj4Rmn_H2dwuL>>AZoNngDoGr-?3b) zL_p8svp+shRIe)rAIs=?v)OEWPIeh!+1!7u>=n1*Jyn(PP~Id5)$VY8yH4(Y1i@Y= z*}b4bUjvmiSke3%rzuuXNSRS3VrE=pD*`bD77I{axjR(9!Yt;}(IR5t9YKyjMmOV! zU>dTLFTcmDlM&iAGAOM8M7J_FKmZ$$BRCh;5m^vG)iu+imI#z@jbA!=?>~~o!?KCi zpwf-cgSV65e>Z>69CoeFSZvUsUd*)SQ)y&ttztSta|LP7G<c`ogMOZebjhwDA+3AC z+Qk<JtecARh4Ny9xBh(9ufJ^<*41FP*7z^M>>Ues4v&c?k%2U<M%S>6lZ_;h?fj-| zoPgmJOrpckz!W;;nvtfZ#j4S?R8m8aTC7Ht$x}Zk+Mb{U%8)ZRZ?|ZqGQW6bACR#T z%9A;~nnfv!rCcSwCC9qfNh61r>cp-#e%6Kdb2R$F^WtJV4Ulov_(eO-D=Gb%|Cwzz zZF_q{$XP4=L@8i}%sX?SpxEZDxv!7MX#Rp0vL2n&U_$Jne+(}_;Avo2Y{hbfqNE@n zZ1_}`c@wg&AvQsyV5S>ee^9$J?n%*FAKdPaNEPRd<$r7cN6~qBCH3%e__74S0f>8D zKn*vpQgh(mxy>DpOv}ubnOPyYCyv}2&MeE7nYMn2BeUhIw5-h3)U?c&mF4UEC){)H zJ#fzV^E{7hdyKjiz7v#mU$a%X;IWxAs!_EDQV{dzqiSuOWqVcC2|Q7$l+Nqccoi=A z2p~|A7vAT$*gEZFk)sa0`()I@C!?YrWh7Dx<HA#cv#o|}66W7-TQz;BFyxkh?O7}f z>IttR>z|3$*3OhEy3d-UNBFt_r6Sr4+L|(bQ(k7Dyq1cc^5BS!yY0ofyAeYPH{o`r zI|JrYGv+88_-Y8jeVf`WOe@_xzVc-j-O*IN6gy7pGnEqcaQh-QQeu>dpyx>-Um0}# z%2dF=)=jqD?qrqvPb?*B=2Qm)jd0FVYRjFGLqPS$O@1XfwB}(fnr|}8V2ayx@!)Pk z>9O97g84rAaMR^|`nX$L^96w%ioqsa)`Nqz-p$Pvi;8N7Wn<4;fn{X{Z`_i97iQ!r z9X<ELNdA<Z+OXls-k}ekA1N1KHk^Wj5vlsK*(BdH<_>I2x*Y<avLK$yw)nPZ5Ubuy zM+xOYf%D!7P=;`grJF~JXefCV9jq=ko@Yem;jBK9GCUT{qUQ0L`P=Di(vIvCTQlEk z+DlK#hr9CK3k@TS09*6v!b4Kk`&ly@(h#7e@M}_#GEgv`1P2IzN38WKiGtd99_;NT zL)XKP?9s=4*e5EI`HA8N%Ombl7{g`8H|xk{7=@B@i{#9qTxMy|YVL9WrzUXiob-OG ziNU19+=wUg-mXnUQ~4roK3$~YvS!3b7y#psw}s)%u?z`>Y|_cSe-$Up&xQ{Q^)OJz zx#mLg5>{m4_>tOfr?Yv6QWLvjpvbceOdX!zS;L5oP?^+dRK-*EWBdSK>Vbg%N5xQ+ zSjjVj#j&LpwvRg)X*sD%4g{j0P|OxIF1il&mum&=<>pKJGj<S~;DJgwPe~pQ$u{Yj zG&oCTi7AAh@>!EL_of%-dp5!qY*7+=SfgCRXVQHOK+<(-c(d0W{DoaMyU&tK&^1GQ zk1&4#F86spgC285FzIb?lVcEur|1`F;$+5Xc4~adS+L6ETQsK$mu8WUg-T0lp#!g( z3!kMcynJqBzqzKc=aR>vY)U5X_RPA~sR8=aJ2!Q@ei21uN1AA{6%PY6b`Nv0{x<ih zj@JS$E3^nB_d2FhCuJ5Y2tMY5EoMRqyN7jo6jv)@eE)04SMWNE6th+Wd$ZkqK<s*E zZEqqrUvbcx=rHpIe}kfPODk`=Kf??sHN%#O$M@_!5ErM4$PeO#3Zj9^u}?+UQn~9T zU>aym<466jU>4>@V$3_NGYxf_g4AhVo10d4b#D)Q)$XD*q@un|@CI4`=m6geHDmA9 zAZp)~kCo$c`Js8W`n<TZJN2RMNj@5w*NdO5ehfWI%^f~eKlx4w5u1A5t3m#F2ThNJ zV~|HI65chU3>p#-q%6>Cr~u<rG%$U0`#^_S=Leg%IP5tw1>!%)+D#!}u?Ghd71ms! zgd+X{8P`xHvtuv^|4saDgkB4v-Dq=kbEK<6pLR(UMZUSoCsA%L*i5yOSBUTxXALSD zrDFmzeLYelTYJSGSZFUz^63+nKsf?xXC8aW;fma4yU@h4;@WuJnUiG?-z*-yAVdmG zVK-j|u;t#u!A0Mo0CIO;7c<8ddf_sF(+i*eh%Gv#9Q+8Sp2@&%66SL5h>(+$a!i!d zD4!`mI7k#1Iqh1IL@VW8XhX^TbQOCNJ*+)_HmZ34X%$2EQ4f;b1&1ZR5!SboA)_=; zr-4haOcoXf`3u*<-SMlsghiC0(27~Yc42;ku7cT(kshWRIcIs<!|`w|Dngm(Y~gc@ zJLps7(qjHF^q0c-SmM1l?5Ak?&~&%nqVmoXtR9U1dRd)`k7hSdHA0YU6yz{~O(m@@ zkxpGn!I3tqXh$5m$Q31X)J`%x|7<QPkbtT;4aVkxnw-LQW}{k7O!iuX9MBOhpeHlV zGu}r{3SBj$hpy(ApYZ)_cen#mm(h)_zbQ+E+aO}lvfDwzdUdB?#S8e+k*`eJ(F>!0 z%GXj$ZWUZ3pk&zDg}=Zup~P<65*+FE3aK%`>)gcQ13dHfbK=DL(mJa#b@n*85NFt! zXBF+9N}i%&|8kJJPv%&p?gRTyi=hI)JU%!}*alO@MlkagSPRuVBxHg<pa$M~r|dnC zylnJUZgXzvfJBni&pWhb*MeO}1rzZ2$B)Pd4GY?O9%mhIWxD>mUuwCbq>=H^<~0-) zm42^e`I7<^6=v_qf+-elq{j9fC*MMfELpd{&}y?t{89$H@3ieuQJo<Eimzxn<=gKU zKIP9krQN|mrJKF|hJn&<3wH>o&m5OpVv#MG{I9Ezy;Wzv`0pkFH4Z-#V-oysdyw=^ zdGkt0KfWG9nA_}n56VG}NTl~li(e^Nd87QjCJkX74)rGC4;Hw>QK2U0hv6SdBe{7E z{;8h6i=K{-!b@BUW;(;`S_zeB`kSt{MME{yExa3*f;E-^1yqUy)8le@>f`B!u$E>` zmSJ%8bB@qI?(f>w)h-RiUQN4F%RpXxnr_H8Ja~5WK)T7mEI@m-efY1DIscmiQW94` z7T6hC*#X}ye8!sBkZ4F<zPD&~g(dz_tXjW>8blMy0R`$tA;5AFRC(;{W{RA49%@(} zqZ<NKo<H%MN8o`1)`#Jj3Vs0*4M)upf5-#`QIy_4l=SFFn2Rtr<+7L=j!j3d(y*3V z8rGfnvBAue&xgHvzclK_uSLylhY7ZPnps;0J2Y%9+ivwf4d4j@UYVGiM<=Pg*{kET zW9tGjEq}4hy;5O<Um~4&TEwMj{q*+-{2A>iVW4MZPNQDfo$(IO>$o>U0y-hs=y`2T zBNeAW!xK0?p`_`$pwZ9d@>b0vqA<N*c!_hwya|4mk4S%N;&FW1{0r%3y-+Z5M>4vQ zFD(x{Y~CXfgz*A}P(eabQQc96(_WU(R;|0w6;9PYB{zR&CGdF=x=f<^C5v4Z6IamA z!P-hTm>WkQ_U6t~k#QY3^k6H0cjHw!AAQPE(1y3S618tj@D$#BCy9d)qsticHUK~l z`7mTV8g>VjtMFM}tUeT_1y%eAz(J{6Bq%<<du%<~1}?anmlX+!aTkRnEj9IVrKv}M z=%W!LlZqT(aVB4{*AvZE0K3Y-&eM=1bm4!QQAgW7y|uMc1eB_tw!kff>OYa=Lv5Zj zG*>?eq~l%^SfpG_ux;a3&+*uMQRqSX!`z8&Jn0bE9$g-*|6q0JQ0bh0!B_A(TSb@& zjxT_#7~<9N>^4dbNJHjZ2;<DvFwXD9PN<cI81QX?6Pu(>99hhK`~aWE`_2F6>*Ohq zHH@D^$5nN=wCf)+w7e#Tmw_TTvj?2EBMKAZhf;sdFBK$ZN5Zo_(;qADp@>7c!#rBJ zOSJG0`c`ObLz|U_WJz+Uv#<SQkp}}0mdKK89Mc!T$I$DVWu21k*{`%M1a5JKH|hHn zJ0BX7{_+IShL__0rM)h42cJhjp1?evZp=~(7E%t=k30fNqVxUBCiUtd@KI{lJiy_v zUjW)g6wieasc_E%oYv{WGBQ`)OibI~>u00N@dB#zJ6f4q!lhTKe6UsD6SS<WwAQ9% zYXo-nesU5U)qdC|i;d+SX$T}?ySb?8IR%@XhB@m71yNns1C~`!-Ej3vBGA>y75A&c zz!N&!oq6Rdd+&@QW<bckdO?^+mmM=hkJ2>_Sm`QEd#?SX#O}Dkqkoz4M!uKYdN#pF zoxxkjAauHHI|UGN21oJ0@K=zFg7wCOcq~Ly80fMXH~PHak&AmT;-quHsWS!Dotl0t z+6qEvmF8UkM4>f&o-P$uTmg5bqB;Q+q-~hefy0EYknnGykQW{Oo4%;v>1Oo}-jrdP zm8yB*iA}A8BE?*>O%PLqle(?0bBnekun7t`&k68A;ai;B;gpIZe!!%`{))n1^9Gxt zY~5H}gN%6F&jQ4A&puOmZzsMas4>T|1^Xd%A6&kVvbp-#6_9iy@yT`azX)TUHpdzy za8J}<)oJ2Ko%{mBseQ0cZC+qxPI#N9goV;xKhxO!MlH^d4C578*I!zqHE;6}htk4< zAXGd}Q0AG)KAl0w^(nFIiea%z0R{deWQo(3dhYKmZJf%wgn}b<hzewkCyIQFgSp4B zZlB}dviACd0BpS~v~6sv?AGINtUq$J4H1(uB^eqs|AV)Yx-&^aLIx5~;0rjzDLgD& zZ1Wz0*mi@|<q4MWeeXEGBVX@zRMA2H8$^BsV%*h_tOj*|6m3)H1(rd9t>WM4gOLHs z67E9ePYptD{lZ&%4R4^<BTAx!8R5(|#UBj8cp54ys%6WI^waBvs}rfJjl48xf%r+* z*NYV9xj*6lwtoCTf@LLn|JGH3K<+06l|7-?LG+6tSsnuuYCCKAvo&0lT-&t{=OaJg zKt&E19P<LZx=76;z&VQ}B0PNo&4m3VBL@yV{AVra`(a);7N_F)uueX=465ifaW!Ed zXHLiQgu76EQbo3a(U8*pQeFOii@-kdkDPPiq33^!2VrzgjaIUAjtYx;s@jiPrK?0) zsts<6FG5e{oetX(;xICjv=o4N|J)dfNk))+zn1kUh9@(|>Bh%4wOIPpD{OG=ZE*J^ zTqDf18uD!JU)4wO8N524F-1+?PZD}NSly`eGz@_H(#Ck3bID%s^uyi>&2yus-Pj+# zVyy($KFOcgf3GhDbP-XGuq4eK4CO`GAZKP7G>KYal{h{qSzj3*62E;@{L8?xyt*S@ z2zNhibCwdq>U!}iZP<&ZV-^|p<A<VLZ1%x<@HZVD4+_Oc|E@2HRwr4#0MUOY1^jh_ z)uC+3L`=+A@C^(ztDDYKkK0mwL^Z!kvndKHC0R-U)x~YImf#YWn6Bq@kPex$+b=Af zfP1=giqYfqQJL6Hm<PZJL@-389&&d8GEl->*n~_&06EoC({}kEX7b-i$Wq4M`ngtp z3;U!#fh{G$`Mzj?tXGq(c)&eREBr**eD;fj3fvdM-{v%ym&`ui5V}f7R&s=ytG|{= ze%0;N&)p_)f=2UP(=-QBEA@M-&%JK+#65)A%ehN8Ka^3R7?`AD54)UVZl7O18~IF1 znO6t_9{0p>Qal9zbLAJ3-WN|t&;dRs2g!@sx8?L-&%_P@%(Z<bGfHJe3rLQ0K9IvO zU7CX`v=OG&=p>csT*<>87FmmOqt7&{K8D^PrhTc1)qL-<Wi2=YjB>6}nNmAKZgK8^ zUaaobO6CumDycN8^vzkc7NQhKJ!E*2idxo`NOuiA*yvJvmS8%4H<64fai9YFe?lj1 z_hufv)gJSqGT0Nf=8d`-&_WK^t7yZ;YtFN7cNVG6I6hfG-I_ox4We>^oz3Gy$81z9 zzI{H*ElvqJ0%@(<D_twmzWe*qZF9y!ui94`Dz9wbs6M}6`@{{!R!4X4VPD@KaaXzR zInpg!>p#Y&9mcWul3I*E?nP=>_dU}+oosdWL~G6GTOWr_+};U;aVx`3!gF+F0tYjC z{|E`s>OM1i^GxL18-mju!6}AdGd6X!>I{l37@cmtLPy^&xJ5}wc`v=Q-L;xF9HLxN zv_7g9|MG-N0k`AttCN{@w8<}2<{Sc*T<zFfx3A*y*2n+6B<y!SXTu$Ns=i<mOs>5< zUDe!|EIcm9aDjgzck8*zbxbV8ilOa?COyDUM9D~qESx9yykAU>DX`5I?s%9lG(bgV z9Iz7A<nV;U_=VJ#v-x$aFWd^;VF<Zgn__PNYLlM%0OVH8K9DZDvs3259u2s5HnIZq z=gzFs3GGyqywars_j`&3vLSn&o>|?vG)Wz3`*3?(S8d_R6Z_OS{nJw<M~l~~Q}KV# zyq$cAvZTSK_P<?SO%;Z=H)iTn&mg`nAT;PzJ(qVk;vw{#_L`g>xCR5FaSuLL1UI3n zBj&@e4Um$=2XV~Cfp3$lg03UnPn&g#c7Hj(|G+7aXCd#vF`^ic8>*$+s#|LMkS;kn zG<-r?b6QX7?A_^)T%rwi#sBjy*6XUEMxpZTm2}4$n7B>p)tMV~ROPH9d`kB--`a!4 zmk-{&yngD{<J+apE`m?y1nN7c$qi-YUt-)*QqubE|E-hf1MV!>#Kr4%e7N&Oq(10J zz^6xWRR|3k&qeujQ;!^R>UIOe=$l7CXe<{2ee&PYU2#2E%t&6=?e*9DfbhI>ZE}Lo z`v`-LIUys{XO|i1uyRP~MaaF8_okH>jqZ@8I@FD81{GU(03ik$py3X^nMmFOXU(1k z$O3Kw;H@i|_+smab07AQO`jsPOqK;g>us8i-C^Y9{aN=7zECUfYBZXN_9#wgB%AC? zz-wPC{#(lD{$oz`t)-nQKN<SK?dz~$NId{$(DaT1jdt#AM`_b@%O!Rp>5i7#1m$dE zoNKPN)*(amHj0t6%er4rzGLpjDN$85vxjWp0m7aGmDBOiBD+yVWm7o=H~2D+ZI$$` zh18MBl`#nGE!QI3<jLp{=XM^()TryKbM7TV0Ay`v&v5>YQ7AX3+t{6<TS!8Ps+?MV zQ|MPeDC>99fllY{l1><7>2GV7X>%zBNGZ)769I#+&=C|cGGn9pcHwdL{xkmse#aTJ zd*ET}f^+Cn)d0ulF85{uJ00MWj6!+X<BLY;{{h}#aY73Q=jhLH6l8v^ek^UT@Bz2{ z_?0+%6I#%%mu7gTdu_~YsW*D1s!a7nh}?my?;l_Eo_D66+h%=xOmK{A7GxM*e&W%M zqFYPHOpS{x$BY--fdTy-8oF%?Z|gFsAmRkfh88;+LOR~z<$ixFrkO%S2{?<hB^Edh z>JUjPoGzN9?wR|AClGQ+0wdQst3QCzPo8>@(D9Fk0G3QKaX=CKfQt}_<T8p*jagaw zpF9q5VJZAd?4aE?oCJ`cmK9L3qacf=q1OOLK}FO({v*}E8mwslM!0B$R}jG7jSGc# zzLGyIp<i_zIa6jI(~((sNSa%hA!i#u*8esRpxD&P#6Rj>X)b&6PA2X_h53E?X5i;c z94`XNl?38{)<{lVGph}~+LfVt=JWckbg56jva!IIil8c~i0(@CiFp5ShZr!l2Zt66 zj9G~*5SKymgA|lxDt^>*LS!Bawxvr$H|m@Lfs-V_tk2I<NCV({;LN6jGSv6iyR!1a z2PMdW=N#8V5Km)JJ%FhVoOh6xzr~<@)6nxlWe))wS_$O=EtL()YN9c;06722#|XG6 z-165rOhJ$B?YwhAS!qx8g?DaoPYgdlk~G}a9Y3t4)(s*!r&Hfa1BckeD%zlVy!F&E zF8<+}|LV{aQpcyptCSHwJ;O4t*NKDJu&TR5gxK;J>q~J8KdY3_r^cwnmcD-N|E755 zb;2o&Whz4Y*jQmv!_4JN^1#~Pgp=)?#!+f#i{z8ikDpc>jkJ;q>c({=lD^@36q^Ru zLkZ_nC(|SY6Nw^@iRGU%Y?6CZ@hU1!1VCdcbC?^vn5CKHWTrRZfpZw+p;c+g<%0qt zYa2G=mqMZb&<geoK1Ecw+0Qp21`s;s(MfS^U^D#duPkLYqdYh3m&DWByBp3XKOPpG z|5v+yy})!Q9!ix;=?;-i%pU5cG1D|sQ})&WL0KJj-(|t-_7%r^K2JaZhPtUjv9zaB z-PGLyni<k}gDH9-(VQp&L7I(0UOw57>-(F+Dt+)Oz8O}z)SV|7xs{LYrXhXnjvBY( zGZQ*~;6{{VVx7-aN>S_0-fSUv4=L;qG-MH9X=8k{p`)YAW+8te937f!E>a6(YkEJO z?C>j-&I8R~S=FICJ6JjOB<#gSh@eAZ*~UM8(aSCz1lC&)b8hO6IMoqU%X|~Mx3owY z033?e<oNc|BmhT-gK#(l;X+jeLpKjAWJ%h}z)b%-H3P_LYf}&Yhu%L@&wt-~tBTl( z6$ZBZg-l(cB4ZS+8l5PB*|u020kNS_8VTF)JoO~{>RYTO__+|Kwhd(Hp^l(6XiU*= zZaSD97oA!KYjF%m$PwyLS`tv%3A&1eugZbz^(?vRjx^a88s<p3h4hn->H@&#n1btk zveF)d;LdBYBf0}oO3w;&)N~Zbc|zju<ci6&jr><cP&NoWBL3MElzm5l-A{=-GPAY? z2^}vC4|=o{7D3ecWQn`63?tMs7;Mai3}Am1N>O5i^}-u{UqUO^Qx;%v2e=Bt<Z?>N zrjQ2g!7tkhli^(Db6s$|!;i*<leR2$0@RQF+j=3AJk}uhifiVQtlYM<=T2z(VcLLv zGZx>3Q>l39(bB4xcy$Z)@mMrPNM@PKCoVt~iVuH9J3$#dyt~!SyT+2)ZOyB9gTn4( zOc~x@Oa1Xt*O%2Sadrok$R<`(;db*$^R3L;BOR#1r=9stE-wd%g)T4iy07#)<~630 z!ONvIZ0fc8tWVAvLHrT{_~HuvAf=esSP^p-EScJ0<}e*1dS%Sr4;w9OnaOlpx&TYO zrbGEMD(jRcE|&Cej;_u~85CQZ9MH!Dd4m$Rv$1z`eVpy&e=!tH=RF+Jp~dn+R6u~m z`~vAOIRvF04hwreqRWtN;HRgXR_k;_H^_gu8CidD{4z2-X8aCYiy|W^1~vX&c!0-C zn{%(!vc{IE_bWY`ngN!2=%lfAazX4la)!Y&BeJ&X*@-9YTqA{kv|)5VVQR1H(1j0f zW%dPU^0%wB$B06|c15xi(V-X~dqg>FcCwzoFcbSRCGwAL7u%YzV9m2#)VR&IJFz_H z%0i#9azoma%wavWCBJJXRBDq3-|*@`(wRB57FbEbrH$PEgofTN!Kb=hItUt%^kdK! zchZanT8itY54z1Cx(P@C3f?O27o{XM4zG~mwvt#E8p92((3(A?k{QvQF~0qN`cZyy zrkz_s(sG0RmuRN&xryKyGl-J+h=p9Rz_LnI8)>K8b&2-L-9T^`B=^mP=r`<Lh#d8+ z`c#;YO{ML9I3W!*&pE3wSU%#Y6wL8NA$(r1%J=XJ1$y9Y@k1`3Itby{U^6ABJHm#~ zTGtu>IxZ)r-J-JeD^B5}K%D93rHQ-nTq#jh?qPH5O8x$mGEAP#04-In7bW{K(@HM( z2plMhAF|)F`;-){>3XKJ*#w(;DMtm0>*gSgy%o-R-mSP1ANJhdIM*G)ganw<UI@2c zdFTQFD!{J$CY%Pvv&(Nz3Y-fGP5=VOgp+66XOcDDO)R&CL?&Ut@39P8NnLQHP96W@ z!B*L>F$DGKmzx!FQpZ<i^j^A*dZ<e5FiqcD_@?}`Hu#kF{{q<zsh#MPA^Jo}F+Ww( z(M&K7yi1Es`@?gcJbK&ILh=A+7wk+CSoMMFUW#Cc`^qtsjdP{MdRxK^{eO>qe`Iy{ zLecRPx6LQj8y*k1q}n=5g?DZ=HJiCjkf!r36`*>bm^64(@ykgQt{H}e{VoU4b_sMy zs~O3|JniK64KX^-SdD5dzZ(aF+tp}6Qe8cjaVY=?pluu*NKX+<ux}YW)i-uZ9wl|A z4BxIRwcQ|mJXYrJRIqM8{8cH^6?^*WGX$#Z;CnBed&%h=b$qwAknSDO7_9VNrkRwD z3l!plFbjQIVm95F^oWS{+S!mbWFw9M`+QkvawaJ-D_@E3u&0eq`1`P~`-r1#r)yBN zzD3=o1c^yJCDq+^l4&K2i{g)sJxoHljfFcz!{1s(EZ&E^jltX8-B#zV75W1e<|E#T zAI*`_w8kCP-+-zD5Oof$vH85$hx5inhQjzE8&OGEkL01BxCYCFj6w+t02cuwqsu%| zjG*D?ky_(QyPEczFQy8e!Vj$z(?4ifa?YuVA*AM!n#)Mleo$}_fzSqpOYmq{8DEZX zqzm7X4Simbp41+-ye|D{0CSqIyk4jGeV8wd3j?F!N`*3h68VwMY35t1`Cs*%OOx;2 zL|AmdKpH$~2XM*yO2dweIKljb$M$vtnB)YB*zl0X22i<7N^nAC8mVzAF#{M2uM@-2 zt_#`6WH{5}l>6ap=7ja&_ziQofjHc5pZgw3xIR^Z1VA;%;<sOj?1+0PzoY)SAa>o_ z7;cT10zB1qBm*aa78D$bjT~(D-1Xosx#T$cD9Ksl|1vOoAmPUKL`Rxqf=lkOcgAUi z`ornmBV6g24(L(3^!<Z=Bm1z=B?@j{;`<Fjo@Y26x~|%|s50uxcX%&6z=iLksNbX| zwnf|J{N>Wo54x@v>3|EL$R(IzH2n88U)X8BT}jb@dah6{%ApSFJ3$o+#EkO^>L<hT zXLopDYp1%zcPoW{P%j8>z(yu;<HE6guJpKR#dzkl$a+2eQ&&|64sMKvYxF^>K(&=C zOc{Ws!C`-Hp4SJ9i*bx<Z$|BitziXTkzovVJ=VJ<DdH^w&{N<vz_y~qf9O=`V#&(N zsb6El-C88oB}1PTWb6?5YIDzdYt|tuSVdMAR)iY@$bb3<@<HX1c6jRqr{7=nB^Fdq z@gv7F;rln>he4T^iBh{%>6@+`gq7N1j#DH@-KYcBFOK*<5(ZKBk1pqXvxI#orcO39 z#4ufXmJO}MhJXb_TAfWN_TpfPbws>I&JWz(84ZOP(w<;VV>(=?18TA}4b|sDAMnFS zbJZp;=S|IvE2c%puiO5!sxcmC)DW`;m$dySfH$Wl-pxozctzUJoJzV>8&l~e?<%}C zCVUeG{Gui<0DuXWV0kJ4Q-W0YzWC$x#e?4rCZQR@SgXs?Cm^GHd-`KgC+oVboS^;k zV(@}zwoV&-$Ve&zcNBh9SuI`C0I4PUEeIRt!WT@<iv_N@gY|imaP6f!!WV;VNj`YR z!RJu*DK~Y--b#f!kmA~+1|cdz5RP-uH^Xs@R*r+;g0qH+&Rmh3D-LRWBo;-o?s<e2 z2v=uAH9;sAd(stRqd!;u@k*OQ;UO=iWMC45zucql9X()&*&J~zfuCM`dGM4@oI|Wi z2RN?udro*fEEsf6tR$lBzU15+gr9anP>6-!D`J2CI-+>cs#22g+y-)IhR?~v;7F!R z#A%nQt<r5G?!o=b*0xTMr}!c{d^j}B0-MS%PR=k>GwuuliF^TbXK?osjtn@d17<r0 z8yqYvzFcu9=3p>8*Pp7sWq0F|r=gydWAkZ5P&C3HK)7?SUJ%24WW&5GkZv2nIY&fX zKn*kdxQ@7M3gcCu@T9bn!2hyf%G7ENNr?3v)a+8*>gai6(ca8%+l`m!y+1VBHZi0c z7y(EC*&`XgT7!=EjI;q-S^x?N_%AlYFt_A)5`}lDiGQ)Qr$2DZ{F)!Tg01I}U6OpE z@fr6kW4G*L;S=eGApH24nt+~_VX5EaR2OPv*Mofqmu}UCNlK4)A~d>TL34F?W7WnM z3ijv7I=QQN;bMGuy{jDPVvC5654-pm?u;Iu;}arOgy$(>U&S7Fq{A<SAv;_U0}_0U zWy3c=V`X@*hPazC7)kptBGw(jz($p)O&gWNRpT~ZSgy8ySN+(oH|?YQuM2qGSJC$7 zlR21XDVQDm56*-i--s#!3)_u}wJqU5^?u;ew-f{byaKVeByPnfUHXgdaQ$T;>IwV( z^U|L0%>I$Y>wYaaj@=H}Fc^@KzO_@u=gw9uE8czaaJ!pH^pK^=59Bere9NjNykGYt zByT@hH*AyVFK~xbm(D|6eFjAy?Lb^AgSqx1XkXyy#)5l#EcXqBmCjWGyA1kALvcyO zo4vVT`>ezN1j`To=e*%6s~m6bo4Fz$e_Jxbx*xi0ZUjN-(0k};18i>5y=j<$opm=B z6-)Q)hfPzjcrpIoI3ylY6ZBF9)ZrDM=@YgNlCJ}h^b|f?Bx<a^+jc;2tz@G47D*{M z%?6*<8=R+9m8*99`mx;fO2qlSELk(Y*ZO%om-!AP8z8c92G&u1hbaVCl^`}6@4@kx zksR4$*1iuO_FSc{h!4L*G<&Wpd6c4F`s?~%NA(^<eP0gZ;w&s!0BQ@^#EM>frp;1{ zIqU;Eo`d$dap4z~I$zs564njzStBt+g>4}sv{9n@%_<{Yyj)j+JvPD&2-KT{R;Zl} zFw5HSvWwUSS_g5hg9rw+QC&$79Be8})kAVNOF5_pk|0s!fN!wGizGHTZ_$A<lm2Fa zkDdbMr2O;Ex#IBXz~x8R2Tc>DtmQio*o=iIP+QbdA)*gKalgkse-LHv>N^p9xwl$7 zxrl2=S@YZS?u}-NJzX_*PtPvOCrieh*SXReWHxXz<Xtt6pcr*e(f?UJ&Y!0I^&>L5 zqRfIC<5&l^-r>SX8~a{~BAl_;#*+~441^<1&okQKP9egb4)+EThyLKtw>;Ol^a`NE zWkfTNrcRi;BF^-lH^yp`s7+P=F!ecTa3p+JUi+U9qG2i1`W?(LVDzcvq17u*7}yk~ zykBaqsVklF-Is1m<Qc!4sxI_|b4?C90n|q+k9#Bn?mr92dke)qZy*Y4j=|2YYItH1 z;p+}Zrp`tl?-cjby}gJ$JcjV?fSy*u4UCjk72}d$s|Alq3x4tY2a$Y4k#rRaIm>TO z?ST3McP}VMDOVnuU%Fmnhp%y0S9*s`7?VzH!jG?BnLUQE-PmVx7_JTuYe>S#04Bi& z5xzr5c49;1WcixaHJaAPoyWpGO>CT95J4Ro)(4Bs=x|F8*Yy(DB?h7o4%=XCEJ3Q_ z-OM-W>gl}6pt|$gS+?t|=QDEpEzWxUvBGz39|Fc0;G-I7;hV}(9&T%@CZ@zv67YR? z>Z$_JPaXK>w4&^qc)c8IHV3Qi(KusSsQcoq2<frdv5Vf+eFER+R9(O#C-8S4E?@o0 zqs<rb3|x-j9@3Mti@z^Em6ax4(mi_hpsJ80^~n(*@WtxwVF4(y`R<-)&^)7Pn8*ht zl}+}b@;UcI45{_|>D?o;PxV^4Wb~(ZCQY;Xv-_i=0a`HBw5Ih#80i))`dcA)=T}u- z&jFQ{_&pI>F9bh4{&jx#FZu2IYmCU7@eoG7uCXD1c92RR5e7(6n-#ZlH>*whwsG9G zhX?bXeHu80aFNUau|ES=0@Q=AZ^8fNk<Lto%YT9E;~qBz?miMCj-~6yMqJ8B5~#_w zt!`;=yV!9LS5>CV^;F8v#(C;igu1BbrR~bZeXq^WrA{2FCVq!%A@n|VdPldcKLiV3 z+><9F1_*px^_uVpaCa`=AA7~-&!^A%KKr>aTkKDgN<Gg0XYAV_8*-l?t{NH<Be;DU zN8f1t{N%P(J9&2Wv*F{mbu`}O`|BqSwuiK)EU%rcmUx)os-W0W1HRj!?;!EPHulAk zQ@)}>I5FT$K#m?Le0tyJHDUZMZ=s6b73kLh-?nSeLc`$HIkiq{*EytsIp5Q~`Db1C z4{^UvzAzAL!^!Noko!U#f&Y~iXVX4U--`<AEOb@};Xc@*VZE8bTC0ryGWZPm?8Uu% zFGVol!r>1Pt$#COpN+eogFAO*d~@FUoV8<vJ^K6Ugc*Rf$@egTa_9Q@AVuZW@CvpT z8A1^KwV*MZf^2{qJUBica$gF0ELXs;YZz0a4B^1JJVgvkSxicoI7#OR6v95u8ocZ0 z@fjUaqA>s(6bfYkS_~4yrNy=B0D^87Xw3T661Dj9*~fz&K|7b91iNb4uu~G&C<fDT zZn4q<4$YOK_()XQ?Vrb&uQsEiM8G$ECAKL?LL;Cz`q#wtm-qMiq<0>C{qVG;A{Yo4 zYdF29LbJ*$?#)_XTm%rXD;1~@u`1OKz9q9)|4a{W%;<V(UGCCTQNW)ezhFK~FVzU* zak3Dt+JMpk&OU{-c&&fW%#9NtYX4@QT8F+B3vKO~dy*kUwAS?=x5@vxerB#^8ppj~ zqvTxc_+UP*zf36hvSON}_Xw?4mx_X6#472R_|8>ch9Jc3K?slwonydCf=2;?eS~9! z6+!@`<Sej}VJYSp|HTUbef*NVw!mmVNLm|d$Rq(f-pnj{NTx&Es?hI;ZALs`E?f29 zSUrL`y4#x=x^fk-Jpx3p6;S_C26QAG_OEj^j$%S`i1aZCMmx0i+N0UVQD%<OCfiMa zuFKojS*-&A1#VQ{X7a1mZs-t!#zdasEwQt$`)&W*|2d0Uie27co4@Q@2S)3*+;<XR z?MJ3XkEEFVwny-16bhj2>i)X@erj4CC`CnxMMA-}O6*|79)vLZ2Z!%`5mg19;g&f7 zLwk<`Fh_yn!M)8le)vZE%^vZ)#yOMX;WkcdKq;2!w_oe+*q=FecY6btqujV`jw0VH z58kKBQhj1S+@bcQzzCp_U)31?aic${?=aqFOC8TSx)0c1&=xjLy)FTmTwfNsO$p9w za$q%*<6V`mJ`}pWMhNKMuUP8MbSqaiK4=7t>YQl)w)Z#+AQ`St-4*i%=7!xry5DF# zc;xqqrk%iz6HTQ@AM3p!#4nyC*2KQ#hXK7xJ*}aqRE}DRRGCA3BlzEpT8g#tY>xN7 zFMS0{-cb4QpIq#S*{lk0x$|)RYo_^rRym6NK%<eOE1>RG4%JESE03!ia`RI=pfLjU z=4xlN_Uqm^6bTtkJxLXKRHGs+)N8ah7yFdeF=C!=bY-Lbsp7MM8AD}zxov(*C01@C zHL$18pY;gA0aGILM~}FiRthHlpzde~^I>TyUy7HN{mW<K2i#Cf&<9BDiz~tt-<5!K ziw{25%E8g*hxK%q0cfe=nNOF|yMG>I*I07fWI80Mq~N?ns2E>`nb4IDt_r~LkBpHN zQKKmIh1;Od(JUl-cO7YVburdsynr@#nn<8oY>9j32M_l>+KHdy>U?s8rHacn!h?1Z z>VCXs!=BuA)dcT3p2!-2F_pAT=zItz_#!dhMnakZ2a~YLY`H1W&fhQX|E`vsI&XF< ztYY4-K=))@TIwih28seNTd-tH2Flu-hS7Gra&WQJ6F}Kb4u8;Psi`a7uJ`?&T3;*- z&|xlxZ=DyA45TH6vV-QYGN<bHus~4xsXeV*fKp;15o&c&;jr>;H(?Jb9jDk^Xgy4A zTU2~%GZvF0vM`ZqC7Yj(yPkiS?<-uX4(sg5^Tr%5FV~K2+k3y{o!1r1zA${oAw69I z$>t82EWuLCk<^TDq9RPE`vbmg77xeXPc<5320JpC@pwJ)Vo7+JA3SiQEzUWOYF4U~ zbJ#SEX<ZjTiac?LEaWxDM8TbqZ&}YAZSnU$8yt_g?k4XT>ZX@lNo!D|r2HZ9GlCuu zLIv@ookDJQE#;Yj6NLBA(Lm(pT!WuxQ-sqg=IA-w`^W?u%Tg#-<E-4msnayp#VaVr z{XQCM^xaO_NCK>L9?;VNy$T)5Ru;YAZJSy2N^qZZOVcqPt;*?j-dbbyVCHwb82eD> z{UZ3F%9FG`aqmb09KiaH%3ua2M$QvRVy{3FNKr;3(&E}h`wge+$ov;U#0;LM5qfrY zGW?H#In+`Ee(n%U;ct&y9ab_G0BB|oHNoy85e(VyocomHzkMsCTIK#yGYql;5gAU9 zfbjOzq4p4mJxeJX&kay?Uv65W`hyzu>7#M(?w$(vqLssthwkE=i193l?(x;!5N&a< zo{|;YxyEvN4%?sQ2&s|(I;Szz($e?*d+3(YNTBe<K_7DjCuL|xia)2Y?ia@$4e7Am z@qT99l6iu-RIJ8=jJ4*)60ZCBEp+U?%|@0_fl_;I)54%H$MPRrgkN9TNrm_k?kD&` z*O2l(9eIRD96rzK<D$uE7x~}VL`zu@@wdEQv8kLr(gWtynjD!{DTT`4FUwXJ;99Kk zeY%N#P(pTe;jc)AhsG2rt{mHbe+A%k(05#nFKHnw9=#j1!7^LOUgBt2wnaVo;P_4Q z$hNgrUc|zTIXsCy_?sJXxX#%Mf94|W>tN^K(^o^skJwfkZS^aT@$;LoZ40xlAQWT! zOY0eSrBEUe(Rx{~t0>r`sz`2YgAXp@nvH){J{+!}0~d9x-Mo|Ak{t^*uie<`J*0BV zZcx4LV9p~2jZB?jortLG*IM_i^tcEd;^qi@FLo2wGEh)u=*_-ej{6S7Q;lMV_NTH8 zpM%J2aWD4aSO}$Pc5v*CR-+@q4u0r}J!UsfY;IP+tyueYI<>~mCKubydGKYd=~hAg z-%R}1PB=}yFZ}n!5iox#lvl=gnU8rgsKqjNkDM3kL0)W~K*X|7ZL&J%cVR(Av+q*O zt5TDV6yeij?*%OYu4JzlOKZCBg7N%ki5EAHDNV;F{#VOGdvO%VirJ$?SpGrJ^3X0r zzmMb1zr}k2gxPINt`(d4Li3=-t4Cp#&Wq*}=hm5`GyoMsO*tP+Wl8RM)E%%LgvK<{ zj--xxQpB%*c4XfaVTdUtLBvOCuga(McZqsU3hzf)^s?pW#&O4n3)cvn%U6z<9F$rQ zZ_>P*B1o}?`C}qHEQJU~rz8M5A)L~|qksxE&7%DV%>bYkz@PYU9W7ped_oA2+n~t_ z5BEzX+-9#tsQl*us?=ArW%uY3(awnz@0VKH3jfl|2ODeTpH~jf`ut7B7OzG#$OiJ& zaHJKt>_uO#mty*VpU=(9M*r&)mzYjr(wQ>LDN<b4{*3~@Q3&0wZ4M{rpG2$e0Lv<} z2i-HHMD$ncvZ1Q_SS$qP4Ka~2yBx08B*``-%lktZn9Qu5+?OpA16LjX08?M}rN8NK zRWNKSvz`8Quu#_oaD@}*Dc5m~*W@ZU(q(sP6D0+S_kK6L-op}l0kJW4smZE(9n>Zk z6%z#Q31{l(Fv;Q7{fQNK=J<mjViq?9DO~8Hx9XzXf6c*rH9)9XOA5KXSdoR+*UdEf zW_o#l{jh8K@<zETilsz>%Fy@&UH8ejK<|uT&U9Tz>)vVMNT#z*YDdh|sA?kv<V*W| zaf2x>(*+fYQjkv3GVlI!Mu%O4?jtC}(*CZrzcDMEjT|?-SkAtNDtxJ$4WluHd<;q( zlo8YEN{++5od(qn$bAeT0h`VTT79^EJ9n;d$GK0lKATB#Vd|gBp(Iv|jzOX<3G+$U zZvnt)CQ~^JDjRhFZ;nNKaL-&gbcX?L|B8O|WkC5#juNm(_6uu$5-J-Gk>$d?x4Mc9 z@Ki%+NlOYLF+~o9DzXOyG59imeCG()>01d)qT_OT0dxvg1opE)t06btudYKjs@O^@ zTcW$$=c*N-q%v#7>f%TTE7AC}3j^&6z)_t7l8g%~>aIGx7l!EsSL^1%(sNXk<QAly zE%Pi0XK`Uh5>h2Hw@r#c#g>|T5S6pB6%;H}Qom%+@{QzIS$%*+f=9j)10jpc4{9(B zYQ<>iGx09WF?|c&l3Ti}Z99qvS86&~-i-XdMCjhHFxFK5To5$LmoSG#MdsMbFXNOu z6gBT?wv6cHuVtIE&~A@1B|}<TQ1S<TI!2&azkbS#YJUD#`uXn0epeq{0f2znA%XWD z#o2dR9OK=55}m-<AFd3eY1vRS=Z@JgrQ%u!GZMWS`?wioF7N@yP+86_{ASC41*$u? zpFHQt>L3tN+Qey-xnB;L-z=d`mXf}ut}VU=Q!(p<dh-CPWSgQy$^XyRbXQ$r`HtVR zpL7;;N#XLPJuM=-8!#fpId&>Pa5BHl&SABKARnDo*^(0VhvZ;Ju3Tvqm>R5@8`Q&7 z2IhBf!IhE>U<W5rX?z7z;@Dxz%r1S@GX7O`rrPP**UCbv%l`2S_VbUOa*R1L>Lr-r zdh9Ta%HZ?PzC<srWWoUU<)y1`5;GY|T!Umv8e${8l*3d3CZ)<#BxJ9WdJ7kqr6cd$ zAfxU#lkczRxTMi+2KZU`>Vyn(4C{KCieO3t6vKOzuS|uKGsSH>g=AASO{WT}bJi4F z5tijso5DTse&H~;n#ibqB47$(Bt`BtR30z<lz@S}uT{$#mqSVI66KQN5V!~$@jl!C zml4VW`*2h$-@Q?K5Rm)sI-A-UQrO5>-Y7)&8kf4pM}v$TGO+x^PW906)9MZ0Fx6{b zI}$<G$=)}1zlvlwUq!UZ)B+)6Od53ss#p$w^@jFPY|oHf-a!}w_}WF6{6GhbD-5O@ z9U>o2YG=3Vco38&Y%aOuG1@MsK*Q~>$&)WhQMpXr3J5uoxh{g|zE?ew%Un}sMz>0d zaZ|{kk)OK}ZZTU;rX@|{ar*vDndw?_l$4vAdm6QWav|$`R>$aszNLL5y|cg4!(4W@ z<8_GwzogfU9}4OMkYvomoD7`s01RNxCr?yrqi=3y-0bwaDw=a{8ks!jo79p)EN7l| z;lp#FMu}H*QOp%(=;vfk++EEoTxK&1AGK|LdNiN84k})53VfCQCMacR5sEQ8JGn=T z*^~q==x<sJhraA&sdA?q&tR0MO^B3{%si-k*Q?mh_Kk1D@<gW87-a{=Ed8}F4IJ;U z%-p9va}AY6XlYn~mu2MUgsjRQB^i5{m`TBv-vqGbzRy(aiq(R?ZxsM2X#Urr>Sajj zeD3o<moF1~UtX;V>|_^44j~h~0TY06p!~KL*zrR`3Yi4zj`1pbOU(18K2Nuv*d`5( z`w@wcSj&F8gQ(z-2X7flDpMUYMRy&~H7Z*$%uxbucN6oQbUGW_sLhmRq<{?s(BLg8 zlZiyboPu&<mBqa-^Pe?_F4~dt-<1b~16<8SX99W$v>)tTYk3U|y2xK_$Lj5GTk(;9 z{9rCkq5dy5#2AgB;uemhA=FIxGPXg@T*ScKy^`^)K2T{X`*>Z|p2iF}2H-lK;Ymx; z+6_ri-0!ZG$aJ#wE^y+4a+n>n${X~vekcq{#T3PoFFaJ&QvWkF1*Df;<Gig2_a@HV zBX@xbU0~XG*ojB=ol|>K!l8U(DKgw#^72g<^^rFhCahG(eoQxWND*G1b|6Bh1f5)Q zXo80RjFZ#LCN%Q;vxgG_z8+WsZ)2$*pc?-CwQi=YM&I-?FCk?{7{57-dsp~$pqmcZ zfXZ%)3=Ub!uKMbmG?t2>BhND6DiW}-{8>95F=TlftnStILIgn6Z;3p*ki7Zcbft>g zJN2suJ$x2I>If-G;U-mi^f;mn{oV_W!f0(wE8-PvS!XR38LgsMq6`RXqsw8Or<lq7 z+&#IqP#8Bf=+HN|s|3tnEHr)}x(a!Vf1=%4{@Q)^&X)?cz`jZr!^&s7#dFw<uWx8q z@cKGep<dBTI41(Z#exD)1cIJJHn1cD1MImBBm&3v!|MK_C4KZPyaAvE83Hh+82stx zcCXP)8ShtB{1+&U6j7{2%1Gy<@55*>x^Fhx=)e&Y`_N4`bA7)}k{b#&sF=8ZqtOpK zpqsgoi-^xe$d12??bq4Hqjq)zJW0T@G~gi;KM?gQi#t(*8M@lVwT}L^P(#)Awz8Wf z@S9v&yBtj|3`E&aR-#{d2L25=^lYe9tj~`0M%bb+4SQfa#+MNO#?|5)lm<jd9DS7# z+&+{sde^|cd_NS&Z!xJ(YGF#_^oPhy66L9w{`+fznMy4pQEMN1*q_ecW)e_LT0qGD zM9v!sc^U9Yi#~MrsBAXB^Uzw=^ZsLqAJ&tyPZg(oMvp@z06Q(d3&+#51@5?Dwir^q zj=w)~kJ+UNjP!_ATxD^)C7SKV(-&vej@wmUtg&TOEFD(3dr^qUm^Z2lZd4Z8?V#T} zj?KtcOB*FpQ#~E{c2qbQOw6fLU!Q1Lzb2PAuvm~@b>XPor*~_!WLmE$GocbqhiHL9 z*_V&-ZtKXkOYVPG`1qT7JTvr0%e0?r!B^UQ#Z2&pHy}I48~AalW{j3WiyCuE5wwNK za8Bgzt=#5BmhW0OQI%N76fu8(-<d3*w8w0dOef>$v}qr<{fgXOyNjqd0y$XOe|8S_ z5or?AVK|_Hpr=sn3$&CzN5|N|<(KSyQ{@M70vKm()35efJUqvF?MwUgjj*IVVle-x zG{#1EZlBE(|BtjsWGduV2iV&pDddJp_-4(0^@Y=QGBU~o6a0B|xk@KTacL!+FA9Rw z{fe`CJta%oS@@LVKg0O<sl>zQD{~;SImU$ZFgP_fE0tME^QC_KwQd{t;Hp8U)yuDK zeM54OoqV3#y%EUffCeSE6@sSNR{H?Nh%w$mYwB`5^I}$&-;K4qY07B`u>8Vj$*hku zQhCd<2b7q7&maf9UO2_vmn}q>X}u<FO;?0ZFYk>d|ECwfdEm_R7}lJ%>^Kc$6iEim zGL4}}<n@p7b!XGbGT7HyW6Ld|Rh0O?57Mmg+7#3l*DyQV@Y1u2%%P&%Y$>JVfwMvA zFLqavopS_h9RIKo@xc4p=&Edy7b=O@P47WA(-D~&NgWwlwCLhU6Qgj&oQ?LXgXPDo zveKeX?07rN?eVs}HA3%iuMp_*7Vv^T8e(}<7wjcZr$&8uQBEGjxayjRrdU77z8PMP z?5+Ss#X5FbRVX3dRl+mqag{#AEa~5LmS`w7S7+m@&#A|oul)ueUwHmNuyrwQB<bQE zwt`+ZS!~$J7wx(~n4ro$SMGNG(7CjZz|-Mcjl;;3El`W!1qVBMD&V9$u{TAkV`U|U z74if1ax1NQA#LNDBmb|1KMU`Uj@XBycK6<lnUZ@^?zNk|A137T&pPC22!jEE&~^oH zD5!1A7^fhO|BSw4X2X3;d1E(6s%t|XPfFkDd1lLom0*!3smr$9P2pjxl3TZ<ZLo#; zP9?uyI5vX#4i1ROQIf}KEw%_jK-Y!iq0E4zYE_JYIW7dk=K}PJZ~*`k5W*Bx?O9Au z40&4b)S96Fswe6#^I66Tjk`&<bbz~0<7qmE-x->y6(+#Y(g_2&<Jzcxk`2AvrGCR! zbbkUGsz1MhI`X(${M?h-#!wN!{s8O3RbRVumBe5zWzvj}gW~Bi%PeNakFZX&UCA>9 zVlA9mF4?s}5hGdS^+0BB1b!`N^@!7;0@0m#po(9M>)FC3x&tV@z7?CT;t7F&n$_Z- zJiGN<NV@!b`+3uyfB$BlyFc}hd!{o;_&%$1Kw`i8pt&vUbR*VMU3AZmB}RRD%mQ0k zmy#ZOH>GLD+#wPR7a=iAeX=ROr8Wfq%g^0#R<mAdQTag${tiehxT~mGPltI7QW;qq zjCInjv%pqR&CvRk=5kx5G+jju<3<V39vy@P9M#WaMH1DVcBfnpb!AFW<kh|<02-PG zMMJj5-$3G3N}OxXY|dP|7_ol+DdUeozm4%q%U7feE-%H#Mokn6*q9KAP<W-MD||OM z1y021lN5^Z4qLlL<L0x|6<4lE1^MOJk0|*$+7LV%GWhG3Bl1zA9`FzVUKfO8Kb~V* zVHRB)E%9bkY7RuR?v!FTYY(>zxVs%qw!TMaN}UXbLU)uLEM!Gp-4?UU7*OY?n@bRW z7X;u%18|Ik=dXB*-utup>cmCJ#4}-I>u>K041Z*fGkVely@oJ4mgU~T1oasfPQ1;< zN;KTR)WXatNeXuYP;-?P33(tkc&vl>QZ>JC!v0v8^am|T2TO)Oyx=|}Xsz9N?hX%X zOqgPIlALs19f)TMF~Mry9sL-6`e}9hncCDQ3pH-{hJ(-rY+=H_rW?!V7BzZuNlSfa z0?)*T-SC9O{gD=fLgCSlwI{#6zWFv-&|BE}+pNy8?r$TD1LEkA4=?NzU2xM47+1g9 z69a)S2PCThi4ErR)jU(ZW*^QN$hiAIhR*w+%Kwey_u0ca$9-%<#~vYs5IT;{p<|C! z$I3``2&vTf9Ou}hV~?m~W;BpQNynZQl91{c^+75X?eg^>+&|p+<9@%d>-Bm*E9y8Q zt{xTJ93rnlYLOVngWRVWFUjX*6XYIC*+?EsEvDG1mKQ!3G5lG*40wbaP6u9G&D|vA z=(bT_YZ%n}9nVPlNWs=+ymnvjesCOupNDV~+#odm8*L2|m2$r8*rUInQ1+J(e!oHa zVf<~3=ReWgE7khWAWa*CGHvG)2bjpGf8WKKK}&oL?m%RRs4>|NskLF=`-WxJy!8Sy zLmIf;W9QbQ6;0-HmER=_-DUa-yNWnj1X@KNp(EWdbi<4o+7i{usZWC(HWk0z)zR)d zPk_8QtEi}x!#M5#26nCV$v*MxvOEA|zZ;9=GNDbOr(zylgVseo+E<x#dJAA$tSD?t z#?32PF4uL#?&l{8WwNmB4mWCWaj`5pInHDypF;DoPf8ezyYiWZI8W*sZda8Et>9Uv z3K|u|##lBRK6MEQEjn>BG&!GUEp{hSqKO=DAm+d+j_c$ISWFJ97%7GXBw9&O$+g01 z#mSpVBw{4cbhP+XqG(Ina+;RHh;PG?&Q`D<B&xw%qF3Gad&j4XqI_G*zt5Kq68DwG zVm-{^Nx~PXZ25130dqInpjgZ*f@?L(iQuA;Zo&DA!_rQ=&)66;{45a;$gguzqPFl* zURAY~*{aEC{Kq{0nm@(#`JEJi<f|2f{w$);mcZe)NI%g&kpUS#+i`txVFpczG(IV| z>89{V)@f$Is4Y-m?*f77EhakY4oKN3yoN<k`o4?RwWl22#PR`t{NwAB+E)_pkT3Ox zKX3e~MoyIRKe+CialSK1e%)ud$c-%3qZJu{y9^>T07yIR0M*ntAw<*bPm@KeQFy*( zwm&^3F?u8jTrcp6ljO+qDzHIKy`+pL*EB+laZba+Mt+Rmk(QS5^mA{IiMX-5*FUG= zQkgo(c%#zQywpcpffRvnpNM+1ieOUy(Aeg)VyO@_MF%n^+q4VHcc}jst?5xAL#+R& zf&MaMx4(I9{=b%x-G7U9%zt%fYtJvqEw&H3ID$r^4E%P@9+RUnW~FRf$ZbTLNvW__ zI=fdlCQ+<YnIO;i?yFod%zCIC6sK0m-Yg>h@A)i=&EU$%M6_t<h}g(vx+ZBcAll4q zYvTtX9~h`^?j(bUUjp3w`FHPmr0sp!$}QDYrtaclMD@rolhnVqy&E~{D%(@LHP(3a zyQa=%(cH&+{~R!zKU8BfB7<A)C3k<}qYk|0XR|M|Ep_x*^7XW&l5Z`J;EDHixEq^f z?Vw;=48hTLVM;e9Lkr64s?(V;WZ1f)ba@W_Q-pv6#Pfs##!e$=6-Jlo$ZkdDr2Kbu z<Q;vzLMR{iXGladAPsS;gKU5Gd!m>+xo>{kaSzZnP{ZM9EA$(@qeM4=FMq+c9Rku$ zU4e?rKHKS1jTc=$7x`XK@x`Id1Nyfwd;rgUWXu0ZMeSaR%Ko5P0Wr|%E_&AiK1sB0 zHmvK>kZgh;x72t@)a}X17S9`46cFO;dMweeM1nMgwAlV<Emg1@nWjIw?cWdeCyPE4 z3e}!qt!~)6F%w$`;0L<J9Eus5B6E(?z(JLw%oF}o^>v||J`UF&iYPKO_AD>n)6wY~ z;)3UYm@X?GO7(g*GjO49N$!X7j%tDo{ZvT44Dcvj-TKK~Gdt2=U8t@2nPLgX%L#+b zDN>Mc(*J(1HJz=wUY&0^l!ZTzG)bM@=4jfD)Tktf6FRssKYIDw@}$d#+oP!Sih(+5 z@d7~VZvAEHysNoR+Be&p-Jb71@l88;>HOdeuHDD8$A0fz#NVU#zta<r+Ob=|o#Vf7 zG0hDPa?lMThxuO+OeWb&eEo8(jslf)vU~?zm6=QESAO8A<O*-jyPasK`d+Kq;Pf4R zk1-)mT=CH5x33B3_;s&(0^RRekLb&5(!4)_ud_ox9#LSrg~;vANo~G(e*Y<tZ|v)j zf(|bK;*JVl@l&GemUa*FT`+~_U(GBo^^FPPe#w24WLX19!+00}_Xj)MRd05){+&pH z9uY_ykny@xejI5#&naAAZsP14AMSR3OcTFfi%&Kl`jvzdDrRcOmZp{W-)olx#-?39 zb9!E-^bmLZ)H%6+mH<HDYe-UdGwO9SC(8MaR5v}|fUmD?EeLr-pcEba!82Ka?Jnyv zEbBcOZ#5HdH#Q+F{=?=MgpW}7^4nsL56Sx&j0SA%mJ#r$RHO($074`g^Ml;9eC%J& z>%=3kD1FiaW*O^`-yE;8aV(oew36{!V+9*Ieoerq4o+%Psk5iBQv%OQxlByl1~VYQ z)(V4T!yaaDe8xyy&q@AaFk!#NoGmNCxRr*FrTz@eytr3HosZIbiO45wtxh2L*0FF` zc~48nVCOdf)Q8$aP|t0LDA@srSo?hHE6pPuL??f;9Fa?+S(7sZZC>3qpeNNJ9CU^0 zQvh5GNIRMK(a`>0lLS(CXto@I1dcWQ<mjg%vTXY1#Kb+-7v+X9<((uyYsJAMfo3C0 zKJbxm3%!D-UP2hl{D+nK5CotD&NqCD=ULi->t>mCm<h*Dz)xD{hR$*eA0N|FnfCd? z7or20_M`vfzyoo%mXG-euqxkJrj2Rim@oz9lOsMHrZSY~3dpcj9}?l2b6Vg2WTngs zM3%-e_Z2Vb4PF`FPV(kXW8X&k-K$IaWY5Pz?tbDR;fZ+@M7)~aw90~Rj;Bw+si}uG zjTXl4ZU@_y^#zdm<e_n#F}bSP!{2x2K?xJlM7}S5=q}BPBOq6aP4&)Si($$+@dF*1 zQ@wmKVh#MB6wxdVwH0RPoWo4NYpr10cT%B}Cb!#Fr4QRiPZ%0})ja5D{e1ItiibVR zY?JL?dfXT>VzI(Lh$EPnL2;Svf9r{kCjl33rDiR#oca<WAU?kMs;WuMzMCvxI<*V| z-iI8qGvFm{@r8W&E@iJNg}HlF)Ew^SS{XQ2ae^J%Y6|FhYAYXS%|jMSoe<CAt60~b zOrdbeNRIQTb0inr<9=mAe`NXCt`t*|w?ZzJhi6JRw^C%OlEC_0xQx2YPnbp1_B%tG zrG6j#AO}`E!P$Qa(5MB(n*ecvrR5@oN|iaCSXcd=Z+Dj*mFT4<5wxdcL0>ggc)h|_ z3-2%-);AWWH&;hVP?qoHBlrRIeCuPU@YBl`R0x36A`_acDU7TatrAp{>x=<e*K=hD z0*K)8XA+!z4E(9G{WR?)Yzrx2C?$dKbl}UNyTh?tNp?^!l(pE)>REkLt$GG?)cgnC z49u3xWSLK~O*YBU_8Av3*|F7}_V6@^3YaOWL0et(*TSTfHJL)2J6yM-YYtF1!|qbE z{pb$aI)~00rT(fp7E!YdWjv<VU*lJVZYC5Viyx;i^dW+o=+tch=Fdd5`-tA{g8@m# z(cw-4wO@=0QxWokZ=o0c-TxPsbBN(yX4?37tX>#PHJk6%;E}sGVX`D<30xV-KUNo@ zuI0+oPQB8evj_4@M8`o1K6dTyOiJJwTqu9}((>W#%IDR&#g4(FvDN$}U9wQ!5oDp~ zCOsw2U>H8umkv=z`U5cgr5!jYa<eZ(8-BZR7#$r>(}vRm-ziRJB*1r){!EDMo|t-+ zkcTJB;{C|9v-vI66ND$)08382*Fr22$QQcR=8x%wi_<Kz`9LaGJJkp+#NVyy%zMsk z$Y}yxs{1;x+H_f#KHqpp4_l$n=hR(A7@Z#$Vr~~(b@n;&Ws69z#dJPwtWPf-xMj=i zrSQWXN=nRfg7rmx41h~5B=Pu2$yZKq^4I-5Y=AnJnStb}%&AwA$9PSyiEB^Ie^?4_ zLJo*oVK=5-!juY*s*A%vjJ|C=c9lb320@d)hgovZT=*!DAfNnOp^()(<_mC2_VaAW z>FlJ48aSqSCn!x8?ct<2W*|1+@h<`x1ODoH`shh!M#xT@<!%2}zy4pEy#@55qsM7b z)@%L6!K40fpuUg(eDG7>DR46R;Os)_=|{LQ0+w*15ZYImXfnlwnDOC0d^i(T;L7T0 zDO@?~bK;_huPJ&v+Hc!!_}4-iWN8~1_XFB}MyHND!>SOEYT%~_+~f_@DG6^4Me5s_ z-f;V3B$r>rWun;m9PN#{97PNok?`93uMvP9x+$8**@W)7G?MmoU{0<*<wBp3)WzF5 zIb_d;-h*}PKV|f;sp|mk>&zyYFqx^v?U6A6=7vU-bZRM_QVd+nck6_cHW?q|T-VSK zx$_Za#za>0|8yk5y;EX&>K~v$hX`^xSV*>tv$saV{_}CH$Dxn5BzQ3yDSMl0##cZ7 zG=nu*EVg)v@ibTy{#sL9oLWYZY#i!wx*2lKn+rK08>RN>DHFZR+#j}Uo}x>Iczs#h zx&&bJ-<%IbIoTcx7}@r~GH;#Fx&_vp_-`$`vgC7(o1p5$74EcbvPp&2e9p13I_=c= z+8;h5m@g>p(-dwYCnR`F0LM0kCNwY(sfq?a(RI4P!|pUqbrlOj`sD;C-T9*`FE4xi zVff4!L&tgs#hcY$e!a@gEC0wAtO)PtbZdk`iSufJ|0m2n*^?!})AJ591Ns-f?STga z5heod4~_8C&Rx^|!xjKCVYo|kH8pkycu*~cI!P(ce=3svG_F*mRPkIbA5{$W^|&X+ zm14qBE@6O%i=M`LC71X!PU`L*>dYZc_(LuLdel4A9D;z%3m|hYmE-y)>%b!fwEYmi z*eV<f5Z`Q{@&2B%|8A|hPp=u3rKt#*{O07V>@DajJ6jOi6@lrqP`<8et<xQ~*VnF~ zQk&|l<R|scW^d-<D@=!*Z^uH^U&Nnq_E5JEAy=QWa~a*4Er*=EWOr*Vxc|v*nzNo8 z9Pu!WUl0g%<eqRx1MZ?^tcdt|`y|h*i34l|bY@f$^tG6}<Nea;e^l>ZNJlgDkoksX zNjO9aDgJkDZSI`6UXtI5w7zW$xtP>up8-GZSoI=$$)TEw*jPht#2(ud{v!VSnX0um ztyZt(xyocl#NWu}d17BK5Pa+-QkUsQ<s;4h`>GGze!c(pmk0{3pa9w(dVA)PhGqgF ze*VTb>2o<R;=#9^=F3RgUW@!sC!N}_Eq{x7wbazi7H_vSm9+$TMt}WIk&(g02FIP} za?-lpgA!*9Uc24XT6J>FMl*rjp7z*%EeN>QxfTT9=1%nW;=XtAf2s|Yziv>!>S1V> zTRbvM5WkhcL~d?|-uqrq$=A#y7aTlyHVjBmZg5Zmuwq{xi0uwNG=V9#bEo#Jyv75; z5H-;iPVc#E%FWDi#MN5Zo_MypKN-kG(Z)`v!jwZ!pq$n2QDZTwmi(EGT?Y529m^W3 zdfRimRFqBtaWPW-tWC=M_H!=2lm~{`|1tai{dD0@Zz(oZ>PIy6+F9QERY~~C&D(x2 zXGX^4%hB@dPr2?@Oka23+o#m9`dcgBNeoa9+qyFNv-$V1{}0|jfG<Yv)|Y~~9=z@1 zFbYRUr(Z19yD|+m{$_K6#DCaM6@S-$VYogqW_0yCygk+rKfmY1{RiyFdFOx4y!LSU zFGlaPYG3ZE(ATxxr+bSZHFZ*>+@ug#bpUH-=rykk+N(CMN_g1WwA8vbz4Qr;v^okf z35vf5eq)w?@d#SL?tB$A4uEmbojj-8cbt!Cml9g~xO4iDyvHxzymk3&%1YaJxY#F{ z5C8g^rpN5Z*Pkg%?3wrkQPv>b?mG^^v;Y`?qd4E;Q0nN^HGIjVjjhF|km+r;Klyh3 zzkRx5`pKU#{r8?yn6j*Cqrpb=|G^zS+Sqz!P;}-WK#L5`&$w1a_RTK*`x^dj2>x-- z05FRb!ky0TX?bjC>Vx)w{1hH1Y*XT4`m}a>S@M3I$5Us|uul_x`4P;~yYpw!{T&9( zkx=r~i?jX7^nUrI+2XA3{meeM)7H94Zq*LA|9f?Nun*EXY;wZJJ@26pEuoXjH@kiD z^LAPc!rpuZb^y0aY3QOaB@(Nz4+N7}_iCMdUfWaavrx2Q5V1d}GCsSppTG6d>BJIW z7;#%?W4u@PY1^Z-NB-rXA3Q|;?6$JMU5mW+;=7B%pEZ~@8wJP!y7A!7MjudT8dSG% zfgTQ49cs^*5U^l7etGT>;&L|(DMEuJLX(&f1>d%q)fNB>K&qP#{P+~&Qhwmvx6PlT zVYCXXGzt9u+eatQZ*ERF$vnN1y<=kVaHfq5U^hi^fqXiHZHWhZF3oIMvXh0S-N<!w zJ&DO;sz5%#?NO)PM>=h)1f0Ev>E5kH)t%?Dpna)oVHZi@=OC7!s9LSmIUe%%F+GD@ zr7Q>&<$w2npG*sB@j&AzW!++O#rqjaJ;inVm|*A*vKa6w*&oINR4O4WXLWZo-j0^+ zKl@Mi{F#f$?dLE->$N%ruGY(ZhQC1u{2xF!?nA6*nzth$VX8TmYf!Yh#njysTuxdS z`uDf*+uL32Z;C89fX3AyOtW9P(LAVpVZ3=l*M79KwJSFa%F^)>K!hBXK2<%VTBR!F zgQ-Jz*<nsZpaf`ttPaD0q^cEvQ?e=?$oa2oIr0y2h?FFoYoGRQ*6!Ns#w-fBIF-8B z0x3m{G@GE@A2+)__to*1nBokWh*^V$AB17dL?0U*`^9{0^lF}T<C_6m$i?_o!oHhk zhZPSwYCIGbR=5Fg$*oDOGjpzjDK@MaW`c~*B&m!^bVZht%%qY`)X;$O`Sd?xQ#2d7 zyJ|H6KSkb8S&9yz=jTpAUJdj{kc67d!uD-H8M|Z1MksPmL(L&lcgU4<xcVpTfnVz0 zIIZ|;Xc6wWx`np_m_yowf*SO3nmnT_IsT0wChU|7VoaRUstq9Iguaxi__yUnM@gSq z_vA0+c2}|*NI<uzhInOqgQaD@{pdFaLhzzNhXEjP7EKwCO|`p>UD#{;PEgZypM?7Y zyex^{aAAu&gYiEcGUS%(1#MSZ4Yw5~&4Ue(70X7Grc4}9bQ%n0LDef|fq$P{Uso3# zEe$WqrcPeFxKi=o)pLO?6bj%~j{u0eXwSYp;^NqBGc6(>f|4M2L+=RS88<S!&mY#} ze8F|>ylPO_$j|LI6~{ClT_8iYCB;quOuz|rSL-=t#j~L~r4o)|z<Cg<P^S8(?CTSU z=V}`3>*r9r9k79(18lJw7dja)dSwsz#<rVt^x_dZ^mb(b7q5!K59M{?hrjIe64S&_ z9M3SI(4*LaFv*G`n=i9x%EMau;%wT@tG_=!ynO4bQjz1S-Dh}cI`hAMi6;+D$R0pj z-yXU`azyEn7a*bd^Mxv%;u6w+=4pj9=mODGTj7w0mZ>M2wr)x&@Ranz(>fwH&954e z2?MO6%UUy*!k2W_7KPqed`#jx&`AKg!Z%PP5qtsR9YX5ihQYu+e=Nfxl0)TQA_H32 zm|;wVKj_qUgvg^1#2(LWOqR7sUgfOMa?}%de+V2<!p;pSkz&$hcKD4;%WSrv*pk$v zv&!t$rrmaHsL5prM$1)Mk@YJz-(Tfgqer-zT83AjJlOQXpHH{y3mWEJ7d=HBPlA6w zY}r@EMA1SZXj&?-<!w%)M-qVJ`&Qu+nHpGLdhmRja9fn@TB=AvJ-kBN`5Y)Cmwo)n zfyXv~?lL2jsx8&6y4RLr5DnHl$iSXTr?$5}0U~)hT<KJpuv<aBzl~nKo;?gC0Z0&l zlj_nT1X{aG;hyvQkPz_$Py<hyW#die3zON|Cm(N$0w@1CLd5KtHV8*Ou?~AJIcu;x zAk|u|UTOP1-A9J}Q=9VXeHyQDmR5wrd0p+C@bIw_hm5bgnX&UT>d=k=ZKO<YOw69Y z;<5wD++l*D56q1NFt|G;<E6dUqcfwI;gM-$%ILtI6%o;+22x?EOd|z76Y6O?CiEjq zw#pvxsvx9mMdjF<QR<_x{LrOM9(0cBcKcH78BN1f6E_IwxjO$UmY!psn<9Snd}x~e zvX_#0FF*`C1BrdSs;!|>YN-%adN3d$(94J^rk7{4FUV73_YY^rfR?hiITN7g0jFFv ztIgeC$&9hMx;un|3UTp<HI^`Ayh6KcncyIE*Xw!OXkN;`%42fp?{8}G{Xi0v(!On2 z_e@t`y`V$oM%zB-2mAb+nGqEy$!S%W9XaO;M<Q*F6qx|XmuT~O9NYZMzecaHv0VH^ z{IFBQvhv{WcPp^7?ayW;9=097T_f!r8~ymiDYYvvt8df3IoW|`v6|}zxd8$7UV{*l zqW5|jbwvD*lk+_{{Rn$2==iIvbwc(<epcs9<`-P`R(F5)*$af_SE1giM``&rMm{tg ze*5v>aj`8KfXwhFQf=DyU759}Yv^#=v2;L{3|k-8yxuaxM_M#(5)|{YC($hjx^psd z+@4{#%W9y@3u+64d#QD@H$dX+ncPIso|_r!jJ$3=DDElVrh9E;Yr3r5Zr}FxmhbyJ z;n7Av=l_fRwL{mbQ@6pl9QLVw{#Y%}HAZyH6_w}HNY*36ysQ?C-MmLhe{+Cr8a@U} zmRTpK#}4>MxF7fr=4Ej;=xj34`*$_#r*gD)@*lZ_(nYcG(Jkix&IF%1x#<dzH_Vg6 z`=Xrg-S@7^sqzi<Ob(VrJnYs?*2@ARAboZUk!|vF10S=<mi-!^VrCm3apu|s^)Czr z!OiD6YWFU?F{>u?B=cM1pLg&EM1%cy`brSm>>JGvBg&%v`U-1#LT2G??H#{>%Z@IJ zynLb~R5!OjM|poytO^9jOne^JX<}H6I3S3XjjrpJ|Gp6zKJhBL=>4{J&0t!Jej%M3 z8A^OD_Xs9Vi#~bi*2?RX$h3XCxTh=Lj46g0dPDiEKGglDYR~)Q&NgQ<uCON;M!MEA zWnBQ9BfsZn2EGNGV@D1IzmQn@J^VoK@twV(Qr6W#l+o1Z><gPg8V)A8(#Kw(ee}P+ z{22ko5-KP~>rYQ0!iFMl9bv|QqN?7V{c!5K1Jk?tg_41}?8DXancDq7s)SO0*%B__ za`gN~(8&DtRHtU^f9x-_E5^SgS~Cc(w~<B+Goaty7)T49FY|n~mZ2lglne%se%2i{ zn-9Rp3VL^+d-3~C{jrPO;w911T+-r6orPD{;Oo&7=hZG}{#PS&>h*TUBbXzW5iVYm zcV#|m&Hjn!`GJ8<+qR~^ay)9sThDt-s_O)a(>-G&H>4<f@@xg4UI`k-wJ&@9-{VEF zXF-!unoR}?Ecr#tV{_eda|=Ij^=fpcI&|X3ZU`d|eYmrzAab?wfz+r{Fg$<#>AyPc z8rB(d)ltQNPw0A@!nox(8t<={cDBS|eOcN8uSBGhy`n+SeVN3?R_aIsdtEAVe`~ga zE$kbOudJyB?7^#mRSK<*3P}1|%i5d#>nDy1z?N=VMTp20M1skXUtbtCV!*HOMSLIs z^aXMi5bV0egUn?qY1%8c4E;OG`K=fNR5#9O*1SRPprvljZ2!vo2WEQakKkPGu-DaQ zJ@D!+SYXU?KS*QUz+$VMAudoAofBoM84uv(zmCfgWK)Oz(<=R8geePzLnJ?1$_XIy zQw#F8y25#Zrax%X?p!%72+FOx!4EoWlsM9orR2C*xsWg^e+&FDTp~eAg5&eArbjb+ zNk{=|VnG=SqM@ghZ;akoZ0cz`*;A<v@#<A>psrOu23|IoN<h&YfJCl>M4*E7Vnyr6 z1^I6Z@}QfBe6+OE<gbnH{1J!<1E|6_tKj%o<3EhF;AS=L7ZR#GZzS#K-W2t|EgNw9 z^DSKfOWV)CC33T2iOG<2C2w0i0oI6(V~!8Dv00d0$lG_2x9bd8!J?Fcn_^M!ufocL zu?m74c}sl-Fk9R>uOwQK4vAl~Nr3L^xSUSH$X@8xd=RZp{iIf>{{B?&8*Gz;mQXjJ zu#O&o1Lf<4(ttW9RuhkI-4hFt<=iZ#Zv;gwE~xJok?yV=E6&xcKV5F1CeO6o84_;6 z$*RnEZV7wecV?I%`8pq3)|PA5{66U*c#~8pnznDQ{nTurDg?_ILNWk66LJdxK3dB6 z;rG{kQph6$e;~$xEA&!C5$65*Gc5PQ#zlW6gOkgEOtVSeJCo}veL7CIEho084^eF2 z>3y60*5bs1(xFY{3teNR{Ke62P!#x~W1Mux+=*+v^z7~Qs)nT{R;RkB^+RZ-l8OUj zpUoFH`^piEXH_~GGLNzinS2ryfOV0jm%Ggmz4iF0;*bk9ek*EKG%0)+Rld9+wakYH zV*b0DG56##@u1=z>}A9VS!#J<_aDnMW_zqcV{EV2!hd(msw$vm=(A>tCcnQ{XKE|g z5^c1}I2ucqJCOg6YkMWec7MLSqKAB8H;&5NDr@}J5Iqa0L(@qj4GQv|>!!t14x_CO z`wb}OZ$(q-VEwbV9=8E`9(t3kIEmS9F-rY9MO{5pQ`$}B(P18+Y$k7Xf`=gId3bx4 z>@wtPu2uP_n48jb(sqx!?Gk1enYA-ymicsu_)4Q%M1ZIUz*3eR_qf|3Pd9f@Pn8}I z2>B-s0wgfu)7VBG(J+aeGZbv%Yby4gKx&L7pS@(CecUtSxsNY&EK*U5uz>ZUL)Rzg znqtD0`$IWav}1kn7Nlf4a*TVtoL^U+?dhNO+}-{IX@ezKw}VIKp?vsI<Yzwzs-G29 z``$?<`F_mJoW8kQR2Lwc7_ck8S|y>nns2DK5#ulV&EfHL(oDB(B}9BqAmqc;5g{LI z9{OyQxca(LO=r=~RB@89s3S^;Y6%d<WZ|O~GBcL){2RLkNmOyK<DuV_YHcZ5Y?W+? zxMBt2$`B88o`1Ux^!o~JtQ>|$kkCV9VZ{Z>{DoaUZ7#>AN%9598>b^s-#j|ERI-!h z8Y*N;10)y=;v|TOEQBxz5UR<TLgvYrahQAnD-e(bd?Kk^oDm?wtB@J$4hWhy&W2t6 z^DP2Z#5mjIz5!ADk!`}+8vO;y6gZT_?=jShqW?!JH>>ef*>veHIP=-y%%Df~o_lAY zP(a})91#ovfR-kJ0d_<8K>_qO06_;UGq@5gw5X>4P*X*33aI2*X5U=dpCPp`Vt%N( zYVb12DqYs0CAgQM>fYc#+)^`Iq#HC+=5VJ5hJlNoZydgJ{pmF_8!P81wk+?8IUQd` zYps8FomS;oJ~zdt7y(G_O?pAYi`(?xbh*PZa1<-FBlpN?+s&8v7}|bv5Z;OT2k~Fm zUL6n%@xB}T6Dv<`Z(7KXgYeA8+MAaKxk^q~sU7;mLi+%J0JIb&Jt?(3Ebn~3H9Qqg zKm!b>ArpQ*X!NSHDGNG-7FTZ72ETuJ)5eDF)-j8>S{%wyJ6qh@5k22p<+L{oV385i zM9Q@%4<DRud-*71d-tKP&Yxdbo;4nO+V$}F_l>2|Ylj|n{r&yp>-#rPA3fUM29W9k zCR`#+z(T9m2@-Jwl2kTm>*HZ0;uW@#Bz4^0NBG6v+JzKSvif4Ga$#5?EgViGQ}8Qs ziy2C{&`X)hmo{XwjNjEQWt)9lS-MO{YAkcDCBm0;>{aWRbE!tF%Xu_gjkoz8Ug2*G ze2&+@E%c9DeOp9N)_7MOT<E*J=Xh=XyVA(E)pu7I0~%@<RL8>AJRYJshs@7@!{n3J z(Nj;a{#(wwd@Z#nA4+s1QC!S`O)FuGG_U(^aXWJ_zDV#gH2feyi>Rw8EHrhK@YZ$h zlYB_V@~cxyw>3}L&IWMn$-c{TeGQLD@b@?P$CU>pF-LOxZvm~E<JACHX8jH(Ae|-y zP0QidHeC9g(YPu0OSo0wxQ8nZ%~1fGp$<{~BG!zF46{);tj;k!GfasRLG9C#ygG2; z6Ls$tK<2}Q{&4y5M;joa<YXK~i130d4H!yMb9!(AWx74Gl3Lt;m{4^yMd=Xdv$qyH zU!NihWAw{B%gq><^e4q6i9t1p))MXQSmwd)hAFB#*LpHl1@NI@fLt^Oqn6Kr0;<p` z#k*7005et{n&XC1ujmwUREln0aM2Ill}9}={727G-IeW@_TuPXu~-T%NaU_^vB!4h z_csad&~}wVs=kAA4pnhj2{5RPpSW!O&t8eEyP2w3w2uHRm8w;vfr|+QQ_4lL$&{Vg z7y(T>PxVM4#|}aGveDzWKv`(_1d?)+Uor3zXsxjAiukc$Cx4E6;?&~~)ZXz8pg2Is zYG<pSBw`U(3XWS|?t7vKHG}~Mi+h!`3^1N-yb(ZmcQ!;f-?ji=#=ASKZ?rzc?;lCc zd$K)epJFr>fInUhQ`oRV8%nhEBWPAEVGr~#Pz28*_a-g{4e8}KcL!;~fZZOcx_lIq zZiWW<#sRl;?+URtp^}*Hey!j-&>P?<V=NJrmNu~7GfUKC3BIrmCbkcmC`MO`9#MoV zrc%&QFp&gTSmED)p$$I^_3f3J;v!d7s)g=B$y+?`E&6!SZr<8!+ZCcFhs))VBJKB; zLb6O98Ht#*<bB+zELR_x{0l+SuGfr=0OO^^3o*&YeF4~5<0US%ehHy%?2wwkkXEQh z%R)#v4jd-MU-7&O=4SW{pvih=3Y4QP)f65j<w(X`3i)%Ib0kHf1Vk@@DCUSlU(vNQ z)`}u5w6!h~sD}Y0fS0mU4cw7amy7SJ?AIBI^Z^9WuOd){npg$uWGZsk^SYeVa#)#% zE7kfUZe2+px{9JVkoxGbtf(Ki#f~!AyINV>c%;6r%yU|b-Y;oOPMI(;SsbkL-w>Co z87%#No&-#naGld>3Vi!%^}K#ircz(g*aI!>&}~IyLKWI}&Kh;9U@wMK^w57uQ6g$A z7z;0b+P7*TuJ|CqX7Bmw^Qof6WH><2DU)2avzTeddANyjO3JDYDlI)R*yRM2`EGq~ zH$I4JCAWPzd0(e1Hh4z(A}Wiw?{z@tiB6dG6Cb*@rmq9X*gye99J7{G%<R(X<EV)Z z?Y-nW;szDu?>1l8l3h&a>TtyBhGc|yI$Qo&Wl@gOyfV-<Tl8;|2mm+rO4L)W)ZwL= zlG=5!1*vxflJV2DcT9E?4s5Gil9;-7GC9A%1X)LU=f^AVqc2<<RpFPhmbQlXBk)au zOF2GAt{DjIj&RJr$j$roACO-qBTf6V7f!4kslYM`7SFTFmxt^mN4Z`W$}Jn^Z`Ek` zF%2OS;pIsh%48v+RJE@bf9{?50zF-K86pwPgKY#$5Y+%C#&N|`Se96q@T1MQ)6?E! zq?z*I5;q&*tsS_WG5Eb^$M-%nU}8H#XgU>iU;Waxw8krBu>(~yt1HQSCl_$6A9r|o z$X*+Zx)(t{n+nXWY9R<WLrRhJ5P!}lhzND^fdXB5H`g6RbDgRc`bLEy+Ri^8q+0Pl zDz;Zy?U=Puraw+?X8^pyjzm8#mT^4B$(VxY0h#~9t@YUdEhH~PvizlHZ=I8kqAcI% z${YyVmDxIAHr9*>jM*2lnV&OVwYU-Xz0#{gALAhWur%hqcBu4i<j?eAR&b0$$Ivs4 zYdAptFnrWYVyKXqiy6CQvLniqr3}pzcNEWrQ%GPe!SrRaaYdV>4+V@EN1h>ZF1+eZ z=^UzXu@<UMOt)R}lyn=v6lk@pC2Y{_-;1R!bB+wgK#x+RkbOdGN$#3ztc_UKn($t0 zY3q0NbCS`^BKLnicRH@`6o+RX^2rk2Ix=*ejraSfSY2H0Ii!CY`+zfk>aMRxoAf04 z=9%X|j|1EBMxyX&j=TU6v2d^A)l3BZ&%1g6+HC-IRb&SHSTO;zt<lW&uc<>)6|3#Z z8m|Mwcf-!zLR-c*?5e~Obb2e5B8M<ZEJl`5-?Xc3>K+==&Ht&}3E|Lsied%#@2?hx zdKiPbEAc?_f>Yb``-P(oDO@En2#SVI?&NO?yG``UUdmDe$TwC{ijw~=KN&C@nDD=# zF3B<}Iu^ToF+8fw>cLkd_2^d`g9^v~t~JX4P<@uMakTxP0{!gUncXdKe_jgg+DSq; z^(I6Cncs@hv+?`h>!yT_Ec^g~4l>h@SY~1zYPSIqO25oaK+kzdWQ!dbx1(GMsvh|C zbzs{ha{_-M7$#j%nA#~P5^=OT=zi58+A8HneBvXbLixI~I&txr>Ve>gpTvoIDqwq& zlV%cF-hZJ&1$=}8YVU%(QoyMqkkRD#pf}-2A6Qyx{^UAn2LR?9%pDR^VdY5x6n;5= zvOmdgiWZ2EiUGKI4O>FXxc_SsHa7(ngA#R9!;6s-^SW3wqa#;Ui7TR~7L;P$P@dLt z!71--Rr+FkKp$Xy&%YEfwI6JI=Y!2T5qb~v6%pnB?8N;+P(ls-rveHWgTz$une|0G zgjt-OcIY_56GY+_5Kr4QE=t06&ftCkn$5ZDDU-rf@mOiG^CAltLfsY%+YH>WE@72q zf0QBgZHfJHfc<5_!aVuNvyDspk>`YocvJzHSIxme7+!<kgWOn500nB9Bqw2|3y*8| zwhF#ym6HVCeZe54fZxQ4q3E-b@$Oy*EOeB|jRMwygites?oI+<PJz2qVH!<HmWbwy zP_<+`1qK{1F804)$>hoz3u|xuYaU^kLHI_)X427_%<PgG@W2q5ITXISfkSf6Nw|87 z#Sn{?UB3;2t2RlpAwDTvu4xF7c5lP2Bn;hFl;0aU4Haqvg_;;hce=JW1EG@#?lA6m zqX8Q-+;AMWsH8D-TrIf{*R$a<&a^o6A{?g|WAh^X<u;daDOmU=?O-oi=yenR?F{&J z2sCcPW-Jr!jfw9$4qM)?tA-5RL;&aQ|GeXU?zSaCyOR`?La=(r?&V(~bjLw0Bg1Bx zL_JnxP3B1;G=hOVeGb{8f{aN<Ko@eRpTV5~V0S#+CJAONKyN^Smp@cfD8jQFB-ehh zCN8hUJ7$JV7$t=-^YEKi2Pv}_CU(T^w7?<0*W!j3Rxi&iDwwquu_s^6yPb>acEsp~ zKrQ2r8WTI<IT%;tz5Q{&lfdv5CIRAHhagIZosE|Eh?zyu^TCAcpbZTU2w)l{<QJ~+ zl7ZSNgK`!TOjJHSOS>#ofuCb$uWkPzeB%br(8Bl6mJszWYZzT3+nvHGWLK$M2!%M{ zT^THKpDK={cRl#=Zh>@^8y=HM_cH#e0-k<xOi1A@w%J{zIWnAiR@Ga}*vb~IkgL2} zW>W(u<*FtPJGgp#zck5v9e(-05<=rnxTuJnt9EYn#m=P=e8a~-+rVF$B|6QXK6@AU zm=+7I2XFpJhq`h-i^0Db;<iRy#|oHd$aBd9^S~TpbMlBsCSH?8?6whR6-|FlXzMRh zhGEzpxk37=vtj;U9Eg8f@q!Jz?K^nAxk^UqrMZpDU7zu<bnyb<;99r^sE}<ML9`r+ za6eZK&GB)V1MjSY0oxcLz?X-q14B~_+hd6%Mc@gtPAI($+g<Z2rb5fx!vX*_7>MZs ztzgBy>UG7^2A2Cu$Tq{^OM1y-3GS^LdsFH9ebeh(KG!94@Nek2HB$c9eZ=Z>{z4O{ zx2K8HcPV#_Pux|tx}g!5U1QY*_XTu)Va1?E?3J=Dr;rj}n0<{*ksp+mDb$@1rCM=L zEz2k<6xtkp5d&E2HULc6ZLTeQMJ45nHgzk4R0|3u4_++Acg<P6W#ET52ybb5dd9>! zEb+f&{P*O*E%dqSl3J5rG?HG@twONjT-_as3y0BH(A|dW87%;_r5ePR30lHmgxovF zLq`;bZTs93X5Av_rAVWJl@?IW!IriGPl!KkL%VIkgzW{?Z%<Yn`J&B+68H?9n_AvW zho=3jjju4*1!?$qx>w&y6AL@og}!Y?zSp@WSB<@J({$mD!gKO0yHC~@vW=FqF-M_# zb=W9M-MP9xT2lA8x9X;l#?&5Nj_M6QHZ|7q4pa5!Mmu*`2loIr?<KZ;9Ft>%ZB;hR z+PKNx=;-|h;$+GQr3sIhz@z!#*d1s2SvU<qQ2Fo+!$rFq^l7}qsy|e|fcQsEF0pUH z_oAJk>vgeQLKm-6Kvobm5s&|FB7C;^wt+h^5U!{f_~-#qNvuG~758Y|`=X6d!!}vS z>lw!Nmq8(j$tPoXk|zziLVaXh6@bZLqO%3)(;(_7_mD%=BQO3V2R`ig6}T7o(dj0{ z#c|Y=YLu&WM-`(ZkKC0Tbf+tginF{g)Lhsp8a<W_#?*o|5E;NoQ80O+{Il$-FKjOp z`xnsM-l*_~TD<m7H*g>p94`@eB216Bp_IV`0acGo8_DaS0Q2x<0pYoz+)DbIXjD43 znR9LrgOd*S({MNKg<AR8vJKq8IN>85KTJk51yqhMcE}bL!o@Z*u!os&FCHS2fefLs zqWGv90WvmWFs^Jc-hVI?M4cH&9%CYc$B~Dd5N6{8QR7t3j`5*N7kkCiB%OzLT4oMd z-|{|x3msK2YN@s2wr_`5c4-IbMMqihd7x#NTa^xj-a&t%32)Lbdb!0X8r8ix(EF|( zd=*|o%m7z)@o(>m?nuzzkjD1jAH}=&0=&`ggp%P-{1BH=%O!l;upl1JA3T3!QNlqg zDtPw2?I6(AH;(-<P6&#`HtGtmm<f;2aD7bdMKk*+`Ph0I_PPLhosJs=aSb5u;dr}~ zCRq3qTes0(H;yU1&`~6GtYj3Oz&muI39(j*@MFS{@{#EIp)Dc5BpTW&*bkUamX{>z zT4}3X2M?YoBCTh-g2?9IHA*F*1_M4_d-C_Tj7pLZ!B@>fR5@>dM4sel`~n^SicYY= z0sOJCqVO@1fL`e5%Jn6@fnSM<cV$~yv&2H*s3TVZ>*{B8PSdef%qQ~<yytbH9X$1g z4dm$!L<ES+qz~R>2t8m3b&_#Qx`Yibu3i^^Lzj7jZe<jF^TviF#~F)$g?X54kn{|L zPngNvm_9{EQg{eT(?H4&O=2C*5unonbP`DK*3fFW;#{JS@Yz}VgGi_G$$LrQw>g-W z0Ji&Wk4s{4&xYl~Osby!b3OacmbKn*bnHA`_<-xdo*Ur6davV6@bQW3IkWhuP1j9V zIvv)p<5`>unm57le}@u|w(k7@+qu29blgg(<pZ)%#|E|rL`9J%E&wlD`A^n6eZrz0 zD@oXW`7dJmICd6zgB;==7lJr4t{gH`F0i`7m?_`rh}@6O9v{ll#o}%ra_7Sj>%t>J zw3`9e4L&DXb_<iUSLIbVz0a%^`hZHdy}MNdkQ%<5>MAqQd;C?tjN{7T*-LSEtzJwS zWP%IelvO#Q|1aM9W3SDn<*@^=#GqH7F$gcoG0^UpQkJE&C)4pnip84c5LxII9al@o zZt$KAGG336arc@~XUNE-d~^*B``+wLn~_jMKA6^s?V#hE#xZ^4Z?bLNnoGcP`b=^b zSk63F&W{V;Ho@e=fFQGhysAU_C*gT=s92Is#toFQxbvN=JNNQzde0!kb<IW7_w2+v z<I=!AE<M^hpfL$l)qRj4qQZh&<cXcycvh}*f8MBJ{xvw?E0-TRvecu~SR7t8T0S=9 zqOcWzDpRcOipJZj@K=t1PI@1`XKRETC*!*4*bjj4{02dAIChAJxyVOGyn6Ru3zt+N zG<VqX4p*oxS@n+Y%)Bn)!cA<({fs8D6=juVcsu5yD!BanX1S<e?mlXk1@@ExaUv3a zY7AL;%I0)@Caxm$;Pc4pn;LSy<_Y(T6j#e|0Z>bZ<u<L{-YuRNcyf^D;4Rd6(0L31 z3BWcNw?-!{fa?;LV{v{{pk8Bn;pKS-*>L*0Ve(^~WjZm+dodda2!sacxBwTSGG*L2 z54YTfI87eZS<UU?33ULt_1D+XtJgBN-rVA2pVD`}&o{vNkQq(EtjtP54R}<dULb=x z?H#rCVAib<h3JI2(~%O+=qG(tk$}&~`E<EVaIUxJ^GKPsAO+3pk>Hv>h*fU>qJ2;9 z1KBGdDRf;Z=h7R1P<8BJ_f10I!!yFooet(>W(U{x*P5Uec>Q+#x2A)ur2Ip-O7yVA zeQA&5Jw{0ecAjVL`#{XnJf3PNw09NPFpl!$9U5froHcN;!C22?q5FcZ<ZVYQ3?wA& z%8}X)92-9~D{~BBcH}<C;LiG@XWRtoyb#|<q2a4;9;j1%m=zD^&J+g}(EKu!SU}dg z7!0_=4j<#1s3ZAB>?4H0j$9fxpH0nIhlAC2Ju<314y?rOtz)6~kuHw3`#Wl>;mO3Y zv$|JXgB}Cq3?x&gCt`*mV_tXiuo3rVm&vO_aK0^iIrs6t|Fq}tG1Pr8!Gz*MJb**Q zOHOqLFO6z|hKKtKbdDGT_Br||O*|@I7mj=AxKC&L?K@UA*ZsiOxkNW)Jl}UtB*j&u ze~^r|LQ^H1{O@}_=|TJw+~C{-#`KS8dOCUVz{Kdk7;-JUbz9s83TP-O+i6M?q4H(p zbrz8~eDo?2F1yXooKmb#)fJ*>cpEGFf0?LBmN~j@j@o_nPyCm+r{9^i<IYgJ>>+{> zhw0VX>#x^q){Z~Da_{8PfMk55MvDk#k3wy0z{r&|2@ZA|_p>QO=J&>&&@ztz#z0AU zW_ajTT*0bCssHju;^o81tO5N(rh~d<62lU0o8+T_ukapl2$6UuLP1naA02_`u^GMi zTzi74+kVdZ11nsctJce)F?s?9SfcBdvbB??7O}>gx?w!F0I1J01Zcgug32W*a}|t+ zDyS9$!zno;`V~md7t70(gWGU}@q?=nW_idZQ~Pb1q|C&p<N}^1$gJ;C7?g<}Q?PSm z5au>(PMc;$@Y!QKh&%R3N%F2%Wd68n7a6<86Z)SYvNR%lc6>52+2oy6ST!*zYyUim zl-c5#95?4AI;8d=3(U<Km;mTW;(=7(Bq@M)u13Ypqte-)lRo7<%#jEXVOq(us&EwU z3<YgecY_TAXpL-?d?CHAqnHFG<Mb=<pqWOHA^UVrDJ?aXoj^vTfTQ*cNfl^ugP^Sa z@1(AC2wSVXik0(Cu1Q1sjan^6A0iH3pbkI10-U4>-Jo4-kZ!mm=C|j{>AsS8<tLkF zlRXRM=bdVOhzMTE&NHjtjhd=IzAY7!pM&%XaI&=33(3o>FFNXPW<Mb1-B7qIh`Nw0 z<_XLY0XN!DFNGIm?Af7Lg;Wd?_*UG5SB{Cd%GSU-)DhV0ThKJ|R-dYDlOe5r3Mq<- zE-Kk&sqQr-!hO*Sv7@X1?M^VYHIIGXy|hm)PWO&(o%j3mpLj6Q`_fE^l6HohQzMl8 z&INNL?JS3)?WA(8zj@$l1kylSxtdsdQ8m0_w!bvE-9*g_piBk74~Ta|svfsoLjWz} z(3=DK4Jyf!e|!{FPTgNcY8VwVtkgwbO}^d5!0ExY!z`Wb8CDMgS`C}IO7fNIA;i&; ziOL*>u;^h)Y+(*N^5ZrMcOW%RJ`PM<5Fk(`d_}K&6p1#P%1`50mWfg7ywpg_OqhpJ z>x5XDgXTHZYWm0Zg^c0?8?6N(#TPKhJ5-Mg9oi@Fy55}`I@7CdbHdZHLC<_wm$j=U zE7_Q<fcp@;Bsa+z_?~Zx_e;I3rr|1K|KvJ%^I@35@e6Ol-1G>Zyq-(3PG}O5a>W@S z+ZTonpC(l(tD5%^{bqWUWF}BHv~ZSiFbP=Zp~&l&LZ-zext<vAKEq`N-35WAsU(GC zi~~T}FnoFZ@+ClUK&LN6$1wS_A9QDf5Fqw6uI@nKnoF8SPKn8l34B~N`=Ee%Tx2wW za3%~}YOvk$ZW!CDndG4)_pII4G`(H~GlAIktnsyDB@rLt!Iqc~8{GH0LXuAllDaTM z(MV?PjI@?$437y%9}d^_>IZ`g2m5=DU$KFL6hCt}^uI8DjMK*6{eYlX;s%prP3j?1 zqbHS%gZFX(s6q*~Of7}UQ5)(uskR<^E3#u{sE!Ue<2Xe04`lhSO<q4}D13h7Gd_TW z1ANbjQCcc`3#PPG4h5k0mVO@#lkbxqE#~Ns<T$(Fg;gEQMwyP{ooA(BvS;csk^zfF z5u{$3X{kZ!EE#+xCr~IsYT)L`_lIn_fkG5~m<-tvYQFh2^1~fhM@9}VXmdgw+{)P| z2}j@KL@J&Jcy%_hOT(67EIgaEYAF(hriekKu$CH>9%YpAl%+6(+(W1(p-jqF6N_Lo zmX&!T8tPP+8*rwJsA4mxi4SG)rDz2Y=1Z12@-ylYLt-^vFY$S*hxAfRa}^}d#EZ+m zZMTs{b|-&SRCYJCRQxy)aRBgNlEzmap|lj+6m>?ZKOx)h&($-G<WS>)_+E)q3t2}E zd)1gG$W*aJX}+d)6B|Lc6iu9AtLI;=kBXc>s(58q+1g*+d`J;OOS9PEV{`q76#)8V zp>gP41{1bxhSWXVvw#bAgHfj7y6NkM?5@8gV1)yg-;Zv`l<>tDw_QgM>%SO2<dtfc zIGHJ=;aJ~e_FB{%noV-EksWBVJNwX2BCaz)zlQH2X1C?}Nq(R9vTpMDw21h7=p7a1 zpvyybtjvfyCGo;Zq#<u1Ggi||wq`t0p;HeRVBE_`+1e)_(YFK4e)x*mqLVzoVErRg z#V>Kz=ihxR<s|e>p*55h-7Bjdq<X;1f?a?|9VoH8dKy6IE#em4fExk$i{m{YT{lUy ze1Q~d%r4bM<*ou9XGl05>QNp`zPPH0Hef{iIuZQnhq70KZ-l$+w20%$UfGa>(Mtn= zjs$N8NUd)qUmGX`qf>h&DUAaj04<c;K3L{womyFEiQf(lUXrb9@-T&$4}=*6Nxu%W zw!kESu>VD>Tyh>}3n#9Icfcj<e{Kf3LtRHSl|{=0oRb6Mft-zG@Lk~W&C^++<nBI` zCnhjCGmUPYnIE`_p(sjaZ|(kAu1XIcqa_~Q!-+ib^3aPKvmbN)anmmKf4qijO$|?< z<|@h2zu9_<=hjCzv1Q*EI8rN(rz5M`Qe90b{l&);H%8C8ZhEHfYf#Ac^huYQ85+N> zeid)g7a;Yz-G-i-&JD5mGm|}7_uFkTz28XUl(vQmKzp6$(po8A-o$Bek5&e(dx)9T z)HhzabEsNt!o#ChvaJA2j_)(5-CR#$X!a1H+dK|1{>;({h+SL~F~|Np?dG1?axPR3 zSZ2(sH`INkmf!n@nzem#?P+twOpr{UJ*v*%&4rt}PI}%hZ^VEI$FIMdc+&JmUtT`N zm}C)0`g~nR?i!fcxZK_0bB$_MSHMTO7bhRu)#2)no)vU%%qH$HhL2k*PrSdD5Aduu zc8SB%s4^-Ayqj!wm}x3oVH~2Y&ekWll}z4b8%uHNQen^P6^&C#Ly#IPw1jc0uzHuA zwcLM|?f)LM*sUsXf8@vhMxK#Mi3;1nW2U^{_22`$=XRJylFx(k&&g+tlVg4)GcI7h zJX74vOFkKvd~Y#1hJTxR2Mn7@-e31<JD@#T$k*&2jEHbYlVX}AqH=(IGoY!7`m&09 zChY+W|0IZ`&45|Z*p6hhwW4_eE!Wx@{oDyn22=B;Y6!A<FRai~FQIbw+55<r6^Fao zL*@Xpjh))9SqI(0)W{C83dVt27;t^5+fVEAi9D3}xzY-$^fNsfca2Nxi+l2!s&O;m zUx8);IV}VZ+&13Jl^W2_P&`db(W0g>Miq+G)4x<Dzpqcm4+{sAkv2aS0RVS;25RKf zdV-#2?13TSkO9WKyC?ro(Yg3Dz5j9iyNlT{=05jbT;`g)xwacdE_01i%{3(Eny$w# zX0FZslH?vGNh;~aP>7N!-RF{2l1imc9Y4SS;PcoX-|hQ(zhAHCQvwLo`93P4_Kf-? znLy&1@Pr-QSQ5R&*-Ze=@8-GPB=EAXl(!9e_RvlZ($J4-KrDCDHVa}u%Tdna*wP_2 zjqSN&Q(=86dYrqJ(6c6RcJf?zr+JXSls75leapXiT(SIDy~r=lC6#LTS72vw46(_~ zjdiL^_JpU>%Tq|gmJq2gTLVxr-}#7Sg81wQHjK5EVpX)3j?0C<xWgq?z;?i6e%%3X z;wP6?q`7B;(Gq(@kjNJ*e*e1j#5Wmm2|E^qI?1C8cs^YOA@LRusOO@1k0}?1F4<RN zN^OXcf@!ugfoqF)$RnUD(Ut&#LudnU!K;JPhAW{HBz6M@q^8l>*(z4LRDUvRS}AqI z@=Sv013t&Q*gK_b;$y1lo5Gl%pVfTm<wmUj=5@j49?}ihhSR1sLN0-L`{ULqzndGP zF8zg1n&rCY^QGB?t;y~csQcq|!T#&+KkShj?ZrK65&;-~ygj@(5I#C@{_xw5J5jkQ z9+hduG=UeqOf*y(3yF$^n8t#zz;IT(fJ<-y7-%^TnEy+FCxG>~2zfwO@HlARU!Vk^ zkhzlU(m?#s;GyZ6*P3=)UIMXvSuTJmdB#MN2S~<8RCmG~2`?=#Ja&k#Ra^8Br1kRS zx+FIk`4#=JpF{)rqtlT@nS+xs>vP)s*Q9CR`2PJcb<dMU79E#|@Kbb+0H((Gn>Q;3 zNFM-ru;8>q_|T&Yn(dVv3PEiC>7hM|L=Z!``A|S<WoVJW<;ZhiO~HZQBI0$gxiNM* z6sQP<YeE4Tqzf`=x|}3;cx_vwK!}oX!|D2cJK_>c5gleq0#&Ung5(9(mPbTCo+3zr zOUD29cyTk(=L^gtztuvzG5GDta=PR`G0eD8`YPc8{S|I8@Z3RkP89u-%v|Hnc0Q4i zok@k?sZ!=;_LR+@zx~1IOTT}xz;hoH77Ujt&hPklR0j~7vulw-O{A*b2%DMy>eAf2 zo_ZSw*Gh0{wgzmo49;bimJ3St`wamG=OlrHt0%XVRw+jGDOF{)?w;mdY2gZU{%O>9 z3b<&JD)o66V)KQJV}=-}{pw^)*rVW}9NoYi?@VZPo4#+lck&2Ke96VbLNdNzW-Hsx zBQ@&Z<VV2o927eoHHYb5(Q^1m5jevoEV6sSHy{5&#IC{I+8%_5@Y74md9ywhz^VIm z#99HuBq%$ME)l_m1;Vdi56c~gWKsMDyq6jP+^ZsU<ZCa++J0bjOYTYJavlX#FgeHn zKK-X<VA38QN)vEh1^NLYlQ;DaGrB@8p0_?Pd+h|zza=6DJQDxvOcg)Mpu>)$b5aR8 zzNV59%cw5t8!uj-Ol0I7Vo07l=T|m+@^F=8W>wD0;IjjHQt_IS7p1jRH~8TS<!%;I zO|y45Gp6{#%cvyt?H?4Z<JVxO=q|g0a_h7w?&pc8P&-C;=O%_r?3|UjFjLX{Ql%RH zw46bAn@0*6k7uY}7IBC%vcTVAz#*Dzyv*5F4>#-OKt2T+Og_avF2acSIeH+d5`bc6 z)_`}&-o~6;eZrjs`ByP+Mg?w3vtb7^B?I?7k}}IlLQ7g%N@Ox}Qs|QLM<ii$+Os{k zlLVLBN2S!2^ABPq;{dBf3{1|frWR3`xD1oK%cm20VelNSi2U;9SKt0si$qKQm-%4m z0?f^vcMuI*4$RHVf6c8QbWpk<*Rr>ww*s<K96I9O6@<9t4NpP7*;Lyn6qIboDsEa0 zTsmY5v5Dp0)8)R5C-auK4sOW<LduC)O)s_*ikU5DfX!U?j^)G?Dk?VoR(4zYd}*j) zRmTacgM$PCGyEh%PU6d#zE|YZ#o`WgNzZl{cwJ6LrsQmt->dfy$*fn&lP719<+`3Z zLBjl`Dp<PM@w!0!1~o4}%QL*tasS$$rdvJ-Nx{vTKEkYdLLF6D_54!plPX4AXqCjD zObK;)=vFd+TjIlV%nMhOTNR3LxP&+VdLc+m%+nIYcT+uU53b{<p?mK+=51c(AuVMa zngCo&dRP&N1vCYcWLfWSRt<0V?%ToJU0JRA@ryio<At%#xY$;uy?&e7<~hoGK|b%z zQU%MtiFZF;_Acy{V!<8xt6CRN>8FTKCkgDdBrdbM?2cv`UuWfN9jObc5bL_;Wqb`P z7r<<LvlDuSEq;PFn|oD)d*yVU%g`)PM^}6}Kge7n9WD{Xgqp&$U6vt!LXFi|F#zfX z#s7McqoBuhUwXrp!N3bcUi*X$TZReOhQtY%?lY-c$PTZ%KQyjJgWq<Ahnj#+Jm4IF zENgY>d2**O5%g!G!Zz2YFJ6``ez2Ik#rXBf4JdyW6BgQ2HIaT}MaQA8@e53ALatj~ zGBHz<MM5=&mBqs)qkHoXR%xAf@ov7A{h^~*U8-!q55jw4aMMI9dp$~mCN1GR3BHh+ zy;`mzz)6sQ@9nw@O$Oz%d~SsXT=J~7|9dmny7!i2HUvvA$}EyS#o-)T+L<jR=gfU9 zGY2U!fbUufZTEA(m2{Rdja-)|s`f1JKXz9P%1X<GC2ugJ-%bZS3oEZr5W*Xu2hN1Q zoXCFQax^6S5XvCQGe`MtXa&(AX&H8an3EctlOZq$Nc=r!cbdGPyR5<Xhrr@S9#pYH zirzQ1Ek2Kz&t_zD?bdiRM0l<z!W@=+XC0Z1d53g*R};&vzu^pExMqZ{U^Uwi!-cd& z21Vq4t3%ix|7_r>mBFlFU+rcdIq5L?=rY>sMZ(%9i<zSvC0RyX^Y_mE8+`X}VQ#0` zXl7b#>kChgk79N>HqP=d9?<S3ybV+n?ls;1-b5n3*)lu!iE8Ei*WP*c<TLRPb_Fo` z>mBBPsO;k_@s(MtmnRC-)b@Lr?4L;q$Vf+ga)Dc-xMq_a!z_?#FULGq(WENntJ!Gm z4neW_1<f0-CG*kbpYE_fx%EQ+UZrcv&-?0~W}X&Y1D{#(s>@YwQ923pEIE;zV4jnR z&Pl=K?^~bS)^Y9WYEleC^1v3gRA;ITO?)2(O{ei=(%qN8=f>K^mt#yu&f|Zw&+yfA zLMM~6Yj#}My~5qtdx}xg4MSAp<$@%E=zy=AmKaF5F(j{T-|l^gn=Wv?qouH)5&rOM zt*|fFIp+NNB(NdHBW|rISP*=?+W+;*cy(4~Z0g!<-r2m+vu$NNEb3Yd>SR8{A{jZo zFZl1~>e5g-gG+8SIcQSI`tnPIDCVv+n0TT;e9%pB%s2PA4oRIXaWz>Yc$q51Y>ZL_ z+_Q+S10j2Cz7h0-4s8&N_S=TARVF!^4><3;48J~+RSQEL4~8p*ERtY{!}26i*Y8wE zZL5Sgmgl5mA|xZ3t-%+V)ma%8jG()R5Vgua#{RhuP4E9plt7sMZoJdDZ126dgP$Pa z?hcuH;tfk@@#_S;Fw+MsP^aL#<2O%S3l7*g7$5$S^fmahUFI5ncO^4mr6^aLl9HVz z2sVJ&OoFrs5W}_uLAzSQ<WAn{%n3C)raE8x&$476{m;ak*6HJ^Lb&76k&rVTtu;Bh z_pVLXC)}nR)}%0DF|5{QvOg3gNO%SSv%wQJSJK{}3(}ykVTS|??S9+}Qy;^GiF)}2 zePpFg`iJNC0s3E}XyF6|csBx2&DsmZ%+-7smY+*(ud;|7mg+xW-poMixuVMMH!En7 zalNrE7{Cwv;c&>=b5l77wa<Zscl9bwO<TPVXTBYy8hD4PV9`U8S=tJrBx{hE%2i$e z@#x>m@7u)v97#p9W8M3DHwDx1h*Ub`#Z~r;+w#z}WiLIFUazR_*#EHB4tOgA!Pu$K zFQ-)PtaPiM)gvaoSh?U(DO(%Kc_9U6g-pD#4|uf_e%@`87&$z$$89j!NVa=eZdmzL zMq-Uc{DhBoK!#UiSESL-tA8ZKJGWJvC;zR<HhMaKs)MCw1$(SKP*2EjJR&F)8#IIZ z1H(f=j2wR!sYjW%&y@z-68=8QRte~-A65>JVh`^-=&VGe*`U@rG`*KCz^=c5xH8MM zZv$6Q*}(Ho@(6VciC955$vW0lD?W&OTdRVOQ7CkiJ>cr8BugywSd1dSzF8_PQ8?Iy zjC`w9I_~%;kc%wbRLK7IG~y9s!CUiM!sR_y4@i(ghr3?i9$1W2^_<RsE3d0~>|HKS zQlk*)k|v+)qR3c?ewDp3{ynGKlpjEr>Q{%_!~J;B^f_f2hcc|IN+@lSrzmd-l9z`L zC`ZuJoO?k3*E>9HzViIYfncNLbzz$E@yi<FO>r>~Z641qG{uh2$K%V&LE^=WOKp!Q zgs4v$dKEyX6|(Yk;ALcCq*-NInvx%sWIbbj`JU-5iXzhT%kwyY+WjipHriaFs-HRZ zZ}*NPx0bu5%_MXN-3$lO3L~cEiAE`l+s&ehMiSzO4ggYkGMyzPrc4F=vnN`ama01w zq+Y3@3sc+N=d_-!Vk-1|LiMME03|t#FO%|~b6q95Kr9Og{$+C1ddec>n*7DkPZ<l$ z*Hw`x4c~V`itI;WhEZ4Cx!-ot?0och9c%*q%ZR#h{L}-ZC$o{LUS_9mV(=pp7l}_! zxI9js5-eP^oWI#FV?CDn^VK0a#APBNf_@_ce^(V`%=_R0UKW*+w||-RFP^s3xQ6<c z*YL7=UfPat`Fpa-;JYMnS6%Mzr5)HEt|$zl&`UTfH_BGv?g{TpX;s+Ukd1PSmA^Xy z)W4l-=U(>|!c+)d2d17K*d8+P4MBBY6bt0iX>+`$#V6vf(gKH2#UYzNYnwsQH2Ty@ zg<qQn2dO>|cN^29llm_eMvZed=d)f=`z!ke=>7Inxv)N9%`90ks8O>#m{{RgxF?pP z$TuItSX;nt$JxBN5wL1&fA+Q!kgVA;tmbr9wps*P>Od@{{y9LQ4$W~JCZRx{pOjl~ zgVH?$tTCh^KdyOeSbSib%6Q~ZmNmZ}^qd#&R8dZSnWzV!*P@*;$a!-b8Z96GjH(~S zuZn9pytAvCma%1ZyP_AARD7RGTSqCJZU(8d&OEwmFhW*<>iiW*zQItC3kC0W??foj z`j-^2aeS?J=6vT7`I;v;x1HE?YS91@vE9dW$nw|a66dNp>7#${dIB4T4m@h@X43H_ z_ARxiRCPk(9({)9^M0637YOMW%aL!H9grPkz-+q)kPp&g4D&+rc4G$BCT3-Ctz{E| zw3EpqL5%g8_k6pXWZ8YaBF%Mk0cj;1)rfJk@V6+67>`it?A=cb`_flF)M?)HZ-{>@ z&hVu(O>Q5Q^chES%dPrS5C<ix^wmSKJT}HAL7TP+&#H6gZ6%9G9s*5SCl$Jzxiao| zhG?i95)3!_`>x%Pfd^+i(E9Bfj2Qc^=wT-Qgj;u9@Tz;jliub~Id=O-RAf;c3$OJ$ zR`2=V(4qsZT+N=I=)!oz;ys=Vm9vw4TOrxYdl|$?LG8DGW-b#C-Sp9zr{8;H<S!3o z=A6m`!OR0Ah~b1L^zq@BUaSVGAi-nlz4cV(KTMg7V6f_~wo#M4?7aV0tZ;7ZSJWs2 z^z&%fdNcc2%1&^O`0!h7bwu_3Aq;=pF*4j?Su{c9Spj99hC0KMv<*V>2jr)E{lA|c zjbGYU8HL{sZIFpJ`G)*f{!nj@>2BATYy(sco+TjOdUTyC5754Xd9en2q0~Jph@$Qa z^UML?vu<T$_FFJ#?%H)XNcjaeX2)u|Syh0Zr2X;ND46A#cZc^LeT4v?I=SJlNA46r zspw3JyIVoof-pv}uiTf9OX4O)?^+SkV^*Y*Fe`AQN4RX-9?mwV`zhsyBxeBPDivQ2 zd?3q~97aaOKc+WaGVzsqcyweJZpx~tHGa$f@?L-`0dvZj5Ofy+D44s7{ja<J+PJqp zHhQO%mb;-Zcb7Ma5rB=muQ}h}tozD+&tS9L4Ub$y&xm-nt)8Izs>Wx}QEYzH>_U0+ z0bN=a0_ZvcvAV$=))ZrW;^7c=Z}7+KudREdGZ$2LGoh|!b25<aG__yeV=RP-C=ds! zD#5a{_eYfGm|Cb+-FLMBCi56P(cs=Lk>c2-z@62ozk!u968gIWzXA-eY7m0xOC{Oy z5_)G%>v*Di301G~!@e8Ing|8wGR$GU4A54+0hk1&+tdJdhh?9%;>jEm3Yf~GCx&?j zyzPq_w=<PI_#oM&9cwyXls0;0+(I_JY_JXbg>NHn5YC&!yu^`o+pB(Sc!dbLWY&@? z-%sXX8AOwLZsgR<Pl>T~F8&b#VeL5}Y5KBJoj<5pw=(0rRvYDHco1<e09jlE^{eac zmpkzxH-C#-q<mUT!<Pto#DoSJUKNxOGm!V+`r}}$3i_(gRvFbiHq)S*p&m?9G21{N z(I_9;4gCfJLi&$v6XxXoDPFy<de<rQ$WL6M;^$Sfr=dG=dhu<$_h$$PHA5YbF-kej zr5pcxcs%286nv3Q!c<y9-k;gx5~N?{`?iWFt6a5);(A$`gL4W_x30H6S}nelkC|$N z+4T73*^RSR5?Vgmlw(u-uF_TeNV!G;>QZ1EHC^GoZxicM{+=`rsvwg)HHyh`O#>^J zOrTZv+#D7}?ZMqHq<<FouasBKVeM_}R0<demz;I?Ur`n&>M0}wnk3}k{(INocW!p* zqH(<@(W&JpZ@t>>z*M+%A@urn9wU0#D`+%cS9M`{+O~PnzC(0L^C^`#Xw8t04!i#| zYt*)C(3SzQKyj?TkPYEmQ?WYRDC+2~DdRaUa>r{bQ|_ZY&x$xmyfk3Z6?Ecl<stD7 z|3$EcxsRtjt)u#$N86^zgvB+im-Xr5Onba)VpO=WImS1^#saWeAlOlltsFa`i4qyn z<qcS1eJ7|&G=)YJF}LuWAd+T=4uBr{nO*#u#N&`?JKM;=<WJtGz33@+Rbfth){b2T zk#-9Mwe>=2&7?`vGbjLPte(-UqhUt5o+c3JXnk<DuRpK4D|67<eCCp__>Yp?Lb5`t zMctuigI3l-vDUd)851mXf8F9iTf!irmT9=ciDB&hkp7I>@w(H5>$)t~Xq&m8toGTN zmpQAvG+w8X31WWVVZI__eiD6_=ViBx%nGQA^3-7(?*wYdrI=!zMKPvT5Ck0DI(sS( zq*1U*G3cTE!{X?zM5=@Pb?MOk4ZKezsMZmAPxBYr{$qvVo|p_Wx@#c2ZE}LSn>O-D zfxymj;>n@aXv>eNUUI$iG>8|ec=3(i>YMG8gCA~bkWKt)340~g!*qXX{9*BDVim$o z>is)#G*)F*-2IpWk<UQ|TQq|%93;^+fh;aa9)d@6RC_^|P&~1B(O^k|)}>3E#N6<p z%@H8B7zjRdK--*RA)xNbRktp3w-A)?Iy|T%BQmdbx4lYrL`^c^i?%VUy!uNYN@Och zhRWV6(pD6WdML&lLykW{8X;`uX0py~)1yyK+jnucE6@V^(WJkwWU0Fw>6?4F;*kHl z$c5yS_HyKx<NsEVJ&SIprM<wr&|bKzk=sT*c15_LOKjJ7Sf$NhKQ{l``94+futbJg zojmB+D`#Z%nt%}a*uJ(s_SD{qI-r$fH<WwZX6O)m#(cU)qfKOrejVTnEhJ8Eo`yn` z-+Gt~vJI&=n8B5UAf0u|T}EiYWYA&=qyq(O2t=k{Rpz}EdK=Y<0I^8J1IrvE)}WDB z!H3x)&*jHupnk@Nq+_s-QQD+REIa)40Ir8(kjB~W#?iQ4m8(Coq0Emz&6dsdd}jY} zqD|kkHt#?m?GKq&n*9QT8u~W!>fq`b`|(=O@BHNVZeC<&vfC!~&w81&fGeTC*T>c% zZh3K`nwo|j4g6AFImEXmPz}*wDOlutwVdQ=Nd2#U{;_)Go;s`7``xX%bI`|?x7n&h zjuBe+4NsD*HE6z0)_KXXgmOPCL#zro+d4RgVGs-5WojG8VS{WkPdlbNT((Dr7FHq1 z5D~^J^;ZT|WCm1*K-k$x11AyQi5KHCL~5k%H*(F>&mL<oR`(i^iUq~zdHxGh17fE& z8>E0tCHnQDl9v8!@<X~(B)$J)`z{HbMxaNhF!<B$iSV<j6G~43z5Odnu_kB1p6@+O zm<xsoUlpEx$e?30H7RWW{`&LLH^Dk<Y%Fho?6J*UW~~9Ur=7h=vF@0=Rqbf1xfZ@h zly%(QQ-ZtClxjhmU0}*?D-aR-11ywe$Xyh3G}i{R)sv;2sE3BD=>Ow16phdztTZ_* z1Ylx83JD+$0;e^Gf+tbVIY`jLw0>?uycCA^yU<$bP<8JSjM>9b@rSmK)~g41pZoLS zfWy3p5O|Rr1-9lMG&)e;zP0aqcj|joiIE|#it6A*1*e>+1tKyKxs1Z|Z{GXH3AmS- z+#$bm=d2miSdj*=-CoFjnNar<)r5O?o;F#J^yJ;1&s|McTnc<%dl%%^!`auOx41R; zzQoI127BEc@<KtZnkjZ-(J>U1m$I1<4FdcCH|2DSZU@EK>FwG00gZzA_L>hdTXe{& z4o!u!@SaJIP>0+j1C){TTiN$n1D>dZ>$(wzU_L?!bT~o5%~?*<+-dO6ME{-J67Idx zmwfJTY}(gYl7f7yE*<Lxo#kKn%ZM|oP^kTT8h8e=K;Ji~=P%wGtc>8DWR5OL?5Z*! z3X<YmWI)BRPTJ!8tXCAnGOz|O{$?XMU1{);$s75`=Zoj=F(q;=ntj&1J9f|saZ&O5 zQ6d73Ly!UM9Q&ZMJb(}3;EAI4u>}8~bNO&Na_xXxtfyM@8QItY9(_o|#<v|>?Pdu2 z;s#CV8-nR>BST58Rhx_7WEGMuk%#~DCD$hXpbUYFB8-wDzU<F`GC!6{m3uXMGxE4` zgu#C29E<NGncy9NPcY4FP-cbsH4nr$+T*NgklV0MtBiZ&$PkO>mzCY1d3B0m55)}K z<_Z5Wc?)WWSvE75Z}c(?Uvtk^;I(w}^wLByM-d@Pr0b;fwTp}?5apVQK0Yubp9uE9 zX+*Ubplivh{r#w85~>NF;izr+|FZXBl6t)(AW9^N!6i(~;*B|v8{hMK)Z0s|{Ac@k z(<~TJi>pKMPsLS2rhFsPEJ}|(b?i7`n_8s-#lzjsUSTQ+`|!d;Oy4XU)1cw=1vzym z-1i-R58T@XAto*;3_O0TyZp5s>@^f%w<xl|O?j7?pp<U1Jz9mPYYZe%x>uXp9Xcdi zR<#R0;B`5)p@tEb78L}j^|RFA1KG1{NC>bM{XA&OrYU`<iYu<ULdzcMd|TyilU8sR z++DXsv1E6tZ)@>6_323&xBRN_hLKpsk(pd`Qa76_>A%yi0OGhMHL0Z-(vg3^y7@@f zR4Ju0Swl7rL&1+{#0oU+kNJDjbLRRLO?jo7ZR9q-a8aef+&bL2S!CbKxtr3N&y=}~ zvDVlH)~NfS>m|ZlgRvyAAp`sv!M@<b!J{}^Tc?#>Jrk6niOwNpJ6WxEKwZF=?bytc z9U`O4$f|+?<VoxBX@Y>I%N*AMRtP=A>yNtV3nq}GDYT1Gu9tfvbfb3)mBhDm708&^ zPxLSQ3#&`a_LlrPZJc+~wwY?j8Z=}=9ghtjX_?ruSMOCV^i87P&Ywv;-D!uKY1T*V z>_F7eZG(2#K{}ZO%2lBGRW_l@$3&E~-BHE`)L-V|7Y%x$yW4NCJ54`iDcTLp^yTO| zi4Z3_c%FI0L$)peU@@W@?5S1ykEk6(>TO$|vMx<8a{g++Mj07B)D@3_yUX*moN2O) z068-%!IQS*b4uIwACFA#%3al<cBuOJ9*C~GQ2cT_#+<AC&o=QbK^$+>zshiQWBNs6 z71d@1q|q$86b5<g%!{19NMihAPG9vWL2lnRB%@`mjjDt$Q1d8Rmn2yWO)kMnQD>2? z-8G=S!p5?|4dY;o*~8AS?8v^||DdgzfAC}{N<i;wTkB6$ELjUKg(XM?hYhP%kCSi3 zxAcRw{>X-66cvU*g26SxfiaJbkOu&)3*5gukgVL*yTkk--DL<=1-u;H=pMJGy*&Lr zCMf-559^7N_v`6tFUW0#{V$cf#eZHIDVzmVX!puFD$OE8nYWoLv?0Uj;*xjiI>@7q zmv=s%u_(BnnfCC|iu7Ka2a79U^F`6;I9Ubn0%9ClqnKQKZ8Ly?@^ZHEBxz*d+Glh( zsvzbdWqadLd))^Fgrw^vYFnC+l>tR=6E#vZx;<#0HOn{z`sZ=7M&K#=UO)~5l4bvh z&L^u0u9}qE(r(7mtU(v+pz_T`Z85vOsjtMeIu~U@6M)DYgpM~-N9(kA@N=mNb+b@r zM*38jvCT;yHNDy`Zlh;vr|RQvx90VntL1}A3X*((M-feanerakbZ{Lq2hB67iDhwx zUPqI7h~R6B`+82zG}3Td53atu-^Tt<Wjr`sc5mCCy>G4KO$xzw@WFQWs^s<ng)X*= z$$(lvSqDnd5uy#+C{5O57rleK(nSUdoVQ6`(frL=^<7K*6luEsCNX`hF-Cs~1wxes zwkA=8qi2#shc$2h$JV54O%G^Jp3sN|samt8(PV`+z}e`r40=GlV?eD<W#ZJCv(z#g z?}!`nvqy8La=`$4mW&+l*FH@{2>YMA^1vpu6HleQQq}8Xf0g@wOiUB|?a%&GHE82R zP0MjBHqmCLA)kSR2>(URqK_tCtheg|k=DNakPYrjdwnx{tLggUDj%upHr|Q?Z22nq znCaf)1-Do&kO^e6Aj+y(`Xq?nZqn3Mrp`r3tH{rK?deZ@|9i%`u`8~<S3aP{XrUu) zC`B26H!m>2?pTR#@`78wilOgx+xy3Do4z`(CFa*DZ#_-UwKkL3A9^Y-=<SflI+uJL zc_gCcqOcA$I0<9B>uP^!8XUk<II?(sXxrNS@R7y-M~yLg#W>GQ-MR4SLUm%wgR<gC z=qL)G&{r#uU)tejCcQ6-2TqwQE}#J@L`jpUvUP0Cbp5TaAxR|KS_Ol>_=ffFVS{_6 zi&p>kW72HbKXfGN%Bqb0i5EYRz^|`Mc6{k;mox$1kAmDC`(;W0{+_)5>~n0<Y1`lG zquBio-=8eNYaw>e`I@P;XN_f<iJ@n;GP-~98?%*CVjT+FQdgS_e4a0(<C=5bXl1Q~ zdQB1jYVK$t=KV;yAf)<jd05Hjn4TNMGFMl@ZJvcUYA=}tUoo!gr^r}3ZMnoLzX6(% zvNhx{b~hP?DqibNGcNV$=MBlzVc}b;(<LGeHL@s>DSG(4ijt?tF&DwL*Sx^F{ZE9E zvi7zP+(N^&*+vP|F}hOL6WcLP(=(F4=&FDvExN91YZ=~v#MNN%mJTvO(|+yu4Vq#s z=Zo+Mujay?cMcdb@S#>?4>eM!tNEvY-5gEAf=)j^iBCQEo?5y)P69)E*Z&JvTX6f= zUCo3I)JW~2l1px<d1H@98iMWSQ5v$wqPsT)ffID~=k)dEL7{`cTMcEM(cDxS3kJ~P z-5&|6TTc3WN|Do>YDSfUy^jcY3m9=|AW)?yxnpO{Kz3DVNU}t!`!WtH@9}$0B#q6{ z^r!23=5zB+Zdc7qoAp*v5c*Z-9E4$SFHXj+hXI1hXOJT3PF6c2^7|iT2FN=9Zlj)b zPys7t+2VFVvaI^DsF$(x%M`!Dh*WF5VQuO9)oc#DF{j9ULLdQHONhBeP{Bx`|Ca}+ zrcW$~F1Z3OUX@|7_cW3kAd%h~q@qOA9IeRLhW9l0;lUZi@Q;@tY9^ttXMdZp(2*S| zsC#v{*1xAWTPx|d$I|KK*Uw-tvv>Xdaed&-j-7h|uY$HiLQgPBEu61LE7`p<%c;2& z^jl*eu(A2}+P)(G2N<DQz$w1UQ&pFa;Cp~D7ko!H7du*~aC&9mpFZXNWf+0#<z4Hb zw3Gjyd9v`(7Jq8+pY3lMIiw+MY`TD^^P?-LGfm<jpbawpoOa4;5-aP_|5*JA>B`0T z-gws$I_g-LEg)uMMIh3P*DwWXFEL0B3j$W}lGPrdbbpyEA1-2_i|xo)e<!+|-Q9rP zd1Wm0p}KIMMA6A$MXLWG2`;Xe>KIDx$XiiEIVLtBGT_ZS8=AZ?;~KTG-H~$1B)Fyc zG4iPOBWJa0IxXg@e9By6;H{&o?sS|}v`nPj4U(JTthk^~6OZ0FGU`?JGe3Jx7dJ%M zbh8X=&f^}83Rj!ccBhA{c)RJE%0HvIIn1e;|AH$t^PpAzQMrD<m*tb^LX6)x!rjHg z=DfB0QaubwiqjffZR@@y?&8<|jg}G^4XQaPoGKJvz<UAx3b6}Z!Fm?2$77DN6ay+G z0Dy3-75g8Vnw<C80bok{QksiX(-(u($T)@jbA_yacg>ZJyGl(0-!VTQ{HNUg$35p@ zyv(MQilaqGMB#n$nGH%1(|g3}5gD6KEBpn8dDb#f^ObAVo{vXl&*3;m(JRU5fWuV7 zdcOklIbMrebsf&8F)y`4q$F`)kVk77^-5e+1ZHWzb|tw2FEGHIAF0|@=@w)!>TQ$9 zLc;;(b_zNI?jRU6JJg;d_)}u*582vpxDv1=knDa^jHN2>Y7r3xcngZGRdJL9X1Ws6 zkNVw|gj*6vv)YCA1FyaG{0kF$a2j!E9ql=^=so!wZ|RcT541cq+S}=Jo;tE<WZ-}Y zlL}5zIUjDakw@1!YCkex+Q^DbfoWM>;!OsPNb|dSe7Wc>xSd&^T(CQHRb`O-+M+6F z+xuJAI7c-pJO3{-i86Y)^2HH75T-)Sm3CGQG)&1-mv2bKDN^>p{q~Qj0wyA)W0gqz zNP7^#`fiUd@QUtkl(+0~lWFEGxv{v{Zp<qKo*N(kv5(!9b>*btyKNF^w$des!2Oyp ziT4)kXMIO0!6JFJWyOEKYeL)KX*_4<=nKsmn<0^!OB;6`-NI3YH=o#>yoQG(cAR?S zdQW$Z0NdfSUb6fbj5eR3`>+}c5)gv~qSk{nJZ{gsG|L-m^5+g&fnU=Tn$0w>-*;0P ztU8Nrl-rG_s6H7A>ZF+C_7>7L#9b)s-52oRX9T;f!0m$Ga>V5NXE&28r{;Q)K>BeX z5b60&Ku+D^&^Obx5al|kF)<XH-eI#M@B2?iRQE&qiYBWFhA;sQ{O9qSbS+#ig7n<^ zdc2(Lt{t&z2P7ScMS}Bt6vArga)3*bz$~gSFK|=ItE89JSzygsoNJa)A|3o{V2(X) zluB#Y06`;FzFNDkli`#sZf4VCzHJDStLDK~vz}in3=1cEvszCZw8+0&?3c6`6rBNe z?JH^qbU4A^Z#kx%P7>pCCfZCBPN&Wm5q#=?FkyDJndis-G6O}sPG(tOC`RT`HMDJq zRD$1Whp7!>-eB%ozy5NLuj^2x75=4Hs`gyaQ5qhqji9F<mD%~`yurU?vR=vm<?m^u zXpK7O7^ShL_Z>(&swV$qP;|D~N9A9|QyWo?h5*&R1X{ZwM1XMs3nXC_q{F1>2pLSU z+IbKgA3|3jI=rt)tS@=6@?+{e3|KVR*nE@zhQ9BueCe{TdQo%gOg|z~c4JZUa?twx zTm948LfRiEKv4dVCp(#!(4_ga>#ifTOg5P$>)de!-s@TPXdsB&Xz_aFbNmjm_+Zr1 zox+hFS>fMijl1{V89}TUgcn38;Z@0--zg`yYo0!_?U>i9;jb;C6hL}re_yuz$UBmN z2p@nS2l{85uF9WFUVQQ3F!H*pXuP1;1{eRiz6I#I8V|0A=`LP&o437|9UFjGWV)xW z)ctd8eL>?ok-znx+*Ah%YaITpAe}oNuDSK1w$wD`u((Fc9&}n!>0zdKgRoNrs)1gi z^#kY?EZ*s1M)P1lQMB&!xhYImcQfMC_gxW3)}yfrzN&d_)r?QAw%|UT8y*82<!^gG z8G-FI-gKB}uh*llG9}0B<+_qquAcn2Zoy{S^UqQOwl)sCYVt}2Y$yKk$#VWLZa(|R zfoxlFAkTdBtL(nlEjhNLVI`9SrTfnP0~n{Z?HHfHifF8?Z!$`1faoo_87|Ea|2l%z z@|x4S2@0E<Q>&W8$P`>@91PpL;<)7j3LK_wZM$L;i2f}6UK+Y8NAWUVDZSxIV7O}U zfYPx!%@`0<C1SZ~T$zO`Es+IEI!lk`{UVAKaG;w2a|~d5)o#P7gv)pMZ0nK*prGfr z;P@q`+|_ypfSKt2{Cl(6Z=!~Qd;)v|Fvtgaw%x!32hN|>4*b{qlJwZWp0U`y;+o$b zP#h<~76*cg@ynpiv9&w@4Fq0oQ1!t9pu}Ob_$xzAfLva1KYM#GXwK}T3)(CRzGx3m z!QLDwAR%4q<{;PD^(zDFi_|MuvCuE3>Wn1pe}%SDK1)Q=VFnE!*7bxnU{DgSCTvs& zkz6_3M$=estp_&BWPzIT(VnQbymQp`2yFcabPftw$4nTt{r+tb|C?t!o~UsK1@!yj zUyi-3Yqx!%Z%3lzpZjV#;v`-sW0w+%E1$H7-#g4U?3>E9-RNw@P1(n~I!}emPt0xC zWF(<JAUA(?34-qr{-{?9Ho)tg(?Cy(yiBzS^LSSjl~EK3W#FIaDXK;&dUt;hE|EBj z!^MDGIf<}CrblC^Mg(S(O*=MJBF@Ij!yC*3D=s|4H4;E#LL4L>$BC=+Gkn}3J4KRc zCEbc``qzQuS3harQ=*9n|D8$-9O}vjFrY9+{&Y&M*IS)sth$t;g0~q)Vv5z5ZH8~u zl(pQMk?qpD>|&W?i<vx)Iw$K0E>MvCI?qhKxrHDLSFTw`A;z5h!ZpXRm{8+&K6iaO z*V4cWZ&Et5tH_~FQkR3J>~B=fSXBy;U$z#FL^PKuEG-iwN;{0<_TXm@9Mz+bPHh%> zqT3;MO)%NtTTN)D^fFVnhXjAklpM)I_FcdWO7R7ywu@fIpATrJa`C+=hecDoI>tdl z3|jr{aPINN|F$CYDGsod!11}SD_l+Uv(7IbJI`<(Mz+k!3L0MSS{(zJ-->bwzDtb3 z3_LARVcp)do2tD|29dT7r+;!ly<iS42v^OFC?Vlg$Q*+`-};I^zps*0^=rp-l5O$e zbNq$4Eoka%05(!DH%o#q*9WAhA<y{*c3RR~xb{cIbUV>Qe^LPPt%(%{)QhltZ0Y%J zN#_qpokO<r7TR7N*ycFzJk*eDD>;uoiI=(P{I9>4vzMaG7LcyNWpilm>&O6Wm!4J+ zXt7rh`b_9>#Kz%68Q!|ICCeBuJF4hxg-)TUmT+L#8_-AC#Y#&*Wt43O-W?svDLwY# zy$fip&)6a2vAxjJ(1s&RocZ{p{^KqTGOY&@7kN7vj}yg2M@35EIdprGe=|aoMlkV> zHL-JD1+xCL#DP#GfRU~JXCT;q*<l>(Sk~Zq3*W?##X@BrZnCwG&8g3VG;dpj+2xNy zqHz#;?CS>9V>0GmsYdV|<orP6e95F!{MKFE!5`dPC+Ta4TZS%Cg2;Q{r(^fBk2(cP zI#Ot(@7~w>+;AKIK#E`{S>Zkaj2|S))_S=fq(i?cesieMwwWXqLwzuIk!wwf97w^> zTHp&JqZ}y?EeOxhia-%!XL?X3-4ah1X3VELK$~~IW-lnL?*C*?DpFo+Zc##qr{BhE zm5{Z@Ku&m(w!cLj#L8!9$8Oh_J!aSN=8x^WuHs!T-BY0`|F%{uW23zuKTS|@t38kq zP}(;nvX6OGdcqR-x)IMP`%ni-EKepbljLUmKejIY*32-<O--_=R1bOZCM~pV=4<+e z$@XB70tWEsXya6qX8m1L1eSLOaeXsR<B^ZDY)G=*8Y(Ec{RB<=HTI4}!348ivshUt zgXyYp&DyrzLy_1gbeG%Fi?+>B*ARRL9N2`e?eXvO#N%kYeDB$o>Lq!@;uu;PAk`xS z*6fSdiImy9^Y%43T#f995>tnvA^U0FkBh;?XU2HKNaDX)6P*^gap1TW$4^}k*UVtO zF~Yr^IDTf3$V~T8#ep<cfi*1u>ow|EkWNjwei<leH8$o|EOtZI8EO`4eK2$!v}k^S zziK`xP9^G^V`b*LTN{Q-RMziW?}UAc)0wwtRoW7Y@d`@WHk9l$)F(YZmH>=FUxfxh zQf3;d21XrDH7aFX$JeZuKB;iXvS=r9{O4@(wS3zXh-2B}kFzGY@ya|95OHB+qN~dG z9P1N*kS8p&MFF6dL)b}T;pSPc*2W=S6%nl$pV|~GR6d`2Ye3s}TiV}Qw#PN<_?$}J zca6>gCG(PWYmr7@gT^|3CKg{pjrRFM4?DiI)LGHdrPTMrKxS@(vKr#-u}}J-`n_i( z%m2<CX-dEzlQ+ZJ;A2Z|`zl=>aa9C3tThXHJ8z;@A*q>#UG~CvncuPI)YRc6{+OIN zO|7X@t2wif_#f<^r)BDnM6PlYUVXzkcuq@Ub-P=1?eMRYEmS9TvvB)QEm_Xi&vwk? zaHZEEYV+W*OhVJjVWNwu<XbGZ0(39JhZYur-3#?Su+4xLpv5v;#!(LEgOk>5_OUau ztYo~GH9ikrVFNz5Ntk(NEo!un7@uWI5c^&@L{_SbD!J7THCul@C;ca3o%3V)`1u-z zpFzKNID|U{uJSdH$uytHX&iZbrL)Hg9+K7>t^T!pr^-QxuY>jcBMwifoS!7c`S7QE zcZ#haLT)YK-&bSXYGTeV9P&r&h7bcIlCT+MRhPqrgbT{anfNi4eSXhO+|~`w$mn{l zH?S|6MWwbAIY(0;U);7!_6bw=DgeVRoWELVL>A@E*x@@d%`c4b>W<QQO3f4fAUn>( zS&LP%Jm3_KU$(<x>@MdlI4rV-fncjUGcgyw$0$p>D6&A@45E5SsCif|C`s(#twDUJ z(m4P@u!c9M*tshp+)YK@EhBZ?56h!JX*H6*Kb7=L{zVrIsAtHH*ix2Tn-T&JI~=#{ zeEa-{Nx0w)zOi!5wz!yk_0zU6W>*fR>f6!-^C$F^)6!Oy054|pnE<@`sY5cF4nIC? zwBCE8qSU*YnDN}u3mJuSM#<@*b;rnqmDz2N@v+ViG|^aPp8@TX3~w8pR_mPRRJcZ+ z?XZ2saQni!FR|Zy9j>iP>~SnT>>>}8MOe=`P>uQehcfX;h`1AfE^ycSP8f~Yhhw{G zgpYlyWYNLGuOFau=o@zUuV?WUz2l;tZpEWbGr-Fq!DIF~sf(oi(T7r}x%T$+5<)fI zRVn+;5CX0@t^g#q={FqDp=uLL4>=fxxebSMlr>l8G@Ve`y&8k6Cm&cDKgfynnwV2( zV!3e;mnpVWR;<H0&_vF{xq#1a_j+ggq=Zcbb?lE2Tj8!h#9psB&o}f~Cayni)R=DI z?z^Y~bT1ycBYm`36X;kaT$245bL-;4TjQOd&jXmQxh&-PSl98u2uI58cmGD5fpq^o z`fTg6Wa8LAOvIr8K&qY;{N%Y^#AY|>Y=p|V#nT*MD&yT(f$h9=CRtNKRulZp*=mAa z{#K-uDfe`bQ(yJNX9JGF9^6g#)-yZkWA?}jjJLFNNPD_$Kd*cBxBZE0dMXij&$_E_ z@~}UP8qh5A1w{IVxP|4L2KbQ6HpB07$efYv6as#}!KU%X7I(|C@o08{;al64b1_JV z^rn-Djt6EhLn867HGst%v)3#gI%}6~8cpz=sD&@Te>6O2yWqWCwHIeD%cWtL2}OdD zj7ZmcF9R)Nk<+aP*%{|omtMb=OiTklliU(C$E=-RjcAnRYZ`S9Pr2ZpXgfT2QU73l zl5_9;<{o@7YpTJ(my2~AuR&*g+GiP2;u#uVe*@pF;dl0Dsn8d%|9ajkVhq43WU-+L zGb7>}gG_=WKB&?6Gf(rCB*&^RQ>0H@?FZ5l2yQa2X3FxmhPf%slN=j=u=%E6gct^( z)on2XQa>~USiAlQVZH2o>~GhcdS-_j(DDdiXoM7EY#WsCAffK4+ThezebxUTM%n|5 zCn`)Gg|*Kw2ktoW?~>^$=a|PUw+vl<PR;P&OjRGbcJS2wglA!Ht_1I0FIpzljgNPv zi7kP#qM%?mzgdfLWqXLUE$eA#YI|Ms<Cc%h{b7(G)moeLrbfJmK#-VrZn2eJjoNjN zfXZqbmeKHm*1L`<+1_K1J!*`6P;DIt3*LrK(akb3^sVy>)rE`7A<5QJWb@&Nr-<@0 zCbx;V|M33>Mk0~o*~OU28d(*meblA@m$YB=@H!lLNp^4+RAOm!!f~{@)W@)(>RT}N zS@X9d!yj9zOWPMpKNM|es))+2(@t+otRLyZ0Bf@AlEQvN_LCa(yHzPj3!v8xb;2Dq zD&^XV;*Awc6kEPXc%mCAWmW5i=r;%gca0jH1}0DGRsZ2D=t9VrwPa;2oB#u~g-%j| zY0yaOF`0&J?G(UVl6+Vp?H%br#{ge8rpwRGefl_WQWaTDlUIT|lP47pzRjAFUT$z_ zcv;R^lc@;Jtuc}uk^Uiq7Ol9O`k(V~BLnE;DFeI8@jiQAcMPjA_RmQfGt?3xMYf|# zRkDu!ml3kLkirmehjG?7tiZ69jtW=O;wuyw#u;zoBMUv26k^EFLQwHfJ4*5#&Mk9< z!pi`HbguiYo0ryVe`$e5GYc$5*eSd2p?@oUUO{&NglT0Y_(RWXQ@RHDDiYsA<u(85 zwiq7Fu4}lPZf5aZ*yN+Me!7`l?5>Oe#;t`Ckit9^c(vT~GUKb5)6@(3Wrxb2mAbOi z^L0X`oZWa=)5HbP(yrp*K#7=#RtvLMLc5l(IVAAh3Epq}-YK=nc_b5W>iWbp{UG%@ zc;*wy8f+fgeh;H7V-5&feT>G#xcNqR)~8T6p`*L~N_I4sXc&%H&C@MzS5Z8T>sent z-U1MkxoauFGN&NU_L#dSKKa5(aqD@ssYy{%Ota85LygG;+NJU(bco?D)FHV2uHsQr zLxMKLNUj+~K5eUe8Tc_X?&P|;_}KR*{k;tEP}%Tf1yik}x!msc?By}X_rg@;$1;6A z!Ml{~wGMcyMGVhaFYI4%c03jq62ioT*NQCWLxODMk<g<+RUUAZkFE^4h$$kESkAi% z?}zYlr>bB0rX|ZnhEUapNJs#X1pf5I@Ra=&O2RBOc$h@Y`H`nOTS8%<up-Qvk+39s zHar`noAx<wgt{&~JN+dW_Ya3F+tbA_@{-(QU+z)$7v1=*G<0Y?S<TfvsAPTy3f#lf z+fXdvr=aU_lxEn8uivh2@h@0~Ge#qJSHHNO@3+v~EuXV(%1^e(T7Zd12p?ztxO;G` zrrWjk2zIfNNeQ4(EEq-XwLqqLwWvd*BFQL3)|nuhh2EU5Yu|TUxC)IkO%+HWL~1Fo zyj90Sh6xYY(iz{u+i`(N;a&@A#Rt;Bx7Zw;yYhK%i>)}juyHb~kqYPr5Gb{1ikN8u z^n)BcXw#(F{f@;>@_Bj<5o7^L-nj0aflacSYd=wlFH1h{O7<i_e}eK>X)Xb3A|H2w zi;~JBH9rs}gGWF`&cEf2U!-~vReDSsZ<WMDpVj=l%8*KpjXW@Ge$ToW>oLH{-&L-= z0Di?sMH3b_*{sz4(dzyKC0hlB8<VcD1&_$nS>`;6fow71YaRzJ>*1w7Vs77%#}M<C z>PP&KIqclpZb0S7G)F{YDyj{qn|?IKL!%xdX&G{_CYK^ug{4Rk1Txr?uQ8rO_CnPj zC}Eh2aDc2mN`GLW1G%mSf2Ti|DZ7{jNf<c~pn6)7Q|KQ+@V~J??w!$8>blQ)L+p@O z;q?z6O^S63TYs0I3Z2OMc2hTST}sJ!%M!76%pju84_Pd_P}VwKU<g7Ll=EX$hY4;* ztpfuUDp3XG!>&H*M|$g8g-U1WwRirMmrTenG6#}}-oYBDwO}pPN};bv&w(r(pdPt< z69ra#&g2(WHJpb&(+4_P5}f8r%uW1x#^i5BZ&3Y(MCYuqx4-jd{ac$o<xMFYQosr# zra##$_vr(2$Y(8;OXO#Dn%Bt2a?uMHA&+2xmDKzanin*+&%p#w2>nIzQ-jDj<%q_C z%TtM8<x^t0=Jjl~`(EY*qB`At{EAd$8&%cxw4wKb=O__Kd@UdAn)v&BuJ=leU5GlG zTz3C@URir!vm!2i2j`X5^Z<MpCa~eIG>|Y~g!_n8a~;o9*!V9hb9?bK(8|$${(q@D z4+jep-l#n-VQi2u9=Xp!SoX9fbG4prq}E=Xy4?@kbx)>ctB3uSPdfI{`jM3Urr_rh zkHfgd{rYb7x*h(7#I-q<g3KZFh-1}%8<q41dM}yx73XOmX4$ZhR_+KRM=5<!NWQ7v z>MO~4$tKt<dclAym}TyS#UZZ;$Vts}a{?E?nQD?fM5Fg5%#u|u6A1&FZc70sN;D|| ztw#3b$4G{II&b#_fR|csygv(*vfVEXC8w^QjqSrcpFOirC#t+3jL|H;l4D3{76Vvo zm!!i%wlM3Wk>BYDg1*6YUawtAZHCbN<`S};&)-$pIdp{3DJamll1YliHV!ifO`D73 z8`><<Ju{E2<BjiQKyQ`x*G(B!iyxUk^D&-F-mdjw#XQ$T?Z{#y&Dl-tNeAd7@1T|p z&yI=cZD&E_yC!@N8~euqJ%>(*c=@`HANC=>IIF#$Av6kFFHKnA-Mt6W@#CvU@xdyp zme4!Lt|ub)+o;r;+=FYR#Sn3H%Yyn7W~}?iRb;$?t5qNvG#onXaWc|jQR2O|r{~_1 zB=UmFmPtc4aSk~-PIR%m%{TOFkbSf)x~Bx1G7+p`7#n?_uJ61ro$)GffkY#hwiYEz zV*Ovb^7h7bs>U<`Sg~&9ZbuxoyC0JA>w%pfllRT?#cLJjq)VYs?$JA!uBm<kJ(<ih zy=OgbVa?H8ug^+?i|>4K7vZ1lCB<dVOGL8f*RaR0nCyCNquafSoLN(*v!pWFxL8OE z>5I~V0EL4K=%jC^V*s*)fw*BVGl(J|^o#7n$UNR6i!o%n@0ndujpC;2cGmAu2Bj%k zc#T}q2o~wp4BDSgHJ^ylSN;+RFNUquLxm_g03$hi*1@b{&x;lbH$Zaookh6YaWnQ_ zfRw0jf%0S+9SBmW@poDel7D4qC3aVS2mw}5Tqwx5?y1T}96HmEB|W9elK?`k{t3mh z;Qs$efHE)nXL>j7S80)z-id<PhATd?*~;I1-YJ!YLd;@3w0`cZm_GdWDGmxclCWWF zox=X>ikxJ5c9iQRxufa_{I8Tty~4;`7fSzgnM2}lN?)2&zvfPKkyJ8X3>c&ZZsMr+ zvnmfIfO|Z+mn-VNZcr3P&K(6@#>ml$sGuAJugpEWy1<7hT1<V|%V1O_%#vBYH*|LI zn}O`F@=ky_Te;!*?m&4dA@FKH|DZ+EzZiTCRtE2S;_bC0l03RVIV4{K$ggC+U}1nz z)VIo<m)~+$42+@jtnbz+u!oJ-734cR93&&>?iSrK3t1qRC}bc@td*fW4}t|-YTfV6 zJPF#MRAr&o9Fq6*3926>V>%pO-6GW)qCn-Kx*nk{swe{zfU_&=#!eKGh}t`aqGtyZ zz8pUQ4$8v7RsabQ3g}!bID{)S1Z_$_lK|oY$u0C;JgFjJr0}bSr9Um{qd;NRjsIoq zgQ$}397gXLI4raCP%v8=P7(fK`9-pGV273A2;o1=IWo_L0{25n>&}vPS#Y*MIW8;v zQs#N4+yelB&BKae?n?V}zkb2B4ws}O>~y1R<a=ZcW>o61GU#>PZrlG+bm!qv_3t0R z&#VSBW5znxW|%bgu@9kP&|uWqmngdliBf5w%^3SwL&zRNNJV+dGWI2;k~XBi>QQNZ z)Kib&{QfzA&ULOi*ZG{!b${;r^^UiAqh=jVBsckx6hrPH5)gA|?|Ly{H6i)4MUWL< z?5giR7sPm3g<MUxdsuP6&+Me6Xr&vW^9yjJ4w!o9i7$?cL3FeF)wKBU;4F~&$G5qO zRv2(cUQz~TWmBfY)cQD0=fCd?%7?>*Cz&q`(GM}`cbFZ5cLp#^3?l8~E73M;ZSw;7 zNr0l2msSb-d01KGYvfXO+0kn0+jz7x{8Sw63M3!*7~+0XuU0OqJh`x30tFg-MFQ2b z!<)z<u59aPYbQdKqbU!CO&JjE3@MO?LUaf8FoUYm2wJ^31CzzfhI%2!pGrx1LOK%x z;EOkAp&&fqpHX}qUrDpTg#Kh)0Fx$GqG!|PUp&TyH>CM2qyb@iqyaOQwP4*B^KDsf zBLkE2U2c0;ZjvqATptG=aI07oAi}R)`0k1Tp`m+4t6|7P$>}jo7m}m)%S)H-c;c$` z*z!@B+z4PaMh=@NpT5nMNybPuh-#|J+%8)jtJ_(Avdop}zFiCbT=20wPLY!dFbnUB ztjjEATkse55KJtCoe;@&;yah=ZrDAx7{)uBtPX?^JoMFGL^{Uwax?5a07O$89vm*d zj;VYYggLl`4F(_qH%-G%dd37}LOKpcTb+!P2HyQpct@!^qPF9sK;ft>=5N(JR+HeD zC1!QrsMfNHe`ik;A}RESN`_2e$N=heckJKYDxla??^Hw=SFXr?N%dZ-{_jTe4p*Gl zihV=BRB}IJn2lP(qpy57R}{)`e#=lnT<diA-kD#k^jUU7gnSHKzR#5ZVwN?SDSxMk z(kGA~3&wyU=Y|f~BVM<nI#c)nBC{Xv1W2DC!xn?L;a`?30)ABl>Pa13YM6)SKvx=O zp^yV2c$D5jSaONpO8b%6>q-MLkU5vJuMH=IvEOI)l@+ZaXETh$ubhSN1xuk1`k>W% z@z4O*eRb6*rFt<|=+{j2yJ|y~W}%W7N<tgwTewM=qKb-I`d3lKDpI4hT|NZVqiURH zu)VQ2*3{sJxkv4_C#uFZvQL&}-xbI<4IH3GcsT8jQp_hhO5mKICbu~@_sir5w|LO} z`cVYH2LR4;Jw2(-v%BrVyPG}z3K8+QPM<xZ<^zvv@l*N?dxc2c_+AP1$~_Wr`}seT zF-(v|?c5?CJtGUG?3DW}NipScaQkKX{{?KHN=!-3hOypNqjL6&6c6Zszmy6{?Nuy6 zXUEA+aP9MAsn4p>uc=lrMWr<C9X&3xAl5PuCsm$=)H6VXL+nX}yVKOW%|Ulf{V{71 znbzm52m4XYROHo_y9lo=F7GT9RMZnx<a$8f)*VxtL@V>b=27csU~Pze+PI=EzXNe_ z6Mnu!>O^&$HwKXK>mWSxOW3*Z{pgci`Osc?cr)ZwEnI_#dDhgvGyh;;WFlk$dSLOS zE)%ms!EA6aUu6LV1{jOK>VQSJ108$3I`-FHl3PV(1*rU?Fo9q!_O3nrYI1XVFO-he z{el|e;$s!=c+Dj*N)8+vw^0q`ma`bC+W?>{gW8Wp>E6mfLRD|<9x4pKd%alxMBR;t zNysMbWugV8I|vgmBsx5bztcR1_$=<X)~$#ni}1q{t9{f|$ttA_$*(v;MVv^2f5AY( z{pbh`kR;)y$XG5@YWcveuro(&F;Y>?dxvZ=>vwQxLK4qyc)lkFuo)OG65xkm1a=sm z*9yO6fd@B`H>iczWSV@vn&2CG?6;THtSxf?y`pZ^oSrGK>a^zt8LfDXow0s&XMWcl z8TDy4$k;Ptmp0n}H9WgR>U_2I%UQ|e(b;(w=jpg$_;m8Voi{YUwmIcShYO}Q8GQ{n zTRV5RvuWyU&31e`jpur@D3~j4$+sy@O30x;j(&m23zPO{U>=;nxJ~$`i4bYCQW>+7 z-$k5glR91b1d<Hjz)LM+<mNDdbU&I6z@j!oNptYyO!#g#^nn*?a&H=R<wTfuqBk)6 zY5)p(VHX`c8ysZ^<6MW<T!-NSnSKSi>8hWT=o{=EpMP3i`4O~}a7x7ut9VxhYld24 zDqp-M!u;+@w;muG?Uf3VS4v2qED-XOt?F9CpU=u@*hG9;GcV&K@wHvu)UE^l@B+Nd z5SzXTp#ES{r9bzX{ySL&DrDry8}39t5Xn66N8Mev?i^F=dxUY3Y()>Z_6wrQ`lXAh z+cL%EofUX;C0VAiLx=h0%tfkH3KbrI4Iack7=VYZ?}UZ0J)@a$bfQc%u$m&0IT0o^ zZu1wr8vb@xZY~M7u?zu;q~Ef4KaLKiiLerSH-+gL4ZZ%-7y8AtiUb<lF^f61dkGRg zCWQe;?vDLgt|Am0-9T}&9K&CR?JdsQ-(#Po9m<y4=npxbI`G%w<+^0GM*-T|@?QDq zd;Q4&^!AsF^<e{dm;|F$VDfUaBpgC|IVU)?rr_;gisl|zQ<WWetC7Qi?29C%5e&KI ziLpB!zc*W^uuA;f9wYITU6o~Am2C<)&q%kw4oZSIZ%TcX=)vswjW5w7<ZV>uEMn-h zO)k)uAwo#ML|@H)|2O-62Ot}|2@RNC2@jK7#lyn!s2&WU$6QS6C_eLrzgtupySYnf zmZq3I`uZ{E<(#quQ$JxO_tb&0IF(s|d3D1r;2SxsyF36^WAxj0ziN*B%P_S!{pkm1 z-uQLSrL&$J=hI){_Ym7Go66r#o5_@pUQeWVn68HFUqhby2#>}{OU&7#ZtYA{Z}Yxj z<EJk#&%M0H53?0a-C15YqF@H&E+aTjg%0oRizxt;sQ<}bdY>k~>ix$KnTMN*JhF6U zhjiI2qGI!FY~|OyWrWR9OxM1@-Oe!1S4-uI5bf={+)Y|zn8`ojZQ0WzDW9hRh>D)C zhI^~rQ<;Oi0v~3(;YViqP_GZS6%@n2w<~$&LQ(sm`H;0aNSv;n6bdkge3Wgw4pb}r zke##poSC=Lvio&S1>dM#Ibw4kHnlz<_PlCm&Zlh4z1V-ZE|})y4zu@k_Ig#;ltIHB z2lNe{f_1x4tFxODp*ayS&BVyuWg{0cnX|LVVvytCFEKyH;(BC|lVPYvJle0VQ0cSr zVAhwrC0~kW9+45ec0S@*^=r#lGNqeeYdXF-+~4^Z0aIB0HO><=?XUYF7_0k|7FR2^ z@QfxQpH&D_KFg??4%By%>|Q)f?%tyJRe02WSeT5Yvb^1Dqr(hS;{jsP&o4VyhWOs? z2tIgD+gaNM`F1&Vu5MUfWmg~rSnhY@NP&CgOFzB#DAfvGeYPv7ff^1jR!z_)ms1bV zL;Y_Ejh+oBEZx%lQ@Zat<?J&c;olz}@BM&RO^KB<pPxNx1vezNWp-CwPy7*arq#9m zvgJ{7vtz~C<d6HW%vO6{6L?<kiTvw1@`v_bjDi1XhhJf%O26sYXp!a((njDu;Q+vb zcX+6FMtwc`4h&~p8V%|}&XnI&20Q|qnE9C>GK&p73cs~-UeAQ?P8Dh2Jo8;fscHWe zXiQg>o{z3@dIyLNU7q{4H&@<v-WY?`=5ghvp}yO6QUBL7-!LscQtW?ifEmNuQ^*+= z+my#`JW117mZoS{$AN;38^T*6&4#MeG>)}tb1GQ18R;eDbz!;?z)LEc>mVr&==%Xn z<;QC82rzHkcK~lJ>4VFYkj!0|f-an9U5%F9x*D(vrjl?l_c*;~yna_je503#e(ODu zR7FRJJ4r*gtfHm$W;ckccXYu`w=zYjKd;k>9DK_-(&!bdUVE@SOO3+mn%u>y&d^o+ ztNL(b8LMgTZBvMQcvJ^vl|7WdP}JP07FT;%cP~Iz5O(G9u`!oI7u?>cCX$D{RTco& zboHw1`Ss!_&|}el0SC)qMf-k<bX2!rEd@o(AB=HqQ1Yg5PAC8loR10&AZaF$quVL2 z-mBf)WXrjuz`}ll+C0#<$IlPh18>={v(4%;v|L+gGY?G&qwg&KQ(C%;e7Veu%z^EZ zry;X?FeF(Xu@(XBI_T|$M}lTWb^5cop<MlzQo>leRnIzz<IO<q<OPbZ?hx+2CDimz z0zJaJ|GhT1m$!5-c`RYXqRH^=Ih$RTJ*|UX<NTzNdCMb3OI;fA3qKp*l#FtlrqXA- zN2=~ThXOObT(JCD`h`0RY`gEz6@ciXpcs?GqR($H`Ma+S$ynb?jm&X5IKERQy1qs* zItrB$m<x}AT~*^-^%`;8j3ehrmo72Cuj_gx6Lu=tuVF~4sak|ITm(Rc0sF}R+zen+ zo{EnHWKLobul#t)orf@6$$_L{Ff`wJYPT3qZMP&nd)8a2<6xt<hnKCLx*RTJm3gTy z$M?TQlWc>rWfWj3^Cb|kM`|I33E@AQg!oL>Vy>y$h152ALcx|xHp=PruiSr3>6=;m ztb}pqdj>}&PK@gk{%kgOmu4wF<Gk{mx8-~?I&!g2&GmQ?138v+xQ}KG=BQb&t0-Kv zdFz#T1`$<FK*jnFso!R~k}Sdz*2Hk~@g^EE#?hwzU9@V^ct#A{wETFhw(9%!G~)}O zWd{ewk}!^swhhlXW-@^Y^gYuN{d1Co;%=@|MYT3Sca$;Uf^EisLOTGUb<U9yJP!s^ z(Vd9L(`bO*|M=|l(zYeZq8UvA%cqk0Mor<=**co~(sGZ@EJ*pnVjfnU1h;Gj5ws2q z?*Ys7QYMM8WPo$#ig@^Mc;#D7oS_jF?I)#F{Qnfj==)Ogl~BxLlcyPu8aM9czR8PL z{yegK<a6=0jf7$oFZW4cGuN+TNNa4-74pOzB^jSqeE?KbKVHHV+oSe*%gQ(#3oV5d zxVP<+&wl#j>`G@y*$}RVbZiLW(6ot4UVJRE$*iNPk%H&sVH?{98T_i#6}a?j9I(xn z^$Chn9%jM}v}&Yu)p*CQ<KfEJw`L7uys{2FcUCd+ZhgC^D}U7^w7VLX?_#)$$!(&k zja9o^={nmdK%I9WBo*3|E7Eic5BjA^%IX^k4dagWJ;tXyl+^6$WDhHfs|7Ajt!L!& z*MfU?i7<X3DV>NNday5SpJ3woyHQsRd=-#xpX>M8bKNdiWhj;y!OBC+U2TA-;%m%d zov0dv5T01~Xtt#Da<eR6bgL<a5g9YngQydFJI48&6FRcTANPzGMke^EO0pN9I8d^~ ziw4!pXQ2d*0iiXKAboCgknl~?<<t+>viS8Z%2)xp|ARK6&de{~)djijx2~;tp1s$s zAUr49yFCCqTuar?w3+$Ya@=<+<ZZuDni1t2RJcgmiyFL>ckJr!rPIzk7W&~5TNitt zPA6bK&;OVuAfrmTn|#bmhmLSLfP~q<vfRU;^1x?8sTclRP7f5X%7shz*Hir%AjJ_G zn#2^9-zh=A2|MR|o{kDR?tsD(ufe^jU`&|2@=kGSNU^k)QCGIccd@DT;oye=waENU z9^+pR1m#W*`WUND-xuT&kS#FJJ3`a5k1z9Kgy+Rporrcmovv3Q@5#F7R-WN0WGY_9 z-03x&1ix#vHkx+_63ll=dQ{28x=Z2Doo+PDIuqV5XYC2xCUhT;glfM}64Fz+$IkwD zxxo;IeAE%4%pFN1!NXCnbR!if*Wh}-$u461wPXGk?bIIDTsn0xe!9%~gtZJi*A^VS z0A}liokBPv!F|QEd<<p<@lC!K8O`Eh3X=8`lU8JtQ)z@Kze5u1?><HnsRpn`5tmox zI>u;PnZMd$r$7Mu81cR__b;gfbo`Qs&=o2l4lLuPR5~|<$-gm~JL`vbSY<dmXzT!b z_+pd%y;KFTo=IUbSH;ULXNPv=ZxFy3NliCK8JDzo<gp^hT`e~{WfJRop58W@hDHZJ z|3bllm#LH1^8=TPu&@c``Y*J0jr;u6hn?I1R4JD3rZnHlXW)8C0<y&TNG85kjx$cH zIaMd+BI!@m`^HsYtd@SLzltpcV5U`$z5dy?n&adVi=G;^UzDb4D+Xa8La>>9@CF#W z`+vxS3QzWD8{CVO#AD`?xr+!}fW<%2{uQx8l`Iuc{?&GM6yDE^kXZ=@r5@Jr8`wX9 zJeoSB^@EDo`4KHr!QRryu*dM7KZ)YEhIUkFX1&jFd@{dJcoT%jA{^HSROV(~NXYzS z7m39G?W5n>G58Uqz6RUc8twBy0>^**ScWTI`xQ|emB-S%7zd*cRo2!6EnSzKzcf(q zL?Lg#G`Z;7+cSJQ@3+duNVOMR+kz~W?-7NUo|iun``mldmF<7Wj&P~@z__-OUii8b zPRvfTo%w7X!D<^v2)s!W6cZZc2BFOIC}9xEn2uHl*GQ5QOM$tG_|EGP$7S>i4h^ti z7^EXsaUiq|B`hapy5IE_w(nc#dnFC1Xuu?sclUYCHk7I>U=xFmIwBQ}4ZA*&1#w7) zI4ts9G0-0@xl{#&a;Dr%RjVrQAfIgIV$0)pIB~Wrw<mak2#9SdS8ttbyv)r=Lg``< zM<76=0^;bux1Q+SmQ@fUc^Q~VdkzA)`1P;!F|&@$-qjlj6<X$+IYPTEQ_5Wypu$OI zw>wK6Y7aZmw~<njOsOQYjK{{ktlfn-f{V<t>3*qFhuLO%O^vd58ar3b0#-B59q1(& z-oHdr4F|4yj2HQ?3y${}MIzvXAkw4i-c#D}KX;KHH89sEstF|xoFd`LG-1!0Z5F{s zVRj~)V1uR+V(EzWCU_)^XS6)x%Hq=ydz}$`k98|MQuq=-z$kFkdePCO2V{WJGGOl| zEOO14!Ny_SUF%>YCT{?Tq=i8roT((%Lw<}Y|G-0qfleHpRn~GdM>qx@camuCW*CI+ zW?$eYWX~9vOr#ki+yK(hCHj!%0*zB@Z)1UY_7$<4C|A@cydX?}JeGEFohD4$qrClW zya-!RitB2pOYQ4SFIP3SXJmrir4s4YaUGP8g$-Ay1m+<2zs(cFl6(d{1&_7)rtacn z*E=#lt}-s|-g*Du$@?)>3l>l@m#WTLhcQp9hmOG>F>_jV1b+0iC;*+fE(lJtjSx+S zm3o|)FY->}4cRfoAq-dQ)f2(HtV9sAElsngsfh$pT>)e|o5xy%SmTN={@&{l2BmFw zKM&Ikgs?BUOKP~&kBHFcSj0d5nu(_o;2M)G(k-Dc#(YbY)33rKw`B8SyT>4V0Ja`} zJilIx*I$)I8PCGpPF4`A0Xv^C-GEXWK)(&AVtI=#N&lw5%yQ#xi*CE|cJTUd=dny3 z4Kw*n8SQshQnnPbW#!-S#Q5YMuhO#NB=@Te&Vao_eq?saChSmZx(mq0i=S~V$Z*8n z#_t?LQC9xnNoj^ny4NCs@wp}h&*<S#J{?TEJH?D-OP#>LyvA%f)MCH<oXOq_e~gf{ zRP0Y0*eA+SPDs<JL_NjB6f6ePmueZT0WUURax|pIckK6}FS_xQ?XG`4qxU4i^T||6 zLUP{Hxje&Sh=5P$kuZ@S!ul@6xgc_0g=L^HO@E8mpysB>^2wvq^42kOoR)WdecZrI zUPo#A*k2G58$y!5h<}hev>%}E=P)1qJT0Uq>@VF8D?HQ%*HkFTG!XOqDU1dO&rnKj zjVbnwAhGnpn`iev$}&N1?wlk+zdrm3q6V|-UR%8*wxj&pH8rDWX07kc{1aR%$&;fU z$h^%Pp%}R5ir_diZ4O}foV$!yQ^meWi^WNzTZ|LO?r>Lay*q_|riiB<8b?3OJza-- zW1c97>|W1o&(7q#1wP5)O0IYIvIbIf0`6v&I4AL+oYr(k=#d({Ie~eL7Q!F6K;iOy z9(#;ze=CpG0iEO;V1_J?+%nv}#827>u(;;kLU%L7j!h5+DZjC>FOQyoi6LCo_T{Xn z7l7bGrf-+o@cHA79)H~WyweYtJ}BF^l;8Klx9UZZ+GY1-T-vF?%&ho(+w~KGUzy8k zsY6>klGn?`wd%?Jf~#%8MxQfSctfokwZ1Vmzm3LG_XhzLd-gm>a&V6$=xNCmcqr@H zEf^3p47;qM%J`gyya`Wi^7o^rwV4YqQ!D5SLX|)MK+jyVeMoYH_8Yn|!m)&(RC40x z-M>ketg^e0^>ogAjwbu+97(RTT`b|WO&k94&Z0;@mh`lo3=_<d;TYJA;j<F~F_d`4 zC|ttXeEjBO-uZly=F=><4E`2bcU|fX{=r4j?eYy+NioxR%B<s?FcwTH?S~)5-9NV8 z@XPtBOK1AwR6)4*(!Lzi=4~jmKDwxC4xWI?jIZW-BgVYfc@AUH=uRk=4*j{>I%2`E zQioSpFMWGd-nX1@^zcy?#-oz->`()8jNN<J=71lo%k4SLPgE3r!ULF13*ChIuq(m< zxRR0*=EpN%?DIuBLhJk7>M^g$UhQKapiG1^576O+?dGsc-qSTV%n;{3pf70d1(u&@ zRZkxQg&KMy1SvTg4Bna3Lb%Rf(AQwYQiS0q&kg|r*HtaNZh61(*CJ2)+8ODBM=d}q za1sE{iL8s(O5Oh6Rq_z4@Na(UcY}A|5lN{6iS$}!x)jL8VdbTE$ri#gUw)Ehe%pQM zNDpi#f@jW#jBKlCiw)CU67Eg8yAB(|wC#viIKF~BEQ+m=T$**gQwWA1;4Ml^p7RvR zgV%pKlmd6YD=05C>UrVv2!lYrO+!^lMfs&YN-EAmJa<zFQM`aijt=)`E3L7^Ih)#V zNtKU!+tbI4&A>n$NDk;IDaEbMrsZWNjb+g>^>O)U4r2sqLdkNSn+@A71RGWhcXb2; zqK7w2^>KPvghAt%Hp!Rz_5e8FFJghH`HlL|As2fG^Rh@GMd2zgEym2<ap4NyCNrr+ zkcdyGTFKBgUVUy8R7p!EU|^mih?Mh`_hyf#yHrw=Owug;*J1bE|FWvemgK<fs1%69 z_9B?F4w>;rQaFNkFPqTw`IDQE{5~QdEblpi5xj9(I4FAdXYvjDJi_sYa24_VQh#lj z@!O2x=WkNcqc1F&XR#kdC2<F34Pe0c#kc9?#hdpKFQRsk8msgGHkmYIJ{2LX(Ld9; z@9%Gjv-{kDYI~rRU1A|DU|EZmg>nyh=SeS175A@xMVOqO^#iw_!c%xX!9{-@zTFfU zl})f|OGZ!O$8Z8BNlV-Z%e_#LfRO?^;82uHdr>3hLb+1m<;LH#$s|F!ag_rL8nV7N zvR?j;zo$JJRr?YdRyurK5^Eq@4g<8U9`A|3L&pXbIT)7zX7m$8O!}%9Z#$_eSxLB$ zo-0X}5T?FO$Nw$T*AaGT7RxUlag0~CT?{*mSU8arXD&RM7z;EZ^xL_1Y;NXQU>>Q| z>Ni4Tef8#gXbCYx?ix)P#<|chRb+P%5J_F=Qh$5mwNJ<cs`EX&D1`=wY{VcuUAOat zIX;F2pBrHXoiRN^N{>UpY;ee9^D<W9Ma%_3JRKj4AQ+rgt0Eo?Xwg*-77SMl%)JC5 zTcgq0{LnGM$g-No)5do}i4Q4)SHbX*#k2wbfe;ER1R;oE^Ixr}MbL9LKHdq!)#7`# zH<g7d#>R%=w9H?^kw3ybuCUWsXA^((ooeW$PAHF}Ws;`lvVAC!$FApZe&UCLb;lqA z0$I0IlwMt5no29(iU*Q52O3L1GK2+Gc7c-Vm-_Vc<n+nIDCS&tLGn{>)ro%?<@|%$ zDa$a0{mH^{8o{RU$fomE7NxGZGp;`}nxyDTf*m1CC9J1eV`m#+k4_~Cn0+VV!{v4Z zy1zONb)N_xP#7Z*A-)trTvE|E{h!?NjNcE_;x}Qa;Y3c7M<_+WSoH8G2|||d1dqUm zILGh5@D~a#Z1z0eba-yUMR>|q+8-)$V@rRiE_rNf=@qHTW9n?()BJgBn!ov0VDasb zH}AKraOaGQ5I=4p;y$(i%evv)_ASJ^h4A@zA#D495m}ol%su&D=|Z1Z8>xRwu>vE} zCefXiHu2oXUqRV*rUfDQ;XrV8_E-BRvEXQ!;CS^!dSKD@F_^<L&l?9n-v8R4PM`^8 z?}Z^_*RMp-)A0eVu79wHd&=8FO?}V3_Rm(2h=Yev7{pZGzS6X6mS8PcdTRE5qQu0e z_>)yM&KHEel5cHQSmy&<=^b%?9K;UPCq6T`+h^-dhcJD=(BXQx=HnHcWv+1(&v|Ss zd%s@JKZv|fTM$#BCFV4z<Ig*<)5X>ZH#vxV9!y7+vi^MW=)+JuOJTW+P$gB`%M3AK zC9M49vz&&YeE;iWwbb~IU$xt`(hqL2+vV<?|6V&}2D9@w+dR;~SP-zn;5S82|JBot zzzrUdpdO2GNuJwL37;yI`Xe!rn{?Zjc1Ny?-8>L%HMRh)?s^=D1-dikKo)m<rou;J zCW>s-OFk$YTPH3;^&1)GX278FV74@p-5xo<tU2j&W5pz-<z$XWwC4+Bzuq&`nbP>? z`Sf;X?-^m{!a}o(qh(r#G`pcyMbic<3m68uIQ<aM&9USp+1Qt7dP$@4m+u^T+%$eo z*HglyY7}5~773RmQ8XbOX;@~FfLTiBL|=8s?UXYzK&`&kMmL!Bm8bU9)W9VNkXo$L zU$tzhFYi~*8XVBO+XN)(ZTsEA_IJIQB{>z|+N?=Re`KsR3a9qc5~e^223ww|t=>F{ zjg%4{Ir}~C$GJ+6fDb)GM<;Nfd*4i7wh$oy>Qp^xkZT<!+f2CDI1^}_JX4YXzn2G; zlh^#rrB2pQnNCo7NV5j<N}77zn)dWjV^C7IWV;kO!E^!nAc5YdT3Ks8u`XALS`o-5 zcJ;1K7?5jLnSQ=rZ!n}lz2fl$p`HaVXt|{g<9bft<`DQqkT!zBj#9crJAN9L9-8`Y z_>$TM8;Rq2=$vCIEuHX#83|D5L<)cfC`j?-B6e6FrMdDb=JM(9LH;!$>L9HlG$ojE zZNRr51o}45ba2{^P|2nBtV5|}xp$A5M-?rdQC73eArWoZ(&8oULFny}re`VUGbyOz ziKc+(CvH#MJgl$FIk|S&XF|E5^-1&bq0`4b^bR(qGp;W97EW8d2zl}@iR`&Bn+DS_ z#=0VcpNY%{6@7AewVNw0JIb57+q_LYmqf-B*@aV<;&u7!#=XnOJPoXsZmbG>rdC%C z8N*TP0C-P>VlJ@I^xEaJSlp3k3R9IPI_ZNmlzl?_qz>?@sy?IWcPmUyRL*lzk&pgO z_`%eMfdI9O)2@wW=mzQja+KrSy;`g_5EXl4MNeJ!VE!hD#&#gCyC5(vzT@o^kMqpx z4PnjRceg)07FmpTcu#k`XUO<mt0^(hv3<pg)LiHq$V8ob*jMODdrGg%u|CkZGHq2g z$Y*r?{UXA^@<T&pw(TRz@zxu1E|3=5p*@LsE;%}M%4`fdMAtal=g2S>d7PQMbFaR3 zpYfOZYm>&0iC?E|Zs3L$`)^1a77uuy2LnT<;a!jXQ9<)cb(wbEV+5mrYUqR`<3B9M z<)$5@X~*5<01ecOv^NLY1H=(pxRq}pBVgeiRskRl@HJDNu`ZPk){lk`SW+yy16&JB ziotT0=e^=6zhCc&pLE{?hqD8ENZv)q>5s*oGKZ3QY8BcK5=tMo#IYlT);g+B+EV(n z`nUDfU%QQ3HipYZ2}Npa%whG^H#sbpdjik|w_2iUi8aNzPh0yfw_G(?q0p3)CB!Y= ztCw5#)^$+hDi_=b5Hp@m8Dt5Yc{03qPs(eJJ>$bBzF1^p{b14^@`QK6{PhM(l(IS3 z?L+yox>9Bv;R@jLu}|A>IoieWkSdIz!4V2H2C-*;FORQ*3#|Ykf9aWrnnR$jcwr-k zLc1dWMI>b>9z^Uh82ndF9-2O8vj6*8gseAED2M+*kQ;N~4t!mHp3<e~d!UXsuT=Pg z66ybNd4yU-kWCOmc8}LABX1JWhlKz0gCJL~Bg}H*i8s_<g^85~URSd0_WEwy6Lo?5 zd~^hENNbv2A=jxR7H9}{-YqBtirq+9X#LK?K#>_g&Dwn<LRI@r206yNFe<wa*9*Az zC3zta5{J}&p7E*;Oi@qobIOtG6J|#gbO<EmdU79Kvv`oqfPNyJN}v+~=6tCk7gG>6 zgn2nz;zHEM0vLXw+85J?^?}nzn_s$M-iba)!sGx7?NZ-uD>qxHnJYlm+5p(3-x~y% zt*F^BF65Ub^xDzSh1cX~-P0AT0WiyT&pOtlG(qPS)-TMz^-cDvz(~bU)DhE>@SIqd zj`o{#%Ewr^mN-d2W*w#Gxkgvz&9n~NN69nSZxM21zwO1pq;7j$A5m^mjd|}gpCq6} z4dmQ*)(KY07_rG%%pbpLe)H(*art7x4u=E|>h@;EzSW(9K7IR?hVcS@KDNkka3&6Y zelBY^H9uf>o&dW%?FyQm%i0>-d;jdD8;ES0ZU~l7m<1=SkP%M!)x3jq5WKB&SC-;D zVb^Ot#;paBt1UF<DE7*fmiIk@-O9P+gAB!%uyi};M+BcVH#ysfqHDI!*Hk*M(0U}z z05QYY4odfbR6gMkK$$qZGo+Ix1ayQ3RK15iN)hHiX-rbk)lp2>o96^IC@Sk_*e5V> z{~9Emi&T5KIFfp6p!XnWn()SOUovB^Akj9FT0cGGx}Cd$Ngau*YDK||zgo&WNK}Fb z44hX{gFe-JTy-=lEHk$z69bFX-EJwT#X>u*=GV1VTo!5N&pHJ3Q}sHPo+qF7!}qN_ z$_l~`5{z3Ff80_5sBh+7vi0k~IEH)vYIrE0%XItUw}Nma4YDKU-2q%69i2O_A6W}X zpN&QdPSW?Rax(e7B!j&({??ToWO9g(>eqgO`Br9ycf;1@sie=z-gdXW!beA}+6AVb z;d%W2bnFIh<X~E>Vj2@d{TI6zRj8pbCjHs_iQ1}b*W;N;7D>0z=^s-yDO9_pFQ|KQ zNLiWPNlsaTT@djm>hUn+jcjyd6HSLXw=LcB4g6wo(WNy%KICeL>29^+NZQFum3X~j z?342d;wm0WV>u$qSstD{yuWNr5&n9(dyRH$?d3f?BDt&iy0`WRzLll3^d|!+Tnk&k z7<y0$JxOm;O`8w|Qi}m*Iqk<ke(CjZVc!<_Cd{a*A72c5?D*T$ygC_kVnbB%;v53C z{W{)XZ&dXiyE>JWT6st>jc4g^W#!uR`V<qQaWsr?E#TzDS-%NHC&OC+5qi!HEu4?b z>@_N0Dj_C2zDq>JUv|ui*_>25K^amL&%({3B#B?^VnZDEi{2~;CoxrZ)l5-)W;yB= zEU3m~DqOEV9390RQhDEz(Y(Fpgd13X(!Xq|^!im|xaqh!C7k;?`{-{1Z=Hu(#Ai4F z{YL4V6Q1F<U(%VMw4WRoPP~+TRVq6&r&9BYCeLd$uNjx7|An}E%9XFPwOj}^#nBu- zs1kOD&f7pA+VJ^G{RxQKw6Y-=jbVnEUuZ8*qtJN57fED(65yks?eqdvwc<FtyCXAs zjOpJk6FDb3lry@UIOHg4FZ+P1LmWIiCCYu8Y0j2e1yNZpGe$-<Y+K<iit1W89qrB| ze*+UY)m6?ps!_Q+8C(MmgoTEXJmq6q;gnE0XvVBDlX!&{G*iTtK~35o4i`TF(x4Bh zE@){`opRO(w@rvH9~Q=rjgN?JREG72{h#M=+P!jd-of}bM*{kPC^-=lu8h}c02Pcg zolmy%ue8{U4`KX#*m>R|px*<B>Mg|=Z1~X&JJf!MVAuK|jLB7Py>ej{S6RRUhQ&~e z;b!|6E~(F?%KR)X4nYLy2I?|8ZhFz)`6|)bc5~3KAHt4OW(a8pOkSJl1u`us`t)!r zJ@Uo(#V)9i-kRt6lrV;2?qfQS!lIc~Kvqdmbi`hB;WIh!32uFfz>sHQK_eSFX|lC6 zDBL^^x}4RJY5h|Z$$038L7P@?dofocxZ+dBm`z-LJMsPBlg7{?6KA5t0V8S*Y9w*C z6+=L(Qy~B4K@-XP9kNg{EdQ0GNVjp`{8qDL(3z1DpsmPdfC|QYU3}ISPM2kCw_Fkx zy*k*h5tiz<b3*X%Ty}Y@o5GsLpLZ1xo^nXapsLMR9D8T|88{!rHqeI|o^gruy;P$) zw2Puq|80=5=xtZyvkDq@-kOa$3^6?y)H%(xHXgOXK`04z&0z|W&4Hb6brxW@Ij#_W zT9TmT_{t`7G1bNT<iy40a=kv9#bOwG5ZZII_-0e&?g1YULt$DE7vBw190L)T!M3%L z##YW`CSlJbXX|>fbqMV!Dr-moprsH&>r(m*VmPmW$-lvWode_79hE7ZZMCrhB86BP zR8$%LVwYXOupVrO6^w{1(7_CfzhMDGZffOo#sG95n5vl?TZ|9(VM*6nrfmVh8C$5= z(j{H(Xz%$$w2*nMuOns+@EdlXvxM==3M66T|Aja=m#G1*u7+T0=`3$gg&#=i$&uxV zpb==>u-I^Qi7AAHXuX!O(7C2!D~r)3Ci767B(z0hZYmpzLD$8lozo*R4MXPqhi?$0 zHbz=<6RvAs&K6Lfj&MK?0oMPve3Yrm_kLOQ!RcQAAO#oh6~Z&A7}R4q;t>#2yNSA~ z++>$DgDEGIZ(!p-Fuot8LUGijjNk78>#-Ew^pSfluWr-U2`A}SQzBG|8yq#_H~|A@ zWL%<&p1Y*%sLQ_Uy*B(4L=8LVMr%6c!-}HyUzsL8(yiTJf6SZa%Xv`4AuYxFtj99Q zfwWC&ARB&?QW<CA0xSUb#O0uIUgbMJ<dz>aVwBo1c?)DL6Cl=hyyrrisiDqN=;H*I z&!PXAj!87hth;V0#B8B5A)yY{IHcb{eUUok{2QL*FB^B$=W$=5pkGI?m7|ClG$he1 zN@epO&tv@a^@&8U-+VHerf&za?g2@#Hxgo~_}Jo*R}t+S*LVuNYYL=c$ic0H^yrF` zBWPDb0&RnS*#YXFS)|~4btKeTbCbF)k95?CdZi8Y@6cRjJX)ir?n;e;?YD{WDY{aN zYB?ktP=yNWcDC%)ABoU-^E1^&$r(h-j6n0{(dX2-17g_}ea7!yz`1@_;2YY;ei|h- zP8<Qk_k&k?X~PA<ZCGOm@mjO8t6`PRAm3>!BE)^jiY*1;hwQp(){C_3rZOR!q=?)P z7m9`~6FAnwFdzO0lmA9{FDpAyXsl2~^cVasabd3}FUb(hN*q4A`7o{*8vh2YqQ-N` z!QPfYrcj>oMxA<~W60Lub&4wYtoTFWMcJ4`gd~vU)yAJ2G<0@3ZmHr=G5l&d>^>+K zvt8T|b1~~2-3<=f*=bvQ`5k^xe6l?_Gz3cAw_2+d_e(Ert0T5->vEmbfP#hi?98}} z#=s9NXY?XS4dbY^MnzBM=}(NzfdIG#-#~`+&`Oh25a&;a7={MgP<?3~eu+sRZl7)w zCGb{SL#_KDruC3#+@_BIA}B39Yq4V|wax^tMgFmLfyukbz#r!1-aII~;t(W2rt63} zTFZk4y<%Kk+Z}tplI7ud)CpWNPmjS<eg`(j3=N(hK+^|}HAGp<Bjqc9XXBr!8C@z_ z1?wTesumy>1h?cMwA_|IY%d;48g>bE3Mg1`^V%4}I_*rjv`dmPNd<r2e1|*aoO;G( zBIDHoYVGz}*dwCD^?(rVy2kO}E6?Q@JL^x*lRh#Ua!r~lSAF$eWROQ_%MT718UfiY z2||~a3nD8r(n!;V_U<SLg9x7ZWa!T8QoLreSPWeL&{|NPycvB6TxT6hqa5D%N=Z3u z!u2ejX_dmW^rf*p@r`zTK6);Jgs?MqQq|y+MSt5xBjPP##i7n`KZ4`sA=X87&yJb9 zio+&be;YpM>Lzeh`ndOSm)2*%`Wpx%Y2>3GuyGVugX*Z<?WmjbRrB8Pr$DE#uso&9 zzO>&fl2|z+l#4-dB&u+}V({k}SgP%QO+|SfGZ`Jwn;J0tA4D|6BJL+$e#XXmm)oOl zlK%j%+7UfP-5#F5*j4-MUhVdjt3r{|qjr=7JtvRa6|k}T`nLf6<I@xQQR}Y7-5OB4 zewtbIs3~PAQ|91Rjr6Q`u=V0lJ9{YWyi6TY9OE}+k<GITp&9M1hFhl<YVzKA4$AjC zk~^UBWgX;Ln5hpIV22mz54~F-OziB?->Rdn4H~Wu8u7t<{s%Vg7)+i)ADebE=%MW< zDjM*ejtyh|`nU#xU=0n9Dg*4>abqa6C?TbxVvs*Fz`;|U2zV~xLhEO6zh{2J_=xjX z&;wfQ=luhh)J;<2cCh?A{-?3W`7(7xbC2_`<njkl&I9Z~%o_WF%s5`<!*+s(89?@o z(+F!`1zM_<?3cO08Hu#)a4GA9Ph9z|;cw?zIZMey`aPv94MWu5kIo~inir)^(P_7n zmiL?UsZBgR(U2aFYmIO=(Z6ZI5L<gosB#|E&v|F8OG>=B*9}4rTQg)18M{A~-orPA z40#y#yhl7v|INQs&NW^0Kd|G8$<(MK%c;KgDQya2+6qp)M$_*GoAxITdZYCF26y#? zlnpsrvo!&XfPk^%#IfTHz6ud1H~Q=Fj}yDb`uY0?pl5$B=-dj?8OW}&ve4M=T=$Z3 zxi8i~DcF}2p|k~{MJ9FRK-N~QPxtkIZN-u*Ps?c+yQx9L-kaOBo)#%{Q2_IV59M#! zQ~z8<NEyfmSqf<@i$j7&6!Y%rD&}BIDGeX!6Q$1=t%tQG`=|HO%<)4P?%SMX(ug7u zk<L@TGhqiiwCCqTQ@i7))HP$kMZa%ypYP%OWEWF1*YPEIa7`EJ081=yk|EffLDS#l zW|*|nh=xN2PT3k@#lEd;AhzOe=m+mk@j-r$0W2>TMnHbLQt~-A3wdVRHUHYu&kt#; zV=A>59+Xm2BKlvIKhK_CY7LOI2L(9BCcHm@{BZPcW~s_Q*IM2Wwa%5aoW5gcy*t`v zS!O(<rILCNvYOo#kl<gnJBFypv(oU83%Y%k#ao#g-6lg%yo_<_MvT53WYz8Yb>UE> z?RV>=At%iHIcnYN3_I(<QD@VzRJ<6ZljK2$u9+9jIE{GR!_llQ_{3Ku#WQrW#*lgf zXxDnj5#TeZ#%cGKrCk$v*P_7B0_IOm!&3%23b~zE*R*E7c0Eh2P%BqGEBUe>nkYXx znR2#HIzw^FwD*Q|6hQq^d)MV3!1Y0YqIz%>H^pBW|B(NvZxjknxup|SYIDxXSJYk( z;oVcXkq|i99eA!W>e&H%NR-Q4lNkRqk&jaW#L^(@!Z&8>cEb{<(4GZ;^=5C|$orK2 z{~R)=*=9R+pR9CA;lIv#=F;?fZ}&5kqya*Qc)J(BMUzxw@H_$z%=eX;@@SkX#QfU6 z;7RU^VLjNA<kCB6B$RY+fJ{s0{&WqlnM2G0D_2Ws<{l_XJol-Fi?`s&FF59e4eC;m zN=N_vzETvGo~C7UmN8v~PuM{K_;>&!4W6ZS<W||jROO2vZiWw8N{U-Gbh4+KIdoiz zeTa#2)C+(+nYwLCvvoa7fj}pw+mJRSYi-Q2-o4n=CgvMLdU^N(M;CVi_!)-x7Dxkl zNpFA4EXNc6woqT`(EX#OA*Ny%Okl^A$#yi~|0Lcr4yb5QAO4_ec9<n=d;G_~5ZmNO z_08Wsm`g9b{x?6|>z5N|anotLVfv5sbkL1cjWZeX0%Y)w8`IQd_wH=qZU%VJ3GmYl z+`z(~^bfsnjF?x#hcgG%b|FjK!&**Odc4WHY<ve2I;|f~N9aT}9qiN}%TxrsXQd0A zqV4a@dX}|9;^d<X3>c+|V0}5f_YnOZh<c280?Ves<gj2oJ<O3RmG(F&kX*|FLl5U< zz$ZvK5XWB#qA^@M1Fr`!7$lM^faO6>DQkS^r3kfk1UE))UAJ<!lps~ZjU&O70Wu+t zODD(SWr0!vXgC(454u{dPi=y*YbBZMf=JSp)^ftp>HwKvFkDTp7rgBTpb%$tS664s z_@;(|tm)l5-?ro1Zo&&1%a3P&eydFD8$hz-S{xhI%xT9M<*eFpgjwu@sY^w?_QP!R z2M99@VssNjR$(VIKgLqP+#OTBpsnQ5N;)9fc~~K9-e~w_d!^qFxv<i9*_Q=5T+$_6 ziIlbCmZjP30#S!;-lepCyz`z8YN+0iSVb#QbGNvP-n!vqc0X{(lnXfcj8FE!s`|Rf zMZ?kg9!J@Ycwc8*hlK{NcQxTH<)5>vb8*CV*=ASmv3l8N?WTsE-@c2gF{)ocY^`I| z$ZV~arWHC6!Z#(NWCl&^wa!Dm^+8%;SGCT_>yoaV`vuZf5Cp@32~t{ccUh6T_s^^L zAAGkb+fzsi>21R^3E7?Z#zL-j-UG(W)Z<4?|EK8i(pR@Kw!lkDJt_gN_dxu^u3N&R zHpi$=w;BrHTv0TltI?~Of*X3WwcXWp$KWHS4vUy*TyU$KYgvTvoQqPhFE&OkGLs;v z4oWI(cyt}nrNj<UynjN)@0M_=!2d2d><hQ!??+#_Y}j()jMN}h(PK;$f%Y~FDyjay zpfmOtOS+}x03ZVjK-<d`pr>pe&ki~KQCmG)ojk3CVS{!$sj$rvX1q`{E8`}oUG-OF z0JK!FQ-&M}ku1h@0X*U|qJ3~z^T8yqCV60yjZZ(?*D`vQq};-WPD%c?i&eL`^{WD` z_G<t)#$4!p&aL7TIq{IPrRld{8oDVuo^=?hY2Y;#zKR4;M4tz0i#M)h4B`H_>8fF| zk`wMr(`;t$-JR<=U~j|RFT-FsmUy9R!g)-+uaZKrSw$orqQqdi%Bh<*cUuy1ZW?1I zXG|MHl3uHJF!#RBT#=3M9#Xlt;%X9@R+4|y6(ImL^g}qAq7Y-^AULf<rc3%uj}yk7 z0@h|?GoqV6>gSd!11**!XT=CbU~333?S*hbgv$swXgd&Kgn+~+$m%`$O0CVmCeAXR zyL`~GTcrStf`-|tz8Z*;)Kd6SE~s#v<Kn4$sMtjR+iogw%WGT79Zc1VaZXdkj$%6L zF6ny*moGgoXiN^HY0QM-7b(JBu~rXx35R8^T_ve83I89y?P}}9$_uj7(VR|#!@n!i zj)TKEY*V;(Q$DTabCMw}NYR2j01d#$MaHSqO^(&bCf2X2{;x;fnqiuE8W*Y280Kp1 zYueArW<=@mScM1YWFm?pWP?dA*Y#svyMe46e5ZI9(^N`ZxS~+fU&nlTW7Of7DYlNB zrso=t+(UQ51~2k-yZhm;TF_J&sOq9TT#AcB=qQ1JyBAig1yLM=e2XZpqC>tI(SZ2x zmkJ=Z7O>Om;RX?o`m%%M?@G=P9CgxQm!QOD`-MEPK@D|ueVlbj(d!D*5g%INhDt~o zQhP=nDK^`hf-5VRXK2!={O58`6|JJilGLn5OmmLg@ziF8!Sslpo5NN*%*NDo^ebr~ zRd>^30xzpf&!1UAyuK6$qLNEXWy9-Nt$N2`<Z~-okxhfRht)^}IHhM`&LugEmPR`H zSzvT7LiuU$qon^vMIsQOP*Te8A}LBUdeHXj22i}TqZED7SJI;eR+lt>*?g-x<ph)V z(#!BoX^w9m=f%6d-}zUIS@@x)-A=m>n~6T<v*2~D1IP=<?s3KIyV~kyeU|i<2;U0| z-Yoh#ro=ya>i(`RWGL1#<g%k6s%~3-WKj^KDIB<LO6=5JTc+MB%Jmixs6U#WH*Yiz zj&>iq5nv;0CLYMq+ChsytGUl|ften+c9RVwhBe4Um;oEL*0r`$#wl}eE(TBI9tXm# zeQRWfG!G{O&MpRt1Zhn%L8Wbz6zt?K`T#7?Fu?s?^v`K{fU771u6N7K@7)`ch0mZv z0oVLY-+pbStf(QyZamcGw<3`HJ7aS;Vxdmk#8ELQV6a+WUXR&y-|xtn2S5!IXp~;N zx-dQfup#_V*dVG5>$niCEHf!*WYQ32^}_?BtraKsj;A9*Y}5&;e_4#SPw<9#iZy}T z|7d;0qN4`oNp|Xp-?qsLRXeUMTYEzcbj+L1cV=oq0M#h<)lNsJqrmT3`9t(mMW`Mt zL7*zoLJ?U0c8%!+vDL+FDZ7R6Y(GUEHbD8hk}H-8U=J!aNVsBW5Zgbh-S&~@nC^vw z7qJ|$JY~#DcfL?-(|;2CX-=7@eEy2Vl#%M=S)SG}rqF?2i~cc}vZ*M)@MoWxs^q2r z6~`UtQ2a>ptJl+fk6kYjM;!`Q@}iv+)pD{2uHA-b@T}pT*L=4^Zq-M{O$FMZArjHr z?ZEw<wt(h(^~$9Su9ow?H}3y#Wta*YGdja%PFP&VCeAB}CZ|(bfqG*wj$L2g=UmhK zuW_HNPHodS&L7qHdMEpjFDm%UulmsSRkdqO!b?5`=&N*Bx<`O7Pi1EvY_th~nEV`* zxHI%!X2@=WW93f#0F=}bk_S1R*Ma>@=pxQNz{fc6Fh&WTkkA77=_n_@nOizr{1DYl zcZCo7c87qR6z+f(FU-sTU7Uu1jf2ogEBNk({vsrH_b>UFlQnqY!v!!10GwJQBL7?2 zku+dO8vOv*R_R$E@~wMCdK15qyI(tRe^<C#u3MSfAZJ3%fXgK)PpUfotyw})zjs7^ zM0!l?I&8-$edHU%l7ao%D{A5uoG3xa_&cg-AmQVO*ku4yPq>Av{U%e3@O-Os0W|5o zEmX-|Q3=k&*D{qVI&d+LN@}&2LTU`|fd7FH*4a%c1=lFyJ!CDyr^&JSmTNPue;-#C z5lW)(-UFlz2jux}v+WTMa4=?Y_*6&UzcSp1>k-;Z_|T$#sHvlPasRsu+J6A*dw~7N zj8Ax(_XxLIh>Q5|3?Q``hIG#;5P|_#JwCx%p9o*9j{uUZcYN6ujwEaGSEs6-GxVdu zG{zX$P;F+=y@`+&(rTz^K-_TBsN&$}YXlZGitn9YSWLo9F-CDrwY4KJmow7GYSZ`0 z0x#oKlN{e0!ho$0yU06<wM-S3j?x{D)fo_2np@LCRtn+#&_xdc!dl!mH#;Q*e<wnD ziz-EQRHCl@^WRmJ?CPC%r&)&@)R{2!vWTz>nF9c9#Qz-rlT7?YU{nWFfqqPWCf=}C zyEIm(C>E<)D~lLxc5hq6Y5xbX5$LI1R#;%;=s+Cm$(9L`+^;wn0f53T)N2EQY^@(P zk-1{vspFjsgT8<<ktF(>D#C|}_D|KSA>~Z%)}M#9noeXqRde$2U(t9OjuQ~j?jZGr zHkf9eftM^$#89nwWHoWp&uyyR%*Q*(5u0kzP=eZ*%#R`_X%&6++>lx$UFl;BVZtyi z#zgi(tCngl=;EsF;uJ=(jIv9_7swlZOL(B1)V>5!e7}uHD6gOk^9Y!MpR2qBKRON| zR<(a(bTY0Q+Rf{@wBf~Uq^&lw8g2BkfmSuTD+w>v5~e#!-GFPi$_o_p>UUlIvMVM7 zx>lpLxw3;K-Pc22z2|fr&ehAJSE*^ox2%2c2tS-Mb)%zgxO{x+mOQs-04D~iiNg6) z@?>NKq;9^gDcrZj(d!pj&Gv!R`6PUjm+C^8veO3Q;afxvaXB|!qhLi%STmVYqtbl? zznrfk1gUf}NfprDvf5^{gLP}Iif7yvgKHGlwWGSS%p1T8m;tHx{qoxK#GW*5*;Pw( z&%Gc#fpUa!!52Ldt<w;Jng=A53-<N!>E-PPf)>{3%bT6X$!8I@J45A*=)|y;RfQv6 zgrow(F%)p}NF;dE21W&almfoRMoz8Rswc4-u#dk#?5-&&s0OJ!H7#{{b9#<_u9YTo z-<Gc4P@6brwE2<l?W&O(?h7|iv*lniYg84Zy=?biH{&3ylkvx95e-f%NreC7=wAGp z?*IRRzjtCMY%|QMwmA#Uv5{)#G{>BCtT`2tYlI~A*=A<Wa|}_=p%S8Wc0O0msZ>r$ zr7KEBhs$r@-=FZl-S&FDZhIc?kMHO&QOKZ0aJG!ByXEeavPT1}#)6*4TJOH8g16#G z+-4KZNY<v}s*Hb65B87_<&%gcoKhDK3K9<~AclF6^QVnLY|O9qGknWDegO%cs{*Q^ ziP0MX;uIms&Jx^MwyBYHdb%y!zG3qmP&dOrjgAH5a}5gz?KO*}RTXGj_?-%p+lDrB z9(WW;oZ4jk>T+f*Sjq>n2_D*`Vtb|H_?<C&=)&Huwz6H83O2AoAxRN#{31_Rl@URB z%Bi48$!9Le-wTxS$gtm%J_T+g@hlYVQ{BFNrhL%5S!G2zL-H)HB$(iV#7g&vWE8?) zHl1|DOU6pE3N<7k=?$1grJx;Rkx^Y<AYh9RyMORKgIDPNiHH+U`(hR_QL)6*!aUwU zLU#_a`=(01o~l{***9vcyEc&ITvD%$y=Cuo4Ob(UzUGWDjn2}v+R%vQ5!d2~#bDqv zS5J&}5={xL=<?A_Ws+EkhR99wyBl=JA%(?_-iE=<u7MvrvATs4L8(}vmqRc=L)5vg zQ)>}CLJu{s{+hHP54KivTToU{mS>HzJxpBZJ7riKZ{k6~e5LZsz+DRB##J?NMAb-` z%6nd*hpjQ&gQMsb*g-7_6PLC6wxQixEgckx5>`kvDy8e<iIT0>JsEK?RpPeb(m<EE zEC|=>Mb`R?@s`Fc?omy5)?Ohp#JlT9i}XyY{9fF~j*z1i>Hfx6$7(h;j^co^c5y;v z5^a&X8-1RLW?9l%idD9f&rNTF_2qvuh$k<u<r0tQ#@HUdJh~EU*=<kDkWV7%<>>}l z{4Ar<50jUa>p1*el0jn^#t5WXcl<P}R(Idd4EV(pd<Q4qmLp$pC*Rcd?LRlSB9P4H zsk7oi^1fZI|3Qrxjc&(OfB!YKPv_bw#ywHIYBW7i#wJCE>Y+(*BUM4Nbi}RyafBOn zd7*I6{%>!k`^c4dSh59HVF7!+4>wgIt{&(I5V3fR@#`>ECA<H%+&uJW$<~tYI|=jq zcI^+cJK&xSASsHU_-c1?{_kZC@srFX4F8|sUYc&qWby9vgsS9=Ri@GxPy3D^`%on# zn)4~E@kGAY{%TL-92qRD{CYW1Mn^@&fNa#2l>U$2N`I&Hv`c<bLeZ!T14W4$1``dQ z>)kEZ$tHP3xe)jk%D-%s&6Cd@7Lys=Au8NXkn0V^hg1&Qa7<Vbo$F{M>?y&KM1M$D zZ50wOlaxmyv&G|M6j<TL?nhcx@ZJj&@l2das`S%~#KB;5^KTlv7O-9%$+<4&Ri?}? z5>|(VN+;rur($eCXUcN&GW8NJ&?TV>zBk&5x8qdsSfFU?)LRqWyC2&BdTFY6P)~EO z>uqVAEFs0aX&#)_I4h4y+Ge!UcaZ}@esNW-1<?KcVRef8vEpyS1?9_?rNRYKK$f-z zxAdxfaeZZCUzdInND<AEY9*Ck(!bo9FZiP>UtvM3<iv~P;lUW}CR2XxMQ}c7m%=AP zI!WgOVm@{x%cA|nO>kw}P8Yt;LMA3<kuVmP>t)qqY33{Aod*LVJ@Jdo91GF)LkfwV zCf%ghWRYa*x)j_<LOcl2u|U4;#KIROgaG0V6PuW7{J)_3$i!f?5<hGCeaZKT&R@?O zgcOP|Mj39{i*uz<18Zf!G`s=Fo83FKZk9Ni2crNTofqx4wATZ7&ys2xO`Z?I*Rh65 z87{-Bp>F5vzt&Zj8XSH-N>1A_Y)T0#ZRt{|14WG4$=@r%#-h9S_uQ!A+_|bB5knDw zV%Bovn*2wibb%=$tU9q|K|%9=s~w-%5%$ln0s>ku1#-3D+Os33a*x%y;-9%xTGf#} zgZ-^b(#K!PZ0*oc3SF^u{?Gx1n(2$e-GTW3h|&riNgI-{Z#qfY0=21t04%Uj4(11I zwKpX{<Gr>zc&cdN-m5+pU_PMv5~&sNuN1ee3$j!IH=w{X&9Ulfx4JHHi++x<QfeMr z1{D<(AMH~Y{?q40Z0yJm%eeGa?>o|!ntWsOC4K_*MpCKA-KOaYS57WTzCJMg$MVLT zR{Re@pkJt$#0nY+)KiVKhkDpojp`&_bmNh3a!JFHpX`n*{qvugYzK(oVR1dBYSb<C zhd*cFL&v#&j>Ou4+Zqe~UhJG|+54jq$uF9!WQ&@sB$>R0nyZykxWMh@PWUWMLaa-A zW>4<k9eLe~-;8=0RTFwc%&h?0A}ZnAsS)xqX4NrdmAyQj`WU&Uut;4fBtE@QOq93? zb7Am<i;h<8Ua!=Y?#CK*<z&66R6jEz6(4LHDbKf1y4NK-P4Z%UrUvf1Fh0e-{nhyl zEbjVT2mh|r>~HtTwxLjm_pgKz-r9Wxe2NQFm<MDEOqKqc8XKtn+qvkGxU>&C%zERo z2z{?1%B_Td)Ghlv;7UM`gi(#8@xzbW_miZLE=a^y;Mk%2snT&}@1n&Qv3L;9i}c<r z5RbROzJXxX1CcWs63lbC7>hUGgX=G!V0?Z^qCY`zzJ4+^&;I+jz;ba)6{`xqeBWY+ zEdBdW0S>(e1QbPQk$R18!0EQJH6TK_7ET?or|kkd892T&;B&;fU-{>Ursb&N2V%vg zB=L;3l1jIgfXi+D@=YUksYe!|S)U0}B*|=2x$jS=(;0kyG5Ek-I>+w0bwb+KIb!J@ z0t=NW4wjoKZW1jzOPeXT|F_HGlAh|zHPHc~R!WmCa<*qB761B(Ne}^17iWFE+A0li z8l#E<$hHT6)njpRH&HPa08S3NstlMVeoR_}Go5WsRbO?6cN}->F**)(8d=t<l<ZZG z&Ra_ey-L%NC}DYYZ!mhu5@{IhYV`sd2=1SnHI38A5TRpRQ^Ya)z>c_tqR@Q))*1&O z%z`?P%xFAH1SC(rv})AR1MbFr$H6nJDcJ-6-S(Wh?PCZG^g1o6HR%F9LWx814;;(% zgBG(*{lsYUM*l<`d45`(-Dv53<{0{K(!ID3`~d)(T&JGj%4`i?ikdz1elO>qN4a9C zW4X5HW7Eab_PLEcLA`nM_kTD3`ZQ5Pi=KL;?|$`5)9uI)Aq`0bcC`qk>Z)dLwY5NY zC>5GIRO8BnBXICAl^y<n2<SwFy6KFV!@*h*%@I5u8{qf<<J*;uyLc`R<{fyzDZ0Q? z#&e1dvGaWB;)Sd|>sbm0=YA&w;&@@_KJfOpAj?#^hun^Ky)gE909Z}Kg>wJ(ppUH( z#2(fELRcEvKR{fX49r#YDGE%>ijgn^%hzQZ^n|sh?i;|w7w3-jsz22n6{vVeT-}zL zEmQ6j>omw19Y;rTqoI!fJci4w0*!D(C+$8~b-La#sM-It>cejAp6jvsNTAnfIh|JD zF`;D_SLk`99$<eR(om`_MF8biZt1eV0vsZ-XbV4d<D+r!82!QU`%g)>g9`#;FYeV_ zn}Hu!2U<y@g*S#oiII5Q=|NYbl4jvF4$wo?RM7NI;edS5oTd<epnMM|1pw59E(c`- z@qjhHg#=izG+iXAn*gvY7;aQW^L)(!@7NL^3|8F*%Md%mfY}5U(~L+k(4h2W!bK1K z{i`D7{^uWcl=!^ZQUkR!ZRp{&fZH#fJ$=vC22Pj<qm6BmHI9aX{R>ZYj~`T*58Z<* zDAt<uhbWe*{WLA!6GDSzPAdPEuhF~5QkpZqrW!m~m9SkO-Jb`hm;ePax9qj&T<*E& zDCct1=VFrWCp1n+YmA*KXW-HkZdifYYO7A<t;9QvW*F7A@4v1k36vHYiVoBmM$6Fg zr)w+E=zarA6G#uD?QB!qB<HmWUfN0ZysMtAKXoRbhbw~Jq}eK2c*wX$3h)mtFuDIo z{$64C6Ff8ZExXYB-nxJR;{4)HR*2n_xrxN**_nWIe<zL%#^pI0M{52Lak}VvNc?Dt zlJ3%fzyE#vLHbX6*3xMCNW##qeSUM`Cr>TieV$?<gkF}V!}BfF<k1j~P$3=pWHswb zqDt2?^rY)+HcTI1*v>C=ik#jizVrr_dw5&QTxTm@HIcb<_sJ;@f;7C55!B*o4aQ|+ zz=~E2aE4<yD@_I7M0nmqHv2bvJ*`Y7k%<ci(J>|NGb=Q=RP76ru@w;lrQ3qMNK+dL z3D=%GVdSP#L4-!jE4zEt?k2u>nC2$ZQf7@QPWAvLJYHhB9~UOq8-*~ThFAbPlzR=J z?E#w-x~T>n1l&sJ=}rU+CGVAG4KO`{)m)?^xF-9oRLGMEqFq5trdnDL{(XmyVOe0E zVb_<!4e7z(>+c^O*QuuRO(#nDoXjzoWJ-Q+sE%EaLir1Xg2`z<ctQ1%si|(LMAsAj z-g)HJzleR@MR;|(Yo<qLuv{bD&z3cACv}149-8k_>o%V5Q_phGpUOpj@{;{`{z;HT ziG#Y=yK*~T70!}krIAFv)(gvxw(^Gq*`nl5>Lw;n+ESL#x;x7%`t%4+$Y>H+kNHGo zfc2FDtHg?O!8n>i>X9F)l^zJ;Xnbrfrx}D4ke5LcVfA2zufk-dsXfQGe^o#3XNq%j z8AP5cVux(n%E_k2Sm*lZe9P_<P86Kp`><I7;ORel4!9TfTV44ztKsM^*-R?qyfrQe z%seA(C7o~+Gd2nooJ98|RsV5=jPPp09fRdnEl0z_D5on0Xu>$ANA=N3;~Vj+a*yGX zqPnj{6ec|wd=`H?iQFJnXLxFItH;pWRW2c>#x`~`#CB7R?GEY;+A14S`&oi;m@>hY zQ+SfvB2@sYFUYud(pCuHovlQdvQAjM0FKoGC?j`Ou|uoo!+pBl3-`zYh>z4NG5tCV z3++?zyU>Y=><61R|7ts6V@k!#zZM)-4!4&)E__h0BPE0`G2E0VJ#4^$j;n5#8fZr- zby^v5rEIvEX2gGyZP$ElaStj`-O-`9%%CtYI@Bj3d_+aUJuEyib#EQ0R`N`P;c$nw zQbO8uK8AnOM)6&+TV-~rq=^ZqA)kqu%{`_B!9{rY?-h8c0t{B!fY4cA(50DOI2pNL z%dh5WSNg{a(G$q9u{0?e%4Tf`U6&d3?{_@@vgoRLKATs}t3UvRP1dI&8QbMa%pi%Z zXX+b<U1kf?V`>gboYiYHd!BpJ^N8egYoqv^ulP2nBP5v1@MN!#X0wH20s2liX{BSB zs#srye0Q=k%>#Nxtetd_c+?}Y^8tUVV%nQzhftU}2GrN<qLv0XN82ZMKH;|r8J!_D z_y;WyV|mw9!;c?HlOLHZGdMpmrWP_UM+3$57da#j1WnmG26Juj*Z*kSvVGJEXLvV0 z&VJ158<_5vH6i@3L_x2HwtRcJ&$Usr|K$`XgB8=NJ3~U$Hd?M98NH#{&wv>+_7Ckn zEsu}0kU2Bx82vJ6akM?%N`(%(=G-Cw6#Qb^S<De9_?V7%U|X?)DeMXBGa5&Gy%;U8 z!fY)S0Op?=E+Z!YIf93J=NbH&x~O;NAr`oNS?=GWqoNjTJL$j;y3{&bjJt40g`e3@ zE3(hyZT~dBe*xoTe!d#KMDKV>Dl9m|ohDi52Odk`eIh$rvL<@x()niSC!dA%*1)L) zh2}@)@BUMXxbj&nRG;tU)7ym#F6#+<ijG_yaa%s76D*le?H8V#L<PU~Bc>>bzrw%k z`c#%B113>{VH+*44zS!1L+qnv;mdn{l>HK>GJR(rKg&2aXI{ka)wI`#nuY~oV~*B) z+{}OfR|hO<OEevU9H_YM5fOW^@@zHfb-<VGX#f4&^s!elDK91dYFNBLyx5Q9)uD2< zz8yIFwT@f`{O-*K)Dfz20qm6p=I)iCcu!+Xa2GwVHC}oA?DHwi(yhoP8wE{E)E6Q0 zJxkJIG4Oc%8NT(Iev#(r?Y-X+-PI{pyME~36~g_BQ`cCMJ4hbEzuhtaXFMN<Ji<cz zOzZd8IdzDbQ(ExALI~L?6nrsp2Fn8GwJJrfoe){whq!92Eq6<~f|7D0?(qGqhl_<N zkDp^!L5Knugc%c_KM%jtnsl!!32YIQn}0%G1CvUFo)(@sXknfFLuWE5RkczS-6<{} zbo%xC^BR5FgGXfFPh*Q$2)1`F?6-hEzJ<Rk22cUYf8AKN)&G*GWPSA`B)Vjdy_fzi ze&DI4tp86U%m$h5vIpLeg>Q*gC6g}%D%6qCaRU<XF&evU?2mgY3=k!jC=%oBg!mYP za((olYQ&fe+SbiGv;`IST>XA$)c-cr&1bOdE7Cg$f52*7yiK=Ijm@Z!0P0zVW+MeP z+TvpordMZdcS|U`r$vY+a-ER#LO-Rh>f8~AAJ}!zwy4qBf%vBaQcOfZ^@RsSd7E$m z5`QA9Lpr<p1Tx%}J+CuDPxbV`sk-X=LV*A)GqrcPx%cM{yUdjJMMkh70t#4)!%BaU ze=d@CyFr54Vj~dXyXYfR$i8=^?}!11r?I~W$Z$+L!2UnHFfv-Dq8VPqMkrw|m#lDf zw-Elc<NgiLTlEL2UI(M)4(al}nxhFt<09-;VaWSn3km&%c4TS{y%Mk7#*)M*NZw}} z?G;4oGtS;0M;-DK9~fgUPGNTD3eYp_a?Zz1mZ71I9qHK%S~|<fCK|Gg&8m8bESsl) zA>?cpD_?Cb@uD6t5vC-&@A*}q1I|4zx~lw`Vgvgy*N3p(amv3ra0iO`g%useaUHLM zO9{p2k4|CgmQr7*oPPZ?AOs2ojh#m4>$OkXe3=NZUD&UTO|yP?^2ia2PV+IPK(J4X zG@&{Fz!3J37RKU(xooH8Usl2M4XMp_L^cJ{-S3k<e!#}W_&nYCX-%etenvY%<9c8b zo*xYLi0bS>_qixd3KH14L4M7so@UR*8QDQTYuE+t6nt^O%XlL`1e}W+pov`~qA$F_ zEX30KnLhFmE&0>gI~!BjJ@-OS8=^h~sB09|SMTa?-Z}SD_uYI~BC&AJ5do}r<zyNn zj@84W+1PzkSmZS3Op!3O1@0__37D5Svbgg6OFq5Who)}(yTa5`PBVW6kQ&^yt@D<r zG3rCu2&33CG2qlasC?B?<?-0<yp#RX`N5Q9KQ1!BEugYl%-auyF_i<$;g?sp75);X zipMS+)TlJBN*^&+^?k?IgI8#&p#K>%$w?)2ZmL~Ia{5)H_Qs>1yP$^vwH8pOxk$;X zK)+$a&#{hVFBts~D=|ZnI7i0BZFBFXN4jlm$V_1#V$c=quz~fE5;e4ak=B1Jn#!ES z^t;m8L)e|nAuaQ6mGwc1M?z#>C$fyTk7<)by@&YW9SvSM=iedys2#&6Li31-14crz zA*|$gh13c$hh}&p5ay1@-Th!13UX8JO3hZs%xOqdFS><ji=ki1rZ8~t2e4%`b=Kpu zXQ6<rM)}{xlOE%;)U^D$a6JU2KJX`5fhhHUo1A9G&tI<&|5@MEoPK!5`+4-0ygQz) z0weqU1Xh*de_9nuDG7^|pqz`1dN#No7D^Q^F(MmyEm5MMB6%Y1R-9I{YGtL;hGGW` z9Y=%@lqTP6POhc}-<to2M$bNjbsm3-wdn|*NxacMfT*NMHZzg0G03;+NX$=!dq>I6 zk@~}bdJ8JTcPVvIxjod33PfZDj88nj>3agaAyficgGunyLfF8&-O_27WImWy2kUA? zD>L!ojh1!GG17~v(u+UI*iX<scDQdbEuX~!`*HWLXKZg2-T##$<0IZ0a3^141Nd!= zLtqNjeiOCEq_$m{QWH{Z%@~VBU!9k?pWdsyq1iya@9Bmhcr;uCfQxNm27j~~|H^Bu zsGyxD)R$DExC`hcCVa{T9U6Vh#vNTJjCwfixh`w)N>S726^1*3>JY-}0rcD?s&at0 zSnT5(pB;Iv_;Sn*96D!jEUy<+UA>MJo~>?D^9%AiesQx}B5)T`PV|9IJM?C8Aq_61 zorvWNzn}Ea|AZBdO`Ph4#jN_5y}Dbeg7N#<qva}_TSt6LuhUTzYq)<;BG<+|T5#ij zcy@G)XoTf<hFGi-gxa}x>V>&x5cpO+<$o{Dmp+&eU6R^aCvMF@82jy;x2Yh68FW#M z(ZL#{0wWy;O7#|vujbv<;#tH&MpYSR=LXrDq4B;A9!o|)?l)|YT<fN(`cKQ@plDer z@M2lBTZr(VH+oD%4vk6Bxm5=_iS+|j4evv-I$e4NcI(A<Wtfsl%()vt$@vWJt(xkf z<I$^T-Ma^{sjsk~wGlb<9pT>o2NzD{D%K8&0(C~Q2O@JT6?=D-T6FgZilJl5`b&DL zUA<BfdeOcuwYiW4ws?H6t>SN6r7m-IZux!-@NP_h*L`v_QYGa2gA+;0;eQ^44E8_m zvU|T}7q!oG{t^xJ@|IcufTOgcxCi=rqH-Ugz!|IfigH>yEqSAvOLD(xO;<hQr$9?U zvpQi<#{Ow!YAqxvU7D7?HE&WodV4C7S6($N^M@YuE&Haq<P3nC!636}$a2i_?V1rE zYH2&}VTL6xgH`HFftAwWQsY>ComA6NY$6M8-&~8^zB%R}=Bw(av{5TIq6>c|d*JF5 zpcCe(gL(a@S9Rk_EeCJGx=J;MBzY*zY=hU<q(wC6PUn4T31LLCSwC7N$NiBS&8YuM z;RhX0MD=%emnwOGlKyemGfwG|@Whx|(O5DJcwM2Oes4ez4&13|qZy8GX<@X&kT)uf zo(XPQ^^a$V4i)&zHo;W~I-y5Vz-uE(39s9$gu~f)we)o-Ws>ww?sZ|rrG|va$xg%p ziK+KU;Bjj7%7&$C?w-3}o6MTU_s(J6Kc5&}^UoNAoSHwOIDPkCL+x2=^TFt5RM3-C zx%a{jy!CN;%TLHt&OI9SFm}J|N$U#tSp4$?u(bSD>5psDuU=r%RWV29p6$q7R&sr? zIcLth@n9t5*`5fyBBnm(BC|AxCpc@8`XYVT(&L>ZP^DkHG|LXHqv?HCDR`;+1!r6& zy`v-IRK`2ueBreMZA^~^dU#Ck*YB4~=ZCtH4NIGfj$?3En!V;<l~X#Qd5guTJ{32X z+0B-|8<5DUnCI0KQKqMmkJg8;cVml}&rJnP@!e%(_({<sL5&6PU&El%u*xkl;7ajZ zXD`KV=_q)n`k1*LntP*banE`VGw{KTfd(4)zx8){`{M}~`wHVcR%iPhYoEG5(|hlZ zn=Qe?{C(NesyEm*bnCGP&$IO(><@e}@LNIV(Sy_g1^I(i)s4{Fp9RXnLyrTO(Oc=~ zTTzP@4fn?soX=GvLxOLBB>KlBBIUDw`pE9|u~5D&)YaG6UM6x_s3kOCwu%W+&rX&y zK;4^19u}e}0cB0zbqnf^(4K!`gt;Ew$^CBUHi{2)yq|kEhSc{JzcmMcyK$M95k2!z zTFw7N1{3Zp@@VI$BxOvg6DR&>(-T!JW-II&Th#G&NzxmbmVbd|D$l4^o>sNU%l>aQ z_g_Ncn>x8gLWv$`2~D;VLX_R+Z$_7=KwGJIJ$Ac9?5hI4&3$Y-+Arsveo1(O{6|4D zY59TP3$5&zaYxWO`_}rJBA?bo=?!{{pq`~>bWe8hK9th{@o`|cSP$mM<_NY&ukyJN zB@+BuN&}s~3QY{$l`~53Y2v}_=$-kg+1?eUY0%+y{Fi{Dci%R%B`TE@dk~nP!#Czp zLja0LS^3X-*8`n(u<QCk3(QwnL?jW)7h(Y+Tt8E|9StAkzE5n1y8y7%vG>5(wigp- z)+we~oBQaja>SU}D_q%|Zld6Vv?^!jMAnS(0<1qL?|Jn8`8li=&36B^yRIF1D{fwS z;eKjO+Wu$rU~K)tA?(532S8r4D|rZ0M>cD+%Ec>Nf@5s^R55yV{N<%cCH)MZ>&2qs z;35T$CmxNAWCMVN?xb-Cc*-hN%tA}x;O#kWFULSSx3fb2)@{eCW~P#<7(@(L+?1;l z_o1pdkE~a8Jzn0y=K79(b-+!xmr2GBq4Z0D|J|=?A2qZ+fb?Bzr3IQ=br3r&)OdZ8 z=2Br`{Lw_$r`5HZVGL#>fI3dmsB^1PxSMLa5a>u*7A#g-r>lmiLD(3!HRPvB>0*%m z?uTqmFntapNjw1ggod_R57e9awyl;Jx@0SHS@9Rti*4FUj84!X7)S-`q8`u@!Z~mK zBT}p4%9=TtxQ|VSj?cE_pRma$o4PGh%Z0GMcTlGqfLR3va1dkfX5j;iVJIR`<M8-D zZy$ZZSJO+O#(}PvwR|MkrcrW9>5mVJD-y0Rbp|XtM&B0$0won(Xq-Gt1~If)-$pqw zUVpW-U`N(ovpCc~Ft~*4hO8@&$drFy9AMThMF^yWS1ul7gNTo|;KO|nIWcMaB+vA4 zHJP}~Mh>2t2xiKXk{=*6%aVSDYgW!0rfZ7KNZ9bzI@Q$%4U3k%iUzX}HMurPKDFf` ztKKQn&b>$nT?cYt{*$lp7$_D%kCSlL7*o|;D`<2GN|%skDL4Rc2;K`|CYLbA#Z)M8 zV3&htwhSN)Zst)TowuGDDThfM7I(9h;En?9smTro{Pyhe`&G9&6>NH~dJ#b|!z-9~ zN>drzlE_+2N09|enUD%`rNo49Frd_d^P=1c0Fu|>r4<jLm;~vz^{+!k6-Rc^)vNjS zI4}|*BDzD1w!?V26-OWS?5zxVDi7-febH@x#cU#}7oLeHQI3sawE4w>KW2lA1#mM~ zZ?GVoCC3H<bwL@PN~>~m=K}Ba7tFRtUyO1)%U8U}a0TZv{aeBZzvjh;4#gCv8`#%X zT*t8+aiz$%!%gIO`SDEs&;nap$uhQmCMN#|V@?5nvT&Kq!&tU4RfLT{KU(5Qi-Z)6 zvY6T+r5~D0NB8eihTk&%#T2zbXIFy_)2U7kS<kGLHM7beF+Ll5c!tWb_h@pv5gMgL z0fHO(upK_XCI}UiON7w8gT(2wMxha+=;db>iedLYnlwv7PVQVg-~<AiKFb<K1@ApW zbTk<^bx;>KlY6~=JaV7f@4Q#<6x;=-1GMBI4MvG)rl|%!=}<MR!Y^vP3Llz|Wps<n zIle1n#>=lRF6_G?2jpl~VMAh1X!RF*-0Mn_IsHG<yL9WtX}j7ZY;C#Gkd+#B-P+^S zk-Vq%d3l$y&@+%1(0>g;NN2$ZsXDfmhS*}8$wQd4n*-z6FD{(UsFE_HSj~#L!L6Gu zP^XINia#pEElEgB9F@CkS9=d9q~8^&htvQRamUa`0b*fFVbccVn)1<zvnMCAhD8NB zP7>2kcb|w!-ZSLnj4-6q|4EdF0$W5<`S0vit1}8axFjGBU>C(}#^^?ZDu7WHc<g`U zHxgaYKxC<vIxyC$AyK1wb9G23rZxZVlR@iy-dH;kWO!&81#FW0jbo#4zC&pG-A_o> zDvp*+ijJWJv_XDpmq0g6pz^i!;@-Mw$$&L_o{S2@9;k5m$*Ifz=9;2y<7MDE`%I%F zAq6+T-t^KHnk%r%11|Z{N|i%3Y6x=HyXtX{!aiKqJkK~!G#CghVoREPRfyvjz@XYm zt?2hO$-s*@b-5x-&1xFl#aC6ez-sAd5(|i87E_#4bX5UnpJnfIo5ep76@v;^llu&d z#f%!ZyHARJE!81pd)~<7USodO2F!Oj(a^4GS~tVgXc+|95E#wyARB-nZaM^dO)GWZ zg?kW9oK%2+x@{>G>&Pa)-jLiS4KCm4l_W*l9j4<}N1tu(CGCwl($5!XC%CRzG*VOb zlcFWruTeP_jxha#E;|lK{b=7{%Dy%sg~{MuTY8mZ=D3g%vD{sxWsmjx@U6r~efi9~ zikMD62j#ggS$b<Vh0xTAJK{a9-k$6;T33SCQg*RVdEiFxw;n8jx9Wr;QGkiQgnLJi zas<FrGtftLw0$clDGAEN^59lfvZSxz>M_X$fi;}2mLYmikd1kx=IVlipjFyDtG8SS zTLrlESUH3?7SOQ3&M_A|TOZ>-p*_iKf3y-%)ci&TLy~Q&r^~nvUn1j4@Z##h7F^!s z-$z5x+UjgYMAf}XyfLZC61a_I*{&!9z*tGZor=oTxR-j;mj>0(1+947NY><Th#-iQ zJkLzeUMt-Gfulo-d;c<4oxU0HefKX0@v&Bi{GH(bH!nU+eNDLeQB)l4s7w!NW>~K} z?EZEf>lpVZP{Gnf-AH^fow-^G&jxHhXBWHxDNG2(Gbc_oH>fqNsd9lqD-9PE(2icl z28Q#<{34_oz6u+0mZ$RdkNPzP2$No~V1c&I?FZ<RR3W58Azx{?{l$A%?l#$X?CB_v zEg%vlcC@bJF81-L*@*0no4WHT_O@irqlYB0{K(+lOI-fr%HL080V1=|oJqW`u5E#5 zPMMhzawPxza)?}3_P==uFk8W*L(}dz+)gEW{Y49G%R&mLzA7=v5k5aBb>W~FmY3!b zk9?DY4<V}wazU0FpmkJQbPpbDI&?25b9%eEra8s>Viw?%c>}*BbG>=D5Liw3cdSCh zt)@6%h<TwJcek`W^o>coR&*=IO6SytZz>A8X^sR4(BzqHs)$XSzs$#6Zq6iuCE!a6 zcTS1gcSLU@pZ;fkf7u55O>5tsXF|{e{I;oeZv^%0ao<UA9W9^?15;UM$8@D}Z|tNC zFU<+CfYsm}EiApCGhZQgLk#%eu}-eBo`YJeo>UWvInP-$YlsgKxs8(SB=mjr>2+e_ znCiyyOV{GZ#AqtdFAA}z8FI|;eVR=hM1?c$=A+(y#;Ulz!<W9R?CyHjVV#t5pgE90 z-o?<Bes(kA{i5n;%OjM6mW)JcuK<VRDfbnj>%<Sxb(6Glyj^YvXJ3*g)OGm8@1|Sj zaS_s7qf_*;g3J4k5P+O!D-E)R;6^7|p0(PeGW7v|mq^CmEp)Gjj|&dMEh2ar-U#9~ z!AhqRkw#gqvY1?Tc&AG`#a@k5IiOvb@DpXB0e5f^^b8q&Q_%9(2dmWYfQ<yOSSnXV zz||ZqY;b^I>oL0_YC%Ene_?_qUZhD8;Sxm37(pALG~V%})W%T!yTtGRmORz0E6%Mb zyNgH%9u#&o{;Ci#sc8|0u;_ZVY<Su%M;K1whZ4m&OswLF)L#}ocU7CAEymxH4khyQ zHN`?HDI)hRf4%z$$kHDp=D>z{bmpA#x$-=s#wQ_-U?}HR3=6(z@dhDA(*z$Fg!zm9 z(rh5+mvkt%@?MuTj+;qXh%A~;p0Ps)N6=WGh+?p<viwr)Y9MFWu$aV4HVj@uRR(Vr z!e~a@dK-QBGwS!|`Dkfw@6S>x)vMJm{7i=H6CwH)JAFKWHpY_CN&rI&xQ7k7WC6@? zP-N{TQ(UyvXg051`gz1^R87OzdQO@4ev?MYLZERbTKNmB8J2NBD!TbiSXX4FI6z6A zc!`ksCi_NSV2ZwceWH;kO6}b*K11H)iQ&rx?t;sU2Mf&=u3<FWirH-~{+fKZF|ZSX z??YrPec%VUz+^y{3TaYX<51lW1y`1N5-P9XV3)f~YS6u|H=u(d_qgg*sJ}qIa=m9B zWjLR&Jyw;z_*>GVm6!fo(u89r8X&i3Lmk#(5rh<b|I|YaG1I|=aUZP!D(_q?+M0-d z$Po08L2OxEBE$O9Y4i%6Y&v$ge0Jw?!MvW&pG&-Xunqu#u2*p={hW1cxrDvLTK#Yj zunN0u`(;*vOZ$z<n@teq=5y_l;VM^tq1&qk0q4ri7Hy7%C<SMf$5g;=J&0Fl%Nq@J z;x?2E83w-vwgJVq?o@H|{Q))q?yqdjF$(|q>a}s5D_;?VGagTfT6{lE7>Nz%CZ+5M z_I*!dC~z>k9Vvkno=XSpqR&7q3GO+Tav@mE6N7v8JM#)f^++ddIWPG&1X-h5@hs1= zp*2sZA^mU|F|AsVe#?#<cB>$vv@DiarUbt_bugk?%v}@W&~~tT4dUboJ&yx#x~KJ1 zt#^mv8yqE{YLc5`t=&p?j6{*I1*_bd+4|NRGFK!^c7oN5!68W_fuoQ^a7ai9*x%<S zhtWVG!~fU|PK@5Xd9FQ7Nf4eyIpUEfrfJaw1$x(PR<JU`r@Njp9W7Q-HvYE;d*ut6 zB_|x<Bjyra!zsBm^S*E0=^u&`_VZm6#CR<8be5CM_yi6j#vO%)iuiP@n13hs8Cw1K z>=Ob<cwjZzkD2T;3tKdr2wLR3vSD!oOVihBJ0A{sB&7Ivl8gb^wMCt>@S!0kxjhX? zI#i+*?PlYVw(neTS!Tv}M}d_Hv1IUUI^pgWkQiU_GqdOes}M^8$nA#0c7*6ea8+pN zOZkU*A9qMk*GWxDMpW-A=fEo7`Xyd*AMCH5pQ^)i>WEG!R|}p=N#OoG*$}vyY@Wb9 z3}GLJxE9!JNgErNba(#g=0s)nKaO-A+uBPAxDQ!s=P(>=4bc6W%B&X^EuG49b{;>7 zM8Hf!^>x~2TFx<Qn)=^Sd*3HtgaoMuxwJGnm0LNwp57@=t@%X04}nize_)ofs~^|$ zx}eyH$afPY>#~wlCGukL?(=d<iDsvq_I9SK%4u2R;+74_`VhT(h+6{el4*rTiDP3} zdNCBX9yw*H^Q@IBal3fx`|_iNJk-AqJWDFn$&+VG;nzFy4K*R&%?G^+il)TrgUp@B zL22Oc$)3a*J+7c>G{NY@u&2w5=|}SLf62+bRc>eanAmI05bK%4BgsG0Q#9+rB5Rhi zo_tu^|FDYjK#NR>V?VE>^ST2<V)NcVYH*gP<og6!szO(R%YFGL{R*PXy;j+roWof~ z?Q_+gK3M@B_8DH2{p|vaO5l6Wiv_&YzA-UT-r0@M2>418;2hv7StbFLhXG-H-TCA* zaDz194I%u>TRXX+j>~QYXQ^+ym0Yj?;@sverIEALSJx~(#(GS*xTeGupXL(UpKNQ` z;fa@NwlImREQRmpFFC{}s@+Q~Z=N}beGtQQbb>N4`8T{ly3M}c7*E*w9gzN@N7Hm= z|2m1m!8<m1+PkKy=CwUK>*uDGjGkdmRaom`Aot6;!o-=Mi?0GVUl|m8b)DzR91T1S z8Na96KIvk7<edLl?p*E5hT(R9fLZ>9qW$!<KVe!p+a>;0({!-lh=Qshyi{HBPjP4P z(fIKcZr785^jzJ)lBo~*+qr~17sMM_)|myuxmUBKVt)8M?7rJ>&D(cu=&C{Mlybt0 zyp)tYlF#RdX(vhz-o9$q-f(xThiDO#Ep*=wDfNDFJXSbc7e&{-MezN39#wt7chTOS z>kU1yeQ*hP=wTR|hvgm&OLcMP8!$Nf@Z^x@m!FpG$)ykxwspj7r_VIZ2;zjGRzRo% zqrdJD!En=2T^R!k#6Z9?EC%bdC3FZ2-UJ&pO%Z&V5+_JG6qcn$hVKaqRQFy8_q^%X zGP3W3l2Lm9fD@usQ5m>o3}8mTF!xK(`73&AgIw4w7wxlD=x*b~Mk<Du3U1Y5LEXp) z|2w|>M<q6plEODfbb*6kl`o!Vz@k_TM0D;KjLz!<skj&V?j8ISRK&`urT8>#ywOGf zRbEKNmC26lpT8d{48cJXQw}qdRVc}h?5B}2$Z>kemGTY_&8qUe<DesaB5T>cJmlV% z>-f7HU-C6-mEacjrH+3~MZbB&dXN?&WhN%IQY)Dv+~JC3Sq}o!y8>c1h^G=GTGipE zVGwXF-h>J<6>vtk@M$881->#>+-I=LJ@MV|u|%@DCRmNN66Y;`t=3PAHX}S)$eHbn z>|Y5xwXlgBA3SPPn9zU2vgqmAIfV=DEqm@OIm6ptr6E=qa7yrrgN};d=k{UQVw$$` z=kw1C#H-ppLfxgR36BoI^0r+p<x6tS@%-((6G_&sM_Jywkqp1m*Ryt${>=mK>&fn6 zV%JUvzc!iZa)9T3<{x5;1ywvO&~(%K^ssXE#4~z|4*)X|O3*YX8aw3cX~(|nzApc_ z&T8#LWORmIQAU;Q>qqmtuW?38bhHHnstfD@_Uz=ql4P5qV<riT^>0x6i0NxTAl@BZ z8JkGSa#4ZoBPcrsG_x*|#ieYuskm^1GGS*hYcAiD4^{N(4RW;vprQ1!^07XJy$umX zUg?_cL+bGBmln`Evg!YqA<j{Bmc;N>K5aErd|mh#Sj2lY0z}Z+*;LkO(S-`}+v{Hn zW})<xcGX0=9alu|-(rgDYLtspmeRkQ<BL1g$#`hiQEu*!aahniU*yayYo??=fo(VM zGrb^{<&W@S@cRtZzeEK+nYdoTK+w>)c1(HdgJ5biw6N`ig?-3r$460|kaWVyMSH=Y zN6WfL)-BWSa=+@5in&VEWJ}5p+Edk!e-dpn=Ie7i&c`_=ge4wuMi+m0<Ct6|{){g8 zzvM$<$wn>^H+>0$#tPxeD>0d5v4`9l))+@H*5`ar@gHtjDA<>?5apca;f`ohge$7U z<<ta{qbjH4RU`z};dgB!V`E~SK1U+ha;xHdp2<cHK@ZHvT#1UE3J4lClX(4T-)mJy z@Tyn<X0x1N?oZ?gu};swI}%_oX=<C$Un&(fmg_bP@`Q_hxFE%TgCKSN>#+{Y{}A=h zLXX;;9yJm%T{HdZ$EO<G2wMh3O$auvk3B+6f#VLJZYwYFKDY_Z`n__n$_rsNrd#JE zDB54}rwl?00~wATOXlu)iv5Q+tvF=gb?D&&cTd=-CxTCRe-s!JRtzyK#?)jZqKu|l zvSCGE*wu3pU$}eV=hBNeguV;v0-30tw(r`;tbvj1maZ{xY3YRhE8dNf9|F_I=APTZ zHFLhIb;kU!v-+wF3$rL+TyQq#!wH-2BT^%l`n~X7y(<0bTb^U9xhHl%*Ld)~68l`k z{V4H+-x&1eXi6C~ZN*WNt@74`kV*}Ksmt1JI3xGwpQYTAAOFQu!}3hL!A&{5TA^;z zf9MwPTcVfW`6rQD8DcL<IuQ7)#u>321~sP0jtoxGNdoH(Pg36WuY6H%z`6%K+3zUi z**y9%NML+o2BWm2xjrfn0KG!2iWp5UHHaMV3ZJ*XxCiL)o=R}7#Ah6?09ap_5z^`o zMc$DgCW5dTR@?_`pw1PC6yu{EA-V2>=~s~YOx8B7-WrC)sRC?TAP3C2Y6b(Y?mqB8 zkN-VwgfPdwF4o|y=<g<Eo|kp_E}ncPJ8Kl&4P2M_<R;e=bgg*&N#Up3w^ulzKehL7 zH#J6Fb1Zka&d4b`diS{N<&=n-XGd;o-f}b6n>LE7_il-4*si@c6?z0hiNMNe&9>T& zi&19O>JMLXsSHrH9=d3f&CLJBL%7#1%Ze(t5&AgQ455<soz=nds<juo$89&IF>EV= z>=O>x5-G|*=f@6yfOKBF{BuJ$G0s%Hq0Hm#%INmD6OtB4c_R!5rXGToKgKW`w+iqm zfY~1L&rPB4I=?(2jWlivl-9mc0~P2gFNk6sP0x@49ViU%W(}fn=#-TynuERZcRb)) zxjNy#5!$X2a2mc?Zk-P>5$eeEV0-5~?K5sCuRa8K79azEOoRg7D_)ezVzOhv{zcJ{ z;wZFwgsJ<tP(3iPrTdBIHP$zzb}cP_MCWFkXGxLQ4^z~hrco|ZXQ@pr%;9QzVd<W0 zh0}TYEq3;0){bCixWlDLI?`9b0$EFkjB@O%YuH>w-V+eZKMx?-dB#n&^UC92o!_Yq zaF~~A6{w_kj$31GlUxVLyeX^z6W4KKJZbY`>|2kztqpPI3pEB9AOfC%q0c=ksBn<< z3c=a}E@7?=J-ZEPs#0CAn*gb`;hqNcT3I=nPO~i?_O9c-T-5$7S7jQIYXQK)v#{EO zc6-_P;C7in3K*W#7(8v;baGt7=~4eHAJbEHMWJd-xKZj5{B-T<)GV#5+B})~VtU|9 z>k{ooRz6a{chumyekK}=q+D{X3%%_A^@Y#AinKc99`}=8@2Vd7=uXwN*?p{WaXi_G z(QIOZhm>snE1`0UIyk?mOC4rIs*PkBI|pI!aKMdrZ7bFO7p~&-SS!sPP>PWGq0(0Q zoGR+*`6r9-^OOLq%eu<3*Kav%$97f<Z@<970s3*(Sf*u&=H{3srlAQVCwsd<kFodE z>O$&QFy$s)<#q@eFuKdjclhJGNta-3hm5DIx3z%)>$_pOUB(mjm~Ka(SXz&yAJpj( zz%bVbroEQ~;-dG|_}3n~d;Fz?$F0cm(2btZQ9WabPv+6l)gVGqEW-2Rlau_6DA6iY zZx{;jk48C#aj?A@e5g^fd}B+HONxR=1^&DAv=LG_q=hjfikd#cI;9;IflxQuKsZ~| zF(-v|Sre$Zg%Vl1%~YllVBS&IR>j3$yQJbDw8u)RN|4&IBXcte4ggvtZ);4Ck|^IP z)A*BjM)ET+b@98pGa$)J5tfRrY8Xy22neSH%OAdqVWnL2zwSPGm$qp3;%<bRgW$PG zLh4>%t3vGn=CU(jYM#+Ne~cG7l-?%J{@{8zkUD(1r#Y3)(zM#Mznf3bUd7!FUDU{n z8Ty6qu5a6FFen(eo=neG+cCA3IV%q{jHyfq8vE=wdfbLQS~B|J$proCyvu~j6#KO* z19x})q}u{2N?2#)fwLD^mKlCESZCaJwol1qpHoxZTEt#E$wm`U`fL&y!w&1gipD+= zB_PaFNpBvlQcGofJ=H8z@?gp;e7A29PKdEm-r20+s~J_M*%EtJnpFfn?;0i3?vnwf ztHNKJRvCVyc8YE7{3oZHPRrU^(kEu~ptVm;KX3yaO6PfIFE`?4yIwndgt1FBYjXB& ztE}V63`^v@1bW~b55l&zE!{d7pt6Boo!O##vh}9R;0i$5rTm{ulzn%>FNL@&?UESX ze+*!T0ubQo-B14V+ivu0P<oWG(8<q&_+)fAok{2+^bu{Q@L!QIJ{?uM1%u|4bo#WB zWtKYoe%1fLU9&!|?H7@vIok}gX|s?n2VNbX`;nH7fO(F-SVJC)7MM;gpd2*2|LGWm zY83}caJ{Xt1D3rTowo(tjvJ;@l{=|>dof5yYBx5$6KZ_DQt~+|$m%qB7fsUvWx9d1 zzKZj_nBbauYRi()O%oTAp|KH>2uqQ#4kTHSmbk&T{xLAEFrKPxIG64<%u~O<98ZbU z`V#+qf5tpi++;{gGW|IYv}0xc^z3B^1r|O9K5c{Obj{90vVkPFGSE5jGahfczTTKB z8$RuMsv7gMQ>?%xs6bpA=I9=@;uO0owl8Mou})xrh{>bOJ!ygICsu=sj<<(83@45p zY?&Y*FpMm2YCGaz5ClI@5Yx`yP7l$`$3M102G=6AUKOaB-1uN6+QWxB&2?iUX?@gz zZdJ$VqFZ~T{WNl?aQAj<UEH<Xc)OM>#7t|t5YFD+yK|Z+)EJeqZr*m%>1+s@Vu4t- zvs8Eq2tN3W-(G>{#DJJj%`iby?%p#FReK6P+*ZwG5gG5k3XyAGPh-I`advX_qxi~# zY*B`@V5N3Hw#$n2Xyk)a`}@fo9fRP#zU!HJtp#;7SRO6WUg8%gFm(trX$wWEt{zv# zyy`QqG><;HiF8Cf1)mh9l^KLaK5j2YUkFv(qaWYz)%vtp_rG&*ef%a$60UMfY644+ z`?sK6BLh+QX&J{|I4Czlkx^iaLd50XcbFJ?e7WE{*#n!ZTeIbc9M|z2yJNTVhm|U9 zwo*6AMJ#t_?TCUwNm5SE%J&0oR|FlWycZ|^l_R?*BZXnk6`@$_AZJRKV@Z&qry9Cs zNS>`PlOM#yt@GvlgSO~r`@ZK<z2E`58{f|D4;k=(e^2e6p{pa8>CW6^06S=GLH4Tx zWe~Tl{d{io&O+JP@ul6g3Gsu2x9^xnT=&$7{U*2;zSyjkZ)j$iQfB7<g$$uMhU?mB zuN(;RoiWg;S>Wr;XfG*1@@49YHd>3FV&?5thLbKUh79R<LLaDZR{EAW$yo75E?4F< zgN~bZN%xGc;^}?}sdK5vTzfREwzXVI=W3oO-G*YVjH<A@T>bkjU(^A)ZdpE2e8A$4 z8huB~VWPe8<DsoCsaTg}d8?DTjX8JJq9PH`_u}tgdGN_Hp>43~MTWyBc75x)6A{Ld zm>?ng#5JKVrnbrYiafhn5I~y%4ILV@Jk-&>jInbtI_5y!<&*Ftf-&c1^kz>@;of5I zV^irrj@G{AuMFqA3m?uuX-0=*dNc{iX0bNuPEHfe-Fgo|xL9szY&Xo+y2#WX;hXQ1 zg!@v0JXHWznWAgPc87An8j&PGFuzSac1_9Fd)CR>!xr-n>P;LcdmsA&VylBXf4s9w zB0BHh<Y3l7q%jbV2vXYYI#0`}AL`mB!6qJBDHd1|Tpa%7c5z0JeHiq0h_yJoQ~BI_ z`3mm=6i@BC;RF3V=lbGvfTIL+{SP)BeaS)d*<nhK7}0z40aV5FS=MrZ!-GJ+sd%4K zj~5Z~wH;blKzN>{c#=^9bt-v!ooE<qQ#j8>xuy6zB^#KbPxvD$lBNw(y7wZM3XJSa z`T&(oh>l2W+}uUs<{6#6w3x-jf8CXjIi|tp?vEmAh*rF{#RWcv{hGbkjIQ852;=4? z+#<ylWpjVDTPY1!(x)mhVIW2JTUo;EbMvW|+E9Xz)%$u5>^A7nSvf#ZkWl&5q3pSb zx8PiOmHJ7>&e<x5E)SMg?=Byn(+j*1Khazg<W0Eb+QxJ7f!@-xg6#}f$^8qbdiRnX zWe%3)G}ezDzTHo~APh=-)!`%&PU%4|dQL4Ps?1f~!ff=WWGF5}2LBaXcMv;IiTT9$ zKNZLTRB01u3GHRN)+&3qe@}IinrTt+zXyiA3xsCrvx0ykdSvCkQ?RdbZga&_!0cpp zEa8l1ufox{ijS-;3^HzQcHtdCieVf~<lEhPxy#fkB}dT;c!;xijWxYgz8rMsuCL|j zmA}zEMJI-=_u$=8*QC%YyZ9<xCkhZlIbtlZTiNtYnk4kS1KiCSKjAP|;{Z(0wNzOX z{hW!JbRzBWFd3jhfT^B?z>s^3$OukV4^#{Sck0ClI`3pIxy>9cP;!_2Mc3}VY?yo5 z{otg-a^}T3nSj!~BAsf_|Lh8d{U=7dAwIqO)`;%#H2q=`YRxIiv^Fv>DtgjydRYZt zGEDU;tL<3YAHyB=u{wL3H)mvfh{NokbBZmibSSI*UQ6;$5dRT~e(D3Qd&sjon{o~V zK0Z^a<TAB2%~7ZaDNzeN|3DkUM{>YyYx0L2^#%tctB(oG4h17>jTc?EO4RG1pOeV{ zuGi6*<yfud4r>mFNic0N8v)OB2<x0{hsLTGw`z@cduxaWqFtwZEW0ZmGBwWfiK1qN zbdmR9tUp+7EYaB~952EoAyvY>q#uYqtKFY=0wA8Pv*W^}kIr7!_D<HXP~(UxRXZZI z%luYe)0NO1NIM-|()WuJc+pN1Q93Vp!RKe^53~nIMS3|`<irfV5MQjmJd<@Do}!{j zSIEu@ezbaOVJ>sH-eFbA@(E{G7)N%CbUyRS*-bWXlP#qQk{7%jZ?|H%_2z2xM8SR6 zo%$jhM-u-+@ga-$Aa<(owF8uS;ckd?OF8kg6}S#gx?5gyySGH!3i62O)T-q?!}#ua zg7+@KE%bd3)zMsNtFB+?Ags?*eWy_l3vPISwXS&2JUDE=TWZDXktjvSD2r`2SNrtD zZ(5oj?XvgTkBJ7NtsA<wYEM84SZ{~ImFeu#tpGP($TaE`tN8K3A!POXJ(Z@IOqc6( z+s*dgYfG=o0x?cE-eUG-qz|;HN3@o@*G-4fbaQuYb|IU)&bfFfQ$Ui%9LugQx%$r* z(JOcUA4O;3*VNmG;j?1F2HWU#j2fNNAR9G$q=1T}Qw2msL|p+R9VuXqloUij#G*@7 zO2oo}sE7qv=uhS4{TI$TpXWT!_qp%uVm0?v7RIoi$cDUhdUo*19q6GT`&+>=w<nri zW?WtS!aby~P}b*`|JiQ_*h5U-xpp=>7&E}PLkEI5*SjuSQP2Mn?5w5_@+3cm=)U>| ztsfm;8%&I^@*nq~dBm?q#5DY$kLc&&;FA^{GYRf>$1tk{Y8nPU<g=nngfzJ<%>WR- zbKpO8Yx6&i!!3a`v8$0)hp(osZYIjT5Y*6kOD%4ruDq+Q)W`GNNv(wa&+583irOFS zPr%N61IexSDF&3B#e-r3p)uo3Y2$ujW2XEVSx&r~b^&*@*S_TqXa1)Bzwe)11Kzhr z#9W>JaP^Ip`x_|Z(+7W2lxuolC79vfU9C0GrBDR}6V>j4GX+};2l|*@cc3r-V3VM4 zk#~k_sTXcs)6Mz&&a52#?xNsb9a!(hRieWiqd(-0$Qn|{`La&1b{|`lkw@vIlxsXx z?4f9(b*8=L5B_Mh3`TutNlKq#9lUE_#8J9o;B@q3jqr1^V}GCld{S6}UPqG7@3hw6 zCe4(g(Wo_$%nKz2#QUw*5=FNsD~M`Yai$p8#W9di(SQGP8^6A@gKsgnSGkLmj{rSs z)dKno4wZ4z$?dL47z_?_?^Dt6$WT&>a%~vf=(|WMc`wwU;nx|%));n;zxrc8`6p>c zNA@Cov*!KCIy!fFtq7KL6RLGPSoFy7JDtpXpzM+rzR~$bL&KcXJB!BpcJZm&$eR?6 zXr@dwOX9}b(6PV~e;28mudQoB-X=QSt2x$-VLwsL*bNtAr~Ps4xcqB>h35uSN*>p5 zw?*{A9o{p=_4^5XOI89ngd#F#fph5%ROO6RYN2n*rE_vR>uO(iESY;<FVw34I|!fz zu7tw@AEA9EF_pdc{Vy(hbVGIH&fc&<tG?L~JkGb?R)PcQqicr^5Y{fAONZGhFSLx^ zuMiE4Zh;Lt!NR@Z1Kz`=Du<X=0SP-89sTkBW3pi$BnSu#u2<brzbaX61pIkFFMZjQ zjge;Wk31!9wGGWKxMIz0+p~O~LIN+Y8g&eW?77nBZsfX9xeJJAiV!@mTQKn|oeqKa z(xn*T{me`G%`&H49h!08(cjeeA=Hm|o($1|eh6yINOAsp4x~BLKCG~_S=Q7X(v)qX zSOLm`hdtifyIJPd%~g9b;TSI%ccb$+_IlG*N4WLm!?6K_GRMzq8wOWYwXhJQaK)H~ zOZX>?e3u*W6TJ5Z5QT6ftrw0x4o|gJ><qU#62+<5pnWos7?6gWbKvulLuSa<yY{0k zT^EnddJf67={i~6vrjJB{}}w$73xKNas68F60SmTPfZ(T>#OgJEJc;@U5K60miQ@5 z(u#J9>ljm}-By$_ZGWcZhqk^Xy+3Wb{$!U{ddT~Qj4`M%>@J`l<KqCn%h1$<YQ0l< zqXq*4JpJZOa>V;U&_2VJmnk`|6#K~GCYPgICi9a*fh9Hm8ulb()0K=GVa+o9^F@AH zrWT>ez&2ltmjA{7cn_|N!gHM68rTWBAs-AF|6v*=L$o-o6V18@i&)~XSj+8XEyNo4 zCC&4Gjg^1f#iuf}y_g$sphw4ymbNu!7<%<`14^u)yYtod+GaoduY-x3{Bm+VYXv~K z)3;n($Z})-xZ4crzW$e*P|*F$c5cMp?t)kIvVz`biXal2y93)I!)|cSAiWuXp+e8i zV(%GNg8Lw{5@)6S79BExa)>{F{na!?B^pPFe<gP^;A@x53Eftyy{ibD6Xul}KE<qp ze9Fh~ioRL~4X8E^Zt3OAW6`%S`8~N5h~1%KQ^fAx_-w9p=>|n3o+-J`lo-5WSvldE z;9n*6+as)vQese}H~Qo4P@5)a&%j2jbTeGh>`82;tG1L~<B<i&Cs99`xafYxc#$)I zLU{8G8S$5%99-kR+UN5O{C2#D?8U<7#_8sF(3V#RT~qCQQ<HBAT@`ES+5UU*PC=4; z)mXdoOuL3>UyyyrtCcwQ@?^D1#4XO*FH}_WRgTwW0Ces*@z;gGc!X~DXnL2JVHGLj z#>vf$_ZbeO{f@H>pQCH9;5#UW(u2V#<YKrtDhJn!c}JVUv0ArTa)@-*+mwyJ=1-`4 zReHB4E>5A@#nJ=Ej!yYpDu|NX87m;RT;&VDE8MI--a7hjf|Ywa#7Qa{mvSj$_7|)X zFVDO&VbyrFpu3YSyOrBr-k<fl_2?fRr{kTJ1+|&`THc+tZMZ8Q67O8+0Ooitt?%NT z@W<H8RA}!I$d~@42I0C5FgoKrfdl`^vA$SZTFur!TJAb^vUs>;5BsDI<dAfmKd7cG zE22Rb(tAbKmJepQ5CAqD-b<<DEm3@%@&Zq0&>na08R@-7bXX^hvgEv&DkK`cIk0UJ zT_HB{Slt^4z6*r`bCaGzrf=qM9u;G_?ZJc^Mvvnu>|(%;5-V<7OLbIG;v^?{%{64> zmG*O1u|#_zQ6yeVk``Dm^c|oyToKt<e{5|`sn$-IU@r6y7>lD7R45+*wU{v*`9OBy z5YXZkhV>|vjh(-+n<NB8jJve~V@0q&35^O6)f@o>#AiJK<B$%{cf9IVkaV_$u)8A1 zUiY04W4k7EdJ#ywXEwInl6_y+Sh|z`4K(n!NMdJ@D-eL#u;i#HS-)E;X+R~YA&l1A z?*Q~fJ>smZ4V-f{9TAOb=l9bl)9cb4W5evWf&Cz?QU*YWNd$kJjpoB{h3Vfrj84lg zcksUESW`$1Z6_4zhfnc6Ec)y4dc1Nwac_&5FZ@g8zhjCo8=mlLaMSPSG|1%=CmQPV z(k2=j>n)m_T7bTZ+Ya5oQ7!B-&1S3mZ~8f{q<mS=0-MfqqKNsb^pOHRT+?f=*4t=1 z5reA?Wdk-5LN_o45g-Ms-hyiP8tt8UEpT`Buo2tVXu^0FNT75*4m$dYOXBt^Z;Ki? z(Uu7>4##1$uBU}9!IovA0!U5K2j4j_z5B!b^mV1u#-zE0To>T3%h|?iY|tZ;L`+(n z@-Ly8@BF|W#+(Gk5;fJ3fzU=s`8ZCK`Y?K~l4`)E@w4Y?)M-*h_@$?wDlC&EJ(YxG zIzI>f?WcFru6Sg&1CVf_P+dB%6Xzs<V)B7Tg9vJd-|)}~uhd2_ZE^0pbUS|Hx&VI` zqp(5`Yr7-T>ndWHt{=@+>cmpqO}=o%0HbF;M40;GkXV&ok6^jO*3ypKIW6Sw-ZigM zD$XD^jn(96RwI_RiH7q9H$Ivv=w`6XOt?F?+yezSg_4Rt6V`kmV74vauQjU2al9ko zB7GtjP{vo4`#<^8PiOP*{VMqMy_Bv#;lT$E7?j!g_c}*NgbJ>Dn(n0{-&A<zolq0^ z%4=+wE4qu3dd9Qe{LZha{{($$&9e<H;hFWvh+)a!G)AOCYP}jxW_xRD)XfRen@(X^ zLk9`C4j1RIBFk&o>mWdp!M<qxfzLV0*3z~1U#PaS=#$^)-nW7XMVaJr*%+lU`s=)b zXKp9L4Y6TMsNLFPcBgDaV}C_(=(_GSb#%nQ>G=}gH}2mW(m=uXrv#2Xz(+XZD!me> zAfM(0rUN*S8T3G-xHKFPx5}OCi0oQRcQ@4Lj@oz+lYwnP&90rPuH27mNpf_SQ)lS( zEdgv7Z9Qubjy2wcHO%*2)rqT3&2%u_?Dp8mk~^(DqWO=Pmx%t5x$&ObMyJ?mI7X`( zop4sy%|iM{vySc~*i*F&k=SfpZdY~TTI^7-b3iEGBSzWh(z0?Rbp&@zd}eP?N9~e9 zW2y(SbQ2(CS-X+pCwUP0zM-AmXD!;1&K7+Oz?D1uPYS|vWM=3*x3_%ck?OqPn=2hZ z6gWok?8{!Odn?si@LnzCF&w&@b2+05C8R+CVJI5V9|CWL`LhTU7_elo4|9&IM7kvK zL^&>|j|{lrylNmCY|Gx6N*=S1F7b~1y6wA-9ZPNKq}cP_4GR-qJ`08d((~a#28Gqw z_Yhs*RT@Va)TbqDit9g?C4N_b*tp26D$vc9aO6JrR5jJE$IEMPc{B2@1sSDF?9Z(Q zVEG9hCXaEd`F1f1AAh_Ne<ovJ@Rw!poA6VwwBT!eE><yMV4!wM2_3>(SKb5!l9`V| zA{^`h_BU3l!$6IPActT}rfw<_m?E$4V`Rqo&H{bVsp3Exz+S`U0UZPc2sC}{!+2zJ z|4ujx43s7CF1-JUa3FxSk*O7Vs_o|xR%7}H*X2SeJPpa@XXNsV-O)jxfPmL;ABUzc zux;%O@4bE*=n`9UX|>kcZ##Wee0OJ6RC%bx-G(a5TRzzMW6Cl+gjP(K56v$CA~_zN zrImiIIq`9n%BK?ITicVoA0-=Nm-|B1s9rf{v=VG9;2`s$-0|eg)nmkChpBPrZmkA8 z`umd4?>()~ZRf&(HyVqmJGUe|scO2wDn#igz&NX9FJk8~CKHRz(rH%`i6FVD>6sgH z%0XuC0zJx)TJ`$)w<R^mI8Dz%7yCD&K-})Je*)PjL@4>3n-^a%j<%P*a%@l}9Cc8O zi;WBw5XAJkMm6K&G2TZl=6zed8koE@2|n>@<Beqh)Uq|j2$C(c%1co;{5}SnJh_9B z?J;P*FK>KF-T<+!$GxWGub;Tz<D;JzfJOOrhKhd(fNOFM#Ll|mx^QVx5@FSHv=_BE zOt0Ci1XUq_5t-Q9Xb1HqDB!An?&i)zpq}4+QRuNZh1U4G>g=31oAmzpQw7)KF(}0O zCRLr<B0Gi5c8GO5+5Llc?QnTVra83=o=jq&va7$?FwaNEOvN7VMm9VeYoQ5MU1o{Z z83FcN+C9b-8OI^<bd-?~f=S?3;1`5;(<>bt-{y)E0pYQlT~j6@O^GcM6uAt4iurxD zXYwlq*G%zA=?sltuj~Y+T0Zl`<M@L_tVeQ9;w-?>EV+%N?Z}9lqU}$6hvbF#DT`OJ zMKKlI6uZQ*0yRw36>{uMq{$gp-j0Ip!VUdbE+r5BW78F!&$F=az({Jrx|E;1S1C~y z>`e8>E3)6MURy|>Ih8!qTyLzH3B!w=!m_a4Q0woJS1^YdgF7ZUwz2A4_vQO5XK>Yb z8#?I7NNfbdAgp8yGeN8OO3*q`^MSo33)mCDPajd9d`wtiR))IFmjBp`j~77X^tnR% zwxNv`0fxSI)a&~`E=%njh5y=evJrP3*vn;xA`G5?e!E(;&}gK7W9`#`PMT!!$~&10 z`dj3c!Dh`zk~zYl=)Na4D6fW4?7ttwByc4<E?G<BF1@2-&q?#d`<x}An|~^w&+glP zqztvM`CzXmm_*pchalp4_UexP*}E618u8-ED)H*x&kwy?dHGJ{_(OJgOV5ip!5ar^ zZdgj5|CxAOX!_=VFJHB9<VA&%yEXz}2m?bc&Y0bVR}J${=pM$}SYJeYK}o1i<bX>{ z>>*kLCTi2^V>uC#jxo(~G&PL>6d+i@hO+)m5KL^J`VPmoWLjKBo)6ZJz<OS*RpQA$ zBJoxTDIYabYaK~P4v|D(=zbBCZ@NgylEMxxzJPp_Tzg4*G#<;97*Ue>*C*axr{JO` zvDzmt2vIa%=6YAj*&HD+W~*t(Eh#oFrB3~PR<mgq(h(4zS0L)>SS4m3^2<VP8%qE^ znnb2NTm9X6<iGeU|9PxU{b_##Y{XBtX-(<fifnp2#{S!+;<Bjc)>137z=w6xMGFcv zHop+CuRR0;RDvLEMj!?P?(rWI#%$4J0%2QcAdnzjt=ZSD0TPan#OIYJ>43k#>!12e z5TP1!4w-(NAe{Cp=NPa6;B$_bX}NPO&26}x2x@u{m1qV;2tZy0?50LM@ih#dc`)3m zV1A55haO8x=y-<Sv2h9Z_e<w7vt;eR&FAkVvL#M8D7;`QHuDISD%`^jnY?~+i!a)- ztUY}ROR@!MC6Qnorg~~9<_uVD2Zv0o5~C=IFVYW8g(VX}qF-s-qCeY3|688|3{>um z-a;j2RMx(o7ri2A!)cA&t_Os=`JyW0h&+aYE>5h1h*=RJxPXZMdogmMhRbx5rm}~d zW1lfZ2~VSmuudO7RC-wGjI=iRXxIRYfY8;qWNm0~HI?TLNP|8Qs4YH!M1cB6C<Y7@ zZ3Y&S<oFK=BA(dATAg04=emO_Jr79oN%AL_g-(fnqcV4(iMvjKB+|YZF6(?t%@`w5 zBmy42G8_785+`wKNuKFOfEz9oJ(ls_aPksb!dpFbC2xlNdl8-D$i#KqB0BjZDoS|A ze!L>NHd5?AGsC+20Zl;dkG-KY%Ioc%p6XxHm2doQv-d@+T9G2(2s=<e!~#(ynSp7y zN3?K!=lMeIe9Y<1_j%RgU!k5k0@x4x5|c0uYr7UIyX692^NW+F%p@sQ=PEW-N|ea# zWDjCP%T)%UWoi|91D^rlO9@+JVza_KZ@Ar2NA$jh4MVZX{aR!mC$h?Oh;4Su^;XjB zmFNT#8cdqY*4w+HZPWjCL`fn@>1*byb><`~Q?v@p61%h{n!dD46mJwoGCILCvODUe z)ut2^{^;`?!axJ=84tH8z@!jDZNu?yy2?kcEC1ykOgnm^d)YKf*DT|@S(ov<l{Shf zMN~jX(CPU1bj$)BM(`3&2F!0MW9Iv|(ZLM#P?iSiwJ_-$;iIufI$vl=(EJa2+Qv@O zlYN@cu%1SNk0gFfaraVJ)xxmO`NE!xu=c2iK>%^!+h=W*@37E)g4?=|69j0%J!@aG zJg7R#f^XW3D22iuw>ma8^{%Bq`uaOk!sDBxu;D9_=AUmhB)C-)nUAWqU0x*lF3+Q1 z6qGvI&HA0H4&KW1w~EbI3lV>K4fmoCrIwA+ToQ5jNcq9*eHb<x%A20~GM(UNc0bfL zzgVZ_%7J%$9f7TTmjLq?NPA1Su*}4)@*B#lR~J;&orO>VwwM_P+VPslFu}8eQZfd> za{zbxhPKc#>%HRy$;p0Q$o9FZt5Un&3}b;k8D4vGUu#paN+UCbt<OWrueGnd_Ni(G zumm6&MZuj__~xm%sOLia9v{HfSbLM4OfgIo4mPX8ncUyCuQNx)aPPhPpRr(xmVR;C zl3MzkDzoc1#thWk{R58^k9|uzmSpc##&X)PuIv;dzSSq(4In3MMa4t*P1~7%qCOYT z*QCGE;=FS?ioRWNCAC{z=NU_P7@~W(Rs>KAK1LT_?Q#XbpIxvOR*7^^f;=~Dq%YYb zg8>7_Ylgp9Je<Z!Zgga@PGt9C+IfD9NS)+&_|>H8vSfo#0I+a6W+9o)`r|VM76)o0 zzg&3z1tq=?_9WlT-qwNH$^Z<-Nc1!G7p&oX-DHsyBO3m{VIAo|qL@DnQ>VTL>j`Uw z2<yGmeu!3TS-oiM>R<_y(5$r?SdYzk^wo^K+~aR-Ee^y_34L{Y#Q%Pbe#J?#3Rjkl zyIQ(?$ySsA5+gQi`aUFxFBx)1v0i?vf2ppImi@H9p*alQWq$CzaFJ&pcq1e1CHfso z>b5TAo}@BHz=)o|FK+q7!}@sgFAma8;3=iwQp@;2Dzn}<E~z?2Lak;cvTZD3;TeT( zgoc=+@jZJ~ZHupc$y+{-p;%x6kOwXGx-)?1%e##2vXuZ%F9`#X3u{Rkktsq)!yd)1 z<gtDjTD5IUq%MhGQW7)kR~u>1J=7rP9U{M+amp#VfceECHQD;=jkFIL&vQbjl3wGc zl$D=TalZ-3B7&=snMP8v)?L;Gp~&N?Dr{!fk+WBH^I0=03xAU}uK*yoI(j4F92Tpg zx4F!IuEimnahw(oA|W1&(0l9m3C{$u90q5j)AFi7xPSq(dP1;&ote0md~Az0SfF`p z@T2znlk(6M<{*isVcO?yID%(WRYCP;I#piRTG+6EN+&+`c)n=1N|7vHqOS0kgHbo_ z-rw}knU}(bi&OjkRUQ%s6MRQn)vV4+IsPBqc?wr_*3w5kN6$a(aoj1&BbCb2hiKHV z$G10Yms4CG;x1H65JN;4fTF<bXao~G`CeIgBtAIy$S&!bWV-`L{Y4QWA`j^(4uEXw zLxX?n{s8M+<d-pf%W@wcl(56(J!^1!`~LKddoUk4&qoJrmH)DD4*rDd;S1&TMNkKg zYWdBH3pCmjQfiOoiyQ>!E%-!s*bV&om!GxtUZ?1N4+jw<JmY;TymE%0=9nWQA-2Yp zRUMqCBK9@!uCHNAl+f#Fr<D_Whlc$PQQv+~KeRgA@%zNyJz|dTOzd*%mX+w~cXeVZ z%h&eIB@><nVk-O$ENVPII}t$6W<hvakZubBnMoJE#HdA*AN@$cp_a5JcbAYWwlyY{ z6S~B)B1;LTUdSEjL8q<oLYHd(@+{Zo4kN80_o{xu?}j}a_o~+jHaK`W9TT+GRO0=i zw+Z@(fSyv4qzpDAhv(75p$8iKW%F7^h&D$CKcWY`q)2-n4M^)WKrabFo!op+@2$L$ znA5mbxmeVu4nA>9+Hb+tB>|nfGf3*jth{LWU4FllU40ER@KyGTL=d?^wMKox&39|z zYdBNHpDdYqr0TU4>2Rpn?N8c=U+|8tkj8!(5_1oVe5&Pfu#;+dl@Khd3bSl0oJuIl zAfPAcB8VyxL<mlCsa8CsSeSY1H=ty8Q#8j3*LlC**bH4yN0r^W*=D~j8a{*HmlUrX zrr#o$-f^COW(K`3-y|}C9%8^6*2*QyO3>9-7?yAn0rp2Ax=BF)VIX_1(k4*A!`Qn| z*Q}*>n@(1GZ{4zaQrVi7xJPt3#>N49@`fdqmLs*lt*r;NP_^sdZ=HJ(=?;jWg7DxO z`vQ{-gI`Un<6yb6A&cH2;*kT_R6mS%)ZZ{%dKEq=Wd@2q-f0az5leploO{5u`~%@3 z@_FM=ZI4*XwFb>K1P)(SJ6(fQ>Bpk0M0%r8MGSaLAL^sHaE}1}woSyX%5{w)f*`;8 zb!y@rU-+s3Imvi=0zjtng@<;yBd$8y^|*VSw4AlD`P_4lq1y%s$gQrEw`K{Cs+wNU zX01&EOLaj;!G(RcVdy5lZ~*~5K(LMy(mdZsc)PFV%k!*!N@ey4d`gyS@%O3)LdmVK zt;qdq#WLul#V|hIqG?N~wT7_{x_E0#PP^ug;LFI5v0hn~g0*$In7R*au=?j;W9cEM zKP@cNs&<{d@6h9aalS@OK*yPhD5V@2y=L8Y#dO8~&GVB+LLkNqg({qEKX%J@=`jOc zZ;RpC3K#Y5ytfU7R~s=Wg*yOYk!{Q}UGz8K%r3yR)5}yS%w0Ri03k^-U8GwszIH7{ z_cCDBgq5f8W}!Q`+XSfFIh%tF)MlRuKtNvrP?zZ2ks`#mvukmapBc$EVKbHQ4BlMj z*0eg!lN>M3iH6D?4Qt0+J-%fY`E$JBX_cPPN%rL@8*7rqp1RaauAf!Ip6u(#p?^PV zR(N)rauj?u`fRh_8!1QaDlx)w{2rxI5K)Z5gd&58W*SSiEVLXY6fy2)4;09HL)%F; zBMw{>UD;GF7NBGa%`1IdEv&X@{`i<Z_|AQ@!tm8tUKsa*A|(U$z5+roxL|IpBZASq zLif&vJrD35)X%Rl_I|*-nd66+X+1c^ZA=_OOV#ha8V;hFw2EsS2=)aLU?}liw;i3- z%=#Fv9+E2_A|1{b-Icymjt`M$WV2LIvD;LubuwfOi6``=6O2|KNJ^A{aC)@s-85|5 zOWZDD^@7DQAut%A(gx3Bci}l4OYi;+q)e!6xkjp5;N5=#adXkLYJ*^-V{0ny{Pp(( zOwm6j6VmD)=WPxxbF$MCfQO*ywZXS#N;>@0MqSV|eANs<a<j|5GQ^Rkh&%S}ECOK3 zCvgc7JcY|-0RwzR&V?aarRLU=AO-tCY2OS7_c19ihy)CfPwET7$*X|dM`U4*APFF* zhx%9s5(2aJ4^LJdkvdS?55~nLfK=?F>Ks-iy!UTFg@H*}hM2qA(vWS+o8hMi0W1gz z35<PecMiQov$G4?v1kczb0xZ^$@wyo<nUj9DKe2e2#=@2e^-h{FV_6E69sNw*v*Tz zecw-u|BdmTK6JxjVAZzwaTLw2{EyH<t@?77i#i-rdm%{@Ip=)3zpKMVb2b5g;dpV5 z>H8zazTVlAY-u7?vnXIEi+<-R{Amr$0jljI@o7|?@ejvsVL^4I<=71DrZ#KF<3D;= z%lrNyvNX7>Di*EURpRB=wMxv@l}vt|x9=sww!mVIBqVH>4pNZ{d~x2PFhb!(05-t5 zf3D>CM%P}le~|Hltu^UST{*xT_eG)WkbRXZ@#_n=($Xe@At-V2sK}#h71D=J6kS-@ zqh9<q!&`iwOtRbV0MWcdd&n~lhtGN}H`fBj1K9?RV;v}<%zl)1^nPL93!`(tXSk^q zoi5*xRJhGJd+gg0l&E|@G=V)rvMY-wcVap(UmL@l@#81%3Z1|H5Wh_5PJsYQiwoUl zIyZJ1LaV*q3KvGQwZOKYZG9^YN@bv}u2Z+xlcps^v{$)b?)<(wOv6c0`=R2VXy`gV z)u0YahV2u#r?YU53j=1_ZrE}WsoL-gXdUlATQw@$7Kx6SoP&_=pXggiSD^KQUZGVg zH#6UaRVp4dgE8ctmJURdL6;uz>`h+_+18vt_HxX)(QIZyWnIa7suuV&zoz!tS^ZeT z`S7CCn%gzDIv1S#ofu0pkI2#zC{HRyjJL}9uO!N5rX*i)2sQN#?Mr|e2%B6@EQ|jJ zn8L|phxMCj-KgaopE8;WnPJ>)be45P!|Hy0Fe6VoOLwjl4HV6KNipm*mD>T-fw8@X zQ>-E8Bn&vgr$}t-^QKkRj=7mH*m7+-ebLz=omy^~hsIc=?}v}?xQx~jEQ6v`d4y8X z(+EJ{@cnKTVD~EA#zSp%Nc)OIrm*}AAw#2WMjHW-+jY8pK&yuNK&rlhtw&7ktmzju zn^nrMulAQ;{^RE3BSuKKk-5xt14o$&*VRx5Nf*Dz8;PN(;;~-%y)!K;hi3UNE^I&M zJsHY7sV_IS*zvgX9t@U|9;0-yJ*y|Pmg!IsCl!0aIg@F1o$v+hEy-#C5qac;j=f;= z3YekZ2Nq4`!o)7o&M^fJNM9&mDbryA1Z=p#o`#A>o|ERvMCSF?NCP&uR%6NWgt+i9 z@C#Ch)n=W@-yH(4M3A&bE#l--ECwOtZ3LvBC5RcTkdu#6?^=bPuB#lOVto2G5=QVl zVFC^BX_N~yss6IB3UTjKt&63Pl<**1D((#z`S5N0KMlll<FS@~iyis~xq%t$l9QS7 zo*G2WyliR1K^84TlN;tGGeFDGpQ=LZe9bX_S*JYlSWEa|&wy|OU2j{PPS)|3rtSx@ znO5Rt<YA<p_>6g7idy8QKozd_Mj%!`!2YtHzL?$CFUwaK3zej!#SW?%Rq}>+YV;&q zPzT8Rp{!c7(!}EZBqTmRw6;NdDVlbOefcu6*7R(EgO+z8%EK6}gv#(#KOC3mW<?<w z`K_pnX}GKu)JL7wtUbh;;CVqM4zc4uIf*E_R!Z2D+q{~*zXQRUA7`r7;xS$iE#2xF z&E+HZg$}{cn#Nis(Vho`yZ$j`JMT6Ne``8-r-xpq9Uy`N7N1D)+a+%j%up#@n8YUU z;jQwA7uQ#EC4{xgSuei2{+1t;deg(itX#_{u){X(U3ozJHsABO{WXX6X;JEa=Kg25 zrn<_Dy#8tv8?3si@wl7Vs*H)fbe~0v0FoOs1TR6wBpo4SbRbN^@d^51nG`K;dova$ zh-9xE>u*xfhri|cz<^*bZTiK8bUS`g)pz%h4z|@afjQ9hV?M!;ML&XhtBDYK<RD~J z(tr2hUx=t`*1YbYgx0Oiw^9W(FmXXxH!eGu^#Pw7Am|tM4Ii+0`s*QUHR2MwzbFJb z!<L^y=A{>w5B+hjWa2wPFqmyChyfH{To`@<VN9eRDvYJ>CW${&WkXAzF~_`>t*%lX z)WEnxn^4&^(hk##UMsI<^Nla3+iM|0nw*TmHrs^>9mPKHUnfgJUk(&O<rez5X3^xE z5@e3b91m)`+J{A;njGoou3+ZSq>&av_Xu*4!@hAY-3S>s<r)>D>2T7$Vo-cXiZzfC zjq!+q<c_^D+XD9``UlqU+GK3*Xy=oxSE|lzpVYf~DMEWUm5c-O=rGG{XSeeHl8>S1 zR2h{65OWG{**O4Xga(3Txu1rH)*b+DO2oU`Wc?4<nDXLJdKbH*g$Y0iq;FR}sN2xX z$PV|k=bWKdnNu42rH{u6yoT3hWuJj&KUV8ldLUJ~{vwJpR{a85;aQBl?4lu;nQjv? zp(Is>G;yoKv&$(2*=v{iYG88S)Hahq?T>Jpikx)Q*oy2GMr3H+=Da!8lhtvq<m=sk z`$pWRvE6*O&eRgR>)qGU$L)S2A#XJI-*gdGg)`1Y9VRSx#z}Id>$L-(In!b(Vc zjb(>bzR36JpmVCeMt2AbZ*#-;DFhB9+6;D4C!s{;IF{iGA3@+=eQ-52?c?A_z0X;P zw-6`eoUn&S#AT*&mL>=8ZN}fjd-K*2!i5TFoOW6I+2riS8pB+c>uu&8k7tgOtbCZ+ zKfO%CnCV`)vjpUgb3!M1Cm#CaIQod98*oaWkS19!QZ3<mL|R5-{M}ktkMEIc$-#CT zVs;JIPSiw|P&17gxc`sCj@wg0NmD`^MQ+*@3I855e}nXWOA@15>Eq|p?>k{1z@>l$ zJu^CZHy?W8waPr)!UdfCV$>t8N(!JS*JWlc!vXH@(~9*0H^dxq*Dc%q4L(IlfBC8Q z;~XvW3jDvHv_DSRIsGIq+iftMayMKW=)fUYQ_+PkB0Z>b9%_93xH8qyBIA&rgK_Gp z(b=L@Vsy@j6sAn#9&V@+gCAl27F)!FIs;;e>L5o|x!p!aFC(O-BJeC4JZTEf88Cgc zn)c2Qo&cyM5X31=j<O+9FWE0{3hvVmKE*hhQ6r==5TyuD-`8cfkD9(eRoQe?H=U{H z=Cv1+D7l*k(cTt78pBiq_)u*=)V&>g>8%IfG3!{gL#^a#cT<yhS(ZMg$JX{@{YJ5e zHUUuvSCSkDyLJqHjT@<+G7ZUwfWkIy%^_8ZL*jl*8DT7yof13lF-&{vJE@G0J~M?9 z-9VU0<Yx4fEM<_bw(xqw{ypP|+oEmm4jkq{fe-yciTd~l4krKSU|vV{FbPA|2P8uX zXNK4#srY!_$$e9C5iv^QhT`=C__#nMgok?CkpF^oE{*^XZG_x-BBb~(@$S#W`?W$r zROPc_{?QWVo7Bvd2%HlU=CBUFJ!q-D(}$aax(H%knr0=FJTJ~-ug*Hi&1Yrfj-8b# zL~kcL=93Fchp{6**rsu*Z>HGq$ItXh0%}-M<)_#a9ip`aSR^1JUaC|^B|*7f(9NRr zhyzBye2$$%)wiQGrm>ev$6ZetK{gP)cGQkq3E<(WGOV@$X67{F8XjIm7dk~iMkwzS zCzoby;8?uUry229(xz@prGPETcmW=%4?EQ--Vt@V9S}ashqtenIV%y9#`B?x#3Wmx zm7a5VZ@B4uOH3OpOHAl~2A>6{V86W1a*?okIE<PEB@3k70T?8v;#^=dDiBNNt0J#w zU2>Mqud_@}s)RDREl40>RI1DW%+2mV-TB~dXY5-7EPS1qS|)qi2RpFsjE(cT(7zCb zS=ujEb+Ib~bw(ik>}E-Nf3ZY4zKjN65-MrumK5?X-N5-4>Hi<?R%gpD<(HC-t~`&3 zyx&29GF^qDE@N<RX>@3OyP{7!+~>Q}KlA$206a<nPX@$^p?sI}C<q9C!nrZcJVT?X zVE=bwfn61}U&7oFYgv+BYk>_5Ir}Xd=L+2+RMAsHp!^Z2O9E7=(W2snLtUh&%g?OS zJu=1<GI61}vSY{gN}bsl#eR<p?Uun*In+X@MY}3s4{8%tC{efU83{&&p%aWhUI*?i z`{)MjtByuLtVmTZt-rQa%y2?HxLJHN#HN;0Kl?Nr5+awm<3B#afS$r4j;<Z4mO4J+ z?<-Tt#w1<=Z#p#`Pl$FT1qV_X?Jzq&%#trQ-=H&;8O&LS1C_x~eWEZ`oU$h38!A@$ zzms|Fj<eS#GDDggCZrs_u`RL=M>n8n>Yx>wBCA;8RegwqesfnEFC`l1fQ8n-g&YvC zAsIPB`Yn0nLXe*ohS{Pzf9%gW@WvGF(KGDzDd>aRT4iG5^6(WDxUOZm#9!8iyNTFA z;f?^p#Vc5|Vxy=XM;iqAY+>`m!Y1$Me$<vv5r9l;hj(w_X5Yl~yvRcP(k#m(lV;m7 z*GvnAfm7@G@#|t3rIXmb@N>)8lsYI(qWHpgaS?<Zlx>71J$Ez0H(^4Wt^{Ej-q@^h ztSeOCgC<4KNK${d_Zl7UM}u8YOWqW}-IJpl2t9on3798%Hoa}WvlfEERl2)kIc8Y# zr`VwhsZJAG>4w2Kc<nW0`~&r(pj=UaE@FX?&cOMl<wP><yT|Z^_3@HXXIzf$q4~E6 zb&2+_4XwEI$es-3$&*ykL?ex*3(sQOGNy5byc6AHQrSENG^Bg;{?73>Ay(4p`_n6u zAjI`7ihZIuVMn(&CUsyPdSHrj(lO(}W2{CTuJyjSZk!}kX>XYH^;dIPPaZsl0Q2Hm zoJoYD=WpHnAhj`vm6kl6^G21roohH_c_+^Rn@Pnk#NjL~upQmU7WZ{U9tS`P=>M*C zp*KYT(Zt1Ff)wKL=}lK;RT9GMz1H8eq&Kj;Hn2H-L^H2$mXCPcND>KQoz+K`t;63~ z*kl)xa9&hs|LDW_jI8QinIFf{*Ss<k+dtp$UmT9SYabkgHv4PN$-G9<7>Lm2!?gIY zToiC(JW6XO$|y;wai6k;>>zrngY*^ZJqPuq!)Z_ed|k>53%mW{mWx1&BOz_hn8YM{ z9`J>Dj$&JcTA~drqiaEr(SYv@tbaTX$p;cxR^+u%y8H+x5lzFoPnY<q;}g$K5+*`% z3RUq@T4~c=sP=6-s=4H<z~y2y|C-wOpnRu`&opcb1&Bhzff~jX!X1II#{UVyg_IpQ z<}#k$-;>c1xv&E^!zG?Rny&@z-j(ZDG%9q853|sR6J0az?Zrl|Ph6hpol(98!>R7* zH*UzoYHIG^*495xp7de}Rm?*i-$_AnP;<epXok@Er2fNOS#O-MRZp=#=S~+pVCT^? zRxa2Z^~ZXCJP0;@7<6Cc8&Rk+*KIyP{LDm(!U`E|XcQ?q9b@@uC*=YVjCuN~oTM>v zoVL~OL#O*Lq@?$l8KH_9Qx_RKj3Pw50Je_@wW7nQ36LEwqZJ?aM-Bg99PY7SyL6ou zrYKE&yKy`Xe6F^TXcP@qy#qVc?lu<Q3+*>EB$i7(!;-zFBl@KjTxMx_RT@po5$g~Q zgot-brELs40xweOaFsNDl^mfkIy{vgiyEBk8pP(k;YEBKn%)2S@ofViZQ6|#TF{GQ z!Jk4ye?Ep4su#A~`!I=jWALtt_=rYdAy$|<X&N0eT1SE3r6G>G%Ze5va@M`er!MqQ zBYAXF+<gd@4-sAmkbQtuJ7k|gNaC|lI(;dT06o>d&oWXvC~%xK?<;f4)a}|`=(W6E zEKZ}BpMNPap-+fHhg$RrMG};apy_DPeRF8jEL7$vWw1nY7E<-xQ(ww0A?eokeyP5f z*iXsH4m^mZl~6SB=5*p5HDBniCB(ch>u%7?w^7oZ=t`MlgN56buqq(n_T$R$g^_z9 z-)JfCKG9AQF>ZW`Ob}ef8cHR=i8#O5NZ*LJQyYIqAR(iOPw)}?=y|f7NHp@LL5XOG zkS87LPKWxeL!J0AyFSQah8T8}5HSS_;ZLD-;6e0DO1Sn&t^PW7Ct2<8g=%$&Ys<;r z1<3^Xts4X5wSK#oXPUH{Y(!)hp`-vFEI|L3;l<}kUQ(E{m<Na9ZtYSo>oF<RP6)X= zg$@t!odamFX#S@#tmT2lx!J!Vwd6Z--Va`UdU>ANa%k@HicS!G+t29i*5e)S_921$ z`+*NA6g-m;@fW}x2~g#J*@s|?@bi@PB^MC5U-S!N91vD6MSN)V!tJ-wh9MC|ArCCf zaSCihhdNBbj_S{_vG7EFcrAa518DD>Mjhip3J5x<u#gTGg42HKX~qFyKq`K)G}-&| z%9~oLlgo{TvQE^-%O5CX_8BJv3$)^Ui9bJNd+D{s;S5dpW@%i%`B&wMln`A)$kP^j zq7)uYx9EE2adPRFH4Wx3@_GEgocYuXYX0Pk%}Y1jgY?4F|Gt5wuYWF$2$UH&cs}{~ zwa%9dssM&AlB7HGMh*$sVGW0t6WZZH2~bA?%n|@mx9RK3px~1`%kq?1o7Xhw-#T~d z)vVx2GYx@71JZi9vi6Mv06y~$tfLPxTK|-ofI6v<fQuk=^-(-J>@a@^i%t-`hTzyv zfgKS^eb68RbYCC5K;V+SZf#0xx1Pp+Q@9*9STx}LP4-Y3>$>>U22QqDHtAO|l>FUo z+ED*OdgsL^$;6MNpWWfzDi{#fqY@oIz!}F|p7^+s4JM!~HBaP`K(^PYC7RKje6kPJ z7AGa#>^tt&v63eb00P=myi<OeLBzwnabi8PQgipm7cu=;GLT{b;z5NE2!J{lE7G5R zv-N85iXsApx}8?Och})JE}v27%3`)>8bDKys`5aBfPm|_v&U;$bORHhD`yq08Nl$6 zWvs_Vuai|oi(34SjUdCn!X=``v&x=FBq!N(CncnGA}94jNA90@EN$rz+P#KVq7*!H zGnk2<xMWKq)~P|WH!GFB6t6Lv;qW4-TuD$sa`e{HAb`cypP=&i4Xm5sG0T^~-OQhM zU9r|W_MoyX_U=31;>>z!!_Zn*ens6IiOTgl3!K>$p*Y~zS0LfqHJ5T?$@*ALVZj(8 zUzsH!apgbuu@S_eHF6#DK+}?HYjBTlJtlQPpe~$AjJ0bjOUh})_@t{kNZy!GzkFte zK~eqg3vR13=L9U}D?Hl{3V|sQR^5e7)(B95vOc5iY~7L#I~xv6*YNC6xiRMUIS_vP z63R<OCV&vAiZi>b56+U0rH2aZsmQ1lc{wK9n+3R47`Zw@ag<`S&eSljS$6=3=Rr`a z%_Cf*vGbL>7no<s_0hFB3dd3eSS>o=sK1)CHrIRmcl5Oa3xL!$S4OLIw(QC=Y;Gxg zrZ0S3?h$ZS8%XfW&bx58{NbHyL2+B1Oaz{5!}@&76PZ(;+K`juYcZh2b!;+`+?O*3 z%Fp;X79xb~V#VwvnL0Go@xCrn42;E`VDNHK8qg$E5Uar~FQEvAB(DfFGEV<HaqS>0 zsu~XLFWDBbtmQy}o~2ImRH!hvhyfsd9x})riDlbbkvqO?VJMT|`f6v7%~yq$XieCD zqQ28~7b&Em8aoXS{##ehlTW}>gcsB_lEvTRV^(tY|51l!$#`=p&OvdSlIv10P%bbt zmdW55T_O!|H9Fgg*^Vk9c8DSga}}I>O^4x?ceSrI!);fouyCL6V<&rk!YY;3&1Z@r z1${ATyX)l?{P(LG%_Y1*8v$Ia%@5LtkpZPwr_uvL-qk$HR{gw>m>gMQy^K)BZ>}QF zauHyLJd4ndBBn`ez@^svAV5(<LwlX@Xldh%GH#oO`i1Cc@9jz{zA^TdYxx?WbiZvE z6hq8Q+pOtIf|thSPlIsArPGr!MB&T_`kp&UG`byJ(U!Msrz7QRFQPzSWnnd(50DYI zG7!mM%nSqX!kj&3^{P2LiY5MaE_DZ28cJgg)eEw0%y#PK(k1vjKHN!V6qh(f)*0bv z`O&fuHOLGNEdtpd*lJ<Na*%Ki9i}zJ6ir;l*At4RD{Qa$_!aFybd~GM01D<q!sxD@ zfyEu%$0LTno(o#Il6!|&{7hvZxe;zOi~pL~8}xp^uh0yh%{iRxN;>dfvncDOdt8u? z#=r-l4`-amM5v7SQ%C4o5B_+lN)@@>d<ZKQ2M8w&pCSRlo7?4+u3FnD{-y6fhV?d_ zhru5Kz^3oqI4c5%b>oc(On?<l8v0R0-sL~KQ}CT4dAv+CC|3UM`Ru9@h0ppK1{b!n zyrQc_8=ivE$^7i4u_^?S0f_PlS(Lm?k!Gs5@QrmLUE=|lf*qGpU+2ylqTVGp0g86s zogo`Uhx?~Ob|FG4l{Ma(@fu}(q2!?ot0=p)!t*X}OIc=0?LJ;}IZc56u*QT+0^7&c z4g=S!Q1Q?#d5w~~t3Of};Gx#18Ri#B!Ip|cfjE^Ixl;Ys!aNR9v$4j>WwZ8=08q6a zBuk74ECqKssw?<lj{qLau1Te^vSb{p;@nnEQ$5Mg+eS%N^xk13Un9zu*}r8oT}(Rh zVBsn9u7#<Z&`LV$=YQ_PKWq`os&Kb@J_O%Q;5x4|FsI8aMFM1mC_Nw~HG!>B56bl= z4B*)GL2)4^j;%Hr_b4!9S03{GT);98erN#gy$)d4>B67g9?XuMsC@&S=6b^Vf`2y_ zS*-SppW#FHy-!eKJyfY`@O%6!Qm(iU_pr)5vB^G{SZ18=m1IB`P1A2G%9YFzE|)8F z>6p41;>--ti2)yTwy-F^^f}pOOVmD;c#Fs}O(Cx`ozrNGm0&tLb-`^tDb%X8Z?7uZ zK}vbwve=2~`@x$1Qhq#^^{2va5>h{lu`Qf=_H_GeVH)6{KQwc3|L%vvme?ZP+dc^5 zqX0u$n3R{V6VjLjb*H(`DArG@8(vtxY`MUc46=ngl@w#d#8|{y9xC9El4xACz5MA& z#CZpd<T%M)<(qe=;v4}YHKr~15S8uJvTl68QM?EXx~`Mh#MQ><C9l-qm;?7Ie4q}C zy~93dFQ(YtJQUp=daS4HMXXvcxQ{KPUi^)>B)pq)*jN9Y*n@HV-bkx4S@&3rPae$( zVdp6)0IO8G1pq0v*h+seV3`L3#E9WJtIbqNvM7Mzx_l3v5r@ojG(&qP)O{`z(*e39 zAT8O(x@FcWepMuqK8OnH+m=*{SHkLkc9TnKhbesn9bpjscKz0eW`9x&wKQ{(7-M8B zfA1G_WMn9GPc`W5)WnkxI4H;~WjFjak^txf6>d{3i58=TGJv7%QB(Bp#dVjTi+H6) zNrm*YDOzbhGck?DrYs2YQd&<dd2i{|z*1R4RAR$<KX6o*xvsW(;4Yceh>ICyn9Z4y z0STd2yhiN>wa1u7moohsJN4hmOEAV6iz4>=-G}g^#ZFENiXoc^6|EFH=av>!a{2HZ zh*5uE=8yAYS8fNX!Kk(-zC{v^HxR-e(a5wGl-3oI0+C~>5VR!Lz+|#YG)S6-4H7h5 zu6j(hk{ytH+n(9A9mgEr7tItI;AhzZp%RUBwgz{Is}#K?4w+*qKI`LHtt^QgXWT&W zri9Gb`%pppLww)mFGDMqul^Oh^QUAszQ_I%2xWzOy<PuZVJ2@0hsgs;asQc&4mBp0 z9rc}qo1Z;%L2dMn%h6Xgc<o7QFFSJ}uX3BC-v0cJ?w)VXQ4f2e5=wP`Q~nA{_F}I- z8LR3w^rt1R9~F#0*>C9FPdwTIYLM>&Ir(LO3txU!W~KUJ<@e~nK<M35WAYWzyEgQ5 z2W8|7r*~MU%zF)xnDbyIeKmzth!3d3Od2d^nNOjyb<8p*pMj+NK==iQOoN6MHzObD zmkeM?w1Br2Qpvs5Y;zK)LqpDd0qjV?C*rLY(?#|bouAD`o^rt%7iTY^uCuiU%6Zm4 zF_coq9nJu;bE>s$?9S(fR-K7b^RL9S_mSVR5SuvUve-?n9b<hTSewUM&B+dpL54S8 zWk+X!EV{W~ZC={WE=V<gQq@_G*t6h;OkkE(`P^%0NB)-81W3%XfZp;cMnfv#%|@j+ zDvBZXw;_OUkG*8}?h|8Rb=zIJ&w7m4bw0P>vDo?M^uanbq%yBtl2mao#zbiy)0xyg zbRDe1leRE}Oe#Zkw;+b);E*|%E}!jCkqNQL*i$aF%Rb*Cnq#dGHleCINUKrS$=mN% z`<24)NH!K!PeFXi18g>GHydTaV4L&${csmF;*B&^&X)6yMyg1Sz@Q{k)VOwcP@G+9 zIqvsX14*A-UT*iP+T7BY7yHX@b8S!&aqlan_wv3r%Km%h(f6t}LHK}kt=KMaquqaV zE!=&x{|S$OFe?u%7R~Eu`k^%3$$(hX*^)hgB9#?()JmQJ(Nl&Jy^wcS+25<!HU#uL zGfu28)Co~A$3Uz6x)Pp1oWnxTunQ<$_O^L*>WuKe?DIWKSKPesuqdsqgi_UHil%q= zof)QCf;5!Vu9@s)mMQ_^jC!+jtgeshe>AE<m>b4s7eg2(D;8^D#<m(_tT64SN%f$` zH$*8<A&$&05)8V3z4+BaugvzILC>V-mhok9Q<<&3!wj{QvFBoR?}t<iA0H$SJ?=~x zmn?*9n_bqHt~pynT3@)6nWkenwu^62x_j#;iPF44(Xu6RDhOt*Fg$6E9d1VO5nM^7 z<oog=d^h|Yt!Jjm!xjs@!w@<AP5e}vjIu^6CS;&39%)|A<~Fl6dg^tiz*+;=i%CX- z27M+0kP~y1w0Pvwd8ExPS3r8O0%1&+qlJRp`r~i@7tLk1AU<e~4f#$IcnU;8SqZjw zEPm`9sdpj|X~k#NoCH1Kpnitc9<R#ARqUxqwE!Aaw&$Swu9LlB5(9$BYVNa`f00wT zztFI=!TP@*cyWV?rKcIGRDb=VItgNJ#?o3<zb);$q20QG&r?+*-62DL7%m!B=Ubim zk2_RVG;~hS2=9PK$pnL|(KF^WVak>XUrA!taKIaMT}|gv14;hdN`cIvmhaqo?yU9k zlG5B<RQ~zwzjK~DQc~;xJU{3U?l~#Cd&Sj6J7-F%F8ajHGQQosvs)>Hhj_2dO_-G7 z8JF=V<$ER#Y}p=Km%cYKYak5%??%2MvnohsD(_wcjX}MAu8h_sb;tfkLYLg*oOJH) zeq$Pd7}g8gl@m7lt%bcil{Fi}dMW3`%AMV==FO<Y+|e7(CDe+{(M$t+3~!s^XN!t# z=y}jepGI!A#X5V31M9N@(xcy+iL;KY6H%>2ZeA$3w`FpZ=2{s&`YW&0EO+$3TGxto z&(f*;8KpS|l$#ZT(Q?GavUcCnou3Y`2Cf74_>ORCR<N>#T-uk7Y6Q!hJvLxSew*cO z-g1*{M^Z|VfqvPz2$dNqK&?dnuF3xQTTe>W8PvB&4m00st503ux%5Fs__0kAT)%RN z*3vVl9?vJb5i5A!msaN2cm;-!*<JxUKI=2(W8M^?1)@3Il7YG-1G5Mi@j|elG(e>i z481{4Yvs=t2KRl{c0%l9$Am++tpj$raM>E#xy)g+3hB8reRk94z_$imhWpjL4*5y4 zoi^6?7lTzCcek8=6LMgxngsrMl13CPAhNM8_iIX1skWVsC0&h46-;43s+`UgQIPuW zVsUi}m^PlSVxac#cCRkYzOv3`$^>6Elm5EYdw<w<Jn*typ~P|R;R_3URV!vm-ju_b zS^e*hx3QdC>;BCOPrOJFA8FX0h57mWi%oBw<?RUgXIkqRr(>n4yE>y^=W_b0BnA$R z|B?@ApuMm-F9MY2I6iPHmXplZkvv`N`=Pw%tp3X{Cp(|KpOX=AtD2c8^Lt;l_AE|g zeH7Ssy>8!ofeM6I<wfMSQ)j_N7~_g1YJ2&A0C+%$zg7JU$pZ+0U_jmtF<QkuR_7hy z#gX11wK&>Kl?wbuyJcURxLze0+b8A8mLMpFODzF{1$USOB;txWFd!$|gFxYf*F(a5 zO%c8gSld&HK9z|n{9i!LmHTuYd5oMwrIE*#3F0F@jcU})F}|YkT+hAOmC9I(fZ&W3 zWW^kiNjv0CD~XY?1zWhxl;B`OdVzA$9Y$u=mjya1&@>k5T}LX45rIUR$kmpx7ynAl zOMHqFh=+b4RvZ@AgV}~6=u4VVR>O76+biQI1j|zqOCub|)QZ!4z24%y+H1v&Iq0Qi zXa^;(-c-?>Goy~bpuN%yWB;<W--B8x{GE=%MT`2Z&&1Ugc@&HMjEOw+6?+szMV$$T z1pqT_5BPXgJ$6HtFwiq{V2hojKbDrz{RkhhBS}+a0KfwW0i+VdkeC<=4bdIlVSx*% z0TvhoDu`LF;9Z)4B#yk*75y(v(nJIZ08sdzR_2O)(1(7Q13~6EHoiC@mcrdb&pVC1 zYF^jW0>}Ej4kdocnO<TdW>=XAGivT>Ue*ei9^%=1TB#^p!>!Np&^T~biG!tyJfjh) z&`b7U7(9*%lN+?YG|+z(%z|*>nb5A7*kPF%5Z6Iuo<j+t6X-EuRh<I5_>yFWZe%K$ zFZGIO001h^ya`Z?iT|bBiQdiGmbmDaus@k#Q5Wsi{WF1sVdaqKiflN784=K#5Q{;b zPb)NP+Z$?q)!QZ{6|u}-V7^;w<qLep-s_#|X4d7;{^_#hiiO(jtvKU=H4FK4nD4Mp zd356z@y{<<7~tk%rUFd+aNvB_=Y5Wl9fr)7NQso#44Xn|m_R?-Rp<^KgBQ2}5C(uu zHsPDV37k;Gb@>4JTVbex9#Jmr6r~Bper)%Si5Ds9Se9h~=z_(qGdErX%tqsh+uQuD z-l^T?aHOp!JmS$daJ*3My!qt>N3#LvilDX*+UBk4fHOc<YTb^<jhl`{y-UdjZV(5H zcGgFkkdJsa7XN{e3FAKQu#O5y^JfY97778n8qgg8D7xYSIt{60SJe;`u7OO>>zP1A zMFfDQ>kv-%-RVH=83wTTesY?~hgVii={oV}&F?iX>OOVp2?xu(1#Pi>aH@rAa0GME zW>+&$k$oLwY>sU*-jHeKqVEu3E%f0#V_ZTlu0$=0-wyHR0+x2(oX&aFnAqx=Aa0fe zYppnGnqY33z^Npwfjmmtt<VtS$z=CSBu7jEja--Bz1gC=)%4y~)I_yl{b(q6k%5^5 zk0=%^SD&$PoGgbZay-v2cTzJ4?duTmTwlUm@0+N&U)obMTVF?9)~&VF3dF^2r*>mp zQCvHlod29C=k@S&M&+nHrfd?Y3C<0vJ|3y*Yw=5E^qF`aN1q7}-YMNF7fFT*;b8#~ zm1Lpf?iax8!G^>UApu5giFXm~-_5TSP47uOHB)EJBRH5;kBWWR2Y>JfVkH75s4g}9 zikwg%XLp!o*S%ynV~)>>*ZcT1AJ1Qp@LzXAu^i)EPWjD_ZO&d5R=IUDp7q6PcHX9Q zrKQW_QrI32@oOLPY=`HQljUMLqm~2rq9Ejq-C;v+3DnJro%)@0SBVg|^j4*b3y5ec zpn?m)2@-e!79fEJXaI~1&6WW5@G0f?hEbKUIsh2SgfEJQUv)^MHO&EwFXS`Gv1~0I z5C6m!V(j2@T*i@)kHwe{%aPaD3Jmj8v8}R9sM#WR%{I>~V#}kxa9U?$XLn=spk<1R zV?^c8oY1Ia?fI*Q*c2%=Ii!ixVJSzG3QDukOH&C*b_uE1WSTfcpke_JrGn(afTkmX z5<pP^Fz=ZliU&9<P}Yk6!oMbGP0@dQsF3nV0{|zG<u0&GUO9ujk9CbZoN1+AqyBF* zwynYccmNOc#MgCF`3u-1$MQFSVR!Su0sN*~DBaqvetC9h2QFo`Gk_oiU?9PPWW*dK z^96vIf({=N%ra0S#EK4~RBXb8$&w`ll_+s|<Ve9H15FMjLL{Y1ivW7yfH@Ec0RJ2~ zYTP9F0>GG_V_4{9v9lnR8Yu`;8Dj!KiU}V|3@q{BK|u``EIgd>kgCgq2nZG^&~+?X zvIP*313=GT*|u)qlKq!&9{@c7nA{!s1VER*4Go$hV`gv~0BQiNaR{f4;(>4;$^jr} z&g98+E@QS>2SA<9n>{<cT<7w@IiX7fz^vNzL)MWUzD{isj-1Di;o#0~yCUv~i3h4V zY}jz{G=&Qu2VlnKUon3lepv{SA^_@dF=ia-kzhyw-3g8)S!De9mIYS=@S(mU&Gt9n zLwwP*Mh&13$GpHpWhj88OaWLh!BPNh@PPsrYybcT7HL%wR|P3hPyz&fHUCgpaA8;$ zV;OSTAzAzElTSYM0Kg7O1KAP_I%oiJ1pv}HM}~}o4F{ZX1GSMGM6pQ*TWXj^#u|sJ zbtUAFtC2=fWs<pOQDn8%20(AO={DtCH`-{NmT3@H*m7+>m!Wk9N#UYJ7(s!N6Am@e z)kp-PL>_r6p$7mFK?GruOf%VpQw<RP`9ck2P=Uul{0&3}06<Y;pMOkY@PG*)0Pw*F z7ASy$RbxHSz=H%uC?SOvUg)8z2Mi=nJ*KkSDgYoBL{BOebumzMU&JWmU|0&bA!Cp2 z)|MQ@Qud^2$G%0RTc%Y8B(nqY2pL4dDput~)DrX?M28iohL&F@2mcX5<2Dqghhq+O z1$GrVvF4f<eb-$`-yKmzy>k|!5=sE%Igk$y#Z;4f@B#3rPA>?$C{Kirae;joT!6<N zw%AevRQ)wNkOd8xkRSjWkkCK_8e|30r(}^@s;d|x5CAH4{j;*n9MVN1L9wK03pxXp zArY=!IEN5m;i~al8%O8Z6_m6M+q7h_QD%{l$d;xow8t(9wXw}sHtdej(q<dBvpFW^ z*uHJc?Uu&{CQwD=D)ge<4oN2+L0mj!CP7jFz_(lPy7e7+C*_;3odfl2QF}EBOfY@) z37RlL_VwgY3NP$O#RVp$a6t;6o3PZ#1QMh{s3kk-Py?qAl>a~i6{b8hhbhqW4?eQv z{vllhkqFN^0~s0%0Ji)Q2HsqV@kJN73Jrij%MpzuV@W%-A#7ns3+>iSQr7*}-uJlV z(@i5={*z6kucVag_sF6354~T|jmK?i2A6|5KbGAtDZfA7Zb`v!8EIF$@<JAn6r^4N z7|#M1NT-yfCr|$ZSWIkUL7NQZaT=@v!a4{5gxLoG`gy@oSa1{*K*e)M=}!ut(f|y6 zKm#(AVW$>EkO?$sAe|b^gaGiBl!+yGZ8?AdTrrS*2r-E+*&RXFkuw0G!xjMegA}j; z050?;I?l<TVC<I$EUh7oN2}hn9uuXrRU~RYN{!Q?_5YS9jc-_ClTu{FhM~t;Z;Uu{ zi?;yqt+oloZ3RilbM{BKzBuH61ksyAu23cc5@cNiAz+&dQb{*~$6otl2}<syo=^55 zl%agd1xrbvf^86C97Ncnb~2QrNDL?}xByd7C_;)+feIVgz*J&5LkpO0AUVt-08TcL z1~{aL2moRbmFN;w9ibn$b0#$%QnP`$qaDKo0M5|iHz{O6BFodFLj>tZ;uI~60Ei!N zbOWXKy@p!ZD@YqL#3MP@279-G%Wm{YkoRFpepoV&9|vR5avB68hNRov%3>x*I<g>W zBFMWaNf0J9AqoK44oJE~l8~IJBn(^$o#+&VPyeb%l%cF(Dc^I-3_^~BA9N)|XbH<Z z0Hp+*OF=I0aECDf;Q|}jm@hSe0SiRxKsYQWL5z7!f=p;aKV)V#Eg}E}l;en1-Ks;{ z@w=N11PfKXA{Lp~kb?l=3~K#iaEg}BHB4`v1fiC-=7~P9$+2v&x$8X30!KIIbB;RF z5M0&}P%RmTOT_u(8PbYSac$97(Roo96j>d-Q3PF!OxHsonWi*Za-*Wvjz{K&K#(?Y zfpQ{3zV4(FJb_Y_FCisNO6d@T$<%{Ffe6ELSp)qPN~aQwB2O7`Oay7_s7O`70|GRG z2kj6-$b^XNxJs4@nbW#kRfj{Oh>mqxQU4-b7%z;Pmp?DEwXI#L(v;ZiUSKf|pV-r9 zS!gq@^}W|hbKT8i*tt%Bs<SM?A;@w7nceJ?WufDJ2z9IjQ8Gb<fPgE=M)Fcx?|>vc z8Xm~K%2U!i!8W!lt*vco!nlgi^iaFq$x-kiF+2!0DTUf)Pw(K6sVEmfR}mQwr!tl4 zo{V+X^<jkoZ~&EQcOU{NfI0fHmLylxX1{X>LGloVCSb&oSP18Mxv;--Dd%}>Q}2NP zi?nrGE5GjzY<|sVHfy~FzWGHOZsICexxO#Jh|%*oky9As7}UUmbX!6e3Z2Pv2%?Y# zz`7)CQ2;cdO&-AuUc6&zC1^N2<NxV!;XaI~lcrRqEw$jEa1tMxs<<L7Xq1c>Wig?a zAO)``kjI|7psN4~019}nkEiRFB8vsd+C4x3HUof|L7AGXDo85O5QQjU6tq{E_O!D= z-df@6Au<|>mdc#Yf*|e8Z&ovW$4zdTkvlhx(UzSHqOFIN`62aF?2PJ7NOKzciiTcr zK^R$<MpM)wmFCF6J2Kh~YgkSuG0BHti&7tqa>S#CkHK8BlMp&YDE`qL=LT}Zi(RaA zBD*zKs1hNncuHgiSsir;0_?B|o2#fI0Xw9b>?E7RBubdH6S7>UX)o9>%{fS8*V@*@ z943s32{2s4y_l!>=Dlw=xBr^UW-8tMDo0umx4ZdxhA$$vMg(>28OTuf8Rd^T46zkK zYE>(^MD!t0@Ed493xFrIDbg41NNJaFgpOi5(+%7gNehQ3e}#IsJs{-;XHxOoW^f=F zhe!x75OSz2CFE66kgju05KJ|I*CHFeMOcRbRNXw80hoo8`;q!;x_;TNr~#%!g5^b0 zyC83`2>z7g5aA$Q>2Pg&xR0i8D!G^HQb(hPxL*9D4S(r2iZ?{YP7p5*<e-B_yU^m+ zQ0Q31vJrvEL&?&FcI92~8rcZn0bl#ThX(-SVc_9N`dUy!e1bC}@#0Kfk;m)AqD-C% zDNI2ONazd%rR);vEdK}wIH1U21psJ;R!oSe0Kn*pi~{)DKqx?{6d3@(Tr(xvSFnJH zAkph>6<f#y-yjgA6;O*%TR2_O?hyo9C6pI&TY4ScTZz&0J)gSeh>plv)UlV<nOPp` zM)kx`@d@7!4%lG@ltWmbwgu9?nbpcLQWkQSMZ8O-rQb$y1m7(I;Bi>|y@|a%L`#$u z{z2S8EM5iiU%~Xr|2>3#Ad2J_AVCZW03hH%6vzkc(gu(WQt_b%Ak%X-NCWiH1u`Pb zbzleTT7*ayScKrs2|xm5gOec}3RV+a0Khi*fX+=)0R>R*>5cfMT@7BJ9}$!es@Fgy zhObPI59$#u9{(XN`j@FV;VzCH^@Yn=%t#sJPtaJzLKvE6wMgEi%c3osnoyD#dLjGq z-ABj^{Jn|%nZ${-mKyR4N-dr!HJ*vp1OOHUs@<W&OrGU<+(3{32_zsv?2-*73KgIL z5C8!RU`2yGz#<aF>Of-WbzpV9T+AgI^Kqi=<byvbq$ff|n>axL{akfOr1+W34ffuc z?I1x!VH?Dv^Ub1}Ne?bMUsotyw!qsi?%>*-)0SAomy{DiltIu$*7w~FU(ldS_}en( zWP~{yG=iZR8XR|gL;{^eNuWpJ*a>W<hf38}<D3{xkmCmdpirda<P<~-bQ~X6gvTVv zf=mDk<o{9%SO7m#MFKEaKStssMu-9o870Ep>kY*T9;6VFi0ci+KiJHPoJghh97LLl z3`!P3NQVtRM3=11FUk)@#3H!)p!D2gW1iW&bsaj@h(ImYVFFrXDThn;o+>8PK@cM` z7ULC#UqK+_gFzDCd{&zDq)$pCL2L(xS=!)`#J!~9HcF6)t<;GXgiE1V9bQ}=s^d|t zkUIi^agq$@-4Fv%flt|(59QE4vW^C-<v+SyLA>SbAwV?DWi_3kKInr#*bY&C$N9}& zM2_E!7#d*~M4%zopK+T*ES)+fhH#Xm@JVJ!u2b~kCt}=)Ivw3`L?LD7;Clj^LEVq@ zp#L3$F@!(_4Wd;<zL6$r^4k__VKc6#qoJP{!sax_=1|g0y@b?x=nHGzNqTrAI5Lhn zW)Q)Qg)32|a1zAl5a%9NN`fS(a^8>*afKp6NT{$JKn5fLC=+%Pq;`>kU3O>gEE_(6 z2zV+aKJ-I8KmiV*#Lht)mYt`+DH5U?QkdA=K_!Pv#wXfn<SzDS*VQLVK4Dk16=F)^ z9|fAAZCgU6B17EDt*}ZsSrN76-rjsu->fDSXlNzr-9S_tyv$2crWWDRNf88r!^PH1 zd?SlKgryct0Dh2+F3Jjp5OEHKEp1*wM4$vdgvX!?ReYdB1Y}#fr3j8-0DOQvDF5k_ z;!Zz+$Upo;KiH)|+)gzdPBwakd7dXkC=x~1AVSz%y^$%Ly6N;0M@6t{fL3O;TB}PO z6rC=sy_JiDO4ei<V<J`PSYSc9lHcC+4MYwqp`xD?<Xx6VS{Sw;cf^ZJY@_|X77^&? z;#ovgmLq>4N^nlj3WX|G5^O<GN=4Yv1e7WYkiZ>K!97OeB5oiDD$}YSsmv8X0xW}8 z*{bZo3IK>mK`7)v*hLxM#S&cE6U^Nf7DR=989~6!wr(4GRi8@MNJdiM?@b?>9UW#S z#}rlsph3j8Dl54>s4?a#xJu}RHc}Sq4c|NxL`uQBYAC#3(llb2;0z9j(f{AR+$)HE z+P-2cLHM6VB+NMq=ci^RMAVu~JOBes00V%f1d;#>aNtw1DqFhFGQBDaPDmX%*))AD z$R5!Nf(S#hgAd?9o$Oo`JVE4Q1m7?cMWCW!%H+(JQy^`o6c$wWT_4USrW5)ZX3i=8 zfD79kltYlIwi!hCnN{*E?b6;&(<)=XnaR}ZZq*Jd0Rg~<5=7S0D@3#)HmVi_d6>R@ z+DV;M4iE&t&ICmGCLJD3TNtb!I>g&*ipls?3fLnMOpH%i0N$b{g!Jt)9RR9SqIL!V z4#Wch5N_eFOh4#qSCGgnu)v9S=*spbgDKSaX;IK5#IkmU&;l)n0RQb_l4<Mu9$A2C zdCBhV&Tf}cFj+aRX_hM%Ok27rnj=vy?|xR#xvRUZ$-Bbl2^WNE$zS{_+-fQB@}d-_ zj)hB=ZJ->=rcxe6fNDihN{%`pL}&oSMr?rG!S~Xmt|8L~vZVqn)9G1A##+~r2>^G> zuQQ2A$cAh`=mQzN00Zge5=3s#^$ln3WKDi+?7~g=Swwc7E=xMAON^bIW@~|c3EHi( z%vxbVNbnx_1qJ(YH~}(6_^ICbsb5m<x)SR7Nf<QVMH6^v3a{|rS)+)yu%|6=4tx?p z<iH!k1oU!9ie+3LdfdSlgmF5AQEdeZe1K2cBLfhC!+tLcX#Zf|t|gJajuRhQc5-4S zs6`bEQOG`oKF9?Cm;(l_L~ZUIMk#W?ZB|8)*V2|tjHq!}7!;w+X#<l50~eTrE^FIV z#Gs8uL+tU=Ru&eKl^=6~wFPn(P+PhBDGYkB2dgXZGMY2?<UmwXg|(mibyRI893{K3 ziR$l3^}u?xg`fPN<a9+<u4AaeMX3geJw{3~JwQDI0as{X0}ucKtmXNpZ~Crp>V1U| z(63zjGBt(lKd{9tu)x0@^GGD~B>iqhu(N6UG40B(Xu=Iy5b&LH$hOh!f^xGU!ERaT zsh;}r-K6t61M(od^B^nQ2ZJzc7OGFKA5ijhKU-r9&;Loot;ECWpButqZyHQa+*aBa z1Vfw9<n3_gA*@6E@U0cZQUQQ*S)dMGpa!A<27o0B8~_1$boxFqtU?*FH2^!nuSuUY zO7DY0>H`1(LQ6*~dPuS|yUQ3i^F$0pQhS-*<S9c`<Q)&Sg02iu2etEbtMe>GWI-tS ziEC0%=u$IvO+$4d%d@&#t%kZQG+wnBW;McT+DLHqhZO`HriVjx@<aHm*)DX(k@7=8 zh2{-}50|Rv5tFAF6U(7MJzBIq4gisTwE7Y@lofygpu$})Hdoa{Jv=Es*8uabFi6Da zCEe~s05Upv_EB5J7VWfY1GP`TMId!w8WU2CT>s(PamfGRw`DQ))7rM~rYj=r_WAL) zyzcXFNAeji9Emm@;{A&!&sK;-UJavlD3itYYNh7&a9PlGQ>`2$zA_3-NIg!B0i0fV zk9X=Rfs-kAdT*6JAdxxnYfIQmM}gr?pX(y6Gk%9_zP0vQq4vEE1ej6z+J&}gj|*ta zB<(US|2T7($)H3u7&5~1v_UxC^{#I3wrc|A7-lt5rj|o^HF{+7OXPs_Mz4rVFNy)6 zz&bZuXQf+P1j)#w=b5UDKSYoMKs^qGJx&Y?7{EvC@<G<z?QEitR}*-GClb9v3b-_R zyvY&Fw;0#+X8GxoqqDx*?%D;g02eiwT>rVaFzq<kjh?FK<!&~Zhq-l7$3xZj)LsOd zgm7!RrZiqSKVM@}ZW2p)wZ9y<;_>GHL8ZmThYqjxjJ7RABy8#YFhoRWMa(im*yBKK zH!Gt+00=-XTgY6xUXNqCGXXOa34*8lz)Eb|H7>!SGTJ~$QklC5s-vQ<N2p*jPwwO? zYoGD#24-1^`D~x-1{d-emm+r9T|KM$ny=q$Zj@<}Az3UtNfCtp=HK&<7={dm+BWx6 z9ITBVrvg4ip_?i(;WevnU;;3@k)cWe+~bl>`n&tQtAwnGJT?HxLwEQ<5P&*NFF}Pd z!GyJJ-_&-s0rCawv3eSs!fzF=-~URNxrBI0<ZRP+nRBq2i&fm!GYFTun!Bb(Y!pz+ zCN*+c0@0sQn#cWh<5J3&r~!&u_p3v^fGm*(%SXjq*P0A5h{>?3LlD5C-{W?_4&z5U z6#x9>n+k}Kh>-uu(MPJioCuaKJw^2#c9dcjLG{#6Bt(o;YfG?pEiHaqgqYiRb(nr; zQ`^s#3A&E)YSuHmPPk9r#gUH|h`znYKTw?z#Cm+VsEv}ey9LTy1j{dlak?WQ7QT*F zw^JoL>k#RpqkwbXL8NcDk{u-K0YI%%ezJ8srRqyIBC}{2DzT>P&$-ATPd)78I$zi% zUwn2o;f-_v1Q!5Y1QIkzaQ|S!fmr}B1kf-`#E1Z}M7(kZ%fpKsuSn_m5P+12P)L#l zNzzG5l};Wuap{r?lO+I{fSd_H2~LnlKmy=d<Vca8J&6n@5+uk_kUg08z~NMBRH;)R zvgpYo1=gV^QuHiA6@Uf+7(iNhI03+eo(~#GZQD};0Rkw106}rbmR$pMQ3w!l0Bm5v zg8?7_Ac$~c#fup?R-7;2LqI8*`XF-op-_-HLB4cS5=zLB95;fLC^7IsfdIbr{L)(S z>(&KV6IN~TH0p<0NOJ^mQFKS)9z`k*9U1`2lucANX*sm!!<kEN=H#q|^UjAq2_uc# z^eGPULvhr=5%|T`7yniPum@|x1jw&LKLFU!Q>;|9j^iHKdj~+h3^1Us0R95Zu>_+^ zVV{2RQ4qoiB~<XAeEOkhiSz*I!7?H=Q|hLcJ}XHyjXWxiDu-$V$smQmYH>mq51J@9 zhEDsfHyleNt|KXYe5kk|qgrXDmt3Ohq3CQ1aj5K+`tYHmqDo3CA2wWSJgLr$>V+CK z9Ev^n+M_Bys_uJ8EV7hBYrluoN-O~a06>ARJAkkgg#imhFh<7&XuzC)`W%$dLLt+K zo_^RVZ$l0{oGK>IQW~kakbFc@DTi1b=r)83eF(<g2&$1(iGaJ}HywLJbu{9B3^F<7 zdSZ!4l>l(=x&N7z1b{lJtm_FV0H6%a2P+>k7Cfh*+VUZ0(c>~IF(2ZpOs}X)v#0$g zXw%KNhVr(j1PTM-009C35WoNqDBys)1|&d$PYDCel7}Lb7vFpZgX~a5`<cZA@ti6a zGhw$=$|WL^lL87Ke`K|%i%vroVu&>5G(t~7rLojfSIzNMihpxh$X7``>7hw!?TqE9 zdW{M@ogBN2N&t#oiYaE#a~6Oa0`plt_oS6}+OEJl6C^d2df?5qzEuER02B}xBykTo zfGz+GD7UVz@4RC`KJ`_q4gek;8|}2C`lmvC`f(%$fh#MjD4wE<G~twEZP?)w1B3Vq z8kJg+vHy-cmiXhueH)JCzK4<(0G0$hGNzuGgjr_oqAFro0E())r>1hw`6;S^R_gSg z)@x5p_KXG~g=#?}0i^l_<F@I=6nH2Bsu8%FuHGN2D?mDd2w-cm#}>CzwVfZE-{{?@ z=ZLQ4wz8<sZNl5Rlt3e?`NS}l2#bmnGrUH{)xU_xOB-(-Ig@&V!q&(q?F`o>o17}< zp@Nl4N>l1dv5+M?fdL>(2<(~Zx-^w9RV6F0gB|RuCA*=BB~50D3b()#wW&SCFjqrR z0q8_0t>J}ub^?L`;HA8=kw6{~@yGLMD6i;2rXD%$hdF%ECGqe~DF3tE5~A}G`;Dk1 z;r~ljPhdrwB~FD^7jp<|Otq@000&1JDUHZn)gzI-?|UXONv-NP6qxKvI!eh-|1{?l z|7kBOH<OC8cBVj(q^>7k!ee_hWR(ZDM}i=c;CyH&6%1HFg8)e6U>X3msTc+%fEj=Q z_5u<EpervW+*8^NGXZnd5S04jR}S^zHe76=2C0;rcYtLb>?nacM105-0PqCnsN{Q8 z@d%Di<V40KPJ9)^qEg;RvM`pUNJWAa8U@2frP$3VgfZ4bdeE$D{%}0b;u(5ausWp# zk}$UG30V@kNJj4Nkq;3exd2dr0crAUd9h2^0^qy{lp~b+#8>q6(a(Myq69uO5C2p= zSFp|C1Us<|(Jd7=5+GFya3o`2js!z7ii$5)6CD{yiV41B(vOVIF%spR6BC(Ojw-KA zjP?Q;nD8{~hYGCY9s%&j1jWv1@hKz#XjdPkDRL<0>`4Q1Cz#%a@M`2Lz)}m~7dipR z7U;4Qp0<Xz0zAYOg3{+!2gNq8{zD)C=!YD{lFBPRBnX%h$`ROlgjd2cjkl7N{pcq@ zAaS&DJsM6%|K`MDDn(?h5{_tuBo&g41T-OC&MilJMw%!Tp<sb#Pl7U8qQLQUU?C{! zq(alv{c$}uy^2z}a<mHqH9?M4intH}$)sM5sY|6KUAkrqbkv1T1ELz*%Krv{dvO)G z5#m=r|KYZNkl_Pn-IAk*!jrbL@g}-5QgfsNnqnT7FvFqP7YR#Pz!~<gc+KVB>Pp6z zG}fdtA)-R5^VXik%t;3W3ue)(+2vvrfmvcyXS?*k(8j2c8_)pK^0UFTd@CxARLTci ztIl=CcBxt;(D52zTe=v?KQ1hkVcOu^vjrE#3c6uF5+$sFs<L!8^IT?x)mFC-C6?SX zqU53yMwIytERAbS^L*5>Tps6S$x*D4<VutD_KLkrfTc>|iyg}f#zRs`3h0itl+eKx zn_DW+HXqW!#=H)vgDLQ*6j0`)j*Cz0f-t%K^V9%^jh$(;l2$`pXaC2H_#cU4M-5D% zM`q<9N|)gr=PGO2gz_rA`D58iethG=yl*igSr~aqbWFvHbfh(@oK)KTR!=**jgDa@ zRhUA}p2T#^2&8Gxyi66MW#yYw+38OoqBPV_-~nxVQ`8>fK>!@JwZCICgqhk-av2~1 z0k~6c)v2}zu%jOIu=BJT^VP2=Dja-n;2zWJp+N^LC(v{&EMv?BMR&%$-h*6VKocQL zUz$inZfq0M%PSaX?mA9(@xI*%K!YhoO4HPARL)}_^Kki7;G7)*d^%30B$9({iHd4L zV&(({d!0%pc2cj3AirQ(!=D071GWK@e^49ci5W480YHu#r2pW7bp$}S1)Z5EyOP{Q zWTsphN-G*8cHNH)a)OitZ<RS=-kpibdf6M<&3sx3&fPa#fih@-`@6nZ9yob+mO#OD zlW08wC$)NFL8)i}?b$jD2Z=gy1;gdnziw^Di5=T^UX@$}XtvtQrGRYEIpu+$3S{hc zL$+ZXD|!T)vgBw`U>(erkbT*$%stXFf<<yfiX2#iE)`of2kG;ccT1v^<X$<`jjxot zb6Z^XZ@+#jnH4x#&Qr~)?3YVk`tn1%LM;i(F2Eqc;8^tYt)fcpA?SpAVdl<GKCRi< zcz6EvhZ1rK6#xMNK!u?EadN?bpDK9Hb3dYyl`nA_DgTcDH)TIP#G6!}$cfQBjcc`e z`+0t4JQw{Lqf?U*O@~*YPNi^S>RhbqfaUc#=Q7lfm3*LPX3x~D%=SP+<`AyGlmhIg zLMyfc07}bRc!~tX2|t1gERL^{d`<ZrOylZK`nC%D0w4`!2>fO+Frw%1`T-RtpqnVr z%526;sKlU#W!yZ?{dA5=b`F1zMDu3lh%)c;dcrx5WZpE*q?j(2mPCyN&`GB50G}k# z77z^SX6A-Mj>w~$&QK`|4&iEw4Q<Ms7UTDZA_VPY1c?tMa7QpsP%vJL1tSc&Ua&Qa ziv|aA@J1|AAi)A&KoL(ZJetA*3+6+DW$N5(N&h5INlFSyq++C?aQ~w4NDwB|Ov=bi zk5{gce?E<^D9a~OvEKqC437dSf<WNP(3%?YtR_&Vc#yvqF+t!X%sQ|qNT8?aa42kz zgN8!lltK@euP1(Ig!&M~3?nBT#QO-*8bM;^@IkERK!X-Bb)KR!AP@mvEYv9Ra+2f{ z6|E-XPya;kIgISQ&~fQZkG<jxb95r=R?o76XfZw~776HP#IX@^QA<`$pcD}y`{)ga z0@h#+EJ}co8UxpmF~OuF1=)<_Sn%$m!urPM*)HT7LlPUa5divu8@ufM4$cv+1OkJo z&{(nGh%j@cqW^lL-q6v=(yMZI1pw!f9{){I$@=G4?2!_ii|W>oF{C6Z0MZ9U=Smte z#R$$k7Km9=DV6%mOA^v5c5qC<q#+s7g64y#7)~j~Vv&w<E!u7<pyndWtjs_{*gygr zr=la{tS%cv0k8o8q)jCIvhest5KU4CYl;{1>!qrRB|*pA2n{Is%_j!%6zz@ECa)5a z%-#Ud{oaZ)^9?fhM=)IP+ZtokZbo!UjgBBhj}lTVMJq5$Ymg$cKE^C8sN(nz%q<oy z`B<wb`mhB#vW66Z8Xlq={W2s8FEa9B{Q7|l)FeH=<ltnk)Ud~YgvIKN5}NFhf22e5 zlB^UdQ#+rI$$q6tWO5asY$v)9B>!M<FbYN-%@8WrkT8J8zrc<K!VW7okoThEE5!2b z9zv)}aKYX#Duib@dDGaa;x6x!F@SR~iPJ&xY<iBs0>bV&!voOHDy`CUF$v8ls*W7N zlQ4?%y*Lx~a85jD5~1?3tp>w94Q9~9FiNIm)T)dsvdrtYY}FnjM-?NGe(@pr^C4_! z%xvurL4s)pgDsJ-YIsK}4D_mcbE_ECw;Yr>#jhmI0S7cdE7-#-4Rb@71sCZC4F6}) zoC}VgZbToV{RZP#_Dv{L6f&nSJzLLAKl2q~H0zXtAkB~mZB#Jyhz+HpKErOb^3zAn zWH!e_Hc?9|lCdHeOn6+YK>wldK<QE{lFIoMlrSuS9H`V&R}M1V#vERNER2RLRf#;J zf@a3l+o)4}&QwjuvomAWNlvsVqi!k+u(Ak)ABm!%7BCjakT7&+Pj_Z21&Y4_6$2L% z0~aJJENG_$W07jp?Jkl@nNLyyqwXREQvt(UH8q_q;FCO+TtU@svLOX9;B~kZXr?lb zritc?z}ps6vfQXe`3)wiLRVK*vOH8XV3ozhP)xs&X1rq-Y40?pvOEkfM|U((qa}jA z$pfba0K~FB8ZK#~;w+J|Esifq*RppmZto1VPtr_5vQJ#?g<Po=RL2ipHz1G{(JI|F z0&%fe((g{CM0@O}vi}aSS3fi`_H|bSBQ#me6+t3^Xr`cKkttPdPxX}Gbdh0aHgzu0 z)uiGp#V$W7HZhEGD2~xlL1GyzF7BGq8RwEv)(KprA^=EWTvxVSS8n{IVFEND1@3k$ zYYJJL1xsueAY(CS8KY;1*5>%pUk7(O=gaD#gmYr=>Sk^!eUN}k4NIW*_8OLI7f3@M zC<8SRoQx(8`Ln0ePWS=?Ei01Z!i7m)tJt<RZM`+l8iNS<aya3ZWo?ke`r#N%z${E) z0}HcRQs<foiYXm1DHaeyf~av>FFnmPC|a>siB?z&rlpJmc~=Z9tmF(!6DogZOK4U{ zsaE$kw>fL7bN?Z>D!?+3;sZ!yGcY#R_^85K-x87_sdd+^*wS_YzEyVl(sph4IBzIX zuz>_DAa<&vn-FqG35uE=1t4Rzda+l6U$tnTq&h$INpco5q-29VCvtr-j-WPSdoT@w z2KR<yW?2m(2~!bwkXZvm;efGyiLusd_zoe?EvR)~wDs=r*AMG#cCqn)R~A%rw;BqG zE4Gp=1!J>T@@AM;Sh4Q$#5Bs(vw{&Yf>o7@k(YxF>Vs9RJ*jEAzLbGcQ(0LUA?cG) zH&9w|N_OBwEDH%^71f6Q^A3+uEr&`;FVc5hiw}vdQt<^-6$3Duz<-ArZd*2Y%i%mA z5`o90eE(5co9M_iX^|x%_gBGUi@R8ZJNRgcA`D~EJE+81igzkD>%L;DgbU7ex-2VK z7$wzsP+JFfh{o(X(2?nbhUwVWaQJi+%v#HKTrhG4?G8%o><juqt9}cS<96i|B_6oI zTky6%1C=!?a3G<gDXPqr2Uh)lwUb{_f*E7VMEQXOl7PMgDic<lvMe#qST+BPk7k*c z9g?(slznF>1Vu1W?a;s?gg~3^87VdJk{R%t`F}w*QTm|`6u<<&f|~2|f$&JnY*bm$ zkeW;xt%6lpIXMi$`Ff+tdb7BAOFE1Zh?1j{%f8oG|I}(xk}&6)b*kAb?{g~-RVm~+ zD*uS|Yjua$eyxw2)OD#1N^2LPiCAtIx}j+YJ|0<hI?G0X=nTQJG^10+s6rM+d6WY~ zt6`DK$Pge+vqr~yDtyLR7uIz4b|@4Q0|ym?Y&zBgDOz=!)}#W5mxic*T0p~PcN$FC zycPO1GPtmhHICY_|5AXJ84!q%1bne8s+mylsOz$9c*$6FE;I)o_*hudq|-S;v{z57 z+BC=b%GMBk4Nif?S4UmB)s}Tk@)jiA8jz%=TDrn$fb=2GWCMN*1A3b(e%S<jZ9s*& z+1N$R@;BuOyEP8_uo3y>yb3wp1^`?EElPl?xnf<vB$88jvb9O3%6KRyu(LfojQ>q~ zFs7Q4`BoRf!d)5Vgat}`Tf13f`)VWhrf-=(__=ibxk%3fuWR!ye2sUg=38Nlp!?)W z!D4N%CIFWEkeeHk<rW{@CK^g$0)(*xv3p&+jKjOstW?cU>&W)@bbCd+sv{(&mE}sD z;-yY)Sj{@EuQD|s7EE4vz9R^9%Or*ggQx%5Nb#~63qyoN2#^aU!4m^PT!_Ktpd=q0 z!iTtsNo*g!!2}-Q13sX!eUGNom$ml@we4t*`1U<dbDhha%u(9RZ862M+3QlZy<vPX z$~T@N#69jd$L}^U^xKC2v!|T~z*D#4F47r?{7HZKQ;vLxrNUemJI`k5$^Q*oZu4x) zN#HH8+_AF)vRzn#7f5_@G!3!LoiVz5(>%pVeK4Y$l|dY};ZrL7ix)Q+wqf|yWM{`~ z$B;C3Edcz_fBG%qa?oMRzzzNTgyA8y@zD=E$`i#LstN5h-~&n^KJ2_J`6wY#Cv&yL zPX!~}S-mkP```@jy?=()bZ@QEm_ET`Xw>(Bha#7IqOR?b&l_WGK^BC9?bm~S29qiU zO3rMK{mF|sQRqPo#sUMJodlpAcJS7o*~2-v&BG-d+y#o;T^zp>WSdxezf`G9SG$$f zS}8Wyd}mouA6wzvxc3I>A#{4b!6M$BMlp7$kDc+}9|E}r@2alA$^ZQw*#Tae=KujL zptm<b7_;2Y=^3)08opDwXFOb+z!%~0i`7@UXVh@&sUFP5*J0y4OlCUP!DQOSZen|{ zsoOU;Nw<c1nuC7XBKJC6LiXYgVD2!r=0PmUr(zLIPUrLftB{i({GlJ}pa2@6xAWuR zFCEkKR-)s%ORyfk7pNe0<{J+#cvTI=%i6u$HIJeK>+?vyKmKZsKGw9hXvz*EMRyK& zJ3sP+EQpj_fcvNScq)MH-k<N7Q%+nOKp7rF+Kf8yp`2e38!-D`cjE(*$l^YT-p(7+ z=v9-26)!@}8v2oS;=w#V@95#l{aNPQ=<QjMc+WL^4<z8&y8mbA%6D79n%(Tpsr9#| zs3fj7gL%MZ|JP|A(ZLVy+hbh!q4)hg%8Lsi==CGV0)RmP8Z>MmQNn~l6DbU)U_r5B z#TNixXxzB52F8ORLy8;;phn3WC`qbZsWPQUj~X+^H29Il3!5xKQk=+BBt#QHQ#cG+ zq6CSfACe~BupyyS3;>{7P&r{j&Z`C$B-qLofmZ|v!iL34wyar}2nqmL6Ys3sw{YXi zolCcF$b5M7>dhxG9~=M*pd!=&fFV$aDH8LvSP&#fju|6k{OA^?<&ttu8q^HZqs+$} zBOh$cl10SErW1qwDOBiC07YRJE=)q{27^v>3pO|vK>u%pRz)^=&>&}V1;~?k{W><} z0lQ??+D%|^Q9pzEpljdGy}S3bdI9Xs_fKFyRDi4cCVbRz(1;ON76eUl^2-;TSz1oH zIp_WVl-2i{OcdQj5mu&|27rQ!DaP7QhXEDaK_nFRfkC(BmYW5?`36#OA`wU2N(vm8 z9CBPG@D*4FiS=Dh(%GfKG63N7;*B`ws3Tne{Bux`K>mY|Knp$xzyuZ$#uP&(05H^0 zs_A49V*`pt)?|`N2H;92VObWII2lOglp@798USXZ*&2io9adC(v@O*XNf=<jVQ&_I zc;o{s6*p1?C7vkgatIt`WQ#j`S14uK`IzXVkpD*N9bVXthnGO~98!P+Q*r1N02eli z7@8nWMCyW!9hi|#IGyFCWRJx)8EL8(bYQKw?sRLKr#|GQldeSwn^En-2>?@b;`S+T z9**>Yo&bnA97%x!DkzFuePyVNl6JSob=`(5?znYXYMwAG2v8N0NhV~_g{%E4(SoCm zDH3Hf1!$#!km+mIO=JcvQbh|+lv-*H#^=yat3}u(Z53L0EK~00)ai%L4(I1V4HS2r zwbyDz9RS)I3P5v_sud$#(j@@NKIFzM^UNw)nwO9Qu~Woz4?H^+1{GHrvAiMmq$|OW ziAGvTAL-jPO|jC%DweOFwRC(6s_CFm68}ATkO@V-31@8=GBucn2GyApp9ZmQ(6j(_ z3{uC{hAcA42Ng=Q%5oi0C<fcmEcoDri#HxU_4MP2018<3>_JW~IrKqXQ(me?R<C-~ ztW-C)Ip%XEcsYDUui09ghsjH9vG5{$+u0iI#_T~zhUEA`J-hvO$Gih-EntEIKpl13 z`hD`D<F5SH0R;r$13L!USorkR>lma#L6S$0KmABkg8)4P#~Wb^ZScY5U;p}=VmlRV zR;o)&3BRg2#b2gM3j@ohlM;$Owryt9kZyL<DGse`U2O}A#(Kv<j|B=jAkm8ONahug zhy{7oTZwcIfQWy9D}x{mp?88r!v7)lLmo^xz{Z{hqR4@&LScJI<r0>dg7oA}DzTNl zMxsN|4eT_$%1Qq6N3_=r%P0^-$_J2@kfsQ*PIbD|oep@w+*y%03v8h84x#{&49_6M z!&{3kD8iLIrv~KMM?dIM#x}Z9E|fCd&B~KFQmBYe8?(yK+-0_-%w{C;Y0$jVlpxWW z$%Z-sqWiLDutrM6RP?&aYm8__)va!5?O7tl1o#v?Nzs5*T-OzIm&Lg8j*Gw>Ns2}` z5^l*%d2R^+9M}kedN}HhxXdMZ^dcmD^dlTN2tY`}2O^+V%pgO1SV$lerJ_X=HIXcs z{RT#_`0(VKy|SE{g6OMdD*uxq#j21dK}9~oz%F*4{N#}kNX1cV42yC@WuS5rMhm)f zZ!F6QH2`p(?CA2J042*_1R@VJY)Wpr^Ua-dV>Xb)=1GTf4c8{w9o5iKG2OIWCBFs~ zm7p&qoJ407@pPvnnUqfx&>f%f2+va<2P<1KNCi)3!Lz8W0I=LnPFZ5411#bo(hI0i zhe{G&ng<nW=^aRX#vx;x^Id;DqWXd&tRYU6Xm5d!RUg#Rg+<7SO$sYA!wFR<!cJKU z8R;jd0xk6<G+G;r8^?UtMZl0`c&s#;LDYgWtl;#ofW;|ycB&Et2mk;$2;41+%Gk!r z5ijN8r_KUU0HsFDr2p(fh-N`zzVjUfiD7#vMb$@_jZXEe4vQg$!kI};I`NnqQY%UG zWR=>IWTjX6SaMPck`z%;Z}wzaVE;O<u{6LD^njUTm&;h2C6^wrU_k&9U|HJLu34LX z-Md&@EY%XRI~@%x*h1?+)+)uduMH^_)h0!Sg3`7oWyxD3XxHG`^&lf-4$8<VT)+Z= zusaHX0FJ<pdcbV4%uR4W{Yfbg(nAag2!OTxG@PCV=Qq8{4Q_7J+4HfMHU?2`Xy5X% z33=3y5Ch;QL+UQ}mQ*C66s5B+%aXcs(Y~x)5g7sO7UKR_T+f*RFzQhc1smD11ND(P zq(E8ZFc7!Ff&W%i(25~soi`~bMloHudk`#7>{#Vwaa5pql~As8m>e4si2!w9;3+4+ zB@2sxp(EIX@U2^1kVidigy19ldBORxQ9trAixdPvg--66h{A{24si%_nr))%%-3Ph z+J&qb8p%^Z`b095<k7aPVnXrAF_qYuT40<Y1;;4oI)CTRiAsxag0T;n`SZ`XCMu=! zu|`NdAOI&)>J?e?V!?#DiREibL$9n9q-eLxnik+yfR;Adf#k&_3C<{cHZ2Ob^psiI z;;B=8YOjoC$3E7Mt6{Apy~zQ3^ayIM=bg*({DUtZEQb^hz_{dSQKj?sP*b78Vzfni z(`N&ThW|zKY>`;o0@fBuhhXe1E8-5^9y29f{dDRRg#@_#bv0wva#$Qh10=Vmx612% zGrshrAKPeBzis^F6=wTlyy?_>Lkj7+5FFuHnRvEUQsD*8O(gTo3XXXzypcVJTY+t? z@e*(dgT#B~SO+v@+1QVGbV38uZSxi{zEt3-XLjz*`C6eO7`4$UByEp)nW=L2KD`aD z)xCSTlOB>m;Wuw%{IAHF8vq=D0{}kibJiChLYvjdN9@Rg00Mx3yjE*&(^_fnXcv+K zuJ!YuK8vICv^K0{d}H8_Al*3L#c_)auPOqr80TGsUpPwMjL&@r<7hJ*C2kuyn0(Xo zivP+qS9tR%eQRyk1$v?5yz|&r=t}eyaH8v7i&?3!_OAt)nD%x>ETVS}df_9!_(So! zPk$T90{}MC0~Aw1fCN?jHk$KJL^LKzN>LhPD#jNp@MU&q!BTHieY-<9aRWhh6*8+d zGF)L#Plqx*rb~xnd*VS$>X(5FhIj_CI5g!I#D{sQr!jE#R=U%F%NKxAhJt0mHg6SI ze^Mg8!)7F+9Isb0&Y@S#BUn5rRL>zyHINJCr-4K`RDpI7)Sv_baA>jj6~sq_ByoQU zbX(ywO8EyD#eskMXMiJ7H{;f3sn&q?6kIfAGCUY{f;WNF1BAWMPeu5KLnS0gsQ-kN zWo|Pi93`SaN)=ZyC|A+4Z5DS~E;xmAqh@fChY#d&U>Fh(m@RimMi(@J!-a-&F?cT` zOcr1XZU~2*I8<EMJx!nhOQ<4#bBAB(F*BHP!Xa1P#x@ItMOfsAZIgvl*oRorMQnzM zcJqZ_BvU41ZXb9k{$+`KbyJhrgM{;gQ2`0^z=0{(iO~2@To(>{Fae_o7WYJSd6<B* zNETYeKy-nMNw<qy5j?LaQ+gAD+j2pz=3_i|jKs(i?Diecaab0>j0eGf(YTKR#dY%F z2vc!rto9t0mjJt!eRwEterSt&xQ7kIiVt~u+<0T;_-5WmJaOhC!<B|<sQ-p`7IkxG z79Kelhm`<&&=&27d;GYPxWpGA;Rp{S9XRD857<S+(|WnJjrBK?rc{5cw>vWEg%uex zsb*KcMSsWBQy{sN@pu)-2omWg63BQX3a|#|V0HMg7c9AzLgfm<2bFwvD67<ci%1r( zw{c0wdP8Yn*m97=H->rzmS;GObLozRRhPt-mvXt6A88kAVOR!Xl~(sydBK&2DUI3C z1czlL=>~qjc$6dKmRA8mrnZ*$g^*(SfO@kcQrVGBX_rw6OYjJfa!HBMVI);)4%a~s z+jDPPd6=+SMn`B6{h$p@FcPo?evavjN{5qQ*qf56eO*{z*TPC-sQ;Us8F+H$nSv*e z#W<SK8J(UPmC;d*f>)0K5CApc3aYu9{$MlV5u4%}LP4bl0Vi_o=px9IExl!sZnlf> zNu1>vJP-Jmj#zofiH+%rJR9khd)1uN8Jz;kl>KR)rFk;I^#E`X4P3{X-wB@M8KJuL zIvA9O=_wMrd6ZzZ6+_v5nVDBHRiF7;DEhgd&q0@Z*<W}$pe#C?rC9*srvN_C3+(W6 z<v|bELqdzyBNE!9B4i09a9ETll_3d%VX-1AVxME#fE#+8AhDTwqnqbuq8Q|&l^CEc znx#+4k^ClL7BB||_HwLA9^hG+K6<8YL=V*P1rc*tP<a*VIsc;CQb9QQTls0H%rTG` z%8n$Fms4p|GKr<uDWF)&qJDD#!h`@ppbX|QB>3Q(W%`V0I;qtIF7kj2T);L0aHuL# zXH!b0r6{N8mXyd7fqc53d&OV=d8LJ_r7Vi2z!d-!00?2aMp+rDW=g5L8bTN-53|4p zBjctO8WN-lsux;@$CIop>ZeUvopE7|Ejpd88l8S49S^Vs%ODT6#uvC6p1b<3B2;7t zK?+4sR|3FFruwO;dKT+yq>xBc!)g|NwLGY5tfXqJ#;PJqSO7i%05$q@wNz^YJFo;> zYv6jYBIHlf(+}o=3OMka|0%5-ghBBd9R<2K$|IAm`v086b)*rtgoGgtFSkbV2BDP_ zM+lp;B4i^AYYvXk1HsB7&FUSdIX&xUjMF-rrRb&z!3DEWqwROHmSQ+UTPZ4gwAJHJ z{_v7M5VI#5Bl9>|83eTvTW6%%gMf9Y!UPyKKnB790BYo&CX2LW`%m{K66N3sJ`iC5 zAOJABgFhCvMR-%VDG~x;0b<|^<uI}zRJMMLYrbR<Y1;z|Abf{aK{K0c!`P?FQz$&E z06l;R$`B9W5>)8-x0vf#Y!tZuDhzT^0|~&h1yHeY2ulf&0&S2B1$GddE2)|Lx(arq z_#m$Nzz)Iy2~dCmJiD0Tmw}^8GW=!`ck2X}Q2!3ewXFtmez3c|DmNtJA+7)*582=f zaPY7PacBgIb$kW9!JC~4Py}@#4gAEqHR8I=d%n5myz)j5?9dC200l<GvwpUj-J6{O zU;#d`2F<X#FUPXz`@cn~4+n8V+W-o3fCDfHr4gG;deb~00X{F#1at5T+5kQMKx8Tj zz#6Q3*)f|KC|SQC2vT4IFnGAFBseirDD^A6B!B}=PzSS6!5`cYHuAw6e8WZP!H9DZ z@?Z|)+Xg;B!VtTuQ7U_+iX(*rOA0^&K0pSUa17W0v><UySBJw^ypJgdu&iqi-|!0u z;R7Ww0mvc0*DGKGaK<w^79r?G4>+t_8><omSpq$f29~f4<sc7z+kWons8`&_hlzW6 zj6LiC4&R^*t}qFDKn7WG1T|nM#GwGoNf*pBg)S@yf`AIbuup+(!{+P9p8UsEY{MfV zruZNa>`)HWPz}<63$uU=q~HjU5X-Ub2yoB_aIgl4012=x%df!7z@W<I;IDz4k3m}_ z;uM{UJ5+BQ$ItA8F~->Uv1T{+CDm+pYV1TBYh%f-glaZp>_aMR*;A=TQIcvfn4}^q zT5Xl2(yrx~*ZUWo>pbUr&h<Rs`@TP)&v(Rm-NZ+I+rBhRJkuyVIsPzdxQZq7&+Ara z&ArZd9Up_or^drUAVB*U6cz&jfT_~vG>#S61`HrK01y?}Y;jWr*z^xZA=H2pw5H^V zDEF@B;bKcu&km&J!f^TjV+oJTt#^(Y`kxEGbGhyANqqEJy~mX|chLa7aEZ#-0PO6@ zIVjKWj>#7HW5#>Ny3hJ=_9mVCqB5kGulCYaT|+i)dFm2vs7S->YUk`Fh|7UFVb7fF zX7x#NJR2h{H8Q!0Em>@OKYN=2k<#?;UGu&mjZhGUPC&xAN#n%04%-zE5%3bcW;}Lz z{y`(TSkvbzoi}WMK*2k=rYWi+XUE7z2gAkHhrJo^U*7v;@q{PO@}DCRO`^G@Q}-Wx z5=nb2HE*uOzPNhr`}>(Ii3MlB+b_tf_kY=d;=yU66;w*O=y`AM;)k`xyQgofrSUM; zv$+JVH0MJ_ul{qx=9GtWW;4F&cg(R+Z|o-alU<O0h#_10e7<sA$2?d4!18>7#U4Ba zPzsPI5|!%Rn~RLF0ShRLN(UW4_e6F@DXMUJp~PuydBFvbmDek^L&wKdIIudFD!mo6 z001eEBY+S%+9U|-Ttgs+_~`+FpJXbd3P9rZ$&l1TgyU4OFs^3TpppLZjG#hcL$<5L zn`-|r@7|m|`Z080gO6gua+8UEBg4HIJV7UhVdc-d6a}4Qv{gr(JKL-jyYjBRarf`Z zGp*d;hRq%A=Mr2bLuv@Emo9D?zwhiecZeqjJwEsTV*iho_m_lllU0F8F>$p^Y;b<{ z^0?jm)hiROCLg+|gAzaV%*37laP|3t_aCm!ZN?JGyLQjf>lWM3CwpIV7>1IsUo`pD zZvX?leLU;sEpGn(;pGbk_kydzu=PYi-?gVzjN=adUXxZvg0+DG`QY#>n^8Ozc2e<R z|3_1gd4jAt)u4oo(LB?6*(0iR^~+uS=w>WoQ>O<Z+Q?T~-*>X64BfXyn0=d|6mKQD zx+N+=ayPNF-_l&%{@Y*a=(+#<qmX^2`|ANcVNYFz+_$Bf$np<wX5-G3{&<>j?cR@P z$)nOgpQk^$d0=Mu+dWe!im)5F_(3IGV+SJpbYk{APwwLSeDRk1>(|TNUal{dTU`A4 z+UP~!ax+qtv(kACT;@1==tT1GcZY)H-(UJu_VM?7!KnG4)$S+Be?IiSz4+&2|Id$q zJ_!*Pf7e7epy{8*TQ2?mGH(Cr@7D=8i~qh&Z*jLG{tCEsGnpYKW41vb>HgdPCn@Df z<n}yJq2qr5LuUKOMgIrCzMZx`D-YnA$Und;WaIC5DOzZ)5XLek9(~w2`giWh?Jp8* zOm9mi#oewLBlSp$40jyVUR)Jc$Yd!53}Tm3QJ>P*IFixs(x!v?rr{t-FMt42sVqO* zxW>gFA`-;_V42sXvknm|Z5)x6QCD5b`1_PVd@SJF$cqZBHieZJh5QJri0kTHj81DD zVl4~cdsi3S`eud|6l37Fy?|7lkfqcs3nWiBsU-@*syBrtP}yjAu{*|^Wm#_0ud5D` z5N}ug!Y}x?sB~q>%>oR>hSJHz={b=mcBw$?4vf53anrPNSWQJ&tZP8Tc)5e+&a_g9 zh69D3m{#lsJ(#J9wik7xQlXL$F)f*tBqV_(b{ppFI}wYhse{!`Yr|SGAVyI7LXE;a z)S$LdVkbbWeJFzJw;M?Snf}KWDmX?y9(;G3C~PTy3-E9j>F(Uz@F9S*71YRcoA#H5 zra`xv`EBryU|TUT(58xH5<$SU$^a7(oV+K7t=Njrp^4R3s2IlpQ8Tcq*Omkq*mV=7 zp`gtQKOgQ{JAiWTk8wHK3ugsXqIT44105lJ%>bxY$hRf`r=$E>8;IUC&YcRPmL_11 z<6L}J>_qcY+2ds8g*C2Pdu?eFwMBJCY;1RqiOTg}RCxz5tOdT9mI#XK!$x<TW{@<U zD!KqoOSC@HSJG!3tpbF&8g4SRV^@!B4<b#;EMGniSX8>b>|(AMhT-1>D~-1BgnGr2 ztVWi+d{>-}<-lzG&Ot0t4b^jfk93!(oCXvq+E5Vi7#!6kd%VL{O6N}L23UxS$Fn^x zup-kX9nB9d2uN0u{5n%64|+YA_*;^3eZltPL`b5|wCWy!Fr@OxVbu7kWmzVVtSVOK z+K+54S=p_0;eIODK@?e%;Xb4?x##_^9ez)W4aq9dNOKnskuUsm^0op9e)K32BQg&< zCZA@yIhKqG_P&Zc4%_S+-Q*-FwaV221OrdULbRJsw|p9BJ4k?J;TA9e!4g0ck?aw> zCZLf{e8ZnC>YSH~qm#W-q!?9LJt^312r)Gk7B1hV^=%E2RyycWg!!TT+YA}5V)de! zs;hcGWW})4vOJ|VT3KvpY+FANlt6`Cpr7E@v@}Uacd$1)15SP1En&6qeMHPH#Y5)6 z-`%p2e|rQh7!WD*rx>EUu2T_+2Q)Xi;FM~eayTpwv{tw)vl*uXHzT{p@8)LahyVgq zN7WOltVEH?>VTBKB}B7?M0C14O!eO;>b?_nZQBn^fDv9{AP++LRlCSm+=yvjtJ40x z-!<%gIKMkcuOrTtd*Zq&dcOl?bIRvO;FWureS1UI9#h?HA8z&q?-gB`YB=xt&lC&z zw<-nc%`#O6Y25ziJ*dL97LU*LqCD`F)-OEKNgALY%a$#05EX{1RR%@Nqf_z2T927% zU}FBU?jtjDwhzD55d`?)NYWSQR-+#1X*Fy>f%;#4Z~IBtaBr@<-)ZwL&Ft1uS;M$F z@hu-GB!xXAE1aX=Gc8T>j#hoj8>yM}t~4r#-ahi$+LJ|`Vc~!1_6o1XsBFVhL$dWM zFb)86`wy3rUQzQ^adEV_YzU-LI@R69co_hmRd(wT-t_RLc~(V_b<a53{_^}sETe@? z>WrZ!c7tedT7sh0t_$GK03UrZE~{fA*|}Tg(}y;8uKFy_z19m2#9iz8W~n4`<k_AI z+WIwI!A)_KcH*(4VKKE$(z!0%eWK(}JLoIsXR9p<;2Pxtt;WN8e0B&%f9bBo?MAm> z%d*)6b$YL%g*h2Uq~FQ@lyLxgbHlc>37w0BsGPJgCXbJOxM%(H>*6MiLor1*ZYp$4 z!S|X=(9w$M-Wv~~#4K2(OKku{D=nqcCG^)w%CWe})BH$zrbKPfPT1#oXmC_h5XM*$ zYc+zwY{`T9`Z>pWz<deg2*45wPym2RK*N}aA8*0V9+RmYNQZv*FSI|ZzziY=2bCaz zXA{yR6Vg9~fwO`@N^Fo)6DKY%V7r_23|=~ABvXGrbLW%rdyV^0pe$c*(#DgVz=IZW zIPfG|HkOV(nH8$IDGLyDRSlT1rrhW!@k(@A!#7mu=O_(#jG*23stZOdKTp*SvqzA4 z*UjIs+QM@VvUwL+-2e!Wl-P;`{()C>cDu_G9~~wIV?qtk=K+~d0NTbaDC{-IKsLZd zUwXe?{#Uo7--C1B9>{^E6>fVJyn4cN?{Z9FFfI5X7X6s^Upx1hE9Ur*l>NODYOb<T z2Y2&nsm4tSwg+T4+p|gE$o@EZ2*G816k3D?Y*V3|TLN!b2rv#mTZ^%$@B6tWCt(D$ zts{MgAM}cVT6!zZ#Yw(o1j4$~p-qAA>q*bvWIUUTd$z{bm6dMYmwdS+=jWq*1`OD+ z4N)M{aA{oadCC9cWTlZna&^g+4fAe@tg=IbvN$!Ho?zwb+v$q!(}!nb;76#5{z4cJ z3G?Bz<~Dj+S!+BrrR>irW=G(@H|>S;#3D){|MO4ub9`V5zkES(#Dp0*wTAxmB#B~# zm2xar=*pq~lm*@-b9#zlL|TCxrXWam_ZjS7Hw-2O(~H11aGA>Pn2Rp5iK7Sd#05v` ziMlQr=WmE30(2J+mha%tl}JYqVH||1B1N{LQrXkFoE+}Hdq2wlh%uoq0WVY0?Gw_U zXz1KV7#APma=b<_vdAqE^A>;n(Htt!2s_nQn0R~>1LFDj?Qx7p){TyEfO;bC5JQV8 zseC6(>oY_BdSs0-R4!YVFF<De%FT4dq7m3CD6p>)zI_QHz`&0R)3_2aEjL+{jhXP# zxWhyG^ih7kmT&qt<i5Y_+3)5g=Y!C0z0xy{(my<k{wibt914i+k!(JQeSIS5VOGBR zK3SEFy$bV3|6SV)jMN34#NMt>QH~GAxXQ{s=At4cQbMsUiVZ+&rD2z^)}xdAQsGe( zu<!|(*)dpudug-{;^CI;Ph`w9faYMBp%7WCR8j8m6a7vQ=oS(<Lk(;~U;|-TPb6?_ zj%}EBd}UoWJihpv3N|vtMIr5kfp3%E<cXTKwz@d1*3;bzO$7!66lhwr;cuexZo*3m ztVJp;kn3-74K=_BzKhxGq}+(>I{lO?{jw2#hrpSo1w19Ry6(n${FdFb@hIXQKjOc$ zSbx_VC1$YiTRvb&S0plYb(?g$PRLi3K#896#MJ&^S=2t++-zS)$U)6Vevdrh@~wF< zRVbe-EnKM3mm!c2LQ(~iIF!{A;=Zr8gJW{CWBz1oXdqfN7x#uL?V*}enA7U!gcbK4 ziOdi9*vqCqO~MyouV%|0xw<#%4kkvWNwMMtl*xcv)?-E(vUVkk74@)4iDS6bmcZ1Q zx4F7q=d6Pcsy{lXawcsrRbUw_yK~dZ1C-5moHr%FSE;AezMX#;g7Lc6Qn9;=;dJB& z^^mLT1$o~KW=-g+#&oZ~Q-*0d*{;R2PcHv~Rjk5u`#ma<LEQ3<Eaw$Tz|jjk5+Zx2 zFt=4+;?Hi`=BrHYG0Z^^j1|{cp4g0PO2mmUemI!cNr4yNVs72NTy#`kida=txWxp^ zs71Hn(Jsn4&-l_XqYLYfa`TO706;%Im;K^*&=%(2fT#P8>ZAH303px>l}+iz_m<^f zS#fGQu3uklfWL^5EPUT9?<!gO$Gd*54eP-CF@}jcc#i&4w(Ak|f@0~z>NH$e9xAd2 z+H{^c2icS^sXRXRo$cb>hGNv^z<-sWjF+7upvNX6mhi21=dKRcT^+cKO@$|~Q2DmR zy4}~0jt92krMP!sKw&=ZHWhVIDWp#YRrpA%Fw41fgCSK6L*2wnU1CUH;NNPPkZcj$ z`tavg18}=RaI5S<Xd}P=g(x2S6ZxxkSH>?{9o0TuSM)(Qc%Om4LV&CnhJ4)<W0w!Z zRHeV#G+ognzS#$iuAEY6l0K^1aVHi1jv6TP!p7HK)$zi{#7chx_C-F+eja@7P27!d zS;2NQM-@S+Vc^QBK<eDYQ0WA+n1Q^vj-(_>R8V(c5K5N4L2{^wL_DG?9u~xhCjVc? zG3>z~4lWrEU4;cT!ou)~eSCO29>Kv&(oqs$pGlk`h|2L%aQk+*Tv=Itp<>rb-Q|<j z0T}gbmb-vWiwg_Iw6dk9JpC#&)P|DZ_;taFUNf(R4Ghc>H4e@*q{r@J)*bt6!v_cd zh;@lU?^30wXfpQ|uNvmcLREw1KljL2H0o3g9qEzko<NrKB|c1`KhB}s@zRGUkYDRY z5;5@LHLo+Nl3N9koC!qd<Gb8cskXK83H5s=RLLpld$ly=;R(d1G;ALp5hj2InGSEt zsP<72^i^aFUxLz!EaD@Z4MxxIZa?6?$$bekvOQ1GgLzY--ojEZe$V1{QU*@ut3P@A zYxOS-`c`2Me6}2wb^+Se@k}`Ih=yKl9MtZYKKWM`<~UhydO_=EhwR}&*VlnQMX2)5 zBMP!tU#MnSnYK-YVHRr-k8Tj8&f$?$G}JZID8CN$N-Fv}4%Hx(D5Vaktif{#NM@>J z8+H6l>fPfw)VT@z1pqi{ce_<Evis)9u?dOF6TKH2C2EDpnEgomb{L62>@I-C=8d!+ z5asicN}qS1iNoStO69voZ@_`|V~9;>%OL_rx~>Nr35HEpPq1A+Q>BG`%dfFVwM{O# ztxwcAPd1%I-=azXzzseHI0lomk0c-JfW~g6N;mAO(w`USNfzrf_kKUVH!K?^rcEtw zVq|I3Ept-a59eH;kSL#n+ox`}S0E<6ZwwPq;{??6&7oTQvktt}MWN*61(9d??Z*v| zL^jh6Yi)Z~B^ox?B7b^fnlO?v_Yg^VSfUWJDS1iT+&yMd|3nxaN#JY$NwpsM!57ic zNvrDCCm}f45k8`ef&P>Zl|J9Id0TQ4(HD8nvqOY?7}So~M&<fWtqSQH^&?~Nr7MHc z?;0mzpQVk`o@#x#qfpTiQ+L5j^{jCNHt;~cX<hL5w#Hmnsct-aB=s42dFuY$(dz`s znmJg65Plec@4+f+AeDB7cFXJ5(x#$$TPJ#PpY#=i<dBDCr!b|=;Ci@uJo!Jye(}iH zXD>)n5*2vK-|`amG>N>q|0{LqrO*@sJaz6d2lL<%UH0qW1G<)ELVKwnA8`Z#cBS?p zwx8OzfwTJ8=WLAxwhxH6?#Aep-qAIEw+Ukyp<PwIIZ0TTeui7v0(z>gF?lMyV{Srv zYE629fBJoJt?Br~tT0))WYyQ$I)L%86Mtl6V(K12>gV@Gw+pbOwef4IQlru+5x&>+ z<<j^+$?1ENU-_F7X4K^7Iw@a|*b-k4NYd_eYiJU4=#Lr)F10L;l&v9Kgi$ScBsX>1 zp9XbjK=%vbrU%|yD2B<wu$7!wo2ihYi!Ac*TR#BiO*>|Y1b{vM00E359==OHV~c#( zxAmPa2>lq3ezP_|_Wqp?dd1jxwn2Szta$z%CixjH=-A;JuY@rp6YO0e%kIAP)CM1Q z7BBM^Cw*^j-xvW^f<X-a8}G)WM$J&y8>L)Rz9HbD{70)l?Ot4BNL}6bsMPMeyyErn ze-aS~OEi9c_>mxr{E3X+F1jZcwYegXW01*nFcJ<*dk**5lhE$^%0vO1eIXH*2FpGQ zgS>+Jq^?PP5+2gKGz`f$&t~%*ZYVP6kKf0fye0V>u>jqqTYUViIR8#Zd!=&!!q3?_ z7ha9=+X=m<r@3R82|~@+w&a}S5rh0GrB72%+NdM8$Rr^=Z*6=i6(u5k3kd$^mO^KH zS#@7q`f2y~{(Z^ke93m9bY&Q(+BUwj?!$|+66oi)`InKe<qt$#MCtq(DccYrO$|H` z&%sgzV1GO`jevOd>C*T8i7fh0=zM!XYw6tV&tNZELw}4dADly&fKK)RAi^Ah1(VjK zR8!|kTxpH%9A)1HN|EGZ{8o6Q3WE-AlNP~&FgvCmqBa1zv(7T>^;PDxtI~jXEqGuu z&*)0?PS(srg)4EFcK4jxc0O|JZdpcm*+etZt9Mn|DnZm<bJ<SjoK@slResbJ{heq1 zCW=6Sfp-Z0s_+PCs?Frd^KeMoiw2jqM=x)7hFC_QNT@aTy9jS4>GS1@)W+@GG<%Kw z4ZKbmgo5!B1ikxwz=5?Sp44&UsB4obhPK+IcKGltD`rgIENKI&Qe}<V`H>SR9|1ZN zJ158VsxthGp}b3fbFX1Xf#!=t+kr1m$>E-*yC?ZN63u$+K8@@9U#`|H#676<P6hAf z1{?Z2GkzgsUv4?;qsB=1k+;ojOY28XopX&JaD&MzrBITqdPL<Wa4@UBsZBZdoNSzo z-SgCz+DO3AwK{rwccK~Xd5+1&zSTad&7op-y5g;nL&L{I^DJK<7oi}Gs^Oe~&aP1| zlqSc-%XVD82QWm|Op=sOw@Z6Cw1*M`p_D%Z@G-?^+{XQA!b&x}$qw$x##u@(MB(Nd z8BsWc&DY-v@YaZpn$W2E{NdlAIjwha{cb8*CckXM>A(qJSKSW4VQniDKJHq#U#PZR z_eWIcs*z!{e^-C4;=}3f1$bLm^?!uH=^HG`%w^sD6QLt2`x@i*RkHgI6%0m+Dn^bw zETp!`$M^arQm{`Fq=xq%dDqr>1Cs+|B>W-e*9H8Ge(jc$``6c97d9qx*8>Sntywye z4`rF{>ifsYXwV$y@oxs3Z<#VRRIHJSX)fIkG(s3wN}d_o^8g>*<W%f{L@3&HkToe5 zBM#A}Qf(Kt(xEK)4JHkSQ}gzD`JmCy_Ju)1{Qa&o&OfsKX1DuzwUsySUy&0(OfoO^ zXg^ruab}4Prx^MbIH?-e(gkd8ZB)?Y@r}BJ{CA$J@piKd(ysl!Bc#}qv3APcP^Ztc z5zQ`0SLV6He~u?#w;Yj=a*x!vWGU*lSpw>62QM@4`<#4XFbli);-Hc&FCuStdFZaq z?}?T#PAj;jQnLff&GUC<SVOp1P@U*TyDNkSoMF8(y)Zu&Ah0#JzwABmEM@e+#-sGT zsWBeAJg*0`uSyiCCpzoDRZG1kv9CY%lzqpq{H14y-ZJSgN8WmMeU7V77Ei_rD-24@ z;+YpS+H21~W4={Qs&#Z#xv=%nVyPd!;!US)`TS`LYa9*7&wznV2qLbx8U}t9gbDnc zuarr1y@n=B2CRK>1OK8_*w8We1a~*skTgFc8dNxwJs?S%VJUW}@|;4-ynjbQum@;R zE53(LqA@S^;sl;U@Wvf7=1Cw)4bK%Od2V?-oiA5Ze7%|A=kCSJegi2>ts2#Aaet7L zoG!=f9yLJxf<Jif&tJVmQ8V{PIPgekkFDRwdFCQ*NCu?|;n51AvL52HNmN2(bK*5+ zxNX(I4pNc3GQ#p1VdipikG7u0Ar<6a<e+5moQ}c^0?gz`d$p7+7q_VD-e)(ZXCT3` zhIojMBfAQoA_t`0JG6k6O$K`S$MlTqHuX*+M3){ZoyFfoyf?#{t=f@EU|@yO()U<n zAC5vr12i|j5^l2g$%g0+=^wLvC5aN_lBS>{<9G9S_ZIcX%80GqP5soKf^E_@I)}v` zSMvFKYOfe0#t$QReL|)LrkIM|V)8ML?GMU6RJ&QX4s^tslKFW8mO(!g)iqqs_fA6M z0h*9A4zA1%or_3{DT@Ebb1OQFi?%{~G6k7?V4+YY(p#hpGRCGbm7?BF@FxObAoR;w zvpY5gR*&YTw=xDW_o?l6$Ya&R>Keq})IL+>naH$+7lg7!GE;aF4s<Xj67X6&aZ{c9 zY!_TLd*t1(OU9p2eVKP)#0AJ+R102p9bfevesj1*eN|jTewra?6qMpTV<JA1H(1&q zwCHE(7`j24>%g=-Le!opy9Cv1m+~E3RK^&tC-t04XxYQf9C@*})}S5aqB~A=81`J! zuO)bVP<e#k_!6KJU$DSHd0KphRT}?30Lb-NiZGH*y#WRbm{vz9?%V4rX28x9m-Wu6 zFX0gl20gU&5D4%X^D<hs)kh+pBnQyc0f#HNDLrJsGKg`x`O&SP`ttT5enly=Dn{pB zS=(~x>2&bip=WqE`;o}9Oipz1M;kZu6`b@-7g4c9(-z>z)am$eU5#g{rt-U@DmPq3 z@e~!<9}!d9ar<l1HQG?f)il&@=}O-}`aEsjLEn7w<K4Mk7mVVV)l4d%1p}FTm2OlO zW~gwiE07$;-!!P5vW{&FQKW;`Mw<VW$An_Vru&RA;c-gnEZz_%6VI^{g3yT${)a#~ zxK$nz=da+d2u}}WPsigX<=v%k)w1N5^tFBur!*^EsLESv(Rzb%wZ8Svl_l)Keea5( zMMj~cps&?l&Lw{Bjw}nqvt*m_ZVIQj+~kI@Ka6(f*}se|%?wG<Gl=H#jvJhJkKe3_ zr@3tH>{>W;$5-WE2Uq7RRWgMVU2YpUjnk-fXVI&)`QbFZ^ZCW+mt3y7#g(LN*j=1M zbN0Y$DB3eZuA98x@vl#<PTv0O&z$y?i8M&K^`a!s_DT)9iG7ZoZHU?U-gkc|n5o<- zG04)FNSKr<aG(sz#sd!dxJ2*OHY?jx!pCogZ>We1Q=k><QMUR^WiO-g`O-kLjLwq8 zF0SqBsf_i7=*0{k4`PgI({NGf`y$x)dS;>=bysbOMkgy|M)RnD9Bpe|u4Ub@zgd|3 z96CUGT+X@ZQJ-sF!Jz0FXiFGbqJfSsrJK+JOnBuXbb9L7nnfI^_0&9S9wt;#Zr*1U zuD!DpLXfMTi?|2|c(4IsHE6DUbGbf4n$SI4Nu^k~NrAFmffZ{(ntCl9SAPj^(oaO6 zlxqF9ruSeB<99Y)z}aDC!Mm?PD&23|qVZwQ)hX%G0^M+ftll=mGVD()j&<)_@5YL8 zYJnJ8+bzr)1F;7vwPi>d`aI|r4zMB)>@qBTA7LL})oO#8#zjRWS|GDzEBAaDX?SHa zF{m;o;GS9ePkSfz5>ZlyvCTIFoDNit$_ZT-+q0E<Jx;1~g*u<<r{GWk>R%A!UQp4} zESamBVu;AV6%1HyD+<wEC-5X}xCa5t(mxvf#_r%>m*^ev7y&#{Y!VY9>1cIzKPEr+ zD|cI^O&j@EzOaMKQ+!g(3si==*Y>dleW>5iJIhd#Sc$rJ>!P*3NOs3Vhpp_8t>654 zp-#$xSh_dkitXG*ZN`pYTiKi@>#Y#RSI_nh7SQjgjnsO2`_h7(6d(kN$X61&T_M1M z>?)5%8ITIn>)4q(6=Ywn#Oqmjx_dzk6>%V2V)?q@MD(dZGBVhohkvNjFeg!oEQqRx z=L+F+-_E2~c3zFb#5feh2)GA3;9--sXB<wvnqq~C2NtZi?|wJ1G}M((y}(A2SQyex zJW@>-6-ejpe9GAgFbEiy69Zy5!SR?t8QHXLDXe7TZ?Go@IbwU}Itj0S>BS6KW4X=N z5c0<axixwyU)up-46)pMIRY}}?oh6&4zb1p2;q{gPFD=TXRSr=BW-;$Wm4B<vL?>g z(QKy@uTSNoADu7%7n1*6PGY0fWOzmn8KNTDoISiBQ}E2MAf=H@=ee}cjqXS0$3DBH z;f;Z5^IqTOy@oLM{?&3(Z7j9oDWug!>G1-T5rDYP#}oN#g|m|eHB;tnpI}k>q(o=? z2jUTS<4NYSD`$>m@s|YfZrFvet&tik&6lkV*_;V$X6k5X5g9<T)B%P%!-6GXn9htI z?Xbubc~O2L3c}=B6SYTkOlq&!98@j;#czIXiO75?{DHeEX^n@3^^~WLGwI@dA*JS+ zZK8wju|u6D{SN<dHBEeOk~<<)T$BPRZpNJ#B7I(&!0a0H!_=MHwj$$md3#&!G$D*g zZ)7lz8`P_}5roWtVQlsC_X%;x2$j#Vz(HI(pjne8tToicItr-9vN}9@%On=Ep_dK0 z5q3>uhG|NNs9W)_cq4!0C<6qD4X^zlgpq(nO7*f1kKg^%U%elTtj;XD{anmYr<}qG zgk$pXzuo%<1v{^7n#OI@>EmO6tHm)qnJVO|U)-cMF5je}Sk#lV8`-?hjV5eKo7na! z+~;vs%e)%PZyi1%sZz@CX7yUWuDin&+)>X!Uh{2auSvzN!2lZ9n*@6YsoeRyHFlLF zxx$&3)PJXroM^<#f*I%Kk>7QB=1bBSp}p-awjJ)S4V$UK-{EB45OdC$9iow)WU=wY z2&~J4Iny7gSA$rMWT0_ZuIPbte%Z}w3s~r;_hJjlR8-?$SVIsT<P*O479#fq0I5_q zf4mBRW{k6C$hcr9NNZ**FNmp-Kq!hAaGz(u&pG&RaNx0PaP_M0GugiRjlMvmheq`F zLTckFdF1Umt}hN6wOrBEeM?7;r(J>aYD5{hAh-Cc56`-qc0c?M8D%oIGU;r4HH*wv zwuRBqWmA9F@(m{7{KT?MN6d5<K*D(Wj#*v_wY#<eorKA$gL}#jD<cmuw5~oC2TDlH z+${_m5(WmyP^}SlYuw`yL`KN<H`?2njT#6&p43;kxN{tTj#4;Wv%#z;_-7+h)>T5D zg>aNlClQKTgz$Z9@MN43*2ed-e8-0n?tVO!3@{?Ii{c2v4n7a7g4`pp+r#5&+U5u0 z;5TPw3xIkb{L?$QpbvLZUOZ1x*V%&=56>k%W(%}g^d0dEmp=F1_>A>(m}8l*gKYzN zTd0=?wwCD{vUCNItw`{CKrm1Z{Ng;h9$V%L5>-y%<)&5G^fPZFz0(Cc(F~RQVbd%a zV_!BR1A~a&<Yy`%S%+utn1)mXwmf}aD&OS3|0!lwVP-EJz(`s@EU&tAolynnk1J&1 z3KID64-US$uN`BQi<4-9C&PKc`n>-R@%B#KVb0yzEF`tQ(?$BP!Qz%5=|Y3p_@}Rr zmvo*-`GT7^Kgj#=$LCu8So9{g_@U`$Nwj%~Eq{mIrao$dX|>EU$L~tsgX}f~r<t*? zez@(_=HJ)$s*sPUjWPKk?oGoUFSR~{&U?OSS&)u@Uc<NDTU~Hy4*u!a6P6ERFKxuV zM*_N-?;8S3z|n%)r}i5nqEb15LU=8K!d%P$)&aj?EYUI<&@$jK%7P~{3U;^XJ_%I) z;1HNH!zQl5n;<nWXLnU6@wDWTXEL0?#>i9Njml@u5}US1rNV;UQ95$Sn;`qw`_Hzt zp}5sA->dUh>;3Y3?F-gkZo*%G%dxF!><uG2$jo6cfC)SAc~{7GV{ZljkY?f5n3}0! zzb?GmeuB5-zp{@V@;ftSEWxz=ZP)kH3X+kMaD5ud$2*IP@TV3W3dv7juTB?p8!>Zk z|5Y;s3(^DyhYYzDxiegfV4r(=@*2L{UG(4zB6__hoeB?Zhm-A)Yq+BQv>4wH?y8!G zYVC04D=sngu9w%J6%!XUq>ZBR@Wkr;{t8)*v$yvCcR|Op@^!40x3FZ4cc0a`^X<&e z^ZLB@<{bde;D#>5mH?I&vux;#+-f;C+2N{9Kbyacdo1kW_r)VGce%aeJ>K6^DLZ|4 z@fkU9rf+OKb3NGY@Qg$rLP8>T!#8<3a~VEz86ox#x$RdFkLT{A6*N2YMh?UG8qQ1P z3F_}m#M1=_m*uks?xSBqDuCH31w`j&V7M$!NPWS0TDIR1wta>hN2@*h_pKIu;rZ|+ z3&~Z}K)%dJ`sBc(08h_B7-1c}ZL{E(j?}j{zwqacuhX@6`nOF?dC927e23~66Vgm7 z#1?O``D?erK^*XqFSf7D-3{zw+8s4{PTRpcI99GE@6vB$ZnT5o%iALcI(ZJ5V@ubM zA@Ll%`z_YAG!)_L%@x54+zw2jOcCC8A?f&#`?<@9vMCLO5I5-$)rN>;YMoNYnvDm! z=`%F%)hda4`1yI*Mgk^2U)YmiSP(@=WVshKXiEO)!kg+joscaVbfGuJbA_9_qMclp zpv~Rs4oeodwwmU*_QT>hJpIK+!S=Ql8zg0UVHxO+@`PMJm1v1!n=wGTRQA+7D_^CT z)%e!wmK=RdZv7ndup$z>Ty`UT^-t0&pB@-cQeJdV#aIXVa+UyXfcw62_J#xA2PPhj z#Gp5l0Q{zMorW+w)n_G;R=@eSaN_N|SGUpyRp^$J>)gzVEh&xp2N{Uz`|uc`z^_yO zDTI-xd^KY|f9a!GY=>;0;l@tE&tw-dd6UeE;XMI7wf!qPr+9QY&^MrS+Yr`<;us-6 zu{stu*fhT{iabF?<pD?J_lOjd<350&_-iM`Yyzb0z|MEP`ybkQKo_|q@znr&joHzD z_!L9NVGa7ke??p{1}Wrs$TxW0WHH3<FvJ1nf=uJu@v><&;yc>nl<&{XT^2VNW(f~+ zHMu3917GQQLl~J31=Nzl`*EU^b7xu{=QD6dxr~AXsfcV|XnAHTd%b5{FD!{x>()dx z-rLt&cADLh3`~3}UGT|YD^7NYMc^Zv@?iGvV4n#NSKP>S&uH88mBsVCZ2sQi_RB(t zW1nD*-u6T*hiEelSjSLf+f)h{1avwfwNzIN)&W+kgX`#M-i+5N%N0h|HjFoKW7o%| zG<W#TheB^n9#tkQ>`C^N?lwiOEU#6<fgHi>P)&A{N?=({qpYABx2IGO5$B+po6U{y zMP%XODb@2)GKTR&F0nU1fl<`s6nBKOeNUCgv+$LTP^m)3t*~KOBAy$?R|B#a_RPRM zcOzHH87x7`vhyd5C-Qw(S@zLHo0`O23y2jSq7ec*KtURcZ~t&|U}BP--`vjMl(Fy& zatPVKOXVw<%U18mzgL+j-(NpwT`rqML*GtvYfCM)PZLis^9#f^hQEf6mIqdUZY(T3 zJz3sTD3MJcZobYf*Bq#rExVJTicOS^yVToLn;xQp{JZD3c5)6IkJ|`Sh`1J+ABuxl z*201@M!}6Z9j_8=C1hIIAh*$#jV!e<$T;uK>vrY+_!#loiI=0q{@V6Qk;caJqM7bf z+s_|krXaQbfGxtQ+ggMbLqtgteC%sk!4sRY0AAoOK{5^T89-*t0eoG=9FD}2P{P_| zPek^zWw&sP#cOi}Kt=Y*p99ne+w^BZlF4<SXIGPSub6dS{m^hW?MHp!&{b(wOW>)% zcL>gS`k)wSb$NERE#N90(FEeb@2Oml9y+0s6sN$jYLdt|Lm8OP3`guvy9Z{x$C&`4 z-EAvBiXNR0z8K!rTr4Tv<A?Bl2LmLh2X+B=@h%SW*uf2VgtjATCVO&#Tp=TAoHToR za|{&V&wICfDOo4&M!v&xy-ws)0f$LXXp;=EjdK|w3_=;>Cl7x8_~DQJ+T37)g$TjW zm|=U$MSTrbetxY)L5@U0-hXZz{iFYo$v%Gl&jMJ!lb(evVffp!Qt~&t2ICL=O?#Hf z!HFetl|)bc`JfBxmUqUZclylQ>^pW82p~&Sl{~EFeP^o%5q9@X5rCDLF}-u^U7IV^ zAVhxeBg^p5KcvX}_J|}+o|jyfv^O2IRoauOO&QxG1%eB=Y_jL>L?VfUeBIJLdMdzi zZ77nIgR?21rqhpe<6<%oU{v;oPYx@ZC`ZB-H-hoqyCW~bi0ZZR=dK&n?T>JMKpe$o zM%n@n2*8VU9Z}{Y@%<3y;1A_vJDtEaUp2_D_t?B}S@O;db)8G9q8^!VjUL~METvT1 zWheB>0WV9U?`?e-<3Gjx7rD5Xjk2re+jM#Q-!n_2PN8hPr2|oCf9Ne1J7^#2tt-6I zRE;sefo!=;GzJT!?9bxKB_^G{>6p?dnjGD0iN*&iDp1;IV<M^B3;9*3cL(??!9_%_ za%1e(LChZK0T>YFsST5-b|2tlm0+@zB&nN#a6n3bt*B0V>tDR+#D8qQl_n`;o_J5A z%I8#_c@d_0C4W)caW%x6=4hl9b9!t;x)ebeGfVvbqGjs8!pYXkh;C`eh4rZNBYH2c zb?yA`knVlMshKM)cDA#j$Bs%F7*=&oyDyg5r|}k~F9J5Y_pKh6Sg$xPs9!+^0<C*O zx)6u;r@JJYNJ!)B;|r^%H$$R5E&DsbgdV$y^Jdrbntqv8Ao8UE9b{>4&Gr6wCqi#D z+%(}T?@jgPqD}HDh83bT^@fQTYzHVprJIV+l1_wTELXekUNopj9?ovsr7HFMbB>g@ zv9IGxM)U(~t3%N{9Shn~rw%I(qpZj8wWw(2ek`p*TR&)ppg%daEu}e3Al>gX?=|%$ zOe1feyY=Yuo0WTJN!cyq0>z>sY5R@0ge&8-+QxFt^_=vQr4WN;0Le9+5g_b13yOfD zlnKwWIG}{AkXmu~%15i-{h#wK4$n#(D6<>@lt-EY#eGqcbTNN=z~g585Xtab4V(5+ zYA;?|tv`l)Seug>0|w+whx!Iv0d0N$%hk#bk-j;{Sdqk=TIKMQGFNn*yyQv0<vWN9 zl5umPDk%{`%C4bteo~*sg#O6#_$p5mQ_EVX%Cxdfd88UVUG=x}<?Y{LuM>vEaIGJV zQd!$*WfhXEb$wbFU1S_QA$+vK`hMHP4{I{ot7mZga<R`xozPJlRPEM)q?rRhQdT|R zsMps_xJ}9eWu$JjJ*0ZWn=^q$cC`g577X6SO8{o_Mc3!}7df3E?f1=*Cz5AiR&-`W zBp<x2_>hy|`ccPW!gD`1U2p{7RrfM!Mg-t3BT>cL2QTYnN-i3jVMXdMvI`vf!Da82 zDRBvXH9-&W@ZCK;)z7;Zxc6<bIZ?H!@|ap+zdEfB*~B8EoOqq}^Cht{KJu^Va9a^b zIt}WjK3ENN-|KraR5Z-Wn`3Lgq#>)mXrq}+L#822$pFTJT%*u;506+9wVZjT=L<{e zN2(O}EJ<PVOFs0%Fn)j67gvp{*i_dL5}+KPR!V*t`;A&K=e^S!byi!cuMwir7?*j| z@|a9qh7VhRqZNA9gMs}$a4+Ry&&7cOx9xLeVH0kNphotHZ1%6Nf)%NGE|!h0II6oC ziG1Hn6hvR3*Q6v3HGFUCB=ihmQ$iq`oG&t?sH(1#M@HIGeLU-CVkr!i-|{GgtB3+I zg7GYw<ZSl-Ke$52We_?BPu5_aFW6q+-P>b!QF{R=K^Tuj*Zg7OzYFpmo<EjKRu*Ye znk4M2qLiE;#ap&VmhQ!{T|94|fcJnOX-UL#l!%+;liEjyP3Q4dUOZ)V6nTn10P~+1 zlskoUdhC6y7H}X%J|5%iJmp#g;>3s##`6+;_38&go{=)$hS}60!6(b;Pgty>f9sIu z#^=0K+oobLb=yXVR<-Zg-6Ep>vM7c#YpzaFR&pm>InjPeh4Hdh=R*tGJ2vD-%uw^( z_apPtPSt~&>(nA6|5>&Bw25<1-=gBFm6gNGR!=*l6#n_t+;|=<Qu~JETGtP>r6A84 z81f_~-au0`?)Z{ug>UWNT~0IV_O{6PA7`suYwraZRz3K9Mf!XV%4jVmfg#}Fm9-@& z$U73;=6!ZKTv`I)Tm?!u8#tl+A|p+4!{&0O#y1g~81e1YlREi2w_Ui$NDpBJI*snu zh&T&(?5IFxRq1vgK$)eS^NrbWNLC%}Fw<QC3as2~#@goYdvs~v*|2<lbd<UQH?VZP zV<AOW8QyHReJBmk0A1zP$FTl`^T#vgbd?4Txp)q<WKZ?1^qCo!hMy(J!KOyOlRj+9 zV-{Urs`1gKgrAmSA%8`*p4{DLL8fK%qZDhce{Dn3d)M+6=*-OEHSI)mKc5+O$^fDw zljO}%+k6HHwP<r+KM76!YCDuu^m+S1UFQR-L#jV|(M2ux>Uwcq_SZ&`9)i)5%xv9V z>Op+_g=}<gz|hPA(J}hb3&sg+Zt9Ox;kwG&5_aQE>E{jUj<wOYbQ=5aST$dfZt3ol z)A5P^M=J;{v)*Z_`zqYAf1cfxJq#f$-F@g{uCwdJr#CF+75uREMz3#?{*6fVUK&{g zsVP}=E6VJd(|@U&AFK0QQy2QL_r`Jy`F5R=6H?44O+@o_i`V~_+T<iz`3vcHooV3d zyN+K@W=Dqfc=)0nPi^!5jLzjq0&l4MYNw~7?&?izo)=HMT=p$%zTFaU<al7_aOL)Y z^dYs{36bVgT*0-I3u-PSTss@dNmr*f)rS)!W^|^Wsd$4oTYX5aH`cFk=^5A{;+C1_ zjsHlC18P?&5$1DXb3%mg2Omp*z#voJxC*RmTBAq+sfh<P#gF%_&LaNHr$GzMJ?ce~ zfw53ksp}Ykf(FDyyhQ#7$LditkrJPYS!Ud%!{kf{h|mo!mcr%%c_*ni+zv#L>{TEM zfUWAB9eP?y1{D{fE)5|X<Z0#9PUWrMY^PpT<+Bpe9vm@p)IED>D+lViw$rxvm~Eco z<yl#+i;{o#58>&9x<XKLTJY4W$Zk#aZ&;Fpe>l7(`7~hDzBQ<r%Gyw%SvTIZ$_@iy z)MwS=g~PB#(2#{Y4z_y^w!ktDh_IycUyQSi`&kI{`oSKONzy4bJz|IvU%z9}yNR?# zPb8I)Z>H@URgKXja8Wy5Ni#TLZqDL0jf9d@U#BI9Q%)>vD$$v;v;iWjI;iuxoB`#% zI%QB@B(FmO^U)DmO<SE%4gh4cot>?|AxbzjwrNIr^ucwF4>@31>X_-KW>BOoG1`K3 za|;NvFJU`YL1VQkj_a(+22YRdJwEP|4k)%Ej-+NfTlM<1W58sB2m5@tj0YCxYwCBA zLbi#?x33zk3uQeD7%yn`>CmP;tC!yB47=e%vshx8^I*nNG~eqyqYj9PsM&PHB^-q= zcE$kREJGB@Jb|ewWG3GPmoZ3N@&@q+6eNgXSvi3m#^sqUR+@68Tv}|vqkZH2*SOj@ z;UJauC-O0%cc!A-fN)G(S+*Ze7S;!CTKYm5;LeGy2JJ)By4!PP+61EtzwVsIoKP(t z{07tO3>_g<juIB8Mv)uCglvi<&C|iTbtk9Db}7=Sn)4{0T@pBCZbNdrwa2Ly)iExa zc)ZnP%(GLV=jHTJ_b}2%_@K@OYy-gb537;YBkG}KHTMBs)C9;j0$(LIH>DUW#u__A zEc;;|X0J<TV8#OQ&KEB4vPfH&78H|+Dga5B1I8a==|gqNCHg>>KKZW-$*|B`2O73A zmyD`aO@fEt@***!Z#6#u1Y%&VptMtkRAk(Kd07cM0C)>Q-K9~<%gKMq+w<t8JZ<HF zGbG?e@gCQ&>n%=ry)SvbaisE3oskz5mJSidK3|XYSgn1SG}gXU?M+?URMeN$kgexf zn%OZ%%Nw<Xde7;YnxlL@_F8+D9n9;#ZYq3>;~};o5V&OtY`ZE0K&g=gvO0bc|Bb1Q z8nRd#1l=QP0D~qXY4eaq<7F`7#FK;f75(q?ydMo)e1RF#F_xKwhP_Oseh^j&(vAU} z%v6Oud`O(buJ&RWV=rT?LE$=-et@6^Y|2T5d%jRf-L6=3A{*@Hq{)Hzqk#}Qi6d7q zaxQ2BG6J1-jF<GF6y)-?v$`Wm$A{XgmG7vJCCiKA6irgH4M^ETb~6xr=b-~hWA=2m zWyjEuDvpml$BIJIJ~4Q-n(Tm&KXzI2`ia)6$1Q&A?Z>V1L2(O~s56Gj30kWggO&jh z8~K;jmx;LNBrW7|{L-MU^N_%YY_%qT1pw;KxtJV)xHG4d-WmBn%nx6G=RJTm${frt zdu!l83PgjnO-ZJc`&uPkP&ynduv=S{D~V=I3PHb7=g2A#yybXA=s?dJH(`qw9n7KQ z4T~g<0lB-S6a9fClyGFg{7u~&^7d>WbesCDd+<5iGL<bL$=vObD;<oEETK?}$b=U& zTa||%+e#m#Lu}|It!$#vbCw-6X6jqhFN)7}=i_bQVRrrb^uKX|-H8T%!<OGTcyDoL z6Uj0F3E*)gb#mW847QhP1q_)lgLh4W{*{2O>+8(xU3|+1rwumRh73gTN#t-2)%3Wz z(O;J>&jWg>q^AZ<MFB`V6KoVScvy9jNMS`)trF{3-$&M~2k4T7L|aWcW|YL6r6(B4 z0r}Jc1sc;H>o)L>dmd}{-JIgk#SSqQX?__0yiG$<quj}x>?jzr=Zrpz`p^{tk3OrK zLlKomiR{GMN~IJBIz$yK{_IXRnNifOVm&jSCLNbKC;qVQY0C?e{MShD)Q=Yoa@^<k zhgO=+sy4FlOGVWqckqN^ygb_(%(yIs6pRm<PoE7{=a`p}jWcQ9`O~K~q3}oI)4P*Q z|AQH(g15x5^ixTO!ZX?era}l&NtC>0BAJv|{PD}i$K<)jAm9^`{+vYhxO>YK;DMC* z;kP*Vt5@|&HuFTl0H9a^sJ-JgfW(CQdC!FJexLNSO4R~=FT!7t2tg$G@`K}}TeAy_ zxxSAt7P?RjV#a2QPLMss^M>OU1a-2Osfv|o>iZ+#U&z$wZ{CpbZ%E<p7gx<7iBYe1 zS5iKxY4r~%t_^I0aX{v{8x;!>yO$Q>L$<A97V4dE;B2E1wq(Jy3tqv0J|8ue>NC4$ z5JNJ^Wa;xshN&d&UJw?gu3ZA&;ykD~_fglB6ZmW7s3c4d!jQY<rP@ktPft*?Ifk*R zm8Wf{0zw(fWu^wx$pXrWaBVZ=fR{HUJKH~Rb)6wP;P)O6B84<`pX!L6acis}dH`Me zviw=|#+^T&lwW0J)qjXfXUU3IgPwcB6j^)ddu+(>$~xjN#X9r!pCkm@2n;s;XYxZ< zD9GOcRueaU3qO4rIb@lHT|6FTK5euVI)}`FShs@hJDP_^Tu9H=Nz*Q;=8-^^xkc`4 z1Jf-0#$|m9X$uGZw+n>TThVjQ(sO3%dLRGz5gyj}nj|po7u{7UQBd(FDsjqgp=KPd zIdbMuWhnz7W@_uy^UY}ru=*%*+<M!M7DxKB>!;D^^bpbx4wZ7@oA0a7c#X$j;L%SE zW6146nIe1dp@gwZPW?k$)HVjqL{n#JHuU01+Skcg>KEsrVbZq??i&sD0Vv=v2_^$E z<B@cg6KcvxeKp-#uE|Ch&%(fjhIDp!D%rP75IgN2IiBkCUF>IXk6*;=l?)oBvJBSo zSUOR?WYExtWOJIDn%841<ua;GQK}-UDKpXZ0qI!KtyXS=@{H3N35h&L{!Sr8o*=VI z-l6Qa_h8eu^Y?~l7CRi<+p{T=8E?j_A>>iHk{=_)pYT6N-rTn_vHyFlL2t-mjj8l} z@N+7n{P3>wroGWCUtN+?^sPC(r}wuNf73f0)|+n>WH@B@9K8SbfLaJs&4J`~?90hC zEd2giL>Su=7<yr|Vd|m4J^g0(lo^L+b1h@4QlD~N-x;iz$uiJ;qKFFDC;^-MTuCwf zoZJmsEBi^TCo1uTXq2{6qiX^q`rg00XW@HEn37n5(D8owd9ZNvQ~@Lf9?h69_y^gx zw##vw`212K-I}vcQBU&{$`NQKZ2vLdc&E$we2kUJXX=No>jOsap#%eYuU1Z6gVu~C zLSAB6v*t(rDmUTTk^w6WY)mW6tGj+@y~>iLC17R^58w!_of;qKt?pWM51X8F8G_rA zm%jM!P#~=$Gq(P+n8KnVcLLp5y7&zJRi<Lhbxq13-+`s0PSMc=$Nq&g;Gan0Uu|na z_9uxd@*7Q<q=DK8xr!9I6p=m9pOwV0B#FO2sQpYt0<?`^?epXvG;$Ze^}&3h+UQI> zl~UrQMS`|&6A#)ZA-eu?Tet3NS#^y!AG1$&E9)9^qz@Q92XBSSC!XTOX{&iTxHZ3@ zj5S5LOSwQ^WmJ#k^xo^6x1787Ld|MounNXf7cpgS5Vepx#vN?S027HF7!v|@cQ`jf zekW;FOw)t<@3>Z_1-BuCXTlDt;|3J@M4SUyoAGCpN|?Qu(`VhqI5(iu|0g7#sKRg+ zgBZDcDPi`8N}pC^*OO!??cw2ufI2X6P<ty9^0a#DNPX>gZb%6!<}2Z}CGeh<wDI@h zp}dJhm+YU<J1P$utrLv|LvOb_A6Z5m{dT<czuhF~fI42LW1)NX$GitW^B`{qEtalc zNQuzu2C30O&5DCYjc@DURaMkInZ8@<pLI8R!rUy9RHZdyy?F7O%pEJYuoKq?G)utR z0HJrwo!Eeklun{rH&JDRStA2NiE>qhUP>|dYjs60>jH1%DD`)L?Y(*>DI7}Z2k?9x zLq-({!Bxl2-Db&XyH+_=M7b0zS;mQ~WeEMzqi|P~kPq{AyjRF(6e8{QQ2J|lrM3M| zjjibxAU*{6s`KEK(ol~c@}pXB!7ElWWFPvek-uQ|&<)p*VORGDUkkl=HEV-rS2Bb2 zYk|{}LU<2JiX6D~g4MOVaJ!cE&(-)F2S2Yo)K3b=M_vb(z(FO|R*}~{Z$@Ss?>uQ8 z_A)6g+9+U)-vwUmsr;3|x6CGhLvl&50sJ6DW^Hvm&cOQwZC9<l5mxUhAGa-sLa%Dy z7RE&uT5ra1B$@wFbRKL;{%rt#K(>J3#2Mh8;U1-dd+(VeKrJ;jS7!4MsJP9Yt8$Mf znwgmuxHU6ZWwy}FY^yDszP?|9>w5UD`<w#}s`c@l++Zi6`h%`<-DP#HQ!WuY?cAyi znEd}_M>FZtIi9sZltBWLrR;zb2MN=K`LaNar>j1$-hOKfg!bfvM8{j@7%+}~btiFV zxG6hd&QXJ-_AG~ZXxwR}x{WfJLoMJ`Q`)k!bJsMId5g-0sluCFn~R<O<4u>lKy~(4 zd$+*ArL0tiY(bu__d)Uvphy&mEYv}$0Mt%Vpl=OjFGFYj92(!plGTv$%UxHkI+`^0 zx{~gk*yw69vDu$*Mm`>Xn&$Y{))>eZT#^Dj1<6Ej_g8}+?tn0&lpPozM|`rs@uSHz zg+yCZYlN&yk!dQf;j~@uE-c`PoUtLl0a#eF#fsT0v`L2JVW@5wy|LF|G}|wKXO!ya zhHn5J%=#`&&%VPRCN#pcA>^pL*{Ds=Cy`Zg(mQ|&8gDeqaVD`L?hXyfYB1V>0mo0^ zN0flRhhuxr1L%%A6i5SKi@2%<uk~Ki7^(?eSznPpbb*5ht^!vO4#0)2%Pk9A9F-{D zoNNeRSEbaq^NQN}F6~M>>t>}h{aA<hRf^yA_5f?8CQQa}e^n;IB0x=z;5CslP+-=* zx|Cxynw`Gi^oLO8x`zd=xx7BdzPZ#LF$4izfTFlM2Qr8#{yZtY$;$yq$iM-0Epy(N zMV;NnJV0$CK&PmIJj;9)pkqu%=NZ{*W%D4U$_qe<B6VrJLK`ww!~OT(<y|L-JU!kP zz)2!Dz=LB2*%|vauRcoxon{BBbdi&IO>tY=BO%E>N4biJ?oYQXB&Qm{Lq$W6DXO0z z)j#qaA25E_R$}b-cx~`^`k?%A@5PmrLtV(th5xEPcMxN1w|2aD$TfqrE<<F)T4Zk) zGF)UM4eland8T(ZUQsfgBIWuMs-QA}H}|Dsxz}{8^yZ;y+x=Cy(_ZE2luczCAsAv7 zPpuWcPh~kLkR@sp?jHmax*7`_BqY0tGg?vCFXH?0joE|pTuP=3EjMG3#8B+EFEZyj zi`w+KiybSvprS$(P1F!kyl@Sw7|4M8M2X1KRbd7=J>?#)QG6K%zhkgp+K(`R&Q&cI z-<~!h5JyGy&e-Y3cgRi)YXcp@mhzU_M6ukd?7)7#LzgGzK2sdtrET=)reza%20ecl z7_h6tF(WkUQn5L#Bh!0SME;}W@U9s~`GphV_F}SIfp%E`;&+VYV-R-UfL^qvmt%wY zsK)3fjC`2`5dq{x_~pln$3uh-gg(bi3-?EN%7(;%vv1Mb06%y4+Z@Bg7fPo>7E!)+ z96Wda<-cw|x1UBsI`?p@Tc$36J4sbz5d+2@V_d6{<eFy@HsZE*=?A+nWa`+Ki|6w) zl(y;F)S7y!OG1V2;&<p-a}i*ko)LA0g#lPnvH<biI=YMKT?D2*8pu#vy<q8-F9u}O zckB{^#8TS?Cy7ZqfU7<!`0J`eIaESfDnqVVA)GbuhdtDhE<Y<Q%35~BTO1ozD2vKa z=N0!Fh1qTsG}1nj1K8xg0m*kP2aBzlMa<=h*ZcIxi*1$6ac?kfC6A7e2J1Ot{QK%9 zZy+)Z?6q{gob$?>RU*qT&2{W+vzB^C$=umfj|!SJh`d^vsk?76ce1Wu3Ru;qam^>P z5N=Ut2@BHzl;xVjF<{T1mwHCA8MCkGbV^8<(R<G|4f&3#{AMkl#uphYe1vkM4=Alr zvMes89!w!Z+Lv*`t9+Wp!OHZ*^OOuJ+u8FSs5UB+*~3<lL;(pL{1Xu%OIihS|Km1c zPDz&&){)gH2wOQ|d;iB$CVu;L1T=M;qamUfrI{x{Z8$b}<=KjJvTw$;N*qEzAiPa$ zT-8~&`1>O9?%#rJ*FM2kcG}>gbbFqstEN%e;W%Z5mAc0i_cNIA`EZ5j8gS+E+{*?A z4^#@4y$UaYD%!DwO>@_@?DT%#27U<S2d4UUxr-{jCrXI@#MeVWoec1mEOVDXq@T|~ zGjNS3?UY7!))!=N-{Bat71g3Q%havh%sF*t3u-3CNSy<mXp#0hh<aMrf)FO&m}Uz% zAFZ*ADljdW7ZK+sz+My;`9%5z$E+)8nNL+bNN7`+_vf2hq=0|}n{TKPXKes+gE*u( zDuL*PI7u`iM2bC<K}G3GLL%I(PS5U=eDR0sCMBWqH-{~@*iHUW-qxbOotEUw=C*LT z4~|)VsSOs8EeG3_RE1G_V^Xd+p<m$zCChWp7%u^}lV7I8BUavH8ZL;0ydgT65ZW(e z4?@Z0LM_^$WAR%j6$UQoTQJ`=pD|ePmp>X&u!B6#rhh2A>#3?8yzbn+)ISP63e}E% z8=wmJsdPWJ5#<QV)zt2ju=)+DxG@pw;z~9NkC&?wO}cIus{rI}I|QT?5wuk{u4HxK z`7#w@dFj#Q#i8VwNbRRqE^uHk#ah9i3NzW%P2h;cAH@a~y|z|CSgnE3mVcxFqL)Q* zc)sYl!!hl_dOH+IjhqRCC4(4IKzlLNR;z0`sjFlDRyX3*4)Q+3v+=~;wD99nI`wgt z;ajqt-Orz0))!074)1@_i~53KO68ed9Ypv9hS<k^Qf7ZX-ZMIMi>7&5-$}*g+y0Be zCqb;hm=`bCE~?Ttv|QETvsYnRN!xeta-Jua7I6<c2g6I-7IemA<WdHQ58X|)Rp9){ z!2OKD;NdrEF|pc5jw*)fC0p$|fH^QVAjz#u*ZlD3&>blo8f1KRQOVa57xav(rMrWJ zeoy*2wrZoc#`=KGh{aa@`i(4mcT}e7Sme*|kDmYjmeqy_bQDKi*6%&mvOY}&tI_)v z=Gls)L#Zkmp{~oJy?P2=0ztP>dcIz+o2}?CXr5V=>lG+<lLmU3_LV3yOzi@iyS7DS zK0}e^Y?+MQh~p~E<9FUT7S_uWTZZ3Rzi=MAG>!ta9yt3lWLij4SJ;H^jF&IojD|6Y z3CJ_B1|)LwDvWuiA$HvR^MSo$O9qQ<diYXA`1h#KF(w*6b{GDzb;r$l;yk0oV%<d% z_1OFeuj%gH+iWZXEcTg)SpcxCM$8NmGXW%Yi~iQ){4P33ydwr^VH!@UDt}LJB$7dZ zkoHXMA7y&aIXk6OMZ^iwXGH6P!lj3NJ@V?kJ0a@o=%PXm4k#IXC(K%P>E3Ok^%lZf zex4?|#Fuw(mD}GhXFH;lzbJQNskp~Y8MTwF_Lij9egW0*_ySy7v3Puoe_;4r#xP=u znGj3V^4N)ZRlc85{tNR}r2*;k`6_~A<Ql%{d-_|*&ZXWpW2Q|^Z2E*k{dc*@`@6Br zR-bSu4q>1m99Z0&I*ORIzdm7qj%w%I5RO@(Vm3W76D$${2Qm;nr#_*GOLc|X<YTXY zXV<MNEzM4dDL?W63h6ua^d*9ll)LL?$Q;_S!DMeHv2%$0;>yQ-H^pJWqYVu;NCFwb zBl@b}$xo72UL)r-!EaR;F0d6V1<fn(72jzqYIP911+>CMat~+Fs_9tmx~#5dX^VdH zrDCUydOhJsx&Mls-JN877ZqF?QavQ(PhIlF`c+2{vVEh`7HY`|u_S>4-|JfwRgd=? z&i68ke?_>q17tu1kqj)iL!Yanzo=q312XeHX_JR}M8%1C;cmPq8-no?F~pK6Jd%t+ zSie=`K=Yx1b({#%8q}#Bv)8~>v*DJN2h3@FuLdW-D^rs3QEglx^UN`&P+UDk|Kq>+ zQv0SgG&4f^pX3v~B)f?VD;MQkK<(CR3MWW5qZ+pX4^zb!qHsxfqC~GEgGr4pBQh_i zF3Nhd-Mb+a#L_9f1MaX)B6`Re1~zHp5{V4rC;Y+A{X{}C-U16?*+inD0f-R`2n~)< z;T7qx=V0WoIKbiy=^+(kootkqO+2MX-pbA+RuU7R*%<4`5ffN{bowD`Stb(Je}TH~ z^0>${`__fY-E2u<`2nMP@mPyGJt~RFvy)8RAbC0{^so=7e$+UfM5bGxZktPO`;w|P zEqFn{GpedMS^t?brO-lC?4#Mo7n47ET&Qk-Ms8r}X%5XNJ1xbPb#)N?iV1u#nX&|= zE?9BhwsKRPyplnLz239!mF(3afAXTqHxmgdL?uapoJ>?Hwf@G(6i`J+hhqtyHpnF# z8%cn`A;CCC%GSzR7yaPmdbx2+HI6ZeXn)Ux>`Kp#@*yGmO}6_5Yi!eWU(+YFJsuMd zRDJSr>HF@k_us`7KClT}lZ=pY=tl(ErFi3RY?gC!Log#Q_|yTJy!*i)wqreP1#4XU z0zzSU*50W9sQsnEiVkvr5_vRleX?YDbbQz~hnPx}S)L(GE=COMlk>|JL^)Se-;#YB z_u$KkWn5yyHR?{zE3L!C5)mK6hnp)bTtYnRJJI)%nwWW)p^Y!jnBzwxTcS92%GOr- zSIG2hL~p9NC^!#h4UAg{W=Tn0#L8JD5?74Lgd8f?lW?+ALzNtSS<>R_!{GV~avu#m zCXnwUE_BzY=F=1>NRVs(vL+DivXuO81Lgh#s+Q)u=Lgb<Id>aP`7d1?Fec*d7euna z<LCX8I{gY;AW>zYbPxQR=$S}wO{Vq8@M~aknajeOlo1IV*hRh}eCZsb0jFsldGio4 z(0_IR_0>WwSE(UzzcgT!3$fzc>(arnZA6BO{KY<S{QF<Cegzi0&%cO1ZYUqKoGiQ| z`QA}&(&%tZmU?w5mEftK0)KQzpwN>WvT{$!m9cmBtJch->=lyYu%UL<1-J8Wj!wNN zor;LE)F;n<e=euSRAD+T7wmg3j`$%dy+V`eZ=!$uPTEW*e(yxpK&i%@1UMM4AZd>3 z_sPAwxkAO7m1Euk*xGQ+mCvL{bYk_@DFe>#i2-s-<f>ACGEIi;EKZK~C##WCgF0_* z5$%uHF_P<Ij?fOo!uvI1I|}s%=VuuGzUyi!<SbA|^!bX@L>28P0-O<Bk;^Wg5Nxj^ z3OrLcc)v^=JJi8b+okAudnVo0S!Y#DnPVF_{pG}c@e>->mvE2~EipnWNiY3_g3!SA z)6AC-KS&TMWvm}1^fN=f!31VRHK-s0?7z!J;g-^{y_swfAKFF#<yavGx5mI4$UB!f zr2c8MACW_ch!K)|C{^TGNx=685yA&A*UvecNhFfs#$eT+Ni|&#XzZa(lZ;K${0A5> z=tQmp7jy6lTgF7itv+xepRI5yX(07Xt};370f#J{BTvfgBQcqeX5d>SYpKF|`P?kR zzr#q-E4n_pP#sLsZSYcNGVxtBRpx0DC)VoWYaz8Jg(|uNV7sVrG!1^I?))P_%+ip9 z>@U^?muNHXkk-Z^s>;{{<DDExY**=yr9_7(bKe)^1Tsf%F&!5CG<AB9G)j{vKp~Z1 z)bcAd&V0Z9{i-UTt@tievC>)bl0d8Vu|^+Tow4*;p}pOJJm{LM5=hBIE<ty2@^stD z)FovVPFZX$F=er=kR&T45ms&#s4tz`<8c*s-BZ=tSm_f(mwgXB7yWPGKUHwtyvKE4 zQHx(x(Q{O>d6r){OVrlxJcx>URObuY4wt@V@8C>nEg`q0odZ(r@TQw~jMb8h+5zpO zxoXt<ksI}`pX8GSsS<~D9G8kqjGkursAhB$`(7)=#HC%Gi`L9isJ?!C<&*T15PYp( zVYtlZ(LH;kWkrHhOLJxA&W6DxIbiUH?uUmu%GM`I7EvH!{sV?&!<oy=GM<YgJ;qFi z$e^*DRPB}sOA~wv&Ux)E`g2n47XZR$&{1*$<OvoTGJgJB%e3!Y<c<b>o;xp*|Ho>R zbm?HJDyP>BoGSG@$&4eRtd<GoX5NT&^6Bri*=rr&P;kP{JnwOu*oo7>c8Or>`7Iko zyZ}uCQelQB-?FGUSP|>ud7;;v9Q8X@nOv0x8QSW9<KB_@&jg0>qY>Jw<Z~C}*T0PJ z7Q5M4gwh66{)z+GZzP59do)aFRj*%19Tem85%cs17QVha`jb@qcl%Zl4IcMsfp71a zu2Th@*u)VpWfLEHfM5-K0y^(pL+tpqD1VA%De;-!$8;#^x|>z1k?qrT_Oa3xLG$<| z|M2{^^U3A+RgVg=ljZ&Lsm1$-<CP}rHF%l9<7~n?k|KZcUqnr1D?E?X@Noayg%=-5 z1Tk`2(MG4O3};cM%z~hB=oHer;>G-)I#+U_7{Eh&VW8v$3G%5B+MbNqFzm`Nq4j$f zcJq>$I%iDO`gh&4x~4z#<@c^?#u20Zl(+0}K&lJLDB`VmY^6W6iR-I(oSc$Xtlt-M z1hEF?v})jXebaeb2)`>hx|JBFE|{Hse$woq3mYGprI^o_Z&=de3tG#@m0H;HB`A8W z*4n)9Gp4~{O)>FAGST2{oWP8n=6MOx;LLg|38}bzN-%eZcWTd7vgG%jzh`Pl{fvDc z(VGFx11BGW>K^I#*D8bKDnwRZRAH?j5u4MyPkjsU^1G$O*?sPrU%|m-ZEKa_Wa7dt z;{FO=<4Iz|cap-#g^uTUw(1?a)H`&+szx6k#&=5X>rrT%xf6(2-k+$UIWkYEm(0B^ zpAP~`-f4LU5w4T^&p3DA;(StGAaBi>D9eSxJBs(I|C6a~LY$_&dSg2LIcr#yT)4+d z(Z*`KIYzm=`ySYcDfXJ=dy3pAr`&WrZcV5A7ahT+V?W8h5oNv+9N*n3d;=mTpQR_? z|NR>w2k8A=)oj><BHzLR+gK-ab=SM{Ohw1HCF7XR8n{l%kpW59;G~%&2RH}Iza)*` zaT+))gQ=ICUz9V+2)*|2bJzmGAmeCP|0fc;WH>G=)H6!zGr6cq$2?T`ysVX>5)k%w zNOXtiQ-?2g7O0y+l@O_M04${mKtN~+kSlEAp!FGKvz+?DoIEvy-L|-*p#tce2@uf% zt6-6s;mWwyf~hq|KTP<u)!!kM;&>A*NTW?cJZBe3vSU7-SjgGQ6n{qS5DXISYb;Kp zj4#Y_el~$bc=`0MoOvLkwC%F6JLe^WD|$e(_D0Iv{3nJ1g|*MxJs+Gqj4Bk~h<nlZ zaecp-zXc%dKB?`JaOp<;^KlUW`{Cg3t8Ta4%l9X01NUo0O-d^tHW&cog#{HFA1ZkT z0z~(V=6AL2(a(H8j%U_fu?^67swY?Sh;5mox>gW+G*g9BNHjl|i)Yz$kD(s5yYmVM zi=Kfdrt9q{tIL5vuxDwDrfZuiXn9$4y>+$$2$Xd7;z58W0!k|~8;I`3IMUgk_dD^% z;*0?zZ6P1J#bV%QqzX+xB-o&L;Yz}Vwy7txrNgq;jnTjh*G6~qw=5C&pzt`6LX)?b zN+wNq?pKzL^z;j_@|vNm;freHr0yROmyMp&muU8%icxr*G-1>Nc-H9kgpT3#fG8wi z+wJCtyv>~g%@FJJw&k_9MU*)Onv|2|S>m)?#&aL?^P5m~3@_2%c?DEtFBjpeGHkou z6EC&<czwjv13IQY?J0iS)8?e~+pIFXt;3_yt<Zlq9<=)C79qzn-iYB!0u#@e3g->S zcYXf~Wrf!!^=JW6A9Dl3URJ(xQ)o>w)XwMX|9_@)D!Z{T<*eN7X$dC@%z?9U84<3n zaa~*0r4mqyd`f$pPk#ALpy+7@<bH$d8N?_1fCQj6+DpyjGLoA7AW`xFZPxhPbSiOd zdRQ(tYSCKZWJQ4Iv2<tOHrp(<aj)YptCBlfE02vQjwt;HQvsU&zf?v($*?14?XUVW zX|z%#ab{d`9J-X{rTE=#Uu!MX!{SB0-+W+XWGU7Vn4kR+IGF^|?UK*j?R8xuQr;&@ zzj-C%MjHsIiS2sZkXsJj=8VrstivAC&}W05sSV*%YV9`VGPCVC3BKyU(O^k&g@lZz z5uC+nqP;-eGIp-sO+Q!PrYPPwy-A@8;14UPQgJ?;X%ja`ehOz@4~`IWsyNNkb6c;* zq)GcLyl!#AC(YjV>71E>e%hOS#p7dSgQ>-4ZNWucOU&t=Z_xg37s?ZjiF0V<FR~>; zy5YwDkgDP08$i^~e9C2-xx3b5Tw~t+>bZNxPrQ+X|7cC4qO7MV+3U4-an8O!SjQlj zp4%p&T`3kk1~g7MD~l*m0*XM1kQ{=I<bkr9J_qEsrJ?bJHI7WlB+?R5r!*Xj#3;)k zaj)&;vL~xAB|h^U6aEAx-Z|?Ai3H|FKbtgI=k++-&GO*p{a&}q{uYsL);ODOPwqx< zU)&iddC>xYV8feU(ZalxW~CuO3Eq}VnaKaLTcSKp(}{dx?A*areXGE&qKhX2toN}! z*(RK>ovv%wMxUB^@8Jkt_DRre|LJV(<a}^D1j@^K>7PVV=Fu=Glg8``JxU0zTw;Es z5UO8k&UL&(EH6QvT5H^a7as(xsAMB$`=P+ps~tMAs-YVse5CJbxsd!Esq<jlfG4jM zESvmV)BLWrZ;mU>Zu67w(=vxt?8z@Yvy4aUF>$uTn(n2Jy3Jq=$FqPq_dZac<z;pC ztcc8oO*?tr4ZXrauR`gcZW^c!E1|}6+!5DV`|oC^+&}vNC4(dEyC@Lj4<2+VevI_m z6TVjTCIQW$(^Smy>PBpm%&Rd~!#5&8gd|W?mVI(}khyro_!d|JPZgO5vF_hYYWC81 z(Ca#Lzg5RA>X;XanKX(^`r4fKW;OKkD%tSXD(VPy0k*4hQTk9HgYaV0J}~f2`H+!X zwfWu`oGvrsLD|e>&vhK5oej$$hNu$8DO`R3f#H<fQ=0Eel`9EL?(SX6vSS3ex>;h8 z;Yp6!dV26PM9Bze*@v7*9jrmkc)X)DVQsS0vE6_;_s=2nDW5Uv6o6$yq-@XM4}iiA zIuPPb4N`qkG?Q`suR#?bNEP7FBH~gp{z${!qQJl7om8XiD#bP*`C)GhIhi%!59z&k zAuVzcarBjfw`-Ppd<Q%=3V$J1e`r_JO^lp-b2V&>qZGwsUXL8zxELOh9W&f^`=hy& z%wu7u<{aK6w9+s%e$dY1@xw=YPAaZUFrbYn&Ohp^EY&2;P|Uf8%=%-j_G4h5FR!s! z^J~4B_@|eA6)+r#NW;JkInwi<+y@48^^k1}mY`maHE4oeFwTWhsNO(X2??AAIIrWM zK6zJ3G71?ssS3bpIji`YsX7*aV;06w=;;ZCMWqMfkx!*;+lVuMdkbTWQ<|0(mxX!e z+YEeiRHIJTPiKp?=+nz~*(8^zh$F2H4=?*))r{<Nypb_|-FNpZh4qiniu{s&fA^{s zf)@u3^Y!7(-RaoNQFd(8&Z4_5nmn{@>=x~xSuyq9eT!|2ka(&v(^@V`6*kKu?|DDU zLFaCdH+Q&cjNwrJ6g9;`b}q7isfE|A$yyyL{O^8I@?|w`edtC_G1M>T#H-PP>s+yP zv)8@o@^SxRMqbJNi8#sAfhX2sS>1K6Ilhfi&m6Cr@+>OCkK`K;opUt38DnWsQtb4S zIjUF9z#IhX2sfvoy`8>Azr|Ii*xlKOfT`Tn9%ZRtCKSzie}&^eA8yyNMr|L>(NBsm zpZ@C|n+o8v%=$>!WLA16(zz(TmnwQNkYJ-K?$laGuyQL7aj0ov7u0TK80aCi+4pA@ zBy1}lgZVP8{lVO>wgsqDmf49d{flbvW3t_7pSmtj7B?M&=stDq)Sp<q_F?~kLUVR{ z%JrJU1KA=+B`)kw_x$m_a%!VmTC@APo!{;CYS{5FdRJ}ljD+p$GrjXh1@UBls3<`4 znI;1@WH!twh<|2$Zmo3Fmdsptp2gs^ga>>sG-g?pJyVuGcgfDzn_`Y&zm9RdenDM4 zIrr?mC8YS9T@Dq3MP>RJzW513B$?J-n|sXNVL_{_mu)N7k$)GqpK-2pHa@||=5~2* z>8=W$7_;L$O_p39|K!8<_pB>665)l2q*JDQxIcF@_k>0`UT&RuqIv4&s9uJkz?YIP zPZt@!`K$;3Lp4D}MgmMjiLkc<psB3>>3|IzTov7;f`Y7q2Le0=*{nU8P#~!UFRrgx ze?;*x@t6`jNzNbF28W-y4!iQ>7$!nP-b(@kg4%aT*m^?bo0z5}xE(`y%A>s!cp_+9 zS<@-jKjPhU_yl_0E_C`t4m<9)AK~D1h{Z#T-bSr}1DU-YGOTs@8@iZ@xDmG=^TIRr z1OLPc0b!99TDrJDUOirdc0`<Hj0Ry2SGrlXp!)$#V~5*`8!7=Js>2k_IR8+r3O*uy zpLj>wZ3eE5&Vr}0V8bk+2pNA3S22Pw<~g7f1G6)u?d#!04NikvOzUG<Ya7&}h{0Y8 z(#I!D<I{O2TQs8^`0L%)@U`Q>TDbkF{vJ4R4L~o<qNfs4+<IIOcH^_~WL_h77H3Ez zM|!aji?buUeX*}7V#}V&xc-yojlPGdnB{G`<l44t&27R|c49;-l%3&5bMX+78fT$T z0`Ryg!~iePqu4m4QS_dH-roc6r(mr2o%p;_JRA;uOlH-sB^-avicinMkxZeBh~G?n z77H)<v6lk@NE*j>yiru}3Q}l+YE2z`%YZ>i+g1c6dD3yC^%yAWpnc*&iD@S&#~fY+ zfD#~oS>b)F=0DfO>IQIDEqPw+#7Q#A7-Dqs3x*_)U7=&HmCEeNIDBN$BCsm+u-6vp zsW2s;p}Z&DMx29L;$xeE`0-BEXQFJFfEza~^^ld}xLG(YE^)YR`xg;Sq@V|I@MbEe zQUAYR^Kw9)Xg>uz#>YJ4iE=mp8#2XzHW2-JJ?;HmHUyND21N-H9k4xgkp}j8Q~Uyn zBkq+eQ6B`eq3%tf9w;i|IpEqQCG^dbyG`+@l_ibGaJs{IeS6&Pk>tBF2dGapwd`;M z(sCb%aiIb(G|`|vN#|i}tcUsGIEL6gn60a6Wbl~zA}`ZR1)BllTF;&|@y5JnRrKNP zzO&HI19%r3gZnaBV@J+3)t^ZeVs7wZFN9fc#bM$g^tfjLuqOKY)z+acSk>JgRd8!s zMU~0jj-nbQ>Z>;n-!3nGG};T#K_^y2iy7jHxhMN!N^0<k1nSlHl5N?G?ijuU0hHV3 zod!#l_t!`iC#$^PJBUm%h$z$da-02Xo91P+=t;Qs6@AT`@C2EXB_M}B#=Ihim~eFP z-skQvVe;#s&-vJS+<6P|8Hkr#5;DtkI$porZM+V>O?(tQJQH<HZl9FYBD3-h1vQ+2 z?VYN;OWF5r2#2<a!p0=r1=W96u0PKUkkU%5B;d=2@r1qjKXZvnH|iBhL0n&)P6rs^ zSF5A+6=?baL})z<Fx+e~0|AES#GBtG|LTLxopH{^Tcv;}0N{N7)io+^B!68KMR({r zx7k@HX+0Rj-x$P2f(Ww-n74H8hdtgp<a1$TAw%M4nO^5i`iUPBP{DM>9Dqe{NbPgR zF)dnXo%pZjS?55OGs);_B6@sHHmdqaTVfcx-k8r59ht(kQ{?`t?OQQ2*<0fNqd9GD z3H5$(pTxGXs~9KouE?I2SPcgz1v!7badJVpbR((iA>3XHG=J_GYMCQ0fObBKx#E98 zf>DDmK5k#14i%)U0oKsPy;t_)kVScbr$l|y#d8LtTUBmjj|&A_5fKdh-u4iHhtl%K zPF#?ml#`k~X3Jurm)0`9E%48O5E-&tb`gmEQ(dP5%80YxSCTe&+c{ZIT|-Yzp+k%- z-4}I7sOa`7%m_;!^!C7(Tmot@E^NjhddmvEedTC@FY!-=Y~=h?aa4D}DaJ^~73C&S zVbOHh{xypBSc91AUJdz1fY+%%-3bw-1GsAdF8oTbrg{dTb~xPn#x>7vqHwME*P7S} zi|A~fa<)V2F+^90@)Pp%b-;ZS^8~AbvpQ0Jp)yBTrcMsTD4TIGFZr0+BJ8p!s+o?s zQHRm*SC$Yce{{q=T)W+>th+{#dfVIG`86J>Q~A~!=E6B}i->KZqd(W7E_kB9NU=~B zEEv)OE-J-!-g&4LnfPUkCzDkVDMrY_ft=Sn>$5wWZ}#ZdcR)yRAzO*vNrkRMu}uvf zvQiQePVyZz>GhlP9S8N<z|E-Qt517V7`2(2#JvLix@K2gdo1l;7gRugnNV=;6~_8u zmwR5h_u{3nF|=h@UmM5ZelS*J#`k3rwwVuS*CD5H%0a%kk3DwF+THWs-RA|}u`Xe$ z{s;cMVfiD*|M&j7-YHSULMz0HCGu1?>eY?-*LR@;t2JL7R|_wmg%k<FL1WpR@|_b5 z{NZ#wfsHs!MF`*smXJ?u?;*XFj9UvlFm){7_omKRgUZtw=wgH6V~xv3-U=Pbprsn! z5aKn8y)$!5W&CC#ts>Yt$0nk_;38ctQ_$77bV+NlE1D6Zo1}AM9qZFsFk*&(S*`qp zS5d^qoLI-)*p?9S;p0TC0{MzZVv4+1mICMy!_~48<nQ7=EZ!j+RrcRA9QySa(c8o# z1vU}v!jfP2XBs%H`8s@&*i)X3tXK=k-@B(`7|)?1GH{5!!sz@<@FIm=#UP^Y2+X?9 zk+ec7e=1N4VP=EJ-HSV+;=PtplBS|S*2Qt}V$oZ@a<@_U0#)wC?YDbasWZ(-&(_!o zE)MYX3|(W0=3O!|(}zLQ&Hl$-%*bx9hC|*KVIERs=P6wC0eHL+)<(qYi?>L3+=nD? zJ*->5&(N{=nzk%BifyN&PgJztT$>cfKM?7;A@bP&Z!jy;8W-F6;E?jDh_|WW2qJb3 z%H_j+c<}m>sd|}X@`4_8A`CnS1^_0B+W>fK=sI=cR4?e$_V$uAzphV1Y33?a+}}k> zI1y0&>pa|U9D3=L_`1}BRFknCLGZ`$dtEBSfnfe@K~OWRSdv1qZa(nH#ebKLUy8v# zFAOg<ezd6Yty!VDji~2s_zfb~CU5A~g5<~V;S5)~)nMF*Tb2u<xLzJQMRj|rsr&Tj zz#*NggU@fU7WP#h<q7ob*9QVl+Tl28Wcp!#CK||_$~odQb&?1Hrr>+0w%{|1e2(Rq zWNf?Ke!&h=K*Jfv<O_-|@%6j$O_6(R@8L~zp2#!6s{AKFQSzD6ehAyVL05`bCN@&1 z+CF`L2Gb&6zhHEDc6Wj8Bfhl2^{E-QueQN@=MtI4K!s^E+eu41Y0A!LqIXM?#zbUG zNiB1A7(RI@m=7PULyIx<(G1<8iqm#EQc)M~Fr?5?%c5g-*#0_{0B{GUhS&1bjvp+7 z)W4ATa@d$PDVu+w(4hv7!*4eZj`$#;C#TL0!~P2u${!P=*G<I*jFY#)Fo;IU#TZ<n zv-o<6gua(_;-Y?Hsop`nCSXmLT$0CMgsvSw8^7c^J?uWS<)*EeWuItsj1eIr2>IZt ze6-`$9HH;7PSe<<rjA+6c+DWz;GUnK-P0+9*y7zE-%K1*$4pJh+~6Y)31Q_#)FU0) zhb**xz!{oBZ7--bI9&40C2Tt%^O)7z3!p)ocwqZY2F@P!>e(I!Jni|iCUErE?ZoL~ z1akWW)<xv;wzad2j08n&{%WRM(6;H=1`s(6Fc0v9RE7oO$`W3Qi`sd6r8^cS*gM1* zpIkZI3*d<4v+qnrfXj=zK{OSg_1d^$i&=}OJmr(G*D`8LUl~V4gdN2=et1fIRPpvr z#S;MgoQ`?TZ+1C5hwlISv6V=fk;&)5=d46;61T8RJPc|H?InRBU7OiBVE^QA)=(Xq zM-l7iU)>m5kr1@zno0GMaK~ct+-+w-wt_fe6qtIj?Wz9i{<#!~WdHYB%4xHZhah-O zWfb9Ao>SY>V9}GSWV75%U&j^)oDPja;X##-3pfVE(%X3Fsp(#?#vdJceUlBy`f>8# zQuUqqOAwc@YuypYgU|L`SYE#L<+ovP(wE(*2CQD}`i@)HZrFXHVBs_#JDY%gDVzus ze0AG-=E<KAQr@?@Q}8e$>?-~K62Ezl_ib+D<EKa6&zkPs?zMdLK=)0b&M>gA;O3`~ zXx72VwEfB>=a^~-W{}&K>#8+m4H8#twq;BX<k5G~kkGe`w${P{3%tD52cHfvyL==F zPu}jH)?2WY>{XETNd-X7=SqZT7B*ioR#<7?sCM7YFv7nCugrb@Ku4$fPsEr?v$(3} zX<Xzl2?w7BP5<~Q;M*Ja`8n@j*A^bW58%0dSqw(zzwSIg-T!aS{_E53Lz;_MPKdH< z&9+JTIFTEVcFxAJu2t2TOg?+c*SQ{dZ@4nrBvzPzJG~ZTU@|ce_+I2zB^$@onz{_M zxYe2;YIYua@}*@?kFhl9)%X#;*ZI13{d23ligtrYw@eTLd-$>b!LeK^i58c~SHq_N zTiTm*(0}~B=DzJAYDuZ~^OwC#$osaO{2FN@5~{h&8bJm}J_*&+%e5ZLnkCGAUEUhH zyJZ;fosQkJnhdWvyz0U&v~aJsIc+6Zovi{722-)--h0!rx^x1$&|osq22&FcrnZ(J z10QTFuhqzHYyNXgt68S91hu_+*sQy7mB$>j1A2ZPbR^f0t2dvlUe~&Dy)#HhzG21L zRWCvO)_%F$;_ojyUc8g@zE$&eulCj9Zhas9ixd}!DnE^jFxG^{tn0N0?;r&xW+3XY zY|P*~SNh>n(SWFxt*pIlA`kCST~__%qt^?*#Y*d9ZhDM);0oTpeC1r}<b|M1jab&l zQ%TLce7ry|W%iEID&meWl3NwGeoyjG7p7i{ZdFW6%N&tAXwab|;Y#UP4vbLGf%rQp z9UZLnT5#I`IOr)mv(TW4_)2UKwo7aP{=`g^T)wv?+{VOrijijl1lrh&yM4&b<FP`b zbIvnWI)~f5$Ja#~l!#g&$O#=_I}lHA-2oIXZ!pM;F#6p2vXC67>>yO>PQ#D-E7d7{ zyev!C@L#)Lh39@v#qgev)@nnan0wljGjE5_q<}?ZC+~YV%(_o~YI4)IT>LOw!|;77 zg0)(rELVi%LQ`b(Yc?)xyHqVio=J9Hf2|OjnuzTU>+3CC;`v58#rgXp?TGtai%p~~ z9#y744!ta!RrVPsH(IyFQ2+tr07OQCWhV{?@WXhgrXt&4X||{Bi5WPSjkvSkod|C> zGk4EFma44TO3|yPr02$=*`#hh4!}D=hy_oQJ9A%@al~UZq;Jn0aXj_kIG!b5EneBi z39tYzesE2FaWyXNr)p)cPw(Y-cl(>}O&t2QuyHnehLpAZ#z*Uk_TYrqh+Oi-+)aIr z=qtmol4tO`s^-Q6Tc;+u(sDqw5XqWJfJF^X%RVey!o;nL?AYYx+0eqh#slpQb-GK0 zmm<8&oShzJC*?;sEy)e8mIWOv&dV>)RlVXV5BS!jdJ2{-4+h$3<xgXe<cBM~j2@&; z&StwQXiL~k*lwvSF>DXe!2Ud~5Q(aOGeCu`su+YI5x@Y_Z<&TJF5lHdgzibumP!b8 z>P=xm%z5=_fMp{eMYy_946-}L@cKLsXUT$yX*#lD>;C=9ZA6ypJrTatr!>b)%^AmB zZz>Hg-6$D!)ugPLW$hdX0cVRpoH+Q?dt7KB<C^Ln4%BfqKd>=BhED4jzI8T!!N^aU z_b{4I^Er1aN!=S;U@{|&+$qxI0=8&mJuITfJoC)8i~?a}>5v^6i|9y49598zCKTe0 z+tLzL`{##@PZXmLXSfmg359w|#d%)!9~o^?HCm(L=$VIW+>dF)hGvWX_O)3OXN3?= z?pDtOw-mC3c2$O|+In`RuD-aoxq^#A2ST6=#%GO&tVovN0K}3y`skF6JNe43A$92| z8#YRh%7>2#7?}7I;e8WpGS87iT2AZExTFLhg|Bqgqp{9Ad^$k@(CM(fAB8S^iP@?> z^nK@=b4bp-NxehdwQ^7;WL&>6zAQcb<j)zkAhH23exvkIyNgPDwE+;JtaxXYYsrMM z+RjO7Jz0a9_P18W&dnTfZEyBZdF!&zTZA`FmuxJm&yUF#0kXXd<eyDtM_O4+a4Eiq z6&>=45mV_45PnlCh?U&bFEhUCYkuFnqfBUhww^h5xcY~Le^)8tA|+FEm346|b(JC+ zpT1}b0?wWK?o(GY4^cPh$YFztK`_5IangE-qZzrkFfHov<7?+~{C#mOV9<Iu#|~-f z*oQR;l?yL|DGoL$9v!tI9MXnYbeE;>JQ?kiFj7*vfY&k#9sA6|LCCmz)NWmIq(6sE zYWHk+YKC1fN)tpUMeBR~a@JAzX)Y@(*Hhjl3s_V+eH>FA)Tw{}D`~%)M%8ug<X>Ei zZQ6d4+HQCdPoy7rnvYsG8@ZJzX;jUqi8NDYb%G{!ofiYGV(Za|3AUw&^zWm<a5GJP zQJ=!%+~~UI+WpgZPbxPS&WB`4Y0F-V4bVqfG%@#nTy?Md{Zqo5wPih-^a+w^PJ8A` zI1@N*&_+{Vf0JQxCc&-#3R$u^G%qIN*0a}FGRzjHvqsryEdp4)8wWSJM6!7w2-n&0 z<QjJu+r~JK$*zo+{k}3-bWk7zFnu8v^Ia%EzKGI(3`@4`bDHNm9^i1qa&$M3Zcq=v zeZ*@;?JsDb?m}IwGElprW<MaGj>>L#e&lhgSz)X)%e)J8x7=u0J9&m{{DS5((N&^p z>*B;Xlpn6>AmY9I`+8j4&3T8h{T)q*FNH6zWtvD@OQs_-HBxP8nx+0Su?CqIJ?(jm zf5@s~VMtV~#ESkc>+ZI|A%z#$F3#VfsJ;YIMFoa$%>V13+&VJ(<(#hI4adql2od@y z8Ls}kY`0NjZn`ZARga+Itd$E^;+@rIaMoXG*qBNVDuXYwvo;=^z{fq*PtiMasquEG zM!Nh%Dy#-Kq;BhE3^XM`HJkoA*t5Ny=^wunB^i%WsROJpjzW?f0Ne_50_UrLXsUi? zDjS~ad-mhv`H->8)#%wX_8}kJXLJ-(4`1w=J@#|p{b|)^_HaZLQvLS+*V><k@83G| zM?-XDo>Kv(LiIIXhf^Cp<{<WZ&VuYyx9TzbSm{dEUPzA*(z4Gf!{(0KXoh6tcL|@% zF<!sRyQRXVD~N+5i?rPCf}^Uswst>md7LvF37R}l-1<-5%Igj3&a?k_(ti7tcwW_E zs%BBfBwKh{r%xOq9Rv9GX4Z(@5~Q9PSdjo$;&Doe8SSMa7Y_3OL^YahKTi~;?-3fQ z2{{IJA~kJ0&zW7{8HhX<biHh9XGIjJTX{Q?4FY%~yZLM_0FW9~zDuFB;0SkIkTme_ z=3iM{1_4;>#Ke@5*!eA#-4}UTSCO(`WVH_--|cwJ`etsPD-(5`0!<v1-3(H7o!NbU z(R#`SzMn5{-+@XM$<q%(MrWHk23eX!3`DjORY8TOgDpz{c1Ip}KLQq#mKlnGjyQu& z=Q%#q^xX*vcPi8!kr{yCw%u$=1j8J+cB=zDg#m50E`ymNm6>joOy5c=zb7^Tz5dhc zos!>JAIP3H8*|T12;1?Bn}&2asqIIwG!Up!bM0n%(cRO;4BEU12>~&w<m8$`fZY&V zR+~*AU(=JLDrBorIi?h3QB=`(?I}7i9Tq`_sVE;Qrpg(J1R_QPE5Z5{{5j9!vQ2&& zLhw8YxlO9d=%c#d=K?M{N~<97MYgO8>h?9-^0s_qTF}&h%?;0qcy+OSN_%Im_KkV; zX{Ri)dz2oWYD>ay&9eUM^RU=8m?Fn9VOQTkFw%l%y`OhJCHO{*nN0&>K!2j(8SlnJ z5#Zjj0h16IYA@H`m+Q1OJr*a<rPrN1Xu&1s!J;g(_Ed7?qtvz)W7HGrrjF@4#Plpa z#J9-MJ0UX&fHBNq=g~06DAau_J+z7&J)apuF!Wo$^O<V55$MugYX|_D#}^;~kql^5 z+)`=FlvC*MFn^b;F~rswD9*5~<ZL$tNC03Lh1*udsna={^l=eiO+W)eO+ai^ryBzq zr|Mt^Jr?kZ)8%Ai?}H-7f$0W;S%C<VJvb2`pOF?Et$_uW$jA*y-USf1O@*KreGVr= zkSEc3;&rq-axTm<=ar-*+Xx;on)#N2jN}nSe<90VM{k2g4~U`<rDY}Z9eb%4HHx)0 zCPw479J7)~MRi?~_j>xS)-|UPpmDtO?;~;y{)mRXLz$ki`TNYHzRPJ|bUbcp{8A7$ z6sY&bWifkN7*VhY0yhki>0u`AEfg_b1Gl8;Xt#-&)TJ9%@_kvELFQ!NDCnJ|nL(qO zdQUUM5amIYP#0epA2igr$ZHJ&-4H@<N+J|9?E-gKq<dE|1Q`KckY%QxgD^WAK$50F zq-`}L4m{=x)&=lpZ3sIJh&8_<F<NFLMub+B_5J4rTw&IP;x_A=bH-UjoShjsDiT=9 z+38uV$8u|-s7SNHEm7B75WMFf+)fPM;t}0j94DuJ+_T5BPI=~qwRM&utgE*2DGgH> ze|Iz|h~^deW<~d?w5^q_pHRBznB|usTN&h`fpltHMfW+vhpHcxwRsr*5j`F*uFB>; zdivn+oYPsfbLeyDC92gvx13N<Zcn0FvV}Tx6v~{+Ja21dzndFO;BI56K|C*ajSOSJ ztM$)-=wT7<&7$_-76xflNBK;5jmJr<kG)tKUfCI5j*kzA1{{tIa3Daf>jI8l4zR9# zY*#6=Ed=&a7U_Crp-TX_xPlM3a&+f8r<!{$SJSC&*|v^|Bw1vxF%sUMZlnQ8_N<J- zrR$ed%jJr_4AYI$G|x^^_pGG{5*+lXBiDIn%A$<_IU~t+PpYB7%dJ7sS+^Wv6aH$Q zfc4}SJ31F(G$;9sn4U4`<L9VH%8K{QTA!}MHIBZC&J&l1pN`1?7Li-}C&xT-uj_^8 z2f;{?xaCF9yx$PuL)E0{g2!r8-DHeyC}#ZfSHD}|oEV;2zG<-6U!32R_3SfKPieru zPw-+!x%;JYy|%4?bS|?8=0@p^D)8SvKC|hy_vX^;lp!{Bk)3PccsH;%V0%C(G~Mz! zNAbDFYxa!g{M<LN3O(Jb&cby3wE1efB>`fyt>#BS9HTM@6Cq3pQhVH6r?a7$g&0=Z zX{-TBMX=!XtiszklbFV7h3hpvNT1*w!_9O`;FEe!htw^VlB)anpIve|+v`C6_T&n% zx1y3I|6$kb#m2OGc%!2DF@iZz)N>7*msxwU$J;~n8a(l732s)l^BqbZQaYUdU~Chn z&UnzWW_|x64DO#5ONEhDP<NR*??T3|tm!wT4Yc%Dn@-gAoDIGrId$usU*xvh)04}b zH+VCVDPi5p*EL~kaAoAOez4$7BJ75Fxj)OxHvuXU=k+jV+SwQCkINi4Ht^Dby7gE- zq(iianHnujFFIuBKPKf7ME{(QTN}hVDr1jJcz;mF*1_=l;I7k-Irk<)*1TVABVeVD zBDQomh!ytMZ{$xP@~2i%H5LEQOvGX{y}W=!*&^I3<8#gvX=+nG&8*y-+aqOxFYi)$ z*H?|3Z@;|jDgNe94tk^D!cY1eFF&1n?Q7L}J!z4AjS~K-Hf69RCQ5j3b`+UvGC2i{ zb%dEtqZ{7R8)&b2ZPjl>kim+J_V??EwUW~IR?;t^iG)nwG<e8-CY@y)N^IRnQ4h&3 zOzzKQ&O`lJ>fx(gCXVTysH=9xRz-S9`TL!9;%R>%(|<MNgvsM%-N%lr8HYbYRNp~T zp;0XVfW!A6pE&#YZb<l`e(l-3wh!LfpO{_t$ws-i!^@~hz%$(v3ltT;h}q;*-H|i3 ziq;j%=1ZsbqMm#TU8V@P|95li`LpF)mCGjtZq?7DYlni|KIJYtA>CoX?Jp>g6?+mW z@+vVe%`qp0J{RsH3LNumsB7M9;MeWwp|QyAUf@p6o`Wit_~oA0>a)I=P_ikA$#C74 zfd60l9YIC^sCwVm&<qxDA>$YEcdD<AIxPyFm*~iN3vN7)6rWJ&@L@$y;+f!YW+)Mw zatg+%%<R_paybE2=^pekFIToI_x6?A&=`8@E#*nfbSH|PGKo87^4Qg^A<44As1S01 zUH<mhJz@EtoDz-PUX8p@aoo|>U23^TW*Kjw(R*6BdO~~5+o&>=^xD9;$*vAbIwE$3 zQ2UCv*50?O^-#{K*LhRRmRs-6oF}|%_=NIs2OZ<>YsTg!0b+LVF177PcE#lype?x> z+Kv{b2ZY?Ki1$}1eI47WX97HFv-@&6-C1hv?-SS|061O=JEM=0ogD0soDOlcdNP_| zC*byh0mh7e!*=lMX+ewQO3PlI&B+$0_OkP4T&81YycsMz85<uKEAWHP1DQWqYjn>{ z>A#8h?!=}I$9g^c@L)y0+jVH>6J+~&N^M`93$D$*GDFj}A-&<|%CReVo35OFdULp5 zBkx_D{j7+^%H8rPT!k6Z7?-hR@(D?YN7v07uSV7K&Pptb>2HeZ3pqNKU~u$o<$nAw zC{WXV|9sDrGNIemEySVqNBH`Gxe5@#LmIdfcBooY)Vm_)L-fPoja-Ln-u-!QR)+9~ zw|kt%jUz0fh}amaMLQA5G9H8aIl_GaTa`Q!yEI6)wY~Ke#3W4wb=lLDkl`IQ&74{T zHWDJ06K_9y@W*z2D9QKgTHO^*t7K{JK4NPU7;wtKc&D9?H_MXwl}J3|McN}pe)-|( zcPrl%mv!Y#55iqP-<!Jzu6@;RGlCgqHhf&Y5O=n;E!?)tR^p2}>}nQ0C)MeTIpLFu z>8I7hT)j1W??y!+?UN)aeQT3bvBKHbooH5a3_PC%rhy%mXx2Lgch}fFI>>&cxE!cF zuW@KO0_CyguIO?j_rE&$wK{AYH`T{KSd5GM`}1Yw#r_oD?l&EKTcYxOT3`ElW}TUS zZ8V)9x80$~!I>IRn*<RndbSTG)0@)i?TDEpUOZ%W_)t&goFnleC1XY(Vg)?+tb;O( z<ifl~#RK;Ljg>^ybhgnLg0RH!;GEDXSomfo69IeUc|y-c_e}ycts0j2V;u!gB6<9{ zzY;6W{NZCeG-GeRp}c3AthY?Ac%2)kx|gimdS&5z($1G3^GaU52t)o$&b~rVdj*Sz zA^-_GJSuzB+yhxVpHoImuYj_)<~KjUl)sOQ?7kkYQFp(r?f$3lsBh2P&xIl@Zr}k5 z$YJaB&-0G%chgbQ+sE~upDkwp`3B9oo;lP)S-HRMOV#!R+Ac;DcDRB~SI4aX?KsGq zuW%y*aof11&-TL98}p=-u`7*IV;d_bi1zW%_1IyO@60wj;Qrj~IP`jblUkgrOZ3AF zUbAZ0*RHV|x7j+^9k4aD6VDL4T3i*3BPUh#Y^o($29fY`<n}|Z*2DCEl~3L#+U33b zdNV+xqEs2yzMdpxc)89K!}wm`*I>#)z2`w!KlL6vJXLNRaOy8uC<<)Py*42v)S3hJ z+lJ3u#pUW8^-*)JG6))vjh<O?JV&zQsK}Kl&lI|g1U4NrCIeYmWUelv$d=j-n%a6~ z==VclA^v6*L{Yy_N(F&q5k=NYyHeM`D=H^@x;<>)cP0Ey!&#RKod7Izy>!G~Nz)CW zf)f7yp{YJ>7jIt(k14pI6Xxpy;zL+saN|B1p)XW{NHqqNE9*GOB@wEb56Gt6=f0yP z29S1Fbz|Wb2NyXjuCv=SnJhz3KS?hL-vp|g#`K#n3oo#EYBos9l4M9syH$S>aOH^| zJ~;dN6X6)sr^^VI(VV9UwbV^%RHYQIgaC{Hh0Fr8sqA!&JFx>aB7Y*o`kv>E#<dCW z7;lYYA6G@6P|pA-Nwoh+N-5g#O<QN4UfAECE+PFBOpMNKTO%su=GFwqB{cQ9)LUPc zTP{jVT&kj-(PZ?fJ-o<GIw-O{y5fn-`An0AD4?!lfecqI8NGOQOby}3TBZGuqBD<& za(n#vGYe*hVa7Vf&@*Gn&M<^jGh;B;>{}{h3#qIvQr}rDV{Pn0U0V{8J-Vtfgrpjh zw7IrK>0W8?*7cj;f6wdr?|II7z0NtG^ZC3#Fa1(CXJ4L;MT8U7xAZYoYjHY6hLGAu zeoc$^+nJU6GHU3a%CkfNj;M5uaGlP$Qy1Y%?mat;&idXv<%OYnS?vI922cILFz84S zod0#MV~C3c$E)|5KnV%#6XmI1HSS1v|1w}-DcZ)OxM6{+B<n}Mr*^>I%YQvIB7e`* zAUKs_9ngTbo#S_nY2?2W$=m3-mP9Zt)f+sm$HQPs?(TNiBHc{<kp&dhc6fp1BR^Py z#Y;Ju;*J9y*lfL?gy+iDz_!=gOf~#~<5T~Xkf-hzn}lvR^P#n3w~T?6`Uj>@8cE9s z;vX01HC%8?t6<#lGOTUNRbO4dTI^kRpH}H*g#<2}Ts8y*%oRQ(4@|-nTLz>L#6#aT z$=vu;i!w$VLZ9N>CXH+F*MLM0$t(Fpe#~UdKmZf&%h*$yy>qS~;Q(tyF;8)oytsS7 z_tKxWf65FUP&p4>tv2_U0feT&w(B3~g#8O!c^Q7aXX=DnB)*5;3*4tds&Z6*=f59r zZfm)kJ&%whe+9eGJCZLZ=M&HVY9_2~I)O2Z=%P1kx-Zr$_te&P8@RaW?kkygEp2R! zp*qB<k9bk45|!&5w;Pm?pB`5IDxn!O9S9z=sG236vTKs~xu{m@l0-xH4O%ArX?`Fm z1(F}yOvg>u@~l=9<s8Wq-ltk0&_35!00U4J?njNQfcV;eHaDUA^aWj=`hF$>p6^FQ zugG%|3?|8)2adc6=>{L4@g${UF0BEWn)S819X|v-?FlRZ=@?cF1%MBT;N1W-+i=>B zzacNWWK4h`2oykpMogBuAUo7OM%3T+)|4>w7PLC81u$L86a}^WenQ1(l@l=Mk>k)8 z)o-|SkX+tEy&>Gq^}Bf^F~n2%$olE*v8{^w97MdMtOWuXOf1Z#j1bXzF1DpZ*=1+6 z3ENBKS(fKNXZfV_@V2d4lxdpW1<en-KE>n3=f7HF<W2Cnkud4&kynf$fI5JYsbciY zm~7CL>AqfGK!O}TTuObJIcnSAnFnUQ$^KJ+RKJ+4z?yt`{M3OZ+6I)p(<dsIgT=7S zb^FH{l2W`zlpf}kz(xOfq9Qh8rJ0TZMpy`)jFC5}L_}DCRM2N&L@{J616Zpg1jjh| z$5${d_{5f{>N<eV854uB)RLuZbS=t{%OtQ_#wO@8_p^49B0(qZ=@}s{)ByX=Uk0*c z4|6X&E--y#80@y;Uz+bOl`_dsSKN&uH*xkw^~E^y(Ls!skLIbT8}Q7uZT@(RdbUZa zNMk;xxWW~SI{AvOTy)OGs-{Rj!hBiNl=#-}`MPH;0^KL(OUJKYq{UE{`yS4jWL6dF z9g)jaC8fX!KRaY27koWs&h0lZq~%98Hyjfoq|H-`tXYyS^;vx<G8+LDB&8UpwYvWG zHOT<3vRZx#3b<aiP_OXRZSpmUka%Wo0ed>eSHRGn6K7F7u(Vrg7fxho*X&m8lFt^1 z@U@syU?HqIGOUI8m-f?l)al(tr6Qd=P)gsv4!NJ7sacPa((ONj^n)BtO<$0x!v3V% znp}go{+hj>QBYq=-eASB2<qpE{@s81ASdLR>hCWgKF%j~TXmM$LU`i%Mxu*PccOJn z`o_&#Mt7Aic2?9jN4^LfQN`5-$5B^w=lk!0gV^i?IL48ur^gI$>7b8n=HFN8sXhAU z4Drmwr@mWHO-`JtR&JnZXX05I8hs!?R2ZNhwtFq9waX#3F&uBV!b&}rD0fsRg76j) z*7qNI=XBqZbXMvbyMB(eUlZ=<hxK2Ycle7}O13KW${_U!r9BWFbOC0><FD@ncFL88 zsWp!>ut?w}foGeIfn~~Gtab9~ZF$iisav;j%=1vOy?(oVUh7tPj=<{d&-&a#T~R~} zFkt6A+jVe2h8-qRXJulaco%MI?fkRZPPLA2{HSQVuqHNt-j@|^^=_;nro9=z(l4d) zz4m#|xUusi3@f^V;t7OCD6e}VkCy#%)9vo2pD*Xv${vid8cJ7J_VM*iFe+fZ5}}U^ z9JIN_f~ZNatf!s6=H(JYYbXyli+020uyU*Rlpc$>?7jW%*0T#;X+FM1OJ}Z4f4SyY zbUXa;HHKkwzbTY@Cqhop1_%(2aJsC+9DT=EOxP>GtAS5lPNrhy*w&#e^^Js#zuQc( zFLO9@hl6yqb)ol}0ry@OXF~_VI5H<7wXci<0{yF=k-A-VBvFu4g%Du?(EsK2)0|xZ zzA<5a;EuVBy5F<U9xAfrfg_3#n^FVWsQcTw5z2qzzK<We(Q(Yags5O}ahJ|Vk7R<F z1iIBa3RciHx8ZKj7e*<OT{?P~LaBHtC2J$cs%>CUo&4AJ$)|smULiRA#wR)u=GiC~ zb=gp+VZxMq0+qS}bz+s8>cb2(s?3##PkCrQeN)_W@b%e_7iSK-KGV!%q+e389X%`1 z1ZoeyxUbBm7M|;sCjBbaUgMBDygL^U3O5h>!(|ABc{Q(jwZ@?hhGhNI0w{`r{rs{E zJfJT7rY%QF;>0r^Qpz9uNEo6S*Kr%G^`BPW_R3r<y3AOcTfa8X4ZHAB*PUfw`=1oE z`jz@+568c6XNTQ(wjShJ#SD*A;oBC8M2Ui%FGh&Ghbu#0eO@Py3sl_&7i`icFhYme z5BZn<v+ex_nWcyQGZbb=UTN<o`7uZQ^<k7((1tTZBxT<8=ckua91IhNt%9BbC|L7{ zochmnLvA3fDMabE^BHtjD|(bhaFUw1tm1Lc<Q$ZXllK=Z`_HJUYjOz~?#c-2jj`w` zMzsHF)>q>LsX|a)z`-|idan#w9XjA|Ki`}1k|wu^QB_dVA3B}jzdDe;>VJVz^HS;j zJk5&;gi+To9b$LP(}XH&u8#$Kur0{f|M@#x#=BUgz_RV{-<4vPdXMaC=2<Z&OCZ$J zsRNHvo>yp&?<$2xUv${E=9f%vvUa33KI(^CwTWycoYoDwKm70A|2<9mTSJ>91yIAQ zj2(Ol4j!|OG|h}Ekf%RL)2kPi)u3Ob2O6gE%xk1D&jkk5XAZwzOh1bZR~3zJh0jW5 zF<lnUz9KdCj7NPA&!dW3aa`4Yh(g<twwF8!1HCbYdOKb;FS&{El#;vSEI~~k)Ecpx z1^x9eGd60Me=M8|^G{1(#v~OhQfSH&vI7BbhZ^5HeTXf7psbZ~XQV-;N{c(wz@PvJ z7aN4>2Q$`+89hh~KFl&`#=5d`F9i7K!#u5{X}m4kCWGnV3TI4f{GQuy7wKSidf0S? z6ODGzIJvUzrX!B~N|b_7?UaY<rK;cSLciaZsqG|iM+ojBf*&>0BkqV8!ZXKZnwoP} zCWlP)JuJcD-IXHC!C^93F|{U|qdJgRrlEGZExja3^9fUz8Q?k+(Ok+991MiA-G-Ex z!Eus1S2czs!KPz2BvWQteQIKLQrdrwc4O1E>mlT?J=%ot2UEpS=<o=V?tG@zWo^w2 zh2zzX#_Y7_F-2pJB95lD0tr;14P43lBE*?+=GVNN>`z7u?l@<RU_?DD$8#K51+a0U z!|vuIcA6RL#R~r<@^^u`0#B(EdWY?pFq_cE=yjz;&%+Vdn-Wz?Rs=pJ21fo)-?kG6 zJodw+RMkwB?U4TA?-_8!6YqEO#fqFsV67(1yyLA!|B$>p4V;8%HbU{^5KZ9_z70aC zq-*^eqS!zU*SOcLp3#1bLKj3vp_dNXFU<R8EBiZ}976qXw2F<BPyZ2)qZQ(cyyF;9 zjTnwL21>m)N)*(t#(U1QVh9G+jP&ME*No2DDB_zdBq?T}?syu7mT$<xlA1L2X;?}f z13qNe$5eK$+kISkA!IcQHQ5?wAhh>3^OKSF$h0I3@3!aV+raA^6^P}r?2e|&g5ljg z#M}k#><nJM1R7e&(~IZqk{i~FK3sC`iQVhxu__LB-w(Ly^GWr8ZO7{}FMHnmPs*|W z$E-yylmv)~=@510$Lau-unEyvW6O_lttM%ck079!qZtI#0ibHaAvFR=SqM=dX#?X$ zzW<3*t{M6Noq0a|&8+u56Nr9mQds(LQoDb4oE%hRld3o~q+J_j@$=mc)c9LCpI}@a zN;1l{b@N@1IvjmK!ADBhTdD_7%s+HgtCnVaXKVn;zv&~jmZN1~J|8{m&mMn@U7H#p zG3__BC8tqStlZti92>p^#c$XKmoqYPje%o4>W?lDaIoX^#+b0exu$ZL#){{|77HUo zhYmw?4E}LM!ZqR3gANvrg2%ul$%nbeUq(mo;?PLWw*80Moi-w3!jMwi5OIbB3g})l zkz{=bOSxgIHK9Qb-PZ<YVXw5SW|+otd})707sw{)%&Uw;Zm_Xak3@%sBy*Z{YhS6` zu`IS=^xUG_4xDJ^a|>u5A(|{=gGck2%d`d1pHiIr--1qObDkEX$F()zl-3(}=oY}9 zkGt?!Zfg|E)L(~vL25kuEAKt=cxt7?v(E4$Psi$o*{SauyAoi3Wd0?Rz%;Q(jyA!7 zeEQq^x`PFB$6K!M5{pjA567GfE%$M}+#79`FidBPFZ)ZmwG(DHP5qm5e17@+5GJe7 zL+`)a*jl0|KP;b~^b)T_$;v!ON#0lvvaOBbJxS$B3ejd<UN@l}OxGOsnmPCc$j0QT z-W<ANGn469bUylxR3BnVSg};&>c4_Fw}WPMVOIsUM}hn~Qzo!q>fmZ(rfnHxLpSU8 zn9AvwejQ^pu?bKcgw1cz^rNW&RQZ_qg?HT8gH(NQ$J^<x?6o=R{Zi2Hb9+25SR7kK zBu85b4t`6i-*;za&oQxhFvD`>no{dHrFM3FkGe3Cm-hFn0|{diMTp<K;x;%;nHw>Q zAHpaM+k9NaS_absoUPp*zOn8r-E~gtT~R*JnHoTL$In<WU{-LL*8heGYePoAL>68S zlvgXy^FQML!KBgEOb8AJBb;sSNuC|R{^M6?EkHFTPo2_KHtiSbjYHHcIghoVdUFK_ zaY^iyOHXbE`ZKeB-I<YTf4w~Sj3ki0q080Qfs!^_R+$;sUrl66BSK$Hb&|&M;=*2C zA8vdEG|*AW%L-_&^uL*{NT6Z;AoyC2rZU7haMRDe>C@cS+0SdY{8wokN&fn58JH#6 zh`CP;Gaa8lbmsBdwFAc=s{ZJGVs@?3CX|;S#M|?|I?R^0rwzJmL1C9n4Oa)rWvcE< zaj+9O5F%$|iULwMC(kkkHjTsER#(*((cC%9Vq_*v3Z^II;3pvl0MDM)d1=JO;p{)S z|KX=qVB{5%sSR)Y%U7C-KJWDg^d(|qhx408eq3;<lz|PGVm(BlLJd+{jD4h9qIKOJ zK0LoYqt?sRWUP@!a<!TIy2<h<B4dPb^A|q%y6!k1{u<?<5ae$IIU8zactImqa|o-W z_ownu-^t62npE~el7CyZvA2}jx2`?X2)zeiXhO=NPyYUd$-}QzYrW&Y@7b`N9JX<X zRY?05uRRIhZH?bMA}=dfS*H-`^6<-<Mj_??6!W;nAj|@EIHH7h`)_$)U(V>LixmTA z$fw~4`^>!@eBiG=CcGRTBkx2>nI+tl4}NCb2u&%vs9GvIzD#fOIoOck*Bo#qbP`$@ zBzlx2^Xa_d_M8F#$=~7rJ%0WPS)2gp-|r|Ih#}<>&i)4z!PBnW?F;kBR(7e0e-Eci zf{}v))>_4>ICHM>I)g$xcdA&TMxWjIRxlf5Btw%QkqIvA6%H<+oz(XKmBfbA_Wl|k zEZ8jSbf|V?9NNEB_)mFR*!Rbi*N)<cDPBAqih6t%*QWWgxp+LM^tediYiG_IYwV1^ z|6JsBjoVWad#NOD@uGTtWM<9Rvy^%U0Y={eyFWow^X8qHayjOUKW;f-e)@&2n6|6N z;l%%>tde2mS5Omsv<4qqS0nX}l6!U9aXw7bpE6;_77-&MJ4!@9L#9lkZ!%)Owe`ly zJet||Sgu-ONJ4-RZGj+eWJ2A;!W&lh*U-ZAu5WrW%%y{4el|x_g&(qA80V6w&s9IT z5^+>TCpzeTbG~Ge+c_DsbKGp~%h~3iy#0=5!n9|8@z?hqd0e}G+~>Z!>B_E1ht1wt z^ry`y4OeYCV9^(^l?0z<cfiXlXALEVf+cm|naRTM?Y;~+DH1{$6p24;Z{lZa8vm6e z_m~SsHgX_jFDy_WMV=H%K5R!2jWp9)vCs7&bHb<t3fS-UXUCZdxM0kfS{T<T^tFk# zlWEJ0w5sRz`?gPAM*>Yn+wPp5r$x&4TvClLAOOdAjIgb=IYfk>Z&3G2BJm<^`_Nwh zC2tAflB4kGR2ps{F!RlC+#cBY7O(??{d`L5EwFo5cvY5p0p%`pS7mBvIa?&))|^!S zGXQRav`sbjkLS_ZJc@9be#fC~++7%dlD}ibI)!J|;Q-?3k#z=DPzf3nhE%1*2=G=% z9?h$3>v>jDc#5)4MhNsWjrX7&Z69C~qG^yVxw1K#zd$ZC%G5k+Ajj^gu*m%2^W~AB zMXL3w^`-K6>bnlMq^wt2<&`(>I$(!<AO)zkH~1d8-4*v#r8D4qbZ7V*6x%4US#+mL ziYl+Bm!x+|3UJj9Er46HENo(Z8aZii<x7=g9+VRgfF>afA8n9&ZW}pkuvS@1uuaCn zVk{HTfK?o#i40@AN14LA<p$|qD4M=ZH4tWzkTaz12>d_H^l_!3f6`|?J}(Tt06RQ` z8((sK!^M><xU<;{kkOK=z?<jI{}Ot@|JZAS=nfmpQ)%#SWO{|rzvw>Kn3N6+u}d7? zkQDY}UJ8HxPzX>$u=l;0COc`K=mWwk<9`{s+}{3~yJr7+-bGp?v4;E)nAf%(0~Qu? zn()r$K@Dng0Cjz&EGX%|?!|CASr0gA8(kGyI^a}sx!h$GAC+|9v0?{g&9Q|gJr$l8 zm~rMxZA;6oiMCiLNr(H55vWlchY1lHI`;>0W!*;7w%^+oH0NcQai`&cA{U{44{bJ| z5TQ&bxI}^@(u$FtcixF%T>~rnOnIB16Zzd78#isVSpH{t`!pa>X3t1>DWi7Q^tbZ~ zEdYR~q&<KDgf#u}{`c-;zAd1a(0c=pGGuo?0LI%VL;w9LBayR>$9HpuyP5Vt6$HS) znf5iS`wD!&P<5<HeW&KJwnTl+BP~cT?fAia(be(u%K_T4(*s$1_kQ0Ty&LCFSbH6+ zB67NvXc!t(i-7R;s-g=Wt%G^LF6H4v$C(kT@#QoZbrt{gb;nBXM+7@eFCa@jNTN70 z59Si}R8sxC-&E{K{Lxt<ad0*%@9kUI=2Z?HVo3ql1Bgu;zQ>)UR60hNE*b;O#3)t2 zg?_r6?dY$@0e7II(Va;!7{@xRs^2T}2AJ?7htIEk$p`;6{0urk#wS51D@EQh0QCPG zW#C!e+RG^g*APIo#<(@<<iDkze)nbpc0gIlms{r(RH_rXYiFX|xSn7AgSe%^PU=9e zm1;0rW-Glu8l8k;pJ?)Su01t_-AUyPnyl^HZXWnqc5KN+jh*7OxO&NCkd}o%<?=tT zzj9hG257{5|3Z*(Cg0_0%a?Jos+g7IjaAWJ_D!tp19pjXoYMQR?j1a7J64)FbHB4W zc@5FhyyMLUl$!bxgC=F8In4GIobhA32Sy`7l4hijO7573BS?6N*sD|5XAr6)=oevE z#g;()5z}g6#uF6%(x6<Uhje1b45EwQqRTz1?+$mt@G3jh8}~oGI9y9g#vG_SW(i}J z9vR2rE%+R{6UiEC8O>NX6^1VmLqA%HsUBFlZryjE)|@8P@U_a8N)Gm?SyTH1f@>}K zM?Il)-WSroHzdXmE>K^I$P?(upo*8TsK3hE*dOx9H_xil{&T23;%Icb{k_}ydjA`z z=JG<N6Qyq#vkDKIFP-`af4O~HyYPv(1OAOmc@~AzF~QhxKUO<RZU?fXnLO4jUzcIe z8P`(b8spDOhaDlo+xbem5ri>urnzL2#^RRoBRJRlt4F$iJ`7hIN`NW8lL!px5u-^k z%fP(|<%{8|ML-@v&p4sF1X9Yi)O$ucr{T7n#yrAc9u36OTQWQ10xauLYE!-TLmg)9 zX$P8q1P1@;Ui^_K?)4|f9k@Uzzk%ox6<{gQxiy*tAJCx1zyQ)pEuyXkiglG@`}*tU zO%R8qrRkDh=a2r$*ofr9DFv&hDME1EvW7zOKw-+t;Tnx`O(WmIZKi|96M)Tq(F;aJ z@zh^Q{IxxGW4!nVjoGj<)#HokBRY}A10j4H@wdWE{TpXSw*oz-W{F<s;VM3CxRqV~ zMAmldKV@Y{-%yWtX8V|P(Zg%^ZJk)T$;wys@98@k-XbgiP%k;}b8*6`urp8CPg08@ zG5rBdu9tZ%_%akU7<?Yg6>wu$O1ZYSt&gmrY~D!-aA>o><{Ct3o<(ECzYoUH<W@4_ z&yPd^{ulrERZ1T6G++K{be0$Z>TXrNq~cu#x+6}=si!YfkfJHjFGa4tik3=Gt5J^0 zfWyfKIQ4FyHydBC+^UxWMC9jOacPju$3~hcMDT^cAbdNMz479Uaf5}E=BPNwS}|Dh zS**7DKl+)(L9*N_smH-luH*FSp@P`c5}NF|1nAEU_>uOVG1oDoa^4%ARj_}%%*e%s z7M78}Cx(lk64MPri!H+whSO<3D-Z84&(r$XrnB2C{<qhV#a=lM*3k$N5c*Mt3r7Qy z>+vv+@!&_IH%bo4aOLs^L|{6X=h-SdV>cH9FhrMN>MWWn<iLyBCzk=S@A0T0^+oxW zNAO_3hP{@875PTKR9z{pFh=lJHL`xDckNhGLWW`fki6|&J1q+a484gPd?t~gQJ3aJ zA0~pgfl;d7YVn<4N5gQ}%!WP(6`(GVG_lx2sq?)BQ4|La>}mt0#(Ob#j)#?Va<ZEC z6@(w{eb%~`6?m!6zF@Nl{A7i&#tdaDKo+jc^RT(1x7bJ=N&fCOpFuc|ofJq7r;B3# zFlZV=*C!YUc@^b`U*qNlE+`;Z3N3&;Te(KDN)z5+o64KxqkM!?rq!nx2)PMT&H_;^ z&hG=YxjSUE?IL)?D&PM0N&a&!F6Kx2wYtCKTYD}J^%v6Hao`v0OhXyp>(6J7%I}$C zI84<82)g{QtSqu1ce>e-nIye+aR1?KsjY<dsq3E<(tkmDm73$tMze&Eg!gB{9i%Ph zIeX8_?LJ-q=Ra#-`%O-fo1Z>S$g&O@DoBw)?oq`~|Ff!T-2%dhXxr?}Dr`WE^MMyy z*PJxk!GefHh4zk=sGHuTxdY}T<nh{jrZYvkPYO104fC1X1$ius9Y-?^ee0eZF%t8m zT<N&I|9-nGtC+w!U|Z99Ro0L?l|_;?&S+4s%g9c9T5~o*e;E6z7LiZa=jvpD3{3<F z@hV_-|1-|;2?*vDXD-(=hki!kH-SM`UU|ctWhTFup5j|%A!r~Jn=Xd^@ok~u+yI5< zBYr&~Pz!kYJmoM7&}_QfbDrtZUVFrTt<{eIVP62`pH)w=##Osg3i?C;(5k7hg@xNP z)ToDORMown@l2`GCdt(k-Jy8<jemj+HCCvoMi%Rp>%BJZPkvCm#8%2(#O1RH@S{%o zLpUbKiJgN>qN&u@yVNcj7q071a#h-(D#y2JO48b0UW-PGYe&8oOzd@Y%h3BuT~xZY z$+hNxZLCFt9OdzRaB>5D!HAoVk85(m{sh&-SenJOABA$rHmXADKVW!_>Cc?RS@7SU z8`*_<pyGs`9okwk5lnal&YJyBTmB8mH1gZm3}LX%3!v7*m4)})NpB*hm(=v63&W5z zh7nIGq~V2S^-cLhkJ>FjK`=tZ(DMpu;%HK6a{!g#w5Zv%NNm@p>u~Y6ScH)}^)C7M zNpG|Xi-@3vGCvpXpvISX9Q1ODO!3%_EIQ7v?zMZJhSQ>YMn;4j33&b9B|6Im<VVd> zWwSa|etmEi$AY1c!9JauTicsT*0dcrVRB!DGSh&v`vXP8!b{WnaeYmgcW_mwA$(Y! z0-lEWD#Y}Jq3=io-xExsjz5i;EyR*%<2NW0A9x6k+yKjEf!Z*u$~7^Hi`7V!eDhR7 zEh-LJ`ziXb1-4DW0;iKqzuvI;)uGhNGroL{;P}xI2OF_yJRSM*WXh3$W=vZ*^7e#v z2JbaL><ZODjA-a^h6wpLHaO~D!~-qbCFYUMqeF+xNnwSFSBs+zkX(mCBL2{#Y$5He zPrNA@jW^2D<JRd(P<}pjxOSqNwV6r{M7@ouo-g?kO_A^38oXEoYey``khpmOiD#*u zUOlpwXez&b9NbLY@#Q1eVn|VRA6W=0QtOrwU1oAgmw(pY_%BSE#6kmgs!eP(fhFGq zVzxR!bD#LFe9*qwGCvO^E5aBxh^?i78n$ko?1}G9x1>qGPae;8y&_|Hy+JzszqK1? z*6c>alE06uwlZj!RlF`@DN(xv8Qvd9j%ZJyE+k3qe8d9z9-<j-QisLiv=8d}i<*O+ zS9m$RUL>K7qhY+#LP#KybnwkX_!%O8Zu*R8hw{Cv>ZLSf2GMM6XR?KJd<MjvvxpBN zM%L7y%V()HL7YzQJdX;Wr$D=nm5ff0B0r(I_3_55-ZAYRTC$`aZpk|=S(8i%CViVN z$AoySLNCiDefQEoN`R>P5am7UFiR49POZXM_74R25rwV~sdYcb>`#aROMNAPwmQA2 zUxc`vi5t5AtRfQH>ywUyJx@-Y9M(Jh4n|pmh`S+j^gS|A{kKrNgoPbjti-u)i+n}p zq9oJNo%W-=!-n++3M5Ts46!Xjb<DG<_!vRiSU$!Jd=#bfXz@@=RO=%SwF07Uo?>d< zL%IWCobF3mLBmg5IdSW7aojEA{gHmO*K8UtfTetzrur)`a_NJeargbSCgmQg>~RPX zvRF-WUVwU<QtBy1J*Iv~mGo$+5kPse;~V!x+>4FgK0T}xNB%#dvg$Sm^RrfAE=)n1 zixIooPNY~EE@#1Az4vxK*3$Kv|Ljwl2Tqt_8{Ck8Q%>ZDoj{R(1GT@?YNba3|G^US z9V4l}H8A9jfBF`vEF3h{27IVm0I&n>H52&woFyu^wl@{h?5X!bzYnx`kLG{{P5F8Q zBI7VXq3hB$-HCVQls7C4LIj*=@8s!kMe0?Hn*A)5`9+)na@DTUeJ>r;4{8vy!g0=e zDT}z%k?OfbTyDME`H}QemI`7eSf<_y!nQyz{gv?9`TmmHcL1peNm`xiuH87`{E7QD z5wu__y@R@tAxhF)CgnmI0z_%X%hjbh<3%cnfnXK47qMD(82BOvF3CFl4gTu2YrgTb zD#Fs92bMqaP=M;LN9Tks|I+ERK3Q=}MkLe!X-cwl>2tHG8eT(@22oI@R&DRMbU<Du zTAdf$#h6da1oeB(8s0v~Y5NuwkeU_^&-Gn>#EbbiTw`Vk-$TQzPVVEY;>&f7Xh(cy zMCyfgz7-w;6^rnFF7~BFs}L{UpQ4%YuVxQr&gC!ONQ2_o8I^u@xbz{l(N2ptdUR#v z7h%1UD@!2*#6;IA;l?>A?txA@p6aOrtzAhbkhl;f`BDIDP0W~G`Ihn6+?CmPO9EjU zO;O?PPkB!s_Y0hiwp4V~K`&+Bxnbe8opikFJ(#4n-$+~LmgS!b?A*Kx8_^Sx-UmWc z!SZKMP_@7~3l!_8p}9OABg3|vw(+?R@}&3Yzb4B=HTsF%2e6V#d3rO4+Dy}MT|{@W z=B9Zu#KyA@9Tqh#^@Jt$d5F5#Qh^bVvA+=yXUV5nu@&kAt)K=wrS-%o2|mP1z)dY} z@z{Q8wOoiwz|iZ7PVR{r(Db|W!9~s1UIj*-3b*t?CnnMDJ2>i|Dbv+Ug<#UC3f4o| z%YGR)6%QBMmXqdEe(1!jE@%EXLWV}kPo!kU@yS{J;EYpz>1kHO6R?U;-kJeDrT*jI zl-4`8=JQ4>$s(`t8ECqV^^rAB`?fgwdG>hl#dl6c_pGlLaEk1uMYz8|ZEwj3`~|_! z^M?2ZF%@IUtATfFh_Uw|_|K=VBEk)J&HRr8Vc&}mw;9k&Av&f)0rsL=T5Rdtv4{`} z>Dfaii8j7v?Q=uNc<JMj5Q%33g6sqKW@dr?9cCM%3jfMpJ&2+O1d~uJ-*nULMgGHE zP0Oy|F4hH;8-HXgELCY_S8Lo0(~PnmQdsp;v^(+4Dl`eJz-{=feCY}foglQaKe>h= z?R@YZ40_%U3ER=f0SmSw(-s@ch6Ap{QYZ-#JuLdg<08q>-9~9pIM}|$mWc?#a=*Le zB2Ry$#Os3{V>_qV<jmeO2W3aB-ek7Mf3+HqAZjNUozE{G3%-Rr{(}%BeInVh3n;7} zuUBzp$ws#+9Y13#uhzT9ZAL=lf@D2Dhl4ySYA-8}ax+6-lzjD8%XPad2sIVG<SvtG zk>8D;9M#^}Whp%cMt`$w^v$Vpt52yQbE(>+?9&5BP50K???(l=mv3*~O6;h+@gacw z6j!|bzDqZpZjv855jd<<_4KsKJ`+0)IgY}eA@#1LVT-5#eBBk?GK3%HTrYjA_Vs2{ zkQ{zhsIpZ|{<)QAB=fp(NI8vB$%QjBR-D6sa<G*uS%Rhq434$iLNv?Zd=*%8t3vzc zq<DoFuzgf1fh}9J`+KeA?fyq8{kLw|#sBjEgJN+Tk?Z}_xa~pX$%ZE^2v|>2z22F; zKlM?=9VK8R?9%nh_08P{Re^T{jgmTa0GBhSVFo?>3&4Pfqz+nh#z_HMeW<ztALg$y z!cy;|DN!ImZJ#}euitm%e;1|-%j@t7=4abERhNmToySb87S*~yvzs5zF1eOiiS)!r z@Q-MSzz~AM`%;-Tf*(hvsUC4%o3o0Iv3YM2QrDhARr0D+N(vr7I{^9}RU9`Sm}<L3 zf++E8(H3<N8)v{lr$;N3DUgLe)2{sh@z36ue@yy?$%?dZOUf6E6PKj18hyH7R(0QQ zi*75>Pb<_*^9vPwnS=F#cJ5vI>nv40&m;sl+V=%09hBa4bMJ?evz>Kxl^PN84v8>- zsLJG7R@`Bs>-7Gj!uhSB5zdpREaI(2(JhwB2*j*TCfSRDm#>reS}*pk$9-nYpJtsk z9{|P2)N#J*eBxLdO-&v;o?91ubdS&B9~W1{yKm)mr>D!<L5!(+%pny(?~y6O$4m@Y z)T_gS#DQ~Eg)m>+zTc#`&{t>NTE}kN+7*Y%PP9JI$oaSaWJM+G$${Hy<oW95sW?TO z6+EzY+g<$R$qK>e)6hCV)nY<;I!71oYU_%27Pm$in21Q!5#_Hj`c?uee;bWYGU@V7 zTt<g9yv;MIt1G(4(b$MkuNhLiT<3d^cJ$-cVbVU`QW~yhQP!H~&{*V1*AwOvw^&en z;cz<FCE~o!d3FZE<;SO_#nD0RSnF_8S;PdpNyTCglOn|M&w-e~=Sp5H>UnN_A(=VV zVa4%^pKE2{#E15O+nFnBcc!=Ysy_}1)P4bY^WSUVev$o44wRJeQ87RTSL%jxX_6yK zl&w&qY!B@WSIF>hnduLLQO9x>eC;Wa1qT`$huRDL*aRL_{04rVb?Mgg2yE9{f{Guk zIz)lhMCG4~2P}Y@#vgFZ^;ilpU2k}9ZStbc@uqp(l3Dj^y={m28b{vfi~-Q)h75W0 z#_bh3GU&Rl_RD;IQPgRq77RsIR}XwpsOg};fe%Q0>!hOL?j^B=4W%H@mgnLmk}P|D z;+}e>Y52Y3R9J0X`QsV|?*X6R0%gNz9gtdRX6}@{b&Fjp^oybr&Fu~(s0t4H=x_yk z9<F8ik6N5XUp@!H*>;WZ`Iu-KkcpvF6~3&|ny)_k&P^6yl@dz}@!U9|(I942Zo~{4 z8y$=gF1qO%tI(z#7?>HJ0<dBZ!$(AZhRVM;>Gkn2b!2+&RgFflwFilxT^;WNu%ZYA zxzF8kXOm+A*^Bnck7lN*91-GwWjW7mow7W+ZSk~J(b;Mo14oA(K}V^%ajsaRESG=| zcgn;HR9GZs(jXTBgbhp@M<Y(=n;*6qeQ4X{{-l6Bp*-wk4y^gOlRGB0-A!-Bk3PTT z^EboGw11)N0i{XVLC(nP_7=;rjmSU&okdU${n}UcIr8~}`j<P6qqsS`<rs>~)iLb1 zaqU){owCVAHcR7rp;Xp=VqwA%TwRRy8^1pPJZ1ij!j-p29g~E#68y+Sg%kd3(MK^A zrjml8{YzWfLHFutgagl1{WAJ62N_~6dUg}bG#m7TB6W`~lt86)YZw1i|GT8XW6y6N zY^8!`3F$E2$9F0pbkQyFwRCzTw{7uHWm2JyKYHDRFzzmOqvS!T<%HEUpx50}OyLFQ zf*;@O7)COc+$+Cpb<3K(6Gl9=A8X!v<3Q@WhPpW0EOGnX`ZcXiPg9(^YS@xef&zGo zC}ACjd=O*U1z}gk=LL9(j}{g~UG*AE>m7E~2TkAK`A1~23+;%KGJ)BEcNi<U);P^1 z6$0i+rNe$CxJFjYRF)2xz#YFXl`2!DwO~?qnXo>kV@&_3?j}&5Fg@U_I;A)xR`GI| zWh>1_%L>^FQmloWKt9b&<xL#_xT7lgnF@nXc?$kidi!_Dh?g_}1dYUtXIaj;H=K18 zGlvVvOXh<SmN!Q_^S3Q;nZX`ziS<8y{OU;>c~*w8a+pxj%SL*WCpN8c)$w~9ACO0J z$!K!w5>j|c;h{y3;k(9Z*XgEf{3n-B_Fk)7vO=_l%yv0pJlqZCn=2VR!D8!$!4+%) zFtcM#fQqoE`?o-aa$iBX0~0F2S;2`22%Fv`00$<#mJt@&>JpFyCRTwq?`!<ST^=Yi zVs?N2gvrz&Nv<{GGfIUcQ`pD@)<ZM}zqeS#xyDp{?m?O!Re*#DPr_-`tmc%#ikW=S z7bf&fAnI~~<$Pmu(dL$gu0_BKz6qn~JApvQ=MUpwBBp~H7Yj@nyfg%{*u%55KBguI zKe4?z_jUS+?mw(`;sY?4;`tTBvKcKAZbq7CKrUu)EJcq>TA$1<ul}LZSU?@VXB_P< z7hK8JXaoHK*>HWvb!ifk5k^x*<T{??D(B<qI`pC(Bz=T?w^M^o`p9Qe!&NeXkyPp$ z-;n{8cM@||f0}3R)eql&Gl_UgQBA9St^>@Ec!frChkNF(lEQJ}>W~h`l!=s#?HWyG zG%P!j2+vbsahQ@Kw4%~l@EsSS_U(*S?j4;S+iRK(_XvEDs1pn$6&<3K->J2aWIEbS zZ2@d1*GlS;IB3e&Znm`G3{RnMGwV({eXLH>gnlz)dTd&zbSM<5PijSM8#IEQo@rax zuB7DiQy}axiOKi1B*@g?X=&e!Ew{Vq7|W;STU?{ZzISPGGJ;+U=W>-a4Ks-;wK<;5 zO{F211C%^i(R*rr)!1_kLam7JqRc_Z&xtew`1}v{8JDD3SI@j-3-GfT;2-1hWxd%p zGr5n!(o>;WqL0Z=c01BtzzjiUU<iH?nbQ*1Z8U(*2xzPWr-TlAu2aGgWzu&LVZhg} z?!B{h{y3by(@n?c_DrKGrcTzPY9;R!05YTEvutvU%GMLxBIa=;S}AdRxYS)HjGQd; zjJMhcbZ_(Csb@YCzUo!FibaDl;&BEo-!G-X^9#%<3AtUr@Aow<&>bmdn$ALXttJ_? zkWHDVpAfwS1@V`JaEsJh4Imy0TwL?J8W-+y*AA-q%I_(OP?t>#>%eB%z!~7biW795 z?yBp2d09nU;B!AnQ|9CBW!YwIRUJ74W-r3$MTOvR-T5jL-XSAXgvv;tH5th~{pVxN zZB@x(&N;iPPw$O|8p-*g*rL4)l{n*Aw3#$Yo}Vi49)ziDyq~k^^3I{2j=)XS$}%%# zu!DRat|1}s4j*-=aayM&4hV|)JMXWr>!;M-Z943FM5Bbw-OwYb7#aQCmD~7yrNa13 zK|KH%1RTZ<H((qI8MQe9jBu`m2*IcMENvgFKkbl*_)3z8<QOLmVaes>Q+Iw9KNMXh zeI2+;9cS<OWg|;;*5kh|%@^oVR}lN9k=*(k9y#N|L|`A%C8pl7+An6$%V=vLe2e97 z@=o_Q#{1u@mz4tBpG0TT-<AmOksd)5Ga+lrjks0HyFHA16&5t~(IS8CHC@tH*5gq~ zl#kX4F%SMZuX~gv7qze?yW<kYzzBVD*SqkRF{ZSADQ({k6gtNEqNC}>McM7kUx+pz z@7LGrEs`VNDOJxgENwfHeuFH;;CksHXZO(m_v`7cMt8J!^EVJnh=cnw=E@#k!WC!h z*^C;~7Q7x;49buuiu-WQ2Um_h*^UhP&!xVk(-AXGD*_QDraWLSCNC^(N;~SyQoD|4 zF#Jv)YIK2+luw`0W@sHXV&XlzOAgKDf$?$eKMv8?E(aJepLBfERWj9?RYMZTZANW< zIF*{%k+k8{b0$B1bf4U1=#Sw>ZS%bknn|s?o(;ZWUQUzt`Bi<+*qM3BI66Ohfv$4$ zT|OIY{GgzV{`SWAOtL#U?;5&8&*4H<f_kPvcIP=Ice6tMxmqa?CWhqyN7K{ax#8E7 z&&?HqQn3J%qkYmm@}$&|5#Xf-ghl-Ar}StxB93i5#@+t|u6S{Hhl`U^OD4uq0CNSw z7h9*K$fu!E$8Ee|YfhN$+_BS`x&wHNGw+L_pEnhTqRw2VE7dq-zW89uXK|Li==ou_ zCYkh}P5Eo5j=YI-zWeRq>KmP>V)PR#I@eEad_nGP7~**Xi9VEJM#L>8xB=#Jg>`$> z>8{fP>1xpa1MjfE6kz&n??2jVCzkw=^*CX$ltGH@joRdfa?}-RAcGqaQ>uR*>)slG zxlx|Nyqa>0hHUSUIv_^<*y%A&_R#Gk{=OPMGnIO|S%zVLGV7D#hMyJ+p=b@4c~l<p z_f)P}TJfi!k_G~B>x%@0@M}*w4ax8rwzN7KWKg-f2vc>UslrF-jv;7J0H&bA6vUn} zBl2Q7rvI{e+lY@W3YM}5VzwQi`}&hS?3?_FMAbuUN(4z0pCnu4g?{VrJmH0w@UmV4 zF&TZzV+(RYiSlnT=}O({0&|%Mo4gC&u5bxWVnMc}R{m}+YVWe^j|QhdKVz~)*#n;? zOjOw?o5^626J=3ffnxywcs{xW>9UKE55mvYA_LzV_`f}H?n>&6H|F3@gun})%0^hM zY9g9#FvR_Bd`!YZlmdCjXCh-pH4jn5L10g~tscX6+W8A)&Pbw#VRitRufUNxnQ)p? zmyald=6%B`Tp{+ufax_Qs2ErUfX@pG<$(o-K(U6D;!o+cecxRU_bWf{Km~J;jKP$* zpQ_<fr!pU6Vs3WGJOY)e-i16p^m3TojCs<XhR`qz*-)`u9mVyb)VX7HOkfnHI_sRZ zjAEKT)uza;#azCFjT!-2gq-t~kLUB(G)ge2k}jD`0P;^KrDvT)cxNhE0ycMv4;RCW z1U9>au}wird+#f@FfkuKo<tCj!O57X(Z}k_RC|Lk{d4eJ2!OSa=T9x;sljPp@Bo9; zyuj1lWn3dZhINq`3NOGE0pXG5*d*W+m-iWPNE%QUcAWS%dV&Z`*x`#=5~GimtEKep zkx#4T^+mtZEj+)j^WlnIW{>Rf0{KIX662}dvbp@j4mI5<q7L2l0Vus)T`LC-_W$t7 z>DZFq?<?}@;n^CxZdVMbSzD-q5%iv2@+}yYZ72Rlu+m`S2?42MM_;4sGk4-FGQAe| zM;OxdzGC3b;=3-GLaUlWFBxa*$@}VBs~<7evo;TN99sF9V_+#ZDbn?ttsE;)YOxg9 zIyP4<b5ekH6~LSmE(gTgp)8^z%wap~xPj4LV5b+nE=q;=hXU&l^&|j7RmO37e6V8O z8ROotbD*QZ;Ms}juS(}S)vm}`>=Y&MUn__kO?0urovf>Tuz>#9?5qCvtO_UnECelK z=q;4&ZiJ)L0GWrIXDBpE_b#+u1IoIh0WxzA{*~z7-C+L?wcRMF>JXzKevSFXRM*VL zh^zuQxj34Kti&K2yilL77T^AX2};W`3f`rFJ(<0r=?Kakx>_T6!^U>y+Vw~u6+19o zN)>3*$<C4RqGKwHJG?p~uR30xzkdo|2Y2>@dndr%%)vDmI0I;wqIrE-zl`vPjmHo* zIv_al@xolp1{C-<pcUS8ZuWHJyPFiul+#F>S;Nkj!Bc1d<zns$W#Km~H@8$3o~i!y zQIp4~4+*7j3if=NQ+v(Ctal$eMCzT)v?xZl?EfNrIHB7V1spQ691TNL)WYPi?R*r1 zAvktxh3mJ6>9<i)J_y-mA*v3*7LZt&sW`CCU>l&eSJx8?s3-@F%s_1FSZBL2<OWE- zQJ4TvSV*Pxu@U6pvep}vNTuI)r8CGpW{#~?k?oW4JV~@6^(SV*y3?`a7O-&jdh2C5 z3+WhYvlORU3i}7VPBN0s5kK+`&f2F%6%bvbtsu^DR11dXS2?psf@B?BP}N92yO-w7 zv#sxvNj%Pxdl8|gT!BtZkj*?p$}b-jHmEI`qenO8@A{I06@4lgwGVXVgc$U(TA9jV z%#JUzl|{JsjuiC8of;}dRcYt7w)(ER;FG41-3cc|D(-S^`tvAYI~X(9Z%~soRAi3a z`CO*1qy59J|530d&lmd-15){JO4|{+Cy%|Yi8b8uEyEb$-Qn;RGj|b#n8LU_VXm|? zun$gMYrVC0vGaN!Xe)r7#2mmE!TR1~uk-%go7e@PI&Q|<{f{a!a_68mQ5bgA?1W!z z;MqZI@1EH!yR~!WB1!VkfTVz<b#_bIPr*CFPbdCr2xZPizdu?Zt>-$ni8{Q1Gr6_X z!Xf(}TlS<y7(A<Cw>}m8h>|9x0K(*J=IAyd@;cewY$_lUhFw7QtHvXr)gd`v^oGqL z#8msvnk$8=h&(`skuXtI#x@`jjecR`Clr$dFH!0+y9g45I@}Yfs91dq>I0Vww_{hq z?tKr*zB$Q%F=DnbqU?BY8$WG)JhmVjrU-qt6G3Y`{{0?UH+ui7T90}9<9}5d<AbM) zNKL0|_gTsNuAL1HsuW@N3<EKwZndB!zr{%l%*_j=H+LRM`IM@+e34SWE0#;Bm6;IB zmVZ4{?JZY2gdPwIYKENBxnZ>@m3(+gHV~_JA*#g%v118OAxF1GE8W2oYU&9kf}vV4 zr#xXI)nP(`TvK>YGfymiJw3Pdz`)hYlb9)y0H#QD>PR`&VHH1&<echZV(v~3H=iwQ z(Z~-79<gQ1pz9|?4GxS|{`nwC$$&*XvaV!G!+!U=wxueUT7p!XRJ47^`(G#~_-OB< zJ7(4@A(-2PndsiOBHmdFL%#;mV*vWB2YFq)^_&-)SERNO;rD%TR7BN#n}EKX?2?SW zD-LuW5K4s&TK<kGQaZOYt@++y#*|00KH<`f7TWa-lXCY3a*egu5j2+dN0!0$>ESxU z<qbp?yO_679rSL(%A`iBsDuy7xP!0k&qeIX!3-^(e7qX*BnRVktRwZ*sav7g{T`T> zr;PodU*lUl9qqkhI?5~oFEg^~;opkp<585vKO$}`2gRNlDmt(AThV9hjQNBja1hI* z)#oSP0TSd_ReJM!$j>?sX@^uY{B;>ta$T$Foh5s>k1aenr57twD=Vl7GZrUk%H8ge zO9Q1J0s-58y82D#@}jV*^sU*vLCRFF6D=E0I7gK!RjLsp-wEVWcHh_ejnR9kajd}l ze+O0&lC~@F@N)rl(;r98ur=mzhipK`y#w*U<N+0_cx=;Vk6y?3lo?}A$KZz2LI8I0 zcIWl8BYVU!pm!3^YQ`*<xj}e78}m|~T`ahn0Y+(-k3SOe7h<Yymow(B*IL5&Yf0zE zekh6wr^rR{v0-0~Sa|R)SotMJcbzBq6eE*QRb^T|Q~3C77CfT;?XUfgVy*u$Cf}Uy zCdm1OA;&P3e>LvE6{3`1FVP)d#I=rV>}izl!CRlF7S^Ml2vDh1q233jBi+@NLE$%5 zWwt}iku!<mA49MQ-v&kRl<{CA0{>&*<py_$Vypchn7(RKDSE9^cgpJn14Em9SqyU& zf_D(a_(OjN%slmMYo0{x?t&>A9Vq`EOZ<8K%pk3uLZ;G^yGhfF#LRbj@_+~QqYgJc zx>D6KHD-Nxp(od`pdkH0f^0lnF0#_^bx>04rW{K#16oj_O%j-)<nD@PMQoHal{DZb z7pSt2>oaw3`jgb^k}5rAf5dX32-z-1T~kJSmTc&w2^VDyr69;r2r|#y;G8+4&>Yq4 zgV~vn@VXP9nT$9l*+E=p?=2YEOEi8ot0f|p#%+ooB$X;~I;M;NR;6Rt&XjEfVpvEH z==1p-rkE=u^@myK@!M_~)@#SY+_zHR_pn`Wf3RooW)d40CKR(aF+=xYmx%d`I5md_ z<EaIomjxW6{FU-OUPis&)BQN!atgl4IhDhwN6-fUY+gI=WCi<_StvUOAPy(UrPQOI zbs(PZ3{W{2b~iI_$n&#E9yoiSP?m6$nKn)Q!5Vtm7ze|S6|J}whSyQ)S>~t;CZ;|8 z31(5VZ897V(fU*ILD?6@#mf$uMB`7`NHT%=vYe526Mprm5`cvR_}%_3E8|lQGVDws z0bt`KQDarCi4!H!J7PqJplv8V9kx7PVDNMCfwRw>iM-!SQP41#?KiDO{opEe(<t2h z@(>fXTiOrDuG6>yvB7_={QqjEV=4I5^=ZCnUVT|tzTU5Ctl3qwFYjSTw4*cX;Liu8 zw`!?5EuUkHcC!1`{`W<c_kK>zb|MJb9o>c_A8bj|ER0Dmf0%b8CN6yttK#C*Y<S?Z z99yX+b~G$F;vNz($g2h_=lMt_z`Z<jG+)^ud}B@k+9qYh%4)dffj_@$PVM^t#J;0) z%13dP(HIdLj!Z1Pw{H9rU@Ikhj8N3>Gn5^i@^QtXr08Jez5Dm{+$%%<!ap(@8D~c4 zI$>mDp_Yvnw0Ut~UL4Lqs=!?z!d9^E0`2%1V1W(YCK#_bmg<jSNa<jej$S3HYO-t; zta_tYa2^ufUdBbeGbt#<9w`eihAtRfH4ZndCmbE@bmBkiY{FfS3w3h7GDufccffI) zDm7cfB@V-YV8@!UR}+}}%K+fClb;3w%m(91=|wnSZ)cU^1eOw8(PglCWS6#L(IY#v ziTH*IK)7LnS#(*w5Nk-xRPqA8M=H%2|Lo{3h|EJMJ|}g4uy&Ti(iL3@!8$g1cDMCy z-;$D6_*TU*>V-T2!tgI>Dfzp8gA%9x=LgVdxt=m9=I5JHeyWf@0sYWD{KkF~$-p#3 zfvs27p}+Tssl|ACkQSXu1d{lOY+&0gjYCB#^)PwTfzbOTgzlsTsbp)Q<Mo<#<XBN2 z^QFGUE)O}&tA_{MTy?vdA#c<ZrL|%W+naL{>c{i3+0_M?Zy{Wwj<XsrvL@*^^#|MI z-rzF~?lhYY7(+)%<{$0k)WW<BL{)x#1L=y;xxq7k-CHR2{i`4p^3$_yYo*)5r*Lmo zNrN{>M%CAecm?ZYw+;tdEPr6?XG6|jcVI&J==vA&$&tz)bK-Ce9q3SFF9Os?j3eA2 zQrl0#fG$s~ebSt75uK?Lz+d6({~1hPc`9dl=LvtXEPs!6a9-6p>v~;%9q5Iiv}XFg zOjSipy%<udU!Mzx4@vGn+`SHJqn+ZyBr-A^!$!V&iupf^&c&ap|BvHm7tDQ|xewdi z@0Spgwwak*xrflm{gzu&sdhKl+@n-;DMCV$baNR=lxr@jFOnpcq|()IzdzwT&Uu{k zIq%o&{d^u5**&>BI)=HBt99kwAG5kj&)TQj#TLZIBS$iNT0_-JHw(jV0^A5Rz<WQ2 zE2@)jP&m3Yb3~!~a?IE%Znomp^3aEw^*XY~;A>~N|876}Z|UeW2ifod#Xj?V)0~T~ zqVjwQV1#4h^Pp}~8A}t8FYJnHf8pqwMSg^Ph@_ujRXA@DGeuHBI68zOwf|gjco?DU zXkLvV&OkI~(h5l>dGJ^W&_L7_(LytP5ZCQhzVn3CqX@9L7K#eaOr%$Kzf`7vWtw-J zRq$=`<i`vc3PZfhHD62~XTTIdCRfliAnB-jBBDc<wexq&@wnU*u7h0*y)c!ec`IjB zSsiJ-w}_-_7M68nDHUP*4SY6rR+OD>R`PBN=F;gUY@RzNS?4Zv#u&*l5wtA~=c_58 z4+^_IlOz++N951Xdu}oc+qkPFZC%KOgVe;npu|4ZLtdXYtF_$H6pmy3(FC@H%(?Jl zO>)gbQ~{^mUL{+mLLif}Di=G#szzLja(IC$%9?HoW5=aHak&5ImL@o^9~4tS6|&X= z1FS@;hOHKu4kZN9%-|w_^MouVh~fd=+D;1_{5(7Yh#B-be!tHu$10zA(C@`E27Dvy zVW!4c5KVEcK!hbIn_9yd#O*f)Apf1()Otww`(KnIXj3C_r%%P%*QO|A-Ck8?ZpD@H zUTc6va^0EZnl!f~+eg8`^NAtNTN)Z(sWk@9rx7{%2uXW|YNv^bL8F2(#qj&aXB5HZ z|Gb51Wp|BbUu^$}u)^jZL~qc3W^<3QA`v1>y7t>RA)T$R=?BTxh#OICiz31Znbm7v zwx9*rr4lQjMQGe<oy3_}vF)G?INyms_uWKjcV~#$sZJ~@RWSe9rb^v##sNwmd?JkA zrW_KA5*O<ad^>~_3m27V978-I)ZPhz0*SgqtnUT2Fr)5sDx2K{xD0cc9X#6JJ9%8b z1%Fi^OCXsfBK9<g1?`+JdGBh`dyis3w4D1>!5moD^o_~Vw4W7HueviH8`!6?mcE>g zu6S}Nj*e1RcQVzm&I^}tIP=tAW2jfpw=G~<KE_5wrK#{*P{9(c%$=O|ItD>)=9i~B zu(>SG@Lq%@@bKjaZM!PP$Ov$YnF~kP;LEUM*bV!<sln-WP5b%zM0gyWp_Q=89Y%&q z6U$lZqa85f9}`@rI|LzBC6cj5xDqAP8~GM!)CvgW3Hvw^4SU^7*L{OgQ-kuQJQfZf zRx>Pwhi5N9R?p;PYasFt2IF0&_Y>45SDVQ(A`|7=$JKvsi|jQZp!<pZ<C2w)21(-! zrka~!dR04qxfz6-KSXGQoMN^aw^i<@f<hzV#@KHTR?Ko9eA@jk$6_GFIX_zCtg?S1 zNlOw46->wnOa?5tWBaHD)gs9-VK?sd;+3iQech)lNx2aSnJe4;lRjUx@jY4l<Emd) zY{zN?Z`(amd)WZhV8$TyVorPB<IbKu4ZBk?l1BAl`5Z)f4hTpglBDx7M5Sv@4L0>d zL-6+yWuQ={2gG}dBI*b(S>G%t(>6luiR^Ah1Q$M?tPsA7Q1aV@3+-8c9zIC?r5==5 zIf<)#lY%xTI_6Zys=uEbbop;^kNsh&+TU$H)`s<3c)&;f-hk89*_Xj@u`{@LRC4J~ zbBWXTgI`m1oIx}4-~1q*t0#=JuejI8a3i3d3QxL^PVcI?&uy2-CDaw@Ww(m8-y+J! zU2rf?Y-O3FYwFZP(oEGT2XhQ059^IJ*7)2Pjn{VefScw`Hudx<-0Wo+(@G>jqJ<+V zs<@3{J{Hp|WN2HR!1cSR!J*6&=M&pA7kXvkgz!9chSagnzhqUZ2$PrJai||s11iw5 zFo$;kz>EVZqezwxny`Fg#y8`_Awltn{%kb<;ISVPkMp*F;$%91l1ap<6JPGXlY9Tz z!K}4@bt`rH$kZjP%cj{kFW)@j(fjC-*~gsUp2OXSYYNrd`>NJ%9@N=WlgR#^y>s(& zVprit(T|s~!{QR57>@tK)jMLsRtsSFRd$bh7VoZpQF=Rf(9*%QN5+<r63a@08~ANA zJz7}gL6+mF?TE7Ish+(3{!mhPiCq+wuz^D3pejojy|2?5HD-)GRsgJ8tCIPi*2~3I z(yL29(72X<kgPZPg)LS<qE6nZ)qlwaLmuFjM#l0G^ITCG4#Tk2V7%+K<0jT5Amq6) z`3bCOg;!PzXkT8pHPEeI=%;IE^C*-7<Kt`==(*52#Y(&ccT}L<6GCN?Rzk8O{n#m; zFt5IXAS;n01#G6ZxIE};2f*?9P}|(b4cZ_bN$13lvYknneNOJ|Ir~$dH*NuI=ia-= z@xjYjBsKQ8;HyWO+M}At6GDfP*A9!_hu28Nd{D`;Dv3K}i<)P>=vI>5V*5m8;!W8$ z8|;)CLQW#<8AMw!?wP!3U}(ZpCbI0|&~!5?K!Ec+1Vt|}==WfZSR&B*p!>_?9y&~~ zof{C%Wb#W75$bof+}MR-3c#UXI$?_t+DuNqb~lBa&frqP%oe7fyOCxhUA<e!QUknp z%AP(7E9={p)d{nM&~h>7rTq#dyJ;U|<Ov2O`<DesQRN9gQ;7<hixuroIhrDh<tgR+ zl2&azx6GT`Y#gi04`>Kq<8@t09C8I`Q)$9>+#P0wiJ~u5(GMjY6xCJo9$A@qRcMcM z(C;FVm+T~(kXWUVPfPbbTb_TqPzYW~3&WrVAFrBm54d+wilB7?fs(Z45e0#9gK zyvA>6mCEWN10`WJAsgN!rzn==hHYMp{C}NTC%p30E`xL=G#$ly@Dn?ZW8%smXc$;& zf^nKBi8M6YL|xR-6~Yccn^EhHDk(V%Wv{_N*eonJ1N?)^FyVrkT()05Lx&1hSEy0f z0k7LS?MA_DASz?ntUc(g$t)?!Zl{Ym`Gl8Gh$tw9E*gK4m&5J2<ixX#KA(>eIcy?y zjo&5lv%CVKSf`-}njAX3ded29N0_R^xicf=vBU}0ad9Hm9%6BWfZ`zK;z#$my*k1X z0#u!jM9BT8h|@BGQA`{c8p5^gF&LJcD(<~^zL5H8+`YurU9$NJ%c%vb!sa?|jO|xo zrzMKm@R)VcET@gJG)Vq_Yp6p3OI=B5a##LTpqutZZHsOYfkM<AuG8W_co}DvIpL<C z3O8fIHn)j+I{R~IItE3IZ#21YTrh5XaMfEqr)&RuoY8J5faC5`gI}^{agXX=AHUm- za@XBE39H=VmX@o03p`*iF8uJlmO|cS;c8b(Ip=R!|5l-V1Iyh3*YC<04e4a>$LVhi z_=6@wA^K0LToUx@j?g1<&f(GiLU);CG<Ng?r)${7`mPK0B%7KD)y6O(NLQN^>i5UF zis7iKM9JnP$$?(oG_M<EKOwI~k>ff{3lkwC7pmsNBGF)}YbXZ{l!CuVUWH666Y<m$ zUj)mh9%MD@sp*ZI8$PJB+-7oBwrDl~^`DW#?#>Vp&BVLRARDGrU-zyFoXTaJSTVM# zjO}viqREN9-zGi<iXIKg`j8AKj}(1@+;n**<~+p}pvvW6UFWA4JLYoza`{eBj&r+t zUb^u9Z|y)}q1O^83@)q$vT#8wK%Ul8-36Z~W*xw(vJyV5z;14sZEKqS{qwwkDZ~;6 z4d?Gz2w;RsI>N}S&k=3|r>!N-+!?5#jzMm2SYCb~sif2-Z_v9b+5wv?t_*C9Idb!! zK`oE_Wg58))~2Ulw(L&X3niLBRRAD)1grN}c`wZoZN;R!5YOI&%{58QqrCEH%#Rqa zoT$N1CKH7V3?u49X#rT53)UQ@uX;C|fN4*&xLKM`7QOYw>l0QGU>%}T7HfT;f9c~| zA6ZirI{L)Ud0(**pqR~?^4k~7B<EpNf4TB5()`P~In6HzN^LliCY;8GM;G^2IIM{t zdce*Q&k0N{x`yNgts>um%7e?<p;VTk0NJ<71pV3rYjQahzz%+J@190sNXbqkL=Hh6 zWa+~po_;NGQ&L$=ZjJ)MvG~x9!mOzUcxs>RTs>-b#@2Dem68s1FyVyxWgc67VMCL8 ziHA=1m007av0-j!?OE3KAnTSuqtmiyw+=FX9n`ha;m(xmWe=8`NHg=e`X>9AUCXqn zw^noaYo&vAXDC1XZW;K3bA8mgiG7yntkDx(n|atr2tewGmDdX1^E6@I;F&BgwBQX4 z`-r$}HfDQxRdVRREKJXvmJ1l?HXCPJh^BBZH@5syO_VbzFW)QFCyC}>r<^T3S>&@; z6so`pnE~6m3x9tg?3K>>F~#0~aOL+Cp^#D5-VM$ZJ@$nVlN{>Kf47j9t%eJ`t*Lhd z{4bV6G`FP!F-m1_vvw7^G3q`1dsOAy-02yQIqFL5byN!UqL0o+8_J>paBRUd!`DOG z3t7s^ZQe;xvwDz4=Rv)TZXzeF))V3XeUR072-~7Ag)M@=QvKFRBHTQoA1zC7*E==c zZyBi87=2%|G{0L21Q)gS<yd*=wr~ZwEXj?B1{Er{ZI^bN!M`3lU~7p*mPqU|wZUsO zR>v*#M*N*B!!E11Z#>|*Yi4<yDPE~pL$yu`aEyj9p%5L8uL(P4kWJADmwCeW$8bDn z7*<?}TPGXR<zunP*;j62fjD#;arw}vmf&<DD>&1^ZznfI&eRs$8qzVzjk?wuBr4ef zLtjKioQW9Jb5yc{CbOY>V@&HP5kEhX<20r&oMANzAy~~nzXwLwGv5@9(6UPlxi?ac zD5c$oTx$KsHp6^x5U|P^YF?iyW@Jl3%<-AW2AL)W3<JMcZ~22isQb^p2+i%?54fxE zdo}aAv@fBs8Nj}gH<>J%yET!eo_rTp=#w>*b;SPO>RD>=<Cyl<M4>C!v-q?}flN|} zeet#0<x;Dwk>wn;Y0ll5qE5U?d9zv&^}i4uA*>EN7%g=9Q&(VTj<ZW{kUQIvD&&RB zLjGhwSIG6JvJsM6Z{;-ZB9#JXSO!!ufwD8uv&*&mF7Lk+=CaD7TW!!=zSv_B<wz~% zjseL#(HG@~fx8|o4?nhtiI63g=?Bao^Q*L2h3ws~CsJ7Hak427VP~iIzRrOe@MVEj zH$y0`-`eXi_MF*9uNh2wvz(zj7^msSc=m5ln+6tOn6qQRZ#Ck7Y(!2z3(b81n|=s; zucShBiz>n&;nJSGCO_Y;Dq2u~sZ{AJu~r1YWUkyk|CPbrtC|&ckNc1P_8__9o1$0( zcNF>*UTeYmV8js&-V5um{E5Cvdel#~dV9ex)5C<5;?6b>IqKJ;7&53>xqT1f$&Rgu zwD$?!Lz5v1{)6d4A`QhIVv)Om9jNP|&_TZog;usl$_56!vm9DIU}q&MKQG+BQIgEM z6EaQ6Nq<blr*%289Jvs~8E=ayX4oKe4_9C}5)uFuEN0pS7-s9i2qvUjGr77DPXT76 z(gtKLC`_|K+5TBsE|g}hlWa=ezi*IvD*xGA3FbZleR&XU5Ct|I$LSt?_MOVmJ0DaO z_Hn9%JN<gIZ1`3Qc-G<^Ec2h;iR*9DJe*bxMT&SSo!^d#^?WUjc0qwS{uaUs^|QY! zJ^@}Ff;9fl5zWq;D~J9FiPZ|(Q<+}n!l3{sXfSyFk|tzG@lLy_&kQ?^BHX2MOx*jE z&B0@#U?p$L00n?*ZtpN$1;vR69cd?QCGxomy{*T7+dfnNj-KpkKO2(Hf~DWbj(=d< zr9=0^n0o0K1Yh;IOrd)ZKlowBjo=WA(eF*A%wBEunPZ*tyEFPSnFE=EQ(dp6$&!K< zgln*=U$3ppeRixn5+uzuS;d^WNl`x!Ht>_vrTRtE89K)qk*4Wqg=rRzuehtB`$h^( zEw9@^{mV9PanH~`fj_-rb90{~H+dpwP5e{J>srnZRA2o3@4-~-FSf@&_K|J(Dk8!@ ztstlz;g#+lGI-lN8Go-c$4^4o$B*MR$Smy;m1MsKn_(bbue(a_`Ot)pbqo1!PeFpo z-4O0U0O-W+tgbB(yoH<|AYt#gN(3O-5Q-O@>du7_qS2k#YX)3Z4C!cv>tRlgidgI9 z_Ek;S^2~^5sIX!<*3w?%+X>Ga7qu*43yljK@@osb=6OT6`0djx`#y!<XzY@D(Y5b7 zzu^5Zw)jj-=&i)};O_?%{QMfL8<q5Z<#i9#ZvTYnSNH;<!ut!y<;4L5##OkM#M_o) zzMI_ckhW!0K+{=RRnd>6UYJjCPgdQ=spsTZiCmx*w(`5B6)jR<)Z>qU^MnE>RCOZN z_5wRGUsr~u3dltONlIg?3lkX#M0^wGxyTFpoB5g_v?RK39v%_-H0QG(sF(1HKK86x zMPtWgbN15CkVWhZ3zfPA#KltaaHGIqKfX>6#+(=UNWHG;eKwqi#}7uc3iQRQ7=`3p zylO`|msP|Q18`|rpp#k^>j|DOG(GF2(^}%;s*59fxiNrh5iAGxg^f6{O6RKDzi+Kk zJtn~)K-+wxP*j|57khhNC-wKs9}dFy7qb=9%2EClx`X`L?ZWJUC-p)udWSA0krhL^ zg${BD1IHZXf&v9a%EX4B%f)^aQ2!-&jTL?<U=Hd&;^Ip757$8yDmq)We^-pGkqlF! zC<EOAM<pdtFYzKMlb30lg(ZjTE`2)k44VT0P8!8gTUie6qP0}VTRL@Pr`uz8CZFQF zmT|eJ^HGtn@hhUIR4JqM$V+<D>}(a_fz?YFqcO5_uEmQuM5bBi<ebNuKi}%mMhz{V z!#daN`{qx5wy0giuXi+Jn;@E#RHig|gO}7i3>HPZP&^#9P*uHpI%o@R9DpgSjd3c# z7Zs{YpD$T*(QosU!CXaFJ3u{#tGMpnU&=iSQdUhxhEfKr+R({Opzf#10But(b#ly1 zkSu{jp4;B}a!X0TJ{VAp$X8@mD4wo5UvVm_aI7*VBBZV)^ZgU;BWHz`6ssK3N&Ze; zMs1X1SR_Bn$pGI_D5@DUT5(k~#0FmXGzOLX>e6?}m+KOdVTp_uvz_w@qu~*o(GJY3 zx~InX_ooCIbtZQNJKkH6#Oo;%9GhM}U#S)|ovs}pF+9{FNMdjO0jn$m>)MS?5XojS z+LOe-+|Kv783aQl9Q7G57S0-D_Q$3cvhoY)5h`Vq;@yr{DAEryPrUm$?gDt<#{q_A zYZMhncvU~@Gztv+1>7Gza_(5?l{dqL7l^PwThBAds@Io2zT)>i`jb2g6mURdqY_7K zFo4vIIUv}&4uV7c29w$5N!S>VA+O6VFSPN7AsFVS5+GKJXgxL%2Xqr8Z8jMw@Pbf& zbzY1)10)X6IMOhmSL+?uWBhJ<F?3{|uN_oAUbUP!->@T#tkKMkAtYd)pY)9t7=u2C zY4}&h%AroAT#4G7sW5NCwn<3JjSX+y#lASTK5#pGtv=LRacK0@k^_Rp;}iPs$?F+a zKVG;kCVLZLt7B$Z*0#g41G6M8OOFRdI<6rP3TK@0)yM+BbvUGu;<AP3pmnMwQWT&+ z!5$*SmZOfxRy}^t@6P-=GHeNS&*InMvR<UCQmF;@$_pE}a-r^$P*<knU;)AubtBsC z*O2@$Qm!o#>*k@%MFD_NG>&YV3qn!wQ5A@BvWFI_iafePEXchU512$czP?tdEL96y zFHr{I0O0mE(O=TUQCd(4Eve)eK8A?0cC?o6<x1>N8`6y;BX<}4g}za|X2t11p6`Fb zO27;a!QR?18>4hTrQFrw80S_=`P47TB~kkf=OIN$e>%!fQ2J>RRoTbxW^?cNa8<w7 zPn?ou`JB;UV+MIF%|rsc48z8XFhpH31|hwQSx#1vCtlyKY0VuGuzp8bI6Ohp0ZUSw z!Lab~tdeW4Z*^boepFJmUTU3EVQ>dkYCYN$xi7X4&ywo~fhQ#F)tO_%sl!L~b}^!o zS1NfLBep>!7Xp+iBBG^;7JAq&$a@0${wzZ7q?Wh9NlSS>TQMCb27C*A0i9_*m$6A! zU7Mg}@kEePuaXED-TK8)$DND6UEfr}K1zP57j%y_#P{&KLhBNf@;%Cz(6>hWjW}O~ z<7OkRo0ZX>X1!t-7pj%-QrTS#e#mTvS`E-8!vmikvMZa9Kaj&Z^kmHO946@|R1n|u zODV!-<Hz;iD%}5w;SKaA7~<6-k_P5WwU{hHEIo)tKVHkVg!RB{(Eb5aYw8`z>EWsz zCVCYwVhEy1rHqCvzu+xdKyUPC2t^zWmGJA4`d*HRTbXF%6>5j`WAYwoS?<C0KBeWg zUHsBBvwv_dKf{-!f-sB>ReugCx4dG&dz?@<e<8hosAy*jwqTI_`s?OOuBPeI>48EC zuGS<MaF24zE<}Xv*uJwnP%=-vQ<H7{i=o_pWdD2j7|e&EX7wibesd@(mvevY+Gjn{ zWU+C~OEXg4sf?qirVp9qw`8CEFrtoG;Q6%F5~Rzz`PxQcF-LOsRO?4qK8{npPEbGy z@AuJ&+ncE^ONRye*<TmVwZmBu#bwjf3WbZ*w?X*Q8?LkZ$F$-v(G~iS2PNg4{<%a= z3pYM>J*l|dysYn`=!G#fcM4eW1FW>#m}1!bcSHeX8R?edb-E~l(c$=@z#M|@5z(-K zACrO(={V6!q<OlA6Mbp{E4h8U7u5^4zgj7UoUb|buIm}>h|&PY=!1>WrC4A=vCEy^ zY?ZD5*PwC7_nk?<em3Y{;5tL@&<xSUy9>P=Lc8~>TPXc7=<%z+%|R+z?Hk#b5guCv zWE1?WgIQ7ZcEZUCA}UMOi7qPm>l1VABr3hYaBN6R>KC`6I+QP2ZaTvuQWF%H{k2GM zH^!qv_bhdWn4Bh*Adr4CF#&DdEzrB$$D&wDsZ<!z{GPhqg>)xxVdUi}O_BR<ea8c< zOP~w%m-b!(dHs6}B2+un-;wW3p?}ZB?SJ78;LRdDdi_gUsQ&?e%FbZB4ec6MyHZ7R z=?(4Y6Z`J(ayxz7(Gq#TzDDECrJwO++L)wQRL;BGgrE4X50wRKNpJ4mC_Rn7ARbzY zkVoy@6;!$1#X^Cjn5INs*SoE+j*V?Cebk2i`+T%;_kDsm2f*vsPXFf}H0AVsP8Ycq z2KEY3(NoA(EvE~%>Sf>rnJ~ISJ4lf>gWa0;JjT;>1;h3e8?AFy6E9VC6XZ|?gboO0 z%T~P)bxBtgydHl6k8>soem*mLrojdlukr0u(*JnFuEEc@B~(fXBT>PlfXrbbFB3^9 zwXkQL_HsN|^)85(AI`t)Hi54XcD%1VP2*REk>K5z$qRVta><9XYLw9eGJm9}f5J9i zEY>a1t|dg}i{z%J8o;WE4+>1_ma0lB(YrstYg_Thmw_iq%+*wgQ(@*Sia2toD)6YT z{prrk1Qm!HhG4YHz@wj~A^Mc8m;Q{YAtX_?i~n)j89M6(buL3IiZGBwn)+6?rGqqD zsg4T)pVf4oyZ%bxdC~+JN{Muo!2y{9(3LG<mzlaa5~Q?*N0<*Fbm$5TPvi%CTq~U! ziV6U%e|Hy5uymYj60BZMU;0K}u44VYk3>t55Nk+uH_@OIVo(ptiC2AhLKT(VkK(98 zB%v2dE|TGg<yFJTCIlxMHi9czq&b_muKcO0m<$UfcP{SfshS^@d1auuyttS?H86XO zzu!X58GnT!TJ8E#5!hf{xel(pJ@5ns?9P=+)d(dfJ-z7U;<U5;I7JXl<{qZcWS)UR z4f)ktu)Y&2f+G}HfY@S8Ub(+|Wdo3ADTqu|m0+Xjj6_&Ghz3%^d=r?8A{byT32p`k zCXhMs0_JY00I<t92s79jCAS&AE6G(OW8oEI20OZ-dHRi&lokfXP%@#T)<I|;)wZ9Q zCp6O2cFtS2pTZ<vmqi%aF6#K=bCAamrUlEI734o~lIzVPtYvjs6UcaS0eiH-V);IZ z7GCP+H2iw~b^*DzTl}`9Lm8A@#sWvxf~jJqm&#t@ag;LtiF8HpFN<F)5B`3y7GHq6 z@*vFB8J7meD}(UrpL)|y{x{Gc7ONv7fFSDb!0qXsi1quK`paPTbpR9i%plk0ZhfEE zg-~=Ajxy>pURW#0@C{<<G$rEw3{Af_=ej&if4w6AlbA!_tI3_OUWT(8OSvp5lFRm6 zR|SP1sRw?{K)Km9R!AaRqDM8V2hQ(7t@k)`hW0#E2T&nKAbe1ilj3NPq6A3^HkvP1 zY!b~!f$_50m!t9{9O1R*@tKw&AY2mq0EAyp8i-#zl+ZSU=aC(wfU8YjPUf`Fpzhej zu#LA~<{H}0Xh=3c+>tiun8-RcRW{xqO&Q2ORyg_eMz3|jWE&g;l!JFiX*<qJuCv4i ze{8!1;MRf?dhOE;F}@+U_x8@<Y?TnVDnZ_RT#aD$U-^h!1!#e31=g`uDL+Q4(_Bp~ zzl1a7fiEi=f0sX-wczAk&n8E48m@njB4q=#pkP-nawP{N$SMhHg2b|gF1JNU;SIwF zR-dJ^Y<ndD4SR!b#-4SZb5f*te^*Dh-$cgnC&Ea(B%wvPXs3FuFx{}Dxr_MW6-5R= z{`HFZ;%n<tzObK$b5w0b8q{i8pW+V5c16;{S(&Ly3nqsd!_iLeb;jG*FIS5@Cl5Sz zgM80==PcRK-z9ad8LXh&u)dm4zt3<IrE4WZu-+mm82;7XoEoP9pBIQzi{4+-HK&g8 zXDed3C0D^64UIeB<zYiH?8`%}rArqYNUl)_T-Vov81<4;EAGoIIe@0f(@|b07?>V< z62)3}3wBzN9j+xP3v_w)Js?rZ$uqA_oI>tY^Y5reN7i4vYdMfsAFG(}ru16b%EH;P zmL{;klu1FaM$wcxzK*a+FrfB`v1~UYajXAr-?n5@IxJqXsd7mCEv{*OHTvk!S?4iM z2T8<zt@jK|tj2fjavs=Cb&h8mGdjZ1hxaLC=%xyNyWo9kcZv2h&0nA7FkJ(Vx(1#4 zhK+0y12b5e=Jn6cEHo}%c%IK=4FtHrRQtPGH+($Dv){x<lg>dIasnJHpDr~FYD*&> za+`14NhAG?fCgVZnhkR6_!xDL!MY==+u0nC@6CEokOAQTP5lwQSH(hlb6_FlIMvzk z*_ZgH5UXzkuRE~Lw!lLMt6b^b;>qRRCx=GTILi$<%5s9^>UD#1B5Qq~mk^jncj@db z(M8#xj^Zo&$BD~JUF!PpGPdDQ)*9WFl-_Ej7ih1>>(PZn^h&CAlZBI0*ErCU&oOhu zs`ZZPFkCe03sS^5p8^|d=rg(b()#mP;>|5p!*3iND+cuU7D3JZ27Hj9)_&xc?B)Ct zQdk)@yT?^|;Yi2Z`q9+OWWF(F)HrfOfl~V#ZvyJ-&{B|7EFQQ<whfDTdnk76C3xq@ z0MtCQyiKmuEiqD}yh)OEcGdt9yYU$#G8W&GX2!JNYyTWka;zuu@`)>FM)$AiJw9HP z=;)_L;pW)Xg5B7gBzLI(>Qe&^rbP+kJ(s~+&&Mm6KCR|IT|r%Q3+ibSL)Eajv_bzE z63lFPQ_Jsb8(;3R=J(X38y=r6JB0siaDNZd;Tp<MRtZWvbZIyNPQjo%57gEBb;N6R zM3C+{RTXd|{Ai7x3>Kl9b!3uUjB5+mZ7aGxP!hwM3nPhbt>FD?mH%lS1+GAibBG68 z>`DYgRT3>6I#*arPZkz=BwllY=w2;e^|wqfQeN|#$(0L=;><``4YYbkv(MOMj<mIP z?|yI9UWm$8wib#hj}h=f?U{)ipQ`1Z&W9zn%Y)M9Hf$ofI<8Eu+&UA9hH_S;B)`v9 zXMV9^Y)&b@CCRDfxsIrgVq=mto{pXbp%dxbTix;iHnLkM_|?~(x3}z49LCdQ9W(Ur zeiz;$mWi+hD35^;x@{o!joC!skNvUnanX@s%jaWANo{4eS8r%Wvd&8?P>R<O=gmJ` zX5wK%r@-A-wNLf-8R!*z@9svO9B6Ty5KdWTnEKh9QX9?!xAhmmdID(Vf|xO{*U+R_ zE**5`*E>dgoTGw{w@Z*35~IVqI(v+Qa`_T<Xcs$X7r=j^vE%0ReT%G+GB93Nq>5?` zu(+%W?UChv&mRWKLqVtlP;d<kX%r&!tCUO%DLDCI?o8~3^4Iu_jd!KmUita1JLuXs z!Xwu|Mn>xb!=repQRKGjHEMg=i5ks!9JB8F=3ZZl_ie9tAxCS|>;<86SBLU9VW(GS z#uPonI|E%NBHquy?rm3$q|fR3K@7J1;k#LCqPvt?3|4J*D)|oLUi7h)3!rK}XOsFb zn_k`y<KCAB`KheT4>9M@ng^tCbQdwo3O%Y#uF@}h2$B3h-E<_1Ah!*h9;oNO^9hbV zG<)G=$7V`YzN(sdSoF$gd`i__TnE`C%n_Xmk0Y1t*lgqH<H3$rq>II*^Lz-&EIusF zab-f|tR;}aq`q#raG6B8^FFTBT+MLM>A&=&6>2Wxd|uK(MjOKh=++y&lJ~p4S!OQH zw67|yFYRO3?^dvBF41h5smJR5C^czNS&yp+KY%_jiiLhj<ecge#P%hAX%tEri&6mH z>`*#XMxkjc@F~OIccIP{<ESgg%cY^p?*{*D(G_cT^euu_0(*wSZp7bzgU$en-5{t8 zTmOnsZ5JL@^wS?(y>)rl$apH992OES*Fkojkb!Oz%Sgp?1USYSzJ-^vI+>CyL)vE^ z-6UBy02c;6J=i2`-oox(A6fiVY~9^+Zzr<Nlg?6e4pOx~p1m8YpKGtTzO{gQFe-c6 zDNcU3LDQAljsELam}_YVesmeL9#_pydNmNuYJ1m(O_^J0z4l%s{!-y12BPj)N^n3V zu)pL(Xk`1_UTB;XclVowyJHcg^JnkA>U^$>idAbGelSf(uHVaiGThdji@M*9iG~J0 z$R)4WoJ(V!J9+2|lk`3s8@cr)#IcMFBz|B^-b?0Go2N!*3D>U1zbp}`f6Se!Hi>qL z(c!7}FuYZ|4KR2=%RTU0uEvI(NTl~~xCh@L7XsUJg+uu(`D5OootPd5J@egsGlet0 zOMbWQ)q3&;J=ig`dWi0p8Pf!&zhgUSs1S=$Xr0@UX*dpD2>byuLdI_wC$29#yZXF3 zkW0_%*qwGlD3X6qUl|X8O$vCbz%if&Q62dV%>Y&=d$4s?=p4Dl?h{s#ZiTAAa?=Tl zi6qTD!X1p+<tb5N4C#k2n{9^3F+7_oRifRZ&$aedm}5Ja7Yj2Ta-}rP#vkvmGe0bm z(Gwae2Kb7UVF(N!r%qbg)*JrfJ^g0nmHqg8Wgq)8_8_oIt6XaBrHht(p=`O*#)k)j z_J;MZRb2Pw3-3Ga@O8=nXevjzSnMxt=r|xEqa2>AtnWjYhu|&5eavF{=~-#F=Z=1O zc*g0$c&$U8R_F~_HSYF~jO@sR{re;(9_}^{aE-_2wY$KJYL-Wi8wG5ce8S&_NVi(( zY*eZ4g^5azZ9b^7XY8FDzRNXL2lAkADLr3=@|Au=TrNYY5pRd+|N3DC*D8dEdbKX3 zf-wXg*qW%AHtl3omSz!{*ISsa6UxH?QDU@n!fT++!We}wRZ8US?1r1pGf(s-R6S#P z!m8A#O<<!#IncD^^|9-BqPh}lonS*@wF^-=hdZyyF(bM!gq3oYy?o#2%Bq1d9EBrI zKP8?P28TqTLU|g4x1y=nlX=s>LMM#97c?lcb{$lEnS+T(HnFeBxc&nd>_ok-fK9zm zRj#?{)y_9jZOc1Y-0^@<*wq=L#yw+@X_SWB?|S=8t0DU+jP+JxsHoekV)YuIgYggz zvtSr8pH7;4vab|~dVdvk7qd~NPwv(2xpW3h6FnkwVN^#`0R1Ea=JOjaD7Anu*rsMP z5KT^Pj*5|_Zh6o%hkqq&--_YAQ^SmW8!NTEFSF{oBFsS1NTR>u?_5fI`NPbYf)%Dk zH{IWCI~bf4UKZ`C%W-A4k~%MX`}xPW9yC+dR2(8+FE4%co#ho~MTmAlx!uS2BAy0# zjEDax{OcoD<80s4h`L<<^qAwv2L^XnlZU0?pDyFN?s2}ui8*^$qhL7ha=m@7I_dQD zy}pNnAUjglwlR==^H28r*XR#tWNF43e`ROrFI1moT?V$DbO7$jdjAMfqVx5uu%*#H zx+@g1ar0XC&~;S%t1_On<wi#kfK(8D{5VI68#MG1xl(oFIWg6};zw%5fwR+Hp0_;8 z6(vGD;AP_`eBYxvxBJP8njr^~WQWr6q6)Txw_aL&ZDH2qTcw92W<$kY<UWv|s}}N~ z>e_>>65e4=>%@WgX-nvPnNZ!6b)PT4AZD^EEe|}X&%yLz8%08=rYz^&1q!STlf@j% zVRxp+t~9fbLf%L0Lz~f?31;w4$*_dMP+wGoJ6mTVUOVHSgp_j$j^TRM&~PdHjR}=b z-x1WHEtI&Tm&}X+3=LD<hZYBMt<~ZoQn1DR9~we{i^&@HA{+(a?_4|cHwQJWBe9Ei zT$9x*b);!wK*!ZX;vm1-&}E*jn@i7`zoaYMxGJnq#M;(vadNvnilS^lfX6yPJZY76 z<oo9Ro2VGf<f-gJbie)jSgfacQofp+nF<4zg;|7L!5%j=XJD51)PuY0*4!`W`PE7t z+#slQXo>6^9`Z@tQ2P4<?tHL6Q|R|SS+_w99#nNTKI()r<h}2mh<==08rOkSvSDzI z6{TSX4-~dg7;envLubH%sNF^ZJRc621>^|qdg_WuQo#hjNEQCR<nrQ&9sT6Mi2&MT ziNm!FWmmD`00T>hgFG!+0f~V?>?@n9T~ZW<(DW`>nWon>P>s>Whe=;Y7JHmhorw-g zE?<PPonI<}4f*#mT6-BYh3@_SB~qD_yXr_d<UR;+wcWA!eWEllRdN2u=+YoF-O(!r z#)7lD+c$@^ahTRYbW9@0I;saoEN3*Tf`{C}c*$rQQz1A}$co=$7-*slj1P49N`?7J zoO}sB-^~(1(qSHWCbY%`9)w&z3N=L#oJlt_6{G;~))yvu*2u7vLcr71A;@46G1<Qu z^QZ-V*jT**ziEmj36O$PrxeFph4z1N?KjsW7jQ0Xnm6vuBEt?sfEOjACQO93N+&_g zcNi!0gd%JjJf^kum+f>ipeTxTN5h*{Epvks<?2CK9)Bei$*Rs$6*UuG1Y<H|f2s#` z?p7gIZ|S}~K~Wi;_S`F|B15uj?S~;2K2vm2hw^3t^gsyPA^@{N@XExy!WQ+@XXD}a zV&$03fAFw}U^Le&77Re#WVQF72#1J{8^Ef2q<!%AsLQf9Bugzwkt#5gX)#(o>XSjz zvH3e>M(-^ROtL<dW?rWY2({Fx(j3I?zGKhDi81a%bd9tmEYOTU?{!}f=f$|w#f?UA zx1#*3Bm8%jNB&t<d~~G0e{Rz>w5b>Mygqj)T2w1wYQTwiQg5}WdA)8ntylH}7ox1u zQ&)$%?r7UStzq@6#2nIQI5m$Z<dTc6jN7iBE`UfZxr=0zl6^7$YGl9!vdfhqxhP9i zTjg17U7NPcv->RXnh4z)lRx-f^N_cwnGetu?`Qk-XlsE*fex!jDh+S1%C~uO(`rUH zuGGZM4}MTS>jPFr3&ySc=__;gtziYQR{6p6=B1ChC(|?>;5|>Yd=>f>zNb#3oCGvi zn(t5swkFEGN781Sp)j#+Z?;k;wx4<`Z2#=XrxEMg$96<ff5S+Zl)h;1hsDTTT7_2R zY?XePYBWmIHBtk?$Is=njMR^%I2rC7yKWyQGZTq0uwQ{^$_l0xi9CCa+u~|IJt0#2 zF}-qB9t7J>zYhU5>?mF06v1yx8o(H*)HabWXW!DAGcLNbJnwX=V0D$oUwSG0!TL5@ z^d4@NTY@e1gneSM4$xQd1O2_y5FTJO|7|K7T<c!~^{M>*Ci$drpuwf2^hT_!UM19h zHoC)@Z*s$kv}ZOGI$&`Iq+q&6m7MS#H~^>zUqR2+jajFreh9wvaFx#?PnMx70ilPV zJq0JiA19;!{lMGW6fMItYF{=+9D682i_3m^H$_VgKwoDX0=SrC-JK`##DW{)VNzDz zy-HnpI1gzNr)8a`xHZAqk>}NEb`8lMic4nSejBDO-Su;S84p^$T=Y(UsK5(4T_!5c z5^7e>YC4WIVpz!lCr&$O9u52U*h%HX;T{pEInD2d80DuoOKS!d<h0FR{GBrwmAF_v zq5z{SerN4$e>U|7xfOv_^Ci+HoWp)CSAmam|3RxKB~f!9XG~gT{;>AX=^z6*GG;vy z<N|lC10H5#o@H+~xv|>$u`QJB+9jfqRbBrKxC{CeyVVVw>3*iP)b*m~IX={9dEtQp zxPCPfqm`%O{pm;4RpAn<WN7HY%P|@zZa*z=Oeifk;BO=Vz|nH{uL5EZ$~C~Q_Iwm$ zH8{SvOZr7~IL5VmhiTN*JRt4jw+bZ2UpN_p`Lmcj_gvRI=9IZ{r|OcGPQyS%(?48+ zV*RqBFyj+A#;uZsw1{=H8<0&Gz%@fmPC|J9uDhAXngr0{^F1ndOrG!4T<~Z8!GwRI z!jKRI<lIM@^^sQ{c<~Ni2c7`^;!q8D_;)g5#Bxa2>OcV{`-1QjM+qEUT%eu-Nl~fd zTf^TfBfQh9eOB<Ii9D%-mNP@K+WQ$2e8j$Bs%V+X%H^Sh<{x!C6EWr8;tvY^8_vBO z8rA(rCQ$@isGs%QHItmXnPlQ0VaA^qjK9LfzyD0I&p$*96XCs%Mo^;}ss20L4cr#4 zGBM=NAL$*`?57>7z3c#1Q8njET5p?o2)umQyq?rS=A`}#-{52pTn;r3ML-~$?&~8b z6tGg91<5sDxDEZH0m#Ev0F_wN*)be3`&_eHtt(RfHUEolaVysGvwm6Y9)&CnnjuN0 zMq?OCe}{3QM`3R=VTbWz#L)VapRtwh=*NW;p53CunE0Uq-8r)MucwbrR@1K;cV7rs zJ%_Q+rZuKTYmhX4W8#=I&eP4f7nd3O;I<%%wl&u#HI&(h%|$h>MYR2MouDST2;-t4 z8{Ps}{tAC0V82qZsE4Gml4V&gNR`^7kby;!7EQ0|puDRPzj!M1SlK8qvy712&+2#n z1(Vf-#;VRRwH$Z3s~Wq<2^&Wt04pp?I7GSw5M84p1F(6-6rCTEfL0H3bbZ&9tLKFy zx_gcFipM<3OYoJeix&|39{t!}ap8>3rJ*;^RYSl3nkZfna1s`Z*CGwSFvsUNANt|N z0vVV!Ppug(KNLS+0XDg+)xExA+-MvCn~>PEtUu|lm&P!CUY!IZVqCbG;pcyZtNXNM zu*NCV8&zscq5xOeZY*@Bp$_VpqV<#Qq`Ia!@Lq8;Ue>rKH<c;FT@*ZwDCaR$MhH^1 z3gs4yx<+sb43S;MTeM1az>Z?XhA5H4vV|YDM!aqIg~*WI-BObCI;cCa84TRF=d~Hu z_Vj?zZsUal54b$RD5B*Q84QQ^M0LK=a|DZsGT;k%5l%OzgDU7GNqJvYvXD9x@b(Ok zC$jbi>z;rCV46VvKK>W+L5#TE<i3qYd?i>sEz~bTs{8(^zrnJOm3NQA@cE4Q29raH zRxlSM*FWYGhPceXLvPpqVad@r^duf8o;6arbdvNHZjrqE<dMS^x_m|t>Ke%Pu)d?O zI6w?BT?s+QI3my>)s;oXu8`fzpB2k<6&i|%kYkkTyu(}IS-l4LEeo43y(uOkD4WHw zgw{OZ#h!i{YxC#UxJ}(X=d`4-i-{;ePAX%$X^&jA7Yw|!TqX=3q>8MPU~4?zu;+U# zdt-^wQYRN+%L{hC2^#ya?|X>R8tfMJ?AAQV#>XTyl%H!*2*Xs~^vl=uy>yk>{2AMs zZEwZW;z$9+RMS)6Bt?iXC=0#a?23mB2W+HYUH+P@gz`MtpDA`G&U;JM7yg@zX?Fa_ zf<TH{hwCjY%O!b(My`dsw4Q!EkoInnScTw^fFJ`XGM)0S?7*+1S{23Cb?+h)BHVtK z>Ij^7m=KgV79|0azk`>OJBqTZLTJ22s4muEu&MTUMrvzPUDi?$Oz$=Bi$Z4=wk2a` zs6r>l_s*<}ZSkaeG;ePqJ9A>(P0pE7aj9pUJF%)b&VJn$KF?^12MeZMj|x?}`1uj_ ziSC7d-L*0Mq3kKubrPwhH>$TBnTfGm)rTPswI=ujSNZ=!PWPl?{$Y{h7+iUh(drKm za;VPKRxnj~lU9G$K617QbfELt;f5)zd#N;!)<ZogDplVpE952ge5%;=?hRS@grdV& zGY{)$>qv`xaEdx{J+BoOCEEe{H#9ilYrF4w>Xjp@qM;!nqhE!^_ZanKA;;oCNnSj0 zpHE*Ug?nx11Qi#e_!@6{U{mS2c>2`S2Yxh(?RQ?fBjHEB$E_7fBmyD{{WN%(%FzU4 z(7G;o*U_~kZK)K)?_-i`xD3z&MB&{I3B-G!%zx1#N7k(qSp@+bi)z0X{R+RSeM*-L zCVDS>UBvH-1lSmibdp;27cFw|DON&wBQMnDm0yUgCtZHHKH>9i%HgDlK?!Eft<25d z6e|Upv_Yi1VkwA+h;c*-u$Aq2+Zif6rcP#k2@zOsjq=^A0@5q|VuSPDic@&jRHUVp zg>^pw^S&t!{}`=A#17N$TN$0Huh23NJu@RN)yxwP>_2gdxH5DtE`liG#}f@Ds?7HO z4AxB`-Y^vYYSyz`zf<#1%kuk`^8A<KZ~xHGy*!S2*mF@Cxd$e?zzzE^y**#*iwr|Y zPOxaEbxqc@FA%0cza=62`^k=iD~KA1jCj`TiU?rpXKU4pw8FqLt~RA!Cy;CAGFH2h zKpA45*42TLf?`wD7gN*-3)FN3wH%|G7Tl{{?{u@=RIZD9u;LD_!tfbpvId8Ha{Llb zJx%(-dY{C?0xXes))hw!3>EA1uY9y1M!}1XT3<T7gw20zFi?&u!>s}f*>?}BHD0|z zUb-=vo~NFoF*L1<#Iu7@SAJLAT<$r`Dv0WR=XvsEC;k>iL#*)U?g-yP8L^rt4Kj%7 z>S|5@rze@Rz_e_;fs;AhFk$=-{wMtF4T|e*iHB0@;|ZiHR%XD<+5ZHJLPySbOJ+3e zx0}BDk$B4P2NsRp=~N*gE;CX%v*bQUy9Y<KVf1hHu_8rt&jOC_V<vj@y7sx{`zno` zUFa6c#y<p8G>2C-`HBsE+KIk^pS<&0JYJ+I?#6M(yN8U%GF<en&o>T`PQC34$QAtq zEc7mHSB!#NUb2+{n(7~Hi=l|xD(;@UbS9!lp_B>#=umomOJDU+gn7*+)$@kUP4N)1 zr)xg9)EdDcX)A_$|33d};t6fa&tQfA+8d6U-u|7e4?0;covKxc#Jg$cSonOm*fpxy z97S3Q1dy@FB5?rOgFr5tDI^rA&3CQQ;IJxg9bP0A5PeO9fB%ZnW8fI>K7$$BMFqax zY|Og-&f8}>F!OIE*ETMWaqvx@ur9n<3+DNk%7zQibr+QFuQ*KEZ9SZDf7JLk`ck!8 zzkFX)M+Wnou0--QbOE#sIwzZf`J^CUS)rwxY-p}`F26>{;g+NIoIEE^N$EL1tSEIe z>#`kvV9u>De85#Gy#FOb$EE9J@2!FOKLgf7n}70ZY>#8eAV3%kzmE~ka2BT|NW(%= zXI4VqRL99Q7v#Sr%RVXh7lSv=56$8wIh7(!G|BztQVN@0y&1!IR`hAkhEwP`Zz&q< zCM<sqt5kB3w-#~gtq^ZPycZ)~i;-vnjBghZE>P+7g<3k4CSJd8QO9}MrR0KyLzu5S zhgR3}F1}}}E{*-{`a2w|yZv(<gi-eG?Ga%_;R5xZztHvEV{ZIrcR-aaATK*0>H6|> z(mhbkmBpmLtoSeAicgtaDV;JTtJFjhTj_g83Xr<RZx9Ky?=SUTEu5Du!i489h|XX> z{HC5SoJYWVKB$-tWky7my~K1qcqv;Y<-9G*#m^UZOAfz!s+O@&)5*Y;F?{O0)_viT ziAuwZ8ye#RKsim6`YBz6q9vgr-ia5D!3bvEa+}@KHX{#S{mx-`7#a*-prmSJWGe83 zVDKLUKW{d!&hPlhGDMlOjMX?(Uhar{YkJNQt$8kcQ+E?Ar+f}&VsocHMK-)>C;89Y zB=IA%X_sa4KmPc8Cm(li_1j==kli_kODo&sJ)yG(L$4wIuoh16<Su{sjS+3QEYiz^ zUBgJW1xw8U@Z^BbQ+HD%O?u@Q;Yfn?3{SG1CdtQ(22#a}Xd*zU3)+SS17XY~_g}IB zkT#VQ?)hi{&>EtrAOLhW+PdRC%u}-8JYu*2TCnm|STkP0JBJkE&X)siVLhAS!{uh- zqkrgNHV&n0dNDPy*Tc#4D(W0s7g-E*R5RCITJU=lGj#*-qX`O;BvGWP>1f7iE9f8~ zhSH$4ST+X&FmUIEoZX*&PZtcPPC@{aV2X-%e>=%k=33_!Aa3W^R+da%^!0$-;O;E_ z>mwMaV_Wlxk|=;@RaErHpw#$q(JlyWzI^4H8(?{SXfitf+ABcLYfG{l8Cp;*k&??o zpBP>)xUlEwr`5um_bMueORG_ywH`vE4`z!rGLYDS%eIDK^V7dH9T?~eoQCZ=4a)28 ziix0es$A3u+YFt@XrvpdkdzpQnsx-5#tJDqAUxSAV!IS6?$Y!{$Q6^ch;;OyEa{i^ z3tSXYI<s7uspjemLb{upnoc7yP7X%|E_u!KzJ3oz5#qLtl3w31Pz%U0;{8>C;xyom z2c2BJO0zz&|EGqDU}^R+6#&3A3<}#O8)B*`KYw&5ouD;qb-igkJFM2D;(X*lZLiD4 z$`ZMWxRVLv0Yu)DmGaOW-7-JN-aJu!Qh&d!D8M3!JW0(bIloHHF$le+j#8|Rt{W#f za#h7O+ug7K(@gbHNj70oa6(CZxILrd*A<$qlQ+Tv7A#uCz?cpeGEr_Yyi-^KmZJzn zB|=-0XEmx(XL%t{ZA_9i*fJ{7d#>jCyrTF>qu(n`pF{n$dMm7y8V0J2^O>qG{^ZLB z?fpBPW9+uDEn7?tOom33hsq5gwE9B8l}9k|pE#*MFAp8sRT0LCd}vC?`Rmtf92t(T z?O&O>d<r}&s&h2sj*#x1{@dj}4}Mw(R`2A13+4lcj&12&E&7xZ{hW(Q)&)R^kGmfi zRsnZooz-x#35KoYw+Z2%q0z(F#(y1dRtXA2xQPrbuQQ`l!`52|wVtv?t;$Vh9OJ#V zunxG;kcmuVs8F{IurT5wvtL07$ffk?PUQjI-?ewqCj|EqC;<R}hh`U#dxx%<%7alB z(WY)nX_t-dx?;>dnpFNOw{*v14JwbGG?M7%SGI$*V%kr;7Dvf?)t>tNV4}oS_qw0@ z>=E3fXCB&@Se{SN7ow_#bnm?#P^Q3?m3BGo@=D!xFwa+ncCCc--}S5I-*f*xKi`oJ z8_#UNY3{g_d{yK;O;i}KQXPD{!G1?5qT+lINIwp(c*u2FOZX9qD`d4G57=lF=Ldok zuuDWlGW<>zg>V#zVu(yH8Rp~J`j$56r3MC5X_S<-y5`~NxnT7;sg~kH$O&EmBcIXp z)kOfju};xBm1p8=zel|T@AGBV&z#eGnNxAptf%lLAxZWjg>7oqCt7ffWf@RA9)}Of z@^)p)xc}kDrP^n?w}eO+x!da)c<jyJAY0A8;a2B*?fT?%)jA2`RR_@Qu7Ey9e*8T< zE~RLJ*YPYwEf%TkR$rlH#}xfhF5T%6M&_;$#hN1IoS!8M_<G5HDo+2S=uG^X{vSC0 z*=d_=!`#QreIFsWVVJWyBg&cFA%t(o*sx9RBO;BEvygO9&6)d3p;RNJq9~P4Kfk}> z^Lacz@AvETdOe>3nZ~tnNj)@hx*2JA6L7rW>xObW=;GYm-=^`Jr=5-qbg;AC(~zNY z$C=^g?-6S5-2^zWOV=65^f`<`6eTm%sBrCG4KVH+Vy{<l84W@MJi`#c@{eLA@dq~| z9eOcN2S2g5Q1H26B=uqSa8yze!#O|5rD0=*Z>E@$^=w%zcKqG3Jz|GTF&IgTwN}Cx zRB%F8$bPOuKfWYa_Bb)s-upt!o}U`FR&5Pu_|@7UX(HJ-d0adiNxvu#CV&$|igePb zx6+^CPNsd~2{EL07^b&yF_*cCf78X7WUBhPn<Z_PEcLp4nB+L6G-b?Ja4)H~%n&9o z3k7lv!8ZeA6x4L=Lp@m|CH&+fMZvPd_4qyK{RvEl^!k8^p<y}>NP>o2ahI9&Kf##u zT?)`i2?{dCl-oK%giCvsg!UI1woZ!J>zs@btng(Q?;wGx|4!5daXm>rk;e%6AbnKY zQ_6zROVj#eGYNy#FRt>aD+mc!5b4AEE_>GN?UdY_<Jjj`TJoAoDcCsuWY-8_t(<Xb zg2U*;K94#Y$@i>8r?oRpl>;w#pPT84qFtA!AJqyqn_ua|TjO1!kog|PlGhLJKX6;c zeo4H%vATnSmgK5g^ygj-)?H9Yf`%ggi&8QuVAv(dVYBb?m}fMYj<|*D7vtV;0Sb0b zPBntpHwNS@z3nQN$Bo7qBeqg?A~n7Hw;q3TJT?cFeYsd)-1X;7__Ls(W?({3QxA54 zTD8iuSOp22Voy5h7W=KmryUT6EcqX43x*keD*+G(=mP*yCCc&#hJgi>N3j00G=y6< z;-0eZiRS5nvaxe+sqccUnPF$tqN}-WQW3!E3%5a=0AN1q<NpvHm+)ic&9OaIkxTJV zokY{JF~twu?hT59Io>{=Xvyw#(x;#PNSIJ|s@8RSs+gOh(H3lfT+~Lk-gOkyc3p9~ z!?w3bF|Q%flb#e=y;XuIQN``5y6Qxy%7)rL<W=9b!o7~Sv5XEga3<EYSnSDS+Yk^b z^Rr9UNu&{>pH{-&Y_Rf?`*Qmpt?}4CGECC@K9vGt3&6R6I(mv4S>+7cxG)rG5RebC z39Y!i=p^C>%@j(xU0^)xl|P=M$+c0<m!W(VnC_QJyWnO{6yaem?GEjO4Q^q0Ne}Od z%L_#l6^~(%I&L&Ukw<!=?{pt}5u9}Ijp#KUdL?1};ZMKQ+zHbkh723!kURgb3Z2EJ zeQd4GmD|Zi4y&xx{WO}b?R<75066nDH{_}u*sbgNqfZ4*hK};VzSKKZ$xMqsLh>J+ zG(}$9!expBkPEpZ<bXgf(}mtK%@st?yH}n9E5kILPCe@AFeWrzo&!5=3Yc%F<%V%c zl8mo@_fp<Xy!W9uu=WvyYE_pnPCt_j(hfMWkH7rbjmYq1(BiBvi8|aKVe-1a_HxPj zU7<82aBYJos^J>mBRVe7Kc6zbK{{lTTZyNs<O+8NKn)UBZWRRmlk3|4;{fGti?lZ; zRXtL;Nj~nFHgm0g4bR%0FQyziX<)M;GkT~6B%DIBVgB1Lyls}hrJ2&be-aGS+6JFi zvOM1py};q}B*RX?ffs#HpE?n?M<_1N>eqA3-yy7NpH<jea$Y|sV$dtDz}W#Tz$@av zE)Td`VfKO4Bk@`X8~DkZqhD`Z=eL;!gY8PEkwe>D4fzsTU%Vk++FDd?8*eOo9(8^D zzmibez&i<z{kOV8f#*!@6lk(YCJR=>LRxJj3bmygU?eIV9>+%bvf+6w#KqcFpg+@T zUICXz)Y~CllDAh+j2g5RL{|p`yO?7*=&CH2Oz#D$UK}6TuSU-=gurzH4Zm=3^O%m- zc0G$3a5#NRP`3bP767&(P>2UI;BP1OwIOfeRy$r;HWc7s1r5ngsmpR230^ux;es0{ zge;9pPNg{1I3vlY6cDK-%cB~5@-_VqlCti;c7o^D&M&kd8@nMjA|jZ_@-9~3E}BO4 zVvfPwX)lL!mKHGcW#aWX?&5l%bX}2z1UtQ_%EJ006M;EaZCq(MXc`&$X}~TUFgvwB zjmimt9<1uO1mkhb=l?!4`qA&^Eh0F)XK~_*zBLYQJPnW1rbD0t@M8G&1a*Z1LP%S* z=ZrzA_u;sHnDaJRg#f)gj3LZGT{9qVY^coY*=<`)P$m-~7ws8nw%!w7yCV#>6V&Te z{{#c>mu1UuWT#}FN>or(SH6^DdC9yUZZ?G3>sOE#5wy2UpzW9u?-DcHeF|*39sxie zV1ty)aHp4sEh0(@V)^78#ra}GYET{p`5zAI-o_Q|b6)BBA(J+kbsJX>3-Je*&&d)= zot9cYrGJ*L@Y|AWGvrdLzIzlKZo{$bn@2~<(Pp+0vBq@d*e=;-}<hs38IZN)IZ zHYi6CD~pGbIZ$E&n7j?$GBDH)XX58DL<;jq(&?<CqRc0uTCvH;tCO_`l6Cdu3HMJ( z$`%U+rf}bNmI_SgKjp%;&3j>}IIdA7QK?*SS%C!6yO&uqhCvc<*xfvg%nLv^x1la- z^UZoIvWk$`x4C-SP{W6hWX+_SDJl9Ok&b%WMY_oEqJlJSR160e;*E~nQ+V+Gd>kUt zQ&#mnz%|8np*}cjPd54@8tx7ecr&6Fe*mCsgBY{nY02)MJHey6vIv^`g_$J&IR_zm z$95=icL3(Vk<;Qp95_%HGE`-{P#c-HD{K`4_sXP(O6~WC4jO4q4PfK}BWtj685h8J zH{}ft@|VKD-*$D$NTg_6HZnH#ZwHpXeiY|=-r|Ox9tN3*mh1?y`N$CcZKTy2VB@;y z^An6LB_qh&u;@0?0D9H<VU@Xd>`WRfpMW6VzSOgxfU~3`?GbS-NK8I7WSZ-5TE46? zS3QRd{gtbctpBIl*Tfc+&;~z2fqHRZEx#^sTVZ<j1%l5Apo0va=z2sc36h7fH&S4C zI}hKSgP60yD*0foSg0H4q%_p<9#Y^iQsD7ot*~<C)!^7MH*9H9tY=!v>E-Ml{G~wE zdOum?X-=@ta^j7m$iVoZ>3ip1P$iqSmHPHA6)V<C+&ijT+fZK6b9<>&`fO^00<u~g zmWD<hV{w(>yl<8snr=U&w~SzDOU<Ssp3fYT0_DdlSH}mU8R&unZLVX}Tqqs;6mPEj zZLS1%M<cp?D^+2n3!b3O)!|S8t%WNUz|9;nsLtkkJ%%Udurmx0)NAQ?a7>0cl4Cvp zgQPi8go2)X9%-+5Hj2RxGk@D+L>Djv?@#+J7vXk5cSX~a)2vMgFwcKF!wyVjps;tU zB7D0T-9edQLyOG&sX}A*u~#H#H@Giqqgn$Z<?Ixbk74uLP;{K_tmvWN;i6w3*yV7L z$Jp>17A&5Oj4U{0^7cL@L1lg4nnVzc|9m^a7le>;6#U_ixG)U2+J>D+tL2ABHM?<L zLU51dN0k?2%4_W-fu6_%BZY5smN&s~S)@=IZr$uMW5bNMb|lW6P5BBvni;cUTj9il zK3Ww@QxfSbKK*Mbl>VfsorDS2u?}@iDS7e;WtVOU_3ztDk2ewN-NQ+xHO2QH4fx_( z$t}RF&%FaLrK#OWzH)2vjNMuJoTu9d?+Eut`$I2w%nG}O2Q5W2SukU5Xdx%VmMFT? ze=c|B{#<*zr6B3;dsqG!7_UYVxDS`8r1W`hi_ZU|(6Tt6A6M_ysBy*PLQz};zRe#| zB|o~csLr0k1&m~&h~U1^!&~LjF58rLH1|dupNAhTj0JUVgX*q4^lPbbG*0$umRkka zG2UrfgVQAgyGq@QC3VuJ3c8ZIx^^9(_{#F4t(x!GMEzSySSi;7*<&QQ1sJ2}$LA%- zL9UGfsM2jj$GYanM(;LlWHT;j#IpB@0J4;Tpvm5#@?<`%ZckUwf8QT8qFmkNi=}9* z(a2mBG8)Cm@=jMZXo<Sw!4=Aa|LN_Ij>Sy~_gFh64Vj2&>s&_*9k=tvx+^|h{Ey<v zKFJ>jwWZ*b(cJ9LhxMY#f+UOs3g{ca`nV45KQHp{#cVX62pz*jKl3U*mEz5;+mQ%^ z;ebR_E%yGb{-wsUH%g6qX)1i;eX-)K(tMsqifH_c5sx6zJY4vvl$?T>ce9v>>c1)H z##T)S4)2doy}Ud_(R<+hPIEKCV(o^^x?R8DJX$+LmFGS#l3ZiWf^|L^n=t5ktgdeU z^0rcYl6(BP-cHYd5Fr<G#XJngPnt`k;*-$aM(EQ^+<?8fU|<xMeqHW_BW7fmNl1U@ z{wuk2p;Bk3^|StywC~{Wj#FoLkVgXuJ#HAFHlH+?aAOQp({uOVlH{H5Ro4k4TvA7d z;~FkD-}@ZSoAF=Oc?s{t3A>x~!+IE%YhN<<3XL<M7LIZv+6E$f!NzqR78{q*7}?wB zV=ou)i=9_R0lLo3c-e8Y?j($WAhNUP_q!K^W#gu;<JL2jBLOdge6A!;A#p;8T)-7Z znX?IiI?v1nctW3?KON}g)Uu(;>`yze8=uacEV0J;^Ir9py=k|Yu6FFXpXJe6w2)Cw zaPfn_ILil-aY4_H&gTK8&Dy1+S4EP{P;J`0UsM7nT_fRACWug5%5DREIZ*bGq`$IC z_J=8`m>}ZclRdY_{9=o)I~Hx@i4d!0-$Ok~NLVTxu0|*)^vp&AezGnGMpvJ<n04y? zl6QxPc9{u1b{0DEo#McHD2d@tI-rCDSl^RH!x|?J2)>Vvk_SD~ehE(k<W)jpi{!p+ z-P)hz@%xXaQeMUI2pB>iN4$J>RGPS(-ye`QwdO1sD>eVx?tG$|%6<gT%nl;!oU7b- zNhw)2?<V(5yK7#+jdDP2^l2as=sCrPy93S3%dit{Sn9Mg?B*dsiFH|##xzMiDc%bW z>K5@kT6%u=sP;uAsTxR47Pei@K!Ga?fG9qI#S;n)*Mje*J`F#wUbjjRn|%>;TQ<&; zS+!uvUv~Ju*&P2~%*&TA9WdO<u`$oZp*9qF7>k11c>C&7=v!Z}F=*Xd^Qw~z#xF;N zH$U5Z6tm6k@B7R7W$Iewj^D=@QKFWD0+X(<?`{Base%BW!twi4mO+xPk!SY7$l@sE z*+PlyY$?+c7!C)<0pNq>iy;Aeip6!n6ulCFD4FJp!$A=;@mVoM+XN}>)UiC?toUJ4 zT>DNlw|#q%swP$h>tY;X_TuLu7)GpT5?;c$a=Uidz1ds@D*7@0Hr53zr1g5-?cB+G z(lEE~k3E{FZQ4$z%wzibmh8x|-~cZ3n{!#$vB51?Co7$vFiuDsW`F3wzPS?nTv~8x zPB?B{9-D=W`@Q8??Ln-}I%aoab)r2wxx};GHJ^oG62uZY+}Zi-J7!V^z(F3)d%z{n z$8njq!+f=6tlGfG$?&On`SC1xkT%y5fU9i!&~*SA$AYDc<zL(9ZhR*_-)+#SV@c)x z^c|<6wiffL%mb%u;+`hzz+=@T>yo79FF;r$NG=N`{<tWGIWDVvyi;26?)l@^p<M5h z9&(2<9i|^1;LL3}e{8m29*rs@S-_KlP0xJDp?rvOc$#<b=8-Q;y8<G!?<aAfsU03* zLi_QlDeMVVE}8T(JxknSFD_bu#pBYQ-{Vs(Zge()NPx0fax^9`=U4DJP9DH0xafIL zyD47E5nUgl%4K2XLT-kM?J7=IIg}c=N<LF5tg~l9*XW(G9x@u%duVab{1rAGeDR-< zDh7jRq!**aQNZ-mdckjct%vTocmRnvZA+;7_)13X{y>+kZ_<R1euQ#;VC0Y!@otDR zQ}!#2B6<sR+iA(sbrcIwRLoNZ6rD;;k2DcS&WPs7C}1uVy*i-0;y{_gi(Uu|MUixE z@~{-FwL8dmQ#thE2Z_A%DPQZgG3`l6hKvDePCFre04{`u-YBEs!HXj$km0*aKhJCc zH2ZTVu6zsh`1Q@1nv-MVRy1YZlH`r)fv<wu;FA`Z>g)C+0s7!=626uS*9!fm=P-Fi zGj!N8OZd+o^^(=EhT0;pV`6pLhw2v~4L^j_LIezB4Oeqy^EsAuL&NqX%67skuK4O) z@rZ|Xk3S=(OrV@(+fsk!!;Mz_XhDsX%KjC(?rS$cqD+_r>DOBfCXdOrcH)E7c<(Lg zTHkEguAy_ktEH31uCbE)kcuq&$#L%*GM;~`PdNy$U<;wNtL6e4ovNE{!4s0{1ZRCl z?1t<E`iX6(!As>?4Lr}4Um7)VX%gT4Y80UNU|sQ!5IGgle#g{&gnO%TN4_xlfR-T| z#4lSv9mKa&uS&#=gGfir((;e#;IE<Fhy~$p)%};Ph3;z|V3<Gwe8$DYpiJzgvLKY1 zOMyY5t#lkzfX{x`O3<1%EMM>g&j`ttql=#8Ll<&D6bEtHfq``I@$A9tQBtU(hJkDc zeu=CPGjHnG_jaD(7?Kg{@+JFF+}yPVCY^__RO85_^QcYj)}!5Hd?<iLNk=OF8I}{) z%L%}v^uFX5=_(M<2<9j=+YTYhXGEQk%>An+y)#!4&@&QNbV$Q5nQuqT*i^W&?$s%! zd*JQ0N>U@5F8<<@0dRfUqu16&v7WND1u$H+tAUzt><y!+G$;zl_Y!H*GbaFnc9Yj> zl8cGOt^qo>1$NS|jC`X$?Vt={n&AqM^`5AFv9o#_OqhgDnZn2~P2+Pv0SjQ+Af-m@ zPJO3WR$R7*KWq3SMdDuJQr^SaCl)K*BA(aE3*5>x2kz<Aym|QRY|TYvE{adK-KtPs zp@IiH`k@IziDb0w7jLY5Y=2<Y#>PKLA8V)#t3e*bv*ir>_}xP_axX3`ug#1~31&^v zIXwC@=QaW_S_J>Mb>rI4O(k{FD@2qiW(i=2i7)U10&A6Uy)C67#_-doQW48<Z__1; zCv+;eVLb$UjcCMJ-U1GM;0@#^5z<i$({Q=YK>pO}%Q%E9-3qY6)bCMcE`jLgn;%S* z<W>l@6=S=BEzB1N^hH$wRD{Du99y8uingOj+fa<DEKQ~!q-9665^zTll>s*0kVF@( z;qDjA)uw6iSaP2xTwgf&-8WyZoadZ!{6uj_m&HH%e1Y=ORVPct1(j3DDeswcq+!!e zy%GEU*y>esOP0u{J=F2sPewr353@!3=L2Vj%&+3uQB&43!Zp9>H!%I^drl^TDC!)s zNfZaw)n61!bLQ0+)nnEIWf&tI5OJOT4$Y-D)XsukAF{k5#SM5<L-m!coV)$TdBVLR zxm9a0(Y9ES6%Gw;VP%+4lh2094alzE&h<7-m#vQ-kVO^Ht%c%nUHAjArz^L`I4;yJ z0ODY!gVIcI$GGpM%Q)$vY~-!-@;Ow#^$mnehz^fkSQ=m7clcqw8Ue&fnthTLU0}`i zgk|~hlp5V(`hco`bgZ38KmqCvh@T93J4zNuQm*}5C1G?N<;83Z?h>7XLRkCR$6L-m zbh2G5VvT1D;&mT=y*hjDh7hm#oP2>k*0M#vdksUjb~NP#9x<(;Yc<*`GlVqoyiv^S zl;HUW?XTg8<YS<!@QFw-RNHh*v0O{U<s%>#??PI?<gPYUv<C#oxApO?w;>2POQ;5& zDz}$0Y~^GLi`by*4|Vdnmsy!F$3bQD;}OM8bR}wl^#Y9rvzV?HD9Ar0_edKix3P?& zQ$*gmEOQy?ff>H?G+7=Dm+f3NN|O!<-Q9+(ebF%ejG9v3U3g;ppusc?eLB8swyWAH zLpC)GD)o<I(imdHpFLNgCl_RT>yoPRs{x0GhO?JHyjp9-Fg_gF*EM+dm;gE_D0|IQ zMOO@Q`PNBgYpTHN?kHX|u;nrXCf!6n08WB{L-$T%W3?e&V0J6u*G>d0>xqg);1dSf z5T*2^i}JXGn3Qs8-`E?+Z{WU&d!r~~i!qv8PVk}t2tpemhjzgnm=J}I`5r8p0=Z5f z9B$n(*-2pv*hZ-gaj-1HE<X_N-$r9ZyabEN_o5PGY5D<{S)Qggf>!LCXz<R>gJ&=3 z?gSIy>3v~O&qfELt)QCPRE?)`7z8gr{>y#D*u$)tvRuTY?L@7;Nm9MOI7})Al^wD@ zeD)~v#QX-gM;ZugEMJUh1x-8KON#+9_SD_XFZ=%QLY(m2pJs`YrjHb~1Ce7@moi?S zx-r~&y5*^@GvD)&D+ffVRxmS1D{gv)U;|yU7F$0eKuW*wFfe3aL5htvwY;^bKl~N0 zYyL}?UpI`Q`3zYiDLiI$SZ{FzP5&avuF2r;r0@ZV0U`Njs^K&lom#dl^N)R1Bdi*8 zKCD;e;8v>934lpBs=^ApTBD`rbffoxEPRGbmo<uRHKWNnxo&7A*C^&UP(|y}X+q-! z=m~%#(dm1*yK%QW?LhA9ks#gh(#60@_Q;97XIV-2<iv*9pW~C6{^^N-)l$S%3nt@N z$vXCUa=Kg4<ri}eLdp20uVYxl(5T@3JT3f2@b?h;nrDZq56ac(olZ;Btpi`lMPuuJ z(bVm7vCd}~f#lwMCn58}ZncLy!i!^z7mFd1K!ip8+4t2yQMJ-3?LpQ3;wx<sz)%dz zQwAPSWI;w|rO}BCAc31>E>=KaCXIkS3oIioYOSDRSs<y@75b;jn;2Ws+kvdPER{A( zfpij4X&vB>98O1v@AdJ7Zi9Jny{OY1YLZ<VBDO@i&Vm2d)60S%c1)ED{;bUB#pt~u z_Ay&ID!BVv)dB)kWHz)@|4u-eQc58smit{>*}FaI2NKMkUe%EW_T$^y?RefWK{Wu~ z?1KlR9ee&PUVAzWvJj*0>j1pi3RB0l=6Y81JJDQ5K913b1M=_oTIKp^n??4C$8Jb7 zy{XT-^<`(k2AnjhX^`?$2pXLx6-$*8O;-t{9wvY_%D_fs+6^?6fXK6JfPAJ<%|t7t z+R}9zsP<v^|IY^`!7LU)lOQ9F=`{CbD2Z|a(>efd!%WDBB$LyGwZW>J5Qm2RZXL|n zh}@U>tEmOpuMNaK<^y`egL;D2J398?+s7^WTDQ<9t_6r&DmJU2Y^Vp@)3iguzMBzS zcKqv|Yocvxu6!D@UG!LOAQpV0n64m-@=mQArh`rHYXfC<^s+kK@HHX7oM!>NCZg1t zHdB!b#J+H{PK%+UpmG}2xR^c-NZh8-lkc8Y%cUPobz<vhf1Ap#;#vx*0Ych$-PHkf z_D6KtK8KGh3?#n*!s<dbHqvp^X&Nkb*#!tORl=wYtQ!VBxIdVSf~7eiHBK6$EM1pE zy)X+kSV(s#!8AA!`2dK;fz~Wm_+b5S%7&;8Q<))DLOxXCEksruy5L~EqKa{he2^-u z<w!Ml6q5HDAv)KJyZj+uXk?NvF`K8Eoy$1S7JUI@RYx)H`%k3-P9aRrz(1tznxO(C zwvI=z*_1UT#}dP+S>nTnPW>r*Ms9!d(jdB+E{<SDIpvO<9KK#ok1M918Ry<lT(z8q zsQaFK!W#k42}gMnt6arOjOh^NIS`Ocy*-oO77o%{NSmmxHYPwnqbs&Igv}Sy3l4#S zZNaaN={ju?)v&Z&f%`DZ#LK7Pf=(q8T7(t>H6mO+z{RCH;2Fj!(z#X_K?kPjXpiA7 zdog`R18SpEYdK}~BZbP5wPBD3d)o8~)zbArsy%H2%yI<EiH|%wm}@_EVs+4;c&&lX z^Ic^OCz>;+oIZB|Y0pOd9l1v5TnpP(5RuG@&t`&P062m<ULh`3Oz$m5%&3`x2;;q@ zT&dnvMeUC0Livt+cIW2oyaK7hhTvRza}9zt0-<zx8fAs1?Hk_HFetmn`2EC`CU=+w zmS`nO+JN0D5cdYiYcVd5+i;oDYAkP_c|KIwVR$?2{xuq=x`pWAlxJ<|&=NaoAAZO4 z>(!sBqtY|XUri80PMZA2Lt|0wCbY@RgYc=-E~A`&oylF-WYePEv4-pF{>`{mjQBC0 ztuNNAZ<PKGV;L%mvT)^<4B%Y=0FjolF}3Mx!eNQ=Y_=o{wW1?C?tr{{#mUF%V>sd8 zgC{q&-EWmsji+108q9RJZ}a@Lni|m6Afz7#9*O8e^AFL?4QaLuRKF6Mxi`$7EvqBc ze^%_!;}O}fv8}!(c^0A>R%qx#s>Z1t<1b}iWqqi9O9DzPj`m^)CHCG+-BW*KuD~YM z0bnC_n_3$U-51M7|IOZ+>u2r^$bT8|0MG`X?;mAsm(lOJzoSfDLpKj}UlJIY!tEjF zr|Yc$cAf60iuBkzj+iDufCn#n=(s1>l7X{POouJCrzQYsFT+Vn{l7bfa1ZrkXPjKG zLJ0X(EFDnFKKL#$ao&*nFl_8d^$k|F<Oizc6|E#=2{VAkI?mii)6BKu-rBI>4G2M- zzm9|4cFeG7P`Ys(#SAlQKJK#YTjBeZYE=d~7?Ph~B;HW=y*=pW)y#a8=5X;n#)!iw z7XZ<v2>(WL<LsYSFH9dPK{RjbZ<J^6e@<xXSD&hGn{PGsQvt4-+)?$PGckh=HB4(; zd~?4d#%p4kGf;s5g`4`eWnhAHtXtE>M5&XaR1w4D8`^0>g$RL-vDa-nK$|y{?Y+E* zgiW_6(u$|8o&NjH)r(qedY^Sv8T_9<74AWOnCRqv=-!?8)VALApU0qPhG2>1$4%%L zUs1=Z>#A=c@^nmZ)ghkWz}=F>AFJa?7_%VKsTQid+_%<V)S~-E?NL@FSff6Sy2(dm zGGo?=%e^Q!$+DZ|j*EH~L#U=zf&kO|X@)CAnK5`g+vFX~ow+A}e842PUG)i!l5&o( zt5!^}jT&N_!wBGg9@R607TPDag8UuSEPdL0{vZR79jBMjU$Jx;`LBAWd+V!NTsd@^ zs>3s9GU$6;oK{8kdnTKp5<j)U&F$#}6yO1>S|K@Ifpvo8`tpdWmgc7*t@WTCta*ed zGoeGpJ1i^V3bxEj-@{Q!;>rWJuXy)uh?yP~yFoPrj@{shs6A7u|MT{JG4Iv^Kyd?N zfab0i?`{a-_`ZB8S0tU)Xvf%_+=)W<<seWu1K4}n1B2{pK#VU26(Y&>xf0Yq3i{QO zE`D!nu3<<z)^f^QM>rSZ-DO*?G7WX+lX}!H`NtIIE&i~Ej;lH>Nax};Ug6bUIZt?~ zzLD+X`49(cdLksczp)8^+>O!rXF*P2YJFP&hxM;RKdRiKx@yB8%}`&bVPn=MWLB!N z&U_aFPyNP@e3}NmUNjTm@wez=0^{6m%`ek+3jb4QZ<+Sd4Nd-~a_;2Y++rPNgsnF& zauf+N`AFOLgxot$Ju1%)_z$%YXAe!TUFwd?QElkymZXZu_HwhCVlhnU6$CTm)p0Mr zfSWAF!mC+9v+BL$A+K>tz$NFt?C2)_YpG7dLS@y*eK`d#R##B(HvMB_B(x@_be3Kx zp!#ESRH|Fw)PAFGlXDw!wB0+Cp3~{t0TAD`h$b=Vwx@hs`JuOFw4i=Ri7_GFd_MG2 z1otjVdCy`0guKj`_W}IUb7_NAzK=YDjuVoE<<k<!Mf6^&-UIH&_p%s)qH1>`sqd=~ zXdm_O!ydd3tU4UO5#A@xWK~H&@?722bKgRjxhg!<oKVqtrn2}Cxqhj!Ve&%<@7t!K zXy!E4&E5a!7Ex!{X8~-ZeuwG#pT4`t(T|2UJ`yD!MCnBwH}$7SbEQ0DGTWh)S5v!V zi-8&}$zfC>vSXMXyQsUnAUqo~$)-L#5baiigug2+1WY`6G$s;|ro#gJ!YM&`q0{3z zq?}jR0`9IhyiZIZR~kIb)(M(j$EDl@f4MKsWIUzr6g*Fgp1&~pYjn0czkrn!@n${f z<)@(it%uRxm=~d*aWUVnZmk6af4t&6KdlDD_`GF4sr~dZmT&VP<2rM-zO1aD*5o_D z<d#MaonPYhGq_liWB!*hw*mUw2%1!0o}=*+6<$rA@6{Q$6()tNic+})JgSWp1?UU* zJ8PF<6bIPWw6wZ?Z)W()d&Fh&RPS{;#AyZtafcjMGwLF<yuJT7*6LUEoAvdM5|z_@ zJ4;?W=0nkSl?kh*T9T(ft?ps&=B|IxD}3O>=QkFUnajD$8q7*F0rI;)uh-sx8fk8K zWT1}D11;vxj%T3TL)5)x^67su`7@%B36ggPY+9!cmU+JS>8sD;taMexHYlT6fbPA2 z-3Lc(Y+j7M3wvhyiuWO0>*4XNZIj2imO!q&<*%$svc+lUsw}}1BB~WViq2vlsq}9R zb=m*6{_pR~?l0mU&zCPAB}63gK|{yWhF<nWb27!gAzBmzxlg-DcX9t4<XLi8KKl9i zn?&sDHNgtoZpozIq01talcRz{|LW64&&*u|p2V(30cCSZ6^OUwConD`ChrW}D%XjQ zFya5<*qFu02dg8rm42Sd^s)JCTuRm-3^sb&`E7fxvcTqSob8m4;QYJuuA>+HN9%S^ zg@gC*DkkfBZq<{l7Afqt*f3yt)%jQLHOjZZNEAa!VPu1&bPeJA_?zDi`k=ezejZEa zkMQ9P?BV<=+d0^oQ2$q>idUA%IA)zUK)S-kZl3&jG68B9BVr}E;8FFM)eHiX48dG) zr9awJEv_Np{~BFw&WC@9jm6qfKp)The2D&zs{g)yWAn0P;3vnaIEpzT=^N7ym2fOF z2q5nvY`2c_EO{Kw&Aid={Mw;u<*4cTw#Uu?j$T2GT&3S}vi<W1iPf8X7O<@LuFePk z^XY`6FhYF4KAl@sk*ACTzPlWofMZhr^pNXc4l=L2Irr}@A7#((w7)zaxCyYq0o7$0 zz-&XDGA5U31gw(%!d&rBjLsOQCwSZOQwkL9HCqJZ6~;1B$qw@2Zfg$vC3?Q;Jq-6r z$tsDs(1As`iv%O`Qo7S^a-(&<>|lO4y~uG`oez^<oGu6mDFc;2*h)T<qQF<8TtF{< zi^+$-f$MBggZU*Bw^m?e*po6H?zlOG<Q{BUgq!zvKzsgZnE<zsX>wb2T85CMJ+J@} ztcQ_&GMygNl<VM1E*F`Frd0hW=YM+l=W6`dMN9?QSf7SOS<go9XSIQ;{}+;qf}nrJ zX5ZQ^=w5qLuVSVEn5niNeJt(v?z!=j?{}VCJtxVfHZNJHq?S}ZYWcpJdi`*g;hpuZ zJijEY>tsQfz!^vY8i+$82>g8C$d}U$wGrOD04FVrn2xpG7X=u{S>8dxWLZp@$gyn- zQc<1Q$0ZpakY=r#xhv~}Y@;2E=$!Gso^yBw;dWHu+j9@`&^9}1l3DxeOq7=A69I?m z38AM>+OHNQBPGPd+)`Sq&#sC4{u6d19%MrmqP)F#uXr9k38M%dJ=n$y27n091%9`} zS=LGMdLks`3P8BV^PJMpqqVCKm)7F>Kn~1%rfrL2)Uibw+=1G7K*edA5?pq^4Rora z)!>SCO^HEMc*EMTI2aK9ex&JE--|*6$*Uvz)*(=pRjZNX#MOAW$$G)U{tI@;+uLuh z7TszWen(E_<5hCK*>X@~E%$xK6s(Bo%k=m8Ju$NX#wvMs?-Vud+fT4`u*XgxRY0sO zU!zOgs}FWbgIEJAD<@l_3QAauH*hKNNDxq&*%HAe6iYb7eZQ$~piLb5uH4LE5ObNY zgzHHhHsdTN+0!K|_zZh}_f@iZJ8kAklYaJ`m%l?dxeRCN+1iJQ9uuhaPa7l(ersQS zbI}miKJCX9A0k5HH{Of69;~cb5G47CV1xAtDHFx|Rcr%D#e7Z~61AC)CuwTRN8}(c zFA0eJT@b$es%@?4E&&+-^~}mUq(B33gV`U7KZ<|SL6rU}uj?ZJ=6KQB4#wF68?{@s zWXD0+ogJ&0u8_<PAm1`GXMRQgUW|9z>OQp6;y;N~j^Rdg!uLTALbNL6&AE3pKIHcp ze@v+8XPCaWt<CfN6QqpCyio)LWSI{O2<48;1lbkX&jBw1J#v$^_Dz()Qh}qMoDuiK z%tyb~*WRj{J9P792vNR<YS=l5RaLFqL=a7t1xHqvo=6VIt$Kr^B%}V>RejOpP7u2- zb`XMPRxGQlK0-47BXa>wQ74_3j?s^v8!GrC<czlscIMw*Mc-&AMx^-+!|(&?XO9od zGVXhzq-`>UiYYMOhPhoQVmjQ3L#&vo%0fNw`m8}bxBlOo{}${9)kamrk0e_m+h<`} zguw*CRnoZOicVfD)Vs`4?hLTKUjXTw$&pGaDNdeMgNII@Jax%g%qYl^@drZ<5RezW zZk4GOl`n_m8Nq{C#`@oQl!9bmSZ#O+SFVO;sK?1Z{a3?kH4W1ien6(F3*K_{%pvAE zjMEj1()rnLjJiHR5X8nSKZsUXeLMWK4FQ0Z*^+#WGOg_J3LD8Vq-!$xZcATABx6UG zVDBYf0;@RO)t+Omx+p%MJaoAiZgzh2twX&H>4jdQLX)q1MS@&`KswPS0>n@pNi?Z5 z8sO3_rhop|ftHlEExrx~u-gII+zB}_v$=!fQe2h^ZWkhRAZ3u41{7}Q$ld2*2#w8; z1*Hec{sjoXnLi)(?EmbS`3Bglua{);zhKH8{#_7DzpW;&|1KV)UY;OCzptOZTA_!( zF&?p=Kcli1`Yr^C4<2->B=jZ*8dWRA#nbTl&4iR=h|hoK1lY9IVp?D?w;oX$vD|yY z^pX(v6S|u3z|uV}mv+N|)A*r%xRg7EBKWckt1>xUD>?Fn#8C16u@<c#2weXcqd&|M zN>mDiHc6iOkUuu)>|=aq*kx;-0FYuYib+V736;7$Z;wfITW~gcs5|nT)us^L`0gS! z#FvpUdn9qB)#B(ETt6<eMbzqK*6fvZZbOdM*I(j*LqIyZfbgIAH08Ux@j*7iZ=elk zC!G>n=+8~qzmTOLZnhc7n{p>Xs*6x`r^^08E%3#s`KO}I=u@BkKhWC}Gq>JKei?d3 z_LAG>-Hx*2mKZKHkk5?z;5GYmxU|;G?tA-@DEDL~U=>cVnO05v{<H6O6P(2i!g6a) zU%n-_?izFTvc~jGkWd>dD))YawYK&vB*|6325EnmJGQOAe!cju)aMit0dAn>u&`F* zu!z~-2|$!DA(llFOF3Ejk8dP*?8?MN*swpCUo<C<drPKnq!@Z;AVJ)NSLB7{wN~~a z^&-C<#V4@Bm*LMc{%#)kw&BqN_Ug0>tTyI9O?#;Vy(tQ1ui*|9;sih`Rdr)SVi-kI zj<tGg`@X|@S%0!+xs&PyEVC^0mVyA9Y%Je>FZ_g{gxLpI{oh!zi*k0HiC22^MExeC z%O4h$?jFPY$7;7q|C~cSzO8_*zl!p??peC3AfLvp&Obx)LY$B0X$nbusM!WO{a-h< z;su*a_Z#Tgi&?O&fM=4mpd1+z;K|!4(R0httrWjFn7x*6)zCpwy8JxWKjQhR2~m$# z<r^HM4$}GKL+#xuxeBK;b7bF0L}l$&7(_X2MHEdGE_k|Wj0+zn6$%UVY(GEp^um>H z!}u+Cw`w@*eDO&Nf*AMKG~jB-N3=@aC!{IvNwX_EN$Sh1ercz&UG1ocGfELz>|li- z!BYDoj}`=m(+AGP8jhwEDumKZVxMnFOtl($`L9xP8zRa5FY@AxwHlWlPlb(&4U>P| zcZ8~b&QY|hU8!n<us?W=fJO4JmXJOvP67dnheWhYIy}lW9J~XsYMHX~R{=}^<Mw0x zXQD6v$X~BMY{`G-br>m_0xd73!xYI6KSw91aS_-vmVbBa{avMTMu~6v3pFT?#Dt5I zdxmid-z7@SD!X5Nd#Be`Xc6>xUafIY_Azj-tO<T6>y&+^iqW&!@{=0s?L}9sqzYaB zsjO-3p1G5_ae<dnwJQe>dK~K#lNA*(TeWzxPUo-K_WhSl?3_H_@;$o9r&rFei-qi3 z_8|a^DmBn2+?u;wxA?l;g*b5aYnm`g`;C|K(r+iRl6K<2Pgl4xv3&8;tu&hKdnald zts;%q6i1Z5Uu3;G?2+PMNs$3AN%G$$daX?!ZM-%bcY-(JgyY=Ou@Qg%f~qt6N0Dr| z+UOzvZ~)~*`FK3A9`P!>mLEXl8jyWfdk}EVk=L93590>RfER+bFhRYlbLiJi_Ru#a z!o?b}&fUD;f<VKob_Y|=PM$)s;#^z@l)DMOZMI-#D*9xR!~1K(iY#z%4|m)1b<SpK z6usnGEOFx7bltH3qg}@{1roO501_u&BZ~nxWzGg3-E4<~qh5&ciE-~*2kGp;l2&yJ z0s#*-Xr>(M;XOW|*qIN8ZgLFJx#{K8M1MmJ%$2j^%sWVw9DF`9?;z?8AG*3^KOn|= zWwkBEttc0Khr^ZFi%%mjOF<p!XuE~Hziq^~gTkl`|E*mdFeiwK^2U@&l0vH1#SnHa zm8S>Cyzj`6v;$GzC?KC6Y&gW2cB?thTjTn|%5NDW^eRH=_?FpQ+dc;eMzM9v+@CpX zdHEt;d(R5Pr(AXJu-CH1<t!QfYiSI@2Iq3}f=5USV_CW6U@-l@g*d71jrFu4kvZ-u zl6F0lQ>z?@xy7w0(N9oWV2==Uyry%jyk<|#(R-+lvf`y%8*I2gz#z}V11O>6+^8@D z1P#Drryw{sBuc0;mI(H%%}acdjJ34*(+`TT9Y_u#?e=f|v=fRQ%-yu@YFRDXsYQVc zk>U%)vg5h50P;DGR}>QY3xP6#UAY70J|Su6{l-DQKBCh;G9}|9>6ynvhZvz@^D6(( zAqrkMiO)n=9q2E=Rnm_~!xK;1eoW#2LC-wJUaN119-mcEugX0B+}CJ#?bV#M8EaXy z>&Wl%zV0%c^U5bUrnBGbaJaQv;$C$KpQrwX$&*b(x(<R-8?Ov?XAdc?hjk1LwadBu zajHb{+Ic*)+U0mI`Z#XBHJ76Q0u6a~5q&1sz2XOIDf<e*^s|_BCM;}f>iF_5XCX<2 zvJV0>HKE6cB>I$3ok<VN+3Yv(q?vE@(-li4_i`1C@OeTt>AeTQ1@t_2Fu0T_C27R5 zi<WCn+sOC2Neh-8g!8Bt68%6hX`1V#-N%8arh&6Fm&Sad2+W^%Rk7G>?UHspA$-yJ z=nFxPv6(j(1mL6%Xs2fl2mr}bz>*XjtkT&nfg7*t0$|U<nPE$t{SH@U?TY);TF8If zjykrTGP;V(Td&Q%a;jxPIa)LVRXTayT-6a!I4d0PD8ItfRTQ<9Rb;MGg$9{-tXs+R zDy2br^qmRdkUQ8_D^rK`!r@xlnib&%JAYrLyr}|KiANjKYzFIyu?;}|P!?Va3?*nS zsbI}+L@KkQiQr7o@P)Z|-0S?oBev;lD0t9Y_=6CG&|s2Zeag*Vr}$=exMDO*tQM}~ za!#>Jxkm0JsIWdb;*RpsSg3-=nnDIqArtE7{XR!jmJp7(98=S*x*A<diixLv*JjTz z^hvQOuu26KL45C?vu5vb(#(l?)W_r$8}se8b_b_d%FW=eJX6E8Uv=vq2#GqB0KDC9 zsruA?gKN%;5jlDvTz_sz{;IA0w+e6l7$K<wn`QAnU=UaB?$P`ny?AT2t>kj<10`8B z=GzFmk7?EZp;>dFrUU^bIOG`Z6R~)4bQyrk*Fc@iSrh<(^t|Z;{w*V#I=CE=2TV3s zMAM^|OqI-c`_2DY4=laZ5rtzqVYeS5ABINMX%fR?Y|4~j&)1?H`4%TuTB7u5Q(m8P z<k!3L6<$0V4>gIMP4zRnmKUB+V)nSAEmb_$i=udxql!z?k{XG)TB}UxjSzU9I*m!$ zng=XHLPS&_IEQ;j^&nZ5li@m2mjD1VuoS(tL4CCX@n4_#vovtqrQ~SHjW8GgNe;0L z;db3YGY6=Nh+W5RZ64us@fenkWZ&QsP>@r6k7$Q)ytrYVfAdj1)ZBqa*?3w~Re2h- zVbMMsF<rUYr%H9$huXG6%Uys|fK-?%+qz&YtQZbLQ(ne~Wlaw6pq@9evtAjT9-+UW zcN_^?%rr_UxvJhfP4fJn4*k%1?1AE7s;ThmzvWcUc8Wm^-@fvDqN-z)?b<JRUC<I) zT!%JtYX!S5mpL#!Ea$7;Iula%biLfecFV%t8JNnnnpt;XH!+qz3D{Sw8V^8z$AkbN z6#L{A#TV8&Q%Sva+rF2xGY~|Uc1LAkg2RACv5>NNrX>gIGyc(|rFLp`+qL95ED-ay zP`K9NTIxS_x$vcernl$tb#ExJ8A@dY=kvdyg<^A!<HNR5>BMIVI?YwOBuVXm=c7;9 z6NRgEZe{Ktf#gRofGx#+wPyx(zy{+Wf;IBZ&MVeNf-2`V4+8h`l=mMV)81<09FxmO z=7Z!Hp10e39Yb$RZ%w+Kc>_Di-M7u%C05{|mQ%d0@bvWG7+n&%ChA-h#Y08-E|E1* z-`(l2dPX7LctG{A$o!YD1J4D-n(@=+I(}bN{R9Y$H2_$T?IR9U;CaOQ5IB0E_RAbi z@FDvx{B|r&U>fNiaGKXxpwQ}Tc2fQOJ>}rpp`SN7UVE9c=7UpxEW@wEc=6Z9@x*## z%O5HJtFqCzXPydu{%GZ)W2%J!L>e%Cw$1BbRjF&=I5felJ6XdW6?i?=(icx|05o1D z62HG4xJ)tKg_tklZIo~$lSj0BfYX>y-{28FUxpsXO-q_D8XSIAt2-det8%VBx4>33 z(tg3!YQ-U6(@bM4N<JsDYdT8>kv4jp@IZ323I6=kZTGC5`SqCWO;5E?A2PrID)|T) z=#`><*EsbpuXigMO906In%^~if(v{g6rA^vA3!=bj`X1q+C2$yH1y#aOMH0e*klwM zpJOjyF~Z~4@w=W8G5y))De39DmRBn@=&K;TRmMB6YRqgX>GYtg`**M1XQ%Gr?O23U zm+yu_(m+D5!Yk&&p%ewWM`X7Fwzo^}A=^)Am}5+{E1I@qf2>=fT`A!E@hdZKexLLJ ze)6@enhTHbO4Cz0SKa7N!N0Rlyb01dOGQ7Azh1X_N!zuL!rw`{J#<+!%(3C6L#IU8 zK;3@97D%4p<*Sbp1#T?A_PaOgJ@w=FCa=kO{>a4hyBwV0@4HLWwvK9wmr%)tpI^NO zoh<6!ZDrf(&C^$AGvnXv<`~}HRNnHT(cIyQRSD0sPR0dOp=P(?6Nx&ETLS|plEn7k z)aBT|Ncyf()CwL?zQoN2hTH8k?p|F_7SmJ%I9A6T*KW`7q0%&YA4N8y&*G1NV#UBt zaP4qJ4XH<e*8RFukGlW&=Fo+I0V9ki<=`Eq6hoIz{~qPce5|(ll%^v={KM6K!_d#F zN#R1-N`wXRW2q8s4K4tLU{?hf06b5xi4<wBQ=<*j({|bBg^p3Z_9oS<PTBP*ehZY0 zW!|}a>US5-tId5Xq4JLbp0p4-8=rdn+1uHqcn?+HU+;yf0~1YW>ddnS67LuhZXF2w z;9%N!DZNdphP$3zK$}125>dMS+8j7F>Y@^zzf8u?|J_k`k-$@j|CUsEPWV@V3?pN^ ziRXU%%PCayOjrq>yV^p_9LwNN@%}ZDS?<dlTcT_32yH3kB~AZU%Q{RNIHBpO4Knq3 z{PCBD1b~8?HUt8%p11ePc>Pg_n(R%cZG2WzI<q0LcBQto#ALQp?k`Wwz6~uprk?N1 zL$J~P)3Aj9;xESRc|DvC>Q}tONVYr{ZGQIwvDk2a_CrqCMn=Rpjqb9rQ~E${I|xDG zaQD2@yTm$W23EDbCZ9tI5xAY0;PT^#gQ+OO`5%{k${oR-fk?+`zMmz{Z<njikVrvu zSpyfob4B^-d>kT|Uwl2L6t*<>-^uyztS})V8w?436?XaVCCI;9zaL(@J^>PCb6z^f z?fqPq5Cr5+sOsI3x*CrhpsUn`ck86E(0{VW#=bQ_JrS9G@$B#A%z-J|qYKkMk5Y|D zJ-7Gq^rzdUrja^kkhza5w99?xz;8Y!{{0#iwy~#7@q$26LIg4br;XlcOW_DYHQE3W zL}Uo6cy%UYRzQH_>a*)VKFin^$k~_br3joHE%><&%D0=b8^EJWh#~kHB&8BvN7_Vk zZVagV0Dg_bHYeTc9JR!AHi}gS6<tA+D)F?Sf^s2--zEr?HE_$rrw0fq4MGVEIoHy? z`-n)UxB+1x;P48R!7p#X`A-)FfMGl=fP$w`GLRC+dKAisS@0TeJ^P&4na~Nq%J$rh z+@?3(TSc?L&{K)1jHL<;ZlvCJs0HqgOB;EdnWnpVSx3!E01*{HnYNDE7lhaBb&bg- z6poaDC#DBLd4VU1#ro3@e%Z4JqaaNG*q!A0^nu-d;lEcr09-5>`h^#*7l0#BO)h<2 z(osIB(2>%KY%s5BTg^GE7hGjK9lx85*X4T<hRO+$4_5S>u}tL!)jkb8e-^kv{$-du zW1vu1UA0k>*1d7BuvEfcjoFkvji2sxWOR$mTQzqx=ESvXg!%*-nuUtfYWT<E4I5?* za1laxm=7I*gYa$KvY-omoT8{;ij~<q6Q*ZwUp&Ck6mFlpgm}^#y31RKwMl2<`Bj>7 zrp*5m!<Db^%G)#5P<I5CIf~#(o2yAzHWYy%T9_N7(0y|D-MuTy#=rw6sgvHp%}tR~ z=v#JXp5SOUejd2q0R37RBv7N|=s<AVhbHiDkM;?Fm=YeM7>=839JE^q!yH1<VyIlU zoom55k0yRj+A~MB1}ZhTSTC=u*BE*Jzc|0_(uU5aaQj&y7kVsB*`v)tLBGbsbx?Vj z;fG}mGf4mk0vI%K1H3K~{0;>P8JpgK44z(10}x%+zw@QOW+dZ2w7kqUt5=pO1p>IZ zj#_Kfs3kIrMr*>-bcOtGY@3Gnmq$KI>7U@cx`<an=M0}@Uh>7y(j#g}_g6K8=ARZm zV!rp7*~n<fY*ag@|K|4h#FC5)O2z_m={ng0c)yWM()=YpWflMe2PjhjfsVCYfbZVt z>d-}>uWujyh2ui>LBP8IK3VRA>RN(=)mc>~=^TSF;m3cwPnB`kp_$_vE4-BPTZw)f zXJ*V&@pW1qqfP6ozl5%D^4x0p;BheuTXW%ICdn(C=Mnum{a+yo<Xcy{u>uAHy0`kF zK|DYff3oz1(nnC`mk-^%Db99aVg1)Lp;roaOQ>hsXA06kj3}44zC+4!n;c;*MdaL8 zaZ~7f+?h~Rf1Cd8dHbPn@-1$jKI$E}URXk-fP7E(hYk~Z7)LW@#PKs(S0PhpGx@-5 z|7BZ{vIYX3jts6S2Pg2*_kz!>gp{5HaP*50aq2fC4=UPSlCz#o=g4T0uGFDN)}T6q z+2Z1wQ;ku<y_R!=`wW@7$&&@E3tDP=Q7-%PUv6e!LYa6Ki6nU>mVzI#DON8o&&P97 z`jF}>h(k!Yf^MIIFee4f&LcqC1{m>MK9cUs(%eG2!eF+(HtlG4Na2Gf(rVaX<8XHR z_uHp=F`?=X*W^{gjT})0r^@<CF7W~uPqt!Joyj3H%AN&lP9IgBOc+?DbQ`f_#O%<K zWA+cc3cBd>0rnk^P^B;31<*WvT6v!KOK;3->qK-SQTof520L@}Lk5z~mdT+={pV&+ z60ougSCgI|y4Id2UnF!&p=f3J73Gs&j@7$x`5F>YH4wRcyZC`y%5V$09se2itN~Ci zXmXv1AUqJ?2RR4TzO-4r6l6UDq0Nf~xDcI&^wxE+-F12^_BjY<<v=2Uoey9glDDpq z_*d>c{!<=#&dzCqguh%qF6Jul;=OV&^ufJZfKWwhCYiZ^X>=)3J)zS>&--LEmpvXY zf9Db^ResjQ->WT3Oty%$88*XPGXmY+cw%>7T;hK{o%L6g-~09NDHxC#x?#8(VCWP{ z9Y$j4PJ>ojL<9u%Ju@`Y9g4(&l+q1KNlPjc1_BBKDj-OyeCM;CwVwar{It)xuCw=R zkNvTrT+NJQjxZO9aMh)wjCcjKe5*+4YN}>iaM2K%8OW$GPO!5OxL9nJZt)rS@M%@= zB^h#aJdvf6%gYFwg|B{!U#mA5so+xz)vVUTl;*kE6IK@;ATF0>fK&kkBb&K2Tw0L6 z5@W~Q;Yhn7;`~~N!R>sk;ao#D=<^{#QuxfW^sP4B8y8&`+;mjlJL->#>n3<E1WqMj z*<oGq9%{=+8g+A9EZQq#@V@OsC2s{}X{W~UWIE;kwut*`(y&mmHo0MV;;z|Nra^Vd zJG#%x5tKwHlZW#!vRXVbjU1ndW<Hm(H%3zpUCOBTA`K-TcHjDv;ol(ZwFL84OpCXt zb!Ff*Ls&@U)Y$kU03?l8yu%27i@o%lS`DM;&c;pi_6_-=GWDy_^2Y%3_=t~BFoR-Y zrDiuxaHyn6_&rnB`H-aB@G|#JXd7PUxo2fW5&PBSY}SjbwCo*5JXSemiF&lI&b9^4 zcl?!?tzj5s8JU1?wFW8_G8%cD&(sf&GSa>&=p@X}Eo_E@Z6-O61(E8B@_DIXd$PGW z-dgqDSY7nB=a#y7vQo)yaHF>_Q7J+NNKJAX4!eHC3QGet>AaROZPwXgNmm1wH5|fu zGjGl>!R5Y)t!>$}9!I3X^as^qU&I+aoA0)Y&$>Q%{)dHxWww0sfQ%k~BU@;rCoVu; zqA-Sex8=%Lo7%82AaqD$5kd@Z>wmuyylZ=oW>Au?CH$Oe{Khy(so!3Qu3Wm`m89~; z@nsvamnKaCSK2pvT-T>B+l)ANwamv~J%I_$3-nT!#%QDN^`l1o4fIUB<AW0sGTH~N zIV(&-IL!OP^O4sZIC(93&aT}3Yn!m)>2FuIe@~UWa-`P7`ev5rt5)uM@EL79i~b#j z&!`bD*C+RTmU#9*PreG$mFK?!xbt`N#F|AY6U0)kzz5iS-R3J@A$N-M)<7=>-LF*V z9BzR3x4D9Sal2SpK<^?)?@CW&pie%7BgSOy9?A1!D9>m1dB`XBPa~3?LwtXiF&6%i z$5MiI(d#n+U#>ylxH;D4Lat{uVaNg>tn^p_6frvu`&G<*A0XahBk3>MnWTU<PrvEj z>f(qLWO=DXyL`c8bb|3oCPo}F{Uh+5*%t<nTr0TEG*>(|@G}o97bWSB3cxzA?#Ay= z7_g6oZRq~IJCaDf|8p(=ZZ2F(Kc5Gqy(aj>-nGw=x(T<MtpBw8Z0PKxB+r?r4rWbe zf<E~Pz4_075_>v6HdV|b9b$)=KKSTm5KQi)kJ-dj%r-s$GwS|E-H3N;B5#pdbl&A} zo20uVl;0BVT<GUr=XrQy2zq0V1C4MyPuEjRUt~)kp;xT@rSZrB%5^Uc=hTxO#G+wI z;#W`t+yVz{w$vH62PYZ^V|WRvnCoWX$7FDn5j+w8vf^!mGb$##dk4YA)DikeRX-zS zo(0IO{JwRj0|Ht!#6)xJ7|9vTYcPfaQvAT|R62>i&4^f-k1nQ5=5KCE=S5$Z4<c|i zH+cONc;=Y`uK0&-x_sA^`aNp?tz}~uWqzFh)oOmK@Lz3MsJT^G-Jvx3IBMrEB?j{& zdVv?Etyl~0F@cXpJDAe`;29go-8%&p`k%{#Vri^qeQ*eMaFFJe2DqNN{anT%tyaQ! znEArxMdiO7K6uVy_f(2Z+|aR*F28-!2Y%Bbf6FG<vtz-Q*fGwkoHtmItiM#D<M)Va z8??a4Gw@`vpvB42QN2*4*c=$i_>x7$I!(B7TKL{hYEzn2c_fmUjB&0%*7LqT2xZo; ze@Gw~odn4AA*o%1ph|5Y&~qve{=xPMDv*<szig?vMQPU5o13x1_AsO0zt6dVXDZXL zs)`ACAF3fpdPP_HI*Z7EvbFh&^At}B;&Ymu+629{-k>$0me4e1ArOv{<b960tuOuB z^H;~Xv#p}&b;aDa=UW73liz7Vl}rcHt3r1h!1ul45+y<#6OH?Ew%`=Db>lcc<=Az? ztvua|Y>s@wEEPWn^7|U2cY^s%!O;z;wMkIAr(U}6*LxV?YFRZnMmzs`U^`G^NBI3d zNzOu=&%OvUSi1Ko7Q~nRtEq3LSW2AGD#(HO!Wxi3|CLuM=HwfW^<jI@UiL><x(kye zG!m?O-VwI@OB%m~YrKNp!k{A)HfNOOT!rSJ{hfEA<8_9bfbuEn$g_+<2@kw*+9YU2 z&KgWxHts{ZJr(hacglXK_-b!PmJKEfg-HYI3glwJEy44$V3EAC)<dLgt%k)4d_fMg z2@#s>NlYHFsWJQ6<R-uLMek1xC|;t{4Lykon4U=UE^!sOtSEzFJ5^bc8Lxoey@`=! z`lEga+*Vj+U-q356B;t2<KNegWfvtB3Ao7APq1AdR}cxOr!vnaD{o`e-((Gp)+Sa- zo!`g&F$d9!;0arjd<O0@N_1GvPI-7~WmG3F)5HkR1lQ|x_6yc5)tRlod`&_9O{(N@ z)o%H|>95o$aZ{R;Q3NJQO>QI97ddj(L_K&;|4vZ<xY)%rc4c}kACo0^E2$MB$7ip7 zb!A<ZMBz3f>ue^4gS7+?UX65X<kpj!-MZuiT?MkyL%1F@2Z{S3yhR_zPnbn!g8%Sa zZvsPAx0Nna!K}k7=2)woW^iteo1r{l5GL;;zW2jQnjj@f{AJcYlvOul_;6~vO|iYp zaz^Y{`|}h`wmk2yYe#++s$k9HS_3Fe$c?ZTI}?)?=~K_kauNlF=G^&=dvcfzjeeP{ zoVOeuT$75LHRQ|SzcN&Dm1AbOxz5!F(_a<rYojL4;4F{F-M9HO4`aDJdHwr&r-R+9 z0VcrsnbVayuq6S`TNFS5HoL?KH7T6T!74Bt)wA&IoBz$-ysskpqfEp@-_>iRJ&q#q z?f}Dk(6Q2Nz+|m`csHf)4hYAgDq=ORWfL4Kg!+1=ReGG^EOcAeCy&Hbh$_mV?lw!o zQnUxiOAXG#P-y+6ksK&^9_IbY?ay$n{n$_YnwCam<lB~PpZF%FmCy9$?l9?RaA4X8 zMCodr6Da+;(NYS@NY-suZYuN_Ve-EAs!30L#h~c-Ebi9z5e5f%PBl6b@pUi2Ed)Gq zageW*O@{ko?6N0zO(;J-U$1R=D%`Z`<CN=L2tI^-0HF|;5EEbp?HVrMxPl$tG~^Ot z%IpvJ0PS<CXK=wU4?%io=tULhQKa?Rw<Zkr=jc^4PBKL5^L7XyqfZ1zV7(>yMP&O4 zN>3EZwS^CoOGI5LH7rRDua2dc00DX;&X6tQWveLIOC2)DST~CLHV~;Hn7Io|+24Ir zzALV9UD976H2(w#tUKUAT7pEmkImpoHU`&7ET&Tw1o)hph5opl=bQJq0`grn;bI{q z8sm#Hp*EjvBU9Sq(vl?-6x)%8M%OYiBdZutmP_fEv*Qu&wY8IhsYszn?A=@+hYEfI z4w!Qjoy_r1^6%QtF@0@g8@<NNOmK56(`4Diyt-lcpZ%cqe8)_Br>Si;8~~Py9~ih2 zkDHaoNerkWNR6p&vbD{ba+7|-yIZWuNm=BX4r{2v3iPS0Xm?83e_4Vic;g9ckGJO_ zP&9;~?Zdo~B?@KTUvc}1hpDSc?|#wH+f%3%yTcOoU_B?@>sxy3o6oFRQ*m;Fe&6Xu zTbLPW_+wX40UM)X#OHhT&`B-Pg&D-Is>$^9ssDBwR%xG6z0VVnKFO0inK$~t;j#97 zXl%Pbqs`)?f~_=To+v(S;b4(af~!;#o!=l@7>kgJ%4(6X>v$3mkSKV2A4u>GI4s&b z^!{qCw9z`s=`Zjh*C{ihz3{bB&Rn6C{H;lt46F^MCcjk|0#>NJonZKm;w={j*$8N{ zvg&{}Xu8IQ%Cot&Kn&L+x9KI}8Yg!TI-U)ZVp3(Mj%d_Dv;raOjkG-bGRFz2)OE2+ z_f;qs2}9lpCoEeX<a`b^%L%b-k7-{J++pJ~y?2u%`Bc|!NRjf%B2Ol97N4gztX$TZ z0k;CgYZq(7=|nm@j54g8=EFW4uY@Xz)O=G>i4ME;a=%cauaEO!>^BqueKL!yK>Nj4 za0jy;Vf-0ygoaynwlJd0XmCx=QATd@pM1t4wnii5o>SRgoO;80$2Hh|!)Y7lheFA| zP5#q`Mox&P?o!)=FcRHw>-h>AbUS?W=+39G8PB(Ffofp>^XAV-V9Bmi$-DoQo)x@g zUXtw#I=iEMcUK_-;t&mWhqV+7;g{OnI@(I_fMQJG0F5loX@r}GXw4N<7r$qat34Tg z&lJGE64U1h8d0k~#Rv-wYmvU(My7!&J^e}k>S@*)2iQXj3aP&~+fM?2l#}c!MY5M> zO9)4u*|uHg1&m1<V4tF#bKt=XuC8J^X!L&v^+X$Yq4(tZ4g0s_aI!G?m9KxbfI&04 zgTF)e;&S4+8=VWA+tc^PJ%a;g_(!|<oI6r-22W4Lh{j{5o4Jd(F3SwtnYdj)8CKB5 zTrIvA9B$A@1D@O&C~IpLxKdFzZ+qBfdm2&CuhHQre$5Cf>UUMkw2$sFW_svP7->oU zOv<qP$w+5n#A^k9p`&uC`C&TPo5g(ou<!GUxwiG0D-&kWba4j3_MafQQ6Ns9wLQ8f z(ABCXW3o_d$VB3iy7o@OHS8+MR#Rpi`ldi+n3Ug@p{-@xz^^1007azvwvKnU@^?Yl zhgcqC_7=ehr`j+gvW`?0BJf_+wVGhHB-bfqWKWR-7d)&JUSpi4<-^4Lrg$`4pXIi` zn*22!G<RWXYoe<$aUG&k+|~DZS*=vGMUwX<);B_;fwOrfxOwoE-WwM8F|LS^2S<bY zePeQbjR)P)24G33uGru1#<d&n*zV>2`$9XUtTPpfxcjJ^%DoEx&`%b|>)pj?Ts9bb zi)gLubJ~Tgl35QS&QPMuvX$Vsl-)OPh{baF(6HFqk}+rbf0uspg{A!6)Uf@?G3qS& z@4u~r?5*y_Lwxk7EIIbSo3gH}MLH1Uh3l8cW#z6pWEB2@p!tEGHJ?|rf)Cr{A1vB5 zP^7Mpbr<fO<!t`McR;OI6~Kv0AAj*jeCMhEA^y_j!=FW-k3TOxqMXBYs9)N)NnZ>p zeA0il|A9o=eHJ^=un%$p-I%@S^b$184-#tLEf~ePKf#!XuFBx$#y_sgErl82%O+2i z7LdaR54uJv$Tpq;2A<ywR|_CL{K3#Z;RD|XpWgaBamdy=l}S#~F9~AN`*cP!(0{Ts zYa6Bw!^{kwiwq-uko|LPRrtXh{gX{>)%b8lk9_K2FWMo529W%!E=9eOP(E(o9h~#! zC>RGog)o2vk#wwR9pW-bgd#K(_zfB;BN<Q)XdS9j2nd7zf*i#*l)o-ey|ej#r19zG z6P(fD7-k1YPNu^YM#NFGX64%Y>ROdMBzys<k>rPpK<9TA&ZMdVz@Sh&-(|My+E~l8 zrB;<|&|Egw;=wov7Dp50!Aj&y;%EH(rNfd}U83hdBI?>UNJB_%`of4QvPff~gwMzE z_Qv(*1Hig7cNguN!dz?m=zZ#EoxW-d%SX@d`i#~l%NhO~x9vF_Z2;CvzL<2i?XJE` zVfTxuFY!xbKHRhE&Tx5KrOu&lNBFxAiKNB-(EF!ExrLxcKzlAc>N-8#SzR9xuggyd zfCw%RY0H&68Sm8C(JnB~`PtyJw1KM@NX_3LaG&DEovhcNxtIoQHDCA~!ynuxeBQ+O z01dRsAOSL)=tiEUq{`DGyR>-m(pdGkcT1vS)B3B)n!gF}FT{m%T)*a&rIP;N({|kg zuk)e@PI?dTBl1#k5>tcG(CJd)tgFG_JnXq~_I3n;+wipba$(g1o!I(sHxdF`;!z<g z5*`@6klPe-fXVdO!$bwtNxAeNr}sv&c&~D*s2q}gCinC#&9fY5N>2gu1*b<I=TAJ| zs5GVb<)|uyWzm#T!uP(3m#8z2ZdTU~s<Q#RYf*gno+bqO7}7qIlrlUT-ruSlu$0)w znczI9LL<mGr!4+F4!vn^uF^8!bTdrZtMS#1rSGlFf{w3wd69Xu&Do3b&j@b|7k_kg z@itWxM93N|9PRvkzHNVgF9~a8XJS_UnX~6Vbt2uW*89$d!yUT+fooR)Eh4!LcdA#j zJ2)sIX^w)@0rmZ#k{C)U;tDl;x=dAzPe)W(efMf1n!u34cb3uJ3C)nXLZhpi>=g#6 zQ}5X^0&~s&jM1&DaM^97PDZtso!`L?^@hk17Q-_}8F>SONVoK?d(PjqD4XzzgGFB- z8u@p7U)K(B9vL5g8~hzETm2Am$e6D^dMtCa92HsJf}^17*&2m7{H-`?zJEVj%RI{r zeVDbS9LPB|%$C2F7b|;WknZ$+`+cd1av)Ti!FuxIX$@`IX45;So_d<R%Z4nuOUY9- zIy(4?&o8)cb?JX421a=!G83r;xJ}v~h5e}DQ(T)+?fqSK7<y9SY8MfBkQTUf7`JBB zG^oJcXDak|X{fe4xqeb-Ldvx(6*v}e71*G02Xx=;&85hU{3Ig(#9rO#O}>sRp-Xb) zT!QZqMR6csGroxCLMV&wm;SIOC{BLA2!6&nj|C8?Hr+A5iQpSyKJHOg+M9&SQSj;q zP=z6>Wn2^^K@ONKogQXFYXNWoBDz81Hm^@2tuczJD>^eiZPSwA#qbxT!kDDxm42Q7 zp(^nQd4}wRg4800QTf<)Sw#)Wj_IVMVPk3ll!=5H6G5lV3{MSatc#*Gq1<i|=^c_F zHCZojU2ytwcvvsY{gxjbkcVs2VCw)FBLRmN27yn+H3g)qVIHBRp;HHY38jXEDKAH= zsIG9#$K`7~U*KO++skh2dYtSlfx4IL#y5(K7F`ZNV3*MdHma+K*O~~Z&WdBV39v_j z2rV6u>y5lV4I*pIKg?H2JWqT068F)Vw~iZU`+SrL8bYU5Q_Sc`jO5M6O^RYa(+3d6 zHQzbEwp&@@dfP(-jI)d!?CcdFO)3o7qnS_ER)tQ{&Z;EWZm8fuG5zZby?Zm}xuN?d zTMlLy_0%mBql1F?u^W2r>?lC^7>;lU06<y*paafB8K402jQZWkPpCr^ErId)1PGDb z8;cS#d_<@(dG(N6$@~3qed*Bu%0T{~u41hW-9_jDnLEJz6t8eb@eqsT|JT(>dI7^s zS9lau>pk&!T1@+qZmHp8!{(~D)%K0N`~%1y^ew=(XS=kyW}(sZf4Z7oM9YM@^$4;o z?6uSx`fKyUSZhrblfWkL{&H_IoQ}Q7)S6-1MduOgiD98}d&8G%RfO3aW4m=EbE4cs zL6eRquY^a!-lj6?N}i-AW@CjWoxx7@0V2Vks;C|Rp1Y89?6UPR|E1v!DW{39_FwB$ zrPYrVQp2LS-ia`D6+J%H*`$#(KYIx{)7&F1mQ_1V7IqU4fsb5RD&m$1LkbF_+MJxp ze|H!$JrD#kK<GYVe@I9hxwh{7;JYsNbJVCPIu**rsnerFkD2-$D;R@ZiQ~Mevl0)M zBVBc{Efucu?1R|VL{3paL<cofLDki{Y_}8~jl^224yV^z8bPdbE!|k<+ggUXp2U|- zYg?}`S@t(7zhqN&^-GR(jKtSm_iV4Pd7kB!U-Nyl*9;2+21h=!2F`h{KMwt>MuF0A zep`P+q><bxiu#|f#)(yJlq9M+Vi=(x<WnhWriN3DimFxL${z)X-C$59jZPs=88MQT zY4@r&^O$gNHmm9e&m^~M9C@)Q$c2A)CDC1iJyO6+nseKAeVj(y^@Cy$w;M)P#<m;# zP7Jr2#9b<Y=Uo4|r=S13tFhhsp1kGPwwCPkyltrD%JYu(m@S#+9q*{mxL(QBPf3~+ z=ZG(MtGriV0<_X~Jv8S-F)#j#)$H^!T-e^}N9jxN4zSz#?!Mx_N!3;UkZmdwC02TG z7?b0>H-ddyvo|W;y1h3hKP3HYT=|{vuh**UHNPe_54V3!;%H^|r*ydd_NNKr&n%Py z`DgpHJO;3XH`dI5nE|^YD@KDW8X1g019#Kix9&N9jq(82?f0T@>-XPF0Yfr}?}Og? z9exO1e|GpW;_&SI;U^-kELB&z{Et4zi9Zi@B&IgEy(R*vd)jw2U+k@A*J>JmRXn$% z2HZvN)2!QXTA~zNL<0%JP!>FLgLy=|BO_chh+(mXr2z?qakHzlN_n~rZWDqPr)1`p zLxyp_0E(8!w`)Q}0RBAyu}g3*ZIK_U(I@-_P?qhuVrFIi<N4}$6RK~3DP!HGPam~{ zX1J_}j=q@@k`~91*2X%&GLl8$&=(&`a{sZBW3&fcQvX?0JXjM!{zGv;_Es+Cp@-x4 z==WayM&nUq8T<fT82|Atl_|kapqH@c^K_pg!Ee(rNCd^9^mLfl`Qo-KhVWl-tM`?* zKQd4QIJ64~sVV~Ogi~aR%Ao*@n<ZbIB$eSTHS(O%jNgQv4u6h>u`rYxU-4>D(4pe- zy>4vVE6X3fQtsGI3P>#FUndNyFYYFXj+Y7^4i8;C*-arbP|&mn!+74k)Hq`b$Tc#o zr@oh#nn=Nj8;lq_?xp9BQ^YQejF^V)WfU=#Vf770E%Wy>D~!t|?M6mzJNB~b63e7- z8jLwEQgwB_OqSVBqi#FU*x6u6u5%#Mk73s6<5Y|sq=(6m0nQIySWzf$(k8k0^DQ0G zU}|HUFMIUo(j3#MK2<C8qpb3dpb4tO_e8@P;L?lkH?xM*8181mfYr>K*+o2OX7_FB z@&RglPW78f60fq?F}z0=*}zB=WH(p_h7{>m7;j&sVviU+@oZrhf}~YG1cInCw_qU} zZH->k^fE|tPx7zXFOyHIG?pOru})YU<aT<c0~S_~L5Zgq8LP}`J;uHJwur<(yj^0k z)^Sm{E2y3-^J4YV!i$tj>#S79T0=Dww?g%n#Io)SdfGasZ`C(EOa)%(U(_nP1$vrn z1=cyTs1DdXZ(1O8LRnsr+OnQY4r~P?(~u-AnFyo%aD^_=t`{#JL>p1fzhh?$D9_cG ze3L-$_c*i~t~KO7eocp1QKcJ9ZlIaQdm8*gkb3$A{*y;&?>i4XJ!92DUgsF*eN*Q+ z#$Adw#uE5msB5eCkQl81fc2~S+<5{m{?`bz?EJ_aStq&i4%ScmPbz&RH-u)bz=%(> zQ}A>{DKHA49>^O<s?!ecHX2l)ON%BELn3@UFZ1nH7YfliLqmgJu^+hF;J8Cu>Sl|# z2cIHDddPZ<(4K<v;RFX{6bD;Nq9DB9g)*mI&w3BWA9@Z5VW6CY-S!Xv-5;&SS;~=N zUvs_OF_p1jm=VfD#*G@%ex=uW37~6*_5eVA+ZL^w%|!f;q^CZo6?11{oQ$pmf@8hU zvk(pbpK;yxQIJ<uCJxUq(aw6itS(wKjy1gp286ntF&48u@mMz>kaAKRhE4zEeRM8X zVrZq;30==UJhhk`?3Pel!H|0njBVd9F28$J#V_Xf4xMv;%!&rbmtNxmtO+x?a~B#L z2(w%rckQ^R7MXBbgsgm^8YJ<ksb-{L{V!hU4T2@o)J95!qtzoKd>)3(8CqBv<p%DS zH{E8Oq4{_chAy#%QCTsMkX!>o{xwm!;1DkVNap(mU#`L3#C<%RPKG+(?q427dn;aw zMF1N^d@|Ch4pV$`&wT`3Q(kWb@`WtGA&R#$u3je>O(#|i%L9b&fbM;!ia)<MYtFj2 zO)nK_eSKUiHST+Z9Q0oCq0C{H#K(1V1!>^>*~rl=bFI>-JAYOwINfmrtBYwF@7wY& zs*Ng4Xp;ke#q$ddk9&x8I;1>WIr;E&!s@|LipbC>{h{_kvkAcm+880PpkrS#d$kIY zYm@p+taFVUK}+n@4Hjo1GlyOK8}^Tr>26I77`zB}V&hjc`Z_%Mn)}y_oWF`kO0A0- zf;TXq{;F{|1PlC~*jYe6*g3V?{hTpNjKw}kPCN_unvuQx*HQq;NU_*pso0s-`LhxF z<IlSOt+^MMZtjF9Prv~4d&yI)<(4U0K{uSjhX$K}z`Vi}WtoFY%yyo8ybjuljbd(N zxy)5{6rJ{CXr4S3hHt!3?I)4>w~u9o-pS^{S!#=1+QUmXe}9l8Joyo$@l8l#j#J_6 z7?S#rfzkc1e|QXznD+2$uD_9$*n>{}|6*Jj7Om-h1I_`<jI`pyukSE57M(MTp>Dvi zU*#F}bVb<OMBfbw9vsSqq+1|*E!g|0cvj8Jdv@hE_gT{-G}8ej@xOay1~(;<{vx7L zgZ<hC5h3h_&K*=Ej-kKqoIeqs6u=-Yj$yfJUamyyH>bY>046H;hl7Ka8X)zSk;)C{ z8h70D>qI2ESv0Uzq9v#OFpJ`_SPTy3NDyXIC0)w(RLTg6S7dmLW4zL+!_Io2X8OPK z%MAYIjyKQ8u;OE*1JC(*#)ekJvV$bnGX-bqNC+o4EtI4l5{Ib`xCNkNMMdHP=eYR5 zc>R)iZK$KdN_-I^oHWDHzk}f$#z5x<D=Wm`q1X%u;-oLf^>GLndSc5{8QmfoXOxx7 z+uT@6Al;r|m?D$$ZRPq6eqJ=HTlHZ`AMWXD;wDQ{Tpz<lt3+i*h*qw+>=)__J8}li zxZ<3oxSF)lBFOCwInOHY*M>0CVVpqe9%32WLY4Lo`A4u=!)V3|7_fkggiRBr`;$A~ zro7%wDdyHaRV9cyLz#<{5-n5G+|!cqjQybmb_13-p5o1MW>6L;Se}8fgE&K`c6Lw< zqTc;8Rva_0jFmtsEL>?kvw#9PC>3F%Dj{qimv~7+fXYVZo({j9mtnvoa&v<Uo4DV7 z7;L1*D|C!9<G~{14bqVrR&)aRk*sT#g2ED6E?&HBsp%eh*{XC5Jw@4*z1e5$*{^rc z{SeOyzLyi4mlM{W6S0u<;5diKlS@|1jdIA1xtAN4mz&U@o4Amhe4Lw_r=-l8=ci2* zhs(>&%gb-id$f>Oc$`<nlg}H8Fh?Uw@;J)q5Kr6lYZmgKALrNc6f~%56x7i*I<PnA z(Y3Z0bS)ITI4<bnc@*W~*_X%aj;84lqZx2`B&JPmQt=tjW1CV#jqyAdR(L!&!uB@r zvEVLZY2>lk?&IY%I##DC*Hs7BulEYE7EZ9+S`88rqQZsD!iXQ=@*{#-2l5cxbijcG zs{A;=1Ic>Y{$z831x61X+|{zfJ*i(Hi4{MAY8U-cD@I7N{>k5-x_`MpVTY3!W6C zt3<U>B^+VJfO*VC66}RT47P(!a<Ra4s`#QpNxcL@Q4%F%Sfbuhs<~Kt@uU>TOTnvC zbQ~#qVH83>#jt~7yht&nSJvL4SW*Fg2^3E>$|j6rmr!PsUuJbu=FD5}nxOcw$M2#c zQWJx6oI+lv*G3d0uIwO%d865St*)L&5tfVZ(IWzu5kd4ovfI<RGOzpc>hNj0oO^{4 z2tfCYdU=SUk^-D<5rF0t2RhY<xfoHoOao1$XXY$eorNwRl*5YMqUvm;<l&h}ptIlZ znlOtSkrrMLKp~Kk^Qa8od?GrI+J1?xxCI0tn_+-sK;9J_mLQb+{UX}fx7S{JFt*d@ zKSUtgVtk{~ZV^SaPZL-Q1M+H=Pz~o%<k9@7<szzI%ih{I=9LT0?lWaEo2`Rqi@J{f zCwWe<)E(=f-{_D@VK$#{Skc;|W+K(dXszfv4RX=-p^kjLAUL&=fM~;#p;rFLK@DP9 z&s|W@+gZ=QR4;g1kLGItH5xGCEElRM;#V3ZI~$~z8e~r!<oOy6GYSniA1ii*H>wsi zs&_VOE;U{}ZN%|4;We6c#u{}4;Kqx!23MMlmzqpZo6Px|Ej600uQc0+H`^C9J9ai- zU2495+KhH{HR)i2L72_dnQuI#cxj-%r&9c+P+~1Dy6VivCoRU3t<D8`--)fd9ZWx# zTiwr<AE9sI4cid)%m$9k_d44Wm)ep~+fw=3(>2;Nue4`}x91kL=XbV0T52ymZJ&mu g6lrvn24!eSKGCmgGE0!xA5GQqZfm7Zvw+6`0kqJTNB{r; literal 0 HcmV?d00001 diff --git a/images/demo_TPbatchLQR01.gif b/images/demo_TPbatchLQR01.gif new file mode 100644 index 0000000000000000000000000000000000000000..40b4af0f12080c8aafb5f2d2cebdc5ce65bad3e9 GIT binary patch literal 584638 zcmW)nbyO72*T%P(?#`tfmTuf-DJd5ON$C<PDVJV$SwI9_8kKGp0Vxqt=@JkS5EOAi zN(m_ezoPs4d!I9N=Kg!<oVn-D^O-TdY@(&@$p*oL&HzXN6#xd;gF~TE=sA?$1_m2} zLt%9EER2kdObkrSjLd9uXbycJ9&R2!9s$085)|a;<rm=lHv|Rvg#?fmf}(Q5GFrlh zHxVk<A}W?5s#YSJb|RP{Q4vW|Ot84wElF`{`DjHYU976Svg*}DE&P&>c8U&hMK1({ zGB84AVbF$uOw#wvOs|-mnP0(<Ub*|u{&tqbgLKDyCnpCdmmA~PU1mLe+&#LyJY9-B z-95cMyu3X^0{l(_VjtcpyB!!77VPF3a&si4JT5E@7a8ai84(>-9u++>bUUm6b}9LG zXA}<i3m0Dz6E_kcpOp9_IjO*hU~5ev4-(1~Nu)DU+5PlnQaUj;y*vHR1FJh-xQx_0 znRl|YBCWGh$Fh3zvxmm+Wscq}NFx`L3-TWp<c}1*E-I`kEzbIR-|pUnkinARJ0%ZJ zODcOx#>YxyNTttu%X{uuRKBl#Q&Ck}QT-BE`|3&E!;HGx<GSZZb$xa9Jue#S>l?;r z9yNDA?P_XjY-$>wXl{Dl+|t?H+T8rQqow&-OH0eM=H_S3&;F;jme!Wm*7nx+mbQ-O zwvNvI&d%qZ-L;*4?VaBmo<Dv3{9RYq)AkoH=DT11=zjO|Wz)pVuI`?;rq``)ZxXuR zls|v-y1##9XkaK|U}a^nA#ZT#{!nE3&|Tcn)8?V?1H;2lM<V=2#@>%!F&kZ&9*d40 zi+MYiS2Q-ZJD!<8o|QgcQu5Z*=WSih+l99iBW)8)6B8@TlOwg0+dESk@7_&*e>dAb z{c?0>dV1#D#B9;b?8_JLA3b_Mb1=U=yU?@$VeZ3X{le1r!pE`cPhFpvH@818|M<M} z<;%v_m(69$+b^qMmRBjOtLv1t)wQ+N&9$#<YwPP@|7m?|{a^GyZEk$s_@~X)jm?ei zZ*RxGZO?t5oczA|_51e9_wV0!o<HCDvcCInd3Wo_?(WfE<JSJz>i*{Tk5{h_s;Unj zw;s%YJ}k^XN{Bm3zx(s(_{_ue*V%s}RC;S;yQ>&9)>uUm2?hcH0Fhr1sL#Ju{@(=r z@0b8+r~poBGek>8ACZP#)^)U{av+UG%)G?xS=G>89@W5Q>6{9BZgD*$GOD#^EKmCC zW7o0P+P6hWD-9mrwz|oOS`puu$J*+z6fg^6u{MpPOx*0!7p~)x-zMs?)#jz<9gock z0&Rhx$2*>UX!aP$up;9J>DgE$jU3;0KK=AO?CW@`#q*F9THNvX&u^dq_zdINKNYm> zYFQmfXP0xE=z8{b1h;2i_!~t4GZV5Ku*wmwTkk3`cl|!aw10cwaP^7XWcN>())w!# zWmYdc_daz&*H$K9-VTP+u<+0rxN04K9nNAFrs2mOZjDw-6)`1r{n(kTzFGddH1_Pr z@_;IJ#JcSHK8vg&w%8-QHKj}ZI+4lz&FeqE&v!Hf$Zy_IsV9eU3Le50KuM;NY@j5t z=}{hBF3?7zxzQ;oL-1}v<i|Mv&f!&;!^_tm#ETaOtlg3B<XX;vJ>6criyY>uMyX8E zxMpc>Hhj(2a&AFGdF^_EWV9c4JqN|~q7Q^rJgCkwGNIkbH?yT(zbD{2-3!!<{#FI$ z1jy7C_*}bDm+xPAM>0ns=-bA_Fp#DlO##%H4I;5hYv(I-SkDIGfS3czFMYn<SD7yP zc)Kc7$QfNtHj({SlYcGnTWzu5<8O6&*F5f*TFsvcaTq&FBg*kG=lf+y)(mz?g(7uB zHidD}?umWZ=Hs2F9&<`n1WX?8pRIZ1*m##sKzFzGI$sNbX4*t<uYHct3oN2V00iLk z(K}C{3kvjZpeClacb{+9J=yP`aqjhfaqya^1TKqX*-0!|eZmGk?RIve`BQa*LMM(t z{sIyUt2pRq(A+&3;14=D802sWQih9pkdbh~pyg-%!V$ZNqli5D@G<G~#_&;jsm8-0 z<cR$71WOzR-%x2#!NtYtMsxErBhC6&Vq>RIs1;Om8{K;;W}0%D8OLHcBmep1&b*`l z(<qBcR-=BuK2LQU@MMQH8`^6pngzs&!)rKk^0i>6eI)G4LKPLK(Quv<>fYHGo`bzJ zczhDMuNfYO()yAK&+db#fE9nOC){g6-J)66cL}4@;@94&NK^c8yCMnD_tNubla7-d z)BF!-Ml!w-()yKGI*mgb3+AGsdCcLFhswd*hRpo#r!TpTkai)+{`eg?sY(^OjK1EI z3}f|g{&Tu~JL%OKB~9t|DQ}oZ|1Zgkip2kRp4<cd{_&ETdU5pO%ilkTU$0RA925b> zPruSv0N`f5j97|ad@LCvNdeg2A4iMbK+$B6++Uobz5Sg3PKB30tTt>khDY2DV%RVB zc^(B6ny7F=;dHlHl?;5bK)TQ(T_Lh4q~r11blbrJq5lrjBm=X7)O1^zD$go_mS!O= zzro0Z7cXzgVaCBoCUHZaM3_&Mgf#`=xg$j!Au(P-t;I$Xsmd8ocCx})V1!pu6mW3l zS2(g4F#0M7c<(m~I$WRtmY&KEg@}W{)0k=U9g*V(@EwCu)oQKQE;Jru>l8;bBj=;s z!bWjPg-4_B4`*^7^N*Gwq?2JBUpdiY#;V(e_$jqsfVwmWlw120B}1XPj>0<^*T3{C z?qf1tyce>VtH1#=1vWR@gH;^(d|GS8nOod|Bk<lE&Z==HDrkn~k;#zQ<A)T6daV)O zDK;buyxmi$^WoboFpOj*?pXm=;^|}Y>0^4+m<;TxpuU@mWFoO59(H<drB%GJ4GH2+ z2cBYpx@3HC?ee=g^IwC4w(SLwN<515psYfsmq|t3Mb3g3gmxWO)P+=;JB-g34jZS- zN)NE#>m@20Cc|kEXf6T@B<-jSLiZBrxcDH_C=p1XO&@DT3sF3_kKK1#>WF{^ui`2i z#LYx)dhjHN;Yd)+BQ%#ajYaiq01)0K%aKiy!+uPS*oyrsNK32DkdK1h0|Q|`SkUM# zR0w$K8seA6=<BFn+DkM7tFlg`m#tgDOsMO8?&~kQnR1)%G5UD#Z7&Y#cQ(bi$|F=? zK7U8(&HEVsWD{oCT;0dS7QKjO+@;)sQE`V2%mFBt2@0+1i6V{n5Eg`+CardmK(y(; zauIPo2uNkVgWwYouJ?*kE($2y3*u0;8|R}Oh%=J?V2hXCqWzBJ*DaN_X6jc?W8Ww7 zHu%MC=~~^EoW{@xc|7XkPhNi2%LEchHh7DqQ#}A6(G-6a20&8mK>@{aBtfsPa&Dhh z8m-J;Ccbz>T3kP~A1;ihDx)9fbNgk1lZA{u87kcXpi>X{#M*N}z~@qmnz2AoYg`IF z?GW=tt%dn@^L0`F7e+{ROpDiJkg7mmubu~lc^7q^O<<KqS9*YC=9watk0$tP5m;TP zUnu5#!Z95K($RQQx#B#PL3~?O+~<=v8(DO!W!I3g8+-NA!Fzhl5a?Yr3sC%VbOhNI z@2wmL)xiU@c^Z0|*LxLUb`*w79{3KoNIV^jb+ZJHD3Iu(pq;*YFQwz_mrdy|RCX_@ z80@==A25OCd$5G!FtluUMuuqjBU1901>hq9sbbZ8k@-7c*e;LsMp4?=X4fj8z3+~F z)%M0(1H)SZ2vDV|>>K;p&ooi7E+yQ@EM*4>i#w}ap0D5~;M;&L)0q`VD4@d-$m~xE zR8_nf5*-i*&+~=x#*$;#YMbM~$-NF51|;rVh0>q4z%@~NYu`ve`gx}g50)70njU59 zDO<ifL*iJ~snY?V9@GZ6IG{)miD6`$COz!G4=JM|uuiamppJ|5ZYUJv1b~FlD+Xob z39O290Nr(!XkVKCOnowD{RpuYy|_nTD4W8fiI~viA?<?pp{ml1qnJdCkM|}{J6|TK zAQdoMb`@KG2ZeR;Xb7h_uRourzGL+EFV<a;p(%TtJ8m=tpg1L2<Zml4CLx)dP^$nQ z{RGgQYy*0w|9bG(;V}GRXAtFafNmj*eYW?>bzc-zHq4`00*|RfhiNImOmD@@0XY*9 zV2RNRkct-gImm&)HpmJY3jJDr_lxFDV~vPx%g=lw3Sg^IkJ$vdL|V`XldoIqzXZ(; zsK=a67rNugbn%mkhdW*IuX5j<lZhIg6-u!yH49NPLU)ASmPwM#p8?_&I8BRPi}=-O z6kT8^7~~0Y3ImAFxsPqYN4^4SdV>cdL^S>2lf7W)LSH&W@+1XLK+xDp0l%a5quGF* zEw=<e5I(WH?~-n<bAaQ>5Vc~6N`spM<&r=zLGhe;8Wr3q68@jBY*#ga-3Rvj`ISHU z02O}#B)}Fx0|cg9O3nkeHfhTMp7OV^o3CPF2o9QFaF4ea0OpzejB8XPijhLg3V<47 zVb=!z8BqjU3RaedaEAit+W-cfiG)9k4%JLg(Mm_E$H02Q=oYZMxb75{#7l>~=G=Kj zX*v?kj_Wf7A|(aXQgPSB1%#tSpdXA?IAdu5sipNX;ps8DVaB>FmOr`qYq*mHTH+)S zaN)4KDHQr9DRAU8{5|=G@PUISNPrWdzz_zt?gcD^Kn#?-Q7OPYNw{@|gE0bLJ^U{Y zRH?Wjh5|g}N*J`c*>@(Nga-;xAYFdeFC^jJeh!O{S;PZ62NW~`0Y-Sh7SkOV05r`9 z@Jqcwl>->Q0wRF~B_RUM4}#1+Xi^aHcra*xP4rnnQk73|3dl#d1uWtLr<#HYNIVu` zk!R}LImAmh4StcI8psnu&k3Z(Mz*OTg_ZzoTo`5Q7BEGMhATH5T?vAl>aWh<GB_vl zhq-YV5x>lVzPG_GALXz6Sjz?E+uhd}zU}@vnQ+wZ4rSNH)asf?`_XTt{MT+rgCPB6 z!(Xhyg$~?1ec|jC0M-gnqAAdphKCkw_p}BC@beP&iE^R<^H@NR$Pmm16kbO&N=g%# z_NX-iCN*G4TKDsBq(_1ALjdSU()H^|ZzV(&M+@nq-G8}Gh`^#2^yp4kB&5$4>=uR- zfjKJO_N+nLiDM(sC^04pf!vYc{~)%<3mL}q9;5a-OSUn!{t8}5x=;_gj%~<CX*fLs zrqT;6uDj7;s(1%%%7B7eRNP3E0Ebh10q;)f!o#5B9@dRgaAGgu5`bZ73zDG*f@9@d zQ%lIlnH|`B=49ndVbCN*Y4`zL5CNWd0y#{Vtnmg8OTtxJ$|I39k?R#1gFx0;XdMgr zw>Ib!7Ni)K_?aiE9+NYCpMQXuBiorY%7GWh!W=13EG5Dk=5mLoIx!7ETW7IX2>7aj zp}|8<k$QXu9;PTd<$92=f05LJmw6=snr0}hmT&qf%zjLtsVE=2WTjbLYxC=py?Fr( z9wm|Me$zLFb*@Ui2nTBcyH)smcLj^o0hSA)&am7IFIxpVXwOE3`fb1PvEV<Z8m44u z5IZRNBh-n7XF3mHLY;;RQD{%w)5FGj9q|oAD3BNos=$RUX7z~>NiX1iT=hV-brGQ6 z3s#mCF#8Uo@eo;rdU7~|^*XS!C>9lQpdS8lG6_(A<DrO0M%_4Ax5X0B@WiJQ#Ej6y za6oim_^h-?E%{I0=m@<(l`HUd2n~ZeguzrQGU*S%=2&1P0!-f$w``cHxOQWzD-Ks< z_Rb8xP77*AK^-a}qeU?516UF{+pYz;|3SGZPv=RVPAMk)LB-Q4o_OnNcqF1}{+E^@ zs@eL0ZtWNFr!$zzncg}KdTAQSfPm}ZO$89JIWuU&Px!sfCYr$3P)P8pQ&nhz_Bk9K z@#}gpl~>pCRJZ&FWb7)~6njTwm{)GS;JKIAg}t1C9K`)A&|M5zVD_((0dxC!Y57RA zs=B#<B$$oWQq*o;8SB`Hv^Kuqu^v@m*u{tLL+Kr(WVv*w?7=@)0WJ=A>H;HG(ZGxb z?_eihB?@q{HbSZfg#QF!0`O#vM!Hv9V&yutA-e9z03{>`_gWh#2Pk7SC**CH*v#_^ zI^F93UR1orJX<xYEHZwVV|4$$Q9sZ)!6>H1v-_kTYn5WWkldYIU|f2&9ELXv@F^)_ zzbr<{%o_$k4#1&+CIlH0iY%?s2z(H&Fnv2N6ml<q12X^Zt^gPmj*Yhffb<bC1Qh|! zWhrew3%YAp4$^Hozu)rJ$#lpBIx7vMM>b`gXfgc<OsW8X`VC{0EnEE!9>Dbs`Io9p z1AEfQpXwb(9YBj`LG@q(<V${T88*pEK)ec)PePL^SDqGIzI)4(ol{NZ$Pz7P_<M${ zJraP<bLqD;_sPMG8MaAFTQO*MD&lHAp46%@g7iuTR^~tmO0CZ)!l`=yqsju~ZSO;6 zplAU=Hrmq4oJAb1L0{k^zzGyEw)uHyNKn2=>|Z^xH+S0Y7aQVY!gdJ^*+`Wbv2|D~ zxtdQ5ia2E2R=SKtFY~o|vP4z$U$54PpAf)LjQA2cTWwgXb%o{vM^mU5BZQz5+Y@=( zmzmIyJ$NMD{kppxPj1A`iI$xP31C5ZB+co6ndZ}(DkvHvqFnd@{9qdXH6|fLy&Pzf zRAJZhO9uQ{AjtuFZ}odzq&m4_`6&YLSeXj^ZdQ3fL+<1nKm89FI&BgWd6!73m`rzG zV(aT*)o5Y|)|}uo9-tMC^e&4Snq>Af({NAbrA}9)*DnkibG@!Q4PfH)`B;bs7Y1<v zhB_?Kk*@PV{hiS+;D=>fz!O!bmQI7zend^`-i4t;jh^`Gv;v1d!yhy=%}gk(^q*R< zKO5*>`57+8^zzsd@$0iy$&=Ehvn@FReJ&0mC(Y9(4vB4MBh)+Bk|3reZ^y(uvkG-n zGVI2KsMp_~yl!8ZHJA*{t9hUB{=E$Svk5M<zRkJi`uF3Vnlis{us@ou*1Rdj2NJv0 z8CfY}no4+KJYc6Yh&&Jb*0yjsun_!bAw>Vu_J&o^^$!=|55EQscD=2?L8cjQqrmzp z@vQ|SEFci$!oJ9?y#3UZnHQ3O7VkZs&)s|Z=(l`$ikY>77BNCWZqGE_em;k|6uurb zwQ17o`tq@QLe$31no_gy_JB<Gq$x>f(m>$5VXa~xM+M!g5$&a+$SP6vbd<d8Ok{_n zh1-Z#fk}7=XPANI(!jec(6qwmnd_h5C48P!`1~>J^ZcvN%hXq&DU6@_(yS5_tVRS= z`b+t4#7*lD2$QdiX8&0^66`*-{c@V{WyA31;g;h)lgrbFmwyWm{`_So5b>!rit?M0 zQYGO$9j-7Q{-t34O9_ec@8ZJdw#s9@dgLE>E-3YinB(G&oR8?Znz4K=;7;F|AR7`d zx3acYzb3Q4Ca?GvY5nzM(HakVc_Vn`Z7{0EP#F7cg{fvx#BJT)d)=&T-TXC&;L5u7 z-*ve)?HW~W!4^}cwHsH<HWIzHi-}*r$;bgo?JRFI^H)LD)l0gJIsqX%Gq4ReQK@gq zsunA<+^)-fEbiO+Td}XV;#am3|8C)hwi6Qn^<w~1$TmIIW1IAPJAG=~b8S0gWjnoT zo9y;2C*<3`*V}T^+a)XC%2vLac!@7w9n{Y2WXDg}t8AHts6Sr$-t_nTYr&m=dp<hI z0y9P`h$;z@b~;veggPYNOzrfpY^GhybRk&&<lP-z*?H|&KIyje^6&2K-<_%K-Atpm zd6Ul4=CdrhT(6J!C_?*diX3Zh`<sdT?}+=~75BMNz`YP4)AT+ES$4<m2ZafEZvEp+ z*^gg}`xpB^E}DM4KK}9jubLWbxXyb3W`E`QGvDFo1C}fITMZ7=hQ-t;MIZeutia34 z;gbOcVy;Ju5|0%cz+w__L<J|b7h8|+dk4_<9*KWBa;Bar2LF|t<J(cXqQtu(^sZ*H zx*KtBV~)CX!WuSgl60~hFKnDNeEEv7#k<KA{+~4KC#F9DR-wc8p+A4xoLF5taijiB zFD;mc=<E8*vK$Pt-s58~KMi`bh)?I{5IzgPbQbA;_82PQjsbz5PG^2THQYSIU%D?- zm!~h;o_vY#X3}}aJ51QUy=dw=S@>6O`JT@qND+Y491zKQcAh)-tBl!5B)3x>%V1}J z2efxw-W>ht&41GUi-`|4yjXv?Ui#hc{<|~jw;)>ad;zSE&{Z<xj%VeLRpuUG=I#r< zh!MGntGpO0pJD6I4Y_p@I&(4e=3?~9pWx&_K_Y+Vsm*_GuKpna|E`7pd4J{a=QkD` zm;OF1|2vlSC+2WU(h+>r3pU;YzD)Vsc&R<0oO<zt51=e!2&PlilQzSnRt-}b1r1Vo zY}Sl2I2GImi*3G|WDDviLU?nlKu{q!%UIxs84VqqP)`c))lJI>>cK06_pfeE6*1!e zLip^qu~o)dLdJnt2`Mb<CVvK2Yn`%K*j*)u9{g;$^7Q(vL@58YMoU@_v*JgU{a`3O z_;YtDi{}2P=iwW(!8dO!y1imQ*zEZIA=#}jfy!rKS*+;wI)hs`F<$f8`f#$`)h2pv z)y>H`rMP_to%S!IC98oj0WC!mi)`Sc$VSz~3xp!oEQMwjeHOCvDuD_Uay<`Q8_E(k zEpz=9zByTXDNRTpN5iIwBkP=nnieHh$MzsZu3zAeHYUqW%iUg`EWgml-nJRcLFhVW zEGvaW-u(TIKHnM%eIt7D^2Zy{@83%33mQEn>JJa3r4Pu-z=DD?>aiHoNpVc0nItZ* zV3=8Vu_#svy_o@ex%RLD7R`z2A*g4jjUl_Q_{=buMf|ftnoIK2^tyDneDb-wKGhW) z_IR{jmMTwCF_)>YX*HK?9-O6D%^q#FP<jJVwNxGvZ?jabKl#cTF;!{uQt>}l|A!72 zT5Z<4Z<mj(_0QJZu3VzV&oZDhfN89zLifd~Hpbk(b~a{wq{tal{!%qtGdW+5_a>|z zbGBAet9G*%yo{W7=B9fmbGGb%PUh@XjepvkiUr%x*!z~Qzjtw&Z=bvFJygJo&OE6q z5B_+^v@H6g%{3waa^L8sfb!aFOTG`EYB&c!A)S7_`RMb4OGs@;p^N{RZ{a6g@y~UE z;148jC*0Rs2e-JLEPpqjvswrD_&*y(?s)1eO-eky<T)kfkdw!g2oG`eB>wPS{E{KE zf7?A~K~SnBX!#<IFT6@0=be#bud$S8@3*uTrP;~jd*9`?=0^UXj+l*H&V{1S5xBZ@ z-wMvDnC((;zh9db_Z4C`s&17n`PStqI#X{{RX6e8EF;y$`aM}q(7E~Gd71MTp+I6J z$Cw3e#A>|gr<-H+G5X<t_p0Bgz2~ci{GmNRH{(Lyz~8+LdByoHF02>)od3rleNx;l zBcZhTALGpBu3>MK@3}<05x%4s`9kLTr|>R`cNd`pKdc3#h8%7`j2sm#=Z_i(7L`O! zDZyP&XL+Uc4vo2ZPe+qlY5gAt=Q<=l4C%h{I%c!_wovRweSKog-lL?l*xhQX<gXvk ze{J&rXiIwid#BCeZ_M%A<dg@8OZDaP$2)N9-`%$(?!S(H{SXG6)xQC-wIuDbdjP)` zp)QmU@N*Fq5aVJGm2@v=l?JYD&{_IbLW#=1K0pB*r}wfrhowjfRMJ`%>z|J`C(1I2 z(4mWaIICDvkMmYR7CZw2rz`~B!Aj;}nnCtdZ(OFw;DKRUml4B{^i0R9<&rL%7Yc`W z%sH;JmpTqji`>d^)m!Gs;W1WVV$O`kRB>~ohm|A=SuT;@+htnA@}0Nt1P-pP)@&Q; ze1Dc{m+8&JT{*1zK$#q1DJt-E)Kq%GCg-}Px6sc{Qw$dy`L3n6*q;DXNv10-HApv& zQ8d%7bTE;#(L=@}#@w!unb;UqE9cH@LI2oRpgrDKE8xYr)38cWZOw+ZWKLGN2f3*C z#8=7XhNb<Q?fr&z33;1eZ(Ss>KH#MKY^qa>-d=xjbbpZ{O`-JB<k3=Y375~NR@8mV zTh0-sUE&+C7sMWh&DpZEL4SjvFRmn>zAvZtY-uAz%<)`v6>#GKL(Xn&s>WR9MTwV@ zgpN(dwYe(pp#T&0Zkz1rxoTnP4KrgM+uXwTnxThV82fJ9w8AUJqTV+weRZxrSeUCj z<4Duf#a%61u&aRV-N2G`?5c+6YD|p-Z40{X>NMsbT_HVYx9NUgb&a#4CtgOovD>~W zdj7FaZN0-##=G*sj`AhlfIq|C*E(C(9*2@{x^Cz=bT4q$49P7VeH>pX;)-Zaf(Cg+ z&|d3{?PzRP^H+R3lO54@(`l<~g?g#BL(xb5RA5am$dCS}!&LM_TRAj1Kt^Z2B~YWm zQ39gg_3UGCSanBpRB({zC+CoO7J-?G+T(F$rj?AZF_f;SnpV2YZ`caE>N(+I^pzjy zH9owUtR0qeSI)RhuHwyt!Zi=H$3x=1pA8kKNbMr!uVhy7OlooY?8La9UbAoiK?;rE z(EXB~8=ZeP6q@++rTgF04{xZ@Fg(ze3G_olV3z{b{VyjwQTm?)9&$hsyYQfGBMSCN z97u=W$i|h3@y`JcHIC*zLnEv6H(1i}_B~!)&liW3Qg3BmXSl}uVR2Y<DpV%sQ&w!d zVIN%~k|eB`=_!v997c^GanzX%-x}hxFD&qk%8MRcF_EttHz>V}U9mjxV~RE#ls3u9 ziY9yWpHCvQ=X?A#p8py?Aw`sI=xuec%{%Vx$!ILv+!aylqf3HCRzUT)FR>d6ElsCh zds&%P?nGoy)-n>;^Gvs?05ZOmhNXS7VUqs3^xo(X53}umHy$YJ2=%uBEBgT3_AZ_@ z*8=+4AF%8=F|X2ASD5JbDys}{(zC}SNW5IDX|gG3`UoDVvL5h`sn0LYN$ChJoJC;Z z%Yvy7!_l1`dp5tjmp*+N{-NEQ!xY^m0sy0KchA2HiQ-0mmO3}h<LAE@izRXdv<#{= z&UoH%Bytu~AVTffH0tsASAiPH?S9VJVWIDfSDA~H!#a`~W2TcobC2M<!My~3Y(M+Q zX%pqCw`tzqUcA)-CK|K7aJ`92I(rmYNDs|mJJ-Xr=r}U?xu8!Cv%GaF>AaI<5LxB_ zuzfzUL80x5zkbO>sDVe{`&xsj28Zk4vHr<I>(8<y@x>g~4Md3sk*sj7!e>*?A5>#) z(vXmT9{bl4vm1Z0U#DJG)(*mk6bt}Q&IEUCgaPy*;i&#L0E7Q@GSe^x%IhjZgEkxB zpP)eGBl{Vm@x#)xx6*Y`$uLyc1^)^%Rn?5Z)QmIM?e@IA@VjlhIW1uqeRnny`;}-o zn6Mvp<<f^->dSA);#9r=X72g_!3a@Nul4Gbvv8Ie-oxpX824m4gI!UUOJ*RUDnL4J z@h|`6sJ*bsVTR?Kf$JLwsS@p2hMT)9e}1GTU2I&r6nNqdcWU^vxAi9JufKQ4`d_$? zG=K|h;2ZXO;~`9E8lnyW>tKl@JRtQJf)tLxe~>JKPiB)&W}oh5YXS0~Crh0J1;Ypf z)dWp4PznJ-@_=;^DQae5L>FkL8my`Xw!#q|!W8~~?GrlbJIi~8;OG~Le7q(D{wnrb zoa42GUB9GHzf@$ubV|QWe!px@zg)Yaj9rU94W7Li7HtL(d;|;ag;<^wB@Wtz$;rZD z1gbC=#M=VoB`5Pb5?s3Au4d3nIHGBTwo)6|wJXgYm1>X<y}@EounP7@8Or+%$_EXa zMh=>#3|`J3G_M)7u<VaMPeU9KjN1pV3=U!;LuNi)zC2K0mR=w>)tQ`PMgErth#&ti zRSb_7&;^pr)?&;fjc4<~y9)rh9f|DIKpy0<%UrJNcCuYDT(yFz&jZmRo9F;iB#>Yw zvWe9+B#3Ni;%XQw{#x$BL{7l;7Q;x0o@qoRSEQ?H6l5eivOnBs<kmz@Z2L&u;7I)3 zNW%I^;>k!7WE9Uank+s_P#Yy0jiy+RUWrZS>oQR}AgFk--N_ui(>_Yg7&Ob68@;<c znz=rD?_`v`JDLNzoO@!Xf&dHC-~m{0e&eVLmX@yqC}5WSfCI?74U}GlCwdUsrSTxM z9vM8z&XFiKN>o9D<+TWkqXbtxNu~klm`+qG1}SxcRPkeou**5}V@>Ph&1z#UC+5!} zZ=b2XZ8frJwX?X}4*q}yr(3>lbA8)Y^Y(?fMI8f308bF&0SSg_O5+K?8-U!?$wEBI ztPPi0C;*@%fChz^aRiU<_5-8=Y>4D~@njjTWIlvRZxB%iV8zBlaCIaKndu2mGYgPG z(kuk|QIOCmA<c)aE5#zWaq?b`Ra=i$)AD52gw?0raq6=C+m*pdN{Q8qnza(klnSDM zGjeKcT|+Dx6oh!=)nJ{|X1&YtVrSWUZ^C+Sed@>H)PeYwAM#fY)ZU#Kz56Nf&Wl2F z!x8~_;AO1JT-(%T9wjsYs(JuVas(%^aK!b(<FILwC>0-%RI5b@lB}-E1GPO*u{lUV z^Q74DKyI^4yNp7e04a{!r0WeJOYFN-pLhH6Hiv39Z1yu8zBU|DGsmto+=4S)Bpbd` z8(#gH9dT$-L-M!ADZZf@9_XydD;v>Co1gJev=&h!0j$YG==H`Zg%LCnDVpahGu0rc z7HATl<mF0KFDBV}5Jk2LS9_t-c%VAZRjMF>s8<YD-3Hb6+>=QszDt2RjDoLgrC^GQ zV!cGv0r(OEiss1|?wH|tY9pp^cW7yM+B0RMZ!2PNV`gl3Sz=}<Wy*4X&g!SQ*RQmw zhO}rJ`?qxSu?Tw`efz7yjkZ?v*RI>!CD_~R!>?u8JCxcxzOr|!op+6zAM<Ld(*?$~ zw5;;K_N72`Fz|p;IBX|vo&B}&Z(i)vw508{8`EI*X|T>BDN?K1F97C#e$5>Zj}Ifc z;7Cc*n47nXY@XT=v(1mJ*|&LrxSrr}`|~_Dq0!gV!L7q#IPgOh$-%jxFlJ~z7V3Dt zfNSKV!?nE+*Y+HeI2{v6i-e&MRF&Uwp=~2<f`iK|2iHBv6sS}7&&3?ZC1>>|+$;O= z<oh?y;rcu%PfBW(Bm7oxs-HB>w%0mxG%c}sA#gs$iUsCd0rM<Q^~0sPJCgixBr6^; zPXOo=OS953Sd|8(Y6g}^5);TI3rCV;1Nagp#R~zs(wl08?~MJk81-sC>fnP*seS(5 z;&ZD{(H<^czVcTE?R$*v?HK2~6YO6|EM0{zlWRY{6m;qpbnV#t)H(Sn-`CNav^>h# zUwu=bH2dt9Sz2U3H)t`%;e6@cQ<4?UX9tg=cYj=G=2INf(}E6CudAw-?4(7T^-48B z0~}#{?MseGC=LZn?1ECQwIDaAQ&k6^j;pWqbuZfJt`Jm&Lk?0Sr*&`Bf3`Yzn&JFB z&G@;z0AjW1W~Bv|orgT+eBtM)VT(xh3InMEz=FNbs$F`zc#vu_q&NlS)J1Y}B&qeL z`1}?>V3&_TC;}8^$0R7AmCg`wH-xF>76Kj=kXHA$i^ffphnzOCkxJyR4a1d1Y^PcA zfK+kNzys?;&JXrsP<!dY=*85ss}!ziPXYQ4YmQp(y4Bx&@UY^pj68~<&_8bE{!qdl zEdf=L26Kt`6}5x4euB}9xhlORmtK%L4r+S<G44{aZAfEyysEJ2MOC3F!MwFF6vdF$ zh+fy|uqA4*g=QZ{Q{&oKja2W*I8aP)Y9s~rK~RF@SRvXmH7Eh>%i?}GWbKYh(@H10 zSHNPn6}cq8n(VJ(A4-{CqukPhM^|WFPWRUI^R~+NRzFR)A+Lo5!)&`Chjbw6QLt_p zK`IQS^wK2bgrK$!60w0g(4@dQArFVvRP)x|5?7J1O^-5tF`JbQed!RSa?E1NMg*7N zwbzumO+O|Bf4|L-<CHj+wy0j%l?tMASc+fQ=i~1SUg@OkqeS->Qd~e<Aii}_#qVWa zy>8qV@jEQs<F#*@pD%e6wCul?=jW#gqfLNZVbQk56Xdr+H7OvOFpv}ieMxUyt%XQ6 zLlWg1Kr&>gLps<eo#Z*|?IODp6QblP`7O6lZk+Q5aSaw7010Y=>A#0r_@x!6-nd_P z!(u@-8VP^(QR=BIJiM4)XB(0~@Y!pT<Vi!sjHc;Mq(zfcV+(8Zn>xGm0+U43LbTGZ z;BMUXfZwD9uKo$s2k$gV-h5WK=F8vQZk=bL1=1~cmdAs-{wAMs=DwBNkU$WW@}N!# z*bRi6{o}wu)o*>0L3M`TdN=EB1JgWpv|y5Oz0}>`AVrF^0wcR(yt72OW18=FO2`5+ z>~!H+6skvo*lxq4Dxi@KX+a+Tk%mEf)!#o12VISQG%T7%)P+YN;43QL)R9evmDr$= zfHbcINT~Y$L&mvd0z?Q&d?W#GOaQUPgVRes$^%F!GvcScw0N^U+_qwG;a-m7?xAF8 zj?V7EaDDLhlQQSph!&V_1L?#b7PJU`xCgbRNpb7#h{eL4THrC{REFGIvdND%(EVB2 z13aH(oB5Myo;R$WPS4#^Z1zFYE#TsyFRb!lT`WZMl%PFIcpyfKZb?f(q$c*lg1aPc zTOah=j&i3R@)RBN)*tdcKja@dRP!?1$KE2J9ty*c5Zp&1Qb(ei;iB$AUOGn-%;5~O zX|cVjUO3bxz`EZybk;!oUm=Jdg}b6)-iN82{zuAE$10k~R8`YsRVt4_alP8@W6iV( zVQxtYrQ=n_eU#7_n**>uvywau+oe&0Sh{;!BEiDZ>k<tCxj1vUlXklTdK(ZH?3fmw zacutl#A4(`<lUjw)`|7m$rbodtdv=5{;H+s&#Ulnp=L+-45C1HTU|1~;cz4=91;GR zq}BkD)kw2_oEAHs7S{k%HvQ=-b?PN`q#hdK?Qp7D9&t@L!n0NJ7L$*>T&iDO$|HM- z-!Va~m!KRFV0b`8H4qRjO@1sXz747IX0Yp{X%Qa&w$7)xqT7~AKVqNX&eHk8)m-1$ zE%S8TBSj1zLOw}4aPzE4(II04wYoyLQv(~|w|hy{SVS7~OfCT~&!`gydyZp}mCMqU z);I*;8n#9(9K(M?E)_GYdO(yvv8jXwU~m@nXV;Dc({69W<9ngqlXY3tCvj)L%I`JA zf4Kd#3=-IIUgd=gY3OpEPDKU4ZwA0aq$NTT@Cb66PZvDqAhmoYrcC(B;>x-98IGva z7Pjr41NXWRcw=-3LDSgj7N=b4O3|E77R3<}6rxITO7O5(a7AjY8O&#NE$|?=7xdr2 zSxjZ<tt!p`o|-p>IKq9k!0r@ccuOinpk(N1s-gq@PJJv+>7x14!89}cS!hE9^30## z{e}|EI6dV7G3zp74)v2LTY6Kx0fe@JP;DL4?kJ_*Zh$*)Um(+NgQWgchNrAM{N3>X zyLtQXR@&d~qQBqj|9*e|cW319?uWm7TYvY@{{Da`?KxaP{4btyKei>5WegC}0dP)J z`CB{#v8c3kO?W5`Jfh;{>lfJ;;n?@^^e_;dO+Eli>5TZPXBD{6$TOHW^dO6E{Z4+V z%@7N1Z2st#dSR9BbD7OYPP)l!g9$hNnH^r;mU9qlym2f!RibnIX!qN(|D>^D8k<7k ziS%rZd67!+_Y;}92HSeur-46Z7aFfZvtnm9+%+n^MsgK&50=FPHzsngKVp2SXBckz zbjKuH03Euq^3x*qire%1s!ME&LFX-t)F5hfJmcMS<@M5lwp9g-5SOm#AxW$J?H9$O z=)4OpHJJt$8L7}+c`@V0lCGDxpTs;VVsO$AUkNbT-}|kJecGSKt`u^ib+kTS#JusH zQ~qE(XXbH%0r~l-kRuH=@R~Khb{JtSVdvDUR3ZAucvRc|-#?*4nUw?0O3~rI{d=9t z;`V%A{xwEkse(*4S106#N<_fCiDUv}knEkSSz5o=F%||Jb`eDhg0a$tVj>w@qIV=7 z;6yWI9(Re}Rp>q!%~T%O63bHmh!e|J(fLpur2pT!7#U5cEuLe{7gKX@73;v1YbEMr zt-TYZnx%FL&}JRf`jkT=_$P(<P@Br3@=g4{?}Hf02RAfigzp7*|B@`xm(`~A#iSCK zP{tt`Yu(A7@Ei<V)U`}rGEQY&k!4<VKy0O*=v#=*V6QFOZ$GvwxgXdqQ;$(Ol4+>S z(2;#q`yf{K@uSDxvQM6N|0mn{Y+Og~X~##pCx{xo`YexE|NSS|(nqH&|7?hlKFA`n zKU%(RIPo}3d&99Ull^^(>if1OgO^h}KPkDDnqSm(6<=&Th*RwTDw{gs&{OwYvFGsg zV|MFk#(Qhst@W2&(W6c8rDSRXI2w{84b<*P4Kc8#s2usQ7dNlk=iO6W?D=ZdwKo1z zc|<U7SuR54uAa)6#KU+Md)?VHk+)P0g{9TDO|qDk(xo}kE1i(1CzGXnT}1vEVuzmE z%&PP-#@kp<U&{Bx-g2(i5Lq-zIk4b(vej^lmucar55_#HEPZcOdM`i1T5q?-dz`sn zYhp^{qu)yx{ZR^+wfeiGPPH%ll^2?nWO@UwRkKICj$h=j7752Ir-?C2g`3T0$LQ%M z6jg6;v#}4yN&S5h8q~zlopAp1<K#b>w>BX?*rjN$_A#G$zZt%F|A$7R`R55|*W1KN zoutvqJ9?X_hG(eaysP(g9_C>xwQ4Mcm!8hMB<Y_n-F%~e_BoC@u<2!@p24rzvk$En zHmH1US_^h6J$mv_saEPs*o*9Z>dQxOE>Zt9w}-sEkm|i%s$}?D4z8|)W{7nqCjSWV zP%{DEi`bPE7-DnK79urUJY82@@EAd?qv&D=_Y?&i88n9vnL;<J1*iED4Bo{}{WC48 z8a*OR)oTJuC*D^|{}W-^Xs<yq-I3fvnh0;V+=(6yk-VMEmLHIJFZAhG{{Q0Eiqjj0 z6hJnSQEQ?+@5RYusBem`)iC9XzTTTH&$1YIjg)O$8^suX`172{v?r9GqI=Nn9-brG zQ-_UVWN!(cw{UuO@kjEcXF1uHSF=TB#xC2o<`(vdOR7G)%qkcXTWewQ<GZ(!^#PiF zytsO*bxy*kt6GS?KVQoGG7nX0{7C=&nTO_g8wQ)knXK16!_q6j>{EuC%yqoi36m&K zM9BbO2@eF3ubhRl5hHJHmv(h;Fj?I9CU;!aIfhG5-O6n%k^1Dx+$U37)MtvkuRW-^ zj$}N<SsSj5)_(q;teGWowe)Wftpb(y{{40^o7Ikq?#c`;?xMBwWE-N<B$15@5#z^= zn`nTX%qp||`F9%z5woZa&&+)80SZ*<K@NEwhY=cU;fNtiP2cAmEYWx+V;#|5(DaY^ zsU<MzeraQi*q-5w01Wdq`W7YXWEoBn$25+HyUJ(PD(v(pd<JtY=9Swk8M9zAYpe=s z7gd}CW+RuaoHH})s3|uKy=gzD_K_TLmAqSKraFZ=A3RGUd0Ao|b?1QW5iRSF9X^YD zIkczqC=?oDF3bCf$t{h2q$xFs7x(+7HE2?(>|D@mq?@ZV5uW+g)aD|U<T0BSD6i7i zl<<_?L-T3rbTmCu_KKcSrAe~}hfpaFu7QnR=vh;5-lp7CF0^4jG|M1w1;DtmBFs`@ zM83BuxbxkYnR#AfLcbn(=`TF9F`4b`DV~?H<H?~hLKw1UV~xZqJ8r**HQ9<9loB{A z-A|9WSuwvjV!`qrwT=rdsh4S_N#kq*f;r3!WSC&1#8p~eTLI<ECI*Y>iCDh#hu8KF z9HTYvyLL7eQG0$$sHJ<__9*_pA$m8<X4$jdi(|1tQN4@xUIf;QC&GiI4VlRdlE(}y zUW2=(q3>v8y|@=gO;zL<7(?;6Ixtf~BB_7H7`4WlcYY)en1O3k&=Yt7L}(r1r_!c9 znM}qY06@Q#gkP*=yip-{PP)F7p)^1USrPnkOtuKxXO%bgp5{Jd%mI-7h&;^S2rbLv z8&udcOV$6V>{iF7Qz*QzhLw!ShCDbQe0>6rE~@-s-^TNF;Cx64i>7tsAaY9xrZ#3N zXK8wX`M=>0o6FH(wFe(C$2UN9t|e#3mtgoV){zbD+}p;|qOA9%2SpIdcMQ+_nEj-w zMD7p~`Xurv;on-CFV1ZCql#R(T1SbzulGnQ#g(6`?hkh8w|=>C{IaA_Jv3&khD(93 zt!-fu%9km^>|2tY(jccmu9#zs?-CQ@SC{NnoibhuT<-9WH@dCQn$`5+W7c#FztU{- z`p)0~hQ3jtvWa~kB70-Ix?U4GeB>G2G{s(Cu1j%p>T@uk0}96UTD3{dAJ($xwC4Jx zh|($Fxw4qd6^+Dj&%U~+#<I;ecK)C2waU9bjcYsZBT&WtWcoHK4EN_w@bV-X7M1ss z-ffg9ta$5=;mPX9{U{v@Sm~Vq&%<xUoH(vz8so)yv3n-hhgH{Y?pgy(qQCZb1yRQr znI?w@2zll`s~D<e_T93(Sld~#@mpD>!sVh#tcD7zFMF>JGwh#WGVv~U!F^hQ)Boom zL9FLBPZmN~z{Zf$e#ON`5s0%vnj~9;XSj*~D!`TE^{p*QvNZAgE88<7x2tkU(lm%0 zFAb4aIovRl2eFcHZ$#*TG?<B`f1Okc;=6FVp-~m}d%2NhdX|*5;qyli6-EsO){_Od z4TS-qIc>x8pAR8SQx(Q84HAoS|K6vzgY}*cRL%GElgS#zVC!~>jyOg?GH=7NqFw=Z zuchLO<(zm5MykC`sSm8uPS8OO$WrVdKPpk~eeh&b;K#gcV<kbkhfk!33UnKKFrocL zFyHW4-TgrOi%f-~5CcZFaX`y)ny%mD%i>)5D+gf?km6vnJcZEt6V1y-Fx};~(dsW0 z0hJ%#PqKd~s6((h=PuVKbXtM<$CC|qiCsf|GU-l|Muen4OArmwF*^j0ISlr97?*<4 z4l@+g!*E`9qlx9vw6sU3&=0K-=%iq}!kopAChKdfRIXcTmkffID)^s*)G7wXL@;|V zc%sJySZ7O=j_hTm-PzXW#ftmh{t}urt~?$pId&p&tR%}Wf`uo5?#k>IWQ3gT<eBT0 zbPs-o3K50)e(^>JaTG-(BSUQNLvipY;4n}ze@VROgZ7k|{sL7@KlKV=jBLP1|Ej^5 zI%uiOgW=O7s%2K_1%Nj6Gijj~Me!D?>yvGJ)kfCq)C=%SJk;2)#-n1Y(g^dYV0mnQ zO@Xb*ZS{c?*Xre2SDCOrCCI8%Oh5l%i4yFqN+Ch@ub~XZM<za5w}o(^fRXUP=tkz5 zaMc2q?9vCn$X19b;`_yU3`Mt#?5t}=kyW?i$IHe%slPrH9TMetF^Y@H0Z5Q2k|0(l z5rOj3Sbz}h;b9&Yu+?Pc^m&)je_v@pQ<lzFjYjH`;D5%Dw$Fs~>7*=^pIZqAFz&_Q zN8G8vC|7`$DWY#*IV)B9$WZK&h5h@L_Ck7w$E8$GtB*d`RRmRM!-+oxSv6s~6Gxr) ze)7`+ZI0X&9>0YAtAg37a?AZ<IEbK*VFSZdeb}IwR=+Hz-=ND-AiiIW$FQujHi9k9 zc~%k)u@4R6`1p^NLJXCRI2J|+c)KPwwrf?a%!0Q;I@|AM%>8FL>LNus%;J5<L<W$H zYsiC&!&lDcM=QQ{1HQ7t*8h3wko%+=FxGWMmCYK}O>yfLpFo{2$Yr2J1%YcK*`!2B z<k41K=GAK^pT)W!ewY*%_{egtiCeV7Nzw;&sf)m?RV$KTYi}Txxjz?yU`j1BcE*c( zo|^|LVw4fUXO)IZ2b?mN1H6_Pz2)~-2h>^(+}qYtu+c)m+m<a40}IVTqOcLstCdw_ zdM(~?V9fV}%E6l7{+6$^Ax9xd&ee}~6J5;K!0~bYxbH#0YnhWr1l6fNL9AHQEklV+ zg2td^UKe}5i3#JMrLu$!k&|S_!9E3XaQc6BPHWgRUnh|gm}vS#!A6ka<D&9p^UTD+ zt430(w)LJT;}J89f(+bu1sxP{Ky}=JwjER2p|1w=k--L|EYtTmGZ{GpE1@BDVQ0?g z#VQ3+qFZ0_#H6^NMrB}No!^n0oB*0-{Km1mSgG3%SC=7j1uZv+7VL4B;K3*hfXrD6 zR@MWZAQqiL;4+%PH$09^BC?1^s-aL9K|yb$F7|P{$@hjqca@S#`IA0z8baA2Z-daT zZTjO_#VM3Ab5Q0SvH~bY7SA2yp((Rd=UhNfm^}SX&|il&eSe&G5GebftokA_e%QZ= ziKx@q?{uA8rAqwA;g;Y9NRDRpAxxTg+sDt~%klM{`-Ozgl|C+rm=p{DKR_dQ(ywxG z!yNU=vt`HVn}sf}XsHn#N0Xw->f9q~SQWc1i&GFx4baY#7SkdWbNUNR8}feta931* znU2(NE;V2<+?J2gH~^_Rg18xoIb%F;Yr%p6AYDX}QKjfp6`3~uN24F%W2fIW2f=DR z=<x^6J|9KZ+IQd1F8gs&MXXnnB_`G%9<6X;K}p|zW@c|p&wk@NAGjY5eEwZVcF<7i zq+bNmpNM_nX$M=N&}*xK)ie7m1?bcP%}Xro4V+V<h908${?8Ja+T4u-W8Z&!S2c_l zXf#A1{q2u#)(k5&Oeq8}1iMtM>Ca<S571?QgWqlxxY72@)exI24V7EKTA9SH2@}N^ zV6_^LSdEYbJw^H>*zh1&Io+_O)y7PyNCyv6YZq|;CgmqvKE1cH-TzUr1k~~R(b4rM z@KE%3zfFOIzA{Dddm)h2c3wpWNq30xbv&a;P(LMvAlXBZ3@}ufM*jn2D#eW5Zu5-L zE%D`k1)u(vVCquABZmtKL$P>JT`cI%-w$Vm&`hE1e>SE||JWMTMDGNnG|_ht==r;! zC)$R{YYFCkE~%ua5c4fmzYDC~#ir$|EclT2+x)HibRu082qbj?@^5;}#%+G&k8JHn zj>}m0KbS~JE@2CwF=&Oqmyy@=o>{x`xXEu%ML}wCM#EKT`#$Z5bqm!<kcgR~LJvVj znuu&{MK-j`emRh{doSh1D#U!}h(H&YOyC_vt8@u3S$|sMBZ$QJOQe74?AQ*qJ*;=W zr2uAKs~lVNv@Tc}P^194=g@n#AD@AmE^-ONmP9vRaBfGxN;>zcU|wo|y-ruITYR|c zo8#-tRAs$^JDT_bU7Vq?6jB9+N$3nxZZCOYP%V+t<ZCOJ#56E<)X0$<Ca$D54RbG> zT}1jEsXz<`1h4X68Y`}t(r(C>3?j(3wVK_FlzV@m)=1o)n9)0<3Cl3QSR%;b`z4SB zk;w0#!rjki+*RVm6mbLuYNJ8AEh3}YGxxFe$y>`v@JElTXN*O6|2Xe;2xL0lkQyA= z{O)EH%;&y2`@CX{4%`w+(*iv*`FS0zwjR+^R-zE7cne)=<=lU(62r>XfZhU1AX+hP zA>yj-m}&xtqoG_Ff!04<!jhL%DQD|VZ)ii5WHD4ApP0P?`Op(3D+Y0Wa+J)5LJ?}e zR6IeB(yt{+c)ilD{fD=~r&h$0U@+RBp;&+S`xC6Ls10+S&5sn1K}$VH459)kH%Dv+ z@`ptnJIM_2{{HB6Lsf}p_Wgk`X`4U_7=1zLh)a*EpSRXE8j#z*2736@psg|fv8ztl zKi1iQSMbB-zgxcMl@piIVoGZ6n(du+AslRbo%{W>wrVm0h6{;NvcJaX(+6~V2;OP! zKJ=Jm?k+RobJ-6BDKd77=bA;FyNEbO;5@n7uvSQCEj{<ERD+>_Yrj|*_Zweakg)OU z)5to#<NKC$n%fr20YG8OTa_AtC(yHT+7PJ;x8K&AT-o5kQa29?qTXV&ZZ#FB@U|`I z;hlR|GMv~!g_20`Bg1EG;QyoOyuzB=wkQlqNFxcMcT7SDMVfRl^bVmHQ3*9vLlqD` z1VR#el@5lcH0dZHYN*o0Q0y%rC?YB#daxZX_hmoqxBY!<&$-qdWBkj|AF$m3`0!pa zMNre}1*Q7BF7)fETPZuK)gMn1%swxvEqel#`+>R^eML~}cFnj_#Zr*DPI^wiW_<cd z?`uo)$@bT7lBUyDlE&n7PqaSkZ&5OEskqguG~8G)Tc2{FHD0Buz5FS_O!HN`p$q^s z7}c;$Xu9?zMHnDQ9oBsG!}m#|soakR_b~kxQ!%5AQ%V!L_5-=xXKXvoHQaeCzUcX8 z0`=I-3xgJ#ezQYnH{;F034$-80tv{51i+o+2AB*D0zkCetn7@!KZ%!8=KT0MzPJww z=ATYM+M|`{xeG&LPqNiyb`G8PQxhh<8}50Ji`7sRYyhaI=?aK1%JhE9+n*{=$wo$! zXhGE9#Rw^m`F|QW8g+jOo%w|;{LyT0G-01AZI=S_{o}&rePQaF3AOn;4v^(G!VwF{ zQ5oefWAcCcaiw}LHA%&HvRGm9Q5&vC{$o<)F|Bppw70|O{-#Jg$PkY-Gb)vfY1TM- zd|V&@>TGI;(V)5JK9E}TZT{F0Z~Elp>KUA4wi3%+A@ZW6X@(l!TxOnIr#z?^)tj!O z+3}NGI@fTk%<z*_ta4NI;=;eT)H160bgq>x!YVz#Zu05~jVtJlif>Y6Yyj`H?ycP) z6^|baQaw<y|Ir+I*<SK+O!k?X+H}9V^Di1Ofsy$9u=U!l*FNR-|J6E<9kWWmWeND? z4A>qwsc3z>J!kT%@!q~jr1YM6<VB<FbJw0}v`JdYKX^-!-F`3IKXTh=R8Wti05yx7 zy44mc`*V%z@1LtbVSaLl;^$j4NF6s|%jDklBi|TT8lmLhc=7X^&_?8X^W}~w$L}O) zU+PCL>Bj?%N&hB}1MwrWo|!qr@pDT^`+q-q4ZHG6mSs<~>yOc!Wde>5SO!|>N$Ccx z4{j`o<X^O_@7Rm<I$5rE*#q}jtwyhUZET|>OUrL4@u5xFl7;mng~n<*dE@L-RIS$- z(<IX%p-qAKY54id(AC2Tudef>G-1QCPq@C&#p@n-%A#KOGtifZg&<GmEV2YN0;swt z<!tJVg7?-%mt;?0S!(JjnQ{m;EWldpxY0BM=EBg5PihV{LMG{akd*a*7dLIwwH(JH zpeJSfQyy+jw%Zid<7f6J>OH2>IP0FXcZ5x92FVsz-Xw)-PFTl@IPVkomZ$l**Pix- zKCL^;ZV^5AD@xX|E;aevk(1O=H%nru$9Mel?~pHk`cCxR0mG+#enaF>Wvd&^47P?s zEdbJ=Q3XU=OpAdQlS3+rPljeBFT81ml&3z~y?(uhW9~e`Z+m>vg1_%)C|&KpnfDW- zL@9og>U%!)iU`o*kktd}<n12oq|U6V0!_7<j9Ttx+s*pSiiv3~oi+rlrCu3rnJqM$ z?L8{1fYv6%!9nx+6E?{on}ZWa1Epi5*TUMPU({bOanf-KDbdPZvQW0&cd%<U)aAck z>D!{>u9SR>s5K!bZhYa6^~<F>w7KWv32}2SmmvNpIQ<g>6KyTHJe66cabB%7e;h<2 zb{d<f{|9aH#5?$ELcV6j^r>vm<fyBUg=4vHd7X>n0c2?^d;|DsPP5Z<Ro_p825f)W ztq*W^eAm@1xRfo9`Rv(%(NEGdR{Yk4!Yq)IRS~ygs;OdQdG<=XQAM$j9(uivyK^){ zwc<wU-TnUJP}2Ec^l;XPYW*$J1Ie0SabNFqi8}~jsWc*8==AlW0~R;d;f8Qze@vGI z;@fC*9eL#Elp}?h@AH1w)vsr=GA7^U9(j7mMd%piOHoyX1^*<kAtOei)F{b?E}HVs zj5$t0d=@GjzwI9@R)Ak}ZOX$-C^u=0)&z=cUCIg;cTH4QT<jcHR+Mqxq}o;L%9+BI zP5ymj@#tQyihJ9QQf`aNgnKhSF||J)iY^DOu{TO=1vTWlwL3A5*{W@%Q(mV5{1!#_ zLdg??1WoKVzqQnEPQnwc{^x!N0^j@(Yn7S10?Xkyj7x0nZaDJ$AYt#|9_{!BxF(~; ztk4p47$<kq>I$%PU<9okRD5QQYZ7gx9p#tWrxrGmCz(nzL+V<TuV+cFBu$_#+r}^c z`Mqo1ett(l{=wlPw-}xqRhY)3&Ee*+!1D~#{WsK^j(^IpCQSeZNvsL2*%%bGST<mt z1wJX~&Qw-z!tbh&t1k59DjPF0KN74nu27H>6&X^BbJnw-o_R>MLb~z(Dj!A60t@aA zIX*juE;>rw|JRkVs%NcD7SdLJKQ7*|X(0~a&m-x*lVCH<r5F?xi3t=R)|*_BaveC5 z+=SilK+A@o6m`aYlvBdm+D*A<>-U4A)RL*EVwbMPAY7$l8ZtcE%piAnqnwl99WK`` zFcCzXNkUbjwP#tyjQo2(!_?<*PAIrY&IJd!+px_fcDUfftxJMM3~Ho`A~g2-$rCA* zoO5tW*=&y$I;*f5$4Q4qy$(+43Ve+-n4EQ*$0A)AfIc(%o3=t`{L5~0;ao)sj|pz^ zUJH<%9!&YkqCKCvm|4714D85ShS2R!|I-#$OJ3-U`ThIp+KvzId-sFW=jw~}hIjLl zR)B&;PKL&sM!w~Yb-jc+!2q#8CKtAb;7Z?wmw>Q9BvA6x^i1Yf5#QOBcakUU{Y+e{ zTm^)8LsSx!y)oXXYqpElJ50LL8$8&M<dW0CpeeO6c!MxNi7kS)_@T2#QLD=s>cgPx zRRUI^WSZap*vBQS3AyW~WD0Lw3$-#}wRnJNmZ2+7*IjVQ(OoeUr>19L6ZvT4hzah@ zpMNO{uoP}p%0MscLG+z|Eu}3UITMR`&#qsrTKB*rTCyxQ+LWOd(<R-t6TG;QpXCll z0KN)yfPlId>^}P2i4GU4Vh}dRWM4tA^ycw1ZRQLA4pI2i3-cA;kTVo)9u0JTKaset zEHjGwR~3oK(G{>7HQ1pD@2Oj-iUbRi$r;k)1Sm|m3PmCiB@ij~rb25yfS8rW<DaaI ziz&G&k>+#(*)NyqbFQMJUfsU>5N!tSt;}6niHDmF`EOzlk%sZ3d=qJ4=SKeQKvIm% zY0D`UncQ5rO*5R!K!qr65$>+ug!K}5={^8jD_JRu^lux}9Q#$=ttN|JL0hlQ7O97i z)Dy;9GI1YOp5FWX@dCY6PQHE#=GfmTxgWK1A!3H{rUS><<~^xx&U16QVndB(+MBo^ zP-}6ZP+pV-QUa_(6fhJ-7<xk1X}Ri&L4d16{&+KdR5aqO&xwot6Y|eKE?D~oxKfkM z<D^`m@@IY??_PQ0<6Ay=Y0>pW3h^vfir8hQ^=tO8W<$~2JCD+1GOfO4Jy07XzyhZO z@2W*Cw_eyA<!)8S{#74Wa`n~-Y<VaCHi}@7M9I5y==n}cZ{Av8=7**OpJeEse4>e= zV}4wGI_WgdYB4<~*Z&|M6UGV4Xw)cB!Rbjnz<`aIF^y!cWGoyD#OO#BY1_%=dwiZ2 zol?-b`JSu57jGuN0Df|=FkSFJeMrrU%8c1#fV0uLptoC9x&}68<XN<xQJc$p?eVQ= z>-BwANEhhYexh*uAV6Td(2nC%vTzU=kMk{;IC0!lqv3AHexj|R&#QEF$3xGVMVzte z0i|Ks0~rN1WxOA$7yNcKPm`+M97}EBFSSvWCz)?rL9F?6Z9d4FaEA@L8_$(?Mv_m7 zC-(fy&e|6D|0i}S|7;UQc$ZK*2Yq&||JwNBu<)Fiw80`$SYk8qw#+JpR-cChddmDu zwl-9e%SYwc?&e+m!?*D}X(rV5%YPblrA-%xH08J00vYW5QG?G^2rFc|c1!CS2NC&g zUyNM=E_kz=>&nDQ-%vN#5DUoC_Efe#-`6HJ{$rpc+{1x{Hy6$weQ<95j_AP~XZ`*~ z*lm<w(d8FsT>pEbI4I-VHJg;Fu)vMF=}`9v&=gm8`KPT>AvcV4AbqZl{w>+{!dyDc zLhEWdcvQ)!qIfn$%84kP6xh4Yw^-`H|EEJAPC=7o`4#G6(P^7k!g_~MsY0vjT&u_h zf5a3QqK*Z7<1ZjW`E)&6M`jgK!+{-6aS(4<e08WKzsB3Cb4$K$Ywp?pa$u8t+)i5* zzA?Pytf>^2YWJUy3V$GyG;S=sNyc{-vBr&sHkn=rnW{~RU7<(~ubOFEi0WBLtc`<5 z(IL4f5P?>ZjdxP1;QIkxf`ca{7!>px3uVxSEWirAAmrpzWKyUyYTV*WTyVYZ)-pL< zY8Tpm^w_<Sw%+WC;aPz;CaU7AgAJvl+f;@cAaQ-|_c;oIjQEX0b#8|X3Ms2lM_0A6 zG7|-B)9kfQ2Uj>z`2Cs)1JCQ5RRu@SsPhWA0tLn}?z3F{My4tK%@5;Eb!D&%(Ywc~ ziknsDXlVTvnNfJOKjKh(luwPgQ0l@DH$~6SK-do;-psQL%*}>{6L!`TqdofbA7LFV zlvwxHTG!IZyCu(<810+alEBObtV{|Kb-)qdHy6GSNFSp}GgpU~OvPASlHI0M1jtkf zhaH(4-ZGW)4Uu+z|1{p_*;bG2Vj#lUHROwG_GZ1H2x4?|RJ;>|G#mYvzWPnfL8$5B ze&^>K4cs;<O@cK{K^kSe&f@hIVg#b7Z3<jqlYYRO5O~jpOk+Ass7$6{(JDn<;q`)5 zW&)ddpePD4l~xp++j&n@8A|*`HJxtbmP%5Pdzi5x^AL^sz`Mud+hJY(ffH9%{U|Yt zwqjr1!XOU|xuAbo8)EhR0;~KaQ<0QF{<R*iU9(G=!p+nfK9kkdI=p}%VQC()$u)Ym zigUJu2}|W5!aJp&rt1KZ+HZNZU&^1;UR@9v75SJ8{$PKCNTVElJep}st*wd!xRKtb zr<azDa3pD8EbeJI9#>5DjM9&L*jU&u!z4D@Wjms1(6Da?L+MgDK0{)Y;}}+kft84z zP>3kjWQ@uUJQPnS<_w>B;a~jHbxHhOf%SC?avP5|IBvUFg1#Ff=Md0lv!=AWi8@Yc zFU#TU=i)2lQ+XUBnpiKkz(Ftookxmj9T(yiQ*boad4K8w(@fA{Rd}77`6|b7958dZ zju89C;ay^){90$X_x}7a<3CtBS*uuTG4pUZ%dgnwq!3Y{i67AxgPKkgc*UyOPdnGE zm}-UQ);+RypwJ3L0V8g}Bj%}}ks5tHXgG0Gn_EDtUKw8kH&`w2j|YF~0XvqutN;b_ zZFV;srBp`KlN^l_r;OHtQY`ML>#N93jEsy5u6z|6nuiy_1(Iwe+OWr>S7|TmCG;3l zTa@W9@s2%$awi5XNKMk6t43L?a^eWSd5pk0Q)A;t^3Rzla|-eaM_xSl<rVOc6+ALk z^Yk&?=@X+7+Ufb~xOQ+Uev-;-N8vk8;d{^Fp9>OCC5kR6py!!_EljgR(->zK9=XXv zjxBXcg&|Db1<w&B)=bwlPaV%~^?Uf;Z}HUGIpLEEqkOp>6qLBoW`6eLz`4)g&+VQ% zznpLqhZWr7ylca#-%}JYS{2#D2!6qR+)p5W78cmFL`E|;&!S=PnKkRp{A!exTv)2e zj>cSkQo}B|g{7%%s<G&yRSiVHDH1Rlwd?8U$K(-%pZJY-{)yDdnpKlbM?1}r9(0Tn z=S}NHE>N0yr8<rzAr4}TThe<P;~n)?P9TsrDm82B{IFhTpZnM^ZoCym$fjPv=;#Yq ze@c-U21)_30g@|;QMXNZK_t=zooJ-e-ukU*(aj^FM$!r^beNbudXA`}LX_DYHLk5k zWnhKS7e$0FinxxVh8$lqO!>Nq5(X5cHkPkp)(*U@*e>T~K5t*R=XC<B{E3NbV8U~G zkXsmZ#el#YJZjxv2_JJoAX;$WAMwf`AvEJ`w5znh6rru1c}Jvg{|NaiaOPZ`z#bQ5 zk0}7cF629b14~PW7mlxYxUn&Zz8_=mO-qA_eii$-ht-x2wrw7@rnX`DesC_Y-8cuj zInV+Tz?W?L?N~P#IeeW*Zz+C|qUac4Z&zV9Ng4LX`Xugua5!(TlXLONFTU-!ZFmWb zNE{`uy^{ogjGTLtW?&<!(jzj@6p=84U2r6*f~619YeQ|Ol3U!;q<Wc-RkYry!xx}n z6=hoUfDQ_i8Y4=sDL^09ORv{UQ<E4Mb(oPj=<6~{PI>gz!6enL(||2$&3a_7V-8~! zAx4quw+ZV#A=D5hBH$I%_*snQE#!G2hq3ydLqXNBqzT-@?0UPlDZBkRtlU^!d$#?Q zm4lV2_wT{>16KS17ZN;#Qm62-ISF??1lL*4TWyIyr<C^beCqL?f55**q7hH*#0Kl7 z0}vNBI<w?Y)~Iy*`oZ|x@bD(CgmCk%TjK`)K04`PWnn{QQTi1t9i<84S6&B{OXpe1 zj=q_X6p*6$UoaH`n4T2Hmfu}iZ-MY1F3kkI#?-dqdF6<RSFQXOp^Isa@t8sh%Nwbf zTbds?l1~MvimwWQ>OWNZ3%q||OaCJ6^5uP@gU$mFt7w451kt#+zVKI%C<*X*MDThN zz@(ojeVqa?#U8auQ6_=fpiT&!ZVaE6+@pv@Gx+qd0_8+;y-_}e3R<lCHT};k`^k{Y zxTAG0RkbQSd`oPkOo&O5=q0*-Z|qnPw6aNICRfQC3b=i(G!ki+?5#ichl#AfzBJ+v z>qNG!^vO>q#e}YkwG5*|>jf9YzA@_sUob_c8Q7FP&$mjamrvMFD9Hb+z>iZ4Y{vxH z7<lg2o8x%i114Xmzx*j8`tY173jXC+(<$XDT=z9hSf~fzE4=fSa>)gvbpPrQ=ta}T z0M&-M8wC$<@8A-3=pyde(zc7KQb>Ng4}#ve1T20F+Fa_l|J{F@^3k(epgaGg#HyeS z<w|Z?#l(%2%kTIbINq8le)7AAV%P=rU@z|Bt$qJnLKFe3jeio_(Rjnu%i2L*D-y`j zR9soms@Vze2k0kR@cqbm#OgoQKmlkyKdG_uqw-+-FN<>>QVLkfHHzT-G>HywssHTg z&P|fPC`!L5l25oLSuX;LgIJ1GQN8fy``o-6Sn>X{x9p~Z1)5;?(c&dwMgt(bx1`sw zk~XHi{jAF4+=2}5>xVfMv2$2N0|v3>FO*&1_)k*$e{kZHGsn|Xre**p!>dw^shF-L zp~0I+EjlL@E7p`E@*XReUz1xfdLuwnf;x)W^p_~)7A~yEvQ2Rl60$qX0)$Zk8rCZ= zffwE5_4Aq6;Q{I(jn6^3^FtM18wdG|$+v_@flUQ}VSEp#l;l>Coft@38ngk^ZD`83 zfJgnpKq~Mk>Ndj4RA!-GW^Gj}$@|8|XH#(vy*oGoDdOL@Gy(LdOYBRAYVBz6GW0eV zf|Uk$z5LkY?qeTgGueHlr@Gn0G@iFCX?p0K1wFV{Qf>3+)r@x)Rs^)k93KKJfTxJ8 zv1*&kOAj;Nsjb)wjJ$-Wg$^CgLqxi{Rl8Haln31yPi=fBk*R#5NwM}7<jT5r?epY> ze(4V@FPAKXAdj#D{Y3FGme_xGCVxVi4;mf&O(oasMOyGOHd9#>s~OpSiZ@l2Znifr zP-r9d5^q);zKx1m)ff2TI##R{UJ#{XtD5fPbWhcc15GFMDAFCPp>*%l)C%brqY`x# zLA}*+V7)-lJ@NIBq^!cXlfd<^zNyt(W*orDL8{ew6fxG9ednei>Y|JpaXPCerv6Iq z2h&_)vA8EitYQ?lzatt?6m!Dr*RFd$xHlKaC+lZ=@GB{vSKE8>m4J~^XI>Ya?GHmp zqYl?<7LH<GJK4%#e!(a3kG_Q{)69w;OqE<mQ0z288={!i&0{h$Od-SOr`)?L_obhW z_FR4=`w><qg-$5K>K4}PP>s*~%P!gc6?}u?xyIBwd-$FB_WMo$A7S@@g#H7qNrUHe z!Sh*ACJR=RhT2X$YLoo^&CmN}&tS0gr4V$lvaXuE+mC;5;~t`wj{afR2V6aBnse#H zZHK;<<I_)v<$nll^1Qkl|LSJrufLqZC>Bx%i(au6y#Dv9fuYWFyiUe{#z|{$xz}oL zoFldP@Lv2<JxE4K8l*yZ>u*Kxu?W?PPLku%8!uwc=xjgjF8tViQ&q83a)|u6?XmqK ztwZLR(_G4PKaqAX$7%!pQ|8YJug2(R!c{q5o!+$usor4`7dsnAV&4sCsb1`StsCX_ zGWqk<g%_IIq^<eN<b@gneeGVQR=G!2e@leyi@Q0xU2pCp`u@KBzZdl$l~>Xv_u1<0 z3!keJ8Wio0?5>L{XG}znKkM=7(}cV`qA?gP_T@k1P1vs3aG$7AcZ1}4^%7gyf9)>b zDgE;DzTIE5@1M$>-?aFBR7?1P5>=b6);hn??^LQD)UM@|{=x3r=gUh?;!Rnz)w=de zjH3Q9!4%u=#T(`OAyt~hE^Wug>$ZYY+V&x(ij(<XpO0%fUhZNm<|=eK1R~vEsqY_p z1_(HbE#gGZF^DvY=oYMOu0M%^4dV3J$qaX-Gq725YgoEk^d=U^NL`wibTZ-wV;c$S zaCwuxgTMk4_)l5+Yk!iOimcA<LFMwa&1@6{jdmx{AtS_f+05>PfO7Fpu^G9fCd!0V zWg0F=r9>>9K|huP3#}0`C}v>N<M(KMCPKw9nV_Z^8$pwb`Ya4hX>GcO;b)d5p=*Sl zkxwVYX33Z%R;Lu{y_?rF8FFil&E}gFdzot>T$Z42i$)eEUvH_QrguttTInQ6M=W#r z%WMR}EUV8|pTb<UHw?er7;*Obv^ia2&%q7VyV_y7VDNcbmZ`sfT;Xu#%;TDpf)n3c z;usqGyVPYzoylH=@|}(e!r90Z77J;_mC;$P-HCUOhMzi?qqSZHl{jim3XO}|-4B2F zQ1A2pa>1!b{$q5V4}X3=)cH^&TcFL-20k?Y(eIXLcDF9I;(Qv67CWc*^}D0)E;<fr zoR~!PSy+_H@Kve}21}5>mFmQYH@Du(R;WieAPhFCLC)ks$J&LMdmm|Vm1Zt_w#vVl zi`L3>^45uQWjjP$F%NeyX|(-HOs3SU(IVQbzju2cT>2bVT&GaXHl@or*VI1{3#>7P zVpA`;+P|xwj+qqB(Eetpn02z#;l!owA_tW#dV==u>lS*S2`BIWISk)w>sm<p)Hyy2 zl`G`9SV|;uaQ4`8p@8X6_kQQw$X<JP0FtgFh2OwrS^#EnbJlCA3ON?NBbk->3q(1F z(AZtsOw1YsM_&qK6jiagr<&cLna;>%AK$z5r~PDuja(e2$m-Zkf6SZ;O=t}I6Gl#J z6+FMTzYjLk9^><1QiY?rz{cwE)K*oHyu>Qa{v$;o-M_Tu6`NrX>P}!(luAabgKQ^O zMM`%v<m$*kT_ZCpr~}I#k)T>u8%;mip5wBxo2#-tCg}~M_Y1g*Mv=^A2E;OqdMSBv zMo`?#%_##{GgMM=jMVBTRL#l??z9t>8zdzwqn#+sIP}|4*=>O+Z22E0S$S1gFqVDV z+)y4^qj(j=Rq-5mew0R##+x0QfUW{x6LVeCr|5xBsz&yuop&<-;;l`dtRiK?m#`}1 z!Xr8`yR%XDQeQVGPF1aDKKgiEVgYIylKNhJp~I9^C;l+RH3JbEKL*=R18dhM!e252 z!bfcB8X4bm*89f<#_`tAmPWJBGl{4({!X!jco7qlTeU9}^^$?6$x}^H_M8RGuWk^I zX)69toO4R}(T2ZulpM_}5}v}-wYZ`MSJ1T6fAx_+)9RC|2{g^?i+V1b>Bs({GqpPT zk@}<tY4aj4rQ}oXxoTtPSrrz-(`1I(tFc3oGfSH^PmBBZh_8^zxe3{Ae}=6Cpjpz@ z0w+XSuGuOzS8e#%KB(JjYXrD#o|G<)*@cQ{e!Z;ln#9F}ZB%h53Qv0z+XEi2Tz^r@ zUqBi|zG1>n6B^)gWTB=%<SYw+l1u3{r$vnj?T0UbD~GAMPAUv5JvgG6z@w%_Wbo;v z3oxeJh#FLLzq9c@0>3=Yyl|nb?C>hx9RnMx;1Jd_8aP!SgoST0pWl&j_X*2f+}VE0 z&OcCUy_;mWu#0jioD|#TOz98r!Y9KTV!*YJP9tCFImVmGyxyF`G<%drR{*h}nO1V& z>-kc>du6_p=-O$M&z2Kh>CX>8tDUa{AOp0=`GQF_rT0aB%hWOP`k8rlx{mgl>?y4W z<QBn@MMV6;lFszOq%uQ)z*S638ml~ML#u~h7BiP?VS!ZI$n>ZutC6HY_^}3-jy9FM z#(og+YKe>fg$oPuN*Wi2#?U0Wodg59fMOkZx<(77C7v8=1nbHA2OcPxc7{(n+!T6R zeWiY%NxzU;G~|-@F5u1U$3*>!MT==QbWoeQf+s)ZY-+aKg_NS|d-DuoeE@&<0aeN! z0U!KD<k8+VlL&%m)%kADopY@%e|y_~^=Lw_*E=rzgsN0E1#dqKaJx30R(ojz%QwSC z#R6<TC|-K*m`$2E1pZWEI5*Y98;UVRUdjhc9?y)8z!e$)7Mi#MATi$4;@rubV{WC7 zZl;KJw9C~#o`}6YGm`(bEBm)d1Smk1&a{g7XCop<LGt;%VYqIECH+cJpw#s{IT89x zDBov|GF<Hwnu(Mb8ef9MYg#M}b6W~;G2SUnL4n7P45V@W=91r^pD0eq{pu?<eeHWa z*zQ(lN8lxUnJsj$N!2cDE3u=HrRmd^Jn-7jcw{Ew=VN`DcMyl5HHihZWy;I6%4-QB zB7M}a$JY(3>M{cm3rSUTzdz*%%#MV+-5FQ+pujJwmk7t<d5+Dx5>31-l*5+IXpQJ0 zayAz6vzi;(a){@VH!_8t`cG22L!Bz=J&Fw18<*kIRr%geH{R0EP<a21CUJxQpw)Za zn0<*r)OLC>U{k0t=&=~?EOl~lfn9$0gW}7Z0MQs5@Yfd>o3@XVso6{rc4P;1ihvWy zf?J4Nq$Trn)x)n~CggDZ@9#a0zf}2TLb4@@X2xdlN4d7U1<St|O74d<y)%zTj~Wjs zoZA=MLwBgvKee{p5{ScO_%Hi<A7Im6kNu$@lOcj_(}*5g+pn4Wz9C(8^@5onn36IB zbbHn*myv5%JLT_P%s!OpO)a#>^!E5gc%6BEZwsum9%GVBHJ4PaKW!nh?E4sltRIMy zFo!px52ITKc<0E_J3AM+#85xRV1F?vXDlK+<HDi)#r+=2PcZZY+xN_b?|TdqbQ^xV zJ8F-Ndee>M6kbsij5+x%Vp5pzA;*={jc6cfO>hupi*{chi{q!ozg`u;?n1q>ig03q ze_-IhHmK}02QHnsp%}=yaX3T=LE^;OW8+Ol<9+?(-wJ`fx`{~`h|>p<?G8AWOW&QN zyG3zMVM2bE%3R_CpH)mOX6b&am&w)wUziT8FN6=rCyEbVfHolF35Z=bvRXbP)$5AO zEojM6Y?KU5?}jImdGoI0Y5<qo-$P55U?KiMPnMjXFsvvIVuJx_cLP+@l9lm?z+eu9 z+ro|TB=|~sj`SWj8zbA0l;XJuwswW?ze~BMB-^^F=#>VU=_b`o%Wpi$2~31h@DXde z5D#*AdjOPtHB~bfcBMNnnr&9a0c|!WRHZ9Dy^VV%t5oEYbOjCVR`9$ipBEc@rJ&-h z<t|cn5tT%MJYu8jI2ZCaB0PIEHt?vIY|H#p|GY~>e(r{a>>S_l7rwOWy{>-ro^OWC z_e&A=nVq&)Cit;f?S==8M;z5C$XB5b=^>zA5KtU-`02zT+8_nudeI>4;%7FJ!-cwl zMSf<Y2AO;>Mff!OivK<p`FOoRKp?}p^6aDsADaM9BHI}xA<-L$G5ajAthIzG@O+cT z`6_-yeK&Xkj~MPgKfYr>%_YU9;6JG?b)N&jn1-6yM$E6oh1T=DY;r7PWs1Icd|b~H zB<5s~0cxuQ<1vs>3^)`6IlTieCW8Yp^vW!gquw5k=eY!|N*RO!H)P@q;jNsQ>TXCV zxrAPEp^0NNC4coIHt(Kjb{@gdcP;k{=X7LoYA;T9?Hw##9TbR`e?6`6w2?;-18~`K z)y4xWZv&XOll~oa$?7)FU9$Gv0XeCIeb#a$EZwlKh6AFI{vGJOuv!VtkQ3To>o%z# zh0eNcP(hlT=u+KPSNURVSYs01x4h2bDpoH6ugi5<FoTAEO9F;sV5EfHPtWCl>Q##l zh`q<~ofZ}OpbmS!V~ZpT6HJlVVI+YlynkD47mo~7NB#jE|L>yc2^YQ}X}sULP>=Db z4`e8;BJFcP^j|U5Hs;K)0MrHn^)sdfn$CbcK4TY7_^XYib|W`1rJoD=c!T+(+--c; z8wA6}TxOc9R!;D5LcF>Wr(~gLe6$S5wL+E4uEoS&kf45P7B@c<6)^CLG~VuAdp6r) zSUr<l#9xn|DH|iw%z}JTs7TAw5iKK1h=5n+fLiK6uWpb#x-wD;;@%DV)(?r>Y)w1> z)y?Wf=(bg}bTxIr+c8zfN{Q8EuwmFC<G>2a##Nu+LSMdk`C(vk7z^^!JgL3gFcP3x zBogAR33lT0ymd=H3k|DG1NAb%l^8b~nrG1#Sg^xH592tEPzOy|`a6(62Xc*L(k>Eq z4i{2LfE)-yXE40)RAe&~IvYM*ij>z|d7AWQ7ks81TAPHGw}74OSD|nq?-|bfKcW6K z?CWgBlwNp4VK9XYdhR>8HmwE?SNu?JDLL08{i){|Z!cE0SJu8)p10S+z~DtUZ`_ff z<BBTrk5uA4`I&?4Qim@v?HAPH{FS!r_$JL9<O_AAKNB%A`H%eXzSF9rKgqm53;90m zoLJ#R8AwD=p`nv3)GPKO>TV%8Ge~0v4;>%}bt)rP{M#<5gU^xWLpY!iGWe=bU?^9$ z#R?yr#rK8Hw|&Ha*Kax<(fbeYAVqahS~4ahVvwFQC|lj{W6@+yfqCGO54*4WW?f&# zzyri@RQ%RzbSaBugGSSMrEi>19lk-<7tk)3d_a}#Wb!pL%P;98;_&gkk`)%B(wRQe z7G$2{VURMJ#}>~M1FUq%KmvAv?uC`HN=JfLf({v=XU3x&pm!8eU-_*Y*bRwB!*5~W zKbX2(M}DWqz@Sggvn*|R$>7I`!KFc5Z%N)>3$&yVa?Af3@z$l2fc(;<y&2kc?L&2Z zgJ%g>P7vV`(yC`nN&_mhKu-lzKEXm%8*n9iFpWgn)*Jcj^iJdNDlwTLw**+GDDL)P zT|B_6O8v5@I_&W@o<|Cn#|kbK$zLtXr>STEvbgrT<mP^y;syM*46md#E+{mp=Uqk* zf4FL0(>>dciHw}y5B`V*0#fs1UqK-fUTJwY9@T|MEOuYr;o^JBg{;NHzmqi_Y@38! z0{2+RcZL0)$9u&BQQvngg~X1}sSmiHvEtm~y~<L5f(Cc67#1&J(wkL(gDO4!c~bn_ zYP-+;>>2T+PoD~b5IFEoGWaPIa*2)D?MB}3ow$aW&E%bJbeNS?6>5|fxk85Sr(LI} z9bP{J6W^a4vJg9Oo)kN<f3*(-e{~0b$zXWXfA}AR@;ls8UP=BJ*>N=l2#Kpg<VT#? zluiO3bh;b#SEE(oIw<B{MJN+ww*!nj&<*8yq`1nTvVzpA(><BsBXG;7NT72!*q|HS z${NXvY}?)q{3FtSsNF6yG}w%o9T8P^^~{Qhg)z~P!NNL@tZFn4db0r-%7GO!am9mB zia$iP5D<ojGL||VFge6RSS4o6GWT+qnR0x0mpO;0kqx~EWyJs#inw%<LA?DOQoHBU zhV_`Cl-@~cw||zPg*2?(wpk!EArAws;@pa7Dwg1(`rlJ>(Btm-Yt!UIc+3tjwNUYr zz~gDJiIcecTU(kddqQz6*dDv|0~gF=q*#iGs@oxSA?BXq5fgZ%sO$+lIleADWDni{ zVl5)29<83uJA;Xmj}vyyd9eCK?G76ihlfAGH!Z8f^jia0cHk+TfMRCTLw~}C;jv|| z7q8Ue580?MWZvmQzK>YC<rzyahbMw-&3$>AIYlCmSdhjYc!$vtduMi$4GYZ@zs`N5 z!chC0<&CZ;-i2<s(=&%@ChD)Hz(2!$@LQ)^)CE$q;G{HI1^MKFWW{Mw+GBpO76us0 zs(9?cV@u|-W6`E~6Hepx{F#c;Y>;!|ba=O31mp<dQnhsPuqvEu=En%VW9U)5uHR(v zO9YmEp%_|FSe;pz)s}|)&!9sVlp2qJi-f0kFW<}ODB`*Sc}!fFCTtPLlb~*_8hig= zv0z;fXaPsIjtlCs78-%;x^p03HwaDk;K6fpRpezCNwvn0yYdK^19f1*Y2YHxySk;W zzsX?eot5bqu#|MDOP-R`cV#TD+mov!Gc;x27RpozB|gLkzUC<Q6>fAtD7_phF<Y<X z!naPo@fH8H%YknK1GjBOb~Gcm)sgXN!hf$ylU55g-1z=Yd-jt>79Ql~SPdv7s|ChG ziD@voW#ngneO({khXmg69Z+;PY?(=kEvNh^bm;dg?Z!_w-(xl^MG{jx9~t$g`Ja04 z!F#HfJ?PKfycKxF<j$<*zq8U$#TN*#h(E9QZ=dTU+%OkBs?~@I_2J(<$Y~a@hnqv3 zi+oKFUPYNWiB1$k=>nICaXpAjms6M5q<v-$a$JrhJkkJ#^2ymlC|^9Sy?LW<K8 z!ZCDXoy6@`-4#iA6ch4mLa)oeZEG|z^u~o>M)z#4V<tQr>Vn((qOma^JPA9-3pTv} z^>y^(Od5B<1{l+0`B<&95L0IIkLSA)3IM6Q`9_`ZHC(+jG0<H96ukg&t~%@*D<x)6 zWp)shTnNcjH2Id@eqqc-wjY<h1FaT0480SocqwF~jx0}QDyHM1x#Vm2ZbMJ(o5c^n zeg5)(3*+JHUk=arwjPNXF~P!P8mH1APyCU-DkzEYNU0cP9YO1o)6?bdNeyM8M~UES z4BsCwgOpv>4X(!FLd17AQeO7NXL6dM=|K5{;G{nyOdaw_9VKawq&ZD5WAviQgoZkf z&6e|pBT<6Q_o2I3GVr(VaC7`Wq5}_qGq@=)x)Dj;h=SeO(mPjYzt~w#4@JMY-lV~I zzE!+0P2v_FkqUpkeE0J!lz&?{A9vX)Zw5S$0DF7l%s>ROtQ)kE2eu*ekT~&LOwe}J z*Q+XEJ3LQ38mP_zx^tl~u@2M38$$V{jiI`>OZ|irIos-I{rd0bkrl?gvSzt9)+L%m ztYtpJC&%d&dF@_i;Pa&o`wETVg(jbp4P1?W!k6{uCH##RS(p=J<_eBXi_GH5p?H`} zy@he|fAQ<n>_!c9IKOKXqp0zkUWQebko+WEtx{7TXJ<75x1o_~SACy;d0iVnt`h6M z>DuUYq3&QhAY@6-nz6k!nS9kj#-krD4wn%6x-pz0o+Z2mbr#m5NSVUz{w==7GO2=^ zttdYfH*<_0`54sF?qpG}^if=M;$fRxjHj(@?D%Y>eHJTv>eVZKC)37rNgr=Ne4nuW zeBeTXvXkFjQi9&V^3-ARt6Om;y_JGbo!t8)b~hefbMA8MOL@^fvut5qrxP^~dtmsL zgd<2rtq&<yro3@!ZH{`;N-aI7(!XPd(Ao|bHyLYL7mvGF6k1wfmSQOuywKesQW(zv z(Sqoo8zUzYwF;?Anctm~kC{~_v%U@r#@gV5XWw6w9zIZ%jLnYUvsJol_&_RR=h=pM zz-Fa$;ZJ7Fl(<el%xd2MJuIY5Gqf^PMCYkdh>XrN^*Bctvz|<`c&2Hn7>VfusU$AB zDAu00vwct;Z|9Q9#@i18g*|EFU||OuKVJ#zCp+HFu@MSH63V@Cx$+^<ciG}sDps@Q zmIlqTR9gzi!H1Hi-3bWeeX{IRzXu!!Hm^b>FfTARAp@1Cvt=Vtd``Q_(os8$UJd+* zy7!{0?#^)~8(d{0+*IijNYn$DC8sng66nNlYLq+<GcXxi=eH>P4QsK$?Si2E=@r1@ z=(|WW5JrYV)rb=GJhFA7i4%pkMne{PidV!Mi=4MCy>DEb+ACw&uXP7rrF{){B1Zj_ zKEZ!FyGpj$G7ZklZ;rr%(8p2<O@&VLWHW*1q&~-@8UaD7fNsk2yAroOc5s1WH2EFB zDdUY;a7W`M)0xQb@4q5|lNxk8CscCCEMzf5uKL27xO`RWW=XY)^V(=gZP*l-VqLW7 z?1JIph2d63aq!dK_mY6|EV3E$q@O|=;#e1f*TF`-t2zvdwG}_LP%&jG<{aPiT=XM< zb6(2Y?sciy4xZl$&&KtSSOS5!Uq^f$41>5OS7B);F6)<W2!`g{HXrC_*p@uhd4Ak2 zS%>Z5Hh+YO(0XL#<)cvhd0G5=>G>ZT`=Vwr%gJI})l=7t?KMoz-R!qGvR6zR*Z}tv zWrH|`L>U8@rOMobboq|)1+hVrn;5V=VN7z<Uw|qnheantt#yjB-PxuBLn&ijN`q(v zy*Z1AOCZepXkMArX5#tr7w%#@St?ES{I@EpCn7b(yE!~(83d|g3kO6nO4pROrykCr zV<s#*@StGMIBB{ev#&{BfYCDl*q5O>w{C&XN}?+66MD34=Fyo13-`U)lX0t9WI>j> zCdP%)<>zvyEcuyiCxK?`Uc_&`J^L_Lfni1(3&mIGDf}T=(J#yM54(&b>$>S4>!V>K zyN<F)W5B$bo=o3&68c6zZ3#5j(nh&pWyd3k>Gfi%jh#i^`I!7r(3r#%u?H%b<nrS> zZc0Dhp_aY>VW0Hpi_~ASafS88JaS9yRTCAu_WCNyZ(sJ<1{XxtCt2pgc7Uizv7avX zHg?*!(`<@0F6F(LWA5K5HOroWUNt?s!N<a?srrVxcWJK9x~$CmO`2lYVXH$L*qsS9 z-q<#<B~TUI>l=dP?WatUMn<wSY|NDQd%=-|XCLhQ^uU$#@e0~EXObh*-E6MvDuhm$ zN~dfsfA{3hi)W6DePp&aeBr)#etloGpus}*I5o>Y#*BCGUFr3H@_hp|#RJbZ)><Qh z*C1eFb_d)yCw9R4)7kK1y$p$@1hDb(Ai==b7TRyn@X#a=zEHeKH>S5xBR4-@w!>1f zG$udhpvAi54Cy>~n{BQ8Bs#qXAj2qQ*iLYZ7Wmu8J$u}DY;(2PGcbSVnE=#qWRj1< zv6s`NP_NXF@)s38pW$j(FKJFJU@#{XU+sXB20ZmWbA1A2Trv+;o|%bUws{&>D_Gh# z&kak5f}DTZFlv5M(A1=Ig$_=Jme`)arFmPN&?4h$fSh<TsZlbLP-sOk)6n0)c}s6d z?*4VJyR$1+hC3`+G8Gu}-$Zjt%m48PuJ@lZTa4adV97z|k{i>i=N(~#k^4Z2+tUvW z+K7(864~mPk$#z@Gg<1SKG7PCr6JW68azmn@MPTZvvqwWem6iOVJY-fnfU7WDetLz zZKagZ)OY*6v35@?(1vTf*~g=7O@36;m8OCeH11|4hX>SEHe6gPkQo=hxFu-NZJp~G zc|ly$k!~!qVQjUrj~d_1)F|u0{)hnxnq?kyc?VG;JUqm^Yh%(|tP<MfIo!wuv^lJ$ z8=~)j74Gc__2&JIHjt}ACBC34OkvQca=+h1u5MYc`#$obR-l(j*19a0Ip_ZbA8b9A z<3CwV)8r8O83z+8FIu4H7zZtP;>7t)b*ck-Qb%8-^1&7t4?mkDc<0=NED4jYvNP(} zJmi(^(*7br86Z$X7)LYFCtu1HYgufUNeo?r6WH@aDXpkv$IsCDVs5@7jAQVuH^a=k z9@ei+#ndpfHllf+v<^hemhnRI9b+QNHnfY^Fh09FPo6(olt}34Gh;+pX982Eq;fTy zqvJF1Z<QX%u9@ayzW!Uzwy`nt{WtH)=tROHq}a;v6)`7uWqkDb?t-o-ZuKkyT4VUH z!lUsSh=boIdgGv5y{bM}W8&L{Y>+{&cd09B!dy~<ulN)0O2X%r!3ggUDHnCV%qAV3 z)SeV7X&bE09r*7{T(7oPn%W;JFz8Bl2+7zp8NRNO01!_LS2p;8dSCgUneZkvY&9$# zVHf$W`tCEHV=MD86ZAlfi?>;AFhNDXye%!Z&Qy9m4I(+6M)AEn#`lIy%UBPG0$nmB zrwZeB^oSzi1hWs>Gez{{a>JO)BB=S&F~3e!spr?>LMQvHmY@cNb(olv8kYC$ii1Y~ z<V;KgGpiH*Ff(ulBta?!$YE%tipz&N(t478u_s^M&Qb@-w-|%8NDbl58@BviV?4_J z#2)jed%r}9!iKmE^X~F<s#Mz}w<4Z;Nswy43D2zNr4dhCaq-yt@|dORcCt+l<MO|~ z7+(9$D(fDS<^{QSgZpi3$VznEL0Y!J&`{QJAe%dxc{J07R5!vVY!xo-&_*fxiAn0t zZNpzT`H_9<yzRgTtJHuBTB0jWkqmqjI6Nef<;&^P>85l2Mpet2ptsG+*aj!J&78x# z{tbsjSG0(f7C5989FV~w<U4Y1GV;92@AXS0lj=TTOZ?G1Dc+exmJI3OPVh6C%N)9C zQ7hhd;=CBmPOp!56zFj1-Di+=?dK{`o2BI(190&X{%e~qzhfcKq=^5Yj7m9nKv}d; zU;JH<O-ffJ8N*%xjn!q0H$l33K(Qo%?c7~QW`-7lhOQoa`w0}LM~@bR5O~Lrk}U;4 z%gDCb9?(jULX*_i(--f69NFCUL&y>etEb{92f%w`8k883<KLIpLb!>H#Ny!DRh3k; zBV67A)tZfueOKmy2Aw`g*W005PB$b_@zHT0lNP|YGt|U(#HTH|l@f?&n`+6v7j1F6 zts8Fc&7;N4B&$+wD%AFQr{^|VE|N18fq}#{qdk9VXrO}gCWu5H9iq@3xqyy^^owj7 zMhN15xL0&k&4M-|5N^oCF6tjw+Y8=cxR%+2=L(L*%%)eFc7=4?3R~j}+8e>CqUnAT z2^g?RkMyp+I-xQ79Ng=mP;8-e)6jmvU0zv(9{Y^Ps2ltwiyq={{u7-U!YCkZQg2oB ztY>KsnG5Q)8WtCu>%w?UBEdoa%JB!F1hI*DJsv;3kqSF{Wk6{#$pTTCamual-yV=Q zl&Q`FF20(WcLTVXUX?H87T4pJM`yS>q-!zLP2B)siFAeONn|#YO3DcMD4e~B3FdBB zF6DRJr23NRrDzD53qt5sh{4SD`pr>PPNl|BZSkkDZIvFZOdW|vTygd_vY6>%1@)qM z<_yPbd27n{z(lzv!&1H62A@IU22A+t6dv!A9hU1{;x?!NnUbiG?EyNGYE+mG-sVl4 zd9)>vZ3CrhD|G~`HbA!<bs6{DRuQr7_iDMR&6vR%s52O8`;n}-Wwhure4V^Wi>=5w zr*01AHM_u|+n_W5q}vV=fguOAi928dZ}Zh4Y3WwlD6z0wXuug~7rO}#x3O#9&h$=_ z@;pLZ3>KdCrkN|z;*=QvrDJb+rBzm_dfoIZEE?KnE+`ywDvutkZZG86+@HFv8!Z2o zJQs>L6V!$br_SUQ7mzTtd)qCtk|jj}b&469`tEf;dUp<()boel$`6{9FAqXYvsx?R zLh%Qg!Tyk_7V2cik^y7FW(8n^cGSlMHJBsnHtFJA=^nci@`UswT<|f>q%ZNRZ?mI5 zAst)Dtx8B&>;}Aj=4i}Sl1(<wWCPXF3l@Pz&62RxmmooRn48`5sVFynNBK`3+2pKx zTL$RMeuf^NMy|)Twq!p@$@ugMzJYdr->oJ;3|P=CcTmp}7JJ~3RKfrK1TMV1LmlYs ze{|`={hlPyMmxZqtKupJU)YcEzH?LCzvFnDP2wU*k;T^hWpge^$9#uv#LV=l$W3|f zH9{KPB22X#7RK3(+Oep8F#h|*ELIWZG*n+IuORF&Dcz|8{KtSUU6~dBkrv0G^R&{# ze)(MGExs+sW1YGL_W?UVfe4C}QwxuyUWOw{gk4|MVYJ}H%1oICM~ls3hH4d*!LIl- z;b?Se9!x#*45NMMD+9uefJBgrvwG(aIK>f3^uQx+AZ@&0%)HRIM6p`%j=kUpOrPYP z>468IW7DRMGEFsTl{lk0zlj8ONR$|l;-srf!ZjCt4}B=mD@H|pdc?c-@#8#-fK57g zN(P_-puueObpc2w$$bT6_&v`cKzWSCGBRY_9b0r1*+8LHV~6&3NCQpAQUOzx^$mY! zAo$E+LRM4))d~$tDAD<{-Wdd4{C=o?)4n0&7&GGq!8u~2Lo<oj+YR+7)>#`vO>HI= zTZ%u#ds%LR@FYu{mIvIg5ji7NkArlhG+k=Yv$R*dYS~!shi`oaL5@s-)+Y6*{pn#P z*&jfj>)t#u_V<53h84|w3dzsLq3=XaFN>XZjbT8v2A}_&h9DatDF;UYGxb^_dN_%m z%H#q692LIebT7qTG2umU;k8h2qb6;z85xjFpy`qnJG6^Pt(hq-o+I*X9Jwc0Vn(P5 zETGQCqt11@kRF90x@Eg*d(Qo{1diw)>`|uQ3Im(mox77u%eU(t6>im{lnlGQGOpw4 zZ{Ul@(~LMg@q;{e8+8?jDc~>SV8>v3PZ(q_W<u$)kQ0Y$z?H7b%1~E&?IwNoFL(Of zw~3Xj9xKNwJSrHETn{&Qfa(#do2rO%1^W2_b;N+WX;7qVzoUP<6Qj(lC6kyh5*U3W zmPC(3(|z|)a(|mnqTXq!z0*4P&Sgn1ngTkd0$l8#wgLF;q~c>E$`!?c&d+dNT&w@g zm)o=em7zM$1dxg*70-B@{P{lm3W_6uvpd3Q>z)5#&Z%YQhBaoMRLU^GSThIDGqTvW zHXmx4;+7cD$t0i|*Yq%6)S5g%?`%jd%SMg78H{opo}@ZS(l?Q#af38b+G<1vScgmt zV;A3zgw!53!C;?gSManm7`Mo0W4)JQ@+Tnu8`sGO;dL(+oLIoX1NW&*G}RW{ST4F3 zG{g}TB03r#s6cfj(4t9@1pmU6B=k0^Sm8M>(&kgpQhqEG%%{#Zcnhc{^06%G%rH&5 z0RfR22MN~&-n|RH_qZj0twq+pPK&#BbM(%gK0|GNn!(g_k`364`O0En#@1)z&U5h9 zd54%av<V}VU7Dea1}=XOGOFM{ff06cy6UdX^lpCaoA;P2`|&Y6)0L{IqTcUil%eRK z;lzOYSd{sqH5>^&ui7&mTX<*$S_qRCK07F*@u`aR>2`iZ*T^R_D+J<kuaT3Zku7I< zXamMG5itueZ^0&><BfYyU<H&0A+ZNGEpX`L<1fje-2XOJx8SBEQ3E!&76!!i7e2Se zYwiu#EKIj$>*ReuJ<Mr<ey6^90kdRH9rIT6?t75;7nbM<I?Kp#))UnlyHE!W+XhR@ z4}gywR|j7=sQR6shykA_f4sQUHdw?LphtfK+Y<4ri6cQSv*{@<^eFsj)5A}(EkQ~i zcGFlz6E^xh8zj%B25-_5lpyW7Wg8Ni|CmRI|DVWA|6vC{0=z0bNA-PyXn&<&4gM6_ z5)CZ;L~o3^qqZB-s$UvGKgY?4W7$e>(+c{YM-U9x_}xv<_L}6Eyss3@Kg_<9pAPQ7 z1HNRF88l6|mI0p|+$TP(izCVZP@+e3s7+K~2b&D-v<wq(fHv2LGyhd}e-#Z3;EBaU z*O=FGh1@HDC~}2BaWTM|9!Gid(NoMouMFSSf(A}0X%~gHKu$$LLcYcXJAJz{xVp`Z z9=!5x=w8HU9Z?f+lZCza1+`ZA!91{~m!10geWWO@<9OoX6uF6_j(Jee0s1#mGS7zc z|Bs@3k7w%t;{eXww%KNL-wd1k{W^DP7x!E4Nh<f;V!4G>o9o=?nuO+(kcv`NlFeOc zN-89TkP4|UrTq5$cYp4&ea<=W^L{;F0<9O<Yn}Jvk8bfU5RYE)0Dm9j0r8!uM{ZeT ze%kc@SH+M^2wPeSILha>a5pjMCS4+K<iBc3{|Fg7v4{MP(rxG~&b~|h0WM||>6u~1 zX)bLl`xF6JMrQEgv>oQ0l1wAt1$F>N!`?020W@jCF{GUFX>uXmVdPYA$@Bopwr;oA z+DEfuy#<;NcjDLhxpaMeLUp3yO+lml+7tjs?$wNc?Vht5(aCe~Akoz=@X-xjpj4aM zIe`b_Sy6NWdfNW8e4%SYoOfx>iq|tdD)=m;Yx<Aq5eoRv(xp!HW?`a*f-h&)#wU=6 zjb*nRqC>Mt<X7HgG4~-Jk7H>bhs&mdX-GeS2SLmypPMI#>eeoH^5_76G0)5u9yQ7I zfB5pku1pVjW`s_=$aVhnI_~>Kbbftio9v%}P=O!#o7ymH#I4m%0mZN1#DO0)zQelm zs;ozW+x&-$pLHb-4>my|ft`W3Q_~AxIxfg={h9u=x~FarA$6tq(ua=irE9uDpi1(` zT=*zmVvS%0t2{|f`zA8BFB2xKWG=alK&57)^z0i#Ur8y~!0qBB_3E*t5nr(<>7k1K z<yvQ0qPUHWtCwe4i(}2P$}ejyt^lBFqHCSes}o0VFOSa{$1L@)Yb4)A>JlgK`j5AG zMpzv2ThdLt8eiEI`I&X;)4Jx#?vT#Sksn@n=iF=KJ0ITexGnLq=klS}$xPL;Gd(ZY z*h%8K9#5k_ZWMn)?uQwK|15rd`|};254FbIh9p0~IJu<v=2^Lp;i3`Yt1f*7P~7Zu z=~Mrz56kadG>X1a{o;gK5OnVGt&dLz)U6|LtF*o@KnRL!cr=}Ob@OHA5dUE7w;%Tf z{#YFQ{h!OE<z#G>w%Fav?^|vvDxdM4Y$~j+nH>mwKObCGzB`$PzNA6TMEj#@L&C0b z?sRc|-*(G%hXV``MAt(lO&I=<-Y*<IOvsRocEJirD@74)H0u`X^K`U(cItF=d)|$x zZyWzAJ^vM_KNFf?ky)8?`{6I2Xd5t}h-0<_X9qFSV^KgR$1;G1xxHL8q(+lWwUxsv zHqhkK_ZHI?F8c=1<Z1Z+2Kijcr7WOaga1wWB1bnXFfP5wPQg(P*~CZ_PNrW?#k~TF zg&gK>k0@s+?gv|^Du~#~BsA!*+z`N8hB5?nvuzc^JX~MN6_6_t4JGF12kXyRh`Ke= z)`SIA3Uok?x1RPWh&UNyk*#e_@vkSa6&;`Qja)KbpD-FmxWDmw9W{`tw;pCCq&wHm zQ($Cb;^}PowJFWP;%CKc=%wm?kJ5qxFQUEwkDZ6drBftDa?kX1FY)U9_9BiOFOIE9 zc`Of?y;S?sEkAL8Ecwy62V!r}mQH*ma%^w~GTZLl@jmnVko*PTQj=A0caYL_>8C08 zm8!n+7#~n^naZT2L|**cb@Laf4@p-)XbkbjjwKGIFXg>@i;IQob}ht?o6M%j%bqen zjBos8@{IRB<jjlRqCpDx()kRke*<<f)lx&ZPguC8I$c;#qqcuG`nhhO6hck64jtpW zEg*fR3Ja3HP6Ie;>am8qbkbE`J3oLs%#HC_ILnztE(dk%j!2scKUu3UIc>TwV1fi9 z-K>S}u$isG0-7US0YLdiqdHsV5My0?yLzKnwszT)0c=98z><J44)}3h0Y~GqlD;Dw z{p9D{z#Gqg&7OT}E1!pv8&*z+EcPP{aWQHw_wETl)$(l6wNq${IrDtIS&Id1eok`x zOGr&*f#Otv|3Q8NPc36ba@u5hq(V*4d{8pFaebkvyEflck_R1X_rkeGtkBi>u-;^< zavImm$PV*!P@mLsxa3BHk%Q`G*j)pUpXef`K{qo#WB63dYqgXA4oHUfrfVPE&kdu5 zqAnr_v?dny(vIBp{)M+b(oc{`fZmL;(4)v{WmcY}Y%7UE#E0dK2lZKlLAJ~^gH{48 zR@6%EJ-*P(G7)-~mI_^5hb8p%@f*f{KKl{$QU-*~Nt)Y4z3$D@T%|&yLg4{NCyR`o zy$bM~HzmgDY3~5MSvU=DAt0C}eHYG$vE(K?Y|+z$;Au}kj7NFcvc&Fg86jL3p_TYC zBycj@nH_i@7c-Z48Y>k4)iPJ?M?k+t+MxWlJ+>KKEo-kxOP2(|4~N@4^iB&j9ekKT z<iOLF#<uv0%UXzBil>6!BItrMK)A5&lpK1JW|v5Gtj&E5UK6Epq|57*XcYn$pr)j2 z2QTHwaG7jAqB&7feG;e=g{7-?!>%l7sF198Xt+`=e7&Tx1?&ps@Kf;O9I;y!K{UH% zf_RPhXM2-ycVN!uHPeC0f>!GsdxaOl-YL^2_=+w>2p{S@n@6e<Q67f)q@tOUhnuK{ zc~(V8z3BxhQi&r&TxX9y+rz@Yi1B-Eva)^xGDRF0b34At!9VX!FUJK`MJMv0SDUi5 zcG?U6#J$mXZ>EC54mru2xb{VrKxeV*@9sWI6Uhoa6o45?7R35ygiO><=w=QMeUBRw z!1K%`=2+WSOWzln9Jav))oM1!r`;}FS$A)3yb-*YDhgncC;-mXSXu>YNuHfmTE;>( zv5?yhvtp%iel^^G(U{Sdg*AM}58vSP{SB_lO|EEry@<99Po}@@CvRMghg@L=4-!!8 zYzzvx-r;S9<?@GH=_oist9h}K)H8dpxCC$vZaCc~6Ss#INexvcp3D-^qxtbE68f)4 zhA#?g2Px7h>B@s!Jo<5Uh}153!;;BNjhk3Fy-6oiHh@+*_%cxt@%md814Qs$dZtAP zRf_V@B{sDT@cs03>Q9`nwpc;0Ci2T3CNuS7{Se9@Lx&7Zi-gSNexi000s3xTWnz~l zlq13f3?qx)h<|HDj~iQ_5bVn~X-jQQX&ykPY<u<aZieGsy^hd}^3<Z@jf%pu%z@7e zrqKI&d1ZceFTGF3#BmbPei`oUyz&G%4=O%A^HH&QPF;L?;RCMa(6oe(BNHs-<XS&& z(_b+8UA@TJuoFRkfde7rI*FbwOIiN&8S|_~aJ}PoaSo=s<UAau=eIH&g2_@WT?5<g z5op$ya?HO}@CZC3SJG%qB8(`ad;6zz%_|u3MZL@%=0d$)dCP@9v-z#NXHj>zfN5|c z_{eaYrWY1iHgQpY^@k;PZuyXgf9LNEKAs5na><-qw0DbE8xd>K$<C#?&!avX51D=2 zE{rvg3)s0Smbs8+M{8CX>9s-^yJje+)VX7B>^~JLrWJbmH@+5CHmTmqEEN~>L~D;I z>LCPt6H8X@&zRogC4egz_`BV1n7+9k_49V%kuM9HV3P^|JX6l{>;1CdrPT@fmBA-C zu!4bGEfcD8{0`dl;gIH(t577Fzs=`fq*)GCATa3uc<Tbs^@~i|KFlhT`q@%<v`D-~ zBID&q+ta>Z7C)nc<fYyXXReri-+viV-9FPLx8@N2`(<o3dfJ;`N_|}`<dS@dejj+o zYB4X+xIUBteJShU<g<0SX@P2q(zIBc1Vv(|bE>Zv@@=;Xp4sz<r`wWbS>z1<cBoJ& zp0mN+YR|FEAK!+sAS`yRI{x@fG?%Mzq@w`*8WyGZ`&VA6Yp$zfz45Z-&`NU=^zh}- zI%t8*t2#rMB@eMw!g$#AJIk<Py;kX0@<ABJ)YjB%IbI^lvZ8&m7o50I)xfRj^3LcI z$kq`s8lOXN_9I9ODM$hoLs?P~Zpp-#G*y=JT&f1%4jGz*Z(bM=BOn=mw-U4E%vnft zZe}*9RZ>*Glvl-<_yS2}w!Z@>gPnDKp1Qi6k`z>GO;gymY=@I@-F>cDF>_m%h;iA~ zuz^Rtu7^ggR!5rBuD$6qMEm$94MuB_6q`Ix?8DU?xRu(7y1P~y=6%ReR`r`)w+_cr zCuai+$%0KhvYd9`xX#6r<Ky)yjgsDkF7j&5C>Kn+SEOxt0+b;(H%%Ojy8AXWT*^Qn zu^E8L-7$?h%J;uAlWPGwKw0_8zKDT7!|u$RNpG0Fg32yDSO`nq(pHjIOxEN^_);Yq zOb8eE+#FPF7@vhZskxZ{`^~s!#;~jkRqJM|DKIVJoWyNu5rMCkN>Kqvhe_eSbt=EC zld=6xaLXemSWN%K<`gVLF?~3HL@JS+tx7EMWANYYRp3mi5?SUyOQb_{>@|6t8W@LS z;mdec7UzwW;u=!~$X0eCVtuo3Vt9l#xK(&XiFf=;(C^?%mJN;ou`1@l9>zfz^ZX7` z&Sla1^rE9BJp~@@idu1%3wBdmanlQSms{~2&N56SVa!QykIcB{EPDDOA3E|##hob6 z1{hUk7zc6OH6E=tl0_+xG5)5z)=lG0m+RYBx_epTo5Y2mL?2gzrYOIs+KH0^!DjDB zAt|-ST`R6pY37Mka5n{<NHve_^S56Oa%&9I@(B(I2?<wneRR`cf!fEebWP@o=_cZ6 z0|sz_E}De1?9+`ak4P17UX<Hf&x?@ZInn^oe8+RdvM)a}&EHGOBg*Npmz;`*01(5> z_ru(XbZU&QG92<Yy&wAFUH+`f+gTOv1r>tk-|>&Qw@6&t<SCNr#PES?no`@0NgU|~ zS0e|(me6SgmvRS1g<P8X?6xG2FB(;7%N9Wa^p=?^h(f$tzj1!5NCh)r?3kRfWcno6 zo?l5-D@B&~lrv1hB_I?RKdP9>LPDq#Y^E{}kTnX>#AhRUi3+>NtWkc}=0v39OKWB} zr!bl?0U$>MInvy-2bhYHc2~*vnQ9>M8F@b4k9xeR2ED;Ya<E=-V!0DZnavFjM(TR= z8`-8oCSC61`E)l1OV=}eQS*N2(`S~;kq5bFHnD;1tV6Ta^pUAFvo4Yu?@Uw>>F5-t zaEfwKw0S5!;6}pOscR%NvXe<D&*S(^55K<6Y}UACpSi*~n{M;H$m`{%OejGusu6Ic ztz4y_r<A(r(k5tPPQvsPH5!;w3<4^zI91`eBo2534}380B;1wXrg~iR9aK}1TMR#| z={l<fPt$tGt=km%7sQk7C3fkczj}2&bTdpGuyJH&iaT{mAqBMUYgcZL5y`ZBxn3-* zppa%tl=h$k*<4qwSwzDs3@_mFdJfT}mj3E?K~9Mr94(omV#!Cmxdu@2;1=E^$aiO3 zhlSqi9+BT8<W$?+=9MVz`6?gGUU|&RiL@MYpk;+7-iE0!bg*L7+}YtAjkB+O%r;ZW zy<?s^O2+T<8eIi(af<rB4rMV82EbL#Zk{K@R-sX=$pOU`T7B3p>f5~mTqsM-k>p<$ zX%<Pk$iGl}P0;KeJVeXu=oY1Li*hk<b2@4@IOgly5G7S>ahEWXd&i3J*nn%^qCq!F z#oG#}lNOO$88_V6oG;$ERHMJl(zZ^MWs}U&;UUCe<JLYEhTMh9aTTljpQ;j2TbkOP zV&T%>S=_BQO&WT*SFDPvNw_YFmk{e^V(=t1oTN;@l{W>D&f^R!`=*qF-+ZGK?oy^x z&wYKONO(4zT*Uq8iRdP;%BAMg!v@h>IlKl|lqIYesxZYw(753Exe}e_AFHEJFJ<%j zgbuy>Lb#J%kq5w(R!IyK^s0z2_y95(>cHYMVL;un_qsfuC`~8iFx81FtlVm<h~&NI zVHNA9QET2Nqi1h_2izmV*E{%g88IaCF2JLw=28`pK^(v<h=tVaL%M{O4LTm_<<Z<L zGi()19N|~A8`B!j_0{TwCyfhz1?aG;N-BNbXn?_#RozmVQ8&qAx6CAw#50unU_<o= zN~icB3@)4fK+-{5bm$A;bn@vwm4+-N<i^&>oyokJ4`66$k=M6HlA1B+#ECLrpk1Hw z2`(e)R>{ez4ByKaK13;8Z95?kPiMCF<g1^!v0|tU=bG4`e3g(I_3nVG&rVe`Cu&xt z>flJ4a29BQ=hWij(89WqgF0e}|J$Qdd3uhrh99;y6*+d?5ZRCaef%W?fW<_Anc{{v za0w5;l(PiL8m}Fs!@4!o|HygJVOyGK`{mMKIvin%^iq&{scORjY!E=Elv~)BTg5Te z7`b^X&c11RM9d=<qoB|fx2)1Js@#;#erVaE0#HF$%Zs9O=VM5sZ3^Er88vAJ3hVc$ z-Z+a6e8^^*rPE&&!=;V;a6w3OOCDVhlEE^M*1Hcz<UtX!cH@PCV~BItYpLG(p4yN; zoC_19f;jZ^AnJ+^nYm{gP4So>oG|GfioE1%w#P)^nTS2=D&s-*bSCmnoT+}UVH}TV zPtnZ}Z_fAk#l#WS+Cq*!U1f)6vALiv>tm?&p|5--wYC4ZH0t)J)!siDnNrplN>ZF6 z$dWk?d|WdO-A`&)+fM~b4);QW?q=dX-+rQtTA<#Gx+Q#oj~-!4K{%>(s_HOPeTvxi zn0$n7<?)C2^gF6ueTV(?U4;h=gx2FobAT<pQ0a`l9(ly5Hb)Kz5KacDzK!0gBfx1~ zB74~-c+iuHDJ#8qSAnV0jzp#Yk}b!3Tvs26*{91jWGiv8;P3EyO{wLgECml<VLJDr zd}6AxlXh5PdJDRg$wx$bP#ZlS@J=_0tZ^&mNg5epODL(*b3`NV^$1eGiG*P|F#O0a z3(aN2H7f3G?r_9~N1B@jbRyx{%;O<QTpaPpE=g~JWQMLBBG(c>t(<``U01z>YoID| z^_^-_Rn{4FvXxGW>(H9wVM&G@0q~h9gqXkjeBr+>&SBvYk?3Mu{brX#r1u&3PF~uY z@}LowD{PK+HtLTpHTkQFe;@lM=A_m@RO!_S#-gIxWaH%l^kypNez>M0HKy#0n!zx{ zSZig15}U!TS#5xzy?XGM^1+uIz3V00Puz@T{hnm1Tf+Q>tb&I7j_&py9<?nvb7k+C zPW9l4n2BxqKL_7L=L?Kvu{7y>S3-zN=}d3~MSL&&&jj}m08^RbuJQc3{PIW*7vbQE zNKH`xb@$|(CzHEPSc<(1Qfs})VV34D71Q+^&l%MLiRMQDM7x}ph*IXA^n=phTfh&5 zJa=Vds<iFqe`BUqW`M#PmRiv3n}SaVO{Ay%dDanr_m$0@L(|%~n7Xdg$rngRJdj?I zie61=dWknJ&R*L-MLLQ}dtBPrr}77Kk_394`&KfIec9<uYa6ngi1=wGt7gUJ=4Rmd zM-)2^yCJh0JfB>Cu~!gtZUN5=I$);Nj4&Wd9;vv}zHHL``HsHBB;)X7pHE+)qp;(B z=Egij7gKbad~~)*Itn~ThSMCcUc5BSqujua!rc;QoPXbqRzsdlvt$bEFwt$gAG*iK z`-;;mpfX$BGH`;HE4P?2hxka9=3-&Eh_&rJ&o9<I59H~UKX~)~L&oBq0_C-6RE+Y4 zk&A=}`{ch}N~t$OxnZpoMyIm^gIi6WDSwb%pvqga0D?DAfI$4bP=&-hYLl<_h3Fvb zbfLQRAgK;+t&~)ZXsX#bQw&4x1p^cqrYr83v3TNYgvH9xYfuQFIS5?VV2>~aNH1uI z+%AbwPrqsoc(L-DEZAdmB~qa?$))vkgDSGb8f6%ldg#sg;8jYOVaLueNf%alqzj%V zK?Q@_9>@-+>Mn3AjX7w#P_^lvvcHHzCa!0P1$xf#o36F`Pxk~sxA#OcTrmS!jWmPh z%S{RV#*PQyEVt`30s0W8MiU`np=J_39?EUm<T6?Co@JzY+BicHX&ARhukDKdeBbkN zD!)^;3ch2D*+1kahI6cA5b6|1?JWF*XwAaGAbUBT#jS1cp%6*OH2%LyKLoBm4IYI3 zG#zrPGNw6PGmQT&8t&1Y+vN2yS?r6ab)NVUd-qkkTuUbS&S;?WH7tpScJ*wau~n4g z<W%iDR9x#Euhlj5B9z<~9An8eny~S`H+PZ_p$2u>RQ_TybxV)T&0C0u{u3q_ejOm= zLMLm!D(S`1CQ#Tq)SXkyp~ba0M|!Dh;83CTT-d?xuMcMVNVAYp55(iQ><?DCNY%>a zWoVP-$<EA#(luA~sm!LrU;m^#7_Qn+4qhmUT}uAxIuie5aHzs0#txhCB>{H5DeSE! z;pwl#=V1l4fv99Ib2u}?Yu!ft;_vm<>kXwo-?6`0?IES7adYH8Z(Ps{*g5ZgFjB~% zH6th3c$tiJ&M{F&3yxrKRYq-`;Hyp^TMw}YUphe8g8xsQ?o0>@k0>DTzpRR{S?oha z^j?c*(Msi%t71%RZA4wGviZkCtNahs@=v5*8$zCCLqf`3QcYIJ{odJHiJ#rPwu+7o zXx*^^y=ZSN*4eA*Q?hW$A-a%^)Kqg+Tmpy?T+o_4Bv0cFFrTQ&1m&CP?2B6X(oZy6 zxy|f1qAkjN%RF~`KeaxwS;c%pkOuYoHGI5Wb2U2`<bv)Vn`fyP+3FGG_)zR&g*ICj z1Dl~jzh0moAbq|cepKZ_eX;ccBVP}-;g|5>`1lctQ|ujkOZYJ$_b2|N=I1Tp5B<`X z5rhL;T@Ko7%P5P&2isFTy8AOw*z#TFL`$csZXd`AjTG;=17;c&nimuLAI2SlIhpT_ zMU(~o?Aaeg$F{Do(9aI)9)4c_{jEOaMTB1VDn7A-I}OPra&S#DrFdQ7dU&$0fvUy} zY=(%KlW)7EBU^HN{d9TK3RLX)9QmsKOjzh3>I;*vI%TwZkX8KVG-pR97k%w(*H!!9 zXlGd15b9R<wo*+9ZE**6wqW}e($!BVwkGgZT;q5k`pQAY3AgvkrHS*4x^{xDcRs-j z>r^@#icIygL7LX#9=T{1FpXy6*eP0HjAwxwbT;-xOYFTLTQzw<`DYsPIOFWkzzFGU z^*PDk<s!uN<2)nuA1+mXDPD%Z2MZsgzzJX+aD>-T)6LfZz3uc(Lv34eraTnk)pQ&Y zawI7)&lIeC=JC?ckB846Y_wWg!gJW^Dsf!=M_mGh3tYTUN^)o0nlHf-t^M+O53fE; z4A7>tF$(bQ$`;F)@Jcp888}IMwI`%L<<Bbzrsf*9E(xPamjCuTpVN_Hi6)Stk+Jiz zh?G%OlIgY8o?7^ysWem_WypY+%DBKOrMCEkOszXF<ilCsT-vhUqQ~8@xKuA)7CJL+ zxZBYDHNffxy$@q=Ie0p5Tx!N8N8&lw@cx@LYu~9wnJdeN=$)c-OiqcC#hZe2wzfpr zwzbg`0TSv+61|r=WWd-S9zM6^6png*Z5~&sZ>1&H+-swf-VQt0V2=&U1<N5$6x=;u z2dm;Nm1xu+X1oo<Ldv-SB5GxvQYtFY(i<S7#%G2bzUz`f?7L;`FXGeHCn?inX{aDv zYY7m(?yNfRHIpi!#~D7}bIm=$cGJ#iZiA=m^hwFo(gx;&h1q~qS@dLU4;urys4CHp zre&$&2h&kw;=!-r&ObbFXM#LK`y>~E=^1s<V~Io=6<zHM^P})lvoms{gXNDrR_eW7 zEuRi9q`PvZ2Gk_ok~7B&`j`h~;(XVJqBxSk2hm$5Z`PfYX54T56Kyilv@w|=z#`BA z64NRICYdd-YwZ<+`}Yb};Qe{}I)T~l<}MbNoCUuMlGGw_!~5cIXtYMXFe*Gy>P>hF z;_%KIlC!?5-!fQd?;;<jk7|*Akx&qhD{G~SZTf*uzN`8@*_i3M89)WULqdy%szL?a zug<ui*NG7|{_>Jqs>>e&oH##07Fjkn$@NW-5zmOQHkVuWX2HZB`6%$cz?Z37Fc#xO zfobCOUc`rD1+cH*h;Tpsq=OaJ<+^={XvIhtsY(v1MpQR=f`yIhi9db+M$5VLJ=;pM z4syAdq|hTs^ZgpGIa+iYdl@g_ugF5Y$-V__p=4QE0t|=2towRQAZk@nC*C*}NZF$O z(UOBFkY$bEr?ReDR9q?O^49a+&g5K?1Wt1T*jhz2Vr0k-kH=mE!rSF`@0f?6sHU0= zTA6vqp%C~8NHzVn=j+HwiJ^DWEhhicvx0fI(MwGl&fI3U0hVb}9(-(^>G{k=OZnSA z&-jnbFksTuzK64XktXa7YbY`h7C1%Eo-%&>Bq|hHp<>;l^7OdW2UqkJ>6n6b-?R7S zehnr}$GQaOs+mjjSf7{(GaB74aAflo3nXXxB2IPr<xQWjsT$Il#;<#f@i-0XkZ_~5 z(7{13^w$Mm<>bZYV`0<;IVMmdv<-mLp@Q(ncJ*w0nqn`rtNp>(&B*(XjyMsK?$;<~ z$A|e}z9HWyYn}d$=3ol6|9X(8tk5-CZij}Sk2}-*6?wVOv|yGHg@>v<GNOceyU2SN z$0}<*ckW+3dy@hh+fYJc0-tfRs)PI1Z@r8YvK_iSL}Ix5;J5>zy(nN2n$TwdJr!t` zvV^!H*(b!&NINym)sy@eHG|q|j;(?pe_t-kfAHAwH-~x7TI+E0Sf>*bSV!%9GA9z1 ztW=-(Vg4p&SuT~AKFL23;q~K#77Mcq+h2k{BnL`mpDKuUQH`AE4DWyE7;2QEzZ_%6 zPM<7$`#^?R;1K|Bxr_BwlA$3ZUHB<=2(V$Co@BJzYmL34oD*X_j=OM8)ulxlPLxS% zsfic$*(G~sroX%)kab&HjBhX&3nEl7&*dkLIiAZYSI<^FRPIj%UuY_OS2Hj2*6umH z@Y#bKF9%6VJtxJ@mi@(kx-FgrVreu!dVQx40X!%T`Z+EE{`JRr`0wqjb{<$h_2IKh zQ^&KuPWFnt{ZcU8tc^MplRZi4%F<Y(K#0H;AiK6-*@B9<6-~|1u-yCo_TIlAg=eZg z$f=JWe{c~~v(8W#?N{4`X9ZQkKeZgg+1}lyq?eU0p%bV=J*!-IEU`WQ(s#MfR<0eL zCkWNqj&h~T)DgtjxX~?(>$Z*DeZc%V+j4KLcqNro$&_fqOLj++)R?Fc-lAWPGIZu> z$M6#{T|g}03xrIB!HY7LRTGDsysevu3594tp28uyrMy)Hm@dPh%9t|GyJ1B`2!iUG zlEih#EiK2Y#bMJs=wCs=8v(R*$Q>VEA+msoDN8s(5M-YPioxhbs!qpnffR1WslD7O z&K5FOyifitx=AGgu+a%kv}E{~C$}{Li`RVvtH@Yb!b)FD#;?d@B7n8J9tXGzPZgS5 zxayPc#+RO7pk5`yb2j6I95<BAHIJ`-9%RoIp^FPqsfR6!`x4-KwIW<pSSE*XrGO{! zMlhOiu`ALQi#$d^sxAueEI`NnfUOIVxi7-~a{c!M)Q9De9f8LuM#OER%>U64e=JpJ zu=i(}Qf_vh;zZ)aBFdWTaPaBqJ5K&dNtNe1RVIikxj~g`Aw=cqaNAMuOpTIs{9)d; zl3x81DNImlElDYcWQ&dN*Ftww(K`f*9skc994%=};ORH%Y!|fKYL+n;bn-5iAB3XS z;#Ia#rG&2ywxYcXuZjN9xgeRC#cu^z$2x8&8WU+tkZFlHQmllYp@wm=uPus5MKg@| zCXCJ%A27a+R-6|94i3VAX}v;DLrSGDgaO+L7QrxQf5~^F82@xdl3tecy}hZS>tOpT z2)C#f^UyKPr!60Tupsbgyy~tZv-l;9wQkCC;vIBC;Oez=h2~^<K!a8~{Wkl*SkDJt z^=;$_i<#n0U*TMb{s+5wXy!Js4PRH;D^N)>xYTQKs>I+#?7u1s7+fn-+^*Ir<Rwmm zD-pyZ{R8I1^q-}1ExM^qY+3A4#3s1W^PEifxX7M7evKhg%3N(+litOO?bOQX6`#x0 z;Z~>KsmT;uWvHY_kz{tDj@<lr8igH$kA?J0jbdesYh~tZ(fC)!kE0YW^%HZ*h?nHV z#5HtHt%}!u1u<Rp7<04X2TEKsXBs9`K$Yy(L9H!1Rrt$nYMrO(snioh*Zf8A)=Iai z6Rxp{9aK?v)3rK1HC?Q0=)zS1Ka|3CV*@@N;>X`XQBb?5Q2IhC)JD+arr0W%#8j<> zIq#i>!$mY~-SWTKbLE<d->OisJ)-SqKb{~)UKG|vXw72+4j6rK!X-fMB`>_@U0gj- z4L+)=?LpIpP#MEcI$j9freNbAIHTO}_S{(bE|YW76oY?59`P5(QDJkv&|QkF*c(@5 z8BEJXWK>(&G*jHYsa63JII|!V0O<j^9BXF{7Uz3JgCD7>+ixr&chbi%Z`@zPirl5b z59Ggw=<(dc$`)`-Y%QW2u-3dzFZ>*^9az#MYb!QoswG4sWl?MbFXuqdEBCiLw&L;m zfyG+_(cbgqPsqzS4bT2X^hB+60RZhI_{jEWv-1u*uNL+%2wmWGD`f&5o|#QPRQlQ) zJ9?T)>QfLEzx7RcsKg>p#uSS>t%uzWpFl-4|Fbj?<Ssugs;SFTtM}VpC2!jXT&?f} z*;B6mVpsILxswCb>SH81xGvqp?sx|}anrZ+O|ak#gf!Ff1;goHT0Iym6v=r288kV- z3m8&ojaxXM&-VjPb|~__q6mu?sI`y~;8;G`gE_x?QPo%}QoR0SI|P{7-S}0U_+XB$ zUC+ynDnTG`YzvP*O6FxQej7JCxNT%o(3d!Hu6<hH`e$&_on{t6%FS77u(l~(!#~zu zZiyR(7v(svcb67TuP7n62rUx?`NgscXE6t^m9Z27=tQeTiofXmA(tfMO@0Cvo~l7y zF0m-_mu}+q{xKc@J<m2TsQp(t=P!z?r1E{i`d%?m^)d3!QbSKrgYDzUpbK)6qIj*v zqB`=?##WIYUS)!Z(|x!T{tIbfS#lm5^JDZvMhj%NHo{|B75i%{G7NUkL+Eb?zl!)Y z&5xf#2_Ox*nWnxS+<8=?D&))z!==YL?8YBnZABxP2MqAWf~bj_NGKL&zNo9e{mVYB zdyg_7%GC&TXL@l}-JQC^r6IgU2|bQ6yzAkg5IqNb7ezAAR%)EvSdlp$DfYW}#xSs9 zo(Kof)QsD4TX8s#VfdIj?BF}XqBYIg*nAWb#fU3YIt&Wa!P3SEc-f_(2`Y+45G}=` z!u5E5P$eU&4$D-jQJ2KEK&c90k#a)ZYY0@ujnq^tH1CJ9eCvIIu%f`bwdO9d!K|c9 ze);Ww1m27?=Z5{m)9tY0O^fK!t&Q}otR<|P!<1^BWYP_tugR-N@l(XvsO10r&kHL{ zrV2wk6;OK<t*<^UKN*xrrv4xgSv_QcYxt&5=PQU8^81~zX@3=1DEOloq};)PX8FT* zFtT0^!gRO7cw4RNX*i%3{0g6z^Ag^J$izh<(1{{gW8oIP6H5LF+_2+^Tc?`>>T?u@ z_qa|lz8i>QPtJYTIrAwz+neinc*J&$Sl3~+gEIF`uC0HT5RVHF!kXo^XY9nIm?G%d z8z1&F^Y?6XkXE<tEVzOtyu?DpC$TsibQj0OWWpLbe7OHtJ+_RSKTkU|`=@(U>QGs~ zem<b+u2+ym12=pE6Sr7F3gEtzLzTWg;^TS2MlJ|()ur}rW?`)yw4_lw#UD;#N;EJf z9GRm0R8hz^spNhWD!ix{s5ZM;iCGGosg?Y<dbAP<F=U=yAULwpWr&3H1%y&zWhc?k z$shn~0V|TA1-!A#eenr;emLA`3TnbsNKp0jLr!nf`C}-8A-(GQ<$``$pkk1%<|5cU zRb)pZ_+uz?!*9HN^wyQi#8-!khxQQRR}65tl@s@()G>dTQ}QCs3=#6NsxKHIuodwr z=@PA+-!L$3APE*=HV@!oS{VEPe$ODixzZ&r>ctcfV!|x^g)KI91%IED0$2Z8kc!44 z4|bC?|LAXtQ)0(H4=*BD{g8Q?F-bWVGu)_6ywE!az5ych`#d<i_Ip=n;`!F*^gI** zyVj%O4lBNrKa(G9nh*0wR+iXfwtN)pf}dVzUTQgc^o|ri0p;l5Tr?v=VT%67h%aG> z=i^`Q*f;lIw14uS=Tj8kv{s~-k#tMVk!>kj!7b~ySi)r}$@q^n&<3`fdOdpaR!%FL z{}{>bJ=DLWv#S>td&tEJb6*m?2<p}Y@6th%7d5_6%Jl}`ro4x#nGIj1jz8&Sp7~YL zehg9dRp*|SW-(QK)KAQNO)K=J&=})kNg4v+s7Ln`M#WxI>N5GgU!6Cg_s~xpuz6!_ zf1c?4^y6b69PA_<s~t=be}(7x*un=dsu_Ru@7~+vkkY<X@!yPDwZCk$dSjD|b;#sX z+YBjI_^w*|F^(s?gcVI(^;*ZmHfzBmb$10~h~0~5om$=_>6SSY;q0}rciyo1ioBLg zQQO6nEAHqWZi%)<`NP+D?WFBef2+da=q7)-%qy1c4))q_F)ww`-U?56n02c^a*L}j zDN5B@N#^t+6S-Ri+iHKNIx?ucE4k_q{YJebacl721;1)0-juu0Rdx0rhi>Y&f<zCW zVX2+Njg)k^oxR2%f*HB!aCuz<p0=y;8860O3~PuNMJKh~k+$7AwsO2?#r2+>)ph5u zR@x;@+}(`I=Z`gw`OkC(PTYG8@#>vWmv+t#7OueX{mMN7;DH86fy}wD%y+ERpWe7t zvvGTV<6h6kM-NRf6ZQ)$(KIduTMQ5nF|9edQ7e;-0m7rO5(j>PRZ?F*o&NUeG~AXD z<h<_j<Mj9cYQF!O|9&X5^+Tp;j4&nMmVNQR??e9R4sNO6Oi(XIMo-6Vo9ZyXDBY&9 zrGMrJ;_#ysEA)|Z`dVH=MB^f~K)T@N=7mHB)fU1=foLJmF|xs#UuSRpium~JSiCKn zVZQb6mtp|A>+fvZ(K&%dvDFfGz~Qfbi+dde?y`-O`!)Q}u`*9)@blb|i3RD3#iK3k zLBX>mZKw0E`UkZ4Nzio3``jV)kKfC7f)cp%QJ07JDe^8XnDS-LcM1yP`c#r~RR@6S zNN@MZ5|T|7_`(3CHG4|?^p*dte3vVFE8*jCw#f0j^+SaiQV!bge#1zKimR5-$o-oy zuIeClV>*Ui<n_X2Oo-{Wh^CVrzk$WgwuoAzqYC?v`<oQ&tZ)(|mb_uY3fHtn6mv?m zt-*(?@nEZ^7EUZ*^O{^(#>k^Pvz_Emqty<_!(UtZNPAYNe<^P@PVoA<F47$8S`(cV zuIaPpDtokZY0k%UnC{pbuOD$&J#<P?`|qO+DW@kL>#v*KZ=W8262BhxRqYg{b28pI zX1VP|iOo&-j)>kg!CO}~JbIkpE@k}rbuRAQEc^Idi_X?!%bbeUHZ|*_B`v>b+x-pa zo<CY{(^a{*r|+EBi~rf5l<WMw=kK3Ao3np9>t8&N+&dxwGf3n5^n%(WN%Ko>ga|vB zeIe_gx!iIt2xc<vmwMV{)%?PY^~X4om+Jkz|MBYY_KH-gOpb{-;f9PwAV+_o-2?L{ zjAO?RbIp6!>QvscUxN(4M=sY!tZ2m2EMJgW0?HNmYtq7@3?{EIPN#OI+;$n?cU5n> zO%ZP5p-Lx&Ha>=z##g0|#f#<#Kutua!#-EHoLimtp*Of@DCe{W0Wlr@?W2kr3T{&h zmyJ1&X{N%CsKeC{p6m7%{*QnP>NGN+Oln>kNJMpkGN^E^_2%c6)<+u~Hxqw~f-sj9 z(sDJfd|1jtr#S_PDf9wnfeOj%KWUyN=vPCENejt>S{b4&nq1qH@H-*Zm&8#ub8dT8 zhF=#ZUznf_j@K4-WOrr54!Kn4p6<RQ`r>wiUXL52kV!$E4b*pNlQ&Lr(y~kCoi7fx zUaRPiCax59zR;s;#KO*fd3a0E^k>DVaigWJFWW;uzrOu=<=6U)ISQXllV7T!UMSFD zh3*b}lJMIBW<0&s?r5{D)9FLo#*-jNUdPq-;dXf?@>O=XB*%1{7XkzGOeRDem9>7o zTY6<@<L+qwp<;F>b_Mq!NZZLP)vnYvoS=yEVYji$<1U(z!1_Ut6`?-8M{I}`5f8=E z6!wl%64gA`IZHZibMMolZ^Tu{0^?Kx<Yit!88%ZvWJvMGmWL=d-IyTIpx<5=cC&n9 znTEX_7jA>0YUzQXau`<|AD=L_{qMb<IoDcB)rsmVx7kZqHU8}dS|cxW-T!j9n`o<j z3H9!}tIFLj1yY17ZeQkLPbXNgGL(MnjL*5{xcYJIOW(EVaHT7;&gN&?+s<Y^D?h#& z?6(aZsXCt@8%jbWN3Q;!>g$Oi2S|kGX6Ujh*<U3iQ6BJPeJI16vw4{&o6SQ5JFW%c zv@~Zy$J!ywRaveNHfQFy1~ERF7@j*2$#zLg8_W88X1ZDE&uxQPPF4HdF5F-&+eSCD z5n@OqBAH1xd8hj!XBXtf9`sI{$CTCwZqjT{L=-(`OmZ^%!-hfb#l2O$imDm4(VjcP zAJ+JJQKf#M7<5S)IJGf#s~r>ZsZVvzRmROW(j>sWR_+U@KpHM6boubr+!siDjyb2D zDOII^&E6*Kn5fmU0$)qaC?-{m9Ho?+$op-WB4F91h*-|Osj<R(^0d`bJ>MnWi@yYN z>YbWU$UB=KnRbr;-$>%UV<bQP_A}eosB*S%`u?MbwnOK5jqEDZ40<QA1qM+DmZe!r zYg;)XZJ(t3@de}sM84rdnv`Gt`yQFk+PvlUl4Wbo(#BXF;9!8<$D}@W$w!17T(;;} zhBvTiu^>6F9))afwEWRWEPnIZb}3Xq)v@+|ftD?SU$`&^o~V4~TD|nsCK5b<&q?8O zA9_`?Qf7@YA@);6vX(Z(A(vkJg*rv>c4xj_!WKj^+5?vu6NlJjL~d}9jlD|?v21DW zrpj0mDBhO|si5;<HZ{TiwjxBhTh^r=ZjqjJk(nT#N7tNo@3a=p-4w;rtUa*M{6uMt zS9^}JLcLzzdipx%CeVhat>uFhlx@KPP>w{`Jj$tCui(IEO=^`D<B^V9^-XnL0WOz@ zEtT-w*`8|vi6;x{J6_!2<s><g8d|whZZWMd+%WNdIM#Q60A1meCQ|lp)g&cBYc7;W zYKK9ZY@39Vt3IKsz4^$e7df{U^)jCq_<2rNvZDRvZ-jp8N2hQT(p1yH?U-l+6zsb~ zaY66945=+W(2f4~tLJuelb}Q9-PpY)G4*;ZlzKRsb-bfbO27WS;PVqgjvjT=GcJX3 z#za_v<0r@%oDWAS!MW=6+0-rA=#cxZw0`g2GDo4vG~GE%=L$o6gTX$X_LmPi<Mik> zDG`=V=WRWIeoSwm%tOnx=hD2;OO8O&9vOI{Y6*EL>aCbCS#Zw$Y|Y-O<-KG95Dvqw z?Ss6d7Rv2yCCU<UHttifczmtjIsir(u6D*?M{%WY@JyA~bI~t8pBQbp@MP?VTw*HF zJT}TD(<RS~mkP9VYI%8W{EpQF-&^wmK#`|({;Yzo%3ms<AUhaKL)6=XSQnDT?C_A< z{B}WfWZu)<gL31>JVQr@KhjlP(kh&j|2VV!#Gfq3S>@)g3s0<<S*y60(&iX;@GVQ= z$+OT;c^<GZNNF%8_}ZgO{$Rghs)&5NZbt7<g`|qKuA>*5O;UI=!@2~GC&~PUL89Q4 zxu$T#<jQH5<o5;mlJtsBOGJ1HXIQY_Y-r5`Zw&WTPl_*a-5T|J+R{mrKhc_k8!q0b z6u2+Um_L;i80!D986IVVi0eTI3tp!Y-^sxkp}g{<E7|(y*hlndkW<3fv%5Is**Z;L zg^gZs6j{sVO=`z0{iotY5g%6#EY3l#Gj7aT<dWj&=;#;Qd8X!ls3kx2U(`_hxnYuU zanq3eeO=vGaSBp9WE;H=R|V?F!wd4W>?Z70S9sdLClU|4Sh$$K+l6MW!u|6!P|=;u z-+E?Wgx_dqT<)sLkMZa=n0nM1NZ7n~?aTIOl#|h@t3V)`X2SS5eEu3CE3oTg-`hkR z<sQlJ9u2Ae=0^szT@U2MUiXQ7=gRtUg0!V@;?{H+MGe*9qo_m?gW?kR%InCT$Ys1E z4lW`R%K5dOSX!dIX3gkO^W5R0oYFP{IgV&73J~&2?Inq=(#r`+-$ZW@H^^BK1eD_f z9$j1&FLeiArW}cdgK~Am$w~nHg59(FSWgM6aH2ySub3->BGRRH{O#pe(<eV~L8yMv z*|;c$vnc;qm_#GwYg@u$uDt#iIH@&3aKDYCI7*!`lzs-+eTF9>ED?{r1ntR~m4~NA z5Wo)@@{euUK1ER9J56zz`bHsX|Gbl(6~?F`2@nE??qC#*GhR<a6B)*NJjtEhT4P(h zZy6BOpnnfj{x=<LSbTB9MgHk$dB1+nSqS>hwy-fkt>B>tye?;h1AVw`yoC8Yh0nun zcrkRNw^@qbWjr3KaQ^K}WnH|uM}lj3K_UHglZwROfC!g0<NFONbQgZlE$^yWmGczA zLi*Vp2FRHUn9cw`_Ml#40{eDAfs??KMIiqLG5l4vhrtfW#Jo;E^|CbTa2Ha_ILGE8 zqODypi|lvU$&7q!2^&%r>Q)k3*#bq{z*gb<^K__OkkHRIs8WMp^nk^TPH-!ozjf<^ zqXFU`J7RY&ZP^txk0F0_fqiiiavX-u;WODy7H-35F!vFkbx3nceum4g{CdDCF4#E1 zm;bSa|5?~{o1oAtG%qcxaa;535dSt_C>4(0#en@g`2TCOGBd~;>V+Kdi#|GlBNT(a zW3WHBvkrF8hX)4Qa@qK}D0vF=pSpQz;=e%sHb6jeDZZBv&%PAqR<_i6Y@aT$Mu9zk zBv{pEym^6MDB_@ZUhHb0iEpOhT?~+c0ba)BMzcYQUS`)3p+)zF%j$uAK(#xs^DggS zJ)~SizEmmKwwC(3;0G!zT5QXYbKz7)K_iS{mu+G5WY|7KFz$2sc!JX+T&k)U6uOYT z+zzS4^S$hqwzNewaLIjn3v=v(_1RRo4$DriYHqxRnJ7TfVnr35dW~D)R}}62Me6eb z&>KvF-21SRn*!2}#pk-Ln&FTKa4-`NQCzj^KAUB%s$hn^Zd+$9sw-eP2y(@jT4(de z_VRk-mAtJk;n<}oI1~_t*NcxgB`CX8(ksyqvcV_|e<N6r(N$2qzAoaB<a#!kA`pmB zZEX_FgafPn_?;P`bTP5pZVuTx8c#f^W0DmzziWq7!v0t>ZgU^|GX)D&$vG62PhP?Z zMKd7VI<OKheUz^LDu%ehhJ9dEyqSWHGYmu9q{HK-U+4gzl~-mQ2MsXlX>s)<enQi> zbq`GR<a1=3Y+$bz=$a+xW(UvpvN4g${^}d3@(^fZo8UB8`LCNOWf7rj3R<PPc*pCa z_p;R+6TxW{p<10=?@fg2bfAQt=+6t)ch1Ac+inbC5Mh3SWjdwVU4bFOmrgHv`qPaZ z+5oZg+3#=h`QmvNvd;fT3T}|W-3(az1)xK?hq>C#JWGqxAEs11|L$4uYz&a@qVj|c zY6vtfbrBs*tku6I#!9w_1M3EpTd^C+&wVY`tI!lb$WC7YDqHH%I^O^N8<>8}<wZE@ zCl@rf6MFAa%SPWd-dNy|y&H}zf-wvb*)8!fC=n3b__>!f<|_1U0rr*4_1JK$y5;qf z)r>edXggZ~f%H3-OyW5S)&1n8R*90?gZPI+buyBnQZO51sKg+IR8qV(4caCDU)VJ$ zj!r;<-(9OVkAc|5LhIl{v-qagB85c1#I!C$TR8vt5HC56*K%4>9nVu{T4u6P8nf&f zCBgv*y%w?_RImlt8G@x0=ueuV!y824=)Jj}%dHQ9)K|)$3&3m_ld2L(Q9GEb1M=YF zzu}T6twyO*Y}KDMi~MtY*rzigBEDvl*wx;dGTV80`A;WBsw>s3EA0gx{TPy{qnvHi z^-1UdvhehVul`KeCl}}&41LQVwm@;xC3V&Od7S<Su?iQefb%u@L0mH<-Xa9w(~rJn zOK;^E0)8B`H`U+YfqunY*kM3FEg%?wp7u(0v&_0vZlCFY@mOjS@#_cp>eVFKpLC7a z=i2@J7Pk=3U+91C1;;PARH=96UrgU7`@eRP`~C<w9d=RPQ1Em|&yQYy!_@mf@DMfr zQ+E=GH81q_cyyc85s~SjtX^JnDNly&jSQ7C-?mF{B#dI}jb<hIj|+QwCc%$W_^aT8 z`(*G9IxKw%H179w`eHW*&61nzd{8P;00$n1x$txBv=RpRJ{g$7zEZ*t9Z2jnOzAV8 z6HXgxRT?M~FKW~@^dEc!dx#e(OoF}7k(y`2e(7AWT7vq&F97bkeP#=KE?ihf2)^3l zkK20Ue!DPZ7c#S<|C8M>Fxa+~^KiF_emc?V%hs9h_pTT#sG%iPO&{2x<11QU@tRw) zU#T(hLi${2zoH!Qc@cE7mwyiqajoz13N(14TwP1Kue}73xd`3T0e^U(h33}f_XHVa zf(kZz5yxpONWNDW`1J5RiMtQ%RkK}tAC!5+%bWN<JrvyN6}-xTor$#7jeQs%seCy> zLdf*WHMU3yKQQRa@%y0y)#Nzw%D%%_=HoI?`VPXwvK|WtR8+}_J^w&XsKyArq4evd z;f?GCw-EllRlzc$kmJ5C>ksd)`M5Z_L9TQo=3Sr;wiiBd4TwpN#j^&v^#-^d!0m0< z1-=NTu>}N=0D(|Q)`H+?ox#=n^`CVnn{E{)DNC8!D>o~{X8aN=;S+BcK;Ol|wK_tR z*Q_>9Ru@)TDZjXA0Dw}Gp=@}H&L3?4kE|h^hp`w%PYTUv!Shxt-^$}lK5osek)E^v zk<BAKpNKG1;QS65hJBO?_gRJd-i9y;yBXo+!!)_92f|@nEf&F@ehvQw#?Lv7NBx~n zysbH_!-|8lAV}CW=cb&i|M30Vvx1XC*YN^}y-?dKXywJnYYVXbHkrMXZ{_C@;=)1< zBu&Z^dUi|T1*UR$vxxhuwo=@+pLim8_Hn_fnMP>$pc!lAsSNL{?pbTU06*{*KQKpL zfqfNx@?IeQk`%q#^*tW?4iEj~4%2PWt{)P3MnQb|(<wdKg_U!z#0Y)Y0Y?~LtRq{g zeYK)j^-QbEr#vw*zhC?u>(P%9^7{37?@yt?CuxI|HDvkh#>lCaeX@fN4}OdMeyGNK zCB@Z+FL1@i-{tfR7f4d?3w|qb1zT5-G;{020t_~N5&^pE&IjIb)W0=$o-WW&4|xWD zEAwyB;X*vjV(H2Y`r+~xB-RCL)v=I%QtB%Mblq=0!)fj-6|%J$E^58R%6;B;-mA(l z@p<`ak2VllIM~_(acZOxIf)p2l)gz9+MjuAYO&H-JyY-j`WY^G1wO<tH|w*va{sTu zgTFWHG0@9RmshsHiH_j3E$|Zclx4b<+*<snUgI0;!`1K)+hpizHcmse+U@nLeM2FR zfAscRwW%<g7-;?L&(nIF2rk8%2zNf?r<b-*P1#EGD=ws*exvBgRy@9xvb*10&fwdT z3?3j0c2_MwQeW}-x4}B;aNpuf$LTM=5hAt}UZD5MhsmJZ7{N~V6=S2$ho?6OFK-Ul zY>xJ9j?HgQ{M$Ta%Y1z$^EDL@zOgN<TJ&|M=d0>@C(khf>1PYd?T7`8&{;<6jLW;7 z^RNxP;K3MTPUibg!Se;T<T5|oUU9)_7s2MF#5+AQL*)=jdDsHI`^V)i;Ek=h9$8~H z5v(oz0RydPWSmr6J#8_2=AXc$bKuuzzSeb67!-199<$UAI}Ct6<2ovFZc7oH|1ss; zHl1^Jf*&YDCj2fMEDa~xuVtP#nExQ}A2gya2)(y(f2&4#$_GZ(Nq>qb!1#@rD!o?c zrZQBN%1n8@$`mcfA9%<2S|52459jmDH+-RE+cfL(jLTPgd`IZxuc((_9VHemhwKAg zPf{3TcenTtL-4sBo~@XF|4|Oj<iPA_@fAXi&_Cg+A9SFrcT>YmLGRfXf9a4tF6>-Y z{EQzop0ZO~J<yKl8)biAExK&YM_jFdu;~S6zh9otmj#?s-js*l(JT_bvF)cdOYYt7 zVO;)lp3P%DJMce>?!}*}|BnMW+srUC_nBet_xo+`X6_+(k~H^Al3PNm-E1SdE4M`C zmWom+l`)JExg_1(l0+f7^)0{s{(?Oo+u1qi^ZvX(&zH{F5+pEt($d5gIly%x)S7?N z+Ex$=eXApI27m5N(?wse)ucxGQ=q@|f8}H(`QO16SRMkBUNWt1JMlur21@V~o>g0} zzu$L&j=6@lj&Kzs)&ktQqJ_ZcIf6JQ?)p9TVx{*B&7SeQllZweOIX}((KcIDGl*I0 zv1FesWvm5|@LYB*RCLV_W2!9Iso8>DLyA?7JZg^J@VvKm+bLhp?y6@M2<g4*e%tPv zv|YLPH_v+4n?j-nYj!uTyfY8#FQ1lYp54$%D17TGXL}9)EXzzeZ>&9WZp`)e%DpPn zfZt3XVTarn-xvO}KSVn;#`Vut2}%EWtZ`j9oGxYd>Ad4f=DE+^=kMNto_c;ZQht|9 zDj<0^_9(^uv1$3@=fwA8{YcQr+t_#Y|7MNY<I#-|@ywjUCqF9MJ?g_It2X%jTP*vR zOXMHF3NT43F)9C8e?7qb?1nATREhU=bJ}2KX1Tb=YzzKZW!Z(FBPUv;*t0uvyPtEH zL#D<~{ET{VuKJkD_3*VGvan0<xEwDM8LPt!Ia17#qp3U7LwJ-*IY?BL!W0RIETzlk zm})f1LoN4b6>CDSGZf1rVM}4fiQQ?d`qL@Py6p|Qg{ndhn~uONH94Y_AP(R(a9!BO zgqi06KWKASf56l`rrEJ9)Yw?x-0YzHh(t#v*7Gq-lbZiTXy=R^Dpf^)DqTT!%s1Cd zpIUGFS`qU?HgZH-UH_|#n_6%~c?jmjK%0L?&F!{9B_GF!-D<z=E7QjrcchcLqrKcc z95x!;CwtcgZx6F1;^1DzwHtX>1YIszKxDt6@reaQ*v<2G63iQZdB@yLyufK+B+MHp zA}VRa3#^g2F%K#%zUN!Ll-cbvrE>2h&*-0}?lXJ?<_BXX+RsCOT#cxTGM&hKne=a) zZ!RT0xV=AI$0=U`T*eBvA=b{zWlMz7<+Az9s)L!3$1EaP;dY~qjk&+mW@~u9NqCu< zuvz=fIREo>?;^X6hjqmvo?(S1%>)T2TV6qCQ7A>Hw#XsXxhwM46|iYkjnkpf<DxuR z<h1@h2F^8!sajSW_q5=vsOj=M`-=2=fU?Y~wKNBmd#$~xy3Ok}u<*B;mb!_-PmP&x zoa8H9wA+Tt?oOWl2W^ji*>5ntsyigd&H@Lz!Vo8t?usH#p8ewbRxu;m0qL2je%*f# z%%BLIY3G?5&8a)v5Rg_M&5hJQ+Nu329sgExuXMk%?0NT|X~LdmBt1*KJZf&jUj6%= z?41n?W&y|0xy>OrPvlY}Q58jkO2KHASU5yUZDmRQ^6!savKLIXlxi}OatG&r9|#>b z*a=}lPIA{MVL~|2kgbR^wR2ez2T!>5$6BtZMs%D#O{{*MO>O?2mF0db04!aF&24z> z<RIQOGS!>{Zt3C@nu?;CeOPFU3(F4TAE7tD2!<u8e3zJ+w>N*W_=LiqU3qg*KS&Ep z>;yY|ZI0Vn4l|5J#5~lAq4T-_0FTeb)}mTvug9SpF#W&n{c^vPwd)pmme7M&hYP?; z*EhQoTGuFd53ZIyeUx>izY~i5ji$<!76^EtfHJ?!Uaya5YVB3iP7QWaFW0kkrQSdX zlczA@KCJnY1YJ1Ex=O5lzV&PHPhLGdKu~N2jZ}czII_<`jpv)Y;6q^9O|pa6JuHb7 zs5^&Vh=%$@y?~iF*E^WuT4&23{}FG)d~`gO%w-|iSQ5V%#10KufY`0RDSJ(cFt}sl z8sj@z{+1bG^tj74mX{==z1eHk>XEB>eX{baZKUaRms`r4tEext{VFYO^~3F6sK^4E zj;X9bT;~_Tca7ZtKkXjZ-c+?~8)fsZORZgsbYclJs0Uj>oQB%KduICwlU4FF3AthH z*|XV>f%^;9qp3P&yJ+W)Eap(7_szS!G;>G6ig#1PM&1<EQtWvzOb-_MpeJyV(p-t% zS@76sl{A~~%#Ha?mi)O%Q7Oj?oE-0y9>m)l*kH{phsW-2pSW>p1q+Q_SI(!TavL)X zYbn%P)C`&{WOLj^v%03JgyN2f&>;(G#^Thi0Tde%e~-(V0;$zC)>8?*p5vPtX$jF` zie@L0OnV>R=#Pyse0E|iW%r?K0!W^6@DNYx6}VK|FEUe|H|fT%K-!Fr4L3VEH#763 zqyKE&`DZ6T?ap*`Y6e(6kv%ri*y=u08fDf!VVsvNZ&p4V89BB^ztAX8$0@{}u$0eD zS-%ZC+D35mz4G9>rWS@wOeGuWJ@xoyaU1oe^?kT)HsAU7T4ZP!KIQjS<`jL%b%|rp z1k7ITU~-Kg4L2d8O1!-2!Ehk8WF;!J(i9IsklBc7Pk{knK$!NsHxwmyzA_3<hQDof z@TpyZnx~x4`=)l|(yDBB6jL2pOQ)I44Bya~0O)>P!jXN^{&1&4n_&N5D9ZLZe;SL$ zzgQ*a{LTU?XDii#0P~+==JK<*!R(fmj5S|DY;&$dZ5v6-dNn+zEy4T`-7_Vub+a5O zDTLsGq^jTDk(PV!UT5qom9__ChsEaVerDJ!HgfjW-A_U-jf0J*wt3USLIW~cM^L@P z0)AoS-1tw!V`gd$?zAX!<rjbZ_wYAYgI&n5=u-PM<EQzrn0_cZSE_~cMs(2LT-_Z8 zr%%AznTK>7@)BZ3W`4YaYqFW)z08javzrWIH2bHr_;n6-Aa%{cQ;YM|fS82bMEDZ& zb|=_!vqlE_x;FR8F~9CFeL45$1|>G<UYkKA@*ZWF)kN56v1?Pb70e;Fvu2pWa5xne z_4<J-o`h$2k6clF0LxJuw|3LzJztt9`${o|g{$f@BU5e^Y}!f<bAZ_Hu|T=I4a&An zz;BrW%PeIoL@5bZ?R9^pbELEX)X9b7A6Fgxs=Yyb;V-P2s3<;L!=v&{(L~z->B#E# zfV*3e2VZdXz3@Xj?`fE2E9pbrZ+kP$#H<exCw#6)<>IIV@0sKS{e*`OdWX7W|4~m} z|IY$xau<6Iuj(*2`r;a?jNb%LXNa(*n;%E}(EL;z1RgYkxoTDxE?y=}9$|2rixW9+ z%Q*HGk!i8}=-GDZ)s*|k-}-&;%Q@fw9eFc#(4?OF`JQdqxo7md*1P>QXUZxzwFF)m z+1f35_F?ex2x%m*B!tztB>dEIu(=~gUi;7AbB<R|JBtwM4xkWNIN=0x_X3aEc%axr zN1Uv=?$H6?qklW%5&x#Uul$Xa`}*%S#gW6BQ^7i7F$-vG4Wb-@syKNa;8|7r6kED= z8OKZB_MTe*>VMmoxtK;nU8>0@_zZ+*KM64`G%#hiZj^}~Z@r)HPm9MWyfjlWd;>OL z%}m)BpwSyMJRso+kTu=#M3JO4spX}k*@f|EY-O|UUC&GXYj=c2AEFzQs=?KsmElXO z%!=EUg+{uqPqbT_bP!^<<+xgi$O&RmG`!<78XQsz_CSLJ;B^<11P<qGXK~_({<<Cn z?nfkW2%UD;|MsW%e2WW|K6XOYn!JLwgr6WO(&4oC`E*%9r}8=vUZ4TwMISvgd7t9N z;{LTjq2lkpIAc?EaL;?BrPP{Y%c8hoK#rS0v+*N!!BS$@RWgQ<8CXq3TLX5Uk<=gq zc##1$w)&;QM(}`P-u4lJ1EDTJGi!2a3)!G_AchGvStXxc9*A4Fx5iLxQbG0vN@9!t zE7P81t2~@7FWpLCx^ZwFCxDK0LATudFER%+rW`Jf^mw@_P}jK3Q`Pmmcnb??#?{~_ z`_!aOkU}xd^Fz-thL+Syjf7C1zQS%bQ(P;HuyAnKG5TsL)RvbPgW*2kNjpETE4)1@ z2k0&$(%D32v_I9-U*`jhpQ}Q&Kh&sVv1Ira>I*$nodBFo)j3Vi^o!!Q_K?laXOX?B zmp3U<ozyT4HH>~kB9wZ75l<~TGM<~nS?j5%uTswB4~@zfy(TF89HX1`fVj&L%aefT zo`B;a2&I$6@5KD9C7?kgiOF^`=Sy?1a)r*bWw4<iXPi7$O;0|3RO(NOP@`}p1Eq9; zt~wyQD7e57acqPr$}uVm=bS)|zJZQTf<~!r(nz+TQc9Z17!}zkY3FnKHI4?dGEYsp zei+F#iq8zp0qSi6v{?WR7D;23ZPAj{@or|0z*1sa7VwVRIKZk=!cZLq?(W&>?ztQ| zV*F0)aUZCFq1|5zF%+UjV}K@txrvC(z*lYLxgNcVtC^(@JA&NaxR#vlOoLRe(;P$0 z9txWU`%h0ee*TD>(UW;Tl{;VW^-qJc8>kYj26ucEjoS+aA{(iB>hxc%4FBGwD{_5~ zKvton!pT5$1m*dA>adCgra%~Wo95984tE3x##1w9^P=+w?xnYFS3iGSkte!z^Y6I8 zaaLO#LHiTCM}6dYOlcz}ztLF*gNAF!3AacPn9pM^1+y?bWtd}ZTdtbw!_Hy*gOgdn z-r~k^bU&8jKCnE-`BcLWPI1d8D<c5<h)h54M^2ko#}Szxjg$jP@52f!_jrdxvV-9( zkUPBo;y8EUIL-N<x6>Dz%k<Qx`6;()@5=;zefXFbfuyxb(xU@U%yM7x_t9qo<s1>2 zLq|mZ2|(#L0Q<@}>ybH92RY1lnQ-}nw#P7b@>wh~mqtp;JeVVGT(HHo9!Z|W-ty?- zvNYj-j_KDsQTO=S@$a1tDG&;7Ju|wR<kzDjTUXpydBc-=l`UG9v_mn9GergNr6YWa zXlc;1+k**Dsz!za4uD}rI(P_h@UEzCzR`OEIiiu4)!m?2jx@=dIa58+T$g!X|8CM% zYA7Mk;;?zUwJ+y6^%7r6d!XF8C@<A}AeX2rXXYFAQyAhxzEivOdRLV}DcQ+s(%hOx z&TkAsD;HM!74!Js!h;;Dv+Tz~HVBezE7@UFCgiCMu6nNd&Kxihgzc08EgyCHwtHFk z0Ig^3O<4AA8^A}?1MM5Yvpe>cuev&Jg51ZsPPKYp(gA9>a-GEc=)<{eRw-BukQ{Mr zMHgu0PjMnp_M9lU!#~`Tn5nr#k3DfByu`2V5A>`*_iyu?yE~LHckbiCo)UqMiH_|- zsZ>LcnhS+0zCf^YDwk8iv+#LJ1SH@Pq-t>xh@dF46id=?jz9ZVltRx82sYP>?XJi` z5$=f&313%SRi$k7R*`@v2nxHZ@~l5CZRmAVjScLuFB)U)(aQb)88wNAdcRm|rzG!0 zPe;xMC7s|{Br54Ksq*e7Im^tFB3!DIPkh>L%NzZI^v6?kH9xrYh&+&(6YdWVn9sC# zdK}bv%4_-KM5$Nc+VsuTXR;hX{nV`EtPzlTk1ZZl1-F9xg38<rZFQ_c-VU>iS;y#< zV+6`^JjF3}fwi0^3N|fM0kxF?&t_1Z{4-trxjZ^E_ug}>=&<j!nNEmI90X*wNe-~n zw<-n6*7OWahiDF2>u)V;gO_x~mUNYt^o&Av>tDw%kb^pX59?m*Tz;@OEEbNYOiqCB zo!|<9%L%7H(BECM0*C1zJZZQ{HCd%bq%~k*B8v=4f-BH#-*MOGj)(Uf`)3c*t-)c9 zwBBz^*1OBc!R#)!uzx~dtaC%{jGip?+XOP2mclFFJ05+y<x*)iPO`H0{}`pC%Qk*H zNud&y2-c@MUE0LmC81~3=<3X7xz7^sXT^ozBnOj`ulz&isqyZf``gRs^o#CeD0$H$ z%ZzDfX4Q>TmdBA_NfkciP=G2LkkbST)$z&=0H4Yi%xnam>sc|@`f_RI>t*ng=5Chl zDi3y_(g7qZ$CHfFtL$g+$nDA7QT1anN+s}B6il;3hlfLGRWJo)i&hE&P&y4kX5+Mz z_-Tv^+1x+V()xpAqrH4ufa9hKq5fNa>W4HgxZ*uvC<l#~_hXiO4K#-4S`BO{e0rHh z4vX^d&d2{Xtsscd<`;B&i4f;muJCx0ANI)4x$7&=Q?`$>EU4yWT{aK7)T>}xjy30A zJR3f6233{Z-EU&9a|rx;zB@e0oa-3rxf>v;sS(STnEkn($XaPCuh_b;caL+y$2?QL z8`~Uja>L2);~tM<`cgY{ZYkL&=+M$vGhG9z0>y}g0d>uMqPl;TGqOM=zEsDWG}Z)k zbD>98e~pYPaQ1)uP^`piX`^I85tj-&&H*yCURCY{Iq$RkwLms1loc(CU6kFeq95OW z%+;7J+`@qzqvGn$|M;;R_ceuro-uj57Iz#0GKngb&jkj+-}~i+C~yGOsUVKEjl(BD z|D@Dg3qSE%`T1}6=Mi|5Lwu9-=h1R(6FHoNmOys`&>(TE+@`ajc|qFQM(%*|<wAu` z=-W+xtMCS|XJNk^|4Gw+ECR!;0p8iCJm*2fqsJ4U^0`K1p<g#88n%!f2>|XVe_w1# z(jd_~nJ*$LHNwmVrr(0)b-v&;72ThJFB+Y?ZuHp^K>T|K;KRo@$X#^ac=ymO!(uPs z1ZJ1iB1^e`!B2#gIzFG>!UWYVCP-2mDOnYmW0V)m#~yw$>HJz&XJSpZqbNwa<fH~s zw>Zn7lKBS4J2;0O3^*!4C~DOngtLw_#gNIDN%|^4vucnPyPK?&;<O1m?%>_|H@WlD zdk+WiL-PCMQ52W2J1$m7nI;%6zt738k>_1IfEACreBbVvS5v&klifMEF6C$bzD%)n zr#Q}&<*)$tT%N&}Z;|5JTDxDPwZqR=gL(9dxU`qf0lCxiL4uRinALJL>GQ>nu$aBC zUjM)zC%2scEn333&(2e1z%Eh&U{6+S!s<_}Ez{>s)Fg*Jg806b(ih_A-MvKm`AvRR zwNJjjPt?8rm*8M8IIbH^Rj4jefCDMhU#^M!dtoS|{JMQq?sNjJIVAScn`Zp1^Im*j zsJp;_h+`h5)HMW_U>q)f;jXRzq(Jfpye1!GtfytIhju*sw?sh!&t{WaEF1s^*3vGG zdqJ%<bNBhjXO3uMgK6ZihXh(mVbl-T8z9qEpng0+KMEkTNmRmIT%?dXXaEhJ=>>Bi z{nm@@FZHR+m`3VFjnqF~Rz4Pw0qTx_lpHTUcF1^a{9pe$K(7qI;u2usct+m^fEs~h z;QsUECWs2=VknXw=pey=hZ6$X+FO8ywZo~73d1&P5QdWW=93i_5>KZUSn+kWa>YU_ zF8chv{3Cak`rzJMKE*pgwbrxwfge*+kx4RgUGC!<oqP*F|9<=YmDF%qTdU~23`GHN z#Q*zpL=x&$ndoVi3B}iEo)7HryiL8<Kz+CAXwnG|*6Aob{=E3JKuk5w9l}*gOZ&}1 zcbm9vl5~`^fp3WT{US^L>!vJ|E+n6Q#&PWAogn1ZHk;Z^s+fWYVHwRs0T-zR^lB8y zQhCHR1H9i<W`X#T$Y66{29vvJp!#{pZ<`Be-aT}FHI}9B7biE>=-J?TFXnfQt$jd8 z;>Ox<_1V^t!9rIitDySW4df-H9X+?+?dJNdu2+4|$7d01KMa>>S|49r{3$e0F);GU z__C?sS{;v;lxd;dPvVEHu`g}}NdL9>i0vhda|h*H6ADvE*(WfrVNmm!s6wz_xO3Qb zjUOMLUikH6<IkQywk|07pkY*XdzrnwKKJ84ljIfA*JY2Me9wQJ<Wga;?N@Np+;n*E z{2zO*(?_V-?<}9?Pk$}`+Y^-vxJVsDod5YsJ>|^aaF&4$52o6_#9tU@;`Z3j!(_ds zmK}{u?Zan?2BgYTx59r3!1|?b$kK<hCPz)<6}Gr_RC){Kbkv(6If!}|qE<B?D#wos zE`_)V>1>x$5FwQ+12Rsf7>Ldbb6}28F9ZiQ=YCu>hV=<JaYtp)b}~yJFsh%gKT(== zP37&><TaeEobhSQm-XHuz2_Qa9%KfGuCTMqYL~Ke2%OUv;Q>+eawX{zg@uiyCxn%f z;D*(v4V!PE$}`E6RiqzHU8)Uet!>rDnru_GraR^7YRye?C3JRhk_3^<Q(^n5RF|W~ zyUInW55M1g{)u-;q31CB%>8F8&EMtoGTy|<Jw_(-D3WZCWd*zjCk{QjH>T!z@3Fnv zcg4%@z1Qz|?P6JyzHE?FvI<hjQV2!|JIG(f-1cccSbL`Z^6%jv?Vbi+y<xtfoky-1 z9`$aWK7O<RbeMw2K5QC)F7?Vati%`IG!b<O^yn2OCXGo<Rz7kw{IdMZ&hj@!zXl`x z%3ObxkNn@ZUaGl%V!yGU_m=UtV<OlcgdF8j{gS-&k+kUD?P@X9_-K68@Z=@KnG=)U z3$Xt1TEki6y^LJ#HV{vas!BF-H(R~jCiLnR7KEl+O6PRQIkOkVo1gLLqjCQ0(xcl@ z(JL%0)MB&x5!GTc@L=CCNKYUB1yFFp#eBhFI(b%?HVIR8?$?WyD*eC%61vzt2I4<9 zq63sB&lnWBI7Shv-RjXErqaLxp<||L)qQ-bZ%}?gtSa(z^IxOdD4m^&@2`9spOig@ zv}CKuvE=6Z4lU$rNLK&$<}S)u?q*dAy!gGMe*49rmB<HwPvmO!vhIF4ov1Ep+K#0w zBV{30=o)B|HANndwfLsnN`z(1zXaP?Udb3u6YCD>AHnA4Y>+~w$)&R|IIDC^TO_A3 z4whkpc^5K(?9*X2D;l0KPlbE37Qa5ce$mFCHeMq}>tX6ihZ|heSb{&>Jc60TmG+%$ z@00q0K0b|C=~s2mITKX7ID**Wk7nA$Dcih%KVENys9}j~7EZ|g>*4l=d=p4EJ1OJ_ zszYyS@?;zX>Xg<&P2nWT9W+&AmD7YJg+otN4_dD#Kt13~Qd{hzqYy-Y3o*xH&V5+x zI)jF5U4*0$GuFJtGiSJ*72DNCgyX~;bu`qVm5o5<jE3Cf86lq2^mhtvjmHo+tv6o$ zr>L`cN7SLZAHG-JkDQqYnPw~srK;eNN(B(d`R|u=AWBA$nnpdGHnX2ih1(hU=i+wc z%-)yz!x#(K3UAg*e!|d97v1yDw{KRwdNmJLPhd7EypC98*;^frxnE5|B+zZT+)Q#q zrJb}IrFI>uuPP&6XZ4O}i`1zw)mHf9S=Y`P@XBW|Kao3KIuRQMC4cxKX8(L*A~#{D z(V+p$g`Wbz%ULvwx%@n=Wv=uX>y2(@LJq!^D9!GrH!9q}ruwglolcxY?QiC&5h!2} z$epTQcYs{Cf>OJ@NDb_Zpn>;-lI0NHonDw5w#+H<C7;?amo?E9bG9Poxq48;UbD@7 z4g5!ICTzw!(`}w8<U?Qi8|O9Jt@otu@0t=<o7}r0&l%atCYX$A<IMw?e$~&bRC7uK zI4zbe#cp^sf7^F+$WqyLxGA>2{TF+4ha4&r;AXTuag^oC!lAgNLX=7pb3xw*RqyjV zSV*f07zlPe9J{2Ita@f5)>iy!nb4qV2C+`$rmMYPw&a{+x!lvT5T2IQ3g=(Dwdl6D zjwux2r$%(1Rn($rP7WEJmVV~~`i(GC2co;!b}cR^v~wgu^Gv~{%%vD+$$&M<&9g(9 z=esJeK1Z)mM2Pdd=zS&W34lx~2k6#^uT4nVY*T6h_xX0<eO8lJPAD{V@J;8yyY7_+ zPy#)y&W8K=Y>rsnJk2^|*vQCIuMo?1Vr{r{$hQnOP#khCF_xybgrFH&pY(e3^pVt> zd#1@JY|U`ujO530`|B?YDp%dUq8{C&8uE^updVp2P?PZE=FDLB0}V$9q!$^%r$p!q zk+lbo_LeiUuycsFL%ElCyzBX*TihF^=0@c&{1j8zUzx~JxF?uh2nV;n(><4=E|m9g zw^n3B7QBrB$rfXI^;f-L9$s=VurDyVis2uP5*sWT<UF}dSwcNS*lDK-f_?FF{Af-^ z-?I43nS$lw8Q-kfctD83hb-Y#oi_LDjH@T7aFQK?8+DTw-xMA_`#AYM`z$Y!ek?;y z<Sg6YfMR>1>;YG<o;U7!)D`yhg-+!`iza5I;25m{CpnuxsPxG?U^4wg)z5h4U)@`7 zX{=hAEldN~&;-nFvqp;OJ3ERh3{P`eI^v&1I2d0SqvOza^3PJ&^iqi2KX;01M4PC_ z+cj4&w2n)HtPZE^uO=7!F(u!r45C8{6kJ|ji^D54rCt)O)fuPfu89g=eE;1;x}QT} z=X{}Zeb|}5LcpZ={%WMLiLKNf+yWnM)@VC-JC4$aa?%Cg4DsN$B-rv&Zvceqs-Ir3 z13{YpTU(E9*tj_&%b!#V?4&(}x_JY{vy2Yk;H=sRMK5-$*RtgUN^(xN68WPyZISuz zcWwPAcb?GZd+Y>^G6KkzudB!S<?9nQg-PwRh!f`D8M!y?wjSvo&G+f0!a_GWFA#O8 z;F`S06~DQKOQLAK61UAkhJlikN2LRZ<pTb*m9<hA2Y{9NLdrK~3V!PDe0}}gL*Vt- zTGX_E;}5RtUX`0aqAR_+%cl-{FL<0POf65n;~}(3oI^MvezQ<*eo{O<dHz_TK%x=^ zr=M&i+0r|=C8Fz&+dm;@I1h4j?;HB!-iP7GVeHJNs#7X)ChfRC2fecG0EuNzMMtc} zI6))>E9lG+V{(3HgKGa-^B{s?{v|Gf>|7#9-A+^{-UhiztTcC4%mJ9K_D%&3@AFju z_$ZBh^1fLG{`{SdB$R>h21pcR(HMZ?f<JO47$lfuTvjtpnZ)?xe$M(z=mqv|xCgp? zh`w~9G&-=42~-%sSseM#^f4<<m}Ism%mE=l{B3$Q%YW@~n_vr|Mk9AvWIc{vgZw^I z1s7OckRo$YmMLebb8S~K59f_zi*b7BK1OH0%$hW3_9t#1pdr*|rp7hZ1U*wGsI0+> z`VXryHQ~GkDPThK|Kl{uW=PLY2+^^cfqg1WPTeTL@d==X3-0nMC*|%wlQ8%5>%DBw z)Wn1Kn#o3H@n!^|p*K!<++81}V3-fkRRF3ibK0yhlt+kKh)+_EoZ{Y`;)qYS&R9_p zQ6!%sHck*+8xkomteWC<^Tr}Ju|M%P=y-rhje>FuPS~R0@5fU*A;r=&Vb>Be*P41I zS{Xt|IX0rzSS1YU?0*%mVv0@6pIpXVz+7@~!f2jDbu0NmBXd+><L51(K#M@si2rSK zTLv$k0MX&RT#3WXe(vp@RGc9yCEiwy8jQq#>C<rRP3|-Kz-|0Nrq7#VgqD+H;V@Ca z*33Smb{WHU0RQxD&6PJKj#Cz$Ks}emuHS*4W79fvH)ok6Cksfb2KX7nT40<Ka@<u& z1wFq>H;kw~#_5DQ!FaF2kO>6p;yKNy-Wu8tVaNOQ_Bs9UTf_XFis3i{=QZ$&L33V$ zt|J*!+V`tu&{)LZ%pGW$W23zYu-uW;Mfa(#0<_#C_2z+E?B`1(DYcm-f?zBhVHMJC z6ht_%qW)oa(p9!`{vxf_F4dgU9Q`Wz93y|SaeJQ`y9CjPyy6nEDshK6=VSP8KrxJ@ zUI{>$Gf>6YyOg{Fsm9C|giMeK(Jg1^1Wr5F#UvT};b5{ihm2WQWQv}~pk!iHWqxUv zv;9V^<sS1Dj?3NTGCRS5VI2DhS9ZpkhXEymTwzUtV{G`29@W=~l8Yf7az;$j11;Kd zCLGrS^-gWCh9nXJVc^eH&lRiWYgDa|q#YMFaH_q71tzYPr$k(}<!n3=YB=E0JkiAU z!n>fGp$_jWp6W%zaV3y9dfp84`_@MOLuSdnhWXq-hnCEdIR2xVYJ(`6c{|xy1gHI! zYyl^mR+H=HfLh57^>bv4YG9Mxvi34Vb>2oWjv+qYBj&DPCx#X5{%Tvukjf|8sReDc zqLD1>@f{m9TF@k?@08M8wRRxxlIp2bjgLZvbtM4kd6N1nrzD1mVjIV3fP%{SBWV>+ zy}NysNfZA*Jy7pY)uujg=%hg)hK1AI2{&rR{T~@_v@xPftcH*0jLE~Tn|sUd^hQ;h zRFW0Pd;C@iir!=}j|TXJOV?VZ$w#?^dmqC8>+?3XWfhb0D>o;5!l4qUEb!#7k8xqy z>h?Yn9HxsV-GIW>2>rx*i8cUNFK6`AiT5l=)De3K33AG7w-#C_I(++9+->6;O*$LI z-Z974Jn1VT*qEzCf-}j6h(6xH4c=CgZlJPWBTnBMmoiM!XbD1n=v8YWU3f~;SO;3M zdFD<V6k7nC1z0)~n?LocR@z9TY6PFIEhKP?u&ixgDBCWseL_kLr6O)eVINrlm8aw) zeaHrEq;d*pnc8<GDmNT5(UEc=c+dH63rU7aG*cl86?014+9*I3rPJe(&iM@V$jU%9 zJ5P8i?AE>}1d}tuYNj2d0x?XW*;(>H6Y$j(aBD2wxD@v?E(F$U<4Yp<*(;jF0}aiA zyUxJGhqRSp7Z|^?Qar$nK=wQ;h&qu?Hb-m}1&F~Ca`$>yP2J;;!hfv06%Vg{%Ghzx z?`~;um6|ztpgKa7<nN7$K^p~x7HnQKObmsV_DX-a7J=ZjK-_y}L)L*5YQxu*?h_3C zoeV&wicdb9xZ|`DeLAf+>KOpt{59Mbd2SnMwMvF|+|yVl@%NEF^y*l(ZdmT<SY<H8 zJA1|H4I)fzOB~T&Zb6)>2DirAxrNzTDu{o;N}Df>k0`s@Vnx?&qyimuRRS<NpxQ4$ zO_f_FsX*M+Pvb5v$s@ksXcFl@Db<-Iticeq?fugpC;2(3vw4eK6QQhfS7->&I3&Fq zu$eOKGa_(hD4y!$Y9aKm{OB;Qw7mI5+1=VbQj?Nu#IJ7Th(yFamU{|=9dY{S!( zhtT0ZNl2erkn@k+)06GAgBb4|OUK)PPYa!YfIK<=_sz7%XZI`Uha>;AM|L^YqvSvC z1M+(uxrRNC_0xI$s}bG3k}eF;ThaueR~_=k`XO2dk1J77GwSYB&eM5&pJZ0rY`P3I zZ6s^4?rDAiTF&G2#%<pJ=+j&$tM6}Gw%pTTwpxB5L%);NI!S8FBz1@`T)Rzh?rh6t zEI&(aA(8WbK-hh0Y2*|Z;mxUB&8Zx3qfbcCN+FLw&M~`|sC{}|x+D1|bn>|ZK#Pf0 zrjwxic2Y;SB=<K}$0~wk9weW50#w42&>iP`5%PMZ0#yY)wcT*cs+@#6XrLw#woCTu zAm844s1O{N+nhW)LaP|%G(<u6v{X%!`(Q*)LndzIRQ|x<NWEF|P>hDV*Mv6h(`YG< zp+#2hY>HHJx;Br^4rD|qwSMZMb7|=mFejwvN6}FLF*sSreN$Z}reuoDmf#FCT2G3R zwa_@d>OQl(II~)u-YQ9xMY5dwW$~dG*0%|Lpb7o8346O~CB6gC`-;^!fIo|ADdd!x z=Md3IxM-tmw-_V(0ejImL3AA^v~P><b~0IBvRgeJb&E%5#t<qfeBnaJg)7FXw2suH zJma(*9cj0W(;GU{AMB+j*|j5W^q52`G+79PMNTb9J?yyr)A-6>$CX;+b!nGV+@DQ$ z05bR-D8RMXksLA50x0Z7tMo|_Xnee<Ogi#!+%7Y$dsouDt#PH(cTiEbqfcvuVN&^l zdo;27<GbifVtdq1W|T;lEx&1d-}{7zDKE!Q$(+)u;C{FHK=*=@`V=Fgmsl>hTRAY1 zzte(XS|bIWG?R%kQzX@HQW2CCE+AyyE^m}?qlYG2Gy=`@cg-qN^xAi0mdKXt`my5e zmY|(8FOA-h?OMIMm#WpS_JO3{8G|$1!Es|n_s^ye$4I->iTJgNP?+<VPAVRuCth!a z=vk9rc_-%n@;rVzy(u-5ts$$8B<r#Me?b54yuk5L)1JRO>z99mzvUPa`ZOXVDk5&G z#sWlLdaZJP|8u=IK*Z3OZmC@Tj3#Sr_%e;!`;M1Zh7IK7@HjK3`m1Y>v~x17ok85a zd_TXZGwT?}?^H}Y*-D9>z--EaA4CijM~9nUt92F1#6$h7m7u*r<3!b{M<sc^>QEs$ zq79bXReHlD`c{g?B*5ZjTE#Pyiq{A1{VCX<PL=#l>UIk5*MaytK?1!Xi0lwixp3bt zOjJHBjmoKn5LAvL<5-x7S|DT}=E>WfrVjI_sLZn}B;`huW)w-{h-EDk*!ySGz~gCm zC|BqD%<s{#5fvASy-)D+f9FU35rtI9#{M{qb{~t<zM}<9&@1$%Vxaik5?$}+u%VgM zPM<;LD%W3>IkwoB_s{UFoF`X<f(CIKENuRfp>z*%{yzp9Z!_0@qX3c>(|i$C#*xFq zYT`N3-3+vU*P?JQI)SXxV)M4pq^yr@5vy!DOYZ4Nv3}N7@s)j_=<a>AfxS!80Bvc0 zI1pP;yJeNkk7tOX6IyP6wN<(>P{cX-nSolr=TOVg0`+>TOjD-Vy>R76cedt?Utdvv zxvg#W%lOI_c^lc0c4fGYKp;awhXgQrxqHrP@0RiS*Zqtm{D|HZ<LC3*lEc%Hy|L0a zIi>t@hC9G-PoaOyWh2Y(j>T@bUhOktk`-bB)=c5OjS5V{0$j<vGe6jd48D8Q>qg6` zXK|m95mTK7p$>U6SiO<ma}Mmls7<~1(B=Xoex=jt>hz$9&gmDiiw2oRUWkgelwD4+ za#oYV6(+*<VevOlVY~iyq8u+w^z?(6;7fLn65VG`KbR0M(YR&$C~~3+cO81m;^JZ9 zx1#>zr%ydg{_<m~;ez(d7gr9N6CaCTSNCi7zU1^@=9bvN=^TXYq<?m(YG7U1ip@%{ zh@R(<WuBW|LRCSj*Kg`OjKA+lUrV0mdpq~V`F%&i`=IutiVNpHza(;tTUMqfEDaVY z`@KMQ$vb316|W`@6&1-;K@|g-bit&bpBXgqbAjWH;z}MXzAr5+v5CtqkImZe2AYt5 zymFF%EF5{|sAo5SDGz%%M82KaEJ#D`B3xFVr#LP!E8@V1O0{t>7V2;5$3#0+a7j{F z6&dkE4OLf>E*^Fz_G;hiM12%iD-yb+xl6GjL+p5FLi3UUJ|xRd`ZSm`LRB|E)_F)F zgf7dYJ0H~t^<r1o7yD5dF(R(rhrH4r&bG>$?NbR~#V(99zeryWYkM{NYy~i)ZSu#| zMY}K2WW7}zb!Po4CT8D;*OF^AmQS^LJm-;`X@&fefaVW0Imc_ihf+MnQguL`>rVT6 zQ>fnwZi{fzG_2WjclDX}IT4=w%vMO3neVgi9xiGcrUEjx>s-1&eVWLh(zzY9dHdE` z7uT5@-aZpriOJlz2*w{~!3ta|ZCMbZ=Az40ek{Ie5H$z&oRKF(JU7ZruWv=55+R<D zkLOg(m8<mYO=!JyGs10ELT?ugP<*4Bsm}{itzXZV44*xRjvcFs$d@~MHdO52yPA@p zG*<vFvZ}HjW+|2>dgdrBwl3va-QSmgb>k1m_hSJg&Sys2*K7Kv4Ys=M?i>GR+`a!| zXYp>7>48bCc3<GoWQk^A+Q@NPkYe#`b5Os=(W9{+js^w}?3G@Qvs06;bXcVDpe^C9 zYSco<Ibq))UEl6s6!Z^2rC5Y1ELh?;gAgfx8|zvhHowpf#m;v6DX`d-YEv!Z%%@9@ zl7C~K4%Lrds9X_HBt#GJom?BLFW*CaW^E<qFmRG*dUP9tsZYNtNe7Q%PD&<uQW`5V z3W@d7iBFwA?&k$~@9!5gRR=2*(WtP7%Gfzos2f4{4)SbI4LG-`z`Shvjys*vC_lF! zDxh23sdhI2{H;zRo!+L1JU_tv91%F4{Po_+-Gsbn-C0@>=lLf70T3LQISEdo$jRy% zWlPRx-Gum@aM&F~d*Xn8&9?y6Iyl|=2!C5>LXU1d+?JcJ0F?S2CHeBYc%PS4F4eF- zI3CWaZtJor);vxT?jGl69IR38+GX2{m2tl@Fw18>WJ7QAt(0z3$h$c~onlU?;uPEM zqXW&xwrmtlp|T&NxRsq(3*TuTV^3sgN)Xw+c*ir|f9Hyg4~ft)`c<P)?~v`FWrtkm zcS*x-F4dp~nbF{0WpdP@{Cn9vtj3p%OQF2H*^3~Rmh~iZs>F4rE#Am>hV&+U^2DZb zLD)LfwIgbBoDd-nREl@wHYiuy^)T>TCr7usk7!HkbIF@W@LgY+tZq+{7)yr77NdcR zD?L1(rJJ(L?0juuf`;2;+oSve{Y7JjlkpGqZTM3<S$Slhf`!-!W?9=}7EC&rQg<sl zRBvF~Cvr{W<)k;&SjNq=x@*yK4j&8c2`%B=r`(s4HPalSSq;Z87lxv@)1xqKy&!FT zK{QhRQ+9X3wRAK)R6A?`e$D@QC#Rl;+9>^E`E+iUtAKJ32N-z>zZ#K466v=FYu#@J z9a9@}O7tfQgA}O7-8Sm}NQx%C=B4*1sCbL5mlpn;Qq6Sub%+5HaIU7^OxIPXrx+im z(8=Yq)1-G}2wK~%RBl4qfF<?xX{G4q(~4{DqlCmC2M%|p!mhV|PV;HuEyyva_X@a; zQ)E&zA#!5ZAF|iKA!y)5E!yQJ)bn{<yFq_>60|q_?}UeDBL~!G6(CWYPrbCmi|g#a zn)+#;tm_T*r#)Vle4jrkSudD3=h2RB*|N77Z{xLms`=<#Xmpa`8yyJ=Q2H`j$UOv` zZ8^`$_cER)T@x%2l@lUiBPw%neWzG45DPnp$wn=^U-gIJ5al{#8JB4NN7j8BvEO9M zgPNxOA3C`?Ji3G5O}KhzEAhsC6_*gPN13Wj#&JZLOT>rl#<6^c$0;)|n)(7W5x*)~ z)?8pwD46#ym0U6I;~O4~TAIfU!U^Mc(j(|>8FQnDdb@3jD_z(2pk*vOqwRu%$}mOk zvLO*s+EGkP0zGKzYucCA6`y3vJ@q#Xkt;o1x^$54o<Z42xaC8vbR@qgsu%f%oj<!* z*>qSOidxhO)r1HN#JTTS{MLO`_#FsK?3R~#%Hk&d_g|!)cKO6LOTA-KQqgwG>0@6Y zgGS6PRtQJ0z>QY2j5#*Tw+ATQ2xY4O+XU9Yrk#$J5>en9iUNzs+cr*7GR0=Q1p<%_ zBc}r#4?l<D&l5nXa^l~RS1%ze+RsErsxGTCtg-ic#mpmaKN0iOS|)nrWk;aP_o{?_ zYsbImpZc|;5q<u_$&b$y_ns|ColARN@#*)Iz2{pu&t3Xi@%e8A=u<?vTi}1zuxp*5 z7W~ndbD7$e3;Y-MpK)QcLvAu_L_7BTb*mDtoikqo4HX++7o^Adr=iF04qSd{=w3Nx z!;@@H)glD*TJMKQl`Za%Cd6$emxZ2sMfhma=(9DKATJ&24vtF7O(J<Obt*JF$nq5? zHyyvZ=JRsjF&-~;*8k>r-=j!l43$5u1t77@x@DTWK=ZE36sc9Q*C=d_IaWT;dyW8* zF07_VD9G}cr)H||=<|l<JH4E3U$Y46nr<21zRR*K524TC`!<EdveL>0gEp1#3TEFc zXT(Q7{rK2?IT#k*1Cn7e7TKrkWZD}CP2bF%fA_j-cX5Af<Le5<5wmDKmH><Yz^{H} zN3aol+W1F#u8cmkSatBcE7oXM>aXLUF4RHy8MEft-1FYG64ncqqGz9SEB64!tt2RS z_zI&O{L23()F)T=U&>Fx0|cZ!-S7NCea(5X#lO8jKwH*0T$9Jntc(kR{?%!7in<S> z&vJ6bkKuXK%NfG#$;su72o+9=F&Hwx2H_YCUyf7V%~jn+^Mv&@E^|2D$Ajm4>RpIP zN1}*z&D;9yms0?l!$Ij-Sw={7&&uN6LmS3EqXaDfu2AWQ^eSJKy>1R6=5U!ulco2; z`Alau@3OOj{R3D#UK|iyv69p8xGaSi_&D{Nb5w`3LYx1D9UR0kMiKe10gnXX3qndn zv5_9=Cp`Trj{jiuAW%cmeC))V9^{ia{EM24j<3Y`YeV8}Bq|9A+Xab~MdvZbn;DkT z%9rmkG@Br2?0l#MTW%Z(X1BxGJjF`qxJh?npCBpypMo>jvC_L=1o&3Es;@pZ`hsG* ziLY~Nj=4!y6UDdj2=^w5e4<FTtQdsI^-|fXilTa%z<a$~plbQzWe$ND0N9DMdq%6| zzq?oBWutOjWnyczhTF6fv)pp2@8VV8ty35%mwO^ONUn9v?fO!s)j4wkeRKNzZGylW z8oEyq9uAf?;F4{wk@RiMbf<`oW(vp(nWGsn(mVvjDU`CrpNBqztmF4cWV5IdxUDQ~ zu39+k%S|~w{=eh07QIWI45az@uVG=?&5p0`(|Jec5h0wCF>=om)z@@9u1U*D9}-pi zGdol68bO5~v=f)Z*zX<-?2(}GPRrQstD@87RD7Ehi>~O}F9y6DIB$oVVKk(-MT~pC z9G8^|2!=f^K$zDcvTGy?@!<Tr!d#G32p)2ufV`^<y*xkF(l1<1)Vb2;;>+W@jwPhD za{tB>K7`3!9*4Zum8!UQ1K}bnoujLgbNqU1Zyj8}FiRh^4$HyA0<e5Pvyma{-nMEI zyDGm+U#SNxD4rEIfd|W_p&=mRo)|+=L>7`#E$^{?Wc<O^H(yq?vRW9#fQtm1?QR-{ zuOE!Hn&!Fu9h1EU;}q`n^wP6K9$FW8!<3h;1(N5b8iUip!R0LXH^X007*6zef=Elv zYjfRyBgFFn*;;rjOKr5{6JGc~Z4|)$aIH4&MUBktqW{2%sZ{bu<R(^P^z~dVY6nsh zYwuz(^>&;nlq@T?9VwJAhy=^>H@8XrDs)P>7QVj7Td2U#8!VC$3{GPRLms^R_ev_3 zQ)a~m^>JBjkwe#;xCK|)_O9uvyv8VY7v0A58oWLZ;X0$`Vxa3%W?##zK@`}x=6gdB z&Xyg^Xpm0bvbDc&rMTlV>S8*bj7fe3N!LG;=URZI5-?WVpF`~6z6@wK!GwRo`0dnS zqp+*Ylm(N4U~f&VEuqBNx8a&>&p3xoJhG}<xSnYBa8TqE!)mm6NNp6gEXxf-dlLzw zYgmto4U33}uoT(a@o-^r8hXxAni33M=9IK#dW&yT7K2OXWIuv_`@PbzAsP;CYX9z8 zIGrymW02fz<o$Ari1<|vD>l@0loeXu7PXg!Qr0eRdP1*TLt_cNm0MwNIAHk;LRy>> zyuTvqcxBXDuSoxr&WIqmE%4d+aM*I_{l@B@8Pe`ubG({-Lr0k8&1Q$uj(1i_TC1h? zI(;^^yv=x6`;<^Khk(w)F;V8x>EXE4;beacqoIEWVQKQl8+c<;hVf?|$cl(ic9F3X zpJ2YeXgcAzU5e=_(86*C%D;#jV<4**(hnIZl{Lw*=8%UY;&Ri%$=1?h6XJ&iq{w4y zWmhjI!wYNZUB=Ntc~#?GE47J+&*enca2HBPOR-X<4r_!dSZVqoR!C=Jgazn&h)sGD zH-z=yxXxOu9UG`Yr6z1lB{qZJYEX&L)S8I$1>yWQggq9zjQ=@bEzyVm!6fj8ab#41 zUL4{jf8j-WlQt_KzkM+wwMi8Fu^_!GEBXN>zAk#&k3dKng7Ei2!i}Bwusi~NkU9LX z{}gmJ$h`Vc4{O{J-?;U$18X#H9R(4QV+PmF2u&Cnp5uBPVdrbCDHJZc0HIFG(|{3N zoFcaD7jdjFgqF^CMlt%4;>`x>99d|#Y=BCP6uqwfz9WpV1zkn27z~O8UPX=F3)V`= zf5C|PdER>o+v%+xG`9Mvu12c7MxwO_VIC}G&e#YdCRi|p9f`2jc~rTq<Qy^dlg5+# zdIYQ6iX)D|uVU(xdw55=thFXZ`<Tr*gLt6d6;`!qu_$6`oAd_{pSOlJ>pJ<n!z$5W z>y@w<qOd~__>`<bJ`pixsCi~ZGRa<MlXGj6B(wHA==2Q&RE3esg9rNJ6NYqzYWX#^ z@3qt)ITtydiO2J;So2-=JNCVrcb_AaUr^rOS!ykq8BppyvUmLbj_VaKxc3wJOOK4{ ztDnOZg>7rNZ8?PwlMA>ds>Y4;4FRJptYlTqu|L70x7L5^4YsG)!rpL-um#{x=vPYM zKU2WbMIw){H3($Qm&5sIJtt`UkyJ(vZ?}lZ%%b#*SJFF<zzHmHT2!JEFa2;<*jHAo zCRnORmh#a^MUaFZX?)wM7i3^!*W;Ow1h0=X#%HIgTyIa@`VF)8lQKXc&Eti@VTnII zp}S)OZ>pW>fDAmpz<*-`tlXDVC#2kSO2j6Uw`8N(lT2?cN6f)hB2{MFR(ID&iYw(P zh0hlP_tjAtiGeAeF#x_-BZF5s_<K3>4tj*v=5r6wVsi`|e|gjz@#R{um&<;|(n{gE zqA*vni(iV}F7<s(St|I8=N&LMOHOaqlW4f1SaJ7>R1Q%9R&zGWR#K>~oxmv|?Ju$& z4BfRx8Yo}PSU`0WMSOZ|+*b<@7Yd$yldK*jn*@7a=9F>cDVeI#hyzQp;Y*d@5h)St zrmYgy4k$713hsI-1NdrOd6S=9<+JDqzBQ5)X%AoDe!J46N!$|7ULXl9z=Jqp_vdYY zma#u*hWYiR)i~TSSk#&!knVbO(AL$TN6YPkYr6MoDK8ljoL<Sjs9nw*iLytGI4op_ zL)Y9ZCij~=(zmONz!yc}aS7nd@jJ%#5b-HCPt^0&=?BO;a@*Ubg&wo+{)^p`T7pV7 zVVVyG(-qwkdSFV}gEd!QQ`thYEc{`gAj|CK?~5-tG#AH~WS-pL1!eRMu>ne9;pLj- z8Cfxvl|OMdusAt^?ckHnT}olzh6A!|&AAVP8V>!T>vOV_^kC6sBJ?ujzT(MdPbZ;S zw9GbN{{`xLHmBqqC+f|EHAruVT5COb_u!?#rD67NF*)W+<#)^->6|v|WZF<uC$0!9 z#njR=mK2ytf*<zSJ@<hga`5hKOBBuX#)rW<f<-{u0>zcpMZ_y9)FaeS*{f$yZavAC ziD!tqaY}__@n6HD%k3G<Hnm)#x|Y9cKl1X}6!Dc3cnBOk<AhY@C$N1E{>}MIcf!Ak zBo1;mGqcSnub4NT^D-vShb?$t{P-;VT9Kf%NnswR0Ejqc@|=Es?wL5?Ba?w#Jtr}? zf(nv#=y@%WQG@j7L-=c5<&A;YXX3>w<j46lc|Q;xY5->KqSqJJVUHrlIi+tic<O8J zKNG~g4H22I8Hg-OTW^u_9Xjfkm`Uhs8*KE6ET?+>_i;fAH%%1UMr+!NRQ3M{<OcB< z&T}*Ia1t+UcV4xSpn~53N-{R=7oM@gHntg3Q_L%HfvZIeN6G!Ox`JfFY?ut`q~5Qv z(>}6@nI17x@f=&{0NZuF=k+M<85fY6C__U_dnT^E6}pdywfsT%?hGA3K2Fz8%NI60 zFqVIG0i#TuzH!_aLWCz1j^9c;AXHI<q&`a4TW+gbHZ&odvFQ-!q~&UfI^ue4jBsaW zdOW4&Z<a+jRva5#@}vAyht$m`wnIojtOmdLFu$@cTi&){8_*)}*68&K+cmOKn_>C! zG~y8`%TS~cG3Gg>`iD9lED^9Eq!J8RC==o3bg&#B-h&B^pxbXOCJy};u#6W15!>yX z0bed{s9i2`z9HlGcJx;WB(t8jma&zqDW3XSM<n)$-&0l>&v3e>6pN7OLXdg1YI%cR z91zjm`DotT)e}<Bd3y;+|Jb}&vNFZ5<h0f{edN{-@*6&igfC64p15QT*Af)L3PNgx zFB4!|H8&O1P5Y1H0Y2$ct#4rOksPGgsHCk7{_RY7skYY}jxqohcB4JKCr0&M-MDzG z<r`L}Ft=x5SK_jBxp`LM2UY?4z38zOSe5DdzHR?<6X8>C=S|OV+j0w(7e#GmESk^# zT6MWNl>J=&Eq~ZhftOQxnCg9G=Y@m#FY12RVustoUX@#1HM$qj{_fw#>bCa#xvu0_ zq@9_2(%NBm2}*xo>Fdl_S<-H9PiFhKh14BFkJ9a8#;X+*4_QN`D0?Aw-9kE1UOBPF zfEIG|%#FNKtuXtdv1A9nTV@wJcfLKlARzPN;^F=ldlEZ+<K*+R?^n)#xNdpj(EFp1 zqQVUg|E?FEo_E%sil`d=534{_zveJO5`~HQ@#L8R;Q|B=pY`i4RS6SMWVyTLx~_XC z5~SF={QLXwzes=r4oF~u1|EoDf(kCkV1o`m2;qW|*ug^(iZ~LWBZ36MgB_D7$Ot2f zC_+dlI&_lAh>L_6VT&%l2xE*83Np$IaAgxtjymqhV~;-m2xO2#4jCj!IeycPIp<i@ zix!;p^U5F@CFF-GrofX2HPk#*%M*W0^H3~<wDXZT|3m`mkvQidgA7ja3`52+MhQk| zPUtW*)HLYqsnkw@1*Q&d&B)VDnM0OTjW_jl^;I=zJ_>21l1|!VTW`fhX{M0gmDecl z>_q2ap^oY%B~{oFOEJ(KGDu{vymG}KmSKU+A8?34g$-1gf(9H>_L0UPgnEM-G|8}u z6rbq0lMF8RBx4J1xFxe&GWXmv+&;40!jHDz%96`IzTM)=DRHb3iY&OaQqvsnRw2b4 zb%duy4m5;U-groemmVLM)WMz>WVF-GH{Z~g4=weq^Nlw~Y6@}068k7)#TH+TamEEs z$ioqWV7Q1QiX745hY5x_A|QnPK*uG9D1wN_|1!@^^Mf?ni0Q;S?>wYP;Kaj97^9RE z%PUg?<B%_1y|U#)z>KknG!G5Z%sJwGqp3Grv9=SOsN^%}pFaiV#60=f)2Cmfy2cYS z#IyrWjt~C`QZ;#@qf0&CRP&8TJpT>&ke1#UxXupO(@dLci^}-gGc7Yr6;(9T%qxKm zBIanVlH!FQVtgJ(5;5#52OPT)BF7)?nE6dP?bO3lGB80ir#fddYwaz%>*Fjwr{r<Z zFS_C8n=Jd>HoUc}ys?HKY@)MQ9$(~f2Om|Sfrb{~)eA&<Q4qnecu1(%9>7{u0ZvFD zanlY{3x{*CnT5|kf6eyak3Wova9qU4{}~E$gdNxc5;0TIhzPN=mc0yQ`D>s9V{|jZ z(Qks9($6-|QI0xjVGw=L2ts_(2P=_d6qhi^LlQy<DrAHd(zx2(9t9F`tf@^p$p<Ck z)EdYA<Qk$N20dzr6vyRI9k?Kd-mZo<A>pMSY^p~%ym2rJN^xg{%h?nq1(J1`BN<9* zoEJk?!(o`J4yuv^CnA#uSFOShk@<rg2N44$;6V<9xPmDLv5a$=L>%6zMm@}t4`{eU z7qVl`o}ghnp19*4wh-4XWbuVN*v1yzvIQ;fF&n1H4j=kJMl!I_31s|Y6{o<(DQ<`c zOz=SqTEHH?!qdHciH`|k&;lj^|JI%>XyF`Xx=TBd;f~dH!y8vDCd3|y%w*<oe-yG1 z$TSqd0T!@8Awn66I>9oRT}YYS?52Tk=7oO9<v-*s=YLi*A90vN9PO}1_WA$}Q)r}0 zrpQJy?2r!+Y6KW`I0G<%5t-G=2c1?q2|?5Oj!~e^c7~b5Fc!BqKEcBYk|+ug{UpRX zB?BGj;Ko4>x)N|GDjD!#2RTAw&XlUuoK+m>N>z%^Z?pp%iu<BX!Du@)R3QzRI0PXu zmqyGbBM*>?5-CVg3o0n#4~+<fG<?CrbC|;<<``x*PO}cmp~G74U{f+yu?k|?gLb%p z7bUxu3+eQRAKa3i>}I2k|28;*7|yB$DSELCW7GkA>tO=+!mvH<(O^9IV!~k25QZqQ z#}euZLm05(5psZIEA?2#SGqBu{k(LuoGpttKMPtHF|%X-3mE_fNWcXhkPuEFgvb;T z+Snp9f>t!9ZG+SeZ79ha#sESTfH4hV$N?eLz{VxuVWp$(!3j~r1U2|(uq2+T8^26O zKGcDXPuzhLeG-+OrV$D{&;wB2&FEi@vWjNZ!yCjz6FKb0sC7K?w)BNmOY2LdyL=-b ztMJK9|0|egc%lwWzyls0lLpBQ0v$v>s!=gVhaoJX848I~JEm%qaGYZu*tlRj+Odug z*F#Iqphh;pfsJO={~-*dc*Zv3A&+)QLmP;5hdpd;;~U?240<5NE{uWKW%Obfy*Pvh z*TYIzGC>PbV5NC-00b!0V0_qP0xsKAg)8);9osNRAKy_AuVh6We#5VsDJI)At9d}9 z?cXy`>!E2PXhemWgc)25+coQXX0*l8ng86nbHu|Kd<X*{OaX|DP-7Lyn34ydp$sKZ zVGqM-ht{|O#rXB;Vco#&n$$swQ_O)9K=h(c&d>>ZSTt<_9?UBA*4`K92vO(gN<H4u zFj@cE%=g{3kJMKWZ0N$j<}J2sbOH@S6obiE7(^OgH3(?Xq7YGPm6$kjM_t9@pM#*r zIoKP+X1FR<|J<<JHn!o7a>%0})F1`GIPna5V6Yq6*an$f_u+Va7{u+6#~U{Bk2&mu z$h{~yUO7<*JQ!Moe`P|GA0D24eW#V!(?S^j#Ru~tp&08h6MJFjm2*_1B)<0bo=+ZH zjydyx9E!7p3XzFIFc9T5hhUAuxsA^1eCH<-Njos%SRjND7}AJHMyBMnJy^jBwP*)B zyupoaghR6=-$v`=agKL@q6*u6D67{-J9S*c49AGap4f)bRtE+d&{!Q>s?k1N^dlea zEhx|LzS)-IJ*C-bM?{FN_QnN<6r*4a8i)XdFg&IhlgI-)Boi4@yrK_*00tGTuq#ur zQ0m<{|A&|~VkO8Es~zz$2Pg2Lo@bE$9G%Y5e0+3nY_x+LXQ)LyxZz`i>%JFr-~{$C zk>u=cugR<|J}t3_SS_#z$#W>iIk4u9ZPWuAc?-wL_m2IQ)_nU99IeNmIkJ+;`9Lgk zM9f&k{q)<cMiMMJeL-R{acDyxe~86j!_Wt4_<<UZKA}dQu?I@92g<+>AI2~_cQu{X zdGUZal~4zDzy+(2HV}mqh%^&m!v>OIC!msc##SfjfDB}!K09(3>QoQOU=Q_>PP*oP zw$*DbC^uwA4&Fcw)5k>}7<f2E44%*oi~$5`5FUUq3T6NeQIa`*U<Ow52d1EOdvFl_ z{}5uuASEBPPj@s5q<}q@zzGE?Rp6#RU+59k#SZ<T3{;>A@~{o-Knk27WV^Qvc)$m~ zryhP)We>+>claI1=St;M2UXx)@&*>!5N7D`M^F?JFj!yer-(GuW~HSeEjJ0{w}_J{ zBYl>Am*^k*0S<}cZ2$BJe1Ha0kVdia5Yq5e88J1=;0A9%2(K^=>`;K(@H6oc56dtL zt%M1z@D9W<ffz+QMnMd#@CIh!LwrJBIOu_MLJUwbA7t@y>Yy-VW_OrKjdP)Q)u<L? z!4l`dM2eG9KLL0;6c~n3c+hYKeeef^5Cu^n1!QmteE=DKpb1uDC1St|z_1B!|DXh| zC=IdT3&yYz)9_TW&<BYX1<SB+=Kv0!CKV`gHQc}r1t<@%pb2mA2Fl<><j@YJPzi0Q zd&_Wom;ih$76pHW1gvC-T5x<}zy+*yJsAgzes~GR&<xlBcSJOI<)96-hK)Um7L*8- z7Nc_86f)uGazTldE@Fv3$&_RvALJknS70>%#16&41(bkTc+dxUU<#xtknx0&)36D8 z;09-)3Cb{N!=Os3Ck=4JU&rVt=wN}@g$|u?25R62&M;mVg^W3f4C;khnl%#D;72G} z4_R?ARM(VEd5w!X7TQP>RaFk^&|e#PUgh;gGtms7KnnLX38Nq;#efWX|G;cyKm>f? zMt=}bs>yA7pa&^L2ese}&wvSt6$ZWXPopph?4Ttdb{bZ5Fa`4sKLd-?KnQN&26~_j z*dSkKQV!N|2)jpQM8*dqi3vzhOUS1MK!B25zy#Z|FL@vZsvw?u;4Y{z2YG-Bw}218 zbP1pkE!dC^SA{`|IgO54jY+AW5yCMZvj~U~GaJ$&kT7%mX`l!KPW_N`_}P@`#7E~a z3H4_szCaDSkPpD143;1U*i#v`R0m>!2hCs({m>8fkdHF31U3)@hPDjskPhkaVf_$x z69^ArBbTc{2WmhE%y5Cm_;op$L-4Q)&~TXP^OP!44l~9mf0RBe|G}V(*_cm?PE<7# zABPRhGNU;Jf}>zaY9mC*HVUuc2a|UQQ34HlKn$R8V2C9KNf0{g2nU>CG`r9b@t_Av zAOkV*10@gxNN@#wKnZ?834H(vc2Edz!zPp?4KWsD?T`+`unBaKoXSw5>`)Hl@G!P$ zaLd4{ocauv5Qm&_o#%smQGf)ex*bwLJ!EhPb8rWDkOy2KYUxP{t#DjBu@CJDR?tvl z?Esu2@uc~Apu>6~ZKep5011#V364NA(nPG!N+5lPi0>yqWOfdoU=Z8p3({~2jaG{P z^i-Ar2mkU0MivGR#|NlDipszYnji@MWCd2x37YT;d4LS|{{TJcU=PE9ugIVar=SO5 z00w&C3_MC~aM_p1NGHjF4fRkkUl<b9We<774(1SDBRH+b^nx(>FeC>*1_KW3AezU5 z6tv?BoH+`U;0bPHCttLgc2I=DG6<syv<|rZBEaPzP|Ja5<0zVZfcOunBvx36hWp zc3=ffU<GdA2X^2Gpm1Zep$n9d45z>gpP&hv;09`-oYU|R;(!fMcW!EO8uGvioDd7W zzzK&?32l1_hfoE4a0nua28lNZTmUapa0l?hb!l)1T0okBTLp6<YEn?ExS$Reh!3;? zHtJvx_TWjR01d=a4h@rO8B0IVs<{E8a(3XkpWAW-|GK%*nxG3BtUgH<;m{6~fDPq< zj@#<5j<yj0M7yN;490-F`&JLI$PV)0yUH*PuP_Oc@CNa!2FI%gNoxgaAPS=34A(#p zbjg>!NWInTrLQ(nb_WvX&<?a<5AqN{ig~)!7^UO;Q6%RL+<2vIqB!}045ZM5&`=DJ z;R#vlrGnuTWzd<UaE{2Z3V`4XOSpulFu=fID}8XXa5xOSFbX}04#U8!&A<$`unC%A z2YKKIR^S86i<fH91Wj<faexb(Fb)0C4%(nw;m~;>CJvP238df$w?GTYFtwL(387Z6 zX>ba^a|%*`16!b~cOV5wupO=nxLN?KcMytm|4<5AAO*-^tAL^kpJEi(1-U~?4ed}4 zhBCf)H@eR{T09`eV?4&r`o+Uqx|nNb5Xzj=Knkjv4_UG$vWpP%G$#Az4cbt-;J^*x zaBk!Pi)AYh(Ez>h0KN1u4fLRD(pzd12&AJDcC1mkF{nOv!$iq&nAfMq^|i5^tRpD3 z4dB3K*i}fYFu#j|%FsXxhuX4zA`^RJ27Ulm9AqVCpbi8K3~&%nrtlefU<RKM!J~jk zg>cG?p%{w+!IX0i!XONq01b(($cqd%%rXpB^KBp2gPuUcv%w~(06oYs4B+ez!!Qi3 zP^+Pq2YC<&K>P*UK?Br-2Bb+nX#lu;|C<Llln1=f3Wk&qw{cy5F(>u_3drCM@-Py5 zBz2ywGiOY!kl+VLa0EdB(GnfeM=(GI%Fsxe#tKbA57QE?J0I<ENAG|Pe((+xdNdz2 z2vGO1Nz{-f!CqJs%II(j$#Qneg0MfTu#DpqxBw63;4sySM2V6Qwg6_iCO;f~MV+kB z@MpO>hgH~s442>uo&Z*&Neag-yg;E2&A=1T0J%)zNyuOa>L4ZYlsYACz`OhzhwuoD z(Fdwh3|tBig;xy6eAlRq*Tb+FEPK;Fx>cZ{4&Cq)tAVdL0XCF?412-Y?Ar=<a0+Cg z3OoEedGI^r+0I;-2WSARNIVCc|2?>ijSS16uk86&gM<s0Kns_E3#n}nv_K2)K%vy& zIv6Al51Z6V{U{lIpcpbDiXaFh65PNYGQ4e|(yH52bU~Al4O_eo{m2oqk<tl)5U=11 zR)a)E!bghYNj8d^)|;?_7s-IxUOUn{+RzSNb!&W-+{MJy?Y$!^Aq~K=CB&f0h0q71 zKn&fg3wEFj&$3aZu(Et|8lGSd((nq~W(rB54t8(|&%nzddQ_1I2(PdhukZ<p)0xJs z*Bq`G$IPXmLTvfq4z{2QxKL_3aS6X5+TbkO3>F8JP1&qUJ?Z=fUqA-!$OY*MxOfYz zlrRjRpbNTy56-b0&mtSM|DoiwksJ3w3wfXmjAq}|(3TrkD7}>1@Vz6(y`PTY<zEiw zV9w?GxzSoqKM*Pxd}I#wuo2L33Z}3n)crxgKs83H-A6(WA+{PhjdnWy$UT8b=-|F@ zgIT$K7lKGv`LGTSBVA@bKkp6SMsg1Qm=Fp<yURe6l=BLF@ec3ctL;Fa-*66)aAM~W z8S&&8cHj#<I|-1nIgwF#ih&HO@(HM%*Box^cfAY6@WK!U4-<<EvmrZzewnMV&n_<7 zhH(p)E#tpK2EUWUs=5Wz!v*l12i<Yc%O2bMAPbM{?Mn{sIc5*|fD32?xt>G}&4Avl z7lV$@BV!Kl@veTz|LyL9gXZ(mI(tJ6&2R~MP!IlhbOup17)v)Uq&1gJm*oZC3tzpi z;lJ;&=<$P6Spg3Da0~gMg4N*E^&U8o-rh!14hBKTvkQ8_5DR}W5(@YYQl}=&tt50V zB{-W5aqtO8_3Dpt2%dn-T#5~#fY-Nv>v%1{yzY%TG359Vwc}1meX$e%8qST44yQm1 zzrgILMA<=1o|QfAd9Vd!5UWx!Ju#jPzW@`ikmTWx_DVkPDCieV!D!9ktNOw5IU?_M zZ})mu=5xO@5K0Yxb1>d84!0Hu`0!6um=J@&M=RJfWVTL|c?k!*(~<98va=3)vx4$N zawnLA?7%vW|E~8s<MGKI5=lx5hHv_Hj1Z-NVMl^B_fBT@;0vSh5V#NrmjDf%@anK` z*LOV%i8~3nj@QR5{5wwyYljOci1x94jL`52doc{|zzf4rwbsJJ%?_(I4y(U2?NYD> zUmyh1t_x&O<ouuyQJePXZ)3rJ6h&bVSFO6?U=HbIFlK)D^>6>)MDL$JF?_$peghEY z#CbbcFPWKUrhxfc2+Y(Vf#kw{`xegPMT{BAdGl6J9j;{RM50qi(qu`LCsn3oxzeRb zd#j+;E9Xt3MRDRRddpT1S+aWHs^Qd`(dbd6NtG^T+SDmia@qdz=<+Yy&8JzlZbh22 zTsUd3|4b?LRdyl6vS}U4iFNLqxVPcXO}Z*hU^Qv6%phA8N7pM-qy_~ROsW{PV#OAz zgEom2;>5*>MV>4<aphv3kmYly%bh)Up+$$bmkgOm)aXv}LdJSnGF3m5{W_KB)G120 zZ%eVA=T7h1UsMezV|zAiexOG$XU^OnEq5bHj{I4yp4*&UwQqO2$oqHj;l+<9U*7zA z^y$^FXW!oad-(C?&!=Diy`WJqs%GQf-~a!nwrK~FtBkVgoqBM&WRO2%@ntMed^yLQ z?6jh&n|9v$=``tD^6(`PQ5z{WzVd0O8;WwOkeqU=X~!O1>dB`j0Bf}I#*3udVLu#u z|ICUa7V{e9EVYV6>%mccX=kEuwwbHIw=jgpj!$+$2MRl&DNL|Y43lh^LPR2El*=eH zGcwB(^W>6blxvPOT=3}-lva=#1{r(uNamho`m9YiKx_NWH{VqGA`ev%{o)IIJUhh| zeBPAwO<GtI5gm7sY33XsJ6*~?P(u}UR8mVd^;A?-{SLnuyy#~ea$=QrR$6Pd^;TSS z)pb{1dyQ4DNvJ8O)^hI32bW@+`D2hlVyWgF7Ja3)Sh&i`kQmcMf@j1KyZvywl8`yA z9dNt>r&x3a5(k`~)VU>}b*d>=T6*iX_g;Ks)p5Uk`}OzMdC55^n?cMv^5C=>{{p6u zVmRICoJX?pCMR#!!Df|wM)^eCI8J#euvhx<Brz>L5viF^UMX{B%P_NSlrkcnR5V<` zRR<YeTubH_*?#HMwm@&ogA7%EQ$>p5^4KC#Lw(lA6<XY!dD7CNL&;KmE>R~Qo5l(F zU$E&_b!@WBHv4R}(}s^#SGV!>ZMZL*iyEvls-~KJ^0~#Hf24VqoNom3&#QLwfu=JK zFa2<Fm2Ac|8C}#l=NuHr8K*)O#i<6Id{nunp3LJGUG#me8vXR_+Ho*p*3TkRp@QqN z=t+sZ>Bc7x;qhdYd%iG(6u<_-L*>d$MyDBM8aXpfGb<zJ5}c7CO;UUC|A{=cOI*X{ zls@;I?aw@N1N06ucvB^gJD8T@i&KV6#+6%6nR@=vuD4V~WIUnCo6~(%`+ooiP=Es@ zAbHsKs{SSLKXdyEQr1Bbb?^fk{lEq{Y?PC4bfX;SC<it&B`$l|OgbP!hX@&i4$~k5 z8u_TlIxqqba8$@56hRO!>`@OC)lGpr^p8}iVmcne?Hs;%1(6!UI)wRR5XEQ*LFn?8 ziM?YL9fC$_+Heawh`|qJBH1KHaW%&*Z!%*<6ErTd3US$iel{FY_V9EHT_mG3zu;4C zfOeZX04fh(SlZDN#lA%C0~V*a$0?*oznSU69^AU0Y0kmFApWO-|C6L-B`tZ$_8ib{ zk>uo3oD?h_UL+^g5Jx@g5jA-T3vfl@4hEwnmvi9F9>my?JBWb}Xq-$Wx!k2XnjsPu zW=a?0LI*YwRE|xCBXk#u)!q7m3wH!%D4nFHR!Ya8YW^p4v699hOp!#_8A&01cttzL zK_GRV10Ea_p*?Pq21Wp45X2zGE+#RFVvHy=kYOI0(u54?iE9;#oLSXQsE$=of)}re zWB0oEr=ST<eXc-M``YIUS3pjFh@_flQgc6b<O3O?2+G7*na!qPQl%?pX-m_lNtDJE zSi<UxR|KXvWb|VoGQ40o%t4S1=7TXCLk6Gj(H!sD@)Og!|IXwxNRf&p#V*-shdW~Q z4#CM(s~NfGR$D2KShYim;WX00&SHu_P@^4>*oHtL2nrGPQY8Gi2R255Mq-%kQqVw# zVVu{pey#$I;sWR@q(&(b4I^hblizW=caJ*;3Q_S>g+(h{S&ZsKPoCi@^`Obf#*ySS z;Lt`nqUu$oxKy>PWo>KklOKMCO}4Ym*GzdeF;nV;A8NH-tiBdDyNIJ3;BZkp;$e=w zy(1s&c!x3Bk+*y(w;k<>WfLV5Tow6tSh8{}HDvUzSO$)^<0Wsu!g0;=rgvAx8V5MI zaSm^m)nG_uh$%=RjVBJI9SF@w39p74d+=j#Lj5SX|Dd4=f4XdCxEL&9*>u?D^r^oi zS;aze0TS=g(Pt3N4bYfoS&QC66|lH0E!x!CH#N#?j6)4FvH=&cs+YX3rE!gI%vzYD zHj<yD=~9|mje6L_7Wa^bJhTy2o_-Z0<Pa`JTI7uug@eiFx?458LCS7`bt|T=hCK42 z3-5Nrq&nVeSIMlE%$cJe%rc@`(Q-tF!~zbH$VRaU0*@&&@@nw7$37z0U;loT6rRu$ zWd2$v28%0&tH8w}mjfEm;Nqiv8HPK!Hyb{6?-z*z6e=bQ;>wEH6~j42{5XqZq!xH_ zH?xkIQ*=@t-&oeOru6_>#iKLxaBiXOiaDrS{||RSM;g{0$OTVI5v9B(b3Db|Ni!!9 zY5*A;w@^ntxG}6;YZblOW=iJX5;$p);+sTDB7K1oi!_{TAh$z?e^+u)b=*T1$q?#E zP{Y^9qzN;`*hOO4L|DQKc2dcZ6aH3%4DQ{dq28NKWZPHK%UU)U!wI$g9F6MHTyHur zNew98u~S%+*%2crdC5(Fa+IfB<tt}-%U%9*n8#e^GpBjYZGLl{=UnGBzcmoK-M?Ks z#mVN7hBVZn4{FOp8ZTbvnW6fPY=EO5(9j1hSg5>TM?z-=Uego@`~0k{Yr2Cc@wh z=LZ2J4WwwtHf&c9zJfNcAq}uU@_9dK|9rxqESrpA0UmJb$uX|z$eufXaf?3r%(0NY zBPB>3@%F*O75gZ~qaKcN=X_SxD#;~DFjkYT$GX;|Cw=Kn)pKlqU33g|N`=57uyX`h z7x_?nH)_;u+!tk;yH^oWd`}J(rScw<ZlS!G9CFon{U1B>dGaxm`)<HD7G$Nbk$?e+ zJ}7A$;xNZLLLzsQfD0e{;0HS3QNoju0up7~cVqw>aDX?uIWRIIB|gC#T@doIibn-R zPZ0;mQw3MZ1<JdHJP@(=xdqHy4t$_D$MFymfd+O62mV1m)G|E`%s>rv57cwMxCuI~ zh!qQphZoTYkDIPoQl`LZIv%Q!{}jQtq6@ZYY6ooyuG8|sAo4mKJPH*lhi-DSH=C~` z$-X3k76?k55YZ)kxP^NliESx~W&i~*VVT5u1;YC~zTk^f6Ac*oz7e?@UAPlVa}=M+ zw4c!pQoE>JaD`HfI90fXj#<Fz35f?xLSmQ^Z-@(S+dw|-LqGJ69NR%3VZEhjwpZ(h zZaA)c&<8&Ng=VM+r7H(>2pnpv5WyjbB14BEGZAU%2CZ8*K};YW6vSo2pmT_YA*sHE zAva*~gRvL{*(n#eTcpjqA8fD(eXxaF@Qh#TFF_!l<{=qIBdin>mrHoG1_T#n%pP7? zsQhcd#Cs^9fjG%0S2|I1366T`gfQH71GMSBx1Y^Vuj<2FV(M|4a_bzDbwY)5x| zM|g}!d7MXjtVesiM|{jjecVTW>_>mZM?oM3{rHC(EJcGnNQ6vCg<MF6Y)FU9iFU}Z zhg`P6F$Z%{I(4vzd*FvvK!>7hyNL`*hnykXTZeX#26WJcChUi5a2t_)NtldDnT$!P zz=8dkNu12dgnWx}XorF^m?JtnwE%?ai-mH^Iw{!<cN@IaAc_9cNTkz;(<lZ(D281q zw0>K#1_L-oBZldbG{qT-Pxu9K;e|X=g~w_vR4~B)`+_wTuu`Bbi)x=ZT)@(>g%$g# zxg!Z)LI;l<h*#4||G`AaKP*hc96e2vF~v+T+p3pzVK3o|7kQ8oe7Fbb@CA7=tt@+s z-=eMG!im5+Nnq%Vd$5OoI0snCiN#z^*31?3YR%S6mvC5zu_`-rGZH{Bi$jnQ3hW7J zNQMW5z(CuU$`mlu7=>6sjC{k4S1==8prx%`g*GV-;QT_zxxdzEH`s_H#Y?<Ah=T!C z1$_Xu1oWdVL^Y5IOK$-tWQfJigiU)nO!=Ho*Frt`yw7`S%zjB1yNJGa@G^JMhh*3k zd7v&7iLvquhi%w~w>XFCYKLlwg+-*ddN>gT#ZL@X%-77&^rDvFI)`RRMWK{0IY^6# zz$SChhIQa8|6*WDjzbA-_$7_xhd5Y;#At?<!Hh)1!edN^r~$OiQw`Q=M%F+$COnR7 zbcI1`A2*!Kq(Msvn;Ota2F<I(Rm-K2s0VXVO%4?s`utKb#iR}l#U3F<069drlZJf2 zMH4IrY^YFaI0x=?$(mw8DN{`a4ToZJ5v7|hX!z4l;0JvOseV92P$bi88bw6Kh$!*N z=|dv4Lkm18J75@uT>u9uD+dgr26ecl4(S&36A7W}vs=IgPnZlGWk2T>D8ljs#H+Wf zISFVWiA(r|I~j&sEsf#WhsomypYgCJt*kFFz&wajs&NM@#Rq$sFc<ZZ&dUejq#U^T zx__)z|7*QgY|U0}-BxbxR&PbefE>tz987X8*N2QqVKLWO8HaNK2jgl6e9(tQyd}CR zvLZ7rw=q<>h^h-gk&5WPSW>#8s|Iz*lw=SDK_I`<d<PQT2L3Qth>ci@6^ELvigBG- zj8#ae5(i+Y1hObMax2j{+sz3v2TcWsdT0jIP)6_@yg;K;eh@Ifiv<UX1sqKVJ)tGY z(FH%?rIZL&k-&z0=!H)(ysE2>eUOEH*oRvv)$T!s%0iTg6ESSG4P$i<WK9MEUDiNT zoOk<1d+@k#3%iWf$!|Sdv`t&JU0b$o+k6aHFR+TTo!h~T$U2)?iTH-;noM<wR|S#R z|IhG+qARj?SO<$Vhj%asfq77Q00wCQhF>bGd+-B4kXL=c2Wn6&c_>hdrCZPaT!ySz zf&^XCl?ZT9A~$12hH%A%d5B?A7vU-hzRH%Se76okiCs_xnypNvvjtlaR8SxWBGLuo zT?Jx5480Onb%;@HxFuxJhpLl>ILL#g)dzQIg<C}jUf7vZJq29I1KZ%V;pmt@A*dAl zjI5=FqcXp))k_i*t@fl4vL#)Z3{(5PUt5E%=37+%;IRgRo4DA9_bM{VEY0Ct#Csrx z>3dvYXkcmZg;*d3WYsNQU=w^$Rs=bR&5cuVXcD)1I{q!Q<>QwS&WL3@#h)ZM|FaWW z*P&TxVUnFF2oI7@d+^!YRnJbvrz(5}jl759quzb61zJc0PiPjjB8Fw)D>RB(e%Oao zumgF$;9nR9Qoz+B9a1}~v}7o?JfNs9rYKeDKk(gRdnjWw4h`wq6ZMrNCv0DEWC>nM z29nwc*!?>Ey<<E!n=vh6{{TVJ;fQb;2iwu0A_E4#?OVZWV)CnAjsykc%}7(4uA*B9 z;WE_gvOqr0CPn4r3h5@>1j5z*<Zl`TYT%S|l!$GphImk?-^2%EGNHXxhs?myKP`sf z;fo7CghJ3QfAEKW=;bEXhfBbPdr;P84JmB!rNtsFEWYAqga%$Py!DBL|1TJ|p<y35 zq*86x+Nx{75Ms)?V=-J3iA+I<dN2pyQ@x#AXLfF9cYbGhj%RtEXL=?%`|MJDwiW%9 zv4BYz7AY1N(pwE~2N{7b=rW~#c+g=>k#%^_e12&7+)#)fuYk!3aDcCIE330$VS_=% zCDBuV4u>o&hjp-+Kb0fFLWg#1w;D!2l}3kEP=rw!1x5IYk$DA$Y2a-TTF!8XqgtfA zNoGKEX?5U*3bT{!bdA=y6V^C|Pe=w{C<aQX11%^Yr=|p5$b%31AQ2(3aE@h{80T<F zhMpJ*f1YSxaa*-sYqoA{w|?t(3|EV#U%GZkyM^7lUbZZQGI@~~|9o9g4Kgi*<j=e= zY`U(=xMe!S&RAp{B9Uz!wQxn%C1q~d*ZI{6x9iDupowNk<}$_ybXZpCDv9b5EK?x6 zNG*%8PzZ$}1yGO;JQ+^ZI6q22>RV-Mae<>#kj`P~g=OdkWAN=~;EUB5hEMqFFGOze zYu}%6hew1K4_)k+%wy`V?o!#~Ox_MZmZ{^z)9eo6P5$n1crR)YQ6PM5BQk|okcO<| zJ)+o5ahM!yaZve&vJE<ic-UNEAO*7OZ`FQ~wjkJ>87yRV2bFF&U08)*KqEiFg;vm$ z)_?|M@P%Hea0}lB-(H5M&I1$rMsEo}5mISnor!wDR5G=0{}fO0`3OYu-U>5qaTrh3 z5#HbL#vq*-BC%LSwGaf`JgfbdkmE}>8|+tqRgtJdL>2V~{uV+eZ-_z226lx|AWLRo z8io7;g*-3>KcIwRum?Qpg=gpmUoeJPz;Fw%@ZUc3Whe$eFpW&vvrBPlq85>DDIrB` zH?=yEJH=$KQ*l54bM?4qw8rO|+O9!AbVNsViB5FS)Uv$j1GL-d`D)=ofNph>Ez^<) zYLJ7Ejr3JqA~`+2Z<w6wVq8wxg=P5d2|sgI_w88l?N;vv46lcGXoka)qm^wpSSAsb zUIk=TBxrbt$q_EQkTOQE7eG&TWe*SRj&Y~hZfB2n|K(%8)RT5{aMwYA1C0iRPd<`| z*oGL|*9#g4ZfFOz0;jTa;c)<*sG1j%w!L#$hDS*ASa)>`r}s2phF2$rWtfl++H7hl z1{AvBpK#<e5-h<Ap<=FOb}&f@4Z9Lvc8O2+W|wxQfOd<|__zsg@#fNMc!gA)FZ6C5 zqm<L$tC6RhE;chewHS;08kTY-3Lw$bQ?GZMkM(7!CsP(PbD^#W4TsF_?9Qf!p?A=F zX!sKu<Qt6miEsK8uXv4LGTVxJs)rknZ}FTE5L9e4JkW7(zb|s25I)zAoUlk~7=@5m z-TIn@I1Tcn@U3PD1Y<CBn}2niUj|HIyUol9{|3!EfF^ZPZ=e);x|ru<r$7AahWe_P zh!?MV$G4HI&+aq>i&22|q0DH=#%W4^HDkL8)#(FDMHrWt27xI2=Yz;Y-~@WV`Ma+K zwo|5)Cwqisdc?2&`&E3$Z~VvK{r-r27}u|5Arfvc5+4`0b$}`#!Bb7|gFj$-hj{r_ zswq8PhDum{*2j5Hc>S#6{ZFxd?*~&sKX&-sXYnt8^Iy$HKmXZcFLG#y@+J$8_IlSP zTk<OQ$tmwacwi%HmS>?BfFLJupulqF$c1Z1iqx`R4j)2{D6tnQYvjy{6Gw0($BrI9 zf($8gB*~Hj7okk4awW@_E?>foDRU;x|C%;$;>@XYC(oWff94c4>V=nn+rlADs&pyS zrcR$ijVg62)uiVpQA1dDE7z`Gzk&@bb}U(_+5YY5@-JK2wr;<E6W6VsuRf-L2{Pqt zuP<PH{rVcz&Rg7!Z^LCwEY4g#X|MYH@uk<4DLB-skxT6K+c%`;tQ~4NadgCGfu5N| ztobnO)?b0bjxBpO?b^0)<IbH@C{d#(e*+IL{CBvkS%)J}u6#N3=FXpUJezhc^y=0< z8WdQK+8|SM{(|2Nj1)C+8M8k(h#uj%cEDo2A|=h&D{1G|V^{yJ9VbqrNds8PaT#4# zpn)VglAwYMGT5Ml4?-BBgcDL&|DlB!Vwj<Z8*<p8haZBdA#X(;<(i2nE@hlnD6-h1 zi!Zt;omy<cSff{*eN#>~q+HP#UqAW<%plF2lM!bq3KY&Z=CpIpIp&zNjzHp2Wf(cy zOadT)%Pho>H|88^qnK{#R;HO}qM4?eYwE<?jAO#d)m7Q77^j_g;%TCcYvpODVX7G^ z4<Lh(5~Pnm4zdk6oc(#&pN)otBaTujrdT=49HON}%f!+PC!@5ZO{AUmSt?X)qME9z ztFqdvOCuU(YM%(HD66fv;=0tHH0Ju^qvhm?)gavgDc&IGEIKJ`f7Yp5I0$7%<x`3= zDpxz0__vFu5G{iVDeQnl|4y~Nn(C^#=c1dgx;MdEBDrH4SI)ch(p%%M^};CbIgf19 zPBW0{1q?O72uaF0gcSy9uZEdpO(oiH3sEK3c!QL}_>Q@*#v60o@tSV(iSdiIid?eE zV%>W(igP;I4tK+v^2Z>t0J9F5g_(S5AQ3;b%OU4Dt8&I36J4~?N8{A)flC)y99B$2 z9ktX`TemCKR}1HKHu6RpsxR<Sb51$nfP>z8SOaI!T$}{*pO##5(hk~lI~StecjKM6 z-h1=ix8Hv&2r{oiw-ztqha=8Z%89>K4kTOO92aBll#?3S-gtBI!s2jtk;9lQ12Ji_ zV7g3^VKUw#(yO!H|GLpi(;fRqPE&J`?6>2dyK+|Rj(c&BmvbNIII4$V?<AooPCJ$O zr|B-0X!8v@XCGfZIj&=$z4ojMZhh>udmp~|xbr?f)!Uo{yg0?P-@ftVCr>3g)^I`! zX`C*D$1(&GXuj^-12BLByp7;e_ZGt$Fo7jooC3v?zO6M-Db*TBIqK)OhmejFy8sqK zG#A0P3^0Tu9AVOi@}>`lg=8pPp{*Fm!mZ4ySrLqjXDXpTPW7Twy;ue(JYkJ-1nq@y z0UQyFXv8BTF^NjtP`iZK6%{%$ieqx26rlpe6(;5!q`-p)ci0fNX(Mw<@n99VLc%km zF^woGU>T)?|G+lF5k*vtqf)Mj!fLsU6o;q;CMt1=U1(z*+rS(h#iGVTA`*a2EM!yc z$jC>AWsZz=qymkUBe|4=a?c<|H^gy{XrT_0W=te0OL??KiV`W5OeHI&BFRFol7*c) zhunhL%2Ap!m%3CJ8(A64TLM!lucYHIS*Vy`c4e2!TqgI1LZVy75Sh|!3OTIS${5OU zn#g1(H@k_Z?)h(Ow6k3}%W2N)l<%Ae(waKk=}zP@BA)V`Cq3(F&wJuCpZeS<Kl|y= ze*!e10v#wp3u@4VB2=J)AjJ#RqK!&HG@=rnC`Bu3(TigAqV2#+@G|PrkAgI$A{{A7 zOKQ@S|5EfUIG7PiTk6u5&Z(m>oheOgYSWwIv{K&ODNk!NBI>-eY4HjwQH%PKbQ-le zzoS!9n`+daLN%&A>18V4s7-ASGma0;=2d|y)vtn;CR7z=F}n)Mtio}tX4Pgw+v?W0 z!ZogPohx1IYFBwKw4wiqUQYXJ)BSMNuYw&cVGB!Bm9o^ZiVf*E_O-ReLN>CJU2Gx} zff7hy77~xhEN3~p+0KIYv!Ly)Xh)0L(wY{vqgCx{P3u|LW|p<2h3#o+TU*-7_O-aR zt!8bT+t~V+x4*qDY=_(1-SQT*j##4!`9uyUK{vY6oi25&Yu)Q&H@n*1uGre)3G{I{ z|GeTIFL}#r-t(e2z3Qdzic<Dmu^Gg??JMtm>B~OyW^xkfi?4l)*I)I>_rCZQ@PPeW zU;zKO904{kcIAZ>MKA&qitq!4D{SElV>rVa-Y|zd?BNfCIK(0zF^NlT;uE7d#VTI0 zhaG|0yn5ju@1;gFnnB}b*to_t-f@m=>|-4_V;M9K@{o(%<01dp$U^q9k$H^dALn?< zJw9@dc?@M83xdj2wz83{tmP(u8OTlsvX{9`<}rua%v<*In$-;EF2DKAVrFxk;XG$M zms!qvw)2>&0bY6ig9kD0#yZZ?jW&mQ&vHgHpA*gKMbr7tjxKYS72W7ZD>}`Z|HgEm z^~`BWUwYD?{&b!Z?dD9^+0&7>w44=u4idon1uB>|t!r)TTjM&{y52Rfd+qCA13TEl z9yYOyZR}$sJK4(iHLPK+01v2u1S)ue3#P4tYFAs<*|xT<wax8of4ke@4!5<py=`%O z8{OYNH@VGC?sS7&*0UBjyXn2|cgMTj`nI>ct9@^HyIbAx2Kcnuz3p-HJKq6s_rK$9 zaBCxc-wKzwx*wiyi_hBM2@iO+r7i6SP$1gUeu26pF7K019NrN>_`V08?~<du;@@8R zyfc1pjoTdJIIsD_503Ml*PGoDAG*Xb4s)ItUFS$wy1*qqba}V@<vH(n|ILw3aH{K@ z=?up@*XP~wEWp|V9-si(%Wn3wqdo0vUpw2|?)JCCJ??U!JKgJU_q*dg?|R>R+e092 zGqj@yP!I&H$A0z+IDi5UK)m7`KLNE*Ao7oIeBu*NfyqPO?2#vX;u&B0#<v~wlmEQr zH@|tZOCaqISUv04{`kmS{_qiCedkYad&Xb>^@^u`?Qf5Jv_GEry<fcUVNZ6`@1FLT z@BHzNpZ4JMKKF=6zVneU{N-Q1`M*DW@>?%?;%C45y1zc-jqd?iXQ3F_5PUblP67*X ze)YM}KK(Ucde|$U`rAK#{e{nb;IrNAd0+9B-uwZe=S|-0VV?cn|6la!pX3=}*-Zch zDBt4o-{~D51TLQgKA!~MAL8X70nXq4mEHA)pX>Es>ses<EuaTBU<k4x1Y)4sEuH|5 zAopdT-(6b>G{6HqfCK<x5DMWC5@8V<;SnNX5-Q;mGGP-s;S)k(6iVR~QehQZ;T0NT z1Zd&vg}@7tLJ`!!4un7iNPrfaVFdi31o+?@0-+BA;TgiA7EXW=u3;LwVHw6D9M)kS zwqY9Pp&stx9o}IaVqqZ~;vphpA}V4bnqlIFfC|__pm_l#sDKCD;UZ#UCTij)a$+ZX zq9^_!8ahA-ct8WZ;UA)6DyrftvSKT`;w!>pEXv|6(qb*z|Kcs;VlJ+t56&J1^gs}t zpDCtc9|j^32I3{E;V~kkG8*GC(xEaAV=@+F5Hcek>f$wGV>W8zHgaPuzF`AETQ&qi z5Yzw#JU}<1V>+tiI<jLsx??(?qT)s4C(>g*+T%UqV?HLL1Gqp9km5WxVKpM75>Del zCZRwAq!A*dJ~CuOIwT_gAO(<sCmeyS31dP&WJYS_Msj3F`e5V*;X8`tNRnhpn&e65 zA`mtJ3Ag|WGyoY|BTCBTOwwdc+GI*fK;oIf5x^QR-sDdLWl##`P<A5)%;G5$Wl}2T zQexu|u4E;iBU0KV1;nH)rXEvbWmXQQPeMTu_+1a`|DsXWqEx;kS-PTFYGqogB`lU* zRn}qyD1ck$AzG550+`}j;$>bgrBgm)2!x^;qFw~hWl7qlT*4tzN&s9Ard~2;W9p($ zVu4q><T;ul5R#o1n<DrD6VIOeUrRP^CzIW@x4&St@{IqGnotrUINMW}c!Dx+Y@2 zW(0&l4V2++;$cXZA!t%%V%C5P#3fATW=O^+XQt+HBBv?}p#w;pB@!oVnxg{D;cU7l zArdEX3TJUv=4(=A4Y*`w#-<rI0LZB%3Dm$#hG%waXL7RVTEb=nKtU0FC2_(fYm(u3 zk|uTrVFQG~4)kVv3MU@&rb<rRU1H~9>gQ`-|EFwPBLy@7$$=(rhG$|nz#M9!2kby8 z;^uHFXlAzOhhAf1l7Jo9ff=ZPDUK(4j^}Aw<9OnsV!j~)kboj2rg+}xX*y^K906Pk zrUFFUOP1kyIsk=^CuXiF8G>k%Dk)#8fL}%>INHGxBmfB<frA!l1iU0wq9+`_q>Bb= zgkoumiYI!0CXz+~Yx=<pv?i9`XOSjm5Rd=@py<baBbcTrkgn)mD(Rm7<SB-t1H|W7 zQl@W`Xcv%x0`Pze$mxwD>1T?lAZ%ukUMYpPCIuXU2P8m+J|&Q1DQM<lmy#)uN@`rb zXahJvn}(_Z6af|>fRQ4pVp4ztyg&^Y{{VVEzzc+CnT~2m!sV9o>95XWtiFIJyuc3F z0S}&^OM)Y;@t_2FKm?FLDLw#ml7Kn#=L_(FA2`6+Icq7dBnj}~N)qb}l;R`qXR^Lz zvNr3tf-7YL>$~dZ4>D(yhGJrdfIRqtL_UIG_9O*7>v(eO89FPpTImFQ9LP0W50)ah zb}6&sC&>xIiFyDKPVBONrvmuF5&WnG&})stnuAJYPh#o$HL0G$>&cenpLXSZ_9!Gy zTM!(90hmD-MB4*=D-U96;VA$KJOas;B5n37e@a`kP67|S01t-Tx*9AA*lblUEY3dV z&-z`of}Fp8r^Tk|ta$+xAV3Hh|K-@dB&<Pz1SG%_*ukvX?8n{bBT8-Ixv0mvE6U34 zT*|5$)T$?dYZll+8N7f2bO9;&K^eHD9e9BqbO8?r0fhwte-7R#c!B}ItO3+O79ap5 z2ChqzKrt|a9~>$PG(!!XW(Z(`AJ_q{9s%H*Xx-XDBAlpk&h6{gB$GPneU7LX96<>9 zfsU3a$$7zpHUP{fz-tn&A7H_=20@APfUFh+iJI=-o~^9ffgl)a1MGkxWErfP0e{+o z2ZTTt2tw(?r5}*OBJ6+yJb)mWK>`?Mwq|Str~u&l!FiH^7np${1Ob@BZvJ*7FFHVE z3hI5TKpEI(0)#*UctJ5J|H2VeZW;)J7r0~%L~j;wZ!;u<{bDHun*r#mKo>A@@=Aaw zc!DCRsRxV#*QVYPD6Yv;K-oGkaK1np*Z~xHttV{mj;eqlWPu;>z)E%j>8hy;n1LTO z0~E-tqIN+IBtYV3tOp<f4>W`H!etN?gSP^41G}UkOoAUk!NeXx5Szh&>hIjf>ic3r z7GOaG@Bk?co*fuK8T5bwKmietLK!#!55QXP;%*n(K?10NA0WUH5b+M!Z3Zhq4ZMJi z<}L+5K&+NQ@)mL#K(7H{0TCNP7eKBZ@BkQx@g~!xybdidifHL}!3)^I3lsws_<<nQ zK=ww0juJ6xHUKGf{{b4q8Yy@|85Dy9ta2nn0V#Ch4j4e`8h{rhFX1(SA4D6Zk^rRc zfEW1a4!~t8SFHjFa_Dld2XJm5uOy_tfEi#x2plLUi?cW4VJO0<d`_koK0qN8?h%kJ zF@qxl5OV@RfdV5lEt7yBcmOt&Kmrhj9XJ94kn-&Y;XS8b*|Mtp+5rWG05Iw)1t35d zj6xUEDuqEoF+lSokbnemE(uVBKPs@GA;2mRvk@2oAR7QOBR~dIfFO{f5rhEbW&wHf zr%OwK0yHuL)H4D^tOAsB1l;lqnCv*etFVp&78FC@1_4Dv0j+ugFr%~`DC<i40hZ=& zHyc1cmn{+3|9}_BEUh-IAFOlgDL@xEax)u1AH#9XrUe2>fS^IM>k{=`bEE8nGF3M~ z8DxPM)W9el0T$FiSM$J5*0cKJ;RHx^ijsgD*YhK%wI9H75M*jJ_iYy3uOfs10-S9= zBLFs|u~*}#PxmdzJ#y#@Lab)99U!u>X2BK@HC@B@E}kQxqBB^^VFM&USI6vA8$bjk zKn9;Q5p%AbQuPB+K<<*jPL=_rK4=$QD##6Y;w3Q@WGW=urHcY4J@Y^UbSmiv0Te{5 zJ|{pnXYY6-KoDes0g&=A;{fCew+ak%4Pf(4gWPo2s=ab9Tmtt_bM9}`DwTS{iN^M? z3M(7G|8NNKKo&&63j{$MS1A_6EF!cne<Cv^cA*)VCnF>=7Fa496SI!~H!?@-O*b-Y zu5xX%F@!^|SHl_*t0`#?c#LPG56<iCKI-|60z;Vrv>Aa1ltDJ^04XSfOE#!6JLrhQ z+Kxi72aq&`t1lz-KnOf_1C%leFhaCR^$Scw1Jpnn)aH&VfEnxnxZX4bb9V@Ab~gLL z&N2c+qu&wWuZ+vMpU!rmg7cG-0C@MO-DUw##%UJ-BcLZh=~5}IC4#?VHYqPSq)x3D z+%E-GIXIUs<x;h@xi%iIuya3onA@fisDK1qc|J><ADH3_3z`S;Kp7Z7pL>88U_mg; z|9AXybhLrD0SKDd^5>AlC7^qNWha0lz_&DmYpVaOoPX#|s{j;?XAJ~_1VF(em}nbA zLn0h*17HD>6KedLV&W=7_KL0_OoEgqw<5^!vQwB#D!>sS@#6&n`ocFkN^Z;^!GzuJ zYa9E$&!SyZCVzH;2lzCkw!0m;z;sjZOv51sOz)|3Ifd=O0o1?~t27Ukua+jaAV7hG zlCmE>f=l8+DlfF9y8C!0cO!uAgTlFkx&XubC=~4MEWdyt_(6c%HonKUPx5b|rZXB+ zK)d?^hV$?vNHz&9cez{c5j+41WWgdIt^~9@B&2T*!2I+obRr0KAxpLz?f~hY|7U|L z069vhgI4htQ$R7$@D3+Co_fH%`~3X+fhX`l<pwda=C&R9!46y~6ePk-gJTwi>->^? zDT18>K*6U+FZj|tdwye>cBz&cFfc+bQkJ@ks$`gIse>9fc9(joil<6$>7*K^y&rz) zr{W#f_z&KpDH18_qv&Z0X&jpDct##>pE!}T>22caecq?dg4_h$CCH^{VqWEJ0zZWU zf9<E9?u)*R-+XN+W03Br%^LT8CLWejsFgM?^;3V1lA)I3zJqFE>tpHXpQ^xOx8hqV z?l!5FzP{?$s2X-@>J@3^qbPa0>h}w#i}qmqOF-=VYVrd_1c3ty7BqMe|6xLf3mHlf z=+L1+3JJ>aFd!jf!H5|nVC)#7!9b56Ne-mIG2}yzA{n-H`4VPKnKNnDw0RR}PJ#~} zGzg(01W$q+DRc}85#vaM93xKLQ6@nHk4!}>J?JncLZwtohLoxkY*?{l$(A)cP^bea zMM98h@PMVpp&&nI<Qi8cLI(yNti=0ZqfbF0-a?$KawSs<Sxe@9csQfivy&-Twp@9! z3b%eQclP`lbZF5vc{(5gR4C;Jrx}lS{Tg;`**oE?W$PC1?3@%-oaC$<cyQsdB`Ekh z9C>o(%XI?wi8}Y>#R`5iw|*Ua<+NCWw0$cub@qeQtBW^(-nxX7|LEDbcQ0K6VAIg8 zmR0{Ae}4BEg*I3lB7~8`V^6*E^g9s21QlG6L9?7Y&4U3OoRC5VJ+jTa=qlWh!wx<C z5JcIW`za_5Lp%{h5o_Zv!xUY75ylv0oG>W~<_jvR8FkzdC#5iSYcC#!9FoW)jkIqu z5?lz-#3P+F(jf}UxGl&htvu3!2^_nU%NIv#;Ds7UD5}0L%|uZ?5+*6)1r?4f^UOFs z^q`|A<-C(dha8}Qhaf1}%s@N^&2J<RRA?rMAY33b$3Y!kFuva6dz4ZHd3vspAYND! zuu46}uQU%x@Zz5xy0C+U2<`loRqPz_$qN-cIEkm+;A|Dw|Ja106y1wIQ~w_aaM#Vo zX3TXr79pwTlKW+nTQ1Etw=}uSo!pY<HkZO&LuiYHq>+22xnFb1CAVrrNGU|AZ?&J_ zU$Dnx`|Lc<dB4x=`C`iJ{9|?BHupL>_4exBd!$RkBg|@h+n3T<9&H`)%zVHZ3-D=o z2PQ!1OjIc6a_CX#)pGc2J@I#uvzPC_i+Xoc{C&*F^1JWjwqIU)C;eh4#TnCdxRI+8 z$GFQ(g6K=IQbgU0St*I9WXpmsY_CWKgLhk5ch0^qUd`6~7vp}@6eM2})p`Q(vB1H- z<YUq01j+Sc?~0Q3(x5KMjk4?SOExNQ{*zqy$y7G2h-&(E@F8wR%hZoro`Be@d025Y zy?sLNED2o9l`pHb`fK_*rm3U!OVew8<aYDyT!&=D1u@@yAtU}9sLqMn|GvIBcz^F( z*WZ809R{yd*$%r0Vu0E`swgPi9YEhI3kh#sSogcdrpX0A$9^dLKCZ_`?N1s@y$gH( zsYv%;gFHazUT|NBYs4Gx`{h3tgI=M3_Vj-mxE|J%5wq9+3RH2pl4XGTwN`kg;@5il zEzIxDhxaRfZ#{X1`R_|U`|@>+f;Bp3yI<=5pS{-xQh)bn<=My&y+VVZzjd&E4iC0p zNwNPNe7Miv`1FB%gHwdb0dm4~V_=COdnT9UJRYbIOA;zz@|<uwO0v_#*<2rZwdM^4 z6JRM=5f-1hQ_o@Ilav$oEU@$ZIq@zSS-F5E;O}IF?8GH29Cc&G&KpVnBP7W$OT#jp z&dXqw$!l!Fig3yNd3k-IOq+rgky<C?lkP&doo80WI_8bfBnaK{SiTB<hBZ;G5X$nm zUqvj;n`m^|WSl!Hviam>s`FkbCwBRm@UMAOgMW=lUOY!#an5Gvz*CeA`?X_|3udPJ z!g(MOFWD2$<`(L(+`BVta#{=K7Zcv(=JR}1F#j}YStMLoYyVNvd0~Vz^G#u6!AHJ} zS{APFh3|IEcnf%RSX}wHSNIrt443h1G#mvl8Ma?nDOs@e)rXf(6|Ae(I$K?HhaVNz zud8<~ScP1D7A`V9pfT)h9Z>-<|75?Ry|6IuiGct=L~Q7Oa=v)uJ^cQ!J|E>@pfUF! zaB5S%HyaOfAtYn=bJ^!N&*^9p$oe7=gbEd)xz)WH?rOB2zD*Nkt!YkzNEKG}lNrs- zB(Fl`;R%ON7aA2zi@HRrl?y*v`n%ZOd#_e4*Z;{ncG0f1bLNqu=oZ0X#HLcwmS*a( zC4}y@f21#3$7vN{Uwfgq+EMhe^K8J0N1YB&^LFa4h+gB%aB+NA(UQgDLAop~I=1-; z)r1s&cKfL9_`I6_IC}OoPjBa?SLX<*MA0uqkgHQKMyxTz;mcLYC8t4sv8LR@FJ32H zok!ipp5?u!sjDnGPb7#n(?qxZ%w1ik0b&&^y4wNHOD=D_#9A8*l`bC*Oq;i6T03S> zS+BA?T|fL2Yws5Q8v3YaPDNO}WB8$GNa2#(M&|C*seYny+KJ1bRp?LO&VG&R;O~AB z75#jH_gl=c&iijg8l5Y~-{KY?zy03&vtcXsXkdz*{W<sc@m~KoNAIO8?0@1%bi$5@ zh7OTiN}?O&xZ`QZ-^yzs(IZrZ3;cQG-G7b}kAL^?khLrct5Gpe5rExv^E;#bcMofh zne1jdk2!3$#ynOe@80pZ9EQJ@c%U+{d+z>{r_?Q>HUqIe%EKYIV^SqUI@McQg?9*O zjSlMXg1v%TH}8{II!Xf2@<koX-e+z}j?Dyys`t40sNR=+eVDRmSMtI~@Y>Alu%hqM zOS&8EtNIJ$jIy1IU(3D**IFNx{rye_UEb8waGE4L?mv*+z9MVzd&-c!Uv>YQ*M%#H z>5{qqpxWpD7rEcQxi5B5V}5x{_rl^#D?~cas661(&*rJ}zkqL7FJE&NbR2D)J4pHT z_VbTzM6)O02R-9*U{7At+r+=+8bo<Wr^71h>+Shw-g_IobCM(5ldY{2LeTI-;fcBT z51sRC`@+*#myUkmcU4%yShLmQ#LGbSNlr-Qj4OJ^X;5>d`%BcT=jabRQU8r)ja_;s zIt%oD+&0VtsTR`&q7+QpB)_gYo<yyx+*~8x^3A^f3Mnz~N7nnwI=YeRfkwf2R6=Pv zH#XTuQin{S3Z4a2J!A<VDrjlPV<Gq3JkcCg_nZ3P=|RL^l9v3^q@x(zkG@Is_2U*! z_hv=@5pG4Yid}U`oC1-u-0OGS`}Dph3f`#iMSd6>P~Terdh1d$YIgESbf87VZ*q%2 zR(O7fL<<@gy1YC;(6~lrBo{1oyC$TY&b<n{s_9xz)710nUVYaUb%;VdW&#cJJOpp7 zRbuYmYEv6m&Sog)BHwciYPEMmA}FiH*RN^ds%&!N=Z!XgJMn5KSZBXKp}MMbHh5>L z?s@>8#g_o%IrfEkSj#?K>AU;S9A4Y^At(z`)ebcHy8A1>{W9W}db_3^TmPr1*bnxg z+n{zQ_P>PXe;<Fw^v}KUfJUr2@0>k7xSJo6mZl@Mj5&&NW<DCX3f=@DBD+7%&@fvx zsTYQbW*TxNF{6F(cY<%m$P+H$ZPd_HR2?U31&cZIr6R}Sb2K!Ah8n}t<wAaYDYD$@ zk6xTYQW<=I7|?90KokSIV#uUkEcPPsIe;_LPt!LCufKo2w%?7}GQ@0oM9UEt@n)#F z?dY;6n60mvNKQ;0mN~?FTL&53%NZybhXzoANk_v?D$tCE;o7-YcZ~z2_?l9Cv-#`0 zuiauhSgGbLB#vHT{cUN?<6z4J9ce8da}hDrjp};}l@byzG#@>dE6hGQRXX$(`A3?+ ziOEMLip;T=bti@2`Hz`QiCh#C?HEhf{CcyCwYNWs{!K?TWs5qe(?>kG+5qSsYxL=- zs2+j<XHMS`ePD=&9x}wpbwk%^s7?rJY@(<RI)WMPbitusOrre~1(!U;ZiRupH~0H! z|Hch5W>E1jtaqKX-GDn1zF(GxXiH|@{H2KqT-pli40MAs=m<W1fs+!U3qCYNmkjah z)h#>WP_5)OKST8UZKQh$pSdDHM)=X434v@T-yIGaoiO2X7P|c8Zw1>uh0qKfeeh1r z%{m%lD^a5JB4(V1d}GbL<A?f3N33z8TXE8_XuF%f{p`iCfkl>pvWg8Z4<Zkh`e-Tz z@r!BqK(@0`@xqA9pdO!X6oZAy^FVKPBRiYGiD8?6PAUOE7r*d8A_(h_tp9o@<`=`8 z!e5_S-D}APfs^pRI*$UyG@&sLpa_<^_NFlff&=EakRM$iYDE9WqTkSvYh;}0?T6Xs z$G<0vQ8>Y@uhn@cwwr_gTi!tp-H|ok%a*fM^Br00=>~{miByIFoyr%7hgnv?NusOW z+~R;gLl<$1&M*Mhc)=|!n&E*e<sTzF#?TYRzR;xT-6F2^4=-4M-A{`ZPbu3em-I~` zUA{%1pVEHr|Ev?Pi_QH*u)9LV1LK%HY%r52k|D6zeZA-Vy$eG68`EQboTzr1#2+Ro zlF0Epf`f|z7Rg82Q}kOtr4<Y<d|`><1(6IE->o2u^%+z>?Z-^we=l|frD_kDxo83b z*=41838dhBXS<Yjc2<?+C{Z3sGQN$+FbvVY<_Om>`qPHUBR%x*GXrN5FPOwzq$=lo zqT6TcM<C~Z9qXVqVk#yaU1x~c<CF^KME9N%DQun?@IY;m(esALA`kc`3AUDqoY__8 z=RZ9vVx{vK)zl3Nz#HG^5EvuD%Ba9dyyQ5`XnMwyjjcdgUS!)hF^=3kPGmJF;P*7J zo+wzrlG<dLKH@ZaHvWhGFETCN8c~Op5-UKDbt6v`BxLN5PB=RLv{a~}cvlWWAXM&> zjle=TqBK!tp9C!>^2L*QD~O1BPGn#AephaRiAdia0;>6l=d%Z@9eHeqFmSiPWCVN- zdy)47$CCy*&{+(b$`MbMYE?t88A<}E907)yCYBNMn_Xo9y)*pe!)DApO_~2>l22AN zB4RG(x_hjzL+#GVk5-rm1tPyaklNQ3GtxJkX=rs8D4q!joCU^HL4FRBBUsHF4(G1~ za%40h=Z-#f67+(>zatEeljc|^YE4<0JNuhBTcX-Ik@bccR3UFQcCpI?u|hNbgvYqF za$k&k%r2-w)X*?_&oG@d#N?^-LVoBC(UNgPp8pJaR*x1gaz6^H{f#G4*%{F<IJvbH zlpNmt2xei*P9cXTE(sQ(=rpvfhsQnqQPx|m+5^F00@P{fsM$hNOCQ%`<f0)wju8?@ zJOTg!33wnE-gVjo$uM;J9tPE!M9>W}0W^av9&RmI)Edn+P1<)l5joJ^F!W9C+iA>u z5A+fJ;U+J>gvFH2p=z+mI8OK>Nf3vP+GW5MyWzTtZ~+=rGf{Ah6!m#3XpQC-+KA-X zbelLJ`9ZdE2bjF?@A_E(G8O1NXVHCzl4K%Z0S(<+fOZ!H>{HQ7(L@_i2-|!tj{ks% ziv%_E5OL{-A1VIvBI1={F1gkji@pe48%JmqGO|UgUfTGPhqBJ4*!!8AohtlU1<2Su z-!@f|+)LMuchH$0;zy-@TU4k@H=HC6X=VtYlYqx}Bfd;XL}62UIZ}G5N1HI{ItS#C zgfYhLM{Pj6L+AFcCvHAc8nuy9`p!MIP4eH|cTz`Jvp`4l28?+40TWP9j5lfwY->$I zgrIM2#_QCli`!wyj8HZfJ$ELYpU818)KW^b&^D?+8zvsq%26Th+lWQad%(G*Irxer z(2<!mMfwXdaS4iDFTtGci!99ze$R=((V$21?r@D1&u$6!dBW0fnv_|N|ES^TrUL(u zEUDk!@6J<1ojBo2SQwWfe-BZdT<x{kjcV<_p8X?{>tujGHZUwq&f^!kU^DE>4?y2r z#5@*x?5ziH3mBOmV{MmMuq}Cpp4KGMH<aj&75A|+K?X-67!JbWMe*N$B;2-!-N%yb z)G%u?%7q>`4@l^}!<)^Sn+4;TJet&d52cBV=v^|R)G+E|3B0IV;tng{cn2licJfI# zqPZJc7fX?Ugao^Ay`&+RP4ZrLOE}Sl#k2%WXc9eg%=aycnxXcWR4#D8xjs2hj&w$@ zb!W^n^kU^P1vHO)9&W(A&7QsJH4}Rq!qS{!8k^Tlq75qY&QvF4v$sBb6D1ygJn>E~ zwz``o6(=H~{+9IfFn^}FUnE-jcz1Row%m1&z}bw3UCLSL0N<4Nlia!N8tU}ikZ06G zQV|R5AqmELNLI0Ke6I%kzrGoFkolyUx4WA*@w=gAJgE5zs)7@)A^}nKkStaYc+N6X zmP|~U@>?=Q`*9-3V&`s}Wi)#rkNpIcG8KIxsKsvZdTV%z7OE%wh-gFA7)qA1MAZ^u z95l%XR&^bZ(C#b<A4{|bduf4oW6AJyF!HHVYuH2)n%Qb_mKNSflPZ<w2qs3n>W*;D zsJk>)H*F~Sr8rm|9)4fiH6qIQmj#Ob;>TxltDjD2^oSwP4Vv(zv;Zzqw3Qq@zODBN zr_{K=Y-tNCF{3v}*~ZQqrUBorn_%iaB)6o=%84TNoB?TPlj>N=Ef)IfX>>QG{jym` zQ^P}Kt52*ia-|y*%(zwZJ@fHh!~hA*pgJC1zDsmaBL}3(IS7&JVQ@p>JsuuFldLw( z^d2g?FZqr^lX8;g7$CZREJp83b6Ddg!A@aMp5HUAjg71|!HNSoBDFxG4{z>UhiMh= z4Qq`yAukki4tFEF^88;X3gRT-ce?r0TB8S+p+N|XVO#pz*_fIeA#vAZc1jce#5rvY z<Y#q9i^tQ0G~c&RmrOSNV237(MKx(IeM4Pvb#wI%`N;%O+>rI0n5TBg6+;O`5wF_| zP(2kCPwE&xDEZp?#z1FQvUMg`7dcOhco-<mZ~wMYiB6yCxJTs(B$kP*qSa{}TtxUA z=Yy!1rE99XpZ;i9?jZL}mNI>={l+SP?9Tt>bMQ6aorYd4d5Nlzmi*26;wCltu~xYJ zCCo}S>d<Pr5`=m;$p7Kj-`}q#mS~d8@m-$=P%-kiqJL*je~Vt96}6dsr|XQF6GRr# zSdA=6Z8cWg6SSjPDSHViyMS;?6zt)EWF{gnkfSNTNOjxj->i=>y7i`)Bd^uGUGwPs zd)H}!CKk+bsXsA-{d$(X>VZH+!3zu}nU0tXI`^I>YL$d9c4KGnJ4gl?3hztLPT(;$ zoJhjG2TG>UmnE0ND$vW+;lgeN-$DAbWyqUf$OkCzM`gJI%BWBmOyqURH{CZQqD7!I z*q47o1tB7(hL>(FEE?L_BEK*FSjwk5XFreU_}$(3Dsdx3JsW$k@apaA-fq<I?k|fT z%NFaR>r`kQOY;1VyHsQaKR>D>97RI5e*&~#p}_)=Dgz7!$MJ&8q#y6_f(*RiY3xTi zmZ&>zuq_KcZlx1Diz=Q&M0w;2(!`5fm)2wVd2dHI?TE!GJBSJ(i~azr-fsp)BAPX> zMmyx>QheBj?}6?#sgdr>OW5^@)|4C9=@i_|<wamYH!$(J)C?2wLpq!N*^*OKx(|dh zqf@(+`QVCfLv&g%nc4o(qOBHBvikDI<C)xq2}y4IO_<Ej?WNv)1-rV);%%wy)9mIa zW#)Ds<|(Y6o5;b2@(G`(Ccmau2QmwlL$dL?A4l%n-RdB|3|r|<L!3<D$rYBfdaoUI zFmJpJXsBLzcCsZX|I#%E>FQo<ZQ({G10FknzQ}mAE#yKtiJKo|*-mHmu8kDJ51~tS z@f#~GGNORjD)%=!K}u;(q3uD-j3?LbhLy@$g}g5gs~pIxxLRc<deX$IVmoH9+U6SI zKL@t5-jgTAyOp(KEfHVhDpm(x-_r=!Z*d0OJrY*GzitV3bUR#bjrkEwdkkz)+8E!Q zesoDU7^NQ760BR&I_}aLG+jSWnSmmGzpkZMLNqs=!g}TQyr!)*wl~AL(J{X?vON}w zy+wjnma18r@4UFJ;Tkh4R$7ZSzAG7tEqz8}Y_H^%+qeOR)jMi)eydr@C!(O5a4T*j zj^GrptW;kSMo;)6t7a`vzO|X#^0dl{k8vBhaBIKH*?j9$H7{9YWKU$%h~iIXrJ(*V z;&*F<z*gsrs*RIIIr{(23z@?8>4t;I<Ukdx@Gtex+^jjQ{S`7ZpCn(=RTAN#xqV_c zdm3}#ELDXxHbmk!t2KT<%+q)`!)>MVmohDY@Y9_h*DA@hdt=3aQ*7b<h+oqqMBJtg zzxvzZ>70vuhcnja$HI=<?KixfbG-Jvsw_{PFW)6&?uo$tFAgL;BkJx-BoCvCzX+E^ zudI0y%(W6-CUiRIWhNpj=G3w^=jfGVa1Dj;vp4o8Ig>Geoy{kcmis)ZvLMI#af}8j z@$OlYBu}yW;!x!<#IcXtT4S+K)yko#Z`P`Bw`pHc5I1bUH=@+`Wp5N}TxDa*c{q8| zUCdF9p|-1JrZR?qI`hVY?I#vFOwZ$X(QRIgBO~wORI~KHE{9)K`N8lQk#c3<TRD67 zxy|=+?Sq2LIYF}o&k4QXI}rlN0D2f%;+}$P?!~pxN@r_2=5M&>n%kwfuo(ZoY*|ho zVw-z{#y{92GN+SO&9IuCpwxA@0ZGHmu!i}K+o`Hh{~5{(03B?0>}vR5`t+})h6K+B zO)9?|!JMbU$VIy&=om=ClknV9`&B|K(QD#Mk_oyhvTQ-4d>Z=u>gPy1EB#?ugsLVb z8t_~5qn{c?0@&*LTKn~o3}|3GhMURQYu_chiOxMU@7>QRnBO2JPGqM>wkIMMX(ho! zMiLHFlULPd^}1`)jco#`Jo0AUU|WBbZqua1otf+);wo~FFu(yO;n;zG$%$f?EMghY zanUz^aj3-s?X}!&ce9nqJWA<_K1zygvA@J5ju+R5KYuKITd*r8HSpgK5X03g@_NX0 zVO~~{xYmpLF`1_769&M=o5Nq50d>}LB`asgQ_udcxFKtN!oo@xJwi{HZ5BbOEh^)* zhAS~YhX(b3AEAooV{7!cnOghj9F~gTe)*#Sdl=*yok!(vI6spe7ynQxLxfLSqh#=3 zMzX^ieq5rk5yaf|5biH#X*bV8B4&CK6E(?VW*%8FGnL2>^gOAT*zBfvTvB@!lTA(Y zv8!AvAx2woA<H}T3zn;*5~TpmNUmaQchdye2;k{lm;ug`U5T8BrJX+NvkDG8kMV3z z#O&B&W0xnu+kBKScg!!w>C=r5#vbYa9G*z{{rx@%#82w`z{zMaqA!Tc$^dbe+!J<@ z3d^cdc22*T;S!n8UnhH(j|Mn9=>fN{H$vs@9+6@)PH#3db^mq0Q3UWiZR0+{+5l+= z`vievKNF1_kF0{aUW`xpfbu3Dc=Ag(e6+^YpiX?~wsv7YT(}Y={8PScc-3^ra!{lC z*Gxm)!DALI-Mn2$ScP!T0eQPz?!WYgP+SeVU%IX#)b4(0f$tgN<9wO}-F3mFhv?my zRN4AafO%CD`ZFv|gU?G}e}^VKnm+jbj~O)L2x(ydYUfqi+RX|m=Bd9UGMMu3k-kI? z7PA}!kaNdED98Q0I(f#fqaw*XF9+R?Bzo@Gdt}p#M%%W9q<*PSL4zpjqyP#~gO6)b z|Gg^mbyl#xp<O-U0p*tCRjA*b;=8X$uXC<Ziw8~8r8|g~QdSBa0)7(K4RJqTCR8az zvi`gHI_065uS7C3j}F9gdBVI$2A_^?pu+5B9`gOjP+K&F_`Ns=r)c)+%2|5o@vKUG zpHG%Z(6}ATV+4PU2k7T@tJ|a}DMU`5SB@Nnt}Eqr{S`?cW5#d^`^cWzi#f*`KPi>W zI2?TUZcIZ$DOGEK72Up8b?0CmZhI#YdTfsk?&tWf7zSOhT`Rt1l59LOEp$#|*#C;c zO_g%|{y9vWh_BRR7UatNN~t$BayKuhW(D_EicRUJosA3QGk=GNgIurOXqbM@vjA)} zniTI_KUgwJTGjh`AyO;GxXODZxs5yVX(p9tZPNv$w$72}HNvT&Y%7B#8lA1{F4|gh z=U46Db5<T)_!Qr@<*@AJ$B81VMzv!(<el970<5n5626yzJPg`2*8-I9BMOF6{B;z= z<eGA8a<%<GYBf*kUvrZ|IMa4?Nh%PnDH+T@5#F|fg#;%yXWW!XY4>i-vES)E8#&pl zz*x=>kN2rq*83sn`=ye@i6%9nP=jGZ7r(WF|FF1@o0*RZ30m%OihuP3Y6L$qO}0!o z+?6)&D#Yf*_!&hS^m<pSZo57m2}Y}y0Wu-a?So>t?T)ZXiJj1O*QnM0HG;jS%Ja+w zuS!IhcWeZ2k_E)!_)ScGuPWW&FE+T)bh%(6J*Gd~pJ^e<;(zU8p|W{h!RRyV@V<I= zuJsD}yF;nIBoEeoqGd&PiKb=xEN}Yu!WZnNI9zf-Ck~}E-!15~lO#SC3et{Tv8Y>p zy^{y8NB_O|G3pH8JI;l<yt1~_>glHLTMqoUXO78u34PYpVB32d=zg!eqOM-*XP>`V zjeb!Rr8mNY<TpD+)2q@{Ep^!*aenEpe|H@Af+CQ?FDp@`%byGax$o%Vax=n9=?1o8 z0>1H|1n<E-b^3CD7XtqrtWXwI)|7c<yw4*6ffk(SS|OE<|Ni|}%g`E|f?6|KlEYN! z!Q_n#cTKsJv5PpPN+x0&Z}JX?2;!9xF~$4LguS|MQ+Elo#BuXS6X=N{Sicc!IS2Kg zi)d<f9LEx0iC6~waKGvR<>5NUcMkHA0Ia9$zu$-a6Ow-5ZN1~c{k;(yI|XqUKXy*R zx&)|6oU;0`kGb~qdcGs{j#%_bTbo0mSxMUI&gR58Q^e>b_<T3Qp9#E2Alt|(byn*1 zBsopvFWe*W-#EhbU~F<84%~~=-QKZXqNkDIX3bHl@y(7Og-*N@3;aTqnkR$?lj5fB zNhAeAgM6s4xXwCNXB2<_28Tf18z{dR|8I)GHymk}A`#nnOF$hwIC*m*4f#3`x<!G$ zWP!?$6w@8hLptw60=NXvmoLp19s}$szCExbpfY>KZCY>_=TS=+48-v};(^K1l9t9g zq!`kApH3uEws;S6Y)Bz{54Vnk=4fW$JMWmC>NHFd%xE!}<vcgT0SK5REs+gT;!u%f z9tZl>JlZKJ(8WbTq2Ln#m2-Ui-B4<`qV^zg0w%al3L?QH1B(RPaTrse*Rsj=1qSq} z(P3AaEww@ww<?5wqzZIAJQFY&rNNMzm-dZUa}`uM#^#nfULqvJ={aGXeNPScuNodJ z0qw_w7>OtQ4a1KE6%v~u4dF_$&5%D%Vh=>bhToDW&heFpiiY5Bn~N%arod%r5}Kb( zRa-$BcKn~ILNC6{=tfCh@wdq}i>6+Mer7^ODLfMZfhsIySq^ffu-V!}-w=fxSK*^D z$OF><caN_p1xg5fC3q1>j@W2AZypGoK)D?o3a+G-R2+euBye;npqwa@CtDIt1YITG ztd@ohX$t<7=6}Yaad8JQ&4j<|&-*Fver-yO8>X^A5RmTU;>2slc0*R$i@46R^@d8y zMmoyw8^JbU&^hL<34-7j9ehA_y2okspaqh64CG7T-^2M!@Mv=#T_y?8Drv4Qb8a%7 zf7Dh`8>=^_b$?&$K9d0X(*rrb3+M?o4@m|2;lOj$FrX%OjbY)Pe6~zN`e1<ytur~j zKv>oih{r*Uh}@YbP$mPD<8$UB#c%)Wxy>r;7;NgA7Hqj1AX^F%&Aa}-3IcmZ6V$GR zbowhBR%(`3YL^zQ;t=no!}FSfPbW#;!U}VtN^{4v|LZOL*g-?>L57tPV;T^*9>fh5 z@M~$MtKE<zXWRYv!x63YPt<fQEmWVL4&$y4=&TOVRwMLOhhAV;yoY6WG5I5FfzvRt z7jH$kc0fM}>g|1!2W^V4nF8Z5$iB3|)D9piR5X|lOdtT=!V%G-z#$T}eiD402r46n zmEj@%Fp&y8xQixGP2gwXAU!1TD`w)a<0X;Kwt-g#|G)&E!8EL;L3)k(7Kle(i<pKU z)hsUT90AljDHzA({#+pbk@a}|cm1@CVX3TO83DMBE8n6B>^MV8dob6k1db5gXOfjE zHWlkch`%(~Njlfo2`)1nu*gV7xa!1c*tzbN#1I1ia_g;iJD>+a;PD%ZqazgZ3-Sxk zKN(v7)$X|HKIW&Y)H($^L7;t7GmR6HSS6e>ZfApB9wd+O;B?F+ZVO!ia8-cA(VwRY zFM8-F_T8cjOl*hpvAbaR2Pe;W-YDOvTu?dlff%6#wyP^WSxW<rP=xlFip!xUXRaMf z_QU!u2#(UBOj5zHueZf*lfCOLNi?U1HU37Tog?MZ7fJ%qQLqoszeS9^*$#Qng!jV) zQYFpv)&MaiU_Jp<i3j^Jc-<)64|n)SIUvO(U_1x)UZ?JLrc*Hi^vom72F5#W2(Dm& zsz{)E0^~JSK;;qe0*+f5&s&XyY!c)SLmvl9gT74}rU*ZA8KnYd6ry(p1}K1uP$(NF zxI{dzFw;p{br=(cexwWd5e42b*pLGz^qwfR!dRHsP<d|$Or(R@(mJ}DI(3&a>hats za4-Du+*>C&G>=4I3Yr9R^lXa@=DoR16^O$DI!B-xHg54a;0#^Squ(NP)~DnlbejNq zb*<|Y5PA@PMxDTaK!QvVKqJgE!v|4X-FiI^`rjJGpeuj_!ZDH-?gLXf=GZZ=@LbtW zA>GY%>h=7!;*=kot$F8xzqy<~GFrv>Y=kd)f3&@YY}c74T);d8R^c7L&{5_^k>c&K zoVJ8y2mW1(g?$mEV<~(9l)>JSb>zFU@i;K7Lx6Z&nnw*bD=p|FoXKKXEKT-*AqhOK z1=dsoV@QCsNpKN?4IJPQ=w<L1x`2x&!KpY<B?(Z(7__1CQusS=E)Q1i@a5pa@soq` z3{XEkH$@jT>e=xPCU}nyyu{?Orvne^>W4TFTByL?-P40fJ@{5f0WQ?Bl}pH2=nMn$ z&!XqzorL4vijDRHa|B33fxsq3@FV@j{R7G(sXlU&6z8dPMm=no0X%`{u7?T!B|_?9 zyzecz->&y@2;5j3gj8Z9zTQJMkAYnXz}#KPd)%4A+18S?>NwP86%(kcs+(Ruw2Z)i zYmz4}6#5bAxNfh!R++cmtnWy_aZ3R<e%n`{fRl8_0g|K_n<X~HFU$SuBMLb^q4i(o zM0Cxv9R>ehoOgrSDj@Wy61VxiHBF$Fy4l>jewEm~bIUnM^ytA%5q==K-p%d?o)<Et z{L%q3OAzcN@jp)+4RkesJjoMU3A`>1C?J7~LOZ5m{8gdA8p`b=!fX-q<TfQfsK=H~ ziLV=u|GcAB&j35<@g2G5{{lcw-80Wa`TX>NMKF^ac%U4NySC;i!!I9)<FBCF&oLg- zZAbLy;8nTs2@>!#2V~A4`ZBExmz6O6+i4GXgdp>;(q8Z=D~p}ugYEfkF#I@8Ve8U@ zTGCwJI|47%h9@|9j==!CYl>%1UFM-RZvWRclnlDgtay3$;w%+%K!V1{Lc4U?eeTCq zIlNr<CLuTGfN$_)l7Zg5qWCys_!kP~Yl<=gKHoKKEe>zBTY_xhATfL3eYo@)xywR- z3zwsyIcbmFbD;~A=Gi5GpaN`}f@0$z2JfhGWoldir9b;Km9y=jV%1;J4h@wC81Z1` zG!%xyp|55He@R1szI#<k1z3dwB01hx5d{Ps1u9_x4?=AbLnj8LzRa<b_Zd_{0G+}h z%b5J5F#gwcfrFDuV{O4rqu??Is1OElA%Myz`3IQ%Rm`XHFV31za@FVZw=x9AU>Y=O z$wgcsUBDB^2mS2}P1DnDXN->OFe8EPb9hK-JoFpG=Kw}JV6f*AdeCl5`wnH;ufUhD zK0;;~4P^}Izt0znC|oBP;C0YaAKFX2*!$<Z>%lkxYU%3kB!5IGANPf>iCyS6QLvpD z*%)NQ-8iB31<*oKqRU=i-+`uJ%vhe-I1cVHd*6;&ZY!$tuJgS_Pi!7(d70xDumE3^ zYQb@7lUR6!k%qnuXWf`2ak*jO^7MOMk-Rq6^EmAeEG1wE@RZusuGVwu^!hT?j5m1m zxKJj8V8_4%^CksnDbGnqi>2E~{5RwcOkrdPK-UMx;{@vIN;C99KYFg6p1><6D2d1y zHOZI21m-YSo^c|d8G>Kq|1VWjLU&$jf<&a)$Yz>EZ2Fx%PK)Pw$-ma%dZK{pIIjx_ zu)2f?Qw*+U2;?yUfzse-T1^M@U#Qn#uEENyCI!I(YU&@hzbHZf^M%CI`RDNTula&Q zbf{U;#J23lq-1v4Pl(YizO9iPT!vwm(p(Nif#k3A26E}6v)ALOpdLJ8WfH0lq&wyX zz6pI{oCYzA{?5~VDJ~kCd3`@d`gDJXX-lxOgp8oxb1}XG?DT%bsk`6jVS>JN%l=vG zU7^p&mCx!YqV3{S<t{__q{HKm{N)VD$iL+()Q>i}W2_(K9(^;9^3e6pB|Q6g-~M*f zw&FW!NEh`i8_!E}#FlwLFUSb`hO@o)-XG#9z+y`03<H!%QhbgBzaoH-wD!s!@N34& zxVHG%q4=?%C%YcR55I*j5dQYzz|<W+V9rhj{;$}cZBGxl{q;Z@$IbUWK);>#(Dt_t z*pF`sZahml975Jid=f7NbG~?o*%q=s<h(lbxV+Qr;C&YS5n<IN8?Be1Yi50vZ#r&O zao)MXtv%}HR>3p5H?AG=?OUmE`Cu=tz`wFnxf(&`)&(*Vr8+<BGx_9pTXXr}W-Wq+ z3hT>NFJ=4LG+cfe=Wt>Vr5UwdP_9*3FQpzbv(D6tZgABIVZEQNOubmqO26{=pQvQ; zlKK;+lVJgEO>6Dpi}d0ANOtc9-LQA9{qXhP!RDBV|FUK7LYLHV8tN^*1792EhWB1% zOm~Xz1U@~oQ-}7>AcNk&w5Ss>{pzYd6FFm<FArTBDeEdXkO%#7ZHxFae`2Z1M6fm{ z<Nl9S3<hUdv-0}>M$ipY@pqdyZeMen5J3_5YGxL7!~$9Z{yHuwSx9IXP*+4exBLeY zwp)D3Ioc+>YuP$Z$|e|Mseg6xrA*dNp;Kleu;j*0*dQkUt0AD=M}LMQVw>qdAnvbJ z@MxefQ<7K2fJewn7`nu%QW3LOn<lD{(oGS?D%Z-Sq55#fg6cDbWQe-<@J3m9r_fjA z&oVpnhxHY;o|4yQXzb(n<3~zPjGg(AqH3Mn>HkRBauKwF46CCJ7sbs@*~t#BO|1#U z_OL#et!HX0VjTU<5(Q(Mz>iSY=bf;~ph&KZ)|*UZI9!{9R*jCR@9q=yToFny3t$Xy z6vc1RM(tiXt*ni!TV0h$#;WHEpgKB_BmlYi7-LLuyV8jk|B7})$qM`Yv~1+E-y`I_ zSWAn-Qs}j(OB?oxjeAY%lAiEbdzlSXc>0#T+rB+lno`tSt+AlC3C-tSP*VQe7a=2@ zYQ$uJyPTKrpz7e(kh+YIIlpTr&tt6mJ?hH>7Q^Hvqqa)OF!==O<idnC<!a$m&Fv4M z_&-CHA_+fO?6mtg4omvrhEZj*8|Ee_0FuJn!-E)+cUbR&bGnHs8(yJPruT2|n-7%V zzgg=u5LI(xAm9AY;jhA=B)6ZEa=kU4CPYh*V`*LqAUV;K^~6e0G}GS{87%Qtu|B+_ zu?|6egY&cvIW+krOTk|?BV1d@`6xy7aGI9I=Q;b9>+)XqEmfv0t>4QE4^R^j^23o) z5h&XWJhF?i5PdyWmlsh>_mI8~QR7p+nO+nAgLybJ4<IU{ZmPP%=~=xAwJh*e`F>fK zf10T7;xBReMb#!tjCZ`>RYXT~#^Vg+&h-9e@|M*`Czed`DUa-we4=K)*6kBF)soi5 z4()o)wo?D2fzM$8ke`owUPw*Ze;k6Ncv6Tw$=uN3Dih4id@_PVIV*}T6ZPMX3LY6v z`5>60^C<WZpF{h(WLZlMrTz4ZF`FEN;s^SXR3n3S?DMqPO3W6)SpOd_LrS3=G<i5^ zV3rF&Oj03r)DnH`M6i90IXYm()L_v@CN^;DHe-5mptGjsba<}W$mpQxtl^ytcOLls znH-b_+Xw`r=#o{q6!aflrcZkB?Ohx|ev$;RCK%l=!gDKHhY582VqEBpG1aNs6_HTM z#(vl_(b4P%dBYw^`A#N6pR;rq9o`f?N_lT%-NLWy){k1{OVb!P6w+1ZQNOFjoxrZ< z6eTO1zokS=<omO8C%pM_oTgdg@jGuV?9YYT%x{_)RI>mll`1icwMOU^k?iZs{h0Pm zQ}yBn%VbJ6YLuB=F>(SL6fcAM@SRg5We*bC*9)$0ELOMGgoaiDoQTCHp7Ypj-x4{) zr?QVsI1YPK=CUJm`~ebQf!Sf|GY>w0-q2d(gzB}^;622nSJ4u4fi49yNs27F_ml~d z(wT>RVKk1*Ba~rtnX8OLQ~6EmJsYk&24`bU^$VyxS}zhY`-go(U3k@a5hF<hl*xa> zmCD!X=Ex#R%gyzxqXRW-by_8(#3tq9;S5hXXYM@R6&u0U^-77pni74#T{g&%DkIe> z-7m|-%D7rkcN?_AjW}dv#O<#NnztK?=H&{Uq!S_Cq@!>ru<)+1SKKzU7gx<n@t^Dl z?G6FdU0j^s44ja6Y8>!rSUDZ;^#=15Cpxfcsz8;#AnT#H9<pp->s~L-`?4lL>uA8H zR+cULcp4lG|0y1xXjJyMre8vBSN@q$lhii~`RrEW?aY))#B!6vmC}eheDR6Xw-Kft zokBVOe$|pAb$9eaLSId;6e-UUf%Hvjk=c49$#1u>Xs5Ke<tjyb@aTg&1`@NPX1D}K zD5e_w=GigW829!kmRj010@`a$$sZVef#KIY!mEDPz30xXR<yht#_lf&(drnDufk^e zzes%PVry<)hs_b5T>*yI7%A?A-9E8)PHK*lCI<h0yQaFbc!ii2{yN$9NlYaY;%w^p zXVcjKu*dHw6`}GaG22k!C~q#!o4iCbmN{BSFKz-)P7+d2&2vfJpt|B3Yy?A4hyCYw z$!EC|y^v`u!2Tw(k>l8kW-Ts7O%GTXw<}POlg<B%H!)}pg9iImM*NrhbRYKM)vR+R z^pOPxe>7l|OJ{;7HhsL$TP^04wI=<1(2Gprl(jrhlUPV{&<pm+;rmW0cr<e*1A8v> zTa<a+r3!#%_VGLMaonhu`4p9uH+Hr?K8R@&PNTK)&Y$;8HfS1V`rw1Z$lU}Bk7oCc z2dI2Il1V9wNoq5{e`*x)JP|sw$qdde4=Ll5N3GmQKEw|NC&{Z-LkiukHn{Jc>N1op zU>(=%uo1iwnFLdbN!AavQB@6nVDe>hNsGLDJF@wrMR7g9mZZwvz4ISO4kl~VNH%Km zva6V%B!CKFD$SgdggAh`QPpJmT=~;0V$MtwviA_wTP8vVH<>IZ{G3;QHnyg}4_kp1 zRGpL&F)jw2t-?YhLSM2%o}S%C{M67@^ZC5O1mxs;2<d$+hyGl>Z(?>6>d9fq<Kky( zq}U=*N9jR0SB%!P^aB>31S1b>`XzOR1dFLG*fyK$phH3+eL7#}sofkpt(e<(Jq@Pr z#Hr!i{1GzV=Bc2q%%|sYY$1-Z3YT6w-(PfgX9OYf6>AxC@du7f?IW|QtG=wg3M&Cv zoP#fK5<}B3y4VcLoGQ=#vu5*a$EVXB^;sH-JDLy4Mz18y%-dTd?6S674f%eX8LMQ6 z@#ep+R9Tk3?M-a@ktlc<Z173zN%Xt~^F(QO2I8VZiYfDPLI&^}4xrDM>_mqtQz%w7 zyi&wObt0K(S9s&3!5i~4>2z{q1eXsV83Rjo;vk2_q;ZM7LVn>ZRRMYyCkLc!9qs^P z%>eQAmyde{jD`U|3+WaC=`oBH5i?FlHmt!`CuO=3a8m{7dJK&kd->P7e1wt~!Jq}E zr};9I4f6p~;lO*FWS^z3>F;@APKLTM0OvP7i810HlHefPqf0}8_#66rp`yQgn+-Vg zf)xakRJ)L6r>vY#gfjCOM#o1oyW-(z!<`;m(UZ<GrGxmgGwYQ84(pgxQUaCrPN!h^ zt|{a)$q_ZQa3XNxm--VDn8OVir3nzHH^!Q!O7n3CG2mq!jS+{uMJM?S=cRV9WiJeu zwyGd*I;A><@?6~Exq{b@+T^w5OTJu#(LAd4o9EWpNkp3Q#!-OR__FQlWkYtzFGdTm zD_~XI^VH3FB}GmX&iBWQ@S)l9<j&70=y_=s&l}*=DVe$S?DY1i^du4d(K4o?Jq92P zOH>HWylN|dbB51DOFG{CZUPY~pj7x=q9<xz>^2x1Ri8XG+~YNa$*mDD$V*f8>(>p_ z`Tm$3T$AQSe;h#p1ey26yY`WL(SXOP@_t?Tl%rr(zp)T7l#&)U$$d5^<@Ct?3j)Rq zpd-{R#a85$d7qh(ZNJZ(?$h}aJc?$q3c$QQ8GlV7Y;o!>T(Yz@cOR^w3|15=L9S8c zkD3&#D$^BurUJ=7;u~}CPgk0z^JZNIMy?#47qS5?`4oXygM<4uEH%Lin5bizO9!;2 zqr%Oo%AsUUI`1HxC++mF3pXv*!#7Qx^U>Op!_o5vh}Ao+)%1L&G-4h1HR5wtT#r{~ zTA}^mjBHMV3csFHZPa|K7C|_82<Spci=)ctSD}NncnbSWPw_ksswr|T%Z{eKxc3Ek znGV#C=xyV_5EG#nM0^V5Hh6`?CUR7?D+oSLc`j_!w}!v#<)0Q9nyw-H=t=;N$|UQ^ zT7$qAc5m*Fagq%bfd2EPDc1zTC6NA3y?%b&T8C)_CvLSG%1NX|xf4+CS$1Eq>1;~Q z$)zSKF4ZGF@}fja^yC9?29G`!W{Kx^Af(FI2%jX86WSI36TzNJ0b8x4)HOkrLb<%t zlQkt$TG%IRxj&vWyFtbi<uTxMi3P7Y-___2caw3zpm|<PXR;Lt7(oG^A`T7J8Wt72 zvFSZOL{GY!{!CGt*PnoKbINal+uA>XTjKAuMocG90=^auk4xB(sysgWcD&N9FLex& zEhfm%q!mdx5b~5n_+5bo7}M#(15IV`Np3xQb)jE7T!;I|VxETa<Si#ba)845cw^b= zl=8Ytv=LC}F;IRoF(#e+46(HiA@)O(VU#lQv`_Z1h8#gWSxGy>ev=FtWN<uL3(sv? zGj*K8B{P|=y2-QjJ&#pDZDgf<_IPykqPWf`j}?yFrak4}4%y7xVN>~37z2z+>04kc zpUlSgjMWz%6=O084}HzJg*dqKA}f|f61Avm#zM*_-1*IJbYWq#at&`3?ySBOFuOJ# zl`kH94T$#^-BAI-SFLeW^3MWD9(^>T26Wr3LFgHdTShtD|4!7Qj`wh5+Rgk6G{6}? zE(|V7dWS2Z7?qxtjmzK<YQOs+lKZGlYm$jv7A_w@2Nk{ST$KeE|19=P2H3<yrj(Mc z57oPd%oFfwx2Q?>nq>8KZtEEGy9I4M$te$d_I1jl@wCgk&L=ol9`*#{W;?IyPV&zH zpeH_Ai_W9z$E)I(d`!YYm80D~OuR%ihd$pNXl5QtZ;GO(5_VFq?Qq$!>D*E68ZX~1 z%{ZLyd7SJmq^!;=e(9QK^{l-wU!}pXz|@>m%?vubOLk`zTxRlvM;B+j8=7^2{D|c8 zm2Mo4oWMwZ`Tg{aUQQQ>N$zp?{LS0#o0tNKLWPw}VNBNDCx$!a3rl>|(x5woL%M%F z()ODQ8+Vftnn_9|E`=ISolODK!ctd_xbIYQa}6*m20Txcfd5D4;X*$>`~Jywhg2c) zU+}ck`MFJ-vayV5Z#r+ZLcInx$;*jb<*=n?Ix~c+_F~53&gUh-zuU$_=ui&5qmn*n zMw0I4-7Ujp9Xzjv8CkQ2Q*p9ytq+hU?fhYWp`A`v!@>W}H(0U>Z(}w&<#&?ZYk=Tq zZer?!JToh&)>lr;WhS_h=Q)S4C}xOj?Y_U>nWA#mxnvP4=Lxs+P+ZIOCq<V1s?NZw z?%b+gR7F%E&|HE$^bm-0NK2seMs7~%Ij)@+<0G!|*!lr|KVJ=%NHf&pURcf3so?YC z5ZQKHyZGKS`oFY8?vJ*Pt5JFVF~v|j_qC`UF3fyxIVkD0w7FxeH{o<zLLJbXo|Iyg z<*M$@(oEwwX|n{Zdz!54wn9)uL0jwfQ`NQC{U#+p1BNt@o>PFX>Eq!$yz-MgZSPW< zDvv*%NPD4VLyBFG?DC$X<#V<Ioe#NOaJ&NRJfKD%OE!ZWwaIA}nv9L%MK6+{>-d~k zO4DkG@A;<*h4opdr%4%+U#bG5>^Cy3eZ(%P_wxCAOu<)RL$lI6-k(ONoL3Y4S`=%H zX0f_vQ%UBv0vzRU6B+1hF#_f>TqMs_MQJ71;zIRih4b|(-kQK|En{&LJ8ddC0!K(` zS6k4tiMeMVvjn&=J-PF^DnfzV=?Av~JsGo^L>(~WQSy*B6t|@Sb4Tp$ucp6%7q(Eh z?z)%pJdq7o=e3&`d1T4Yp8OQ2K+}NnsN%S844tlr@%<3O*XC7J7riMhFet+<CB$qT zIlDfGK$(tYTU@F^F(+c4$47$eEXn0S=u$SDLW|oRG*6x^#RIQ%@SJNW`%@D2@M(5@ z)}4GoZR#gxlKCwCoGjqy;%m|>sL7cNWRPk)!^|`B=#GF2emp7sA=1+#JuRB9vh<a& zY6w8dZMcPZ^Kt@QcFLbOR|ujRP2vMdhUcNTZ`aK8IfnzIiwjP|Up-RC)471oV|0B7 zY>j5xB{3cy5|;rkslocootV4AD*$c0a~{uB%9hSG^?uKX!KraXr>tvF_0pVnc#S<W z{x$(`5>LAQ$LZ_GeUS(c;mGQC)GD$7zIZpNkQJIrB?L<d-!LPeNl%U_{(@t2*>jL( zrMZq3r#Taotu}$z<^lLGQsC{2r`QahVoI716L@12XrRd-n@)z#r$o|0hEKM|FWFxw zt6kenHGFPLW-1?ZgIt#k&W&m92#q*)Gu_+o*flzNS^yZU@W~esF0I<sKl3qQovb{W z%oFx3yEd)$`}b3Kz+t4aGc#{bi4_1I7n8OuPWudI@$$wH^Ut60wu$nw-dGVvij;#N zeKcFue}vI-%2CoxIz99O2t4q$?&5jRgPTw01mHKmN9YNOT}jw?0!DfN1NzKmoewDk z6_E}3Tz~MU`c2vip34@da@(XQ^I*Sedbx;7WnK~d5xjBrd_6FB=;$B8?M5NrQb<M7 zQ+#8zFNLNO>B7(pKn?+AWA;DoSf|d*=}V-U=>%zB1G<aiAt$j0XnJ6v{NqQ;x4nPP zBHDsH7hKJ?{l7u$!~&Mcx2npqLc-XvyHAn?)tv$3se(b1fDcWX-r-?q*n0^*EjdL1 zOU+cfA+^97@-rVSsM1LN;;$lEAYds)^)Suf?-5P?aX>r2-mFAyq5b~DonK-FA(Vc; z?|o$Lw5y~fG?NoE	mQc!~*4WXkiuNmk})j}_cHkH&^e6u8tB|LzGXyvWz?j&;Z* zcR-h-i^(p2+%`jL6!1AbiOVXT+e@1GtVcm4`2L7ZWV^Wk2CF(Dy->y}^%ezS-_9*5 z#0@9$9vuWEAE1ssmVR2k<wb4E1qmI0JkTXHE#3^KT9cN<LzZgiI_8{en)SBa_m5K$ zP<N9zx};-XZ=aH(&OKYCqL8e`mtyKpF319Y_$h46X=jg}*1poV{PST{E^uVI*n`S* zNxHSgHD1W}xN^utl@ELuSLsy0PbtJf-OKp_J9&pbaU~C0%9!IV>wq&YH4#*REl0YF zyV==m;$NkEQo!OWftx$n^W+b52|9zPTy?x7$1U^Itd=`6R{D&Uh6(r7V|@#TN9SJ4 zjuor;z8U)wVtV)1g5P+VnRQvSQ#HxoQ~u(7Y5aEc6F4vsq^#Ob8Ah55Eq8eIzG*!9 zGhcRses!>jEz;J2Yz^Q0GMt&*Q2x}mw|>|{#b~Yz9#}klvh4}7pX}Iw9sah#SwerW zs@8&Rart@pXN>57(LNLRPj-zTSX4J)v_d{G@=gW)Zl2GTdEU}nHNSj5WCQWmQzL6! zJ@f<kwv4Iul8VqV9zOBLBomly)%;EVw$6JY*Pc_(`)_PB&1M$cbbuC6luPWrP0MS( z0<+>V2hFjg<2S3c!e^s$n;gf>+SkGF><ZqR=j)1e+?_OgFw32F`XGK9qqSV<0~d7O zTq9aK-t5h~FjCfwJUWk_*}73NZ!RXIOWP@_zsje_<s4zhF6#K_s!l~!22Bg1Il`yW z{_?*iir7|~RxuCE@crkq)ZRzJbCe$J8)a!M?|&aaCZ#9c(b?Yo0nucN9PnRqeRC*N zQv0!usj<DEoTKF3m!GZtka{dfS9J_#si=XHvC_#E`a#gJDD53Yb>YZkdO!B3?R9b} z;Uc2J`>esM2QiKpwH_Qe$vrBMGPTwkVA^D#g|yzisPZ`_Vo80Y?3Y#Y;+Lx^VYPbt zxv*n99<Q}j!F*7y-M-ZTVg=%HX+T$EU#SX_Z#w5};##h??(!WirjuA+#JFk<!EWnP zl2A2-968fe5VE4^ET}TH|IDg!K%a+}qBDFO?eU>c^|j<)DEGT+?>V~xh3&wIkhHGr z&$8IM(`Hvw<#7S<am}I9Ijaj#Cs}8RM339_M#FWlrx`N2&!D(l_S{hQ?XhGF`Mu)g z*ILt?bf9E!d-AxJYt-<#itAYi*&$;YuP{x87MTgXhIyMD<>=7F4BZ>^Cx#J5W42e$ z?$sB63r^fZ3d%*$uV(7~mi5f(+bHk^o;Vn)%n)uFVwhWeN$|<``z?97IwX-_Uz3%J z{5Pw$t_vShS&TWb()z`0f~NZt&)RBz+z)`rADi3}(3y~!=Kmi_XW`c5`}SeRXclyC zgGotuha022OGQRVHzJsf(cK~?NFyR3A_(HfXc0%Kl*lMarBw8b?%nTr|Ayy&?&G+x z>+?BJ$)0b=liF=RO{TQgi!cu9sc#K*4_++YyM3^AItkG@zIZYudE8E7<0_{8N4q`3 zRq<O3<0NJg%WTKn_x>x;%%N&@`g>Yy{@6ZVNPH-J$>8_E^b^P5JNzrJG+uw|jMP|o z^31@{lPB6n>tyc@^>{NT{hiJqdv^6E9M9cbtWBkj10P>l3Ho!SyeSxc!|Grce*tri zkv+9Hiq3~)CT~Qiy@Tym$iDFWb}E13VTz?2kpH)v>FuHE`k0Vp_|dp1BwB00DzFw& z5N#~+56h|$K@^w}Ab|=Fleh^Ncz>DEXpx*bw}vp*#{zs(Gu6pD%XpD*cC^{)G&p<+ zC>%@kDYbU6N(5YBDJo#n7Jr#@Q|Y~|PQMu9>nFX)QWESVfkE2yWz87nF#=Qz)Fd3e z$`_v!Dn7iT+cMp#wiZMc?02{dAMO~_+3F~qSQl>^QqGC?B57!IRp}4V-arE4uv+^^ zX9F|Uv3YA8KO@WOnfc#_*U?gMh1cZnI+`w+wIRN{<tZI(n=e%=3cuC6vNfO26+OPL zSbgQX)&v^-pWw#B_$)v8C{d*rlm}r<=hTvsL@z1Z7JklSR(ElD_fcZD{HO1hwaLeE zFufR`$mxpu_EAbnJ4R3^f?hO^2)Vo==2$jY=Q4j(s3UVy#a9nEe%+Z9<W!5;?n#!_ zv(I(dAaE1r@mvL>OcG-W;PClTgRuN8HF6Osz%5bMsRnvS%?JLY$yBqm<FS2djo=S6 zL0+B6WRV0Ln*ULHLsu>SUFPC*%$N#u^DP|ne}~qv0-sS`ry0=w?3CQ)GCWIy7rel1 zRBOSDJo+k{<MH1E&$6sky*X5BbgMD%9fFZ=!mY{<o^hBjJ6?UCTOqA0JWScq;g$ID z|024GZ%wH|yRY)D3q9>fYBE-Tfra?IXc6$NHqllqZ;za)<twPhD2tnP^ceVxudb%3 zFWR%`B*k|5I6Q4sFjINbVj|Q~ZK8f0nSM{nr<!hV2wG8{?l7~KOcqR44;bSOBlGo` zkd}4orl)UrAt7(lg!q|`GTxTbLvFXD*$Pms7OO<4eHy*&En<$+PjmCnc9yE=bQ!h( z(A-XE0II;uA&qE@7e0z$HrS0U5xDho&~JP{d_tMoM|?_H|J>6}owGkQK<v`1+atV2 zge1D*)M)8yocbcEc5>oF@vvc8vOT_4LBa(QR-LG~OUco-qX)+UTkb8-UcKXf5w;XS zW8@ryzL0s1pJ380MAMY(kZ*-os^#Pj9KmkcBYhRc50VFza{@WMh4f`*2gXi)9pcbv zZ4GdzuUk>=HW3^d%&gmumDl=II^GiaP;Vt7B`(4Lme#;YdeWYl?~g*^1C)u%A7mCT z3@Gd$F^D`AedoJ@hm*D4RRt!q(HM{CzmcQ5XX3qD%Z9SiJtUD06r&#<i6=~eUU-|D zmvir2ENg>MYDq_O4a!>MdbceF+n`Y{&%L1AN+Y@-Uv$$VofA+0b>DW2XR+xb!9Hwb zRml0!co03xynHM@Uo=svXi0N_6)1kqVf$~~zSS3v>BO$-Tx-1=L2A#az8fyZLasLB zu<Xefi_Y@sA>gfphz}RU)`S}Z>aeSv{J&(%tJ_M(CaG!Uy#1C7%mwORQDMyX;Gf@T ztTwuDBdUeikmENhe1w_*dukXmpytqohLYC4O}-Tmyg+2T*f3_If2C9>zQ7yg)C80g zZ)M-}Htw7Ef|CnZq$RF33GWA_>YU<|9hYl(?zAVt?ujyc3j08ndvLr400Pz6c%)Ie zjNxJimd$a)gXb|B2PP<IKRpZ2sY{_047V*xKC0zUb+Z_ot<1eY20&FRm>N%EL8582 zvLoq{I=RI~*eCNst-ER7ZQdrlIpTeLaH~>NJF}%<8Fwjxq>yBs6KaIG=EGCcR9B%z zCi$KnSL4Oc86#z*ouY0(8L51KN3K0)9VX|m9=KG)qTAK^6Z<et%W|jBfP0O1jwQr( zfCNUf>qPHub4xGNrQ{^xuh**IPnClc^4*zV0M*6Ebi072LwG4IB6pXeqQLCON=BD} z;aGV-x?33uS5n0nfS0Z$DijSWw$n?t^Td-`mD14cT?9dbi?XOWRgNxE)F@HloG4O( zyVy=EfF|&s<6X>3Q$GNe=kbYI?&E%5$;9%tIe<nCX~M}xMIc$S=W_L3cl~yHNL_-2 zxXm*?3~w5WX9yS~zVJkCR6By6s}3!yhS6Si_N8Ounlb7Ov6Qw33UCZw+6G>dOBuvg zVn5)Y1YoMghr+6dGFaZKL=3_r3@;VAz0n^sV#xTOg|-~aEzTawUdGFxl5`2!oWMto zbqhMnCb|jN8bR0e=5eA$*I*M#;|U~<Wf9$wL<E@#X9H^c0(JK<D7IlV`V%E-U5Esi ztRj-useQ$ZHT;I-#Emqr22fuseZUxA+$>Q$jvl^^qQbo{>nqLaY>()K80)~Y-%9(8 zx7w(quIex24Y~$Z&JCsO(6luk_ZU&M;`61mDOoifv=jwuC4fq4Ns~dL<pf9*QF0$3 z!G{4?0)Ls=7_hh;J@k1f%AOrU63HJl$;aq7VG<|bjl`6t591}s349sY{`v&IF{{xH z!Tw>4081(ztvp+Vmf*oxZ!jC1Bw2d0T-(8MyRpgBdF!>)*US+W<Vd<KmU?rTM|M~A zPBD6FBn2l!xZIlXqMM56W38_DMRA@UdKV1i9zs7GVur~^E9^;GSrhKY@5pFr1EGg? z>4I_evfspw>R8Mp@Q&Rj2(v`NQo!loO)A1{P`H#fD^65Nnr{9*<T@tdS(Ze{^+3BF zsI~}HnZsz=`AA*FNR{Hat8vN<E;mAp7DA2h#9j6sFs;H_U{8U1+js*xj84%YJceGB zW^qQL;ZA7YIvm`IUaCFOZirrr$53=0AmlZ8Da-K9xgj{-SYr&YYv$v`xfryPxwn&} zerhP82Xu+q`1l*r$m*>rz$e)+ARAG${m>U~G!n*RPCGCC({)xEgv@$CD$+LgxV#%y z{-3D0!LlLu1rgZ@L(w^aP&MG=fuXV*P^22i7XUywB}%mV>#=xOO$*>oFTdS)AtiX` zUn%ar!6V;vSvyNGm7f1%YzB4DnL)bjabq4{kjLu&N0&FnA6kB}>b8<}E|Me}b|mKv zO<PF|H-MUYlG*i}*%yX<9mZ7u0d!G7H30|hizMN>L`f|iznQz2wU>GwP-Bjq<K<si zm111ND`HR5b}9)`0P3C(DhdoE?1)^404b-zi&=?M`_jlcfMi6X@+oa)j1!i_C@Tr* zE|+M=&DnL11|)rch)9xpIH@hphp3*??Z?bL6@KHiwkN<hzzC29Wnw!L%{>wY1|VAT z#xnsxa2lPY9#Gbao_junjt-}MI=yFC{7f=$tMqfI7G9^QLG2u?CjgX{la*GJmG&C! zZ1dM;$+YY*IKFt9s+WaR83OM6I>A4u>8=`HGAnZWD|4X6?L5q77GQLxjaws-TXQqF zcPjYe=KGLzpyKhGb{yuxnC$C+dlVK|DZd=;>MUtBjB<}9cMAhtpon{NS7(T{ID{#M z0CnnsW(?efFu89DuIgs^@)f*t9Z9h|v2^AFJY;a;2Qce2opzq}wKznrfTeZ#-58+O z2I<!Z9up)t8tc&5&Q#@Ls?`NlsK$^YjI`5Sv=Yp$E&x&`APcQ1wsv~0RnsA2s`gk$ zq#Q=LI|P!JkoY;(#zqE1b9sq7X!pCQtYY5ErKQ@#hOKA1=pQ5h8e>o2S;cKiV<)M~ z4DN;`s=Pp<W{*tWi>Cg%an51<iqKnaH4MKUiL>k=`L%;Ko%hz5>}J_Wp$<!b@+aaq z!|R<u^)qIHix^HjT+s*G*Td_|rNm~7{WDtLa!7Lu<r!;ur>}>PAKOtnEAV{r#jQAB ziG!Xuz|d&;nt}<F!o>+42Acz!Ayq%qO$tunAx0M^P}ypvcmC<_7=|YeC8&qrlJmPY zLnnJ`Kg<FV`^`BpO>l?+ehI;}x(rG@oP4h^%cNccOdgbP&sI~bbWXFr!<6w}#`a%D zo@7W?d2@zBe6n_$t3jzB#+d}5%Dwv2;yfe=AHul1J585;)KD|~SJKY<sGYDiZDyB4 zjcf)giv#WIjpVg(Dq1+fNts4T(w+roKMJo?sl*{-bKMW~ZD8l#hwIXHKpB>G!G3@! z$DqJA`d!W*#=Jmhp8m`&!k94<@|UIa%;cpVKERpJz>IWKndveC<W7_S{xe^14()Lu zb8lOCNMcGg0GHvM86HPcs3WkQCVDFe-XCNRHaC<RqgOt~a|^YJK49Gbkt3OfEBAY^ z#bWZS74P0Qx_2(TmUH!977d1r`Bk!>t|w?;?{eCpG8Ut7^NxZN9Z>qr5c#ltO&{<k ziMIV3#rNVd1+6Wi=`yxL8;9Vr$M}#77=v~>-8mqhC{_WB%#F3e!p5irmQ*q5amw}Q z8sR4zB;lqAdMN@~dt0tC!%es7!~Nmiwq@qDY8;CwQT5cmT2Hb+-IF7YPH2qOorD*Q z&q>W^&}8mHLDkUwUFh%=^kj6((OaHXjGh~2HfI|h{XD#a9IQT>67ift<lt6UYMG6i zS*luRMXp#zm-&0ForDlWeradLsnLDBo*w=0yIq!_x~#vb*?jG?`5uE>Vt{0UZ2eEh z&46;2r1}V3-IzqB3V=YDVODlD67Wu`6===;!ui?{8{46~arm+gpusXwVHJPrwOow~ zvj)qB{w$?yH1`SBNh^TOW%P%&tGGx$oBAA1osQjz&5qTbQENzsDiz^8ouVkHM^Y}4 zACj+^=%44?g=j7x=?0Ihe`#`#!)rw{scxfWoH#W$atrc1F+I%x5!874+<!GYrsj|| z&gX0*FYKWj#%q=%1mBJjW26#3W_5K{V3S1V(dvw<5jWXn!&8IqkeI>rN<Cq^W+YbD z25~L4pxn(3ke>lL4{a6{p}QVX3XEcOG3X&Fi;-01@LFB_;>0w?WfIjw;HSP*tbgIl zk(YPgYZ^ZU{p<o(O<-yzF~tM9lX<`|0l*L661_vWgk;@z+jlPn7GP_LnFmrX*$9KT zlT6buldox|`1jD(!Y0yL7vJJl+X2!^oV^Knr%0`n{uydvB@iwEU$5$UX>pkTk#u<z zn(;*|$A8Y_AAWtKC-*z2SJ%hPhzA${YNe>o3@49?I}Kw5dkZgV7n$}J*=iSm%D2t6 zD)ui5>LQ8I;Wvs%y5wZ;ew=tan%50@8zru5<W%yqxBN|S;sfAF5&mW^P=%(I6UQr@ zp^<v@;%bQ^V-32kmq!V`HJ7wmTs==?pgP-$_HtfYUXv<z@}g3Z;GtcYK$~YwHd`$n zEIb-6)n79Kd@iBN{Fi1g`jKK5DI6TYtai+WP`l9y4$X?sVYrWP1ZpX9z&UjiwL2;N zbfUTZ{rHEs{cPUBKiCzqv)xA1_!6SH9p=f|9<|-I@5NU;HXlb_4$n*5hQ-}h;+BKT zD59zvUfqpNXAWcZl*D+guTLsZD-JKNzFDXj!1GyGT}xscJJt6k|4QRdzzxgwkQVml zA+;Vs#r(vtdZhR=;0T?@vn)#HHxuolUF4xctNweu6a;(TH~KXuTD(9#26G995bmdc zB)3~_9#iI#7W4@ICeKvx$6gliOTi_KWGY6z{rhO&Y0iU~_xv{pVi-(8GjAT?MPL9Z z193+2H9wD$GxO^?Tm28NueGjd=iWaLK#6JaIC#t@3T_h-UI4WO(!Iw2UhQ?=F?s#r z<!cQe(|I{i<ukKKwEr7mQrG!<$?<jOARG14*JkyNcKrxM!YSw1xG7P|cdDQs@2l)? zbj)o|w?>{t@>biJk-y!RO|qS|(kEkN7%ux)UDZ8fJ9sB>iWvH9jgjg>A9{&wiM{<V zKG(qQlWo%$h3~eiP^MWCFr^=-QgPz@K1o_ppAQA#5x^aNN`SB0ZfU-W1!)H7Fi|Qi zA;2;v(FQ~wT67EpRe$vgipgc7E+i(uXJiY}y<~e`^^b7bmH&ojN-zx$CAvMClKo== z?j&Sfj$VaO#F;Wm?zu_M^2_kGAwhBeDIrNtwXS%}`A|5RGqtKxHjV>pnk#}%;nAis z^b4izQ_lGy722^s_NQl_n{ror?^72yefc4jiHJ*|c6ffKOf|$FcirF)Y`?4>KYU8j zb<Odyc;eb|Z}MlZY03S?&J_8;ymCG3g2g~pSLfF8@B@Z}c5dkck&E}v8Hf&Tq1WEr z2Qc&L#T~l9t`2Z1n76^&-3WD?eJ|Rolu$9J0muvQJ@f-!&DRT$e1m!6*Cvv6KPh_d z-C7^GQTVhpHgxG_<fnhV<u}8>yumS3o1elZtqxi?Nguv{7K~pW(k~ZFG}DdVm<(K! z@McsGW#Ig06!+Ofh!eFa5BeIqkiql1wfOQ|`?$OR{W|*k>CLtCxbP3V_FoZqikgSP znsi9x!oaED*DG(#V;d`OG{n~zs!~tqH(>FdJJ*r;KmP@mN96S}Ke)5|J4N{S8C&if zek@PeleT~3k|V;mPtwZcf@*5vk0ScR%VW>y0U0VYqU#FiTVsZ`qBU6#6VlDCGZz1K zF9MW>pPh#4Mb-T#@q6u>Gd;Z34H(K+{v-PMVeE>%g2?ou``2nwG^i2gFhN-7bSSCW zs)%!wefk!|Y3(#^d`*08+7y}XG-EC;Z)y;o)r={hDxk^URg2R7EB)IzkQs54(@iz0 z6Vs9~vr*kq0dXT1vDeA1lq6kCTI3UEfdjkDW7Fk7x_Qf2whIOBMoP&9x7wR<Y0h0F zK^_NblX6t%B7C_07Lf<ShtzvF=4SRb@<-rTmzx_af`;5_-mIOc4^{+UPmHYGm3R?T z5!p3;y-c$q-M`%PH~i;Ql?V=W5|0r9kSZ3Du+|sPJ>|BZt^I9&JvaAVlx3cjaR59z zL3y}nY`51K9(ztEWgAqa)jhg1Z*Bsgo-t>JMT|&)@=ThFA1%GeV5YOf>q7T9Lv8Ip zlYoNew#D5i9o?D>PkX;D?mZ)}{DDQcY9|#=?YnP2dc3RFkm2!EY)nWGQP5cK`Vygt zaEUM@a_x;_*7f!dAxnoOPTMO-!-CAhHLNevC*haBHJeo3o3U>pcm!cNq~gWz^zY3N zx|<3G9(G7PytURmf}W!a<z9^)0b{Jn7b1V@1jM%Ie+6N+LS%lmv+g#)Rf5cj`l)am zN*XRM@$T79^RtyddmZmr_7;QZR)Pz^07f35>jIe@K3tjxg0$P(#U4eK-AMf!(*y92 zOWMsZW&!j#dIWM-VWp$erfxH;tpYepQA5fyrfX)rUAu=_w=Om!UgY8R#(rj96(EWF z+%|z55g6iOa!3Q^H0?EFDla*K_iIzC_K319XF!d})~b1xKq*N9IV8MNYWMpX3%#?A z=UK`d)!t=5M$#Qf2}e%bf*f*UE2iK*J<J&s(>%G`hZbiooc#BnbA<Ym<SJM5o<!7D ztqMTdq_-1A$W&B{j1z@LI$;pK4K&gJmY;i@XMvx;o+DCj4@ziC(U?er`0f+Iu6cM- zy-1_m;$rY^x0Lq;9EpE?3x2y6M;GM<@^KsF3K+xDxsY?t;%alB#%#)BS;hF{hlCGS z8Km4EfNop)fWCThXirU77Z=gqOl~78Bh$k83Oj^72b#AE3kj^khu_0EYn2FEhW@)= zBH>i>drsNN4uuywn732!M+%3;_z2I0G-?Gs<POSPL;Q&_HP`?siiVz;cy7!f9+<z1 z1NkL=`OR{_yJlp&H^32Xh7;sLvKY$^a+}4W`MEmnA`c5|;hSGYs1GmZI@Q9GTbcZd ze4tcwGLFssFiE5h3EiAjgl%n)8yt~%!iU!3t!_BFK{9R5<t*euClNJNQ>1sRsM-3) zZjnuzv|d21&`-Ci?;H73VP`|e#5-$YgR_v#I;5CSW~zh(!7#dCtkCwZ3^e~D7+J<5 zIF!JwO9NSY)yY1)T|A;&jRRd>UPtVDeby;jbNP41UD63i{Z6Ro6Ug@wHmhSodwviJ z^dJe`)urdF=J2@4P{ZUGkg6Hc;`X5})<SgCTYa&nGghtx{<CLTQllnGHqKk%ahmDF zeWL0IuM?9By(c6&`;SrW^eol;%t4NCJ$7tvUUDxlsvjwlwNbL<|1Qb||Az+0R#Qjp zABJA2W9UHy_oQ+^AGXn}NN4cj0mIs#f4h5R$pKJF>D(F{*KSufx=N<!A8V2_I7H9O z&_H}Ywb&}k9)F>2go6InDb;fvyO~!T2XQO#sdrz12F;VNY-*WmRZX+g%umc{0-7U> z{1P?PsK(NFm>pTME{x}SQ}QQQ`d>oDBlWkSA-hDbnN@awqgs(Ml!?y0d`RS6=`|zW zHWoQ#wwJ?6;f0XtdpBU$m2)3Xo^!2gXSt?&&H>>A5^hf>lxgTPkc*?FuyhYT8z)x> zM{xk$@#FkT4<3@oEIt|*SmfN`a2DEaXU1}Z0-3)$3pv$9*XUlSs5lx4Qp4jQwoLM^ zuCL8G3eQYc9ZqB(=Vx=Dt1?Mv*n=E~3>oNGjp&-Q0<V7e_@p=RY<vumb*VzZQ?ZxP zV3`9i(|!R#EM1kKR|ff1fRG-+`Pv(tOimv3cw*O(?KC;}&*Fnmn;JKBh;g%zXj8tv zRgC^b5me`5ty&q6jnh+NYHCG^Xt@WDMT?k2Ga}Z`-Pm+3mM&*SMm__J$S5u5w<e_x ztrD<uBIw82E7%*tOrLFOni;5~K()YM)DJ^n?n(bcK=H>h^PxxiYCc2$2D~qSzq`M_ zXdJ(xGiXq$`@SYeD`X91xlOv17MXRQYzQX_WcNRAe57}SBs_0I6=JU^&dT}=zO&e2 znIa;7!d6a){FWGX2YXpnUGP1>v?<zEN8K04)}4Kqrq~!B=g;z7*@yW}>c}ykoy|9Y z|J8d&9OhJdp1?0WfA(SYi!T%KV)aH7BsIk02S}~jp}5(+<H=KHjobWHr`8{|Yk3?X zfu(E8#!p5xj`Nu{VC!t&ai;o4Xz0zca5dfZTlcQi@q|3$Vrgxks%A*_lb7P9)ZhGf zaxG>s%55FbWyPdA6#)tKojdqKBl*ZVq@K=`g+%Mn9@RZg+oVo0d5<^4y#<OtrG5y{ z9)4EyP)CiutOYSCq3C78VGa<-JW1vmLophK?Ch)Hnvd8D^*aE&b4s5sX49DGIVMb~ zL7*rCh7|CW*VY<E;QB8AJkf?J?R$b^^D7#miBj~KAV8=I_yY)ZNmvpZ+7ne`zR`{w zL?UQRxp}!ACSsWQlizXc2U%E18{w>O9A-A`w1!*FiePST&xJfIzU2*@NDQ6(Zh%ri z{CQ91sTTZ$6UurkP$tX#hls1l+jLnKJPSQ-iGcKNi*zyM2@H$X)d;Z#!fzQOWQZ-k ztIV-Pp+7{y0)Pk^0G~mYsjxC00L9H1mLswmpXKnjP~bCxY&-4THAa(M-pDEdG=;)p zjDsXfO&MA{v}S1+dD{_e8FuOLBgB!Z1HMRVKKZ(@??kKAogEqk^B$tnZ9ob1_dT5+ z6475<c*lY+U~H<2*c2t2aIbzb>PV>L$mh<xSKTQ_PE3_-hOm+v?jS5UW0kY6MlJ^_ z5T^)tA_=)FJH*wyD%c9&%Yd%hm3eR!l|CKmmJ|l4hyu8fBgA`MSV$I9Bmn2NLd4u* zbo(i*QSjK+Az4Tg3HI2A{o52_>=e^?@KLj#{Aqc#y~=A6a3#ZUZV`Qap3C5r!2Ay> zze0fxgr*G1muBHuQPSZdM`Cx6rCurrZz($`fM9N{$VCb`1I<%G$L7>5yoTiQtwGdf z!`o`5QvE)3Q3QkJd-q4**fg_cQHeu(Yf|rKq!w~zGJs&oCU6e&s$SA1R3a?uv5@vO z_feF6TYJYCTCh?KHh`(w1#WEAu!HE>K&vc4Lm)=Kz0%G9X4+G}sVGWEckD-4_G~95 zT3g9v!?OH&JSm_lIyQxi!gjvk#9)C9#^*mVs@k%FRW+*F%*$Cs9kWK2$P*KzPU8_1 zAtfBwJW=o?;X&sZDMzB&WJ9hvT02!j{I)%8;xTuYVVqW!gVPLTa#h5MKvzcOHo@_< zQ{WrelOS@%l_tU31no3w#KY(M@$wgY?F~Mn?^po@R?wbwRvbZS)-*KBGQfEei!em1 z%~Qe<oo+4%f^JyAQz{@pqyD23MX-e^l0B<0e`@&4IHBPgoCaC_R|D2T_QSX^=3Pda z!`kEf*XXYcHC5k>OLRL;5-Ow2nGrcb1dx@&g(1hK00NV4vt;1KPgXHz!ytoX6?Yqd zjszlf7)#^eK@%v<;#g1!kyu3$F~sp5Qwn;}V(naRTuuO2f`ClupB@J~H;Q0Cn#TXL zR+Q6hyU?Nr71|)O3T$|<s@eXCvHjg;8|=f+O|s=Dsg5^svtX0DGoF||hBe`Y+KIYL zHMH?Byq_ezQX>*mklcdalLPdY`e`tzI~m__`df6HFlfu_ZH;TS$t&RT#BnsCKn@fk z1&YKmmB@F9UcAmFyAcD?Qal~Ij%M`Q^6>s{_QNe--5ubgNmV}TLV~hzf*(<cEH3Q) ztaZl+Is2GNxlPf1C}{g2HnG7_L_)Z%Mqo-^c%P1KB2NewAo5UDOgCLm9%~0#^LVa) zO@G9!<2s^nLfOXj!;G&`k*Gy51#w0rrUFC~DSUPNPDjpzc0j56$P61vR{^ytmb5EB zUidt*a=$$|<SPMM!+~umaJm$ERIHzSx1Tw$oo%t-_d0mmH*Lvp;sb!8sGq!lYT#xy zf=RXr8*}z7B*OP_w<r6l(?`FD-GSGBia^Bd{yR+?OjX^)YtcZFQ){#(s>mFGe~yY2 zSw;#vpo>R_WwJ7Rb6T#rK#IK!WwJg5ZpMcF>Z<(%7T%zPI#2}a_HCk0!YhLmUrKv@ z+_KZ1O8G{z@2(LvBXVa@ItwNcj9w6NClTB9<eUI~x|`8IF!U$wVz4^;2Ql&^SU~|S zcLjlGg)qBMGbJGfx3P%HgvKkzO89kAua37v@+V`@Pb|`+ajqR#j4n)K;cfu%R5f=2 zQlw#<0jV5U<C@CAfAsOG@cwsJ!thZQzt)_Xa7_0q!iny}+)xizB)wW=y#^zxdMkQ1 z`sS3_$|md|foBQ;^R0#J5os3z<libtyhdamCvryN`-2oTL`re({pzPC{VqLfOq3}l zPy$fno8KhE7JenZl-BD3bZ?-Tws9gEHHg)8#h(zob&qAkui`-;<SwnS=VjL&l*!Yh zNvKWwBfmvf6Pv^dFA{Ml9ilc`w?6-hz8x@;lwDfn4R5c3GGST&RnMAGqR2@8Qylyr znx_r$SB*`p>6@v3@r@>FmAxnI_@1m^X0Q=-`X&WDxe5;<!W+zNIX-3WXqh><m8(t3 zjnGNA6Jz(*G5xu)R`hVni<!xql5d<4Te(-eT8gQqxR!S@-q?9bUo%N8&pi}mjQL70 zQY8w_yN^Q{;RLcYl#**R;m-r~%;{zdOWm6DvD%+$5bu9f3fnzV_$fBN(JbgxvE;6x z<r);K&zAkx5V~D0(n-;AQ*9hT_6-$TJ^Lv1>R8Yt@xOZu`HGIEy%!6R>&o+ouo5El zABvS8%imBVzKKozi50OSA}S~XS+Nr5ai3#l5LqpH%*m3(ry^H=m;I$luLGWZjAQi% z(7uCJ9<cnCc?z{R=et|7=7cH@*txw5rtyAV?DXZ_9+pU-xIq#a#)KoZtnubGZ`x{_ z5A!*V#nWivo@TfS5_~8MUiA`cpnx=L5cAlO12pd;MZgFxxLXs;@4=|}gR35p+^ulB z8hF?K&+pjKH*&^DMQGN430!snVg?#<Pdr7N`q78@YO<SmHqKaBgF$tdXu|-$mdf?5 z3Rkq^l9&7=bV054K*#6oM^K%P`$w#>!<MpS(uFoU=r#%>gM>E#KzdL89$Se-Y4fOH zn_2-GA(7roxS~}rIp+ngv(&whf7;Oh85T0a;@kuY3A~4^n%u1dd1(hzvR&BAqa&}# zM*b2T6y6m=KnGgvsl8kK6CpWf*yUj%HzHR8K+apYcTeKk(Ocgkv`_*7Vnx&$p}=kd z*sK8K2{^k`0^3}TNEot54xQ$J<Tb)JX#^Sk3{LkTRjf_IT8IK#0Pd`30|OqtNB;>q z7i9$zSvM$g@f5C83L*`S#YY<HPzPUr*L@>+#o@Yc%P1PFi3S^naYN;0x!)rhSzsRP z&xOxP$mHG=S-mZ8$WObnMJ%KOC8VOQwt*I;p`?$|ynK-YGf0s`G~XGLy9xK?gmu#< zPuPxK{hyz8YRkPhT|+3n?$2!4sTw&AEXx|@&F=)Rtpt%MK{&%^%wkQ$0M^Lq>1x?` zg~~t8#BVh(#*N$2!k*`>;z+};h$@_-#<!8lj^7YWMlR1|;UQ*7Nep~`85E1<_D$fa zBMQx+5vQx595nAOCf-&`l)=2nBFg`m5;G&QRwoT3oJ)1>77H#;8DG70C8<mOn}`OE zt)WK5WcV|Al_w0~`k6{ZG*MzEM(@<^_}=jrR?@Ne!|%GOR$Ii)Swi3WG)qbH3D2Vu z+g_j`fT5Xg^+d&dq+>nu_ud%V84rS;Cc*o?gno*$be9Xa;^0MC=zIeBF^KmbMPvhs zD8eEfup(z@{uqGBK9a8qARr1!pTG*QAoUi^HRA3Xu??*DA}PI;Yxf!`a74gAKTS~L zC+;8B*Gm_v8blIKxU(jiNDz;AE0zO5?2u3=%0?j;l|kXXgLM}rjVgZK^j-0g5<g@y z{65hC30n0@+4EIa<)fBt;T1!{Il4x%y0<T}fwv9fp5EQJFe`I;|NavN-iqVNK?!Ym zu})z{2~<jS5b|^I8YJX=<OC;JibWybS;3YNbLcO##?Nm3jN0&QYUoEyHZov<!ZU#B z9|PZK(cd}s;TDHP?|*MBZqY#T3=gU@JME{+y530u40pf2<SF7^UFEmIvUgX5CJ4Mg zi6ZS4A|?PH4nV;`^yW<(uouwtq{d$O1HVSx59ZCNKQ%v-gPJDC51*hl>M9Wr&gDcZ zJ{^ys7tw;tbd9%h@LPQ3-d{5pBrb7W`qPX4(|rHW(?=<l)L)DaL*bL7-j<*{I8}#! zwgxQ6%<AWx!m#Rk#5WwIl)`gNU@JpGPpi3gkOGqlU_%P`F)9Ht$X<l|$M)wf-YQRo znw$vwt*s_=q1ifSd3zy=vsT=^T;o<z-RQfA)>V?m$J~KD(jo8KUle`{tLzD*j1_a6 zDl|@2>fQcx&Z^c#t})6K($7$9CP!G6>)d5iZ<%X$YRupsrAh81zIJsKN;$Z{iCG?d zn3?KQ*5yBvAdhK;@X9D??{1;!8PegGx~^=hum~I)-0KXpmnlrKdZ=;_boW97L`dz% z;mVIfe%mUwcOTlrR9)4(wx{bX%MG%1UhK~Ne;I#iccF`P^>3`>(yQ1B@#aXeZRh84 zeG4yq{O?@t-JC2}<aZ7GtP?w%EA}!B_S-FXsjqSU-`&<9>j%{jgh%D?9{ku}qW0al z?fa3V&_S8~_(}n$<aOVw@`?W>uP=`e8|SlAF^I;_rem(|FEj4T%I{E^iHpxTR5K(` z+B-%BVtoxk(qldNEPehQLl%{;{pY#p|9U!e1y#z9n2<>^Gvn%$+XC52pIB7isXgmA zw2*iTOEi@z?xCdc5`NdDD{T;lrZkr4Q~gRj!p8j`*l#*PG?z}Frwb(!>a4X^m+P+R zer=7m(fexVn617sj=!S4Xot7fki*tOG!C0E+q$h?-sbQt0i4NKwT)^Rx&LdTFO_Xu zEgqFRTdlP*_z=KkWi=l&o2})6zES+3rEOw2;OT3ZYfldIXWwalg}t1V3?owkDI)jc zy2fP(Lkg`m=3tp}kLD9F?<8O7UA8otiDhtjamy|9;Kiq?jeW^EfwxjoJ3}!L&CdbR z&MnsUnZ>Q&2A<U4IUQ&E?$l$>oF)DD#q3*H;3;Ps$jQsmR(IJ6W34|gUYo0U06MW8 z+No2u(%G(a%+)!WEHp)YGE&XbAqn_QsxCU6*!X?lD6|=>?*~Oo|0^2wey7&wFu|wu zAn{~U^}#WFR7dIKRH5+x>2bAV8WpF{N;~v&-wzw>8y~K2)qypRt!C?_j)pd@-QDt4 z3pFWnjoBJsigczlx3V!)+EIASP3_>t#VO0b`+sdO-Thv9Q+I|1k|p7hMCBY&e0lc# zJ>RvMJ5YnUCiNa|x8~p*TV+pv%7mPTwJlnGUe5TcGCTJ;6>)pp!W0?X|BZS7+4p)@ zWLOjO03jOs`1UUHZ<zfd0s8D|TN2Bfv0w~2|4$zG*Q;Sqt8HyxI~|X_`W@O(<--QM zPlq>`tvfp!h5CdzfNt)a0c{LuEY@801Xs|BA|F)+L>7MZc!IBfyB2zz>?25WO94Dk zRxYuYga0g@m(@68UQxCM#cVUc)sC2zyArwR<c9UhN_YtrPUJjpLCFlAs(gkN8s%ix zs&;uTaNR~)trcrmQd=19h1b2}NV=GWt%z+6hOHcq&;XeVuXs6wsQW>Wmxi#}T|3P} zi`yogmVSjd;xLHYd!yGAupmnU<!*~zGVLCL-Wj^!6!vFCBgmViH4&K;(^?C^Inz78 z9GPnpIc072BD?1^oAxK=oQmb7G0Z?S{L8qF{`}FH8CL;3yKcixW?{^NPbIuBJyk_% zCS6UbnY%2`L}vq?gWB4Vxf4<^dyVz&qbrKS9j(~tA^YqHbU;XinW1c}J*(~&G{ovS zNwMlz?k$?X>P)~S@()tMuoDC)C77s|M1s^O2bq`qao~A6CR#h5L4}UUX3<X1T|~zy zpN1=331pO2!&bRO_;dZF!Ccdjk7$}K5DO_qa>E;Zxrd6;-L%UzZ3Du*ylvz~*rwAE z_31oMn~W7Rrn7>I9)}4tYsFrK2JK^A3*1aNmh5F^pYG%~L`|5;TFBf8+|>ADR<7QH z9ggyq3_tc_l%46w&@}^?yowmz*qCm6AakSHDzwG%5!;6*1@+wRf)?jzx27L<TZX-_ zX?7WCDR#I^5?(zVu^zF9^fv!+*<`tLdC49U+t1sETlc;E00?<`mvm)T@Y6>F^VBbS zYqDROSY4o*^FuPR9s5CG$hM>N2qLz1?Qn$OI^R}{=67`7#=}lI+%yFSAt{FpDlr{U zcX1MemN3=3oR`E`?ZqU4YGl1G3RG_bfL8Ae3Q}qKx7u+u=)VnrF1dUL`y_9^=PV{l zhLO2BH?p|ao(w5z5i_y-G>ttf1!nLh)n^$44k0kg7on2xSm3=jMQQOAnT4~7n*$le z7v&zT+lMY^Xd(eQ5r;+ao~l|H#Vi;1fdnQujlOm<Z<%`>Tb1IX(XdGXX)*i)xy(^` zF3+bLc-ps5U8#TlQ@$hJy28|>DsI@6h_ovkbJ#Am7}@D$O}`yA6rE5@7|S2M_QQ+u zSxphlY=|{8H_KONN@d)rH$yXK7IG+$gZ{P{1RbX*E|qvONt%5HT}QDyZ(QKLbOzv= z;z%(F_z8{hN|wHJlofl5*Hffi;HToKU*Fu|eE&CXbS2R@17(XB6qfChG*M=8*xrVJ zcVkkN;bZ|BV|Yf*k~y<PnY3D`VVh(N*N328yUahuuDHwCo3lCB>lBj1X`#j-boTY6 z%z~oH4RLMvPp<}(8hc|4muF}o4F=tL>l3EtfEjQU`2hC*kWqxZnsK@Hf(Y;*Q)9T^ zZb)!B>{;2T?l)ljSE0tRy?GBa6J&05%zByv)5|{B{*9aXai^eQ8cu+`^_PHT!?q_$ z{{%(^>*0k4$SLaWxa`~8Vo^g0BS;o|7Na<Co*n|D&OR1;Q+%C&EWlV+2A7_9g5wsK zVpLR!WcQd~<NMDnS<Vx3@_^cRg)cJCSf;d`O)d^6FqoIB7>mv@k4qFdF&pN|!?G#2 zM#4)@Qu-e$*#EK6zv@xBv$$xV+u>Eq_u&{LIJugddHU%>^X1QyZS|}{{oee;0k@UY zjMy9ql{{hhlaoL_g#P<d;SY{(v^(zxTUOU(4IMhEPhfkSW$ztjy}9Tt4E;TJ+4)Hf zDMjNCQC-#-gIJ1a-?#+5)v6QgS#xcdJNulA_)AzoKN%>r>&0rI2Na(3I#qL<$+~`a zfiKO6p1Z4>@e;$JtKv%@xhoW{%1tkJ*?@m+QHSTRwp&T^QJm{noK)}bi!om2NT7?z zqrXq^1}k4+kUAu@hLJH;zH4TtzwUI*%)Gt-&m#F2ICOm^vO-LEq?y^Os0K8h$oYaJ zfgvuo0A<0BWMOaOxbDTQa-0y`p1_V3^IBypAc$M9iT6Ebu3KfPYUkQX0Pm1*R*rxJ zBE#dW*~apqiP0Jd*Y7LOTS!ad)dfu7*7(eeLXPd&#ipV2c`m*_cubQoRY~NQIR34@ z*Fz#(oE`IxYQ~PnTiSFCYAB#Kfg#0?wTg~4dzINEfytgu+GCYPhV$k?0&9d9YYBlZ zcs?bVB{g!}F;pux`XZEY2yOl9bBhHOVxL-C4L$c_5A|X|w=*>-Fj!TyPAJ*EAwySY zAs-IGMrP^70`}B^dY|A~@G1(PRA*j(%5}rV|3Qal?3T}+m+EL0@I-q?t3X1z9qT<Z zYXVu^%9}Y&6c#=Vu^MCct7DhH2<{<TXk1SpzR05%kTrhBT|5ezMKM;2Lch*9D>Y?( z5C~U~<6g-FKSV|t@UnM^B46iW#eG1%JQ-K#j05bUjNH)hWWmRA8A+;IeJ=i|X@WpW z%@3mBAYS;Mol?9b^kHP`2mwM?Vs=onQ$J*kIb`UJfc`#ao)LwMrG$Pc%~Gk8sCRMS zqDaPIGy{@dSK7f#D4C^0@B&J1_;JC)s>bI$@DabOClT^70v@&Hb6E^JSj}1%p=&zJ z`m7yHtr=r`-NZI*2i+ut4}PdYQ}V6TC8W2C?9(M|Hhg^S*pI5gPl^;A#*4ozTVCx| z*ojimk<?7xkOT-yeMLdav<kv`APa{ONq5=L9A-X##$NTjQa<2Y7r={$zRpg@D|X;5 z2e<BN=lw(lAHR^>^};_^!3SR8nRfPgQTFy~pkV~)aRU2(wc;klvlLiTBVBfwXm1B_ zsZN)%uH#k^Pcqs9hp82~azW7X8OZveAQU6N8aSTB=7C~=RejAoUZ&Q(q7hI$oL=FC zwkM{5H<_69e|e5eSGIX4ozR!SZro~!l2I+GR2VL@Cn+4hC|-@{)&x{ROn6DGWmFe` z$d;GXKpxZcRj3pPxMh{?m@G0Q3i*CmHoNnP%33XME`u+EG?K(=e9hQIHV;wuT@L69 z9fnS)a#Xs8nqK;uL)=FReCu&B@1IB4c524mWmc6SYUZGDFD9{SHpN3$YPI_w;n6eq zQlv!%Uvri#k@xc<?@>gozbLDCG<ypj_-`JVV;833ku{c9M|-8Mib9`$fG&|?mMvMI z%<4<xc(({4w6w9U5~GPJv@*~aY@F>H)Zky{`wkiQ-zUgyHM5T>>kf*wB@cA$RYyu| zP;aV>w@BAggM6-5_a{e-FWB7)!n*`D9dE%9#*jraq#=)~*()YA;SseEALm%sWNTVG zJ8ogd0~w<<(4dZQs@WdcK`C@Kz9*ICLd852Ei>urx=o;PQ78q){VbzGG~>z8xW$qv z_}S{^UM0rL2#Dn`2<NLO)(@MD&y1G6V6zcSq&nz08QNo?|CTN6cE(eUH11_lD6Lxh zqZ;h@>gj?<rI}lsU1L)ABGgHgnb^+ch=P6*gH&iV>|{Lqtz)X-V)PXy>5|9XNJ#8) z;@)U^CfD$k`M)qN9_R}cvwemU+kc^HG99%aVPD8uwyTg(CC2CEhsrJ;)g`Ut%?jGe z<u5E4ZK~P6ain)EcRt+}sygW$f5^=u1@%_~AE9JG8qbw(Cs7~GK6enTS`vlY<S`}Y zu?3SKrVDmi@0i-Mzp$5m;b{57IrxQZ<_q^HFPtp%zgE|a+_1Rq#SotWIhXdnoY@`t zq&xU+cW58%GoSDlr90a4<&EH%(U~rL?eQ@QVH@!;@3Z&df?wADg09Q-q-OS{XLi4= z0Us-|I9`W3(t$s%vj2$>&B*M1Sl(l;TSju@X6zO$P-1wQ2i+4*e=^bQRA@Sv_v-4n zf?9r|zulAZk>^i!^<M?`3B>a{i$f<+40logtDhdV$80H8^k(*tmkVvIwt6_S2XlbN za4i#0UMXkl&t>Mnc&w&%8G_P+%$IBTun$yY9#}*(hI>J&jbz}-VYt;-jdk`nM|+(; z9fFh9z%e`M(qUPX>>Jy_*Qlj8WsWiy80Luxh^i3b+l2wvD~e>w({NE{QUXYw12jT@ zFp^0CwGz?7Aqk7naM5RMC$EKJid4%%7a#7=hjj&_(B+7JsYwZT5b247tdtf@xE<@; z!}?$zh=3l+gR65s4iVr7DSXbPV+Z|h2eC2DLd)5+?hWzj4&}74LYLHj2@SK{Zj&h) ze*DpS#ey>$#cFN|+V??R?f1SEqP}0it@#6@F3Ltlfde0p98g+rw91g?!F$!97%wG{ z<k6o<67C$aTOe~_#~u~Ie3Jv@DB8D#8cmWLr_Ss+8!a*GqoCo(1BDerHz&uh6co)W zF)__LJeow{LndC}O4sO~-XSm_ma!e9j0GzuUMv^6TR`56f^EE*{vJY>y)^87-a1pp zN#}@KRd5UkRN>rcWO@AZ{^YlgJ^>5n3KUa~D1)cy+fKoEpDXm;h+s8okO~SUZ#6n5 z^lo_n-4o6y<g(|=!*BLLyiIcN>u~COO5jQYn}aBuI{EDaVY12nJ@B)H=Lhf%t-;HY zJ#Ip_u9*UdzR$MkicxBEXPtIJzvq|dRbT3fiC}T&=xz3jd-P=57B`}t*8JfRWK+$0 z(b$LS_DmGRuyUoZX&t!y6YC36=t5pGRV~~5^8Rdf3XLfnUzWh^n()pvZ~TK@6Z&9o zb1}?r4iY5_JW>Ly9L?QUn{~hI9V`Y-s-Be`|G;6~;d3{AJx~41pOE=}rcY$ZBEjyu z{HK6Lm}wV=a0o2p$WCFOjlP@JMhU$a>TSAFaP8^rLS9jX*t`dLE)#68kqxG<PRF6x z_3ao=?ZB0k`I}BNGyVB#QsBFXK;c)AM%VYy&kK$?bq~z6u61AY0goVf$;$qDYc?wl zl@r`Pkm%?}ufO!hT8L*j@S_*_Qafw-)xP7bMFPBJ5!L1Ode)h7xl?~hg9!1cWi8EP z>S||tU@c`izD#+?BgV?RaZpKZ<(b+$WV+g}Znm>D(!VTm;5ocjsd1T5@u2u<nLKxO z=2RZCyt;f`&1$yBY|O!C30`S_z3?nXLur~@5$&Z%@m{w8>mRbohxp!oy{g^uK{yOU zS$+1G%w6A9Bdn8-@JzatxmE#Rqj=34^|5v+v0SePK2BJ$>R%I4Sh0$Pyjx|AMOk*e z2FI>44vQK!{HC2-bxYAcJ+M$?=-?W>sP2$nPqbdI3aocXUyfp#tuE=RSUmqscJ$m7 zwSnlWf%TQ>oe4~K5vvM4>yz-JXLdj|$A*6)*whYK#{mr!th&VueP+kt`On!7B1?C^ zWF*W=bMVbYK*F6M)VXRprgpu}L5ErJI|l`5ju#ym1r8uVCQx)t91Pc28EQmF>*<%Z zJx$T>AU!(9d4kt66QdrTcUK>`77s-82M|vl+>C$Px<Y9U<1x}@Wm*M1np&S*1u)qS z6H^+8+Ialr4@^7a^Ah&w4`0921`DEgLlPKk$j~iRpOEK)F8cmX+qaj~kZ1Q87RZ6* ze6U>t@J^Mp`UgnDD#PDA$%Wo;)GD`J=0l)Jyv&__p2M9m?j0^KI)4=Nn{VG46pxOL zdlr<A_!V!+oU<$#czM=<RuBwsWTr|Q_?;ZjnR_Iy=o~o!{%Qx(J^aRy^3{|89FBne z?9|w!15x#>LC1E+kD9*}!oKiVf)64N9~pSh5e}U=+N^<FmGWB*cMlf+8NR9k33<_3 zwljsGKu3p=udvg|fvM;zpt9}K$pEk}qQxPS_me#Ik|^_SYmGg<Q;yf*qlnY{U58Ao z45O92->pv{B32x~0~S}B&O!i8hd@IPHZu9^OSUuM-ESHjyGqdSR`!tiu)QA%d$gRD zDy7GC^=;+-ZzO}?DC|B{!l8=D&bx06t_$&Qcm80|2hT-#lHSOrJ_GT40aV(VLJuL0 z8SCA)=dngVuV3R1c=j`5j$4ZXlKKfaN%*}ru-b6#T!*vB^i7E?4xIiBC|@!E$@af& z`G3^Wi_m$`Gth^MiFP_jJFxUO<Zj#irY+UN{`c6U-)i9}lZq5g0LSN^zdm9Xi0-Hj z9tGcdG6j>yDPdFRHoaz?#rgd2dj96M?kuEnj=1}b?|8)0nzafF=V2JR*6yyfYUJ4+ zwlP?288`FQwi=BOTb|ymwW~8PR!A<jMu-Dx)=u`(u*yzGzFV!4A9EIaBG}?pBrbn! z9gYb6(B`-F@!)b#<mOcU<xk(P_D8*}l<i(O>y8Q>_rrJMo%DN@eO!Y1pIZ0d{L;T! ze`Vp=Z?Z%)_PliA#GhPa{Oqq}ZoOqxM)_4GRK18sl8)*7hO0{&_O%Nk-?u(rKACNz zI+AYm-NF&lG)@+sxqrzwgl|vR+ctXM{nZ_Nm&ydOoTtS-BgY>;Z;-Eo+**C%?*C=r z;Ck+>&+i+<KkWntbuM6iKJRS(`9sfh`1*dvZU~BjF@{a1Ip#tmywywqS$y;3Lpe0) zvu-d3q8k(N%r$Oa;b~N-c4DgQ?s(vZ(9WGvR{KB1ag0!KKg&RE$Xw)T;kV!&iR4%A z2XxjOl!o$-IH#!bjEJ}S<`-*20*I><oTC+SLC6FKWMaA$EVPbCbprG@1gd*LCpO(j z+MZ!5zi+7g7!lpiX{w=mQU@~qeR^7`DPrFj4G)nKJ(m1B^gG&qv0}f_-V9yqKy8T{ zSTL!&)Lr3S6*mbu>@~yi-f-IeX;Ik6Wh=J@>-7$@M_8|Hk5+`5Nfg^&j(#m`7c@0( zUV&uI_b>l(IQPTtCCoT>;iaVUws7>H8bcueN3-`8VLX1ZOYI}4vF46{9iI0MF4mdZ z$9vYSH}Dpo|GZjomUPn-8vo+BJi4iOm5$nZ<AG<wgD5qx#D`Jc4q=`!VzT=N*16(7 zd&#_bn5@lC1&8VKxDk(YmTW`Vt91V|)rKP{Wair;^-aHnzf4~ORYX?{Vxzo!H|eAM z1l=1E&7I|eYc*>OT!+dkFDeUNJZ#m5jf<^^4EUrr0yk<%8@vx75q?jNZ~UeTM>I^Y zCYT51NcXpiIcpr)-OkA<yU~?zDxjJcD~Sl6G`GIo{ol{Nml5g+D`%IT3;q?l)P~&P z;UAL?@bigy?vFr7LLL085H&jV-AT-4nTHz-Moj#MS`F~v9_8-nkC)%bM&x~z)7*XK zd-?MXly(O67f5mVd&S>>+O@}qO0HQq8MIA3(eZbFCJ4ng<(oo~W&xstMkK(E_-~P^ zm3>6rZw>#^9$Q~tqsnU<1Vf4h@h>`q_1_q5e)SJ`=;_N(%@8tFqT`9blM(*27GevE zLorC&;n;n>fbcUEi-}z#cik%R&2&yyAjyJb$)tA?(7~2smn0^RWwq9#65k0J<E4DD z>{rhQ`F5Xivc(ZOb2yU3cxspx0_emyD2f71_GuXL3$_}G_+=jZbW7h0j6c5iKZx@Y z(kV@((m;aZ>h_tJH!j>{iEG$TV^Mm+_N8S&OXQ@|UWfe_01_HU5+3m4B3Tp(H9KC? zH5?7)A*5(5+GldlCo(XV`gG?!Fg0>%4ZMHEt35G|CXxS-sk88k;t&7*uuTu4g4EL8 zEwxLxbO<6PEFmqdgf2@hAuI?;iIfTmN-7}e(g>)e;uoY-K}iKgxqHw3oqO*eFz0;E z%siht^L(E7>m`#tZn7d2Jjrx<ihzuyE_8blrn_B+xXzX#9G75Zt3sz{LzAMZKMsvP z&dRN+di1Q}p1gmcAlK&^gfhx;WZsUoplt6dW28G$1Jy$xiBAv{jqmrE7x6`=t>d&` zG6W5+peiWIFcc@n|15d(GHw~mTo&?Puw)Xoko{0iPtZKd0ikiP8p~)`2Du<*4ws$j z=APxe{Gp7sEG8#KkO9mCT`{_BYMWBX-&Vf~BqZAxtbydEarV2+6$SAdhFi<8cskKA zesnyY;qc{@=oSTt{g!LV1Sw&_?lA)2*Kp+uXaB0*6OA>$%W=PL%MkX}dcywJcTK0l z+!NTV#0G4NhwW_8tJSuT{O#+b?dy1zlg`Er9lCzoHzc2{`$8!r4O=Bkad*>SN4r+^ z{dQ;@uzx16?isWm?bx|~RK12v=7%++4Apd5(%fMJtb43oA`Xq|*8{zHG#n-KDtYcb z3cN1($7$5(=UMH|wOSvoKhEWD4IGA>Jwm)oNHJ6on==I~KZ>|AGobRMWT!Up#-Gna z!<BqHWTW7y+1Z<z?H9e%+ZOW8jH@E5?E}*p->cuwb?mmHu$#mS9U+Ndm*sRGCCXfN z`tRyXlGlCyZwQs4KVrL&9lO@TWuiaLo)0a7vVQBt8QirZ^>nGqEKCRAkyVrjkWLgT z5t6{D$@)6OlbuW<iW)Z7Qn;OZI5=k#rDHu9B>UfRowqRh8^biOQpvDRPPw3Nj)u1X z>XY;dO^<4}KlhNMJ$4VGY_q)Fx_e<zV?8wM*Q^`wHz5sW75U7Y+g?JVpNBBtLnDVV zjN!+}L#AicIDLKWb*Yppiu3C*wdBsLGG6UH9wOm|?_zzFo)o&dI2;hVTp0wSp1y<f z9+d3F`ifbrzvZ28xK}Q<<~QK<AwlFY#$(&-V(`mBTbYPTp1)Swe}0V^M9Nq4#rc^- z6(@cxPv5KT+{E}^nW~K3czpC{ZMJo0qH12O^y=TQJdK<mftc_TUyDV|!j(_2EKM)O z{S9zOy3F*7@Mk(02YQQg5tnzvz4QJC;snXfgw)8^`nVf`qQ%qyl#ik<>{l)y;HPIr zqS{?P-8gz7$Qv?{nGmTN6rO&s?ci}#*G~PX`j0>7|0D;hi!3FzM0c}stwwdPn7Sm0 zx-QW#sGdFN`4@6;=;E?@Po`)jB>`=oi`*+dF8DeZN=}L8-*b@dD1UWdA#j4hN)F0A zY?XDViDO<U>+#Typzzd%IX&VYgc;_66r1Trxrvp$zjYW|DSCCw%=dR*_<Y1;@(?|C zH-T@|J%ty%YHjrcoM``dBsa<3DUuSTG28%EwCh@v%{oc*m5FQ{eBkV@8q}{mpOBha z!E-}rZ+0!nqyafUdig@9RZnOpm0ZE#CP(#HIpUk}Jp1=lcNc=AaTi7&^K4WjH)fZ< z3qP6JuM~|N-hAe^3b}Il=#JRh)nJdFH~&P5*<IaXS7YYPGLAs4zu!M>MlG<({puBU z+D<*Yb1H1YdotpC`@rKy?1s^T6qN*f^tLBt+xOa^(s#dpcAdrT@}2S-pBf*(yL0=H zYx?)MAJH+N&;B)8@%=lHHTk`B=g#Tmbo=l3ch3H1#U=jHq2b2drq?EX)q<ArEt+BW z`7y{?%rYGYRf3`GlcKG|FpOe4Ju#uW7^c-y_$h{kyL)sO!y54b)Wm))*E!Elw;6!t zs6w5jV=rc)&Q%GIzUnqH#qw-p`52IFr`R`3Sbp>3i<&(dc&w0q52vfHkW`N*ovzsS zMS&7s$wMvi&Yr3oU1@Jl(No>KAv$v0y-7G-g}`o^mWNX2dXx0ZDzSQeqgb_79+?vA z`HxVma;IKtsGiog9yC`^C$QuagT8K6lctpZ^CdlfSN%o}eM9eDY^=V?wuVTtzJ#5= z*{HsGxW0uQr}?(N6}OTlL;vcDzKy1V)d~Yvuiq<`x}7sKW*9gpN_rI=xO5skEmCov zGjL;<_&&i~N|b#No&JDzphRH6!#llHVL;DwV8=S$li|5{!~l(HI<CslKh`jy#PIs+ zzzt19KiFWa6Ey=q7#3)VI~<5m8Vt1?4A3<CE2sl>8{+E*Zt4$4dK<Y<4F>lO#zh$2 z+%~##IvCGx93wOsduWtUWt3bum~1{2uRjzcWlYo@BGe59wix%5DJdn!ckRxMGwKFO zokLMdL)oi?<V52bSL5tc<20$axe-J8+s65JZ|}iO3KHKIxzgt@rIv(|N+G7Dtiulj zNo7jI<@&=F-lR%z(+2{>Pwa-PBZeQjk{-7V*YpiPAP(2sk?M1YpUo9NuQKgl9BzV* zXkbSQ<VITc&0d(BB@-H-9uC)4jWkXTcd(B%3ym~%4!2K@ydE8S!)@MeZu&aWtdn8% zRm(`1`RIW6Xsys_Kg_%@adfb1^o8cA_!4Q3GCF){-W+Q-9%0scI{G$uw8w6AYSeVf z?%im_=%<#^nX1w8snLl#i@`pN&vpzpYAJ4~7K?L3d+E$C=`2?|4g3ojL;}?;*E9N) zW|9d2z<&aRdjkL<l}pn~qYan>0O|~&K~cT0i<mIP|9D?hK*3AwqD<UssT_(TRWs5{ zs=#WGAGb4^TRjc9WW(0h#0`Y57!M1H$y9aU1U!@fpjem8Nn$kkS3^M;dE$2vx0N^# zpY(-jG}Ab>KjC|MV;SdjvuM1EVgY^GxH8aMr)go_NF(>DMM}RKAxxWlzkcQAiy+~B z?jc4Ob6{<Eo#$52?qXLmo21)lTccO}WQf3R?nXZM;R3~g`O)^~jSppd>AV&lEnAb- zwol#Ob+mr_#Q5@7kePhdi};<_TaSlgB-dYcz}>hvrAscy6EEBkr*&6T!fkfe`42Fa zsHTmmJ3h_-alY=y;+xqsjg5CMyQ89yXvQwQ)~bu0u9`lr|5L1V>)-1?v&@o?x1D|( zLq{*I<3!%8eqKbD>a?3Tez^0q@7KG~!Y@A;*jd{uhUpiV1kv%M*5_wT&$@Mql3TIk zODXIf!V|iyxXO3LhPmD(nSbUq=_%0HY8<ZgCcW>8&t}*XX?~GJ(HiUKDr|OEJ!>nN z4~G-;+D05`8tq@z;g-sQj6M?uZY+nH>J)bcI4!-89|7|2P>)glb6yfyh(CYGAOhK2 z@zpluK;xkAPW3F*_`}YvRoI?4ex&(fD7>nS7|r^jd_%n-mkU$B1ZsqK_+c0|@q3pw zKF`^Id|V<iWm%%3bmpEybNzI3RN-^os=!l>NQ9;0PJy+F4!;ukUZ{$_^63Noa^al% zl=}fQs}atFfPNlLow!IHj__^v(l%pME*V4X@*v3WI8~MU;ity)eU(;<`C|ZvJ<ELJ zgMxSak#w7AoKP_Khq)ricIK*Qs)#<J4{4KeMo{SLj1}bo@i~`Kv3GMSPQhr~)pu8* zYh$h+h%RX6Jy+#d+_rEU8jQxetCW>8U|#4r)FqwA9t0oOv(ns1oV51r^f_V-#{tP< zx<-Q1R%)Hn`pvpc${!{5HjIU>CO1lYo2KZUZJnl|@so`IJ#58Yv02AUk(JgG+mCP` zH2*ql>~k^*y&EdO32npn3bTX%uRve`6kvkILjG@o{C{F(YJr%R7>|1-({W1pM>u&@ z4rZbC1ai^Xs<;1JjO_Y$mzaW(@)|BNX@2~!SS|eP+}q|2Bbasq9S>bu52C{Oo`m#J zJR}iiR%!acw6%8nsZ$>0-Ega<IbifEjpxr8^m8+Avi2&q@7x2U1vx^@eyxA%z#n}5 zGV=2I!W)MrI=hBe=wdGmAKERWS!iXDENE7`%@RKs&jAc&EAI9h_5zm(kIktCGH7T? zEs&x*NIY6w4rr(uq>R^xf178Vp#l0e@$`I_CBjR@V1^#?_nqzGHT*DL+J6wt{f(Js z-v!eUHi9B-f#Gbz@^$B}d}Y90Jp6T6%)}h>wM~;ZI#0Od0`Ab<$j}H8A|wh1{WynP zj7N!7yW8=^%YjHsyVXKnCK=pPQY?QN!HXku)5DP|^RbC(NgQrD^=c?-IZf(!VmFe5 z;KPBc_+p4o;#hS8@4h^mS<b>Nv(wmN&-;0svI%%Q`GEZ>;2!J?el^!F$zUzd$&F)H z*Cu)DdcON|OLu`szTbKw?s3g}QJ_r?28!&Yr35f`eq4WmU#}4@pyLh!tdOJ5R<SYX z{Wr@=BDI?p87f~lE6IiuTUEIZ{#%a<d}_BImqdQudQz4w@wK`t-~Ve(_2b&FwRJDP zetp_7a3=AsuH~cuxB9mA+HcP~e}4V;oPv<tZs<E7u-!N$@^rgtROQ=t^O&LJPRo=- zz)tIo&(ob3bCKV6UM?m}es5dN5BT1``S|Jgj%{9vOtqZ>$se7E9|L}L9j`zA@%r@V zw;yi+q|`12b|G-L8zow|+ryx`z1s^KN$vHqI|lCcbNJTn4RA+o?+v0;r1pn|?g#F_ z6?;<mKVoFLL8*gLrB8te@6<Nx4&H12+E&!>Rhs;uu5;nW;kdDA{o#Z;mFPFgh=m+Y z**V@gns$mRVgfo(6{u=rf^_7JhwqJ_F9yok#y?%>3i~-bq^rna+`CHi>q~!ay_Gm{ zdN!dt19RRto4Ix`{?}5sZZmnoo7wxVT=j96GEmKtZ7Ciu`0S)Hmfns|Vt~U=^^@39 z)5%srMI~N0_L}yXTr}6=Ta(;^%-=irdY*wRx9MSOx&`+q{ut%&dTM+hQmnnC*X6SR zY6JCm;)I8n(bi=B?X}|fpGL^kMbcN^Q~$|qaog&LOQ2l}rjC8(hfuOmPxvnuHYnvQ z(Ds~s0=@anM%)+!7roN`T#sWX;2In0Qt}dGQVkSn=)H!WQF$@K7=({oDcUvd*14Oj zOW#X@{oPF>RXy_J+(hxnR`XLk;0#;<W&l$*j@>`{5vHa@TDY|F=5CqiwG4OtiL;Ds zrU=c-n00`!$LBuTgCQYMZMBU3kto<oD=QSWdrhk7T;DdoP?EnH8pfHNX)n|ls|6#l z%l<;pq<Tlk9`wtg6m(@30)l2|ul(XwW2oTYzIXznI7RO3D$`X(xpS3%tJq-qO6$!O zwb_4ui-Xk!j|6fW1fQ15ldo%9@odfT0{^jO>ikCo<N_F^_^+2u!d01k<!($9Bv2<v zpS5Ucm84WC!Ij3EPp2`!Kgq8r!YUNl!!-wE%h68D6+k9y4((|+rJ7F+<kUh8L^QK$ zt?-^`GA=Qw&yO0#2umChtDuhH%jwBMfxa>%@ZT81TNC7Lv@Kqp*gWe?sLINxFLx7f zQq#(J57(a_6$T>JL61%WTOvR}FZ-gfL(dag;243`LB(6SP$7S_K`1iE$Xy_i_d!T9 z#(_W0zWT<^C+H!>AAU0aP&PsJhL89Qz$#&v9mwp|;{e<zvH~IHZFN4%$gt!q?0w~s ztwh;nYg0Ejao&w%gs~;Z1pCBu@;zJ69({RcU`+23gue`9#WK0{*(%RX(fBf#?ucJn zUy+%`rZ8N90l?U!htYi^U&|SvYD*-QZ~OCJ#_J}J>lIv=Mrn~)7;&z8$@0P|ez9MD zVh{>1<7ZvPN)xh1K_uFS0t437z*m-iMG*B(8~S~#gtHR8I))g1+L0r(fydz)Bsieb z($Rq9PUM|Llf<mX+m*<6X^!kemmis#-N|)$+#Ip`n-tyYHuizQHl7#-7LAyFpGNm= zN&<oYPR4)F17)M!qEFQr-0Jku(`rs~Fji+`#4>tddx445h&;~g{lvfIJLY@YVxoBt zTO}?9V;DN0Xg8Tt*td=W{lO=YGPZpH2<3Dj-8z?pUgz5D&h&64>I*jQbE7nKyEPZ& zCm)7&B?$ArMJ62fMBL+kgi-3YO59}aH5gb8oE;IrnaBj_n?Jd?MWwM{?L}w5LtuqA zvGEiEerNU}KWXcfo%2<h23jbdL&DpuJ&|Waj3;9Ec&57|GRcir4zrhBH|17-z7z=0 zlL4qIHX~N=3w6>co&hqLe8pota9}lASrfdDcS5t4DppYnUTB701U7L=(xN_dI9Dhy zL_L}9O6NyO>h-9TeQZx4t<0_kJ+Qf_*I8+IRfZFA-(<oH?X4e}w$*NIRXomXQr4Vp zZye!3Xsj~GJM?k@jy_NXW0NwI_G$}a333$anqBq!7C*Hm%>#@vgf~QeCPz16ULy<> zb~!zze*Q>w{6cR0OPm8ktAxK(lG5bt%IRscFmqPq8>m&Tq2#EliyGvyqwlYO<jmZL z_xLAj$``&lC|+a|w{;fm8-tvQH|v@zk+J&KGj|b`4(Is_6P(?$dV8=g9@}d(|H`Ag zz(|hBLg%p`H55odD$USlckdjh0CFd9X+3?C4n5Ri<-L!XZ9FaoI-pyRFTEF6UT)8p z<@v%fsETH4bm!LFY!)MN&UGhWDTDI788hJEYFcTRzdx41q&iGPNG6FbX#j0Kd_P0T z0?)aC=QEc8IeELgiGnN1ro#L0S+b(>uZICSWIs`xzVbpJC-r;zm$&H#;3N<Rgdnjk za>vA78b)g?6mNqYS=e={lOl@Z;E)DYC7d~n-IF;k<)xbEHh`}T9;8V-M3=wOVh3hq z<%xSRJH3z}Z@`CVOc&I_H#LxR{<e~OQr1ZcuHF3EyhCoOcgXV9*lk$3yuo~zXl7=Y zM`#p7kSbX2t^?!0-Gsae$GW>Dg#Dt>QJGbcZdmwYw7n{LlMs;S2zn5ZNAkP?1%@H; z`C!5!Smb3iNImayXaFOuTtZa9y<c~fhB)pZfC>tteD@lpT&<J9P#<M}Frd0gMm|Do zXDNc=a>(n3KFlnLA4d2hEL0Ip0v2IKWk_c+P*n~FlTUzWdjsfO^!8Lb_=N*73fdM5 zP!K+2p0x>D3U=T>sMUa+W;g|@V;8SAK>daHxm^G{HpD~AVbpnrtSG!_bqE78lKHGL z$QN*lCe!ixL@OMi?k}oT2{27wP;5p={1qnTw_Q)kWl(@So`Z#yor@0-N7mYd-VVq+ z_;?si5}Y4e!jH5=Bfc5Ji+AxzESxsm<lK4tUJ;hPF-G6E45#j7*iuqAfuW*Il_k+M z%>FigH(eBlHr$=IZ9T>QNdO`~0E&ge`H^(@xqqgBdT3gIx#at+cEwioC|}U<C6X$b z7$xyf?P{rpCp^SMLy?!EjhbWb1_VV-4I!0=5a#%M>eX_{+G#I>Q#Q()4{8lb6wC0X zq(i##3Q-`70O*c^cN>DfWg+nREVD<ntz~W~ngj^;#-B~9U5#$<40BIGFWOHntp<HJ zR4o`rYoIT#QoE=YESw1|&qeV=9SZPayHFE%K6p9OT?~xIAd4`_fC2Ca3W&jEER^4& z$L1@i@_YilE`>AXtC8X5Y9k4@R5?WL;tiNQgT}yJSRx_`$)XbiR|H`8YM>*KfgFeZ zz~|g801uIXLm5)~IL|aPpO4jgy(~jnFyhZz{@b$X=ixeydRI7Fm{*O!Iyq!6)zu3C zEo$KE%>7hHzI7)s#R%Sm0!EC$7yzL{0Q+Y==-2FW*X`nt=;ThU;^6mkYj_Sp#=bG8 z0!~FgwFp>fLisH+q?;+s&-hPBVtpj|90eqv4aGy{?L6d40W!>S7oq4L+vNvMPt9}Q zLeM3dwS<DvyRg1U3wR@K|67pi!O?kH@-CF|XE@XNi2`;bBZwBbMQ}i>t3FL&bYW9} zZ%clEK+oa_)>Cp(*i2+7-fR~NVBm?kSmC0Zh-@pdJx5p?da{9uHcg>w@Y*9^a5<bj zBc6+FOba&wmz-HPYe?casA(AqA^(uoI>YjM31q2iAM153#YJ|Q+tC43QdY!9ff^l} z{s(RiIIx;Po9e)#h%U7?0Wa4OQ(p%4Z$5^G1|hQTprJW*<<y(TWZ&^bdoNR~Fd2|z z4sD3iA~A%E-M)0FzuL?&e|G&69;|9#Ph^%SwY4WM#gmFyawxb07?%G0i-)jsH!F#I zuyV!~$`i?)YrM^m3^y1m+;yVa?&}-q1MX?4Y^HN4;MqB~`p+PSfP|Jqlf^*4+8p|E zgntM^+!*OzW|lJm;^_dzwA!g!R>Bp~&&h%Q3OJy|!0b(k4yQNBH7a`nnmXUQV+<a} zXT##FApB5x_TwJ4oV3lPZv#Hj6nx+qZO<y=(ikkrA-VkGJs(b?9mjg`AQf25XDo_? zvoO0N{P%sH;uA5j#-i&IAo&vLM?h?z-1d_I6)_dU7|;%lR=Q7g2XaL5dD0v#Opope z+Av*8ZBRK2V5QRlKNb1Y$AE9g7&b#_PppjilZ-YgI`_~f&_??3hN9L2{D>&hj1chs z3ZFw8Og;p(^(!_lgWB!FEOuey_&i8xace`6e}h>xrZ%(SX3-+!n8_p29Bb7Px#ot# zgAgdBvF!R$<dnF^TMB(ugXuNXyPZ^j<`d8|22PbHd!UhdFJU-2=x$Ld#|hM|43-xF z`i2zCyTkQD@cxTQ?ls8LTi{*|_zvTJ8xHJSIo;%XCE9o`K#u+){*`ja%gSS>YwXvp zM8NO1%^hiA+-}SAEx3Nj<NL+!ii^)6q41PnP-ioEc|aX>oD`V`9uHbQ-^CA?Wvrcz zr3zP~io{;Q1qgBUz#y7#d@+sy2bi2gS1&q3<m)+I(uMciJQ`p}EO1{splG)9OcFfA z^1T!X4NNOUIUWXvWH2t-NzG!y0$#Iov(A2PaFGDtkG+PKGc}PP_^~BA!&yq??c!3A z`sgNeGR({hQt%Y^?kPwYOF=9l-jQj2`au=@>xBcoij^n;=sQ=!Gg(vr-z5-t6QmC4 zd_nuF^xp!?BG1Jms8(YR6KMPW9;iG8+Wjoh6ubirsB41WPJRj(nP$uMmy6~1*%02l zDCS0My+B_7q1yL2aIb-JVlk_vjio;Z&O_h+UKl)LK`1Q7_|?LM&&G<2pFS2LfiH$Z zR+Vnvl{=7lRJz<CUC+ITY7x3d;8e(?(hj%Ja`n9OcAjJLSplFUA=?aWvc|)Ig*GXM zkivEmo*^U`YJNmjz`qdG#0~SVpfbs*)vC853IwgE;GA3;e<&O$H$?qbx}FaE*S0pf zz9=r|jMzo`?jj<}Y(AkGWZ%Acl%|mH`g*7Y9U7JJN0`o!vr(J|`QynOGCd3f0Qw<t zzu&{c^uTLJ&=K8ghDHQaIGZ~2JfuJb9+cMr1I!h&7E#|i(R!kU7?%hbHWj)w%GbzE zkwDtb#k(<#)z!5McfelZNzT6zwf9|-dsc9laiz0*)~G;GyO#CG{g@NYiItOFy3RMg z{|&#*h6OjkkoD=FA#f>rz+}7P_Ozp-%cNZ#TiJEj9d{-cQP%O!H_)Xvf#OmqOA{jW zu^r`uU=63J8Tev%1hz+)Z-`n1nHlY-BYD{NBN!_iSn*c<ZgKE`v-eK}njjVh%eOw- zo*)bvDV7-IZ$Un}8n<F$58k*>`SqYG9xUJO4tl_v@$?M<!UIf)yrsw5Rl(qfQk{^I zLOS3M$k;{z<(wJc;y=IG0q@YW>{xx0plP3EC`Rp38EtQJ>Bc+(xNvQ$<2ULgD?+XM zPDtGBgft6R)Fezktuv1Ghp*3OVX6KZI0k^wJMHl%gaBUZ)`jVXEiu*X(h<h2;Mlj5 zS_{zjW{vUt_6&1WNwBMV!CF1s5rFx*kI|XG3j>JIC929ESp?P}{9R-iZ@A<^7Y-(U zv49a%K`su2qSejUM(}<~Y6{vzKi^e}eo2g%rJ2B7SyijZpMIw#M%V&oUA6$+E#06+ z##!NO9)J^Q=3RjWaqU%PBO}XQR^x`;Cs#ud{4>9~5#r{sD`QB?MbbQJQMf5B53}mZ z%d!~4RB@lJAml%EEq8-SdOk>kEVaN{=&R76?);i-5Yv3av>HG0yC~?+SlT28zKjAD zlyr?`HWJ^n#gbQ5&X`zou7H!H)k*(0t-E36J4I_^AkJz%KM2fU?AKandPTQY_L}X< zgAd5@Av&5&T8~S9=fBp;u$dEJ?f0SP+VNN1hx8jZklD{**-vw)=!3s!)$?vEWUta? z7e9#ubN<^PFqy4deeU_U&7TeJ%iLm?Pv^a2po7>^`KHU0a{j^)%mc7MV4+{MK>wil zs6s^Hqn(@IUf*E(W-qssEDcsY+nT-k-A@^L3p9p!Xl%G|2#3>t9Qy9p1Dmh})kC(| zzb2;7cRyHFNCWpG%yvBlzO!dP^ZA)#R+hU3dPB3n2;F-Np!L};_TV%OwgOw|y_BRu zWL}CEZ}7hI*$Vw*%z>|G=HCb3^2he?INhpULzaslD0$HVi}V0t-@tPZ$^YG&+#|u9 z?z5g4XM%}5*wTHY5PbzSlm!j54y!_37Ql_~*lm>c58C)2?IM{a7}}Ta%yr;_qpYIX z4|?MdN5(q-7b*_Vv7~3RA^aK|L!T=w0lO}5j$qcm8o_01mQcwGf+0hFf@9)vI~OIv zTj-d0X2k_7rstSLqhQeG#|e~Xmxl-=KZGdm9{!X8883s4HyA=5o`{DtC0HGY>wqus z2vC(_>Se!SdmjKozweI?sSn87e%frQKewo~GBeQQwN&i+gPXG8<QadP;ZGPATK(hC zi!;$00)FS$(^LOYCO&(oISlBTC3Q9U*x>BMVE;`QvjtsnywAs{%hwdAFaO<<{cX5^ z4A1~5fC&2rEcR}ob<N<C=Ug4Emi5!lNxStGSpOd}GK|yaf5gazHfyH&(pO(6a@ww& z7b)N9ID`WQ?~AqKhz#MOhN(pJFwh&4XsByOPs3f;Yc$g5rc>|MUu6HyfhtD64d-&$ zc4|ULna&j|`Z~W59Y;Sfu3W?j0XSTZ%h-fVml@sT04}Fp_nst1KEo2Hz2*CqDa*NA z`Ju}%jl&qcb*&KH-0D)3fP%eePpa)7y9Xs#j{HB?UwxCzQ~Y$57;tu-9?>LlkQ0xU zG#r05CXUta0u~HQT~ET+-#yUD@_SY0)jwMDNJ33^rm?X?TA`fZvEn%0yiz-l!|Y3~ z*;XVrh40$G*xyGxck;H)n!LWIWx*$98Y}72JTd9Vm#W1RW1(oCt1|7fy0oHIR#jo6 zEKhV99q(nL{{|kc>G?tElQeD<Y2*sFefUQei9KkE%2B%L^co2v-Syn-^Ro>`e0N|9 z#{8`c{Q`q&+*Mgv@J}!=@df>eMmj>m0u3<eL!NUUEe9COzJV#4%MbQd_ognQQ!fUN zo@|wFTTNwZ^t1rqtL0SgRX^(t12WaLe=bA$(**>Yt@M};l+MOK{+ErD{`XI9v~XM3 zMBbn;vqKjlK?8iK<~-27Y;8@Ad<x$%HE5MjH9Xxc4sP*85UfgLZ7cymXoyp^dtZj` z5=}!OZTsVnZ87QUQIA^fR6#LvS}a!D-tUR>AxP{gSDDSOl4K<W!P$fzoSig%9Cjk% z7#oxRE0Go4&kD*fcdUCtQln{bp9EY1IYXB_XYjE5VVyK>iy4U2ei!EW_?9vqLVRzo z&g-rrYsG7<!e59b>OT2itKQaLS8uGfUX>y2nh8KF7l{-qhpOj_B}#ac9l)um`93J` z_40j4FOgE_B$khwNa4%mu(2JhtJW!=&$i1?C3>)&eW7gjT}m6p8FOAstr8k?#L}SG ze49V`$XKb2zi+>oA(G!#Ccq`L$^DWhB=@lo(3V^pU?+rgNE3Rn!QuPyTwOqBP;7gx zTkTg>=D?Z9o%{Xo8@b&_$02})ZO74EII#FQrXu}X8iL@x8=6vf3-*!<dqTQInl(s9 zYgRaUVnxFj?jW`C#eKJ?1s)rnaRc%=#R<Ja1sY7j-IGYe+*==|Pj_8!3X6SgYB4S( zEl}1487$?*#XM4RoQC*c3n@DPa<#Ah!>tP|7}PhvzZCaqo<^+X8-uTMYNBVPS7A5n z3w@SrC;ssq>IR=zRk3sqa(Ha>&;+3ztA-gpOL)|5Z2A2OD_+P;V1Cl=8C_TgpzD|9 zdD6|G29e09h60^4#qgVLdc5m_;Z#_pc)n`K`x|mWFm<==<CV^QaOEPWAWADY``Og> zlqAQwdFqi)h9ARvJXdN`D5@gUt@^US62*aey3J4}b4wn+h2G>4>0>s{2tucsn_b#t zB5tP#kArY6n3~o(R=G4-ywO*VwR6&%WLilanuA78J@xP@>&~VjmvXy_WsouV&L$bL zbHPX`r~#+xH)XmipBAucdI8>^T%v1j@ZBQIo4tKNjLxR>+3GjJu9>7uc>ZiRGSLXY zc!}n<oBJrFaL-kf`m|9QYtq4fZ_ms=u)6FsS-DoRvC*Q{7*nz>rxLiA(JAghM%fBB zeH_ew>rUP*Dfo|*r9#dwJ$-T=e%f`p7h6m;g~H6R5G(KHsl4-*GpRmPf_l!Wkc96w zCA!r?71Sh|VP`0lZ9z7gTr0wof~)%Xs4ua;7$q+hrezYE!nxA<UzAFob(2^Hi&DRz zrItXZxkF!gXo4M5)Q}u}<dG=Rp3LVWo^3e_O_SttH=N%atHW>54HpeRchI$eP};`= zOHDLlAGdEBIN+MC9<tJK?5pGtz4RwHS^RP6R89m{yjNy?j`32{{n`<ennghYnq4}e zY+BM}QTJoZ6^8~XPnL|Nz%%DtwE9)=_QHAkNJ{?}M{-ts&jVuB1~w?*d?rK4Ir%}g z=+q|-;wnwGCcOdIM+}vA?g{*vD!U<WGm)M6Lcpq$^h>H~>W6YjqsZreX5Uw?>ne@{ zFaDN@X^Gjbm_RuSoQUE%K*kQM{VmV2pzIt9%XZ*u%LVaGyIx|l7%<p2pk<;i^3AoF z>fdF{hQ%GFt1x{0=)%KZi%cD8|3TO2(s8a=`^Hn3bV@?$MOs5qLyc^i{OgEVXQ_`? zVYPn;^jSaw5}IM0WX7?~DsUbKu<xNR1MaLm=NWk1>n<`}%J5MACpL~TW`Xu%yYGO# zd<4z;3`_$0Q}wO^m7vY&vw2R?^-J3Es$8WTkE+lRnxqWKEpS!}v80Ab33AX7^fQ!M zBn)8!9p)TzbtlUI*iHH<X5O2u>Vowxg9++A4+5$(c`Xq@O1A)XkHxqb<}7L?Mg#bx z{(F~|+#>QJOmhe?DGe1tB|I#4w{ToNcPQ5sEFZ?`Sxxe)l18Zw<v=*Y$}eAO-8YWD z=+~W?_wnV=9PmQ&R_jIlD}(<;zp%!#SVY+R^Ry#0NqZKacG+D2sTuiq3s?h`qGo<^ zBjrAt>#o$vu6#Bl<&a1b0R{Q`%HHjgbICgG!dO}gS_+5|&!L!B4Y)f)%IUjUrS8lw zoV_nmQ;B9dLrmt0hL9DbqC7YD5bfv~xo-XMF06tdE=nOfY+m)LTp*Waq0b}nLk3I@ z5yLwI1`}B+`R5Ud&-2iX!7n2frCBr%Zp;gaZ>qPQ=CN<qD1BNt79I|DjLewZG*acb zbLd59`#4sB(F<M@#i|boVY}&MhVb<OffEM-)TL<EO=Zr@kZAyKGLhZR<^{D&2f*~A z=hkFugT++yevK@Qb_W>lem!4>ad7+Sr<kUaDD*jjR(GVW>}PW@e;~j5^ndHxw}zic zNMBl#26s;DcSUGyq}_SXU-ES7ZHU|h+_{0N`T49wFCLglvSvr)!SJW~pBJxq8~<w% z5}G&*t-90jo7mrw!Xala>?cH8eZvYPR(D;mext|xogAHoIS2yqgQ|<SW4=e7Y5PeH z1pTRu=$!TlV*4zESNw9TP_ZEBU{@^Ak{K9u^w^vDpl57nL5}sF{d0!IoGc1E6f$*+ zV*pBmj(gHx6Ql5dE#?6n>|!YOG7h(9k{<}i(J_dXktAlQ6r<M~WQfern{4-#MtTan z9d=`r`H2fhA|YW?UT&?t<Nj>w^0$^Nc=%SK8WEqumy3GCpCJ{ZDPB!v@zx}wu~dX& zHucp4+Rx?oh<h{I;^D|d2A1W-QcfOqv>flZXGKr~77v$2lX!%rEI5*cdWFw=<RHK? zWKfc{aSt^>)6Kd~nlIOqFi%xL!IW2eF}buVsY&>7EDLM7%ogX98ftezFD09LJt?>Y zg`=(>FZ@Cd!o7$Rse=so>0-Cj*tsOFl??LTbG6+sK|3F6FGAmPBw9u5XS6-n0TD_q zlz`1d^T2f3#XcsxE@CxN)3{50C_(+0cvr3|x_~=Kqu)2t@Hy$_f0Rz5dy-vK{zgvw zT?#~JQ7f$gvE1`I^_XuOW#HkRpRuX)65EZ77>p{p3sp)gy_GD$B1RQjWTU0F3Q^XQ z>1w$oX=6iRC_y^pHPO9u>Q#a|ndk)rsA|iLF?rF1!L*j4v!`RpF^U+6L%8K8E70)j zMjz^nLPBa={}oaauMorFABcDXkr4PgP3~2)zS5N75OEQfR)@Ojo*OdLo1RO$3=Eem zr3w!hCwG^8V@tKb6*!GyiDR(K)ZcQo3|Wx4{s&@D=oKo_6A3Jwx(6w)NpJuNfpaDm zqohFy(5gT3;*eAxiY4OdX*;CvlGN_*Ch_WvcOMf~OHktE-h6H>QEl+lEMZG=;1a1m zEyVC;#ONRc?I?fUsfT{2pFFWFiMZK9CYM?dCET<|Mxfq}38hPeL_xrq$YGpntSh4V zYE#2V2bD|eB+Vs^&h}Z{9ZJ5agi6C8BdTF%4T7m9XsVGF-dTjYDc96!Y$zTAR}&(s zfyVh&dO#brSrF@0Mbc9{Cnh;4Hu`Rt{X-fczq<V(ZTV78fg!Mo<q{w*c&Ce#iBnam zXD~np$GPQVEbi2@v0^DUi8;FXfkt>N)9FJxnWC`wZk+ucrR;L*G4ZRp*6BUe0WHi( zkTf7Q#>jJd!n}q@koGbf!R0v?=AFL5Zmb#j`oy+tQx7^*f?`-3<CGrTeMQ=hX}sG8 zvCvCkyqIl`<6|~RSrbCVET(Ogpa#9(GI5)yQr>(Mg4&@`GIgj<1%=XzajCe`YaD`r zoVDO9$lV4S01rzg)t7dc1WBOI*#6Shmyl$g-fg*BB(6f#rAV4q8WU(#;4$Lae)8?H z3CvBiU!x??;{;W-YN{2aVyu3zDM4N+_cm80LKqdxkuHs~0j%H}tte36I15Tp-&I?M z5(2>~+nZ)M3{s{HRvYo*IfUR@o#-q?;w<A5@G1%xN~U%vxL7Srr6=m~?|F?U;sZ_Y z8n>kAPhU?mSIHv<HH~ZIWlUpa-btaZnj*NajyWpW)Dwu_b5r*d-+DbjH7IESWHE{B zA8+zl-7xr6cp#nzB<h8HB%<w7Ly$UOQ&~^zWJBN@=Zt?B+X@HT092{)CL6q__@Vcw z<hui!9FJp!NrC3XGr6P2m0Nacm;@aFc9lpT=|n|sI>hY?-Y!esV0R>fL*B7tZ|W@X zV@aQdNa15vDXq@7+%Jh@$&R})KRBV^TkdPReyV#G%k{C05H_<%smfxS(-D)ZHws1U zUrCqor!^$X!2$D*&-Hf)qHoF*(Qs-vD=thD*wwvXjOwv*%xX(<0SGY^WE_dMJ`n0S zGetBuw6yQJluMG0W+95D6s`T&eb>;JKS_8`mvb3~*+#t-B*lc>yWf`N9O`1xN>cv| z5vsmI1c+I&Y5V+hV_F8xc_<u5lBb+P<5gB0HQvoal9n-1jtuqRK|K;CxsYA%TP4j2 zlf;i9XHLe3=N`T37`u4QlupDQGVV?{e%-AlBPqCq#Qqee03%2iybQ-9y`A7u=n3U| zJDsL4`A*cHzKs+9zxZ6D_g(rQIMNdeObAb(d}ID3PxoOS2}@2WwXTUXg>V#1Xdgp+ zIv}=V>d#CO_N{a(_$xAt=}q+Z&&NseB*;ZIl-8pK`rC%moAZhpj&&ByWP_(cGjDtv zQtWYZ6W3{rm*9dtBE+GDON$Wy%J^CXx3&foA}&p*Jv)3xo8jjY`yuo$&?qlO;v>at zJIxX?PlBylKRrcBy>gUVNf{QV)m?;pgQiz!?kfO<pN~+UpIs$Cw-HHn{(qJf5tK7^ zG?UF{f}>LobZrq^AV742>5&=2Nh+zEh+wN>Q)!a9K2qwN!@V)2Wf@8taX!6`Ar<Jb zGJyt+87t*`|Mna+{bz4Buxj>iIzx;LSC%Bq3A0g~J6=KA3ZrJdTe_AIwt1g(oRV?z zslsDKPqM7dgH@MOP2X&i(VCWq6Pzo~&2mxe>;cL6J?XD4tp=W(%KL~ZM?J=;i?y+M z4XpXgNM3ul8u)S5yfkNGM+8Skt0I7_kD<a15SxFrA#$tav4+TUerdUtmpJ4^^Lq6A zYVVFz?(5!Lf5kdnM^iVUemLZVLt5es)Xhh)M~8|k8b~_W1Yx<=n3j#R)Ss^t`C;=3 zia<47vJAq@#_#W5^}7GQ-c!>3JXF-9&D;T$6#d2SN3u3<#H3^Hgg<mQuRlj2x~X2` zCvd<Nr&~+|L{St>?6)djp!{#wk57@bDKJG#KHDMZfi@_jR9jptiEAn8a+#2<vi}~; zAsyzNQFd3T0rt6dVG5O|GzQsHd}WJSm69=vI<9-B;vXR=S`{gy$o{@1M<kU4ei?V2 zh_=C5C0kS{y%6ix7^(#ix3~n1UbZ4r9|goXyf(76<?Vg^@$U4aE0$berX2~%9t1?x zyUwh!Bo7Q?iWd=u*&&v}nx;sbF5fgZS@lH{eim-ey-teWd~+rp-fSz^)aov0t;?o4 zw&C;uWy7)4l80Jz2+GGG+(J^$%aG9XD1}9$dRs!-(D!dJtb$sSWDxvj1HUteH$VVg z+Y;m2VOM8H=6){S#2ImDq?lOMCvvjL%QazUXcNCB-2C{tTi0*w_V;z(o$<#b_fWw^ zj>jJUd~@@plTMcZUc8?fPROSXlz5MdCCs)b2mdx$mzl%>)rgQ|Lm8pm=5<s^DM~Qr z`<h|uW!&y&KFSsN`a8mAP|{c&4eif=O;m#y?}cRHgJo~dF&pit*CHXgq!k&I$_vzn zN|UEmjg!5&geXbEh!!;4+5G-d@II<VBZ<#Z%bpB5Q*?YaOA~&Nye$+Jetkdra<p3- zM^e+0Rw(tc4~9t^eRuk@n2kws>{ynOB?%zIzDae<XK5F~2;yp=Y%z$di#CjBsF;ux zZ}eByCp9b^q#Li?!zf<lQj+@1@LTEn#>Wr+I`<_O!kcI|bda=y>EC~1k*00%L3_CV z>%Fw01Y1-;()N}2agyVI$f1uB#?5P9I@FDPV}#+2y(r1|!uD>$N_N>EadATL1?rkC z)_!KoN^1Xri8gl3@w#eMQ<x(TNP6&PI``{=lu^)SF_RoZ2r%?h`3Z^GQmBb?v&ZS$ zk2Qy1z`ItCFdBYHCI7tlZ2ziiYS>xQ5S(y^en`4{78#tSXUcb+k<vJ`yb)#Ok=nKo zeA*`hN&MQW-k4heCP^(MfLH)cHZl%gAgWox3qBneN6F}@1(dd;Zdl;+=uSXM6iPlK zd+2ADRZ?Bw$)jt{KIAg<m!!z7$W`83d1~;h#>p{q<tb<ISR-#@^-0m2B-`D{4By|) zzEXlKSF^~`(hK3$$cW;li8`Z`y89&C-2^V?n5K<CMfXWAaxpEwA61@f^?V|E;v=Jk zldq!QjOx>xmIY0#|9*DCt?c`skqf7zzEZ!GPPy`a-wQg*#qkZ^IZmbgN>hVpT#kFU z@!yT`t!&A`wYiiy3}Us9l)V7QxyPR6;le%cpT-=+OJAT~-h?}mXI;SCAFq9i+*~?4 zm_GlKnnC>eBKRmwmX<BZgAMX8_vJ6Q4=5q~B$pxRuH)^<zsWbr*M<Ya<ItyTr>D4- zqing8j;L3aZ&3Dxq`2Kbn$@ml2o&{<npFz7>yEt&OqJ_V#mIdmR#BTe+@8Qd#zobz z?ae*GA+mr`j+EcN&~UDVV^iSPzVK+y*YiyJ$Y4)-pbuad%nuiBB0nJ_cnY@XWr4R$ zHVOsbrs{2LfjJ4aX|E<1h~L2W*CWXpsu(#(I^d_&e=Yu>nha*ie7ZJ3<ldC?1)+|@ zdSI6>y4Jmk@+Rl+U$fnO?K69u3)kRV&!ks}azt&P1)eCZj~1!gmZpY0mGXYOdU4c* z?h3ZTbSG$A1H1r4J^4<<!GIaoCZ;j}`x`baXEX!T3YQ5wRoh=3zONYk-8D=v`D?>k z%qE+1w<DckZLvuwI+AEWD-vTacLD2|!D-9Gv7vr?yuUH|Jorre_PZ|uVbaF6&X!PY z_<sS=RFyH|(6*H?x{T*m7e!}jfOm3;_NFXJcwU$pFY-%;Dfg>2Re@CDBD_GFcrBj$ zlJxf|vNRo|v6cM0I^7WoY&{WeFvG5AVr}2`BuxiC{&Pf}r?jHfQ((SPAlKSdT{zGF z%B}0z1)lXWG%9`{R61LsjXHM&0+GwO28;=~>errn^5%yQtBXFk`QI&HN5E45;^lW> zt03@aw|5;AGu}UfdB&fxi3bSBRoD(7Mf6eLm1yzDg##uRZb9uKB)t%pmOSj&SOvFh zH5U_olFWF7;J~f13cB*5|Dq+IwSVo9^!aSnOx8LUN?-;~M(w_&BjOasD{?pYNAR~o zXy8EEX&5bVcfUjW<(KF`(rxEx1hX|da4r(S{f0D#B0%kUCX;TbXG>w=u!-T)hzuRB z?eFhDvJ@J#&+qkK13*SMiY>80e8O8VyS??C{#)^fQmy8)15%2gFs}}mLtk_TZj@1k zi(?gr#a({B!<@k`td6w7IAi4i1Xt%f%mxsWIl=_DVUt~-rUwSPxFdq4V4OFQy1Td< zg(+(@E#+yEZia(y#X(mqb)bO(^MP5~YZzm~)nYDXEEo|yedE<%mAO#cs-sabThCI> z6>60_&VIy*S?FqD#C(EIS2oY3O1@TGSsXC`^^q+bN)h8O{2PV+62TL>@*w7)`liG) zC<R?rpb*ppeP{lY|NITj>~SB#K9fzV7+K@{Nj4AtSLMOFUCc_E_lxazt~;9hZ?E}e zs!yxII`_xTbhM7pUv@yWclyy?HIz8_t)r!Msu!7=Ca2|R;Ph4PKRd7ZI@G>gu<Oh% zd3{Ic-`R<+1S8;A#q7M~w*NAC)#4696AiHydLvF7<dwI31tKWcO?yf7HY|IA51?oi z#xv`fJnfT_qSCW-8WKxx&0so&6p10<wWr1gAQoc1oD-n*6sk;be!PogK=l0cfWc4x zVtxFq*;4-jl-2!&b^(RPR7*`0R-_H(Pt{JUL#M!b@uLo@u*P(^4A%8w`F`1)#tfgp z_pBeP2b7x{?*_#Ra<7ODs!udVE>;Wj9#ju%?Kfsot*>aP_z;%0iJYt{B*0cPWT4QL zof#`6Bq;vY#HJ}Hzf(v=vF5EsSkt}IQz0=u@nP$nrrgJx!V<PM!}d*0dCy{nrM$#P z&YUNj@?Ufc%Y@gAT-|TF|9aaCc3XVZgSEL}KvP8FUd`xrh33Ndu_8*9;ucM40FX7N zC^gqukfty+v#0B-PifzW-aeq|781QQS@Zs8Q}cuGv7(wQ;va5JG?)JD6xBYc`4G3? z{P5qYC<ZDq7SGyJhR_nzWvd-aQfMh>iWAcplo(I7X{k8hC1$8tJAOB;rIPorn6aM3 zM0QR~m57$Oscr2<UQ^2>nK*HCFNw**iI&GIUE-GEwUZC_Tb^kD6}L)|m?~#&tv1w> zu(?+|^+=($#xhRAu2N#U#-_E_p-aM{xpulfto5neUkRsPiI0srt#v+Hl2;~cKejfV zwblp4NxH5`d}^O)eHPgz>2^^2>GU)7B9jD?>6gSzZmwTL@=X(s@A#SiO#Q|+bjmJ= zq%%2IkaVw0%180(=XYT*noAk!nRO)p8^7JxRCVr#`{k$qP2Y|TBV3mb^qO^M8GiBN zMVE9?_|w@h`!8xq2_~l!v$JoDBHLotl0!NFNCH!pTyOJg!yih1*|K@r@v%!LvN>jK z)Bn@6&x=76%IuflnjRHF9LAx80epdCN@-G>711WSnOlEVURQE|In)hUxctKF_0+3* zz2ys;A!Ctm?jCll&zN=5aB<{LqL8t9$VJ4R{c`}tS%A}gi7{NQu&$t2#kSZ|eb)nh zmQPCRmgsvM9oWmYHz{je>Y+oOtmfLf$(2zP$;8+^$u)&fqSGnN`kk-Oy^h|0A2cW3 zZ}=l~U$Wtn*|-9rA9b;az0o+3;l(|E=UW%o<<+ILbGyum=q${TjJa(Fpgh5?{u6b( ze0_c^?pDTU^A$|~AMhUyhIb#wFC|#gtQw_e8!HoW<tRH<!6ng-bpBg;_xY^I)01(7 z`uEt(O-<noRWb7zfnQEOzGf>^Z%`(l0Ih}pqv+m?aCro<{z}jO`IVZ5F+*?0rcCQk zMNdP&A36HnHMNAkni(iX$<^`WZtVY_2~|kZ+$>YvyA)IVg>;|<T-{Oqm=JPed&b}R z@~>TR1hjp*yp&_Hoc>1oAISx)U7E8`zOiGT=$XyIN6X#$%<KUpPR}+V2i>dHJ|OUe z!&rpWn0u3?w~$|(mIzRDoqt%l_SJ@ZR|!u-3IrSe;!<)oj6<(HOXwQKLA5%*C?^;| zfn<K8HpfFo24*4VzD;D^opGjY=;EaO57L>T+fb02?75y$USKr@q0{Gsp2q#m`?#c_ zc>43g@lVr>fctfCr9N)m4Z(XmEOexjr<Pwx&$Izb1ktHSvax#L&70Roo~{Yt1q4N> zq%0EKpl3VX_WMGl0;td@^lhH>YHm-gL=ga9>i`t4WDkFHYrTt(5BKNKT$d9goK|*W z&VwJ=ehge;r;ZQHB|MwQ-j(T1<oVpzw#j&c01jz@<&f6;K5MlH4=NaCyYDMQ(iuIP zBi~CBqmH>P$?}8($E9P0dIuvxCdB$=(R}$!2A}D3u0Gm4FPZ0Movc(L_~+pm^j@&= z+|TQGxYkHW<!4XgZ1ZQ(4`qf_+U|&N@Wi6;EvTp;59=K2DVFq}X0xu)0FuVnUdHOF zPeC8oIGNN@I~bgI3w!_WoLBE#5IXMGaY9Sn)IGm>RX-x3`19~3JLm)r#v`>)eeR)e zZ0}^~Wr=f^TILrGtF9fLrtxtQL{Ie;BN(TWaxP%*7ToFsGi}tp&&sg7<Rh&9X3_^l zQ39HSzzkXPdX&RdHm^r1`nP3T#qzGO<gKh&uVG2=^TLTl8p0NT-vO=lycP7^m8Elt za!K(8x^?rmIp|vgtTlTgc!%a6zcq`6$GM3mvDh-n>4eI^W*Qu3^a5<ER(cCpt<_J5 z`6tTxhM-hzD!Yx1aDyH%tA2PqeY`p|RD^A$U{({ra2@utO_2E~JW!n!rWQS&%|gw< zUc!;5tp9|_VV1I8FNHIc$$$87ql<huZvcQ{6|p+qEu+E2(@arxB6`2x)YGWr`L#F} z;5@O$2-7f5IQeT<tIVc0H?HE!D}D&w)DnbP>#3o1FPxs~F>+w!Ga!O^-Mauq$f{Rm z+vz9IqHy8E>AXtk{tpx$J#5ty>Z+&WX@YVFgt`UGFJhQEXqaGBm0$b?B`DbCBqCov zdAH)~jco9$fU<XjD4wWECeUp6uwZB`5H#%ESjHKw#;!m?sEx*Mmewx)RSU~`I|0VL zUR3}^a7sX9usSFrpE;3-3W7bxg6`ewoip+SZpVpG)q+{;wB9HWFOBnhAUBq?3d?Er z2+e^#&rzm!SS5n(R@}_6{%X&WPyW7Up-$3M99pF(5!@eR7{@T+BEXJ^&U-%;mBxx} zy1Y~ta9lS1Wp1g0gK|z$=&CSusC9SVvv?JTg5w(#8nH{>>!$I3f~=hY=P~vo4tvfH z3swQ=y%W?zJ~*hbPHOSj#jp9@;`w%K1XtQepuM1u>s1|n%qc`fqjW{Qb<h1T#{R>p zsW*HVei!MXuFyN7S0VHc2?-E-6;LdpgCNpGK*W#)2-VP05JMFdrHY7%bPx~$8#V+) zz=o)(Sia`uxA&Pdv(KJ+=lu^dE16kOp8Nh>*8pA|tC}frS=Ec@lkAvl0hEwXK}5`| zXE2N<p@NM=7z&SDeFXRjFV#aYyw{|b$s(>d2ko=JHZK7L5cN<Sn51<FUP7w0-A<V5 z8C`El03eE!vShtZ1wZk_HSC36)@Rx257=epag!kJ4hwIoYYq#Wjp2IeJhc@@<Wb>d z<?pfw2t7p0M?~v@Q9~3JkR<M$Cx#72s5;SzY<g>!x;b3E&o?+TS+L{)z4+Z_fXU%5 zAJGeiK`Vz6;US)80a&L>md!7<AuFk0jcfP-XsHcUP34^-Okws{i&82CXoLWs+$eSV z-HU41JM0MQ&~H{y1=J9)75#KYt4D?cfX{r^BTJAZTEs!k`88|ACrz_q0$eb-USKZC zZOg_BT8*yCT`_A5QY|J@ZU_QqHRZy=_2JGs@<sYMo+gMmW!!^qv1n>msqps!pWK+G ztkzoL`-H!WPBo*JHBfEt_Q^Wlw(r29G+~A~WA{EWs{_hfJC<10N|N2elj(#1`H6B{ z$93v%#(Q(SfYl^P)&umxXAsLB4Sw?v=^B}N%?zgS7%xB---YHJ<Sd>tktrUQ?jM=# zdiUPZ=$LU_>uSwmwRrcd8&{ig!*gRqj`6CN^{mwrB&KRZSL&I?0fiptG4m}~v*}Sw z>gc$ix55v(dTE`&m1SqyXPtsDr`knpkni5e<ZLI&9H&XZw#~6Uwciq~`##S2O^Z5R zZK*B6iNad3&JUjF<|>gU23NJdoY#@v=V6>h;LeG5M)$F1ui0J8?V(rBJ<HxGJXui^ zdhq;{Cr*o9i(^hCm9kGY0MxE)k<+=aJPFz!wol`5roj~V&^&55wa@)sb=D33)5V_% zWA(2~L`_jbt2}riYT;bc3$>PE>5ul_j1cQDA69$EFk*zIS&mL2W*g5PS%=3uegA|n z;Ct9ZG!cD+r&dYNm+m8#y;{WF?&LSyxkAwKxB2R1^$PZ`$o|vn>$W+VF80!$8$RYF zaWkFOkN;xHqAyA7P2ciFhnYMC$#w#M%lf08YBSMx?9=Y={71%m;;D2eL58@>E7Fc4 zphDSeE*PsV=GKyWIq=AHrIFv5^b`aw_^@>FM4%COW;aX-fXvH}8FWA`t706>=?3l( zEgIWovqsIgWOzKZfu6(viH#Yx)RIp^?-%-n7Pm`dW)TgUs-d30Cm5<znzknco8)x8 z1!021FlT8xUn$OENPgHT+DftVt^9Sf8oJfk=!t6_`kZ9E)!)zdX6L>!=_W~|morDF zH$*IV={ySCrYxBoxz8tUNUNgJgoRACm#V-eed$0iQ!3H2Dqi}k@6V2HnFsoEPdnva z>&tI;%74~Z_}Qtz(Z?dYutElk5?zW421@E(N_qy$rd`Um1}ctSDjo)^{#~j^4b&pK z)J_<vpXyRSYoL+SrE$(cv$9L`l7ZIcF0FP0?VDZNcMWtVyL28H?0ed^@3n#MW|!_~ z1HGSJdK?2BvKuG#?NAtxzDFrWq1!;u(9pEo(ALn%vD?VQ(Ab|_T4QJu!R<vhG(FXA zde+b^r`znDp?PJu`6WY(%iR|3hL$(GE$<pyP2#()9vE6b?Y4exXtUXE^V!h$XSXfK z5dZ%xMpiJgQ}40UGa{ODUqnVE#~zZ0k$uC}?eAgs$i-JM*#C)YXQ1}~52&`Yemq~& z@Yu_#;#E3Qj+iIw)YW*8CZ=L$cCV{xrV{smqT0(3E<sFF;sD{6g$6FFJv=SCmDB9` zKdAO(Faibm`MsLHarJ3CMOg_CP(S8ehAd>4Kcl{<^GX}FUA%1s1yBdy#mZjAXD;8R zLiyB~LjV<nMNHPH+_?5qAW!+>F2HVCXQ~Vw;;Qp+4`95rSKcxS*zAQ`pR0auK_^GC z0OfYA+wC9rT{$8z2CK$D!Kac>@kNkR%?R?I&wIs!2X1|PoW;XlPRUASUc(>|Xa5Zt zpUNx-D4b_s?hFinFf*>6+%i2irBDNpzcDa)E2npkzH5RScm0n86g9pef2w;-*EAH6 zT%qw>tjnDe7VV+O2yABuX31uHO1mga8oeT&;GY@_dlnQK>^3eXL0|~1IC?_VCp45@ zv0KeBsDdA9(#|)Dy;6X`kRx_x#J(e#MMgYZ&XOKZsfdyTz_23z<9n=f5Bu}$6^D}F zy{+`ozlRA1DD0*jjP>^hyCyI6Mm4w5bF)TTj<Se^I;4gpBa+81CnX`S_#<ARxu~}L z+P%x=BHwfWzo-^erCf#x$WmMJ88@<8FP8mpRO`$-np~o)2CzpW|8G>QA~yWLQSHG` z{Qozqt^Mzz!2h7y;~oEncK_d~w)eyK?VbOZsP<8Xj{q0dw&_Z}Kfpz`>*C*>_0Po( ztY|7#{uQ$X8V#p$YSpK>*DeLY*$Vrf&X%cFue3SsgFODqOEBMb^)!A8@hrMe&oX7n zkxf4tb%b*7J@JRFxTy99E%W=6LzP#cKsfHz_odLgPI-&aAf7A{PXM3zEN;>|#1LRx zd&&b`ZlQRX#M$@rHI);Qv-k(I+l&7SzrMFNp;|ltsK8P8*6~6~l_}*?RuE~m^wjpR zm^@Ty4kj!;_V>HiR0A-p<>t1<;o!Tve?A6Dea(Ik#Bo<#fk(tYpND>~BUOeaPFQ)* z$hQCeYAFT<j8G2sZdSAYC;oF9gR-53ASW9HK0nRTvvC*~?-2m(&$a*iEs*=Iknkeu zo6Voyr=LB4|JZEj{QLX!Glv84vjHS|2$EbRvBY%z#Xp6AXdNQ;K9UVPS}7R9Ep%+@ zfT^lY5$>s;!0L!h$y$&{=8l7h3pDF^&wKMamjz>6G{*UO@CLwarUZoNXfK$_6#ETo zwE$FAjx&ZN`EQ5$&v_Z=SzL6~=u579!5S%hFW)<$o(WmN3g4`1Ph#vSdW0UB68$<N z`45tRZKYoNO;(W$fR~%-AY1$m2Mu|@WL4~CfqW%M-<_aBs+EM%ydrBI<Bj!nRUrg; z@oKE?Q{*l@%k!<};SU;cv7^e24T>6M)miN2iUeo@ycJm;Vve{8JvB{GyX!0ViX=*H z103^<VU<?ShV`&{08bQ5uKsVM#(~rviHuHcyC|7oaiq&g+`Do<{RxhZA#C!j(Ccbe z@fS3TEdhM>0{`W{`Qe%UjGbJVQ;tbayek;XlP|tX!@nQm^^Jp6uFY<?r$}+^j?h@u zhM`&d^Q-qH2EEIqZV~kzTOMS~&s@qnRIh@zn?FHgVbf$CG_OP!@0*QdR7p-41Q$1Y zgpPofUl>@=D=tZr%5piOM^NXah8Y839p7*iX#h>s45$~Y*&45q4`R*>sAa7&-nmo` z=O^l%t6Xo>G)bDy%M))bUI~4sWy(9pr25nWan1O&&V2k-3kYo0QG|<`AMH!SCR$qY zPcTJqhUwU=p3UM2;b~6@r5usEPSPCl3Ck7(RPKZahphJvcNkxK7l3e8)}D@|Hl!uI zinh?_T`Gy}7R?enMu2qk$8E(CGVw5FS?Tjlys(`2G8#u8-@AW;BUsw|@0YfJ={uHp zOc2%z{z=wM^Lb{$s8UIsz`@6PrB0#2!o^hGBp#f@MpuPW$;nm;`+NCtaUuC-2q1Ax z`amZCXl`v%y@`M8qzk(Md-x>N@h14vFCj?kHogrXyvkRk^0R+ZY279B{J{D(qU>Zo z;{MANR_Ocq^7l#g_%$YGo_GBwpz)EAwvdl6gAR)nkDZNgzQcj+`DYh2C_bL#J2~_O zYXM(<VfD=G_45Gi@}oF1IR<o#YZV!+DfYT2e&CbtXwya4oPa_JW+bR07>{*u{pI{- z4uTcBF!WCUP4vTGgSg48YfvYZPP9`bZT6m9?0GkSsy_<KA?A6Kln@4+q&86?*{0Kh z`pW?ri=TcY0@r0JzNIlb@`MpopI^N0{CZ;z<GWp^x2*jB3tpeC#xc(u3Q$es(y+1O zD8=UZqK7u>bLiF8vm3Lx)T)N-(slZm4)Z$d<$acPugxii(+V<G-ef%=+cYt+525eU z8gl|1%v}YF4TKtJqt%!O&;N#Jq8dalL?Zv~rfZyJ3d=p{3op4N032hE%A%7IcH6v# zk@EsTp9Tu6BDIQ~nO_jlOx8@mzsppq5amK-()7m=0Q|cGZ%rnw>FdWTPfyvqe>I+w z*?F6_CW$&fVZ6-?q$Saq{^BoEtEZf;f5<2v<xF(iMKH6oWsk4e%=KL0T-~4#1V7J9 z-fJ*veZ<>LY>gv1YERb*04X7<x7C>a0$sdE#;%vcb2~{#$gi_SO~(-Jzh=$vhez{~ zL>`Is%|YS2rfHZW5uu|v{`%<5Lk-wj9NCg{WiGSkkRmt!RBoP<ixUlP6#Jro;ei!s zayIQ_gI4=B%@5vox~b{6GmwO3H-|w%*lY2i76pw%?{fR<M56xn;|29t*FOt>q0vI- zrS3kOayOLQ#Gl%$*B8o~uX~EhRMNH^LAv(H0*!tBq#<^;Vc+V9dBOiKXVt}J)(Cyi zu5Y_mS^TQ+!p$vC{_R)h&VkFqKLm@*)H%REGZtoTSSbXHs&<;)FeQay@~IgV#P7um zN>VRHEABi;E+#W-f}5wt+=?Fsnu$BD<b(j&@O{OGhc`2x;sm~Sh^3An`}$POHYb!B z3Vxm!_<hPc+8?aPasNy4LwE!R=A%(!_N8S<-W#1l4Z{&;RQ*n6NT+hR8rXGNKyFDi ziu>iQp!vf^LwqwqLac&H%tvM3zv|#~)8ka*u%0Y0yIsE2GVp6-$l6UuRYkPX5|S%z zl5i*(!TNB#P<Ys3n=c68I0UH$3`PQa;YXG_A|dffj}!TaaYEeypnw8qS^QHlW_39z zMatp}La+G8towtm^Yj!BfCN^ugjQp$eA2cj4cq6@lulmPQvOU&lqge&O7-(AwQ6Sw ze8A_d843-va_WX0=O~ET6_2|Vp^YY5H=MZH<h5f2`nQ}iLli)_PQfx^j|pI~Bu34T zoA|*us{zLCoEFCjc7%&Grifm`gJrD37aCxBH`b{8pc+x|?L4=nz-E0Y=BXiHYG3j- zGtikUM;}E~{Q}i;sC>m)@P!24061zPApx5U*N0lSWWc@@cnoDj7tr6r<8JJ*s<B9J zv9@y^su)CnK?03rt6Xf+>rC&^4kjcXt@GI61@+92H${>W;3N+ARnm@1PS{G?4^Yv_ zAT&ScWGU|y^1^;_j0_5+F$WF7gQcuA07$~q;fgfjPUTNK3Hdz0P42XYnr*8eO0Yvq zJ<DEQEJ6+=B0PQQp^@VDr-V0X6+`Yp<H(@^WI6>MyisxDR~CRRgvA%|9H=C*z>9HZ z01j~s0FL1hlc&H3dohT2U^^SV*%4#pRX&?w1}Bsp($v*X1(T`qFniA_ATXzl%pP+y zk#gbeRRsTVgiaxoqre~*45G+_)WLwEEN&PGkpd;6fzxa*PJ>NWMj1Q>o$rAUpP)U> zMZ)ci7wynAb`4(;GUL4N8W8-j)gg5%2Z%e*wb#9S+^Z{hYPgpw2YK{tQw0K3d7zPM zCkjW$7a$aieOF-Btf(|r2E?nX8js|Sip$CYF9gurxA-}&;K+{Q#T~=sy{h{(So2d5 zss)nmbx(c|qK*}{P31v~d5<cen`b$JVX0@z1)~n|USad*81dh}T>8cl{MQE>QlW-i zW6o7^*kbFxOI)jbu(X<KUXAym+xCODqauN+I+Y!SBqPkb2q>^qxG607evf#g@*->) z0j=W;K?{UDqlD#xP&59Xp8Be|3zG4O1Ux(#0J>Vi(;dpyp1C#IhBb&PXa6+Le!lyr zAn&B%1t!JIS@;qaRad1`38H9C#bT>|>vp_JoWz>Io*ZB(?+h6<eoITPG<aVw_+y3l zHy+dxaXJZ-BI7PJYnEWS>jYTnyPL`x<~1HT&;y5fcd9IjjZC6k>S6IdPzyf)1U>D^ z{e3o$3>i{!0?SyzvsbjAMvA0RP%bzmi`~LUK+mEKt&Lh<lnC`d%1dF^K{32kNy1;F zbI67LLqAfE97F~qDkXW$0XFiG252(`al?ZbBCj5!z+tN;79EJ6nqV4OlLWLOyx8zB z+1%M<r84Fm_PpslZ06wkp~a#zW=+bH=j0DwKWp#wdngq$%&SA^-4}t5>L^|R>3DLe z7Fi54!a-d+U<myh$d@ayI^#^v0r14{X5jXvSg`81MVi0`kO2TM0o;D`(8Yc*Zyp^^ zxx~~0?X^1lA+3;wyl8dadmTyZTK+PD*MDH?usXsW|4JxNWjf^ouu}>xM(9a5XrBgc z|Fl~>hx1}O+JQDTljF7_9Z*6C#H$Bti1hSC`<(}~@u+Qoa8C2a?AN+8;Ur{`kPb9K zAinqGG*atN>7-=CBpDurhr8h6gj7WI@9T)5tI8Eo@SjI5*ATa&(k|eRr#geCNZ@gt zV5KTf>KQ$sVv6=cF(`=bO(@Q=B-gXApjvyFeQ_Ju|Bpl-$DXXca%5wiH*F04?n<ro z0T2(ueZD~rIV-ogc+wva_s1jE;-ILYt9YM82!{9gPG(YEx9I9kxCko46P_`TDxzM? z&IP}&7T>$AEouqA$Gg9N=TS)&bQE{2_vO8q2AbRhBP=sMUI2sQ;6d1Gt_{X%gWvn> z;PL5g&UDkMg5#8`Bp2|+#Le`4@S8Gj)*iw50A5_lm|a3^XO%;1v~N`A`2KP6H0FN~ z@Yaah8T($ZqVm@7N569hk7<K=PY{=nYzhSHKQx%7l@S7~Mm2*)SNXmGeK4QKZ0Z2w zOA?HmEbwCVMsS^9AozFpqDr6Jr(M3=Eso}B;7$jBNZuW|*RWVk?|U>5d%IFf2Lw3g zps;4~_NlUC9Z0UqtMlY@N-b-538r0+(@h6AS!_2VioJC=)>S(#<su}W|749*LPRRB zqIdpDCbF{<T~}+sZieufN2FC5Pc=BFB0|8LMs7Spe;mMS6Kbfz-0tIf7<aK>FqvF9 zOP@w9T<d0E>@y|Lk>dZZ951XikpBQm=zv~v1=~*J1}nW#9`ozBnvM86K3qkb{yECO z1<oRYB|m}5??xBq1CTyK-{bbJc?!a;@1Hhn-EZ0S+)1eRieT!vlkskZ{B8a_I9}Oa zFx?Yr-8u}ZoAY%AKi9x`Z(XwWY`<(-V`+C+K(X!qq~NU?+~V}?zuX8Ur-2WmC^%_h zlQxx{o>KQY5S(HQ4v2<eNFhch;FFcHaj_X#Ck%eR8Hj^B0dV<?FqgO)+qm%${DAN; zs4FkvL4oV$mN~ZO)?v}#TM^o>U{c%zw#jYc>D$}iBnmxC8ttY9ynIpL1lPgQCnEf( zTeuB{^9rajR44DnU+HC9@iT14!8a!=HpU?OE)Ye;Nl$L{!Gipm896JcJ{1h^Xzq%F zwjZqe+>b=P0!Q$vFaoN)@3<e`JLQw!d_l*P?wpt*#P(92&Bf;s9w8n2X{h3X64ltX zUOGHJ16KF)q-OD3S%hKSj6V*#ausH{GK}<+Gr>JES%Eck{%bed>UkalLJ!U&h6Vbf zUzixOlMhe#j=YFIHNBh$J_XtsJ%^ijgY&FGyYi#xOk@-bw%7-A#et9Rz;^V(1Fwet zb*hh8gAw3GfNjhZoznec5WXtFjxlyQZN;B!l(sk8wscJ@La6_O!A2PPJ<jO;{Ym6P zLJ+VL*#Y~AhWW&R3Im}3$LpD?0$--mA7>}R76iY8nVW3<vav~7s+D7Do{7ks^(*iv z0DO!Sbl)%N{(Wf^c!9_~+Lrqawz>etK)F_(clA0%A7yEm0>L0pINnAm(w24vR#%?J zy?Ic89oqg+jsFe?|92FE8PhuAzx~Z-UoBYADKCIv-UMNhUb665?Z>1Yr~v>4SSzT^ zhO_KTgUS34DR)o!-3IX1$wfwy1Dg{G^L|(7i}M~lpC0+XBhX}n3CFUkE+Q6F-XIjK zH~GuB;Tc92#+xq4vnvhv_WO*duOh>ZQwLFLMenB<U!=5LL}b2{`Et5wd&}Du^b-KC zqXF|+t`n~&{5t961i#46-KAaz*l`=Lti#?k&KKz@7EROUgn6X4Aq1E{Z?{4^+&^w6 z>gs2nBXUVB*tR45gy%;Hf##H>=Z*zGT@y*97I#~J_ObkwnekcKYrFj!{elY=Ui)l$ zdHC3s&*%5`8&aClXW=F3%~Xx`M;tYCiF04#yah{4g;TbKzb>$%!0oJ$T`u#VxZw^4 zD;J1*(4K-F?@zEDrv^9%xj;><OV;E3f|Yg<FfJldp76eqZ!Fr&5&S0+{ntA2D7Y7L z8x6zFbU};XM9Oc}1rEv#z&zWt&s6iuO0>mVgE_jojgmda`V5MY=CU3C)18g;)CboD zfjY_${`iZ7*23KSwMZ<o(qjg|!>lFYJBp7XUp}39op5jk<^-;Ik3K$NwQY9n_-9=` z+ItjpXw<wIar)36bL2U!IH~mL4S3LxS+<b+oN(Xv*45lMu+`yM83gVF?5+0WH*=3q zu$p}-yeAKJ{4qciwLvNeht6j6b*&&%#Y9BT{VDN2?Y_Y;`{3+{c5rj&r+6pq<os5y z>^NWX6wu*sfGzgNB7sg48UWnahZL(kt2BWThOvvJ*Z+-bLlp^t6-M~~AJs08o%h+i ze?n$cj?W}sd^lC+_39X1f3`r|Nh$jl#Mre;6<7zV2=;Sgs)rs1z}dNyfVW08p=|5; z=E2_MuhLwNyhMQgF$z*?)&8H444(P#A6zy7H|_;6Zv>g>myNT5aO2*9J=y!jsvX=o zePXQyXMpl6pGwt~w(`a6{o>iw8V=x|0!zMK@f%A9I3ofR7XxpODfR<n1Oyv&x4B)Y z;P}5#?U@glB(>@Do>OQ#;rfxzBeyQpn2j&i%xhxW@b$A~az-#W0tx_~E_kB17%2$M zOH%Qn#EXQz&53-h#g_24EmVkvBfup>!3I<D294Vx%!Ke--plzKRiOZL@<Q#gD-AZl z7`Y)&3t-w=0~G*`53u9kr?~rES)h(N2dwa0#vBl!CQq+64_9q~3GF1|FK;k;U~5#d z(j|t0v*zW{SRG*NUW-NqZcIZqK4wu#343H6TFR{FPWhP>*GTlf`GPfGE3ivtYz_6B z&i=zp4VTgi%!3I?dsCD|$o~d%ImHed-ojpv3Ry<pPVv=X1FxyYWX+4n-&zAqD^-+R zp%FKwoVMMwUVlXGKMfHej;tZ<5OC+7;K38)#{P#--5^)xWh?P&<ZT?#Dfj)IdbxVQ zT?LiPs7et*`|woxDY<OBGN%}3b>nh?pK7Gf5#?!^oAk)6%251)G&<V_m5^{ab+hT_ z@;dt#0_YJIu5gJ^vkI@J<UuG304-HjKITVPsOyhKezAtA4`U`uHtxTkEHl*<QOJE} zPs|!!@O8}MK062VuyX&{sH3^G3xWal;pX8Z#tBkayl+;yO&##LXkW~J)B`+TThqAS zTN3DdL`B3nYQ7?@aIL(bbL?vSgtW3Xj@Kaq@HUsEMhahXJ5)m|WM-GWZ)*t7EqDe$ zRCcbVf#vExXHj2j`>POJ_7!0jHykB*S}9UXI7Qrq=A>H57JhhdwxEg$Ij%cj)9IV1 zp<8s$R}*ro(yL7>!ZuZz2Mbr(n1X#D7V(CGCy!pfll(#^$-FLIlZI2I)j?g|@~GFD zLcWBzDxXVY{9%BDD325{c;fP4+K1whaA{gcV`K}3U+_=8(5Yahobm!&G3xrYBZ^sC zkk)04BN;-i`0#ns_Uzr{&tvCDlz%JO(BfN}Nh2ySFFyC#QV@&cMLqUju(xsSWcCCL z_Te2T?6OU1vU!}e+$u3b0{4Cq=X6$`6vP{nP#DQvJ0<J{w*_`Y@|Y0d*D*&{0%V`D zJ|Tthhu`73pT0{<o<x*c)+O&=D>0LWTn`=LQ-bSS`5)btx&vH?MlMVAU{sJ~-0SWt zoO1pnG*BxOY#*#>sxj??>3%b%)bhl^;>p4>SKn-hVDjibr}eY+I-xNY1CmV#8raVi zB79xQf3h@lQX`2`3g}x~`Yo2+=;qGhf{Ig_!IZyBD;=aD`?poaG_jy@)zos7y^&r~ zqHmZ^n5MAL9z@b^t=6HJQ5VAcYUT=z2&sFM0nfHbAaY&je^BicLCHbS`PC#Okn$G; zSa2R99Z(MELL@=cW74JhO5s+9y`K`_H{=^t-*Qjx^*MGEHngt}P4!RVE-<l_64rw5 zZ?A@Adn^`6-HV#?do-M}O^UP=o4yiH4y_dqLM1j2XUq7(TqgUFOBr1*?Z3Wc0WFhz zOCzuw@r;_)RjBkx$6!|Pqb9xoM69?=qY?5`m45u=Nj<v@A^0MtSt^neii1j{61ktG zVH4O9%T*C+_PDn0#r~~+VIr~iYuS`Z0ryB642v21gEs8?cDM6wf}S~G=fu+i=~)0A zwp_Hl)ff3p+#g@}H2QE@hVhu`TTZwrJMEG2)a$k8R$}rMy5jf#B~kB?^o!VM9Fp4T z5;SOkv(Q_Q!6L7|NZhu(uqLknrm|Xv5ubS61tq;NTxh!Y2jf#!!LviB*;f`Hwco4L z02-Zyf|G(fT0tGXTkDSNpoh`~vEhqdD4Kgl5g9&zJgLd@aPcFf+B4<v;s<Wsj@pe^ zI<&YLm)j+Sr4Hp&e51wYQXMjzD@5AHbxyvuJo;M=cA>ZDvuk(0jEM$a%GZ^dg7((D z$QuwN{3YBj^o6)mBUbUK?0UR)4uV^-7<jwo1UKI=(C4La?cSYjSM=BU#K^~b6f<Wv z5%0cp{}NsH>9*OIl~+o!77m0gq7<&&2$KJ~bbXQ8!u*qV`0sLwC{U$C0XSC60}i1L zlE2<;i_cc{9D_O7`(8PBV<4<*!mjqu{S#F@l;FYn;US6Q1Hoz2_qv3~_OFoHffWXH ze0ZZ-iyPCTZy>_vwrK4WG1uFEvY1%AmS~=tBHdp<i!|Smc(t+2gNZtx8^R2+U-NKP z*0TurQwPug{L~R^Q7m+Zhbld4AsO`T_rhu#1h9~8-EpRd<oRA@Ith4H71e+-l%<Dv z5y^6wQjZ1Jrs3u#!|b1}Jn&tihtsq83$(c`*Ok~9>om--G=*=d-92cjMm|ipj!iJt zpQ38=t4BGMk&ZTsEJP+8DZxhrk`h&D9x?p~En^8kU%cLvVMrFeL33<bi<h7dJr4C> zZr2ACi+;h$1txe7YP0l}g80MjH2mh6M$pmxzo(`MjfKb3oz{K(g%UF)3J%P^d3N{% z%9e+c(7RK><-N*;49Oe$p*!ogIZig2|He`@)}x_w!MAyK^w!h$c?|+6ULUN#dpc>~ zK$|nJWDlNX`O>gYH`3_;fbf?v<)hJNeY2i!tj>Ec^LEUT_fHDLeHO6%Mu33XV^KIt zLHPIwH?lqumlwJRIW)5}rm=+C>@Yo|R1=9bljW%R{2dl8|BO1CXlEey!S&swS$B_2 ze}(BCG|*g5#@zs7X^#~7$8%)}xQ{X+MvEThE%(<?3IThcI7i6*`fypQezKWwt>W1! z5&PJyrJZN?D=o|E)$uGz^gpx?Ho#Zou6eM;?L#H<3YjZ+vsM$PUi}R6`1(u4D0vOK z@)ZCFNzWApa%@UJ>UpUHX_u4L={8DQMT1Ogb|S^<=29;*<PL)+n;THBlE)kiLB>TI zeHSrLWaD8@gNzQV)i*<l)y$8O&b<WmrQmB#GlB~T`_DpvOG+p&c20U~j(Z;>u1bFp ztK9RhJ})5K__z2`s_thf_3P~+MU|1apv{j&TSm&=T#!KPYvK<@`zK0qa<e@t`kZbS z?-yG!QJF7k-FE`=jP$kao-z9^vJNXV*Q0XKIwKsDB;p-O8_L$ujHMl@VsQT|D!>Q* zXI1CobGs3XDwqqCJ*{femis9Xvpdy?^r>E)A<XAyrT1k8?F>3=+-05~b$v8;9(R|y zf=}TcG_xA9?ZD*q-L2eF)vaN!&<2_F@<7V?0M0s>WpSQ5<Tf^bh>?2?H~vEg15B0f z-5y}lpn4D6_l}K}N#1ySo~ySdf>Y}Fo~f#r4r)J>2RiT_r}IM~=y)g)f`z;HsUKFE zOc2fW;p<w3P6Y9fTRj{4^Tz;8v`gjBJ?292c0pZ&v{P3d!?A7t1KFeINa8@QY0x>T z6v>MDZpO;+!aGtTV~SbEjAbD*MnyOlf5$yVZ7j-K%SutH!6+LF(}oEbddbY#VT?E- zfPs>bI7P^x>*r`UKRI>eB=N-?Tsg;t=l`8p*F+w#X)<F?)s>Ycum+eb<R3B<og#Fz z9#r60_}}+*TnE?qqS7?@KVjhMEAp*rgHrD`GpxE9JB*YL{LK~{dZW0g(-6}MRUI<5 z{{We`QyRX5sE%niATxEa(}Ro>W`4^I-^9_EQ=K!YQkVm6XrPFd!|==wC1(k@X=Kzf zB}Cc-8ciZKEN-?`JdPI1of=NeMft>Q6)a^Xw-6ZhDtANgE3Ml9^qHM59X0D2SfSrl zeaTdjbj^)K#0+KcR`+rktXUozqka71w!ZxX<eB#&LYJ$UCBn_Op^%C$RA`Ge4ZIr` z3==xml#i-=0`q`k`qzm}%0N>S<F1dD$exeuTDNnT24ba*88uYmOU+^1$zFUWe6|3^ z^N_e0;(~<$53s0*L{eI`xST7K>yR==)$8(A{Sz4EI9O3i?atWz259y(dXfQ}sfrE? zJVs#z(0^gnP@ESHx4?6uPU73ecUy9I1LmU8P)D6R)u%~s8(dEKs*!MY{BUoLT)m@7 zBhBfy+1LdJB}*0WTAYGB(7_z5%8HzSz$eA;b!$PkXW_k1ZrI8K7XHw*$LdE7>P3&6 zRV&lG5yjERqc#Vc0=A&8k+V@(6!KTD?LSoHSmSkZhPk-jsn!8eKs_Y9%9m~<uE`7r z71-vtSQ%lUK46~;)py(#LLt)xK0$@5Q6k^X^O)mraMvN_81pG7eJNA7Etnma;l2gq zrU6=TBO6s89T-PX$jn;AOoRJ9G}?Rx;lO6nU6=nJGphuEsfOq{E>ZT)XBBm{pxR@Q z>{&jemOO@)$V0yU=XUzBHP=dTj17Glkqsk&{<Z-1RIdEN{r**e`!l1(^%r`^H<-;y zdA4Am;~n4AZp^^1<gliPd6eu^)ySj4_iCx0GBChuXc%{E!TS~J2tYkHj{vq1oPqQ! ze(&ct2rzpPCh~jXB>X^ifZf{Y{k$Q@*T4HIOP)?{u0>dc#(mUZBX-vXr!*yIjO3l6 zq1!5P#cxA%-__k^i5+~EuaS9Mm4Sbr%CFy8=D+#K&FLhs{+?$gJ7;T(B~_C1NVMPp z5o+BeZj?DwR22{<_q<E4pSkEeUZaVb)h$2%45JT!rNUGxWbWUpE@J0I#@%pVsm(o; z53OP9_RGo?qH-QHpBlXwv%ZxOnG>oqE7XP}7Y3FaKgSdw6#kEH&E!dyWVmzD{$FNv z3R1`1z(9uoC!qFi$=eZzX1X!y`(G}>O-@W9mcmA!8#rC2`ntfgu`{I{vOt##lP5RM zxI6_;>j)SoyY!MuW9~DL!>N$6SMUBaeo@F={tu^48q8z*3Y9<a6N6IVfHvM9m_oe8 zdwzK1ea_SBuxHLDdwCDue^9!!C(Jh&r1LXIw%ur^xU6W9lt*5OxN+p}yo)B5zRyfV zM@($<8go4td4dPHTmG7N`=-!s9mSdZeOWJpR8iU#rs@(s9E;FN$?X>9hg^fimq0Yh z=o>rEd=)_nS6e|?_s=%e8MkN7C-YR6pxJ$pqfzwBWz27Gs85-<&4@umD4H@EC4m5R zr|6a`6}_{gaV>@W14h>`uIes#eLQ?H`l5fs$%B;0%of!JPFNwTwrye^JFk(wM(n3s zq0p|oYnFn&FD|Gr^)ZjU4QjpNpZNkx>G8F*JVIKfi7!Je5LEN#V5{uV;%a?wmZnwD zT|=6NK{@I_u|8YLWrl_y4HZ_%TzwN4RO=L~xkA(Gql?^v8eo|stGCF_VIEfzM|Zle z{>Derpf;W!H1PE;<9oJ}!D&~r-dxOQv>?-#Txn$cH&mLQS)-X6(=Q_|{>s}Jc~jBt zS2-hkFM{DarA&(73x?#n3ORf{9Uf%19x>?fO%-w5I1J#1Q+S5$M*x~rP)+ulNb#EE z#JDyNCb$@meXH#QZZg?{`I3wz1T`c)BBuhy5r@Eo$=M1<Mf+GZJx>aa8m!w9Zm<$z z5gwYmvUcyZ1Wh-xzHOg+n~+&bcEQ%NtT^3midN$369h0K4jTYfE^p&7@k(^dl?eaX z^)p4xw!n8yKlDF9oLYQcDN8qOs<@HVOe+jL)fk?ev1t`8c&vgchM;QB(aouAjazpV zVOg0~Fty<KPhz6-s(i9C9_3eMT9YB>LlDa)*v}oYqnH(D)r|X%tT)^qv$=>E1W+6v z#%0!8SZKj8gKOeDMys2O>GFHkH%+z@ngxKZr$>8GB5`vj9b$kaGn`d;viW@>K4-*) zCDOUsl(z2g&UCK&@G3Ct)NmGuz~V`K`>_VMmT_Ak%4{9efQpi2JSV%gyh3RJR6?u} zGZs}O={}kfETMT!t2v}u3FS;Z(j{l1)_KWIiRs82%Tz&ryS>f;-<$-fPqOdl<1-6U zluPa`v+EFecvwJon1fB07Mo#?n$-8PEqDJs_!6;)I4-bppE(5o0_NIMHgkSt{jmW% zCN}(Rj_qT=G1vI8XZEhc@)PWYTLL(|hex2FTubtSBy6B^;tmxov0m;$_Afz-<~E-d z1#8K_@2Y?}PeG05dlZcr(jF*6AI!|)%adIw^Dy}&KF8qzO{FR`Yn%CI8FhNEjXBjk zw6w+Wj0vcH1HVY-eE$>h+RWeo*jN7Xs!M`5M<R8LftYh-#Lhi6DF}bv$F0*(wi$8j z$K0W@HCD6<xFJAwh)U!?j9AG|d{yF~F9|BCDMn6VlUQFJk-&*!xV1uoY&)McJ2>5) zsTqEy#73F+(!xX?rP?}gkMu}llkznXO><0D)(P4WUC`3l8zmSyzw73~d_X(!k_Cas zu9D_99m2!9!rwaM={s2DevY}nbG8XS>1OtK=A-V|2iTL5@B(W5GV}B0l{?IfFptRW zDc)pST#mp(PB4<+e`o9C^-~h=P^#`%lTaluN$xU1@}ZB(f7O`D>fEpa*yq~7TxO=c z<dYUSz%evqc<sOk;}5sHqr@kXe})sekEf^^6|Nb5xBw~#00Y2Y-OMv8hncCKk`#cj z@XNWCbkScDZr+z*A|QZy<*DD7=S@PKG}v2R&pFLfJhPK@X9^ls6lTlW3Y)YKrXHtJ zzJH6Jg@mULtL-sYAO#yTQ6pb-<DN5jU<Xqq3T~oQJ|_)NeaXe1%#V}dorT$gkfmQs z6Ea`go}!E^m~U>Jq%o6>;8Yx$mh+DO_aW-^d=5&1U+w`DR21%WW)3Ly_j68t4-CF@ z6de%0mG7BynMGGg$s)Z+o$AZcdz#bwRG=_+JwUhFCl_L+foM}WL5nk1L?QNC(>V9l zod-Xo=FXvhO2WLC-Z6$E3(Q({fASTEi>HU5;ig60Op{dHz0(K6{4ul;O2V?j^mz`- z^<;37BqiT7{qaveEpfFsN;DAjW(R-&o23+2c6ec*mTmrfqJxO~N?ttb!!0+mJqrLD zq#f)C1Nm7q=6|7D!Mo&Q2sM917Pta*_~x*iw1xjqR2$S>X%Mm47WGYSuEyfj*N^YM zsn4@b7g{Z+W`wRp*8-xa!%%n~fR4DAsiEd{!IpmHJAqr{)<y4Sn2dG4<pb1Qan65H zRH0{m37d<DTcJbh#Ju-kKYjSAw=zUSis<rVUe$2u^G7hUq&)1K93}LGGz@!R<>)G~ zZrH|}AgJ-?S}~$qL&|Z$SZeI23mumgl60-l9RFjo{j&emH<N<xoBe(;1qqqQ>ROsJ zald`7t4IX`+HGSio#`xDY68$9NAm9zoY2s)hQtLn*O)!I^R)Y@6N)NmcTQLJ7#G$4 z`}_N+&=2>WgZcmvycmkSL+~^Osv0gvM9MbWJEsqgBN=}Ww7m8PjO-MYB+~X2nTmN+ z@<ycd0iwXpF3nRvBS2gXIA^@;$nOly*Vrv}KAE$8S-36;^nO&90PBspB`U&cV~%8H zi(7$bJpMPTeJAWCAof;)P{p6X4B-HgN>2zC#ol~?JFvqfy=ErPk;j&xK&72NfnMw& zJmzH=hY>}XEFCuAI+WxI8B$_s^=mW~Iv)@<5`L@rhR|5ml_PL?PpQzibLic?3Fc&? zpz+)Ls`3J)b%5a@xUY3w>~>Fgp?T5sJRg;tTvXeB=SkyS?l8o%tz#Uby?|d16OL-i z0Ym8-2k}!d;YV7bXlZA^Oc?NC@AoyQ0yBeL<y_in-Trsm(wd#0r2oX;7A#g%^9d6~ zKBfYmL2$9=y~QJ<V#1B;KoIJqU+`vngYGEm{0rO|#^tYKo>iFSLA%ZYVYSe`+^678 zOb~=>#qa(<sP^iB0fkdN9_H*1dz<MPf;u0}E1N#v9p}RHC!Iw{eQ{z10=OB2MJMe$ zMh~@HH%k?=Vw%2aVGcV>Sl-weBguQWlpujqvKGjt7LdWuVjJBtdBH`s$u0)+i#cKc zQoUc5QX1kX<tRQ%KjeU(1g8ktety%n+?!|G){g%vHZ+PiGh(Sav3Zd97dA4B#WR(Y z(0Z5gi79WIsx#7@@AW8ay!RMM=~Wog2;~J#^W&$y&zFYgNCQR-3>jcocWF5aG@8_e zv?tW-B=-KZ+HFom7v5a3%$+3%SLMx*V+eFNLjae2-#C3WZc_FXJ|*W%SjPi<`A~%( z-gi%4oIU%H<M^R|?(*JQ@}I)sP$XlWAIPDU20MH6d*d4<$21(M@;-OjDY`Ke^!a5I z$Lu$Xbcv||1R*vP4BdhNmF#g<fST`O_Ta2;x?;N;YV>={KE+q1hlM@IS{bBfp@OJs zvh-d#a3)KS;xe@%{LtKB$Rh@c&esYhutITTia&=Ytt0hE_aziNPtqJEUOW_Jq=dKu zK+c|^aQ9g$PsJRzs1s9?4cu?c)_fPZqSKXS7L$pM!oMcyD%xS{8?#`Y$R8suQ})j< zlaQ^Gru|=x9F`~C(E2$aMZe}|lO|MzRG84h4T+BL$N5sHhzfcMEWNEY31sn_%X`v2 z&VlQ0vT9JO4ohF)Xy{kP*DF$|uQ<B=aP3kIKQ^l&`i=J^rs1@ZW-#W%;!Ud>C81OJ ze0zXWEa1K%|ECYh@>~-<y`oezYIXU=KqoQh@71$gH9-lDUnM`hj7}0nza?yJ;Vp{3 ziW(%s?Mi}7_H#4l_fpjDMwgrze+}wzj0OQ^+5>ue*O7G1EMrUpa=$E03|XFQ*|RlY z+<RZNNl8=n9D*7iv#2euO16i-d0^EN+yJmO0l#8$+1E#D--ntke)9k)sBbE)KPlOw zy{psCs9r#8W;=ffE>^A`zXbG6O7NyVx>m6*ht`rMOi%6S>>n4>wq~l=pdY5Ga&F)v zd0vS7e#x?8dWzk`t_OU}>w~=$%Z{SJ?BpB#@*qR4e-3E_v+padmqh`_EF8$dR1A72 zALkxMaM~a2E-!y;VjPb?+;;G3U=6JS>1B^L=AzoJWPi7&5LfMkHyA6UHD|wEJ|6f# zs8*cRK;0LoF!kV~@K_P=y-%*bUeDiZNwfnRbtr*nFWz16t%Jp@pL{CPs_4fn4H~0u zN{Y|D9vHg?cy1Hg(oELFZ{8_~UpswDWEyFL!+XJpLY<Uc&hHsYT$dDfyf5>bC-HF! z`j=+r3HlHN2VT+~(~I}Fdl~BaMTJ%VY@h4te3W|MsP#2Rsf9N|PydQ5a$eXob;GZM zV%nht%f*Vo%T<qi8$T7V@0^Hoihh29q3WXiuk$-Uf9R-Ax#r6-EYLr>%3vhkMXhG> zhPbXy8H|++#*gpYt$Vre>QB`@&#bdGR_pqu=7V(%trDL<V;K4Mh9qZH-l5!rAfq4h zcUzP)<VMZ~mf20tUUVv)(b@V_(<AdlZg-5?$(L@oa~l|v{}Es%Y!M<Pcg#IIR0c9{ z^O|;j_EUn(F`aNyX}@s~g>39>-5EBf<ehVWljxnFZ(c{PH~<;PSu7F6ev3Rn|GIF6 zeq1{h6&N-K1d)=QLED#h0~+_f69BDo#s8iU{QGMcm4EFMm_?KgQ{nvRRrNFeyr-mf zpQ;DI2rMtd^Voy1YMqw*3mxl~&4)~mS2oFPpLyXZ`x?}~E7g3ilcaK^k=*Q5)N+nK zFD2)xwhw6IeLpd+BlSBLW%EdOr!cXmWck)-a$BihNne6wBl}wedW`_E)5{%Q^|X#` zgQu|22hyL-<`M_(C7(7*^-~k<`~<^3ei>Pfe5i(((Z1yadQ0??5xUo}?6)|4Xw&a* z|M!oWR-^)K75xlx>gy`Ep9xBS4}2i{5hB<!Z|~){J=gu~3(rqq6UoW@(vUcl*!Jzt z=loeuwg|+*c~(kF@I>mg@t_iIcSQ05ej)~QNy)7J&;5+MRvVlbenrVW(3cwe_P*ZM zCHwmldK+IgcGU$Hj4L!s+}?tttRo-ai5UFR>whq<clhaS2_soIdeTC{yE=#+a=9>~ zfs~HX42AvsF?V*56MzIhnlyg#3cBOeVSD$aGX2Lq$7XN;lbPV>-oNA0U|n*He4mKx zKJ`bV9*=UT=$H9_t!p&fnT(>dNN|UCBHEO!05Ev}6Jzt(x#|Vw04Aipg0b&SFq|A4 z=FV;h=z0JM=&)T6DImSs$P9KrRsmInMcbT%S73RYDeow3-d;A}bA<FAHvb%Zx`uc~ zj2XQnFR+aj`aO>Rfdvt(<qY~vsN;Q=F(KYMVO`ED6XYfnj}dl-zw0ZC`K{)(5wDTh zVzG)6*Bx6W_e*5gN%l{uMBSIHRg`Y7lfJGf(_1Gqs3<#8Cp)Jo_oPm4S&=*Cm)}-Y z_)(|uPZ5i##|kPbiq|X3D=DefE9ojJo75}YD5*HqtGFwv`qir*QBn)9SBq6rPp((b zP}0b**C<lbtf<$lRnls%*SfBx-CM6csHF2G3r520JgMKetfae9-(W@6wP3(@m2ij# zoS?G4ctegV06e1dNGcl^J?1mQ8#*XEYf_E;ls)W+^bR(d#44L6H<)H9n`Jkc6)Brn zG?>>aTQoOVTvxX2ZLl0vwwh?Lnp3uZ!fCKxR<_w_u-R6&{n23iPZ^JB#0#nr#2X3n zDt2m(cDgD=lSZPA3dy07<gQ}x*Jyu4#UZ@WAy&mPxzRC0g`C|;E>dx-XmqMoac*vO zzOLfZ+vqZ=;yTgjI;Z0Hq|t3z#eJjEeOtxjN2A9-6;DKyr=Y5rc$1gBs<&E`x2~#> zNt2I_s;@(nue<7gzoz|1RHH9KC4*J{lizB@LjR>U5wfAC=}_}Fs97XC;A==)TT|em z>Y<6ILvyN!pEMm_Rz0%ObYz?B)ZBKyt5Oi*k~CF<>;;OvTCiGku&!E&$%dD(BE}-z z!Y&-+tfrZE(KE6xtY}U0xSGX3PIW|fb7YZPRP(B6h1#*^jq;txFJ2B2Vw#Tqz8Kzh zUkzkzjyLl_WEc580@lJeqDG_t-6Lqs-fJY<b%cM2p(p$f_Z*`~cWfB8377!t?`xo& zH%6ljHr<j&TdIgBdS?j*1=~jarX8aM{ET^(I$@rNe``27Jz|jsHLoGY7tqv2N6ibM zrn01nW1H+0;#mjRFnO3s0I`M2!wp7UE2Asy074&!1Yw!|ieuVjyPdtwa<jT=F3awK znzU>Z8lk3RE6-z~XAlIiiXfGeiIE&8YS0ZR8V#@!!j@V;18UMpzxi@Vqz&;hiD)Z2 zDo7zn6=aIw2}1K6Lc#Nm_~{mRSY!}?<k(iNT@ut}D10$)RJ)2GWR@vaH7t`t5c+6m zozhZQNH6`t_)<_TC5$j9NA*7nH=}9*HQd=T-MHoLVkAv4bXbLwDV4+{#G)nEx0W^| z)9Ya%6X4?Bc@QRm%{1S7ceH2JH1u*iif$E3&lc9GP;$GbL&xj_;xHajNdkrft@+(- z?s?fg0IH30HIF3L|FE~{8NK|K*VvV4o<zhH-Q%k0Cfa**S37WrirK+~t~9^qsO!z7 zh**{>W7JZER9#XwLc(6q*)pe$YJ~D=dXAd&YagR|U8@~?$Qm&$gC>tb548d6l+7#h zobtl{`=(Pw{jyB+blzL_Y6;I7_fnSo{XQtg5-kg8Qd`*U*wOAT826IR7z?|du-~M| z-AqzPh3mvg%>{Y$mNnXL__n&({o`s8mV22BA7=-?Dt6jmo+AiPEy8leV=SvO)o1ex zioDQ=KX{CNROls26+p^(m2_HYHZO_LWLX*<-Ygt!RyJyqLeO7{QM4i2PC+~G$6S~m zH#ee77!e<CD9(RkCC2VM+C$V&88+FCM#zs%*Vb9#KSs@MpiJ7Zy->}q=(}A-GXuvZ zlA)v7O|P6+MjDZ?1nY;>Xi`1U2Noo=j%#7t>TUrLLDw~tG3d15al74pVGs^5xwvYv zr}JMf0Fu}4JkP{V5if5jgxQ75%WqGN6HUuTR~$%Y1#QNW*OY{V?k|5Fm{#9G=<W0( zqxU{}Z9_EPzEh5MFe~G!`*(fEL2o^I_5GoX@&CqlA;IRJqfd|N+F`Z0Z`TZs&(v4V z&g`aVi&@+HZBM<Sdls=Dl4HRuRjEgYPrLHmzQ3qxrvCAHcIrQ<PJb@*K!nvwwA2{U zGLHD``1Q?+_76X@&H9ez?2|3Ma_?l*!5@OoO9pQDDh}K+nQIcKtGA74Eb)j_?ersa zU<#zY-j1yd3i`$<Z)w4~`k4Tdobw~yhS}V6IEOby!D%m#8vD|1hG-ZCPABFM)Ras= z(A)IFVrTOp_gSEv2Ts_TeaT?b%OE%)GIK^vVA%cAm*n8I6ryR{s3o>jdUVA45#4-1 z!49u4_QN~qF<r2ILhn}Y-FN!Tbb7L<KEUF!m?9<#(v7Q5#QnR<&FNm%M9F@0_)fmA z)$C}TLbP5Y3jd+os&rz$5v^mOB7AJ9|Ei4a)U!uWvt2#Hz-Mj<?x$m1<V!c%s!dO0 zirgGsRDx+?6Ar1+f8Ie@#?Y;5GPf_R>Fp<)9{P%T4ON>AR6pBgM2VN3`7Df3I89)P zRF3Kv*cl$8n~TQrBrellUNZVT$t%QiqHN0f-!pNA%8?Va7CE{G+J-u=!!|vms;<MB z&qNzvy3u^B9l2fDVMXSU-B|rqvnsl|6;zmO^qEvt8(z?NSoY=RI-XtT`d6p6>(_lh zNY#v*58%|MyG_@jYNHVJ4pCq)Q;S8#cw`nO<fQ>Uc<5?o63(S@@_(uLOd`j~vmI}V z)%q0NlhrW+DvV_<*mKfj`bqKF=?K+_hB8;FJby=QWaBNUbk`HHA7X>leLKyP=%zge z+HF*Tl&KnEC%TRoWKw~3sxf;~-UDruPLLtjPHS{&NN=0Yesdb7Sr2gEj(|Z-mv#r; z778e|XN&uE3qRK+bd2(cd<!@=YB@$%Wpi$*Qa;)4()DqKLqF-}ahrPO-8ofI<0+!` zJWU&{A?;1s8fm+Q(zRYsRPDkr^~nnVyrnwnmLCm+BzkT7?BpNO&3uXGlb_3cfA}4~ z8rlv!5YelO?@=X>np2@>9S{K&Aj0as`K5PXBHeBVYW0$~uEOA#g#iLQyD=Ys<{8N} z=a>(S8v2gd1fC3%!K>~<O*$qLh(Bbd4{Aqe0&PPlCyCmDcBi5VwxL&3=uA^Uz4P6u zCi!_GSpD;YU}w~>{O|API!SV7MmCM~jL$c*sK-&3`iXi${~yxs`>Cn^UHJWiGzduu zRl1>9A@r`HcMPa>6{Jct^dfSH9;u-U2pR+hkrIkDQA6(vh)5BoH$kb2<(8B0e)c)f z%-PQmXXg9|D>Er8?{$4%7f%-WawRO{mB9rb4P<Ee9l!5z5{~D{Kt}yLrOmPENJ@|M z^iZ#mhUf+K+FH2~@arqR@*mamKZ0g@dqi0auYdcZJlYkfU~s`fm63;d)>2>TdCyL& zf?mvXcHekxbK;Uj=!I1x05Hg2Hqhxz&~fNCkkp8%YmE7vQl<&^((jdbWfUJz_s#1a zFmJz|-=u`u)bklrCg^|cyO$o(^NKGaZi9F)m-vtm$4Ax|C+jQw8wh;~ie}P4D;bzk zK{^Tb_X`tr1~u7uK;d5DJcgm(4?z*eC%KC%=9c>R1bX+<6CL5R6we->c0HwWkX}uK zYICr5-Z?$QFN2yxxmjD?k_5$*P!!%kogA+=l>o-k?hNQFlY3HSU60^PDtV`gL5$jZ zuAv&uASb`L+LXu(hH=0+U32*lnD8)VaLUn9-=!XZ6ZTx)5PGjjLyACra9KZQxO-y| zl=VLSFf>9rPPNzI!VH6IUK|5PUmFj)x)J1Dt%<ht541>(NUt&QNqETuoUQRAz5P|v z#Hca&73O?bBa%hnOV1f~uypUHCU9HJrGEEmN_~@EbZ<f?3yvpGN1E<u;1d|YT^Hnf z+J4Qi+<@((ZuP)~HE24!Esr%Ldz5L%VfPYVjc9W47|2>o*5-kHL=1l!ahJANO3Q+^ zXI>t1z2~^}A>B{Suv~9QJwct^E$@-w`$FN-*Y83Wuh_epdE}m&kDs<`IwUA+sL1LV zknZ=4ro?@`?fq63Zfnsae%8>2i3=E)1~7#|zOeEOVvYtcABeW83`$-+%YZawP-&|d z8j)lhuH=#x7Iyt>koeXA?_@>ywgJCE^L@HE5;I0$XmJSF{Db|cV^`)vI|<`(A#Z0( z)>;NbD8H^&clM<2lDd;gS83(152x&&(e#fum8UzxK;u;3oe{@`cC(z*44Hdy7wu|R ztP!%-%K%{H9~q{dQS_Q>%XT-(I;)r5Y#Jy??~L04V96X$i+c)=-*ac=1uXBY2dz)t z&CN3k)Q*F4Y32FYq;if8rHK%s&wP(Z`<le`6U7PpukOm)XP&y)*E@IBraLtFI5v4t zJh}41PK2w36M6obsH>5-AN2V#JBBv15VVkKUNKle9S>aS<gzPK{(NH~E5tU}JG-zm zd?!|ay0hrexOV;58X8D^uUWM}j(_f<Rnk`H{IdUVbYn=sd~49WiwP4>QkVO=n?QeE zg>l>ZgPUyRm7<mqpr(PoJLzM4IallYw6(Q%VARKsurpcTqX;%<<}>VHe_Ct3wX~SR zP3xU$kJw*LDs$HQ<d*tXI$nV`4RwD@1F>;#SEvJI!$%?AprMyNZ!`yZBntd01w!6L zK{+}eG(0IOmZ+|xfz_XFX>vOHE2{guq)*T|MjZ73mF?4}`m>1pzLF0D01nvsAB!A& zTJ&*C+o9vsa(Wb!DnbCEp$uEp-wtJN?XjbZuoCZa%7{E^k;8IOWW>eRin~kE+e+0h zSoyK~mP`6zaZN*ZmiL^Zsn7(;Rs2CjFEcwX=wnE|?2m2#sfoU8!o5hX?nvf_kY%^N zeyLx=DF*I&BTIFsjarjaCN^P~#g{*;4BYp1$habv+M(~GVD~_gNoC>@_DN|3jrpL% z@b#7q)-l^^`f<KkJP5dM?mIdh__fIc!q&X$-4o)VCt@%srhmyLDF0l9r0?hz_UX{s zV<~OAyhF-=F}n1`m|=ZT^#SR|ysvDk>q_Q}aOP95GpvB&7R(r!`bl~eSz%jCiEewJ zb2qjy-)bd;<!fQNIo9$0O17ExIL1$-sE(4r&JN@Xh#uIl7u}SfT{k(DMu{1Idv^<x zELAYvkNxGCy<YzL_=i^x|Fht&%CeTj`|`Tr{kjlz&JW&;L(*JUwgXnm+YOGKU_iR| z2-^JEhiWMFJCU0qBbFURoT2teyl@?%?@O&%JVLn;GNlfT147c7o8+Tw6}{@cgH>TR zROZfHQ(#=cC1e*n!6XP2KKJQ<y5={mVp&;jUL4u1c*K92+3UPBW>Z^!{|Go4D381O zZQ<k1Yr)?xSqHm5D)pUHgn7n2$WDI7FmdW~q#JyvK30dIpkFO$5nR<%sP@gdy1Lcx z7vIFze#`mk2UE8uZaK|u)N};TZJ7wMy_Mc5V##QQ5`!396d4ZWV<CnXeCZQxVvZF8 zb5+I{GVM{fN(_Vw=wh_PgydH+!qtV>)gIwcsYw+{gmn*W5bX5}V|pY`x06*ng_}aA z>d(G8T!g`@^aY{f&?|$cT7YYMgk_@Wr$J+ctZhc*%r}9>nVHv_?6}z-ycMkcQKZDB zR@vgmIEaXe>#I#<0LjM?+>!Znveihn(Sw8EW&kUvFOpVLWta*tSMv$$AAVWK9}#~o zdwNFXJU|irzUPepC^mpgHRM-xIjwNo)G+ywn1*Z2T@Y0q%9bU$k+}Ey1&o4A(|LwW zQ{qa6yziNPr#zFAwOuoz{uu7Y!b6tYa>WP4N9>as0q^la1yYZG;bO++6!UWV_qqBW z@`pAM5js;iG)kxAU@yodW%-;;??|&kk)g-DZ$n2q&6>0Wi<vbiZt|m-!6}Sjn%2Aa zKD8qn2YdFUu;P!Lna-x`qS4F9m+WspPU(rX0f6qCGNU;8X6<j$NZdU0#pD7!&zT0} zMEP!1NX&#dTd4?6(wE=98wAWCw#*V5GaO5qi;E1N@;&xs#nc&O%QdW?E&n<B5x7{X zyO3_OuyyJ9Dx>H=)+G8=KRa_NwET%MgD)zH@5)o5O%q(y_W4Tl7KdoVBETWps!pq~ zCNsaL-Db<$GJm?cK(*92>`V3xpM86yPpMnqw##jpXbgCT+tB0g)v{FkE)=)Ad(;;v z=J^-Nj$*nCh#@!D`wm0aYDVYATrNplsKtn_NT}-$D=PClO`!T77mRKB41}k}5~iOt zre!FO9GOhLDQG#@;D2twaXv?SMdV@bpn{8%e91N2);`rh6H5#EQK44XqM<%)nhNH! zZC3mH+Q8t8ehZ-x5z(JB1Lv*XSku~aM1B09hEF&<@5p?3yd}<a{#>_n7B0Nw>+@Sa zqQh?~pITk=0W*nk_0#)7=?QkL#O13$?=SXtguI4J%-lHM%Ku`@)`e=>bE#y~&%CN( zXHD*BU8SKg%i!}3yeVd05))~iX+6(5O*Wl&-hJ=axRTrO#IR!NLbIF4fPmtF)~B*b z+dBn@Pb-3qX<aB_aCOisT*;<8h+V-{jEO$|e=)BUrbcCGs~TJ|i4krL3)`ysJk#%J z((c0Y0W9DXdvJd#hT~LF&x2ifz<h3EMVlBb`fPDW_m3SSV<v0-fQWJbP`0X}P}~mo z2zC4;$+q~oYj_4zZ)8oE=m;KMXS%xCbZ#&;>HZS+l{kK?8MC#+K;-{OE--2oX7eH6 z;AGzdE6U%1;!isnKLF@@>q0i9o1p>khe1>EKWQIDzaZX^P0L3pbZ7WdSd4$|^|31I zPo~qM8k~x;dPN-lXQ_hoZyV`C3;wIEgP35*BvSx=>I<SZI;%C7VE7S}?G^L<lX{Sy zsp}4VLU_d)QRtA+=3>P^7Kt2#RML4d#w76_&@$pJN&k20zF>>HpiVxCHx@*+mrD@b zWoqkJS1L*}i54C19l+9OquBgBct5@}<#5F&-cu<Pr@Me5%JGbIT1;!fNY<P}xooTX z5W#tD*z3Nypfnc-;0|D>v@_A4^@nzj-3?@{pPiWGF2=KwJ*Z>r77mOqapv>%3u|<- zSOdgUPRgQD?U^@@SlTy{cTk$<gKME(es8pN>Nbs1RU^|$Hr^II719oqP~hYvvzKYl zYb#;s-NJZ5ORt}^Ir3}^S1Zo$QyYzl3`7SPXVK^KYP#Es2n{|)pqBt8+OVLwtDW|P zkTCV`iT9sER{6K|42-*7nKMpUjlVeX0DD2KKIn4RBp^`)SY&?nn;Ym{Ofvd&o5?a1 z1t4L-=byqXjxH7TfN9?^g&a7LsDDuG5G?1gpK6M@AjLIos$C(xcXA7uPZBsl0GV$e z(CJJjxM*zmx<C&-NQ&Ebp(Nt|jNSzjB<bu6gDTY>*Z`^CP^w`9<l<QK>TOT4jC0>_ zP02q(`&g~s=mM7-{dDMpI@9m=m(CL1lx$f8wk<{S=##PxKq8IF5G$#X8Lx$9o=y5; zh~1_?lJ>%jun&q%8!;$%A2AJ?$QcN&b{$EGzTNh}5}i(7jf)+26R&nl?iOLW$SR6q z1;D!^<h?J@uOiE1%zjIUCFH9u+pMQ30hvS=8%EL5I75-uQHNR!-y6}*RU(5+Sb!2( zT_*6yM8FBg!e9{kC-ua4Is5<y=o1*}=e{k67yh%#k-6M%pUcxIPb|KmIMrc2z`HqK z?Z%L4IAdZ(8T?Wgq@?U$S4GiPy)U0Atm5&Az%HRx22`3N-)&!kQ@clEhD%>6*hHtr zkFZuE+e_R{iUN>oEi?@9?P69FK^u+do7bI_XFU6cfv+z}XyT~=bd=9LUQfQ8vo3)3 zbg$P}|3pj#wAFx_c&c%OK~Ov%trIBZr#}JT7Mes0AR9%l+|4iP6@esxR2xNE*?~M7 z?=nsFTs+2ctie=Cyk1IwoyIB_e|%X<!ZSESC60-LJiZ|>Ft)_M8YFQ?DG_fgvdJJJ zeIS`}AoWl}zXV`yyC{-p30!ZG%np`e8RU9;Akz@+@dhi~-YEO>K(<Rst}j?_s8Me0 zKyE_m-232jvyJB#4$dtp$*%>=Z#ByA9?0)2DbStppN$In{~jnXC}SZZSmq`y@(|0W ztjHCj$lIhSc&I3>tRx<yB;BNR?odflSy?qiS+hx5_fT0+S;Z(s#jHui>QKc-S@lYY zs$-Mt)k9S`Wi`(bwVO?90f%Zq%IaYu>QPPVcMjF#lr@q<G+5us+&$FDR@Tf9(JZ=@ zA)trmDbsu$qV=>%tM*W<L0S8Gh<1aiV0)7kBjf*;x`Y81AQ^=IFR4ox;4!6Ax)PW; zWK?E6%X(7KqUI&0|BuwwP(F}_`ERK!SL#x=%l}d8x|qcr3l}tR{=cQJ=BMu}|4Zt6 zUj6==LzC}+OI<ywf)*_`vrRtls;`c;)XujOR)$M0TI&{GL>_K0jI`E&{*TlpWZ6bt z>LGE+UK?#|SQ#LTT0F39Z(JKGRQ97wT}>NrDF$gmRvpb-@2W06yEfMG{L2Tb`v_g? zYT2D{3;FVC>_zLh&$I-Vv(}w$`zwRFve)0xrLK+fa*K!7FFTIE%ryCZe)IChk8g`T zX{To|zUusWxcTnc^|!BH{{FGIGV<`^>sSB&J~{mI`R(i1bSDWawMYbW`z*#WNmS9L zF15|Y1hlc#QX;3F&r%YPSJhIo0NsjD!6Zv9lf(*qmhVbEsaj5zYuQ{*!}d$9q^nH( ztYm1cSFL2~eBWHj!a=21$%foFSF=qep04Its%@?2;*F)(@-ExmT+4Uxdb;+%q%PNF z>GeX7f}86_K2M&m7yGwt{kPN=I(>7aG;;mv#)FveTN@9FP?=3iA~#*?B1u$lK1x^H z{%@%(&(3%2aiLfB){~O(?X616|B||Vx1Ux$sot)xY1#gtQdj5q?JxB-sO%24m-~N8 zT~l^`yZ@28c3VD%fBF9>b)ik<_UTfW|9&5jH(lxyh}hX5z@*3>42s?JKNym#tT`B# zYuz~*!4AkBj;eg{KOEE8s5yM2^JC}mEe>|>Xx#8jz|n-MWbM(UrTXsCJG{xc<EhK` zbg9e1yOu6>MeH7ba7{V)ea7Qn!1r07%G&R9{;j*;=LrMnetZo55b$Fma-;Ugr<fn7 zyL71wCV#S+cqZ^<i6lvvy3*CZo~)2f<bST_*$4hyEA+1Wxn4q-x;7{&^1n7K?$M>L zs>-@w+cm9Ue|@12(50^C4}rgT+cxTcf9?G7l`eI`6#ne>p1JjBe^8Pxb&aZj`*S#M zqVVt06kX~%p7E~#_xs0)Z~y*SOi}oIvU=~<-=CY6bg65n_1oXydjkrme~v!fI{o+L ze@I<?dqgHn3gekU8dPg94xLT`OPY4Uo%Z5+Mk!GB!7fzvUIGSD#$;mJ&0f5hC}mj& zw;$~0?$}Ghrk5eSO?&v}_L4P5%TN)6Jwm_sQgDbz=+hL_UJ<^1lBwk*_Irc95?cFr z@#&8^D^2@koc2>4Mjvsv4))1M@29yU+|Tss87rk`i>+c{dXpMx)dz}VpEXRhhxG=+ zOI9+3nFlmeZJ=^E1{P1Be$DPUldL>Ze*BCcIvt%zmtFbRq{K{GCQ!C}081?WLMgNa zdpdlbGsPrsCJa_!($BrR$RNGVhSE<y5Gh}cJA+<=Xh-Vh@6Q;^UcZ?gu#*kL@Aa?^ z)69Tocm7qT0kt+aRJ>u%J=jfg-X6WofXFha&fq$#lbjLY4-(iQr|6|Nz;po`5-bc- zVF^b0iakQ~aDr9mgtNk^?!2`QgDL>wG&8z}1DFyp)hS*|3O_0rctJ@NnxYfsKJl1+ ztf{8cmbp)?J7&qpM6m-0*BUP?t6xmkS)D+IlR)LZq3))}Y({uSq9B0nK?C@-o9WGh zb4(^`jMbB5|8jmwt_{vD3QX&y?CcjQ6ZHa_%v&+#>5_tGmlXIiZ?$ozzB@?~q#sMa znVRru30rP49AqNVlJGFR&`{?U+jM<AmxQ(FBefO=Af(VO|4iw+Jj1WINhDC-O&t@p z&hd2jjw>~Ht_*4bR0pktTnZVC<C7fe?=`Lvtl#TalQ5qha^e=r6G-BH1IJVCj+$70 zChJJJrMTb7dsGDp&{k@nesgN4)&ei95X7*t28kWkwp}6d&ATPrkf)p3G<UV$ZzkQy z<7#KMktau|Dk%rH@On!1JNCd`NTv~{SivHVVYe$GHRVEmdyHzMil3BX)y;;){PboR zQ1!8h>P0dPOSD1Sy6Ew3kc~A5_orUUOV@d-_FMeqQ_?DM7o4mzKJUSh26xstbK;Yt z@=DQlTjZ$#ef&ZJAZLb9KeVnA<OT%zGXqO{&T?l4CGGBKR#q39En){XpZv<04<3E` zX|G@Vz|HL+8V|S0x{2;9n~XH$r)T?XQq-IE*8F|S`K>?k@IG70h@L6$HvVoRAKZ`y z|5h$EKeKo1VIInoeB+e&8_7iH*F;w2Oi-s2cZzz)k|)bW2JU}a_Rb&JAa7Q%wOBP8 z!oe6uws9g<bDWXSbRs>vB+~tMU5d7hWxRA1BUfo1Rc^ZsdGj(CAZ*93{mYG+jcM^c zHTF4E^LS<ifEfug3wuiZGwIQ*!Mi2Z#|c&1)c-Nl{0(WVyUYe*sG+eJR2iUxsqyyC zkNDP4lGTr#6f4&Y1uKE33sd`y_A?1H6$Q!HkTDgZQ{`vJo-oL+>UrDM<G^m41Deae zib`5x0_&zGLaFIl(meFLL1I!)lQ5DZqHVUmX@UX+V7q3Jz(@LG9=?FP;fBrp3rU5q zU+-r|=or8iPd}w}At~?}+=}4Bo^f2+?Fxda3t)ro*R(|3@@`rd*dK%rW|!{Nx-JU` zPlZ(uo@7Q-<DtSQ@!7lkj35VH<S7NJ6!2w5B&=NEy>Y^uC?N>_@d4MOgKVm_EVsQt zJjP{DzG~C7-}Ay%K=TBq_SYut89xmXy+KHs-R!UXF(@!Jm8@Dlmg4<Uaaj|<_4(;$ z?xS8cUEP-i=>Iy#ZpUBoaPciUXA@wN2jcs8^TlU|i%8V#=bJkEI-1S<2>YgG-bK!> z-VmXzh@GNM>O*+qV+P{wW?__QVE!d{`3<`?8vCS=@rBE-04ooTZA_~F!kk{l=dbJ& zJD+S$mB-vr0Y}U4`w4$EJ0>!z7ZPeL!esW^Cs!g&%LRYZj06JNvO^ISXLlFfa@nI7 z(B3|@pb7Omvz`E+>Qp|Cm|eU>S{KzcM!OlsPSfD&UI<3J*tY<{NMv^RzH<13>&$!P z&NynD!s<XkU%;W^P(U4!(ff|l{o#K=K+X}7eN==P1>n1am?9$sxq|gYP^&)>F^m5F zIFof(<a0@&6^5Gaw=*>1P7JmCLtyS8phKw__1{ZdA75r005f849pD`f@Q^EuFeo1S z?>J)hN}|dS(RHGy#CJs4qW>-)x#o(Rq{K10BBot$SY3(t$VQe%u!0&8;L{11IS##) zk5+bNRK}u}tDx!2w@js2IR?O5Cdk>=po%>}j}kGjW@ArBD^F18)^BXMBE||p8eyna zS7Zq-aogDSqESk{C-?F=>mC-Z$OM$4*&1lfNoXd32+dSVKJy;MVGrpaN3D+|)+rE1 zJmf7pWs2x&#}u<vDQW=;ts#OVy-ofcAqpvJ9OC~x^Wk2{Aw40$FB}_v+NuPH-aL}x zy%G?%7rQFS>SYQlSY#f@AqzGf{WnB6iN5)gsBjZd<PX+$H0$~v!fnwXz>_d7;Sb(( zzsI6~w4s;8t-ZODnb=}ta*Ufdd_^Md))((`4lvK0TxLJz$<kW>=OX|-I>SmI_53M; z(w0oy+C)}Y<@yA<gS$v9`|vRU*e4>Piiq4uDG!eu)2@h?%GmYsSVjtD+XRIvvTgN@ zRG-Xcgyc!@#Q@yiH2^sB1M5pu<CbIY>yJrr8~EQ8Yi~08Usv0^%a?hiNN*P-XQ2fQ zW=Sb+sWjD0)q~sun$LJj_C6uPW}LOYEs$e|d*wOm69N4b0QA@XIaEbsA?D`lQi(;` z?NW?yF|JMCNbFW*tKB_Gt}FN?2hD@atx(__hL!(r0xkljcNhAr|MH8W`$25Qa0XA% zlE(thK7F#-eAEB!IO@}0Vm~o9sm(pK&0hF4g`}jP{4btdgGauE<pGNY`;-z^d#8UI ziqmrPHz?UL4kX^FSP@#BhmkRA-4(<}kuj#cRT0HQqBy;SHe88JCl3m|DUfIiK^QfM zD=SdCR^XM_yorpO$)x@)4Zj<eBTn@5cyzAOVdXJ}B9+hf!C!-^%;iju&)s`P2f0C- z_k@bGZ?`e-;z^gDmw<%r49y>|X`-(?2Dt6ThJ`)w9)z=bUeTA~p(K`Nu!j&F1B%R& z8mclh_Ykpd_xFba_sv8n9Z_}Dk<(ST8EIgI(-lvdhlmiHbpon}2(<+6NN}fl@kGth z-0?}i2G#dRZdNEQBd5_2Z*Sz{DJM$BEF;3>iuIKWHh1Hd_b9$6-bO>PY&8?BzM^HR zOtne7MdDMju(H#qRf<vfgJcwIn=jWHqE_(Lz^1G6+$H5|(G9fO3YW+A59ZRwx9&tn ziA5^{e3VPcdF*@?OZGC9vFC6{jh&VvZR1**`IFM0q8~bH<!)j>{;I7zDqQ#_vglMd zn~Gg`N~wnw>EzTQTIyEJv8`J5QodqGsZlC?Icy>IeSG3#(f454&)}jDmf+5rjww4G zqBFm0_hjmjprX<us^v13+ksjZtvKT(v3j?mQoO-YzoCnZ?Uxf;^%wTMU87fgBil;D zweCjY-;G%QCME4AFSkUMQ)l$*R^y$=O^Oy&oiyhQ{4Q&$P5Zyhfq8Pk<@$#Zsyct^ zQz+Gvx#<fo7I<tSJP@E@fuv#4$8E@O)N4j*P7MGsNx3enYWpwlmM_0e0~g{R9*qYe zXkn&1L}xiww5uzu2#2V^q6f#>KF|>K^T!`B2-pPtmZb4E0Kf}S(>NqZu~={k{&<l! zpT)Qm03K5zeH*A83v?!_7~TMb3d1T`V1#ja-gq8J4{VJw+9KqG^^kX*(dP*uWeunw znk~>3VuxchB*Xvift@SvUXy~~qSCcQ7I-!+WE@^W2<^e5UjRTk5kbJf?7^@n0G%jg zIeQvux0LjhiJ=s{&x-DAX>f&4Vp&IB(GS(p6J%C@79bUi?j2|Dq8auA$Xh>{GO*}2 z0{xZ1|6u`4QkY|C%r6L`y#Vk>9sLxGW|L!qcXe{OxP0@2H{jqD0H`M$zKKNNN<)`C zWBa|x%Gto`g=NY|GnG>>8m+>Zf?6vUS>SHWnxk--;w{=9tFx@Nvo`vy4?5k4#meIq zxGV?CX5*ih1J%3OZ|D>(#<~w!uTk9IQ$x5S?JBrzesjL+p>}}xApow^+7X>Rr{9*` zG!=!mR=cu5L0*Cab9m%sHS`;1)NP5X`S0ijvT;!FMUS)|z_m*Y10G1hbl5fb^Do_^ zgqrNS4*n%DPEg=h&geyoG4>ehMIM61CH`OrMsb}?W%Nq@tSQ3orYrg%p#9yi#=s-^ z6aVyMrr|j(dX8n7iQ&@4MN|N71gckh6T<{@gLhk^6R6-ASM+wlko^_(KDK2dihgmB zTZBMJ1L}3rC?tD?;_~_e8=9^r{{%xk005AC#4x~M35d~;cbozYOyI=;O4l7Ihm6Z0 zmEI;;o}DXU{7;);9m;lQN&_3EV+^kSDHuO1=WyK>8DozoYGh;ef^QcQKA->RFL;=7 z97$`<P)yJVpRpFUc94L5|0CUe(;#F${fc5_qm10`^JY1r!>VpNaqQ4#6*I;HMZdMt zeAy4r&k-Y_MMuv})E5L9WPdrn+ia<AjU>RFZkx>Turp}R<#YTv=Q8oi>IH<G^yF+? z$Tx=x+{gNlt#6%$VgEj(erk`bv11ya{Pxj1NX4k<4+8fIXSe&NNZb2n5(!)SA}sCP zi!V1r_T}!P-OQYHgL=|rS8q3b-u?J(xvb0Y>DA5$@{d_h!EjD@PWoxqc_^+Yr!&OJ zEe(bXoNo`9AC`5Q-xDClY61XQb}>f%Gj7cTM7uC6buy!$8Rnj$x8d(02$)iX`7W}W zo1jzy{JS@5vzrkUYM>-HOKlkH@@3@%oDC=eWf#hQ=l9PKBETALGl@ZO+~<+rw5y0i zG}KXqtf_s#B+3irp@A~|rB|;DLfItADmQ;l-N@Si!{bRtqRfi)r>P=58dro)a<XhP ze_m9FpTBIa3s`EP@A<b#U(4Dh@k+A(i*K^h6qJ~fI17z3$SjyVmSW8l;vs-l%a7h= z#mCyMB10K9)gD&htH!e!Wd0}*OZ5?b(9RC<M2{yLkG?vfRA*ESGIUIMaOTQ=Dj=bF zg)5gb)BtP|TH{l**yo2+_`|niHGFu33uB>LbQRTiUJO{mze7m(k=fs}2>&s#D&>m% z6;SY*^a4q34|`|n!z2Dn9+>64G+O<|w)K|fJbpz%t+7}WYbsUTl-<pevRe3x&0^<9 zUjPFa`hUMMi40so4x{4#7v8=>v>yuakvO*+Du(`F(JX`lCWG`cdmWqTyge@AzoQwy zo;hx~xhk>p;(a=A|DR~a8kYRAI!tW3-u1ttng0wL7*|4+P1iWzr62wG`Q7rLXy#oU z=TKpBPwt;4CLsimdG^aF4p})c@&59EqL~Cw{dMiYjbB6aa@cE~;lMJ3k7QP;@`bUg z$Jc5*!kX+Ww(~R9U#M+P0;@^=V=n{)KEGVMD<P;A;WOEj^bhxWr&in=C6{&T-*%1t zje%Ni^;ds1!dA!93{F3sUkEwcdpnjp5V)s(_yuH?cHfd7&8VLN57D)uY{`q|D!EqL z8vxo`1BeM(#I12E56ku$(xX|Qih;S<Y+mjd-6UtirOaDaVB$q3+7?Ok6o=(h$rjT` zX%erb+|w1G_)s#G8w*9#wI*jo^>qs(KhvYx(3Iu_^5kev1z8DB>_cndNkW+gV^Zd7 z9AyPAfsW~zF`}`x@#nmvv%vDG_v(K|Gv`(RCQ^a3ydy$7*K*QQbB+8i^WjE%5mNJ5 z!%?{OYVcie3isVZWZ8ycw6*qO#?STtie~tYblauMFkekG;ykB;Rbs;5b}Q{M%jKc6 zYq6)kOR~p_Og6<gGmVkbB}YzX%DKS_&x-H=S2R<)oLLN$*BIBF!o^EfrND2{X>pG) zzPU3*?zz%j0dvW!Tu#%8>OOGyko-=t?U1kyJkPK3Xxi^vu_xS+WU$f6?y6YdDdDC} z!re$YdyPqHxXNp030ru(<<h7aIkIE54^<#)^J<sCZmKYHBoaLMVo`5cYeOUY8$Ftp z@H{N%%Co+(bEF(Hrv5{D6uVW?WchYR?viCrY@4q!Z(895K_ZK3Ii-7?@D8PV@o&nS z6q)l9Dt^^r4zIC>zmziQk^6E~DN?1oQuAi_&H+7|T`k~(P6YI!&+AMivNE=x#*K;g z;g(YbJ@Rafg-lI@z??`BK53=MrQA{ZMWK^h+$v@UUwrl6r6GCGlvg84opt36AL-Fd z3%?_GnPyPWx`I`>b+nhrp*J|5fVif?kaWgP;1Pt^22g}aemmm0s0j{ycYNp`o`D|S z-LV}~Y9N;UJLnanbXR?uIJU9%>_5?rU$X$sa-RB@QEwMS>jnS>?(~b+<{krJU4l1c ze(|o0mHtFS%C!qox|b+u8h2L{U_j1ln5e%}tWgRu2w@t^-@tuH+YQ5qjzrpPOOa%c zis;eIg_J^#Lq=`7X&s!T1g;9F+fV7UYJ`G#9$>+OG#rdULl1q*3xIe^hzzFmpN)$E zAXq{}SW~(=LJ7(0C1o7X$p&A4VX{!3<p#S|CKXsya$u+dX3oc0oDQ)&P`_jlV%!x_ z4J;x4gXz+v<w7=6tRu}UXN$?7Rn!jQKzba?fY8kfU=rf;7D)``vj7j;3;>tG074gY zC_uE@#zFBu2^@167RkXy*kydNgl`;71z#@s@3`f$siIb#&y%w)JLMtaUCe$uEBB^O z9%ECaM{OKH!mTc*N?eVj2`U^#cPs~$OL?ul>~f3Sn!VH*C`G!_hl!qh@n?o{$#Nxb z7_YtVYtdAIv4qCRMI-_;7&KT8V3a9j1fJkeiKgAShkxl?urDvh3r*1=@;q^HQvgU_ z4}ptG`EXP4AU?8QiNm5E+6SG85m-|2L=S4PG`8I>=7dXHNt>6U6XPP|5K!KymIhjv z6aY+#`g3V(gXl}Z=v1Zl`=|KZ=2J<3j;i#=p4vv4zk9+MR%PZ{jf?y>R{en0m2Iv_ zX>(7@3OA^iwg=)RP&DM)7`dr?CPF(D)|kx|p-QPf!2=w^rb-V}lE{FfkfEYDVUz>0 z`^+3UP0i8`9zaVvJBdri9NlOr0f2(YW0J~=8!sT0jDs@+wmjWeOL!m>GE4FkcHPZS z*1*z?!c1{K+(5~l0O9K_^P{IihD{~U1N_zfoD&wqF|T)b1N~$_ewr?50W;SHULA2> zWxUrmqFQ&Q@|l(*BSi@8G@!LAe0Re^qM+dqL?&Df0aO?W>RQ0Gr+y>C+s+7%Xu!0` z^^jINOJD;4Kuuy{O5`q-Cy^1I2@n<9M9#zlfW$ZeQE^!D7fz!pUVe7pEJ;zQ;x;t# z?K%tUc4W^;WWQ8_9_6j8x-A_CPi<f!a-}r%L85~ysItZ(Pup-R1)LdfB`drsHUk%0 z6w~W(yNi5qA5=PTl66UERY+EI$offL-jxVSP&$ZzK#nA##%8J?+WpKGN|a#aHC6Om z);sUquVDNxBkZXBlndY1%>j>03btc_uOb*Z3($$T0UCD)CC=02j21Zx!M{wI)C|{y ztHn~s$!{JU(}Iju*hYjs{LP<Kj&51YCJL<h2%1cGHM!wM1V7S)DSfMhq|^Zn8?eJR z7zGwvq#+t;DRSvpnC)U0tAN1lCTa=h=d;7VaUxK0Pp|`>`AE<^^nPWfRlrcX0Y8M7 z_Ip$ELf~1$dB(Eq9MQ?BhtEX>miLm?7_*bjN4r?;@gAi?!~~3K8H=ZezTnPyl0wW9 zdo3oMI;J)kp18uli&twpBj0GydoSQ#T}!XzwR?X!P1!qa`n{gmuy``{uDk<?N_mQ= z+4o#96{p{MpEA%gp|!Hea*83}r@e%;xH9;UYx+wa^j(x_6wnL+ympEyUsU-y-cCbR zrw8|va_iXt37(=#Ssz!YB=HOTg4LW_k4qna<dIegn|bGk2qi9fZv)y21r3?@#K1Fg zRbXiuy}Pmi4H4WX{ZARrrqC{q{T?Anc88dPbFKFuVd|Bi%RV8imd^UHT#9`Xcs%U< zN@f;FS!ckeKYZM?vw7UPd4V;&>E1lg=0cI`d1wb(rqDj0(1R{;P3{&JM&fA<?12xG z{rZ-;?b~*ihQgWr@F3RAfBrPqrUY1A|NC>?dst&|AL+j*GFBmZr#;H+`_5^)_k+*8 zr;_M@NGjlX`{s&nRw<jiDwoUPCg`L3rsu5oWMNiMtk&%MUqp)R*@MtLr33b$340>+ zg#D8edX8{sp%sCw3cm2}4y7`f@_{9U#v%lEivxfXB6BU-=pqglH*VubxgEC%3&Z{s zv<JE78k^|lQ%++Z`tgs*ir(}k%$s1MR$GE>Hjyz7S-Xdrt-MopFZe=8;`u}3CKlGS z$Wq?K5`%^L;9;?N<~RaV^>gOSWav#InBNGLy{M9w1Z$(f@i-P2pGeVMXdyO1g%nvx zm4tRDggT@MxJl;%zzP|Ii%fhH5pKFkG;;{|NV&FP0#)MC4<W(|$4N1#MCLg3-8dZc z%RQ(ynx!QfWbf*jv;j-rW0KW?0}=@@T@jI3SY||Ib)oLFD&0CMrRjH)t5}6_hqM+` zwzf%R4>??yBhF~>j)#4q?xjRmNm9f({1rN>a6B$!CN72stL9>gq?y_SOwxFW2QA5y z3{5tGdiuZy(M(q<$!n4cLPyEfCyE=csGq@UUr#cb+++c&+`08I3XHzzoa8#7eDhwk zhdLt86@lzc&u}0M7D8k8=#nuL9kX=;026#@1_65$536H`b?nJ|V3^(#VKzKk4cHjr zc3n|N`apEVI5bP9J%>36)d$4N4BRo=OhG&3ZqZosPBmbV_FU~D<`_KllR;*C0wm0p z*^>wkM@Qr@GTS*Ydqy&45tuxP%qe^6`HL(`;h9c9Q%A5``8ee5!JHfIIfpi=t#SBV z%AL<Y!u}}?pO45LXUfpgyjMbwPmhFL-XoRJl3t#P$R#kP5D`ISSSNw$4jJN4Vh$UR z=A9|@a!>ee0^eQKY1Swx7)r=wm;8c*>lnmI+Xu2qCCc2pv$=<O60S2gm<ygIg^-~o z7%1S%Jk~}^aF4YgWO;^$4FQFoc*r;j_A4b){H|_~y3z&@)AYEir)|-_*^&wMvr9D8 zw0GhZbFPwfT;B;x2(dV%s94((Qn&|$pH8QzV4bAe=yEi3HI5~p2#cgS)QsacPLdZy zi}ED`-V{A7s8oUmqpnGk{LG5`Ht%?SfJfk&7m6r_Xo$-=ObN@BfG3C1d+Z7<W&FWS z3QH7Lql5^%f`1T0VCu)^97!v^f(GnXJ(P)#;tS0+Wh$Q9N>kKK&%@@!weEE*!|ZXO zU{`pi25g&=-t5bI2+WlL@&z8|NlOpG5)k$!q#v>)w)(P8k1w}k<}s)d8nJJN_*aTl zDowgVfv8s(7t$bwRIoAzmO_Aqpp!yy%(d9cJoH_PD=dfrzdTq<(~PN|Nlh{?F};_Q z=lwW&`)2zAa-Hb*`V>o2l`i+OPwywgw9LpagP#_d=R470ZWxd$k-3TpFBpg4GQZYC zgvU^oqlk#kc-XyE`kUnu*%&?)g_4f0YTLHD1_G`s%N6yYoafRE2h*k;12>6qt#;QC zJgoLE^pXSY(`=jz5o&=0U0Y1A0;+wmh#IQ$LMptHz;g2piyJNdJa0*(xz-D6=8D1j z_Fr|Mr{p&6P=yVMS|GPuBlqE%+@3u|2p)3jB;AJwHU+?zM5r5@2^z)ZLW3CM!1grQ zBXi~g9CHZv+LPhhY6AQf{aa=@y+P)gXF?9Bt7I>_@p3qZ{veT2xc)$<^z|Og1q0Fu zjx>E5RlkdU@|MKxM1j0Xh1x9M4?{zl=He_d5H}n+jQVs|raFuOThKxjEY?<1;59h- znlCvFmny=dl!8ObxHn2^w>-<$JSdhJ(WLLHK=fdm5~XT3$6IRmQ13awVSDLr1nPw} zs?A=y!F-$w74i=j6h^BlAXd+6!G07syr#fwam-mhWSg1%tNi*lN>O0bmSQ?8po|^| z>Bi&~9RoG5X)M~8I-aB=r8rQ9M0$l`_E~JY{iVhU4{<}k@W8@ksgOHpu+R`B)wy9% z3s&->cEOjm+7&T4mwPb#oT>reS>!osZ=brY029gb`qFqa7&8)u+NU8aPDhkyTv1?l z)F&L=;&v;O_6xUhY6Q?(MT0n#K@mi#ExO_Oer<Oev?QWBgg%!wlDIgVdtobCJhj9< z_}TjxwBz`f^1o?5FG|)i{NV1)1;BS2&ulRQ3qwPizP$3;d*wodMWEYUC=e4&w=?kU zQ7Ur;0MyU}458sQ1`>1y;yjWYiB~&(8YA3X*Hk5OV}xe-M<P-~>f!xf^B4lB%K2pi z>Lrm9!4GZxQiIfnDG78VUqIqsK*EUN2z0+Q4HAK4rtl>V&cO@F)%@BB7YrnLHr-iP zMZ`iY#g$NYzul;Fz<;tmm)L7AFlgTSQcyX<)}ha5@zwcL=hse{*Rq&?7d#|by#Fz- zvtAYwHV&_X)2eXL*EE<Z?#au>^een>x_|z;?u@e9sf+nI9Pmgp;eghtGXfJq-DyPT z1AvXjlMC~M$M^eWI_X#Q`o)?42t53NzuLnEayk#sYV(Ssdg-Q-1ZU!W=u>{fsdN4% z!p(@rDq5Yun;#Q$viu{>F>f}x&u<zdlUqkx{rX<l^m&wkG_n2NH4q$jsDBjFAPqr& z87%;Ss&P0Y5)e*@4sDZMekZG$!q+Is%wUOSoe2XG)b8HEB`rC=mlIqSm}lL%jz4`D zZucp<y#A{FI)XTP1r6@^9|h3;9+se4-~LCZe6TXDo(LMuV~%8JT81}IAVgSNT22@S zoMk!~m`!`r*!lA8xr7)ZOvt~_p>y!7^V@ItC&g<Z-8w@GcVM;zSlHg%M=}k-9!mjj zR5Jrww?(oxf4Ja+S#+5SE<Lk^e`97fQgn!1z|?yNV|Wo-)KswO9hlqRh_mHud)?PR zv`2&AzjxSuVoR*1$e`)Pc)tB93$*t9Y;wMA1VynoL~zbi?~UopsWw}Q1)9!2M*7(u z`Ued;M>QUyb+K~3@DO;RGzvM2dEapdCW`|($c-u>-r1k)=15}(@Uu>T(zVXrv;6RU z`f&EL%-obNx4hqnC#4ckk>`3`J4Q~&7fMZ#(ubNp%CLCkTiChRN3yRE?oT?C8KoCK zxgh}3%eP_U%~1q+k9PNH1~j9s@D0Ddn92gEZ0e0j{kdnFnhpzyO!k8g<c#h}%c#tv zE+WXnclEKO=roIgMPFMjMB?h(gLD1TR-h|Xh?M+CX`z0nn1)9k4Su6<-?sJJZsr2G zc5%KOlq8Y<zzhEBCQ@isTJH_n^-W_8YTmV@R5N|!ecC1s7KKkW=YuGJe04km)<n0R z%Xm+3hAQOA$HZmErB5C^Pvp*z^QTo`A-@|PdzwXx39w4|609})bLIT2Mg0dG;z5ft z&T}#UBJKK7CCqU@OiK&SRa%_RH!=Nw_2S&eewVkw;*8Ql>tC%t%U=6P;j=F!OnYdp zBw0KOAq=1X2+h5DlPPwisb-@(mi_9b52mHPTOZ+UZHP{dxcJC|JVLeJ{a0?}wQtXs z#WI&4Q(w5rulLK_XIl5y--iFnU>^O`;X`d|O-lmsk9vOOJHM;zlo|Z^p!dOxXU~Mb za!hQ8|EqKJQPd6|@!`iK@5-#l%s?#--r@4vl)PpOEPKd(JT6)8?tCGQ0-OP$Pkyv} zfm)COj{?3q2<!&Lw%#9xJ=sZ}{gdhuqPszU!#J_ar!ctuX`i)gqfTgq?+&U9PDwhc z(p5$XNj<m4fix+Q-TQ;s({nq{_#M#OZ>m{`nJ*zunCd!o^(E6M5q``OBVCtBy6*#b zLnK-AxkUy3J=#Vbi$5C>`nJ#Nj}d;T*~5t1rLnxk6*K-S*aCq3@mfn9$OSWVQTDS; z=3!RNA#ir@-rp}={A2T)2sixEgEvn<$e}j}Q>|_gybq4xIhw09$#<<K+b$z~V<%Tm zPna2W9Zz*G6(c`*mnJzxyMD;($0FQHzgJ-(Hdg(+R(m(D?R@?BTadz!%=4q;a<j<Q zt?1LfjP=gQy*a)f$(O&7pJ>R@cc?EI)SRpFtm}l7JBq&KiuM`h>t~$B_?3Km(wx4K z`Wp3lx99>#wDK=y#nW`K(GaA7{M}Bc|3>=ZtAJmpnTJxJ)^3!1wB2JF8-z_<J2E`& zxI%=9&as$Xd^p&y3b0w1v=NrtN}cU9=VYzAB^cN*559Y5KURFxy~^y8vhU1v>0wJP zg%-CAlo<XWd3);zx_AD9`7UqbAFiegAtM59)ymg~GdKq7W~iZ?>5t1h5Pt8UZBOd@ zU3r{ZsuM-IT$GT=!YASUwew|@r^VBD*-yjy7C*$Uy#hY1w;ircVJ(w>QkHrKY)iH7 z{!Dy&LyntxE&ts0{`9EXva4(9slO#qOG?Q^Ewec>%h@5T(EjnD1LJoRbET(Dv){Su zUDPWL@0>z~TuunfegEO@OT6>|NWK#C$1cA{;7;VttI6_Lzdy5UzfoEa;Z?fU8|fzf z?0aTjTg3ik*b4}7{pZm>W9Dro-lgusZm~ei24G^*gLhcT0IdgTiAt6PzR|4YwbGiX z;C7SuH!iXli&{bG;^z%nwNx00#kqO2hUH$<KcU39yaYvKUhj$qWByycHsb5W{L)V! z^W~vbzO>EDmwuyKq_E4A<6yk_NZurN=|6=%B$+k>%ZR|@eT%xbPq}^yo$D-zD0$!{ z{>-&sE8vWN?hwlc*=;QPG5Fh#=RI5}ef%w4tOoy_MWH4sQ+X2zI^{6K>6CZp%1u#o z?dN_bm*fQZs$8;CUu(W}@s7KENx%a?0wt)MH%Inc^CNRX_pf{Ig?{70>l_{ck9d}5 zc)mVdzKxJ&fgQ@bb>98uM-do6L?Sq>XG%bd1B*JAX;*i8mAkIWNLQ8ys|fdY>%n$= zd#nKb<(%26$4DDMK4wkdQ|xhb-^Fiz>eui5ShLqCw^kZ9c`_K}D-b**oK!7RI~n-G ztv4RV=QFOi&Ti}E*q5fWLlR}-qwhpW`LXjW=e*KgBW@2B=dHK1J?u?}P6OmB!^i## z&JqQlG7ZK&`YJYFAMNv=t|7G?+yiW;@(NZrgJ9ww#kV@PTK|i;*ZLB3o0DhIe8|z8 zx7toMxafNG_zkWwv4XaI3%dq`JdI^^5<=<~cKMv^#_xlXpNra0^L`r2zq7FTiuXhn zu-yLs8gL7=Ow*Fk-di6vUP{b#iWiFbq=*OMa&lGJt}Z<G=4bm9r0P2$R(m}~H+<Hc zRc5NrOv$&@E7oj)r@lt(c4p`f-aCMP7YO5(Gh~DCYL8-ASfrN+m0k(hk?KcYZLj=& zr45ip_WOQ^a2x>c4_3%p=U)5Y^Mvjv9O|8$THVYwyl!vvZ+_q|@~6GzfJTLZHY4{q z5jMs5!O*CB)6_)k3lH=ewL3}61;X2lOX*cIP1mWoamx7&fDHU0!<1r#Syc!l&gO1s zer<YM2D9-Fw@}rA(K63uJ<xN`1gH*$0U6?OeJ!vBVOybxI^}ozcl>!(=oTyRQ}n8z z7F%;9b9t(bwh7rK1t%Xqk#;?O!iKCb6Caf<P`;ehjSWh<>VS^oF@&n@u)*;p#zevw zeIa?_mpVr>Ng@V4R}(!SV)u<44>gmxoxaPR_Yt-Z^0gF%8y4kK-=2v(DH^v6Ne<Oz zyIPhea$2Y%@<`W;r<7vM-8aFHZJErkPxQ17?^T6z_r|R`Ko!#Un9ork$!xXt_Np); zZ8Q>io>4`meB6?CPT~-@QfZv4-AP$}DYp_&IWGw_SEhddNX6!G;BNqU7=VGYhOyu9 zy5Uyz<K_)?LZp*&rZK-!(%0NF=gU$PM&`2Y<~+~G4Yf}=i_i5>QeZ|t`lW~E*(y>3 zYgHz)#OH#$7=r+wJRbRUGlX_(H%FMCmk<?~eEtoVDcI-Y_vRn^-QpvU`<z(MYV6DP zD<-qvVkEkc6Pa~(9w`BXjtcQw^ahj9c`LFH^9e^9pXfrmM#l4Px?Y$g1%_U+nwV6P ztc!&kaMY7v@7cBN8Vinz^x-oQ%$6MKD(aLMX*@gG07u>+M@<l5u>0Nv8TsNYVtI_b z@x(;UqkzW=c^55mk9B_*4kf3>%$|y#+vhnyTE-4_+9;iFXYoDKLj`Ljus`v=g5B&w zhT?m8t{o1|Cf41p(wm}GSMljfl?&Wc@(T=mF&}&EbNK?_V8V6~k9F^JF6V}-{i!Y+ zdOa)*a)u}wZzi$j#8re##c|k1!v3uGy-1FE+PEE(l2vx2QayCl12R>3IK8B_HA+wC zK(Zo!32}RHn`eqbAM_-?j^;_=H{F<<d~9m-_scd#MI<YbbZpd_L`W1*FDL45w5(SR zC<hLw#&(Jd-n2~7`a^5EJL^{dhB~15slT&vHLl2(YQP;%fGD(YSdi{)S!5Ymou}MD zy?u0(r`z>i?hY1F0^q#%Pmj_?Y?olJ)Ohv>*yO(*OUzajMxM>R>wnMdu{vHYo^0_o zulHIJSd`jKeBbG%_S-o9#!j&&A<84FDu;icrypBfrsgJLz!|wvCG{!U@<MMJB9;o` zE}<mQZZOM>|CW!;f9&w{51e_u4<s}Rz#4!uxLaE{nE?z~3&e9oIwdQN;*vh#-Ks+g z$3prauB$pMF<&GkkPH*whK_l0q!dH#QzX*WEms6Oe<ojYnDz2fpPyBpwK0QEW<D+y z6?zFgQtRH&JinAvUgr8hnH-mSqob$rJ0V&A56#Ad)LaycHDG<SH>$wkXOZM09m%43 zRzfZfYFgFJo~}VUJ%8lJ9BHc0hZ9UHVJB4<4b3X4t$^uh8|pSC{_+9^YzM+2F9Sp_ zMt{G*=H1Qi_{&n7W=8LSB5FQjd@RC`{EI)7%r=FRZL20SuO@c!9Ai^7I`$=RphfvU z0P5#6g;Vi0B7D8L2E|f06Aw~+$5^5j>!-a@+4l~Ql@i@D-3B2N6-4M2Ad;(&kaV8r zw!4-G0#>Ps;x1*_3)hl8r`yx7c6Kq}9`6-emQUbXb%iS9^?kQo{bZ!#peod3UTYTD zXqnW9@$6IlzHD~EZA`6dusfUc0s&?B+}SsLIMiy`P$53$f*%HZCo1*Q-3{HjhDcB# z^=@F*{Aoh@U^;)Nf+AEfuZ+cm)Dum7K9e7R)gu)`JFXxmO8GD>y5V}}Zbw2i6U%-F zz3yg5T*5rGTfbv}QX=pP_d{H4iJAH&f&Dw}y6lUx>9kfxq!%v2engKWS_5QO1<{X8 zV9d*~rht6ODgGzP*|@t!950#ja0@wV@kNQAg&=ngSjb*-ASuOW6CB-^>_<tlCM5e{ zCDz&KgCJ1vLD|e<kkgE8BnL#00{Q~4Ii8W%?_j-`D%?pE;&Wvb0phnoZCbPhtV4YJ zVcFNiS6UA7GOkJH8j>S3Nh*ca?I5B!X98OpqYO<$=A>Si*qGJCs7`8hd6yuIk3Z$5 zFz^x>6-Om=K?w%D5TGh0nhcGqf)e)9pTkp_IeYbVs^Z8fzj-cS2i*`%N;t72rZAbU z0;a6NOkhdEYb4`MA)F;z-g_V$OtLkduiMj>+ypC0fxdJks1ypfwYB~kR5YKD?;eT! z$DNUHJYHs;5!1%leyLlW36%8Zl?obkj>xD%1D}_Aea*GH<Jk*cVnTUQH8%ai@0*NR zDg%FHyzrv&S(1$EO#ftj!dnrn!EEA944>Iaf)h36HZCRlB-s~x7nXq2ZyvZ^A{e*G z7JyEXnMn%a$q!ykwxJnvBqm$88F~|vqX@~4Ov!jcva3dy4+$ELPCB*5c3Gk!*l`AZ zT(dkiLB1_VW{>N3NS}gmi2#~+r^qNfN=E{xeU20_1H_Bt62A5%6kF<-fK|V)Bx=zT zuaO|Q|BI)4e`orS`vCsg#+dVA80Ij?InVhlGv^$p91Af*NX{W?2WHMfLXlI*A%~Dk zWloKdb1G?s5T#OI9o@UH>%Q)PU_ZRC&$Yex`aEBcCn8<#5TuR2?o|viL8J?2Jyj;^ zVDOYX-DH-I-aKK8m<Aa(^~W2R#F=Gb0b=kHhmSopfsvWQ$#H=-n2UdYKerO6ml-+$ z(Mf_v(=rL1Bgg6(PU(!-CmBJ}cZ13@oaz~2WgMF@8$1Rgg<v%$LXK^Lbs1m{G^Hq5 zbfAoTGWCg13AbSM9T5O50f3eE^~$Zmtl*CGH;c*xiwDo2=mlip1}LFP6#tS(hRnWE zZex`QGnGd@M-koNtM~LJ`#_RJl4O}9CK^(LD|u;|cW(Nz;SvX61SKFU&!IWaqeaM^ z)_rU*_SeO>(VQ`19Ocby;h4<YIdh=eK9p#GSi;B{9u6{MoiQUT)dUY`4~YgF&?Xpq z5S=ZuUKvG=E@by!^Qk?nd9n%#kOv`TWD{6|Mpo>2LVV<~`v~m6?C`neQRtZ70^5UM zCXlfks(?|Oat8_3r+=;+jLvcU9WfIzKdKE-W>e$>%b?C3?5ux+sVt+{J8vdABaUfz z?%Pyxliip2S><bj=X5jUlBkvg>7o1S-`R*sczd8a)5)E6j_d}7jO31~AWrD-n;A!V zqlr5o*$74u0L`}b1(IZHks(h}#T0)yuJUPId)Egf(KPZ52j(_6ozDf!^^tjbDSy8` z39yEc-luyvLHyZ(nb_t#u|3Y$bkwTJXi2j6db@cwrHL?w6IXP$v~#wH0@0aavK80% z#iJ~BKU=GzM;3f51;3VL%7k-7?6d9GbCg(49J(_ClI%k*PyW7{sb>x~@V3up8_|sh zn+UL*(k4tM$vR~eJ;sO$XMG{8{gWUG`*`G8%LuyKqMWA>BTIf+Lg7{fo6$_Qy~!2> zY<fvU$B0kU5>&PO^j*KZuMF$^#i{z{xB)}$Hl2N}gG-Bsrl1uA?O{jRmuua@d0%}` z_-!oZOYv=DGQ$}!L&GxTIw)R+OCt65A5Jimy*=sHi)Zyu0)5sgOE2n-sV+20-KLY+ zEwZL1MbDn1x{s3ib?vFZBN4P&yomekA4A#dC#nJ9fci)Lir|Nj#)=s)E9%J&H=E~b z!G`u=69ias-yPt5<I4MHw&Iw1fQ#B3MBk_~?rKIcKJ$u@LC$4%xdpZpg_-AN(RaTr z(G{1glddK*(~X;`p)?Kxh7y=ZJ$5701w9vpUmUca(>=df#!L07whxJhN=-xZyC6XI z$)x9GV-};u{<7Bm)Tgf}9|XL97WeuT(n_{)>>{te9KzPD40NQC^zst~3;<+{t&!W^ zMwoPca|BqD*5#T95@iRZ!rY>6`nMp-N=e}OFZy&R_F&H5(np1?QwyPSToA}K{MbKu z_T7)ktnV9?N4cyVB3kRO?ldnub$8Z@ji{GkuXo;4w=%QhEEF)JfR(6j6Q0%-aE9dT zTK!W2Szsk%fvNW?RQ+3Q#_Rcsk&Em-iu)r;w@rZoieec_Rsf=h2Y<>rW)3_k4)Yg1 z50(rdNwWHyiJ*Jzb^v2VX&)rIPg;%a*C&#TJIGWKiR?TvVCgh4P)ov}(T;tm(y(^D zTKK$CW~4XWsgKI2%na-B&49nBb-&1DBTo7)9tBkUTpDEH)%}uM=B#l!I!)xogtuqT z<!E7wuLQleti;D_xHA{Xcu3F1?>2HvgMT4J%)a_32=N#moUeOYu>+)9wkp|2lFeTi zy-Y^1KkKX1nR%5CF3kwQJdodX3`A3}NSwLWl;L8e`xU;d+OToT1r{|!O$vh&7@39v zJ|P{h+KHNfx~D?efy~`^<u;3d*dZab8*n%~wpz308^!ff0B0{-_XBOE>IR-4A&qBQ zC^Q&<a!|v}NZ{?Dp}RA=4s5(MiQ+VtjsgQjkW9z8eXrw($6c%4I+DzBMS_WQ0CeVy zOn4Zzzh~)U%-Sg<19IV6_O1<D;=7|zjO(xOvlqA7hJER*g8}tU{WFJ6u``2uT|xq? z3`Non1=vkAAXr(-!UC96v<vx*taW(pOyKJo_+&$mje;dOR<z5XZM6?a`77^i+~?qw zL=is(dDT%62#8t-NivGO<v~^o11r*2Ts$c|=4;LaT5bW9V{ahSHI%H&64wGa3%8(T zU|8weR^O;c+~HI)keRr}RsxI&yDt_ag8n$2{BtuSm=CJ!5rlvOAzN&C-(6;olU7-} zo+Vk27$Cz1IbPV{zZ%l@oXIINKhtW%$EP3QL`HKSL*+bDMEFbefwi|NdU&!7p3J8W zS7f<Q13QHu*INwU9J%!NyivMZ%y{fRz|jCAY6BGtE?JK~sMP9`s17*$LyrdyQ8zAO z!f;uMj150&Pvy<$dQu^!enG!^w*N_OmjpoJ!I1=-B$nx;8<uX&m@B)xtAWqJFhi6I z!BL5?pK;HhLONqT+)*d3s_&Zi=8)lsHYa=s4Ot7*0+6vB&~iQ~Y9d^wP)DX|MJd`% zElgvkGozVs{m$CWS0-7C7FkW_GNY!KPFH@~p~e^p)1b(#vvII!fM^L2--h`T3a5&< zTn{JAOA~xT5WBz4Li7zbSqQC;IW|B1J$|3!gn?A)vpLJR);``<JtUu@ftMG+U2~sb z?Om90az2_<3Jq`y{_>t84gl5$tBIu)g=(<4cN-~B$1%iBa%mmK=zH-%pY;?dhf#tA z1Wl^7ULM}Uy1~wJUQe2aep0VP`@cinkLQfznzlDMmX(=kc@I>PCGyVFbt~$vaK_l< z7o}%?LNOPD_ukQ?JQYGAfBIiA{2~cNr^-Bv9w(dGK1JOQvdhim$jPrz=+Irx<m7d~ zUFj#sW*h55ZebrqC*|5ykuZlKS^QJOLP*V9N~AmGEpkb#yGNN8tdpxMwg55M*ZLQJ z@xI7am7+FbJ6JUcc2-wj#Ww58gM+jJMMaMjD`A<D)zA}&48oFep;6YyC|CrO`f|wS zs3eIJRGs+~`My-dNrB^Bu>NK-VmGV*`^djxCn6ZTpI}k88*raZ(-kT+3sy4vu~Y1D z^zSoF%2{^WPjUHJz(EbV2{JcI@mBzgm&HXrb??s5KYy^NJg~3D_Qvuhq-j?xl-aH! zEa+l#U2wIzxO(Z=IqK7lsL!b%eSZAc<%*6i%ugJEhG8Ct5vgHGb0J2VZ@|1%*Q^dl zga52yDd@Mf-~<oDlL4d4Q#M(HPgV!3GJK4_|4ltvDU#td06sQAvFw0c_>S^81k1$z zOt|(FeHdGD#mtcBvfR=!4ewyiMKT8Aug!{a07UUVGK;e7WG5;wQ7&@5@%sJx$ZIaH zB$}dcpH(z8^V?XAud`4o?W~7iOlDD3pTX}B7j8S<sz@|q)Jf7Kh#Z2uY+(Q_2Eifu z5?X@EiUWu)M2?a&ssZpG(>wJvG-0sYW$;+YS=&E@W)nH-4_(vWn_$>7Ae<U;_4YqA zY`H5aPTkglOL%T!3FEM7z$$2TMBH*P-GK%rK1&w_F@3-R)G@W#^(DO3Spg~M_>!A7 zYf3OF)szx+=a*o9zyug=g>68I(hl(heXqJ5gaDw(V5UZw*HXi(vZUvm(x-?A9qXe- zc@ozmjqZiN>^lGPhsN^%^7d^J|7ouDr~LQ-y!{Yw%a79!j^e6lGw&1kwAUjJXvx|4 zC*OGA`%tS1!DwpejfT|q1d2|GhtGdIVQOl?Jzxg3*FjHSa_VhLo~g|eVkefNbrVf) zmkT#dAT7?gPr{M~vT)Q{*0M9B-Xt#rg-zKlljj1ASKa)5!0uUi<M@A^ZH}S2lG*_E zz^v|BYkts;`I|A2kO^s*^I#&;Wo9NzsRD?0F@9Tub1@3OW`oEOIhBN>iih{1GNn@N z1C7^8g7~y&tP|IQ4&tqH&0bq>EgG%?(=gz3(^;x+jdk5??Iuw4M0n3z(FOIMJAw;l zJ&$`&>s1~uIw&WWVR>Scd}kb`&r}b(*`KofuQ2{dz(K){&(g^nVl|ZkXBTj**M^9k zQ%6y5x|*S=NJj=;`cnKbvq}hOwpt`@wJpdc*%MaFfpD5ZWhqoxH@kb}3h6kTZG=HQ zX{$*UqCi!ek?Nh>6)CFCcbXs81OoB$`NnnCMj!Qm#)F;BZh(P&pBJfdE{4GT`!W4+ z8)3(YR%6{4+7kyxu2(xn929z{rQ>*thnH4)&{M-G20E!skW;+5iEIlGw^H!K@oRSu zmKpnox;>PR`5-9lW(~3v@KT5w5dnMyAyTpRU#KZM-?wLl4FKk-Q^u#7Oab~<3{<KI zU57pq)kK$ZuZT38H1>~CMHvJ3eX7roG#>rYnb3Y7d7Y+uLB0T;JCh=3{xbM0pV8Z! zLHUM2be9^ib~7$7%x$LF0bL7h^8n*IZ(gh47a4;V-II!w=yjUvs}(0FvF5YQsUS<W z1iku(C#M*H@wj=1;7x0Lql@jLvN16>2ms${jc~uI02LwlV%cwf9Gl08XsUc+llm94 zm&+LEy!SxI4OYjqb?d@i2i-48-zE)SHGNV^KSwgr-R*pCVY=7z?)x>LH^V1$vrOwa zU9&deyntF#iSV_?J@{{L_s{V{2?g%$y^#yg)BYx4?v;z=cHh?)=LO0E<!qTuS>b15 zWBYC#GF#2%T90C%^A2+fkL9rO9;p%U`&pHyUN00am8BZ1pkO9=D+$lo48smPb9W39 z2)4?^{t4y3BrqZw?w)fB2#9O<e!gke#N*sAC;j%2dTI)#`lhoZgT>qPxQd8gC>ctA z@<v>{@2U<^IH<mkurqv(<q5;^1FG4tyNVL@Kf3YT8)BZT7r}XC&rTW=zEN~LXqk3^ zrD);++i!JxCOTe0VZZK1{EA5X$7%;>jv27PEF3CZU&EhMOyb2`WsLZ(@`M%+iT|sH zsWJljWATMaKP)rD>Ic;a_mP}9hOtS>l;l#_bH1RaG3VH>;;P8!hIspY+0rd)x7?^2 zYrPd<TNB^JJTvGO<U2yy21$%G3u?a}phjp1Wla!l!^v08?+U6IbZ-j+!=k*$Xk>xO zYMWn0ZtNEL;)<v^J|R(|r_^aJj_)|D^4D9VXiQCRnCzg)em9$<{Ti39k@vt4S%z1C zEx&tV7K&n(sT;2;Uh!?2LrP`LE4@Q_feAg0{4$oI(_O<?`O3>GnJ;{6qU2t4uFvb4 z{J1bU@J4n`pQ&A^LapU}#XWMa;h99p9a5Pet|)R-Fgqeu%Lv%FMuuUz%;rJ73+oic zX1vzbZZ#9$ESljxc`d=RZ}Nu(D^{#Eec&&^cX@yfV2$03n1KTIh+$c%I|KJ=l{a*Y zDStsFmuP#WSj~2g73|f{gZ8|yNqns4|Lt{6XMCOHm#y?*^=vtjjUn|%vIK4aK)$GW zu=Id%hHj!TSMcTYqBZzCS_?WiUIWB?Z9iAcR%Ek-8Dz2RtN<Zq_2lu6f(o1m!=T`l zU>0#sPWFKq5Lc)KG@t^swjt429hx4Gm9W25y;Ja4sA9jB`2Acij)kxGFWU6ed-l`K z`UHo2(D9Nfe>Iba)co(I-tJ#Jv^A~8^3bQal3vnm#2wdpQmj4UIS)p)t-n0hclvT_ zy1A;LVg!0OruW|Rd;i6h1M^VenaHQ444Lr(n2W-CV=3nlzHa|EMxX7bkPkg!pj=>C zbzSyI+TkRO3+ijcrp_vr+fn<sPi?l|;GJx<>7>n+5>uk9D`^~tQ@=}J=G|x5TIeW0 zwaP!}x)@s50qKnVi3pz->#CgQEnbR#rBbET&>CnPS`aK62Aey@1-+$f%^IN+!BPU6 zI4ul46N4}AnJ<w9dVJg;Xw#kSi7yj8nYPC<q+#R(ve14B)a(Go>vqRV#$TJ$YMKtC z{vJX(*K~R`ZBQaI)=#(nh6b{<fO0mX8G!c^M?F}$o0hOQHIwUd&^o5PV=c+rB0J^$ z<C1AOj(h>4P|^@$;f53{GP?12$=aYCH<&5!ug!&>011~>M@O{ya5UATc(}1gL5~W< zkNw&cC58on?@vlm#eM1UfRdrLb%7i;BT!&KUcAQez0Mcd#D{Zv>!%D8RfN0PC6|&! zS_0elGjx~TSN7GkRl_63jD{SF!=Tw~D6Zgbn!^-RE3&V(Clm#<XNWeC9yH1a%ra=J z^6cnrdM3{Mbk9Qfz28%Q^Od2Q&{sEU)o%}veW2B_W-aMG$`de);X$zkgtelPAonqA z8{r#6U(_P81zV0U=RjVz%9;!LQMrn?D;_x)y_WWS?mgZkZ%3HXJR(j%tuuUCHoJ@x z&hvwwGyJy2cBTEgLR%$tVlu@ObEsyc^Bg`g7ERTd7Ze$HB1;@^PnJ5`8F(G3%f@RT z_OhzSl7hBRhg}g3bx(M6+muFvQj%;Y+a@{8cGm><l33WuALvP6sb>SM0K4Abb34?1 z5pCm4nD9zzQs3jBQ&;}^rHyoFHKHZx0Z{FJX0FeMVaiMLq;|H>A>;_HYDZXHAP8rN zoo&~rZ&~Z@2eO(1L*V{NqnashnM-pIrWO=}mWh(cPQiyh*6)lsjISaj%B*)sr1$p7 z1`{Vt8IYy(`3*C;Dd3Do$F-Mj*OcPP7zV|Njr-tQHLQy18;LWu#C>)`Ua%f|SB}*i z7|IgBML0QEY(uqMu^rcZNT>|Qw*jO{D^(<Jewt!lPc{dR27=Zp%E4CZ>oQ7Akh1q1 zWbhl;<guxYtnJ6gtqc7hCbJnoa2wDInEgW6bRX1d!W#zT%=B=hkpe9LHY>8wG8ylb z&NOKi;$rdkwbjXOV&5O*3e2eJ;KA0WS1<P&+SBfC%gnVH{+IPKh4JN>4aWB@u<jCN zaZ*Y<5~u4<*4`b|+{f;oqfeeaoj6<&Uk2MQhgkz4F{5WzdLH*RutK|MApZWc2UezK zIHO#a0y?CJIHNN|j?2JvT*k)+jvKem8l@K{|3&G0z8`de>+3BJ8yBG2hDOUt#S>Cy z?l+?j>@n8P=y<EONwO~INyXZmJ_^sfZjMI99|bK<S7=P&EPRJdttqn8IF@!gzc;8e z0TMYSDKSB+1TFl_S`m#sY2e1<_BpCHJnttsz>P>rWq~4Jv5E&)X6ZQeh`l%b{ivW7 z+c~f-0Im-M8_K@>!pzra@%Dof%Nfw`#yCmeoZ@PEU2AHZgQ#N`5@@AM^uH(Zj&*{( zF*IIBP_a1@VzDc)*UDhY!U7&-2~C{hK9*HCp!XN9UwPVK(ploNbbpd$e6HK$Ff5;* zoqaS`inGwwBXD-iU$zxxY#(Ht<Y>&Gm@uu(@synaoNfTle16C{bqH32ceYRp&c5C_ z@K&w6I^fGF+_@m^jy%P|R@vwXr-d5t!3*{RfaHV~+*vTPDdQfS_tNfY_WDcndaEqJ z4rVTId=uiu`Vu=Jt0?(pyeh9ehef1Hmtm~=n66I>g;l3~jAQ5#HCVoMkkSModr;!H zxIDW`QoBk?zUF7XL^17#7^mA9w+<OIitO|2U)wZXdJ>BJ?qSYwT=~go*3Uere!Rr@ zcvSr>{VgxkhofQs&(Df0b}N)AbYUZz%mVAhsQU6enw9)jur?lNHa`SA3upPaT8JUk zJl%^x7VY+o@ELTMViQ0p-w3ud00BaP<-0OD9DuD!V6%<}A@}M0f3R_7H9fcKI=Kw{ z{9pk^iaAS-S2$8h)l@0AaL*0%E&c*ESC<Pndl5<n>+W)P?L)&4nLQovO+sA5r>unM zso}OZrkZ6K-yxwvoOw4+U%i2nPP4l<q;o*f+O_IgSVkSZv!c?YwAqAGrQ_F+`*?y7 z3qFbPQ%^ehl@91UJXTU+qymDK#FD>}^}PLxlTH)PJh<5ieXclP^-lOK>{Vd^78k4y z3BE&>iF_VfZa?4gz6(AUHeP~hJ98E8fN`pgoB)^gK!M=xcjs^AE#u7laUEgd?&(Do z=C%&L*pKk$*SrtHorI9X+T{-0@~BoXiUX0SvrY+n`jKwV_#`S-ViRo|TN@4PE6nF{ zwDhC!CIO#2D{4<h^QSS+mp?h-d*vf&WGP?X;)C#mzIQ#cWr7c>n3_#>^j1XhrkP1t zF)Nm-K+#BT*0ZMNrk`-Pb~imBOZ)&UZxJSIu!zortUG6y2Lx@Zb9!yDqT{U@H6SH* z(u1!cVE5dv6tDCF&LC;LFoa^pB%9L$aux10ZK}-~v^BHM=;vBJ{Wn$a#~qPAD5)@Z z?VO6^9rwlDTW2>o!}(6aGmveGrSG<1>L~<TtmBN`hxqe`jGEXh!9>f=cRKTQ?6`m2 zzgwc?FWhX{@+^iY$MT{>{H6YYrvA}?u~On-OYx4Di`n+ZkvMZin^`JkylLW&@lo4{ zw7Z#>ZL+`ev%?7HUun8Lc0^l<xl?IGJ+<fHdW3AwSw(dDxyi18bLLabidBl4`;bYP zrcZZvVD6AH9HM;CQ1v5H>TtV$w#i5OTDf()s5|zZzp&_uxyfw1O}7u41S^qlia~lt zat4dpZtIVV3L$F#?$x3ian9M7e`ebVM@B}-9`71pYWlfi6gOVhzc<@wM%)Z3QgC=> zu#pdlnls57{SZTUiqY=brnK>A<DABkTuSS={>}LAdX%YD_#c>98wjcjw0i!=V8<7I z)-*xV1Eft5(W_!r<iN@}71ETJaYp=(8BjOd+xYum^pm@Ieyu$}BZevQXnsmyZE@}8 zy#ssYe(ZINFm!H6n$GbK!7xRO)}d25k=^obe$Vw=_ayr67{^l@Q%A(-T28HRvfS<q zrI8O~t?cl^4?E>>xmCR>(mXe6?|Z1>f5K(Zn$qsV4-J@8Kfoca$_ynO>%;tCcg%u2 z74En5f5<RQ8Zz~E#}5Xy?1awyii2GjnKP>43S}Ty?Zsu{kaU?TI14>pF)|Le0Lm}& zX|qF!&%i_jBpJ#do9MYpYu+#z<Na6Sb_=9KT@aT&IVUp^UAst{If!(3w|aE9(YTeO zsi&iGGFs8K%kXKVz&jnmHzO^<U6<38N_}p1(H40fJ+JsYKj1uS8t);6-`rFc!${tw zruk7Ya8Kj`L_f0CSfNdWqU!JoT=j|kpF#C~XtmGa4A%tdU0B(sM!NUwSF#<LJ}MUZ zQC+2V)iQ@-=ssk+4v~MVAz}B`uw5^;Huw02Pku=m#xFjTw`t$w!THOw<~M@|Jw<n4 z?>O9n0(zt&QT;3D&%Ed#iri#j^9*m=$no|O&R(4CL6_IRSgGL|@y_Fj!)4mlnVft# z1Z~FkTouv?oA0UiLdj1N;jG2u>}?rszE07cr`Y3qj^FF{p9>DDpE!P`Z(P7BRL7~0 zSt7r>kXAF=gM9w7OK0~XRb)<AS0Eamr=di^z0iX|M~|=;1KVSNzNa&%jLn7^KL%Hn z{9HZS4aN$dH%N-@lj7a6y&CJg8l;=Np^68Q^Lt?B)NtP`IE#9mPO2)eIU{{nKlXGG z_P^++b@o3`2InPe+kMUp1>)h#t&GQ-5y3BZO@=PZBEnaw7B64xF)8Z(ID5I}*qr7f zkfm`USb1Lw5!f@HFD<xr{FX-gibDE?Rh+@?NLCNQ%^p#n#+I4-nzN}RiZ2rUGKaRE zq79YrryIUY@k)9;o3S;^#rtHF^7;ar6MQd>;QHI^cia50?>lB4B#G)<f-au!$f3J| z)#}4TgsT)|_irf?&G$+nd*2(zPMtmqBtK%|<&Tf@mY2l^0Ft8mJ$)ar$R9wduLF_M zLV9MX5}DoT&bn-zryT3ka5XBsAsa?9Fm4Y}-hCf%xuM-7rl1TPrT*hcPTlN=?<W`0 z+5k^9@@$%-aNd&Dn<|`sSz}DW&yzB)v#BG-vImlstudjmG!qUhYkK{O(BBH7aD^SK zQ)J{)ul}}rU66mOmz6<)tuc{eIFB=FwK5mTD{7ngMKx~K^38bh@bMEH>KxafpA!E( zRg9Dz^zfZm&N~0trG-~RYk9C3`@wUZ#TTX_Ekc8)^Fta-xMO9M<<ifs&uI+}PNunF zrGw4XAS=ZZG!^^MGC(bctd^wkZ1N|3fN@mrZ6GV62~mdQ8qJnX`ym>7v4z;aChMeD z4znVd30=&L{>X6f>4>-QSJPb07h7H?Epg$<q25&93#r@R@ow<8c{uOVo(Wobb4bm1 z=;uS6xmkyCNh7_zzq%!(vGs)Fu+;@6yRjedDif^5QR&`wwTSI6S0iqyXo5rvzekT> z(wa6^kySBf9Bibh4z~3V*gbB^&~4Mb=$ph|GUZro{inUf*0uSb39gsnC%4l(Dxh#O zGFatMZ%yBwYRdDUDJ|I1>#?KSt1x9f+AnRqhr*S61%Cu$A9`y^6zc2K=|T+B%Ew5^ zBI#=p+0dFc-Agg8rue-uA2@EldF4p#?VL$&D$dMZiPsjok5?~VY8MZ9es-gp=qXq3 zGg-r<Ry=HLp0bHFh}93%?47&Jo_S)N2vN!1ojog!`!SE#9`=^QX6<lCN?xg41u6X@ zA}|X0o);cL3wA#mWV|7tZh4soXb$@P+X#JfXgI&Ab@8#M&T<}k7(1#&5iPKcNi%*< zx~+8mns|Z2n1Fg#`(G*HhY-u9F0U7-^<&lsGfc}0196$WAZxa0ysvT0Udq*-o?L!G z3mL2}R##^nX;C^Y3mVIWRTQ{2S9iKM^2rz-U!VTN+UP+5H!(45uX50LLSbT~#~bdh z+|LjYb}TWu7VgpF)fuwz@Y+#?SNj<{Rm8M3^8a}I(s1`I{?*aE9Zyx8nD0%3k9x0v z?g^R!>~3%@`2>d6P8e}3de3(zKMRp6Hq-JxJCyOEGY~T16Tte-_sgL=c|E?Ec#D-z z{T?tJ`$+XC!9#Jv(c;u#HLQ+Zp#m+V@dd>EY5-{H{|s2WXU!A6u1O+P+{@YOa(py( zwdK%R+T!Bg6QA7YrK!o^KFl<FJ*~QY=|5kOXV+z1cJ5!;oY>y`t$C`EUR6im?J!ix zp;mz@u#Bz%<PF8LWX&6)oPa1q0N`v#LB%eu{e-HdZ%Vq>E-DFy-bl2+GmJ2c9;(l0 zCVt~Jwix6bQm{xpg5(#V3!5gDEYc1s{Ociu+9m+)HLaM?b?@_y#A$~HDS?wgXt{?g z&rdwpc(6PBT#No^yiMQ(1bDv4*lwr{qm?&k5&nTO6+t|gaBy}|U2zvf!faFrL;(@S z0os>HjMX;Ewj^~*Jagi(wTqvqe1`tMuqx?|1NT*8%bGl3F&?8>Ms<&Zp>o(%c$_dG zp!jUjaz;tw1kBD9U7Xb@xiGl9@bV0a*K;ZGO-jjx+V+iZWSnhHrdEo-v2FJNwC*0p zR3Zr4f#>255e-E|?qfr@*oeI5o2wI6p(Zt%rNKL>XR@)m8P8R-$A5-M1+mPiQL&Fr zYxm2;kHB2+$7>ngh7!SpkOJ8Ru#2JR&!r5L+C<~}$|$~BLr1^8uCFM9gXXLCVmB9` z<`i5mZ8+-T9lNKGx3=qbjVapda4WOZt*6KS9O#A)%_dN-2;IE7x}nP;*;^@#Uq<in zf7BOlp)f$zH$(O@Dm)58wsrZd`El2ZF<}y)>MO{{$CUKQzLymByv@_E5eOUWH_tOr z&u+wgrEgSTeDbAX{HlkG@0Str3(M-Ir~gf#jhU)x@T)jqsw=@hb{=ABUb#A_eE~J> z#B0#);k8Y>*~xw@Z3z~7vk>K4sz2Xf1NA(Cxw9@%(LFt=;4)DKIj=<R=3PZ&u<z&B zPafUA)TD5Uq#>Czd}s7VO7z%=?(l}*mtVe&X}$Y1`l0zPYH|FPZOGp(LH2<oYVVwG zEN@(N6=M@Naw=4(j!JiD=<cZI8S^ws31FwfPtQPG4Zy^+>NxWCU$7SPtg4=@Ym_X^ zTWWUSYy%X)ms#zfus@v}JI$R+dTwVi?#3%vSwPkAUgdpMZy}hcg2d$5DObnjU7U7^ zTNkpC)Whb|k@oO{SHjcwc6tVXKJXesCd~fGaYtgtB~5(ac|OGE<+#1@NRX9=`snw* zBPw|4JskUnj}^L}j^b^ljleF&aE5zZ`@flEH`#IH8`8jBHqu*136|S;(I#@Dw~xwx z-<`>d7<P?2u*WM~V|nVeH?Le1_d6^7o+pGYNcRnRAhe`3J7xH8PF^JQ@$jk+=ZOpA zoxs470vWp+R+ATt!^zz3VB1<4wy_+rPH<tsB8d!1?Kln{FwDYgmg9JK_ojYl*3gsl z#W&s_Y#P!ZINxc4Nhg-sZGv(9oEdV6dV5NZiT2$=>rL!E=FOn_4r=|KPbJ@~?IfSf z<vqC;l(DMUWY}hfC!cbbS56lJ_+n_Z4pkG&eK##PFo!B@FzjY|S}Oiz9o3{nxE`I^ z*1YNzCYoRUmJKkxCw{Vgsw5^4>5Aj)YK@D2kBMn6MVrjrata>A7okq|9sT(4>EFD- zTZX2J=2objq(~f<t2|`yuITZ$yl%1H5>DmKeGeWvtdg#rxAU)#biFbwV{J#55tpQA zXIV<Rq^_Og$G`#)OJ~U@EUi4!?j)VBwByOCTh4E-<o-ksN&XF+2()%XJf3%gTRVRU z(mp8;z5E<Q2XL4o(QGRfXVKxNOk<-4%NrpHa_!>sZb0-ie`bxx-CBfjs)C(C?JEDV zfgxG)AZ(RO?5+cuspF_BeP>}PV`EFr2I1qq?Q;F$XXC8|-e0p(+48JBrp=jjd)?5a zz;3VMGuu|m<rgw^5b=OUfZS<I)*F}ZHAEP;Q*!D$;cU&pgM6HP*Ab7Hpq7d0354Xi z6Pd>VS%FSVd7GcIr{Ay45K_$;CLJ~0fVFeY;X+gb7D*7ir}$KHCB(Q}EkA0w4$pkc zt?wU5_2L}WJ%UtI{>?vi+d*~D7~Kvy0V2kg1tAahzhHeN^JD*9M_(+l{~is4AFp<f zlv>VG6zyN+;JDqFw9KyD9jJC8DJc5wX*>N>TyszI$|lbz#(9|_LycdQPsLc+n`aAJ ziy1;B64CQldNWoef4AS82%w;k#odGS(52@r<0?^7=iq19BRYd)i>e}}EO^9(-J00! zy-p}p{K2*jywy=sr`pw;4N6=#Wti?<<+;=inG`Aib|a=T!tkh(zms^Dc6n-shhX&4 z=VkRM`j6}};OB1B&5vjFcq+TYhOdhshT(L!V)Bzwi;gAvXOlGZwwF9#C?i_IEjl)s z2X7U48$+%&7sqo(DAbpCl=hg_Coc``RJ{8ut$ttTYl-%=I`QjqF-kPj)PU2b&NHL< zBa@+AUD=d4dsAC$8r|lm|25Kz0f({w(1LPZhmh|gxTQJrhS(Sun#75Vm*%-p%edh` z>1)@zhbo9%vU~UM$Ill*T+t7fo*_S%z4Bkd7KCsTw49xkDL|8Q)K7<3Gye+EfULOh zGDPAF;@ha#$Gz)!ArAzsg(62ZeD%UWXrtJCqzDhuVtVh0esfDldgJex{GK7{eI2{i z5YBiyzjS85sL9L~hFF*Yg)e;zCqcWKXY8zIxkxSyE{oxb0@(^hR@;TOY-y&Vhh&j2 zYdr0{^9k<Yg7Qx`u_<JzXZ5myDScRoSqNRS%M{K`I`36HPxDmkkobV-(EN3kfA9Ov z{mF~}4%44}X>2<8rF|<M37|N%4_CP;09zoq4iUoCLc|G;=#giv&6CppOkp6}05cyC z$V$(yKk#@=YklLUVAgR*QQS35Y+}nWy`^m>N@;iiRuRgF&aR!X-vkF9^3@)Gt<hVl zk*puZJ=ywc)BzE0)c>Q(W`k$@+%7q_Dq)QkKJv%%8LWyJVEJa5B6@*vjKizV8f`~q zgh}AiU6Q0~0dGDkPG?mD0K|$&ZuRHbu0_Kf*wmh2BbrDpDS@g*3hvT8?q+D?Stgfn zu*WoKt5IMnu>dXCabdSkq8lYsS}Tp2Za3TKT`dgWlKaI64q2!3>0yPTtNc(p{4T(! z2Ld?h>^7*-TDp$ji(@N+$4p3khig)Qm{yS_#M-LVs1t-g^Q`|JRg+N_cPFHGL2i9* z3tOv=jy;-|e!hvxWl?Jo;9^`~m@;07oQl2_4U%*T@)}m=OYRiAtXNuxL8z=<cpWIU zh7u0P@*4&U=wbPQPEjVSsI5czNN*LhR4rgbTKYwh04#-Q8gfh!5V<Nv<++sp1$jJO zts5%|UQKTj@bpIUx_qMZsT&s!z{rsL06w13?IQ*rd`~%~2vo@RjQ8>vSwWplf#(*l zl|`W-z7^oN`#%3aChtE>=yf+f&KgmFl0e_8mNiM-H?j!dsMX;j8k>J%kZz&lcKM({ zcu&pwVNFfxD#4cTf;Wn%c|b^qb7Ki=yb=KO4YubhBm_rsWxlYeP-*|MBiY+lA*7>v zd)ADnJ#m*J`X*4|*EGCVTW+M9-E~9cU$rQ-MzntBmu<~jcZ?+aZ7oh4xC=MZVqN8w zPV7V8Qoc3oU>hF0&e9_ztf2ufg}64L9w?Go^ogs3FI;FP#7!j#Dqd70(}AUmGG6{T zugc=>pON3Fk|hXqF((l43lC!w`G%QX08{+PQh1bQ_!kPS5TzH3v>H}<tc9d=o#Byz z?Vqy4fqb=7byBJ%_^?2)oR!0LfY_D`=Hw@Z5?L5go@XD}++m_OCOws+FU@1c0_-Is zH#GHi%|=c-A;xmLbVP}CF=7q>29XPjf`u@RH!LOeYeYTc^f#)7{ZV?hvG_8OA&4n) zB2f0~zGRr-!~M?(K*Uk?N95+Xl%2}}{GJe47`=PfAUhcLYk-nOer_eW@-<(SMG*FJ zPzN&ok9aPadBodvT3xnMQgfz@1(&FSEMe+8u)CH#>j3aCz@m5tu1Dfh1tCmG0wHk{ zwIH58ZR9&ZtV7e^(RHhzfEo`J2iF+gQWrHM^9S6<&4ejffQ8clKF>k!y-#Jq`3n=% zD)$>7d~GZA)^ph?$&}7W9ITNdplmOL0H;-cClsv7lBY-(7Ow~UQEfLO%MTh58?NSO z?buic3et}|Y=Zz3`c^zi<&$cvFHEktR)1<$+?G_@&`~-Sg=X8`nBFoV%Im+PiIB+3 z+24*5K>%<feE0lfAE{8(-Q}`}O~LMsST0o8R}mr|Ug*K|58!hVRvr%Ek9X%eQm8SX z1bm#aJWK$=N#`jeEfu=MOXw%wp`_zUqKm6i6WZSG5srHilH(+J+6DL}6wfZr1RXC! zcXt|_r%cOwUU|{ym@U;;!{FN4T&7E{*GSH)M=b7oNqO3!8ij{ekzd{QRsmqx5?{<D z-1^1~FnLM>ERKNFe@oPkm~I#G#bqQue51I_ap|bQCyRlKx4XT1)>J{3Mh<jD6U4#x zZt|xFE_PvbYA_UvwL7@V&qoS<A1<H5VP*|SRaq~-4ph|N5A0m@Qp}s0SVgAR@QdcU zwtEDH1_W;h2n#H@Ue|}Uits@}2!FcR7TuB@D3G2j)r*ym1O*<og-87LtQjVYKCao7 zjpy>KPbp&KnF-_DujWr<hJ^-u95Qhp&hlT`*Wo)3(;%_6K&i;{vt0)9Lnr-2nl7+z zUy5Wk4iO93cS5HJex%y<NH4K{A<6+H`MO5Z6a;kDNCr$!K(pe%w*)>Q)DX^z^95>; zXvpmo`H|W1{t^!=4xPYe=evI9EO&AzJ(?@K`qSE>!rUcAa+1ycRN>f3NA<=*ti*tU z-p>Pm&T9!A-(9!GfFdAhNR+R10Zt^rE3ncBCqFP+rK9N9KkbtQv(@>mB#p3x4R~^- z3a=6ATwV_UCb0RB$wgMkcOmEZxo;L;6rZAd_GQH$eWm-l$}5e%O!YBBi8;>3HY4j% zqQgWx`88J#eU9D#(u#pJ-NiH#C`i!?|9b%b%Tjs^0QQ|Fq0i2-jmiB>j2KxvI|btZ z*MqQiS-=FE_>AypG5Mp|6w<7Cq!0!MqYG$o`=S7eu%vH!KV$Xq=T^Lh_X%V@2_EL9 z>Uj~bU+M}IN&D<|<-(zo#CP__ntuc(nI`~jME=*3zTA^lB-3L-4$ND&Nb2c!$I$sv z4fYMWJh^ldWV+sy(frHy(hllmV3=I@dksz9{J`>k=?&GrGWda*kJzqjT>xIYmzw<G z`rdy8MKIsL1O6XOjs~oBA69Y)E49Y#KC1e9VD|m0GP{jxjnVmSfj;+=8<D+Rqx^HS z%7sCZ6Je#+KJsB1nvgE(LQusp3KC>om8@;OTPr~bymAB}x<vRw0uuKAyLIU>6Sk0s ziwn9gf*=qD8t4xyewM#`<<c3hZl8`s&ZjTWAbdB_m5F@NRj!*cd}NBPFPrn@R<XN3 zk$N2{{DaRGwapdys=$<er%3O|rE=fIeeU(#S|t{Meie9$rOA`=N8Ppw-4anQQk&0J zJdy&B=iU)9DjlFpsGoxS-8S+#kAPy^{t*qP2YS)-%{jF~hv-R8uGBJ}!coHrLQ30N ziAVijHD9|k+w_|Zf84rUUhp}Ec63r0QDg}tVtKl|WNwyAO+{vunLNcu)+m5O`cdk9 z;A8!PMR!t`1-v#(NL)x;ZlY|8$jJq^R>Z07R`zYlvK&)(6*<qcHjmRUx5TY)%DJkX zNZh-4UCSUX!W&O{SfHDj_#e^r<Tw5fdU*|W(pQ5ZxR%#=Xc3zTw|^+M4+VC%2>-67 zgs*bd)5XGzK-x`w4Uz^^tM$m*AkSE-sL-CtH}BTvgQu{1q?+KY<OFt!#Ehj|pA92P zCQw>=*+sfQ)dR`gU!U=i5DZ3hSwK=ju2pI9%@(;<u~sT|RUoxSOwQN9Vi2KZUv~*B zUIiQ$=Jb*Ye2G7LTIEHLZ2KJftiq%Ck`y=keQx#?+vwjdLe>Yuixy7R4G0Ciybd}Q zl$?|X6RAnods;W0)j~psXP_P$NSByN=ckIbgCC$?St=(!euI((s>Ok7L^evi2*vNR z3Xfie$FIT}M4_Zr0qQ*yO=Nj#jpzyyuHC@LNB?9*s^_a|r)nZ6YNQp`oKOFGVHcSX znd%WS=yekHF%;!Xd{`ZLvHB=E^KT#ZG_m?8Msy93s;^;OYLeU^l89E38yIrHxV0F# zsp4DnK|sj(Dl+!I_?D_TD~QR0>~^tYuYZbFZHs*cL{wLWEdoX2NkSGV0i!^%Qq-U! zL12n0-gO;)WRb@YCcQEQKLFDu_xtk|8zmX1<?2DxkIkn);40%joNw3nDQ33+EW3XG zQs(FXZncX51ZKkT1A%^787Nl5bE`6QS3I?r&Yl%y`&WatC)ThgPMuKsni2b&B$3TJ z$JO#(tdv69+5$@E)T$5_B%TBkM}v5i0^er_zE7?ZDZ+|rl7#+!6yLJsGn=c4X5-hB z6V+)Dsv`Nzp6b7CCEdIFCi%%^bL{)7Vbq%&Wf~}$cVMD!>GcHPZGD5p;%au$T>`0w zze85WDNvvrYx;zQ{OKnb%M^c2kFF-9UiOsBrAtU`NE$VS=hRfb1xcYTJ}rPgU0oHn zPD30Gs=miQsnoT2f2C&qV*p}{$XEZihD|`YkayuV2suo5^L(#b-St87RzuoKbB8T; z???Ls9iFe{nQ^9Rl!~{>#<Ytm_s@^*IFsP}m9;nz?)qA(R%{{E9Q6b%S+)8j@Tt_V zamnVJ@FI{n)BjV(l}}pO^_f+^P0RP!&a7WQ_TFKLX9ak4O)MypE<F7Y>0SBd^XF(G z<fPKkZ|;_!bMGuiK*$Pu>G<U!L8&y5c=h(LH2uV;OOmI9=$zA}E0;;|{y-nX76}9< zDxTXI7Ke*z-lSi6Csd^N@~(s_dE;STi<gs^P6E=n_9Lgzx}D=KDhgMcS>)i)@ctTm zv@P@s6XtL2SKA%o)9P=QT$B=`i5yDj;8$|uWXck6j{);@y?V{_cidY}J<ir|S#0xt zl=7F$pmnJ;_<4nSjzQb&p2+)h?9qC6eJ?CP%fb5``L`7soam%t1z5)bp$HBwWYb<7 z$U3b~4I1Z02Q&~zc24fC_9g!P_dUW3|H+LK^Eg@UgY$B4+<X!0<aO6z#w+P$zm%~Y zC$&<w)8hw!ix7Is?aP%9=N&^|oV{k>^G5VyQ&>H;CE><STicJl<wuu}_$>MlzpOuY zz2$#!+8Ce^fBuq$T5b%J#Bz+0*Z!Rdpnc9Jz0XwM^ROM4-OI&I8NT+e%QLXK+Hh28 z#G`SLhh<Ts&ZaxQ1b(xv)b*<-GI?l1mTdN6mQ%@c=Zy=GzidkCG0NPYW0bbZ#jz73 zvo59|h;jKwZ{s1AVGeHWlUFx1#)6AoEMR9#PB<n@`^LDTYxL@e2X7$)2T(Er4TxR@ zKybG?Bc!p+o{8{-%X0uv4hgT+7JQ9XDFQpN8pF4(Cnr?9%k9xwGT3i3icj|m&ybkW z?jnbweH}-I^YO9AbsE>N+98uU33gJ9dYY5&lAgS?DYKiEl(iAM?Vh-`1qO^4Xt=48 zho8nH+MoR6Qond1%hO$dp7_cOk;=Mk22$QOo)JQ;>udA?!vWp_cz43lxXkR~iC3u3 zn{&?Cl);n@inx`0n4PjHmsZwJH+fm=RtKB!@vV;Tah3Z_f}QkvqqyhhV+xdlh9{`F z9P=Nt_r_I~Yre4_3{iI!&TT_t!C)m-IFcb(;1oNibmQXuiET}VRpZY7!B&J50B~R^ zSkXP6tnxw#pkysF#ABj$brgOdC>)h(n1)Tr&cogF<3HSvkg#p%4G-&AOo=ZR)xc)+ zDV9u=pR4pK#PMs_(5xotV}I6uXlVL@Pgrc3<vQuKSk6rtTU2~2G;%aZh+U=1<R`5u zyK0oAtcN9w0f9978Gq94&fycs=am<Djwk2ui4ZsipP|!yYmai2>xKzjDr^Zj)cf1X zC;4@hpWI0JltHZ&svp`a;?U^s`<tjU-Hmcw`Gn-TZ#wX1=(rk^j*~Q*QvSwe0NkXw zC%Uyk07iC!YueAvTUQo4Vgpt3J1K{9x27&LXEK!?h6F=}ZUiYp2wq8nY?cRs@DW+4 zj%6noYo3JsVCfuQ4?%fr4@-VvaA<cl=)cVh6YnnstELU*bgiyMKL2eqsJD@8Q0OcY zgCEfdi{bKMT8Z4uhG=?r_P<P3Fqp&Ht(cMWpe~9s%oc%P`LtmLRl&>lJ~DTw0<*CI zAnYLvQSpzl`2(`#^8%dQ&HiJVLIX~K5g0xzo2hqHSc{lOLsbfExJ{cV5+9gVyZN<M z9{tb##OEt$(^#lehk|%A!~IKI4FA2iRwB*z8G;9a+`e1y;lXpyIKS6q2M3Q!{f9wl z=oRJiXADb^Au>$l2J>%M2W7QJ-c~#FvqedX-AbT_D)YyZhqY+VPm#^g+8}23`=Vf9 ze)@X+QiiGr)Z|=Ff@pCqjapU)i_8Phj3n;s!0vEJ_O?{ncTv%9*+ueg)4V$9^4txn zU1^|iMD9B_=TaF;WUQlJK{1)@_|ALLMk5=Y-Bms!^dOz%V}nUkD8FC-n$%v?vlHur z`5y;jYvFB8Hgg1lJIH#u_ud>T@uXZkc+ip9xh9;1KWYSfP{V(vaENEhTBJrp5$XsG zh*Sd^h690VX=o;f=Eh^!G$bwb?KE!ongBIGK|Jx%TbcU?XlWN$siFO$hIo);-_Pe6 zhh}fgUkh-hy2Q2;Ha;ACOIqxP&Pyo|XP8^Y77-XhDtvoX!+?aD{+)#O6r1Z-fPj8% zC7Z$YA&ZDy<#1xquh$<!q}QisuY+adOmsI-1V=Y0`Ub)dTiz+ygYpbg!0;u+jw)>? zzrbTlR(N;x#0`nsSF%G=y|`zp@iC_he--w+-)3_xYjhAh^;P;mWDD<@$zrPN_4M%b znx{Y&9sMy1GM@k&i&{edzJ^Uu>e1fai%)YbV$FhC<#Er9blCXu#4ULSXS&ubG0X7) zltV$-Nc@Xs*Hwf9)$c!_NVCnDIPb~xt&-IP#r+z72Lf!_+iLFwN>FI`k%$&M-MdgZ zetkrKw|9mGHK!n5qoD1-LyYGB)l4n**;~5(85Y+}J)L_|;(m$|F@MWlKI|Z>^;S6T z3PHr+jv?e4r2T3^Zt$=o8*+Jorn&ei066RtITyyNLS{b4@(l7v3rJ}{4fDB$4ZP>I zkCcWA=3o&9-SvHJCe<Lx$32ilKEj^iN@qSkMd3my?(`|C&5j<fg9kv59r8&ue_G!f zH^AiJ`R?{&EhL;*IkEG|J1{rrisFf9H~E^(BUghGnD0eD9#a1s^jcSFNm*#sEJ#xB zmyV5wAb(ER+0}y!j=K~1s%Y#gz}2%S1dL!Y<Ly`474=lnH5~4UZ#+7o9K_^7z5)Qy zGb8al(q<R`Ubvsc-IbSgb686L;9jHY<aS)MmDu5Qrdlwa-$UJ|594Bs4sq(;*f}Xy zxT&leR<mfuQ88y0(rmu&92{LZ)c?ME{{(Vnhju)5ZCjG}ZutFikCl{bzyMBhb^xaK zP3QS#fl6d)^(zI&d|de)2xw+<0C*JdS=y2Uo1j_O&zc(mgQJkX%KIf-K71{VLmxry zh^v!)`;<1M@%rd8w@-Jm%>C+z>b?wDvAZbv-6gx1Pd~ZX63nkQ0td9CyqrsY#XBBn zOkYPP?Ry*yAuUqApU`pq(*N=DXRmX$OdbNu3X~m3iYe;F!iWU;dw~o48>roCAH7&@ zOx0YuP|-d_Dv8d=N)F4+Von7o4f0$k)}e4Pzz_dk>a}};fvoNLJp-|6ihqiZyBonL zbt%K0gV_JyRc`M-xgB8XgT-r?@0T$rMDItB?7uDNIpyy6-+p?$a(lsF7sn!*u4o&T zoSEE&KTXItO(H8l^Zy;#`S$lz+%{YZd_?EBh&WCfMa~Lv?ib7PHqNn&kyJQ*-9xZL zXS}M}9Pvls3x#K@I5-nATrEskRUt<?pnW*taGA>UcbZoumQN>Ee<zyI!(n!@kfX69 z{@gW|-ONAV$nV7g+-36ny$thz#vdWe-6wD%@?z@mVg6qN7k;m&`YChwPCKAVFCXI5 zmon2e!nh9u%!PEhCaZZ9^p5X@W_WG+wU27UmHbyQd_VVL+@fdGixiGyxzh0LwL;p$ z2vS-H8_;L-q9OK%JS4Un;z;E1lI2iaAl4Y37ou=8m>7Em2cwYJLWfI+Q;t&}-^L=M zI>9}SK~EF7@-`{IWx4+`Fa7SwYVP3wUC4D3lYXp;%Vdkt%uKCn;_AW^EEuVO3KQ*@ zjvT_`E_c%m4hy+|Mf2}W^B})qE}i7D0E-cA{Jq0+pKUpw>XU~5;N4^52w~_GodNp* zuLr=^9W7KHZ6eU;1E4twEP7HvZ?%ujwU9_CgeC!;nbF7V0Ittl9M#bnu#Mw?(L&uq zLh?FReBZc(JK(Hs+ajY&iedb}*?_KrtmCKzuAf;|OHfYZRAcXiW}?Gg*;MyThu`~w zl4JaTh*^b7IseJ#pj3*M8~NX_3tDIJH3=!K5_7d+#r7r6Z>ISemOS4$w2ZR&`l`7b ziEMF9K4|>$YJf9rJ-I-UV^|O3xKB--h92wS*k0nu*iSBJ=5wrb2-bOSryucYb=yg~ z6&&t!7a&9y=gtj$<Nm?qdH?{wnO8ZCMXHjxA9O&MpJfSWIh2)fKfq^~!7r%yU6uTK zRUzwgcc1J1!UFSp!^r_v<d8C1xcI6{dFOhOCs^&{R|ylC7DIr{u!P#nYTsk$N|fbH z!^hTAIL^tM1TPX3_t}!lpqDW)wX@IyX6E$(4r8ikd8x}CLv(E-e^VicoGhSL2&oL= zFR_G%-R6%}5s89b=N!xG4WJ~xx?JB^>i6NgFszL9;OZy$90zofqGtkrL(nw%G{X}6 zGA6BfyXy0p+O`gM4Ie>B68Qu~pJV5`ZV63h!kXe>=K`Qrp(o#!9YNizj~$!lcqqV8 z#AN#)iq6HK>F<x@o6Y7rx5=Hk-!<2{+srk$kt9j(MlN#=$#;y+-AHmv?jht_D)q%& zBO$j$P41V3uS%u-_WJ|&*!gVdbI$p^Kd<-m>D)?5YRxfcWvil~pEbA?OW|1lyPLV? z0-6u>#j)+9^PVB1Pmv^r9ky4Sw-id)idd>AHbZZ17uM?LjS3VQZQXCF=aMN#-Y-aK z<Cj`Zf!zaeMh+z&G}PGqlF2O=J`nJ`SP3JLIXV&4*H<8Sk#5y=R^LL4Fys}6&d<7n z9fxK~IRH5$S(1=<Z%-00Z?it2LOaYaJi*<<_@hYPT#!hvx9jfzuEUr+k{$cfL({8X zZx*(+Le4KnzkY~6x6Q_D9esyk{oNsn{`7K2m3J!SOX$^NON!<$a%@(J+Xgj0WE0Pl zmT|erFZ8hVP3jqAF#`J?uvQ<iHr|1-rA3s;Lhj#W_49;M=#c38|3inJx1q^Mw*`M_ zA|1(m@mAZWWc!L5l+QQi98Pu%rj(Y#Qd}iIdfVw~6*TZ(`Bp+7ssR;LeOQ-Q6x1LA z36r$WZ12tJkUTF5bUFkWe12D6zw`J^_*|Bz<nDp5qj0VDa9}qBYK(?N0({FoS$^EL zAXE@9S5(~NhMxR@L>+)i2rR)D?gj$bxOCh7d+i-I-M<3}>54Vq(sZ_G9B92<Wp2?A zy5VB1_lKXt)t?u7+++VL*MKUy_qDP5qfpp|SgvQ2p#(V*;Wf|YA#R2O=%P)RTV<*# zDhf_M6W(l<oOG4?PIuX^W3Q&N2I82n=(E+4pnyrnWtUz?fTD3MenjT7d1#a;C=tn$ z+FN&fi<Nr|+Q}Wl#ER=g#wMf~hygjRiWoG=TV}DhRb#ox866(->=y}C%t^Z1Tzy`~ zJp<Q_+r`xeZk?(N)$^NqTIU)Mrg=sHT=hV0x2s(pHZL3{TR-Ep2~pQ1)MNL^p-Hj4 z_i)Ts1lDo_3x41Uk!oRyyqin_cN17*D_CRdA$PeMBgsiTAl}V~#vt;`=1S9Ulsj~B z_<EY2;=HHt#Y|gQBbC_o52}Xe^VDM4JvO8BE;J+xJ+HNSUj2ycHzL1ejnqjz<NEx_ z03jvK>-2(syjMw6`x6=#g;G9x3V+@j)vX;G*A4d-DP0&dzryhU@*4&+$oK>n7#l$R zg;O9m>%x<`feQ9~76AS(^4)WIVgXk(0MJZ@b*?`Ib|p)Y(~V*|pn4f0^8Zf!NWW&8 z_uHo7w6x*tFRv#RnGUFDU#2aO`aQV(%{cc4FWwS2U*UZ3sV$}v`?#e25nWh5oHq~+ z#t|VzI)m%W^5CXLqYr!BBx@i7eY=A70v${_U<qw}8G~j}SU4hg+%<ceg&$s!OU@s` zG1q&d@GAU9&*AUxu_-J3yStc>Cfu-lAtPhs--~-KNvvUKGi8vn!5#V;tQyC)i*USd zJ7yc-b@@>j{0WRw#MLqt8Jt=cAIW<offqmoo3(;p@5cFiLKbgPtGO#8xLJ}AtlG7V zr3>moXB`Bvv?18y5LBRFZAH8SA`glu!p06He>V9106g1og@jP?=hG4{ZHC%#gw=H4 zH&GZgvw2LEV`n~fhK@gfbO2iiz|J{kb&XHv$62m1oJ7;GfSbvP!J*(R7cT%<i@-d9 zWb^YhNv6Y61(RYAAjg_)0RX_8c$>W>zey^zU4YO{HLz8diljoD2?ky-nvINT0BYcm zUPvX8>&YY)-q2F9G>W;}a8G#9;eLaKU5fl%a~N{~&f;uRCW7@R0oDL4=H#5qi?giB zLwxj%Qo7N%lI3zmZ@go0=v5Xt2F>bE<dA*Hj+BWnpM*Xgu!*SvVOuZW1^^yKhGguy zYyFW7Bg1BVuIetc(WnnIyQ5B8>;L0^woIY^2B+AZl1vo--CKOyT*M|P^la)TS0~*L zEGG4c$~8-${Ubcrc022-?FT{cxfwtZw8Q01Evj>N?uPBv0s#0Df*J9JHPI6SAadQQ z&>y}A@t=g2A|N^y;A_WhlkkuUe($S3C~q3G5>N#9jfZ6{@J4ma{L_>cVn)ud&}%;i z>_o%h)}2p0?`;{BFE?_vB(S#*zNTwQJ!*xq7@bA6+tG*WjeS&M6os_0J2B6N@b_AW zMm^CXw|R>ZECHEdTTe&~db*gvdasqGdQvVH0qH_6yBye#^;*Pm(}Ggj_qjzns+eyQ zMeSup*5uM*cTB6$TvmcJQt4dN6zk*XT>TF-1V`VNkK~=AKOGdlwYut^H^5_OrLfjx zAREC8Tc2f~Sl_u<(`EO;)DhNoP6U{)<MGWw&~QcI&CozAn?F700THZq!0g(qSWPew zBs=vCuy!G!4oFBCnq^>;<NROu6K+}o73z+JDiklI|K>SoiyuX>g;Uuk(79tE>*w_` z#ZH5?fPd?YGBEWYpF>*^Pa32YtuKB#gH=8G6gJy=Woc{@$8ZkLUd!2y|FQmzX`@w6 za(9v=MVh}Xh3l*k`UtIa+rseXeGbdXm&pKiKToh@1+x_�$wd?U+BtvAb>90O$}O z03eJGzMa9=NPHJfWQ8*G9^l+WdF*Z3xn|xyR2qW>A=&d=eQqhOX-2XAs9@_PTIUtI zpMACulrLY6`?RLl;UCKNvx3X$-s~Y$0N@hW*H*Wu<+~z}gWS5+U&3yDzAK3mtp(uR ztUqrAug_t&X)GNp|1kqzxj>SMPDKn5G1Y>B=+`7c<*spv_HpE+nHdrX9dp*eV%T>o z?4N;RD2b~>+mt;=r;(e@o^bYcf`HmOhrd6Q@D+l}f(ND_d-bhXvpKkzgdmAJ6JNl) zF6G+$M?8-Xo;OIo5DokBsLmKBI>f>QOLXE|K))k!Nexckn7_tBejJ-I&yje*7FglO z;SZfOV!7}i+hcBaom>c>YT@M>j3$D;dcpAoNC%P~%?U6jd~KOD{g!gOY{2?FoGlnR zQ^^etLUriX&E5DG7G7ZmIM4p`_&lbW?QG&<fWyDer!SM9Jbc8>pSIm~<&UK8?(;qF zu1C>7=06=?{(XqJuC{}8Mf7>TX=MWsSfqclKwsjBp~^Vxu{?=pPDDTnIK+QknuWPe zu|!BLk+sN^tpvb*>ELXy%4}?|&1WLH;W=|}CBL>ylh)x1cW<-rRMGnmio>Uuw>nRz zp5Gf68@?m|<(Un6?Aj|o0HcEXeY^0{)!*M6rXOA?G`@YB^6~k@F<Ijr<z>~bdn!VJ zXn{(7Gt{N!OHEg%DqlQjTh<HvJaAVzU~2D5XW(p$--o#`SG&X4Cu*<G?_cYQ`?kOS zVgBp&UVj>=oO^7mYs9C;IP9kOBP^cm!LMx5q~SLnqat7<O@^y$JZedcGY_I}za!b7 zS!-_1KEeQgaU@GC*lFDQL0FEYOqA>2`Y$;W?0H_;>GMg^$Bt;O2bNb)eFq)Q*#*?x zo_4OfrLq%W7(OR+V&~5?3e^fn?N$B$)lj^3q8unY7T_pBY`#?Kvi>+{_aFQzt+qJ+ zHE>w6jp-r*0}+Wjz_3Uc5KP(rXzcY926$~m!gd15b)VX${NQ*iAW_4q;@LRYxW{32 zu4`7ZG$+7G`HR*9B(FNx1P1h_8lN7}Dji|(8)a|jhqoB57m&VM-#lituU|=NcRHsO zVm&Peu#JF9EQhAA7F>+_$xPI^^pp95&dLo%vyRTAu!*zN)g2|@ts4|1c(CEX0S)4h z!kMybAL9UQe7hnRV-519hEMz1;7$q`4>ewE(V7GiK!)wqvE@X%a7HB~wM*<a$H1M- zFd^naYl~56_t|m2isGvp+=Y!-xyR2^A6&0ph1PE@*j^9-IFCx_7`i9*%hoRX1~n}I z#mY;_c2q@Pjba+$6N(y9d?*se7CGW>_U_WnYcU_9e=I+P*f=x#+W6%~BX{0I?)y^1 z8O&0{%3w{~KMPF*t`<DL1%_!rdd53%Akq2#TDMfXiJW2zJO>&#Fn!q&WAWi`6b7P@ zUlz1|?uze}{exxl;->s&uP>|`AO40<;NgDY&%(e;_l8Y_KVzHaS9fTQ_BZZ9@=9Yy zR5w3zG#H~qV>{;JZ?wGlE_^<Y^Br|3bU<%Y6rXnGHOy3Hxl_>KqZ*{-J)vz7o@poK zn{N%!ODQ-r`P++y<=BCUaI7sDP(ovV_Md(1R;RoJDOPRtsFq5T7gD`>YhU~}KF>wA zz{R^*rY`CwOv3jl@A%)(ov$6PMp4z@iw8~sABtEA{2_bLUY$#f{hW#Nz;O)D9sGz{ z1X6^9_gvTWtt>DQ_?T8lRuMcs-Tcr{+{2sO;V*JM;bOj3^=dz~p=SDWh0q4Ux2Nkr zr6@XPSnT-Y*sPS=eX#AX$^7O{c<0wnMMabiMAb^;!KZPye|A`K`R)&!M;s@`AE6-t z3m4AiK!v!3{>9Xso2KwOT&l7mJFBHt(Lh?Q=w|&8!WNV5I++50aA1nykYvFk`ngj9 z;4?(p6vho8%}PK&`01}zN-M7Oxucs$vp;6TW^s`A7qX3B{WsWYXsw7)XPFLedv;PY zU}R%G6xrg#?nWn(RN5@R9D%Z{S4@-t0xv^<cd_MY`G_6qQaHvA`vux@d6~Yx((|b! zJQ|H6n+Sen0+7RoshaCvj||c_Z`47pnxhm>5-h^AsUNTK2cBTzcK>Ba>G_5N5JPJ2 zT5Qb+DzY|#nM{|xH7^n5Wh$lR)L0fQt{p$l8Npi^Oswd~x^uz1Kmb($fcIe;3;fZ+ zoc?P`&dv1In_0=eN1}1|QFRyZvr9qsM5pazhc1?XDOf?(gtJ^cF@5k0Y-ar9?5D$R z|5Y*nZm{S8x9&v%K&Q!YDX{J&gQlKSI0zsjI_qJwMyzVn5e^zrdAa%#1E^=u-!Zr4 zXF0YqEYS*<2A@}YA{KlkepV>jeVUryxL+-%F3N5=YFZcv(XIy&H}$jQoonPSA!St_ zR`oh^0@mK;zv?BKeAAn4NOTfwU*Hj?1KO~RvN+67f>BkgN-y6c0MfvUGb_A0dMP$R zLf38)c%(wU942;R$$E3)k3*wY#lGU0jTZZy!enBQA6P66N`EcT6)&~lsoj&3yefEs z2`%jOjpY18Z}w4%l*F5gR3n%YRF9Esc#KPdf4IrQKblgQdGV2aY@z1a_u$SJ6~)Er z&Tk(cEr8&tYYnKQ@XNO^VcmO`v-HN*1vfp;<=w3fjczX0-d4IGy2kiAPt8kur+l4d zGn?}NVKOb?KE5^GDOk~rYAkoZ3OqH-&x!~7PuHkwkLZ1)eKvQ%4cU@W*KwU+EBT2% zt0D)d*J8v(-|t$u_Vd+Ek{)ejM{-D=E8LSukBYcm_XLSNNu%AbIAp<=-G#TR?;>RM zKkyZ^2;V~w#alf6^w)Sj*>?5Z)9!Y*AY!%nNUwQ>YJxAzMb}Xq|09o-U%qknb}G}8 zNTmMQ=wZ&hz~&fq3_*HeyjRcVb${G%W(S$U`!indj?4MolF~~jXNAL&a~bk$l{r^u zR>gdPN(FyT1JExzMoDr}l^>+8(X+qA-9|E3588M%MdZJJ);e-2BQM=MOUk^oMAcjj zl6{H50Ok;!+_y`5yN`I4_-Y~_sh8yDJ|T%vDuweyvbC|BZu4-9qlG8ou<IOEGzq!y zCbc~5unXp53nON=&YecDqka+IuxQ&++t_qUOIltmFXh}?3X0N_miR?AH$G;DMSNVG zd*Ofc#p7L1y7rF9=A?zQ#Gm(%OyhYo(%4K+9XX=8tHz7kKO@Uua$HL*k&BqsaXTpu zI{Q33YrE@Wd=SolX`x!;JzXtwHpJ^D#eL24?&Yd>gC~7a)naE6x@K~RU%Z;mVYy)q zx!AIofysI*i7x=XvbKc}VZVT=U(qL_&lEPp-m&KXU8fkORl-`2bArUrbY=LWzvTs7 z+uct2ar8Po?eZ~ZOzn(d+~CM!Kp&QR(mkkL(xy0uguR(WL$aIg_`Y&4t5}4w8Lxpu z!(>SkKXA||6>UXPm;a1h4M<pZ#IKlTu8UF?pwy9lFO}Up!ZDtrmsNP7S5JUKgK2{w zR9Cr`r@ODum6v~9&j@1HU;p|EhBIDj<4T189sa2RMGaU-4_==;q{+WJJk`=!lQ;Rf zS!AZOCMojvx#9FWGem3pRS?CnpAXQTt7-_$_VWx1oqct73p$03dbJ7?h%Twvo8i&( zWf>H2S<Ns|bIc_i?B9I7`On#(v$HlJfK$<!Nu{@mRjX1eGwy~lw?^va*2Y^jR1kvM z9WVAr0fJK?U+#rcx>IcsWIqMXp`UscS9KRO_0>O%_LT4$6pIBfRCt9$f$x}^6h(}c zq2O_hSe86!4<lh#AXfH};AxyAVj2|NyM61~kuW&gwYwe%^)5>BPfK;RD$T4&oyyeF zRyL6`=%b9OyD5~^J<Avggd}jY-YzoHt4xpIB0uQwLuAp=zcKnvG)x>)Dp($M%q$3O z9;3Cp9;C)pyntn7xB`ntad{Q3%$azI6L(kQnKi__R|jq@UH(4zQ7?I<5AvxZy@C!+ z=q`NOFX3GeEnqjMc3>~Lo3jd`0cNja@W$b6O_6jm=7jWysa{3;Ze%?)I1L_+hv2LR zyz2{|`mlD;MfX;UQr|HzeO4&!esnXf3^2;M3;<LTSO~>;-~Z(LgCR5he0f>aGUC_- zc+BTwYZ>iMjhNw<Dl2JFr-V6W+y6o~>1W4`kP~<)hLta@2_kszKL6I-!aU}sRhSbu z`0hdN=u~QAxPE3gGqm5LrrwBkNA=vEz$trX%-%>2yf>P|I&X>HFeN1z&`2l}j;N=2 zW~Ms4e){%T`4SH$v>tN3tjwl6#rv$M;7x0lx0OQhG1N1h<)3aj9S{#8oXw5O{7<h@ z=SjBz<Unnl*r#}t#5PK#D}`_Zaqj8LJH60akePq0X;isC=Yv|)PY5Ro-Q=bkcyK?s zo*WZP@#h8$mxA~EviPRZZfpbI2OwWy`qdHAZ8ZBoBg~1tFbci5qv&;Gf^8JRD!3jx zxN`yeqNH`)_Kj_3O#DN%NLG8w!-4{h$VtT@<b$mjHH<_>VKS{jv9vHb+xs8|cM-fR zl<L+FCsn`jbxn2X)+rS_hm+~KKw?ZlwmnemDL0lPLk(B2F}{P{PH2DAWWT$|7m+aB zhJN*Fg*?rnGmn0NIbe1>!x}4s$XL3Jk_>YR5rX3epJX|hS*6&FfZRq%8$@!(o%;rQ z_FcD3Py4tQuNdL$DfKJ&kB+UFnR|DGanO*)$zT-@Ae6vDxv2{kb>eh7NDZRm`YQw? zDn=t%o+Qv}4kK8urzuga>MwJHyTYM_KDJf&E&!-y(TkN3M~McoM_3z<C8$6-op!YZ ztTJ%>(`ui90K&*?v1Us61@Uk;O7uZ0G(`{4tpsSTQF-I!iC~^;6njW?By1NpPrePE zaWM5|y{Rh|J3{FILWdSFSggEm{5iG#nNRY~yVgBh6OsN6l170u+QPc&))jUkUT7el zCUe@VYByzbHeDJ?CCA3r{X&rI0O=Katg_E2x{nGHJSiIukoA0AW2yZ`RV5?4OK()B zO_-gY6CQGiq^R7|q5vS705XQ9J<g}0Oo<YWghrgqie00`Pj<v3TmqOVpGt)d?94CS zc4<|4Xc%?r89J*_gHu)diSn$IgA{XMg?tG|Q<zoLK*_sLl9U1c>E<=f$Zt~-8hV2y zm$+qHvy!>G_RR2ga^z&G`I{b#OZ88k=Vf;9#BYm5^2<lQw9O>U@|0Yrh>g<wxNp_Y zJv|T$Uw{N6v&WU6z?Y{lr=>=+Ou5l6b}DcT|C-FJ?Ye0$@WQHwa{EfOZFzdv^B3Ig zVR$Iw%(36<#k5K^+E4poCrfFgre2Y%TeYlG74I9v8O#grhYbx7-Y@fq)1_Gb%W+QZ z#zwPMrnA*w+~V#oxTH4q2;Ng{Zf8m9#Nf%MyjKcCB;7?8pL}zB#yLG<>t?d9Ti2Y4 zvW0v4bdG_VLtajsDrMF*U+tV+j5`{Cc5TU7JFEEie9s9vV&q<ywnWkIha#p=!Ab0u z-(KhYxKGy3KOJmptzD>_rOM8haw_ZC#4}$nDv9*Xl#pGVY+k-3wk!!IO2I#rh>7&8 zLc{2JynmWH{Tjjm#MNt={<2p-gnYygmQ1f->k$+gHPVS6H+0Xo$uqZ{@KchhzP8DE z{mt3ZwRg*zpTY}*Tp_arYpCd3>he<IHPqq#>u<&}gMZiuGn|#8mt9#jwq)F&>0bIJ z=Gp3NTy;T)Z!z<Y_Iy-G!*$LpYjz$dw=-j9J=yIomD)eOLa<X1?E3}J|6na)<(bd# z(rR9M!dtLgs!KhynJ<}%sH~Mw%=B)Bl_ozonw^)JPA`YW!@=K6VlZ#Xmdv)E%Ls9A z8ULPOgx<E%XPHFrn^(Q7^VJkuyqoWMw~VPNfBbxnPiwhW<ty`bHF2L9+UL=Xs~Yw` z*J#?>p+2ZYAKe^AN^=!hC#C;tRjeEw)azsX%F|%q2VMTj1m<h1=8HA<HM93M_wcni z3-z^3^ko1stjm2bwD{V*^0l4twfpF6zwhht*B1x#a}@V;QuDiL?B{Incge%gCDiY7 zqMvJy-<5Jdw-&#vul(F6{H}fU^Vs*h{@2eF=I<r$@2%$VW9;v1@9*c~?;q+Pkm!%k z@eeHb4{Gth@yb7V!awArf9Sq{*k6AFEFfGwAVMu5(l{W>J|Nm7ASN{6W@12WPC#6F zKzvI8gA<Z45persK;nMDKYs&=Fnp3YK3NS<GRCLa<5NBG<WM{%5ucWWPcO%3wBR#e z;j<?2*&p#a`}o|ycq%L~PdqSRE%1(UV1a$$U5~&*abrmKa%363aDSC&pZ?%1`La&= zwwW9yoKYg7lS6PWCGM1HJSD=lHD(bKN{8I9+rGuR6X^+U@P~#J)%e$^x=qf80WLMf zl-Cw+*V%st7+P8YDY4X@C<U?`gN;!^(m;?<u^?@R{UR2`;DB4>ckNusQPdz)jmsT? z-PR{`^KEiPXnB+%*^WR$Re+2ZQtWW#a8KyJJ3-;pAU|TTkuFJ-0J0V&`yp|gqvTfN zb{}l{jo5CRBqgM`A*!AkjRP@0=vM@Z^Q1)KDN#svzdz&<B!j;j6thJM#6heHB=t$s zTYG369$LcT6=@jqK};qD!E9u;Z`b-I(GwccOO~x=)PJ|{7-OD({6HS{hsIGUZj&i# z3Mt-%S26WZ!>Ri}ncu{CLcJ8g$^?>I5jl}ciS8xWPW&6X;25B>)1*ZSiKT>61=<8D z;T4l1xM#<8<Uw(eer&3TFQxWe*st$y7TdOwlV9xcdv<j4#yMy(cT-g;)RXbL2SE0Z zeev`vSs?dt<J?>bU332r+4}j{zy<IVIj|QsXgTjWmx){dWJ6SUs1c4F>q-fqw7jnm zwfW4ziHqS5QXCJ!-UndnNm}S3vtZbMJBx~-8hbkcTGmJ&tRvZN?MBk?%b2*0hCqYy zH>``u@t)9WV`!X}v!K{HSbOm;dW32{6XJ}{bZH@Zaywaro9%Wl1)W7nB*>M(d)pz5 zu~If%$nRrFlQH{cEs>YL@r5ENzd!En?MDVN5b;PTj*snH_gh2PBnEU`s+&o(2<#!q zY+nzyPh)04O|_696NW^q_nZ4jDnrrcgooJVLc=E^A>8sTsJ*Ikh_x=r2*C`RC9nRu zZ~GAvX>t>Q3#x+v=o660+>H=dXv|iOH5Gb2<y$-vlJy^}Fq%o2&SWB(8f8UE+@k!m z#rPd5DVI-<Lqh@Q$$o+mkBSt-3ZU=^GvlSz{Q+`p+EHlzPE3T_4LtOl3yI?&#bC6X zwN7wo#bjg}<yh`#jKWUKnMIgQnD{+t&>tHQ3QO2^@<m)TbJzojp~KgaGG0XlNdXPQ zw}uGZqZoMx>!*=)@G-7L=F20gx+BaA#AN9MCcTPeqXotsCSBf2(X%3{E+iYGnHdaj z2Jb%>PlIq#!s(D3=&x=#l6q|F#vFO*D9*6%;~HnvTxj|6(3hyR6UQR3+GeU-1qfC2 z#g5MGPy}`ogaix5=7;T@^3H!*^w__<zD6U*6p>M}N5A)DJw{09(?|-vqzeiVXN6RQ z1txdo$Zb!M4uMGtNkXB?Rz+r|QxqH5R0DeYZ5DD|E0YnGgqj5Fr=>|KFbUTuGgw-N zY0S^AQ$o)WjSoI1e2W2TBT_f^qoUw@sPFfgEE7UvU)UUgjworGRIp_D={#}o@??rN z9!xw~9nCJ43uR#~ac&aQjr+3L%s0;o0EC|#bR4e_mmba$H%aDDjF1`4mvgAHZHSN^ zD-=4<@GrHM^*DO!jNTClTNG9G9a+M3_^}s>{Ple1bjfmD;^M+|mk%^pX|`dk<_`~O zIN#{j7Ipb|m&1dHj->@JrE2O};peZrTQ`v2Nb043==JiEe_SZ6O<QZ;)yXLv>nC$b z+c(9kTZXS|l>0n<%6K@8n&@_{-oD!!cw{)X`-7WcG+K>)I=20DR>3H=sasuh`>sX| z*ZZWiRf{R9)sL_K0dcAIJY5a@u;>+u4Osj)Wbg@6F?w_2oHF)wlr7p}wA_RM;NguN z%#|=$dwWL!95_>N(i;@`>pyvG-oWj0qYg^gr&mq|6@#mp=f{iG2jS<fRz@|y%|zzt zEzxTQu6t@p=jwdQ(wrcOL@ZQN<gW~HqCTTj>{O#Fwua>1jIU2(7o$MZS)Zcby+LVA zExge&$f&=H`c|_ssqs2E|Gh{UzRFhrNtbk$t%RviZNWtgYna|b=fyF>u2UaQd2D(s zvxq~JI=f1{%ppZQfBfBs;nd{2tg=@soj8>?Exs|+W3$z|(h|Y^0e)wkx|Qn5`^dM( zEoTK)T*}+M!$X{|=(ZF=oA3X5YR8RsKn3GlJ0?&rE-5^BA6At#TCEjG!%%r`n%Q#q zw!;ezYr7&Ratw6*gC6(z4eT;vkbJp@do`MG<nk3B4l7*Psol-4%WrJ#n)hax^%9D> zFcLB6**?e)Y3Z|2`Z2CKCVtCy(B9~<SL7{rv+T~Jm*3|~AKM@HXmb9$h`ab!D`X#I z$y+v~!J?nOL#tQ%&hg)vxJ&00mi2Ph(RlN+^M6?$@k{X8YikL2nn&f?Z%(0>%<fLe zDeP2cVW050+<TlkxW=iwYsP;=HGZ;kNW5o!c0#v@DYJdrMw8QNy3hZey<X6k7l%^F z8B5*;@s9E2eT1DI|E#`L$;Iy$y~dou@4xoYvh~)AI_!+5kC$M`*H%*Xn)k;^xk`;% zZW*$pbiUWZ7?mW7;@2FpE{&+3%B&IO@>1vey$5!xs88t5OmP>yla2kZC-!Toz)#4X zyL6)T75mqCQ*Fs=(RusPu<D#=`!8%*_p(!>L5>EmPmwlAqXc@2=E>H(yNZM&rYx<^ zf(}@gw*MWw><^KjUVeQCi>W^O?7NkX`eY_EyIjh_WL5gB=JSPr>I?Frr<cYZS>@l4 zT#Yv=EyM8r;e&d`2K3flkwGnv@GJguVt>m(C%$iWdSri3<8@o8$R}M!b6gv%QPvrT zs|H}{?9P8jL=2g#G*E2*+6x9yX%!pvgorForVC|NK!Yct#xr@jn|89|o1WKt=(D-8 zqUz~Z?%q8g%^%B`V?~@gEwWX-Un$3vq+H@Dx{ZCXi(2bk^LUHrrz^P^Cm+Lq(4i8r zaAv)pDv6r0(Hj|(xkcO?fyztL1-v8K%tJnK=R3tC037-TkH5%r{bhr?L(MlcrW((t zq$QLCN2#tg!E<<uo<2`j9GJxEIB6;xM9;moRxOSmA2q1QWc%Ytd}Y0038W)bYf0l? zcaN;9dJ^juHQL=)jv}5F=9&n1p48eB7j1E-tj#{jwEtYIRreh;EE<yGXDPU3UJG?j z-%+g4gB?r#ebZ5!DoyoXVTx|6GhgE+n&cu8rwc1qHT)Yc_8>1sc%n63ma|Qy;DxX1 zMBxP7t)?7M4>2+e&x#vZ71T%r3N;d5Cmhq@Zb?|d&R(ciRuwn(04$;6m9Fn9#Zj2n zf8pwDr$RR-PPt~9g3?NQN-Ps+!ep|gdRwM9uG;l5$kIG0O4>J`6mSF}CzMq2#V<+o zKT9Jitqo@|GUebD!1(YuT_~9PwZi+FEg7to>s{Z+IYYJ7Ywgnq51ENJ{Rfdgw166| znFo=_eb!-k&YTpVrh7NM^b}mPZ=_Y(<yT@^6Dz=1)|iC8r=6L?^AThhYJW`=lH6kf zI!{@vk*E|4F{#PpyRTc*!R5uQY`Zhoo)A?~gfQ0}?=zv4k$eGL<e$3ur*%4a#7~OM z)qFARz28Xu>a9ugb%#``xa8(#g*`py8_W5@K4N?5ysgDwbMQsH7}M|ff*y{KqkW}Y zMI1Nwr+IQka5WNdk(SpV-)JWUSBuV}n>4rb_<}{fASP)vfhPotD~A*-A=ZjYkA{UV zC|EkpkhPUmIN5y`gq;jOeINRv7TdMjF&9f#cLf5xXE5w|K%jc^Pby@+UU)EGPIM{q zky)+Ou(dT*xd5GdxoA~l76204k`>HWxbyP+%TT>DaS&k6%UZ~XI?%?@1QB%WMtg1? z-O-VkG^$VH7WIXqhAP+L-k??+i{e6B8#+F!>fb6m==nrkvT#C@$sDdWyS5J|SbScz zx?TR!YxMy+Y5l33Hs0!HXNUY$S^}?{Wy{C)su&egp|UYp-l`1|cVF6~pqx##N-;a3 zepURLmAQgvC7aDbQfX@1u*oqUyjdrWy795ga%f5wIWqoQMp;OL7VZ~1VkbU(vLsVx zvk@-%fjHMYbUp5+mhzQq(L?T3g{{NfSi&k#G|`mpLMzv;GE=c5Di?CmD?2Dwx_`h} zY<(x>>#bE0Iqhi+JqBz8@&hZ{)aoaObUaJHh64>8s!_Cx7U6+2H1Q{dRE1>8e~XkP zAr&VSjq-~0e{eoh|2_Hc%D22$ZGO<AH)Y{&x9__wtB(z1rsy2&arztF67jdt+IUsT znSZ|7;t$b6VdF5wi6F&-Il*$(5pomh{bGOW+YC?lvgJ_Er(ECa&%fA@wg~$pwO$`k z^{>|}q1j!Rp^9}&^{K3zU0BgwD#V3OXAeB4i8GW?MmfODi>{{Zo`NKeIt&zL<u7uj zZlpLVaZ-6OgROLHSf|y?!A6dI3_Or&{0z8pMVgW@YhElR_CU2?Wm0GuEhWE$Op_S# z;?u@sjTd;L<2a<^9UCmJXMg$q=?r9Y(l23rm>Cv)7zY}d6Fd>^ClEgEbnNeMLyg@T zu!MoH=iJkn1eZKd)R%Zf)+edkQ>;y)<K}`X_n=`ffp_lANK0o-jwtV_=j8}KI03M{ zx<K@kJ^W{A(@Y@3-Q(TT^`BQV;onHuL6Ce3Q2w}I$f{rK7$A9!HL3uq&R{QEasGS% z?e^MrmJB+JoU?9$XLdKPt$?QK$t29EkZOUJJ3-5%l=CB4<0X*lmZj2CvXV+4uWO%N zk8QsnwgEwx&2uQ=Od9tk={Vb5;N~}9z+6RJbY|1}cRpFw&zsX3XH~3@Rk93~$<uSB zRcuA55bVXjtXTt;5G0*xl=W%%m~sL7oz_9Bc$%7-!<)f@uU{n2{gOnmRUNzmr+3m8 z8C*kZzuTqzT86ot8#LoB)62Rv#eqKlQ=$kFr-~Tn_OdZi0T~bm^eR?t)^f}TtaOcl z^7i-MRG4+X<Ob{kEU7faV%66_l4^e?%}=~6P9J#mN{VTbz667=XO}nDkSv0k%wtKR z1ybyRDNGQMx;x4C4^7#yPYVHJjY>9TusrD`10v7zOVO~Us`&e>dTuH2e->&dz$Nxf zja2vr|6mNz*F?HW2BILNGA1Dow#go*-+C)(J63iopH97ixdI5F<pmU%3`2ipM6;12 zpls^6I@7r`{l<HUU^CUaRZBO?^Kvq_r!W*DLnf<FuG<DhrFpvI-p&qc{)Om8Va@bt zk_W)rKx-oz8oaa5X%=f-#-!B^H9IJ5yNf{hgRK%}lqT+kg)>Qv1LZuifk15bH;{fp zk}4f!(u*~Y1;US+`H`Rq!=c}f);dL`99;qPEueYY1KU>vD6IjZ5e^%D-wQK$3~^>{ zWmuzZx>FGNqQzA;xwZIo8n;oZA#rl87L+nj<z86DWI+;(>PH&VOz=!6qy6x#K8A)z zXNF|JVya^0fC3MpxHp1y))(^93<XKfM;OgxP<FAY@c{7CHqGc1q^^q*c1_~4O+G^# zuN1(0P5o(|T_i37Sa+o6ZY#~b2YA<uhJFsNy33(h0KDy2JQgSaHr1>O*n2ZSATH5t z6uoeO&gs#WG?=|N-Bac(MZO!1!`1?o@%J<ofJO`uc4wc2LTT(ZQwdv#N}j^8Z234j ze4GZJq`yVdd2g=bWM~MIZ(2Zk)ZU_-iZ0QN7JwE%for`)5$eTaFBu9B`-Y#yKO(=H z{owH^NoEpbNF)`vnazt)<clyyhQjkg`Q8cF7|+o@U<ad$HNiq!RM&-@LjjFT*IPOj z*k58z7LtSvN!mo3-cpL{LVun@soo4otEg|eGS{4?VgAc(apQJL`}SF}g~GK_(!B$q zge%rU7Kr5NSCs*o9AGt1LCW|f{$8}0Ki0kcH8%iY(8;8OCdmVchFNLK#x*HHBtsUO zkS$H$6>BT(Wd+}O`1hmE012^xF^nP|3RxVc*EmgkXD18^O(un~I6p4CuylX&&n4VL zi$I%RD-$y;j}|sns9YgxTj3OdEC3l06%~&$v)Qk+-7CG?H#+}%IFYfB(gf0{c#$L6 zhL_2Iwn(boAOk_#ZXZ#YdQm&eYTwM-2thJfBS~0+bZUyf-rvf<0)F|LCWQ0F^2%6) zT@La%t}_uE_CGs``!@#3SXI3-CuGRs7{XARkG_?K!uzv=f^jpMK-)bf?<lO!DOSYR z)THUIj4lSo>mX~zsW*9F^rT-O(A((_KCo8qS`0q8i?9{F?p;pOKJG8GPZdl9t}Ky^ z-A#=<LGm1ZtYv*BlgiOAH*Ng~%GW_^Ycz$Pevv3sLtm0^k>|{jTlj#27<wl^S=9=D z-JmE*z7yLkr&7RCW#Q|=n7z7z$%b_EuBBZ<&1dDM5WZKw!!2MN50b<H&0UKoJWf*R z!3vL{^#!q{GLWJ>#vqo~dPTYZ<K9L--5fr4lnRsphwwJ>m@p<8HTYZ^ny)}%qx_3E zwJPf+*2uM4o`v@C^orMhv*&x3mnxR^S6I*7;=zbQtWeX=hr|)pov9E%NIFO6xPAJo z*&1X|pTNgY`)vF1w@G><G<7qqfg#qUsZXgXS<VUs<1p1Xl+(4s$};-yf=MXC{;7^E zaJFjxyNYr}9|AxUEC4Dt@u;rRG+X<Hx&b1(&DuTG1ITb^Z<s-fkGd^W6Qo9p`RlHS zK-Va(=@>*Wsj|vKctru*_8wT(WgN^lHU4$f*-Pb{F*Wg|-Ko#Wo>|v2bM*E9df~WK z;2_gbhNOAWFFOL_XK<-iu=*o{$&y&(0<8ArS3Y*{iAGyg5!P@(PQ0~WLIp!9X%VXh z$!_%u&R{)TA5j?W)_RiKY4Vv85h!x1I_7l{olQ%%r3KhyTk_3H<<^iocBPB&^vvF9 zm0?ilg6?=X>BbI4n1O$4dBAebN=GLh)GEX#Nn*z&<S9{|1FPSIrM>J&Fo?bhSnZQ~ ziP9s*>LbN4v84i<4uM-a1$gY5VRQgeTOhsgGG$wGGfMk3pJ=7+j5U@a8Pqe0odV8U zXa;yk54GarKO^bKq{t!lhI+;GOlb9iz5S-`(YAM}o<<SFfhfJ923-p*p2=ROUitxJ zB-pr9l4etq1~*fPev)VnP0j~&(GjGGz#3_VD}kcW>{_KIG<~>>E}UJC-j{#?X&lgu zWw1uh^?X~sXWG=J{Lqo&zN<#3$=XwWVNX6tp^jRbtKCOIk_)YWG+J37A{$MIfT;)z zbg@U#p4P#Uu5Q5B1ISs5WKH?xNJEF^)>R#xq5>MLG)YsS_G`ZeAeS`dH7}W16)Ie& zbv)66`)Er}?9HpW>2{LN9{|PC4vmMC^{PoQByHuhz32<DQ%oM}z*plmSz?CBaq^y( zUv9F`O80)BK!${7SW2Umih0_ObQ3qL@q3*SnjA3+8HL2zum+W<8J^bKwnpP@ru0rQ zN_4C|H&(g^!e5hgG3-d6nCD#0*mOW&`Ef3m%4!o~FQ?KjchHcN!;(cz58OghOE6q% zOlKoku!FGSZ0B$Izy0S$X~J8?R0YD%@GGbhnle2_DqF(Jd2Id*zh%}EFsP#>^jcKn z5T8}@m3{XDGX<#!!0gZAxI19vzceL8m)uC7K`TiEhf!G=My{pa@~luhz-t>0p*0sZ zP>Ts{-4YK_dYvHU@jecjB>gR#@c~UE<sDZUQFx|2H0#(~#!dS)&ES+tzbJ{XHA$wx zq8NC;IG?1`iWGyB8rprodR1C=svhmwAHHeQ+j^~U3ldyve)}vyh-;Y9S}N8=+VFZz zui_pH0)@u(tM?=!;hCa1V4`7{_9+kmmQ_3bQIFdtPd0tv-T0b9dvFNka|fOw=`<tv zPiaPdtSP1@03y=|+x%ONY9G^1bL5n2K<5}}lJR85UZo589({#1OYozX?+)7K9t+d8 zgVCmWVfM)~tY`No#nn3d6eJ0*(QHS_@!<4Y4~*cNB7&yU;h=oHt9}JY`IzaS%gqV_ zQ=vrPqn*!(y#ColtajD{$2d_RK{DQ=DHY7|mN5|Iq4VYIexRoKE7tg-Z%A~Xh;E;d z3Q4;xe01TbI1lbk-%3ER%EHd|^ZRZHh{P_Q=Dr2wU(j-0Kc-YXFq{OMhtg8f-yfEK z4)UQhs+W93pl(P%|7lX9dBAys>2Xc|Y+YTD#`^7s)$wxmR5Ip_Ee$iZQK8Kd&Kf(r z;(_!*)V}{?#Q<}Q7xk&@0*#K7)QfUj7U#{mhrHimOtywzUjNp-dcD^vML-LrSlBAN z(mfwRTE(&aW{o3=KKH(vyai~n{Cw-N6&Cp}S-*k=i(=v!!^$7`Av&?B`mep#Z}pF9 zMoSTIhQCag`D9OCu9d^EvGgmXy_{|DXRHEnGtkK4)ym!4m#_Kt)<7ByK#itkA!@Tq z$Ze0u@AX^8A*H&aCfOTR$iK7R>hap<HTTv;5@j*JDr$dw5c}A#e$;gjCUh%F8a6U( z-hMaMY&HU7-0db>SWYD9yotTUNiwPayy}!#(R1wX)sJT`)jJ1mQSUgUK9_>JglKHz z0R25V6RN36K{8wcGyWK>9{T%@#Dk!gZk?1S1vE*s6Zl@3CVFu0_H>WuG7Ad1u^jQ^ zz<<T_S9$UsS~#FLW`ph7Z$nA9QN6W6t!~UWrUCunH2_>ImfOoTm7PCE8TI9j7GdpG zD*G_Ek43hKUd-`Hc(rc$?wstH{MWm%fZer_s>l&RROAN+${N)B;YrL^)a<T54<1*E zB{6lg@CG{NniaD}cdL~*2;t~UG)wje>c)W?hK_S;VkiROmEt9Zh@~eHU$)AuDHjUv z1io8z-0}NT_AJcr&G&CNTxzUBkF-L9=Iwk<BQno~P%*aL=vBgc{rf&9=CM3!*Vk}^ z0G^}kQ`PLoYL`O~1M?0irYf;tmUP0I`R=&rhA!;|Mook(%kLk1f1srcoR588@ig>X z8s^c{mb?eH^M9xEoHvVgBUUDgf4#H6svY_>>gBB;A?^pmyYKJ8LVCInMzS|e&NYaa zbw>R0Z;I`@AaM)tNV#jU;91QVH!%ev9=}$%(TyO`>h1>)S*40c;ii%}<DR#X`Rr?e z^s?XLDO`g!&U}>8SdRwgo>lv(T%(`9HO)=Y<Monhh^(!?G(-?Fx#WwW4UaW>?Z#eb zcyAk|w6Ld9zUi&MCQJ|TT+%i_rdNGxNM=y<EV44Fag<V+a1^+iVGmB<c%T`iw^kf6 zB)KW-a)O77Xzp4=#2)lu?2NwmGpL+puX%^1H1gcrhlYqE4;f~#VlUQP$9<L$yb5`0 z(j<?Gke&x}rEStbzfY5EFAvo-3*4Gc$5M>u+AK={Z=)Yl5&LtglHlI7j(Ih~#_?X6 z=fXLWH>a^WnQGusCaBXQutLZ4A3K*9k*y8Grgm#Q^<^)!x<Vd@z7pEw@S8ZSn+oo_ zj~a~Gv#yhfNm1+<Fwv@{<hUUl-iaFO3F(R*?mQE?8lv*~+||W__q%1WR?dYUGS8M> zMZ+4eJQUZBaP{WCeH;!I@WEZ7v1%VzoE^w_B#uD<afOxG+}JIQte9g^tPgigXIq_s zZIh7Y<48?$zW3*D#L0?>Q0?j)s(BY5mHFkce131$iuB<<AKN-tZ*h;D+u-|ex}~^L zZ@oo%@N>nMCoew-Lbw6l4O<EwZ~y*&9I|FTR35!JHNYAtx1CaqvTbt_ja2#z;`5mv z-6*@++9&%UqVY;_eX{smPFa8wFhTd<vCz&Pf|>q9(Ho2D-jFEj%BHycq@xAIad;s` zEatdezq(gRpCWeSSl5RyZfA;_crl6v!g=wv`f$lLUA;xonSYiancI0T$&Jr7!wO&c z6M7|6;mKAjEHV|neRpEHFE0O{InR4`L6p$iW+C3yYI<*>Eqlpx{Cv8kC8}LA7u91L zmO#7ySD`-7?4^%bH_p<C1w@YVtm2EB96;#y<%|?pi!~8x$Y~&q&;tTI$5|RM4xv-2 zjMmzESLWdveR`R+Nl_6)-x1Dr`(TxK2T6kIxAnMzb48W_Fbm!ePQU<3Y;2Om!e5h} zup}iI+zQg_2V_O`(1a-qgPKR}0^)Tn2`TDX*uufKUKKN$$QzdGbMj0kb-lUTR!N9O z_2(#I=#`d8UL63E6IGU^<|Q;nc%7G>h);$c6<Iu6i?(u*T1#FVg{E&EKw=2VLiVw# za!)A2qksC~Dl=r%N5?a+n}}89r|#9Eh!a@mZ6}`?aE^{seX4R1lLVt`YZ8lL6Wc;_ z22n2_ct_T!m^tPi^+FVvD#&)W(m~(0EJfxBxjF<>SQ%hQf8sDpUxjq5S0=~mGhWR2 z&j$I@yEJq3+AEC$AgfhHAKSuay6J>P;E{92dkad}`7R&6Any6(*4fcqnMX;FV@(YS zMI-+yb|y<%I~yIfWyB{`i?(=Ko)4<L;L;8fUHyOZQjf!@Nm}%yE>u7Nuq-SVD`UG2 zQ3X~oQ+X+sk3bn#3jH||6_OmS&UMPilG)0=L<UBJiC>GSC#DG`+NwOPM;*?g^?c?G zB9JuJ4rgP|T&rsvxKmZ~CCLgSG+_mIh&*1Qk5!ysk-kfj(c<9>uGm1>s%KcRx#V0p zNaM=Jr69mwP|=wR-c&G~=N~8S802(bkf4RZBBtX9(f2%W|B$|lOjfsEa7USuZ`I7q zJ6d7B*xM~L;epGhVeqWFI^+;i%BL=Y-fw8qT%z_u{=;XjRH<d9VKo3X#pDzy@%x0y zIKB<6v(?9mBK8TUV6vk;rA21&5N#cXoh+-5^V6QC!T56y>)=Dq-}GU1nrB8(flqzZ z1!tVej{8gtdsWmHMLWpnRcg^2(FH7x9ZzT0bnoWyb(MJUPC<kINl}dbHB^`Y{NzoY zJIlCmB}-RWfkU6DDN^y_({&TW$1efVVtYvIBmG0jb*oi=fBa?T1KyRGBGYb~=dgZb zn<)A|yguvmrvXNqBywg!#rA!sxx22A4~|i)MVf2wuW()J_Th2mHa8Bcgc|8$pbiL- z&=D1C6r9}r$7;CzMkOn%8^iaSkg7cC1yz^v@{Ci2%5TkByz;uDxa|2wNJ|kmpm3>e z%Lbla&XWqC@q`-G17W7wB!uf~q83@pGPzwqpyi3IoLn<TrGz^^5hU8aO|hxtL0#mp z4SrNN?_uVhWAYx0FF|5eartCaYx~GDHbUQZ1eW@&`r#TQqDGF`B_S~j>}T1k?Y^S0 zk{WJKFCAv2ZZ!KPUkibsCltei6<&Q;4A=d7W<`a=O_O)Px4jEcmHoUNWEv2bVC9jS zl>`kF&6diAp)3hBB|lueFrV^FJOeEn4>tqojhM;EiLhv-c{0;k-whafmqheD_g8bI zsc}#)&R6beUD4;%?e=m>>se^s?0%Q$n)u`sBaV7P7{08HNxeKmgI|ut%3DqKC#Ta4 zW`->KyB)d8qwIxy!+*wbA7ur>#Z0q-ReG>4&X86Rr#q2UWVe!Y`vi0@JPoUm<Mr$x ztq9?+`auON$INF6K0*b(1}b}f88SsooU&kVgTg$BOBqR2#PZgeh0;V$AbL7c!Q8GU zZ6fcVR#ox0$RLd9lb_jWC2hU4H)BHY^Fwn?g*=#*QBQ#I$Y|*de<MqlZ<D!ikrqb# z;YP*2=W}A}N$0-R4=b}^SmLZeY$duh<Uw*=IAE1)8wt_k{ocQ7Dg>ww$Pe0Zq3Q!F z#PaV9AE|$i_*O=KcH_`oY!b1t`y4A_k16()6mY7Xhyn@)L*eK??mhbcX_5q^IO7fE zDg?lGh<pc)-Z5S<dV14-wXuEXUn#7}lN4Baj>zKq2d0+N3EPMX`v?G$g~MBvHwcU} zRnRyu`YQFK42IKei@(n6t<|IEH81yGDY3drKKDBR{<9U4k)$sfrn8|0-84JVC!BUV zR)QbtoC_OlMSUC@z^2|6t={u-uJs}w_2OFfk84yEf@mVJe!-(;(O*eyKN=J*f@K!_ z1SbKUp4(h>w7?Oamki|G@f1JsI(H%|5Yfk9gNB=ViEm(pf`IssXpWN#SQf_QbDyvh zkTWZ(TFyVJu62uvB-)A*S(Ef!>-#d&-<O;{=PwQ8F~wM|A^u`?_NlXVd&VkX+@>)? zOS_!CHhd|4d=_4Cx5~GFL%1N)^EetCYnH&BwYkPVkziJ#UzI{^mDfb;&rQ(zA{yL@ zlIIfogk4!g&dF@=t<<nIRR&KA%SrudRG0pEhI@Tv6||GY_0tn}Lgf34<~UYk^+&J` z5cv`?cN!%{TE^f5bT$?stOd=!;hFt8N#Z7k{riB(6Og!1rhulyHKr}jjjydwsugva z$gnCgLp25v^W7c~G_~J7kxew&Qv7ozuXYmmUa$O{3T}OjP=TcQVv^_xMby|yZV-G$ zKfh*rO;m1$GiXJk&Yo|ND8@S|`mv9p3>GG1M(2RrEDxzqvgAStieKBp3Y8>O?HGSp zXA_X`gs7IM!kSNKD+I8%6Cr6txQ8SwgPZxe_Z*>;4LK?JOH%wvrQl8lY@aD6LV;4R zuDS`4)foM<5Xzjynd^@go#=xB&xjBejJV9^DlEC&R$a9+bCc*0Yjxw*FRxcynPTl2 z9avhlv!?1<e>TBX^kb!1exKMcFSz@v#F{6ERuV_AkJMbHa&6LL^03HW?L)bt$0}7Q zAb^j<+brgyD(caP9w5qUOi(xJ>;%AX<pmc!WcT%|AP^z$NgQ}0tFD(&;R?T!BsXkI z(CWtb3p_H9)N`L#&Lddkx`FRfyrp?}++27IdO8FikvGRfM4m{B1V>)$mOK~DXL{GP z=C!0maHV(!=64-NsG^s_^HI(tE89t)BT9-TdWp$x{3KM0Yn(@Bm@-ch4d#<XI{O6m z;kTdLy^c_DoWO|Z4-0#r0r_?iY(;cf6#^PTWLJ?qSJ=mkl;r3HaH>=aWnf~6BPyD2 z#Q(DrWt+JMQ^s7OO7gz;F3B`tH)Uo7ar)jR>}$zxYbE8I>-_}_El8$tI6x94Im`P* zd%cvC`UK`w#U@vT7Lr6JBqj3u49RQ~0;VS7YeH<MU>*KTE**+2S><y6g+n`{o|-y- zcRJnL6+U?BD6iY-lI^}8%yIi5wJL4$+f@VZN;d)|tLO;WB?qD8%7Yo#%xKrMs?fw8 z)PF1R9R|2~TcXU9Td7iDrw>(RD+~eZ-%Cn$-*V8wJ4SWsh&oF$+~DO&m(3W>LKe<n z@OVa}R*l#H*gErfsQ$Q(pD|-Lvm9&oW-QrjY}qxokX^F0j-^7<SW~E(v5kFFB$OF@ zsD=_rHTES$cBzIGl?qW*z8=qS&kxTZaJK7QpX+nZ{l4$leKKrY*)9CbY%NE+tfKwk zf}+tw>B0cnN3*iWE#-L-?fqHiHxf@k_)8*leK+>`=+4>MUGP=O3j!!|e~7m#=pZ2# zJx>7DiSqrki{rC+%8luxRbL~CuE~dfdEO`Fvv)tI*8((KZ3&{L#Ad*&v$3AFF~9tt zjS!<t<$fja>v^Q8*}B9ZC3u(mM*V7a&#@{W-_PSn{|A%yq;u!_SR4m;u+F~^(tD7R zR7*b-dRM-mlMIX#GO8sE#t8DB!P#S>E03(g+F#GlVhV`zH1%KdR*C@<fZk7n`WfeY zo?!<*>v31q-a@<zaiZ0HIlm*7Egx!lA{7!{Ww;|tI@>?2J>6lLxuXi>gkZO@B+sZL zUM>wBy0OLa=d)UFIbH^HQv26sMH&f1;bE~i83zRn-&%-M8nxPzr6nRl`yrA|4bq;T zGA;Kj_gda$%-I>O6Z&)a$6a*#G48z{seOn<Q~f5ck>;;6*Jns{zAXWa+sD57%{u5P zeP`G1IkMag8TE&TEaL30w~$eAls@_B(pBGA{Rt8Iwe9znQtk(?W7-7qezG%O`3l~Q z)D-8RRoCWyF%`s%1|!KNffGUswIIXm%y7KJ#)Z&~yf3X19=`Yj0Dqr{|3jDl<8|r8 zqf1`nvU40->5@X9II(#o@#~G)yN`ow!bk!Ya@O0g&c;V8wh@T)j|pYIawYqjHIq9A z1NRdgi95WhdWsx+&sH^E`aiO?d3sVkQNG80e?<?$JlFcrc$&6=QC@!5*GaF)@y%f3 z^&Nl^xvfv6<gcSr7Gl$@UrBD1C{{F!=-?wq>H3bI($&P%_LdPw<8t%9Z$@2Ubp2ZH zO%~QK>YR13myJv`RCd4piJqGblM)%fAwo>Kb<FSUXKxukZ<TGP`+wl0=K&$RUvk#f zCXV!4&pf#ph17F77eD9aeYML~nbbAY^m(5p-YE!B9D?*M<+~0gwp!)goGSdwxZC3! z_=PTEScZ8`kbeiMQo#HhgczG8$qoLH)7&0Ix$N>A`(3!gjaG@K!@5OIeWei(Du(ah z;u>f?;}rh%;ovcD6C6o~1tN`y3J$7z4E=}kkqZfSpKVnIj|MGzh7J(*+#)z<rL^@X z$@hFLbS-bnm&qN373{X|J5*3{jWN>$@!G#5umNah>lJ4^>Ej-!&wp_dDEB9ayH2N# zx6v&CTF|Teyx`_Uw=bSgm1J<`*}4jJp*i{~*XkG3``+!9FCs`z6LwzdH)kv9$KsM@ z7n(wP%X;V-eV>X<OV|TUaqD!vN`Tznz4FzwpBBAs=D2s)r@1C`^ryr_CtFb^zUVar znLD5?L+GbxUS+6QRd`mJ%pCW_wqZ6b1?=d2eSfOL<jo^}0mCMu^M4fV93Ztyl&>Pz zlDuSpVdP%ZBTN@iZ+|^Hd+EqyYbl-7t6u$BlcvV(V`}}%vaWVgk$mhGp2T;KR7Q?$ z|4KKPE(bG|8l9DW{4Fa$_zCJ3p^tGQxb;fl#q#!J&)P4G7Z+OPTkQVMxhJMCQAVuw z8<o!+l&#XPo_LeEf|pD%k&jc{(z`|7l4<?eB>Tu${M;;>!N)A}<nOo1&--3-BHq3` zARh|3ci=Zqv?UR-|ImDg_*sJ*3)#+Herd6p=yz<y4G882L~dhN^h>LW=}r$7M~u&r z4-XDJ+!AjarPRLCz>F=XZ_9QJC~r;gY|DVq68~qx?Cu*u;Gp)EbRTg68_m*?ifhMX z&q1|$bn&P2O4|)Do|(4VSQ6%2&!w|P|ASz}H05SyMg9Pi^Q|(kIbzO4x#l-0HPL}L zUY1JdrK<oYmH7xN*ZGulqjDBC$isQk#ntZZjzL4-6Xoh-lX<P^bnju4$RpBrqVM>- zxg423E%E`mPB(Pu{#nF7ve*(qem?|ra(4IQBezaI6?5gtfAYE6e0(h4OX>2rBPA7e z;orLx%v!vbWX6loX*_&12Q$}dX$+CPGizhix%=O&R2fIvcIlwlT-FcoDd;bQ{C}9l z!FGoSGs1D5Ef&&)+pRln1+g!!7*me%Nx@#Rh^|eG-FCjs;)x@NpS>+LI;6x=a*`V} zd&UovHtF^?Zj?mdw~&|S%1tMuJ1A1e#ig!5fKAA*9FC;w{9L*3`9|Lkk>=SSL(W;= zBBmXFUe6nM?O2tq<&`*yL5kFCj^q+W><?$4gNJ?H>f_}pr)RU93Xx)2?0joT-+v%C z=PUP)*milJiO}(dCGTGWcOI(aWGXo0A3mYv624xGweR;Ob&(NEe5ou?u;kfp8WFz8 z7InAqJVZRDd0bA3^x11xehDI-29X^9^ZE8d`ip$aSiDmA+sv2p`4XkM`f6R9*7>sU zAGJ?O=eQ#3w_Q&BsHpdwl?wL7XVI~Mg{Z5qWXIjz8KC6q?BWVU<R9hM+%dCLv)wd~ z`*hkPXYpuF%N4a7vs%R`AHVClF^h86m!Y-u?s{*$xMlvRG&arxUPZ}t^psB{VgbnP zf4<^7Q$Exz76}oF=18(a*FRe9Ke4?iHNgDkyL;{ph-no~<4ApZv4hT)Ps^!gt$nV6 z5P0W5?57sCQfE7e$9qV!v=mVBP?23-NoTsGZtzS`U1@hV!RpFVp3@y2-H|z84VC++ z9j=l5`-<!zRtyvxMtrGVbeDY+Ha<C)6J~Q=|J<9ov2)2PSoVqDKfO?|FIn>Xo-=w1 z*FOmpww)Sy<0AXNop=!!n11c@=^uBV$NyXVZ22k0UE}29(3I89y>cee-zIy{so*Cm z)CG|T8jXX;jlyRX9OO6dy%~I&uY2wtX620mumE%%hJVU6eT6luIXTeW@O8pKX3xJp zgGU=|jU$iy9(i@VF=90in*$Xj>jo{ozU%P&$MJ`LomJ;wf2e4_;}rU?W#xL8!!4a? z*rxD}RPZ+U@}eEOYhUgQpL1u-!scL@d;Y(_6Cc{%^SMgl*+DV;zy2HZI<*CiJDV=h zpg4o)@$ff^VxCoQF8EYkoXKSVTF0I(Z&94XKA*t3RMm<q1se>6FJd%r>W|fR`N!@c zeJ*Nu+BW<OOm<^xYUdDYJ4V7ReRu4*Gi9qxRMO-lWdv(K<&lcrKjnJ(<(`I+C%t=e z7Ks(|z6`bAJwN;BUYXY~i`q#?$3TQMpUnFu@A6#oy)9o5;@+>?sX5|h=I~h2+2GML z>%p{){RP(z-%}M`%~prPx+s%OsI!BX0F713PFDX?CE0uMjUnIEDpfkThk&5GVYYjl zmOADP6yKP4>)cny5;?K|?G3AZ(?eY&gGSvF&GSZy;~zq<uWyWbg<n15AW7P?O9(Mr zsq%l-SkR*FLVDO=nw%dA^RsR89<H<3=q!6UNSO<{UgaQ_X7%OyKTD6SveiZHgWBJ2 zJRI1z+}cyS+_pz&KGWb+{!d5an-osBl*3M1+H4`<r?Z(CW-eWC%lfI~5eCw)TZs`f zmr6*D(dkqDPv2iR((uhpzs~-{R!-*fSNpZP`_$7zOkRT;*&a*tAGCB{EVjGod}rwo z=yk@_BWjLf+p*6+@p_gg+5eSg>aQZNi|_wd`*6TTIY;aFOk{h9tHUGZGfv83vJZCv zervu1UEe0JXQ*9eE`^+WA=!&Fc(sXst5nJo=~cSE!Flp2n_`Yqx^Z16O>TA!-K)s{ z>zne0VLHcD$=aAc_h5i^ee(6TVGT~_PfrqN|JFanY`xCWxh~02R*n+|$cF~K9eUtd zvVHbLQ9>pqhsNn%|CS#?b-DQAYsp5~vBcR8<-FZnf0jl@gPtRATMhDGl851D4XP{c zGG(j`yv`OWN%B7mI=DsA=*5O$)+23A|1p2LKIx2{w1ZU<j%p5DpYi)Ik3alxt=cn# zdTY0sFXCYSkZ4)pL8CuJ@hE<~7MoINI_Z`jG|Dh81rJh`KHgeOeGpF;vo}ia$q8Rv zyu8{Y59}Z%P75o!i4y&c<P|#AJ+;#gV@f0%k)k_^)PtlPKZl;W%vOj1x`d4&{UX8D zi+n|^n`|in3~_j}PJWBqz3;U)MzA75+Ux02{ryo@7fkzQ4!?F?7isTdD8FPbY)kt2 z<yqG%X?>L)UCdSa$3q@)WJo?&^)dh6iVtA#xDDt8ll`1z1JzQw&-^aKKt-Fq(>i-T z@ZoPl7UBBfocK$M?SZ`Y%=3<^#A_CI0XibjQ)X%u?mj8kdxGo=&M8&K)hBDuDWzRH zuBExdst}!VMcMHnxOje|<OVBIiCdD5PCTggDX8qZELH9Yughe-E-NI2E9Hf*GJg>1 za@HtaZuegmy*r|}&mc2>z6B=lGj&5+$d*X1GE;WOb3##=eKKvq2#xoo%;;Jry%ERH zw#m$DwSoZS9gTDM!IiY28|~f>0vV+3oRP;XKP$;t^#jn6tk6dR%-wFEwzJ;t5-zJ= zyQ@*ZNAh%3R*ZM)u0TSY<{2V7(9ue&6$w|7UP*IqvcP)=T8JE_BuVy@;Tql$Y&a`H z{02pkph`b^mckIvr@)o@HI(f`lTyoL4+wxJ<?o*fsSX;RN)Zs5OG{K|?ZsbWpH<t- z(QzU4%GdL3%#$mz(H)AE;J~h+wU3g3p?Ebn32E8YgFWAWj?_uJEB%k3v{Ga%lCwB+ zvqK@HPO`D7$1L<_^IBSrM=xP0Gc>Zs`b6vz4LOu?UY3GY;pF9AHubZkA;KfLbITBH z(6ZH&Pj%U@N~NM7i7=w^aH<7W01T>1P+4-lPsyk`4t#%bHDS9o<5CDiD%OrF@{8qZ z;7z<2bRKd{WhPOnhlur3ZI_)+6%bQu<r>-97`%+i-WNi|alDgFmpS-AQ>u(zQJ3W6 z5I)4?aQyptb<4nr0X1zFiO%WL3CZVwY4XJfG!Nd)>!06q^>cD<Ny45zE2x`JZK8J$ z%YC*xo4hy1HsU&A#HV$&C<t}t>B;`O0;7?VB<957iGK%;;6F1?7d4tzvMj~gcnEWk z5|O7pw+1R8JvE(*$|G#sgDwu5r&tWpT9Tj!9}M#Jo_?Lzv_{f=Hga|zD%RW7EtDOW zL8<bs3EN<x90^e69XHb^yW2Et$6MQ<ApeKjZM-I4ux&I#2UiIxiKY)f$-XE{nIS0| zCfa22tR3<vJNHrwYz%`BAFDJyjqs~Q+8;c)>iyNO->?OC+-#@C2WPIc?_Yhb_iWST z^8M71Gc{nc$H7yHvy(=eW+_@!U&;KP=?Ih9d@I#C5>|X`54@G?v_=ORc2?3QY{CBT zrDA`no#q~#Z1)ZeamOl#g!-{0vWMT98eWolC<lM!_>8#Zgzc42+IRz{R+#n>U1Vcc zBK{Ev+szi#`r?)q90!+$lqQ%0Lss#ffA6|yUN-Cz-jCGzRA4jzc>EQ;`t-4ixS!5; z&sL(dzK&awzHL<ND7oF%Ui97dS<=z)@$B6R^X;wgI;odOeHc~eJadyaVrI<(k7k5B z+H1ioi%cSiO`7bmJCy-8dzjkjXN#T37F}&W4Y#$$aJjp?jHj2;KQWGH3q%umFwuNU zs;8=zR4mI%)sik`Rx+n`&d$bsS{n?DT%1^)Ox_vM;GTYXo9FBDeD&t5xR1XBGUmOb z*ZZ`yLTRN(8QS*wqX6>^;p+y!7}ZwvL&V4>Rr)Q}(|pLy=+<xN(Wd}_wufLJO}=M$ z9L?dnrs{bd@~2Mov7@<IgeWd|*1!A+_J$bVa17T4U|uexBiMrZL+GnJ>~#=Y!p3~2 zh5g48`bpEv(8jJV!y8=jx8@>eEB&_zCK!7+82t-`s&Eo07B`{|FI?V*uUD;_1vNGj zc0m&SY;nm3)|;L>@J=oAW9_+R(wHmm9hEjsan!1lG(JL7(upGJL<#viX<9hMh-ywB zQGGQelt)6iv7m+vhd$HLKUqQ?5c{zc_nzQCz(1a+ZBEX2x13D5GMVy1Sh9}~zp%C| zCud)5K2u~R1>?I9;fphYpNR0H^-qZ46I9o`n4uEMt>K4Pc<3k=)QwLGT1Ho_(eH9a zc76#PNbpq_cADyxX6JOdQMDl^y(vGvIVRoR8aK;wxT?+cXJb~mA|JqmK6>foru6>F zjKPhJ7CQwkZRH!Uaoa^Ks4iRO(h!<{6MdJ4)Avwo7{X1H<NK=I%_Gehf5z=wiTm1< zwJe#vTD9++>d90QTx*~pje!5k6)}&=dgz_~(~t%8*$Kq4V5#6cHrDPe$_+sH5l{yx zLQN$621RJY75AEijilm6xVTG5R&4$mF-YdAN2<zFQ6EUSlpMFvp=)0WXAhr^Q;@nc z6m#A1*7ZiF!Hg@`I|=SUfZI}qzLW4JkI^?)&us&mdOp{kZ;6r^PJ9|ROog=j7LI9= z;}Ue;cq;c~Z^ko293~NU74(T8f|gM5KlzvvPf7pfYahMidYf`1?L|lYJ!V+gEiTH1 z8u)Riyh+6UCclz_^vO@Yl%IUdfKS0jx!T&Z1<!-%Emq#fGJ2c8ca;=JSIaN57xh!j zn*@NuWq7MWoY&~BnBTe8PYT=&4t}JH1(JfO%WyM3W(CBoQH3^Lg$^y4sxu3CYN7|% z^drgsgmuYru_Bl5g8tqDt9k5r4}#}vYv>AH1F^$=+;0NjgNI!pMEi{1=rg(_Y7xRl z0cTx>9!z43=hU|C?il?_`7Raxa}z93mHGLZ5%Uu}eD-8cGAfEHaGP{%lPxqdgeq_? zIEpI9NDF^U1*bvWo-j2oG8Nl=CO)tj-{-NZmMC4#`G#^bmn;ESL=FdFd;!dMJ`WwY zEHDCM7s>bz5F1Xw|G304JbK6Ww|)*4zQqc;6;o<tTy~2t4e-b*G}J2^s)8lpLc%@* z@j=$^ZVH*!1*Mt|#7PkEPsT1Rhk8j@+|;&K^ut5|n5)!e6%uw30KW5ak;{kbb8Ljv zEBfqlZ@Ji2aPR66w$3iGC#aHfRMbrkC+v?+;h~??(Cq}+c{Zkih2J0}`U&`VKt%$& zNQ;AwQpI2J!Cfu5TXIxXOL+e{7ZXFk=F?EouF#(ZR8BQ2#}$9cuB24DXf!3Ve!9}i zqq6Z&jTGJE69qd>Lv-=bDSX^vHlmw_?;xOWgZLSO#x}3I$bC(wkBoTz1>2)`XY9{C z5xT*+H;TtYEQ5#;9%h(@=dkaMkrdvc?*l#xOKSMD<P08zwA%b&Hf`Sm1rr5eifFh? zAiA53Stp=nn(id^J&1ggvtD1xlfWJPcr@ZO_wTgG0tGkiii#c;$^>_=joG4N!l?Qm zc{mikPJc?2^cp));yjQ{U+=2NeU(b-L*)aQr#w_Q0nGvNgVg#}3T}#>wO=F0_99N{ zw1sTJBOW?_nv03&JuD-jyZJE7b3$Gp9$BIr(wd6xF3NvnVIQL(yE$aPbHzq2W9mR5 z?;7X|8K13=Z%|GTta)^;zOn$sZwpsHxFmER0}Jda$aCgl*0}Hn{&9|U)5HAo))LIk z`j9{2by=}BZ-;O-!8^~1`Ob!RgZR4?=_$T~MC_ATZ-vLX_f|>Rl+`m;CRKlfa0|3* zhi3E;4}O-={G67;V%)70y5N2cCu@)0Not&xY4J;YxUh_&Q!x27Oa}!X>56aSHg%V! z^qJ(FTi~XLu(=Gkw%?E5n3Nfs)W-49!%xu{DDW*1{Qv-X?$7Ujjg<?Bw~-$9I=nFY zB9-2T%jKbqhR~I4)OiBlnTv}5)A;Y)b+x~-7kjXz8W1a6;qMXm)D=<7MOV5Cxq|o* zGWJ2B|EXiGM(`)w%EZ&<J`Q{0IPRn8>e#LKScn2w*a~0Jt36UHF3!qYrWP4;B`w2b zhP@91@VS@>9{L3faeEoM!i6gZI<6RZxUMU#E~5`ERDKG4;vrik9gB0x@6eq=d6V(R zERl<`%_l-a=GfR8Rm^Q3cVeyZoNUp54!CoL9X({!Eed>XhnV`ZuFbRi{g~*b%bh;| zD*rn4MBQy(AR*$dQMW;K9}kZ4qjhxka2tv*N#ni$;YZn6ZcT5M8qsMI7ssn|41xEP z;OpdvJcqu<NY!l;mbWMFzVgfY&saW)&*LFJyYhz6@U3N>x$w*87Mtf2P(?Cgo1lE^ zM*ntSkkrc1*>+bbz=z!?`%m&sU;jIS+X=K{%D!(7RQVjqr=VIufvH+~ymd%q$l$TH z7cZ$01OcUM(z%LZ^)OI3NEjsmFyrs->@UX8*8G(<J3Nv7tBB2G45992fXm?X3^;HP zFy<pp(^ZRwUkPKacfgY3R3Oash5XiV+6EH5CRs~DyjT{%@!)3&_moWgRG*oX+HeD8 z0O$Jp;E{(0S~(|!aqJBtbu!Sbfgk0H?5*puFxx-TF@)d`g?DwjJWCOk!&`rQtwe%^ z03EFYRbE(YW3$({hdlhXax^p1HwX|S7hXX*JX-xK=r(DdhXcrf5*FC*9j{UKnb4?u z4N_W;IiZwD0>tCkh(p#Oc5-VKJ4t%&k=dX1?2P&rC?mw}1&6FCjVX-ATr&eE!(Pz| z`Acd#ZLxg&D58=q0AnK#6!cb^8QclOO|T#^D(c%ZwtHjZVSJp=0Jhc@UBZW`uo0bh z@sV3^vQ}@t=U>BXqgocymHTIwAJ^4VcOvHkFj7q&47WS@EefhuwgrA8Mcq+&=b|#1 zc)r4wKm9NmTM_&Ei=29{wlv-Xxy~!jJn_CRS27Q{W&0M@pOEwN+k1)dokc|KrveDd zbYUvL^B{yRjK4=k7*iqeAq23DTe6=L2~|M<7mEOZ?TQm6#FHVD0Pfqe&_$|%v@=rw zQ@Wb7`nYb~St>+$_KiO77z+TzvLdUN1r^BvoR502IBJ%qFgJwjBf*IjARCN(&z^U< zZ*u?#O!DrvFAGXjAnrH-ad^<{-AvAoSZDgN;@BtGs43e%T+y<?PE!G}jPjFz7jj?0 zmM~<q^JPau*#?hY+UsNsL8}j;q+Ayq3>MYqK7n-$!oD7!gNt83Kt>7gqxk|8<k@<` zrW>I|76pC=5WYh=R(!?bX8h-Ge3<UQ=gLrpoeE0Y4uX_|04+W~2z5AMKDp@u>nCGH zx4_7oUmvVs)18I)Qr>+cFCFhdid=*EN%0~5Cy6ipg?n+R*6t4@@@9jf!nBjkZ=OpF ze-}Kl43>tzn|*GR#zHRPgqbYlXLF*@&NT+1QX)T=65P9=>wO!-GqQf%gnSmSTl$P$ z9{zd!4fzE8hqMKE8RsGlfdIr!m|y?^0GfgT6u`pb1pwqW071&yaoMd2NKy6UJzP%v z|10sO$*Qd|Qs7F5tB?2Am%qIEe<VJI<0Q+<SH)xql?@OXiEO*;>L>ah-5sga*CyZY zTceY)9uI?0H_;czA5hxU<QyJrw&LXa2R&E~tw~s!(LNjLi=nnql(Z7}W#fbQFKEyM zYkFhBGZ==b#>xJsx)0qfMTa|%PwGGZufms%v<#lw>!awwJ9_cq=aH(zHP2-O2noFK zDjLDTPva21-0SPRfv1fZDuW!w<2vd5?DzY&;+|!;Jo&jWRGJXy|8EJw4U)=R)_nH# z_YZ!1`nJJh8LZU|C_-AtnuV++2eu!Tb9wQ6>+gn^{LMpwAYtO+>B?ML)H;MFLU@GW zg>33C@)N*=OtFhW<${(;fhPiY!6oCs_m=^x$}CeUZ%5+WRj#Z62!!V5rD)*R=qUuW zq+*)kr>YNG>nCD3jEsSuP9AHCp!sWd?;`zk9LL3Wc>?6A`5PX6WxydX0qRGHw~p7x zn*$akR=zMT=+iB^x+DNNw}(o$jOC~;6h)2)E!>Xzba&xS+^^4P9qw(ZEwU3Oj^>#r z@2Ora$=Ls8v6OXC{d3t3&*0DgTg-^h6-CiU7Y~fa>?nL?dBI=qR#jAgsjhwe<x35> zYg_$m?W6JFulJfhRe!zT^6Sgj2RyjO61PL*+)`c7p6a0b{{3G=tUsA*e0wzNc}^>Q zEGFXH<C*VYY^2^MYka@=K<sCq(uazgy)|0^7qhRkw#IwkI#SO`W%X0+^qzv{V=wmz zJaZSa*!tz*x_?@LTl@T&&rVGX=#b`QBxD=1(wTUrl+-1AacQNSkfOQTqjWQ5wO6&W zcC}BlacT7>sax}BzurX1&jG`Q+Mk1_zn6Z#A|tfchOBp;UmLblxwrP((cs(Kh{<jN z@;+Cu^Xp^YXYZ|#A4eqFPEb;`eoY44JpXGdu=3uo>5#^6zur*0|5xFgIRE=?%)-6j z@8W)MfBXHOhS<BoPuvx{G0RlBzcH6#@O|S0%XaVPJj=z;P9YS3eNgA~vgM^__lbLh zy2a_~NQG<t1DiSmzK6p;kLtAb%q&V;foe-s=-=-TDh|gQw*#Q*kLoi5Jf&-d2XRU) zq@Ky#<S35!qoKyCg)E&O+`ax?;Kk<eno=m)Xy)d7HRI1>Wm&&xUR=4WvM6z5$Cd-| zQ&$AcN_u8jChr?r6zUdN!RihGNCjb7#|%WMj%h<^yY%YVG1D%(a5O-Pe_wNF831`v zk%~tJ#Ew8eOJqj`Tu`jl?fR|Ph*?Qm7Vl%hqAYu=Vz^-3i-?=JW7>7p<1UhIY)<L+ zBW>`9+bhX&nLFh1I_!=*<N8_@xo~{a42MhDCEs#Vm$A`d1Gzw06gnwXdDdhc)e(Qf z@xyJ#F0$Gm=cMmB^7~#x+EzbXWF{PaFNyLqp)YF33(UfeU@^9)BI>j*r2p@u`B|r! z(9GnxL8PLO==*YLYT-*F@Q#>eT!6>i_$Rt>!|)J;;xA`jR<=h8B5#YFM+2^%N@DaU zu8cBq8%?`Ere}MIL-d`+)S-Z82t|&)&Xe=8)diM?PRa+!0f4Xm9lIncq&4c0Dzg=r zllh*YhzH2Y3YZnLIcn~}gov%lAOsg6KaWa+@k9Uu6!^C@!jnR3a1^)EfTV(IC5Tk! zDIx(e*3lJ7rm5*vr;KC=I#N;q7zJqNOy6YqtU~y&6sG^DGBAnS@efUZ@lH<wI3lTP zv18x}j)DUFPFIP(9fD~9Jaj0?v^oy}PD<8N0-I1E(w8L~S^>hOKDj$D+;)f=y*((9 zAl?PgWH7B9s8oXVAOS4?(puRE!ih^fJe}Y#F97K>YQA=8%v9e+&<yFoG1e*+;G^Kz zs>oHw;AxDb#0CK9GLRk|qlR*{cDuQ)c-G_Bxe7V#c6p_1BMF*$gdTP`57ZebJVGoM zUQx4<Z&eGET(1-5w9BoN-RQ1#3ecnp@HuXb?G^zb>7JDGUb=fa?KP+D?WjRd%F(pR zbwXU`c?&*~HH}kZ4&J_{pn46?Xjvz=-WyfTBW90C7$`Wis_@^{Sw#XFgbvr9^Fj*Q zH;um*>!T8PSG%Uz^*<mc^KLrt0Cv3&r9FB740&XX=9RF#j>O(QANuTTeOMP>A(L4{ zj^igFyuL_7?jxOrOHdR6ev9B;!Cezib*&6b%733{67*(a8IMO_<bGK&VCK&z(^d(E zNE-&Ct8?JHCiV!eBT85S>5|_{5Uw57V+v=64>ffm>pq8xDxij{f1mx&tX{F88?=s8 zz#cy@;EAn9mb<6PZ&Y_*=Y+6S9H+Jk05r^UTmvKWqaPnbXqQ!}V=Adwzkp8_-?9<U z4kc}bOua?B2nxWb4k|U9q*J8!Xa^(&&h?~^CGHM<q6Ub<+)Uf47jiT}vld^hFmXla z^AP4z<l(a<IGF&y2WChl3Nuef_!&d^JAvAv=ficmztJ@3m?lEhFAeTPPo!nW;fV|* zgdRZ3q^qh(_xQA%uTw+lb|vksJv{|CyFMP@J?b?^Q|cIWW1UNE8|*Rq6{b8Jn2=!- zSm$Y{68N?z%G5nzQ?kbdHis#;wh(dyfVN73{>!_|q*LHW(?sV+B7UaH-o{SVKcju~ z{|B2TTs>sE>vfjy7bHD)drt3>j4nFi5#$Ygf<eaJSuW;UbR#!^HH!KL&Pm+E9PP2b zFY4}k;DIR#Ri0u|B8+)g%PB^OLGRwq3rz9;x0oipzK0`!Bk`rI>X%J!gwV@QuKBl1 zr>hbPtC>-K+^2*?jaDPq-6M*D>+%g_iyEu{>Ai;E{&s$%Uw;RC4uJ3WIJz1Fxc{zS zn)D+;6}4L+q|I{3t=Bkv>vHJ!t{9J4!eD-iF3#n8;)v<I5m6n8ll}h8N=vxaOl@Ib zsR><mi||mA*&V_7Q-m2O+((da<5#20%@i<z<ew#{1WzE*Pl7Xn`T(K97$gYNh?QCi zjb;(rxRa#Q(%Uy7l(mlsD$3ACT{A&#J2Lu}PdaA>u=RMFEP;slo}C)8E`K8W(^o@) z5Nmu5{?Oyfrv=Gj0=l09cJsr!hvEQktgd!^x)=SYE!4nGs8Qdq%>aCF06u{0@9@p9 zY2!P%@CXBZD~Rc4#ge>4#Z*BfGIY`wI##J)A_&i*y3=eK%Jo-Zvlul=Oqq%(!8QVJ zaaDjGhrcEePLP$F6_VevZApf1x;rbL6;)|C`|ndi7LhJI34c<_(3GT;?L=+8=>pfT ziVDN7l8{nFKdhT&LfO9fadJz!=xILU$U@SUl}i{%#KR#Pz-HhjF;6avR#pn@k&s2( zEa3{ao9CkT9h!%L1u`2%_JW9J*8_WnkyntC8>LYgH)_O0<WCZl(h7^R1?`7~a}9Ku z+ykXFXO7)&p{5Y1HoiFq)C^<_Tw^AyT*k)4YOF*-TVbgwSMPa)ZZx<cN6>5eC~+8- z1F9=2`a*}p>-i$V7t`a1T}r4JXl1NpGUz%%3$SAfw8E3Tz=4a&aw}2k-dFW^3A(Xj z;H|KuK&D_F%#Q?S8w%6NNT`LJxjuH9>#XSy?FE2KTy*z!kyFsDxY@7}is?R8upgjT zBY}u+_-P~^E_|7S1mp}v{|f|BUWh?e5auV`>zcAt6}aLWuC-n24)BgNQpggivbTp^ z20`>s+Ld7-VxaO$5)!ELOh#B_!0KphgDe3H8)<rmAO!XY2{_VVj*Fo7CE+P6+(+_t z%>*QafE2I;^N=E5zpsZwLfoaWZQeW0u31l2vrD@%DH}I{9T49TstjZ}tqE(8z$4sT zfPy*|1m-X6Qy2Bry})y*o6Ww6K_J<6A~I5n9*+W|P}xs*VSZ9`(8IW>s?c4nf{q}3 z3<1+Wi-NWye%XQ%06=xU7RM6=NGy<Z`9P^`-V>P;YJdQQ&f!G~BXc4yVhmH5f^}E+ zO`-zDu{M+VO*Zx&-+T9PhF~iqj+>LW%|oPLDjYIIMsah5=|W^^RNGWS`z5Kz2f;E_ za^UF#I5At0h@Jqc0>jp4q(tuZ6dt8z)T4mCMqm^_hpPvE`MlG<1_&GIUZMCxXOS1A zim&^^`+{x`qcTK@x!u%b^iC0NCK$&{)UdxJ1qoi~M;JnjrK_cWf@ruJIKiS3p4@<O zuBbC3a2AOG&36!_?rfi1eC!<Ukb2lv18*>opRK75y8U4WEhF6iurb5dj{snmU7-Eb zv}G(40P}P&OZ_QljDC(gn}6ewJ#~<U##kVfjKKBRBHq2QBc#IjL8!ex2u*c3ybaNa z5>7$^`=)iXD9Fd#F%=cpP73*^b)ynfnK%25z#$c|Pm213MN+JzW>jXJYs!DG2J$~w zx~Am{yWvHRb@2g6251b>u4FY!CH_udvoGNA;3;SCBEqn(1T;+*{6sjc)|!kIE{~&C zqtG;|*^{OtWZJSzwpUG_FJi-osi9h?-gHA=r4l+@laDU5s*bD&g1e+egb;upH|Gd1 z+0FG@MKCIY;Gx-vh+<bCDMgY#p#d)Xe9*m{E9nniiv{Qrfl+0~;swnqrTaIF0oT|V z^@tG3t1vnW%BhV55U|<GKz`x*2y~J<H=bBFJjGypQ4dL>MXHK9B<vdl@HLw$P**9n z{gka4j2cr0QPS`@px#RqHQfX<dE`FZ`Z(<z&6lM~zr*DX@cpEVDHG|#iK54z<nnt< zhU^Hk>D2%YC0VGS#yybCPsLnAp4o42XChI$5Y}37v)czul|;KgDaEYdP|Bj2sbCbX z+6@h8R?GXm%#Q#c`?Mp2pFYkO#?U_92ndWRwY?m|V&Y>!`I{&C)6NFk^)SwkU%%<M zI^2s_N2_T%>77W}r1{4bO{vodN!ZD8)D)|c%qd5GseFkpM-_l&Tp@sWyW*>JE1?J= z<2lrruRXV(=HF7b2iKNytfL^LI;TP%yeuu4nfd@Wn^T+)dWg1!Y=5F*(>?D>CRRD% zW$a@N4%Jfrh(xIrrah@e1vkxqZs5m8zWIQWyPUR!q?aHH!qRhK!q^c4`eT(?9Q#2< zbDb`wV*bffs4wPu?2E$LVzMZvYqAvdrk3xVEhTG$hxx@5L;T4_-F!;<3-u$Fe+U9| zDF*{eksrJ?j@sf`#@KH|)tc>?ZimaTV@wqkyp@fLYAyo!ILFpDfv|)bA%qv1(Db+R z)YJV1DjJi(y=`Og7l`f|!Xt`wl{PDqyPNxY@bLXSIK7ih?3`DN_)qe2nMon&*jh!b zn`1v|cExY9!i)|lYDn^iZ6z`;fvJskQA6xilkUjv3|aa4yChNc6);|K7gh<CDA?Ts z0FE3oCaO@}=xYwb_<?(K&->x$s_h*4qo4?q9;JaE<X-czxZ?{{?IfD=L3ru}B8C91 z;Ie<2fVo3L?;ZN8=pDhDy0_zcVUUa}p@u?JiS?&!S`Clw&_CeYr~jdJ=u+|D)aGNH zj?ol^@6K8(WT%A;^oTu+j;%4NzLNO+1<Ing7r0L<5OZ`LoIVE{?lk+Ewk|F?7f^37 zqH-Rx86Sl%PZ@*my||)zv9~4<P|XilH45=tuUs3<pcZ(`-bYyE?c{FELlVs9IJiN; z|4tSgVm>{oG2pcfUrmEQeTgE440E<elVGh}SeQS07|$uu&TJ5S>+tfb5aIxkS$}B6 zRRT-tY4JNAJb&mCdIdYTJYr9WBh+7*e$8=MhS!lg1&7D%oa}eR<ChhKRFjOSm2gET z5bE{Hx%C+b16(0^AZB0r-V>i@KRK!xeC8e~7>}_;7SKNR!LPZRd*MRwiCr}*j{(Ln zIx!5r8ebg;7YNwT(_(nJ?(F!;frSCsL@yH3;zE4!GPt5}%UjE<qelkgAe2qAogAd% z!`%=C@zYg;(@BPx;dLRTUFebhprizYWO2ORQCLGA%;!FQj6HHk3*7MOxUk%B{7Gnm zj5970(LFEhCVk7X2er2SbS7CZ2GyD_IDwLm#~i}K<%~d*t<bP5eug%n<~Ab^scJY6 zmI3chl%XCBp-Pg#?wV7@2H|Ujq7%V8Z<Y7Q$!lAyQ8lO);1@Su#BK%P?=HW)c~3ll zIW74dsPl{;Q-<Po)oUMXVU$NPsIg0XrjO0$OeM0B7U=g+F?B;iQ`os|-C`W%<uV(C zQbuVD-S3u_$Ri74|A1MUA6kB*3xOoFBf?EX_%<hrIFNP7*~yQM@>our4nSk?gN+D$ zNgjp+6om^%)6(IGFKeM=KmN9uu*Ct9-@ra9mcqtJg?zdqeCLZL914*JKt#ZoPeZMB zqpG0p_8J1}503~1*Ic{cD=dI)5fC=`LemBXNt60dL*nRx%g&1}t#zL7*nVU|%a6X) z{A0gzS^-iN&0>P~hrM<JoMufnl_2XcqV{Wng@`ZJ7R~m{X%ICJKQ6*D3Lci#1uO?& z;L<v1nE)?zbxYi>?+J!8(K2`H8Xu_`bMD`luLBl>b#(|2E=(Sd@Z1X~02p}czQkSV z2AZ#k4E_i8Ev2>Olv@8_P7~jG_YMXUVuUQ%X;9n?`jIEDlADK|5gR(Va}xNklpn{! zJ_8ht{ktEm>)(%Gc`pb-M1CWgDIfjN)%_4#l`aLh&0J}LA~a7e1N?cM+fJpA?lX_9 z>e(la5>^fBSEc=iejeWo9@swgJHATb+C)5Ypi%cL#vi#2J7w}p<|=>nJ`>^RDl|&O z&rn~dwxVBBCR|<_@&I5w5^VEDTeyI3`#>E6euVaIlNTx`Dj730d+NO*$p!S>yB>Jz z%{LkrR)<qM^}FLAf;Y4XfGlA9=fxKw$@rVU@Z*!&x?^Yk7<h4KT$0%V5crV>hb&)y zAn9TZ9=f2LN<r*Dw&~Kkf+ns9UD#kizF9vs3nU2U#XPF|A?C;0Kn?#q^F#7E>Ca*4 zKRsyLST3jWfcTT*zlheqenSGqKX(1O0ved>LY{WOV*VYqm?*rk1CO}2$pfMG;QCd9 z?6p_BUQ#{?(Gico>nx?Rui${ESz88fZ_0#{-t1nxv=8q4USM|TwuTWrGD8q6Z=LTt zYnhCdlUTB$PV5EB)P0Xe56)O+$(db&Nx9G4<tRJdvA*U0@lc-DiRXz@hd((M=%0Vr zVK3@zahS?ivUev{?I-}9fL-|7Vr%HfaC5oImw3P#_8~K&;K*0c`zKt~SEW6dyz5U7 z+_5Qq{GmA6L1?djZkgbl+t8${_^Fy4y-Mf{2&jVlL1{~RdF4<?&$3@vrrd#KS)VdB zAhc6V*;{PVq7R@&MQ=Dg3V2=aR2*$rh0Ha&A`fxRIQlDOx?%f#>3tzuu3MvB>~2%( zQcA7PEl0@D(_cVZCLeS8>#;)FC%ndcr@HT)_#6HG?Xwr18AD=dZIg@BQZ_>qZ2Iui zb3(sQ{1=yVT41=l_|*1)uV*dxY+7ZMwh#h!8H2(Y;6lsn0}I4CheU!avRMIXBz=iw zg*BMxmRqR)R7NNLb3h6v<Q>M-EbM|Rt#+N#>%Yb@rq>;mxsa%xNB@%Vt2<=bY)L#t zRjTjdnriFVE8pz+ZU}_?3jqht7^>UtdC*a>VTE*8cG&j<Cb|zQdbzz+X%66LTCp?( zUy|M@j<8*Hj8t<Be{|@&T%VJ%vsDrisVY@wlh9^B+OY2Su!gWypfC{Xrsr<2azZte zu8t}N8Su|mS&Z6{9wE!~N*{|ZA1%`xqw5`MIO4TZR7NoM3<*r`N2bkIX<pgk%#u$E z{_4C7Z&qrfWZOt|IV3{}nTG&hm(Kn?)nL_QQpPYFfH}n)3{Wdi5V6VFdVD-$U8eln z=_OaUW59i;1hGF+Mm5tQBvZW8kEwP>9N-UAZ=atr`R#BVSZp6;>^fs;5;dg86gA09 zUC&J`$kfSDY9le<NiLf8%z2MZ?E(S`gQV8vXQSopNzY`XPt)MH1T%L-ajUG-G#y{~ zvAbIqa7NxviVkpYwISHya-RfM7AG4Ir;JIdZiDfVja-6h4(kKjH3d#ir4P~s@QnT@ z*bNk<=L6+m=<LF9Y{{Uzn4Zn1xMuV3Pq7-+kPR6i0A1aI|8>wl!PQ99CNPze5juXD z@%r483ojd#szfbdPg){g`IZ<{8D9V%n0C;2f?eA0S(T#Oh7`da#EK}th+URK7RTmn zw%BpkzMI9&+K9x51CR2pIC`+xQ(?0?-g7DCcB2<UXM_r3V|HER2m)?mg(qTHx(}#E zM#}F;7ShY?<Zg|sVCwPX*P5dVGVq+1Y%<F4r^&mAujGFK+-y3zG-kfg<r_K&X}cpI z;`Nwj>Ry70OD^GDhc-MT2QIjSUB-mRU@Z+VqBf7?FHR*8uChj<3_ViPzBo1@oMY_J zYZ0CmVae`@F1CX8;h5xP6;o|uV^GTOP$(aT6)|MWfywn@9tt|dG-=s(Czp=7jiuoi zsLhv{jGtoi&CymyVs0Toj5Sf9b58&jr~Hf5Zx)RJW|aN29QqZa#UgBWWL+?g>MJie z^;Cys9qwCbA#F}iN@zMq5Irh$Xr?az35Uv>NyQR@p#*<eTjovJ>4oHVyTs!{_ygn* zmacl}t5~Hdr6=8LpU!04=O~AwpPW=}gi1(%eti=eXH{8ny2f*l^>swAl}@<5h{?3D zRPNU_a}j~Nr!J>}Rog8cP1R4FZjG&q%Gz7iO8cp~VnPX5hHSM=1hj8_gvzPPAoqq^ zI6biYNzj?Eh`Njd_#a1#7j#rCSvT|<8EM3LPz4~*rrNXBq^M%OCXf_tqzBzcu+HXp zc(_CS%qpSruS#@)n0w9@p%OtgsEDS1>V~+OeNU5(JmXTanONcxnA-fI9$q@#R1ElT zsOG$64`wS^OXw6$Z{8^ISj*MZ>W&QdNcfl)AQo{f5TJ?Wd9ieE`HJ1yF`xaiWm>rU z5>f!`-IF##CNVE7_iQE^7a?=AZ~;|V-!Ja##`>+;EZM8qg1w(lz2Zqo_?$Mjc1DOG z0%C-SSuozV`VxEax|o}W%}3<euV$a;($Sg)x-efelW9{YcUn(=f>;2U>_)8-Ilc<h z`9nauydB;7b9W$|Y}LB13B7Y*JxvQ__%KM?54vq`y+9tEE+QRz)SvXdu>V#@t2U8% zUbp8TGDn6nRB~1Lc8%v!?~W(gswuK8Ng37VJikYrI0l47o)<CS9G`H2*c{Y}Ip+vW z&PqVOJ+Me7gYL3uH<e8-uaGbYAJh2&=xpst$VKzNo|A2^?VbFpbj*lAKEaVqm<QOT zBnU0Ckbr#1wg6vFCrDW2_L@<Lm9v%;?m&G=7RZ=)q9=cJ30j;=G>P?9cyTwu#xr#< za~s0nGIy^V*FqMaTtWZZnYyj$Aob)#-X$;Tc1=LpT7-tDaZ1)b4mRNhW5@5CPFn2B z(?af@H?4M)=bTJb?9nJmWIdIhZ=@gYP9r{^)A<VRiZqS1EW4EcWY+Q-)JQNBA>a<s z)`nrjf=LL!=f6Uu2a5ORn0%b}aJ_0Rw@iks=BXJn_zCp@S5iv7O+xsY1}3N~YWKfo zG>tfq?R8)Rr<}m}A_n$+Oj`wnwU|_;AoU`DO>K>y?gwR0W`ydOLs*#jK)r`&_kJfo z_X!S<K$cwn5dLJq5ww0*@)ml@MibWp`Ytm2<jcTrWJ%J|loG|?)b5?b(zdVnSc<cZ zlNzp_`F8&OiiFj`N!RN{a$M2Hk+acr#?742tRE_G<t`viyPR0!yP(n%FC#4R;SbF} zBY^`7NTRI4j}$!%qQF_C^)YS3I|8(>`boshaiWz#=u<*_g}<daF1+G`-H6jgq%kH& z`-*T(r*euuFwYfo@1Q%?v5(krLqN+GiF3GAIPl3gJ8<$t+5J7p#slH#i+qFcD7xaq zmyMBCzs;;rzalCHe*{S^Se@?IIyi@LkMdd_|9EXZdi+8~sklw*;m04DCVM_-9Z^); z#Zou63Xt4nC>{QRFp9Uk{O#iSsg&D5O#Bk!K&+mkl(dt%ikfFF>-Nlc|8LdZz2B*K zA~WDyd810->rw76O@|C|rzFj-1XRep#&>@<Q_Yqdu5Kj{&E#r)^3pz8C;P7c^ed#) zU)zx3g@njgcd&cy7IwX^H(|_wp6T8$+xR|ZyZAf+>>NZOK;I}Fu9Mx-3!8YXkg zmgu@kfO_^0E4!5ZU?aIb9U8}i&sUM_tCAU#MhQb^?i5o77aD*}6R<+6A8r*NzA4h7 z$U{9!bzu6Am;&A}zTc9G=O&FFGe^adj<H_glq?GjQ%q!#^OKmH{w#$@se)lhD>BSl zHBsvcK7sZmku9F?D{eiTcVeTAp{hG4ifXK@%VX8pk34@H(YC!m5f!e=JRq6a?T}5c z!WopI!kGJ32uPJ6rnWXy{E1Xpb+aEq@JITK9M{SKmf#7t1&f-MG?a3jk?f%ezu4C9 zXo|YPN)}LOT9Cz^*3!DIkn0vmGNCiQ?v^<}uj50Wc&wngG;(*p>1cu(v-)}BVn+f` zGn#1)c<*%+>tb<Jt^!@rhAqA=C>*R~KvE>7>XxM>Oer-_Kqj%!nCm&OQnaZ5{8$PF zCaDSosFOS85M2>^sh5!{nO3$%eDbND0wTmZ3(28-cXqzH2_1P>M837<&kU!vM~n5) z12B|jXdksJi)?*PHi>LuZGE@BjfLP5m;p*X+v(QK@C|sSH#wsSbqaugTg3n|U3Ar6 zdQXD&L#cZ*g4bm%_D5!9F8ACj>#b+n;$(XT?2$1WGDei!=0kaJ6O!X=drR~VDGJ+P z*F&;k_E|AWoPdJ!y|#tCj?zbcHODi~#&sn+wq@rZnmOE3U}sgU<e;#b{Gxha@Q{7c ze4lY@X8a@~l-N;a%FRK&tnYZ~?}Gpc2=luS%#?b?Zgp2^+TYPbdMPot{=8@j=<oWM zH4tNaR#ud3N+{4Ul8o%{A9WnfPu!49B&zkccGx4oK4<Xy2doE1Loy_$P|7eTWlX=e zMaP&7vnQgLzGIsm9jK4#y08dO4{_W+MMxU*z>`hw6KK8d8G`vC<ufw_3;pPL{%ys? z!MWqipEArdNY%s0qMw&r`dTZ$h`lPD>|FQ<{{l1532<0<%sOL;oc3r<oP6-lGTB4s z)!&TNFhj%wGv&)a@@>bq53<bdxP}euj(CC@P-S((Td=JC6+$cZIm~e-pbuEboZ?Cb z8NQ65bmtyBlr*G+6dx8=PF;)<oHQLAToi(by<!-0If=a<O2bm+!#8$dWOg?2yD86P znM8%wgr4q=+F_!ydkWtTAaqv1Xt*QHHB-lEjn}HVuM;R>xT=esRE`@-@QWj|l0Z%* z!43?`gx`9tqwF40m2yf6xgCVGOIqHk_ZTtE9Z4}vi8f5xe*(GpJW~1gi21$YVb|2* zwGj(tk7RI&wU~Z6Cgrl~=)w4*OG>Gzs8Rc*L9}uzb=l$2*yxwUQK$7$)lPf!tx>mo zZkJ^34=ay($hkp{daaI(dA%K&&_woj4230*9kUs*kc8P`o#gJq`5j}FhCX8_q^DrA z1v`0LZ2WYm!)bBHGfCrJFwgRkw!j9@?tt`YR`0owp0$Z1p@LrZrYVY;E~@@Sgv~_c zk%_3&6VXu<7n3Gpawjg8Ph4)8i0zz+8=Hv#IB{it;;P^zO?;BBJju|XOt6_uJTjSd zdNMg`G9_t}nLC+UKDnLNFqz&tnK3q*`EfF9eKK2ciX}dEO?fIuf9m>)95{I@_w-a= z)YRV)02MQJt9+`UVXClms%UKL_Q$C^>r=&o(`@l+j`DPg{&cC$blH*V^3&55QPY)4 z(^a|Ccgv@%8>VYIr)$Ti?|q!Uzdrpy@C{e|O`Y<adi^&KZQeXO@}}YRo5xXa8k62M z<-U1R{-(L%&C|{|En{z<eSGtL{ml!(8J_q|tMW{n{!F{gOvjO#&eJnpQ8V31Gd;O8 zz2!4~4Kpu0XZpux20qRVuFt#@d^;rmc3AoCYyGz)Hg89dyd69Jc0B6sMAF;I+_zKZ zZ>JmHzUe%Xs+AHn@b=yM+wJ#)?}7yo7XSpUBaLtKZvM#0yw1^&AAO96pb3G(q11O@ z8s62Hz5CiQ6-GdqjlKIJ_<mXZea^?XEBfz$+Pq&o@_zmF`(IJ-e{1D@NILc6+(`zq zQ+FfpSxfuoJzfw%bA{yv=O>2`!A-ShetbE6@a?PcVfeX8&-U9rl{+0Ii$hycK4+tj z?|JJ5<l#M@6w`Z7{wMzGc_eraoK261N3-33nE9qSAre`m!*l$D@$kY<_@$=Zy8&9{ zBwYXWUYEdO%X`V0u@o0^#AX9dbUzckPs$<+I&+g113b>>AI5$shb$+rMq#wFGIs5^ z(bt%8Dfb(H2~W(=>Ox|+h2XTX4Zjg4BI1#s!nw3#V*-q-6vO9}Iwwylhx%rmKkNX| zG>S$ydXg_JA{s_v>0xQ4?;q~-;S!;vJS3tv##h+ce=kmGPpF5Z7J@dD90sIl-+BKh z6JuUwXHew(NHYI_D0}m7s007+`)y{-ZoKU~L-sA%vKw2LC?urK77}HTLNoTY#*%#* zOLj%b60(*xW0x(2BneTHa?R&+eeZK$=RWr@*IzK_%$%7s^P0!w@${v@Rf=!0!2!v# zNTgP@X~@lUW*CjUaSuw=BR50?EWwKkza|><arNV>gB6q?<2!@2*uLc67uA!3aQBKk zq(=Q~U8qY~CR0eP1SGG0n5VeoOWJUb{i?VK!d(TSZBF#fSoaNB2o^^i>JFxtDRtQ+ z0*I@>Yi_NZxB?k4=nnBNIod^~>kS^^8oKa+^K){{QV!(8rrgYlpE5#U4j^qu-L!U@ zd6pH$AM3sb3pl(ClpzQg=&Y$o(<tu9MbWrd8}UB@A2JO@MhBi-xE~nnQ)cY}2b`!e z%cQkOK40S7HxQJln?E<E7!Xh4DBo+A_Wa1in%lvNjP7M_h1LMnoD@LV483uE*)H1i zZmb6tUJ{k1yjW799Bn{#hnA5Zxkb??gFL)8XRb&4@3?1_O~u~5r5#9m6i5f%h<YJJ z?+$*R*3@0>|C#~bd1Ut4Wh2_tElOXGC{K=dB)ZI+tz{Uwlb*r*e!`605NLB^pxoB` zyQ?ITXxh*9o`>{4I}m0v!n-dj@q%ag0^FVG;(?Dmp$*u$xWP3qc+TN$p~}%Nc>0U@ zNc>%A-(#t|x6=x6pg&-w<>$iNe@N3Em)PD*D*+!_4_V?4?*3$p-Uy5exiQll@G%A; zUZ+NtFPeRM)qQH7j=jZmmiYY->$a8<tDb%FpBuK;IEXqFuy#n<@3;%t?9ht|Y|h_> zKbqloOFQVCJ7x8~Ni%{~E=*fD;wIO#=F6X6=Z154(DjDxM46FZbH;Elkyu=3bdh=- zhBJ2EE+Hwqy-m*Q5qBr`!$Wrlch(1a1Z>Z5=;z4Bgvv$3IDDQXv4lj++cAh!0!W^l zdylTuS=U?wmd4bk`Xt}Q|HJlzzmoYLWt~b`I;q0nI(@>Pww<H!>vrC`AEYKPrF(2* zZ*q3E$f_4nrfa^MrM?Wc+o^cpmZUur?H8<etU?}6rRRtC2#95mC5#jX#2~J_#IAp% z?FRY%+gN?f$zb+K2v&ePcXQu>anEcdSy8rJ2N7#J;%D_PIT8Hf>3Hy@Y4vKpzwL`8 z<qd?&Jx!bY{?~1i|3dub;BPOS`{_LLeY5(r&4;K^d`&3wtE1sd%f_E~I0AUQA1A6u zg{h2{bRT$?8f6vx8H>%{Ytyo4{OR$INhRS4<>za!cm9?7et8UtyHw}0OTV-lO?=A^ zvSmivUk7-c9XRLuYs~y-#La+%M1=dt>5%VECuIRMHVC5Piw<@shWLETXvUet4nK{p zs0Z4I$8raz$M+i;4maE{g*R$B!RHsgt)^VOqxOVxg8%pZTfeg(#c*7R)}0PYB_CRu zHRa!nz1tU5X!u})!1nX}1Fr>-t=RUG^rO0tmGY6eYrJEDl-rdfvGxE^CVA=n=c9C^ zD7&4P;=>3pqu;gBDAmIq@!s&i4$;A`57Ww`TxS$+QXVpCA}%4r<x!(8_h?No#Hn{s zE<)7#r5sB_BwrfB?KCoA0}<fHlqq0zZ^@}MJ@x@LN*Yc?x>!mO8)7E*P9iS|Oa*6d zAT+i|{F<NuzJP>J|2%7IbTNcR>RwVsp4jgMAs7D4*`RI(#yl`W1V*E=Ng+!k=gm-& zfnexyVsNW%;2KAtEI_P(m_Qr9k`{=0P#j9K;&RG>qJ^+3Mgyt#V_z60HhUseDG}d) z#k`4OJop&*f-8ozk1k>c0=Pk+07!2D&MfV=gYSw!bI5ya><IS6FpF7Mxq0Io!w=v- zU99UuePkiSWa-;`!UL(2HZNOkpNkA-$h(f|fAFNVX0a_-ORAja>@-KJevx+H7q?7v zg6Bag41nnQ)MU$Q_XEkPD!WFXZ=3!l9of)NZGY5u(kenKkefV#9#6740cVXfcYet( zMt@%IRe-<blqd~Cu*iBG%B`IA#JL9iSx=NJ(S{ZQgoZ=;^}>lJC3@;T${G8SEY0Gl zzZEwpDs1ZRhFHvxSAA%`46S+oqay&8uld6O&7iBhe~sm4NL|{~+NmKr<g^*Za~>$J zb+VzVHG~iEIY@2)RX<Ew&A5lT_b=Gy-eP+QPZNV0F=ykm>y)qNDZpnHs7EY$o)Dfe zOyui)&bjnn<rB3LAI>0J|2Uk<#BJ>CNH3gtm%agy1h%ny=30}s3WBj``p=S2AJ`h2 ztBAB53MHHwP&oyhmSBzK0g5{@I<E*&AT%53cpRq4-3+QA%DshC%nHxpLNA!8t`W-Z zjm$Nc67=v-E%RnXGEN)<CWj*(vu^VfYgwIPGKW|MQI@{{(rV^8>%+uE|IKEx{E#DK zvI49*{8o_CKdw{36(SGBixSn2%5+9RVfZb$!4Ixtc}T_;e%NH1L|H)`T2x(tVfCG^ z#p9Mu<EdMHl2x?>c0&AU5oibJht;!EFWB1lB!JKZHR;-37g0VM&cn*6<H+^L<1VTi zDbp}%_waJkZO)!8LM}n?UBmQ+OBlc%eAypo*H?H!0}}N|wsrS$aaGM;d;FXtVnN<q zyJhyz=?*#$ecVf=Kcs^M8O$nH8Iv(Em)~oul<Q@)xoRxkflnRk1gz@Hdn?mUQS0Fi zobm$_-C3?LPr5VCkQI2o6rdU<yR$|sfsGVX?ZDY%1!}aiQeiPLqd*qk$NMIT?-@aT zsF@WUN|TqhD{w>8fY&*(abjKBWM<yhml=obke~6=jI3C507=u#*J_F+XZ`0w&MsPW z$&<x>Tz*_zd=%B4s7T@oJ-lx&)st8kqyA52HHooU8CWvec3V!r(;nn-XLV3@qadE& zU&NbRm{BS5NxRzDYMXcz&<9ZavjLA!bzhsmw*RSGin1I^Z^dY9?1nHy3uRyQ>D}KQ zRzGP?XwcQxJea(6rR?Ctoj01^FOG>KXJ=D~HGi*V=cn_1u6(2Q=YG(N{-51J?Gp>n zU>x9kvj6ps_6eS8#oz=Y-a)6l$_mrKLs;CR&2l;ej*aoKQ+@4D8VTo_Tk-Hp*XCn! z*>L`2{P)7q$GfDO2vLt*jiJ#_mX|e=F?Rr9>@#akb4`@8#+;nd5-H5>)T6V<f?$zy zbP-ns-y+@tOexckQ|&+@#@TYy#Cs*)-od2_(gE&*Pu}V$#oah|tUY$*3QI*LxM(<4 z0nTb+HPKOS!KZjndU$U|F2UT9H+X-P8EP-k0l2<I<(8&*I?ON6KNA-gV&M|C=7sUB z*cJ$#lIW+OtisPw=7kl?jS*M8Qu2<4#q}giNSA$5OEg3zFO?5me);n0^I#EaCyBxB zD`PLyUbTwI`j!t~-+P(fek>vvE-~c5T$k}yLsUMc-1LT{L*{$uTN>z}L$@vKvZh)^ zmFvofJ$>r37mr10>l^RAlk0NUHN@1$%isIItjpaF7Ss47F%mRZm-n+(OzTJaNXTAY z{=Z`}0#uS_&el`ln&P@F71T)i`T|^txc({0(OAp+LiRTCa|#usi9Yp3{C~xb^d!fU zlIx2_H6=_gRg67-S^rEnM8ecbay)aazC^iA;(~9*c<x?(sn%Z!^Ki+D0_KLYbDENt zDHRjX<QvK_gh*Ny(Kg&H8!D{ZB(3WzCZ}SHDnB5R|E~ft0LTJ=A+PBEFBAaPQB;45 z`2R-%FpKdY0-Aj4{-Xedqxnqg%SMZIRN1zCo?*F)&5KNOO&TgDD{UjKnfqc>$HFd# z1Le%(l^^Qd#w)H5zN+rK)fP+_DC||K!+jgMQhuth`acQ)hTk+}t$-A$!N9A$lbG7| zKMKH2EePYO<Iak>8`^==@%&~j^<Tz$&nWE+A!w108mGa$st3!mfR8ga)e%9sLJHk_ z&wrt{Y4?-<U*yoB*lC^RzM}K_7up`Y)$?zM)cC!|>hw<06aayXH`FeY8t5h@M%vr{ z{CY9ooljE$LaMISQ%>~2?Y}1gT-@IDY5`pbHn2y2DGaN;VQ&<Q)ivkOpvY4l@-@nq zqj<FfGepYDqR>(>i?L-|<>PRX`SlKykYw->9pEH6<@PCYRK}v$A(&{(6RQH3SS6R0 zPZdQf+<liJqR9MZHO0K*SvCn`;TRjc$KV$qSzz#GE!`eXk6;MlbVdR9_miD7JYIcq zG4thQI;SHC!Jh&M?f+2#qUsI!EWHGK`L69F2@lM0snL=0?$e)X3V<Dz&w<xsfN-@h zCQjrlL+TBQ)_EPMUvipzMV<vkmC9H3-a+WWoWlv6zz+!u*eGvWN0+b~y_7VUI6_Sf zBmsC;a&^vxb;9!@<w{5JKG+la0v6f#?sOSdjhc&+*w|`Zf+Kqf>CCL(2%45-agvM+ z?Axz*x@_n<Dn$1SMKU6d?zJBO#0a!q1(K%ON7FDJ?f0$DynBk;9W8$Y(n|Ktur;qQ z%~w4t-6P@jQZxmCrSS!U>$I@blPz?_TRz5UngUQ-Ew@*UxD;Gg3kkx~6ad3l^c+&o z!SC4NP9{{|(Y$6p5lgSRALHh)mHZ^6ScMfkA;YFriM9%kgK2wLgZkz-Y0}_Zc<miy z5~P8brT|=0Qr5A(cNHyqKWD{%o~8hJT1{d;B)IUsDc<_E9CNa-pr>ktDUxJw`4+H} zYQvxMA;V5wMdzj6_V3S<PwxbLf~umAzLed!La)OMh9Bs-`Q;sL)r&<0jl!Sm9&z;T z_>i|65T`YOCa7HFE{tp5q;SJdcWsASbfNykJJ;3+vnd=CPCrNQf4n~m|M*W$v>HG0 z>BnN}qr-jSaZm6I5Nu(b2I+5aJ34$564GqYeXm|br27Lwr8oKq9iT8jm=AII*)qLG zbhD&p|K7GCoR4t8ZCs_mPrcPzQH`)mm%OQOR8Yc@Rde&w!v(#Zx6M$W3Oq`q0Q<(j z{FC54%)j%<zf}5Gt|RaU>m@<G6J;?nM|+K-M(i?UdSJ!ZAgW-hy~CXIErO^W)3vD- zqg+}iREBdS6cL>9`nl0L&D+&cthGISN9G9CrDYBED_sCXeZ1_`-N&9S;k_m<-Ek=I zvo`oJ!jc?0O~&CuV^@(-x1yqAE$+UGUkoq3Wr^I9AcLcAvFKdt8QCQ-|3axgsDLe* zjS2u^`XWF*SyQpEGZ`VVEb3Y=bX6uI6?yyGWCj3Sbpg*h7(w~F%td8{E2Ha8*Q4rp zI3vEC2?qKEmta07qIf!_1vShyEVG}~B#(We-_1tE3*O55q3^sSob~f*ZGtgN5Iq+M zv-{c^he8rEthMXGs{IK?v6YUcPotCo-Dhnvi1%yhF3@F6?)Jc~K7ElxckxE7aT|8O zkmrGDzfchQ(t8%9VvQ(BrbJqODZ?%C8gX{qHvSxlDU$m;a(cMr-SlM!-^5S1-tQ-m zd29MzaN~rDLAb{Y|J_MdY~V6P$d5P$dBCmE-9dQC%c`wAr|jh_tPP7I!}4VAD1{(T z$C_KdeDLEbU<+XiOtu7u`cXDBdUw=b##YZN$=}|2|3jlhDg4k6ub<({s^J@{%Ew%& zAJZkQHwFW+%lLkPAWrt49%y-1S##&wO+?{fnB4M<R%s8rulS+f_fO$IWaz~We3Y19 z1lr22n_KwKhuIVKx!ZXneN7iKp^H&g=yGl&hc)piIf~BXax4T`A|gbv5oo~c`ME;x zDCK!QM!>DgvoZVW&F9G`H|@n4d}<)%?VnkIeV1c5{+$)-65gSs6D!`Fl2E3De?X2P z2n(Wtjr;iVrRT(Q%Sc7HPW8q8ZNgjnH;d<fynrTs$^luUg!_!h=1=tm28_vKM)w7u z^YyWGP(GeW7PG^GA_)-%D|D|9#gHZA1V8Q(-eMxYR652X1rLUl2$FyBrSsA2(yIZ$ zD`;&OfxB{5n6ak^MtZ4pLok7jQJ?d2$y>z%I>5X2a8Py^Cxj4>)R-?QXX7z?Tx1N& z?5v)UZ(si6LwA+jJkZ$(tL;qA2gBc~Dfb9IH;TWCCHe+-587YYKTkvx-y!u&6-E0L z>1te5e%U^xarRjDJKzR)#K;rAE|#o$XTW)qq0p<#;}<|wsGntUC3q{C2d~*l9Zktu zc$GZsC3`o2s5YiTO2@;Oh5UXn+%tVydQ}rn3e3P;0ea;hmOh44b(kaY$oNZDD3TR) zdg(^&{m)m%l0|!36V;1(C*46+%iGB|Agz2WbX`Qz0cm|Gr#riZJqr+VGcqx$Ov#B} zJiH=K0bh&MOV)Yng6I`EZ5}dOUc9{GvWVXO_2%z_UD(!g`#&Z5fP<yYDCa**;wKl4 z-&)VQM9cf(6>JrBnQxSkj`3K|vwe)mW(dh9L6oLI7bD2*72&5YxCbH%FTLM?A}p6J z`$UxC?Rhn%fc`XEu(`BX4z8v$-4Lj3RF^&M9-UM4#qFf8QjLAy=Z_M?jA2`cng2S; zXrH!<N8;@PuH&Y!f6~`7y3SaLGG^8K7Gv1&!q*k?wm(>KA-Ip<<oUg0_7MC4p^r;8 z|L}cf&%BR7AKFjtxsezxyV%^t7O1g*c83$-<&WU~xdXM3(r3w>4%j~P{r6&>u&sq$ z2#z5Pp8H;6*^1oBrjZMm?90RXh&Ml4Gl^D6wPVc<L{xL=x{;inzO*wwI?;RJd_F9K zAHYR=eX70yDn<w*oNy3+p+{fBsLKpKoEm(JwI^qfb>57E=!RFGfcY(Y2jWUP5!}^v zqbOi(!1Av1mm2Sw)<A4O6W#D|69WD5sMEa~*pY}}34j#&g`hFT!|Ye+#leN?5PBWt zuDKgpB^)^_k>M4JCb@Wtff7qZbS><?;6vyxLg_4WVak)%@_`73K)e~m&)s?z1xmt0 z6>TFA^sML|?tbZYY3&Wg=-fxwqP%+_k<NmJ1V#iBkhKN#Xe|NzNG}zFi6Us%bmz-j zpsxy3*3#{JUhwMLkWm0=ut!5{qu@;8AHnE2TLOm3A2=bx{(XwX?m{2h<9*q<<1hQ( zBf5s0W00JY)@k5pDnndZjLlPUy(F^zDKrrpg{8y7cM<Q;fDu#@z3r{b=dfspm}j<e zPS!fljiQ^^E@_p4N_hAyH?Ww(Ro~<|493t-373DOUr)zRxrwtRU1HIJhEqdKIuUI< zJoFZc(AtpvvM7M?c&h2KZAN%Cl1ZM3+J`;{yxd%Ez;G3Cx+YAf>~X9S?(0l^X&F=J zeb7b@I^<>nO^TT@CyI$BLPxQ$#ZbclaE+ZzhdKv}o0LOfsuX&+v`Bd84MZv!?fqnl z!f?$RbFT)~L&QXgfeY42oLuCaev#}a5uvJ3e+UVt_Kd!yl<5E<L+EfcPafipr61)8 zM*#HGI3=#=3^KuHEk&r@39Jod(81l9!fg;SU(G>!j&O_e7$+;5%}Myy6pki^D<cq= z6W}876hd<2xRPd(DZ>3B<*JbxD;*+O?&dX8dc+r|1S9WH%=E%fBcmn2e|7vBRD|{p zA}9uww9T+kb%suW`Mu|RT}7Y7a8-0leC@meTxO~#W>%nX+K5}jNtScFa=9$<2xl>7 zK}M)fWaX7K=m#HqrsTO=lT8vATdIzCKX`x#_sB7?%d<3B(!Q)Ez3E1%`Cs;@N%-Em zof+UV0LWdTAul<%PJ+aO$&wC$zrQ#bXAGKrl9TnzWi&8)&%#t(ma~q}i|99b*Ok(H z7;|Y~<3|uUdxhyMA@#61YYm=D<IRtj^AbNW4FypwjB{zEnH1h2qk#V0goM9&w!vyB zGj}0+R5dS&f~MV{#igdd<jJv~QWq{nRIvKuPkn6$6<Fwd$`xVGhHO^!d&nZf1JD#q zT`$f17Zf*r8%4b(Y~`$`Q<3FMCL>5NG+I5nnLqa>>{y53M&`R1mp{|Y<T@rn_dxt1 zQ%>yuGlb+bY;A5rOk#C8m{TL&QeLuEMt=#VJ{R=V5C&Wz!x-bhLHp8-Sk#-QQl5U* zz8;CT6XUXoSd@qr!k1jcxvb$uM71ny<o-C{hClz<J+bjjSrk{<LHO0YmGXSMxH&Qi z{g97vkkSl`&2YhA$f~gTg0bp}v0ABs3*MiW5OCGac~z11no0veE7ol?8|96q;;Ops z(w1qb(_%hNM{7pOQzpU!b9IGk;T0pZ@t+9{9Yu08XemZIguh&7Pb}AItICh=iAEnV zgB_@=7N`s+`nMuaPMZ*LzTtLGx!)_Y7KJz<q{?+k%6BevV{|^<*D^N!5*c6q;w#Cm zvo)L&FR-LySw%6geTvzEB|Fd4e`i9!*%oZ>Y7~PnA#-4eS}lZ$Tcq;kt#Z*qcP)*R z{eo~g=s>3d);mppE*@VA!t@CuD0<(6y7GaTohv0qQiW|qRDq86rQ7;9_Yq;K31+Xe z7h5tf6{qE_6kK^oc`a8BTNa1LHaJM-DP4U9tF6I75!zIQZTc$(43O1nlC#71l~f!N zf%4LC99Fe5NaeS(Bs`Qt=rx`tzRn&r&+@R-|JsT0seuKxG})bhIk$X!z`dD}UAq%| zKj(F}PBw_GgypceT-?;i@TxD1Paj;W`(zVTeKn=#HOSVJcU|qZMRNl~QCSNQIoG7l z_dKXgH8b)P-#&UB*CdUpg;nd+`|lJET#Yn2^NL{?8ZjYpM!iiTLkvwqgq<{}&(FnY zWrDs9ZJ(q<8?r(E0nM-3?O#<|ph@t4%$q#J8ffQhSOL!`cWkcv8&sKSuov=V5UfLX zJQJ_DQwd%G5I*r8Q)O>p4h=tE1u|nhO>K0yg*xe`B(@qmIOiV@J?sQPd%^jfJhaB! zop!Mt;*=DKmr@s=?^?O<2O-r;^CA}s-HL&(BLq<Eye?3Ki8e=#5O53q-7D!YF}3_f za^N=rXQB}vREs^t^yJwy{6Yej8okT!Fn#7&Z!!uX3({}(#u;51WM*iG0<FYaH{NJZ zQ*hf01(;)VCEs{&J?tZ(<K@5>b1<sr-Q_@ZJ%t6JFv^|8GWIXwB6y?g@kE+Z3wUJ$ zc-<#C#L*=f>01Bx4kn3yAX6iJy9O?Y0xCcR;Dv7V!Z0fitcdkPyfJY(Sx`YtC3Y|u zk>ZUX{N;r{0*0C>eGrGimV|)Ls<6(gzS5k*;ou=El>bt}*(NVW&!yZ!>7fzqFs2xH zj)ZCSVx%$IhxS8I!J!XZee=>9`86172WKJ?M<uX6IHglh#>yEFFG_&jtpojDn4dN8 z>%%dj02+`(y^zCRG-dq-q^wATM*z@Rqx7_OfGKwnlB;G@gRYcA(U0=zI;g;w(e#32 z^%Qi!eLt6`M!!9##f!1hp7A#TFr1)R>pK{a@t{P?IHYsD3=8D8j^!&LLj*xe4HcGz zJpv~b1u=i@!NwZK`YQA>VY1ExY?2<;{i|AV23_ejfhc&dQ^440K6ykzGhLqqmc|>& zlUHeXUIJK2^L7(io1`aMJXKgUL9Oc`$KR>wA5D1_-b!=UKZLPk^C`EsX}hi&qNnP0 z=4prp(l3!VcQB??OXKJ#gcyM4B{1agjMt~zBmy$a;RD?Bo$i^de<<jSA)w{;u~3=W z*h`|(9WA${SzpP4&;QQa`An4^Pt$jfa}3jX`MH~yd=a&EnKEOys%K)aPmaor_2%~V z{Z(?s!!HmJRMH2?i39u>eo7~4(o$w}?D|yM)?9GNg2N}oKmkHq?p{<!iN7bJ38bF& zo(VA<1I<9ykomuDi(739=O`E@L)!b?IkKa~g`9Or{y0)S1?<dPn}Lr#!6U-FCc_eR z@$_p=@CoIn%MK!iG7nj%2MAZRm&gAsO}U0Fc78)YT9_7SpXv%(=Hox({p}k60)n`N z$g@Y(n<LR-*cBO;ATzL9bJ>`GGR|y4lW*x?2xCF+r(<RmbQFmdL<bQ+Dt5|tRIhga zop-HfeDQ6Zd;253H-_=<ntBm0^B4j>#$$+M8LOT=Hk*79`gtpP^3nBqE-jFwZLa(_ zBk%S))5#^#N9L$O2s((eqL4Im`uX@j^QqCq0hhL^ZZnWE7k!M!aD*`aqK<h!-uUMT zzvYFjdh3eN7@?7nXF5MZcW0^9pHptE!3!3V%fkQ#w_(4zy!WoDAk)({MX__BHDu7- zb3RuFe6=%imjPHwU}R(fUIk+w4}ERLZ7nfl_+n6|rl7>@VL7@Xli|7Owp9j)q4D=4 zM>TUz=AY*mPlwuo_U1m5S}ZKzsFT>CD&8TM>M@AUH^6-JtS4sqdVkHouWgTU?f-Ug z0=wY%%^&Z@Zj<3LCZJ7Cz!|}*-x^>O5hE1B2s;fj{GDc${m#<46M232VIjBg9p}yy zdzP(2T2ktL_t3z~7PVh)^N4_XXf^~a_4#k(RAia9zyjHiqA%>x2NyuYMhqA2+$xVH zFV4z@PEj6%hfBC^;OqJC^5F!u6C>b!f_{WSMvo#4D<@tgME#Uw{0TC6YyaXSVa{Cu ztv`a20zXgd{j9|cI%`Kn<3G^XvTah==deF{1*aN!Sev}izE$Wq)L)?^3N)GZ^Z|N# z5gbeSxSjysxW{Dp98*D&c@EI8hW<9!Gh*IDlTOg#_-B4hOcK|>nSNv1#HMJD9EE(^ zk2XiHAc3`qV3AxO(6Ix^jbraIZjk@5T5O^m7}LK0kxM~PJ6JBB26Intf-eZW_f5fp z5isEeSnvW|yZ2WE8vi;2Y-y4%UP1~NFh)QBM^!*8*<icnMkLo406N0be-!{$w~I@f zmz%5?^f)b6^yAoMZuDeWd^-34rvTU_(-J3~XTo}~aqA;GZd}Mc8$w$bu-Y&$G)Uw( z$g=uk8Fz-Rb?-+7r=lhNH2q~UkpI&2>usU*JpWYyQmpw@Hps)}#S}JPgLskWRgkZH zirF^bZ?uQ}{YTH6K^eEn0|-SyGu8J0qX6u!k~@%=ub;8KAk>Fr8N#fqGUhS?58QtE zJrQ|-e~C9yd{=1-0Qn?@u11<ha*;w-jf6$Hf!gcPq-DFzs-HgV!@1hgd1E%)UmBUt zN!o5*Udg(Ln)T+mejK>BHk?0Vr1`6NNq&yeFoySU@X^7ykM}$lUiy>TMOB$&1RljT zyWq3kR-S8GW_e3!9P>xW>7vB+-8939nUC@Qdt7d;y^CtYilj0}YLjzJvx$g5^-8S) z`^{@fx?HZswQrB%1LQYhlyWHrz{Kwfg$lQPOu5XehB_zWR9|Z>mLHK^{&#Bbw2%ij z*`%bgVh;y6BO$lgQq!#DO%z7-6^2vfdq(B4OarlcVII5G5?MNM{MqotYTZTclj0aP zQU!1Qn{ZuTqm!qm<XD5I?p7GZh#>Z?-txQ-cTf5pvNus1i}+xox9!-xejZq5w!r^3 zZL7a*bJMed)|@!Aru(-lTbBLn<5f?Jjj*nirSpX$7Hg*`22;lO08Uu986EWn#TTX< zHCZaW;@TKSwKL!lPN6@0&HGDbg|*v44_ijY?CyGw|4UWzreC26M(y6;d(VDc??_@J z+TsRe(r(h>4YS>0vnka<2e+CWqSG<a6tjETcbD!VB@x8?3Gopb_6T%h#v=jIX6F<- zo}PJ~>Y@^f2zGT<mrPgLuhVu4Yf(8dJ#<UtI9P$ITS4@{FS++i*xXWeh^b|~e6dk# z?&Tqpr6;-mv#}Y4{>1VDU1ENonn&$B_-&qI3C9$VhH00FLV4Z^eP3UFE_uDJi-FAD zZTrPPn;rUN+v;vRLhN|;tWDHwuU-!App|)?tA<a1($n>A<$JjrzQf(me0)c=FZyQt zq<L3d(wnQ=^q|_fUf1=Rq9dki53%LobFaSBy#J?3XO{J1{v=HS_;yv<+b!BqD`-!i zeS>jc@|_vwZfa@!gI!0p&jDW>KZm}o0KRJl@1E$+@`k-L)DAhAc6}4_>tnQb=<m;^ zZ$kfkf2aNE@2}5q9-W*Z>;ZZe0)(APMCjW?*qR7%WtsvIVGk2g(Lq~N!#HTto>G$z zE`WLxE&y{t8mQ<pr%@xs^c~Qbn{?S<Q6o=BIACw7=y6X`qt5m?;QX8P_<vHPwPB86 zq>8=}`)G`zz9aL~CVf%m(b$U-j;zmA3?!{b<7|2y*&CV+WCKRyZ^E27dsWWKr;R4K z>N{~yHl0&`HJW%Y!ijfH#ZYZ(^zr>3C;o#bL#>~qPaeUX@${-jy6j`*XnkiPwq~Pq z%411SBAkUqRE<rn$CA@~oJEzIjV}a@rR2kIi5sYzSf-7omg?V<yxeSJP3wQWh`1$v zOZB|n)L2?$&ohgz+QIAV@-c1FhH`W@3^(`8GXS?}m9pBQfE>MyAt_PZ$QiUaZ)etx z6Iu!SCHpW>)F<9vn%P_x6v5}b%rpDRg`siuvGEoK8@3aUf4o!V>!FaVaLrYHcquwi zR}eW|_O5p;XoTZA3$un?xKOJ-T%5Cj>p)*j2Q&NFVhcbAbm%ID6B#Crt)eD2x^V6_ zQ2w0`#t#@nea$#s@7C&PpDAxo9ot8r3M}MZ$XF!UNs@EV)t1WqeS7x7tdY-FGViwy zL+v3D6I9<_zJRQtEh&z9Cln>=(G$;h2;wZOgm6K&2DaH2iDeK<m95Ci#gC%kjgtDZ zD_@@phO1rnwkqQOM>M!`kYy8^qsRSOx{@{81eaUDmeg5)M{~Z`=53cQ-*?K_lQX%8 ziFdu6c$Su?)!<ouX<6O8W3+$M4wGyiEj82!M$&6-I^fDKJdItQd8^z+_c#!*#P@|W zQhv(&b(5%1I;A>V%joM9iB%zv2iLo`YYG@%-JOd06l178oAlVhNEdZhoB&kO;>4>~ zNnOVtN_&Fyt<N18#4@^2duow^_D~+GRpI6FPK+9sL{H!G9e|qy?E6j`OXMn{XM%~l z>rY`G8PP!&55s~|ySZ0u+?mg0<2?GHaC+)@T8I!LWlMT93>cp6(U~!L<=63rQ%1T( zE<Q-*Q+*8{P}p=}@GVP?VS2s;DtkoQ)fDlaWV{W%BlyHqjsu92StVjls#b!KI`qGd z3~oRv(GTotdrW+e7PU#ZAfvE1doc+0nofqh^Xa&~j<?~S(ndwe-Oqp9O5d)vCrZrd z4QMSrR}o5B6-d_O9eipi^Yb-I=uT0W7C?O5s4<uJGmWhC_nc~L663_tCnTKmL&LK3 z;{z|J=XaC}RlL*^eQDUhhZ!IBDiGi_4ewf**?d~d+gD+!BA|vRa?cWPLsORoj@Hg; z0F=b8FuR!7SofOm>Jg#lPJ>%B`T%5U)41dmzdJx=Z0WcIZ6$EgsnjWtbtazTQIC=7 zl~%SI-n<?2`_(|-HvbGA(TmtU8tGB_kgf(r3M5S<<%le)-YzFr0>2lph`#d_p(6s~ z;e1~JLZkx#NKJg|+s{+V?sizc?W~T0o0I4UcAhM;LV1+d6~Ox_+}+mf<>ZXUhii0E z41a#DaD8{W7BrRUW!l{(y`jtWj|4F9ccWn{B>9A#p4{ZCE3Az{kp~?&E%PVm!;7WP zu6l>_9EWo+62s`CI==%Rj*IDLzj0sCK<VHol+ru6`jQA%F#o76wEYNwN)+c<K?m;& zq%Hl9ehbZ^0PY!$EH7Zh@;ZC&dFr{d!FM+mv!T54snYcqL82z1n_DTcQ`>|5P2=<R zn9E9jl!HHUmrk1bw8T5WRQ2sa1!i8g^N7|`jgO&(lVI$z=DW4iX+5cX8vNsO{z>Dt z+tweIc~<YPuI2AC^8KOkz2=0ArwXF}Du0>~QvS<$I%?db2l_LvL{42;(DN1{CxfIU z>`+Zh5Yz#{gxfiV5~fv%+sefGi$YzNjhDkoKf_c4sG1opF|${TE4Y!Tc>wpAXpg4y z(54q>2zB1^a>9<ye)b4W@~eP4IQnb!Xk}AXnASON#DH46&L3@$jc8GOC7?-W5hW*- zRWt9@WR@Z85eRRrRJ{X6+lRf-(|vWf4~~&0o{4E<I_?0B)MBz_L?F?>QxGisFM982 z+)_c5wN#Xc>2S4@VqVJxltuCdtN5H(=ijV8;l%&~Zm0EV%b`+4!9lp=)jIwaE-7^- z+6-g`F_*zA?p1|SfEQGJqFSaqDv(G5yr5SEOGJ~^uu$S-h3r6z2Dej(ldlwD)LIi$ zi8DpK^i`41i5jibdL@;2-LCsCI$E=pStq{Z`y4!optzr{D_B@b5klOx)u`E!@i`xT z+fDy0rBf;ip|tcO!2Wros)~TSLRnTTL`7k(NF|`M)9hHlK>>4vSrTZ{h=CH%%)qjt zh#$*wrQHeu4NQ$eIFKXkkXku^o*5}1f@-wI@ZBCN(cf6$mg8_=iXop+my;yo?nYE7 z7t---9Qu!@z=p2o*QiQ|=q(4KlL~GGXMLD{c9cvC!csgcl=eFCMDt*Ux^#`1$1@{f z@r7LyfO*s-jc8w?+Pj>H+%v|fm<ce}sHI8-<LxM86~rP_MNY)qR}XrvP0=@mqK)oE z`*=yzbxG&dstLQ7`y593+ag};#t88i-dK5dZtnG|KL#%{Bnwu0*@iehi397Fg*RGW zdX_~Q^Ta&S5i0IE|I)3pfV*ANWWXpqmn2SZ>=~?C&D>GIMCBAp{a_Q79BN&Szf0i0 zWo{%n_I7Y1s)SW2*SP=v)==AyEGb4&W{*jD#dKtUs3Qi^<6Ian7$bmhe-|;-dZ-Y@ zSrkwc_3GH<!>Wj7mwe!;@yUc~|I;|Z#VxZ-N0B5>i1N-0Qjg##eUa;&G0G~1q^w~p zW_o4wC_>ZuCdlArW_my+{80zYRIYMU82NdkI5Y-IqQrg#h-&t-2NQxv!WY;F^ejy- zkc>M2v<k-8Mdj^Y<UtS7RTrooLMzWuxdy_S%ZKPg3M%9-B6ACbk<i=r(SyZQ_C5I2 zJeA2Lj4`(W#Wu>p3^g^1cHbyt)+|u%hzLzWTv&p#UlzPW;J%On<qi=nni$0$Ap&54 z79srBh6U#yRcMkDuyIjXM)00Ef4&^tdI`4eY{@K%xGfj`piCyLW>B&hA8ZtLzbsme z4S6@%{Pa^w4s+Cn7^1dfHJ&Ft>OtSdvyqfEpD~ikCADu9L71WD!MJt^=;$UHU~5Tu zhIhArzSDC_uMMvmuX65y5_3i%K74{f9&yiW*kp}jIynJF{~w6S7$6UPhgAOGASRh! zTtq!U(wo`H5Y_*GRwg&+`|C>0H2i@flvO_nm}>n$mC64gCYvlz2*ppUEEfhEDyRQj znH*Hy(5-X+--yXvqnA#JcUk|^{5j}X)42bsOk)12f((`tx6L6tivLrYygP_s93x46 z#?7lY*L@zL=*4fBH7}V1x3?1h_l``S4Z6OF?bWxrCf~0&xFa#TPOk$n0{=lw;>15o ztG@qlW%5TMA1AFGv@uh6=OeC>8L-NbraPfnkr{ve*ch+0v5Q6mr)vRQT>}(b7O5(V z?vNhONOa8^s$C?)*xe`wrqVh+Z0jif*g!~wE;;lh$>$@9)1|C{)Xo)w3iMs=L<2`x z<cDH_tuABkbkB{IcsVTu0$?Z<%1iviS4^`(-)?+*LRe(i5BH}Ck&}EW8To|LjkDLu z=I10toE4FQY=QI^D&!=^0c9Fu64gJ&YdB8_a9q9S5_=z@xPcrx4dUyx$|Q=7+cHA} z<hY+9R!T@a_8E|P<3>l2dNf;3t4z*X(ZG^adBglS_%qQF!T8H)uEc=NFQupHb~gy7 zsbMD3d&Zm-63_zle=C!l<Vwgwr-6j#7?NM|cvozK@8W<YtuiUv^GxJ9)(^q0QyXM? zn)=hnLbaDxnS4MK9?AEtUnNTf{wr`42LgwfqI3pfHlqsb*S>DQewUdU&T5l`B1k-d zP^!%>IWwgq_|O|7tuPJ^eD%@hZ#Nu}aa**4nO|-DvIQrtGWq43x;d_Bu|TE~87pT0 zoHO0S$4}A9ft)#;6&sajo5s9LSkJtSkf7$#Dw8z}N!{#<yv3flSIWVa><S#t#^z}g z=TD888}iu|-;e1azXHcLq;!HarW+<`mC4L^42gE+q<<lOJ$>gf#gR`P-^tu}#d7!= zN>$Lt>*p1DP9_HBYmfO<mclr2hx0LFi>Yr>nP$FIzyIBNPD4!oO`?B`7N23cdblYi z#xb>gK)7urW$`|(^tsxlmEQ=WN2jC9*k=8-?BxZ1{>fis!M0t7y=8N<$2(f8{|t0# zL)Zm`U8e8HKX_EzseD>rvlG%_4Y}q&K$&jiGt}r4jZfIMLCk4H?1h&G^YP!?zdh5h zARjlNR|k%Wh5k3UzW@5JUChwW@lM_q{72WpxqJJ@A7<v(6IIZA*O&J<vhd919T~w^ zz4R9TKAq+Mdtpa~ebdq;`0=x{aB;u9eP&(Fw+yCQn^H(_Sbb-tv|OZ$M&`S7^tuHM ztE{xaW3dxv`tC3<#{h_G4)dq*9$vLk=cHK(-6^3w4oF3WqB|Lt-)B&JTPl>T)^RV+ zE!LM!*wsyu515$gRc0RY@M7&7VfWF=I>5yjs@w1}GOL_D+I8g4UgBkN%nv7HWfpG> z>E1njcaHr|ByJg+Zs+_qjy49JvCm5P&`4)Kmw_R$LyvpOJaP@$b9;@hV;RXD?{{nO zY0V1DI~cRhk<LI0LPuAEULF}1L-!OTIIkmI06S~0gLfi6lkXJnjnF|Sz_^MRu!Ztm z1A^E<uv>_}>uoqJ5%22NE&uNKsgE8cHw#{*u(t#`m1*@_iEy9N`EJ7~aT3~((shQ8 zaDwnT8aJ>cBaz|jd2w_^WT$So63UX^+IdaTj}yu#x|tkC?L?mpZ4k$(@~XPNPTWqM zVwFK;MSEX-pt-p~RT;TOyr7W2nZyu<CyTl5m&`5evOxw)?YtA*kXJ|qBAnK%BcXtp zFm|j7h?mwWaL71s^#YGb6V=B7WPRN#`%6F>U8#NI1+J~PXC#ica@>@V-DHAUWW;jT zkE(P>?l23IIH}~?<#4tR^XZx+e|5`a31K=;DlaV&Z0hy7sgN9{);ei!)6w0`egqd1 zD$bXaL2|-gerShuz%MLq-86idZNjc!d}*HZDvFsNUp19pW^BY=<qmqEKxnBgnLhq~ zO7sE*-w6ExyB)2b<I8^e<`{-sHpwnBu6jxnFn7~HjUfiPVI@`_8!SJ|qeJ&t1noqg z2VO~mC)*Y3Nvq2O)-|W2LdNkXGDdtGD4-71Q9e)U!nZyoKX=?OG&$UKIiOsY3cieY zM}80Fkj|3xk`#A9cJq-<bRw4a8t4VP_OS9$Ay6mVhSDt{f1VryA)w9#hT%Nq$bvJe zCD$jRz-HGH_oI?lc!8WcYVSt$H5M9r6o%EkGMd&@AVR;Zqho6yF0i3gkG`VE1kS^F zt~M(SDwMX-j{OCY&Ngh&9Zt&J1z=wXS0?POYZ`1H=3#w;9|DNdVYR5Ufj<WV*W+(v zpyj7ohw+LO9bBq9SOT#}?Z5~kF9=Ysrqc93tq@MzU^4r}1llZ6_h|^(bgo6G32JPR zXUM=QuM+5prPHN0&0mlmCstRn_carnscSt)L)h9dW{-*pQOe;kv=)-+Uukd2^G9Z% zenJ;6Gx6!=cq$Wnj30x1QFurFK$bPc#{c>)z|Vi?9q!jnmB`JFyE<$S*^%j7>udOQ z)!73RU7a*qq?>AwGI}NnEK+Ds53w>!IVQOi@8r#+A@@twhHb^Zc(Sl!!H2aEP41YG zil7?>YG~$=TsVI;C*Wi5t0%kZDQD`(;CTWN6aGkyo)L!vUEteJ*X^fj+!AP0^NIqN zF82hfmKzF9VFg3oYh1t*LZQQ*d5m~DA|r5Gj=q~^mKP0db>d;AdSb{ubmsl*>xzsI zFG==GPRTaRYrZ<0-as7S+EPWIuR((@a%*Sp57OzsxSO3;2fa;n-!91XiEdD0?XatC zh!0US93v@znsf<+>VMu(&v|fjUY|Vg^~XoKYJ)T}n0o$R3*jFC#QuAgzp^Ekj3`9R z1vsu<F>~?KkpXL<_Fof5LM|RPIK-U~E!S8-q$IuvH>TF9M^QT1EiF)F=WPB;0tsh( zkvtEv!S}NFNwv=5?rr@0qf+j4@_umP!hG|Q;BBKWw!;uG^n`?asIoqgVn6p97lG^5 z($l|j1LtjyIR?a8t_d-Py@mPfg$65w=gBvR?_Z_aO)LkYZ7@JIz!8#kwV;M}84Y0= z#Q_wC6+Dhkg;pO3Vj{uRe~RM8pa8{;3jxUEFSxCT;eTCc-2kIpA0pE(!|8Cshv6FD z0mL+DRD(6v!3}E*T9M&GQxW0jUI@X5Kn+Sw96NybJ&o`sG)0<PoUx<0Lz(U{l1wfX z!Ln*Yzl$OKcHnZ87n2F}mPUvk+N?lKV1sM4Ty!)*W%$?;8QRCx?i2>;wCYF?W2A!> z34>}NR9@~n^kmdeumojh6ljA03Pr&Z^M{X`V&!+0{P8hw#6XXyP~8K&FH@jw0oOe* zdK>dtU<Ylx76&bO1h<HU(LQizP?G?_-xu4i!o=W+67B_AUG5pt!-l88GB_gK{2tJe z;H!gfa}K;$gK!r|9lt^hfDDa?akKXW)sR3jtuFs7ejUj)>l^V2a>t<e7UvY$9}rA) zl#UDn5u>P`okZxe|1}O@h#=!<PBOTww9{*SqscdF1}yCZUGa!}_JIvePZk2fd3+co zC<&AF7%mvGyLQ*n2#O2@bHpy%5L`eD%<)FzlH0>?lt9kk$w(bCis>fb6|1nc0Jf7| z_!h!vYZ{S7j&-pQd_j%`@Tp8!9xfwOOv*K&o$5R#zRCCPHXF#uBuHVSx6I{Kz>A>^ z?=J89(4W)SUW`$zDb?jes+$AqJW&qWY5jcz)Y(C#E846U#-d2k0f$ea-Z%inx&BUf zQ)M!(3E(PVTUbhmJD@=nunz#48Oi@tKpG(P3CKvxG*C;D3N2@VCovWP4A)%KAq6P; z`?v-3%=FBxFfJxz{1cEwV|;u9n*1jSk1J3ag+)n>O!O8zY3OBGq3d-<I^-1*R1pQc z_%6K>mGYD<6(yP?s1pt{;n-Ed89X>lWT0U*gUzW6!mN-{b<-0k0-_W4Nj{kuj$B1C z2{qw@za%eYW-0wpd@~MO*eBEelP@k+-~Eu!J*wPtB@bB2E{p*csOO`Ea{e__t~r4s z#RhKp7$_6`-fe!<4n;*>-BRH@*x3RWZ$Zx=v7`Q08gH#T(lr4>s7o!(rY4{NsF3-L zu93YR-|dJsLH@7}#jmI$jS5Al)bsF6Ex1S?!U6SgqR1$Vm|j4yo8i>mhtN55jw%5^ zc#H5QqR?5znsG4RSg>kJy+kR`F13JmIkVd=xcH$M-H9kID{wt3K^AagxZvSYd2FZh z?oTMS6|<RhCwm<gs&n62d!=FLjPlumraSPv5w1Qu*~~YxKx`O;FB*IuB|Vh_4KgV7 zw84zT%>q%|1lDs7T&#Jee)I}q?6$MzSUW^lzZHjkg5V`xVPUa0r}B!HikvL1z9IvE z`?8T4C8yNN#;mOOFF|JRjEgCntH$U~Qbu<RC5NNLQ0WZpHp;|{{z}Wak=Y_sD!wd= z_@&Iug)VpQLH1LM5u<l;Ko7!e2Ws+zN6G5BiG<9@<`PVSyyv)(Q%?ol`}y93wD)n3 z9SETeT~@0{FZf%q&yB&&tO6Ye@y|m1>$?aYonqu%KIS1UVX9So3E@RO73p5W5uY@_ zQ_yc$c@?IY=VrI7_R{3aW9C|o*>3CDF7?n8A+U=2Qg*Otm7D&32GPEyE^$`*zA(tj zZuiMV*JHLu_iI6OkigAwcw0TM(?9{>Wo$M`k&i9qLcyNeV~0{2G|&{M)e_U7bB=>W zre3mF2N8o#>_*;Iw+AU6PnDc`SkIH;nHkRx)EfU?srJG{L*z&hK_0&^jYiysI=j#Z z+3GQKMHblw5IV$Qr)4me@MJDuCRwU&Ghxz2Kl5vWesRGhdwIcJfxG;3^Vw6SflZ}z z`7VmO+G=11zUoDGmK0O%r&-X@@AYZBdMrtyeXuCQi{4~O9q#bD`%Wg8Gm6%4dkB3o zIG1n!TG5LPf2ZDNWQTG|)z}L_N}N=-@wuZqP~u`D?Wf~VY=07#uOLk0+sm&QU+E_7 zyryK}p|adpVWj5=4>KW-C~dh@u;1-}F&TD*^w~O%4vUV3D+ujMtu(na8G{{-nc0O- zEvz1yk7|f*`ee7!My})Z824I<7K|ECSNau1^M_Nm@m;RvW^|if70oa+j&}LrwD6^v zr@}AK20zx11@ZIUx*9!$tIYG=-TGVckGeHHB6^I6V%t_RW~@CIdC7iwM1v}5b**<j zM)O*5rpr!mS}e93V7P%te=0C>tV-R0X1!R#wGdF%)UG?Nu{Bq~J_<%`!qDI2ajP6U zi42BO-+hk31T3ljhweBbV-LyLh~T7xCB*w3%wtoqv<BVn_3p`WG?fZ3T*A@sV&XKw zN<8?xrvK^&){}sNBq5%Y5sl^n&?H1v!obzQSfFFz7Xfob#L%FXhG5JqY(y3BTWA3z zWO)!EV*0SaON}8Q2GdXJEAJR8B@RthF;4Ri4q%6uJ`YawBA&Jm%~lN$N`t?4h8A-k zPH**jlCf*1;8N>QsTX6vJ>%D$hwaispRWzR&ly?|eqRa<{FV+_*LdIW0ahhryXJ@J z`2vowfiIUBpW`tQrqMUjU<-AaaX9eE3-gCO3Sk=K@C11mM&GWZkL|%@{E!p_!1Q<Y zkJp&^Nn7Bn4#o-!V+C<sZD9;n%gA|sT#;j}v16R68V&0lVV9Y35W@(XjiE-z{tzcj zL%d#gFrH@^*UFWqK`~Yglb1t03fCvt%_jZ;nEsbz!qpQFGIyIaCK0t`0>k69{+?%u zM}_@#AC?xZpHTTWe&5XZ+V$y1>Uc;sV=&*$@;dqtFeOM!0_2XX@=e4gx*k)<EIqYF zWIjB){sEpo4s^_1U-&@JG=BQq2Tat&F?Rad!n8^?h)bO9UYjId2Q|J;8{|s&Nl(MP zXKQ8VxGzsc%gp+~$7%ROm&Y`)GuF37EoGSJG8iMuU?f9kqT9wrLgs7#&QU`yS)GJ{ zF~c8HhsRz~7eaeSuME!)R*xU;%tJaE&*o0fdoFVMV|FwKdNn7n<w}3_9HZUye-Rnu zb0+qyEh?5qrmKd;7KQ-Xr9%cFPGcH*ed(k}fPGk!_Zt<0TV@CaA192kYF+3zU;N-X zI(uzqS_2%{7#`99Ur`u&Z~#7(@fq(*jXsq*4BJ|RHu^S!55Y82Kf>u&U}hl8-A@^c z)GQ4wE$G}2ykk#d+#s&jL{PoSh*ApXs?$f%V%4hM6fgVf6L!#hhyH;n)1`lF|5(>s zh>WgUOq=9&_eG-{p&)Hp%wZecA>w?rK0nr95g_3<fvnJfhQF2;d1+twB5rKl)u;C3 zF)d`Q;WjwXzrh_jvH`4w+yJxN<KYGKY1>A>k-%mRSc(PKYj7wFhBXSqEw0ULsaT)9 z^=Elt@OzLB^VQ+<SNJF+K#hjbZMFQ<@5iq(70@1u@$uFd2wi^n_Bkb4rtE)PSoUud zq2Fd?*@A8`UCI6SSa@TJ|MLp}Hi9m@ZR6V`#qCYm4Yc>W_m8)))o*XMgO9fumhf9U z+xo3Hm=5#4b3emX0$H;_-M{UNML1yc%8tt9cl5;zeMH<>sw@Me^@7~)9UQQ+gJaLP zsQHb9z1ba1-N9?`3E$ikeY7W@zbE--Px|AY?8%;-zz_Ko?H`Iae<(ltp_2bY?adF3 zk3Y0deh>uqb+z|tMB%wd`$qZuCU5plKki>R**6zBu+%=Vx_Myz=)gAr!0ye#wT}lk zP7dq^emZLZbiVo1<<U>K{GaY`etLZTdH3X}m%uL{?O%R3e+4}H6`23)!JA*fAAg0O z{2~e*hG`#0+&qkWbQqI=829Ed;p5@slS8t=?_}-YsW*S8J^G!I|2yl=@0^dn^G<$K z1da-|kBV;|m1whL9~}+r;6782fSv7%o4mmvu=S^LpZWj1)JB_o!F0S}=5pu*;7`*N zo;51gumfsd^GCz$e{uKT!EpZ#`|n5D-acwXi6weS2+_qV(IT=+LIgoX31O9JL00c9 z(S@uQB?v+y>gq(q>Lq#zf&}U18)xtPp67R-=Qrn^Ip^Q=@9xgd?96*+ci-1_y<V)> z)c>^BWA^ru>J&)C3M_&GQ70h3uKXE2TE>>rSZs;^gwY{$g1GL{e`=WiS^fl}5TSM} zj7R=#rSd($fz~6kI@2Mof~<YS?f+FV`7g@k`KbT9iiv*2vu8S@sRGW^x&J3+GS__5 zq);PNRT@T~EY>A*LKdIzZJIs4RB%3;_sR#0sw?NhP%|b=nwo{b+%zm@_*I_#n=*NI z&-(ctm8?_Z*i+=-lJh~^huh<#W?yOHk*JwH24!*?%I#rw;Mi}xn!s_)GOsbTPWs04 z-KPZ#K)7T&3#R43bzE~bhL7j8+a|U8BBNrWc5>nN)X|5co`-zg9l=1GXpDqvqw8E> za)7#k$yY_smGvR{V?TfReVBq7J<0lH=X}4;=jRS~$F7|;)u9z7P2>j#_a>gcIC0~= z*3{hdf(J9TH(IVny%~YY(z@|a^zwtBM?%_c9$URT8yYO1S{;{BQm4&yM*2<r-SzF* zf?Ma0>%h2?aC=_=@l`!-w58LSWOM1kd)lyx)w?K3le(lwVHK5n#j9bQwHJgC_lzHs zUKRDHGHzw4hT<%g_1^a&UxU#phX}NSTSKM3;4n|Ack;f|c5J?fg<pmCImxz$k!Sed zC_evhaM}=)m8&+6o4HQgh&1jiPt=n4!RhUt&W9YS-<OKKg$Zt{hmOQdm--Pe7DRaP zdygCH=c?w<I`Ntu1qlP(f4d&%djbEdm>df>&C`*;c<WJUx4A>1f3*<2If~5s?TUkM z#121cyi4x{4>R#*r(bniYznhg&im0pbw0)GmO`J!^zQog>_!DOu3j0BmbhYm{jM8x zY`$MsnoArI;u_0)C;f^unK>#=obOKDbtQWxmg@tGdcHfS0VNYomxn6=plA>-j@>@v zv@v#b-mS$!{Gr?0@wAk%pu0Ja4`Mx(3IaqB<fx#JFJXcqTQ41!!pzRi;5S&cXSyee zEcTlZVzUfPf^Lt!;0|hL!t+s3f!ZfLh|+UM!bLM8s_u=_CJad{(lu+sYn|!lynpvL z^gI>3*?OmDIc0FrUni?P|K9I<VSq>X0vmtwLX6serJ0>rVP5DgF5gMX?Jz&EaT}`e z-4B|#Svb~YLmGi~KQ3S^DO45kw>q6R@gCozy7)+bx$SNte}`4F+fJH1U(lfpfg|Yo z&uspys224=MO$23yLVmJb+5{_y^P*Ve|inJsHP7J19$HD%(@yPdC2*J4T#wMFg^a8 zL646oDF0*sbSC(rw{qDt-8;&c{I8vwH-wR^#El+>9(f55w0o96y|nw$^AenldA+IB z#B@0j_h)%%Wxdt}f(P<l2PV_6ND20`9Pwd723bxW(_&9qSGQV?Q6CgP=N@N*V^Z!? zc>EmGDbuT=)VqqAV(DhDO>}>?X0Dm#U7ut+%+LI@Kj=idj@UPPyf6ZG7y^=o4DQ_C zon?)`&D4G)?Lz2>d&NUZUuy$L+%0E$_{NdcMi0Mt4mWIW@NBrUCD!*~WG$d-*0W8w zWU9T~-LK;#BWhHthC`<fvKlKODPDdo{F^*!C#(Wfj%Y@d>{2tKbH~#%%1$OSRrIM+ zqLTw>Y0mf6v*D+jhCJdU`Df|<V|l%LgO%WIlvAA46-$k)-^TF;7J7o0In~UYboh)s z;2fDRPn`JWLtK~8S9&d%?6!3=AmK=-koU`bEek29++~l)@&&nPJ&a47FE!_`t*7-d z8JFB>|1A*e_i~smVdB!dLH>^r(lEXLU3A&bb#(#d%Tsga57$NV=l*bATrhMDn3d3f z6Q)P3K0bNrTJSBk!{<sKyJP0Z)Y&k;hNh3MO=dfpZhmXo?DCBB(shwt{tIfGeVCdk zy}~^3`;VIzha4{M>g;93+sbAUOOx3=dwNPxD>CyuCJ5fhr1Y|=l4PAyJRyHOpS<11 zQTZTp^9TN3m1=wOyuuR)zfq;;v~Di{cL@RN;b$qLDMgPPDqPyxl?T1$ev2|rpjp34 zy3yp5wI&LgIhm8AS$!<@FzBb6;E}^!H>*=@wMkz-Y$-aakS*KfFGZK_@~@Vf&-Kar zZP;X;Fj*fIc;n|Hg4s(DQ*Lr~Ls##THskp7FmXncRSFxoJdR-HHyun9ZU5<45E;9+ z)TAgx!_<<VuvB<wuw?Ccn7O<S#BO-5@h^ZC>P2em+gWtS3W%F(htRBlW29S$2Haz~ zRXBv1aALx~3rMJMy^|BkzgMBJ(!sPG9^v01!VgonIET5VF3vx1j{_{uu^Bra(i*<< zL~b0|HVuikAu37HXLfac9=_`gd$3@|#k|0F6P}l0A@||7>KwNkTW%Dy3)a1@m^9cZ z{Q9*wM*zRpp&e@q8{c8{>!V-C5dtbHhW+l8X!NbShSy>(`ky>ljk{&(_A}8&u{xwn zT3Rl3uJ~PYZSJCi-MQbXv{Q<td|02O%5_|xOEJ7)!p7yq6U5n9KjovD+g;9cB=f(e z_FGmQy#F!YNDsH>z_Q72iE664kGOiZrzjT%S^qN2zPP3+^<jJMTqLiQ0rxrKKaA-{ z%H*ByQsp;e*zm@a@g2cU)4gL!zC1LR4Z0uw#JJ`(2(y3LF-}@HqXbsFNDpFd<N-Rs z5@kO<Iop^No2|P6#*WiJ`bM8eJ8XvWEX<`pXGRnE++E(*hAF0hVr746^yvEe^DGKD zeJv0^FuT-k^u6Ut4cCzep?>LzJ6)Eceagm%xH26JWC={Z6TkbC4;JtvVIe%#ic_TF zIL=D`Rgou)I>7EP(XaWc9;2t^#GA<)lsSIV{2W;9wx05{u3{$115W_;WeM{AS_zH@ z*JqEbz|_tcepcKDIE*c4-c+t~nemWedpsB9DvCIhVnK!Gn3fPAE9u69BM4AffLW&c zI^3y^&3zpWJMfE#6U)hU9(_euThRA~hK~B5XtiAc;0Jo9!(f5(dRoZa@NU3=c1-`Z z_X+Kjf0dP>1Y8V$s>S*|agI^+cz%HN;5>O^lIA}nsO^5{`NHSE`dEQ^Sytyj`oPl{ z>BoewCKca1D(3MY_@~9HOxFUSAs}7%*bDeVPTeZuDP2*~R~QcAhWv%QDaCbG3gR1b zdKPOn;jVZX*<{iYKfiq5q5FDFg!)bXF~j>*+9wL)Ek9rsf8^I@O1Z)#a%XE)^R8){ z38fr}!f^eJRm8(p!8jFwd|!^R!v<4Ip#7|fLMGwsdI&GbPXlK)!|R|qZ)w$Otcxm- zZt`i(&bEe=RXB~i?gm9#$HiV@q8*b)zX8a%E4299GL!%y;GNbEu>&unO}gG1UdQ6P z|5%tmYnmr6Ea%0~o81+z$^Z?<FqTTQlKlf?CDA;uudAN%NW28bIWg8~AWIZYMUFG8 zOx|9nZ;Mq)I_^Y}&YiAKRp}%~jG_^xXvq^N!UMP4RzJ^~_4Z_MgDeEFhbXK>ajEy} z_ns|bA*&8*GrkTDdV2-(BVFoxjlc9>X8bzj>@yX)kh~8u1IYRkeOF4QFIKSJpy*!B zxR5xnX8oIXt@naU71X@~ihSL7!>Noat7|XPFJKP2tE?d|-G2*R5;hnk>(uX>(eGBO z7Y%mZ?(LsO{I}%(KX8cl|1ZhC$^q>E3J#G`3&{HZPdJ1emyKhL@&ABBoM1Od;E;^G z0`M25K`&4L7aZbxT6-1(%}Rb?2KW@B(d;qy0_tH)$P>oRb*nvb*A8=8s3!I;cCg1< z>COM~L!M8H_tX-vm%x3A9QgeHUw%lt5#EzGO^_qZ&CC@||4!~Z)M4Mc?IM?QI0K^& zKE4}#aO#HVS0jOow<xo6BW*2TcV?gYW@zl!e*3o{Qt%9&UF(_uIOPTd4smZP>_gkX z;1K^*MM4*sM>{)@@+|52Sji(U*OhR%kI2APKw1$dS|cK{8pUZ8m@Ue7C}$ka@4vMg z>?$opu?+!M1Wp0yNMR{pftf5<|K;mylEQQj?=fA_2_dS6RCpc3QUoWTdC24PF3mvf zCpQNq)5=aD0PTdJFxP7v@pMR5Ze-b*d>ugF9dtoRiAr&;YPtAVzR&acI|&0CM$#Uq z0(Hg3geo2ua@w75+nbNXi-e+0n2RC|Q(f^+{9;Q?|MEi`^+t0ud&^NCBy;;2Njh9$ zB==Na21%lrO&1~N^r50iO43INB6uz4Uw+6?>pY66*`VbKKpH7xUEK&h<&jR*Wu)&m z9%Jqga?Oll2suBV57$jzy;#Ie$nc>AsW!|eNVPA8LmxrEI_|yPS~}KC=*K!eA(S`p z3=n)5Oy3j2d7d#caT^hn762B)S2n;ca^WURkt0H|qT(=7wBRs2CK&S7(euLa!;|~{ z{3TgBl6xn5^-J2#5)6xT{TY79>2Nf;>{C|2?V$MiSFkQ=h9A;%i1)e?7SMI84ykzG z<zA*HUZdc19b}LsKIH`<U-aj>@K+BTw|<$n;dp*Q@)C-3gWE>;+SBHWhlb8vriZ4& zf@ghZzApGZJNHe1@a(NXV%fq`SzmO^w9JncOE(m41{Q6zCfVjVUMcFTd|a<M%F<KC z%$||+&oXD8g-PkXFng*Mj_dWZsi)Td+AhEG@z;*D_h|~Zbc-;!0l#4l`&jq=<L}E^ zA6>r`_6%-`ya1?0cXj{#{rKlI*Krdfwv(ZTeee>e`>Kx~@TpzD0mT_+%Q7?&D|+{# zAa~O8i%%Uoaq=18YaFm5C4_~}r$>L+<Q2lSw#^Ox@{gm;q*L$1ORv9IJ;wIM+lh=w zS{diIs-wQVh`(WwOIUycUoztY*wICwmBrh8jz963XFxYbkG=HC-Ejof4L<7{=w!JK zlRjS@eE4bxOq|+}jrhI%<tXK@EU-(||GKkM2xr&9tERcDa6YOjE!UDPV!}1MJH9L& zyigYEfmcq<8mx;21@jJ~8Ggv=kJJp~Z6iypMG60l$2I)$G@%gC93|>ZdH=Ki26Ngl zKg{q+-5sF>wpA*-&^U^~ewdaf<)DR~qlsU`0oMEmVnRbhrx#6yLk*V?NSlL^9t{sF zEYd|#jsvlNAHp!{IPvFeI%3mjGn;KDX3igHQx^$$G^O&_?JM;}?1m$6QzHo#lws$v zxCnH7uGWfd{^Af5#z&%rU=&2*;&ej4@_Vc-$~vNxat3ya65*;F3DrKno(IdFmV88j zNzt_s%ws*u-zATPjF2J;OX>#YAUjkg11p?IW#&p5dL2<wRP-ll>)!m-tMG>$fPp<T zrjZCSvSrHuc2P&GhXR#zWkQlFgtap&>5;Q5&|oGSC}L!OxN^t0nw5s^o;Ko@6_U1& z>n3b~(76?dQfKc?Ev{n0OCqI+t6&`8ZKJ7Ay4x;76Wbz8KvV?lU3?%|$xp@$m)nLr z;^HNNLTa`cxeMtfpmSyO_EhTX-UHizT&#+T(^Aq*rF$Z9(`P}^4q{GKw`B}0W{|)+ z&<QS=dCFGYosa5`O}kXm^+#7HvRyT~0?1*~8YjFe;}v;$*~&vpL@QRqz_BXDR_2yV zYu?Dw$fx^3H^()ZK*$pGE;V%fqSvafg<J+#6x{R)S576XEIbPP%VU>-XB1b*zqORF z3ecrmqRHa`U|Nd4RYi+x=&qy!_-^*UMw6lsUkm+UC7)d+L~k(TtM1Xoc^FEjA;<5X zd0LU=JGZ2Dk?XCj4%#UlyijenCTWKIA%#`@D!wfq=~E%DZNV2QK1+kD^2BjCe_)9) zzRSU^0tL*p&_FAXoK2ktr=L5>%fX5$du19Kq&B<SE!n6AvTQJ9Wg3kcctwdgoIREG zRFY8ra_=VFRS(Ei$B$Rh4&%q5!n`b-0D@1{Akw#2?Xy@^3q1Z)C}!=(rKo2|gH|ce z?4`q>J)N_920sA@Ly%;tA3qA1CEe{1#q``0r3hwIW{W%El^4QJ97XWxyO3hE%5_y4 z2l6c~1$PR6)@{j?8;j>Q$ni>?BGA8F2C)ZotfGFiuVSFI6Ia#TBj7#L%t3uMXGYvB zImhskC%$N<gOCCzRl4mzwLD7-6s3nu!01(v+gyuI?WI?RBuwID?b3F_+lt4#T?dpH zt9iTp-{Oj528F(G1?^}Dgc|oC7d$f}fCZ0!oE2HggpYC6d_Hxa*v(;t2KW@Z=;?KX zwE-Bizu!sz&6L1P9YhTWL7q0?hi9Fn`7ZSB+a*?}?kFa*10WKfTX}RMj@^TLj88(S z<0diE=@B(HR43{!vs+AWz!HZMKtLJ5rON(>fV@c|iei>$+F<D}wa9ghj{%GI6xBH$ zB~nH7jI&WYaK3)OmAe3pQwlWsmMwA<zkS+((51Gu664<v6`DlH;aMK&*kZ4U$8kYx zSru5wofqsPwMAB)W8@#==OtR#t{g_+a!^2OAA^rU&a&`Yg?(fYQpywxKy&eM{I8;J ziylK5&0Loq@%`JH<x%>F)uet(Y@3!V-a1A^Y7gSA!u3U-;?lbM`9fGw`lHtIn8^r` zrLw>I+UTDQR*i2r3JNb{JSe|ywXhfQJ_{SaVYkM$a&M9%k9Zt!N4o9^?Lxdg{f;&4 zc>a0vb6+!lH}s+(^;(;dJT)TNi4r4PcW%sw9=Zqv<n}{Z4p@IQhIuep5wdQqT7gjk z-~j+E?qfE<`#cgHDl}FV(tX(2byD4FTI^*-s<9hzmqm`uoOZV+8f+qho)jO)>~IB% z`<mGxfe;Gof>_dzz2=0z7O}R#LoEpqW&_y$73UN01Kvb~nPOn;V|1)#q(vP2=khDe zU969u%LF};cwfe92s*k<6HP9_BI!}cE>cU3`<2-k!7dTyNdJkRa6}PgmOU1rd7QOp zX|e=;NKnH#hkJOKi72d63CCEHo{94XXmM3Xn=zC@wsuHpL%{ueF|m*$H%D?PfJc1P z1*fNA7AqE!vv*tY;F)I7ohQD!ncW!A{7|2$OVSKo5g_4}B=nr}i0<il^oxFU>+=M= z0FZYgp?{0bm=ej;<pEzM2PuJF@MJqnH-{O_Kw$FN<Q1J`LDjm)31k}tQwsb5_FE6~ z_}d+pF-LO)Fhv>M1hBI_sc4~l^#gvNBTd$<LgSyuYjV4?M2Co!CqAYmK)UYiz=5~l zqL|Y#hqDy6G!_MlWkz^BS_?lR3ah7bNaVPm352{NqFUdh;VS8f@DyxNI$X%_>nt0$ ziZIm@0TV(e=ER-ZLZ!~enI1`i6LhS^HbqH32)-H)cHN^hi^C@IZt!U3016-*zA^pa zz(DULgJ@xIHIW{uj$ktmazA4BCjQLi>S872vYw@yLAod-`_5kosIiqhF)rW^6>}Mp zHM6A!3y(FXi3q?m(p^AnV$|bv$1vjHyA_Q3PeyMHF-AZ^x-$9<vS*ZG{_*E?2$HNU zp+{d_nzO-+cqog5)uruB0FT`ug#&oxNCjeo5=fb&uv`JHt-uG_se%&V{C5zv#2!+y zLqtzB0+^*|T${_o7^<9b%2sy0X@Ea@R`^nw0oyVW$0FysLBLKSfMUakvs--cZ!)4r zAKQ(a?nnA|xNwBCR>pj8A(!|0Vkgj)aNLH*>adc`Yzp!A1CzWH`J5!Fm0)>AVU469 zi4*!%h4C7ekV-HqO(L>RjWZkt@D{n&1=Ux&EJs7f{mwJ95g<hz0b2QRxrf8YifV>n zmhgO=On*`dgfgMEeNymNrap%dj@cCV*s$1ssF3sL<>R+NnP5p#W|ewjd$xKEK+8GY z4^u|wZu=L*yVS6pIdzAio^^>*OR0p4iVvJExm#;j67)Hli8IBWOeoVho`V}JHkEpO z%puu%{y|P%w4G>17CtL*rEF6kcAuQ#HDCVO;C|Li&|yVD<`s;z!aBKL9M)37dZbkd ztIvJvc78MRsspo9Qg9`+w_isDXiO_o=z%?~sK`mEwB9%WKAjCe;NNCZ@w|D$grt!L zLVfMCO6JSgnM+w$6$^tT85Hp3U^R5O`sMD&9lTTrs=>FLU|S?qlM9k}6_!)SYC(F` z$6IvP`a~cPq~*}Xf#NwBe++Y2HkDTxBqHYeN(U=seZyLKQ?-^&s=7(CmXB4x_d~5; ze06z?maA;gf-rCR=Xkh|!Z&1AFtf~P+SB<ea1T*^@+8PmP4UjxvfN8fa#aVr9`AlI z*?LyTk(j<*hlO0MxVz#~+#=&>26n$H(wwg+&Y^ui`?}%<yGv8~)<uku#{aGMv#)gw zz9@Y!`Q{5Wq?9ujFX*ofs~dmBx1%Wb?$~UPzUJEp$4(kB4DjgjN1pEr@{xd;Q0-_D zgq^RcH(s4t3Ur`UBzF~+`DQroQ2M@rySWmscOTty)Vp&p-Fpn&-EM+$L0dVL9}=1Z z64M!*gEkg@6BZzrD6FR1EHQWHQe&=3L%A32QVJ@!+~Qf>b=ZwH*u8lHKEIb%y!!FQ zMQ6#dthbMfPo)kM5u(g_3B9!};f0I!D38{bS=X0hJH?{fPQ1ELn%$Fv+=UUVWn~<R zUB5GPC#&Mei|-S&Tr-~xy?x*#q~c0L8jWdZGpqb!f}M3dHgSZ?ZKa+v{~&NL|9q?z z_yP&M<>(0fttB;8<wk=1FapDOIxv;3=c`T`k|3Rlol&hIKWmNA3hR5eobxDJb)b>D zJHle66WLapdAucLB{v6r&W4Uh`~hj=a$obhcth&Fdy|N$?!$`C`0E*F4HgmZ-B$+B z_>7@=9yWxqcI2#g9|X42@+23ETa<00jk=J1RB(XT`j;H-`?D_1g_v?D?w(abmK3=A ztT*jPm*fIZO+uT6O{7E;Xt~dFA76`a={qpM>+ZucjljK&{by`ITWRoeTNOZnR#VP- zyzWaFhI!?Ks%e)Bg9kjV>T(nPNcdcGNRmu7_~B?wQrTQsHDoZc{2ckqpnX#lg+Ja} zXNXw~lf964c?Grbxxr{*C@se@-uPAZ5A;96jCKUfGU3&%YwPZHL=HvnJurO0!*h)t z_l`X5xrHiUKxN`FO4g4%c4NFkUQ+^**~F%y>etnQujuG_7p0NukP&tfWG``K>LmDr zh8m=yW^JMe0pKGAJ+zNvkSdPcbeWlO?~Eh8smK?!oGPG*nGN=Xf0QQ<^^2zb7Y+P< zE%hfUyiykYyE|G=#X)Q%iwGd9osO)*y`U*$_Rc>badX@Oxsy>-A!7*EQL`dCB#n*^ z_5TQr@5v)dsaTy51f7gE4ac26Y8Yj!!TkuqN&TZyPDXh#BT9+rLRqdPw=rg>qCIJP z(#wg_o6u|kNhN~eY+S!rkXJ%M1|NgL!O$C-{8)l|L4GqtW+b%0Lu1ZAD~z)zJXAMn zhfyPu;Vi2N9b54G%GiY>q+2NJHvphzz&}(*g`dGP1LA*7*O~Jb0?0w)3?v*!Oq=>m zLj5Ap10!bN^dtemREiAO9~u~X34D}1m-!hEV?ss%z(@$^3vf15W0u);E?fpx`j2X1 zS5h2(Hc^JIul2U}4p?10-KYW9*}nDVxRFYPzkZKM#sHPcoX<;ewG`A#vUrKWLJ?-R z|BlM_F<8@)7HAsES)u`UY0TGPfULcl`MsHU?TgoY@Gu7$F>U%w%}iJF(i{dT8KLj( zEvbHn`t7si0m}f`4p3l2z?_~CD!gD?W_%^{4%oN1tacMNrwe0fDx(Pk%%(G8RGg$O zC-(I01DUt5u_X?ZRX$(VW*Xjy%2GcCJ8lbl<Cnkfb4c1PHxw*EyKwj0m;b3*+bW)B z_J%+6hp^beAqSi?-#8u!tVi5g#MREQ%FSL~T8fof=Zg$^-N;3z!~A8DjrOoy+1?@2 zJ57hFD*8;g23T7&6WzY#d3yC1WzE_|CYO8$U61q!*A!QU>-OG8Xl$)tS}3krf*%Q? zT*Ed`om{@h3tw<nNHpR2){bNSXZ_ovaCGf5ENvqeTl9lEkyLwjQUP8<KT}9R707UK zYRneN%+_kmJuF=Ie}k*6!^I}!8cDd;^B(|ns52cVp~z~qAFt!_MpJI#%gDA`$`;fC zRid$gOv5p2O?RA@PQ!zaBqG6Q_gvSz!1TpmvP-(BLHc<xv|tAy;gE0M#$e{oVt|9N zy{<!K+W?{w1;}JgYIskvc1d}sfV-!`;xJrnC{FOwC*U&|Tn>u4wRxs!iaB)V=+Ed2 zMu*0BzvwhbshQY&a{y3LpRvF#nNJ@G(-QX&r5+uge7f&G9to`ly^iWS&M<up3q{`E zJK%phF+|0AF0zRpAs9f2UqyXCSpgh|qj~=`!*2a0WRj@4nxO%Hr%pUbdBgu{o3kG4 zsrtp19aT?HVP&H9t@xgi+h#sMoL&=t^%04<41OfzzO7(gae&~bubbM)Na}Z>?)!bP zJqmb0+F#sBK^2=E0{;d`e53wI(q!LI2RHwGV=?^>E5eGVe&1~P9!WoQPqQ_Yx(==9 z+9Hm4ecBW@orDT);~akG-H;)HDD-HD<5RE%|FeDs{6_lD)%B*F0%JgIdVGJdr~Q1Y zDSfY{yq^B^-qSe%{|hWa4a&}D9I-Jv8t@xz(_w!$j}Bp__;*o{G>}@z(So1*Hiug) z*e4|R+D<UX>(7Fwv_BdBNa;5u7wn_2Gc#dWnU4OG+<%1s%MV#Zh(vKzMaH~Y{eOl- z;PUbeZac^Uy}&N}`q?toyQ=>i9D=U(fR+7}p84ZPWvH$zegE-8{tFH<y@}5~=Z1}% zZW7mWL;Q@7=Ck~0({gujY0BE4C}c)27Pe@-yVv4_Y8UtxW64PF|K*2#=m%<<g^p`S z2h%xDSF1~UCh}W<ab@@+b*9yjwB@NjkBI1U;t9Z;<;eX}f5G+do=ffGzl7sPvIwKB z;w*Sk7YjMp(BDR)fmN$!ep{0@%%r<imF30u`!K<!)3N{!vc%4FoyxC{%`d-&0WxZ< z-TRjR?T36sd;MGda*;7MxJ)JL?8!k~NTX4VCQR^Oa0uA1(Y8dJd&r(C&SEcZoF=QB zE}JG2Yz83AV(faX^DcspyU*euKf9Xft@qU8xSYN~z<RwD3USz{8L?7-`Ei9uaLwa# z|9ZLOPLv|#sr)zF^+u<j_WG1^M5`a*@8+?&He<#b(q4vBRN%SWl-nS=w;@X2L}gQ9 zOq=7FSt`}hafmo{{4J+z=EbV+T7FN@eEB2O3&;K;4u(ge&58;SIper516Iz);dIth z{Cb*@bCbXSa%{aZgA|JuHDX&f*ee{bWs2=8*C0>W(srSyrU4sGGlO<=(dy>IYGcRD z|JGfmI=h~`P%zWGZcfEAU3%5w8PcbC{myoAL#icNT8?mJ%)~(!pD1}<B$DRMew>&w ze)oFNW?4YxZQzGap8YTjwKwu3geGu%*vwVX8Z^TIwpXux7Wbo6me&P~KW<*5ianuN zafbf9n&&mBvS}T)^!u9yHZyp_G1JmnrPSvGTg7_hYxy#1@0Os6!pQMpuT$~6MGd!# zV#Rn%yx{Cv>PIOPUzhGe4_O(?KK{X@CP(<`s;*$O(=F~#JNuR9%~&|+gmQ7(M9KIr z=hi#LKUqCF&EFhY6m|cqkdS@x{e7!f`s+%4HDK`9Se@}ddg|VNm#sG+`o9q>FZNY_ zKT~9IY=8lWkYg{eN#I{p_Zz#A`e!T}DX4LGN=d(cc<M%M`yI~+{{n6L%>j+?#b;)C zE-c=Mg>99NyweDLm->lorJISLFKF}8%(Tf?dHLU0B(Z_kpJ8c_ZT3HO!ZfvMFu~p% zv1=Fx9HP(HhH90-<sbTUa~Ws9{HdG)hX~c-y!rX%(hUGok*~?%+AbVtz#-tdUILyB zI0V&EM6ayr!vF8#5Vua>eR<LD+jw>-tFvshim@a2M9zS&^V!Uo#?Fcpxua3e3S}yn zZeN|qn>p%rR&08C$<u!#f0<SMVMllesoV6#o~ypfqOwUiT1sdMudjab`#>PFw6K$N zU`&i1r=3;8f0xfd{huLYpEWr<>Z*%!x7_Hh2q=JVFFF6!5HtW*_-?sN+(Gi{M<<jB z0)f1uG!n(nzJz~iSX2*k76Mc=2?34o^w=WIu1j$Om8x+UaqKwXKo)9%F%0-3o8}k% zp}eWF@*i+5HM9RDpK{+xCG1+HwZzS;XZ71MFe%FIx=4KGzP=RPhnaF>z0kXKTRVfT zfvo){a}Ctj&?tKrO#uKcROz|uA`CFeEJSK5(_~7dMQ=?O2JYQF*XZ3ihi2uQmw0`2 z)eSN8?8N#Bq{;{Wmtz<Yyc6Fdar?%t+ZX)<Gx3W#TLLo&$-aT9PqofD--JXY`#I_0 zA%j?;7GecBH6@ca?kN5+1l{qyjW|fHOqbA9WT`nHmTOQ9pwFqF{*pT>5T{O%$3$5% zL}6t&A&_qDE_S`-HH7TsK9oW?u@s7Ux5w9+W(}-x1G{7yt#L%k+urP~r7fr*LVGES zI+OBRpq5~i09KB_$W|oo-;;FJ-;YqJ*x(ve<o6i<B*xkk$~q8>`>L=<cffD(z)t_8 zM!A%uD6qhFN1!Xs@u|^w{9A*4xe1lQO))EWSbeuvo5RYGuv91X^-~e(5y>0~;Z9x6 zd8+e`0xrK{uYEUI?ZHvaxJ|f<Kh^&(!V5(fWFb`9$B5d;OM`ol{n0Ehk$Io3?4H&J zWg)LrDE<h3_YGV6>TdM~z@X{|Q2JxE-eN1H?_fgSPeo|jU?5jNvHz6IReYc5paN}G z(#P03Q-Ev0C)Jo@s-*JfuHPwOy?#bRu(z}_Y^PYG&qfKZd)&@euM#D*srcCHHOa18 zTfN4pS&DNQkZ4lmc{S%l3r_CH{1DsOh2=p-sqsA*P5WnleTf-=Vik-H+~L9A@w>^} zaPFDno3u55<=<KF=<-?(;mN^yC8Gh=c;!JktiM!aL+7q+q0HjIQMaECwdegtC!~_- zS^6~xY3b4{dfq$1a$)V5_&b`MonE+?dNT9CvjI)4Pg?%iBXPls=8H=gf}Xb(ezg0^ zm5lUB9^g-uFMm1G8Rwh6)0U_{`f{|%z_%E+n2_chG=350TO!W3Z4~fRC*Sizacsy3 zrKiCoPe1Bbya?H`P`K?C`S))1^@82A$JDeM!~Df+3--KX?=5Vc4``WL{1`BBZ|Q4C zK*#sRPxoOVD-g}V?qf^)vHBrvT%CdaN`={@E4`<GtPGT0_7zx4)>rd+SSOC^-Rm)i zp05~7353WD-1X3}%E7+YxX#6Z=f$d*j@^iQ>diO#LtnE(Yu4%TC=9PS7t^zCkW$XA z10K0T*C~}mI(EJJzVv{(p#$0Q&&exNXWlEBNgJ%0m+(MkX(uVm9s{GqUn{uIuc=q> zIi?p2KKVzTH!(Hr!*$KS-HrWCDO!~BA-RUjp^#tlfF`~Dp8Vs~t_%&~^By_p_ua`L zp6NEdeTwh#;6cVF>gmrXOb{YN4#luI!RXx`PDq$%-81D69i|Lplrl3555z2o)y$QF zIUw9T<X4-Iaomda$47s98-8CR#sf(HeM%EsmF&rIOYubOQ(}+Fk{!WV5BpBxUA#|o zdxZq_c23kWAa}8(n>&I3wm~Mt2^9!*<Ey*QpoM&7V?~_t(WX3*+xutF*%Y-LaQaeX zj&sVYIu*6Z#p=A%k<C!O`QIn+eoS0IA+sFw|0}D4ek2>9%cF8w^1lb?zRpA8LWVKb zjLG}|vMQKntE5WVzG|$TC}&LG%YFcasV7&Tou5_xugUwVX%^raT7xP&%<TvdcYph; z;NpwZ#4}*~)*@r_ZrA#6t3vbsg`k7Ari*RLg@mBQw?hwRM(Z8>bA)bogdC?ij^t^m z*`aB2j&G7RpFr_X8@I;dGzPL5H@6;d8@+bkjNE(fwa^&=`-Ew0CcSGv$%1!je))Ox zP7l-UHyNAeJG0Nc@;hn-njA;69vz*GZ5Q}Snrm>o@o3TE?)InS&qwV-gF`=zAG{sC z&v1?${f1O5lm8;D@Zo^4t9=AaF$eDl>Pf6xOkZ&=ihdomHY8F=Ig6B>eaL~89I=^s z6F6(@Dg=x>Gzurmm`J>11m~{V3CjNZ3F0GPtc>N<@>XNTfk5VX@jkzRH;T&EE~XDm z`d!~;SX_16FeP4XzNAk10|x>}h$VwDeCa=4rHK>{il|8GH9BS;vy<FpOx}aoA5IsT zqf=MfwT<MQLkwSu=rHduo=OYU9#IkQH)Jc6QFYra&A577QhULvYWwj5<)n$4fFeu0 zK$rwGneyO|;g*DkqK;AVWaH6030+fd>(#R6_f_th+W^Hx6Zq1Dt?RCRcS&VZS=b=9 zl){{R++WvyK%&nn!byH5Z4D-w6w@Q-%a(TXWAl2Jdu?;;<0l_mBEy-;T>JeOqfZ>x z-Ncq$NY_S7x<xs}Py(abVz|S=$V>9W(i}q)a~Yp6shFL1a(}RUl`(lY!_*O(SRkPE znG*aqf}8P+62j~IBMs7cg>_5^Cn<f<!{tXGLrBI&@tCM=C`WyKNq}Ka_v;?J^Tk;D z2Q7kN^cx^doL3%+;7X&kzy(Yu0c`|;F6se+hg2Ol)j#{Xb7z%>df2@r%wJ2))(t)` zMNFy6_33Zcd|%@K=V)S7lgx5@RAEA*BuUIm`5@-FYzDC#o}zymL<2M+5~FHUtAkMW zvtt#=*=K_a&PpN4!Se!91%%zEkH0=V`7HCBVO1#22{>pwYanO|Fp;qiv9<(&KN27x zoQ%@A0N7iGb$_;hTCaD^&SvZaw^oi8S`65A#GKRprgQvOYW$h=TJKXI{r&af#pvJP z9|v$pe-39ZAN})fGxg~2;mk({BTTO6Yr}qo@E0l+)l7zS*8za6eYl<#i!`ebGeGh{ za<I}k6{ry$lQeI0+6pJ@*{)-41c)-6@g%@1&Ci6qwa<LK4b<UXD?<ZyLcr}oo%S#E z7{YoH;fQ3=!_R&Yr)TWQmK~=nCRHC#3@PR;FzA!G>YZ@)^%^JB;Dys2-DsDJIleH) zZAUZ+)G3E^OjD4Gd8-(w3MOuveY6;D1<E+m$2*AUqzPKl-h+|S^a?E@!Yb$s5b(^a zv5swP`kKK`A}}*FV8EW9og^Z1?&Xjr*qip~i-_n2NsyRwHlsqlOzNWHt20gG8P&$O zq%F6Nu1%+B)wSI^7I00?zUjT-D}36S+j6*jD=dOD)PAvVMAR+gNZt{i=x=#U$pM@x z*t=2PC;iv;B?5&o7Xg5q)htqSr3f1aj}rL6l<V7ABJfpNUt>iQ4C#7cde|mj^8WbI zXy^y|M_&P;0|1HPhtCRO=Oi?^tche{zas3dEgil*dYpA*F;BFso@CWnijP8J8+v<5 zq#ki8!-BnOR@aEBE<Wq=WSPuV)LCxxBz=bdp^pqb2iK1^4`SwYR*pFKhX{4c)Z!LO zVqxE>#2a#!2rSyO_kD~J52s%$wHmqI_bV+$^xUw1?Jr%KH*}RVl!TbVAK3yVSEvnK z1Xu4GV?Hc|^(t^z(H`Eh9V?sa_|;^@V#Nz6JXc6&vUfZ03RCRus&LdTzMQZ^5$~|l zlbBtFTS@eEnm{0o5*<)$5Gh!!67NgD^0ea89{umD`Dt!vQnkaSRjUc!TSvyuq*wNr z&b62p`2qlYsnykI>IzBL%0)17iZ<rzw`<RSb>RTzi1R)bDKG9u)~*fK`tKM`eQf#G zx^gG++-w)tJ?VSfri@qcL=nb4=biSZtiIeX9v&LBrPB+r0>MPqGc;N22>3p~t38xB zD17YxVU$YmLGrGDc9m?)?Lcwk)yEHS^1lOOW8|wHNTk3Xf$6$te)O`(4=phM2k{vo zi+0@Vg1&34#+yjTDfkJ2$<4Ya9<QVbG)3}>gvpjx^VTEzeh%v7=2MC$3pA32X;eBr zR(o3IEJX-anxM;DB`bmznC0lTf-3X0EsFNU4;q*}%L{K<RBZiuG(!5Tr&es3?EKS# zvm~ci+`kAd_0S&fMD7-30$6|fxN<VoaHkuEFy7Vg_%JcgO2rqQ0jGeGoHt*LB}Uwo z14;zE+^5clu}&+InUI?JNC66<({viu7*qjMsS?6ozWZz1^LgXrfRUXC5_7MOp?6Q# zN1H#yMsk_}WWm?O7zK65xxX@zZ0ZiE>p8KPw4nZ3!6SQ~*Vkv}-;Aj=tRk**<xloe zBe8&19G=>RO{8QAyawQYy<Gxd;jo&Qe4Y|Pzn1|oc)sw$C)Ax1MpHWDWf#kkTaFgY zhoX)5Ux({RJ90kV?-jkuL=I6`eGBQlLen?#iHhPk@;&+n#)q&LnsPD$wpPq?e{>Tp zD+2W!;&e1CN){g^wyhHcU;2gA3LiF`*9tJ3%T;JW01IL36x!3+Zx@gOJY6Tg?#C$c z8h^P4`DZ5&8ZaZ%hzXchaXRM}BL+}n3A*NN39h=ak6(KOvn2w_AAin@qQ7+r=BiX- zLg=;TDgGHO*VTe`aKG?zmiF)T`Priym}C<I79tND*xTMix-C2Jb#(i2!E5y|Z+pr< z7uW@1vSE1KE$Js$?DtHiC&N)hO1D*-*gspEqrXpn(zr-@j#Zp?KpuzdoY>)+e5LfW zB&6DrYfz$Jh3C(2;qQNcg(h2k_0CvaJzB+-QU;Dx*0oa9pCR-5^q{9FwUDIs!Y$T; zjz8C){QlKBr#f#nfM4HFa6`Xi&!nS+2+*Jv*rR>%5h`|sfchYdoLrIp_Tt`WrSNMP zP6w6+MGVN#aow1%Lr3mI1Fj;=WYHoy*a{-DoCLe0kER2_5CJ(wlRtUYohQedGceMs zDU_=r{JlNq;R@{HK4Qxry(Np@-bZcQM=^&ZgD5axl2;7O4L{?>(iNZ_7;Uredy5;p zOvfycu%q^{3<7kR5TO?r<r)~JABXH&iTKAJyGXhBhucRsBHI6l=Dl*;jeR@#G2AQ( zW=2QdszV#*#Kg>=+9o2iv#~pM7~doK{i}ho={ZW=R*{?C^4OD?Q@<lJNU#_m)*1lg zQV|m~=(tS^65+wk---{8wtVm-A>^bahYm@q!FC<Q4bxC<vgisjGJuF2rNBD(QNqdz zWrPHMS2XhhiV?K!;7@mL`rd^nPBtseJ14Hwu%-JbJx1Gr1j{00Z;@hp1CwH1Q{r6% zdg{;zP0{1Z$x}S385Kcu5bOalVwj5UAtKGl4Ad^lUlwf;m?WGNGf)xpjfnh3j_O&F zIXjq8A)3mrq86NK>rtGnXAsvfi?*RTE(9W&RVeyaNT?wNz(;(eCAaP;J%Oib%csez zh*HFY`5aEIldwHUbmTTAH7XD$9vIb0fyKwgu}Vh7TOlj#5wER~Hvqsx89fUme;T_h zcP&$%*{#44%gm;fC5B}eN+b!pwAG<?a<F1nkbXk?HXV6OHiNY?rmPOqNkhI?PP$`- z3?f9l*$Oj9+`sxW8#MFZ+sDk)<&zo&I1ZdCVzF~g*q5$ZAL`Q18%FfZBE!J+9)l$P z?F^%zC?geg6)h=%lDH}B%%<#SyPZjXnHTQuHenh#LO}Pfpx;n6>c=sceI6*qU!EAa z{;m$&CyQ>)!S>6-GFDOzToFNaiMf*L!d6LzDoI&&NfiK4Llc|*8aEG3t)46J5yE0m zx=bG7^T$Y-_maq7I--{*zg%ZsY-tJDW8c^1RJr-j5?v^b=<n>fIazdueRj{vgALb= zAObSyT1J^YLOdrUHz@nJ0m2s)wh>QG+bZDZ<$5a$M&}m3pDUW7AZ7@-F{=Gq-Q8t8 zXd4(D^W9{Fj%f}uFCiiaexhpd6cH<Q>mUm4h6s>_Rm-N28ph<t$8ESG41!=|l^Nng ziO4*-9~bsxbHN#(B8y*~$C1EkUR((s@nxmxy(Ij7E^dsD=wHj6K5$zD^Lt5{hL;k1 zb?8U*#9YJlg~8+s67pOE@?_<MyGH5EKOw$(aV+r}hVdCfZip%p&S)+%@Q8>wz{gr# zD@*^tIX7khNG#v>L)i=-d4d;H0^;WFgV#V@AGL6dSXe%f5PFx|v6eRS6SW+dVK7wU z>lP(qm1LZg<r$Qr*Fr_y&PHx$RM22OWW-alZJ0{st5=-!Q<y_aVQy6=e!l1vt&(`o zvzJym7L55s!Zd@h*Af)JstkfPL%0K}ut$F*M(Dpx^{1q;UQ3CtqIOo5`pqZi)S<&^ zDX7N<&N0rzymi{Ed5`=tC3Q7+Qb_trSpgZdLBtiVpcg-s(E(%&8Cy=q8f-t*S1G@~ zpIBCxM%c~@AR&7L(<5(}c9J66dD9ars5!)f_BvFcJ@)yLvw-;z`vu85^|u^of9xc! zGVept#C*{gS>La8gwAkH3kku<Hn;Fe;xC`P4~AU_vxSwLN&}O~s^uMK6oA?wy_5SJ z4xCb}Zl^rYBp~-zFzfr2({86V)Lxtu!Y+ciUJ$ci*SPtz&JI}vcQ5R<Zy2=41z00_ zFE(xddYE*tY0wIJYb8}AD4n&kL2v#^?(w`{o@X7D=ffoU?vLji_|qg*n%}(^8SgSk z>*J8$WqC%p;uZA8Cs=A7vXhMMWW1qDxi_LAX}DQ@`;>tdS;VlsjPNqrD5-al3V?Yg z@rWAAbGKGhxNJ@)veM#QbnOtRyz^8!qNU=f)t2J_!02tu=62aWh$$u(>Rdz*GFIO! z*dB>av3nU;f47bXHT}qsaw4K%xwi>dG$5oR(7#Ysr1UHzq95Pxb`O4;D|Y5>`{D&h zRtKRR<rcL;Tj-dW8mhz3{l!-zx)*HDLq0|fqZ^)7?gN-X3YxhR_4)S$t9zY4uJ?4L z!yeGEJ+8IeK!emyu3vDri3+TTMjKZ{&f|sGWU<~Cu{>g@8D5T^eUlxq>a=R#ot?}w zl){PKF4lW5sP-KKQjG$<m^b$QC#x$*1CT8wWEH9TJE=|ZdXKjavX<18aVp{i0Ex0n zVX>w}Telfi)_Wx($J~3{_tCM8^S=P%Cd8xfTuofqaHc3?0a@%`9rk-A;^{up3lEPb z!XMh87r<zn+3e+uPF(YSSAuQ#X=RRoicTOg1H{4sO25E|j&f4D%WssoN7L5rT4Ae! zq#fk7du{r%$OYG|f#01>#_5bq?)Q)Whjp~!I#l5>A`k$sfbfSzG+aFT7=PfjDRu|I zKBXh_sBff1(cO%u0cf7Lg6Jj(zs0xI48BsoShq)usBf#(YwajkeQc|W>8(Tdl3Rz! z$dA-G{a{!XFxK}3cka)_48FEoiBTIyFA2sppI?x2dJ_7fY@jSG6I6|*qcT@$dz5Dj z1NM7Cq@@F7-Vqhi1dM)^Mzb6syXokUHmE29{E!~4^ZeDXg@WhJm<_&Ru@KCMVf2_R z?!((MdL5Dxx%bjgsDjqs3Zy|L^4Ik-+79koV#8=<j6P4>wcp7A31)+b*w<jU>rnMH z8bE^Q&=5hku-P_LCWzuLZhx@gtEq?-6GgwGOaRmgmb8iPePnzM<I}!+?lbwox-#HY z_Ys=D@B!T`iz^`YH(Z~x#9-(or1c`*cXzmIWvY`fR<<(5B?AuFWSc)3<KBzEPD<CP z%J3#2g!f)%lA*!23(WQCc6)R<37(sMXVQhV3f%r6jfndUoeo_*hZ!9qPpE_{7aqw@ zW+W?R)l~Z@zStd}jNn5SgXjSgx)?-$bf15W0b1%(%lGTmcBjgTuN@0IYgY!s)HB+0 zGJL7jyEFv+4FZ~k@U275gp9aRXL2Yr_hj0K3CPz4wk2w(H$j|v8&>eINdW=kPznpi zBP41O5~mTt1elAxVamuv+$H$LimamY(yL#x?`4rfzeaOq^ZjK}jfVN3K_r91u!Uc4 zzK1lUL0Us_wtM~9#pQwP(_uDkw^b?v=*R#X3{g0vRXO8JLky0<#5Go3-yob%x0`Ij zqJsoJmJW%SO$5^s`TI}{0P06K6K`5O^=9+j$+?uhH|H={3eB!4ADypUCSmnk=ki-R zx@6aN{w@vTk%o3tS4gmd_=w&>RQdjPCkkb8`oqSLCbgs(^<dcDl?~3qnMWxr02$g^ zhq_CC|NQ)FAdNOkuUNCh4g-^Z#EGX=vwW)ORRWAblo4s#6}w_4Eeguql26^6jsDoa zR<QMCXf){e=qCdDj(vZTeg9|1e{mA}10LBzKwpuCwUN;u?HkJWKRz-Ui=S`)adDbq zt?hg=Eijx~LI1$<22oS@@F5<|w0~b6wi7f0`#F!QUs=hlLzRNN>35XlYS2+D(98B~ zVkR(qS!jOUuEdGM$#w)lFmu71%h{oJ@Kphkd-sRrxsDdF1pr2*y7CPk=>=l;G;jkT zx=R+-We@AJ$Bo&;hOeQwfX*Rugtzf0vp3C7wmsMP`|U23{%B3TS-aoEpbrqMnN9Z% zNbiwPXWYmO?RW<178*%gObu1`qpx|=4)}3UPwJY`{X?;HpcoGDTX}QVZcFXisuK3| z)t9#K>3j8UFN%rl>PMf8@L%={kX;mpRRd}eHZ{19`exrywZBb0k=MyL{mpZ%2cGS$ z(uO{>>bev|A7-G~_Dv}UfY**M0ohJk^}@sQ@G!YrbiOP!edR#l#-CuyuF%u9bkd=S zC^-D+Fg|(qAwRD8!#KakkNXI>&3){}qdOft!{{CN_1(SC4+N2xG4x_8_HhkL75U3M z1SJfAYj)IngH9K2UOxDhb?P3B{mm~ReB1Jb-9uRcRvPS5jtUfaUe{`Xr${01ZyRr^ z;jEs+(=CsA1-;Z0sv`P@{3i`J#4_^~nXF#MV}X=z_$9UPG7F5!`#omhe^?d%+vL5* z?mxk~d0#xse9iSX=dl%Ao&2kN=K=>(E+mRcSxCGXh!Ds>wrh}mWiUmQ;{sX$uxp7a zFuNjkt-<^kyO$)_wL>S%bPoN$nJNP08{4Ycx8VnPaigFZ4OSXrg#Wy?RD4XFIHth* z_>nyGxP<Y<z@=c_LWOJN>tdJEt)7Rt@w@8Z%2OD6EB0p7?~!fIje$bj-~J!}9h`Sm zyr}PstGRIbleKvBn07tl{p&kRM7y<>^wcvM6;5<&(eDe{<|Z#8T)h_YI*(pS<-dMp z_FP%Cp?4wvb>VAO7TU8LMq}MYvC6BunNGUq$++_$;4IH${{)`oek;q%N=e?b+D>{9 z#gbAgXXQ8~`c6dBL@ZBnJc^gpJr>`xO`bPYXIK@^8cCLyGA8d#V0oJ>{d(dF)0MpP z2Z|9dhimO$%j#rUL>vqs579+9%Q{UOis9}Zk~X+|h1*_t4Lv7DXPce=ec_SWxJt&+ zGaX!e2@;3n)yp(DiHzfzHb$4E=*z9HBUNhYPGFKk7yO0Nc{4*1{)>)WfCf$3q)ad< z!|g#byt1s|&fsd3<&FEIn????qR*`uRt4@SKChUhh6B}CeQI2n68dxP-{+mlQPlN5 zm0`b>aVD4eJ_-srk?KV=)IGX3vU*RSitZZhh(kA+NhG07LqA{I#GXB|p?mB~3=<EB zjIn|#ihaZ29ZtnA<RD2Y<?VX>1Dg?3b|rsSMClqiBlG!tyWGe8-hsB<R+;xMJ-?NG zBZgsBc=n4SGgp17*Y5iC=h?g<U2o{yAZ@vl*Egp{-k))K*aZOs<Cu&t*>an29A%x6 z$T*fYXyYcjG-UJ=Ms_&cBVFJZQ?!o7X(hco#)Wy`!_F~Ac&B5``%wq0iJunXmZ|`T znwLHK<5P0`d2Zr*O!s(1R8>u(Wa~FVo2Q1$P@9KO^B%rrSQTIzU!3|9U>OCzCV9t$ zKO*yLueGf_KkfD4THd#t9tXGr3-WpBF;n_K!u7Ad#d|!GIizo3>#}2&meCVhE;%av zp{_aVVpq~qFS6-HrjFGzW(4Pd1?pJ5)ee1^oO+KVCE=7S{1ryEkd%p4SsG-DlXo81 zO_k3m>N&OUzzEPz8XBz`5|zbO|6^5Hu`m!%m>7%H_zbshYWo_aJSlo~W+10P-W3J} z<a8bXX?1}QpgdZR*ES>1&r_pFuq!sMI*JPUE>xH24%F^@IB)$E)?>(7QZaTh@jBzK zS;&Oq1qSi`9~_;FKhxhI$3NR_?#zAe8|F@P-`v^^x#yM$HP_s7uPF7k&1J43<lbD8 zP`QUBbHC*lLO1s)gjCYS&*S$m>~qffoPFM}*Yg?o5To8luqAM5f|DfPePY@b2<Dc? z5mj_6vrYpF9C(**QQi8Ki$z3<@0dhvXMNk~P*^%CiS&P~Lc$YY04d&NBbOZA>*N28 zL{u!ANN9`m6!dOSk>3sD;L)WDmeJ41J7LX#VIe>hd`=Ki!6x1G%1E?*;M5kG>-ry0 zL}pvhDcealFOG77h{K8Rc*kC8sZrxx7Kj8E1nAR3V#1@GtBM><%!>%TKosOKd$%u@ zOt>9+j29E=I&os2Xn-W^nPj`W;D%ev!t0AL@t5^uAsy24Q&lh=@7$Riv#(2j{uz_x zL~yh11o^+I%hlMokCV#S%xuJOD9aD2yu}f%%iw)%CM>{0nv%%QM7+G^UOW~ltyX2` zbI_l_<wyquZUCUT9-6rMX!>SPl`*G|RsjyFmLzAvdDySRviE=y^YoA^J4R1ZQeI;7 zwB<r{m@#W{kZ%Ws5|?b%nE?2*<X*<W=~YHDRi7x4{X4;VaH;<q(8F&u4>O!;cWP;w zQT*LIKSo>9Frr}i1LZ|zB!yF5;+8L$h7Mc;LQ}Od+laej%7$VEsebStqla*lW6`7V zWN!`#9%vYt!&0X%Ra%j*eDAi%aB4bt8>#__fdFyny5yjzG~(N&D1b>4D_r85|i zH)Re4FS0t(Kbpx9vX;~ZIL>DDYHAZ`=QAk$BZK{VRZDI`-sR%k8Ht*nOI*M%QE~?{ zsz+IK+RuH{u~zK0X>&&9<(Lt_uQMbD>2DjCU}V^yCvP}gp}8=x%Kw7~1GWgM-T<Dz z9S<{2%$&bu9D)P}d&F!#l3YBydDF_sl`<xeEYjAEJFS*^UL!l@lJ9sBR0QCDb%{#- z)j9xzB2cAxT4!sVlVsb2n1=UXfKy}udXN0Y$;|VSV6);0CUw<gQ0&(-Y02-jM9twn zPTBaCj`RKDxx!WB^#^<gUpL}3@|JR+=b`wo%qiusXHIDS&JiTA_U$YahrDbx{lM2? z>HwTgndXUaZ;e-S{l(6<=E0tglv2bj5gkL9X!eKQauasF+_w%Z-`%|;=~np6@Q`2H zm`3R-VvR*=IXvo&rii|y!<=3(r6fRx9v#&2E=(H>zn)+M>{0ADr&rpy<(Z?moY$ZM z^K%2HE%hCHX;DRqmKQ1P`Kz7@Hg!w%z!GT7SM`(!ziiyXax01z@>9LwRKyOA9g*dc z=uP($fDEUqYRed_+hT*W>x`8SLz($*EwP7a(1^<0BgfOTrBz%vJtY@yI}Mdfx#e@6 z4=;MYI(4BjO#C&(YD?!!mqH@fa8*1e4y@(FLE+z<>(A_F)ZCYOyLKwE?e4$Uts9zD zgswx%J<NuRMifIO5bI~eBa+&&d(|JP>ucU}9WrnCI{hOQHa-U@U8jMC)7;~A|CMvu zHc@!L2gjFPPD++;p>Wvap_~&Khs4n3o=0hg)|~$^e2L>#p;3MO)~Ljn{$Vn2HPZ)V z?0Da^opWk9%9Hs(PhDq<moVC70_G+;qg7dfzVzsIt(Vc&p)L}=8@+lHd}%fuS5z-< zFkOtbIS7(-d^KRZG4{!m{X<e{=>R^#poDeuNA0nc@E{zjKLJYfa4XZidT8=aRzFdf zMB$FMg$fB8QHep-+Yq@Z@uu-QIWA9lTUusNrUEm5kiqI`+Y@G4#@oYrp0Bw}OOPPd zzq;{5x@D0WkT}g>7zK%l48o1^b%A8?l^Nwxu?dBuFQ(X`dh#OA^Aa85?JfWiccGEN z1_K6D7|9x47YY_wp^>pE3^3p+FVl*|=;iTUtzxpsgQ(}7$P}n?i~NR%l$#_922Yj8 zQzq*QMI5DCQ}p7@GY#v?3|lF}8RWm_lD|u-I&_L80xZW;zGR=IgMes+Qgkp>xkIuX zz9?9|D3v{#)}0sw01j2q0wDJIJP^AspAfZsnxxRB+tj1ymg}R&96_sT&Z{AjsDHcI z)x#=gSCrUg_yFWx-M1}&S)lHV+|TGx?@*Wq2?F@t`5`ak?i}xghgo3baf1*;+edoz zxX*U+dKiRw5kv-0ao@lojS-f03T*_cE-BtH6bxj5RCTGR^OE}Z9>4TI?SX)5)q&4N zq+5qlew0I$Y^kz-;8H)T7LaUUOQnYrwX?;HG7^Ka`Ip*y!eq{jxju}DVm@V=(n5o2 z_(9Yg+2IY^Y(@AtjqL5M0|I68?Pk!^p@|wSP+wAlmCT@DEX<pRQAbkssvs7&nr4KI zwj^*n0fKbaJHFWP$Yt7)4-~6u2Eh)h;B3LFW#IV*Dgg_@WiWX!Fkxu*)~(IHB>l?) zVrtd#TD`p*W>D8q$oWlkx*zOHP`b@we{fw#xbbjBN5fOn!;razYZ$YG3~tkX`g2+% zvGz=7H9iET5yC)nu!)d6dMQkI12&ny=fxTAQZ;E%$zG-}Ll8$igj5Yqo(3x{LcY{I zDzs41KSa|H&7@kv*a=O2Ok0oU%S0Si5&*Q2N&fJJjMtnW4tZQa$(O-w`FXHQ8RqmZ z^8x@D!q1MgK#n>Lzc#kM*<KXvm-u}!u{p1$UH)$1qcd+_E3y7To~RLjVNc@CXBvXI zkAGp9Juyr~Gl)lZcC`morIlZWZl*~BOU*stp0|v%Qz5A<;#jC?8f8!TzEUe#*Oqd! zq9iBC{!9R(4pb=u)|iX)g~Rfz;&WN_^AO4!gH|FST&8I9mFYOFTgzw6t7(}D@Gbi3 zg7WKwOb192!XM<b4JCSEmljn90NSG$@nw1ywltUl3Gz|d^8S$VWh}R!{Fr7H6E}Ip zT>9b3Zv0d`n81Ry*?eHx$aGT3k9P)3AxAY^!RS_suOnCyL6xI}PktK3I`GE^+00PZ zg4IlhQqth_(GQ1`>2s!~a9q|2Y_~`b0)36yE&@R->SGgB2<+eGDaY4S2bitnqifFu z^=Jo<;%8k%p6^=wcG)hD_68zhXX~h%&V``TY%2!;r=}5!+U(DN&{!m8mjKyj0++Xg zl`JUxZer+WkZ33sbq=f)YpQ6LBffWEW3f`Kk)mY=mAcxj!_tOw<thtJzsACR_m{M~ zz-zae8AX@;y#T>5EOS6;OJE+%GiqSI=#ERq1glRYn{gGr?se(jD;tEF75^k9GQp3Y zU<FL;BB5saRB|*+cmtCP-Z9x2d<Mjmh?lzH$l}RHU6G*(=Yh`hn9JFM(Qt_31OyGl zerHO4Sqj#vJ9%K#lPDbq07QjZ-%E*Hrd3y7=t#q|9s6WtUWF%S3!l0;Ka>7_PHyvD z7*nhdDESID(c=Y-zyiY#rIf8GVSQ#7rn?MY4|tKZ0y!}a`h?5$1RIQvMJVkO4RUcY zKJgH<t#`hi6=D)kOI@WZWpJut%Z1^iC)G=|Eg0A8sF=q}KOA~;4qSBu9GI-8M4Dr~ zg#aYT=z&UF;hf5vsSh&l(;=JgpSkCKu21mv7sYa8n+f5q30AguoaG_#<TGW|7cLq2 z(w>&th}p~5P!l)Z=Rho(iLa<{R%MUrv^+JI{rvS<PMK<|SiGIA8HDDS<}zxx-AhGh zfSyBQQCB4u5mU1P;QyMz<ZVYSIz=>=e7qt8maHSoA>N)GW_+K`KTJKotP62nI!lj= zU!RDJT1*IQmDX?9R~mV{y>_v7@$HLOS>s>gqC&g0ES;WLS+my;3_QlGXL4&D+Kz}5 ztYrotD8Ou;E#YDJoEGb-X7A(3cA67lnL$e%Mx0`--fk}ybC`|JBkMR*BoE1cWt3Zw z9YsTPVs4qD(~LxI$7Q1^vcQZSNlS@DJ^XwjK5fbxOD#aC`$WZWp7@2gKZvv}Rk6%x zpj}F7iB`x2P4WwEgI<y|Rm;!q`wRSy7$<rtJ3Zqg&vciSKH)|vtZ0u(pM}Y5kgA`j zIp@b|RRyu6Q7Rr3s{P1_+m$$m`7V})FUlN((0L&AiAjoVgs8gzUyeJP2I6iZ^OTrs z?UKDKAcw#c6n0KBEXjH!?#>DeFclX8FozBjeV67$TUIS4k}Y7#Vov$yA3UyLAbNGV za}M&IH|BNEef;je+!>zWf&h~%J_0@Oc&@_y;Bo46@tikB;}<2SZjC)Kh?|@<16a)8 zSx|&&q}slPtlH_5M`EzJAajng)C_u9z0L!B5;S}AI)Gq+bCpMkJTorSbSonOh&GeU z`hL#J_tQ1mmah-ePlJ;!s^Yxh&^QXd*3qr3{ORns%cYQHj%knqmSM%gwkR{{iJ>~g zVs1tiQvKd&u#t{8IH<8B{9%-ZZAb7sdtc;VGENX8N(22YrOJdt6zj<Tw<!qthmT-Y zos9mE_O4=lTtPRImf@Gr3&3O?5>AGUqhX)uol6$$s~Ksl5tu~!2Gr9}Jf32}D$~w3 zjjxS)CsWzQ*3>eLwxnYj6xE7TZ3(KOP`8bbQtH!u`GWu#Rq<qX_}Rhw7clsB>_0nz zH2N}gU8$-*=5L|(_b&(~SFPQ}prZIHb=HqqZ{$3a@7(=C*W6%4qQwV~(#oxlE4)!o zStB5}Kp^&0dmDXzBFM7W#QViTvn}1$$-GLi*ual+kmYZdpp8jOyiKDL5SJ>=#ErqS z%aCKB%MX_a!gW1PlMSvd2I)q5DI$IM{!FVOE((vlS$YAo6^GDmodJ5~k`${Bk}G#2 z^TJ`mwO!bit`Ec7AtSRNw)%of=+e>a)Z4ppet9r>yTcR=^`!Et&$(IF4&xbA1%*G^ zS)$R=HvXoc;X>sk#z`uPi=<LT5z$9b*{QWA>yljyk}B0YEg;3b6`g<6FHsjc#@rR7 zz~@Di)JQ?vSV$l*QCwL6SmESdn;1mbkG}BfTYuOcm4KW_Z-?uPf=`aB&xv+4m}1M* zvcP#=mF<IOQ`ReBjt1mn&=txk^tNAuMHiY$rwntVB<3Q$zG|qcs<>;s9<#l190QF- z#CGeL?U3Jl<*zUJ_vZzNCpZq4r7g(@iGUZXp#3TOk^f+K6_^7C_l!Qyj9d))>@1f( zlt8RY@Fk}Bk*E(8)}jt_2RL=}Uy!3iQ?7@~7pYX_uLZP{V1F&3H=<zrRiY{nMKLxi zGAA+Qm{2Q{p(PN^^5hNH2JB-47Ir?%b=?;oWr~gk&A)OtcoJ-|_}+Ss`$8MmnkGgM z<@$_%)uet9DD>L+d{*VV9{P#k*^8Z+e5NCIwv)}z>a0BdIfyfxyJ^q~2)S|tD-x5j z=gAVM{O}4D{{F)(p*bCFJ(Rs3LGtQ<lMajJMNH|~g1OIA<jgjCPWvBYRu|5DB<X}E zteENNA7UrmI<8@nfp>r)p<mO}KcZTsBe03|iG)ZihnS9(c}Gu^?10j{wt?Q)HP`Yf zxoh$X?0?xrqG*X1S>hmPLap#Ctsp?Xa!@{M7f0f>lCQ=}>_}Qu{L?|z|E-X8ics6; ziZpUB4g#2o`O+bFB$!KB{T-HM8$Z}aS5au)kIZ{F!<B!H&WeTkG22wdUBfVkzC5{} z3Tmx<D$hKnMf{0wnIMs1m;DloCYb{E@__-Q%LMmj=ftbd3B<1JOs8+e+umrO1j_<m zszP$_EV^}aZ=f^C@&9>=51zmE0K(;Dj~<LbBfvSKcX}bh$C7PR)dd%W^U8su-%FAM z?LU(wn8OV>pds?i&~w~YtHbv$HO_qb)bo;zzQ*on_PQ0zp!&jYn#K1}Qm$bWeOj-p zoTjB^7fz;K1@M%(R(^f@1uX5oa45L;FG!e1W?BC-2c>BQSILK!uMXuKSY#LRNc-Qd zvMrP`pE}4`menoHR`_yYaj_+M$uymbv@bK9t$4m6XmcMunx}qws@DIT>{yZR_5H2Q zZ*miKBmZQjfCKrdisjB*(r3mN)b+=Qi*LT!lrgwFmj0^nsxp6}3#0v7F_a{Dp(&`l z;3QZ$-Q4<SgGX;&`GOO0kiNF86LLY$@6)hKVJ|b^@^NpnKsll3liGdE1rdizu?K9G zm^&&aAYRk-JhbHp+ON{Mu^c4}E7>rkHSQb~`%l|P)}O|Ob(@W@7GN`%iMqwvGdIeW zFKSm1?`eeW{J|Y;Og(gX8eA;%V{4&VL+fV~uUw$x$D|v~iwjLIrS0J+g^JrQhr27| z1)sDXHQP3xUe%RVyrB8Bf_F6f4V-UWd)cp%9mrAsLGn!B^I(<qGq!W_0gOxg#A2oy zXZXt=pqM4f?09;(&E4valO2mnnFy!s3CyX_<_{BOu8cy8WIHEIlhg|)$eiKUnHu(X zOBr6`cdd1Q$z<DE;Ltg8xU1+~mw+T6oTEYf8Qk%5wnq9n7x!;A@}*1>Ru~3dAldcc z0b0`a`y;tw&4WQGxBi6jU2fnJN#K>zUW~M?LL%Xi<egz~4VB;*2Lkx~fnAj3z3%#D z0naK~h(LH%D_o#j&6rtS+qQlHsXdHxlPkqgc}$vF^6g63gQ#f0(&?8{9fM6zxxNq9 zEZ*=|ppPH7eZXsm`#>|lSP};6>UR!KhCXbGD2ShR37m_bQajqz;RK%1H96J3A`h)` z<&lF!Whv&ZF8m(G$uPhzXs$F~@`BVEge5>XW<4$chsvQoNAKl5UxXTvEa)KgA&mm0 zVB%$YlS8$LE9(8ig>VgPy|-~a{3FNx?SIrq)kgHcMYt}+MA)r2^_Zi#{Z?LKU(@Ut zwZ`J4oX!VJY(FjvPe;!xPi6-O8;%VcaqG)&&JXFW$4Re0h?;Oc<yqvWyOfyaffWWW zAk~<G+>>N*dEy?bA0FC8PDF$#hq+c!Px7JtLT6*%N|ZG*tTb;rM#6@k(%r_i*JVsJ z*7E~9ai4l+e@9<4Pbjz6OFRhY!oAP-63`D9hjg9yYi?_L7LkD7dG@UXt);eJlHF{+ z8wnoAEsMEuDMZk$ugza29XX3<m{xlT6u8s05Atj?nH0y~EX@hrqTSzHqy|oX76xoR z21G)NP)Q<fTCdL<ETr=LnjbIwy}=#-{e65I2m!Z)Zd?CX{@N5-62=t~xgxq3n{fLd z1h`DAvHn;s4%_anw0+kn{5ZvOcFRMyEmlh6(eq0hhoLNha&o*+4cuFq=f%)gAn_dS z1oO9|Z}|t$Rp_5B*8LOKUHmnMI)YdV^<egOg96=$%-A|cTFxzLF+koNXsqf}3D5kG z$uZY1&x9-Fpp0uANW^tark$jHL?rcL8mY4?IJH+Y5mVwoyOfgW#v|c_uD&lc(>pe9 z(h`=e1KJDqDFY|e-|uB_UP$yj?FUF#&P^C0@@#cX!FZ1RqYN*gD@j1OK8B*Vro?}S z1=+kJHiQ}|&5%hyR-J0dZRuFc&Mq5qSN$UTp&llyXqOg_2~B$%n^2N0m=;~NiSTow ziU(fjZIZFR?irSFYyTTp%p65xDBDtV!J|zvp<JwQu}7@GU*Bqi^XBB+^Iob{rdPIp zM!f2ITuQyHHXO@rRAii(CW<-si9J_H21I2UndWqjde4M`HkMYLOgdUkx&OrmR}x0^ zarPp=cP=M)u_ARCV}^@mD=uT6*5LY22$wKZ!!i$co`Mv_x_qJ;n=@B{V;Prnr1uNb zA<?Saf!&HukU7niX!Vyt%pg$bfv!ZK-erMXEWIcRl%YdMw@^FQM5D}PvOcT1);A}~ zgfUkfp?_S?HCqQ0IemdUAW|wH2=8Zlq0S!mK+_N)F`(ZzWVK&)`+cLCx_>)-)dpV? z_zoA(8n#QaDDp1GWS7c3c!Lm0DAn+*l3O@IecvSsCirT&pUN#=m{BbkdJ)yH;8dS_ zEs83}ZJ-n!QS;WdQozLoHGmVG=gRD||8IN4-EFr)_A-`e;IWx(PXF>IIuz}%m?IGJ z6$C`ZyjGm7Vg`_US;1}r@%YF0d_PylTa*#lb0_Xqr0Xi&G^}j6m+V^pBZ<|fX}0;_ zdy`Yw>Qh~jUi=I4XF%6$7NHug5iii@_U)5gy-n0)PpLEdw58PRZV-G~-H4MB<IUZL zOy%S0Vv-A+lF|*9fci+Bt(n!-NVvK@derjN!Us#DCZ=@2pc2Gc7R!3yVn)W2rAHD2 zwU8Pw<?W}%|5yHJ!BwW5_t0zjifHYcO2n`8I=}aG+E@8mS3HE)kcoMdG3kL(MrQ$< zDJHMxIqt`d%JeE5?PYh4&D=vy&9o7{qDj^W=dmb1Lk%47P!dtBEK?RGD%ZWMzoAyD zW;koauiFR~(G1tHHDUEtK`Gpw2J!vP2|wkz$8n*R$~QN0>7JL$7Z(lI(Uxn&Z-yDn zUZE=!HlRcub+LP1aOts8ffU!s%l49UVanv*6Y{R@l;b<9u%zaM{D-h~qHz0p8=m7c zp?kK8RVCNeiViROe+ewL@)CKC!-F|xHCDO*F3I5HO3sdR0>?(U;d(@!o+1x>*tMit z*lBFH(h(^uav*#J8>d|$)&4*qb9x}kT{Hc!Zhcb{{+c>_1hF#*%M1}JZ5`0h5aqOU zqqdv?JS{q}^*t0@#%SB5O5-Nww_fNBZkM?7`-M6_+p|oN&7_uF>OHbNN2z{TSsi#Q zjO}`cr|{*m@b1PZ-yc8qUV;X-YTXE9+3U)BI|^o2bK=qq(tRxxSdeJG&GA!zdEW4; zm#HFbmBS8B&G_JVCaOLNpR2Vd22|lZZ5!lonBSQ40E{ZNG<9S<L|Lrzdc2R-bF#Sm z9&=efrQZF`dG%Ozg@0oXDkm7l|D>_=JIl{@W!5X4yEHi~m~wI)CqE~b=WCTqn^^L` znQEpN-|57e1too+J6GfUMb%5z%)K}H12e#!*#9Eicp^eZeG6Dm>jZR=Pr5q$>?f8< zKx|odh8uTBU~}u)OZVrg`gH2$o~s7`zMTqu`txKceYGKqU*sCCM<lJ=^+bEzHS`sl zB?6~4z9J6V-P2%#Xyh3yMmcDv8tLazwUy(a))_m*5%nCw61$)_1&O%Dxtk^+012A7 zV#b9piP3`b?v4n=7IbZlv}w6lmoBK&dlaf5pPPGh^zZ)@NAWJtKE85nes6UYhaiea zQMIrp_bTSkL|Ye_y<&P|t^uVs<zx@eCzAH^&5_g+V~9c!iI`-L%QI#a$K~a`R-b0< z%X}zTVKaEZnTP@L0L6kV#c!P@PV|dHgJh0X%gU=Xnf%4pw%Jbed|eJAydNxU3#onK z!RuQlyFA4kU@jmvhoiYSAui;hL^h3yqM?0E7u_1%Q_j~G--3U1ZjCp<Qr*M`uiPrL z!1f6=6V+lre1DIM(}a1G?B5<NB^VR9PC(8`0_O!0&e7OU&2K8q23vC$Hh#TT#}nZq zL=ju!UQih}U0Q`9ArMd0pBM@CKQk6e!cFuDH?bDF6%|w+Gh9-k;Ng5ldlDT_`Z_^` z^%Ehb0zeT&E9TDpoX3yt6YhtQg^bq(x?JOe2;ZMB4o4OrKY{?Z|3;2T^>>oY5n1=Z z2u*?DN@OhljZ?+@%wmXoG;2LtlAYg~oqY1Gt|aqXM*pPvTXUpF*QC-I!~hGC>^muC zLv-dOEC;9F#88(&<>lv`meDX7>%oNGk&0FlKZd+&Le>z;VOJ${be;Dh*(0_VAMLpY zn3w7Hg5~07^3~$a2YoDNAGixz%J~k37?|Kj8S1grr&r8%iXa9Yug><nG_@6L{PAX5 zfJ&_K7@ECO5ws_^F`WYAMRQLGe}s8spBJmgwr?F_e8wOA#yEK+P5o6F9Lj`*UOwIp zF}WC->?`GxbgCK&tibUGOM37AqcX&P$U>y=z@$$&?QT@sdA;3%LdF==B)LgVR(nYx zLTz2y_N~WbH#ZJmZR7(xWwd!-980(nvK1bkWnCG|g7#SRE9gy#_33z(77)DllVrwe zxP0b^ks1f&Z>D$f4x9V_dI+p4)^I>hu!=0PaZ#1#$dRyJ?@`cJLC)*#`(6_FZ<VS3 zeI$&iSj!x1ww@2qLJ=gb{s_84yIUW>zKxcUoX9XAO<N<BtfB}SH!dM+eG#J$6>bTF zwmG*<=hdrvriCGLtChV;8?h1!S-QuGZ>|nFEXvORa<Y@TT*&$A%c1~OSGMG@%vEus z;zrL^-y#)t!O}D$Pr|*-1}0oy&sL5|a_*}%Fo+ibaVksm0gTFDOOpKxvO`@0K|T*2 zT)tTff@`|pIoeP__NY6$=gm1?mwi-jSl#{L+^I|m*15+qN!S6&9(T=1A9EQxRm{Zu zvHn5#Jwe~wz0ik(BC%zgZ!(M!SeE4QZn0^9jsBBCk0n=a*Np($M6oYou#1<p;P=E@ zJd`C?ARyKbqJj*F^@m_Xd+ci^Dr}UR$9l5_OSJGs+A(jfe3|2tDJ3z^&;|lig4h;@ zSm=B?ag6Bxei_UYzt=T_%RgS!EiUv81#u4g-FYD@v>H1B@|^HTiwxp<4@aClY2IQN z#g!oqY;)6XPDsBVET)>rsiyCuvc>L4`@^ipX$H>9WBymJ+AFApxu_U9kLd!RVMahA z*z9?OB{s~puc4Qi#HuBK_C*<4N{YaB=zItIzG%2=O?<}xMnA`ag2s;X%`2-9NZq$o zsj4zP8e83SVP8f)m1ms-L(`3=pm)bHYu6%)+Py^CUg!!CE79dS_*bTI!>0MMlAWx> z*It>9;W?c}hFBB)#l*;xH47)l<8cXrHP$N}>v(~<LFbl-=PNJEDp=&-T0I$ns47Ed zf&=Hx1804ol;`$#<Bp-5d360EuLg{X0i0LgEX}nJM2j!d2h&vCK3z=)Ym7qwn<jpa zp<6{Q#w`)bANWZtm{xcs3l91(+Dn|kLhk(f;teo31_}NmIR~w2(kivte+%`BD5tiJ zdi#Cy1D^b}uc;7OAkUE1tZElgBWDcYY5?0pL7aSK(Rs0x8%B@53{f8N9?>Og%Lu6r z_Go9Ex5ik?Uo*RGgZ6YZ((|WHz*J8F*quLWi-+Y!;Dlu(8QwafN`?N`??TMdkRJh0 zd+oP=rtfBY+8s)n>zMWRHh9lH;n8eLkx{-J>2dcK#zu3IC^6r2?;kUZmS7YJV?DTr zQ>IGF50|YTXH;F4EIyhm`r!=G!SL1sy!?TzG|+SO6|{c^`cPHk5UD%SjZr2dovFXV z-&SW~MDCRLOC)J+QF3Mk*}a%^?c#BfMuzag`Oa>OIp*Q!E&bRUw@~Z7!5}Myi6}T$ zJA(vr@bT3bn81~fvla6}=3hPmUM}JpiaSnDQ$Aa-=XOC7MHiHNDY~l+Ocg}JjG9FX z7J1g-UO98YrN>Yupi<UytQI2qh_KKScdITaai>oyhEFpp@ya}t1KkGKOW`SeJ4QCU z>?5*x6u2ny^rZ+#ohkWclj!;VITuw^aRBl10R)kvCM;B-biXm=HqYG)#QdBHmBw<r z$m1Se3>6dCE$nR~4<}kI_7yIDb+323mToix+7+(pttgu(Ox3jAx?^Asd%jttZm~Zu z@sxi8;28yY^uLW?d0=WJu&ZtMA3->yg`#^v)&gR2<&75iWt4yOx|%}=CFJ6SGqn96 zBsY10<CWn`&)*Nw*gB<)@0RsqdqhsC#$tV0$`fK0pg5+dGB`~Qt}9#zwc{4w*jBrE zC%OduK<b_g31)R?eyald!PR|6x*K3LsRvQc<Nl<{^=|p&q<LH&WuV%I9L`!6{p4hu zXvPx69`~xV4&U>2v+IXy@}E$pBxU=1Ma!gRF<03<E$9-em7G`je%BTq)i{kD1Mm|C z=;EWdNP>5j!?M-|vl_^S@&?6^)A^mvfnPoX^{cpv5nL^5t~){}h^jwLX>vD_@1P(o zHohFGabLbH7b^`!hFHh(gyz_NRWwCc+(SE#x3ktjguWL2s|lEj{dVL2GMAFKh6eVh zk**8`t=uD>QU8=Q8Td@+OFm`;V<JT!2(>N(g$?NV5p@QsvhTiqp@A=!8Y^yuj{F;F z7G|Mr^nNxlK`Lu_*2;Uk`S=G9zVv*y=h@6L(Um!gzf8XGJ@}T|B|ELsgP8#9rtV?$ zs5hTR@!s$h(2aN4C!9)MF71d?xb3Oq2l<aWI<a`hB5Je!Xu#8-<g;_!OLVc@&vTVN z4dX2Ky(ux{c(xG|hy?%;JQOs31I-u55Q}4&s!F(=BC1VD%9&BIRZ)SBtp%d*d={+k zDNne*VhE@4gtfIP>|76#hs6E{S#${lbGyhZd2SsLwS%vvyT**9A@#WHo}=Wh4!%3} zqLuC~ccAX$>z_G4r?6WPI%$=H8QSLzO#|&zYqlx*jXw$=9?gpT<zapF;ihPPDwc;% zZ8*ZFLi9*f{US2vphxQjwY!$7cep>?=4hRtVfX3DUQt})T#A&@(Kla_j5Jwap(hFB zUCw71KQnyv)pU0~yT$M>YS|wYdMTQkCQ*;t+h1PX*x<&69zzstRYZD?G&*iT-v7KN zmZa@X)lUU!SrJdCc8eGjPbY#6#b%v0p0;_vZTZDyxx*pRrRce#{9uw^aYpmn%eQtQ z0-R1pz&*u-qJ2Wig394l1MBLf9)%6Cf*C|j{HT54PcGxxwMcVG4$7$mkXSExNt39Q z^h6mg|ME3R3wcJbi7f91<$Ci~4bGc5Wa6=IQSdP?h_Bwr3oN3qTj5r3N2tpd{mPNu z6=O=c7gFKl$e1~8CeDPIE&*$`#*`0tybH`1OGILK^)U#DL>}c7Kvm!XzbLl>`6qtL z?a?e^;NVyF;1qd0NpubzG5O^71W|*3N-vgk=kswKqW+tJe1bzX3#ahRJ3j)4VtHr! z`bS+1ydoA6bH~)4&BchVN-1HkN>II*pquC4FmCYm&bjwO@tRR!3;;RN$$tF#;?y4l zg`yr@4Cm5a$mTRye6UB;uSYk^NUhaQeS=ji&+<zoI5UVEev(c)*Q4%yA11Wo>yO^N zDY<s;D&+SUjtV?tk=*I`Jl?rKIm;StC4fH&zxVLN^I!lj>)4v%K}_UEnPy`%Jxx-C z)O@E~Gri8-kt8JW<FdSm;+Jd_i1Ie?o`uLi5Z{Le!9_@wF>6J_UvipmtlMTu57<|= zTx%XXC~OIKM}+{P;v?770%opHs=I4k#~jO8=CZhhH~JH~<*f21GMXKkt>4O9H5pGD zL7oW8SnaBpX0E8Fq1AH%KT%V5NzDrj;Y)m#TP_24zVv>M-{FsqS#!Fr)s`P|dHg;h zQP7|u(*HH<iw5OS_Ek*;4K>CPtJNnfhx+7m8giOqcH!^Sr#6|>-5dhG1B($(If_j- z#UJ{<{NPl+nzh#3T%$P<=FyPwHh?UOW`pmCkyoKv(#&_oG)B+(r^s4}8``l5nfCnM z^RkJ-Y(n$(_gx0sU&F0z8BpP%2?jID(X4T_7x%C@!Yu`g(8QKLZYi<?Ro)?de)LH+ z%+`|?Ypt1?C>lN%%_Md;a+A5(hIWkd<+rP<zFZtUIM0EOBf0se6UX+0AOD&_jK64I z_LMSsF-w$U7WReTdEA4jA+oC=R){J8j%t{=z23D!V{f!XD|YKFr8<n^HftL-o{q6T z%=fL@lNBu5#XukCNA726+gITp7KYdHC5lD^RVKP2p0&)9*Wnk=h?;`r9~Rf)`PgDD zK4WVv8}d>^4BF_^N^CzWyggyU6L=$b28*;3hs<DioLb|cK0CKf2BCk<E7RI(-X~v+ z6Mb*Y-xqFQDei4d0;3~axcxu(+>>-a@-4VMR<$M;IEuT>8x}hBNjwZd%E^}wE@?J} zC%1v`_Dxqyr~V43rJQnFIacI;`r;kLN?&%p=MFbe&C-~zi&bNH9vEeVh<j&k%8BX} za=NT$nyb!_O_L6M_<`8c?Mh59(1qY`Q<=`Ti*=DJ3ho6lPhI%z@vtDksdP_0#7#sU z^?=~@=*`!|-3E_+zl@R3l+7|FW~8sP)bM|kgI6({xlBKn2dd3z)&Q60{Pwe@bl08C zPTXa9?$u;yx(smAk>`B&z-5<Ehx=rF|D$bXad5|@%DHp!{REvH-gjtDE7^4~mEL!r z%je{u3Whv={PbW!_1C-oH`6!{BJbVCOP{1MK$ba6V_Vp``_K0u|5fXR?UcOY$0nSS zPI>`4T<I~osvggO>GScXY>EF^#^u5g5uMqR8x#)Six2Wu75<c#FdzZHu_5~^$X1e8 z<co??a)MH=uTfo36Me2$X`w7{G<h<V#jlQf{X~QT;$e|{@L)X{*o{{>LROuQL$UVo z5qbalR;^7Ygsx$kwfd2Ff+D^A2D_lT`(a!yXqwiGN5=m?*X8PBf-p}Ta(;LAD*oDh zz!aCs4xc(h^|&g>5fSU&*VL8dTw5m5WVXmxiZD^Q1~pOGE7obBWF~$G0YWFpZQ4&} zEDgl<G!teMI@PfLVp;fg%?E9>jn;E?>5E9q6T%QVL9qfIpsAmlqtDzf){hRv$uoGn zNm|n<G{>|@#|XLgSf;-QynOz7#8Wp2Ns$0v{5xKxqY`0Zm#&_i7S4|?fdWsXR<w}G z^O9DXaq==tQG)zEl1E6GJD3E2YP$mY-IeAG?>0$wKmoJ$$eU^>#>1{S8Lcz-f6>xO zGk@%7R_{?{ICxpDr^e^8j9lFG65MWOLj6WPhs_okwM`dOSQ0)P{X<ntu$s9X-_{uM z$6q!SDIo^nN7OvwT%H|BWge-1LL7^+av4>>mmv^`w<u%rOtQT8EtPhQ`RbLh8RU3` zgn|hf#z6<cr^=zoIW`~x<$zY4OgY~55PI(1uZl5evu}ksd^^}YORiRqiY8vD_v_a_ zR*fv%>HvoV@n|t$7lQk~O73&bK1m>S=5*JT&^VC5tGRdbX>_G{J1>Lc9L^P-y#i00 z7MPnrp3Y#~SHU5{oc480FD4c%+<@3y6N{$@m8o?by{jHRx^@vvIrV8*l_|TwI74l{ z;PtU<$Qx~`QMIOGod_n3XQ`#y4kukrqYru#%34MlQ+$e8#aDq?!y$ip<;i{tt;G9` zMQGyryD5KK*YBM&NrC|d&WJ%x=AlLY`n&@ZG)CY~i$QMtOtY$4rxcfe2c=XZxesXy zGKg@b^0Oofi^cNTIsuyWF06#n;ku)Pw^q$RrhdsPQt~xFX-UAAP8G4ew;RpeUz z9k=yHp?0H9%l#AzN7H=gl6q<3Z;`wI0n_i+cld=^g$J$@#5{Q%m@alMsy^G%qj?rd zU%1~_jaV0jl2X-t5429f>J<qDbO^Tv#zZBCZ1wgWB%8JSA$C<j#n8>es@;GiL}*m8 z)6@f|K))06mGVyN;@0UL=LB!fcPY*sL?PBk{j|v<U-&~9mVG97F=p?5&`FYWO5P93 z)1CZF_D=49baadtY-N?z!dC5&N~_qb<Ug0$C2)7uLpPC0Y%0e<gHB-GfY{4yvDMYp z5cAX&guRQv5^~WG3+##mqAF$eD)1}&EI!G^Ua7(L_k|}~1)alVm?rA0&-`w}&vR;9 zgjqoT`&p5ujnF@pVnuK(fzNej<G*qlcC90`ei*9pMNXik{Ep=~xK<Z)z9);2C@yI4 zeeP-Ddxs7`y?0iP1*~k1&f8Mw<}F9^ChgyVeI7IMgnxYODUBj@TOFD~I*W6p;agS^ zX#)!hSJr*YFO!xzmywD1mg+)}xvKwmV_AE03)Pie79PDV4$t|*b@uHH9Y#IzHVlI1 zY#)d4PSt#w{vne34O*q}!<O)PrwozHu!>y~sGuo-y9TH-zxaGr&(tGv)8_t-lkv%x zJEEKyA7t6pjge@#VSTI7+JJl>ou`Q4@#+!5d7|&8>(>???_52Fd^o(se!fRHR1YQX zbh&Op6@25(i%K75OUwAxS5a`XGaty6!edGhN4;MhZn!m&mEFMvtYZ=_l|z0#t*Yx7 z!9(ExSY-EYf1hJ6Byhupr<}sZ7M?bq)D~GkN8T>$`GO38SP*=DiTgj7&dh`w_t~Fo ze@_D5K)>?)nvvK0k3V+UT=9SXJJ9H%2RiG^D^pu=x|b|dI&(cd<t>Wa-;LHc(>ihV z7L?9DL*>6{I_U0r^z@mnz7u~*&X#a0>yIjxs0W^7WxR)r+XaEb2`H{9hOs918Z88@ z0Jm|YpsP!TVewz5l-5u7TQ@Qn<G0K9boZaty&qk_j!Byni(M@CgQ6W^0KS7NS;JR> zQ0oBa33P8RL^zo&LN9gB0trumM3U>A-<3L7l_CmCMRLjfC8a{9KF}R0HSe>kJK$5{ zi_G4!-@|Dvm8`7SKwh6?`6HhST_XrMvWh9zalVJ!XhOsa827Tze(;rUs=5=ktDI{w zadb_UUW*@i!p3$&O~Lm`aZRE;K_X6MFFZ(iiy^+{!7IljE}zMp3E~%-bUp&uF417v z0oCePB+qzQ`viL*<cUlY$B=bTP{7U@!+Pv9r+>YmNsm(96OoHOT=~o)Og^c;vDILU zd!*E($R{5?@u;1^em^O8vr_JgB{9Ji>0?1lHa@UG0$hB8Al_OpIs=mEP!oG;C*GvS z9l6ABh~hq=!PccSocj#8Oxb;Xo;)#~5;0|0M7=wt^QM*x@UV;eF`T1JbEaPja_%E7 zm&@GB#G{sFS<t^cuW0XF$-S6__&vdN=Q6h^o)WywU57leU5j%Vl?D4qNqrVuUJ}L- zPzfmUUNy02VWKlARBA?g3y*LV2uL+ytLR#gda^L(W#Jvm!t2jq^DU5C&-}4h*Qs3G z6(pQR5L#fQ!y6PI+sn{A#r!Ccz#gI%nJ){8cpSj}H{;VaRT%AZR1_;vz!-N*)vdH+ z7M0SHdMIA!!Jk3qb+#96%RF`L6E4crEencG=cS0vcnBDJAW|Q&RRaS1bh$oh;IZ*k z-r}j`tc7K%?N%9%{Yhm{wrLqJM3I^DTqW}9zNXz>DLnKN3@RmQzs_R9QMO3&yUTRS z?9-?^t0##m1dK{u6louH<u{S)UXyu4Mns~7Th+u97>GYp7)}jY<_KM=0|uAG6U}gL zMRH##6<A+{`jM7Jf*#abv*#i$<)28rW?snnqP*TExx^*Dt{QINXt>QM#Xp7a@(}$T z1c|o$0FYP*H==44YeF4RN3WOyf(Fu&HN92bRiz^GiNz8W^g^j{BuID~C3*6h_Ql?* zp-f$3lkUU2cOx6rPx4O^vrh!%K>`;DZ1#Az9ZH3KBc@$8QkGLyr2mo#ggbKloo!Ru zPJ~&Krp7glAdnc{<l`z~ru}fd<J!;*E`EX?k~KVNAQ@BxB=c7g(1yzI7vs?#rQ#U` zAzRw1-}}VhS-Q*-#`Dv<GawN|hBI=V%aF{w+a$1qXA8x%IkFvp#&b}RtQoQF8+(>a zbso-g9E!e@0`U5Mkco7)nZk_WDfrMZO18bmS07X3j6%GxNeT9^w*7+2>SBuIl$+bH zzVXE2LYZi7DXOkYA~{}c($RWz5Q7_%EpI$;kbV9<Stz`Lt@SRib2hK)64yGOt^4(z z3FJy1zWdnut4gK66`OPs*OFadt<dxmKdscB(QN4QShRxCxVr6jwVOPZ!ZMK(!lvnn z0z+Zkxm#T`CByuRH6oO+tFh87GY9B5*~SWBObQfO59X3z;<F`qD4@947y0*N*~4ww zj~3Z{N$}mL3kVLDF4@d7Slh6XtD1tiQ>pqQnx{w0hjZV!l@Xj5Y2MsN?i!5xlNz#> zh6t=ZvZ%`)1o#^QqUw_QVhAEB9BAJhgr=r-se_owv@Q==M7G;G0fe$ao#ks07$kAQ zo!DR#mbU?}UC$@$0fux14tW^2v9@3?Sx8q|Y^=7$Q9Jk}T<ALdQVzeb0TbYi;yCV? zcf7jI9V*ya_4Lg(4f<jiyOYPjg=X#(#$mOY)i_8rdHvF*EaT`IqJWVuL<1E`=H4eE zM1DBCYjTVI;2OlU$p~`il2{jG*=2*LR=eMJ_ZT|L{Tx;)j`A>U^AKEXxh|KX)mbWL zwltyb7u`_J9gxdyGJ_A~AVA+R?QovVHzuAa8h6%+x1i9rWujxH&R9qPOW~MiwTN5I z=W(oJ*4d&i2V8W9-t$HQL$b+(SYDe_wjT#vy?9s?z}?%!{@532Gmhx)iuu4bit#^L z=Ui~9$(Uzkr8;a4IVX>KOk#@v$1MM!gpa{PzSlQVbRiVIiz_my#>kuh*mKE&MLnt> z<^SAH_H<+nA7wFhf@OstpnJ%c3I>4aJlh`AeoMT_S(ZU0H&W0O1e~?=;1Y9U`}~aU zhy<JJD*x=+TIKv;edW?%8JBb7J5w9=WR$ogNEitn+L$80%G;rpiI3(e6*42bf!y@O zkHGmO*jEJKK~yf1z3OL^5!0m?4AI<e(e{(;8%ntIyjX~qO_HrpC`i(8iT^ehhw~K( zMR7SYvO)-ghXlzi^24al{1r%H<6nZ)yMksq+>T`DpM#N4@vtthW2aN6oVaNTN^G6w zDx<bP>rmWT9*UQDQ_1=7F##P_YisQdwoc*w%ZIy|L8%dS)G=L$b+?N^eN2z_=U1%| zv!!IX<b}_Ggx`ULdVfjml8X$YdEYNd1Q8@d36eWY#ox(yuPg}$kp*`cam$NBJ1AkK zpn%QNeLX8S$0ha(B=-&;RyLOywI7+^T$<Tc>XXf}6HD9f=D5YE<G>c{)=EZICf~;8 z5iaz0QpBp4#H0qfCePV^Kp^}aJ{k*zZd+f5R9p0rSp94$0sb|sbnaY~U5AHw0Yie+ zAUYCR6s^dM-m7|#5)Sex4qGZ75w3n9QWC<*I*Ss%y~H29bRV>M|0+51*<#j9I`i$W z$Ons&XkE{5UAKo~*?&yabMhilKh(|=guovBL7%seOP0h|mc)&Yp2oX8Qe;Ayl1tNt z$2?29BxoOxI4&3e;s((zqB(PIQc_tsL%&xdhRKDlt*1<I!aJa1gI`5G`GU*1>hh!F zhXp5kZhpt5=5u7h&ZGPOqMi=8+Lt7@<wf?z0=c%6la<ca+I5?~osI2?i{k3Cr^zi( z7RoC1KD`7FvKY<vz_S^lqJ`?3f7hp5!D^PClY&3QmU1oPMLa>&LzN>>|M7Gl)av(? zs@M>hh5OY)bGtdA1q^XR$D&i{M`vy}-CYtqBsZV?Edk)09rT)?7tl(V1*hX^ZSCqU zT>_mX`kh5yM*>^a?`PK6^~kQRX>V`8?utAX|G~d}0}(|~%UlwQWN=?&yxYgi^etU8 z_IZ9qte5ial^L00cl6Yc$fSjx2(r5D+QmfKV>^6IpQ!09{z~?y#NP!8Wq}?Y|9<%< zzsUbgGoi5SS<J}KUlNW>{0B>d2ZT}Pqs(I$0XL6l=NMdZNG=YMoD~v#C#m)8y~ke{ zpRN3Pwt1b)>ZedLS}&8J=Gq}JK@g~7h)JD&6x=b{_S`PHM+^JiM`yKhS4;WVl@})8 zwT1N>sF_!V3ma;FaSwl&bs{4s$bywc!!`OQ5I4!;`4QHRF4m5s5n<H9d{dv8&_z*z z<SGzc+Wi*KVy4sc6)&*A$li%;ZCi{y{yE+AETU`(nPgqWVMFK>(CCZD2zSzjBV|9! zp4|+1H#zk8A?14MM2`76-Lzg>eOOENzo1ZSJgc)#Gt1|OL}p_vkm&HD;GgHi<N1QY z9<wjsjc|)e4*z=e6(n@X$bLyGG5;l~oBAe%Au#){8AR_6q;qnJ%zq=XBc0~Ab=s2N z-o9DbCRflF7QS{~qHm8Opo)@QC>04%x-V1rF6_g5yuau$h_dTsPG+3Ht)H8Vj4q5$ zXTBF=i-f7$qz}leK-WU1Xb3}wV5QjNxUf(#s(DCw>B`??Yga)>hTxCVEzuIm*kZ}) zi-K+*k_#o>?jS(<b`A3a>2&AHvE;XvoLgh#x@~PvNz}qN1&=ZX4}peT6Odw-5KvR0 zN0_rU?6mGDv?N(JM0AYNtNq<aa*+QJ;3@&h1^m#iu{b(>^}&nI6d*`tGWmW!BPyMn zpAHgP#tS+BeR-EG$t6||dH3eld&W<~-5JA@_|qll2!}jU+dn}7i69V8*tvI_tCB=J z=h4l2VV=35+k>%ObBQfA_8I$)+h6G(`M>!aA`tITdht0zTLgjKr9x3jGx?Bra{v9~ zHk0o*aNo@l(LU+p$iD!}xG|Ty7G=!$&sg!2%&pKMr0G(RjBHjf0LXdrV*f)Vt3i3w z6$0|<oYVx4Sk;?57uq9_6VJ{V#QgOAK>QAkwc+`5xcQq^v&!&Xb?9Fv`dPu3u1^Yd zp^I!zMM6(fSA#4ZXM`RDok2t2&apWwRJ)n~%97hI*3aJOAojDXs(XiQua)L-zgP78 z(wU@mKD~$ptg;BrCSmKB`%*>qZgb!oR)?~cTsu>7jq9(9^ltv+&^>{dW<%LwZozL) z+F>x>1E`*M5UDn|7d*6UVH(fV_lL}~xM-{f{0p+$x8uOXBe`?;G?Jaw{I2=e$N1lI zdUbOsU|BDRZ_l9g^sRrX<rb3m^k+XnbLVGs6szh;)-I5m8kaIxpz8C>cqc#T;fzq= zgSBDt>fXIRh3F=u<9lu)d!FM8&#KC~fSOf@be+muScJb+x|wH^YzfUXS@FrBRLW8Z zA|0zfJjWF{m8bqT5J%yM%62I?7KJl^|1n8mKog7jgv@2K!eOZFIPnVpa2ELrJcLuV zr8UCc@+k6CvEiT4c*IEs{c3VFp>1En(R$`nva-Wq1GMl`Yq%WnmsK9=e7o$yu=u4% z;mMSTRapZHp{0C6r})>&DY_dQ*`v6%4s1CVlTiM;vap3EpsFn0BH&SF$pyvA{M*u; z3gSb#UO`RszHBFd(wp98z;QBe9D^@-h#aAa>>`D;Twey2Dl(>+ktG>rT=LI=Snhj6 zbIb1yw)Y~AhXuhjWH;My+R(V++oOt^s4tHd*kk^6ZE^z+Kn8osx3-49;_8gPbHyIp zzh~&t@4_rEJQNF9QmE;Go{tAswKm<p$E>71yx&O+=obkY4I7a7PkFg=8Q8TRT8?== zru6v5`a(Lglnle5a0+(D{ZO4A({o!(N<>cd&u<)eGt`G0Dy+g;6#9^jY^oaQa&GIU z)rLFDPqwJv4gYzkeV=uG_PbB$k35?Hh0~`jc4cQ!ovGu6CH9=y{WVvox!)9lL`oE2 z(TQtf8H`tdCa-JdmSmAUhZegbUEX(}!V$fib=D?&O+H=OYiO1B`txu@KU?Z(R8z|c zPI%_%c-6RDyoo7XZA+~}!AM(^D57}E^#Ga9Vm~TB<Q--Cyumi@YFq!k=i_?@Drm|5 zolWnQ8x7M!Ar3p%JZwPSw85of+fB=7=Yb4#pJ24~0-fS5789yI)JkP99i%%rCS<MO z<p4fmO8k%2FK~4MY@xAC*+qSSmea0vdBEwvi%tdfC1N-zBKuuTMn(fQGgm6EMlA|I zU0iIGa`*77K*UX6oK&{gU*<i`FnLaUsK16Dj~co=&T%uV;}%`zN^c>z@+h6Jh9QMN z$}f!RdYIF}d18Hk)GaPD{mfW=OK>ORzFsha{b*B)2;}jr9em<^sW}#gfZ&DMY5khV z)nREty{UuVj_DzB<s#3>IpWNoY&P^#?rp!str#jHNvxOud<KXmF|G(MBEuPiD4sM` zqdDWdxmxRp>RXIE8#$JOmqr%$f(P$3<HiN{Zg4CAA-B}z_*~q!@B1;l{Iv3&LXZPX zp~_2Sd}Glm74m1%-@G|5FKu++dS(k%$HXBbkt<@JGUa^>EU)}5A_{ULnf|s8T*8?v zVx1er$B~*DxgMdcF;S*^$!f}()5BPeMH-?yRLNlr1f^;YN{TfwVJiq+BkD`?TO?-p zxh1|H8CToTIn^)jkKK3MUK<%a8v04%6l~i~RGH1lyA?yY;z8{*o%tU_cjC|VAIAZF z%r?i29GSC~Yp$Amt{ijbz9}?k&dk}I&Bo@)P07`qQ3xrDH0BCvj)YXMq#QqrqLknM zfjz$4<NMv`@qHi9*ZSn|P_>iLpP89Tuish9$!rPjaEZ-$M2uT}WfM+3;tFocaGbV_ zy05$4XzRJwX!W9jNv*Qw_|(<Rt=V%8?$)%CpG;(ztnheJ$wvQZk59ux@+{1OAz~Jp z#)pPNBfF`x=i4%MOUA51|GrWZajJ}ANvnDWAn1GKXZ=|_S9LBs^Jnym-TlR&bW<p= z{cfsTv39!7j<1~4^9KHC+G@$4A6cs2`_tpWv5(6Spu$h)b0$)zQ+m_W)Z<gY7Z)2O zVb8um|LsE1B`E?lb9VLwa{0%7Z{8%N@fp@&7dr%|>n@FWabbFvByoo+6nH&*dOK6j zs;D|RAv1Zy@xEsM%+<sbPKJw3is04ts?3x>gC)4-oRJ5<n2*>+f4#T!hod)oD_(@I zBVB6DpIT|Ch#Kpx>_IP5S@=oV=8$~fObokG!0R@1s93+)BbX1L7w>tb!7>Mww89sV zj**D(cTpD?Y6%m+0*mS5acf%k40?FoX->+rKT>Uot^bb8q2p~`HFLqi@irYXg{~`$ zKp{DMijJv0PlVIfi`<$=h4-NT>g)SzDazJ5iET9SMaIhoG)33#EY>PoD%xj*u6NZN zlGi$m=+ibY{Jnd{?69wiF4!WAi{RA9_MHYR@x(ErxTp;l))UrV@*SN%PQ8|4e*!bh zJdRiL*2jjf>~WshKP?dC;%-r7R&w={^D7;@Y{d`hL)uIDX}K$^qfOVJJd_+>!<CTA zn$EJTdto>o{Ty?=o*Kh<2@pqf42;D4O63^9=leETQuj)_`O;FF8KIvi8M%oZ&4lVR zSOsF!F)9Vu>XoZx7mcbEW@k}pzZ()J-*Sh#vS&T|jqg-AX?xfE6H{dUsk-F2m!jiQ z#k2o!r)25SvgzK@w^W71<(mEyRng9z;6tK%tGbKogS|UL5llqafONVaKru2WNlxvO zG~env=O6d62`Q(E?b?A2t<G^Lccs3*ke|`*aZdO?iuBZ2k!!!9THqWkQ^`uVC-XPy zjJ#Ke{@h9P&hNl*u77hzF`u&qpC55eYs!pPfjfhe+|q|t+H!6i<oo>-7h8sgcfbE+ zQ(fNQCh>(jq?r_v13w6#-DbzZ33d=)meqSRUDwQSOTLlnK!E)L14P|hX&tqL(5LBi zCHV_nccG6;{5U#FMjX{!q{BnLv^2~%+_=<8a!SAzL_4-WJoDc|mrY#Wn<{c7QsUF9 z!0*7(o$UxNj}c$-WxFSP%Q?qu3O7~n9E@p>w&lc>ug(ZKCZKz(xN&%Q3Gc3cXf=Z3 zR=b=+bd7`mwgX$Ez1eMf2V?^cv%1rb1YR*f=U1rGmlx02UYid|$Nc9p1oRXr=Cu74 zz4`Ox{Eg4{Ij05B#>lp<c^(YKTseg(yDjr<IN^mXS09B7KM8wlm*_j-7Z7bac8w^T zPRvmDSDEtqutfY|02`z@ZWnW}EpdED=xFhRobAB$b}>AP^BRafGLLE9b3_9Gwo4%K zb?@g)QjhIshXMF1flY2Ht}0byDVFCmD+aBGIbZ8@>At$Ht9?)nfqO&-p>BM%OgK)t z5MY?%*%|&P7Wq&4%zZ}SFT|Oj0L~)->@5I3L~)cePfu$|B&IuFXeWL_am*Mbax8QB z^MbWn+58Q_Q3g=@F1W;ioxsaciDOU3f?Sr^Y#88BJAt5lOQz#0zQJkABB0%Ig1OYD zD?7v!GYAgN3-oof_h=w+%n?G&WA;pAM4e?%?1NhD5<Hpl^+l+^vw=}1&=EVHc|dw2 zIbGX7{ryOG%jt9JZi$&l65<@})<*g!g1Z;R3BYkw^Rma+g6?1;K>&c30b5WWm}tP> zyu?vp0I{)S)u!@W@<LVv&UWCqOzvY8U9$e<afak&sYYMoK*rxlQ}62{*qn81AIR6N zk712ueju0eu<vg>PCp2<oCK?`=Nz=-Szh9vE6P4Im8~9B_`}&W<QGnso<2|GUShzy zaa<qkVGNYGNf2K#jm;pBc~b&h0RS}uJk9`;U;v3G$Z7(B7}^Oq0?P*I)E$^sKWGE{ zzXCTdrDdANdotH)Ycx0y?dgYPwV&}njT}7RA)-bS+$VKgcE#^wd7jdQ^xajo=lwJ@ zN-`SVRki#-(bDH|un(=A52-Lv4a}7lFqoI&X2kAkz)pp;Gp#h*ItPhq)?&j3c%jVL z*|1%ZBMzv!1iXj?hN8+8mw?YoG(u2Z9O)Vs6phS!^?HiygZ+3hkb{k(+q|<ZPnTfQ zW5JZ$g6{dq!8J8q3RmJGYy|*I87ZMul`P9uPWzQi7{j)A+22xOcd$HgBCH+DGwQ>~ zFo1R&Kp6}shQOX?z+T9>muknJi)9Z&aSCaia5NimbhdK7LU1->A+WDJjetw;ju$Wi z`~ZV2q-oZZK+J<YABuDM;07W6AYSr7!{biS7SOAG3AW>Fb<}F|#g3a8fvf13Tg|A^ zDmDEaq<q&AR@thyu~ca)Q$okxD{+U$PlAF_9BE6nxx4Hvm)HRSad?2sLoB!h$FZ=^ zS-N&DxIOK-Ra`Yc@0)|`Q?!Qo<vWPq<T`@v+n8JU6}uaesLU7?ew~w9nSPZgG?K@& zE$!r&3a2#Iqy;w=(QD#mB|k7=cUnyf9ExZ^bf%Q={nCOaFM(niSFA<qC`+}mC=Mq2 zG=k#j0>~w}L?_G0TtRZZpENS)Jc$P2bX}(d-BN<WO9VO3As<t2`9we>sMUQBxcrq( z;uw`R&nu*-ttO%yUVm#UEG#T}5}WPF6So9|6Pxqoxkl`uuII!}Gx?t5Km=MNfVa+R z1wyo=f`VNP-Qw;D>9xzd`aAM#FUQ@xk)>Ls>#|x!IUvVG7TiFbnXyQL`e-JRIQvE~ z`Y+#lMdQ-W=MkMcd;7pk<9Cx#R-5P#wAB#tgB{NZFC<R6_E!|oRUCKOQS$&*C;$uT z{ajmqnZ0lcQpL%+mFa!u0cYZAz2B{A599;e4fuzhHOw_Jv(pmu>J`RSh!i7%q{5E% zC<wm3^}d06k}C8b&I-PAa-X0rsb1Q4mFsEaiq)vR>2@*C2$jp|!P6ZM?r&6{I4bPB zoOme*_j6u|e`_Plx7su;I}z*BL+~b)L8^J}I+l!JU-?(h27X>vI|TULyCE=9gAtGS zji+~{t5n?X26Y%z^p7UsBY9$$AU(VV04nU~632l-;;+G2@6G3r66Eigz&_$&$Ow*& z)~C-N!q|g~7E3cq8(|{=kSB`$Ph)4V`n7<%9xBS~4$4a$DbxR0*T|boErO?==3;io zr_oQ~744SIW{2g&jwAB3*i7X2KCYJr9QSuQngNXf0{8o8e$8Cn2O%%3r)pMc4a=O| zU0jXN6S&+6FxTpnyWKdx7bK7w17iK4GZ(@BE%=&HeI08W*P#K|D*_LI+SQJWmeJ7o zO%*@ip}TFEC5q<X$qWBOerDO-u~a6wk)M#k+RIf2Eizy#tH{@gTBNcvG5)1KbU^X@ z*|~k8qt?o<huub;jki0YuB<IZmpI+AU>OKA+6X+l$uYvq5l7{!CUA8zn7dT`hXzBw zr2<a1;(a6~-Lc0hWS*Y@fRdpJ2~&OCe<6t<flqXsjN|dkgEY{%x|TQ_?C8w|PCuO0 z5tip3N_mBvO+IzbQ1Mlv?m1LH@rzy2ea6d^u~%>(o@ZDHFtiBC#qCrI4%np?w$g}s z99yL)-dzaJE5TelH8*E<>RTR&|D=xnL`nEV`+ot3Ga^t*@kpN(gh<Btn>fyoE@=7^ zVkv^BnLyptfh2S4zqaG~u*6+7{`$kMb7fPosEBS0XyaTk&v^kZ8z{HUF=swQu^|*f zB=mrS!}c`qcC=ET8<@Ojk(mu)PUgXX61dJAbA^kIXGU<+Q#lLnKTIot)a4;>EFt8j zK|2g2Q=z?zLPya~^R!cYs9d`Y*aC0!$IvO+*NLzjNhMa$F2>WjOB3G!Jl_ypai~$I zBlgQ3YA(qnO~L^FVD(K7!xEQ=OM^N$c%CGVVXMyrusk1@FJf-@K`P)%`3&NZlZSj^ zsNlZ05As^mr;yR70w;7KMFh_1J&w$Fn3$#ta(gzsLioXy*CqkF3Y{)*dU|QRZ_o~E zy72DTGcF?F8eEx^0I<75;36`iU@YXlsfF`Qm+$x+quCd)mR^3#gLdWVJBbhP5TFls zx!x$AhBd#1@gcV)K`>Dv!D`N*G%hF|$uw)T88GcVeO&hYXWYVPR)jX0+B$XM#*3!~ ze2d4sphE`K)rarEf-@NaNMcO)yoDG`QoFF79awN2mg{OL*McF}Q(WBVvs|SgDpf0* z3y3^6HT->Be6MJO$-d+K%@5-MP5jxgmj*(IOPmobLg5jpd#%vo-4p2J*!R!FmY#VM zFF2?y*foy;c>Z<MpOtkV0T@+_&HHhDPTK4>1jvBKhgzzlsUtWR!AUQIS{Ldc0^VvH za@A_o_Hj?AIQDIR;ImbVi&<a*fv00Q7a~$%JKHci4fUMLRon_4V{qkSxrz2FkexMf zubecd`{%EzfxjyiO#|?F4%0ZkDHZ_H&Zq_fapmQb@msIu<%+;{M^*93EzjT-8Hd=< zUy|NcmP3Ev(O1vm@mqQu6TjM%%K1k{$S9d7;TtR{%!1C~GXKc+!hmxY1zTgR+1h+X ziZ`pW!U_r8ccd2ao)ac_d3FdIY`5;#V%h(8*q-TCL`I)*Pz|_hGNH1`3|nphkIk3p z<oU|Q>eIi20{1L|B;*Y$m-bJNR0&86jb~FwXo#`#x_6`4PFqUSwAg0*qlamB6f6w@ zJE9_aY$hy1pC6&rI|<V056x)?Y9^~3k$`KAY{+yKR|l1AfbcYf1${4hQ<7_SWPp#} zadV>z(dB0uL36OmmylJ4zFy*bJ+YD93$<{3U+A^XAHJ>ZlfyJ*M|kBVH^1`baHj}E z?#@H&tT>5FkkM=%sg4N-iu31<l{;*JQf}p=k6-_scid$*HgKG^54k2bdy+jkhNyhg z-=SRpZJE8<rO-H-K_4KSJ=>cvA56(<=W~B-J>fn8a8JAasLVl2UMOe*Gy!%wDL7CK z^)3K)Z>;(5bQRz3{rTG4n@9h)(}C`uY}`eNH97&-Y_Qgi<(@U*oJ&|^QrhO>hb$7? zGSjnmZw?I>VR^0GvX0zLU$kup=G^<=yu2f?CFi|X0Z}(<E$RV!``yhX+8~yFA<04` z_dm5<t9l(dmA9M^2~UgipxwJrmW#9BaQnA<p>3@jv`@RW46ZMT?d;s+pO!W0EM{fX zu>S~rx5XFDq066}_~9zk+Gk~AaU6G#Ops&mL?Sr`3^=D+y+SLWtZ!G&y!rPp3qGIA zJal>*=DFUqG7)SgIsjlAe)yM%_r>j#h;K14nqex3;Ca6}#xf@Tl(bE)+vJMLEn)TR zYjcyUW_f2#a-`g+&ef9EMvM77xfh?sGZv*WWUCLa%QhH|(-|;to0!+FEUgflV81`3 z^pqqBD~R;zt>ymyw&g>2z(~4uO$M~$U4`cIhjFvh0JUgFUPPTmsPKiWO?eg1L0I@x zueSK@&+p$o`s7Agh`SOrwd*~QA$TERac<9dB%h~7QRuvwR>a-G7onZon^w)<5i7ds zj?uk|zkUw3JsGum?dp*9x;}nF>{*n{W}|`&^h~dxjjQw(^`5R4%bkFaAuiA>FXE4G zJ3o)HJVWpw`*;1z#Eo}VQ7clpvR6+&9>?u}ef!8YlowzbvHK!U(yXPdGxiHj9rFct zx5fD)aO{3%bUQ@&gz9c`#`)*+7j=hHWe}Vb!V*w%<2lE*vM`rX+s>HMpn$ul+D-*) z1U<-@5KoZV!<<PvT>etvSvhI*Xy@ltOSgZo0t7HN#~*2aE=%pZxm2Ntx$f&yfiGp@ z16s10xQ4z_i5t=K*DdW_+FnVZI;%`Yu>TI}5{WxipgWd3&xZ5-3HfFsaSQI0@|dT} zU&NzEgUl+EH`q)?f=iE-ggxfg%+4fy7v^VR&|j6!E*(vc4PPfXMLOE(9PB&VX;!cS zB8eSaPEL;5kIG}3O260LsUL5yIKi)%PnE|!s2Z{Y5DaCllK`ow`rMFW`)*gg&ZZS5 z><78<8t(Mnw?AHME3UgfD%^0#Q{L0`Q8<WI$m2SX+<j4*L9Q6j*!MBNJn^z32UHwE zP2D+BX>+~oSE<yn*jVq^fUD!98SQWV|H0RI9O1XGbpll*V$VS2y!I<CINK;q`d`W& z%ffpya>bBJ)Aa?{6`b$BH&}S3=2hZ*J1(H~jpP?<oa2M=Yn2H<wJuqY?Zwsoc2RK? zd-&k&w0zjO{ldbAU7_}wjo*z=%A;z9@zSv_nYQJ>RTQ3xImj!^d@k<(vr~RY_2E%i z*Xr$r>$hf1Ml5<N68{_SW*O<WI6<oVzA6hpf2C10s=EA9dGJDGy$Y;Gz@z+#ouY!1 zb>)=W7JEV$Fh_npofJJ~8Ls&yUT9SFs>9dj8!>afolV#_-wQ|W4z{nYKE=igr$tHJ z2y!nYEo%J5uNAuX>dpxEzw??6kNp=j|FARp;6qHfidY!hP!#_%wsB1?|L@a;xczC@ zn@RL<l5f9Mh!bxn|K9BU^siV^;Xd4A@Ic=KkTZ6Zb$(D~;uNfAFFT3L4+|8>!@qgj z68Swmi|oJ`dsDLnx?8jNB$#<QWV=+}DlEq%3h!9xBk}Tvf!Zl@O^+2tU>oku9frs7 zmh#35H6j|juBHE%60R+#d*%d|jW?E>u%^6S_5OD2#^cB>Rvw*xd%<5mgFX9ogjLj4 zz88lksQ%E5Mox=>T}KXwEp}2d!b^yLXo?;>W$~-V_ZYqMq`$&f*b(ZpAh8F<mDE^7 zO8K4TcCS<}$d~ll<ds8JNy6i^_-k6h=taD_Re(dG<nsKVZ{{y^1jy10G|U<2b-i8= zo0Kv?e+5sAeB;V*lBMp$(KB7`Uj={{B@+EFBpq39NJmQEeI{1aF5P?O!4~fZAJ01B z$SP3edt6`n5~^Z9JBm46_t()qSKbgao_4-;RqBhVua;#5RPo|0d#c<?^&K@4<MPk7 z*Yx__`t#Gb^~QEF3#=#J*=2iEl|bnRZvCKPyYJh$?F|!YsYc5^fqE)`9r6#+`1RZQ zv6v$PTT15M2<~s48J;$dP>6RZl6aF;Sz9x4sl6Z^rN#|foRH8um5UTss?+%__d)xW z!@Xw$QhZ?reG6^3m}L$f)*~0`%(k2}ZN}Alb-~U&!tG(@bdg#bP{y>4%cd14w4GOO z&>Zj5A+wiJ8#&*OZZix|y<Zzt7vf1jl+u3!4B18vOK<;nrR6a2tle*D>%wjWGCxy> zR25$e{BavGb!jiG3-wn@a32qFd0h56^qSrucLv#|qeeO`$U5QjOufsKhyGz9o_{XS z4Y@phTo)D=mT=`{aowe}`*T=$(w{3!VAn3X^!14B1dlZt*Joq?*P|-_cx;%uKA*0; z9@CuQxfS5r{r>ay8!!HN?vh=5R;9z^UMG0%*So&h^bb$?@W<<L$hG%JU3k)V!qww- z*Oz}jhu{4B=PCf=#{8DJ6z)VUo2*+OR{)MAevD-|bL;1?$E7JHdPA?d(M6dqtlqIV zFU4&@QijQFCHe^5cN<g)h{*C}^0vcnL#p)=*<p#kVqe^bb=D(tla7565cd&`Ok{p` zqMwwk`zy<U$ij-_HB1gGUzXj7h6BX^=Mdy<ESjDB6UBdjXUk~~F^C*rO0&oJ^ADnj z(N67`PzfiU*Ov1N5cpQ0*kT++XNg5>!hWiF=&0N0qM0g@DRtqO**$lO!bCf^U?<af z;_3ei7YsSiMjP^G(um>`Rq2vTRN*g3g}Rps55hWX;JVD5wqrorxw$1aJw_iY5NYXn z(^dD*jv)^gK;Q>-1GE__vTJ?g=hhdV%Si?3>Q<5X%BcVpp^u-oOX5E?lz5K}X)m_^ zu;BTeT^3Fh-O9_b^yueMXQb#d-{q?A7I#|B1fpJM=S8IZiq|p>xyu<G`g46e$v7h( z04n>;le=9h0YUWtDtMjz*Tvq`j2`9UA|&C45LtEtYAzpk-L0U@vPV;*^DK{c7Zq}1 zhh`nCqmr?b#%rAw4~$@!&3=pUgiom5>oEkuEbD#w0qh1!t@%0r4HyXxLi5CrSYFun zCc*%s4QPPDuET$by8L_pGd8_nq0H5DKvAsX1$QT)D~0^E6$}_6@P?1vF8MG=E{X&; z#I~-keqGW598TPbJ#IV`Qy{4IG{3Q0#%?e3lW14r-_BGxzvpJ4pcD7(yD$KD6VfL( zZ~ZM=iW>v~8KkQl+g^UWlZXYDIqT20K|}NUPZ4)hB^H;!>S}$Q)`3Kk>;IAMy8`)w zQvYgy^DB<T`-(22{(K^?X~bLJ5nZHNFKwPW#Jl<H_w(9U)f*~2WV^U~qyOZ&W#Uew zs#L1@ym`9RWu3p_9hu_a1Hp1^h7?V=KF;{LR9SQTtRQw;P#y)3q_H@G0}&uw1Xzy& zRKSrm@gz$`n(JY2Y*(*-*+m&nop0^8^0@S0(8-q>Y!(bQeH2M;7pMm(ffw1B1vkA` zpb848k2JJs00obbqer@F^yf{EcS=<Y?p|RZ_E8$cbG#@cU*2Fd*wy<tmXq8-@rRS; z#K3-VkfK1ULLN{V1#(OWIqrh6CA?bs5Ihp>pU0+|Zm7dZwWfk27~QeEea@#u4o}H{ zo|66cr!Y5!?AofQiXy46y$s{!3?*nj9LbGD4+NBez2{QFCu*H4IG{FznMzEKX6VEP zs$S32e#ytTW0B6nNS#(`B$f1zULjjkNj6lV#T=WwSehl33Bt0507<fTBn5LK3P2Pr zVZnN&2=cP{2$=emvj|gJ5J=!fyp(SVI3SOWx$bVnAnDNtXl0o7vC297mS!L%j?wJ{ zPkWz5vz}uMne0xU>x)9(>R;A)oxr2x4vDd%#3Ld8Xfy3OGxa&3mmAo6Kn}0Qm%MC{ zh9fab#S6ZIud}}lV*11*CYlUARRXIHZz@wT)yqr8j=VT+$ApfDq>(9dNLGa|7Jd|q z2sK44omFOuh)gHixdBTB04(My0tk}Y34_&=mz)?%ODanBHiz`DK5fy_Sz6!)92Q2y zLGN{dmSQxVA4OL=y@^-{{0+vjL#{J)tewdBqWf*#z^ji7KU<2E*e;x3;k~#By1dVF zhM|Wf5Y+|1A$y<%21S~{DurcLGXUyt5be-l+b(c?2_$ea^>R9!$sFnZdp4sg3ciHG zj1_YoN%KInoJE+5A&6p2M7IWzKLhwllFhmmyyiHf!`9-^rybVH8H!KSbi-KZjc)q( zN*i9Hpd@f`N(6vnHEA4ILe_U8B}svTTQg&jV%O0xH+}e0f&`t*QWry5*`?Tw@M&w& zFPQ7#?tws&l9T``kkJV{*@?iab_hy9f_|!jYe{-xNJ@|$`DonCq?M#J$LiEdiK9Z^ zmVn%;7N^Wv!~m=!OGH<En)Mt|k4myPpEyRAYx?#edX$>zy{=S}Y95>a5;&x7G;dXl zQ6>>ECh@3SrD=>Dx<QU_;Fnf3(+(u#8QoD!<Z+#XX!MJ5BA-)7W&oOWcJ8G;g3ZiL zHI!F3h6Zs)5hbxiDLmN0oNU($^1<4=9Cp8~8BJ({;@mjGuoQO-N*xZUkVn+*A~|4B zCGA2IOVTnGi3oEhIn1ht2U)l3X*1YD*>#^Q$T>|4EXq^3!XVcXsqcZb9@QS)(z#T^ z<HZx*OXe{Jt->WuqutSPYi%6KrXkHr$|+e(@oW`vDnawZu>y}SB)*nx6G%k71-d7) zeQBTs<KclLBs74i(8}h*#7og+yE!6r59F7}aLe8$9Xb29K4{8hq5IvJYKy6wDB$@e zAl#cbu>_)uW0mn_5our+y~i&}r7a?gn>IBZJ(OsZqhSmke>_k<FO_AyoA)odxU}Bw zfyAEq*@r;Nqi938BKc@lG$L~1N1$Z)Z_(=njt~Z$b|6s}2eb$TU4o}E+s{Ld5TA6? zg%TEJX1fCizDyn0DFOQ8$@s2by=^d+zjT5hk|-yGv&+~;LVB|(YHR@Q6JC-71M+hQ zl1Qc4u!A(HDTomk1TPT$)+rb0=ojPOVKp{+`5`UDRdX)&vO6S{eX>pGUP2w>Q3B6j z8u)8DSltP@X53q;;5@uR1{5iFJ`;`%goI+<n4+<3XsRuey!D<OOyKZi%%KQC-&Qto z1~}e;q>Y@%qbPrH^Y8bb^Q(6cgUW6$gWKK?1TF&M$DoP7pjbOf96Q)P5O}>JMQT@1 zy8#r7&%KVIM3mIOjr0VREND`J{v#Jd14~<%>$3VAS`IF^#_?T8QcfostD}K6zNHs* zc%IZLyj~K0=I^Fk%w~cBg{D(7EGOa*-(O%~>~k&*NrzlKF(8S|4;&!{Un9k$7=`8i zrLi8mgJlK9ZWNr`C)^15ffOx>8R#jHYJ;_%sDlKsdm>Q`;VwOS`188Z5AU3%rbnTl zbf<#wz%^-uFh-%pkB6V0NPHTUxDR@s`C7+3b=1EBa)$+ADt#U)ObH7Vw7~X(>qyJ0 zl!Rk)XahNU#EnTFyR@c8cR@T#D0o_`HuCC_iC7e^cyWYVOIRQXArOo#LRR|7SFQw5 zeN^%xT2=h|?vM>EWiphJ)CF=zf?}v-MiNP-Bt>kF1fLrYKzWDa7WB72yb0!OD~6Cw zhVgc?uPoTFtDSwDvY-#rvCgm9^3F*0r^KI>kgZWR8am#;USU5*dPbrh{0W!L#YoJ* zicD+SaJ&2)Bg{LB<b9YH-AZx9f#dVYT1!A*H;<%0g|ZSwZg^0P0XbmLT|JJ?u$3g> z!Dh%C;3Kha!j2Y+X7i+_1uRn%b~9bmL5+yQ<c9ToR%uQ+kn8Sp2>WH#k`$CV^9iT< z0|@bqyfNI;_)6V49R8cs$FgNij;aXme^O9FMNaZqFZx-J^y*HQEl%BvV1QR8*-#B> z)=b(PpB9Qx0PK=O^C`|WRuyd8Rrn<@G&$}NV#5x!LD01G$$pJ&iRt;mO!tI&4%kB; zSPbyEuiTl<-U^|#+XX3}xP$Z!*x>F0KD#evXIHHAQtb$7DiYu@JjpJQY1I*>(pjXL zr<a~k0O`ZnC71Knqe4%|qS9?;pEU%xYZi7@Zlx56yzRbe2VVS<x-};7^{iX8^(UuQ z@M$NoHnY)(u*BKjX^MyF<gq#(f-DcausCub26(Zd&>xZJ%m5|NQA%-?c4}#IE2nnj zRxoby#v1SIk6ZLBdirrI_x=^)^F$I5X%-Ah67&6k4kX<KQXc`icLAN&fjWUCc?3x~ zokf0*^o5x`UJ~38^IrCqTw4WMnM$%A0Bc5Ri!U?`@P^!vagS_WJSqb(N`myyO5m2X z79u^Z>RJ6y8bBedX)z7<$drv_0$8d9=mftMONH2Xk#Ax_N{6Z54A9UlBoGPSAi%Pk z$=64~QQRLl>V2J+aTyB#MY&I|arr;Qm&D^Cfd>4-M{KrvsqSthr&cas15j-*8q4IV zN65);lv!@%x5=jK4DyZJY;mnpX2l2t=iCHCL8_y9TNotFZ7})v`^b^bb?fGE8aR%Z ztXu-tgR>eOUi=_f5|s{7b|YdxcPI0L`dcU&7t=PeU-h5SezQZk-HW*c&K1w)N$nKY z)%wS@LNxcBxn<og4M08szy)?z=C314WxY<5i$3qSd@-FpfN~iC^hax~cspefubQ0P za5`}7sa6)DmaQ%)8d^8-htjym1GOV|txr>CgY1B^2$R?)Fyg*9)&O{(`48Vh@x_7F zGJwv30@{-ghaBomUdDKI9-KJ?Is716v2b@IR8Yw)3eXDTz5t><WwXVTBpZnJw^Q^O z-I0M4&TUQB@4%sl5R!yJ=*XsF&PB<-cdr2yy^3fBcp4?+jVEU$;~V(gO%SStEK4Q2 z=0V<l7K%VbUd0lT@KNzw6pdZ?M0A=9H8hq%o|W!?FZ?6H6A$|;@}hu}h>Zde(vsL+ zE}8>X4%swgiF#cZ1LSpd$W4+JrXj-SWP(%dyjHW+4FG&1NfDgz(thqF-r64y^vAQR z+JR#Untu$$;s`)Q$@gSD#4j&DumKVt1_>d^how6;<o=G%k8iN83a1szf(eP{X>tUR ztHCsLfmMx4f}=>6-G;yVerf*8ZWmKmycB)znp<4!qK2f%SFHxyueFtN1?D%83~!LE z)~Y!Lm8yS}@l>$UO``G$Ic6?8f0-XkBQeK2-{}4Jm<tRs0NOAf7W3Y9<PfX4#NIXd zEUoKL8C}a~q3|n^5XYXzeGlY3N0d)z)!Aj!WTdFJ?iX_><*`HFyQTLH*N)N1$*8#0 z1mQIFsI7-k=PS`j0L5u~RXL9>evvG2vH3RxeEKFyk8vb)@*h}JG9(VmDgqx(WPq;S zO=E2$Ytd3;(|P<XuYRZgZs~@K*i0nSAWVk$G6O^aEXnf-t5%RlHfH`4(}-LHqyrHV z=LR!RUm#0%j$hUZTcj0tBO|3=70B3DTQx?09*I1UVLc>Ue|)I?y(>l(VpEQ$T)fH3 zJsOFeEHV^lMf_?n?+Ra{1p!g7Ukm&Hok}X&Xm5ChTkaxqE5s_gSL;e=D*Uppl(M)s zF$3InF7Lc?V3o$wpXu3t<#0v3`}CX3;<|4p?*6%bJLnC?-}0RGZ^!SGqZjX}NZ<J> zsvdW=Uojc=t*F<*u~)3@^V%z`hz}mxsoN!iov{f6B`0@Xa>cu%&cC?`JD-TQjGUX5 z(^0i%Vyy5NM!7bL&qp_An+sQmT0E5$!dISznE$=<Y<}iVjqRIa*{*Px$~CV$g<mv- zXeHz3zp~EsCLb7oJ<TH%)8U(q(Y3fQ;rdRQy+Ui<kF8i^dx_2?9={kdDt@KN+YE)( zWdW#fr#|L3_D=edt+fJBO&7h$sDkRaMfg?{HCF=pY(FGM+34C@@#ku2v&h<$-hIZ` zxCUmdI%lrjDm;geC+uC)|F8?6^wrJAWM^9th1Y#yF{*_!7^vZEt@nAW+34821p`8L z8#O!{TLb)~>VNU{4DZiU^=^d>;iKY`(@Ju8s<=<i!6!&InU2=#2R)AWRiYJHM#Qz& z+Id6~JAE*nOufdsOSF`l53*(E)kFNFBhxUQ4<+#p&78ri{Nkl3A!idazW9d)vvnJS z8Vmb1<M8OF>4^~k{KjnE(p^qMRKHJIn8onhY7+kwl+y%yxk-}SOKpqJqkT{$nX5WE zz;AmYD$p09Wggtk*Xp%roTK&8irGH=i4-*zcQB90y>HvY3D9|uD?Dcpi*tOZ;{dI> zC5mMjrlYoT(@yzE1>;lhLr)&R68&x!l~bLz6B77pKw88zbB*9@tv&5vZ;4;Y8J`}J z;@B=l?^)G&XfBih?VD9G)}E7pGfCF^!6!7@rbf$K=Qn38Xy4N=9(DY%(yvJWZmTgj zKFQ^Cj;9nmBQ<Ds2fc|~6+S<(Ujswl4vhfG3bya1icRg4vbC1%*cKW5g3TqKukt2s z^qs66vqT<^JbwKo*U{<m_=Pv(>p7nWxX3Dd`)W2dnLAhFaqq1Ea!<?vs8Bdzgui9e z_L1>b%{WUVGyQpH^kiYX>V?Ix7qtz|bmsR(bCSyXt8MiGZa|n`-vB08EirE@M>9pH zB=E-@Wo@L^e@&7+7dzCZdE{TFrm(3kEJ<d;G<eUs%*_pH?W7en9@L7DbeV`Wu#lPL zC-*3t!g$WteefaON;Qror9BM0eth!H9A2CAy0`B_*Z@Z2x*c6*Eu}6BR}<tBVcxP9 z0k%H&6<tUlXHRe|int{yt{O*#)%U@G8FaB5eFLX^2|1FNY9#h}L3%!E9J&Gxgv0M= zKlJt^UIUuKpKjP{moBFXr=CrGJTk~Zrajwb=fq1{*oW<=@aP|=aMIGv^fkP7`MIUt zJgj(lU$*50-C7n~VjtEdGzg9xMCJ`}aQG7NigD3qe4B?@mcc23+DXIsjC?6Md*WlA zm@L>ym*aHpGS|gLZ_Yn+UN0urZzbFL3P+)DX$|f1Rfg6TolB7l_*j)4l_<k=lxL>8 zOCSl%ET8$|Rs)+e;EZdci=4d2mQP0u$i*G62<&uG`2H<r1<b7EQbRbD)3n6cth1sJ z<>~&3D>f@0^<q$O3g^SfVt8dB^893m#-Uuse@)ynCd<ouX$PVLHbAIN9z;X_XHL`r zhu{@E6YVK`?yw?~M0NVGPEQKO)2&ALZre4CiNl)?e2w_eu0gA*Nluw20{hs;u&#r0 z8h-<e$lQ!6I`-UfX4ioI7y=`4i<c}#?c)nac{$|-=f_`6ty0o+cI@q|iL%3JtuVkz zR(QjMuwv;+xl-5BKJHKemfwXPff1X3U4XXngDIQo?;|o|6G;}E#!jtIOI!{Fn#s`s zApH820M4lfc6;OmBeB(1798rE`6JIv7j1~hQ&GuriIKhhPQD|UP$TiJi=xxyo$XCE z0;_ZpFKj5kRtG$Re+eAcewslW3i?`efHM<a0NgtLip2RS9inyV?ckj7&sNE=LRtb3 zpNI#WS}J26M%z0qFvz}5$G3(#%a;4!-I_fYS8T31clMU*zOTpvdsA;uV8zZ#VDPrx zkSJOv_hSzbp46Hua6N*@K87yxH{Eoh)v&~?1Eb2^EW2UR-GDVoy{emUtNuMD%Xvmp ze8>PK)W8eW7gK_V@e*PCj0|K8UGxXr^-0CcxlXm`xL%+@sB%<xFyjGHa(*XiFUz$` zTp?&|&m;C^RmMn?;@^x0Qb?bxpb8s?PN6E6zMS!mx8t4!o=$bouS%?}{+tcF#{OBq z-a99j#=?IeHz+sLcRs|=H*-JTOiSKAqv*k4(<9ZW4XUGB{Q%FIKX|e(HVbT3y9{9~ z7*;l#1fv@I_@7|S^wy@$^VhzesWu-}+_6hz*1=#evXqnVCG;7cy8OcEilz3d&a4c- z*6cxX4x=*iKAz#t%t$TXo=xDZv@#cFDJM@l%zP^VaLqpdSP=5u+h28{f&V*-^31Le z;!5oo-*Ou^TRoNSJF+VN#()$uJn3O*t&@7JQs8sjg(rHhU&2*x@H8GukcApa{6(cH zMOK}V?Ph(1x96-MAXhfy&HK4`XeN50_C)x23STXPGA5<rXLKqqde3H3V{H$7&+{RJ z+>GmS^r?uzNs4ZpUv}=7gw?eB8GZG;8<PHg?KZ@$EgWyseBT?YM#Ts=bPcO~TXv4x z(31FqHkQ_&5_o2PC0b<Xowi>KESZ27Z|VZd|Eq%P0kFK&8xXnBNw9|4A~(s-RQq>d z(1b|j<%B$nUZi*0S>{0ctefeDZ>_h2YwwIJ1LIfYYuBPmcmY@1psRhvqQp#+sN7<z z2q%j~^}h+J^Y&IBC+xEDczR5q6Nk%7r?_fDv`92^KrOXuJ7_mW@V*^L+dx-A;KXb7 z_Dt*0y&?yR+b)$99<5$Y=zLDXlFxm@DqVGa2P|#gdS+t@qBx7<QXgO8aH5jr(34sI zia=;66@#2(V*Dd1T({HTEpe0J^<5nY1}wiFI=r_p_w?-%1gxA)9eO?*eV(?B#-KYe zqYW$w!Z02FO46Opu_!~g$Mp;9wQ<u&3jwO17{V2h|3r{SYJ_y=75$7|KdPbs!V*zu z_w?<35|VvLYl~IR4a4$^>>^HeFt4;+vQ`f~bAAz{-AWh7v6yvW)VEUjpeYg!^j{<W z!qG&Du0F+aR?%@H&moPw!4R3qF3vE3LowP-bghAzvs<j77=($j>B*)&m~k*59b^RY zr^B@7SJJRCsjjYqTw1&7y5=Maw>~K=QWJqbt9!-$Xkq-w?aS`S<G6RR+f}ck1<?a^ zVe@{}{wZ+)P^6YF$MowqjP7SUn~MYgzBRmn$HWP6kpP~*;g|XDk~FL?sVot-;TSn{ z7KIu5^}cz&IU2LzFS|rkWNM3cDKaP$^Q2M*&}9G^K0u129$lptH~}!w-DQ#KAmyEM z8Od1ekTc<~SbXY@i9>qbb@oAoiQD3V8tItCqqm~$^w>m61FbUSP&yjLFFw<6%~tg0 zuZK=c>WTLfw;)i*gHr};g#1U;A-HMbNl#3G%6U#F7qF-754@w5CAI~!6L&x8QH?GF zV6qJ$jTwwiE9)7>K0Y-=e!^At!4#xlKN4>w0#7-$)^`Dc(Zkkc%z)1rlxVuywJ29! z$nbN<^P;;%U4+-{da7&z{91mP<8r#pMvBa7x<-1Y?f@r#<dU{|KV0$dqmC+ju{0J_ z|4UtLx2?undVo3ry6A37GK2Mk9jopPMzh>@#u+H%RG~RAv}bL4<#d2Umobo)pj1TE z!?6f;V07^|-5o%6HzRReKeCHnp47+5Fc51n@;?Bol^f|nNy;-ArOWiQwKF{Rb^n_E z$F|wEq`1c#Osdo}%`%M{QW8}ui;7R3PYRirD2Lf&q=<(0BlC=+di#+ZeSHV8X7g&D zZ{AmO*tlOC%g(SOX6T-ZEE<)p(p0)q6G^#>SF`q<dLU2&4)p0+DPVWF!guNN;ins{ z20@E`Vy#BHGj#F#5kE3X!_6qg)G%d;NVEXzP)X-oF~S!IwAAiDW-B#MuTlIal2lG= zN8e@yx^;*P<DRT0rL393&yLOX%gm*mNhF?QXFWU9zi>3_hLDb3zjyNLBQn~^ti(vf zfUdK~qB4h3*$2iC0hPso=aqmGZlvxuLB)l@=)6~xO?16ox~VtuLak^smcw%Zqt0Hg zHgHMH4cNZHs$Gi_mY-BbHJ+plu=TuppVnTUzdfQQWv!cfi|TPd`#~{#8c>tKxZZ}* zC-_%M*gHU(N`Tb8(NYZrL_Dt_If79<Havp{>aDQ=x=1?Fr5b^BeKhcs8&DQ&RA^M` zz84@}I{TuCl!zzY1Q^Keipq9i{tKngI+dNo3C8UjU)(U#rUq%_f#{hOWwcy5xu!fv zvS`~}YeeGP;Qgc&v6|CqiL6;80Gfs$eIZbR$8`RoeTWHzQNu}+(Ip)n5s}7pIVeVD z4X6VRtQ4nLx&!Ukm%8iZV@=Hl15FbS=-O2Jg~YzodBi6N6IuxHaSvT5nyy2@=u44w zYUS>~wp7e>K8Y3gAIUDKqAT}Ptz5Uiviw~)3vP-h1a`Tw;RY&YZV^$ftYZ5{+KfI? zDWLX}(ZwRVnc)X>Zm>k?0J_OsqP?c~GG({pPQx5VZtMQ}8TX3-Qj(bK%sTLVb^WOw zBRH0*8){lDznS>$vgTalaJ&bJH|??WH7AF2IeAK>IRmMotY>@r)v!cqEJhnm5(XG_ z&yr4Ffc4OHodG5w%W6^`+^g~}25W&HH!p?JFEp_BFOrJC)7NG*&Uaxxsa+SJNl|ab ze2Xi8_^PqxFF7Q1LwHFp=5666wrL0K7pMC3><*OB_HCZ;Y?>V;nVEjX0ILkHzpD|G z_s{4=Wd?(GqF-kF^mLmwWiIER{ib&%$Tx3CE7~bo1fw|KC%%DM`$*DjpzEm7#R-q3 z4~=w=nQa|omsjhdM)L;Q7)`M$;l)&+o|aB8V@SQfQ~jgO{It!TPh0;Gg=^U|p+qrS zA8N})kA~qk04n3YX*dCAD$0&p`_H1eeoTdL%3xm>SeE`X3cd(L*~!b$3<D<mF2G3| z=JfZ*ACJ~Ae15VRGE#YNkS)7naAc_QM4OxS@9iHOxax_W%L2A%O8QYy;QdC@DH;&j z0Gx0E0>M{-E<{bRJI@ysjLT&k9i0Bv45E5ofj7de8OWH}ZTpPlDT@&7TuhwLJ3)<* zT$^i_z4l;^A=wwnvx4*G--Fh4zagM)r-p#q1ATH$#7oH}P1KUf5MA4eRiUVj;qzgu zbatkRE^{<|;h5Mo`pvmj`W^V%yZErCx4gH4mqc&23o3kjm6`U$s8P-`6?5xK<VYW) z=<NM@j94v`A;jo8-Qw550Kc;|*DEQ|b8y-N1X%Egw;!BQCUUl^@(JG=rFUaTfd)hL zDKU0IuE*|b?Jx*M_z$j&OpgGN`1V<3ip~N$fZA&*$P$*Td>7b!{dA61uyLyBfXA9= znomibay0mF)yYl|xIY6B=XNiXVPl9Fs7PE>WzNYMT?-xg{hwGYX-nAXM4I|F^>|0Q zgXQY)&l(*Vwf%P8>2FlT2#UV9JY*HC_v6xq&5k&EnMuP(Qqh(d)Xo$rS>IzbE^Bw3 z7)Af;lZ0cmOGx|cDXJZYd3YOi$ras@b<HVdg~!oO`Y}yfshMmUkp%h^YNYj*FV&Ub z<==JGumT0eh=^Tcs|`jwF$L9=VkaG=qZ^^K)MuVmgUZUWuzcbK{7^`<)0y$elU8$e z4O!4u^Lo^b(y@tgCdqBFAONhXl|UUQ7cuyow%q}pbYd=+_}(hph7@)8b4;L+M)KPo zwQ%C&4izWPp93AOqU}Xnv(c#el`}J+MUPosjGvz0U_D>5qf=XRqG@H{lgHZpG}hYI zluPo)@BZsON+v;%FI_!9xY?qyDSad6%@F8u7|NNX#`r07t1qm^MNf((-$fVpz?eaK zuv;9myN2p!oxx?_y)XYtRM1?_4vE|?kHQ~B^VfPOsBAU;e4S2G*eg*%v&h#1%VvOT z`+msK{yV{RjeShRPt14itU`euZ`;m5%8uu>Ou=4Zq=8RIrP@u^4yUZU*dM7{Y$b9% z#F89C=2=76{wCB#l8NqDOT}pV&6@ngDDtLHmu$OSdn_J>md=S)%Pnrf<$PIdjYd7r zxT$XW<3?r)=2?l6A^@Y$+kZ+8WA>ITU(QNui%1>DXxy4%KL05vFC-OZw4|=i<zL;9 zIJc%y-X|aQ#M|;{OZRcnFH5a12gUS8m3;$MT?}!IE|<unXN&=S&J=k4(BlHo9MpX6 zM`!t??Xu~{kUZd2PoJ8TYuuKM+J9Q^Xw}BD!`A?9)FDw#ks{1X<dvJ$Yv^Yt^BuQ; z(dn{O8~I^MyI)D%tQ*#<_x+M%)xmAe8|x2uyA%KT%gF0IlERbUS_9Ihmq=<<x{zJ@ z*C)zzUL@o`Mw;r!mydp2#$+&`*B8c4`a!Ok8|fu(wXbG9*GYI0HTW7E_weeG8ro3U zD?z)#NUWAV5kXI68DjF%*xvUI{93Lx-9yihT76|tc(sBf%XfG#b-oBW#@*V{E&-yt z(5P0@TXf2qff9{1Qgt^oIj&B(^~<~gP!m3cwzKo4{T!Mu<YJBjtIB)iq{OL1<W`Rv z{FGwfXVfgrs~{sG0pJ(dJE29o{!*9j+9ln@Kl<Y-$^*RgGM&kH-51)JoOPWpG*F8` zhkWmO_wa?LMQRe16@^dKRRcC{-U`l$Gjb5n0qmHASQQpO`OuaZLUeQS&zS=t?K&zp zT>n;V?=+?Z!-RO<PW6kH$6TDjNR$&xSp8BBKXl`ajylZ9g~%7Gy@D5(A_vTMLNSfl zsIT40HWU(5h7U{VsR?Ff;yl`OX~>_fCzv5M&5m<=VkBiYBeR}W;g`vc(`KUsYG$`} zzRI33fM!;AiE_H^8jCv$B`GrSD!s%$xm|wo);;k`Yh}FAU9ZP=W+!^#CEOs6TwT7+ zmXqVL1x!glLb2+sIuOB55&{f7jz03sw~&2wT0Cy9b+AS@aOQl->PQB^E6mq48_p8F ze|XBzJYUk{wptvY|D|FD_ovZEd;wN>WuJH#-na1Xye|IgV1GU;z^)3DaauiIAZV)Q z^t%_ppJt_Mfc4p<{2N1d&k}#vb`{Fx=Cntxe;ni&<eq*U@dfoSdebq;<5|?#*(a7o z9-ZOS_1XD%tgqN+kvOut6W|d(gIOoSxgOVGC5>)VLr;IyT6o>{ImmmaE&aMwC2f&5 zm?iTqPd#F-H%Z|*9_Ks%IOv^eaNBBU<Pz<Aun-=HUZ#f$X(o#ueVARDb^f8wKDQb( zcDz6BCv!&I`94|?cqOFjNpkg+qK<6K0q$V4u=B=Aa%@Q0X8mM_tI~z|x!t2*zuw#v z13bu=IgMo^o#lAmAk#`sJ8!eo$%m)_5&w@R>t*DPJ)b*~9Y-=^b3gy&4)9qUzpAe6 zcm-A*2W$+r9`tMF4~c}SjaGl2Q2v}7+cPgC;b5A7O$1rmH(cx`pZ`VPVj;*}!v6SB zNsP_k@4q3%CtJ1`&b>KQXze5{oD__!yxu}eMpPEmi@a;!BZ<ao9Q8@K-L9$?3Rx5O zEycH=qEu?sYyDRpIRNEtQ5E#uZ+Tn)l>(FXUNo09ReG_nSC3Hj=M5?i9?tif%Qwrp za$U=$Lc5X$Td29#HdJ~u=hfQ1(C3W>Q`x8w#qX%{rQsr|-~08V3T<10^M1u4Vd5Gm zfO@g0g&@=X*!ui01!xZo3Xe^R-;;{am5kwAaSc5Vrv7g|e@XTS7nl{;tbGNeqtkqa zJ|%kha}&ZBmfOT5o(B!*2F%_10(F~-1LyiTeO0Io>IfPZzOWJp5erX!%>E%~=dIA1 zW%qoTt$(HBwQ>cF*Ioa@%Lym<%kEp{ub0Jp1=UuBujI?-pnos>!9oBHgU-wa=;17@ z-^&5&3HsNCzbQ?N-52+tNQa2gVdARaS`MD1%VP;CE#)zzr&3F!o;S)!$e#D6@LU9> zQ($_(`-Vy{89kG!42uu8w0Z>Uj3|%jm|vHP`)cxEbD#LIkmOCRuxm@Mx<^W7$>qvK zxbOOs-;A<X{ug1F^fpp>R7c}?#<1s`4%E9Ay_(yfyexkmEWVZ+7Y&z42yVYVYbYvq z{bQq9k=>3tggg9?1GvUa_msa!DC3Gvc}~oyUX8_(yKcg$2U>5QY&ow>Bq?2aXfA?X zO1~~X_WmrSEPg9uom-Xs?1X;j!9BE@M3Vtfk7$^U-!Rb=D?1f2^^P`##fV1!cF=6~ zMjimLrm&f%j7a0A_!3sw7c``=bP{&mN%G7CJF?UWpu_vP=5+t)71frrobf#mE^!Wg z0LP*4d{3zn&8wzQO-1!eNVMstDpRy-`{b}zmb}|oM?IW()=l#jj=DKk8D1kuaECAK z4FW-mK39Iui#H?4coYqwX0uNjdc8;9z5*ClSO3_i4CgQ#{U=S1908syVnX^JDY-YT zYM?=L{o+_O*uV80^l!siy#>SUx3%d^-`CQ7E6_|gc}j9JenxnUoZTP9SJdct%XGFa zdqg)&JQhV+SV%d^^=KuD&pzuHT&HDX^L==W10i|=hPN)elf+gTeydLN;{{7Ym``1t zXV=b}MG|}|6EpQ5kxsCPV=mZtBv`5znH@i}a{7Q~`gR|XDs9&fuQdiL{63ZI%Z3S@ zXU{(>Cl7^b^Gj|#yDdQ;$q7TMN}f1vc$BPM`o-eQ#{gJg{LaFaI3lTiU^m2HYnOKE z(2ye<Pi6^$XUAd(#7@6@dr5QZm2p^Dp`v$?5eqFpt&*MDuo4nKoXIJ5kh0el47TTd z0&`676G(0_)f<@1O`xsdKkS<7PE<iPmkhWJ@{FXJS9-0yPJ9+VW)fd5aj)T;Xpr;6 z%U4Kxr%ql7wnUiZ;-2nxR4pJ2-=*FW$vm4IeoIl~hTxXff;J-P*bo{Ucv}5i1efcY zr2M##?5Sh}k`mPiet;X%4V}v=3}_cSCs3t1zv4dq6eH1~uH?LG&(rR)CGMZGJ$ODK zC#zyryi0nFFD~nS+qg<+TT*k_`%}5G=`I&^zJ9<S)#OJIFrpt2Q}B%?N2`CS&*n`s zOgZ1e+Flt#H{FI2QB}G4Kt<ypjl*ie%V5zW1W2t5BX>zT*RI@Oc!mL1Z<vJs`~L1_ zEs~s<s+M7aCkk+^)5SUnU?p8QF8lQVxjOTIsQ&j4pIOXimNR1;`;2U%LiSWMNcNCQ zMa|ekk}XNn%ot;=A!MtJom7%!tHzQ<G)jfkdq$K*p-ozRe1HA^3Fq;6o%_7beLwH( zvcc>6NKi*DFvJ$Pl7UAG{&XQh-99O4gNsBrBW_LMB4yXs;#+P{p)^LaUP`P4hK~sI zS2b7c(H^^%mARDON8jvtyc5DY-Pm)^(NM~C+C#^8v`6__zr-TmfB?*QA^aOTvh859 zl~<gUrPwBU;}fn-bgSY+_pkbCOKCx<cS?W0C!5l~Vz(Xc8Gf2=f92Pc58FSD51&UM zF8_V<A*d57Q^?@R8%k1r4g7unl8onX6lI?B&IbpCGnTC$2Pk`#M%zMMO?&lIG=&nv zclX_As=N)r)E?!=&8ph*5`_BXDkg!!Q{xb^`zD#v-!|>C;$J?>WB8MM)%vz18exys zY#4uAi?Hv^Ap*we*JA~Jkx!ZL!W%cd{Is_6KE!p~{b=&58o;n`v&!VA$b5h0KdUjd z1lz*c)Fjn?&wI0;=X{9<7|LqW;2xTBL{VJsTh49sjKQVMUn`P>=T~4m7)#U9Ubc+4 z0hwk49>`78P4Z{mZDoqf5SIN^xw=9rWru_2Hk}$>*MpNALpIOHV7IA`&2BMmx`jKo zr9<`sYPBi)-_h_zEx$KEs+I3};Ogd(FB|cjLO*q3c9gLR;}&&C?z6kj=#(0rmqKoP z0kAyQ&Fj^sDJrLJBFM^pnpYEDk6SGlw?Fv)d3m$TTM7Qh)^pDZWnjq`hY{Z4mGXzT zu0KN6P2l|vtu6tDJVO)}?bymBoE0UlX_^T#T!C(U;-ZaikVm{3+!hz(o+Q`M7;j$M zh09;G)6ygIo${b^rUa|zi@w<4=Lcs0I;3PiGPQ}SeUZV9Y&DDhfpzP}IasB7Ahz3| zd+?uD(UjPJVq6-yc-rqFU~=OA*LyNacc=eMj_m+O|4aOSvghyT2Rr(qnwxfJl&j0! zPSIaxT+q~{WB&<dN5d4nvAH`Q)if{_^91tNTL{Z#;SO%NNfy44t@a)QD`LLltdEXZ zm@7i`un=9!z&VNFuUNR3!f!!z!l?M=kqFck3c+21|4bqLp%AzW3TY5!`~KU@Cr*hk zm=^3=XOLhGC9Sa>_WM0X5o_->I=hs{nBk#xnMomT83|&TGA8TfJAq<T^%n;}i9vT? zJoeHsh<on7@+|vLR{HDan}0h~J{O8y5I0n{>0teJwPmJy06na?`oW=$-Ms+$-<LHO z6>x=+pD`0wx{3L8GC+|p?ovpA00m6NXG|G`J%k1k=HOF|lN-+Ir2ME*_B%z^kAZM0 zgL{v__eUba0K^ze{#X~%Tl}&`EZxGAx458G&HgjSe%|S-GCV|X{H!=dt!fWPf6Nv< zd4zt<R*vbuJxx^u043|En4e<IM<KpnDBV4R{UgK=jHnEb5U@{Vur8_}#kksQ@@7n# z(5~gV9GUNHfcjFT%*=@N!3M<wh%*1Ws{KrBn$Ft+<c-ptokx1s;TFo}HmWOK>fe~J zhncE&(iM%k++LO(i|wepTe+92xygpSrK#F}R^#cA(sdWLRS2*uP-7UY_f_p#W~+%I z%7&4OPAPI30v$G!U=}H>V~BQPp{9k{xgh8ZK)N5mTG2_N?6GNq+B3Z^|4=gZLM5f} zt1-Gse;lbP-PIy^pAXEgT{3B}dubJSiFVCBt~_FjgzahkL~fM+Vyrgfv1KOmtJ#IG zRu{@-yYQVt{NydE?+h7I#@O;gYd6HMVT*xlZwZ2@^oJ$;lDYJ`OMObHRz9U7zNyr_ z1~F;qx^2KF%mFwDfkNM|+ir6jQPVeD-E>;0%JEs$CWvyVjPhHma@MfQ=!GNq>645A zm9#M0GH$Cs=@Q&#+4#%Ge*o?+3uD8c=`8zh-=&cKT=@xA#i<74%}l+aAE6Pw8SZb| z0B>H#G-IWzIrY`<Jmr^6%FI^sICyD{g!{y%T)Sn{?oRqs2JYYD$zxvjymq6TxxU3~ z*CJ4vV9L&m<=mZ>R;UUAUHYE-eZ3HVOttztf7cK~&}bm7r+bULRGK8_$LiG5uC;m& z?z%S8dT6k9f8MS==}Xqfxpw`yU7xt6H|UX%J6KVKTn1v8g|}maqbywC8jVyy{qKI4 z$~04<nWfyxRvBLZD!S2UpdH5L+aGwjV2~<Tj=Q|FX|}sYkM!aK!Z1(0v#noMSSFYF z+<R66sTmen+|}Bfnc328*UeO}en@}|ZmzNkf4k&X1m_Fk?+R)^#EdR^Glf$;bQG;y zRECf3lCfvXT2o0ozVFqclE#Rn(VV?|zI#czIM}mgYXu4g0&)RWUfbw_cHiyky?3Uc z5BCN+JQd^0sOp7u#}^F634vO3mr^V>_@#|C0p9V)Wb>-yp_=?d*G^gVH9LuKs?;}Z z*xxTJElGbVq20$Hdi_q>zLqRcC8g1o|IyVxGu5M*>dQja+BJd7eH%5sXJK>n+n$5B z9iDewfspkg8Lk47zL9)_VCbdGP#See<t6iAnBo}DbQ8T>^GUA~7H7ZizhcY&W62@d za(y~#bB<~M0tp68^89+q$(P@KY{F20$M<_T*Z5>k`8Vu4c6xmg<K3f#7X7Dt8R1n* zb@b`CG{xR@lg^JpZ#G=)rMlNVl==LW@vkd!g?S`IqV|odxX31*V=|Bh53WG=4?vXX zyVMq`C%&*xEOniDF0YWyCXYpi+HU!#4Iz=KBw0F<##C@%DropA#It4e1QCQT{1YJ_ z4pEq-%e63ao(Tye0Po$UFoz}=&k`&Iav3pdqiYP*C`I+9L~$M1Y<NRs<)c3Jc1Sws z*inVpx_m<~yFX@h9Ewgx<SGwC&K^>*?A#by$Cf2`;WfI33<um7n8#1D<)?(|j4pLO zFZm}F!V_BLSK2!D@a!-4*<W<^mX;Ga5LI}_kl!hiR*yot&AF`y!X|X|>TjuAryqSm zKl4IfeRCJVr%UcL1@D$&yu5EJL!wYSs5mA>C%jX9CM5UG8Qpt!S`Ow>DyJ*V<LIwA zUzVo#WvS-TaoIn@?=w}p7ulIG_va?cX<agKrn~taTDgt(#<cQLh!UULWzF3Cn*pu@ zDM%*BLKoT#NcQW%$v6@~>6&EAx32wETVx*ZIIaGpOFgepeLqA|n@#k-^T0}DLtXBA zV>$5vUEPN{f|n@%qbre4D8_YRl9;F`G&PpJ+7q^<N!Ft|hO4kE_GZmGDp}b+SVkz6 zS?!WA=Cg7(&_o+tqpKB3SXr;aI2|hZ2OzAL?fpBb{+FnHgH0Wis5W=CtP0c%;d%7& zfeDDVf9}y=r?P)!=l^t9Eruvryim)Pq~7^S)PpFA1c?)mw0;_%P&dbQN|6l(a%I=0 zLOhg|`by&WpOUr=4e0Hg<U4o~fYEA+(pW<2xEb^Yc~5%%>NV!`u)Tx~BH~msE=*P% zqH4LHs3Is`px~YmNh@oySET4f6861W{ywP&@^Hn4Ou4)@Nw^rI)O<i;>ZNLdMAc_Z zN!Lm4ei?=bAr@U%*X)uVFOy#pEB4JT$kwhlTZS4;wTax+zOgXXOx5@Zl{8dkj{o&% zp>t6&cMi$k5e+rlTvLg;ZMOF5K@<CfTj5Z!w?i1Y%YjNFK?sA9B*dvY^ZbYRr>35n zDMnBgMbvY9rM16HqzlA~G<i7@TWw5?7!~5Z>58{>N)8qOL*O^G<CIsa)Mwgu|9IP9 zv~Rz`z1|M_^>XgmkaqJJCo`r>HNw>1x7oBU^R=*ONLxabrGs7;BnPUzn5zELOfgMB zAF5OPA(0lZ31tl+a)x^yQ)u{Zy`tIGgA46}va`OS>^+|CDnA_WC{*#^NAw@EHTxZi z@A$kO*`c&O{ee4~^hXHdnX<E&PVA<tSN12?v#^G2x#H{UV+_=oP{GDHSRuUSz**B_ z`X>^{L?ya!F0MoM*!E|0M{GWA=wJ%91q7Oe)U2QwY@+JUM2N(S#@E#IzB#v04OwYL z1IhtFifWh*$wy0hjCq0NC5%R1pSn)}8Ix19f1P3}w{k}{R)ARq$ca?dDXMIY&{5B! zZ+0w8+2^2-ze+2_^BXIwEX&6u;cR=CN<U<G9Yo0(BJU$n^8BP&0N@K2!tEp6|LL9b zU$f-~svO09h?rtx6Guw=^{Vp{&K9)YC{EJL={kEypzck@WKhSS3FJ#@RKUMz_`<+= z^5ZIJ@>>9Ck|=v_8&XA?KM`E`BvH$tDE4Y&<GXs^Nsuu#13mtxxz#FB!tf@k{z{^O zro?+w@F^M9b1PN-;IXwQ4A~=8uyjHFEr6J0)rnTUHC6W>snFpbQyLaewn&T)UK%}m zEcS7iaubtqk*c`LK)X@Lc}x_Kr8v!0%9Khv;_Lg~u$}Z_X!o-l{BvhLdml}7sf7s? zu@I!8zUn9qDWq6;LrOCE<3?I#eUd}74EJ71-t5ZjYn>|f5S1UG!Wa{uu_o-<#>T-f ztMUjc!`5%MRC$VVM|i<mVROAd?*+Dg8m~|V433k_*dT*Oknir*DioitDzV$3wjRUx zJvW7{(W&lN-3(DYQYITGAm*7IRejDjzjC0m2!DkA_kFN<-~Hoh2I{M9`9!94{W=hv zM&MDDrl~I*rAGqax?pNd!R~$2wGn-q?^AaiMfmr%Q`N&HvXw$a5gRv9s@e(>zIp!f z4)-Vxt}@J?d{EP1^6!(a_WXmcq%taDstl1Si=Bd;44u@!w0+?O*HA4PpOEwpOzZl( zBeZ@&byc#EbR9R#!sW((+I!a%e)LO^;l*~Uni-SdD#;M3Esw7SO1O{I!kN<Rz~<cL zSG$)#o1Xu=_HOi}?TbO<zP&pG+Hag*?NW^)u0JHUP@>X6z0Ta}jQ^nbO_uHc-_Nfz zyWi4PeI(NRAxb<NA?rm@`hWH@(DA<=AFIy$`n*#G#DXt?D%Qf!E_YiO>9@1y?n-H$ zKcNAv(7u7AN1=L$06;E6Ed7j1hTkiGDQT{m{QDP1=}mq9!}V?R*5#&<4ZHEI)(8pU zQ0j22{9!tIYv^SEt%^q%D7I-Tj!l)1FY4~y|L2EmnMp`bMgqNNK2`gSq#4ca-&#I! zm6n82b!x61xeC<^eZ8K*Y>t#ZqjuTpPW_8(-nYwT9o!}d*J938|M82p&+9z#CU%uu zd*}M=yAkg+<bGyOTAqmsy>tARsAlp33nr~r`b_z5{MGw;eu%zQ>#+IO?^-TxO*4a9 z4|87g?#i=H#8B%Wy0kZce6D@aDZQ$2yg}x|_zBn}dD@B5*62@WdX0y-x#muM&ui~! zU3wRFunGSD)1Yd6OpNY^6xXjOrpIm{f8c%Nva!|Dv(O-i#ExHIXXzM|yIH?3Zy725 zE86>1sV#D5z%iik{)6)azfz;KjE{}=?Xv|IfBwh8hThGxd<J|~GZ~&0BewmxY^%n> z#m+MKLC<Zas9rtMDoN3;jyq_1#5Ed;8`gv+DSu?_#am$XYNyt+tkXshTe>B`8j48# z9z2~xfr3<R6LE9~KGgam-rV>5Db-wWjmIL-<xW9{^<+%+QO|<~Awf<CZE&pK#xeh= z89jE0tP|TWhv;0G2zXv){5<bAXnEl6#@RA5)7FjK6BdcxVL00*y-h3%3e4f|kAG_c zOmBRu`25f9;j31M^yV%vICu>^1LACKMSNVho8>zb*}2+gztecLiGJH%xa}EDZkO*M zj#uw#5P@l+j`vcnMYD(A{O$ITq)h7|6#&rahRhi>PgbMcZbjD8SV|R@(QdcdvDY>S z-hCg>lLBOO7aBgjOn<vU_HvICD9K94R(=@MZw&n4@VaUZwuE`~N{GGsfo(U*k_I4Q z*~_7}Qzi|OJ|ALw#yb$Srb{i#mr7ro0W>H8A9aD-JqYdHIBZc-6t;Dr)ShiT7?MBf z*=~+hB@dA36rx47C>w(YN+Gyyr(PI*8>P({T##8@&Di+Dhp>I5=Yy9&mUO}eYoEDw zaDe$L>_Xnxoo*mQsJZZD^2eKS;=QOramGCa8g8BAX7!$RQT<+=PFBu~V<rG=!@^`r z>r@^rxoJR+A@gzTz6R<IneSt*->38UhJRN^*{TgsRNeh|@vQ;O9S3;EeFkQm0$pl8 zb^fR4X6^6I5N_yR3jgCi1^{kWcdkYNs(&>fEUYc1o%X@AyRUUxeV@F<-693ROS6dQ zWy&14e|+K?|I_z(^%Jrtb_)Ucukqwg$4T<nhiDz$GBhxcN}<J^-r3o95=+fKYKHO_ zB0{HC-a0&zcLM<F7!5U2Q3mYw`w~|XHL=%u5V6~Wn4o%Hd375Eji;f`7#PqSHV7UM zjNr}yI_wJ;gWm$iwm;eUMa9Sx0#O3dKtP4Q_4Faj>Rm`jadx8PWZ8h`RAv;m0s*)~ zfLVkR!hR&cY{Guq@)QIHhz-8~_JgUv&y0<*kvd)`-mscOH+_p${=`q&t5$7HoVdlF z2!6EL%N<_rXvc#6dDmAkk`aRHaklT>d(bSlwtv8t2)qOUV+SE3&XuDPP+!@{0pUO= z0IbaMbfvxVJF~?&m*16U`$LR%^KuK66A-`^8a-}fmD7>lz`JldYD;Gq!5Y;5xp^Z| zah6tOel}_SGMdA%`5L~mEHti{NGtqdD~mg-EgltV?RJ@l0<|<LZJOJ~b;He7uHUvV zLBknh=aXN(4k&6aV}M%YtNAiqsw@>{4=_}LbNdxq3Pn7tZ##F19I)z6BWVSFC~^pL z$EE=fXDK*9{RNi_006*13V;DP_&z9rS_2>`6^F*Mt|XL<o=<<HpeF^~;8f~hB;cg| zzapyHjUlNN`aEu`8oXraKTzs;yLzYuvt?>>+yer?@_$8iA~FeyB&dPD1I=~MYuqcG zaP>06lscDvCc=0_*sGfistrx4rD6Pb@Ja2mRLX+zn%k)?z$p91>%z)``p!XxYX_R# zbVlu1H2RDCe3_c<4P*_Ua;|h@++<wUhMj?T_rF!igC5voxQ`(q+t|Q|Yxg>vLWT6h zjd>NrfdE5P!dBh!&wZ%l?w2&RZXP*M)1eOr9nzepmzE!U3f1~^<^Guk+NZ6G&dF!D z&F#YiCXd(1sJHJZS_o%RHGVJg_fI21$wLET2mK>FNrf0!{K%GG-K8TALNuN#Ajvg6 zawozfDbG=`%S;hPZlk$`MGope5Yb6B2j!8$DI!gPCb`PftwsrhsfrBmgB=hNJskDI zQ$)c)#dgjY(E%Ie;J!<b?B2<J>myiVn*IIsSiHURdiIY;yaOc)99v(kSH34eQ&gqf z2ZVs~fes<shn67}KgVrgbCA~ogEo<z`J4lYSU1B7XeB=M8rm@nqkcs>l$|o-)~1+z z6+qO-CL`F{y8E}lA63!lrExOHi!XoNXsc5GqE7m9Y)l=^bpGeZ`i6GL=THDxLs!}) z-`@zLX61_A(Gj5RyXyuX1)6}9p&lZ4yRjzHhob42lHrVMMgl5hyF@;KHy}K2cX@wy z3`$dc!W9`eHrEEPvXo1d+L$doG;cHQN5|Jz(mJ7$>7Vca$%S7j?VUT6o%G|4Wh0%1 z8tp>589H63#l^Z`aeS;{C$K3-nbhULwZdLpK`{*@53fQ`O|<^4#^xPc;k<~lBh_vL zrDV$*mWM2kkNRIB8!{FSLsKm_#F=#G>j0E>)i+X=l^x?7k!(R~0pDqF1Y|ZG67|B2 zC`<dWLaml=@xj4wFU5ajXiUqy3qL$by?=j9#`Kts`@2S8H?(tdUgO=#Ao_2La^B~A zBA?zigE$gqVsGvLjHHv;oI$d68J~t<_l<Z{diwLP4`pXlzU}kh6JvrZR8DN|)7PTB zdRi&d{MBabFyCYb>l>)xTdPpH>9GKLbwA<=`sAOb{#P+A^mDe>7LL|B|9-YSKCm+% zp#)_AMZ7%y<s9#@?<niK$-%oXS28jQG?=IPx2avz=Dqi!#rc2!{$2TS^ZfT8pGs(l z-z&MazHDwu*r;iY(#(L??IsQ_d|`tbWpEvbF3h3D^%QOy!o0r=AHSGH!3t2j9l8Z} zVy=#X0CS+fTfTiU*)T(ZJ%%dKA6evCJQ3jcZdeCR`lrya<>1;E4FX%12rPjPBuGTB zcFP8}rC=nfN|&Iw!zj%?!B4J8cb67aoOU#CH|eJCLtSHH>OPfsvPjYelf=kOrx<_5 z4t{S^hEckYwZHP?);^8T#0x>|aqXetzKyFnS*JCpWnM@2QmvMAvgZfQw9zcbaDR=0 zhH1?Q#4M+%rrhGr0PWq5j-F{vd9~J6dNO_k?(I$ajV?3#4<M|Fu%v>Pyg=;@j|Y#e zE?*L2s|`~epZF<#E$nxxHoo-OMJcGfNHia4(Y=H_B(G8Y`;(^4fT$<g#8$1jx7xzr zJ1Zh<Yur59!RomO7zuLi;DV=?AKGkBG$dWQa=V-Mt!OPfypsr2kWosr0myAAJLzCl zl4=?IDX%3v3%~Cm1Z6zJaftyCiaZ^RClYwVq=fX_HUsWZl_vlLaImvGFz~EkN3zro z5an`A={d(hL&Ghi`(_XTpxeIH&~S4u|2)8Q{PaPmXKZ|FEQj|8K)^@3l=bN7q?Nt3 z-uVp6`pE1zfAp@^=Iq`eWy9A3A%JT#B#;3Dh!reg>fM8Ki+};bvN{AiSD}C<wPB39 zMP2F|<NI!e&L+EkNpD=_z3o7v59=(z%BQct(gV2+%H~!BAf9y~El#j*`r8E9IZud+ zW1DL>Z3;bbZQ^D1k2?*?*N^)<zaC$k*x%B6{Y3c5!HHh&+vJ<N2>O01=-sa&hmc}z zM;K%O!=q#YkfV?gpF{;1s56E(`ySe5Zy{^qfZBQ*_jlS7Mza-8|3Vu*dqi^M)x8DR zEeR0ek=5b5_gC)SOq?0~@8=Km`~Pr;EM(Y!Yx3SgWb9_+S7?^+dJlRQplwG%M`8_^ zRWPy6JJaHDfUGUK+xrGhJi-LR{FDG8kA|I)got23yah_$>y(se+J-W*3kEE*>`bq~ zdSH;K?GqjZs?2!*F8TiKiw2Sn`s0sXgO+o1TxN8f6$kdVMCDg>&KN`=9Ax}!D!k_s zWT38Cu864CHp{u?I@-N9bOOQB#5BEUCnTwaY?dzh88&79V4RYu*3X3iXpU@!B7CV^ zS6rmBb%lOKYFt<Mt4qkIkCcZy8osg8j4~WRE;gtY4q&&1x|Ud-e<{~b*mF)^o*@eu ztkc8%U9%H`GUXY=epkg4;8yY|Hc-PM3bKgWulzcCxe#H|E*bVu3RD`<)o6Zbl^IG1 zP?{0h+lWgPlJdH+LBJi2+;nMRntdM-wcLJ{xiySiF+Pt^Pm}V?jH#Ca=0)1{ZjU3Z z*b>=(iWF5g3T*<HOnzARP`(>l+<(1Y!Z`Td!WhR&J^Y6<T~?uCP0!#my0DqE+CV)6 zWt*oorMtH0mywJ|7!Xr3(xv^4&KNn7|N75+TLZ+#Vvh`uZz7p1ady$fDELnDRI#Z7 z-!gLeTXl!1wA&X^PQ<Z-4BlaB9FD>t0IsR4^WKfnF?KR8m~cR~42a{Xauz~3Dv~1q z3mudGaV5v=ou;8iZI_SNeQEps_Y0}v%s7sN^mCaaW?JyA<|LURX|T7f3!T$n&5tS; zLYyiKPtv`p7s6creJ$Igc7<T`-CV_nVt&ff$bsk%Q2Z&AsC)Crwpcs%yu#**+9+@V zDh}bL0L$5JTHyA3N?HBbhcf$T5ZcwCZ?CsMQE)KM+Vgkrzl;J$mt#4Tw=*~>bNNLr z`?VX?lYf^>jyiq*Lq9X(0@f2M6@9ip`19drdB(#E^(!YW|NeY>e&ct#%rXs=2VmZ$ zM8HPQ{k_D(Sg4-g2lg#W0};p%+DD|l+4A0s`%JO(ULaAPJ)#2+nYk)ha5Q!0&P2om zEY^c;y#9)GPZ@i&H~5-@Kd_Hu7MJAG<qilr)?*xN3v6u}0bt-{>=P{FxDF_pe0Q)1 zV57S@fS5ZNv1caxxMN(h_bll;1$-dpdZ2(R8u+o%r`8bEC`=A6<jF+tfqU?fL>>yl zj;Q6uc&Ct=*wc&2wvUpL5Vn3T8!F*Zf>XHOe5sLhr`<6R7Flo)jQd(ESQ8PgsS(2S zPDL-pIqjBVS%9@*l30pZ-zard7u??;!O4y<C`?0+;7*&#d~C$d34IDczPu+GjRJ13 zNZ+;q&(x;f*NrvR1<&0j4K}h*2{~B~Z1_m>5esY^KOGR`nX`!xyfcSmc^{>KM<5R7 zfuBwRUvN_sUS%Sf+{0shm<OgNA`3Q>ER~bq=8gGjn0`ix{$!Z+vhYH+Jbqeq0lDON zxzU5hi<B_%?-z0ZH1U5Nz%d$b;ec~hFsQD@ueg)qF`EU2q_p>^u=|lt?{TZ-+<bZb z2LM+t1PMsaRZWm`5L{xhP)69nS3cnmIgGoUtTi&fAR--L<bY(9hGJgoDc)N#&OaIa zVhDD{ftTIEya>z@hnxj+vQiu}yb$ksChLhs+O}WPo@l_vn^!3EusK-3(83cRgIlzj z&W_;mkMS@j){xAXmhfg9IWDyz*qV-FV@ieSAjQI+$(gc}Gk^%)y9=CLEI{R~?@|=T z{Yw6f3W45Y11yX$8d#5^4_TxS=oXftBl#_uv$M$vsvjVff{*wplas7da}-0+f&E1Z zZI=L`5CBory9)*5CH>QxDqV$8wqI``LB0qq_Xgd_ym>C(GaD?d<5w+ae6+w;xua`A zX($^Fjdc7sTOvm9*IKg&7ipJzvax}|gl!)Svo?bFR=7tT5YfTK&+BraU6-In$Ol5? zJqq|YHL^nC3N&pWHXqwb@%u~x=jw<L#Qdr<K5QgEtu-BNO<~5B0ulJ^M<s+v-c-MU z`&jT|E1Dxj!Q#s|3z7yN<|w2R-)LVx!7r*H3*aM|H8gMwxCn^CrW}Y_yA#&|mH(kR z)~lJ`QfR&8^5s{N4;p=P3d^<@=MW*jekdMOS5S)11aIL#=M~6}T-dG$&PO=6Xo4ST z_~#~-v>B9BC_5((Q{#?lXB1;31mp;NHn?acq@<l+3<xhHJ<uuHc?%*(Or0wwtu}2n zZfZ@GmShGd0;sr4f=?n`#iLq#jBPqA?L=|fh#2d72CQ-C<-`>MWf)Hk4=Ny7qk+ek zpgRM^)z@301u%9EAd+6EmYS!5p4@`JwbdApWYn)cECkTa0ROARL6q!@Xc|wI&=)D! za{%<F6x3xW;=?hYhhyh%I)HSg_+b&#@fYJ}3fBE`vJIJCpPk~qPM>QBTjG&t3af6T zQjUJS3Pi-~dZRm7oOfg3P7LRh5cj49{TKrbh&S|4U?10GOAJ9tnr&Xu^$l$N(`@`K z13R0I?*r3cykd^9u&PL$n{Fm?<q8l%z>n0QoMq!ju5II$utKqK)?U_LxK!I+>)I8( z0pkoxr-$$O-T3WPbz$hOuX*^hW7l84LVqj6dpUtM;+mfnK4F3wqepDr2wJyb2U$qx zu?B)s1cq2oi3KY_!g^Y}h?WW)iBgur<e|{1Db4su{M$nr%IVjd6fln{;Q8Yq_TgRl zx>@)d;bt+|nB590@e(akhD?zShTzQupz-e-n1n&<;z5lNP_~zZidOUo>7Q=H=}G2! zD97S;s5B~-fl3p$^9?)RRJO-{0)IB&RV%?eNdv_F85>*hJ+0yI+Q4$5yMTiEY6uQ9 zKyJw$j|uRL)wSCLsnx4Bg~H3Mc<}WgDEtWCUhCGuP|-W?fIVkBj5P`GBkrFr<S3VL zRE}fMzKZC63=V^>(o5(%$9iTQq24gX;1l@vP6jTtXykXz;dG+m<3w0aBjy%5TDv_L z=!$LuPo&=OkHIUK;O81Ulz!iuANA?Xj>4mflVhF3(!e$Mw*2(020iZP^em`H_`t?0 z<vK7R`%XYA*g7sfVMz=X?S&e(M{2ig^Sbc+lKK{}Lr1QEQBI!_;pR)2OegG!dnchQ z6S^*y$?k;aAOj7tdaKfr@%6PpP1a#BRT@~bs)(}4KU(XrYJ}YB(vE|)$AGt>#I6Lt z-dF=rA*1)<Xh;6X>kS(pyr~T@UenHc0SCrK=$SUq+Xr0f@IyGX4aP|WV5+rZPs>=+ z$JWb*9d|xwBd<56OdgbqN&wOGpb-LySsXBGK{99{@p!LH0$5#=s-f5a;M@Jky5`Pn zY-Q^QOY)C#k=;*}TXj1%`o-9G!^g?e#M-tS3$sa8hDg@LJ!n@J{MG<Ul7n3ufC-Sd z{unsy8*H&Yc4B|mC%I;s4}<-q=SpTfwxQCKCwni{huDR1rHS>3NbFY-o3DbET8dXi z)%<kF+y!|zMBtkKwHM0lTH#RPVWL{}qZxhB$bR^&bvseIYj;=+bR>Q`!9^L{^s^JI z?D7;2!M_)WNh-^w*E}8%5L>$%I{^^_GlHo)R1b(TO*HAljfA_igv*^x`5(*la}ZIY zlhSl#I57AgJGeg+lrd<JPXNc{`*l=Z;*~GW32)ux<9o_*M+QRwb%Ng_u*VHSt06=H z3)K0=m~F%~v#`ab$YzFg$-Ic*3*Lw*P2=ax!%H-bP!)$k<)M)otUsajg@&ryCpp6L zbDJ|5<wq|oIU9h)_qXB(@Sl!{{q;@;XwKTcEi7pf90x>ZgTvXFUXU3VicHJ|Pb7dp z#oXGDDR84Uq+|$;G)mi!y6Hao#siECdvUf5sg?;IzBfMP^-^X1fJol}z~=^C0zYY& z&b5QDa9voRQt+z?@koq)%z6tGJcCB&3NImVurO;K1gRydP1ayTd(wsRtlBauwI#&8 zrX$7flQ-S(kNh2j3J^PHhEcc1fb5q+7Os0$w2~3PRd3V@oi~B>8sYJ$W<<B-JeNy( z6UeU25ko?`7;A+C5Zgh^%a|Jn9@iOOd3PC%@Wv2)`<7>$T)m5wnCSC1;5i!D=Q~|Y zLEfGc0})cQRM44*3<WgH28qmg?HpmXkEBg0F;!1{5^5CFW){C`BlwhsK7}Q%R<{K& zVu3~Mg5mqA%7;VqNNZPc6CU_@4!a`8qJFyQlwu#zq+81#!z7q0F(GyB_YM64E_ISU z&&SrY&>QAKrtoqSa3o5Ej95&C-IzY?JLuF1$47e|O><65%lyxMCa4J$TZXw7;c5a$ zH4caW=Z;?h&!!Zv-!vpXpGXCbcI21qBS7a`JaN;Fhj1fl)6L*8i}1k}Y-Whge8xYD zz@9NYSEE-|$HI^&-VNsSeS(E9t@o~nfrrF7aoHa$+@|xcPj973#Tafnu;~jRMjR^} z#t5VWLU5C!H{64`w-L?9NXQ8DPnv?6-${za=fXbGb}uyIVId&*%C$?<q&|1MTaP|v zj}D^g*ule(H}8-}(4~#C7Nl}M3@^qHgG}1cbM3X6)2aB{wW5@%2C37O;qz_DouYd) zH;5;Ndr^4*n}6WDO<$m>`&)vJOL?Tt7zRjnxv!fv>Jqh|AGn*`xTu*^`NBUcfHDk= zM91F^pD3tn?&bXj-TM}Mj=d#@T@i?;TM*2t4{x4GMSftVOFv>^&!-b6bTJ=sK*HMc zGbGT=k`mUG^+a6iS-dgN$0V>Y>>1*@#?MfXX&77WK!mtaWd_Rh&0U<Noh=ML;5aQ# zfO>R8CDM;6E8olBT<2WZrmJVOzK07?qMvek!a4;$Gvc%RFz}W@#SGv0dG6+i^JgC< z?7{vJV+S5!c7d3yVtoE@X>Li%b>ZcLMlQgDd#*JO6#oVj#NY39>Dpca&$GOo+(0Aw z-gwa%JQ6`FUq6Is?jlAN3H$*7%2~TVV{ZTmO-$oR;neI3-6b|WoT|LtH+PLL2l(wV zqBnoUE=zU0MrZejcl{}e;1Odx&l#tJO}_WJihH%YjzEvc%IbW6eK+|{&_B46*Q`6& zTJeaqw&BOFgJ1D!&<K~1Cja4FNQBNliqY9#pfNSt@siN`bK<zn$|qT1V~v4F{CZxF zW&*9!R1N}VYLXHRUO*NVXiDsJ;{K2R?$Ur2^gryRi93l5gkt8#VYCa??4k`@dvyr3 z&Ui7fsHu}R8~Spm+#TNE#Z&Vsd24XX^2>*Retx+vx&#Iu&l@O3oog|{44a&MKa{HW zVKyvNc*Yg-BtFeqpT+nLc&q9TT-h4%W0nieM;2`hK<s$~aj%lo_Db|%La~(dTKA=X z4litJY=_q;5pobtF8CybA|GR^6s^0JJzKWH*bz})aWQEEM!R@my;G?i<+*prQf7~x z(XN--t?pHhUR)#lm)+=;+7o@2HKg2L^oJ5siUv{;-<fmEL9yebwi;00R!!Xs_j}jQ zF14C14Dcj6bg)YmXUTq(srHnhm?bBH^XIZJn^y5qn=(ME_!<R<mhI0qL@5V@mW#Si zWC?5FESB9zcEAl|LL1h0vCV#kjkwO%1}bsHR6YnyEG_NcV6GY}#nDdX@AcSI4hM|A zLj%0_9oQFKLWzDISQ+;Oa--B-CVm$gI8s-o$j-|dr3BV`AXrLBs~R;QcxcMLW2c_m zI|9ogD7~ac{osw9Fmxa#p&rVT-<&FGD!T@FO98<sjU<v6Kzo?Ge_21+sO`^&VBrJc zHarui{u^e*k%d!?XsB?9B0uTSJc{Et$10a36G0F~>FUF=4SUpXnfoWdXD#K@mMOL1 zg+2C`fk1)ewo3FAQ;HQ8@gl!0<dAiRGyp&Mtd(moiwe$9(XJz>G+R|4p2J5ug>Y|J zAubt8%~h^Va)Lb+RF7<iPzX7OA<1RTS-IM@q$!ozo3IZCvuP=baZ^TpSkijP@-?OQ zy^k~}EBJv_y+fH?cAOEhTq;CHF~g;|CtK@13!eKx=h2w%%VNvkiV}d*<i~EYboj!? z-*G9EDDBWqXP1xL64+T)*0J1yB1Kl|u;jhKKUQ6LV;Fkkocyt%ar{cO@>D#<X}Pt+ zi@kz6TxQ`!3^r;)rbXX?Kp2M&KSQ$LVHAN@n^f~zAVy$I$mQa<k2aRO>(%P^XL8M! z>|+0JeA?^9Sp|FTW1`V?YrpfzJmU5^{|xUOO<YHued_Y*YzBmq*iNz^LX^`1gWYQ; zu)1U}q8tY=5XII*vTUZZ^ZYG#9ey$LlJ4gKdcZfxHdE|%`^sqC2*=~_q8^pcTfzI& z5JRT73mMaW>F|rxqyI>$S~ozRxh4YeicseLqosU3af^}$1&|8+q(|@2)k8r6-Pl{& znLW%s8MEIB)0AdM&N9oO^@afyON$>K<{W@!xhgNKaV9_!HZFCQyo?D<aG=})d0PPB zvEk-QM_3VJ+Z==yQ)(ZasHv10m3uM5!I?Vj;AGfLO8akDiW5}uL?3NznugNc@>8S# zQ2lODv-R;Mc+o|6dE7m=ka+;B)GtSYvy^);Q0_1aHD4kD$Alo6O>4_95IVo8xOQUR ze_r{L`Pvdont&vL9<w@cb0HY4P)(9`lG!<B%m!@~{WSZ#F-_*|#c0YP31vP^y&a2< zQJJ%*RLMT;Rt!qFx-QFqj`g%o5>@E6DSx258DULEXX5uUpc{X1z&ld!X@C%RMO@~P zv_4!kYK73}f4TsM7-~8H*(^!JK2Bq_W~VQghPurc{vEA_6OooK<JrgKW>mII4N!M- zQXjfksF*$zX`XJUha20eLhE=7@TrO-xev999b}w>jfVj>K>oTl?@NIucn!iziGKL0 zpqP$@Y4@smKDjVH%mZQH(+N(!ux?qK2Yr(?^m>zOjV_FHWv~Ac4O=7`gj(J0{JuA1 zlstQI*R^5ViU5-s%-vvYb!g{Y0A*)9(y{s$zP9gu_Ptg|*=$oKKo?dF7bNYF(!ieo z97<&dE<m;%tU3d)XgeCBZ_}Kt${#Sk31nC8)if(jn&ik?Jv;CSUVd0ZskgDvn?vgs z)+hoL>;+Y9f&vtwUrNn{kMxk8kSwE7oK1U_CLOABA-vMG4Y`A2^*F)}o|LO1(S4-Z zD9M?@SE}1klkFlpn!H75;KE|*?zFSum}y+pxNQHnruw{Avlyqb`eB>7v^OtY>nOL* z5!ImUbk?$}_*1$f8<82<g0sUjy`i|oHCndTQ8vb}Q5}1QCZ+Gr#xJXOC+jBFvK_pH zM{i8i-iGX#xzwhW5aZ^K^h3oIj}PhP>H+Z{*!{t5*?Zo7*`E~Nvn_I4rKsVX#3QL* zq6*b#fY9p5_n^G|H~}<uGu^MVnQf=!gGXQ7T4;iyDNQTfg=^b}2crMh9=HWKblcP? z>`G=qGCv<z<zbti7$V~uGWt&4IOY4k$P|2fYvokqCCGfS_~39t+E!qUt#2Cooboxi zM}OMmweN*FKY^SB4A+!bs#IxpQLX>5f{pX1sr-&{1WO+pot>!4?F7WmT5pF^bX9)! zA9U%KOBBP|qMHfL)!i=WDbF?b3IhcMcNd^FsE$6U49GBr9ye7IdSG%&;b)0?Xi7Hr zcBR7UBd8sO<+Kn{laQ=)sIB;u&pdp?GblTF_Yp_u`GUIh&enXAa(C+db!APcW4C`d z@~GC6yhI=(i6oXzTG<s#S^8A){DmR!cj&2B&7)V%94a^Fb->MGXEN0~cEmRAsZ{&V zBG|@kSdt3#1;ZYf+J*fU{8#WdphTrV?bbCXPNU@X&2{}XL_Cv}eKwS7#k&a|N$CtT zp?1fdw1L74FUqegy<E54hcJ?K<^|#V_uF83WiXD31ie2(TXj_U<?qYpT?zy4JJav@ zoeWNkja7H74adhqrq<s6yub631*Q%pwNz?b+4NsMy>Ba!-l_Jbaq<iEo1+@K5-Z5| z_UXEZsBuU4<;nNQRC=u(C^)N+%+aCGe_Jsh4@rX-t&bd+lQa!1(HW{&mH#Ni*w$T$ zavcjc8ER_LdXt~4U6?K1rae$>`uQ2pW6J8|VZMEK1<wI)Kf4`0D#UrE;+6SBbd=K+ z<?vSi3EF177ZH|p(QQ^<K58>3?%D#wvd|fo7K+k~M97{+?HIel5p8NNO4>or_UhoQ zZ(QnoL$w^bwaV0`&@{F?hiYLlY>PSuWtleGczg1{f8<TPMjPAGQ{3S_XNUm6vFwN2 z1aq<2o;9<Wp5#_EVO}cWkY+NGA41~CI|$58h!cv$<Dv_`5s1_x-OpvZpMbk>L-;)v zq(jSc2N!Rs+M$*>GA6Ci0;esy23IxhOjRS2G%LY=B~(pPgU%vkpugKa;_~lt1INa^ zTg64Bj_o@FP}}ri)_m?O?@fnX_y^!D-|1Z=Br}F`%h9cTgi;IJ5N0)-GO5_+*j;ny zY|1I}eMV(wL|p!!Inta3Vt!0jF=6wCLQ6fPovEno2Vg_OM`@EX4eingu3k3mIGc*w z>RQ1Zazwi}#bS^mJK()bJkek)$O!XB4ioi{|Kaaq!LfGz+*a;)NFUEm7qmmAx$xKP zA0kXQg`<M9p}<`Y6_dQp*p0|Dd|Ijs#^YJ)>;}H##k7Us&B|QMrQfLHPkc*3FIUKI z*R}ZtV=21ZXsx43OW8Ui_HP(Vi?ZvN21=)J;~`uACTCe!veX#>AL+d<&kNN==iY<? zyiq5>o$DsU=VJ$_m-7u9`*{|~EQ6F?{*P}5-~@upMI*e1j5H2Iw~nGl9#Jsqf6S)A z?u#sSz4%%zh*ktx4QC~#Lku0PAO@)73R6SM!~aMK=*2<a*cEg=&D`sDGT3o5pl3*B z6Jb(~V8@@@>Z(YsiU3p6&hXg$P4{AM@S<)dmsbTxVBQ9xvLjJzo?Aif2-FTRNlUjI zaj<*&%*OTMo|NQ4yQI^|+f=U+vO2!bTd+uBR1lgjx7yu)8P;zm^ECaibFy$S#o_64 z3|bD(YE|ZAUiWR5>EwyFmDP48)p9NlJY_rFVUyJbF;FeB`3KpDY<DX?Ft2EW+kP+) z>B@g6N@a(#mNoaJYGynQ*yG!g8jzRzebT)kVh<39pv}XR_4ps0idO^pX>Iz-he@BD zk|!oDv*OIZ8}pwyn<_K9AFU%-y^YNa)%)C``qoyXZMK@KsH5(rib7FRKM$PQWk0JA zILK{$ai^VP28<<_WNRAiBFY&Uy=asdOSb8rX{$J>um(_g3^BFDg--)bRZj6^Wcdaf z{BNG!BtAsP8~X3!9sTsHkD^4w8~FAf&)9~UL^jRv)aY*2P0dU04yyS`ILocI(rlq1 zLNnDlG}oQa>(G0IFXmg;O6Q1^gt91Y-6vnDC`E71k9Y&hP_KD#x4sPOpY$#^t#Ir5 zhC#Nr;UV>5O75<+mz6>aUI|7617DhVU-w4e3UbXE800Esrg=G~wG^)h86PjQ_Oe&@ z=ZY2llu-M8QCCew!(-O}4pl!X<G8J0Q_`_oa)>h`UaJ8=jPLo}#QDf5$5_`kWa!RL z2QzkN<`hdcL^nrf!MI9Ppqr!5Ww3dT``5Vrh=hHpm2c_$huYLMuj)5yaLPDqmC(c6 zQTkhr`-HY3R{S({PBUkmBlJ$v+V<En$&u_@yxs7{==d9NlgM>tH7OahdU-*ZYZs7~ zRF*PRZ+NpYWh|6*b1^m42X%kZn_DZbiGqnudah~l4fNEtgnK_E7+8+MEZ5Q0AgmUJ zczKW?CE^`|j9l5(Wu>dvZfX>0v8NN4wml3<vZ{6SKGaU)%VX{?MW=evJmS}BzO^Y4 zi|G4|Iv$we<%-(W_*|$9T0|&EofwA7t!o0an@zO=3-v=B?SX7AVZ4$U>FYo9dMw{} zpJaSIFe^GPrKIDUmnVjQ3bn>3O&)Vju94$o&gM&IpC;=zluoKmY1U0|(rzQ7JRPnk zi<;QA$QSEKY4O|7ciw!F`j2d>=?+7jIE*+Uee@D5E6QQp$IvR1bNr}_d0zb~9px$O zR9q@L<phOv{tW6yAWFLxy0k1k@D3)$?p#Nc`ak2+SF)e&k{wh+oe4(9M&#d$dPaiu ze47#DwbP3E`TD`cZ{Hc;<@mDYX1RsU^yZ`M>Z~%R;&e3XkM71SRn%rOYRacXqlfT7 z*OVjTW+`7LP`S5I7v(>uM2iq2BmEPyeB5S<?&dvy-dW^SIYwL(eK8s5pLIUY>-Iz| z`x)Y8=e6UEYvIRHYg0LCEkk<DGWlc*Qp2*qs&F#7QIbsA@<%kuKBER5m)agJrX?oR zc3cVKueXE{yDv`d3Yvbg@{A*%@&J166ZzXsP=2k5Uq0v)8!wu>p-|f#Q$%gh{TWG( z3KV_gn1^cH^-)_i;2C0s7B%-yMGmoQ`mouMc9)Xd#xXWI`54RBX9p_mq9RAsrN{J8 z&o=3mI<Q62hbu-z6&_5fO|q=@;kAxf)k*IV^mzKuaL`;^L%7YNFhC?#Q53}7f9yG2 z3TTxAYE#+*@quv-6L-*_d^zX+$CT)~9N_(d)D&&{h}MX_LUdZ82EWRo_mJ-1J=&<D zfK<za57s!dbR|^NISI^#1=Co8#oxMUTPW?qmjg>(*$yq?4tk`6AM(Rpf3S|7<mAu+ zu9)#L)i5P?mO!#9aF<Vx$}r+y$z2%B3NEWkyO$Tv7*!wVSp}h-G)vmo?`?FLr?jz3 zRnI^Ve8;ROXDs=;wg=$A!%CC#8$LGKJ2FMc!yxL+`^<4o?k2P2+_Id@WyC@=ek{2+ zL@Zzw-l{x-N&bib+&^@%I5k%TwW<I82g~eO<qQj|DTg6tV!;jc9`yC*`L-ZV_UE;} zpJ#MlJ8eOi8)<R;9L8C+^`C*c1*iBg^#rx;A-kZyzVkZnDD{Pc@&l8jEs&^m+?tXu zigNA9Ux&9&hKRETTTjdLk5S$~3;Jx9m+V}ANS0k@F5>PE|9q!f_0`nHH;GfFi>X=B zyjMFWBcd_nce(pC`0jB*^&Ytq;v<)I4g758vqEIPUrTDsR{nBOqpsXxeX5w=_8B19 zp3BPFItE9O7G;!jB<ZxcxsNt>s6qq2ayK%8&%?y~g$1PkBWKqa@ay|v{(9Me;KR6% zP2l~o&8~}bm+qVOr!cZ|%xkyFr$km7r_2QL8NvejD4yC~r6AM+_FQ-+X2wzq*u+2C zUVBBCHqW6!&k_0R{j*l0FW0s&aYV_T6sb@ZVw(TbmYWs<vngR>UJN37O^&WieiWHi zm@>8Gs;(@x-3Ph#!t6hn`6K1ewYFwcWYFg&+}}I+LzYtNTT!|@zS^4KIvrszlk+^8 zA{ma|v*MHb-^Znc6{I0!RG3$Q|9H%W73m9dTU2)NzZFY6>ly?6B7!xa3Dl10M%ksD zf*-E;{vg|W?z`;5pi<>6r!78e6Il{e%Ip<YtMk?m3}5Y&LuH4&s8!?t5hk5fLseM* z=OpI+s5%v~4Exab<HVk#!${Ulu48x%CjWNV84AMj;H40Kl+I>;w8eYNA;MGD)V(i= zX>c>3RqH5_QR&oia5@(5$z|ybp5KDP9nIf;G8}pU^@0JbBdhs-=vz~}q?K;Pm$k2t znhoUjUr5zPX+LdS8feoMwSC*b_Y+mw(n2^$t;Ro2H>blcQe?4f%6f%}&G-mIuhVYo z@6kswCvxJ{KjcQHm?V_t&P*&olZFnTcV;ibf)AhuPo?@Rpw8~ljB*gX^7_^Al)V1U zGaA2ogcb)m_9+1OwiABEjIg>eyUK1%xw8eu+>I)uBEOxAk2{>{xSel1m43Iu`TEb_ z$1Jn@jprVWzXl$e9X|5jrY?8W$4^Q86gBGc6d_Ep08McSyD3%Fc(f?cUFxV6@(PRA zyY_qJH2%Cf%v1ARh6Hwe%;NlR)cT1FGMp45SZCwT0T#$8#__eJ{<y;0lN<^(xpAEp zhNz35R*L*PdLZ!wW$TGT#6ZOF8FP{?k~Qkhmz34k>na=zrY`*45sz98M!nUR@J>@m zbN~Iy2cREZQJM~6Twyd9_4|<gxsP|x3k(}6<C;3z1#AQgfFel-!Hbk`E=IvPY<7{_ z%O~l0HUuwe*r!gZJ=+i@Qgq;ag{#3B=?oM0H^fWW;z9{6Qdzk`hW}XOBJU8Kms&3M zcsMD<Th6xCrR<h3v?n>~ab8GYt!Itr_0aEnFB=Zsjar!de*9&TKjsMR_z#1L=FnGW z)*lR?o5TyS!`t@Xy|Fd9cL3_JaZ#%`0<=WiC22E7Yg{J$y&XB3P;Ck1$<GIhl-t<G zf~JM}Ut4EI<-0F#KDSS%g|p~#JA7gFyKR-J)S%BSQRrj}*sz~SQ!0fF)Gk+8_RZ&a z;$Ihr%e$C1b@!oDv7_BH46=5#g@oD=Q51LrcmhEP70p(^&AqyP^2^&PMW7f6R@TWb zto^zA^XmihjjCPui2>`1%J0e9(RW-=J*Oqm@?fAPrK^|Z0YoIrdw2(fBp_nS*QV7P zMxy{@cSraBt!vdt-_*Y1XFJy5|JG6rtfL;`_nzZ2wy)|=oPicS&$d{~;3#j!X{C~Y z4T>g}(LTv^7>M3gE8-zG1*OvRExgC+Ytw}l;tPSrXSCPVd@qJ|aQ7;-OC#ML%3grx zZ`HKB1_3jS>p)Ev;0ZbS!bMpAu002rvQvm^c;+*2ywr#xD6{W94Tf_VWxD&p_8DcL zzGonl9tc;JVwrx(MqVtv-oC2Wu*vORfvxMqc>NnvA$$E?iPvRo9bk&OBJ0GV=V;*C zQdMoxR^Nw@s-Y0-8@ksKt86SXQ1PKFmLxk^TlK@U-qOGLlHZMw^&Oi#4oix%w*z6% zH{S~>*yg_N)Rq5Hbm#F<{C^z4XV+q_y)4$v?z->$mUh<?Idb3ibthK{DbiXJ<ydD3 zStLn0Qn`|29fhJKDstcCswm~>_wW2Mf6U`CGoP8y>-~J)9X9!jHp&oXS4uoX>IM@n zw0?xzSzY12(wFi=6zlWa%h2-6Ff2RChI|Hm03qf9b+nWh{~_(=^adba2%V#7EqCQX z)d7QDqnh`zmu}~$ttgOH3KD`;0uBYaRC^}*&d_;yc{8!2a-(=a-{Gq)Njn}&Q~;;R zS&J^ik0UTz?WyV$zIU%_eZCN5^2q3iyB()cgw6r%>~rXN#cA-_OLv{}N9$L-SalVx zD*zrVCdS;JFPzc_P;Y8zzNA!s&UK5^T`UNUt2I);L3mBP%sHQ`*aN%E_a7k4f$c$C z!hlM!Vx|a50GX5Y5k6%v2ehFg2tZDtp}}^K(DlQDyk{(cZh`9eSh7J#SCYEy4f17% zl;$WL_)Y6+GEyI;vZDq4_>HGg3*u-!`GiZzcl`q=j~14Syw(369o*@i(AxOgXmE*{ zsgc;`rSO(&@*i9y!za<ppQAHLx3rJfP(sQ`|H@e-S}1=fh!qfWPu7bI<G_H34&EQc zV0KkqybUUHVECy^!Wft@l!;=;=aX!;(T8C@n0w$36o)h=$r%cDFa1m=uu<KrSb`K| z2|VR8#@JisB5AO5x(&;8y%7@rmrnoPVX&4tB~VqjUSyQ*CR)nW)74^mn4PPP@@DwK z6}vWZ(X$#ih0Rnl;s#;b9r$cRwF)fDYn0Jmjsnm|5Zx|M7U8wM*_{sutXU=m*=e#p zARI#XVHPR$CS6abo`0Z;b*$P3N&Z)#`y|M+{hX}%(L)_osh6~50|0lcSwSL|wII`> zOj0$T@+j*gJ~^VyLvf`-IiQOt8T%xOZo5L`0rE%0&p#XrF6l|JnU&HJu;qxi?pFNP z?`I$3p9_M`8{Gg=C5O?>c<MzQ`VDEO;bWB?f3`I2!l+uFR>Aa*r=@I@Z<OB5q$Q}? z<7?3}lm><zzyuMBaY+X4EB7j66LKLlEUX}OQ^v$D?v6z~|7u;n<;P2S7omQ&@VzHV z?;9)8&1IHCzf-$`Il@wZQXPL*Mowe5@B;CH@ta(630OszVD)4VKMSxDs+R7Wl}e79 zX^l+u7M32Ab?(*^txx*Em%&1n1*UJ8s2ye9M3HbOLPzK!5#8ngxQ;93RoM-jxGUTV z&^fvXUeG6n4NWi=gwj67yPq#%1KoAuXyBU3eAa;Qz3Y2VCYxUrf&`}ok*ez3@{_&8 zO>>i!zRwU7zJ^=bU`|<XSr4!|>}2&rB!OyXVpn`kLB6SlIcI}&d|UUGZyx9UvLAh2 zSgb{zIQxj?6^3k;V+w3KXA#RfUtGaE$t_uz5&NOz8OCxl7)*Z!J#;G3bV<se?l<)H z&DVqXFWNU?({|561|RS90@ITHI7kEXeB>S6FpjMuIWxuII>Dua)qI+Gi*DvphtnNb z<o3g%znqgmt?jaDiw1q;%5GvFHN*P+K~%(OZx_!sj~*hC^K*@vw}`$SR08&1{$h@| z$igyP&?~RB&!7&{W9|#yqsu1U54GLwe4%y-TDlKTMOaHsHScN7g1YL$8`c9BK#LXr zw7~)AE48F}WiKP%qufcw=4RKR5xSFZRPJuZ;^QxrqXN}>@frf~5k4{|38dJf_q1<1 z>)(v|5>fs{Ht-rgT^JuZkk_tJY1z%w0qhPUKpR8?JNI`4bKnR4qAOEfwG%W(laO?` zs(Lzu3aLWsj}%+N$oy7HH%bfsY1SqD6<}p`d3;Z_|58i<?5VAI^rX%y1K6zZ9V**X z%f}MjW%TUn#i*CICyt<=!&`3dmjbS_JT&o>kzbE|+B)f|oB80cE*;ya-%#>g>jIE1 zAe3}a`$bPm0}(!Brq~(9I`iNG+s?Oyit$PJOk-mar7-SSKEjVJO)<=^2_Kfy!S-ck zpllModezqxm!*<<0=tkUHKUg&0Y#VnV5rm_!d?bu`$(7Mk^!86-jS}0u6gtOvX6L> zl&KHnk)v(t^9e|OrqZYlIx^;lmKCbjfIX`ix-qZ!{E^C4mVZ9Fryt!L5^nILIbA4y z`f@|+$*y_JOxlp&_ACoXJ)gBKEM5YHJav@kY8keu6f!3?<;MQ{1;#8sv|I6HVxCc~ zEwfV~7T?X<v2etW39fGaOSrXcu>9g6YiHD3Bm~qz{&(C0OTF@4iM2zF&O2Me_^dGB z@xtmHLKAM0sFptsp{(%#p5ea7oau*CE<>}OhtqH+mNeq@v`cb+E)3{jCN=I0sLHk> z^GaPSB)$i5p5uQ}qgC(`?p0tXK;hfo^4)&qb#wp2y&I9ef0d4vs7rzsui~=}0Uvit z8wjvZs763Ce!!N(jIo_e8<M3dZ_-uP9;?)E10Y9=%#H6jW?M(z<i~Hu|5t}`9B<F0 z3p2%{X;j7-IXRxcro;%1(}_q>-cHVsEp_q#c8Zt6PfXr_>DoUG^o0sF<sKgd;{l?y z#1Vr_i?KKiQ=z)MUUL^Ko!+|<FPjhE<6w#<cVgur{lQ&oImdKtV)XdP=VDf?EA$gw zj2Y`bSYy$EC*&cTGOLRx^B?=WG+gWyk-tk4LKCy5;jF=;qFxisuKa6`sksGr9#8G@ ziU9uZ5@jFxy3Uc{U39ZaB4ikRmCf#@;8m_pcm-A1$89v3Kq$OHh@B!RfJqWyKn5&6 zI7^VAi9IP(dcygrk-vbK>3TpG%Xb(%BuSq3BKv>k1RG6(i10&Dz5|0epWqhlCD>q` zb-(P900riALw}v1lQajb=k0rG?<z1yjGiGLtM@((On#Rr9HJ3D9@KF(tQl~l<pzm2 z^lqoaEg~9(=%@A$%^1^fjXnlHOUc(!l6a{gY9yGb%p|`T5Hc>Dz)gcRL?LhjWC}rn z7Zse!nc7{RrqF%Jd$-J_D9S4RUish1{?3mcdQpN(breR8rhICqQ4eP%ND;2Cnck^3 z6|(&x*G>|~xr>u++C(sM4b&m(?xmn{+HjO|`ZQCHBk>ps)~?Cg)p++Zv0IB`U95QX zQX8|4$b$$vjZ6dy7G-MDP)Pe8^KFT<?J(cT8OuW6i1@Jr5R0%(y6hkzT*14SLQ<ES z+mnpvEh<lMW?IC~l8Ulz&i;3j*{wVNhM1F(rjTJ!gd_DICH#dZ_9J+tBGLVa(@9*& z+7WKS<{2X%=d-<w8Pgm-H1DxJ$@eFm`a~#pS`-X*LJ~u%9sg)`dW<ur&+C2?QN#V+ zwQ?ekMGtMH#^eMvjEK(?lta60ieMoZ+-__@LO`8x_{@H==}nDnN|llRU`f#P^Mys- z`q4&Vvp!G%R-B6x{*O>jiePZEEs+40z2@UzgI!{E4tEuJ-hG|%oAj1~LL#vcJszg? z{#QBoE_^7s>cW6kk<-mV0AVrYP_tyxQ5ln0mD0ezusonl5Hhy%(L*L;17^tiL=xN& z8&2j^VZxHBMD%;}=mbkSN?ZOHVkm)J#ga)lnkVxY9q0;B+?Ur7Ol`+*r{b#Ia~ERz znXw_lw=op{SVpfT$yM<_8GelT+)tZK9ut9#_)3vVMaZQIMcBmAhenB5S!qF8l6_}n z>C%gZj!1sjD^J{wf;`AxvSm`MS4+*wR6+m0r0KoMke}x-O3hI*{#Z0cGnr+t=q&aM z%XxZtn?Yjn=Z9q6a50i1zeStF^(Gx7RHQVly=Y+JJqK0Dv0xiEU0U|Dx;Cj-JBVd- zLyD9mKvn8gb)EHmJ}uF}D~%+Njh=g|a*l%|QJ+$!3J~?+M#W(2D8uL>?NL)w;0r-n zwe=N|#@8aF)IKx>p<$vPEKc4(S|K~LDFT50;Arip{Hy978W^xvB#48>-Oh@nUMRx0 zlyVv-^6%M?nTiO{i`4cq{~I6Fu4a+0tR}|FH>W@9i&`UAtQOxwOO}Ek84pQL2%B-O z8VUEfw<k3Id^GrW-La9f%N1C!Hd{dYhV7Nnm!iNe%J}WQuvQ{_{Rsv#ImN*Wy(U#n zZy!Fal>P&BKsge5=1KDC#3x?ELL3lLpW8gn$@9j>V-*SRBMP4@gPn8ohTvU&4)YzD zL{)`_slV~p!zJpm39G*I|9SY56sBY(5}E~8iZLO5qMLnJ<w=KNz$dunIatzXLwLSZ z1V<8j?dG`GWnL_QuKMWlQru?$wQgONdj-6ZzO!<`Aa#{Dku&Q;dDpUpAk%NdykC%g z6in@(RoWydeV0-K8Uqj@;=JH&=Qi^{Jrir^e#v?Ta=*hM?Fp$LzyY)ESu&sBZdzF2 z$@w1}CLnu{OFZMgPpaMT%?0s!5z6mB_^|rq!_OywZmkiw$fBj-?XoUu{<0^PMUMz} zCPA`$f)MVjG=+cP2bD@Y7Hi%g3{fk+`Q#S%MIi#~i?)SW`*D$`24yyV$RSo%BY#b< z6wC)GzvX}k<SU@f;z>b5kDmvcSg-7omDP0OiTt!Ozh2Ixi`w)3-+J8Y1-k{YlrAgE zDJ0~>{ku<9j?Qm9xmfMD-iwtj4p=9RcdBgB#PSukk(7TX|B;+MOnfY#RCnvn_akCL zgo_@*x7?MyRw~~sfuxy@zRTxCRZ{Cqfc9yYBWX30nUR9qwKJ=v`R?K}7LCD&IQdOt z(VF&b*945hTSOMs*^#XZ5LFlx*(!Bp#-C6?S+phoc)Knqvl1&2kpAZO=jQ$@tFJt> zm9E=c2gs^?Kll3q#}kz#dG-Ypz=eKVfSm8vwhTU=hat>?$xpy)`@*Dt8u4p_G9Ob- zj3R1El2HF{&ts%l1ty2Au0P)<;<|{5YI*5n`nY;6ai)F~>q}NiH`!vcLJd|)o-Bb? zYd@NHM<#v+0bni&Pj~l;Z}Px&g6hd-;#aWZayOr(I?$i1__d3Gg3Mu=ilrD*XeVl1 zSg>g^iBb3DfHv?G*#yr~9!QuOI;$19D-MM;6jkYE>{5zw!rb!y!NZbo{MTEQfMNe5 z%d*ugSYaNcqpjp{r9@R0>LoRG3g6xdNaRUA4PfgS4DKZ2e%OgIF$U@av2WB_I*##K z$4ewpw2vf;Da;SzI(0{R-~B{B=lO>kz<#{UaUKmyOL<RsJ(H*m?;`xn33*a=bDH!V zye(fVP9E1-6YwQB^_<{idd?;2!!?a#xjJ>8t2*&05j9Ef8`!2UPBc?C;;3I_OBOvD z&*RPxJEH{9L44L-!ug@3oMfW2iP3RG`^U=9PrxVT8Mxss_wvWOjom}G66e+w_`ocG zR*HL@cgY&%VVo3okM3qd;t7=~BgnINBF{)pzc4Eaayk?togFN*6KlU2NsT&x`!a87 z=)b8>*+G(o*pA9x5&roLW$Pt+sGP3-!jYpQ&=302^1yxRr;*NWO5p@W?n|83{dc_$ z_q(R@X%ikL1-)`nMx#IZEHB$Sz3>)Fl#@s>ECQ=ZQ?N_%a#S6Y@=(ZsihTAY$y1?% z_B)cMCRh}UTHR_hK|(TgRu{M+_DCZxCSJHAEXagm@{?q9@FMiwQBhyLT7!u9#rGOh zSjGBwunZa!A)RRR%Ux~G`lPgGrv!`P*985qU9$UMlfHGGsQIPb3I>YEQG877vRpC? zHKp$$`p!?0<pA*qmy7MXns>lz9Zf{wyXO2r+=O=KKqaQ=k%o*H<GLV9e$xGPw<@@5 z$`YcEot(n!8p&t^?$PgNh7;FVfMpgrUu_B}q$;7M;7$w4G+xeqqfmV(+6g3(`cv5{ z{;D$e-tNKopI7b)QF4`9a+Qpdz<+FsGq>bKeqj=)ebXwe%HDleG#aGVTm8pu_}D!5 zlUxKLN9cB@wkQxa)OJ~_*!K*9jz=s+B{)+yRiCHkh4{ClcsX>1Z})*nk&a3C!DG8k z$-}N@WP*NUK+G2-(b!Cv;BMwWW!p7;{h#WeXQgyB63(vq>SdR^{8d>S+vs|73A2B{ z_rUjzfVOW87w}a+c?oo~sMV+mT=fX7&_o+3Z?)s3RAMND=JE2eq!#_i%NOIhVmn_3 z{@~@L#0)gu<D@*~Giv10TNWf=Ivz?#g>sDjGTtXCN#ZN{e(Qu98PHwg1izfC%#b}4 z5$3P#lG5gjV`TF|v?yeXMN{QT$Vu;3xhn8U9;RWbF3=cHWVSV<66Ip!<=wSNL7h`~ zV=h0vTFjX!0(`&Mr&A(jqzd%Ab9Tv%$D<>_?thM&V$^0x7I&{7duPse*0Tz6v_Y}b zJdM~3VfU`-KRCB{|1XiE0u%-A;3;Z4Kfm1kO)fnoM(B{HUlQlR-#D4r!@tVck1t}o zd|iw0e~Q~Tb&5_2%MpzpeP($y`$Wz|Ka-_P4wpsr|JQXCpvfPzBChYodc%dw_xj(+ z-lyk|f(?Z093%|MyibtiVVdnyd!#wj5T{ODXHlW!sP_K>RdP^V#v{ciSd2Z?<94+{ z^`=ByG#63cr<=Y_*4i4C1&)glzhE<c&F?6C_U7nj`&r)A4qF^;&OZO{MgdfBM>ogc zru<Z<ltW9-1-l1l7$&)bs_r_pS+-s|XwXrq@)L;ejf1&?`wt~JE#VgG^xXXTj<+Qu zGK<`uM!+iA`Tnp7DNd0Ww)JIajOea%3B(3)b?`Ys9fDnCj6F*fb9TRW2HEn;B{kaa zfPwJ*fe<^J2aYcbBdv@|T>J7)-2G{B(g*cv?B(6d7b_D?BUz_&OPv~6)|e5kp=K1F z4rV?W$MzOO1ZXI5s6U442T*t+2%I+HvdHl}TXsv?{CXW5%)U)!=S~WbK*(!#m3MdS zF5Bb1aSm3bN`uUGkcYuH{-EK`Nr-Ge+6cq7+R3Rp7%Gp@T^}}jI0ho>)0znB3Lfb! zKze)!zCUMS@fNiAhNHV`*)(uO^ue8>li0;>?0W_=UhQ3|J#oipV#y$GQ&y%PbT8FR z4bM?+3i~VZWj4=1C)}(teuu<foPG6hcu;*rqKccg)vr3FJ!22caPr5nKhoJA%qG?J za&aLqSm<stXIujwWC;A1wT60Oaiw0;)<oDRC*F{2zQirZUb*brex`D}ILA(--JVBE zxR{f>8EfTDd(WCzJu2B{CzTWhWy)!rEI0wcs$M#yyO)w;3{=1WFz$U{4FZs1@3|(< zGtNTkJm(wKKL^%3oG$tRL@zw51@`k?Y5(}EM&jq?{F4kTSv*icRw$2@t!Z;0qYGOW zu5!jj@110v+tpOUzTlC#|1E`IAHF-D`<`5$b0cap5*O>@D*NTO>hlXjsk-TQ>GA6$ zHwwc*^i8zK6#jf^_?wmSg*z?*E=5sTwanqrjN1fs;QUB+jYI=~)mMIKxH&vDMNiW( zZ@<S0cRlPk7<-K!laKqex!h2C_AX?a4=CZm0$#%cOLyaIZn$hbn+S2!va7ga9+VfG z`J}XQ@~!@yGkr4#fA2`<g*z`Ft<PQ6TIDiMhuK6R_=5OZbId@=EcONd&29HzX(&QJ zCcDS8GJ2k{5%)myr>}K9vUFVzJPTTG!FfIc0rG7>-cAm#MSL&TT8Y5>3TB!8oZLTF zjiEX`;-@pMyxESj9{2#*XEw`f%ZZn_XoC%pGRROt4jvx^(0$Hbjq4XUugRoC1FG0} zKIOW5yyk6JtQ0Mda28#?x7x*H`-pZ(j)IVmcl*z`&MDI45u<K*V>=OrMMLqtht}FM z<Ls?37Zm$4MfVc5%5EHb@+8rbD%fY}W}S2#5kx$Aqn)MpmC5@@z}CW+>;B$yZ2+1> z<R9B?{w-#F1WQAPoXn-$?wwWyMVo@+(DNkOH;Wj+l*v<H#XY4spV;LL4F!mu3h80m z3b#v=Pxl&-A7;7%rbzROgz~K5I^04-$x~vdIAD>ET>w!H*~k)kH5oXnFchc!>&`2S zc#nU>N1ha_OhL~UiU13PuDX-!?V7{|SS9-90PBp4jmfF^Ef69yjAY~dtXxF~R@0PH zL<<66c--h4I2e|m%nZgwyuYu*T+W(<Bl#mzIfCGqIIKg`aR^V2lW>8|x1Bx#tTSSr zHH+xr&!-4q_fSAc7z}L26!~QhRV16B&sMMJZMdJ70P0R(p0dr`ZG3R?SXiVT556xn zaqB;`xhW$tgI*U*)}l}vPV!&EImD(YshQF3D7#6l1&hQ{mV37ilRUUG3njxe^~}^D zMK?GekV8F9hnKyxU&~mWY>4mln98oyskgQaE3_*n_XsT>PgnMLzRf%S(pR4-5jcXA zm<9c0F9pUjdHR=Wf&v7~_qcFniv_s8_dOu<iiK~wj7?l>w!zsyU_-3LY4y#V$H9?n zZZo%dE)GWGXK?H)uQHv&a=L|<{7>osR;A0-1frw-%`k%XXkQGo&eCC+1|{fG5ymIZ z(9WFtb@N`ZRYg`|E}U#NQsOo(FYx%!9Jy&bO}{7i+2hC!o4kY1Y$5WsS6Bhv-jN4! z4TJY)$CDrz{9bBwB%giUaYJ~^gZ-oevu+xaVH8Y4%hq_{ENR~^)V9*EnSM0Oe=K-3 zbzE08lcD<XQnELIV|7o-ewjp>&pwV^MK0Su|MBemwQc<~`kCEwt-)pk_M=C|Wnd4E zKX_Kvd6ncfi&^emI)}hd@7p@oJaO6gQ*IbJwY>XL7m(F_##ua^^BSa1a<l5TcF>E@ zhfnf*`e{RAC0v=V4JIP1&<`ND8vVS9kM{!4u954!UM$GT!&yhbXsQbOWCS}8%K?aV zb!*;z(yL3sEY*P>19Q+dd$i)#j~!Ki-_JG@!29|RV#2)iXD3n&ViRngQ0T4u?!Y2@ zTGC=wH&+$pVG&cg%k!|_3E)YP{1o~c&Kb^r0xf~GbB3bCyUrf$cXu)5axd4qQq<0* z+@#C$n>&C^9j49k6|7YK5R!jbsZP)Js2`7nARK{pza=Bh)9!hm=nXoeB=YwVdzIM8 zseT=7=<EP)5_BZx8MRA%Ix_{;Ycb@mll9)?Y19*lmgYZR2>uT9xi2OQ{o%9*>UXGd zwsq!RhtYDO#<xFOXVUN$6UR<fN2Fcy2$Hu?$Y^$0Qnu3vMZlKxGx<$bOYwcayx@Xq zw`A!(9r`$SUb%YqlVRx0YoZbY0MCq;|KQb2KkXMFenO-gw{c5Tnpsbr(thPBdTERY zC3op|^2@L|V)0VZlK!uQuQ<6~?FAOGeVR#a%vnJox)c6$^(_&$y?293Kt1<Y`_0BO zH2yd9npN)E2TGUa4x%-`?yIYx;uH5XPY?Mjp*z3k9R7Tsqxfhu@*?b3yINIcY2tV3 zZT)Z8MfXck=ayLUdlnmS@3xyzEI2_w$6-i>J`}nN$S}n_&RYX?)NFr^Fi^IJxkh<9 z^lSW7#FuQ&>tO-wGv`w2=p7ZHf9gl3O}}p=Hgjx-pq<7}G~CytH%pi7_xwtkLRtNH zf3Nt!BEDA-eKB@|=aER*@-DG-=2!AMSnza4zXUAo&V$Qw5)hZ+H`=0^T6_@t;c8Cb zS&->7_E1kAn;t%yr*wnHV%+kp7keNT;1W4)N5S$CzTbxb4XM-IDec`KT&%0bnZ^(A zC%CZ9avl5Q$BQXk2+qW_c^3F<H6Znz)5G3V%=O02qYz^}KsjnJRnZccx*C6k4gdvj zv3ZtJey=RNP4tUKv)?5I?^FwILiieLzc*gQ4TDx-Rx4R}R9h)-ofRPX*!D|jun`18 zI~ngY%E~x2G@j6h6C!d<aqjpdITpZ`UZFyux=J6xW_e^7xJ4?4K7)xx1<UyFQ|nM0 zZ{e|c<9;vqpaIlV(`Nwjp46s9Xb`UK_HeQ%e<_3GDGH$Zv22v#3TqCrTzddj>^WQt zRuu@CVKE6Fn~X>cFGL`#cwq{GVi`zF$Hg&t*=QJ|nR6j22VT#&@%90h5Q8m4UmKyV zSI8;&MM0Fs4)61u;{TxEPP2hwM}#so+_U+dj1WHQuSZu#Q;kZY34YHr0@Clu#!Qm( z8nPguqKr-3*-*JET&*)tZq<u=S_xzP6UP`L>u*Hm{U0AgQU7^a?8Hl!jeK%1Yi2I3 zLdzDQWo9LEggu7YrsrM|Lm9x4c6tmY#F0E*;>u-&bN5yG=Quc5IOAscR%w`>X>$N5 zi5nL4#f**O>!{VQ{NB?7I6K-hw|f&+uRg}L)e8PC-TevGYC=nmUBs(2v|!2NXB3xB z2uL6iZa?!+ZH4EzxI|$%Qg$J5#{>BhB*&{FJ(TtKH%RE~hQj%Q7fIk1FA&C`hE*f+ zt#{x#%gna$aE>zRBT&N5&)Q>fQH6E)WUnGJ&Xd1gLLeX+zvyuUcpz_LxF#CZ6nE85 zLN3xtd{4ehE>>bd)ISxOEMn=nLJJ-uN7+_5eiJ0N-YKFZ8|C;^@@Ixx2&<ZUg45{j zlU9}zjyG}E@tA0kh|G-2nA|NDbzPSM;VwLdVy%1afhge7j0?pJ({ZBTmnqqj9ny%1 z8H^H%Yrp&uC>_EDDt~%cq^6|34w8gnq)I}a^b&TK=a7v%0Tgiw=Q52TE+FTI8sq=7 zf<%V|U#gj2cAX>=3cfwVn}lDHv)RqL8BSnw$)7jq6~F&G97o%vPN|~`mSwLj7<O(L zZX9E)!O2dPE=l$-ZH_X1ExIs}O1#i$5*#5@J<H!sO0BjNh{?gp)Jb;qvkU=%lBbg+ z;~`;DbR8ttwtd9rB`Z$mgOx|t>`<PvIsG&`=`zdX7?1znB~0BmdEIC+)Myo5$K_IX z%7&n0LgNR|m_Wg{qP4g@S<+WLsc`jFe7Yn(Uhbuhyg43u+Dk&bjGL1z^p;KcU84;< z&n@9x$@Xq4RC&q$7%NU2Mtkz;%-Fb>$%25gCm+<$5|;f&)MdPm`b#C~P#d=h0T1#i z@kmG2r=ryi;lx{x|JmO`&Yg$^&$RnsOh_|^Ns^B72D~}%T*=N?HAwVh);GoJh$i#$ z7^3sDlX?!i<z?&C{4wYGGdGb$)MW%I3~~CxEN@*HP86ke4v*<uRB;5A#m<jD+5Np9 zDaDi$Fd-v1sF*|I%eJheJcd>0GY^E8Zua?S9VD7FSP;lqs=0)lC1T;`@`E1ehFXml z)Sr@i+&XTr)Yj$uM|VE5WgkVOlq6w=7l0y!+%Mv;c1rc`d0cqzhX}*ec?#Q`+zaSh zq?1;I7>9+O(|Xt)I%7I7p8p9_i<E5}?DfvN>v#dEVK@`$@eCKs>*uNE7vm}5h4<s6 zi3LXmJ%#20#LE8Xq&l*a3q<%g)Avu=1yF})PvsVrAT~-0U@tR0vh&hVi^R*R{`n0S zSf7FZ(2}NiN+^*uOndpg;yrx9r`k1xWwkH*Gt74C!^I@3s%gj6xXBsIkd4Q<->E*R zCl@dG?80cm?%2=~QV2WY;+d|gQcnv<&%dP%0n<+Y<to1So#%0UQjOps%@@%z4+JaN z?bGgPx6Gw%O4PQ+`?+ez!uljjbFfX;^06RmsFz3=Uf_DIxBg1Dgw-tVi6%#|?F@s@ zo)7R!y%*)Bc;|B5St;Q`kbK3>xQ|h|7ErJYQ)p0&671FJQzQA?NvMTky!TMV%3Gk_ z+g8_9aEx?Oeh=H~c-ClFGWiAW2{!1Rr|1vuL}Q&#Eu<GmP;k`i%lJBw(C3-Ag=Tzv zjG=ZT!Ff;>kG1H0d{Vrpfcx`6B~R={NMiIX?Nn28TK=<fEhjfZa3}_-W{6ai?nH2O zM6A?8yX4;Bd$C@Bvuu0a_vx;L5PxSH$m0_-B*CqWuPG|+<@3PfH{6U)df=_#FmQh2 znX2TiC+#yDO`sQVpQrT`bg*)SX<5Qq+WGFP>#soZzitb+#fQ)9WJzA>0q4t5FSz}b zs}j6|>nG{;I15%Ygx-)2d}uk$WuY;WN&Rdel!nR!rCkO`NMFgjpxfuTA>>;5qN{%h zGL+&LjcdmXdBGx{Ik<_Fg~w*lv|m!mO?kx!1xIN&(;X6QYRSVs1(I3k_ix=Oyadi; z9Ng`k*lZM#e$^>x(s?(qE0CQQe^;ky@}T&hu~MzBtLXQ@FZ(4My7wl>(?CG+%)vd7 zpw;|=m!oB1YjdCoJd@=rL!iZoP0w|IOX;vcGWpkb)XW{+Glu5X@|ZbBZI4wii8k9P zZORbYyd18pci%x!&Op$urc7kDC+yFa=nGdXgRho3={<-Pe6SZFQ$yPCiobjLYE??1 zwA_JL&bSmC7KloErK9`swqEu97O9E@-_QIH&hY8$fD$TO9=#NluJSC&xRLuVsv=iV z|1(43)z!xnE!E1E&ZZMmDxE1QtijfWkGJ(698C(khVNOe^Gj0^@w->+cCXgzv!S9u zj}U@D18?m<y$<hI>$%9!_$;aAY!a#4pc(T3(dvDbft+fR#5q0IZf)did0H-61?SO6 z%>-EfdA2S1?4)4r+oYU30zm_yU|Ca~XX}eem*+7LD$W@7^nZSl_NU1^;YGALo6%Dd z^lH@4fac7YmWQp{atu4pS>Z-f)#1aIm#ujjh4I7}t*=_!7WkVyliI17eS@tpFX*;S z>bEb%$PLG|Z~SSGDSNdl^y;AXRj}8qzxo}lMUu-+4eW;<Tn3%Iv7G{Kog%R~*WaCz zvF&)g5c6u6>ep6rgKpin?h}XIBm<^#Ec3{$jcIwvv@z&$i0yG{>p6Sa<7v?A8{2!K ztvC3vH_V{#od!6ft?$}lU%Wy8-z`w|*FFa#IG~wkE(9YJ`$a06`8ffDQc!ySMeP`# zvSBIv4jCyATtF#~kO+1qv#tX$Q|g--eSatz1S?~^WgvGrJ;>1o)Zw6*(&SbH>1d#~ z=c`oeG%$52bKI79wu^;8820=Ef|fxY#UbFoP+<BkA`enGf-Dq1uBzZ%H;@`XY)UWz zInUjKi=@9gBtuU?*~lfOG%mtytl&o%SHjub?jOTuS$T+qc#-Gg(;!!}fp5Z_k8QZ) zinOIqsGK$uy$Awyd~z#?9}y~Ecjms?6$UCqq>@h%ByeAzosfERt?o}7j$HaBw+sY* zi4u<*pzt)oJ{*^%nqbEVhCx$=%{bD>mdH!(diu>dPp^*n&-%!OkVCpqT`!wR; zG?(EFZ`_PP`;5rH8NA`FWZbN5`>f)>SyjV1&A2(;_PG=P=17L~#&Ppz?emuZ=4}iY z9O4#S+856LTkteo^o?7*(7qV_Z!yepDKc*9O8e5ae@pR(%QxbdQ`(o){w-%3uH?q8 z6tu4t|65@guHKJZeb~PG_}^;1;o7sfwdVG<m;cr}4cB|()?c@;5B*yoG2HkVw=vPa zG5K#}#&B~XZgZu5bK~FU(YE3DA93Fg+P~{BvcKz0{2RB$*VVysZ}V~~?kbM!&-T{# z)SCeu?9$}+?l~?<yx>WaODgfB%=N81&AZp;gp~{yq**_5lmS*AxC-RnlHm__GCR-# zizsEkl_NyV|FJZM%J)T@d*GgXwuT*%?M=3f4BujB+1;s<nCrMo?fp-NLRIxp{u6|p z&I5dV)4iU1QIEMzI{ebU{SMYG4|`C%(IO}M$7pf$!2r+YD&1hmvW!c!hn?Swugceg zcZ3$@f;aUnJv?v#O@tZ`VULneR$+AAfD7rxLRHI{DLnG7ZTvPxI*H$4Z@T$IreB2O zRSOMXhkn-0QE+RCJ>pQW94ycX{M?qJ{@`sfk0x?-`KgyKu$Bx)e>z5<GbIzU;I3OM zCMD8$dJ?!wUlW5q!%Fl&Wmb>Z`?zHt>S{8YvrN`_g?}U;FXH*$VRBp@@y!WW{`~&S zsZ%%InaC+*Wg6n4-vfDwhwxntGYW}9*;RZ9<)#LWC%OKE|Mnd&<M>ttDow&ECzk`b zM^Mei^@+ywJCD=!Uxa*JF!;qLn5RMVWzk188Vy?>|J!A6$Zo?>&xWU*mwsNUGXE;x z1MoLz4|%cwdAf;Y;dF7k!E+$_afm<6S7&wJi&K=HIKBUOu6*|h<w3Q-_5tCx!c%dI zya<}k4_!$9aGd|nl96~VHGreM)ykQ;JbrGGnP9EO5ijGBVxQ^bWL<)&;1DU4NFL^f z7Be7#Kb*osQU`FyyK*@yMrfeIhFz@J9h#YBuITHPZPmMn1U?#=`Q|#RX&_S&98331 zAt`eOI$8C*!WX#JBCK3XgZC_>IYgjyx#7<tIVK`K$G2W0I;YUl87S>1tMcTKQGsy# zE}|}+hm{-f$HORt9vq)FF1}4!F`u!ybKyZr(%4;7`JJ+_<dk@IE7NFWV@$TlwP#s( zL+~2C#1akr$@4~N3LmKuREN2FFYYwb?KYx(_#W&^JX$g=8Dk-xjj_L7a)$?kJiB*X zY(z(DO7Mu0YjylwYEw0}gIZRf3@G`V^A0#^7Xn$I<srO3(sZVqbgio}BX`zxje^C$ zk_q5pEA1~qjb*;yBpdl(ZA7_>b^&_{)&Xs+>>bZoUCLg|FaRP&5L!>R)*GL`X)PXy z)5tJH_Sgm&L2|pt{$nTPjOub)!6Syrs7Xw=i6W%z%1p)Q9G%>24;P8DR+^fTbJV9p zTJs7&GmUil9L;SaUSBdIP4WEE908G^A(NjqK#A@Uv%Eo~H9T=r_2KaBAW>g>k5}8~ zq)&!E3u`tEusWV5hS{R``iK{cIDrA5U>-bqUAQJ{spLBHY8Xo};Y`gU<L^<nmEeu1 zLw*QxpP_H3QoJKPLVo<#0>)~1^{9qs7B>7q$M)O6<4}PJp#Svg$OkU`16Dbf+=esX zSVTOT#OUdIwDym*-0|R-8E4`S!pV{@q&0~QuMg5mPxXLirJR4&J_T;pPIq~L4vp=v ziw3)hUZuysd$l?;4U;O~MYD#nAJ;CkJDQe@+#cyom}aN4kEF|<YyCuQSxh=PJi~LJ zE<j4}Ok(O%guhfxu7{S1fZl{AY2;X1=XJHvxGLm@JU_6FsO14#6`~;{g%R(QvhTfA z6n)G>HAv1Dkr-1^CUN!Yw0r7qO7x?lj9#y-cve~Wc;1@*9@!Ap4BC-%xrohbn)YgA zMXWBu7%kiPQAZnLzA~dx)znA)Jp!lI;k}_Q<MxR+xP$tY@Z_R0aWRh9x2dv5&}w7- zc?Kd#LP~M;xU-L~yJ9ugTXmG4$U9Y+Qk-IXOUGqigRYjgfrjXx_V$&y?8PVLGG_sd z&$5r)P^Hng`6B1A<iYqH8qZob3%*Zp@e^GsS6p>*nN9oZLY|Yq6#B7jvMPv}AR<el z47c6a70T+kRGqCLF~LUyRM~tfenOMZH`&gAkb4j;E+p@A>RG_YR2W!QT8QhOY1!Db zNNm!b_|;yokZvMy=*6FO+vKF2D!Wxpy*Z$A(+5*%4QM1BxpQZ-smzDj!k&0Lvg#s8 z!(667n+1Nu`KDHoY+gp26~kcT;lZ(<sL&FjE>a-wDkzZu@rJkTtPEBs!jxXuk9r{0 zJo66PkT!U*r|cpO^#e$^9-{k8m03GfXGw_c6Xhb{7!eh4N;++y3rOWp766XjZm1Vm z%tm18Ahn1Lhll|xj1#b|_bL9KILl!p)m0nh<KH)gL`bWSCqL<xpUaE2bHk7Vj0wS8 zA;F>&P!YZD%)3*paR~`#CmPF|6Sr<u-@X4@NP~fhK^}h#2tymJdpkmYiWev3Kcc+% zu8*jEAhPXjX2|A-J|!W6eMi5k!Q+)8!<7hy98DOhug2FJJ%9duz6a_u@I^m7|Get? zDy&Y6r|!U_iMW%{7h(++J@)2~q~Kk)vs*V6_jVFtfDD`d+s;~u>ntBXr?JMd!4WsQ zQ3uORij>UGzkga29|pgv?VMywt82s^PWOdcs6MvO@xtXd$@5g>SOEC5f<00N^<wIr zz;orQgUm3}n;9vgH8y1r@D!2e(7ZVEoZxhAkQktfxSOZmr*Y-29b4J`9K`%x*oEFp z9JXoU?tH)(=qcScu4)9V87BwJ)oKIzsd7t*iEr`)`KqRgZR;VdcqgYk;p}MZq&JC5 zd)MLpIDso>R=J>4iBTL>n+ohOf9BaEo581<QK_GXHR3PjG@Z)qX`IuZf({(c_K#ZL zg`B6XR8#sp68QUZY>v)sKDsxv!}Gfps}~z<uW#^OZ_XC~o0a{FO$`a<=!3oZZPwsR zOKY_77S^`>NxF&%%1^|@-rSa_e7+o%99o@@;Jj>PuyQ|oQ0~c3s0rC5URVuRAv#M{ zCy%9OihAjPIo!N#8Inwo_D|5;k9zOY#7OIWCN4BO@tx8&BW167Nf`3&#VhYDo$hU# zh*-S|>dVqrTh%9-ojNvs?3J4|YXaT`LgiFWpPFA7pOw7Yd>P%97GlwCM+`%fO-|_F zEw7kXxnp)>d?YAjXvS}y`gHiy5v4UG$EX#sW(SbQXpK<@l9LhPaN*pZ)rP@3m=LIy zq_!FLn6h{>L{9gr_vY=?;&mO>#rG4S^yS1vLkR}TaOmr3WGp{$^F&T7?@rQ%<s9D& z=U*qptrzruxaKTW()Qi`Z!>+m5cd_hIj@*;cT1Qo%Kq?heN|&V9qcg(lqM*`Xsr6l zU2K_eJuDqZ5#kAPzw$1|s&Rm^mpV>tZU|l}zWnQF%ub2+`>zkxj(c(X2Hs5pRSu#U z3|v65T#T*4>Z0K{%%Mcm{($oJR}(v0wAacJ9~7KThfZQY=ra{#JsPXujHEs6x4?Xo zHa(g+MD%!Zk6XKJou?jRkBIV~$f|NJQoXX(u1gI$g54i;@E*NPLT_6mE3B_C0oP_p zMAJQA$Ot=Zn|(Uc{@hKp%bq+d7nO&f+b#?#2TkZM;~MQ$WtriB$*U(gV<r5+aK|YD zs~W;og}hPWZTWR-6d=4sTiAy4+-pF7>`-<*FV3L~nVi8EpGrV7*dQk8(>jSblEZ1u zq!J9zd`E&N56?Iboiz=ymcWE-#2?v;L^`{rjRv7+IFHb>@GOH3B9iPcX*WV?1Q3XN z`JG|p`mhhnGqf@vs%6XN4N<rP05YPJct<XaHKnZYAl9bEHgKmF>;&vce0dGhMl)j3 zG9f=0E-L4bWVvj3jKbgm8Z|~`Z}mV3YbpdTyWRc>Z`TPsTZQ&m_U4#Nx#!RIq(4;> z6J7~D$!PM7&(Z9eO+}2Lo*G9TO+#4fkt?MsPv^ykdN^2AL)WvgKj^3z!`>`h-e;=N z!ikutO-ApMGnR6$t6@<#dDlHoY5c?B!~6ZzGSlXLbrqLI)_~M#ZhSAE;4ZB(TZf!b zk^B|P`2&p_u%;nNR0X3r`qFhCEwpJ?hN>q!AMHv4DOLIkrsq9n5Oh0}f>aa;mY<20 z+K%fm5fS<cS@$5#)&-(TsP|~-F@>h6tAJADDd4ty<)Ph6B;4#`iyuW6Qn-3{;GeXQ zSj}(-YEtYzdD%)XTpCmeXTR8)Q+Z4i!VVg#$Bz7IWLWPhZMo;&K}g~TAt!LCeA3l` ziHma%Ji5DFKYp1EB+C}5NwQ?Z*F(?BC!xj5Sv+uX!=>=Oeze2_Yk0KV4%MRG|H=;! zWM~xKpFeGI+>q5%n4OEJ*XydyZ)l}~ZXZUu%wc{I>3Zk=Pk-dHy^;F84iid+xtGFN zY*0ZDu!;N{Eyt>)CkG1yasiDG9A-I4LiZkTD*-@yQvTmOl)Q~guQS(TY0*6rY-bCJ zZOXG@%If-yE|?iP+M_>`(SMRLYbuEI!x>zJk{1z1Z&Elyfr4N8=zNtUG(uNn9hbp^ zH*f-gXdGe(%2sGyuvW*<F2QA6$8MyPN3>Ik49#gZzDBup&SBP?rC!7gulaXE|N9FB zRF11XISrVw<FYLPLdzkY?C)8C*MLiCo|U=uNfnsJHyq-%5$8cBF``bsAq9PR3m(~v z-XAW4gymG&7;BvN?WY)u=xJmbOInRwJ+(_d@r-M9i_2R@*Y-m(%BJwHF;vVG7U_X< zqoQ8ZQG@Db&;)k2tCUjjc!~Sy57u%lT%2-yn3$FlC$EgZURfI+cWz$|I$6&3VYE^s z(ZBB!5r2S=>ATp~iFno_ywnldG@YK~ZwIe8b1jrDvPFKZJL2Mm0hlY8V)}VjE{pNz zDw(i{*F3FHc5_ITUtQx+(f&o+o4<BW&zM*Gn$N9t(ywcF&+THgkt2n{X;id<9-3#2 zx1o_XpB+UDQ016`oGBF+?-z!t9$ONeuo<%^t?brnw0yHrK_0rM&N-kQk+~`%Tqf|P z1IfNuS(;s#n;>R1QZ=;qU?Bo)Y$IOa9C4SL0@==m)pOmvtX@;CRBVc<xr1J-%LeEb zteGYdE+tbU`W;TBAm7SYu2!}#VwzadL<&B9V^ETSur`*|HTC}!juxwD5d30tcpXGC z<qKyFjhwHKk38a@yMOnRDk97YsJqG1S>A6eIvaX~yh$esy2bHcM!u8;_W%l(F;pKf zNd`F>VpDKYH}=kgGRYzP%k=%hj}1RAJU$%b$f6@{2<+~CoDWpcj?&1F#K@&#WUfc) z)<i;e9^x(^*J>#z7$iCpmIF5O-YGoE@~F9S`^uU%?zd#g8E+SbYN2{OZ`FJHLlW$< z4ZOlb`ReS+&&05z0lSDTSRyeJGNWo+m=gLNetYKGst)h{G4x)eO6s_qrw2zDw-R8D zx~VBY)qz-14}Bg(eK67dha~a>^iW5lMT*p7@4(jNTy{g|oQNv&YlkYN0II$~S?EA0 zB)nYR<0=f5pOtHz!Wpt>=VbV3gkl@EiAN>hN*&yHxz^~|M^yA#+t$+8sXtm@&UVTg ztFnn@Du>H@7>?L4)gk6Q7@+fZ0)wvqw0O>=TjB8~$51l=u7_Mqx+kYu%qisO&~x5c z<U}dYlqcfzmY<C?x*yDZ8H(IjZCljl+38@ttlC+ygBTe>I!Sg8oJRiXdPQhBqomD4 zJ;qb7DBl~UEHV)8F{NOvpK(1hqLbdmXUjS#@Hr-IZW;Zv+27JaG7ZxHgR_tOVSrt% zRq=8SFwEYIL#y{P|9aQ>o%Vy)M?A2;&mERN^qD#2f!GV^lOi~5msa_aPTjFkh#@I@ zkHOc`2nH4Q-KMF7=6m4%eD3KH&r<2r8^+EEJhMgJGOjIFm)KEaAvuS|^2J^}Wf0Qy zX5d2LLrA8zY>nXec(EWZ)c0XdD<)r&9I?A7_AL`FML~bEMh{sdHUOjoJmt$Dvr4zY z#LSvAv3zir%WZm>e?S0DoW#<h*lRgW2q=Kt2KlmseH)D(wJ=JPHhi@OZ_zWz1K1&| zaPA16n=XUu=I@S1Bq5lD6L--2bL=jqPJ$vMI8%%Sm_0KadA%I@f>7wQ@W5Bf<FYy0 z`id$`UsK`T%OZ+6YlhThsGR~V9QVt6AQZA&<OHa2u*9bvp8l{|Rs!ADMnO=yEIL3P zr+h<SQLg#{0j*$pBz6Bm=P85+ipOD#J#Od28~3!N-&u-CPqt2v$j{aY=vAirJof@U z;rDSxqUG574%cxq&=NdikHObY=gHsY&WdNbJR~;X@l*f`(1h6E8DINqfW{n*EkP=i zL^LiAqxuUF_q8U3g6tz0^r#cu8rJOqwIMG}2tPuJp62K$++y8Eez&%U#}6#neW^m= zrg7$2tw#-1mD?Anv0;LX3S1jh_8kNCEgbX~Rk+Dg$X=U+y#ZHEf3kK8-8(~j`*>0p z<iYA0$xQQ>sPFDrYS6U7$kI<3Iw0Y{0<TT8_lFbLajd8)#0Rts%eDuL&Gnd<lYdWe zf7{X%vpM2m4Qn@kp-0U7Z+ZjmKu7D>u`E)Mqr<2jBI4TLz9245nhLs@9jNY5yofUg zkOYYa&Wh!4(k0y6);vTY0pm@2^9FNvmLulAHHa7KFF8Ih`5A(5f_Ng=tr5A8r)AP- ztE1SLwobP4ja6x553ZWWQ;r`rrs~da|7J}(EYYLp=>9FXY?{b_3GB4!FO<zfyO&yd zwpF0MnDY!V9A@B&!*Rpi+5VrV^Jr@X6&O-k(8dnT&LJ;O!|}#&0B4Tt>hVcm=3?Xw z{L=V96>u@(W<7^Ks#8h#Sz4L~u?+)P4O8LuA0A&YjC#+t7J9ZGfEzmYv4p|jTOT1t zKXDw@aW+L4q=fjpZODcXE~kJhPiu|;XM?u-X9|)8v6ZeAwJ*bXksZ^VkN9j)7@#+y zfb}R>>legbi#4z#N;G=;(_3yu0?NgAMhTDjv4wOc7<i}4c3G|WOrb_q#=wao@cJvB zvV_)FH_M(4-Kd;}EiMJ$#pfG#S}!mHTJs1l6g^}mh0B_!Zj<>Bwn0?-ZfNM=yzZ=o z$pRfq$I;<K38jlyF6DpMb%f`pB^fziG5+x#iGO5cTd#3ti8%$7Ohb=DOri?g_q;!N zI-~i#L>+a|JNACJ<0q}7uNI5!;4i{!Iyms3FPal_fKq|&QqRT5SR1z^^fu5;vBTI# ztRQgEa~?ni5m~+k8yXIOw!pdFi9M#YZ^xm_>W~#gSTx_}sf)jmc)wPx0IO>Kxl6kX zAENbq_mH0O+avTWq{hekOMYiy+rx0SE%1)Y@k!tbC_R5&^n1E)6x9HR4~+<e4|yPe ze6lwJ4PU<ai|B}~2z&6|8WnSzpkV2r5UrAXVbowoMn3G1YponV;iPRGGAb0Q?*a65 z9M@3%TI{BuR{YM9d8Z2X*Wd%M?i*9pYu=;vwU80i#B}m&<;$fkDxQ{zA>z;Zi-6x2 zY6zG!c=nrf26om5;euUT6Z@;~z9p&VJ8X@*g}Sr=L4T<`0zsY79i&7KUL~LLx|!z7 zNJ*;-=aE_CRBq0Y`6jxndeHbe&%m)w@8(olhbKN04fjdFH*{GI8$dVG1!fCwC)2rs zFr^zvN!QV3n+mgBCEw4ZD|S`To|N51glB7&%d?PR8E!^hzFl*=q+7)5#8V=78HC#4 zQtwxC>w>)7C#9}{1+N0V%XQy{64xVSQ=J~Wbs4cYPx^ix-}de|>BFyIwm#RCaE{AL z^fVHm9sOn8q+K2<sgw9{)>Cq_WpgyN1T?CbzftP^skuCS9<hr%9)^FeDgH4?2$*Qe zeOklep*ESgF5znDAG{sDKJo10e=hGDbd%ow7PRC#Vq5dy^fAM?l}!D86E@c#d6&&u zG34>s@3QMhjbE<=EJ1;c#^37J)uqC&m5k^r5|k^^T0fKwlTUn8ov@n1&Im<%n?B7c zG?HO8pIv!PuB^&r$9v6RxLN$uI)|%e&_9REcshJkwMi&OVi~88ge7Vwskmk4CrIpt znMoDQdw0b06fO#*L0eMIxo-u&<0PCx(@d!hj3l1WZSh?wti5vwcS+>~OddYuBP-Lm zN-?*BO&av4-l#B>F#&Sy<wWJSHTH(zB7d(ilEx^F_3@$$PjK}Zi>je73c;%d;al0G zWmDvjyC1$D9?q3UzP-Rk<^6EnFp*LMI&Xhu8~E(U!`JN`^QDOF18KbFZP+PwgPNJ| zj<-};-s$_?;qEg6-WF5}7tn&MMS`n?@`(Da&!WDxQZ!B#sht54c@yWk7E_~xQdxmO zf8$lR&^67cl|HK=WxPh#)!wO`!EF-?)!e)e7gQQ!tV5eWD|hP)%+YkzTJrhrSD~K; zdI&=I^!hw+8$Gw?i$)fz=_<zYT#=_aDXopye@?NR7YY11XmjVz?=uP$HJQCdky-A` zn8dfs)k30apS90d`uhCDDJrS6FIGOvvk^Uk>`DqaPH@T+>p<(S@+VPxdFhFZ)-tx| zfvTXOrWe=B#X{da&%$3xza4XN!ytPz<tVz612$g)eQ{?tegE98qS7~;{Q1{I&6Y<K z>s(yJ1|=U$m4uAHZ=4%6x;cnz(HMaMU+BB`dpRoVruJiLm^Ek8tqZ3LdAX{^Z4=uj z=nkc&Y1j7u4KpMeqr6=O(Tjc6;X>j6<Ll1fq5k84@xRPIWAL&@md27L)Yx~;*tcXS ziLvjDB~hwb%wlZ_*{ZP>q7bE$>{Jq^vS-ayDq5uFo#Xrcoa_8_uJboMuh;dup3leq zalc{X&8M=i?{je1NIM)+axVXHUG{Y2p7TZ@3hYmr-yAxR*#{_v%XLWh{W^L!JLJJJ z+utX&#VIH6p!WiCN?#Oup9b)Ke34CW?A4yaarv$W37v_lPn(`$8V2bcMr!w;vwzBU zaE8md<t&{7*fth+JrYMe1|=^`iuM_A_tu%#pGDRWpaLhw4hLGx>;zwq7kME-wi{*{ zB+u;#s26arY%5rv<0F{Q3uArjG((Mz?DQsu+5NbT1e=v0*RX4XTamp?O}-1?wTJT( z8!eBQew#4(w|0H2@n&{XGQ0N4R_=8wUG@bZMQV_Q1{y!$D(o#y!?ZZDx}3c1&S9Mm zGN;FIK>B;t+n$nBDnNwgndE#$MYBv?EbNmI&6mZ#mXM?EqAZ_IvC+5K%u9+0PP<yO z|I8qY@^XA2r#-#WCnQmjZ(fCXc_nlYwbBYOjg>#c?ezrk%u@Lp+CYsm%L5JkiJ<Ge zYOLLAt;|i#u_Vl{D;Pa#(Y>+Fml|iu))uSE34;*$A1Q>JHPz^6I4#R&wW;hG*ijH_ z3sg6fT)!^tjzrcM+RMA=42fc*jxywyE8E*#4SCv6Ghe?D0JeLGW5wgNJX;w_c>Qlf z6ktZO*6Egyun+Lbi5eT0MJ_5z0ysvlZ2#VgdKB`g@1DQ%NJq`sddHWR0_XO=s<}eE zF#Z>kS9PH1oXE;s<CRJw4?eE6RaK984Upl*vyyxCU~m*M0h-mKwPz*=57s`p>{IZ) z>Gj26L+;w^d-~5!LZ4cjMZFM6G!wu8T%y`opeM80Iwp2eUVJ}9IO#j1fj<p-)CrdF zSQ;Eqmb-q*X~n7Wd%V_LT&(|F(IYPp>Rselv-5CQzrR3H^gNg7S-LHMVJB+1MtYX? zR9V#x8{M{!+ZQ=JnAiZajjZ@x?WV-UUp&m*70Trvj~NNlMT)O|X+N$u6!KO}a4h!J z>4+yQ5xRUTn_17LKX%9f)0Kjq5k&`H;Vzxw1EJ-6saSw=Gm#HJ$B<tU9{_E1X6=<T z{ytTB-dwILhNXnB>-M145WC@P&gnwM`uB{H+lEe$;w5iN%gaebzS$1E5m+Y|)B#yt z50oNxLUmRQv83GbY=>rrX#RX2(IFoUZnl+wB#E$0oi5%~)s@fCmUg(7D5;T&(z|gl zOcGq;j--aNRo^B0pG_*`9-#|5hl(F}s<?I_ZLmplF7c93+iG0MPPH7(5GCW3&pAmb zI`B5)Wxh}%DI;ABh(W<6^$%n^%Y+0|8d1f4EKWe7!i)EkappV8f*O%f%ZSfR1DbkX zm#UOZ-ANtqy~m?|WYVQKw`FA~ny+LG*WhM-u>R6a;gVF0a;+yyOXx+INBF>jlnpD3 zrDjmBxL)?j_gHRtA2vp=27B9XfH;BYH-`0L^xJ8BucUDtWV{s~*$v^#w6G4gDrGYv zHzKR97bBRKr9GohLhkTk0a)hzGsUJz$d5<BODagWvNQAVw>-YD_90<h?AFh-d+wEy zi2y|$2;viDI4HaYws|%}+Cq#Ds$eicIZ{OUTG-4*@1TEaS$rlPgz1EodAuJC+4FDX zTJoN?*B=dt9h(BLDf{J<uaN^@cT`Vy{&`I)8<yK=p@ep8km;WP<*wm*QMHy|{wdD> zvTT(VQNF+X;fA#itX}ZLIv*hScGHSRWbNxGA(U0A=y&F)03Jahz|i`(w00iJ?1jm6 z(|wn2d5Hrxts5g3e?)2C&cP^J3B}&E<Ctn?W=`~ei8_kj_p46QATsMicD%#x%~v3; z;&uxsI2U^!Rrt6@c>kv{x3*oNclJlM>^=8)OdcN)mA)d?Rnl>(bLIFG_Y48d`=Jm% zkWmm*^4+R*@cXZKzKoIZ{<^P%ChQgQ?=eXnBZVEzn$C+!Oc`_IwRfhkXjSF)d%@Nd ztqvyX?^M!K(E=wsHY~<OgC5#nUU`hz9oe$SGyr3EN-%#nMvRQlIlWMQy2Jp$GfW)W zIwg$MDE9IsTsi1b&6qSOb0xvy;$uVBEh)7cLp`RQ0bs|{t|S0H85s-k43}yrDPoPJ zkd7)-T=<~a-`%Ae<b5CELsQ}s37i2yNZEv)(otJ-T%XyEd98}1mzxO~JuJ>gFv_S( z&Gi|8WpofjcSA?kv@hsI{(wUkuFN7ltN1^*fZi{}D5-~P!gg+!g*zGRYGlnOSTM$r zM2uL}6e5<Jol24j-XJht%3W3Uft^&CEhWR&5anQs8aV??aAa4|+CwRwp=`#9Nk*to zk)k@%>rAiG1C+4Xh5GlFJ~;ynlmfX~;C*-2VI^?$;y@8ez?zIYPC&#+3e8Fh$(@$| z`FqcU7WOcdf;p2-j~Fy2KplB|)_hSmB{Dz(_?m+tf%L3k_QujcA;3yd8p?5~n5PJg zpjwWbr~_ji-2~feRsBX2)cKOiGablN5rh2S;W5q3^RBI#8!$T<aCq$QZl^BLkzreh zcT?4dxv_Q0MfB8`%xz0AE{rh-jUgd*YKF4ehWSp1UO-I$MY3ZIP5B)Rk9inR@By}L zD;vN3Q>1;F!%*`bK8h&^b+!Y^m}Kyou)|ywLK0CV)p9=%<%&XfGnArZ2<5!wi&(x@ z;F0;`fy2w*tGa>4e-!PTl&~3im{TEY`-w4tY9^Lsm;)4|3%g=3!+~ODm(IA>&vwXY zr*|Jtk47m06bF=ch8?Tf!TiAVK(o_GLwQz1#BP(78PF{@FoAkF#WAE>F=HG7yPSR> zPG+`gl&X}~{j4Y5W-22CnZw906lRzQO2YyfL1ve_q0A+j3KwljrB1~pq;Nl*Yh*iD zQC-izz?s?GPBL_;ta;p@BQOOr_F83di5cCUbVECU4Fg<Y%r<EDU+eW4wu2$tdxKE7 z^Lzj6I;`*tl0hP7kgN!;l}8qa8?mG9eYZ2*oqyL<)4D~B!M?;2@k`jJ;~%qMakbal z<k5+st>qQ?33kO37}E-6eA`*$2J?FIAw~lvlEgTSGvJt@(w`i?Zi)(l0f8G`vtq8* zdy#QCT<P|Ot8U}QPrBkGZupd!@M}vaE@(W<8fT>TGRCgZxjH9l84No_ItqVS6uR$B zJ|P&n2|R7Ka=LJF{N7iw>s5k(+uW*}FBXy?`TW`cC-G2PgvN(-m>YpL^|v4c2UT0h z;J0F{_!RvbIZ9i3Q4mz0;)X5Va5bIFTQ)5Ar1l>*M7fa5H*qv2uI~F1c*YLLTnf$t zle!LnQo&-XIBiVtMi1yQ(XT<dp{Wde?rlGS@j|237|&FY*3D=}s6Bfwy1d&fs#3UZ zxqxyx_DbLuPb0(7BXgm8VA9Q0+-r{a%x}NA<bI@oG_zB<H#k(}a2oPd2cx8p0BjV5 z7hU8Y6Mpm5%aTtJ5;aclHIF|lG~#2EVYl0g<gHx)=$wytN@xL%Y#8z#49I@-X#<-8 zTo4KEXOt+Vf6CXT+@mysC6g$9t<t29F`6DIoN!frn4SzeiL_p0KAg0kKKh)J_mYp& zl;)Z9N?_Xp)wh>PqELH6?sHB|31afN+p_jQ+>4(Hjz~_Ka;bZEUc$6=B`V9NR@t6c z&k8M+U<z@#M1kp5pS_VN2+*7nAt`FWLmr9EHn#R{#d+PRJvKrqo~2DRp3FVhjdW-x z0ugYf!mRN>zJuFG+iSsi$mpH@0wZ-uKm0y`z__(g(J^;?>HXD=4aBh^na0(b7MH^S z7w)hP!H(1<lYDy5`dy-C_5p=$jM+f~i$Q{>jn&lO@O%2-Y^=QMM2O+ov)uoT**XBU zhfgJ;Vfw|{6FQrfw})lZO2j8)1^#V7RA$YeKRof)tdKUwe17Bg+gNNVH~Ybg_#!a1 z6zji_&zsrdy_TDG{TE!R)PLPt!nOzWdp2KbsFK06f4XDHj^p`%F?;*Ta5}^~pl+;C zlfbgt?T!u&_<ceIqCGm_6i`EAt_Dl8UIqXuLT^F2Li}3*A<jvopWnXr*NlWbm!r8{ zv2&I*g~mMVp3#xiNE%~Ka!Ep;g+?T2h2k>*>9LylOoinF#peY^cu4!PjLyeB;>uZM z4%5(#xsSxWRT?OlmlNlMoaP|q*9*ly2ktncP8uR)IT<P2K8ojp9stH$k}9eaSrHxn zx9fv6yZEuj)0#Kg(i?XMYo`w#46fxId#@Lq4Y=sVEmwnAmP<$muW>+g`JI+)x>thD zuCSN6&_Fh8<#Di1mrQ!|ahiLnne$3^Ne*?VS?JB&a@rW5K{GLKQpmb%C41qrsE_Bn zS3wDq)xd@!bZ})i+7QrKtZ*}k%;Q&!fV!PqElPzV0boSO%f}qGw<Gj~Gg@)~trIr6 zI4}UezH;K=vRwiNy4@aR!}ha5NvE%brYu|FP~6MGLc4Jl7b=}{D2^}^(X|?RMJwpa zqC*A+28Cph=;x{L;+aA6dM{3FQK%78DjR}BvEkNUfUnJpHxq~|X;iU8rbvdS>j&|x zhA9?>51Fz<wtPx8dHPqFIwh;V%vFaPAkz++<Z_H17ks}2QFx<2HKh^vV<}I6SqH`E z8^=QY3(6@*@r>SE{X?LuMx%DTmNO*Wc554sc4zT~LrUkD#viU`LV>dqc|Qa`=u7lO z3-06U2Y+_~6wk`iyrOOl`sb&hMy1wnm@k}yVv8i+lT)M2u4G8w{BYAeASsOPU@F-9 zZ|P*oa7KiB#*vS5$|4*92*v4qJ+f*P_CCNe`oY2ZMrXF7YQ$??20z)NM{a$oeO1vg z2EaoIR-%vQgCZiLChTQ~^p^sXcQIr>-_i1?H-pRzSah%MQT-)tSCvC9D&YsTeEh|u z04i~qc`W5txqmDm$P$>M?(tzSjOM&xE`dHV&x%>3rC6bPM4IY)Mk=2S1y(HgaVacr z{hx0H6{4+5-xW$XiZTZ+)WU3b|El=-Z(X0)5Bkd)qVoR@Y$(tFxbo$FEmLuU>hb$C z9Zyr>#_wG5A4!E>^JL@L85e%V!w$_8C%yzMe}J9eD7t(%kxWM2+9<6h^FJpGyd?{M zAq(x0L7@cUeF-9m5=0Lth#gH34@i)RPuO!lLGnU^)YXK&w-TfuCCEHakbRpV_a$N9 zb>)wLH;<!H!2glTMFBXl12y`8NaZb61KE-~+Bw{o>Y)ob%PblD)|$r`Roxr@f2q6x z;}5~(l0sNzhDje{xVNuAze=FLuEDj{jaS=URB+-ZuRgoxvK#7jQEYg1!{>I^I;6;o zj`Z!zlKrEFqM(qy=KG~zpl9xqm!Ir+>~#kf_Xwjj6x|?z5Y%W?*2yqvgvtuge)hZ2 zVKFOF=CId+h}PAo7V3@@*_=9?!(ypHaz{?%!Y^eH7zcJ&Cifk_XxVY)$b&mpWzb3` zF!sUS_zTCZlqC<QWOfVfI|t<`Li>WBLG3qQWm@0+@eylwk<1GvMUDHxF*}3K^Q{42 zG}1t)%SBIw8ntz0*Db?IABCdjKa@0DY^70c*T*iNCKZL_QZiq0CaG9`c9|0l*gyad z8WYozsG<e0Xc439qKLz6K0x*vbwS<|Clk(*fjmS4F{77NL4*NuS0g3<cS-`VlHwAm zdctc9oDx3!-LmHzJvl22k@qVXE#_8&vavEAJ-Mg^Lzg1BaFqf;5$gv~k6TtUSfP-O zCl+*6VG!~BgaJn;7SpdFF58JFlx@8)l{j<wSFK`UhD6zTfv7dUt};j8*9~d#9&Le4 zzpn;zhmPF8PB?nmE{rJKZx@!hk5|9vTAHxc2jr+cl9Ge;+}V2|7Z@>K_Kh@WTqQp6 z1pvqq;{)r>zSbm-mSN=?k(%hh=4fK`L92S=uV=%N?eI!p*Qg?kGwL<-ud^yLx6QKo z8iyIaAKS2e*_EvugX&*8zY7)z)dQXN;a2JQfA8-SSS%5SRQ$?zDVvkXkm<Ui-yhcp zo7xV4DCQlrIUpHsI)<9FdAe>nsh?bRzX?-VJg9oT@#_<fJ{WKmv$5swgzB&Gf+G84 zghvnkOwWht^DB{`TJ4GbKCZ#viEDoJuD=k1>{NG!ocA)5nE)bYT%K7fe){o-#M0cF z47n7$H5GBaX=^%WS1O+&4{83KO@0&mb1rqQ>F0d<&z(;{-%^kVw-++@#BDFKRc>xC z<rsY4Ugp>y{Iyc(9rtUsB>d*DcmE@mv+^dCsxHZO7%pXq3IhHj_IdA(N*9rq6K%JR z*E=4WjeZiC?-Bqy*UlBFz^CN@Zl(qIjdEr}ULO5+OEF$#6H+UT09yIQY$ScRi8<dF zZap-m--v(dboi^TQ2MsgGd^H1v^3CG9P)$HE8>pX?R@?Fb4S={ii=Q-+7ROXI=cUG zYVSFi0u(K~K?Q42dS$LyD2SJyV&m*%nh8`fs$j_i9bxNp2XP;+^U2T_uDN|7rp;20 zmo1MCSMA&TVuPtaA}@HVu21gk2Fo0~B(S5I0s+JT7#{#Y{Qy9=j)YU8^bk7|83#k; zQDNJ1f9-~?n~8zC{;GZISb`0ttdc(+tq4pE59;1e$c>Ltlvz_9G9KK_OYX0h{Wd&g z_N2wt%W4>cX+;1|M4Yt-f#|$p)lkTlPc=eG{jD2v*cvY=?5t7Nd2H`=I`QJwbtTyc zhWBi-FfqvH(BAKX2<k#GZcuWh%#N5<${7btB9K7Tu^c^tnoBUgcZbfZfq@biO91?C z&ZB-LO#54DPsTfZwf(b5Of*(7l1{J?zP7i2_tFZYq@6cl)N}=*IW@LEA1=dktLH3L za=0u@9t<$PT{hIeru`#r=V<i1mskJ5A`b7^k5MF&xrigG7QzlshI4}?0RmDN;0V%& z>A3aXqQBP(MW@@U<<<a#9rEjVO5<)guyd9F;Az1N*Ia5K^(=z#@A0IXjcRCRy;I-; z@WhA08eoHGbPnTQy4yLZb5hOaRD*l@bn<nDAFA$D2M=IDtS0Zn5TT5Z5@tom`OU#} z0D?f&dTSB1bdZg(Fs5r%@+Xi72oS#K+}4Q(m-Z;PguR|!B0p}q&8fRXXWsPuE^4Nj zH3kVh_31Ib(|qAbOt8G;vB!CBm3cE6=}|42zMU2#z@$}#UgebUFcNshLm0j*5WvhA zz*2Y+J<PVr$_{l4ciEa9flM5?A9Kg~ov@QyC$V%T`-Lt>L>u6r`W4!@RL!!Vet_6v zpacszCSp;&jF^knKZTq0u}$v5P#neLcbf|xr6P!60M||CZEpO)6E)6eS8ckeSpVU_ zB#O36pXk6s)CPVgFPXgD3Z)8KTysb0c-VG<qm#NTJ-IPfht%tyl9^9ia)bU_%FuAO zP>Zn(VSXKzUtO5K*7s+#CM&UXTDJ&s@?a{^ExP2xGEf)^4s7X@Y2VNP0p*q#uUjou zEop7iOak26=zHIFH|if~$X$(H?ng_(5BUo#(`wvtSpWb695m1k0b02J7v99E{%H-} z8HN&N^|G{jfHMkmp#vI5gDt+~Z6k$h$zhPYflytk1fgn{dzMNwy`~i(11Rlsl@o>n z{2|iqwK{q>uGlYb)3~e>2Mf7bFFI^5VDhi60eSsCEj@U&X5n*#l-mb7&?6XlkgW#* zZ;$=CPoCKxyd`SU6NG`4Lx~WvZQAQVlRr}xI{VwMABi0hH!1Cr9sU6<AeZGrPLgll z>6nxFoS+Cp7fLcztYSIojmy$?(e3xvWbY)tJTCv#%iUsWqw~z4KX2o7;*>BJS%e46 z{QW$ne#dw;#iTQ6^-gky^k?$2g3(AW*I!eInsdcLQRZ#;*FIb4uhnXX`+%KhxEkp9 zwfN~r>E4uI1iz5^7^p#a3jmx69sL$)U9q%(tqz;PM@dv#xodXxH|LySc;?K5m1s<T zd6DyvhQ4fT$UUq5F<qWF&Rn)z#s4PsI{$DNQj)C$D1W*}QxIkkKU~ER;}87KzBBVs z|H$)Z!u*x*4ghyg^3kC~u){y^TYmq{J|!>`cu=^j{LG%mV#5o_^QpAIRi87T|0NCk ze^2Z#{pNAu4DrCNUoV1f`m$Mf=Z_ppd;Q?w4{xcr1pIT3Tlc>$J9*adiNiT=_)4*w zc+{u!!j4HLmg^lyyS{q5xvBvq$=wId(~N*D_sOo3b)QdP?>_(Uf`+B+AfCDNhjL-d zR3>AqX^)*+*Vuns7px|~hM5`XxVlm$6+ew1KKz@XmiFzz&JLg|yr2Ts0j{*W=fy(L zyg8MIZo%?xQ@{wY6Az|PFp)^0mLvGj0F>IT0Vh)d61va(RMHq`7Ecl`p`jO3OV_9X z0f8<Nl=V4}3`C>HgASC?XTs_7D4@jq6h0yit9r^@75v>zH!jJ52MU@<B%MJfr-Y}D z{p3Fw0qWX;`l>X!VPqWz>BXQq@XkHPft`v8Y}PsNVNe1^dqko?;$phJ!2v*Um#O}I zN$5TS`-31@KS&D*NAvJlhPP`%9ay}uTPz9e!oZO%bkPn8%OtV*N}_np={$TIM4k?i zF(_9I%Z?FO!Uo70aAE#bFtlLuTrU$V%gVZYmttKaxXuEv@|eIFrfIhi+77+zSf4`z zh9y}u226k)$Xz>4w*~7c8GpSqMtsuhDCjy)60kt&m88s!1?Aj5TT5V|Ch7awj1Me~ zf|BUwsaycb==gbjo=0uxWft4+#?|>Bp+wf$d4g|*rd<TblXC8QN8h%k)Q#nO4pTKN zjknqbKY}^isqqcpl4`FDqKIc$!#O#2;Oi0*o9m7Ozv91g1%Qt8JY*JB3tLPQLLNKr z{w81JURcSVbmSrpJ|)t=t2%PARy#<*XsY1d7DsH2)iDHzwooJ9iI~)1gvevtn=jfv zzUcgm@YaWM3IN=t@){_}_6gCiJtvP&6@gY9>xeVDcIaX}vbGxy?cq-&ppE3w*R8=L z@1y*UE-k#wEwE)ksmKaSG0=SpUn+VUr!s7HDFbb8iOTcqMix@ghXSD_z&YFnj7R&% zsrkkekT1bYfD4N;ReB}qY=+(GoJjC9zN}<{fu^Ea_%aE36-dkRvL9uI_q?oZoyy*q zc4Qj0t<j=~E{XS)2`3;<<G^Hm1vKF}Y_k|KURY6DK5B2|*>S!CsDLb%3uu)|JqD90 zM+WbCou<UVTF}Eg$3QC;?A>1#JT)Wjjw_eEi_Vq`vlh%x6oWVIE2u^lgXk+<Yu|!} z;)3Sm@73ZStet#Y0(M9W*QJ4hdf?k*;1AcUK=;)pqe{Ntku!Fe;yH+GTr_<b_q;Cy z5iUhjuc8)<TaQ($?lnr>5B?mZHeJs=q$(nF+E@08f~dvStw`|e=2hjgs_2wZD`tAi zn&4-{RL?s2>r&z77RM-Ul+1680)`7uxC(HQ1q9@x6{w8yT}rzMsYHM6=9o`gTc=d= zZzfw{VvjEf0nPBw9I$A+;JE>|kb|6v6pn1JG5Ap9yq7=EmH)q8jroHl7zJJ?xP36Z zrUZ*Wy0Z;xz82gh#D_Fv5U!X8mkhLz2)$cju(m=_30y|++JkVY78JlEE=*m<$YVFh zDzZ+S4&pHn+2Czs_pd1zkc(Nzjv-q@1YURN_r1FUOTggl!1peh?>8=qk0TE$fM+)l zXI)evo5)K>V6dmWGkG^03Q~{N3XK~BVErwO`RXKPqC~h6D6mEXUtI*3H=-{cfW2R% zf8O9PLY<ZLDQe<2BB*HlEYN4Dk&HVEm2ZM9N;-03XSfagCc9@|5lnzDNclp0FzL<K zk>5&|r^W67j%&VPdzSEXu-;_Q_2t%)!mRo&JXXCNOzMUsf2RW=a*LENxRZ|<d7?1# zyH@T)B_shps0A{N!8kG^j@tlBsO!G3pWo49-C`^=CD=Z}e|vAMY)kY<huD)U7=Xer zx}C1RTjZm*`=kb@Q;O3lm{4`$#OB+tUe?5`N%=W|);C%ZffdOlIBBDJU$*`r6u8Ji z(W$6E%WXo!CxU**`0)exDcH}19L;DjG92ARLf3V}Jqgg&-?xN?n|$ud&`HfeGg3pO z0oZ^Y0RYkhqCc}1SU{whfWs0Ij-^F`iouX^_&fqlGm&)UaAhNNId?%Xbr8SC`Y;{5 zYcC533&dl9N*CGwRQ|23w9gAyUa02!MW8)hkdRGy(+>WQMCENLv0*Xuq=Ip+C_mtZ zzn@I59nNffLekIX$~=r_J+gEZ9=}`uzF`$8xJ9nhj}(5WFZd<O_#22BauJT<w8Duw zuWZpFq<iV4dnMrQ)sC_~fn6tGD97<j)A4P6_qw21-(<3{-~Hp>Q62Y01((JISqtD( zPLhsO$Wn7SOzTEwmhep<u<5>0Pjfe95u06($$kn341h7m(8bLqPlt<38qB1fz}W1Q z<PD738St((lF~4ss8IV)4IR(LetW8~O91n`Q5x%_1N_3Dz(k<gG+G6$x49CnfW5`J z_|jz%P88_ndKJ7DOjQM!o)~=tb~}rQ;XA^ZdKYk*jIF};LtMkMOu;H#K4KiRq6#LF zsqRv6SkFBywM^rMa;ykk$Hj5*m9fDz*xnp;uN}P8-5IHaW&%$xEIw3=!fy8OrX%yG zfr3@M09zm2U1@!whnUlnS4jp>#(=AotbeLTJ$RwpxW{mL%&m-JfP<}c$%N<ki*0uT z-Nhkbt{v~8yb@@K13MapHG*Uch{#03bJ}j52_B&W+nsNeH2$e|^99o?3L*LC{_c+; z`4A_Uuqcf^=f*~FP#zR?V1Gyo_wfTCvJel)1WoSv-Qr^P-#eP59si^bLOQ_!CGZUw zd4?QGkii0Yp;tM>Jv$(FWM+6bXg%2p-Y0<XUOiUuz?^g$KQ)G#(Ff1e3m@J<cz`Ox zEy~v!Z5f3x7D7gTD1q(3&Aqzhcj_R8g!*|S!y{Wb$;EM*BsjaUA9uDeY(IFx=+Tqz zlj&GsxxK9%9Lvl$x{U+RTn6jO=+9(CCEg3Q=_v{a{uvY%lJ7uT*bOduUm8<H1JUUq zB9eoE@&iGfCJzq61BX0=M_tuKCyqT4n|Ym-`|9$mV|R-%^$UoCjpqZ&h2;ce67Mi3 z%sHbx<MC54_`ezGIKP$#xWFNnkzbsONh;@*8b@A)R)BF{0-u^qy%2>QQS4a(;TQl2 zs2wiaF%{}3W53|Qixgx^^CkN^Fjzu3-Q_0G412_nJj+2CtyP|5c_lX!G@HN^ziR>V z@iM&Ex8q*#N(<LAj|ILSGmd!BH3vpI+?~$?hbju`_maB58C$j+YlIt{n1OA6lU9EP zFK?iVgpa~n*mt`zwz=TT_vQD~LCG@{agLzF7!j6V3zhdhkq!=xIgH@1JU`MLov!<C zqxZ=8ppfg-Zr1*t3v2bB@=c=>p}^p}JLaA5(z=so%7dTD9R!Q8K*pz4l-4{f;d&nh zZTk!+pf!Y&S3t;1!R2Sf5*r%+l%ZTJCh0HHT4R>Zx{F|lGdnR*>vhkG+=)6kVW-xs z7kB}w^a}2tHF~`EJEicJ3;!<=^VVZ^(cKPz1l)J<9aMg_(j1IZK9wVd_*}gr6o@|A zjXd=44uK4BJqX$_z#M=z7~h%~7vVv=56$mtczPL=Fm$#{`^qUn&O)R^!uY#se!ah^ zZW|BzWWQ>i0o&8SR=hykNkYKrvnulsu)yFe9E5TnSm)m(7KnaR{WO&T(;+n=h{zet zng<E)0jwRy_c9*Nd4517o+|_n1-!7i)Nb5Y0U{oBuX{aQ%Rl#N@Gs^i4pT`MU|@-( z3s?&$<OukVpD1v7tWB`zouDgn<J&!0ewXNy!r*&^xCQcuc`YOm-n$c7J1B+Wf8e$4 z1S&jKX8EpPx*dGXsBct`-!kC4Uix>1jFlUwUjZAlf?u!+F4#@(dWR0bUmQ3o`x52) zxXS<W*oGNGz6-wiL4*(K33PtZL^|T3;$IQs3JqFE<+tX$$mgK6chKvO0pZ<W5H0A1 zdl&baxi4^6&7T`$z6hU|S#i7h?Z|ln)``t~%X8@QMc?OhMbCeX60l<c2OwYH9cz?q ze82|M9pb*iiSU`I>FZw*Kg~gX&i#55aItM}Z+3%96qts6aT&Ze*W9N@AA<;I2A<f~ z*c{2YvI2Cki+`$he6;cJ<r}YCVC7gRny<4;LwGe69zkho+qrW1ks#E8+t7FercZ*x zsP~U@YU2pVnC3T@gaGW(WPdk-&J<mg85y>S>O1=PK>i!xf24B$&k!<uL6;6;JQP8- z$P*JpHU0ZbT$gQjrSfwyDYunfdME4|6ras?$QcK?$(f0`hqQ-r=zgnKobqlrEt{`d z2~ANa7HRMi_Ge1bf<{qo!olor6@83(%h!wrNqT|4ec7bFduNpKvn$r+UYbP9Y>6g@ zwD)Jf`zJrm50rb~8ugcq78XM+eChV3!u6$NIJ0*j=E@#s#&GrzlJ=dzXk615AnKO% z0tChD3l}P3jzTq-NQzgz)|GBalnqIg*1B^S1ACCU@YWg9ZjF$e4N|ZLw9$n$ri-#o zX2xNb+=<`GA6`8hJP?sH7MBU#kAcST4xmoHes=Zh!Iw)b1rmpDAQuM2n*zh~#a7%^ zaw4cYSr{t^u0dThHLrS>3jy{c$}r4^M#)|bFo9zW8o*vu<BlBsiZBye!&q_EA+Aay zfaEW{wYYaki}l0e%-TJYp*aaQ^kyjcQkT_)l^nT4%dVt%mjpMVHtu#(Qu_l(tW~ad ze$=K0Wknu(eiKD++X(~nx%;d<EU-<DE&}S(5`Lc$)DB26Rv%Gd)qYdSh^`Jy|7wy^ z{rTNa*j6MV?<f(uzs-e5?nLdl=I9=?DL?sLBckxrylTW{+I_7dmm>zNsIJV7(&}ns zV7n2gxpxUl(PdVNQ4VGMF4gS|Y9^|A7jbFo>Z4-3-dDV_;0sv3=A>%pe~+0jE!<^? z^Y6kE9gjs`ue~$P(YAzE<_z+6yHTf&)?|RumbNR22M(}h$&I0R=QtWtp4C?nzYo<> z3vkcSvM?tQ*rhK?r~{4MDw6cpE~;);frbO&K*xq!5MQ>P9BwYQ#RE_lR&~iaj4%pO zy(Db6EUWUtMkaCCH77JbfSFy%<Trj-!VIgAQFL8+(72WfDfLz~FZsb{pA)xo@2Tbk zJ~$fJu>%8W@?J|jneZQ~Ubs07BpY{RkY*IqGNk+<Ca>*3)Lh<#{)1RxLAWk3+=mul zTzdF)$HPmouZ2pERbb}Rottc5+`q92Oc1>oL3wf00LJ}D<Kag>@vgL+COtFQ_gIpe zZX{J5U$(+d9_^E0TuY5OSKs=;>^_1rSt@Vmptj6Bu4JzJIU-Zt&II#pUtvd;u1Zup znW$c1=O<*O@;gewqAY(c`Qxo2^FM3mGw?x~c0KDeo5-Mh20+AKUP)RaVj=FLe&RJL zYQ@wPu0+|5r|6ivYw`kt<y6rtIC?+2hJ;A({dTRY++bYLpp55x0~jlB&3R7S(@#Pe z^=49eb~|**5!ew)2;~W^I;>!7#)d1;i5#&MQ-gJfZUp9YBVqo~#Q>ZBjZ&$<fLg!- zl(?#1A<S$yw9aq+9oM1PbapKBXvPxqQcHH1sbW@HpQR;F*rdyIFiZgr--EWmc0D_a z8{t0I8~u@g1)Iy<lW%!6s{m%C%E$ic!0AV5YXEicu*r1;QhB?#G3z*mPXI7;vra-x z^F{uJ<O1b%KKqi;4|X3#P`^7OZvUva&IzAD0uy`kPw&3G%00HXZ37#qU}ZuCkR`fN zqznCe9p_-!C$|7l4)1mt)w2=3yVEEOw-+TtR$&juibpOL1?P$$3&4lGz(<yaX3y=o z4yDc$Iq|Ar73yK#0*AE^y#1AkYm>2~a9<oUj-UyWxt1zc3CuK#wTSd@2Nfk1@RHWc zt2?l|EJ|e^rS)ktJWvR5Blfn%+{V3OBlLi=8drc4Vez2Ox&+7hkB=*u-V8e*g`&to zx(~p$2BhZ49E%5=3{W!}aY|kzwAT~Y3}T&l<SeZ?ft8C;S9_OnTGw6A1No3elEfP~ zIJKt1V-o@>*HM&>hUL-Dl)il;V%fybAP^X<Ch!QTLxwTxev39HxOVqDcV0E6^8wR^ z3EDzko-S*=HLFP^#URs4?5-$VlkLDs!M~F}T}F2^QW(v)s>F2O&e)OuNXo1}79`lX zZn-b@UZr;oPiRJM*j<SzPyG%Brcpy`pYHp<zH<jRSuZ5sRaTv!`m+7quc~JfzL%UQ z=rYsIAv)WfN4eN%xw)|o1nxBFg0Bbe0Sr*n*F_!SED7D>)hd&T*|)@7WhM=Iu>&Ua z<y+Q!BgbI)l$Md<lH$&jr2~7dmI#1ua5J3BG}SQTEI-Mvu6`m<lreG3PA;UwH=}5J zi=J+sWXoQcXoGo^K+GF4Nr6o{;J~<iu8(%7c;3ia_aF(DZ@<hPxczyg#X_!c;jv;u z-$85Wt-k<86e-7+L201~!-038Q#K|T{vd@tMx`)Wlv?qQ{LP%0zTvUbp^qy!@<k*< z<SvsDvneK*Dz#oKI0>xPkt!No|Kn?@@7+}5!=o$#3*1>39l%-sk;<E?QRhZ$TJix- zC|N<L;Y2~~`K0hpyYF2AenJ6F8l2$fLwm>ZSIw*%B@Ts$_z&jp5!(>;q{;+6S5mao z9%KYrT$-MUJp-@Z(kSS>;;Xq>XG@GYmDBl5q4Kon(Zc5?cP}I>R`1(YGf++q)D>8b z%Lz!Hrt5lLB4h$m|B=91%nZLjJ^h9$^%#-Am|s_Hzi)8Mj=h+3ioD4<^D)}yUC-mf z*=hNE%i6iolS`L#K2*CfEE_y>GF_ygkD>Q633#cv9on9BUzOWc&ab03ZsVsE&YayQ zr2Z$<ePU&DQ6{ohs58gYU?m8POdGCLQZyQqUsU32)3H8S;Nxhz1hN15x1!~9rqGJq z_uA1h?vtzUc9nrMUWH~}=E+rec>?Y16x#!;pc(Z6Pja!D;BOaACv+;F*{=wAd0!e9 zJfl!_v&|MM!vDqW&--xO2WfRKM!7l8ILEax1N+NcnKG7QdXJ{8adA2>$qFAg$*ulX zTt<(ylK+7%Ud#C-GnpGp$3?E4S=k>im*4>#D7tED4;}%-ozmq-n@_(Uf=4{ikRAbW zf2HjkJgPLM6(<)BfiYs%$ea1Cr1u>}o3$;6$2+p$?(VS{{jL0MYtdA@6FOTDb4ys& zk;l?IXhFX|o}`hGd#_8{nfMB%e?GPEpt_=+S#x0hlN+;tq^Cam+Zu74xhrvFJgdV6 zMVIEN2;lo58&=vRyw0sQ|IjTMKiTz7u^ZwiZ70<cx2Tece*}SPh!tGR{AfyRHleaF zPiC@+5BT3yo97u8HA4ZV<CS4NxM>6vq1!F?y=(R<JH&_OUSJ}w!HPt|MWb|SD1_cr z=kxM=&(5IJc^Qez%AE`JwDFROKkPpX?7$5uwGI}mioEXLqt+&40;mHnh$tiIkDx;r z>R5$=1y&-g2?avD@ctYgG4qBIQlVkz6#M>*8-{Ht=&C46=_7wKi1Mntb+W|dz<0~m z7J6W5+mT8Ij!Stw3YoZV22JkB#G4~eOCG(~>huA&dxv@<eJ}6N;eg>x`9FO}W6Fsa zbFUT@A5_YGqSz-Eg18}#lB*&7$&{z!n3HLJDpSHr7q6N&BZIdO=)eX7(n}L~Y5*BB zGgcw^80iWHgg#n+E+_bCD7seNB7w#g!R#<LYqw`s?Y=No^#XO0VGSEhh`Hne1EM)B zSX%d;O~g;%K`LkqS<g*U&kQCpS?@c`Ub52Ih;zxzW2RSerY&@7_C>`ZdRwt|Bm31j z^?Wno*?6~ng~d^}HI0PWu{wVDxguLL8Wj}LuX3!DW@lI+&rr1*zSvf*jJ~0?Sn-wA z8rJ#HnZk+&84s)OrT0IW?lEzi<;RgA2kZE^jA2T|$5m~`-dvrlPbxwP%<3wO_*7&j zA=5ys(rcxrEa5I%L_Ua(uv#iSuY+*cebS;K_KKGq*RAv|UzH(ZR+6dbs)+2+A)u>m z)p~|T|8#oFu%&w0NfdjFMMH)pp;gJr{4q1j?nX*Cb0V?T)2=}9m!or_^d%{$&x*3C zFQus^@NhCZ&*MonVc!*x;%mAOdUcNw>shvAr~quKGSxA09ad3}4JYG{FAQa}5t$Uz zs01XyzWow5x})NXxHZcjZj*>7<)ms5_UEH7E$Hn6(E!_-#+GH`s_`LvTCk&^{&E;5 zvbX$@!|u+Wh1Scr@8$S7M)%|gx*!?bhMzNzTF~`ethD}9XTM3ybY?S&N@8Sfw!aI@ zox%)7<p<_Gho03QhYgT6N@-k{M>FzAsxFPf$|{pE@7AK)u}mYLBsmdaa97L?)Dp~w zn3$=oi%LhqPcO9FXWYFrd(kjPzb5NOi=z!-hoth4%QoSYB8&jL(xW*DJSU?wA#>)K z>NgGc2**Nb9AdoEhHc7>_duF*5b)J;jrJSyIM;TqAxI;mtLkxPH7mIJ$ahnu#t+Vp zVWXki!~A4Bgu~biqgwY6W9WA@Tv3=kuZtQHV|UM76il`lyz$aP&qH;u?l(TlgO{j( z$s$q%C<C(z``QWq>Am|ZkbWiiXsRu-3W&4_H%r%sP*udbCHqO^gomeROC?h5Sq-an zl*G%hw|pfQSesi%?;6I^RFO#=qn_~Bq?4DjBcG-<GlIFu!qiHU^5UM06Dtkse&FlK zTCbdZRh4Kcz4-x4s*(yayxFY(5=9_ThrO5C{*#^n7ZHgcjXL?})Jc&-4#Q*ESgQ)n zn!ax~P9xFXQh&TTf3`HpNB%@=`BepL^Lm<bhbLfXPB}Trsx6M<qC?wIJFmsWa@D-q zuO@T##Ez%hanSa8;#2wmaYE`?Pbo}SkP*$koWdvo6sJmxjxD-8izn6;8tpO594=j* zx?+7TJ(ZQkQz>#SRz=Y(jm)lkPS+0bcg!$d^u$&zp(UZy4eh>{DGy>3r-+-+Z~U0P zCB9G7=V0^xnbuXAy&Ut~o-^&CGj~qT+-1yk6wTbLow=VY$jxX7Z=ZR%I@9%I<`I0h zTYPqNuc@8vY@hXPzvt{g=<MLh*&&ACLqgARt>4gD%eto75x8G`o%QvJ+2^%>mwvg8 z?Vsy`vqV46zVMuT6*~9&<lGy^++@+*RPEe!``paH-0Z8lxz)M(A9Fiz;qwb~qnl#$ zOM3Im*7L?MFE$;S&x`2w0w}w&UtX+#qLs5&qaPQbY}n_U8p6Lkqf@yVMyR(RJbPLp zln}m0BXhL}0p{U_`EOhwx(oc81%#*<@HkjIWqWwUQ)4?f;DhShU*f3sKeVsU0v2@O zk>nF%c$8sBa~r(%VTt_NG1hT5{m|q~<~E$(P2JZ4)#gC70YJM03e?fSF1na9eRolj zafB4@h<$Z(p~i={p#}dWo_7WSy86ul7x?ZAfky<&bC|9P0N&d)H5|%;0|6FjCLEgS z0!^%#CMv-;8K$e>gc{{89tyjmM8LRD?&m=SyJXlqI0WF=f%c9-3COV(J79VUisnJK z+D*uw!KFRsa7o0n$^-nHBQz;Pflm+d+o5G|NBHF=*k2#Q&l<wdy1=~&Bp3ovmtmXW zgOqFn#o_`FHU|S8bZydphheBk2mRpovhg<t;an3@6{#2MrxL;5ppq6{81wybJHc9A z36$sdqM_Zgntl+lO%s1dQ@?@|m3zC#f7LAsqP;7*xr98?q`oB7Z@k~n(}sJGW~(Tp zA_Y3A-CYS1?=**@o`#D-a;O7wixM}NO;AN@Ht<7Npdky4Ya?sva)_Zb?=XE#;O49Z zp1MDxNNJnyF9LN3c|#lqZIVSTf$SJ4uhGVWj*LPzB-n<NG?n6@+~RQB*pfSCK9Il+ zBqN8COp`m{t{1P){aq`$!&UO(`8z<E%m5w1JX-|Cj{-Ml!s(P?vK-30gh!i%D2}lO zPj>zWf_hIMEge)dC9&rtc*9MBz*r;|gvNNiS)SyNgm+}R1P2~OWnJSPa)AqY!PN+B znhQLoVj5Hqr5(ZedNK+aj;0PHlYJQCw8;8FwX6#EzoO&uaTu*_=&gh7rfY)dTo`@; zg&oJ%M@0pDF*Ju`6up*l<_mX6>B0X()fQq5ufa@bNxKHLyJUDzO6(~r6cJZJb6GDB zi;+!Pf8W7i2?p(C9YoD<#Zn1NBfBS0UN%|a-5Cu6a37NYEjsc@G(x1jGTXCx^3C99 zi*XteKm=?<ha{k~pN0C;4#r7*;SIyHwpdS6g7v(D43s}Dn1|(=FNq*1hTS~le~YgX zz<GVtsXEn>XP?!zd#q(=qa@h=3hZq?KB}EBbvTd&WX<N~u$l0-JYI}hw6h#)SwF63 zF#es_=Z#kp^x=>D<j8j{$laHlY;>2ENHK#<^0m@DKc6pE$|!H{@|Fb3;9ZD;`I4z& zkbwE(Aw&2P{pjpwmMIs$OM8pmRXgmn$y_jdFpyFH8udw!@dAWmgaprXgMXim7kslB zAQ887|8-0iB3#~^;Rd4qAq*ilh*Xll>LZ+y-ILt9uXn^FSbyjQ^Z1uIl(*LgkGp=` zYe_EP<4@)?ZJU;7vlKiUp?DC!c90#=!Qx$m>)FJb2&o!eH1p#yUwl8Z%kM<uknuN? zuAZQALU^=pNKQx8LI?S|2ZR4mobu-cKZ7uzZQ9e%2?E!6$v2lXU2I&FmYshlpN|Sf z{d`H2tfNWJ-SNDAV*hek94cnxtA)YIrPEk%!(>~bDE~ciRMdw6*78US{8`-hmN>Q( zlH%{bRbHm#mkN)H;2pa(voR$+_4)%c?`Af6-FyS;Ckc0naL9Phf6Rw2{Uy?1p0$%= z5SFyI5wNw<ekavIFo|x*3?Z{9<(2Ujr@~%nxYv1RHP57rvxy5SG#s4Rf%-I;lZ}h% zj7YsYnm~F>d-^ZIyCbGuKd$Ov$|5s~whceWTg(?y^_ES3YZc?R-Qf9i$|sc(#WoIe zEo`({&&0#y4rMSSo;Y^!`}jafciC1)mrnjX>9etMaws*2kN|WiyH>+@$HOOvSzl9G zC)rW87Zl>}SfRdrrcFZ6-<?SWkc5{s!~4w!hRvq7D};S0yApO*72KsRTNH;nkN>lv z&*rAUpWoW1b;C(rndMwK(7`xEMjDvI&3~K;+nYY9m!32%7T-}Ptng$9c6XHtV7}|2 zM(#rW$WHetj5*)<+em;UbatO@6pfP_koTvYeTK?qyca{ob5<wU&Mj^@(zoq!lE-Ow zyi717_YMEA#8jUR<R}t2zY%+NE#%JbkT@^dSTO13rJuLESRF`I;t~M<-=*@woV^B# z>%2|HVUB`rfkxz4r6+|4yiXU}a?m|Kk(hsxJfxV#iN~m=R=t9K7Cyk=dm<PvPvX4I zBiwAF7^UHQ!=1XI1Mu#q<FM+lx^?2fL0}EQhD834RNfl<aZ7WyBXR9TQ}kD9O2S3I zy&BLVT)pQdfUhKNEXQ(32?&{!elJA0NxSd}WUOL<M$O_<k<OUr10J`0e(2?34qP>O z(BS?5N#%O$lda(|Z_X7<16o&r3?e%RCr`VGdna$1U991&^iyqO{eT*9%{fpj_rt`( z587Ra!2NYU#3Jd#UVJ>n=>L|=4=1E*xTA{h-HPA&XB~im8e#waA)y^jJwZ*s{O={i zVu94LlL4uNQXXkmr=F@cgfL#EAU2l;0TbeGWI{g6P$5$xt?H`f3$D+uRNl3PA%5n% zkFmgKL|bAk0R>374?{dsQ8poB06~7`7_m&aP?lIKU#diOGDE&n^YGmkJDl?#LNPNJ zp2*GK3CuE5F1>SvcEm`q6yj7Gdq2`k`xlrYsMas0gVn7eK%bEr>w{N`S0*>n+E>90 zMIf5oKWkxOW)vFk0O_tF2Gk|KmvuVP;ZpS2<Ck(>WtQ=W<LVGnR((yw{V2;1BPc+3 zw+IZY1z>~2i3}JLP=bjkg3i|~s-DKDWhgu~ug7PNoB!2y95ZjQ;?F*CR8A>0`Qm*@ zB^`O93}iKCnH;>gYSDk~-uto}&cwDQdqtZniZyunH}GrB+?-(>fBPxZre3|)bPwL* zm4CFR#l6|v7w-$0{3Vxn0d$4(dW-ag%nuX8p<1^(`PH?~X~0li)QO;M**$ZK@x+}G zqiChJBPRx5$?iCx9P)tKqq;{?pS};6T@5nT9k;&W-9mg;5w834Q_Is@FTJJuHT<`O zN+=8N`nynTy!!W;2>-*LNf9Ayor*w+dI*l#1aR|=hwGA@^^VM(HJA^#cN*(Y`!gq} z27l$tk$t2vfwa7Ys}YL)JFA#t`Nw#s^??7|U2RM+K+f}->uN%zM?ili<^U+*?-F(X zMwjtNsrRh7k1bDsG+4ODr{|AZUt0pr_kMnm(uTB`EIMGaC*V%_br***wOpgZYwP2V zhs?@boX-E}%j?Jjb3RL0Vm^sIcH|tjdD1#&_VAGNEn+_3hKYxsqw3)`;d8>pqdUDx zubv#j1m1QwY*y*!+xzS^%#`apu_<mQ4)qeKuxm+{&oag5;C_<*4|FAht4b^B$jFhR zJ1_1%uhFzn(&c!mik02rTM&DSA2#lHm4LlyX0GhDG8qi&lVz?%%1j9my#kSf=bCXp zDFGI}eY<W4Rw9AS5W}A;TC}Ie+Ww*;_-Xv!T#G$*+x>@zH}(ON7@&Sxe(%d+1*5s% zU7j)9aHDF_D6ao3tVbN+Y<4pv1XQZV7)v5<J*>Jz@>_Kx+9?Gr&6Udhn}ibLS8|r& zUx-wvs@;2(1^TX<5+(VslIok=c@uSX-5+>liADXBthy@6*4CFpN<qk-6OA;98)Npu zXxfFr1&e)gRwz+n+M~~6HDYNUeQLXL!Qds0ivbI8?Lju^@VD26*8zKQU#rhE@pkzQ zDLZrK`)3IUt(@8Q)2z>J*UholcRx8sCnS=1f~M{V`1lal1CJ7w-%E%zy!e}9!<3L) zDbVSKA95jP8pT9P-l%(F{94{N(XFj2R&B_qBg{3cs!uK^hO`hCdfn{Wq7Xe52CS3O zCr}EUwr(`Ak)LyB!QyQ0)PDS$m^l+iS1%~E(7up{v0rkEHPz$c2Rrg|wcG2R&o=m` z@Hv_aLIfizmPfEb?6lP$34aQzZ*t(~hLMn;Y4D`lO$)H%$BvVDp(=ZStv#paUyx&b z6U^gV!<&a+JrzvMP`V8^pc~d=H!xslhdj>F++FHhz`UFB*HbjoQj&^sk0usKu}tu< zagSUWx+g2M9qKF(@BgSC<$h!O+P@#T{%uh0ob_Zcc1fIGqNx_N`6>Xyy^RpQZZS4K zP4BS86gUkl+*M$Npi;E*3!{m5?oGdUyL*3G194~zMrl&s!qE*g;*)!31o?3L`ij_2 z!igi#SK}S253rF3$1yzLyIorkzsST=m4dL#;{80RnvE;iFSTMx_hWC(hY1Vr56(Wi zB1ObYBX5l<G{cS|vQBSW{7vlWle==oxQxin&4)zqu&wP*eS1v$mI#x34=@g<5;HYd z7exm6x+Bp+IX;pu@~yw|9J)qGRgY#rLupw3Kmx;6cdVCs`2zyIWSOs2wCC~I0KP3y zAme-Lu>U{pk{vH>1aI7#`b@O!r=iM)j4uX{d<O7W0vpugCvi`C3}#>Bn%TEBCv+HF z)(Qdq>+(9<EK*VU4F#MU)>LXqwYkK%z;AjqLlh=&dsV0D{gE3(EO#3_ok72xO{EZx zFLsYFoZ$mJZLMDAzte3D){LH+?fqYDy?HoPfBg4<m@x}8V?x<AA$v91_hyW2MU!Mp znj~A6AqkOT?7QsySd!f+*=ei^WwZ!ML$-t{ic;?Re1G?K-`DSV{r)@G{Bf?i=A1e2 z^L)Kuug9a2tHkIN=UvoofaG55Zmi&XV(mKrpA#FEhn+8+O-~IpV6H108LB%hU%r-u zSwzRkCe*Ea-M%M<H9r^%x*~TWgX}adbp1}to4SoVuH_=@08}%=D|IV*L2Pl-2%oie zBc9#7|L>m$1J0N1dDNN3Bivv0IPZZUv~vy>rfISYNepNrh{~~Rm5Gf$Nh|1iiG#q# zo0@3fK+vhzNK=jBv>ORC!V4$E_UOnWzFZJv=5V9d=<WI+h5UwMN8Xz}n;ZI3!r!%G zbVmDidj0l8m98%qVcKuYPVQ7)>RPparakebey8qs*H^~_?a98AKO57#)?Ci$OuwoB z`IK!c_YTvU`F!$M+ncV9fM+_hKk9#V{pk93|3HTYI<?!w-@O@qMt7dSVRt~Kdn-9i zcR}jZ-iu4!-?N_SE*+>e?7h6*{iEnWcZG23_jr2ucEuUJ)k_V(-#zKxsSndzyK(Bz z)SK>~&Cm2UZa4h-_@nz*_krFf_0;|x|Fhk}Gy31t8}=7fp6$H~)8E!G<Kz|kI7NBR zxl?vc@GA)CERf0=89@hH`iD!N+J$k!9)qZ{N`GKM;lgw@=O%ymKG$gqK7a{i!JPha z;Q;|L4o->#*rEUT$B$s5AzGU8FD`QTFosb63D3MXr-lK*c>7ce*MB|x3?LW-bmBPs z^SH|qKn@2S0HkaUg*Pdjn&5xp5=Yq5---e5Xxtld%&krgUWfx<OEZ(>G;roHcnk2N z>?8quJoBI!?P!RU#&J5aSXuyBGBU1lfM>cGugU;f&Aozi{+c@by9xjtO6&u}(e0n0 ze)b%eBvJK9u%sc_5C>9ah-pU(E?wo6h=dgNi%S}UD8=A~V|Y&z7boRdg&~-T!5dP* z%94NpOX9wR*pZ`L8`mU{%z`Spq-FY#dmNREE|p7`l+P-aFOpQKC{?JJRBSF)?3Pp- zELD0Xd19jU#H{4WrBb#f_|(tRQ~xBfkTNVv>hzJa(-Kn3GG)pqrBu|*RP?1(jmlIl zq|~g-)EuSMUCPwGr8EM{H111jMwe+OOKD}5X%$InSCnbjOX)P1>2yo!4wmV@lG2+v zDASvj(qAgm-;g@<v+T@2DIA2&Dw4(@DaT7l8_1L!oRlW0mlO1*4UNhTEu_y{m!EZX z{@MhpxbAEi0c!9qH<$<TZ`nnqa^cu(W0}$hP8?2XFe-M^uu2*)(Srw4&(BI*EPWOQ zaOw-?22Ruq5NFz9uqh|Q2y*<)PaIV8_$Bp+mr%I~z2i9V@}autTDy5xMe}6VOmHOO zg3F>j<kc6-qP~4%Xt}9&>P@+N0EngFV;P7c014oPH#uasIh%yR*G(eqv&!J;eg{r~ zpUeRm;^lPvW!@U;V!*_o$G;zUIi`9HZvs*SaJr*?_yP(V6KN*`?tXDF&~)N3pjvUG zs7Tb`&@s6}J+=Zb7Xd#4*2~BwFvBIp`d!<(+>PFAGp@L2IX3tkYB%*g6n<#f+IMQM zPl?RJkM<bYifM>Fv`Yj5bb^6fpV!Z&Z;dWz*Q5nEIhrzhPq!N7ImiZ7OI-6bJg?q= z(O}GplOn+k7wWtqzefGxZy?u%M>7HRD3{|lA*giLrk+bH2c(f&p({sl;$%o<7#vK3 zbgX3XIe6|`BkhHyumDFrIWW1z(9RRoaPbkD8-#~(q7Q>zIDtbZB?hrn|KS1Qt1Amh zi&(Z9Z<L@*its9p3Xq6bTH}fAmPsrsJzWX9Vb>?d3O_w`(5F*SU}r*A-Icvo;9}6p zA-aI`dF!02TznkB**jX|-8k_5RPvEXN+XxN=Twddr>H<bwwxf;E~`$bGH<$XT}IxS zsJzKZxywn39T<?yki&2Hs=^2-(2+{1$UrvAC$$Fw0Ed}hw*DF%%zRP9f>oX6t|ZC> zZ~F?57z&FU+E4f78B~A&+lNQI#c!Uq8qT-tKZFliFpM=2779n~A3wY;-IKPuE=;gD zFbr<zsz~cIig=-wDBr=P8Xbz1Wh06Y^=s1!TCC{$-$fr_u3Bu-{eHDaB&hpERo4s9 z&BOcvdqCg0=aEItMjF(80n|23RmXiDduJq;cF>n>(Ic?S)Be3kslW}N(Why699U5B zBu(RRyqZcbeoJ4!jZ<|Kxn!F9G_dmbIzbvuvOod;v9RHD`Px;kzAAU6+F4_bkiI)b z9O4DNSA1*NPsp@24{4^#mR8oT?GQA`z1NfA))pW<I(oEy_PM>7b-T$&|DjV+Jw-n~ zS8w)>6%rES;T4yaY!R>8Bu}iS8R&G%y$g^^=452G!Tpa!h8-cCv-g~^mhxXESizQG zN_ZJW_Px)lJ8i%_!3oG7!k^xC#TVco)>GACYqK0mGfs(`CImd&F>FhCFWJ9QKoQYp zCa)H1?B8N3Cy}GMW)(d6_9;ivC+F4=dgY_2%@*~2t*h3gKBu3&vcw()%s?l{L*aam zNT5N<gm?vCznHWF;9Rq!o|HW!uV~UIq#MpMUEAO@r$`7H4D}6;i-!tDYTznu=^k6^ ziMWsj3*DFEwD3<4Ww)IoXnX71>Z4v8h7D}V)jlq04}EQ7siLdS3$18i+nX7EYA}+@ zzG6(7e6m78+|_74G*|@-#+Dxsvd)IZp4VzU<&_Fjr+et(c>nSx`F}BJ_$j9DR*k2h z0?tpiaP_!YDB#H;&CwH9nN+wex%nZbI+qM?@i~hTyDJA)Er<vcA*|14t1%sTe&miF zI)&eN(CsH^&Q$%BFw~(RfV5%eL(}gy*mCk)`I_agg9;u!_4U%j_;`HT;Q#8NW?P^U zNXSclUK2uiQ!#;SA_#1MJ)%*dMO;?zq%r~&?u0kucQ-{^jC9D}au-jho}j8vZi$aX zspN3n4mCZT!k;uNh;9O5pvn$Ir}3<_9ATEl%Ca_=?{S)qQg6<-8u^{|%6&F32=@7Y zi)o|rwD0powuT&5zQJfE+EQV;&__+#_?3x5Y((rGszxMes=17;?232uvv8_D+SF4O z#0P1SIyOX=;0LQ)QRyC6xGO7X)&=|n4D_}iYZZa6wTc47-kaDb&6yy_FYZ!_ZZnJF zDgxjhaS-H<pSszB51s)6`oGq0iHLLp$dGrd2(jI1qIN$=qAEexlb~=Fbh@?wWoenF zrxLKc?B4ab;-N2cg*3bS<jmN(Ryjdpk|3(2(%}9^Zy0n(0n+%9EMpkqJfB2wR`q=~ zj&Y}IP)xCjQ4c@TwX#mLx%BEyeP?cooCkoTAI#~^{;Dy2I)NbX#IcmWO`2JKPSxQC zEdSyz>VUn0TFBbj8>&WOuXo8CXEgg19lUiQCmOGx5NVAhXdrEF?}+{FmGSRY9o@F! z>vQ@ZexXAOepmGJlRH;jRmJ1nf;JZjWmgn$Adt2Zx;cGX+fT>$@7Rou*Lx}e;J)i0 z%yr$KUV|PeIgb=vGUlBs3fIMb(=%(TZ8Xqb69EJoKl(Rc`M^v>r(MYZsjm-`UE}<) zF=e~isFkzR*Ban_P2H=Os#ZYFdEk{BJf(tI$JeS23aR;bG$E&c;6=PIJgG*xtK`TV zc|3XC21b*gJRx^Ps{=QGR7Ys{gVb=mEI)hQp&xyQ8vfbK7oWsqe-YG8YHF_wc!jmx zs<Bl5^qFyoKyO^qL)@v|(P+yU7>aYa7xqAx47zis=&n@1+>OZlQav3#w-ZtuZ7Us( zI(A%7m8&_l8pY!5(+3t!`z(E1+X}E+b}OHIGziRA0{8?{w-%eCaYd;@rZa6`JZr%H zr-48F`A3K}5&<J|AJQ~tv$XDhysY5Zw)-*2QcE@xo6@>!M;MUT{E+KycA`&<81(U> zsn(2Vv}E669yRMizXtfjF<npw!O`;D&P=F_@DO*i`s^FD7B;N^_yviaytLUy(5>lk zU0XsrsOWt9dnW~gF5N}sRPfi!)VR-AHTwHRuy^OfZRU@FAu)KJ975=i-B=Q6_8-Vy z)-ifMMNBDRK6r06E$G7u7f~iPK-5wF_6t$-J}uAk+I;PM{#0EwLDY6hnpZ-C)u6}f zU7T*Cr^l)fQ3cn`=*!}=Xm8glZ5?KCQ_b@PnGV)dB_MH3)!}PPLfkoe1iq>5)9Hgm z<<X$_1lYENmYu_&87_3-9S>Q|Zf8nt=TXNIr>$olFvrU-x;fNR!J<!+VmZX%o=4DY zA;EH1wMo1ZrR5I&Pli;<5kJ|4X0{~KYIk<v)}VJt?0Jw78Z6_Pd-H()LBdhCOgAp$ zl`yGj@XdZGG2Ha4?n#$sJca`qST!~x*~MO5&vPpv`sxL{6uaF@@&K4-=!pu4au5ZX z$noyEQ@@B7pbP4FRAGkugNH@p9ez(-an!>8I(aRGoyf6RIV$(WBT=wVMd*_FJ^TVS z0HSMT8-BK&AYa~xtt6bH5pK_gE(f6v)*|vk`-O<%{4gIwlN~(qzKs0A{iV1*WS@nK zDmBrkUxnQiZEc7c#Ua?kIhFqqIk>WET&df?#nUaRhE@%}zm1h#&J0m?!GQ)!Aa$ia z6`bgn;)+B@H{P)4@LKtr)a=uD&U*d@dM4D4SsycSr9nR$A4vGP(5RY0t@sI&);O5Y z)iN-l>hBW7SXA;vQp<(Nb4`SLS+D|+tGZ~*{SKWy!CB-F5N?+fn@Yk{p@(FwTFF*D zjxQmDoOA?59aui%^0qbYhH=VKe6)bp18388*^3ocZ4drGrt(oOIIb;nYG_UgvPBYC z%>oR^A7Bp|6l=3h<=UAZm)V6amv`-%2e)h*uJx>Lt6=$nvo|>qAGjz2l&iOp({P<^ z@2eemx0c>@Wcyru=3jMK=}0T4yXG|o>1jjWy7oNfm~obFuHVg(?Dc3Jxk{RR#Ln+7 z>BUz^j6;D`WXN0e?OX2~uK#B$5AZ6;69!cpp#|)K6aXo<P{n5!#Qk*<l-gP3wLDg0 zoULCNywi?9ETv@q<OFa5+yWAM)Yf?C$MX0in`cFTzj}Q@H{Y5)>A08Y_F?(`v*NI@ zgM(YWCm#J?1u+?*L+6P-T*A_(1(0Kj#9p|3Ewh(xDkt{+XDaXG#Un2EA2L-M@8`dG z{^G!4JJ0a}!Rv_^2Zh~h#|K4y4@NIO7Y|w+e||I^VL5axPU-cKRN8sV7sqowUz<j0 zio)`t#kH@86&su4vW>WvWk*i+ATFIxv1sc<0`<8S1$PEL-@MeQD<H({S_#LZ0Q&V9 zGtIrVHy0#(VxjqG;3wWPg};Isal}eu^h?6ABr8kwd%SUpp6pAjH|B>&D<tm1;vc-Z zXnNw#ne%7DqcI*>wRi7qt{2u_rWVD&o4DeeRG04%wEoVfyGUqg<XYT`3EQfn+&h?y z3sXCjt|dv$4}H2hD54Q&!b5Q2@fV1Wdk@maA)O`qe&+VLo=IjPyW=M}yxZJnHYmv) z0k|3Z8l(i*3TMrRaSUF@NWDGqji&iCgk@P#!V*vIBi6JAAwZG)<a~nK+2LI0^8U%s zDStx9dDZ~KwTK_a30=svd-Xt!RNlD2b2pg-_n>*+%Wk<a#rd{K>~$v9xhU>ro=GB1 zxs-M*$$R>XSeiOaIG{6VdbQ@Z*m3dNwhjA%N~qHfntj*F4{L|MU|cYnW8NRuxi3RX zkr7sxf3A0IsWXM7VVt0R|D0D>HhXxTrNnOy$vA8cOx<=8X9%Y_eE(5IiYfG3D{}bp z^7^flVjNn$SGOm&tpc~-Tr955AHC%Bai>9yxv(?kUYr21+dQ66O$UAJQs6_$l^1)4 zoSNM&Al@$*zb&CZySIEr+LGh<mns|6nAOHHM`;xpz~T=Ye&@Kq#lsi1|6}~<N}ec) z^Z$Y~DmXZRFC4=h0PFzZfQgxu(0Zsaeg)NCQg3ezTFQ)FF#R8JhDV|%{r?Y~ku4)S zRABm~;$^-H*Zj<jC$1K3a0a)y*?-^+4K6dvi>9hKkBDVvg?W$hQHR7HJ1x?m)=V@w z^mrrBP293;bQ>#DJJ-BE*<$x`Fp9_8`)Yf@o4k)TEe-bFVSn#G-Ndn|y;l5+j-#!O zH&XbrIBkbZz_EN;r?0&l4SM4Gl6ETLm2SK0mp2uciU&vApMHH$zcEr|p8s=stPsCE zo7B<b{i!qTRx@q8aqII?y5d2gtpNyyDLq$g(bc~5b@Iur=lbX<I3Uv*b|B~`8M60n zWgs2;tXnVm`_l7g&;$MMKj9yKeEl?5ti81eK;&2yb3NBww{h`URs>XCt}p_vFLynH zU)i>VilG~`&IuWr9E%XYFC-Z&nPoB`hcv(vokg2h<`ag_GB4hIBX4`-zPfebjXPTR zO|GU0b5eSp2r}$feu;mRpB|i7fcJ)BjpP?Ih$rp{0b?iRN|MS8SDYgqJnW{Ew4CIK zX>rHHWiDS$)|!hY=LyNiAD^Ba&$L>qS}u}&QOTdAuPra<5wW@=6Lm9Q_+xIoxcfk$ zr^vKRiIYrwS$T#9n|y~h8C-ruTb&XEn0A$Jv`LPjDX97P-D71|xd&utzEq<-<)wN~ zv0olm+P5oa3sk~@qLL%Gl)?i!?W^MaJ*sX!d8t2w3A|<T&H#~+6sz#$mF4QKhWGM9 zoR1FC1J~MCL}bH@UuB9cHCG3Z)Kt|+<X=a;Gs^6DGM1UDt9E$YzSepDK5MQ+v7%<P zH$L}+_k(W|qh2nxmWgfyI`-$ClHZo<xVH!kt~S(vlUV^nMzmYy`;=Ptt-$x4zSO5& zHCtP3$;vwaEr)LLG!C~b<H8Awb(DJ)#h31|?FKox%>{~#cgq>EvZ=GYt)y^kWkT2K zd_$A=SEZ|W4YKqWrV>l*0><1xWa+6}g7Pg>{@GW5-UZnxY<52Se&BT#K9Fh<HKFHi zpVMZ|24~=~ycvrx&-sKX^sA-|Yvl+`pK#`pBfn}hE{xgG$}736@q0x&)6sI7GZP^* z=w*~-zg89Jf>nlee)sPmuj}0X#<=TDS`2fQ{WJ0U$WggSfI%*f{{GR%VEfIPgR48t z4jY4?Q#TH3pAEa(f7{JocfxH@-^_M^(z(9ffA>;vcJ<D^u}{*&LaYm_kUyUr&cOCS zv;*)i$3G5w7^g0Y6Ews)5XOdaN$34-&#L}?kw`i&gom5>>VtB65qwR_-(q*V`ATbi zd1(w|T}-%nTWS>6^EwX)tM?(D8LeJ^40WTjPtXDrEdi9G4q_$=7IpxqNhAfDVM4Ib zx_I`aKrFkT!4M#l;%v{)^OZ~*ibys}om(sY)(+#~5!*T=As36jCP%<L-i-0`ED@ax z9MJ5ghw@=KpgOzpN@BEVwe1Wz^u=SS;Zmx&UG{CsH<UY>UsF^4EhM=l%S=uVI4pXU zA6J8`<cL3ZkkCSaC9uPNIm*(9G#3jk?SwAHD`(Vq@{Kx~j_8P2aG-`Bf^@3{Ok7?+ zNCdlJd8<sXb3WlXHhBYT><b2=Z>L2jR{W9N6X=(I{h&+N)Y<5vCduh#mTfvtlh<^_ zR`~(AYz4z9f{O?s;W-3a%P|j4$AYKdc)T*L;IN_`0EhR>_{uN?JR+o*{i+*9F!M?S zega2;#XQ%6+mf6W3E;xiOBE*O8Y>4gQ^;0jJjf~&<LZ}?K-$rPNxU|d1O>rv6~!Mq zV(M!4CO4YG8C+h8aU@YLve8bTtE-4HW>(ey9NfgsJ}DDck`bw-l9*I&b%`&<*ZDIW zI>IiUk0-hm5F`LMW7|HFlz@I}?Ty1V_G2E_kE`F+dFp+&S~jzZ4*e|3Mq3;AZy^Cy zsz4Futjgo9oX&|IdhFTvR|Pweo`_~q0Bx+<dkp2PY9zJ*Gj`G#nbNcSDH?Ls)7AK# zy}Px#^rI7X9yTM>6YbXJd7*WluK6eZ4q*Mw%@6Cm?{++T@msyQ6IoA&M_%z0dfy5R zt&_7y96s;=Y<rnh?|(S`{i^ld_Q{vtmlno(H-cL_SbysS`_9d7<+XIK=rsht8JXQ_ zZ|P#as}Cu&f}9F0>HhW9CzON!>0fa8vxA*e6sQu56S~U)8_~o0M_F7twmoQx%@Enn zV|CpIH3LJNQKu0Up1b{hAdW_y;mq~A=*fO5Bj30)wN88;tpiw>#>5M{p9L=M4ko!9 z>rHP>gp=+(*VTun+)ca;thGuQNGJlYj-^WR*bV7O#HMpeT8CqUhRsom8FxmVrBc*h zSbHmHKkRfqE!8G|CF^@mrh|);sNF%`@IYfh;h!08(A`&oj^4g0Bd+?(dt-ecZx{a+ zbH$0~H3e9x`t!bYo3Ln>ivQ<TCY!XPWBhwO<CVYbaU^j5z1<tylBWmMa?0|G`rAtD z^~y^xSFJmKzoREVtu>AKV)r4q{Au^o`nxZ`I+jVlFF0aSA8NklBzkY6M!)$nKXgrp zU6>#AXnqu`=;=!MGd=k#ARtW#?S1RdhY}I>*5@Z4x?jkjS=l)8^s?lJe@DK;%+K3? zJbyQWPc6TmXm08L_3~SPW|`PuR4W5&u^G`~{e-60+AH{KGg`-?Wc_|?zpTa9KxCOn zT9kjcqJ{6(nE*`BQtMDsB9H&VXEC9JZ`*^$Cw+%F0THE?J!8yQl#{c=k|vb$+(-Xg z!E;@)S+vRH(39W0`K~T}CqXrV*&k)kJ0HIcXz%?Kj;y-!clB^g`$L=Lo%(x!zmj-6 zCZAjUe4PJx&Fw<R^!uWK`X^nJhr&8$mQOBwWB)d9SNv&76205yD*EKz&p$0U#?yRf zF0VW~qT6(DoM+(CJ>le(&IQ>ELDl%~?+deBW)>$91^`Yd$4Bim2R1k*QtDMCl<|?^ z<9VJ|B30ws)gbyUiB?P%DazJstUCm;?gu>v8ltechI`kpeE#$%r++zWD}Me_uyAC| zKa*;XDT_dfZCV2t(DW_D{E?&dXF25q@rs_m;p{cio9!TMKlAlsh|spHP%L)%fSajN z{8u3BpIP)N^i2TsZ~AT+XHRJV`$MC~yroRY?t6zWAQZV9D&Y&eEE@*GbID!|!;C}r z(7a1@iogU<0qfABG4z8g<>*BUryP0@0EB+|NSIu2bd8W&Iy9<5<=XWFXvkB6H%1t6 zxuq~R#z8KSD!Y5=dnz)ng&Np=Um-2REYJ<7>0~GuW+8{RdLMp4^Ez4%Z73JQsTpRq za%hTyOv{Y4le?M(<;%lGUYfk_?BaJdAo{iuinV#D_jza@>rm=Ll$}gW;F6yt2TU>? zwUcUhKh_nvd-p2_oiOD5^?;6|XrjNO{bOQXX*Z)4Y~u3NQJjaUd9fY@W4@f-xN_V0 ziop2FocQY2_}a<%`rUZC+~FdjgeKbrsY6%F+!B67MYYRao1Hk6HkoicE1@^`YTFJn z)FyHCaLlmD^|)UNFIyclgk1WClAdJRziG9}T@08AB<E$`&7Dl@xNOI)4E~7rn>V>~ zQZDY%ai1@mSKv@!D(A|9b@I2$EA2$y(BpP9fhi47QA<oDT*EGAIi=}otidnjfqDW& z-XZ;PJkriy$cDESgEo>yA%xSa-ywH!9+>wjB5ig(a{k9&Tv?$7AGLYV6ouGeZ!J|l zsDBz!gSMN3rPpO9Jvy*XQg5?+q@J$bmR@rinU|S}3$hi518cbGIopi#<EYDn84Uvo z#3}pGI~kWuGcQyj3j#A^T`~cZ|IMLHC#@`JyDXQWEVtY&kG3q&sVwikEV6L6pH{ZN zU3NfFc3^IHa9eiBRQCP7Y>IGBgjP<ZT~2gRPHb*Yd|OW9R8I0<PO5P31FhT)yWFgx z+??Fpytdo|HaKH1mnNK7s+Cu6msb&#SDBkv-IiB7l~=!)M;Fe2td-wnm){(e-<q4> z-j?4vmEXOW&k!!?)hg(>D;Nwa7|JaeZYvm_DtNV5z!WZgtyTEeu5co#a5A@Wx~*_# zs&IC%kR@C+f1p*gU{|yhRJ4*?wAxm*HdVB-SF|Zy{9UVf+phR$Q1NbV@$a_c{i))A zd&PhVjZ>Qjwx>aYX|OyRcRLL+O+)>rp+!pgv`Yl+OO6DW2<4TCw3moYmq`3B!HASf zYL`mem&yc}%H@?Rw3jMPm!AAxiWMnS)-F@EFH;XL)66T=ZZFfFF4O;Ah7&0_&@MN$ zFE<J<H_0nEYcD@PUC!pr5=9<bYCp8He`p>2&^GU(efvX)>4%QLACg2WoU|*P?JHb@ zE8OxbJlZQfrz^ZY?gVERxuC5vdldn{J(}O~F2WJtv=FyRMQr>@HxqSdrO=7O-2eq% zQ!caR_Jw_b`$8`2D-K0^QMd*GUp9Gj;)~9>7aG}AVGf~z|C^db0RZ>~VuMfrcWR>l zKdH%Kh+fk7|4L0WLl?`yaPbpHZs=nML;o8$cziJBq-e5|@PDa^jT>aArvGq*r!8rK zl>rrwPgl4)yj}W&hRic7G<*6#xIvG<RlveT1NgWu*E#FC$>NJ6)mKNF+1_FD(PS1t z`Y$#8nE!aMrNQx;KXQqSlD!!lLDdqI$qC$I494;(COg=WST920SM&?^{P3e$gb&A8 za#fd^c|5@;qAj)Wi+OEZ{=*Hfe`wXn0xmkSHfA}){w(Q<X##USak7H2h_)X~FF6d0 zHyncRtWG?+@#%ioy`P_ZdJ+zx7W(^vKNiPoE{sWZ1x4`sT?<`TY2N>{`(J7blZ-w1 zpVS0C;>HSx9dYZ8;3;L$s4}=o7L}cvu15-5x|KwVIIYY@%VjXHfKc1d-`eTFaG8%+ zYF;TNaJROK1`Z>Q%X~+6tZyX0{<88ptYhm4Db;|}-8l^}6St6dPQ9u;9YZ1+AP$w1 z7Bg*Ksur^x0=_I}+caZ9FdkLfe1dk#<eOZ#cA*>j<l$u)pwlXJ6@Qm6V;OhPI%XLU z<<oMG;Ji=a2#??kCP8^4zO0m`8hLPn09D+z0*$J+bdaah>X%2fXtT>f{p*!8iQQjJ zR}&Z1p0B3Gi5$qUq&IQO$B0>|!oSuNCF3}N6IQ}s=>2>j^0@#9g;le>Rp+J0Oe4kh zCZ&%-vgC2$Wrbq+)mtB%!2@RHtz0tpy-=%t3{^~7OnapR$Wz3mA&=bp*5w!vXK+am z8lN!p$de~OlJoujtp_GsOU7%y&QT~v8jo)Fe>(lVJbZcZo^Kj13)3gMuHV+!xyh;d zkiJ_{po~CZI>^SZ!pHL&Cx!R@ZrRS%{&*#@o?90%En!@kJbLKk=etH%YJKZOROEf& zLfaVVVaeN`YA-sJ?Hh(2J}8!Qp><iO#sms?YVocO&MH%$Ey#5q2>{!CUlZbW_s-<W zU-Ubsq6c1g+K!KDpMoHUw)#3ZxgC{L#R_J2KHHX#-lU%}R%`iy%B>?#bMYtcEz`ce z_q<=f@uele;OO7mRqy}071egQ?0<lU@i-bl&4!2(b1_bO-Yf&i9=<H~wwD3ViGE<o z_eh{bJ3h~6WB+Wy8K1v9t+}f0Aq}fnTk!hPBQ3i+5_OvM<_FD96lFj;mjBto#`c4S z0HOhX;I23U@qO)BP}T{}BXRVW)J7}bV{dAPreQ-2h&K7S_Hg=BjP>bqQ{rVvo9#QN zr>B$0E$;tF5L`D}Qk`Gqy>>`>0JHz=j3O5u{8Dio#N)(>kxrG=C@4YQ9U>g-dLGh$ z2-SMPDAV73xN0wU=_vb^OTXgyX<x?3Bu(gH=Mfqs-nO&!$djRg6TyuMr2TopN2>9l zH9X?b>il8Zce=1mB1Wxg&h*Icp!T$H^dSD-cz61vHy0DHym}#843-uLc48yB6r7Kp zY96Zi`&?UU`<OpMUXtJHu|}2>UPdFx)I8wz1AtX7Yb-x(8GN1}&;)=PrWn7Nae4!o zGIH`4<9+OUR_o~Tlec$MCu7%>8Hgp+AAxjJh3{!YsxHbY!Wb8Aev_sfOR!w`p>TGa zT4bNh!^d&q*L-j1f6#ra@wDotTo8Z3;=as7*mtOc5|BT+{|=YuYJ6q&dr|vZ?5U_1 z2V?h}&Fz3q3Rn)^5{}NGfeyz)QSC$kJy61Vr_zw?JCo9F#L2Tmfy$(gLsT>5FefU{ zewJZAaPp@SUdWjpGDC;+snSHvvrN-(GAR}QCEnnC(PIDy@1_92b_x?iSKrXsXVT$X zy%<&fwtPd?drO!L?{o}ZXaIO>-=T<pa$|^9L}ep6YR)`2v)0U%R!|il0+GHS$`R;S z^m<r@XNlN^Q@}D=zfHi?3M$>-)f$3!YDin{)}61nrNY&QNrH+;8XunZyfA(fEJnF7 zWUZcks8#8tFlYFv_s`@D9B#G)?QM_qem24HF@C<apL$?rjcI?YXnr5g$8|ttSss;N z)4Q!W9Wi6c*&1m|7Su_5AoQ!%Jxa<idt_!wLYjj!4Ju$#+VxJGUc(<3|2X)H{oCMQ z9V3tH%}xGPX#{Zs4a9JVj~>QrE*c7;GCRW|p4s2iE$aL@Zp*;O?{f_?&w$x)zFd5) z{gc@Yz<R@%M~U=VQu7(N`bnzPJ_$G~1aKsiO=S=ij@x%JM~jY`|MbwhrjGN>Fy8`M z7ATcjRbRWILo&b_eEKuJJLp-mXyLryaPut=W6X?8KC7m&YrQ&TWbqg`e{UgznB5p6 z9tZl}@xD0=JZ#(Sms!?%v(aB`<niKTQUhWM`zLeM<>c+WF5RV5HChM5LW7M3%bt>H zgN9ss08U3=Faj-BJ_g(RK>+Ka4HWyCTw6~{`5&*~K)^V}ecJ$Yb;bC?^lL;(6Ha>F z&HTzVQ+h|W(75i%sXz`nmmve*VLJU1PdR(Jg-X-N{CI#R3JgJ-&YPp<oaf#%Pyt6m zK61%{Ik<-`)CH1Rx30S$8$y_>@s46#ZEsWGPD0MHb=$5%Yr?>HSW9c$$7HYUdo%O1 zPg;7qy!@YZd|(-Av@GJ0r}oRlw-_zmpXa>p=j(g|p5J};r^_eYSa60@zV+GPu8oM= zjycF&K=)#r5B0pR#7Aq*mP5(pBp;pjdnci4;P2cKA^D$S2fvz!c~Rek^6!0Ka}0X6 zg8=*(@XxywDz8o#`Fh**3XTBUOlmix^h}>%cxC@d%|;$e)zB~DlV?@f)XAz#WkMe@ zfw~HgzU22ENAI0%DSGF%krn2!_{peaM6^C2H%x5SBPD41+R3|58bUX`ZT^gmIsR-P z`MVMD>)wnF>TdgUy}2oiPV4SN$zH1WMN<V$G}<qwk}=NTfxr-gYS=9YUT4uoH=`rd zC0|D_6&=gqjafwc{r17$->E&*b+&gd_#OYkPRpwh1LtD&P#E=B($OKg@^<7$p8lTz zV}A?E`6pcN)9!;}-EVW-N%Ms6UGT-f-yZrPD}I#<cI@6i*d5^gha*P_6bNz2PK?Ew zHJw2Na?$$<<B1njOC_dS|KVR<Og!07cwa9_dHpNol}1pJVCc98r9(FK12*V)cF1cR zbWTes1QyOG6b_fW2dWH1ngj{N27zJW$27x1ffT{mpwwkbnry_I<>2^V5!XtBrv)jh zmBI5E)Q~atxh$0vPp!X8Rc;N|mP0Qy5m%Y0k0k0m4QmyH)N|ucbiK{=qiXElTi)a@ z*bKFAjT)iz1d#84fkv;!+%Km<0XkyaIINtASY`(43sKHavY%PVqPtYR-RMuasB<gP z`X=bhu`w;sSb!80q8WL2H##yfHdGTGwi_LOuo6pcjR|y%NY9Cl5~6UH#H7Qh1ty2_ zu^~EJNZ;5<*k`JS3Cc>-dJc#Lh^P)Cd<4z&NjAa072%GCt!PA(Orn=vq2+YMOIq|K z2~|8qg}X+|zK<JjO*|PMg3sZP6N>px49?n>&w|Bs9*Z&)I$sk@oo6B^**cA(C{yF; zbI%jnO}KMXAzQ{_sZ8V|G4Z2Y&});J(ZH15O1`m4{@1p_dv21&fmAb%<VHH8oCRHf z4i6_MWD?=!jD(fv@W4$NW0yOf$oqXau533&Y${D)E>T$cfn;3LsKx{O`xFUb!Fr9L z8347&L@g6h%5A7+GHL;b`g}kOT_@ik!6uJTplr^QD;eUq2|2q5@u5IbFW>+!+T0Xb zMntT$0wv=f$OmQGnxZw@G99Ke9rrRxZJAR-StMapS!}4C-4SJZ^eh?mm4<vvgTKVV zqA0Ki4B{mbwY-VcaL;O(OrLun<--EED8nL2IkBcNleUZ%D3HT~j$paJqEX7iSuXC8 zZ{(uf+j8aI9~9-L<^IYY5Q^Eth8FA{X3JOKZgS@_^ZbcCckOum0azpx@jW%h#S|I7 z85$wa{_;6g8a!Ga8p(v_VW5s!SZ8HwG@Yj(7I{o7UOFi6?Npre|D+~o_n@4(tat8* z=h2k)0}3*a39mPW`Y_=Sn0ajAA)BP#Kt_GUp=itO-vwq=1@|Ep_yI6?N`@aLX9EQD zp=SW}`!{LG1vE;-F4r+A*DnX@v{xu#=203{BD9+OdZqC2ut4x6@+$^WhJpKIA^vo@ zoB})_17`;(e;TL(!&_~G8bI@8ZbH~#!oPbE8xn*aoNP!LkvNzit++MtJ~R$m#{MI~ z3agDXKVS;8-iL_WKfJcZ%U50ae^QgO)`M%mGtup?H~vp*63Lp{<OP^qw$l~<_K!5a z1b=72>w+M%d8JD2rHa2FJs?4b$*6f6avFg7G4dJ?$Xphi#Q-;;^Sd|{3+vB?*jA>7 zZzAY0)I1KAsa3W`Oy7&nwexsXnO9xiUhVAuu;?{cTUN<q?V2Y08sVxK=9l19SJb!E zyhTWQcQEQ39hIET{;<4wDy6x-c67S-)$iJo>RUQM%@j~KF<qM%h+2*-rBs)G{Zbd+ z4)@2vzp^4<lDYCWxv3<G4Oub%cfAfbOg}isp9QtGh2O{AFJmF+iKs_zS(BTo%Qkl$ zDUl6#>tOkG?hg8~FV#6tK2w-<KAlE^D~(6)H45c7igYxJeP|TaL20}|e%gHS9fM>r z5w~`^zY8Xo<B$vhu^50_+PtT+(#Ut9h+3!QPLrPKet4q)=Lt@<$$+QHCm!V2{)CX< zWR~AJw};%?<bJ?-G^0?N$Ey1zQg1~;F5{2{k187sB*l!&9bN9us5i<5`;oa~ri!Vw z)Tg_t>!~q|B-A>cCz=93Zv&5EL5WOW)0KvEqOB1+t&xhYC{bBI`#MBNE6<1QPgvBF z46+={{hPtoKO>^Zup%7yk)XDHI`0b-Z#RJ0GrGqUUot%0THVoJ%bo<&uCtwHAJnYl zV0k!b9<%P#aH*30)6TCQ7nq2@On3twu1w~s!tk`Qz~@+CM>3Zct8(}&@1IT3%4&W? zYQtw+_y-C#V+wKmfXSmL-#tcw<C#2fiFsCX9cv%DYwop@4eB;@o;jJ_d*_OJM{}Jc zA~I@tf020iQh9fnygMwf9lF=wO%z8WYL~&gzX?C5z`I`^9P0j{>fAG-f}Syjy6-hT z@3|vCq(1S-_I|W~O7ZBOjW;_H40%IDl%l!oQ+e)VxNC4cf2WGU)5SFy?)xO@pH!YI z5)To84zkkE$3^~KP1QH$CNg=-=sZF}?Gm~JR-O+w&lQHbp;SJgUSp7Z6hu3P=QoXa zlaAUV@+$8oz55mT0p0kHh+MSh{YFD=(0Dd*$crA8DjnUzL0JRrojX5Kt4ZV*mb+E7 zlGWaE|A4zPpWNX^Y-=X*6cTf&m}VpQjQapBdmmE9gkMdCHgCe2OdebdPX`?lLr0u` zQT6#sLIJ=vhDo!0K|2{Z(Cn#KJcO=)G_Z`}Rb53j(Rg=hs6DjzA`5xO7Ij^|(S9GP zD$l!0=B=S~X9LLZM5O&%!_BD_NB9ukL$vxma+$_<4AqCNcFar<u`PWM=+IXf?ke=y zZyF+>)KM2#Phmn`h#B{Z8Gg($BU73?x@!+Wwo-V4D5?1OJS&3f=QNV%NBReesVL#} zk1S+f(1^%Kbt|pHQNbd%N&0FnYKXzxTZ>wPpw6^*Kf0A`i2!yLkyY-z%?A{opTx(X zNT}g`nkaYHufs!4a}6^L<fbi;4-FbSQ`%Akab-bBIIaumF|SnaaWpcR4TU8^{27%# z#DZPna-Dc+&OYQuLPi6Nr)v{Yk&0@kakntwBP2u&CX;t+xN~oK49C_{!E|n+>RQJs zN!Z9hD%&bOy;-wPN1dCDeFjA>${@SRyiSR{oCx4G26eAC246Y#V~D0K7k@f;l7;SF zC-MHK@C+y+KT>LxC!-H}46vde`jo_I*m<updGp8++1k<;9*Fnm2Y&#vCC1%@gL>fD zWJSo+)OU5c^=GwU8+~Q^+*Npya+4`&H)(jfYhr`Uvwwg|$fT#21LGr<_n%u3DEaiL zu1JjV<c3$0RbYCoHqrtBY0yCTh`ij>K@R(2OcwkGf&r>URwu=Wj7~}AJ_ks5F2x|% zSxA84gG@v~3y@)x)4tkC^uMzLTQSS2NCE)*`4=o3-#fStu@UDkL65z{z=P?~U>fuW z7Lo_#`=r*t^nzq*m$xW0ZAc#ngSaR-q@LZv6F2VFR75p}HwHWY*{h$fdw;&;y}NGg z)6qHGfATB<^@W5SCUb(Y00#@Qo{Bo5RXdc5Xr=M=o^Qd%Rr<%WnwGoF<Wer?J!xRU z(@9}v^yLBC(^(?YFNAj=;QmWT3LTsnsMpIBEm}nTruzq?-e3VP^b(fxwtEEPiG`3b zJXLI_C=0?yrrw}IZlFI~bX7KBU=4Af`-5`msDc>NiC$*veF}74cCm|u_(|sVF8m0# zo4xodDuw}HC!v^MR)#kugIgD`{#(4RzqFQ$^4UjyqwxMrMb5Ci7Fj``DK*cQgR63V zSU8k#Q9LI{uvX2oqRyQSeeNRc<Au~1cnI$=^2=hgsQS7&<gG-Bt~C(H7YiMv67dTN z3-(U!2&RFbqq$4btKL}11rnDzZp)g)bpe3*)1X(o@;0aP8n7=yiRJzBwEjKF84@%c z4a*_I%V;g!FY~(&NZdckJQ=CH?GodCucC4=nKgQ`z|n1``87w>l9R>KmrbOCIm%%s z`llwk{%*Qj{v<#_4&c}hAk-%yUFzPw^7qT`LWw_G9uJTmhdohmF)J@<JXBlcnO0Y0 zx7ybD8r-REZjLXJx?isA1KlU`<^IhpdvlRUT+dFdKCgrDAAnt%?=C$m9%ba^r9z$u z<uLz3tZ-Zw7?9p(rDkUWH$1_?4e3kf;jfG0dXX`f`r}cp|M%RGcW%Gv7tr)-B)M^M zf{uDa;?ie=FVNvTB&1b5dfGVXD-Kyihc8XRf7ZfJjFijRAmS)&@XXI2f{8meh{e<p zt-q+912XR}V_-1viC-l$I45rLSxjRwIthsq_ypFcA&v*Hp4Nv%T-&wAu6olTLJg4a zIw){G+Tw}RTchzW+tpbG8dTV6D}$Sf=|^2(5BUyZU&>jOYeOX8om+TpJNRI+q`cmy zHm!iB`{B4{#rZQM!*M)NoET7~7y1t@VzojnJ)0zPmaQbTtS~Rsj}p1OYE^x?&T$~` z@>lDk`Jp7x`?{-Vf)3_6<cuwrElNL3JiVoEmR@21G*Z6rip?cigYWI3Am%InQWtQ7 z_{kZi4{9C*+=2;jeeyMYKXsbc#PHai@nrQD-kLZ&+f06FUTjpD{?%imF1z|C{KL~* zPZtgrK6YQd6)S2Q%+U4yJQy!B*Yi%UQ8_xf$oxS;qMdc%l%fHQLoMV7LGrMQ*}g*% zVQ9|5+(#j3+tz*RaZY2_%MwGyDV40QthPw`+f$>CnYHTzP}wOLDLM|sYly{j2|Ckp zr=)L@6@A;MT=G4eFY?GYRvwEy*%8Tc+VBv3DpK6*mGD6NbFs3DTpN?Q8_C+Qv4&{T zH;n#*U`EMW{$1rukBWTsdCZGEEeWqxi_8+}rn1EaNd;c*;}Fpx6elS0SS>a=nN{gF zA17P8>!qb#KsJD$0fZMbU9zg8lI=%#=h|fJ$-O*Ds>0>`TAQtsiN~`x`%+Y2SC$^2 z{us@JkpAC=j0$aM`cBFGGm_*=2?&mSeCfg&E;Xx*#!;(1UM9zh1%A`=73t;~hc4#W z7!({fya@|>c+}FU2Xb0)*`$nkq6yc>XNmgoFj;$-RbF`8|Mf-jP{wIvF=o44OjE&w zg(H`Jp50N#`3>#46u84K8u1D-FzF*Q(Uj}3qqX$;IMJfO?Bw9$6+?dQ6?Fege@FZ! zl*%k^2q8;Ly}>+QfN_cw^ApMtu*6nL#$(@J`G(fNkC)-iT&uCF_`Utr?Gi_a6OTjo zwP-DuT-S=AD!`|{R=nFIJafV}Y$H`5LV_TL)W-%@2>W!ppKiSBrv^#KYQ`-ei2HO` z85drT?6j8f%5Zpm<*kQI$67h(_LuyCrS{C^(+{3-jt19hmN^C_{W&pW;W55&IILu= zKTe}FkdUm1viJ<e#M8o~kGrgJn9B<2H$5;8nBq#3(`-vg!A0YZv$Gr@zg_ri#93A7 z!9jZM`TkmrUci)jW?>b4F(@jz2w(ed+4fOTU!tejEeL;^UCB~jU)HrE%!R?zvJ%!z zxr#jRiK&WWXQun30_L<Z-x|H`@Uws)u12C1uL<jDl&QLVGWY3l9RgB&(4T-*8-#7Z zMKgYgUe(5@-S3)11_l%6<5MI4vltM`y?iu4B8sb&*B#S$GOLH%!j0pAzaR%B!%R)N zwCSX`t2Omvmm1?zOTdA&uOV(~5=18G_-ej$vf7OuvwzQ9Hw9C%(MIvA^ip9a?mS=2 z1R|l3Dz?NNR9Ry3yyIYr?J)+lCoYzIr=BuZ2Y+ti^iTF09S+SW=ZkJL^VMFL!1tdV z&2HU}Jf@51&tJ*sC<GwgLp^YTeGU{E3zFTYL6vh@hb6KKRjo?-lB8cKV@sl(ua}}a z<)Vi+2<>T;&-GN=c;$!32lAuFGaeb<R0uNYu$l#{`frtdqo{L75I>_YuS7NEWg9*} zUn;bYj?rNFCOf{xi%wTYYf!9GzTLUupf7Br`cTXKvh|PXPY1EaDl1q)QxhjdFq10E zpg#-diaFOmcdcVB#~9=SM~C3~1)S-O7_K>}AtN18PaiuPcnld1i#)nXs`?Xo{YDO> zPsMu<buDAfa^Eg`fMSP=&+5w)9B?yITYc>9PmqY*CGrOSdSdThO7PYOCr4KpW*xb~ z2LPiQ1-ppz;CW#d##oP;hH!~D68!{>+LP6-3cLiYrm)2tgK0?ff)XuuuSCb}S!2bO zbJuz=Mo6q+BfG?F`G<x3L{+axOAayM_|zW0CA+bs4m~`-XC5I?$BBeWS7|p~@AxjA z$GKo$xSSGk+G>~h_F|)GCcOIM;SSqDb#+Be{&NQ>n1>b9{xMyBQaxpv*q9Z~=%7x+ zQ8|-~yv4Bu(b>vA^Osx6cUY1~M>gFl_8R&VcSaiF)8TvMW@OO*IX=Q9pD$BOCb%o% zoVQRPKcfmF%j7`2Y`zy>AxEop;-M}S1GJ=d<WUnceCBEd8;l(ls$If;vyv(+7S!%2 zRL1Sb0w3L_C0`Pt3KBQDuABB2Ulr>WS==2oe|`4~r{E+5GAOL^ien@#-lV)srAp@K z3#~EhNvz^=wr-Plq`<vQJZ6$hvwy41d6Ft(x0&a8^Yg%W@yP)_c?F<poY!3QI;_8> z?_VUrA$a`Oc@N@A%`qBOg?LQYmDVfFIG|LhI^ZEVvfrUBqHIvWb@-mH;vpIZB<<hN zE2A<f*1OrGP5UfB6N1R@+<P4Rpj132)VE+!*Yz^zj@S&-ka|<z@+Oc1Gu)(}#*V(` z(Qy$Npu1f#lR9Ey#ThcI8KeCmJV~ij7>7URk@#gzq<lD8Y);Pj^fnEo#r+;>l_S_O zdG?ejg`*%?2qZGL$sJgP=OYcBL`G0#gA6#hFTIM;7qkX9SrB=Mnm*!)(|lQCobVh* z|9Esbk3TD${#!57oc!3``|iE6gB4XFpJ?-EX>Vg17$X><#N><`L8w>_@#Ew^_k|{c z+F|jVI#}P>jpHgRLvjS&=415-Zr`2rpr>}DRTjL;ELCxzuwFWmThZo3wdWqR2+_cq z8zFjl<UNYo?IMhzc~c6?BXfB{?low`rKE!xNJAvkCL|q>AuVB?M^Ty4Z@f}@?MX*u z<Qft7D-p1@o6WL2mx`}~dqqF@YMd3;zf*1V*Od2{+?`<Ssag5Y5!V@gnBU9>eD=pD z;EVlFlp|IA(CNJEn(OMTbEvERcnO<7+wpb?LXD5V!PaKJvd7$N+u|7amG6zb_Yn(v zx_Ap$p*}@*ytpun^@3ZaPe{NzlJM_$ty}0MUod@40gUGftRx7FxEJS;OSz2`)MXy{ zCY)SwJ^mhYTt=*GuKU-)?5~?&Ia|&5$etdz?>;`?a&%!crc;yS>IuDj+xhJMEM1<# zST$p<qHyRfHljr<6nbLqWRf>xG2zCaF10tZS#eZ1ehVT<^OJhTG1WPUIVroUn6<j3 zdHs8#EvF<6_I!k2g~qQ6=akbd$B@G@WSsCyIJ`Onex9n$04c+$s&a*nm?IYKq;3fX zC=oZ=dq7gPIC>mim<~2A7P`{2P3@WG=_d0?(dMHAS0W)bhi!wRc+5bWIgl&IA~kH& z3{*N?HY1(Tnlzx=cdB~>1l{=pwa0S4LepuaMxp*nKpyHbq=HTZx7a1yNTu(e?$gxn z)T125qGJyfF`O!?Ann$Z+7!;01pX+ka*4|DSAW8#a5WehNDi059=tW211Zz6Y3%7* zih5O0hCC_es*n=@TGZ9bNWabKr=(OtRn4sN-V06b!m7vPxntzzWBm9J-NbMiz}N%1 zAk85j^yw-K+vqG2)v>%t7dNPgArFTR^!8-;O?tHJMbUeyQTMSiu4bxk2CY=kz$HIT zuhs{;1PxQNf`$;mM_YD*FZmN=&^s6;%#6SSDHeg$IGoT6c}~?i-KN#fpa<bfI8G>A z*ILQ>R*|Yz309Q@^;jC(?Bn!VQP#24kXAjj0ytnI?8j&^7l4vk(G1&|%WZKtLk15L z%2h5Rq-^420$P(WtHPG4RBR=+ou;IXhIn8j4br<;%DMv>s{NKcw-{gze&}slVhDSp zGcblc)L%T*JKbyIo1f~ZDR_Mstr~Gud+5Qx9?jskd_8i0>jSE05Y>VP0<D2nRyf4z zr^SJD8`a^%I?}l{5o-n!QZSHmB|{4X($$RAs*E6@Yi|;>c;lOOaZ#s;@QNoXCdznS z2BZN7wNOfR<%<bmMcV{MxnrW-D-nKfxh3VJ!_tSFj>X&*ioVW@a$!V!^(NQ~Me0kv zbSFm7jDtNip#qKc6{(_DN~GsdR#Zo~3>bQ=GV&@j+7BD!0mOu`aa;aFF@BX0M$U<| zKO{#AN`ONN44yR2FBRUeK|`XPqL(6kf}g5PQqSxP-UPt79G)n6(emc7Bs2VuQaK+v zoNt8?6v-*g2v;znN|^}grjEHiVGuOIe@KQm(+&YSRQa5g-<UWyxlP|K>aV1dWvk%? zhr)$|q@51}mN`6Kl~H%d6;JceFD@_>UJr?g#P~9zgUM7tj>4hI@nkbng9aKb2eEIz z(KnGUtw{kSnZtWZ*RD&N2-W#&W|jy^0dxp&Eu^6`+Jgv{VpWkVAx&uR$V;uRtHd8A za!(tT>@GsW+)<{jWj&(o?k(VmtyG<e?3eEmoQC}3SlWTbCg&L%e-`K*y+2%p!6C<d z{5s)+Av{8h0lK%HlM&IZg^6;FJ#;b$WJQlOgE6mEj$EaI&D^-o?Q)s13Sy>HZVoly zmU{>)sr0tZoVghL@fetk+A6R1F7Y=}xKxe|#JFO{0U<!(W26Qetmww6MvqYERy2n_ zYNJ!n(jY;$(XY-YR>(&S9E<X-jQK3h{l*@WKmXFh4H_6rbryOhxx+oJ+B)qvcqvmn zzWvFm5R2>oi>32$OM(mgFo=Q!a4RApxVN}x#c;21Td9F7H7!@Bt(W26J2fkuQCX>J zSy_p=Gjrvuws2%-R%%vOzWMQe*Y_`+bDeXY^Lw7>z60Sq6X`$Gn1KZ^O?wm-s0_`a ztHahH<+}{!Rv{z)ZBxFhwv|u2c%#A8Z8a+)<Ph_WJ@ag`TUWV}87G}kkYU3S@+E-w zvxWEEuq>l4kv~xxHc=VRw*&Vhz_QEfNnQ7I6ALa;t_IiUJwoU_F@{LLqMWRlt8Nna zD=AIN&PsO9k}2?0pnxn(AniQ`?C;KL*;%U;@bPo3HRf&qjr41m)143k<`pDPWHQzu zE5e!6v60zg06HEFsnW<bs-M%)QMO$IlQwW=XH|yX0#0R&m`Y_vS7jni*`}=^Q$#Nx zczd7lGed3WdM*JaDulu^4G99BDJYzLN1qQWS`av?Sd!EG47xxD2(Uqv$o^Jg13c3Q z0S2ML{s^!q0_-OG#<kzV@{_9YMCPfDvC==)Pja%h^j^K{4}K+`B^8l{9!3ku2@F{W zuQX~_G9P?mRh!*j9EXRn4`(GsWu;Idv6M^?j)-2okjrXdTYRNT=e(8%q}k=x(OAKi z%arkP=h=@<aSWb33%)2;tXyvQ?s`Ual^^!F5Q6eAuuJ9r?~83n(31_OrxoacXc3no zq`SjV-T<~HGcek(4+Jr>#Rt{tLT0N>-7cnU@trO^;gQQMJ3h;nnn9L-XtN^}JjC)L zh!pR8^W5wWt;+uIMo~iXXjQ-X=q|VjDN?+MJ2Hm@kmr7CEUHF2#!<7ZbOO5RDxWTc zm5x|>e9Acp0>o1xDfs!r04+=H2LfPe2PHRQ&chC$8QxJDsSVmY+XGQc8^8J73}q4O zE4|b?S2t(gZP2V}-lsNc_uMl|#Jg+c1Cm6<>Vf*0hT1GM1`tgLB3k)a0#m<BNGFg< z<^uQgslRmXqd;}GJ;H_@=JW62ZXA}*tWbb<hIbdsdPk(FQ`mEs;HHrgtevHDxnS$a zrC}RO56&B_AMaIf=l}ct(ko6@G8OW1Uu2x~0L0<x<iqMDK$cIM#FTI5A>{(7gShcZ zPH?<xwaL-5@mWcn%y?&gw)@yo@Wm_;{o!X^@+aYaoOk8!E)UTep7_J7agd{`!bVu( zr0G{1co2H%h}No*7N22AXjd5r-mT~B5$=&on6OHtJ@*-=>qZY^F363|n93-!<}-D6 zn6}y?ZUm8%754MS^x~#If|Y?#+M8%?;kobV<g*}eL_y-09F@+9<du&%ju4aZSz7Ni z&rr~DoX``_1KP1~6C>ZT5sLRfS;?)X(EygmMrfX#_)EmaJ=L%+5tz|X{+U$Bv!NLE z=yz8XDl~=ZOBq%@tfs?l5;1@hN$Jc7v+1dPFcb(o$d}TZl^|MR^*5NTVWwy@(_}-) z$eEyP#TY7K+T&Q?7D0BYLGAzrDMt}^!nDBN=HJD#on;z0GYkY6${i73%KPW*f$pMn zN{-cMe00Az<>tNyxBaF;mLg67Zfp-r?X8~AJDD0|<@jmg$t_Kk;<>^Q{FD7!1un-h zDlfC!q~7Pexu9yI3rPd8qB(D#(yi_}!{ooU{^yH6`Gq-}nss^=Jd!=fR{wI7+~SuL zLfrzV%}PA{QTN!{gUYn(l)e?2s%6{d3K~ggc~$9G)fzgl3uQgfqrM;$g<d`qa<9Cj z6m72*O&hz#6r5y0vCugDqd|ODiD$&j{$N*v^Pi#V_gBR0A6_Xc{n+WCSn;4bVW>Lb z%>AU*6MZpX(I@q5+wR69GO$`1U&}(9qhdrWyzi-HofrbAaWX7-AhAQ^+q8F=bP6^s zz%eB{N3~BL7L`fR_S84~q_C8r5T3UO03}W!MNVvFp0I+%tX>rN6Wv;sI+_iM->K=X zEe>jg51#?qt}<DNoJ<k1ASPSrDN}TmskOuCGe>TZEFTF~kh1X=sIT0+Sa2tnx9DeE zDTenB(;Gnd*8VsN3wF2KbWQHap6=sdZ=eNa+(i7<VQ-Hv+gA~ut4)PTZ_?py9UcbX zsFu3ATr^(92l*WQDkHbq|ELP&Mgkw47JuW+I2iuzOPmgj`O3prYwqN1z5X~Rij%cr zaC}Sp2bks;_EuPEXA(fkT-@jV@MXFM&0YL5IJ)bb-NjpmwZia^7Xhm2EMPp{-}<No zv!?*7JyfW=%2K+{jN*az96F<-zAZNZ>3)CL;d|@0RZLq#gg^+N_s-odAo^c$lPeos zUJ-YRCgBInf?GeidOgFF14ey4!Di;cjfbVu?k4?AYq%k!_3kJQUm8=Ct7ep|5VUoQ z9TTyEj5v983jak``edRt<S5{0xYSRo?&(**(}Wq$r?OrG<4<4qYyFh-^?r5;^p=6V zk9=%ZdUWcwC)X(+*xFCnbX*7MXdVhAoGvygOc;khXkihG?^y3pqsSDur>XW4LNLiV z&%JE}e4O`F&`XO=-#hkR$kK{{T!mQ3tC_op>!N9N+bdFwr#2M-{H^oa+P#zY-#6*7 zw>L8CEM+*S#T#El?j??c=l@|%aDE&=0At?GOrex-{<zYjc-q~!ZPx0;tWk06!7LBN zpLWZ)+GZa<VE!idWL_6}@j#UAC5jQ!iZ_!M-n{_Qwn`^((oJ_5x*M#)mk-!^cgXKS zzEvz+?T@HgAx}uQfzbW(L=gbJ$(xheM(U3~bSGOz%Qatw{cpS1v#|`@|HBR9`b*?~ ze!kT0RZ}i@d~U14jW!}GmUr!zvUTG8yoXwc$%>oD=Z+lxm~HLJM%RlbackQ;(;V+> z-nU}D>&~<sz90JXo=3<nU??QM?BXrum$lYSxq5@Q-c(0_h`({`c)+m-t^-3EpZv!H zDlZJPU+O__pBUPEbo_zIiS-@h<y#+mn!@hu&}U^kXPcH%ZgWCA7shC3?F%Sc9(T;H zf7x!9t+PBi+Wli|UJGX${ad(xdr+)of5lqR0#96a%erzW@F7{uFNtxwSwhY$CQlc@ z`J!(Rmsab~kpk-Hy*#d{Rrr3yFZdsPknM~<L+I9b%@Fgl_fPuII&c)u8=UfXvyE~{ z!7{~kyRa;n%?>tQ<<|WxRt*Ua(9Dsc?*&%TIIz4+M6{}l?W<zB`JCmzZ=<Le>0yOO zp9@<A?$fz|n9q`4>ryK^QlJL6SRX2@%LGt;#;m?D($$VGQA}M-8@s(Ej^BLXC<@pg zEptib<c|6!&Ap0QFENc8s{|2DbUH&!Ylzl6m{c{&eUoA)m3-_}6Q?~x1Mu2-6n`sT z22&@4PWRH7E|-N{Lv)lXtlkXyj4FQ<1C_Z|-PSyK^nLc-GCUnnb=|EqRaMdw{i93w z=B<anbz9o}9b^F3mwE8p>+7ebZh2>XJMKieynNB**pR75qZUvZ?xOYH*VD8rkX&fJ zTnnnArspgbv_CuZNFVU_%j|KN8(T5ATRvg}Z(F_I$@pZgRVi_z>z&YXZ`;Q1#KT%Q zuQw0J9eF~_iV;)-?o?IqfucCi?m7{zxO+NUNvB7FZ_pqhfuf`IkC!-LuEN`ieeT@9 zZu;-#=bt(4eJJtv^!x^XH0=U8b$2X!B;PgW`mt2-*oDPD^2kA;_>`E=W-{-@oi&^P z%%;8E_I-E0vC;>#<kNZEzS|ZrKY2`z8^Zu^^n-D&T9=axt!Gf}c^0vkk_z+ZW`;gn z{#Y|GOb=2CSAFCwal-FG0h9IJDke#QLwj553%AHM3p@I><rE2zqticrRSt<V5!Y!H z_I5;OZ7<jxoa!3ZR8b5geMnY1*1dUIFCF#Ah!;3Ha#|}a{L0AtlG7z=$jfBU=a~N< z`nqIZ{x+aVpdn>FL<*-?zg=G4mAQU1ZOOwj@1m{MulJY!dEytmTL$}G6cQ2OyObYx z&n~%JwJ2xL`K`mG^#?mvmPNBeVPZ$a2{Y9!%b6rKRGX{I3f{?ld7&U?6nb7EId}K< zMTBO~3hJQlfZi&*=H>VbjJc!O^Y@#$Lu#+&g;kQg?xuKjH&KwN^7>9>x8->`r5u?J z)VUpYS><m$f;0ZikaEw2oDr_rs4acAo>Uh*#M7#*dE0cjUM!}MXRlS_6mw6JT`k&R zzXYO#jW`45?QI3ORTZaP6XowHMWlUiSMyq~%kivoP&OvNa;bS)XbF2C@V?8R8ZW@0 zCvXx9j!^ChMVFqe0s*82CYLR*qLZl&(I>jGsHH#|Tbr$rckD}AjwQ;vLj%xAXAiB_ z@tnO2<_(Dc9!FD0oT#_2km?II3)Pq)y1y$LevTj_dA2KKE+JOpXcvokk1p;{S+sL& z6m`b7=i57!s;B7Zjy{|yY<LdIGd?tI(;*F)?LQ_}-vvHTt%uGGHN;-{qrU&!^%tVo zi_ZT!=UQ0WUd38oR^OxyD36jZ9`n%FTI{no`mJbmT&Wme>&rg8zqb*hGpue@nrXJx zCVrkDhW<J`bHGP1DSe~KU?#@NqJ{{I>SiJ?nu2g4z_N(x_R5CTKJ5-%5g8hz)X5fd z^!?eKmjIN%uvI3>NY#=KAC>ob&%^hrm6V;=y5y2Csul910NC5&<&G1x8rxK9pzX!v zxtboaT?S_RjxQqC_|<MU-2M$O(O}*G^r#@cz@hO??RUsZt7cqLSGgb$?N)Som{6G7 z$dG*+<zQNvHFSZ`#J^cpUvfP}bgsOKasyqri6>5`bTpvE)U&i8j~u;oe*`?Y3Adi% z&Zp3q<QrR?4F36)v*1m}w7ie7r_(Y6cNQ~ityXI9-9<CU$JG8Ud7~&Q16FtJvvU(3 z4$w%<E=VVry0~BfJLG~2K-3w$wX>GM{u<wL4<T>>n64TZ{16hU6Yh06^HTE_P`0b* zKmAtcoyb|L!Lv)RVw|)r7ze5^_n|fe!75ulxygVVh)-5d#t$h);mc|&d+#}pY7WY` zf96}5JU?D;*SJs^{+fsRj&RlbcT?>kF0i084nJ?_P#V`#HuQZ+V>Ndn=Upfna}eoZ zaYZ`&oBI;%JSEe3gOX+Ad{N@`Y~TQx6s#(<9G1lCH7%`b-?-fpu_$)jmLLJ>KsTkm z(;hUlk(LFBE~)*PyJ`29k$-lUB)8pKzP<7**Kj0Z?80Z`MzzNSAh+Lz@9anJV;+@x zND28B8T@OLJCSP*<sm*&oNNx`#v)R=n4MLK?UQ3hZbp)UHuGTTO=8|zPJ_x;v6J0s z2`rYPrW|pr<JX0j^|;yw^!L@HcJmYKk=d%q@zp+?5aayd9aW1S=e<z$idoh*lW$qx zpJxgCQy^u*vX`>93>|d6U?*oSI#eEXJYW1K`*UPjUZC!<>h_YPY%F1B2BfYY^^!=M zKSs_YTlA@&*zf9wyx@4qJy_Fs=90$}RAbF~bl^-OO`j)|h9AIBwn5=~H<Th;olKS& zX781oHz+$4mp+kxa?&2J($(d(|1Gh=A_E9xaMH26{G6mluSKsgo$1e$w~pR=E;~UV zw9VekjrFZpe1gwVN|!F7`7S&QqOX}igxWu`(Y8l=>=Dijk5cZoP@Y-!$qwdDFlKHv znH{{@ThJ^9h*!gGMP=^);w5>8LX?dXW!0==m20|5$1WEJ9NoM0W&3&31wXl>4koca z_V;5V;(SNki9BQI0oo!~@8|$NmkYo6qDy5iRsS*OSJiC2*ZhZ}hkCw@Ol@Bht+q8? z<6N6;^nr)p4*FPZKeL@V)%^`Q^E6XyQ93&qe?Rj@c82jTHsdqpSeP|n@l<wd*1F9# ztA&i8=0@Jy+qJNt9X~3G0j#JhO0?W&71+Fsr5{h!N#{b@U_ly#q6*b_3gZOeqj;WW zZQeIOw#b*E4~#3fUQWDyT@v71qRBsKi660SA?q~;=}j|?*+?6N;1>}DtY8ROi|z|= z!E2as`${WkW%GOz!k&n#6*5AA^jd|E1CQAC@iwdWo?8U5r|qw{pFe0P2QnV#eV-s} zLZ6fM$*^A}nNA@^{V8J9=z}=uXATKdj8?G|e$z=a%4eRdX2C4r{|z}Q4BHz>^=ftx zqn&{Uvmm`Hk_uD^Fx~r<CVE|)M=#HowWwFyuNsz)$*Y(o*7kYO9Y}E?uX3ts%N66| zn(McMB;X*67S^*jAe$D@+jGy<#}0>?J##51%fLY@(+mv`&tSK=ppz_fVdhu@=xvpv z`a|(J;=)_I%DHKtcF?=;(!2~mrjb5NlR~WdE~L?@@>#SG5xRt4rW2OABsNeA#Z;br zV-ioo%4Ms6gqgVJ{_Pab9B0Tzab;@v1`WokLBFyz$AJeXxy0>iH;zF0^!&lbTf6`_ zXyX9>5lBcA2A$8|4XQuC3$k#>0ycVyjUbH;#z-gC1|@8S60<-MH6P5p#SJ_+&a^aF zHb;@r2&V%CkU`X>jq}lO8jUygDbo&U#~fKRDUfN13O@6tsdKOL4#{YI5uH4WSm~J$ zcKR)yuHnu=L&=xM=_&~Fh<*A<Y(>EQ8~=o<$yC=U>a^v#eoVoL@(>-`%~gStO!%bz z+aQaLbR`Z0<IGf#?Nx%lMfawES0D3ORHrGdh^$~(){{>0q8c7#yS{$w*GlFcOdC70 zUK9|(Cfl@7ZP+}AvArYv-5HwIp!?}FYMrw!oROt-WLtd@h7Z(i?Y;AWWiU<N-vY`t zM-n$L(;TynNw}?Ao}O^icWJU&#|nG8SAK_SgqT3@GOwoBDHYZ!y=7=nd*uN1zI37z z0`#+DNydQusX{ciKqmaZ5sPA;jTFT?iew69%IXu5RZN|6vRMmpe=Ey;dr)?qs|o1Q zTyGK$mKM%@vG2PkQ&YQ7rz$t6@3Q<`C2i2uK9EKu*(R{J3kW#&5SwKH0xpCeSSI&4 zTn$Uj%}5YJuJ@X*${9=X+y{_FI-G~Q%~2m;%gG2(NE-X3$dMUjjddZs6$1|d0hWP) zUDDOqJ?<|c;MGLoDL6>OnX#|MQ@#}!ASAh4v1I7Wv_yez4aLv#OP`84Xvhtkt>&9p zu?&KQ_H}?Px_gytfu^fX>Hv=D=G;Vii6w=d|Ks{q)j%ihSGh|4F6AQVX_8$z58r{c zp=zeZHb>SRc8+0D-MI&<L?5?>#zi<}7{7tFkqnZVsA-Z(2g61#lL!yYt7|Tr;HXu5 z*o6xvD11n`0@CvBHKTC#+<D1X6&l4#Lwqp-rw+f&m1FbP8o8)ZbZX|HNvz7NQCw>a z`QFQMO>Lg$P>+mnh{3dwUAB<HC{KHcg_mQh@2CN$uRp}xP<V4tD<S*Pf7iRm_VlP? zx=$GPbt5eGbiT<(Z=^R#ud2qTg?+sfYgFaCZ<d6LE$t}P_Op6s0Tn?~nfqsYZL>+* z<7DGLvetxNOV^FZ*f2p_Oc~QPi|4(LmBmNFal7M2yS>R~P8LEX8k{kFA43|-TceWX zTMylp8L1RM6tyYB*|9gEW^3wmC96noC<DV;(iMZCrdmBZCY@eba9%2V@Wf}lp*r(( zIGJgmy{d<vW<53Jp{Kc~>Gc_B)QyHh_Vw@#mbuo5BhMMPLftc50ug$nTr8hUpYAow zCYiXi&YINx+0gt~Ae8vBd?vdr!IL%Y$hHb3YhcS2vq=JwWzxAlrLr;4R>P)#HdA-J z$FOS{2_H1sS%2YakBwqkzV3fs%hN`!oh$B@2_oXeS^c@px>GlwqHi6T`IsHstBH!? z)V!T+U0bxc^G)1ysitD_Hso9^Q<L)+{~D+zw?1;~EfESbswJCGgG|)PsJ=tdZ{n6n zxmI=*>-Am~m6ZN*w7<Ex&ZW2Bz{Ax><je`y-u^q@_C}ECT9*xnVHvG``MtJL&vTtI z3Q|1udd?|~@P~Tz2UQi_TBa_FF{TPp;S+b-PJF5#wSLlTlmBul+s72D{Z$u)+3isY z{Q5(ktXr!Cu;RLomi+?{xqO18AJ?nw&ZAVNH@G`{$?eVU3AM@?B`~p(kVUprW41*L zxeXu)5CS7^yuO|=>tM*UNha@0_D5~A%$Ez)=c;$u1=`jLBAb|QxQt2^6UDE?zb5Mj zs#Ju7tdiY$nvur86B?u_9i8M`cw-1tzxbAisXedd@KG)O)*gA5O0tlGJxJCWSjNoP z!0J3aU#-Cw((MpZsuhCu39b3}ngR&umM^0Jysu1=xob9K1?+tq;iVEJSVp?$G--b} zN%wVyNj~=}`t$zg;}5^QSK9e-w{D{8jowjFljHq2aR<MNq!}>c)()K)|3^OnQI5P} zz;e2c%A$oYa8VY?M4Yk2<qQeyosheiK_#@kB=1^L%W~H7Mc~=TLi=_M_icQMsU<g$ z-1ROeOJ>52ll9H>FslFL$zfW*zvq0X(G=6jGtw+=E3URPP;nWayj<v{Kc!`wb)}Xh zg@Pnb1GTE0B8-n)r$pGRkJK02+i_%m`p(G<uRajxnT;dt<e$x&#ch6R+Pnfp_{tEC zPd@I35Lty!s#p%1X1--b<~MZ(FOtS$azztyL^{?9NtU<)(oxknV1q2exrBNC{P+po zv|d9BOF+qIU9i7%P7+YdGEV0zLz!c!Tl*S??1Fd`LcM~+Xp!oua<_gfmY;h*Llr>} zJ4?56HuW_!BVXj%rjpc-sF?Nbku5sNc_A#7u1Os`t<op4B>f1Ic9u^+QD+$_<(^+# zm1QhULZ%+m^AXmuFBcwgYU)Zi8Dc<t81xw-)1CHx$$Efs?hjwg0p!>HR~WKGp#0s5 z$L)b#=Q6NX_kihyaHr1G|NQjcHSW?*u{biTmkd;qYdLcyY6Li99Yx-^DrAB>qzDav z{CLn>pQjezYq)Kx$>(ZQ$=%w`r?djCP=!`@WMmL`tRvk(icHAF0{E`SIClxJo>^?O zRH9CU<hD-xSp4nenOm8ePLe$w_||w6;~k<Do14_FuVtj6eNYyFDAO(P<%n=U?pJ)| zV2`8<xfN~TqF5H&ds#nrejFZQXd=EMh9;5DB>Xy8*^b+(3o`GvFPmau)b9s1=5{FT zw1@9x+TIhkmrlKEUGwf$>Z3&;eVFAgPd*4}+j>hoQFFbGoG=G6oCckLR*UX*$l^09 zLi?;2iN-zoHZN$Q&&;u2rF$C;R3B+-&GY~$TXjFnYl49+9x4g6D#*3Y(laz?r9RH_ z(F%IgGXJ5zpQp;>=~XcbuL>2O+%lr)r|1i}{T^1_?L|>YE^1jRU`dtfd!qL{PHW^o z$&n@v_h5IgsoMeNok`l+%uOLWtedec%|r$=62m@qdb<eUUMgbPRP)?xuKvmTv)O_( zw>ov&oU+G)4sjJ&rmvb&M#&({Zl29-Z`@>oVh6c3b&9w#ISe5DQ|5$igpB5sALH)T zyijULPEp}Anv!qYjQ5(O4ktckD08^<kqidbL_We&DE2<*py_o}S1WyS?LeB^-f~;2 z&^`hWD@;@>Cg}x*NhLtE{<)(u%hIJM%Et?KNgKKR!~c!c<hy(J@gzfe54S3&EL%@d zW2tZ>>Dsf@^MO!1hP)Y9YNrR|n`U6fvwO__osX3(>;{&f6Rom+IQU<<?2eDzjo=qR zIRH7}baTKFZKKpEi)oOJI(c6#$jXd--m;F|JE)x=;9MJqwF5adR=wr?x?@*txxLpb z-zP)|IGe_kwXvX{K!$uixASj}T?@!I9&}VaQV)D1O1k68u79WV4^G){7nD-Y#Z)aS zd0!COjLOpuA}V#0GzCQoKrSiXq~PpV9l(eqiBZnTN`*SL-8aO>e`*?)m4CghlFvX= zxR_Cvb}dkO769!5-2cSYT;*1LJ){+0ApEy^{g1z~Z|Ub}kN=*$#Zyoq0HhFxwFJi7 zj*Nw{WAp9Fyh-bGRk!7hQeJky=T#UTeUS3};n1^4N|06JjP7^u2a{NO;4^1hy}xJB zaJ>0(1@*3P&0Qzojb1+M?^M<rIa2euG&vHcY<|Y<RH@ciltt1)ciOXIpFJ%BZt!%e z06G}_sPfoEv)`l2xFh#ZE(}!I{xsk+sGBPq9FHS*p<~U#vUaI><Cqnj31$Dx^6KLN z?M>uN%$SkeQwnUV<xs^V8s`j*wH5n*B=9kH(dByL+{ejVZg=;?E`7(DcBa2q@XvFt zIdG<D)w;n+@)BnMIkU~WV?Ie9$;lrsI7A(ObmGYOMR~Uw{ot?fxLJw^uAEEzf85~t zvp*B>-tCm2Yk4Mo7~SW#bhD^BRZ2^!_@e*V$7bcU*DlSNlo4x4W6C|8_O-;y>*3YG z6rWGMt{v7{sG4mdcJtLC>p`eZV@`yu<p6*T(=+pO90-W9&QeYs+8g#9yga7r#EzrC zUU@9Q4a(d`mq4#wI=Q%+-l`??sZk{=yDlr=Iy((?nPwRM{_d#ja4f>jj4T2;t51wj z@^pM9!khKAS(fswWK4~P1m(qDjQ9-*FDBMEu;74I1g}8zL~5_NN{i@94z5PZS%w50 z|12M|8s&H;?jdflSzT;PnvTsdo1FIX^6-1<cPQ@VOTP#8M)rpuKXk)_?w4dq?*BW{ z2T!XcYSkxCyEvJobZs`HVqXs*yIg~U>L@dv<zmYJ6=uRL0B07$n@^s(QE~Gme0n*T zNcZ8vT*`@%i#;(D!hp0J58zsqu+F@jaU(j{`T~IP)LXwc_C$`~JUNo)B&RLLa&!$1 zsZKAYsY{C>ql()=^1hSZVRvbPzuuQ0HRFXpw}>FeS-9&SGKh!^t2Q_|9S$Ot5dqRG z-X3p@m-2DNcZrgbJyAR*y(_6qYk>NkFyM8~b%*Nu`3XnTrPfOo?=HNMp8a%(3qP{n zHtcEs<nEXSgdTIIdPym5Ra+esrkS{U(Z5IfT20KF3%L5s(Dju|Q4Wi1>fV7d#}y?u zpVc^tJrnzY@&<U3#4IfY-4!u~F3sK^W+hsOuJ#yo%~U4#_kv{XtVmbdX<DV!sZHcA zG8Cb(jt;Hg%#*XNVK`Dwv6VE7tTT1q7mf!ittf{1?h*T|USt|)%9Vdkzh2t^sUzvd z%##D3oAw=b;YHRqT_}VrAzqRTJSxRS^21`|LHRD1DjQ`Z;$<DnA{V_14l>r9w&)~L zXDK0Vf_4flnGeDV5N6E~CqU1Hi1BKJ_+dN?v94Gc6Iyr%p$6lnDx>XilF8#9=o%fc zt*~lA5{IYoeaOl72F|)TR-9F;)_=)&vJw`}(p1^{SLDD>-H8qslFU&7luyV+jQ65< zCD4|Aj0W|T;=JH){-O2>NeqIXZ?x)kU9-w@BekR;$URihE?5vSu6BBRHJuvb1$O7K z5Xq~;o8t+&1v$~~HNP@+$G7v!YuA+s>3dTqaG*<HM3F3`iig^W&)&Ci-P1Rfr?fhL zDWJQaVj0zo+3xA^O<}@XI+y}($N?99jigC0N89$&ev9@5<xuqoU<_8q99~w{Z?<CW z=f{O7#<NDl!=Cm5>50h=@D>2T;_oJyL{UTQO^=$a(cmYO!_eQmGHlko;OVdvS##r| z*7qjhp5r<R$8$0WLT&j;>0x<_a)VZ_+`?$91!&?%zn-pN-eJ2;h3#2kTvy3`wI4UH zJ_-_`ClKjJXV@xg#*xJ0XsNtHGnUx{$uEgoh|nRPY>Hq;`NT1BB!P_X9^#=zuPgb_ zhDlse0^g_bnjPPYnH!MBH1<Bki@NJ~!cSQV$AA|yOm`V@-%})m)eT`~D_{kc&B9#a zXNI+MZwl&t`j$k9%c`U7v{lx@0a{<~;f{+)4K=5INbkpAD(;;BeDld7OZ`?n2=HRO z(SOvqz>><6yL1R_J3}k%acRJG?Yx?A7X|cs=mmYCyX<@8J)Dxd7Gf(sSo(WY*t~}( zRbetj%E5`BsUj+g)T2WtODB%j7~i?DZzb;W7A&Dk4RhN4<LAW%i08N$K5#?Wq__k^ z3>6Bmnyb>?p6Gt06n2nwYFSOst01_z{%p%aAIhq2x~W+a5Zxt&UT%e0`&PgMW?67m z4Q<_3qD;sep79KO&kVl~ymgY|c)|vkf5YITR&&Ea#9-in>F>&3`Fk4~JaEv|qPo)u z=OM#+0kN&4LE)Q?lTE8v(a_=eIMc=qSb|O{+BNSm-v$-+ViL({&6KO4OGUc~Qy6Fb zl%lg8a)1OiKv08heSD@-BW~_ybn5<Na|70nUSQLzI_Y3uD>99A^VQ!zqTh`$GpmwJ zFA5nyB{gK8%E<S_@({A*eiUUh&%28mURi}W4xm4_H3*Z#zQt%AEp_>R<D%@TKqj<y z+|*_Cr{u9#hWs)+ecw4h$v+yN+B0m3<v8$Ga&`&+Ed`oJU9#ylFnF?9{oa7w`|Rkw z@3#^zf7;xmqy_QzLBy;#^OI`B)LF<15fAUOmhJ}3uE5&oXjc5(vl><0O_7>Nd~uh( zB2|%{6(4+lK9#}~r&0z~mZ?&2rd3tyvw60Qb+D^ehW0f0-NQrDFD|T~?Rc1py>sVB zS*o0x@q=fMTDR@1qHBSGDK=!Fm?&KvGJv_E?NGHs5SwJLoFQw(7==z2M)2#*9`%sV zC_T^7*ab+srEbe}un>>H1<3aXA$dS+bdxj$dVFK;PgSLVO5I_^cmBHn>f?rU_ru=( zm+fTsANthwKaV8#Rt++5qV$ZHZfXj;i#vwpi!u&2pis*>mc7|fk@MtuYu%xawB@;T zS2Xtwf2M~Uk9j?e7xq<Rmm_gtnmEnZ_1H+ZBWe{_bfx>Slfi@26%*|RvF?}xpVQbo zB8A?W6Jd(ctNq$lXJL`~bql_S9VCpys+S)uE?UKjXpHJb)q|PHt&Z_%D{j{I7mTbM zT?oU$v)o?*R(vT!hzoem@>d{0(3PyD&dsDOpOdYrl9MwhUOxHg%t*(diRHUqY0rwT z?!MoPdVJbUm0iU{CdCY%e^>`gEB02Oj~YJMQD1VpyFvMF*Ry<y51Okil4{PESyBXm zss!zoOn;6_mq7IZp)oYsbgtYaV0Z=w@FvRr#;LTczTW8H)y@AG+UQb`JN=dm-`nM* zZEz~9+A0<c(ABzN0#NC2-HWZ*7p}w?c996G5jot*;&1~gr4H4xASHE;lzj5>24DO( z0X|L@<M71-3gNEU=<=^EtJL6WzL+|&XO`Zh*&prNB737j`L^cA;y!=-R@j>j80}g? zZS=($p_+$W)I39el8wFsM0M3Ew*pUu(0qbCuoo7Ue=`);>oDRI>lPB}?b%nI8J-<5 zj=uCOX12M)2UI>@%ELn`gm`S3fH+6AiFK4M<)YUX(A_}PN^XI0ef0@g<B5XCd5*9X zu8GZnrZ7%t*U4t%FeIYPYPPHAf?Ph$EoDQ(m5VVflq3weTfxunQ5_FDaz*tT74z$4 zDvM=*V`0mD@jkwIEfp082gDKtGw@&zA2K#FHNb~j(6(m?l{JnOn>vMg;^iGd1|qGn zfX9j?VnNM$p(TwmLQdJDus|*fD~0MHvd5^%*X|d8N1XiKd}yQ&slApRxjy(L`>N1_ z$1G`3ZbKhWlbZ)BkI;~##c+76)G{_Ekryetpc2o;#9voCYRsz2!Ing`{+8rD#L);} zT~?!%)_bHlK)@(gE|Lbzc2v3z#IW@wCl}Icv%aTnEK=&yLS7&qYKZzoYUnN~*+(e~ zaS>K^GI-qMWwvB5UHlpzRY4VV1%Sf|V&MS5ULPOULWeWSGC$~;87j1jR@o{JwW#}X zZ{h0VNOtB{J-yw;z?6F9%i6h5oAggw?2P~BCy~ex9cy(8ZwZ)1hL2r8vz>_904n}w z?Crk5ri9*wP7I6ym+@`LvkNlO&59{Nz`YNs<pt>C`{~~RN%1=hqC{DLV<nsV&*^$D zvl}Kk!^!vRwLgnu5Ro!Mv?eC)_X<~OmH-w3DH#Ig?}a036C}PYEcT{990)Jz{uB{J zK4L{v{4uQTNV`(GrVM0D-UdjPQpMh4#V%06<piTJw(tc4G`t6Wzcso>O>UMCvmxFR z%zXnyQS1Ht&0;^bB-y)k*uM&O+WRYM)W>b?C1Tb9vh!SI4+C|Z)v8{n;O+BYdnme< zp-|g|yxp4+>ti2VkDlIAYHyM$GXsA1ba|j5)l5W;5ikTT%imbX=1e%a4O0VDTm$N< zN;`agZa?MB%iTho;I@TXNMWw5BM@0%2OIc?5X=u2;_&<h#6Jr-{W`fH!2NCv`7QTH ztLY_AK6#$e?>o0B1)yGEY?u5^6%)V-rYFQWSa32He1QP|ohX(`5K|{w4NxWi!^+_u zrU7*}9W>Mc5k@X|e@d1H5d3MK{>Qz1S12rJ@tQ9nNtZhK?_$~L(0I-QY!R3j_+3@U zO>rD&17p_53j_AvxR|sFm9{>|*2)=pgJnY&V5C9q7_OqApJ+D<xlB}E17a-dQRV$A zdkI+elUvE5cG^?^yfBl;qBM&;GP?j}y9M+-7BMiTv_gceFm#CvipfA#!!HM?78WP% z-36u@D;$Sod@u@RAylWW@eH}ahED>#ai_$DRY?X;aB2_n+J<;90ZcvN`-UKyNf%#b zD3sH{=5=WCKKZoC`d(bfH4Ufbaf3BKtTYj80t7^1MFd!E1#Sq<+|<~;8jyG~wW148 zgNK@#3^R;4<#3DsztH-NUx+HpT-4flaKkBQTkpgxH!On}4cwPV`3!h1Uxl;%PdX5_ zC+mLfPmz<nu-=*WD2NcC=C;a@oRB2>n2+*DHOf%gZiOUCWk)W&asgS7L(b5tMKsJb z9ahW06a(dihSO>%7F}^^EjQElgUHbDOJ97-{LQcI@*!ZLcf^+XI3IEWE2jSe;)(@N z#)&Oc!QMUS3jWO=e#>ndEoMQ!nTYD(vZiP9+!y124r7-{0mef%HvtAR3~2--;g(N~ z)A-vby_?&rxJN14`LtQ*#^aL9(Da2<4~f`5oN||(O<cPAlThc9FDNTUH{Zh0KU9&! z5MO1ZdWZ;7TIHAnrln!8yACr>B=+gJdv$1ReHKljLsIB+Pdw}%hPv+!E7}1hd=u-@ z*}$e%4q{h;Dg>S`B+3<Xl|(CHkvL<+x>VthaLT_JjA|M?!5ysr!|uzHRiT`JJGvPs zA(+DF6T<HR02h8j6t;<XsA5+rV3aQufQ_DUkSQk0RV~P4l5BV)E;c(X^3JPCOT!)^ zZF!uu0!>C(NOT1oExVBZU*H|iOdfozdW4JG3WJAokpslQgk>AKPpD=Z`b+WbG8YrF z?#AUZZQ8SDe`NR7p*7p+3%%wkL?nRQ181NYiR;S@&#l{<_<GDbP-$xcWz~Mh$W=i? zRauIEQJCiQ#jkiT)i8ZarA!;OyC@7%gH?V?vBAmhF@aeLv!1qGrBp`IdJo!nLE<$| z@9_h<VkgtXIG}+=j$deG=#sRJI?9X)=L1l<@30^Xu}QjkDFHlLBHjxCEEB+y)c5h8 zVjUFOTA<?SxTr^H{G;rvoP~=}{>A%@vyU!DWhiOGh}aQ;q$*chrmiUKR|B^tT_sE5 z{ujOGyJ$R4D%317k%@Z3=o@3Jh<+m9tHWf|)YiBm+o8@c7EzpqA47-Ar$`ZWAEk1v z!a44L9b6;_Cv}B}>ILrU&SKaM>CRC4N}vHhN9aP1G=1(ZU+pGw-hdP9P@)vNnvJxp zlQ#T`tmO{ZD*>u#3bS;jMS#*cLvc^)p!|sij5Ao(8EiTv3}7dSeoE39k!TC%k(TRZ zwKrVJ7N{mEKreR6m4NN#8~#JU%56ig5Ga$k6zp*Vug%+SxbFx~S)G3oOY`X{Y&_`O za%)O(51kwQeb4C5W_VMhr918-H!iY+duEZqCM81;Wlj_2w;0l|42{e_5nUtp+uV~0 z%{=nD-ctIA>?i<{3j}QRT&|pt8{h(;(rVX$O34duoxPvKZ4JC%)!}|8FLymoP>vgU zs9t&qp8`zvU8}ylka@Yz^CcCt2tZHM<V%T)L0q)`z@@#KGZz@LeeJaj(aRZ92~}nP zEMqrr6U3J3d1X}bf29F?s}GF6ZcSKR5?8OAysazmPb1!A{1IPye15L8^Td;-D(t5o zEM_4J)_d=h?GRV9_^GqP$JT&XMY4uMaRJju%Nx<6M3sh|+EK1T<q^Qtj8@aF%ZCO3 zAY-c~g(EMS8dn(bAAHhGpX?1yWx-F=<(cx6I?OaK{*^rTB}t1ZXwGJX?RS(rF4pe_ z4O!17;Ec6)g#<4%N!<lB-V#Y-APRv!)m+b_1-WUito;IJz6ZU&p!j2Z>gP0~MIt*S zAjd;Z%JZ{)xF`HAAF@B_YTGRK_aSl1BVv*4)9(oVFM7oOQpW<ky5#21d^33Qb5|Z= zJU-VuCUSo6{Ihd=I_t6C(|YR-_W3mU4Ppr+KM3s9)?7#Up{Wv8cgWJ4l~jApx{8D+ zl50E6ihm2i>J>R>(H#ug7TjGx&)ynPnVs}{PWk>MiS@$+BlWNP>RGC5&D>|(c|XL{ zv@9f>3x@+wv+L3ta5bQF7=k5Y9e}o{$p<Z9X3G@+{-y!@5MSt$A-qTMiZ>oSsK8_f zUMTy^e(7SdvrN5f8wBp73U1JuoS)Fre^dVSU_yc{g3XQ6f5fX@d*@+w@4fOuUC5o< z|IQsemeL-UvjK3-o80gDNqHIga(O|ygNu@pR{70Ey60{VBs+^mI$Xj@Rc-6H%Re$r z7q8DgvS%nP*~dkSKVz2PV!rIe+~X?iM*06m3t$fFRZl)%zT#9Lve5ReV;+Zus>!Sq z<aD3ZJhzgo2WGK=$>arDe=a5*Sdz(5Tqi0L&Z|x`WVGwLq2E1%!hXC^GVd*M6qJGY zf3)VauO6dc#dV;M^^~c~0V)L)9^*IRY=u4<#i%;a0jZmFRw$XP{G?sy6T6$8|NP;d zX`E0snhj9C@Cf+wAP&@KeRL2x_R8%RSNY+|#+#$BkC2q-Y3dng4E#fpq5E^k(mVk5 zr51KCMymh(cz)^rsoD7VdI6u6AH>V)9c~oGHVhP?fI;1}#><X*s%|xQIVMdb75YaW zn(h5EZXV4O<#m3tZ$XrMPSm46$=x`HKQ_2>y;?+WPWQ-z%m>PmC#!BB{YYtYv($fc zCjy{r@ag4oB^~V-DU5x23b%~B>ELLYX7?#&o5a=exnu`Nq@8airDSs{S4PRVFQ_^p zLtI`fz`1{|U+=}E(_+WRy4@$2-d8S|q+AfQ=~$g;bi1^_z@~HUWy_IA7tk`M&IKy{ za|&7Uq1K*_Eey4+S3m6I-Yj3PRyc_4I(L8T<&lfee>lC6H@_m7>JPD4Q|eEPy`Lvb z57FVmFF7g(I(B3MM$<IMYU47#&R7Qp6g*t7Frod~ljKLK4_lNaFPytOW<D+zI$$?p zwX~P7T{lja1B{LGGBG>pOgEDUv&=CgueqcVJSV)u&!)S@2abu%=odR=)a=k;bOA~d z#jRd$8&s|tZyO9v1W0AdAakTMX-orPkIc#JO|WKCyZ~8xgYJFM`t9o!Wk!gnBDE^C z&?T}u@=DH%WAN_X;F{LYgA)<GIp3g|*}#TNR_~)gW7hK>KF^f4+|@ky-JA7!VcYdx zYx2}w=bV?-a(1Uo;3GiNfZj+8L?Iwc%52OUkWD_i?;$(M^Fj^dm-jL3`IX3)_QW4e z7vGihJT&X2rpmOp(^bVy$DsYA`muPmT!VX!suKHo8=;a$tL!Zazkq$03avhD%j^xA zJkpm9J7hN5HHxK2Ezam2b5<3TXN@}yVg*)LmW*3=TL3atKLH_?*i+)DQcLw7H2gR& zBWm%XIH}OOb3pDD{jR5bLchY%{7skH^0I{JpbP84&e)`!V(U$6uaoV(^Sp=cgw&K6 zfImde!f#QgBu%=e%f^S^W}v)nXNMa+oF+>eU^=>&MF<AIJB!cqslXm5q)0W0Kzh^S zQ)K(4W9oS&wn%q=5Pj9)=8Kp+Zz8NVv7r#N{SKxc%G~j!eC;tj&k>)NRhnyX-@ZT3 zhgX~EYBRuQ$pb!Ckv(lId<EiMlfp|gCMTh!5k24TwjA{Xlf(?v9jM7(c!)884k<}w z<D66iq=0x#8<i=BNnK7F(dv%pJ-3g&8C*ISrBZZmYsBb9cMRgWW~n<krojXK%<Q#? z<)$1Nx(`4%d2T)Eb@j!VWX^vvr_k0n-Z(Ef-}kUyNbvJsxkT9<4U3LQcQkqr_z5fO zfTACAvaEaWDUG%0nm#|y{)S1ZeqFqzbV15Nt5CY&v=s|B1|W>CB;<#omk{k;{rlFX z>N)A!l81;{#+k<XXOfqc7o+BIR>0fOXmI`GX*|8Zcu}p_4l<Y6ELnF;QO}JC(F3y} zz>Rnj;~qn(M{citeY)-Ix;jL+m57P%MBz!)va(eEbD@_Xdd&82BoxHPhS7(Jh50?w zg@CFC=ap=y#PX$o&ICDXw6wKWO0y71TqZtb6P(t~LU$45@^-2Qtt!<~>#TCeAELF1 z6tbOW+dJj@OoakL!dn%Ub&j-BkTk2N^dEcF3SaFsZa-OgqUF8oYT)3ZwZx0d+GE<2 z1j(qNCFFK7#f+dW-q1?J)OQUczYz1n2~F`s8=*FpjEa_S7Rs#qrK!+FUc5_O&=XGj z$MI8O52+IPF@oyDWwx+}nb+w6egLvY7y{VE=IzF2XnB?t5!UO`rHk+N-)p-RtWQ=# z<2YoMk#S*1T}=(OEc2jnSOPvDY5YvouHGxJX1HMwGaL^AjC#Rx5kr2hG1KGvbLa%h zvVX&@2q4t!>0SK>g_Hb|zoE2zd=wY;nxb>Pr>^kwV-REfxO@ZlH%0W!^@w18pKWGZ zL24^bevnPU<CCGH!>aOMdPI!IVv3H|G7&esX7Dp@@GPz|YICX5N`Rjw3LMmlsbpIX zBE(~w1pg>rZ&$IAHCqRVpU1|kWYe=43!d#28$6xq2?@LK29&o$!-YVRm*cr99gXI) zhNsd74~btxKdvHMoBS?F4HrV9at4$ajbW$N8!!!%vg*-dWv;pDVeg_KI`IgZ-x=?X z0ki3-b0Zy>3>)C5QbmXiwZfRxhI8Nd#FX_De#wMX-m3!}oK%lX6gA4OzsZ9RAelfq zB;$MFSe1xAvrRlaI|}hs;FV@i%tS=V9)CYxcEx+x0R3fLF?zgD#dXlr#+iiZT?IV^ zZ-RBT8Sw1StSseMSwsL97Qp9){~FG*UIwBc_oQp}WCpWVWQvrfzowqdUqXGV(&$XQ z>frpNpz<X{_A|gK;m(5C*XU(5b)0-)<Y#eq$LH&x&R%zJ{5J2(mjgWOiN0vgtc-a5 zRcUGBW927$&f9#o<BeO6`{KP+z6OFjbgPF8UuKt>?jN-fwH~yXF9Cbmab&kw?eQeW zYMrwxBBlzm-@6SQge5=y@4t*a8#dP;@noqSJOESLLuF&L^MZbV%h3A0_OIm-QAy4} z^TEy;`-h`<+c*+!vK!b;o4`<NX}_@1Vd<>oDv{bvD=Aonjk4puqLI@l?%ll#^BRqc ztUqw#l0_v0@-ClMiheU>)<ek?w1=bZzJXBzYjdTdmY!dyv?q0GQ=Tc}C2!|dF8-q6 zJ*OK?E7FooQ&VCiui5j*_lI1u{S!8Zw1n+TD^8y&mbOR_O+T-vaKKwS*RN$!ZkPZz zW7omM>7j^OdJv;v<k&s~HBp+9R>76J9JRkh*+e!zL;69EN^PA&{A!-M9m@8|Gp<aO zC@<%iHPmFa7g59|TNdvXoTyC9dUIwhiF>E;dyCNvH=jEN*Kk_a-W}wI&7O`@bCRT% zdss!zng;05A}1v_tbTIB$Edrs#Nf`gQDnm5>Yw+aOeHm`=RJ*<4~gEVr+LcWnmaD* z>*HuMxdp|AQZI4@gt#r7e!Pd`7%81g6%MPu>)fwz^G`u!3sZ4p$I4`v4pmx78~gmk zQz7+R1^P>`BJP67!`*o2OOQ<%VOm)JLh-ER9#<?HFEYZ(&Ivi_FQ3M-JSm<Z{Hi5p zt<0{$sRRCZBkyYH{zvWex`(eF;}6F*tPYt~O=PC>LFn%rW*0+LJJ#hq!XIm7S$8i+ zPzNH47JNqd<R?;lu9F#JQ2@inRyZ&@^*bG!I|%cRw5v0=sO$U(YHo+ljwQ~(%c$V) zN!i$9>E`?3yMUuHt?t+HlEn&=+idL6h8P+G8;Xa07>A+mTKs}UrOGQb^3_f-XckVi zlN;b>wpe3v-~lP4juiXSe#qgTgW4(LX+07T{x$eOSANqb{WD8O$?8Iwb7lkrTd1`U z*=dkUpqwd%RmZ0&F)(#_*dqtQ%RY52GGaXv`;Vh|BjEtGk`4esJ*na&#e%&T^A!fv zQlQPtuy+*6_dHW+V`-0wOlgNSGn`o@HfkRusty2%#Y+J261uaNV|*q;i^UTLs9co3 zys-yg8i!r=i~IGjq^p@)+jzt=?%A{b)-1reJMqo}a%Cdju%;)#LoPXB9CDv!>r*A| zmu>sB7?MN~H#jZ&q32}vYQa0v!V^Mi)Bb5DFX6R>aO{xYm!DuYIr55B&d`q(owgHS zWPKJWaDM&iC9ck~Hi;<#>=6JpDm^`A1sNEZXaqRE+fXhOq|0?)$qI$XJ96YplvfDQ zl#Lu-BJ)~c?zJKCAONrve`X91yS?hgD;Lx9%j=Mq{iP-OfdW0nK0xK>+4+hN4_V)| z_+Ogm6h*?m%Fu)WiN`{IsviRJAT+92fpb9#QS6*xig_dZ6+PJBvgFY9iX&os$aqqr zidRrptAvQZU@hX1K*>=6c$g|t#?g>*DLT6v_FtA+qtr>|1cl$<iUi!zsaA=|Hfe?; z*up$DLs12QmAvNtkJrE6L34zW0q?4bW6ufDE26nbVs6vVw8kp&pV)+n@mwUsuWtj+ zABXw>EH!!wZ{tH~M747nhS$iVRwR*>4RP~^G8RSR0Q-M2lByPm1Xqj_?tGUiG>ss3 zi=aVG5S?y~1TR)i=v<!qSQ?)gZzhOPPI<kM638^*ucxGcVZ{cE#eYaierkn%wkXo| zDv}U3`IQ}%s^of+Bzh76<w*s14~a*y%@)kW*IP9Vmf&s2VpkpaE+6@+^wCFePFC^` z0UCmpt2>>mvs%({8hR~NlKml9+0}i5Al{!+^V$Cteh&7U0)Ih)&=HY$iow^uiJ$8f zjwFb`-v%pyMXxo8H4{WE=wMc{LwBa_;T}kTbnVcbcoKmwz^!fK$-wC&5b-9jn9LM8 zH+~c4Zif@B0e1Q)bct$`zI>q$D|W9~^23I**-XXfVd+#~xS4vTk173`0|vmCxDzju zjR=0*D<0h=Ci(!H6~FIm65K^YvSI6pziyLaSkq!eh;1sY4=WnU_sfpV#iZpTWT1wt z(3B*<dTaM70(4wT(k%J#2Z#DvdC5n7)dvuT=2q*P@x8!cyr^iPXY<mf4`!mrHb8CI z^N$ro&hg9rtf1vRq*DM6%~*V<=MbRPDQB(aMeeEhFQuEroessoXXu6WWcb(kN~JpJ zXgrk5hy3w}y{n+q)-^v!rzAxLSv8&(i}HCw5J|N$Z=*mT^@y{qG5q#Ms5Sf-TVi$t z9{%gdc#ZK&M(e`3Nn#k7iPg^n1FF|b<j%<L07!Lw=)bMffqqfbQj)I#W~P}=7RF}& zbIoVdA%pWej|htGNg|?3=^wYiZdeE%3+ZGF*YX>tv&EjyX9Fl1t5uMv#kLQe#P_04 zJdbI0d)Bek84H@MTDR~CH6wZ-f*F7S)ZD$wBm}e#QuJv~=A*0f<0dby`3wJ8X7{&3 zkF|;o#9suhVyXxjT7u|vy2?wcZgy#KQpE`mWxW{}>~brtAs!Zt7a#S_l|Fl>GDhEU z$URo72KAd0m~`1Mz~!qC+%^i<xY7KWs_=vYeSwEm@bem|HiTr6(GL<mf_2#tx62a) z(7^&xNLSDQP;?&tY`$F_PDB!Wk0cUA?HQXI6|q-iRH+qv)K+T!G!bHNT1wTbRc%pK zRWw3Tt7eO8Yg0whMVB}4zwkWI=YH;U&i7mwOM$xj${c2C`)Tjz=fP?y{O_2zul&8P zaYP%kzaj8mdCol^4(TLvI;-OdFvR{VgCP^{4^*M!vWA&MNWw}dnxxW#XLB7A+RqpH zPT;&xFgVhZbvk|SXIB6z)cbBwR$|UJ5E;-<?cyDU2<UK9XEG64XO|wBvK_6kcfxr0 zzFsql=GZ@MI1~^VBZfHI7qtPH!U&MtM5z8KbQbgYDX3#QEw@GVd56${4dJXHGBlu{ z*;SfyBsZX%sBzKd8Ml4NRx4!>V74X7f~v;)6FDcR*lI0I#AFc>n%A|0x&Nzc*YqtS z$q0G?{k}ypMH}=nmbSR>=AX85#4bElvyvnxz}YO=-cB+5t?;JRCud!4lF{P)f#D1x z6gv41=iMfI)lvl_p7AMPen+ThUKH-eS(L3m`^fXWf(j*1K`)5@=ZU}e0QBEE*VF=A zt)XB1q|0os(nELlUhx*uQznHkg|tEI^r!hEWr%wg!|G2s<21^qdJR0Em%B9&FPn+r zIDC^=F?0PgK>euGcPN}G(V!1-sPI<Gq`rp3gRS!}o2a{UG=Cd;nS~Rf%~Eqc^UqjU zFkslIA2NlZUbkYK&3|TKj}n<4-luRePjl?!1)i^Tx)<CE;AVY}flj{_R#~Y9;GtKD zkh5%v8I^Gw`h3`&dB6bkFP3R3JoM@6I4Aq`KT>^TG*3c``RbvRqzV3rt2yH2LAnX& z2$g*$Tr_=2_7lQfz>Too%C@ihG-`}{)ByYlV1Xdn+tFCs@I|C5_74OOw<0zp`v*wg zX@HnF?;X?D4st04b*I&RQI|86tuXwLTy^-R>)B_QDi7P3<=eN7&6U*KX|wfBa~yP# zYlZ0R(sfe<A=b1*P^74YClyL%>9|5<yn^vDir0z*bVRT4e`E;r+jTK=n@bH@xQ8`` zf?d(v=1X{v!DS3`KgoY3`OtuEJ6tYBK~&oM9!`(@jcEV$J?`h>!VZ|)sN3AGZLGh3 zT`$G6owT`a)k@@FTX=}}R+ls{@DaN4hB=R=`r`W+qH*zGF`VPA5ELW8=|A>q49k&$ z#<<18_9b(7JySIw-Wwy$>t3(Bcv(p#X2bJuS92g%t;K<ux)N9BI09#vJ;uL(Hn!39 zw%fa})*th3RjtF6XT8~@sdw0-Is;y5b{U*;P6OE4c}*Wz3_c0Y+m}S1bg`CDuO~Ec zQ>nLhBW`^kXSr<97jU%lCj7}J2(VWr@%^tP*SRNr-`Uw`^=hkzY5?&y{+WEcLx=qA zAqJdM8S~$`nvbSZ6$76srNX-^@)z}96O`XpaIqfpfup%T+@x-->%9%A0`H`I4V!m7 z8}KC*`0e9OnQYcP+&{VsD$m)fyzOQsRkhU6dH@)9bPDGw!R&LDT?4vvwjS>E<Juk8 z27(DYjM5<FX&*qa_msqMulRww!wPm%=~!nQ@PxkP#L_GqeVmhokzYhE^I0qpA3`eQ zhuhN^IrKsVmAOC3%Yg4q`uMn(9-i^r)n4%EXHFyP^gUxVGr*h-L5+UiU(>7W9b!%| zGEPnsC?c@0Q>}-$Hgg{CalK!>m&ubbx3XZtvWI8i2CzSB<sQXr4g)xy6WCo3_NtHO z^9rx1*3S)<ylL#c9+R0)g737r`{i*9FFSGW;tk&6AMSSV)nXrH{P(ac$5efA8eUgW zBgi7#I3ZkCrpN>c31>U1S{}GYg>ttysC%zJL_waIYLMQPEl2V#v#Mu6yS_p%hl33O z0GkgRMns70Yp5B<hcSowP5P9Dk#>(0vsc>S@5!&6cMJ|cuOn<#w!>|o=i44lJxHa* zzs0b)E)*J^@kHD7xJA~~{XU!dQ_783o!zZmvYO=oHINnk{6Uz2FVAXS_J^<1=q(R8 zM}ZS(iV(YdJ~QM|vhCj?VQo&KIlV$lD}Oc)*PIoN?4w1l4HbS))JN7t3^bYxGW1IU z9mZBd^m~HQxq=5flzyJO2hO?h)<*HILoV}3KJ-DpvBKU5V|#*f$&dR=1G4+S9-i%i z>lFl2p<{<^Nkcso2Ao&9SWYokSN=1QWJjz4iiAeEE$+|Ec-FXKUm|T^zs3ljl5fqv zg!WD4ku+IkXE|OGD);L<T3+)!I{SOf{{Gbsp=DXJ6P`&BvD|PgxqjH{Gwi4qfBQXQ zX6@o1-1@?r((f)duIFZFa8?KCY`;bH?#ibp@{UU6`iCP_-c)mxK3w6_v=_6tiT<VC z@bg;ooD%NPqwp(l#$b|m``rb+QXEw43hn5Fjm6pRi&fZE4v8ysJGOP^C5paFbD!)R zZSUFKV^Le4zYl0<>Af=R`pmzi(m4xCbh3#ZUl{bhnFmvjTkU?oJo?S`vEp(2-*Lo4 zKkFACy1~2iSN$KkjcM4%by{w#Waj|+>g8{`=tKi{Q`a5mzxq#A-}91ii<b(duJ%14 zYwV(wb!u`aZu848=q^28XnDoHQc4%xuDG3Zuh43XT@F~<a6Z5MzUN)VMNZR6M3c50 zr?9xQ6nnkz*vXu-#F>8vOwqF@aRX$)nxHRy{}8R6Z6}=YZd-SG{&T^T2qWHb0|r*L zLjy)$hj1+8)0$kRmX2RrLXnf7z`S82vJ_Z+c)S$fc{+VU*z0zNsrvRF&GJ#D*=+Ou z7mDZZ75ZL_Z^ZaMJiJ#rjKL0|M_F7X^Gg9EX#&9?Jae&<<v#h{eC1y)E0|vfN+G=J zxi{Gt4Vx4+mtx04D)E!uTaxP!s~dO&*2)g+Z%1b4tL<zQa9GSs>u$p@uq_>2EbI{V zEpyv~rSQTb<`-ENFiitIfH#jB#q()e>4NSfC%(@yX58(CrILRnZKN#KzdJbCUy8ou z7`@B-TA=NhWyM+e(&D|`nDzqy;(+>R8T6KN>Grt#W7}h)rrl-B(aQ}znH7;OO@o*_ zEbolVG$GuQ4Nic=f~j(r^*mlc4^R~Dv#Si9)O3md>Be-_!rE|Ovbd!5Y9qG<2O#<A zxO4dpSCNLlQ9%Q*+H4O67BybYGb!Pb$Svnv-4bXRIo>A8rT_06jMwIH#k<VHu@K9l z)|IZ7eKZAFIhQ9L!sm0z2F+ZAJ7H=sj08wadBu_i;sa{3G_I({o$DBV6j|v_r?qxu zq`_7J0T3d7p~|#u-KH+mo&W2VA040kdYdb}WXpp0g%W^U?ArAaYz@8`X3(;z(0Lzt zIQ>d1cm{X_{<SkTviK^TwwV&?bvIxl$|3QQ%wYDSAv44Z;0Isu@c(rrjv(Za(@Hg- zo|ZYhl<I5t(p7$_?th@aWrN<+I$dS4N;f#iRv_w@H&Z&CmCS2XXq#HHzjL)o(B`&G z8f~!lR#N=#{fp|KVtwz;(=2@A{fkvIKvaSAr6g$O<%inaLapU?0*2ikFGkBFIm(2j zt~S6o*a?(=nVa2zrCsCJjg&`i^Wvw(L_PxmyDdMdujgK>@vNH%N%H0Sh3_Den2e<Y zyoHuin5`bS;&j)Jv;ir3T35R%R-z^v+pUvcYoexFqiB`IxNP3y?qnX(d#U9uQ1-%K zOlKxu6o?vuCjOucE_vA6<93)$*-s|$KZrG!_p^;ya6vdO^=BN!t)ptB>87;#j6eXZ z$2R7z!-s8NXbA+fo$i$r52U_=ZSmXShisfkkVqiF%wQKR)6sU@XQ38#1zRC-E4d4` zQdcmaz=dp^$qBW}!O<`{+1#T?&OV_6f1E%<kwuw-J?kmVE}mC^734g-R^TN!O6dt= zc#sn)mG%z(3V9+5$^3?9QOrsfpnF%<h~lyE{uF^JVy^DEC+yd!i#XY~tSHe*QtpPI zX7A~Ql!OAZEmI`BlRJ;xu`cvz6`{LF?<WU%8NJ;x(gRH8^grWN+FvliH=cn?LpsQO zKZOYLEfExJc_pbRrj6rdwZ`bV0pVAT!#a`e*5Q6?xg{ypu60|?>Tb2Hs6UsPqP#68 zCe8`ZrJG8ncq0Y6nVs8RQ40P6N}u`aGM+QSC7VT|nQY0nSftpPE(5?<Hih#_02pvg z%-vrB@*0X6i@K)sX8SqZci9ZOoF+CIF&b$IeBz<)RCMp^#yR*T6Ij*6s5^G$YwE?g zbAL8=x+3M*xvt9XsO}h~`ES(0S_sl|vBjonQX6W11giMqC^syYoaz2|%cOz#{(VAZ z&~(?3P7gs_iIgEi;Bky>kD#gbgDm$)W?f%t(33~oUhy-Zk+Gv=XXJ5DX3H*`=oS@x zs|i|0C0{f_l%!c3Ke^r8Xrz(!hMH*S*gbnsQPcBYM{c2C%RbCpXOeV}f5uC=Cj7pO z)wi5kUv-)2Cw05^4!PS;Kn@CUf|te-#AC0HBj~qB{<kYRL31Ft@6x8~%`VPyo<AZs zW7DJz{UNp~v`9d?u`HF3&2R8hkU#T#_4?_I#0t>;>FDV!FPF}JJ#U`G#=#K1m{hpy zD(4IK0qYI`<IR`DzGgXj+}jxFrJdwk5R#b8o1cPjg`Hkm`bAF5>rDQTIgth4x#?Vu z&E}pS5EumvsDD^$4I5|d#(OIHz5m^^y~BS4%Ru2tY<o~XcP4#q2(S_<($1y}YZcz9 zk_I$m2PC}<vRF)%bh%=3f=^b9&b73L&SCNhrDj59<Aew^hwS$8xx4qY+kyj)bJ5yC z4No^gJT^lqvViK+=n){Vd;PdiGUK^`5%R>pL9S6c;g+5C+N1yeUcKILVX-+l8f5S$ zH`0~-_-(1QDz#Nz{^fwsV>>0gQL9;*`Br2df!T{&HAj_A?1fgGIf{k6u&F@itqmCV zj%cG^P=YQLTVWn&POOZ$kt5w{6ZF{`QJrxeHV8=5e3*>w5Ka@~$T|?v4w=32?<M6; ztWmYefA1tl2+Yw2AT9urQ5-{pJnBptQ{(xZy@6#p8wl`1H8+I@-}ZJeue?4Hk`&d< zr1M;<+1wza-UiR*j~LN{(7(Do&KK)(mkd?h0#E1twC_tUE!@vP0kLTV3`5x$!Ezk7 z(DS@1VI_@2I*cu5i5kdlL!plQwA+g@T<iSR<YZ|)!jKh8W*=vIsY9L4@qeO*_>vBR z*P28<ef>$B>+b4eOh5C5XE2{cKr)*T7ep<9#C*E}$UfCNUU=2$T;mCYL_Kpm&T9Tj z2@}^~b8pPTu=@{9wCR3`M*?6$U;1fU*#6a2X8l;r$Sd_};<-ue_(AgO8Zpd4;3GKc z;NOqVw6O1ESPqvqpJ#w7ie#hc)AB<m-YCGC!41jveC*99sKgKBpZ#CUE?>O+qp0GB zP0+`jE^@AxACvKis3O*70y+5^M6*e6D=Nz-oZ>sh`s)+Cn%cXZpx;}n|KWZgf~V1q zN}emywILK|dozrCGjQ=~i>5#EWytVBywEkvXk3B^1t9K5P=A(V5gppCqr$MVb6dv` zZMq=y?Wu`cAiwmc#mE=6U7dS|ZHO7lRhB}x5hdA1u=n9z1Q1}*OzW)9c3Vgd+M%3_ zON-v2Xf$JEo9d)%Z&{9B@W_Dt^9H@E%9*|mwVxqh!uKKC(Ghf@moz2H>F%~zCd{iR z{ds1L7UP<yv>+?r`$C`?Oj5xhS^6wJ8EKG=jD3;~AeJ%<&s<G)@n*h?PQ6#ouYxqT zb8YXmG<@8azoG-px0Ca)f@(B^d6+B29CWTGoPStay(9+>s^V721_xF#SYse}n8=}H zLJBP@$vT498q-1=DX(OW9h3)J?J#mA$Yea!|D;8u3d34XFE=Ow>2l<Ofl#e9V-;u| zXi)o8$MdC^UMnf?27~XCbrniM1g~U?aCOOaBSfr`q*=2V1GCi#S*tZ=zcHov*}1KD z$N;x-V76JtxHP>d{OP_yLm6oEGj=VCqFhROikI3_rPbzB+m13at;{2-7i?gB3g6_k zt0<xU%xVPiuz`sooX6vA2YziTHU5MW)Y_NfQ~0j@LP>=<OG`%7PWGB8#l}!($qc-F zNb(M+_>D*++It^0nbZ*te6>e67mRypsvIq#o6O{F9C-o<G8-qEF>0TT4CYCvDoshO zJQgUF;i*Pi^zDtw&h*xd>-}11W=VOpy#UrvPm2;gm(ZFT%LIwz0Vf~^DsYB(h}7D; z!t7~^L1X=~D#coh9N|(f-fZY2&t{Vj4ry(??vhqjjD6w2)rz$GJzKA<mSzLv;E5w^ zaNXowf@=Ga%c~$;&-Fi&4H_`!t$V$6@}|3k=C6f&<=TuMEFjo(hOBfxNkDQEU;iqL z-U=4vK0?+#OSc)B)gR2SS#Z7hqgeQJ!o`I@%qME&kqg+zRcQ%bX@Sxrexj6kF6d|l zi<~oe2rToo;$q0VRD(uZIUXWwmR**@rk|fZYs7}5y)X(&n{0jg;}2VP#p^1f(!Ifn zReYxnQ!1&NUAreEAfFkO_`1Ha4>-XZqBZrir8i6~E$|b#sc@2P0HS|@m?^CZoTOyw zpqGW+8X_+{AXPTK-laCXO&4nL886ps=eXMFT9F%tf#^E1`__UJ@f6i6sI69-H;{d- zxcw81KP+GAX6dV^@DzR73nPu7SzT-J6G~J%G=Z9WS<GDizsyD#q!t5_Ik2=!C)YL~ zvvfv<UM$4vi9%utwY$>Fh9y*;HVMSc^uGXQ!7*iYPTRye28DD6#E$92I+J%0=egTY z=!ii&p;mnK!R8fBx|S9D{*rr0{#cEu#sfi?Rf>OX&EpzyJb|Jr`X~mVhV3<OdnN28 zG#E~xl`VsV04bV)3)sx;&?bE0s^L)l)4M4{wyRU_mslbg-l&%6M^PuHxWNq-7(o6g zVTu&j*s#S24d2O}#+cjOIY+`!P~BR2f%89zZ4%Ow;!||ADan4GL5!;Fom^bU(5G|) zUIvz(cN+O7k2kv0<ZpesP+?Kw!Bav>*0ZTngTqw+ku<y+B{94+;u_5QYqt8CF|O6C zkI`+a{4n)$SF--GhzBfBSI-*nEDyB26@j^2l*;nb<?RpdHx%?a5pgBe0J3vwnnS+D z`+UY&r?iNbw@KewyGI<Z8?noJikz?E9#mVnP)5!(Ad8=nOy_j7@aiUQ>Eq>jMcy;X zx~b=<7}m_wuhkY@_w8<Qa~)DJFMio+^n^n{d@-pN>{<oY(<0wUPYbEyx#pI6{*zR& zC4x${H_QNgR3%?-G>qmI4I3*T{`@u`5521fZ3tPu2e{9-I(iauIdUY0Ke7o=OnzsU znvjpf5GXONkf@c*Q7~v^x=DSbOdGdUc3Un^I$OA8@=+G20<jG<rQ36Mk7VXkOnE?- zW&-6A;n~t)l>o4U6SGYzd6OsI*id(Q!sBl*)-p18<OyZ3gpxRw8b?i2%}?2gE#<Dw zteAiArSmr9^Z0QBCHM$DjDLy{64hf*iFBHX53mk!HT_%S$P&3CCD$2+*I469rClY* ztz1c*%26$)L{C9JmKPRCNb$N9SbtaZ>}3goHFleWx;CBaXz3VY@>iI4mf3voe@5e$ z9u}wR9{CIwRVi0C$)qms$kVbYlqUw_9aP&{-J0Qi>ao_(W}pZ2bxJEMbZ??3dD%0S zAA0K?P%53L2J=%i!<n#aDX0XuGa6`nn(cac+RI%^IlK4yvrcc*n2qvQ!Ds2upOsTq z=n?{=T9XeMFPd^=fzp8!NY7@`uAero?+j;>4!xR@TVV5eE?v$k8BPTO7IX`E`_uPL z#dlHXEb1Lc$U2RTqVKCw3T%V(EG9Nv4SL2Se<_bzDbj_|>(sQ^{4`ZOC8~9`e|)tn zVCAW*r|usy1dw<I&j4s80O*RHxs@JZ71;M&c-8yNV@lv}*X0t?@Hci{wNmkT1>2nz z;`21yB}NS{3NNtda#N;VCoivJn%~F=)<uKGMYP8#lXCv1J`*`V%E@)oSDXbTCaq{$ z3fe#{FBjU`#HJe8So?;4a(l9_Lh+$X*Kh&Q>u0UdxOC`wJf+byuxVuaKic|`XYP5* zLsN=-^Ep8RhI|<V4)>IfnG}jvtqMAXJh3Q@4Aj5%u*&{m*ESa`8<%Fh&u9xvE!bVE z0fC~b>=N8F=b3iDo%iMbPH(q<6zeP(7Frg`2bnDPAWw!T<m#V{_c($tTBL&<RzPZm z#*%=Hw9*vB_fHQhgI}mQG|J@|<=k`%0LOHtCZ<C@V?l8%l(PI_mGxEYckk1mO9&x& z01L0XBC;<8HOd#yz@1yd8=*dCf{{%4(aJZ8Lq)gK)2@b7)(#l$2#jWTzzLY{*iuLg zKzEwSEy9BRPq|Y2hD^$(Js7Sgi7^>@*2r+l*GYU-SJ+<im>z*|OvyEWdR_SO$K0^K z9!0Asnos_74@?JJ?4({Vf_i9ybY!N?*Zitm$AyY-*(#^Sz#zH+i1o@{1)tOc!uC?9 zhjN8mnF2JBC_Kt>a3{JV4CWH<G@2wzF_dOZbOI%mLRCuW|CF?{fY0A~j2QhzT;gh2 zt4$XRTr8ZEMOL~nU7Jb43%w}GFB)Q!#^6gQOqTt#gR+H>ZidN7;rtFfU<LdktrW)< zaAs!OWzm%B+@nuJFN>pBT-G3x;$RPavVJ6+J{5Fcj>4kAW>*EF&p;o~f@6P&aK84p z-J?+8V4W_gYhzkcW2#L)6m;g|Q}Mn*mCTa>Wc85e`!uM#lE5cX3KWmbOPgmnQmnT( zuFp&2w7`N@8Uxf$x_><g)Rhc^-;H$Q?BJEuK+aV@YJ`MTrPv#!C7z_I#)5S+BJ9wI zp^{O*`{en``EOHS=%<5IR3O7dU95m0dRiUxIM68f3-3WxkZ&LNc9BuDUrHvTfBF)n zJ|bvd!|t%yeFRQ^U+t4ze4a=i;{}P20!69s62DyauUVj(kUjdy9s%%Mtc5r#<sNz6 z$>XH_-H)(`-<<<tfvpf9EpPw<8V3V;!a{_Sq63~3#l~He<~_I_TiMghs10Zd_}Hec zl-<j%yk(!}!!+P|_VdJTGv<PaOA>pQ+Xd*=t-uh0{El8ZDnWk>J5g`~TXU9muKg)X z1!YQjWTi8RJ!Kka?aw@bS>z`>mOjB88egRkH1k`e{bL`8#f}MU%xA<#m7dsZr6v-f z;Za8sfJNmzM>)<=UnywF6y$sr!_^&u5pOWy_E)qs<@!F2(=qL=Sl-0L@1eYMg=SO) z02*orwWtC|herTjLs*peXCHpxe8dq(rJ(pZD-E?RwHU?nfm#M)=F7Tf$S-E{Vc(_2 z>@TF6GiNk06h{Asm#O}IEb`BNV7x}{U**Vn%N!-9D=(=r?aCBL@S@U#hnd@1`ZQgO z{_GdU9r}@HjlZJ-6cGbAdXBw(@YQH6<$4Jvv=MsU>{j@RYWWK>Vd9I$o*RFlW4B?@ zPy&?5bgh}b6nAYSb=ENyNu+Ry7-maHh!MlLZ$}s0%0Uk23hUgIld?gYMr>;pT<K)9 zN7$6Q(-PtJ9Cy!0W9AD;QfvqXvl`K9+F-*?Y5i%@{if8sd*yKsM;Qo8cAMK+{QjE5 zflF5b8fV8Q7bCye?)SRJ`hJYUyUx&$v>dtXitoE)7AdT6F-jhN3EvI(<VwGoMXlDo z(&2CL(6he1;VESLaCPK4hmzm8Kuq|D7k9Kdg`3#Rdz6!i`wT?L?7UO2`vApy6!9$l z!{FxG*mc>D+F>92oH-N|V_l~H(-XS*u;S6k#~1x^-lj4(=i_oWLq40>AR_>!>WWhG z2TxzNjJbZzfEV$KsM!k93L?Nw_`9|Ty!;3WncLD)HOHh(J}u*WV5!T!jv4AJMAezF z_gGkU3a_10b*i9O>8g`Q#K|RRRLn?$`hHcRsovim^sDnr04geCt%F>k`#uFMmd3rf zP#y5z>8FW8%bu5L@}p-0E=ncxQIj#7E%uxWyK_<H6nmRGcnQa5>AjmSy8(7O>wg4h z%+}M--I1N2K627hi-Fc=vyfhHUS7@jo<O&HCZ}2Mdd>*jvpcsB@<dm0n{aq8q#41i z&e*_w7r!a+^DFrj+nJ+oy7ohp$Cl$b$`sw<&5gB%SDKp|>~?H%&350WO}#Sht#uxh zI=vPet*Fh{A~5?GWWTf8*fr&fU?jF8BN`_(kD1oJC5AfG>Izyf8Cq+*#d+K49jwgS zs6Ri>Z0@?rpV0DbyT;PSOyZ8cjp|E6l#R~XHC18lkFE9@8OKv-wis&k_EnR2b-#C? zyeqahw{V*1Z?LQgu!RB=t>lL|&ETWFcv}o<=;E)V24mRGl!#0|pDM8ufw8@rF_n^V zo{O5Rxh{_<G}kL0Pe$HzdGib%5jCk8H)8)9J~}Q`O-1CW2e)zaFHdOBjzkTqRh)J3 z%&QtB;y$R5#G693=N*bT6~Fh)=4k3Xe&F~FJmA)9wu0wnl_4*qvb4X(KlV|Ia`6AI zw%KaFJR<}bx^BLSkE$B8-9Mcfh?*MYL);iSl;*WP9BiyH;Gb8%VaB!k5#=#%YYa;a zP#(QHmfz008ZztteE;cs68e^ipEi&7wmi;Udw)vVnp{i@Dl3P#Nf+D%6q9Q!o<|OR zk^H-72NoF$XLl)RV>Emh(-u>dr-+Z4B^*E7R&4nFCCkBD{t*C_tpr&4o2j`!_gPWm z)8IP0!}^e>tZK#PE0E2XuPE&fbgn^1wr4^nGGW=i==>i~h~)xvZ6Ph?Zq*sd_Pe<S zEFZwAhPPp9khb7&4wqU$8X~V=o&L4pKOnS*N!xRo^aB)CeB9d)+io;Dnp_nFv25!& zW}5lSdLcK&{l&#Undl&SIpgL$eP=VR_j<5WD-Huf@2(i@jjWa<b`SklozDq<UDJt} zn&9gzJ%?%Z%)H=06FkD0YTr~&^S7#vJz6p8oeH@1C3qlh6>jd{7@H1y(!!G#4wIDp zA!X(22|@C?T_jRdFvW-Zzp*UC8m7;5&8qcm0fsPHAkH1FoYP(*p>S1OLfEb@qpF}r zE4h=c#@3sSJUi(VP-+BMP{yp1Y9e6p+^`B9+&|w`TMKRe#_V(SSxErJtXpg#Y;GX< z6y^eq3$%=QqI_rcbi%CJmJP5RmK(`Pk%4fthPTwh;|RlQLtJ@*Q&)A~+t#?xoR)vI z9VmIUXp9mQ<Q;Y6;)tbUc@C&;rqS)*o&W~h{C4ds(R+Lm2Gs%`c(B6U1Hp=wEg!GA z$y+qFdX-D8iU~}J?L-iA6K2A{qcIT@Fo5K?TQe&BdMmA?&3%@uN>|d4{c7i)tnKC? zdbB#fr_>htrE&PQ=aLO>ve;r5Dd*ogo9i^lP<gGQR*A@+g~hMK?ab0t7#DMB%>F8j zzFUz&_8d%op@oUGjD*{Tm2g*}EpC;QH^5+YBJi6xitlU+wFR)SGD5Q}>M+VI0g<;T z>K!$x5QPNEo8J9F;>!V0m9;4j&ua`islm6OIjYNNAUT3Ev)*-&L|l&JGK3#vD1(EZ z>~_-QzOw9ts-qF*x!I;d`zts7dwKL`C_zt`)L}~Zu{qd<ya#Ldq-6B5ce;O&g`TsF z&E|g3Pez44@9kwObRA&UWfP#cZjq8V^A~c0NEgsX$)*KU$~CafqGBz$tOcT^NT8Od z9p{b<puA`G)*8@MRY;hYD2$q07xW<9M7Dw&SUfbHUh2N}<7)B};2j&-Tw&5NJD0KW zZz6kJE6swFo2gXU=W=r)8gPtd{Rf|-Au6Zdops)K<A_^F{$LB!-Tagl3|nKpb`N*q zaB20YWbUP*_6N;tzc=8&JB5@I*@b15ozxt1W#~KHf*tuFV37(Hq!?J6LQBzJ#-^rc zT2wQ%*%cVP##y?n)e8M*xtV{j%#P7iXJ&Qja!>!DAvnbLu9iT}mL10Il8?|6`Z{;; z8v9?-huYL>t~g&ZVuMbdUzX18bHEAtk!Ljhc6R8In1v7GueB4gEWd4^J?O)L)e}jn zj={-ei_$C3l_zBzTpc-+*YG+qZLM$B9P}zg`RoJ4AQHuD(y@x3M9Y&``d5KW*H_3@ zw+!3W2sJF-44)tU-v4rA*f&Q*eKM>$;*8^3Fc$u{bW5{Cxz7buKdXL+snK-e@(V4a zJ9fVt=3A;|LWtfvON(uuLFY<iGP&XOp@3#HHiQVZTJYYyXI6K_qTOCHO4Z8ab8Jhy ztFob0-FJd`tmk-~vJStxRa}1B@v)H#WYJqhRwj5AS55&g7<+o6j$2dD8vzYGsq}#A zm}Sy{?tYNRbKV@;o11(+$lWfmOtVH##5Ir_Puevn*<6>4dGVO>z38cyHyq4LBghYj z6Pj9)vo{5uE4;mbhhLNVs!^DR{D4Ynk5U}=D_Rw#;u+L`jPO^>eLap-?miEHHEgSu z>-%Zdo?rGdREw*c^YTc)G}zV7=!~TI*<|q--sUJ(o*{rEijYcMiclij>i?R7c2RMt zmrf<M!p(=c3!(E53(byHt$fZI|53bVtEqgr^WsPA3)@~Bvl>+5LaO?tCr3=TwDt$- zVaFm;AJqD;YomLswwcnM0hgvrvHyKgYvjV<Ns?A%|Ha!YPwwotRbnGv#yEir2`>wn z9IZ|=B<S$I6G6!qgD=dbH@>9|hZoy+iE=TS3I8#D7D$qdpea^>T30*(#{^EVw}Yrl zLlGwLp4e*!hzNfpix1vaFD1Xy=B4k*a_Og>D%kHT%*1xx)m<*tCD4MUnE~z<KoW1X zawR8Z8PGnxm_gPKC#&T%oB_mz^h(_6TvUuW5LIfZ!N@mrM+D(s)%pH*7|NZocWAFE zErA~KcJ1f+gXIV>{1OP16d&CxF18&JlD(I`U)@h)H1x;j@s)W>XVxf~qdkn#9)BRf z2!6PDbtYlp30;QX?RJWuJ(;NC>PGzz1nHO+=?>D+YHwo<Jl@?A^KBuYYJD8b5p%6t zjXdPh&c>;mfwrGqYCkpP7wwl62lD^vN1KuV9-*76J+plvK*I{-Z!~l;%SMYS>`$7+ z3Q+hDQ3lh`Oh?O488JohNeCG8Ibf@74WH@3BzuO?cu;TEdllIY!`<vn@H?5Umr=#$ z%85XwKCCVgboNirb8uDc<FuDw<41+_bq${U+62&rY0_T@!>IQj+T3oJ0S4;Dd5Rk# zoxwU4l{#m&bD}CU&g=|;d_(y}Va%WYWZ;0LG)X3%gv5gkOUbIe;?953kj!+${vqoY zQ`Fw&yL1v^6_9-gUI~WTr(oZNynh3HDfq|G+9*}R0f_B`EL4zx!MGYWH{8}XOR{~i zO&_ANae9p)IA99?r$|f7^&|sf6z^k%Umbi>sg*sT<pc_x>X$Rap;~btiPc`eY^)q{ zdg7q-a|0S(u7+EiHtyBr#7mkZd2|c}lFd-$4;I(Kz(=QzN&{{G0fXP*^ybDG55%>T zp=ZuVc3PrVs^Nyg4h$kz`BsN-dD4N14S?XX_r)nA)E`DXlL#I|lHDMA8XNOT@g zY6GYoTfXtl{!J|&T!kMQ-!SWJV9zraz7S9GG^keKSZ$cEk^coAO7-#Dz1ifPhO`1j zO~3;73)up3dJ7=9jIhna?WyXm^Z${xN5)jdNiu3FGClRMa2o%zA6qbk-d`+_Zn9Fb zEz$jhL*cxp`1t2RnhL>pBVR~_+Ru;2GL_8f9hk;rNI!@ut|{uBK&<cv)@8{EwgL>s z-0?3fcx1g(Y$ua~gnrbk59q)N6KEG4Bn|oO9snD?K8P8qZ6zH@{NDEmGMJuWeU^|g z-2K(Lm%u8)R9^af)-oe&Uy{jk3<xlrHXfu&kC0%0`a?d{8%+R^3#-D*)2NJo(Qk&& zE4DwW*JibIi?FcEa4|QGlW^u<E`9wxhuGxz-mnyuNU+VO6YWbi>8&rjvkCZW7o=gO zDhls(cX#)p%KF{R;kA8si4NL@02&rhvd%1B#vttdW7`tq=^**pY|2bm4Og$;WOn%J zM&__tEKc*Ahkgq#@Hoiy*X}FN)h{PBX)Xz5MF0;{7O>|B3*HgN1N9_!>F{Bxy#>{3 z$@+)35tIQ44|7+B%itU%QXUA{gKnQlTc?nAiT*c?fRa}-1rlY?B*(Eok;zL{+g<T{ z!;a-z9HL6Lws-%KmHreD<h)iU)wORmj79nwT_bDYbLQuOatj}02Mhnj$z84<;EI-i zbW^VCAB5j}v6hDANhiUm)i7}^Og<!3cvl1fLM}^+o*3%r&VCB1a}X=qJ+;v)2FW1J z9vsjlX-44rL6JWI02ff^y|=k}jqM=3`aOwT6nm#y!Ez8Xme0_c#6QAvu=4Ny-QyXJ zjsYbuYrtwIsBFuHV4?$HeRj}r*KP%8c2yJ4j*`ZqMkWU~@76_MEut%MMB&mb`@c?` zgA94Elo`(3?9WI7kpN;<D@}M1P%FHPa(*DwlYA`#bhgf3^`gF-&w2j#M1Zc{loer$ zC#9dK3VWa8%fd4{&>pnOh7)$^S0Wg09QLCfz;v}kr@rFq?Jp@D`)`s5w0)HFrmzYv z<Xd2<-$-_n`@<W#O-4**(Pj)H-xyApzPth&6j$R^zTuY40t5Jq8tcM57@L)dZ`;2g zT>aNSvqr}=2eAe3)E+Cwy)@Kapa?pzyv^N<?EuNNnvCty6kS_3@N7|vV$zF@ER^wG zS5z#+2x_n&b7+pTvJ`b1J7rN`b#L08L<%^9H0#KG>08m^17DwQxOKtC>qYp7TX2nj znu7z90ft3MV-<Fx9)RJ03j?FQxJMydmivISX0`C&IcXEq+|NI3WiSAc=|B!bvYlkV za5~WTgPh)XtbfG7o0yRE++SXJd0q|{ecNNz)jw#(M&mb&{1zk;?RZDPiDBD_#lB+` zX$Jh+oK_i|Gqz_akv{m9Jwi6`>N5c(!09$nC`Gpd1mqqr8}b5dKMIW=I6rp@HOK&1 zSMmr?X;}a%e#7a@e>m+_{`cyl{6b!uSkO%0)~h`%&qn=>qk`UdMa(x+W~Wb9;h{|> zPFZX6^IShPGTGOY?gbOLm?Cw<M@1S9gjZzq(YF|<ERa=(OEHhiqpkPoa8I^cSzfhY zj?zl0uIKTz(Bh#BA*luvVK?eOJ*Ft1dALWo<qm5z7Ah5enT&);^E?KgYjrya`qhkn zkFO2=;D>r0iozGeN{KU>*qVoO?d*oi6*wTU;XEob=;3OinNx7~yMZ1?!EZoeQ2~kj zJpUO11?L{iF4OEQ#_ugKN-krCD`<OhkFvd9zI9@~D{#%}ZoTm>3|H9zq&fNgVb+V~ zOAm)qwcU&aIzZ~BS2P01ZtLIOK1aK6e}Bjq>0EbF^d4}s5~cXr_|X#_@Gb7o2b0r> z4Yv>K5VS`8XwkfI(7fy(oAd*S6xLrgsOG~Ka?xH#ZFLcSY}SEOzJ}G=`|kGa$JGIi zV9iQRJ#=0~bI}?wiZ+N`=@$*)I<s>!bie=wwbTpUpYWMs`Tq}f1<K}Q4In>}YCjhq z4F9oam5QbP)7#|M?sQ7f951;aR0z^)1xZ!Vl>UIwW(+Y48>6GfZj~VQ*!~NHxC<k= z3v)mJ+ty5ar+MS!)1-GIryrEIENshTX#4=&!=2z`dFksgSD*-Hn4@Eu@)Qw2aK2+e zP0_{rwPX*=D33Uad5}08^8<1QoS(53eL5ft+WUTFm-zZ;(pc<`*Ih~Po`#7@f<g$4 z^RkZmkvAk-_NO1qvYiT474mKL3ratWEF$f8&@Meq7T9?;&}tg_V}EQ#RHVuC`i<+i ze!IL5erq=FtNx89BTg<KeRF0w4o=5U^REDS%z%7cKt566op*6})=%$zj8m>?Z*Ey& z@P1`TWX=nq2?0R8jd9u5l>2Ioz(>pH`SJ^M?%&l}d_Dfk^+mE$4}W{Fq_q@~+rXbK zTPx%0kI(I&Reu|b0LUKyftOPTwbMfobq4%9+Lha<4?f1-xwv~G%6j|z^qpXqArp>G zpTf-)AfPmxuaTkfJ`L5FTzI4Z@r{0&jeb-eRv7t7NfZp;d?oOmLD*?5gqVJ-NQX02 zTe>o#yC_&wty&!bkgcGpP2uXNzq^UL(GN=&CTic;gcrYmzxb&msSDB)ushAA==K1U z-;xI|$&&8=jw?K>4a1!=lq+3t{Qa^)M`zPPzT(7XwO_=H%xJGLFNx)I1q!FcW)z+5 z#RtSLzLvw|Y`p(0zAw=(B`Z$>sGt8#vJwTpk=OWpE{|K`e<oi&p`mwT?#>->()kXe zp9EqX+AseW9K?3qz!rM<vP}YI6R|r-z~~EeA!E{e0pM?S5zlJ%Hr1W)35}mGCaVSD z<aQX8{|vzA7|uj*zhh#}G?wK5l)%v;RKv$2&7HI=q<>L<K<4Mo5NjhdBS}(FGLPB7 z`Bso7CZ&ee@*CG<<#Vld3G(+I>zU;%ts~3Z%V_-LYI+lDUnu?jb=c8cT{AJA)qM|j z%aSz}&F`19w(N1A$pJ_JB#Sio-zx8mk>%jYWY#pN!7($|91WC>bU$0bBiTlV_PY%5 zVBkFNzsEO#bN(-`J33|z_FtJ~1g~D!cs72HkNoC1bGza1?~leiV`qOJ!~T*}JS#yG zYy*ouUwQzH+9VLOfLiPn;ThfI^ni=n;P&FiUunmV*rS?fQ5&P^Z(8|o8gaKP%)U|{ ztPiJbHa~fMtL1}E#G1pKjyPWb$#OvKkGWIc0DLve%R5=$M=#rXP^~gZsw2fR0NZ=V zG9UsaL)_(M@OQ*mu^pie@<dfI*LyTi_46HXV;rC;1NMmywEZG9k<9WcRqk@eY`ash zm%_SQ8n2{H;#uZ5faoUQYn|rf#M2s!`J3a-ik7zExXB9p>uZ13?4dbpgQb{N=QmlH z;6+kTAV`$&dT5?r+|M6>g<`{32QmaTlaO(dn`32~*Z(2Ue@mKfy8H#skr1>0?%DP2 z$yPf#*VCZsz=n`5tBr-Y_`9bMgm7sA*(BApoGTi^i{HL}{3v4Z?|AKDZ+QA=6LG^C zKz&7M;yVb9>52W9@}NnqR9R9hkWe1hM>>4UbdJq-FvLv$sGrB$%65>~)Q8*Xvk%fn z2hj6;y7yZj+7w|&w3U_D`ga1#Z5+gabH$~byf`2A?2g`-usWT-CF6lMM(p{~xSxl1 z#|<lVmF}EL2?ZU_zP9=|=NdH;(!JQO6VZ1>xozO{+4q+3VI#T7{tp)|T^BI2UTl9H z4t}h3u#?@c)R{ieK4mnvp6juzmBVS{IN+1(6w@Dt(Y>XeQXGSH$dlrC%Wl)WbQwH3 z@91Aq^5#lNFaKNDXyb!al~$@)79kaNbHOV|Phiof#O>yyUtVerD<b!#hFvQDkhU0{ z^T3c17+}DVrPzVebe6ARGK5IA18y$McL%IzX)T1@`VhZwERd;U*4UpF_vNqPN(_nJ z3nHCFOlBf8-^4-?KBXiGBAiO{<g((bPJy>ysZPnZWb$GrSC^vG#Rli!up*FG`m>5Y zgU<|{rIWQ7SZ<RIY9Pq^(zR4Xy%}lyjtAHIooeHSvJ^r06EQHd5B4jIU)%=Ggh*~g zq?KKLc*-OmOwm|refPd(uYE#aXuqTS92lS!Yr%QYwOLty(7oR$^yS&d$?~uWzUBr& z-MMMgO4a%@KXl|T_r&^8`VcS2e_R<#40Q-rHdN|eR_=|^Jxe@zJq$FpiP?x?;EZeW z94>#;`)x}v;s@pV_mJKGmzA;2ud<Fl{C9?mt&H7aj#<gMAbk4m%9)8!U}juulk5#O z<J=4Re7J1%fEfdey;pc7M5>7B4N<Q5XwC~74g4Fr)tj-6@*XT6MuxQ?`IU$3_naXO zIsg8Aj#NbtZ}S=QMK}%E^b(Af*rGC(_?m+N(y4NtMCl2iAzQvW0t9s_bE<faHOk;+ z<w^eS!GKK85)35RF}7i_qL#Rcf5#T+L{|jSo%0(r9B~Uck$+t2df%o@DoJVAro0f> zxG1_bPaz?&vdt$fD?s>iTFeMtS2MLH@ND6w;zN+a;xn7v)^&75tT)0YJymUxJ2$j= z9l0Mcti1!{e4UE3>G(RN6MBm?Vvhp=N?sFXb~Z!)9m>y;-{6IwR`#?SA?V1jlAFnO zjQ{}0qU8kV3Kv=LTB?-mCyO727$%F`43?WGl$%RkcZQ<R32za=Tx%+41qyz)SzUu` z3SscPs1)VQ1({(LS#<fu4U)jq)&bdg0`zh$1W;;gEK}E1#_EN)jS?L|*;Hq0JFMB= zGysV>+1uzYGvA3fWR~M!w2|K8syr&**8SxCdcDj3#>Y}u?)f9ucr6_7@d!m@A+Rc; z+s@{`8vX*3mU5oSi#wSs1<e?dk>U8QM&RC#gmh54Ux#-Z*z2O`%WCep5kk&d{yFvA z*i2hK^1a%CA&p6(CMa%Q=sPh@@wmSbwaDA3Iw%#Rb(|A3C?-&BW#N$NBMwLbas(dY zc&^ZSZ{n-X<^U5OE9Jh2G%SKXY;+!9usC2-77pV!;1K0z&N!3xstNCvc9pTXjHO=U zo;dN<S{{7<=R3W#p=Ct4;>miYf<}kI7_-lW!^h=E`8}pqd|O_@$71VQN=^-hPeg6> z57BHb&J#%e)X9atWIiC<Zjkf4D{uP*I;Z;^(tc!Qcs8!XzG;zlJF3}9m^7X6+ZpP@ zQh;?~!Dp{79YiR5=0wmT74PA-VSY8)g{^I{`vxW|dnC4iDiG?&PN@Es%R}06^pb^Y ztT#ELv-nb=?@gf8^0+Mr!7Ngy$aS|MTMeYeH^7#VjxFf=RmZ>!<0wWBYEW(Q2eHgn zL2d^rGTD@*InCT_<E;tcnjG^DG$&m-q*6%AR+$q$<9wRlBIh*jb*Xhh1$ONvpT={r zMf5Cx)W`r*--Tw?<k$L0Spmd3ot0B1+h^{0Tv)d3b0tTuAa{-l5Ob6fb2u0N<TNBQ zl2NL5%OFS&@U`@%tDnkU?eU@3A?@*1v?9<Tlx;BuIk}p_^A3mFC7M>Aws2f)5hMCO zp!{F+etpi{<{<jGCa})TwBBE6Q#8x&#$fRtT!sa(W60x0)Z5ekH0!$0f;`R|4boj| zi5;&ssjLQb=R5oQXnbYyLtRBU8452`A<FqA4tmHFzMz$+$w<qI+BnDAPBm6Z!g~1( zda^VTl>uD$SO8i#Rqcswwa21huFG2jjb~jrg#OhG?JBH&W)n^#B~hw>g_*NC^=ks$ zEiB=q&_{C{Ve7%_9A5)QksnoLl}WPC*0{B$#xc#c)hRDYOIMilR_q|^;4rg-EHr)T z`}-BwT*dEX4u_r4yZz<<9<?CEshNo~*BwEC1E{x~2-O)`%}M;&qxrk@llI~LxmKrk z89=MWNP`_g`fq=txt87KLPUuzU>yZ)DZe>7o$Du$%o6Aq8;~$8XmLqF^t^efGnmDJ z%M;su4=~jUAZ5AaYr%hNrOGd1Qnd&}{BudlAKZXhaLX8$yPtlbj;qS-Q|eh7yZA&p z@RNgw)$d#3*@X0Gta(MC?XtIj&bD4{r6#p7ZQH)dQg5+M^KU!{FV8p9Y4x-x%QjSf z3Z$FDrZ}#)GGqTtn`lJ7NKpTNv#RL_n*6Sf&7IKCdrCBY_1h{kI`*mX=1ZG+EZrnS zE&E!1UCnwDn5~chRD9FK4rWyV(Z-`80IKjzbw`Ofn)%a>6K*?AyEiMH$H<9BJ@uH6 zE<wxxe#CGJ#oxcs;aTbqgy#caAIpo}{vy!~MCMxyECb;VtAhDh5%JHgcKrgbo+4tF zUkEKP3H>T+IF<tgmJy;#^UC2?6^nHBFpXHjN47WIw1I%2a{U=>iofHhpf|XfNT5-s zR}&-s08X^PE*f65%D!>tiRh>na$-KeB91(M#2S0Qpf24q#S)3!M&)ClXHo@AU%$Tn zWuuZ4QS&GkU?6<hkFqkJPR@U2q!b#^46`zqzu9c@kH}vL;I&$1XIM?B^ZHv^cfW&$ zqj0d;%9D#aGLbBUY&l?g>}eXi-QpN1G(`HIjul+)e|wV6_LoiA@nAHde`*;k7_j>C z2bwcwMc@R@2&_sLzyI>rqzcn()$Rx7bpU>&T9)&l?WPDEqfP1*HjR{QzL-_yR!G>! z6#OnXV&7VmEuBtP<>jcJQp57qV}+Nhh2LN)q30B04bdrNQLl9A7QApLkT^AsdT%T0 z#e_aFjOcFNbw8`-y@loKA;L#nPpu|J-jg;n{Yw^XP`l{$C1qso(UWU9QNJ4EWcv2E zEU_}NqA4n$Za-U}>HXpZv*KL2j-XG42LH532zrgeDMl2x74AkWtSL)e8x(R1<Kvq; z)#n!dj~#yO$?wxI%(gE<00P{(S+j{E?$a-w#=it9x1T2;b`sf+0VymJY6n%r=jA$# z?sJ&+!+gC3Wzl-21?b^I`7xD73MPH$Gcp^<xd22}VEGcUa0rPn(Nk!=MyL<?gPzHs zQx>AIR1=#}jh@e^&?1y-Rz^=mDW?>Dql|1Vxy1<B1)|>EPa0Qw6_lbh8!7n)i})of ze|&a-j=0J>CCcoy%D-p8T$NI+&jWM%s$MR}Oif1gRHw};-#B=r)Q!%~M8lWSQYd>Z zOAdH=zktm&DtJ}E2P=R%#{n=93HB7BLl4dJWzMk*Sgg`73y(FjcpT6i@dbx807L-| zyRnDqYL|nj^U8Coe&p3(S51Sw!i|uG>Q=d8Nhl*M-v*Vh#h(kZ$`7lV_;y^?J)i`f z)uFB;t33IqJWr=qxq7O2chG!56{*X>N!>a`_i7Bs3^E4#b%VE$g*lW;LLA~{9Qj~% zp3H>?C`K&vq-e1&yG1EY?jP?bo};9tbe892iL*$<E3a^Vj|L5twO$`?*qtfDCG+<R z`vp!sMZN(AE>*KH5k+$CM4F3aUH}Bl@caiW0tZC4PU<`Ss)`|*XM}LHq(%?qa$1bN zmkh)7&1mcv7=3lP_|w5;$NuhUKO)|fV*!gYB(cyX;gz28zX%4mlsQtlOnDrzV>{W@ zRa80}4xqlKT5^nwB7U?eqj(Xc;rw&esGe1M`3(s#Lz|PiCreHGulohX&6@@pIEVy6 z#43BEsBE89Lhv_rbNXJeI5SODn6_j33}?s9hs?(chTEB^J!UhV7hV%x+3OehwkqsH z68VM|(eh?D0s?+u`6K&5y~T_#<}4+$4(T%So(a;G{6pfAtk7AW`U#P5Y5)C<4E$CB z)Qz72ax^gr`&u6%@v2Gq+A4c7TFvqS=WP=9ui@^_kz_OejBynGGg%tJSa%HwSG#0C zO%nWIz_+rBF#OJjjo@Dx6XG)zXE+ej2}OfrDw&d{l9CY<)hKs*^$P?z%?V}$0lNS? z(1WdA%Dl7Ye(Sb6FPpgvbAkm}!LD6Y?8xgQlO$+FXc8!_2-FI*yJGK%a_E=(vMSK= zoxk^z2;E-x#z5dt^_R$1%WX%QCTrCLMNS7Gdk_1d39g(^sbbWc^$?KiiaXA3gT+_# z@X-wL_mF`Ck>{Rj>E;n`<g2RFU^G#Y{8gw%wIlbLx&gcf&Mjl7<Y)$*4MPrN<7gtc zNIVq;-ap*twU-2MR||JnM^BAmKldZ4{hQ*~pAZ97-#4Nl=%(XvnOH+sCpt~lfb9nW z_G^mTIT~M|B3mgYFfz(Rn!ENGC;Gt$mB{Nm;CQ6~O+WL3zW_ykRJ$}e2vjKu+Ifl) z`bBo1CT+j5l#{+K09I>WQNeo-9~(eO5l1$)9DHO>j(%A1A;fn8lZpL6yqqkhrGFzJ zeS8(JRn0#`Vjr&(s4-O=HY|)4yfoE*O)A1}wN^M2DCnf=1FV9NQrQH)^45OeaNvMj z-8<J@jR=LJVg(y^a+0?*^oUHMnR9}PXGStfjxsjuD2K0{0Dx`D0hc)sEORiv-N~%m z6NwDgacalS3`7iKpJR#>Yoi^evHSs8kx=Y^x4sIWU<H17iYyV>^$#sSYYOf@{qjGy z-ZQAFHf-BnkX{MBLntCm1f(ipLT_R~nkY(DK<Pz5(9ny3p-R=zK~d=-D25`vgkD6Y zg9<)?f`}zw-o3w>{r=ehGn2`htaZ+Pt@ApL8cs_oiF#?G3J(O(IME=#+`u!Yb$%!| zIX!A|BuX!ivnEP#W9NDTU*?%tu)ydO%y)(<QRlO%wg+FG-xqgE&q&FKaGW_58mkf( zvKA(&<%GF#yj~KJ=W^)g;o4`3@0dN|S1cNCny7mDvDeBCHeHKmHJ*}OaXA@uzBBjM z5~8-!v{m<C6>GuzMPnBhAy#-cOgDSh^0f6&qB{3&?>VLKVxV80JiE&x%{HciQIU>} zV$9Rbdk07N{yNLJrkvS7#BMl|Isl*_;4UNgg%39j?jVoI+($IO+3$QN#nwP#uG~V2 zZ`v7~FN*t}Jcnc~?V`#fah^3G&3@p($L%s=;DGtg>5DU0hL|WlN_~)yS|f{umc+-M zN%a&Hnj5-5>@4gfCOXskCjM7RuyLCY*kV+iQPFc#?}%-~iBDflpuUnVam^qPX>#p* zvI(b&ODAudIqLVm%Xg#f8~<G%z!i;$T?!=fe7qca&<UEqBkHk?T6uKu^PPu3LuI~O zP*25>O03M^5_q?n7Z<NG_?*nkk2#WzN+nu|wQ*S3d`UU3IxW~B$Z?V@dgL)f?EFP% z&Mg8bj@zTMC$!u-AgJr~<uH6R585@ng2jn%0|>e6^89;^_4{Qt`)GkI9RC+Fp{G$o zH`N+E;bLjOaxq=Ld_lHG{CuJ2TvN{ILp)DSu|eiqep8-G%elLQtZhI)-nO7H^G8ZT zpmne_@<(UUNJv^kR^;;Ry}wZ}5AxEqah8&$ySiIkK4Oc~%e?ypRO6ED-Qf$DS=gpH zOCHv7;O*l@T3SVgx}v=BJ^mu+R)ormg*V6?+jx;GC$=&%d7V49vn*wj%~D;Of@oVY z8q1qxBJZD+U|$W~_7cV?Ke$|VETc1Iv&VPJXnlWK@U2+9`0HFHU;P%wcJ426eG?Xy zThm<hB~BfpNEHD~O%oRPjA*{n&ME)k5lb1Z0N*ulX3JN>-|%{TZq{v?XOW+GE%!xv zmP3Wp!=Ig^TS7bmoman}<1Ilb12mGwGAD`1oe{;c@5Gm1%<<Hza4R_dyj&wrVjq7j zXJg_bT-bkFcyfH><c(-zY82bb5*OJSUf7l=SIy?ad@uV8Pg-=UbG<d)$?0-=CNlNp z2A=belOPMevY1;$q%lBibOgXJsr0DJYfq~FZMkhLlu#ftt3c3eH8pp}mQi^soZ*Kw zfrw`!FXlX7Ej~LX!_&(m^~_eddO16t7&4}H+a`_Yh)GhlH=SqLnLaziJwv^>bG5@c zD($PF<+oyAMg$4>0JTpO2<hb0Smu4HTxeCgXDrwG;nel}19K0HR^<K-piL7)dYDXn zepx+!H6kJ_DnojN>zFJsDt7v>Q8BLZF2>XBTRneB#>`EAV4sEj{DFwPN-t4q-EWzb z++Hx&zd`yh#QR&4!u(2l8x`!LNW3IpQN~-6A*|L3HI8Zt{VtTz<M~XzGYxF^agBYT z?J(ts=(M9r<SBlS&fC7urt2DJ>uUK<V%)oVqv!oZd#C@)Nu9UuB<%y-ex0lrJF(Kv zQFoU4zu?hb)nxu(RyktzV&VM8EP@!7&vKvkpGnO7mh`=6IP;a^F*VL?S>!3R55FT= zTKgiW?e0n=s|25liB2r2Q^nZe3_jT(ag&b1L1O%CVqead2+_m@0X+Xb4WXIc{jZ;e z$`v@wbYvsMYBF4SJIEYs&TRJpf6|K3nix+OPeDN!7cII9B0YTBO4zV?d+ZZ>@-pw) zah{E%4<9~?N<I*+Abi`gd)$yEszm`Cp}z&O;P=;9cFm^WXjWnOF7rH_Rknzr$5wau zaTu7fKV$CTKXZK<FM2K-Jimu)4gi2Gy}bJJp+}0YgM}sy6(a>2fnOE}8Y;)05Mq$R zrj1qOrN&9|R|XqDTlueaM4mHB`%o*JOWv_88Gdw{;dJe7yy|q{>?`kO>RIpb7nga% z=4S?rhE%>Z2R^fU3aV{!7qQ-@YC8Acd3iP{p}6|e<_ml6fTjL8xt6qit-FoK>vAxg zs}o~Xy$2#i->X|I*7}PcsC!Ue5-U1byJNw*joKI2{0|SGKW-$NWc*P&VTcxTy6@72 zIvMQU?&ALXxr2Gp*_E#e4X#EojH8Z&|Ne)zVBaV5k$?WIM`tU~3f%wlcVNZnzUbS? z+N+<hWXtEB1HQq349UCzXt0yn@@wPD*-l*vJe+%CVxrEm%j0o;H|E$+zVrBw0Z8dm zD~Xah9xF-G6;&(A#8cTEjse7j3z{GLV@z;`#tjGtcLn)`t^M^p*2L300DbW)b5O~f zVy?S>LHz(1gT5XimUB_gt+C!*r$pln=Ikl4iXw$CjjO3{D_I~5HGrmPrt{T$GViAR zjOS)ix#o#gb+5QfZXAB#g?!b<I%SNouX*68dPeFb+TSFRW!RtA!!cA6nLoqB)1P>` zD1_?s=z~jZRkVfj&$$3LogXZ~5byQv)iHrrN11~<htrSD6gJ<nINg7{2qK777IO3n zSNe4!q(c4H#uYr|&5HG%nblAcfg1(R_?a@blT25Q+_%=XoLdUX7A&+f>(z+NG+BMO zCK&ew@XM7Fb9?oaqe<60NyotOKntBPe%p11P?&v}oyzSskeADsxdziS2SI@j8rANB z{HNw>zNe~h#>*>vFrFHusg&j__ltHXbry4l<+==t1ocbI57hOWU!_*iloD0sgy%Ok zrwDbql|~6qRnEGIXQGu`mt4oRTef1@6l&Y*$HHr0Z$6B?vg#!=eN;AeU0J3$aFF+@ zQ+-X0pmSnh)S!!QdVT0^{fuV*w22|jpm>e_rC45{qvb@ogVTX28J8}o|7y)N<kq$# zCOp(xxP_FNpiJgn{j2b*^>JnTB<5Op6L>^8uxw3{FP1x}@oayM)!5ma;R+V2AAe+` z6@E2JoGeP>_0=-BFgd}kxelxf1ZXv+m@!10oy5oZWBVH}XlnlE5LDD&-7{4s-ydzY z-bvx;t1@};r6c6oS|<9`QLF2Dou94BadIzcB_Fw}$q&N=qU0j`qqUA(6aHESJiNXb z&3o(zsr%TQbhgKvSlBNprDm_5Xx()=Vu-FB;-44{P7CcbD@NM&ckyJ@m;`bpsMDBR z{e|NE4o(ooMMB(g)Vl=PGYQ|6o3iMsKBoeo8YyL@vsE-DafI<Prw3CAHQcIMxbuPw zB`PJfM&iT}%1CvvnC<EmT_{4g7&Qx5;2TK_oAMj6d%OqJs7>JtGwv3WUxljolnU3@ z*}Y*NJ-y^lUSQ$uJEu^mQx^Fp-G#9->g-2szcMv;?^|u(f;I8U-F_F$wf5{ebU$0f zVl>YoZS9oR3f5+gRkU}jJ4($y!O_E5On7Zc><3TRZJTI;LY8!adE;Rhf$zDAw+0^o zJlTG?$3&W!^tq3L6bCI9zP#_q4X7pB)5$#Slap!2LR5}Key_>LM2_4Al@u+K3%}D~ z0{<K}rP0Ro!2p#{lP^0Xz`9i67Y(AkZ^`DH==!8vze4xA#@VXv27z~psrEEjg5B#b z_yAMv^v@C{+tbb4zBO*YYlGfbIxV|g1LLiuG=4MAI5+z_Ed<y7?hbPhX4UXSJA*yp z^ww(SF>@P#EAUClzL(8$ts6r&_^imk9hcZQ1dvFGWrCjDE#8Jjs;w}%>)N$MVz!5o zdh9EDef~j>hj6-bcir%-vW+JP6w$K*IEd4>2ipOM45g6wLFnz$yxaZ{-VR@WRFwr1 zykv?{?k6YbRDsZap?%kcel;#dCY}&w1=M_;AKrT{p;}?`%;TX|eazVxcU^xKt4u|q zREAmDI;!FXpkgVtZkz?rFZXFq)MtgONbqlYNdDI09_UV#$y}kup9)Ghy}KmAcHQrt z_Py|js%5&Ot>RxIn{PDTrE+BE^%z*$II~^qap9LJGZt=aO3_pCcqUi~($im=M%k1I zuG2qw{2co9@3`f}=Ws;kFvB@5yjG3JE-{+Vt5ff`*LS1Q(q7F42mKaGX04|ZQyPLh z50F-{bo+SiiB7aykhqA0kj>5%`@@D>n-d$9crAc{3Yu~il;L;LWemBly_rju7B*6Y zM!l-bT@j}DgOudi;~e0noy`Zy`f@fop}F0HpTUqF`?f}f?rzU_9!A;<%%#=|U2cGW zk@Z(y{N*gz?Y5N!`ETh@3%_LXysC}UUSmgTZP)X*SAjVcLW|?IB%fU=>i+oUeY$&! z3qLv2^x?@1pG_+jRdeGJ73!&<v#m?jYvQ0nWrNAu%&|sG_P+F}zZ9-oQmA;fvF7H^ zDSlg!h)75!*EF$~p@i$b6cN=s`O&hjw^(0*a|WUSkR-*@T!o?=8q3v-TpiB%o><?_ zEVp`oA$V;WQ<2!O(p;Yu{^6E<j0g1Do4vHCHW2DU#HZlgkRrF9u_r~xYzl6B5MUQn zRc+s`omS`QxU*WxXpSrDMm>nc-4$G_H9Vc{jPc@<pgTHJ^f(%8TAXz|n%#ax8?)O! z@W0VFVex9v?y<OgubYCGnBTc6BI-PvmD3rg$5%zRlX;&*$!+7SfykZh3Mm!bp!6yB zD<)jmkPl$W%DPjAcq`{61P}WC&DvPfHtlypmiZDM*mvy5=U51o(VuO698b|&TH)^? zfCN5L!J7RHP{iT>I9?$byRZ)8@ACfCEhKe22>w#!u~Ui6TR+&-zXd!qCyw6kNT7c0 zy0(>pU!KblLtSnyjpz9q@0C-UAD}3`8uu6kYkKOD?rSE<qo+B4^WyIXIiKy*Ps~iU z0^6VcW#Ox#>2tXG#RV`(gE2sbS^Nu0$^0=DquF@16?QgnN(nNs-)LdW4|<a>@vc!X zURx3k_`c=?cy7T|w^CBy+kk#Hziga;B%W$dJ?<oYVecFSQtxSju$H?ZQygk8>%u~o z&psIof`sm=`93Zo7gXNvp<zFguv@tEN4pSzKjs<Ev9OQHF10>?0tE(JGiJgLYpn;U zY>ZcaC~!6=LyWs}9Fw|=*<nse0bQYG`JFhA5RlD_Sr4Hu{ygschM}>>9-J&2u8ILc z(|8P%uNMX&=iJbR6!3Wh<o*(BVpp$@rm5?yZ&ByD;ujQAFR(+1d_zNc&|n8-Ec2Wg z<mB>$8u`GP?P@G`&hLM)qZgxs4(QkkGMlO`6Xc0G&WPP_(U9uKY~qZMe(KeUVZPy* z`V=+~7|h-nGIj>@sq{k5zWe<?D~B~1`jX1qGora!|HE}`Q<S&zLqUnEPq>)Ebkr;H z=%4tTM=@%#{g?mlN_tLlMY8fQEM4PQzy5{<dv;TuIOl<>LzR)Rq8#3g<j~YP`@0H# zvF5tijatk;g{|2SOec{YoIxr$=zTm!TNn8#Bk{=H`F4i$dy>VbA9jZlf3S<4rOG={ zAut!r4P~Sg4H`>e+oh8GYr}e|*spY~N``<8Qz#Ou`VFTwO%YI*zB_Mkdt;Ndwkxoi zbD@HC8kY4icbEGv9(10hO;f~RH?%8ik^O{osn*G)7&W<m-d{_KTT56QGT4d)sidI} zscbiDq4*<T165H(qihRBuBe5rpNjfc>wC-;U;a2P>mMV^#lh#I?t2OG{AY^D9&wXw zXfT(4dp<|o&|A&fdyT5_ksN$LyOaR%Xe*yF#e>Y~@eDrz{>wOW56?EY1o=y1o2tzH zmHTjtjvgT(gUL`!9JH_&RpW&ITZ?T1;67B?AQfGi!5sHs$|!8xbS&qg*eAcU`*iFG zfIJ_Z-kGSxCz0;+>Ux08t-|Hh>0M+%kM~CqdSB0^0s!W$QCGx3+4Hcd*bDERU>CSV zUK^hKNkJbG5`W_FJ*!2U)4<<;p#J7WANxUX<IvTLqLNi?%@jgaKv9sIBXUy|-oggZ z**;M*b2--=XD((Er4#5j_?{GpX?c{32mA{T@iZl^8FjPn$t(V1j&NHu4Nk&F>b)xd zFak=ORY&m^%!djNB8hn$Bg>Z5vH=LArWQ5WRq}WV5v7Q*#4)!A5$|Z&&lK!mJo+U8 zev<$TuSFc-*|v8nn}plH;Mk93*9`!e#<O`ZV;f1PV0S4I4hK$I2iKpcN9rz;^~p!- zmR3+S*(mdD%musv$WzhFfeiB_BRmMuFg&E6hUyJKRVs=!Qz2nAuqF*vlz{~(*ydVj z5e(`@L675}1jV0E8?1U3jS7l?@SAWGps?*PC2SD%6=(T}Z4uWIIoNcfPd6-=nnIkz zT~Fkg$t{0z{Pa{~s_Ne9H4;AnxzJ2N*0Z3;Y7ux-SSSv4l?FMJ50ay~F_ktoyXYwZ zyG>{QBJ^Y}f|2hBJ^uw-Ku71Wq%YKRsYr8oB?f)PV<vX*xW}@&mk2K4^mswfJP*?6 zZLuCFEjM}GvomCG5YUh#?m<t83m(B_`F+X*^_qg@2p~-wIFJNW5UaX0g$Qy&dHaEG z6JVnhlQo%Yiolbq73||iww5KfKe&WTWdhInxdW{nWSEr518e?(Q#hi>jd@fy1*5d~ zLZhG|LE@Q;rLwHji%qIk3mJ98A<khB>{APSeT?oUK>t!pN$=T)6w%$ah;RaIu?3bv zMbGb2cBohICFyzZ_*Lw&U8|^qo2uZrq^T{Ec}YW`TZpqYW{M8;x)YJV%Ke3kY}`#| zY*eA&w!wsxVV8h}&tz;u0ruN2ss})N5n#nm&~PfOnBZsIV0~CB3y{=;4j+G`N3{?L zjCj=bcr=}Pzk~+p!X!?KX)O3*CH0Z~EvTpJurt4H^fYXrBU@g-Z@<&kz;o=X6m11I ze9@tZ9H8DF@T(Y*LBvyFwp38$6xfyuGkFGOieNHo5rc}D0~+>IJBNzKqv|>ig?h}3 z%a}w}$8S_@RO^+de8cU97aeBiw`?4|{IRl^Ub=*n>y}VOx~RrlB%LlX#soqmU;(=z z0|4aZ1i3(ka@4?X;E^{7r~(>#7GS$nN-!x8`$iBEYL`8tpsz^OGk#K{+m=Kthr9$Y z-zt>lRT$6T!D9;*kr$g{c5EPG>J6jO__ea@2j_b9BgARXVii^*temm`?Z)0$gd>kG zMeZWW1mssb+uvQbNh)|!5%b~wn@K#IOJV+38g|L=;U*1}JHxLJ2R7)r9&*=?NaagZ z1%P_4=1Nbmo5fHd?~vd9zk==`&mgxwkV|y5a44dcB;*Xh%KQ+syGT7eVwg0LW6l;l zr+=vo`!|ZekxIy~l%35hGC3jlO0iysuj`0}{*UG*bIan(zDr;|#`iTUs@7~G(WWV= z{rbC8iv(L*O<$MRaLb*0oo3EOZ6`nNQWkc5WMdq!m!cS|39tQW*lHQf4kdq~7Bf%l z0UxGbK#qDeVsFT~b_GUloAo^`b=_=iyG0z9b+ZVZ5F+clh20sW(P4Rs7d&plt_O;0 z1CU34sOx0x!&>x%as31(gMzDF)%vP3=xdisQIqZ>^#LN)5vuhB^w(PK;_mbPucHrE zIT{wR3pBh>H)4u@4IgxkUPV>ZzOL-;k-e*K$T6{7IC=It=cj$n?}B>v@z)Q?n2m$G zF6NkyCB<U^btt9!@D+NB@M13L4$be5mG?A_Jheq;8_Xftgky~o>d)^~pK~;Kjhq>h z$0QIgI48FpbqRQGYTcEAB`CrZmP{_um`R6X@VytNlQEPe`)9kEmAcpHOITD`(a$~A z!(z6%U#~J8WVi5ae5GwSBj?-SU;N_I>@tI0!?ES=5+CryqIHowG)#u=%+ogu`8l3i zbp^A{o^AzFzwEK^6(w-<SXwO@Iumt|0!_vjOd41tV$V-<Kly`)M^oAIVykI*+Y7Sk zb85HlXg#X=pj$gqP*^PW5MJSYEV09f+ONIS->Dp`h>-e{7DETcC_2Kdp&=CO_Yl$f z6LN>%B7YP`5O)Z_>5u<Lq5P{*mG3b(l|Rg1_@G?JA;aR0AF-VwA+&Gj;5!kkfU;~S z$86EECgu^*f2lgkeb}<2vJUIBY{1Ap%2(x5l4)Hz#3?C!T={mc>?K0wt6#zV^W|GT z%hQe@8lc>|l5C?gg}B4FJG(tJGR#vE`O>K*hJeiU1D7oomI4@^&&*!7-^H-7c~8;F z>>|106}iz{d*B&4mJAUeZ<V?yaxC87>`$u(J-#29aVM?@J)SiB!^tOQ5#97crK@Zc z@46PgLQYGH4#k=x??O+^)Lz}(8|JFJ>hRn|huC4aDRri7H`ekVq>R3H!2<b`4l~+~ zBP${@$trVr(jfs|t>5;Aj4?Vhw*+H*VwJtTq|}|e`QIYv0v+q~eIo_RvBP~MMQ1yF zangA2R4%5#k<@Jz&2h4FgK_-o13=&wOq%bt*p>_0>585AJ&5x;)lVZB?=u<f%#_9g zpZ_8ga9;{Lz<ZM_?0;Xi5PW}BU=g2<r<bumZKK4zcWw#~D~a8*-$-3>g0t&PD!rkK zcCr^bE$k-j;Qo8D@R)1n#rA&fi<@sg{QEcgf@e=bW$(2AjPEw;CE?|tXUc!~+&zK9 z0-ush0AluWKZJlZib3TzUfTI;d~{8CfPlum+9UkOFO+w;f)~zT?_vB<tX&c5;yx_G z_`&W_T%6uRm9Srr{VEZ;N%GaOdUCgYmOsPte(kc}(Milb3JiGxdFIpSC)dDr^v}=7 zA)x7jL%n>*c;WfZPR67qn<!_u{r$HZ?Bap*SPW}yYRJ*)kr+uLatyCu{pNu3Dc#`- zm$j(<$j_f`KX=pbYh{XZig9quJqQ7N>@WO4rU1whKfVzf+!FwlKEX&hR4MQ?)CpD! zEG<uWB>7(~Dd8(bBRey<?mhgawb!-ogn5Wt9?OmK{B=~o_+wbLS`t+-CB<JCvhf%3 zw@31?dht@13f95_Bj@T9e);rcCPSK(`G5rzN&olwBh2T?#{wPr<0V*?8(Rw%h5X=N z8jS^tQ6F9fECUq1T+*^`JcgfD!x+1wpUgd!&G~5Wil$d^_(Af4<(hHE2~F;EF#PJf z<Wr6vvHX`98|L|{-XDANE^S&o){guK7O>tTl^Dd_81_)P*?z-uAu>kV;)K;xo6P32 zr`BI>UpT(G_a<-p=0xBWG;e<$mHX13oJ^EhH~DZixXkc?MgI#a-9E<n*WYuW(-rQt zdaO67^A@$eOXZiF$xd--_x{us*N}ht`$mm%;I(fd7XK-y59#LUf4Ie8ZMyTC_y@|p zeS4wF`%^CyOYgJz==66TCTUSExg+ws;p3~n_Nl#LR)3|wT{-6z1Fb%=NwlwXc_}q+ zb7yC=ium|gC`mPWD*SCJUhF}kZ{12?+B8uw9_{cZ@Pnj<iUNTJCb_Et-0PN+2v9p4 z%Q;~cLuxu;JWk$`-B9RJ)WfK+)#?=$zCYEfur|=E$9YkITn=})OTN@+rn-+yGa|1i z^TtQnUdpeH=neL7f3}uSAI=EAV>?ITcjr0|0kh?~QNt>We8j~!OITm_Fjqq{rlhm} zjh-iQFbT<l#)l!x`fXKZrgaz8KgFK0Q0HAZCB$x$b>^b>YFR_&1BJo<LO<Hx4K6J$ zG52#9vkHBctni*UvczRSgA}b?*vlT+?2Em_xpBF2<hwl{HZra1k%5UP*t$2_#D>)G z7rL{GH8f7@Bg+KUE-y6LUB3@evoEk6-WlbHGf<m<pD28*+-HFZEwYrV8#R>Tl`zzn ze(?%L(P0>}NT%OVSbo80kenwc+Dnl!FOpU=Jt&vod{ciC(js#+Pj7flUGmJ(AL-f9 z>=Ug{F>Ke;=HI6nv^pn*S=pc5>bP8)cd_#>n)#RNi9Y8MBK8h@amMS0rHgSGSomaS z5|7}&-n`H1;WyQ!UGg(HHs?)Q!*E?!47w!R5)!1^JW4&E&J#ZH>9l<=@y@Xq@_l_7 zmerd(m0RcjM`NYeg_0!6;}xM~AaI?^e*#AsCcug!1~p-YGL^|mH`=p5CJ9-K$tGke z-4agX%r2B-I-BAy2y~XmojdgFOOHESll|HgR%Ao#&hI#m4wd6Dp6$Y(b0RCb<HBC2 zztB}<tgG(&$hZ8FDXkvzgmGGhOMPy<LY#@efD(o2gf3@45R$J*FcKMExmA)Z=#id& zF>v^dEsS5D@G6$8VREJ8ZWC0dBHzwG;BPSSYSE<BSF#@Z(Dd;<WcQlvvTE4x|N5@W z#Dz9o(pcGtQR5F!W<3a96&la@_+vW;Eit#s?MXy!N%m_yQM!0H6^;J7)t|Qu-nBt! zCTpNqFkWTLk#$Fxy;$qi+aUC~)3MHGIh)+<mQwNRHJl$GXST^24Cx?a<6R8n;_ews z@KgZ8kT*unIz8SORAoMW<$`fpr>_c)8H1$!V8y11kc8{t(p_j(!N1fhe`ozw+v7D( z2Elzzh)y<qU)7f@TpZ&*ON+nM;h!d9p?HcD+$-1E*Amqk8zZuf&;AE`cAlk5XrZd- z6Fyc7=r@e<>~WJ4RO@~rbTRV@7<tk?fE)C5HNdQ^FmrJ{CAhJa?;2m4W|>l=ouq$~ z+p|%~2z$ZYqGU4b!UUJ=qo)sgqB-m4Ts)<I2$0k!^C*+cU3@>yz3xfnTRx+xe__Ey zO{MewBF1aikEi`xG!Yz^F%tc^YZMZnc00x%cKXd$#&sU)+^t(VUwZu0Ood!{2dqar ztV-Ivc&4Z#rb0UYs{=7=jT*CAg<mRWFursC+`Nu)+Pf^NR!txYAFedDCHEfU978#Y zD%hhuTHMh#ea1{I7HhRom!he$MXX%zk*-lngBaWl#zMSEff9qyr*`k_21{G|_Ev=S z#0Xq0hiWVkEg)}_WhBJY)M+efp*<yR#@ioFE+`>AjolyDWagR0$z;t1b)Vnt?^VD? zCAr9Vzi6j{R255Fo`_GsyuY4omEA?6>0GK+P48EG+Vkuau`K?nZok^_4dE*RY^PpQ z;_tVK2})N?2iJa2)~{(rUz}oL3(f_}Jod->R8`l$jC)S%)v)gBRm*IcM(VQ#ReJj+ zJ^BhjPmZqijXQo367-b3fE#$47*U?SnV6uuz3?Eg5ELBS=pE8@PX5DaMKj|)X4UyY zfY!B+Euo4kF8}N753&z4+P&5%9J0lW9#}tWxC!yS*V5kmF~aVxQqNAk*W6h-Z{}iO zE!IKW19`~0l%aO{g&zKW_WA6XNBwUGV;JqrUC=o-_a4rK&aLGIvW8&pFKIE$X{>+N zC>OG0RMR1L4z8}BF8L4fQr5g*_*^SR99n<<of#Jcs(D{eWYEU@h$EKzRK6oLE;xdP zIV(EUvs4MlX{zCpM3whnF}(IDrmNQAnt?dqXXxUB7{(htH8>M%tos$>pg21}I+Nw= z-4U_bm&7maCQ|-DMQD%(k~x-O7<BWyxnQZ(!o7R{25j~k`}11wNW;Y$lv33<pA!@o z+9%h7cJVu$A4OvC@9p?h**ssj{OLCKOvK??nD}RoRJNIxUR8UyH<@;u$4>1tCe<=K zw_JGJHLL%bzDzBW-;}l<n`}I&FW2^7U$LJZtZ05&6Uii!gXZU<KkN5y37XuJSi}h4 z@s`wX32YHu{KKtS_2IdE=zaTvH^GOm4^nSAZI+GyzH!*nu6v8jyEyx|7txGK6OaA0 zR)<Omt$M~<=<`-{B_O}mr-F0B^xEQT#0#I`FunF0wEaHO`<%p#XMz=>#iDoDO#1ak zZ{=0SZYaO~H5};k-D$Q^O3Ns$r+Pfa9W4wDQBBU^OMWDAIes=yFge3uy2LB&BDdbr zbk)mr(u)NnKVM2Po~`~C3?yoAn~R>CZBYnr^!>Z-cIWQ=tVKw}P^7p&@45H?VMAVZ z7yTDjdG6!;e?MQbUE8_mYj}N!_vZ)FDz`nocWL}1$D1Mj{|x(HukEBAjmQ;!&->KA zY2f?wW#yZFS5fWF>jB4AG1m@=36TcZ6xn$Jr^6=Sft_IGyNSCZK-14RC~JV7`?b?i zk9x;mobR6`u1~*)MDOhsG48(Sd~!T?`rbkDlZZ{Z`^Wu#I^WAr|N8>MA8-8px9$5W z^01O|w8h5wRmm3d_2G5M(Coe6^QR-eZ2kv1`h?j!bN={J#}_%mxAz^thZr5nv^Srw z5O!h+pX6vC18I!+Z&82FzaP?BYJZE2(1EWJKA7oz`L3OeBmTMamK{xm=+jnEM2>Cd zhod-Bv||d$2r^u#j5*yR=FSn3K$lPtG0~6AR8Nbq5fkCMB3HZMq^^^%iGXyMNDx^9 zOh)*T<zMT{YjsJl5rqo7@HJiXHC<w5fa2{W8GSvZw4U-}m#mxKX)Qe&u&z>;?kN>L zl^VEemabfnuGU(Y#<1Smnr@w-ZemSW4xlS6q?@cEv6KhE{q#OmbtCNc&4hI2w>y)m zx+moIPe*hME%r!C>YLT{2%~#6xAlbF3>4hD@ZfiH<~>QRj7|~rclcNX-Pk0>#jb0A zbamzR?StOgEp}a4(<K$Y6OeC(JN4dhGfWI6dqe;pS%x<o4R02bJ!%p?!GJdyxM|(% z$JOVb!ii8cLQr~xBFKSSM!{KzAu2|9QVc_~jC{;hPD=JgO!Wazjl5nX?)>PB<m!)- z?2lIIkJ0asweF8|>yKBdcMIxI%<50tPQHw0i74w&nd(oSO2RMoKLig@B9g>$0~wNP zcU4T*$<Y!=+-Gv(2xF5+a26r}uu<WVL=!iD$m#w8RA)bqFu*y$noIzat5{OD2a@1} z`Q(8zm2}G>Q>^Ep8aw!m(?C@roTD}-xi$s|FqoaqBwpIU^Pa)_*P<LAWGxf3hS=U5 zTAu+qNf`j-w|dLn%r+GJ+8Z%tS)53ZL1nU8gZYr5(C{OIQOerT>!~4B)Zn`*WXILP z-mBP?Yi1om!$Uphzkdx>2O&m>hsVGpr`iYUk|PsqXNFWprmROW--oAzMrLD2=CVfS z%SIL&N8b00EKXfW_8Vwk9Qgzu{r$Of96h?CGP<<fzG^+X?l!s+G`bl(x&^-ALmB<j zIQq3`bo+Ld^W^BaAEW<)$9B2K_9VylRmQ&SkNvP7J8&C23>y0xJ9d;c_N#2{xN+=v z&)A=-vA=6$|9*@yz;u9{&T@jzs!9hLFz8?#I>en04W`55=<sYhqMVLwqNCo?(bIIy zIvsmJXM>F6xX0N~jB}`ta~h0u*^G0$kMjhN^Tv(yWsmchj|()73%(l{njRNk9~U_o z7llmVxhKR<Oo*#aNEl2=+Dx2qpO6ZkI2kt~ojoB_J|WvQA@^=VetP26`h>#4#A(Q+ zBKM@yiAiPE$ukC%DmIg<?vrZ4lj?Dk8rhSY<&$TdCeOW_)S8~uUZ2!Cm^=@eB5+R; zPfY2mPU#s;>Dx>hxK9}dPZ`Bc8D~$Kluwy9O_{x$GM}Ehus&sRFm(|!P2!%mJTYyh zI(^At+S+FNw_AhFiK%NY6-iDEh@I+`EHyE+)JC&>G=~HMNUSRT)5JK?ZTO5f2C8Te zQUl29<it?v8Lg&hk_Hse043We1S+=Ne0NEl4EI!o0*VP~leXuISOE{nwJKOpDD<0< zou&Z{Aix}*5<;dYy#U}Y#m=VK?rb*Fdn>_a&Q9w&4xmGlor=k+m%<2haqe^R!E*_5 zbBWn=N#%3NO>+<4&81AwrLNDV9n3w1%u~4M(@)H2sLp2^%xBrmXS>hm1Ydqn0zFcM z+AhTsLgyum?9Tc@gO>z76%)b}6GEtPtJce6*#dsGni0nFcd8QXy=@b53neG4oXJUk zwHnp$7HS;LQA!M$Vjeug&-S^h6@>kYw6?5GBq&aJ$}!T`g$$RKyCP9u?*WkY{Aybv zR-M)GTU)TiP^eF<!|MY}7YOh;1=-0x5rV%8?8b!9<0JGIMYv(%9x<MYi{ef3_sNO( zLVJb|#{E=d!V(?EAXdJKFs7XE4oPcb+VWOnf<k|6x4WZg6ExYWWq#UnBp4C$?gL*r zE8w?~L@)UGVO)`#;ACvEQf~RdCO+&`JVzMp_PXP`yJfL9$dj6Q+4$O*a!Yq7$SHt) z3jo5U+o#t*^0<TEdSHOuxTIQW06FiwyQNPY{4A5LOZg=9JoeA?aSoQV06f|j0GigX z^ZsSXh*LkY_F4*(ocOt6K8gt;6xenui=u}UUtF?EyOZFEEnuI3=@<`#EOWmp$}vuQ zC+y7O2)&)Fm8=-2O$Gsq&|9==u2K3O07!oZR{?B+t@n(kWiA6y$xiZ+VnQ%I8=rIW zUO(hA0Bn0F&ElN^CQL9C!X<M0M9x@85j@gkIfw7VJhP);C3i|;tTrw+-vibPA%_AB zC9UjdMlVXICEZYj0QL{+SKHYR5%sZPBR{Y~ZlVii^(WY@NHIo>46nCFI!U_$BQRj; zaw2}Eot|VzgE@q*u>^w?YcB&wJQwYu)e>&WPR>9mEM#jj8NQm_pAZgMknPge!V}jn zbd2#lj<u+OUj!gPF8E0(BysLKfM4;V!LK|X3-nk|qQDS7vgP=ABV({z#l`O*;$7$C z8@Q2i+zX*q&R!jK+TT{Dlu+y!7~%#npPLmdEC7<l901@9fCVnZ=N#P`1Lu^z+Fx7T zoq%IEOvKkZ^*rD^<F(jd=h_v8*Gm>M30RBCl)m)z>cIb7=XwFAQ=`Cudf>`pb;HTA zCps~#!m`YYP>xZifI*wJr)jx`jjrR_hU)1|6Em+5viqHJFP*xRh0U64<{LaFpE?dT zKY!oix7rMmS(ch@XRVWZUK<tj=`9(A5;1SBUG7c<-83F<Wq!TrpAf!I7LYqS<Mgc; zg?VQZ2C`4zX%<>I<1zfipi=F^{AtMRT7wzYaOaqv_pO0nKaRAw{P&3#cxy@Ub?e@0 zs~jzn1%MzqrJ;ttAOE}xjG8RHK9<G=6@Hto_GR>a6h6KabqY|V>{5NUe}ZmFJh}Mx zp6|-x_p$2$4g7}zblG-=vze<{k|pPZvm*GnHkV?4YTFYbC=WV5w(S&2HxwSS<&4na zFQ+De-fTR!Yj#XrPR6d>d;(Q?y=TZSTi;5AN+}wxq%q3vqF|V%HIavxS#U&%z+9Ev zJ%t&&C{BY`fWU_Gqpm?tlo_q%gkt(1TV6$~2m<@3Jf#9I%&4<Mfvc9f8KwdB>$yQW z;F7z+sjaI~ZWW;$PiW<uqA*m?Q9O!!DzP~Jl)2qzDNxpO%@N8`J!^tyeJbM{jeQyg zu>)!e&}5z5&O(a#R+a4uKY%6o>OLdsb4BB~na}<L8si|SFKK|KP)@nc>uIfKpO{HT zeamFdqr))Q=XBQJE{J=;em8vLMPljwp01nQb&~9GxpdBQYpKSj8)i?S+dlMf83NZf zMO%I#txrGwxpC{ij-!1u-=GakyO;OJ*)`s`il`OHv=w~xDs1D+2!CG<QuXqGC+)%S z*~@n;LMdD*X4}7Cu<}veJ5f7%Tq2jW*(SxkV`w)I3p&~0y{)?_UI38i&H(r$v<qDh zbgFUOfb(y|gr4Y#%ESqM;h?GWyqF*;7fDhwU2h`i`>a#Kslz$9N8X3?ZW2j{3%6S^ zhp{MmLh&NksCMy(prH%uAN^(-n3j+Ce+#!Pkyjl<;{-@cKvBd#KL>;Y+7(#Kva@)# zmU&(0)mov^i?GdH*N$HsC08DYt!WbR8Jqb9|MCfWkKmeMF1k+J*GDlw+BShupnZ+! zbw&7YgVBpNLMO;6YNrXL_~+KpB|^l`#B9gwt#KF|algV0$5QTaMx^r+Xkco>a-&j| z^Z3kq`9Cwu6E@#|8w+!HfR4@)EdL!F(HM-s??r*%CvksS$oGG9;{WwlzJ;mm-e3MY z<A`3<c&=Y7$u;b>s?titaI6uyJPDB0o=y&n+E^~48017Ep4&D#PBEp}nCE1-fX-l? zoMbWPPJg$^v7#gtfxt4ZA9afh>?JB+y`E0#?~yv|ZzPgf!d1D|e$rtt*&a;cZSH?} z>c-v!r$(1^E9?(L0H>6jlB;|}{e~*NAiy_8LU47fSGB7yHK=e^c!aN4=h$Cz8Q!Pf zQI|@<x(Tw*$BT34_3QCiQ9fyuN$M#Z>xpv!Q9^5YM*o1tia}<SO4&&x6H}KY4uFbw zm$4f#<w&v;TEQXYi2;MQ3;Q{(!{rKh28OO3??0lUD-;t<{+~8izj=l7qk-WYXTRss zQz}#{O-8&NzUR*kSE#iNjQE6qFIYlXYV?_m2IPM)+%m5`J3BBM()PV*H>FZ_fOs*W z|4iXw*`{_MKO-%GE8xkpJWQ3jd3hViDyS85)6B0+yVn>auu;27Y^bK+_yK|?9~qq) zR2uhwT*}7?jbbq_woD6|%8!yaQaZK-fl{nXH>=i7N?(z3+JegdQlWt4*-M^Jrz+G> z$mriaJCfi0qXLT4C*Co&_W1Xs3QCUVS6)cFt-_tZSzCp?#+3f#E{ndCHat@kZgW%N zhfqqt;dw0}Dj;-)dkBB)@}v2&)PFJTBZ@IBf9TlTxe`LTg<lnioS8yBed-h*B9lzS zfL<?&P60Je*_y`wPNn>=kq|Y*@stpin95A;8@lbp1z)FC?ysb65>e2>RUk)b-lNy0 zIvq2>-JFvbvket*w@fqsIFom<D0Ay87w-Q{3R!>^*aAhe{@<i9uBHC(q>wNzG_EUo z_kWY3wC^FF(-goL69+OSFQsXDPL!EupR((4OS0M+%vJE#0cy{b{qN#$rtBMgF+B*@ ztkg7B)_HB}nSFz8>=I!q=CQ;7PKpP?o$zKq2^Zs|5QVNb&>qj!UCPVrKnTk&WT}|A z*qz8JcWt=UKcScM=-U)kEWm{mt^}eFUv}CYc?@&;XMR>?Ym#bG3e+ytf1Ry$9eP~k zr;y0j82EM6u~`4XOwvi~rnb8!QD6)Q*Y(lYufA{6`32HM>U7;HLgqbmp_X?9gj4lN zhUBur>tEluCZAn@dx#X{&oa8Y*-8Z?m$oHfdt8!l84Lg_y+nrp1!#hxkrvC4#S?~6 zWG#Xi#aS2UvCJ&~R*AX#<}F`}d@Ht5WY@#OhXCxiYnPMdd4l7V8!g8Zq|o3Sl&Di1 z_Kqa9TB1Fe9pKaFff1LB(~PA&(>Ykn#pt3rdCK&wzWoFo9;RKfmIJZ@0B!?-78NaU zz~kbAPT_JRpJ1)kyMMJ;=A^C}nI6N(YT`1_5Arm@2?s(==~tAml8ZugM4E5hV^5i) z1%YKwZk1g<t2E1&|3eH0Vs&0R>0;M!Nf#t>l!4(ABuiEpp5#EXVKrgkqJn|jK*1w{ zgJpep{)nmfk%=s`Qg;d1uV3oqb>an`hMJFA;E$CLYjTG|$nRbGRDRn(1N+NK*KlGz zzFyR>ztQEj=@b90?MrjPxAyI>uRgDTj6U;elgQu_ssD2*Sk%NC?Bwcl&*HZX;NX?? zzW!gYz_pj356*rIexn;P4qas>v7n`5j|%QcljW6fNhFx>4@gyB-5->0xLr>;T{*Qo ztkQSbIRb>f-yBU+TExMHfuis9Klk2E68LXB)rIj%jIi|b`&#FXvPO|~TkP1}RA;W< zDhi&yzA1D#bM4M8N{-`n4Kpd!Rs7yVBOzZcniW3mvI?y3tg~`&F-}oFMu5obMDl-* zq~+*M@6b;VVAnKOW4cfMTDz%A1%MpadxVX=OBV0_mWYZ`x7n<AsTa$yfTO_7<HT8j z2k>iyaJ{x@C*Vl9_RsZ`*eJ-WK81Ed2k7PR&(C?E{2_GCV*l)pu{B;Q?G5+&dmttT zkOKyVsoJ`qTu=Wa{*HG0VaNuUkicwZ7y`w!;qATOTAFyq@wNGjjN|RErzxOg)Di)& z+QBNYONN_MS$X?u(6cz1-MduqN#jnW14-$NTt8T?pBU@s7X<sY1l6AFMCI?sN)OX5 z;9IoW^4<SQ3bgwwtH|(fyvA@bwr>Rn_<?|_xndk6!MF!JSSk!?tgyo-(n9fjiF*_y z-Lfrx8Ihi3t40@M)f_ggM<U4pUCP%d{mMJnU+}|GubKcynjfwwh1F9+uZ;!J5bsHK z8!i?3S=Fr8Y{`7i_p3uqj5YW7D2e84tbezR49@PSQ+ghYA(RJ<9riPFhs&hY2L>#{ z_cN*Ja%m%zL96`ztSa+zS-XKj+qV7e+LUtnn<hgJ|367lO}oK_;nizw$m&O-T$o9b zXAU{PMSy!SlOn0nK(@jX1%4Ba^QC~q0Dp+QGczfM#m>Md5EpQ6xM}%Bp>U7UpoQ;` zIrMQUYAg)0U2CS8MOP)Wbwp4^_vn3#fB-LcFNTV5Awle$cz^)E4mk0@!B-iox2fs2 zX5#jydgML=@X%y0Ts|d6O8Ma88CqhgVyb7iRyrjk+PWkbXQS;tIQe+Syu9SN@?wHO zo+Vt8qMwbV7Vci;3;Xeej0bDIB*dMzQLVN&NIBVI-&Z3Q_XKn~UJ1r=@eF#|%(XR| z69*>i7&mdUrguw%yAW2P2QRFuA=fI!;msUt+^#tI6RjXfhHg+f=#?%Puq1ho%7O@; zd**ghus}+S1@MB)>()k<NU<!zNYrTFE)~iN9JmBB&gyRWoAXV5h_o&9K8jtw7{j2> zpsFAM7a30x1&A;X*~F6^dkZTe`b^J#+0hp63Q(Ax&)|wDVfLZY_9l3epDwS?6$*hF z>%ExMhOy%Wb=&=LTR#vL?P8srYx{cl13Uo2Y6s3(?O4M-5y(XWay57GPQmars*{7z zyPq`P;!`OhXLSf??ce(F#R!7;W3@d(Iw1b6T;T-V*Bj0VW&3E}9D)P5AXI#fJ5lqi zleS@7YkF4uHsR^nWrXM!=HP@edoKYD3<H4QF_FiO;y8I$4D+9MT?X%d@*|EiUe|-g z2iXs_<;b0wyQG(dLfl0lW%+3c6VY+QDM6&)sU57)#fCSPjFKlZkgWWWlU+!1io&lR zix+x^1xy4nm&9OZU@etJ^VNoU?8PQL_^RqT9KXhA7}1!i3J>@oA#aVm4381rtxa+K z(KULf*Xv~A9}1auNdU5Z1_0iu{b@U%{^?yn#3<jA)wjdH5;o3FtXUq@Wtp%=Ug8Tv z#rEfPV)@@m16X#5xf3h!@y$C~ij!rOeCg;=qQU7G!d|ccy&7X>`MFlHXsk7ZMqf}& z6oKx$15>)3oZR0ZqLe?2QbO_9{B-ZrP-IyEUl00hpkyzG<B<bTL6QtwimMT`KCxps zhT8l73+_#hGZ?Shx*I=9xR0y^L^v&)6WQg=Z|^V*Fet?P0gefBRXod}Fg0Rr-GjJQ zPN5|~b-<(jyVSY0F^u!Uu=F*bCTF45sHUjLSk}Zdf1K7}vc@=#tE@s)Aq&56-w0e- zvf^;(hO#zH_gbe@YN2cDnV6=9+2&8Df7xMJr22z6O9EmD#eIJ}SozTwIQP3{yk$%J zTEi?MR|9PD$jG=%KmnI<^3m4j`Xg?YyVJqnlf-8s%ESdUpmNl{8!Bw5MAxC5H`n8@ zd}0U@6aD3?=?s5VbZ{S{o2ai>){}1pUqwVGnEDC+(Dr`W-mXQl09)dX&8Z8sk3Z!< zzw;poUc)&I1jojjz(Ai_5^m9b<E>qOg7;oC44oeL-C+GB9sXsRa61L3pK^KzAT#zI zKd7B8Jb>~a$`ON>>~_PKVFoyGJM<<22R5epLRjvBiyc^_khwGnt7Rb78XgD0<DH`7 zoZtWn&Y6zb+{A6S;6`@uB6`A~-|;!k?ZmWN`{I$3cT~@lAvru!(26ToB&Z!8;^u@) z*bN5x!@H$$SILN~TGDkV*cQ$-i2_fljs13q-RvleUkvMF$M(Q28gTNt-QdIO49zE9 zm#@0#Uh67x#}*U?G9-ZHV1ThA&XWYm3xTtC!Xngh5kG??XfTjJ%qrBvp%u4IwnpiD z#2h+#m!2$BLw5ayN*+L+8HTtU2EN)eu5M(o<5Em0K4GXL0TG1^B*mhY(7B3efEMhp zgxsfKB14I`#_UT>F0Xa;dPwx20L(Wowu4&iIt|CTBiW`Zd9NG<&48e#aj>J?>E%g~ zC}c1NRH%sdV2&mZSpgEVij2&`<H~YVgPL(u_(TVGwvPm(XVSzC8fJqY!OQ*tuJXXE z0pT}|UEjq(Ek!I(;_d;#HxwO|JRaUY0-q(Z9v;QJksv8X31EL%E)AALgW=%Gtjy+n zE#w;s2_Yu4E~D03c&2v~)};+sD1mFOe$!>iKll;>Cp*iVQ1X(+Jwn8~rO4za_*$(a zK#Fu=P$0N<$pCu<Na-d(P0-iC=}6<mNyrx@WDW_*Y@?SYBA(M=z4$1Y5zi)&CTe0B zYm1wrVoasb`%Bpv%gAdKUod;71<luS2`pd>31sp{s*)lo&|nWl77g~C$vUGYfRrG2 zY9Yt8)N;k-92)BR5^e|=y1A5oncsYg8V=M3?Ik$v)37Ka+<!KX>jdtfJy^x#VMIUx zP#Z&>4+HRlfM4#s1}s7Yc7=d5`jrn=LKjN2|KQ{P*OQhSX3T8o<{<O|YVsG4z{zq_ zhX(HWB<?okB4jq6)gSIbLR6W=hHB!%O>i8ak+9BGPNfX9Vzf(30fiA1MyvFI6eIe= za&Di97&L|k`oWtn;}(-}5z?%j)krfLT&XdlyEYxUoS9k8RkVxTCxowr8ISyg4pJg$ zc2}C-;bJJRbRJ(2%e6uvi#d|3!aZRXE8x(?Et(_`+(^ba+kK>R<r84WjSpa7jDwiv z-lZbiNvj|0mIv;zv`|vhE*$0$F+c!;y_5tK+{=MSJeoKjM0#ZsyS)h)vb=zm75Rv8 z^;DY>Q$_kUxIpcuxm-Ev8<$NH?&58TT}o~S;c~)pSU%xZaTV<mC>;c<gYf*ye@c6l zMM=%tb$e35Gf6A45ioh`5ompEx1@g;K8}zbz$xE+RL*#XI}C$8CE%Wu^WiO(?<>6L zL#qFUaosyMen^GG!b52=yC!@w%o5F%t49OC<=Pm@a2(URZ2B3O-u9^4q?+3w>o91R zvRk>nh451ih+TRJVe#qviOZqo1G}Y&I>;4Vbq=9`$NA>q*0ZjuN*6@<Jgq#RdJk7u z-Q0#N-_4hEN^i=qyvXDCMHWYGuADhGhl_`Fzw+B*_TEWswjS6>Lv-S2oKZfmob&<| z1%1BsV#x~!`~9L_k}ZgY+N0&FsT=!9h9tG&tWAn}lpvpvJrNIZFQ3-Fwq|Rhmc+v9 z*^A3ido`8wb+FEQw=6^vfDCl6*B>uaVVuLg+!crT!?ez&-<QFyo_zsXM*2A1eA);H zsBi%|5bXq~K5bM-aX`JOsU~q?A{)fgo7cUFaokX!R2J~12B5&IsF3!}dX#g6K_lE) zut}f2%JOUUb~x?|sS(27e0Ly$V<5qd1WP)u^AT*Fi*0ghYyvBxbzZeV*&Bt!VSchW zIxaREb!i`mT_DxZATj@uFl^%u^_R=;UPc;HU}ge-`3}`z9dLR1-iC6<0JS-D$aKZ8 ze8#jD5%q%AA0`Jh8->GoG@r08KlKo7pY^JL3c~=DKroBM9Ws(}+yvW00XP_65-#WL z>z;x)ZD2I(9_lR#Im_T@_n<(>2-!U2o(o^iOhTy?eoFu!!N|uM{DOdg7M2bm-ojcx zx4&&`#0)+Q_ogGR_@%P4ydIZ>7?Iw1F0}nQN9v_wd&$^ddahq^c039gr@%tmaV>sG zD^eY@_$_MhZW$emJ10Y>G-9@eIBT$gV&_*BP=t*5K|$={9=JjvFKLh~PBgePB3%G{ zFoav|Z8NO#GZONv(CCg@fwxNGGO6%4ZCxYjSb&QCOo)CKiYeN~w!M1#XW{jP+#4M< z@OCLi1?Ylxw&Cj9W<snn-KCez-~AuH-u;ouKmPx}?7W$|=9F`r^Vyt<*qm}U$I!tc z$57;uB#mv%u@QwNXF^4(Bx;V$A%{|^6r~~^$RQnl_xikl_`W~CeExy`vge+=uE*nc zyWel=gpIIqLb*8KE^P8B{|iEm{vXUH`S!ijyvw+tkI;?SDagCdX`!_7+rhXe(y^yN zBo}CMF|$giCf+TAH%3G+le4D>`G-uwuQ939pa7<hd65P!NWciVF;0?)m46JO3;H`W zdIioSI{|>z+HTq2RO#pF$Q}S_kMQLKRZ#=a=LN9IsjKWl;56pKD*t-vl|FKe@5zhq zF;#*+gU@ZN@8x#eJ#msQNh_5WW45BCQGjx<T;9a-4t20-m2tZtcPa`y-16wEJ<iUC zA5zr?v^M(&@;BHzeVaf}Vu3)plo21sEUVy&I(z^n@we4>9V5f*g^WHe7NxH2anw=l z_V_Q2;ab%Fk3Ves*@Bf+gd?p>pa%oaVv=?OA~FLW$m03^q=lZ51XR9Avq+7)?M+Cx z@%DHWpJETBfH7Uq1qegII;Y3m`D=ag#&aO)<Mm{}u*F=wgr=;d@gqz9x-DtPM5^Gl zA$Is+cYBWb(@OL(VWNMr7ot;(uEKbaa+1HaA=jF^SDQ=)L@WekEH$mXII-euXqOfH z&AR74Eze=Z=_n$$H=t=IzNC(Xd`NxB(&$dq#Fr&UOKeVG8|myE)eiY<SrmhwyNEYa zb9fjw3V;<+#P}Z7+425N8@ue6EL;N>BR+&4r&T>IyM0JT`64^bq!v{aa1@}<+%1}h zrrnE7;~!gn&b687jmJJ_Gg@|>!It?c2qi|hVKDv`m^P2}q9O}c$L`i<_kn$xl-b4) z$Krvz6Yc0vz*B@y|3exs@haz|0N%m$)>=ZfZ&EMPjbAmR2dGS*{pIw>VL0J2rjI&U zGJg{K56qZHZGC>-IfeUBId7R(xX)k)5t#Zh7%@u20&MKH)zdbtn^O7s<0$lmvt#>S z(Jw$9J`k}{X*1D}h<$VeMtQf(>6O74So)cm51^Z85KA!m4GuQ`%pwLq<2VLh`cP5O ziVEt^R(b9C6cFHv9#>X-vvV;AVg%Q-Fhb$452S)|2NCDl?>LWe=BduXIk?&KsyWAT zfRJ4rfbFhajN7RIm$A_@f77auI<LS0TP<*Te(Fa|tyMOrxHbAj#Ztvrho`jL*J3ci z<<s`Fw6)VEkNz&V$U3}<9(;13SweF1*(JBjuRozCmpUr!_v3&iD&wa45<v~T`(P#e z*yqyP<Yv-mpj8molXp8`#GXnQC_-81eV$1LwU*MLRhT;P^TU|D_A#X2S7G~Bs@nnh zesEwGXI}_n|CBM>=idSWf<OQ|Ik(~687`_}A?_vqIN(;;+^Xm3fzuiNqGi3#Mh;ct zxB-Ys0ys3kl3k9o37?jh>Xm7O*|Q@tj&*))G^=t2m9~nuu-?=Jw*x>I&8Mej(so?H zhMhSuf}jSef~_NNCc1oAJp0{BB(#~``@&>N|Ja(?fowwTSKcGOClCY>5T2_D)|pB+ z4G}zl2#05y->_;m1J!r<w_Ly~4KR*`T#5ucyFMLng;@}g&+bx#INryv6lbrFNp_%e z9&Dc4m~;QS^5FF*&3p?Q`^>dIrndVNbPehd^VJm#7>)-%AoT-O0jfY^;PoG;7kOu- z_ZJ!Lntz$8K6l;$WZ{HNzHNUSP;g)eZ~QCB0eLS-qb07kL-Xm6sNj_w{I4CCyB_0E z=HS2se09(|jEFqJMwD|-#*&9$Xfn^Sc_m%8Rlvj@(njArt`FSmIy0KNV}E<*H$ohN zKLO?;bx>DQFgIlXe)^_eb_D~lF%9#$u9&}9w839yTLS^59}=VM9)f@lidL!zU}ddK zCJ2&@z|al8iOlns^jQwGro`=?ZNALjRG5VOf8eikg>|X>dxs1E1OEOm?zeahFkY8< z6d((H%~*3V)|jIt&H>?8CU)nA3L}Ib-0QV(wmojvoeG!o{_Jxz<Z*?~CGRhOccM=r zpzM{B2d+TUEOgaz|6r{0MVZ214r5Y#E}2=Hi4PL`CFn|>OljZm!NbLx{tvoVBtpk7 zE3Qyj8rp~B5d~?G%CUgGi6R#ZrW95M?E1l-_t-+{K4Lw+2={#UgYS0C+kw2@`*`5* z3GO<;7#79MssT%>ip~6F&qv4R?J(BiGd1O`MLyzU|8Ihl>FC_U%-#O~oO9Q|ym@q- zM-c@9g;kdI`hYdGQa0B6=m!v3R9PZ~95r#mvGjlP0cP7AhS4U#bIWxnmIrnLi4l*= zq3c#UHlq6(qh)lLu5Z$DKDBNg2I=?uEB%{H!$l82Sx{11HG2UizPb(o!UGzoG^&hK zed~A8@2ED|s`I#C#|xp-1C`g?VS1x?u?_>u;fSsem0NF5MM!+Ny%}92AUJGQe7IJG z$Nl~oy@@*t&?fhq3B0`~6AgK<w=-G3WWQe7y$!7_KYlR#eI?Q41O%7^g|FJ%SilWD z-5xjTR~`C94D<9l&{^P|*OZb4(hp16<C=xCt7`%s4&D9_{1sDB_2<9iQ?z8S;+z!l z0uJ!RGn*#Ln6Q1fiAlA!^^v>p?;JS(5dNdmg<5Pc?EY)Q8mAWur9G$X>kJ^&e)&ME z1Zw8{JeVrPx{DzWOoM}INF^TkyWn_B9Ox`<uix*`y+M$8{mSkQU3<{@NS=|cdNH-W zYU#2I)^ej+S>s=$s4hwd54f~07>AaI)!z$cz9>=V=HBeN>WfF8dN0T<7iUZ}+9y!w zy+7~ahF`jpA$c^q24}b<lHWBFQ5q3hkS$lGYFSpCYwTvT%VnDv%yIijKD_Dn=@5F& z{!jL*Ui<g<3fmWmJhi*%A#!vpx(E3!@e>EVUtcoVNbQtTgRdbf`v%^!2G_6s=uePe zaaPF0=<WDp0&Ih~q0+}c-5QD;7rqIjso5n*mG)UQbZ=>dJX()^8JRm+Icb1-boG{O zGYr7~Btu!#CqHf<r>8*Yg_cT<?yS#VeRNX*cwNPk4f^%;l!lAb8Y+*ZcJGeW=ZDe# zY)g=jAVd-23&3wrYv1v;Tm(!`s-B$e)r!x2_`d&|o5(4qnfv?Vohl^YNoFa2;$%LL zUG#%#h{=fuvTaB~J9P2UH@4o$-XHA^@_CMzDSr~c9OsFogaAt`J7X)!x5^F`>d$x( zhD1jr+_hW0lA;n0I#v?*r;ra=YIRsC8BS_G78(>Kh;*!6oyh7(4{#@Rk^Dpj>#nsa zeBQpEgZ8W0Vb<@0mpIpR&E#1TMNZ1N#tSB}-t2>(c0zd<)ps3R6!}CyLV()~t48z^ zpc_ma4|X<NcEjD%mBrV9h`q;P>>M8V>tzWi9JMYe^Bgf4^DN)9dQIM12c<kQp-8>+ zq*!7ZP8zL52f*@uZq(+!6@i>{>3SzE@H=||*OSR9b!W+!qIR#+9RH-SOOsy==&Niw zjT}6Z59}CMu8!U0*AK8n9G|zs3imP;{Kn+VeUuE|y`v<2xVmeY#L`X1cevgW*6`Nj zaxdH-iA#bq1MNQwk<!}D<Z26%6bD6ikZXpPJGwV~$<LB<P9j#p_}H@59zD4px?FH_ zW^TA$X@>+L{w^l%K($@0oM6Q%2#|B%X}8kFeF{p}=NjiHDBIMm15Hy6E5FZEnou-T zK3>r98MLP@KJSd&qg+YV!@5H5uC?Bq(Z$~nihfj3tT{8(q&}Nrctb*>$PJeDLBG+& z&F%S(JDVp~VKi;rBMiLFGVpMVCn4k0^Ya^Hy28YC+trXkIk5s3>K=1uyK|;z;H^O) zkg-E)oNPI(`o#b8k(Pa-Y3z=k_tF5MWVp8vR3h}WB%7@S@{zMg?_4-qtf<CSxnntP z{5bmhd#;&vY~Hx+;;rd`BEnK^{!xaQE;g-}q8fhhy<{zJd=7uC&e6cXqgmc&^WgD@ z)8JX@MR9FQJC93iB5zAB)TEFaOwK1|mLHq$miD+@)OeH~(kdo>ctG=@djW>tnkMm* zPh`KCiZsCo73~^=0))ESKX*;{Na>9p4je)s3t#W~0wJ&BEb}vBk8t|kDkLT^^g}Os zU}&C#q1s(<qfHXQu%tm=`rQFBseXw!dB{(NN1OnWZG!aP8@y01CVBL#ukQ8O!p)s2 z6NRwgUE9T47Pz;$E}k3a^)m9nM3cN%_(F{XLa#Nofvv)n0Nf2(lI1!MqI?p(GC~Q< z?6A;1XPeRhg0-gbTU%wL*`~2&V)1%`+>z>CL{mQr*_Ey(DlxPIwZ{C+$rWUf`Uu{4 z&KWbqeJ(eJoytWdl$0ZgRbxq$mo9(Te~oYbsjv%3k*?v_tirrwQmm>56G~X`!xWFy zXfGOP=9gMcFk5re(Fj1Xww3r=+F*M8j;m{x0C1vX$^70E%M%7?oap_0qRIVG<>6Nv zPOdLsrSJJcNy@mQVx2aFFnP<G{GDUU4vbhHG|EZ(^7_macka59GN9mNy|bBO`UW|E zu0rCAG;b#o`T48eZZ~`wWB;qY$TRviim~j3SI^C_8=}s^Uq34Hd$o8u>yg&ylE{<N zwY&KS1uy8i4}O%5A5nf}5_%^v`qt~LW|MDD_xT88CnKvc_8LLzhxhj!PmlxifM4n> zH3T5MdKA&N@~}SJtLfn`sg^tEBAofZZ&p^-pCl{xkaf@_{S+~`T{FZbLZ-E0p8SZ9 z$*Y%^TS4mEgdeF&M`i0y9`~i2J+tE;!dE9$Luir#kFGIq*Y0z&BTCrkLR@7Wlg66s zWL7t9>Jo|H=`Gh^c_}`!5v~69heX8K5zfGrjaSUfZf`u1t<^K#xkhT;DQ;Up9X9GG z{$%_)Z|g<ALs6TYoHM$jA$#1c=04xwpW(z)2P;uG`^a%Xe<05Et<~qt7O9uPhhxWS z>N$71@$CyD#TO=|e!d?U79Wzgmnm3v&2z+m@}DL6O+a>gu%h+SO&c%%wBp<d2N~?v zKku3m_&eJ)s3ymp;qx$$+76rI4d{`L;JGJ9bpA+|M$o!`pwiK`sM2+onVorpJM7mi z+1wXN56^sEcI#QJVXdVZ(uAd^W4>6KrXSwJp1-8s2wl(WQ7Fp#Tf;gNr>=5Z&}B$; zO;|%MxXp&z`(A~@0FbdPjz%!rF(zGMKAot~;<si^>!EbnyfUs<OA^ECJcv|Ex$&Hg zcOn;_9AVAG88}R&8|C(q&F(G@3%-tltUa}2ats}|A(VLQ96ja`uh#UwU|bWJ&o#`O zPgk)ceK_6kiZ$>jTv_wOJC*Pm)uvgCpjEkKYP<~<iuhiD&}bE*Z}+|@(=Et_=9Ov1 z0XO=S1_D}c#Z?*ujqr;5f^XJQN?hpHcL7(C!SEIxRTUw|jO8{r&088R4_N3~LPClL zW6G~9%)pFMJlqd?0+kuLfeml(O&ey3AGMkWA0?->-XQL#`(!2tbibbv*aP&_35H69 z#_4->lSxR^3jF!aM;XB_0&eMhx%(K~JqsMzjv^IXrH&q`yj@@=Rg0EB62mQsQrB66 z^3}3}0`|Qt;d3HDtUU+z%MX<nY0Xulni{R?+kB2F4d63MiF99~4C-9NsLM*fq;62= zIh;|(%?0U^>#XOeWQOmX45-{g9=Ts9f^%3$?8#O6{uAnv<nSil@-2z!_!$*MSIFOk z((Rzv-E(+VEd~JaauL`y5!`Qn)w%E?E(ECJbNsFYe+Z+cD&(6iRJ)F_)Tp^-y7Hbp z9Rp-5j6e@m=F750tvDkea>M~~N4i})odov)%Z5tp-%-ycU!^}^Fl9Cp_R3+(9dxN& z7+qY*Zf0~W(t!~GFM>G(1m~TH<z?^4P<?S23kB8lB<Z(4V2};d_4G78KX~;yH%=ul z*(dWrf9>3#kq6DT^lfMW%CSv)?5(ksrrl#kBN<TPPA}VC&Q{o?4!atp_-QdWbzZi9 zV>G`+^=$jDH2xMk`M$qCORa<M(FpP6FpgF0J)Xi@a78RyT}L=$tZWSrV;ed<O{@~- z(K@uvCYTLFJqy!+L^&E-OL7(H{wTXw4jJv2CPtPrZ$vh>ij+ZNj|B}_bGaJ+6W7P= zl(wx|w$d1J1C}Ns+iYGAB5<n*O52s|HZ+rSl4NmE(mCxQn78EW4`fhCnI{^#!!(7e z4!UuGw%1I$HrZomKRaE>0Odu}sUi>a(<wj<giPzSX1R0i5S?qo1K;7%=%=@Rs*SBo z0d~5!ou@t=s3v<<g%6r^(4}Y7FVyJC&v^{_*i(fhdtrb=RvLB_wbGk=V3u`&gxYU+ z{}ha-ndA{C>84qu_hp%Jzw3&V7k`&AOYND0@%)&9NSQd9rLgUk&0=c(Bn^=eroAu+ zE}cMTxhJ{q51EpWp0X{1eC)Yu$QVS*gKjD?V8Y{IbdE-=vIOV_l%$E0SwaAi_!uRD z(okWiC8HtQ)O=MEOO=qOYR7lx{eA#UOLgYs6(!LLPe{VBPb5^M{QmRr+{ZtU{uM#* zxaqSpS8@r)ROU>&LBccn1SXyR*dvA)$z!Id2MelX$|m`6XQrHl3WD~cjD6CL(9XX( ze9hZFfUyS<Bg>fawSNr#{1W2uSx!ut@xqC9AbOS#Mb!MH3Ol6F{qb7pU<Pl){aWcV zWY!)Xmf@dt?Envb12+cB*Z0~jNn?Z=2-_F_B3l^WD<XNRR#bhJ^{+oSc;?(!VF)|C z|7Nr&unj49ALAc^Q6{FzAS3q7fs~cWtkFjbKIw;5psQWJ%p`|^2>~58LQ7LJX4|8k z<HsNo_s1~v&E|-r2bto!UR1b42~;;+X5(#j$EXJKOIkp{fw{<6*;0->m)bGqW~`xm z2brtz45#O}3H@|CCR_2z)4BAiy{ubaDDN{B$Ii6+!GXJ94yEMG<W5{}D3{h@`!bT4 ziQ=AZ;&W$i!<kh0GLxCdqK5{1>9U<2S@uX%#N*&sU!Cu=o{9NCLwOLM)9oOxk6(I_ zy?|Ee8Q!W1c=e14*J?DXs5}2q6;9M`Cp{hAv-u`02OdyT_U#Z#hpI98YEoh5;N+A* z&@%z|Rd{Y4HZ^IU;f(Uxo-vz&sB)pYF%{S?c7vrX?q9$ocz_3p_dwCrx4piLK86_b zs9?*{d8A()Q=7&_{o|FjfaNbBZ|18@VEd*|%*bWjNm!ZK>2XR|DM47!2&Dp#8>ZZt zjTwtf?3pE_Z1Cl?%~>;X-4&Z>9wpG~07n<ScUCT!w7aMP7zm)KbkJ1<L4%6Xxn)O2 z!=cTTTL;M~AC&JIXBNtqW$wUw#1WRXTJ*e7x}XpU7}Jfw`GvpqOWg;%>T*>lDsnkN z%<Xhyq%8^om|0eT&}FGNDjeacF&af)@o9S{en`VF$UbJN8w8v)MxL<qZ%w*iP-!6U zeBYE)gO&^BoGQ;f{UHvw%bmH%AVC2Yp#mpXTls;<&khb7zdSG>e3s>ZmKzpee!%Y% zl=4r?%STezM`A=r-d*g;Rkgj!)?q)AXERQ8>@ZYZ0U9qJ+P;?oy@VZKWk6vWCU+`t zBVC>m9|vX6L&6MD%3fOMJactYm#F-><0_7S&u1{ggZB)f+!P;AYB-Nf?Dt*L%3ivD zrt)>Zj9Yu0?8y#jc!G1Rxsnry-kh`CBv$f(%Cfmr?nTRh*CKLdT<IN)39U!k=Y#1i z|A5q|w`>&k>KH!`Hs*>~d&<@4b1BV(D~ELu4<uwl!jX)UmkTn^ygTp4$cJ(o(-=&z z@<t7gvCOvN(TA?ZlP`HYU89rfsY5G|ABej$8<hdt<LybtD%ExG=kge)0gaiua{X57 zQ-)o}6)%)-34NN=JzZ2O7GgH`A$rF@BIKku#0o--QbD$kJQ^=&Jyp*!prTw1KbhI0 zX3bbv-d9WcA<PLXwN{2^C&FWmzr02q7a@+i^DQ%4-*>1*w%J9}x$m|TnFnd`jPA_$ zHY|^h3w^%V@sXFe?`zelnYZA+0pr5aZcf?ys0>e*4~U9#$vHE|Ji|Sb%6+HZkvZv{ z!T*DGXoBd-q3@YU*AIXrgUdI>R)rc0d<a*4s#!--P4<RD0Qt>`iqzHbf=n)SSr(1| zi29<xCcCe|f=18!g6xxi4Mk=M-OCN;z=6tk8RGKqW-)EGti<`)-FLtLERnvj#iDFS z-k}|%R|fi4>H`yAbk>(0f3lv+-9vdDD|y=)6W!m9E%L|US)eV8n++ehHJ~<~rM)l9 zWTMJsgw?5@Rd!+BYCrBfQT2X)Gre(XI0ossi3*R3v%VXzL75MiZ5Nw+98HTWr+tn7 zimE~tEFH)?^AsU*Z^O$Xzau0hikg{NQM@s7lnWj`V~4VLWt}C!_nrv%MkZ=dg6ynV zL)Z^v^O^c@Sd^6vEy1m@AH_bwixJ4Ng|3JJW4b~TlwB(M{pXiEDshY@2S7YJ+~|j^ zL}5oAD*LItN5}H<aa00TAc2g0wzOV7k1@CSaYj%$ENt<+^w|CWR#I!4LhMPr?3S$| z{Imrs<4sm{efv&uOy-si>hSxMKVBf@{M%`hViAYKb_`i3#9_U;X`5y!d_H`Nz)Mlv z%sKfpXl?tu3(B}-nZBLI5n?@RL;7KJV!jFHoc*bg6ONS141T<9`;BGuLtef^p)DMF zocgtL=jylXxKrDaR)V)~UN}XsWa`o~QgSs|>DV|QWYfjuqfbumK@=HTbnH8)?m-w( z+zq?CkN+9z_pOua_N5{jd=GZ&w$46W&sUB+IDr&AoFmi!yB{gq`p&)Qcs#5=Zs4Td zH`|VKF_)LtDOz6yhd!pfG+~<qf+M>MzA5f@Z#;!J|2DS&Opod@`cjg&(w7tde`g;` zpM4a;q=vni{=3ujvte>4Da0J*E)Ije`TO>qr2D4hISW=YAr$~w3qKfgq<_mFOVob0 ze7I6}O&R_?=-PfN+o9p#s?h~|)$wrKWB}ZzuR>Qr6nyB+TISgpJTk8GQa&lA-T?iq z@yFkWlgUUF06_|Ags&2M8JJzVQA?}DewL83drSD5++ePx(TUGXYw}#S+`dAMi0=x+ zMQUytQpTtfvOkHhU$PivbFA=_e6%~?l_x4KGlevdZm94W)Qh^&pEe>M9fbxCr#wUY z=>(zHfTg&_V(WyZ{_IT?(DzpIT;<K^l`YLz9Vb3Mxfc0D>#%!0Y>ymVKm(|N+2=_r zpfI*O6`xSoUmD`H7rBMX9@nFO>V6nyk0*S=e3GOEq4)**@op`>32*do9sBaj;PcGQ zu&1_u&T529@Lj^e`qYnu7j9<?Yajb#{C#n_^q727<2d;>B02~Pup(_@M()Oa`})^( zdzD+K4b%8%_G{zQ^sVDpJUi#-9%Dn36`$?>_vhD-^>5#<{5#8sF(#zJC6fs0XtfRk zU7%B07yz@CT}*I(NyH3^qv8eHAH6z=EMm5Cb(-g6Yq@OIrVhCr$AKquxjMtf@_Ew5 zHHRpi_{JJCrwc_h8t{7Jm}et-N}-UlH*q2#4~cnuv_E1!u+Yozl;Q;`x6Rt~+$`ac z3p;_?CQ7BS%i9X70Lw$^Qgr9f4<TS;_~B^J-c!mIrwq5>kxhSnmp4hq>`|#=rpAw* zIVcpIZIZF)mr8AcBtsrZb4XULFFo3++Hg5JyYBLp>^*8%>&lYVnyxl=sx@Eh{H4~? zHoQmu+U*y~>eugm>Qukc{p*){YY)a$qisO)w8qULwfh>k9`E_B(LU*5s(JgF-)YS| zvq$f1-knSSt=X}VZK`$eec5TP&gG{2TKB(n{^scy!=~EZn=elDa;rbx*M9i-*Kcjk zZUX{^1D8r6^`h0gNPPmPe@Oj!M>CxP(E}+ugA$QlI*(*d|Iy(RbIf#y6fdRd4y!hI z>5lAZ-v6UJsxxAy_t@ZNir$#XN|)aF-rs-pCMf)S^(Sql&geg}SMSz;>TLQ~f6C2q zufa2~17{4L`$l#fOdmS^*I*_vXRqOG$fYxeFCv<|4PQpz|7-Xvc4V*7T*AvUMz2q; zbQ`@n^ZT#Sd>X&G@d8sS)%b0e`UB&4@H@c~?+P-12!y>PYngnQyB&u!$P4{<?*t`a zUGU>Ydg`9&LsQgTi2*J>Z@F>gYuPRXs)rSHv;FBQ<KD;rPKSm}O*nxF_UhxWd4<BJ ztB>C#zyO03k1jr9`>p$BW0Betf`>Qy=zI$YcJ{2lytI42-kZ$bsnEx4E9ajdM+A$F z|5A_hcH?TnYp$kqj6D{>C3gfRxCViyrStt+6+G&xEX9{H?~$|$u}JC>-k}2M_8u0m z6iV^|oq#HUFzx@;@F%XO^V#wWbE4kSi78c75k8tOFD=6WME(26!_+ygnKtNj9LyaO zUP8@$%eo>s>z;3bhsi9FM)q7#FcycA3CiL97Oj-*(4s!3eOHb-*Z>s=`>{7xt@T=U za3_-1a;Q4{j5zw>DS#|lPAr$fEM%sWK;Rt;DKy6wF^xSU^=uwt^wrMTVkVGa3bH=J zR4-CDaj`Zky%Yv<$oa(0^A&#-RIF5o-9BW=%!JFUdY}s;`mOStU_(0uAKH#HP-$}G z4|fkOe&moPL;6`IRVbP>!e-I4?DgN1&R=Caw^|XNvocA=s?O=PR)nLCa`%HwoL#Tk z2pOw?FqHDVoNy`-zToL)@d6Gfl&llxP>UueKM{IdczMe&g!v(faYtq^R*${Q{D*|9 zJtLj)BB}4bv<lTpwNIp71EnPPYrx=?yc^`yK8klNcm!2jDRhQtlB){78R#Q+qSMKY zApv0Nyuu<cwsg4d!nxPZ(v+hpb)nw;<QaWMO&iI&@Xo?xEp^gnPGOX<0ALQ#u*~0A z|7`Qol1I}Ba@QP<debJ;IlZFTp+Se05A?Kyq8Y0#ImVx=*bbFDk@W&k7-R<w5Y1pa z9DAHAw;Yg@UQ#7&CC)OO`+!Izd!;6{+6E}T6NpKP!6tK|Y8YL9Kqb%|poZUTp%5NR ziX@!e<kbaKXVP0Khm5>HUA-T(t3L6BG_n<?s1=#m3N0@CggErr?YU9fk#b-=(j?_{ zh7|U>WPw7t@X;#nW(sN-lw#$z%iYIb)0J2(eO?3|<j|SV2MF3oAJl2CFbJXNqp}*C zuCFvk#6zV%SE^H5-SR&R9qar^`9x0TJ8+AuR+*%hsd~wT@zBtt(S8|W@T)4nTN3tg z>+RsNp7R3Rl2ejl2CMew?XS`~TV8P`<4opTld+o(VmlYRBTu#w-$V_G`furfqg*IZ z^X3to#sR&C`71>N4Gm&XK_n9$6d09vM`r8LWWnZn55xC0((c54h05P^4~0)lxhc5? zp?mX^g6T4Wn_olrM_q&LSG@@5h3E0D@@uJ3&=KL$g`Xz>GfCy&l91<4IVr_Ny}KUY zDP~$k$t*T}dPhw+{_Iv8c8{%?usu7Cc(eA%IUfnYOu>^4{~i)~NHVY;AX_w{0Xa85 z$8SDgY)3z<=pLETk__>xAIC3vE3aGx*pK$Q^t@@>Gvj%ye)DD*F)vvIvHLRoj>0rC zPpJ_0jBEbt=!1e~HoNca_@H!&xj>=qUMuDIsGYUjAH$RrVFs_V;|wibR@nNNPN#NU zZVsIkP;e-|Klk$VBcs>&{Di5~gl^ic?(w^yX~NQbpJ{II!pq#E^IJ=o&r$@z{Bk{U z=dMgX8nKnIHv7jUyqq7h!TZGmNtOh|d*26FAn%GyTgpB!8D#iGJMO<)Mmg!!vkUK7 z?Tq}A5y7*<WV!wR7QaDNk|jYT4ORZR;5|@oB@jbJH1v_+mg05-N#q2Sm?d~1GeG36 z8k>~TZ86ZI_h^C_Oi2tR%xjsx(`fsA4OhGS1KH%&c@L+ZWGBhBN>hM)T`S_VVubbP z492I;1W<A39bM$>=FP3k#qCeSABu<Vc#mlX=pUK4dug*6^6sZw&y4uT@YwqVWQ<Xn zkJm2q%-;JU*}I%y&mny?J>R+sPU$fuH55B90fN96#y>w!z-<Ebx9?u5;H=W4`^*+E z|L{5_OPn|Rb2a$!^@OR{d2gxOO|);<C|GM#20&J?KdZPF*DQG!$SC#7OUbIcw;SVi z_t$jXvQKtdkX`h?&+m69O&xr+NdJJY-0Dix<wA|@c0($VXB6QZkIU~&^guslda|!P z`qKyh`e<pd%^E&Oe-WxR<Bxoubu5tIApC-slc?|IfYNyXw$^9JP69UF#he$HjDv-3 zS7=FCo5AJ<UO1ah6qth6CjEti**imJ@h?EF9D{?BNDQnA9he8uSN8_qtR1Qeza*wL zBCSzc#p`2G;^)!Rdy9x4NM5EhefTm4wyA1Lqsl(qN_seOicOT&9jpCPwfi5DfT$+m z<cMO`L|HjGrD{1XIeEisd2=}h+iC@jqoY}`f+5T3OON9BJcT8Sa`IE9jA|7*$9sQW zALdn)+0gYWxtFWb>i=-RyMxC2t2J)sCDqO9i9<<TAI(B%({L+Cg{q8a2Mw&N68Qj` zt?K6~{#yXqn2Ii8RO-6O8+g|k9F{i>tuZ|IE|GIV4QnlMqUKpET{ip3bW4$0QH{w7 z0l~I(v6L6>*W{md^hizZK(dC8Jm*5cEy!DJ$zSrRvM|gu?g%1_@!GW%ER||4wG^xj zYpu)`tZi$pT@-A*Yi$lI*oH2Kq(IMw^P=J0Gm{o4%Cqdog6u049O`Qwt}8g+sdapy z;51n4G^XJEyw>@(g3E_mm#+%0TeYtL6j~GjYQ2*(R&kgMg-a@O$?0Z5t-HCRr){05 zi=vlzo!4PS@6bB$V~YC|L+*ZN>nGRwXa&3H*ZDT(3|_ADyRLZPPTheAiU$Yl4vr}v zdR}+vwc_Cqb%(zy`ft_w|5FV3FscAk3gi`X$SMUX)dy)Q9WkswVy+ZyTOaJA6yjYU za#$%ev_ABhQdnYrSgMv%ct(AAzEZ@6`iKgpqxJPiuPa5~sgHc16g5~MHKr8(ygnKu zL};6gMmXxgVgJ8EMg*Y1+W$)-^C4L=u@Wl($;SUFWdF&=yi@hRW#j+d9kCvei3dm< z(*M&PabE3^pNEP^jZlTyE4Evc7ef+P4R(l<r*9nWOBUr%Y?-|oK9t=({6Dhsung*L zpFJ42j*F*Kth~Ev&`0HDVLk{P1N%=QTXXEnmyaCnq}+TzBGldGnZ^u4q4A^~S!YQt z#C=86c$LSUw<Bwawi4*V!px{_5nxeFeDn745;O|2qxn;S_N;%GMF;iX(GwSyD*86) zx?Fr()hRO(m|y3Q3)2rBcQWKpu(!*q;Cn2_|NY^8z3q3eeA9*f<y->9KeqnLJC$Vt z#K2|f0URJyE&R?D^oPN==kcx5VC!ATK(`D!PazWt*66P87lL-<2>`#H=Lk7*$c>$y z2Pa<1APu6(Q0P5!jU86V(<(`KYa4`Ycmd=fOj;!juoSYEMeQdj*uoQtAKeQvXI9gS z&=SfMNEe<o3p5H$^%O%*_yA-Q&xB`NOAZ8h@>G<HbMfZW2PhZ?@YQ8$lX(t11p^Dd z%=pKn(hp&3vr3V%04D|>xNMDvo74>n`c$B4!r1xZt4?K93bnp0$^;aZ(WpY_Ao(Cb z6QOH|&$50n&je)C#hO;GYr`dl;3A_#E3GvWz=tYWf}}{M3T8@)l7xo)R->+M^|Sy1 zj$pyPR9FOce^cVYJ6F83Cn6BIMbAUQvYFxcTqppCFB2d6ty{sqQv1Q5phkc#Pa}w2 zfSi+xxCfhMO5d*cKJ8~Ym$(ttM@dti;E3)^Zaex`GHO?!O#Dz=F{Ie>+ugtQE#HSV zMp(4AQNyTRLxH;1-zm3_M(#iK*xhV`PhOD}+l#nbuW4x_fAIaNm{hIOb<KU6n^T^` z$koTMuVtw8p;f<th-Ri{__O~b8=ty8%i%MUEt;7Sm@M&uTB{L$%tZ;#8aia`-Pr>M zSzU|1Td7hL&FhX(&VS06t1Ys24z*AQK=O8bZriga4@?bZpZxmsV`Zk+ucg|H$9^q0 zHfZ_co9=%7wbJ@@*5z~i^s(PxIzC?i{k7}I*WcebNbN4Cop`-JYh2|Ue{BB--}<vY zu}}N&#?=1fe>Z2sZv5SPb@JQaAM=^o|F#z|9{=}qso}=IU!U)Od*F5bf%eXy4Rss4 zzuO;gJaqAs?Emx+z*Yi#3p3~&3#rimqmY3nT?=Oco+E`IB27uF>Ece6(!d%5ccPVc z#^;%oT|tjfSxjoEU7ytT0G{}|AP_{NX9EkFKIJ@x%z8Kfjd_OBPx)Q&HCNn!3fZzK z6sU@U1AhqFUK5rC8k;U6uY#e!vLuYCREynBGCMF+Eeyt2roP<=lH-F!Tsq*IDm?>+ zook6#Co**nV=bJ+-(t!D>)oTPoV0BUE&{9}=N`!qMD^puQflOO`F8TwhqxOAJCxu} zigy+UX!FU?PVV8lBp3SMddIz3&qs5QkSm0wRgyiEm=Fjpw|hQVJ7sOi@5RliBPcu| z=c}et=tc+)C?a<ekVmn>65T$7TBK7Wp?f?+POxeTO9b}*MYm!=oMDLHM)*so6KdwI z#jfyVV<G-D#Hl{M9X+;x=Lw>rH4<>)qaB`^DBm7!2rA+!WRS*SFd?{s@(%^L$MjZ? z{0XI0=#0mHTCW0`BPQl=d1bz7WdKRZz-@WACAW%+oMe!Ng+??6`9$%~R~_nfall5O zd?CS3Z*bPaxhu}YQ3GY9PH_iT11kX1phM=cP^yrZ+$(^#Zf6V{0Azt<jVdxNt1v*H z59@8r+MQZ@#gC?c@ynk^GOA4t2<Nk&vhR~dofzMPWr)wrz?IKAOm{vHu7*_61)BD- zm1pJ=@Yxm1GCo@T6a)j)5f;Qd;+^KJMAwVLG?IHf@B3}t)U2wPY~7R5f`hd{Vn1C4 zzgN)3k*F3aJ3+=(_C5D>;jK#L&@jgXr8~LArm6(Gq%}W{m|G<by$X+k>%L-WEFceW z_XxS$!BsYTh|RR9=my8RJY!elX^<;CMe^G7d8-iGCeNE5G2E*>h|VV<ETLXBZ~r6+ zO|wn-=;(hgUJUCDr+IFUuzv@hzrE^vBbmbEBp~ybj$ONv?iG}G6lE;~U9&XJ{b3su zb%c;C4owx-eU=RY+7Wy=Y;p+D^jdF%uTQ$Lg9cj|DF<STSIDpVfx`eG^(AB}{UlZ> zwuMfZ;-+i<EMqGzKErf{uyCU^A2}Yrl`F#)y3X<0yikQnnvbwr9C=rSffnm6GmT*1 z-P5TZ=e;MOC$G`m7!zqbH<GuXG&im<=tUU|gjS~6WTI(`WD4RCNti|6fGTi4RzeqQ zse&i^wM_lwOE@s#&Sc&N48!tHyqYIp0FxLa`B3UZJf$(>(Yg?<_Ud1XSSrBWgj6C| z`2Yzvm8m;L1QiWPl=dj@J}XagLmebAR*tMw`)-X`i=o_n0h2rHLvSJ2xe4~p$aVM; zsDp`;?Es+KqATEAu5MYl5XnlHQ0kPuLyjSW5h^D{V5fS$u2n|4n7$+=ULR1+ab#=f zu?Q5JE}mhJNIO`Cv(RL9@LTc|FCMt!e<#cMH3f{M)ts00?h`g^o@=o*7y?)k)~O&& z2nryfJF536t5oJCIqM2Rqp*G^-{&$m6j&f|4f`kUNgc%dke;I+-3N{{xM?^?bGq>8 zYTejUBa%Y>+8jcrUs5t&*c3rYPQ<X|qZl7`cFU=L-GvZ!uKA!Xu};?dGw26gD)T=< zSD4ZWGKk+ockD$yly8C3iwG#aZ9U*7_&$wuk^tAXBiNo;Zw+IAfQz!k54)|~saXj# zj3?zgHNLxLZh84e$6ZnWe*F1nCF&4KKc$z(R$t{S&39E*h3g80u%B#kE6}>1V&hul z)<mC<x%xvlV6C632%Ntmmc7sw$@ZCXI~qiQOGfku$pA?u(A~IL*5M`Nt?do#ounV; zugm6-Jju4cPidjj_>v9__<!$x@_4FO4@d_?TLWk=Ezlx<>rDs+;T!~7h$8$hkS_wM z8blN<HU*(`FlSZhCmB3Cod_eMyW>F(0+`H+6@fs}RT808m<0{WJPFfh!(UzCvAPjx z5p)g>#U#-)s3;%+h2aWqlE9gXa8eZ^H~v^%(dlhNFdz}Z^UdlJfEEdCv66zd!Mp(Y zZCfU?AOI3egQcPU0$>djk)Lm&a^_Ji8Vb+Fhp<p4T+rlXpvm-q8B|G|LRq^6MLTSY zkifAYp!j>(aq7Y20m#2rpm_jDMag-Q!0>svR}9>5M;w3ic1EEw7&d5UH|P&{Q@f>% zeS7jKV->+92e^<CAwa;S5$I9E3L#6Of3T1}2?BxW@>VDQM<Qi0xCcgAL%coK#ki@u zRQ5D)&f^0k3i2u+suscTnebMnFjplouY|>V<ng8-84+{FJOrJb2%cQ!uLFR(7$k%* z!}l)uA|`VWQE+xupi^b<uKoTTCG6w*M6S}|72fBofHPFvUu#(|ClS6AP-<&D4hfgL zkOV1=Nui<RTD>7U$i@J4Q2_c$61WurUI2jW+akP>?awp$lTVYP!uHRxbNSuWra-~B z0cM|3$6*u{M-fGzf%h!J4JDj#JNv<sMB>yETWiTXg=5RJ0^cTqJlCy`5Yfj$TMmJ^ z0byZ8;Y+$evAEkeAMgg1zo2OMi3#*@Wg$St-LnHZAqa9uSSG{6g$;+=fzd<Amkpqh zZ;^Tu^1vz_>V~-h=4a?*FSHgQC;9JF(K4#V2lR3FaG*Cc&N`tO*(30UiUSC^BPQTw zb{ZUS(F=pO>#*rCK=}eIGZTEG2%hA?AZ_qBC?IJ$PX!K0%og450E;6^l&x`ZR*wK2 z*B6`;_4g$J$@D*^kJr;7f%|C(8u~aCSTkS+c7J>v#^FF5wE!K6_Q@<mw!tB77on4w z8%FruI}w)-=(8@~7RZ_f*N!+t77F=^R4re4DtIxR#52{9Je%RwDUfH>@m!}b&oCvc zMFI<jL-rL$3Z*~{;wdTf;WEDDstRTj%~(|=U5IfExPn|rR~dlwFI)yVm^ukZ6yNC) zk}qWPFfzN+xE5VFfs^-jc}hC1L}c)!6T}(@69TsSfcOZ|q_qrA%-=x+4>_2qA{*XZ z%h90{*;Z}6h)$=`BUMUIcweg65crJ3y|26kNh_BPbh^x`xM1%c;mdpCz!uM+&<h1i zVvsl!p1o8AO}hx|L3VFpmqT6ZY%07?Ir{ktWwSvJ(;41&3Z@gS`l;sXP6W760+vi* z_)k_lCA$vk`zj}2JywLu0?>=9f`T@<yj?<#!TW+gfrr?vfDh@f?C>|xZso((f<_ny za2fD+C?n@8`hj0;KuZh{hz8$wT!Ho2-ZH@tsy18K=AU)&f3P1r2m|`(D_}Y<oqk}> z1<<FV4C01qvTr%i3U4Acn2UOz#*oi6wJ5JC7G~9LF!yt3aBJ)eTNQBG0lZ&{jUEC` z2o22<7j1qveQI+3GJ(EC5Y+h;zDO&7$!>-4VPI|N5PaB^dur?LTjo(flW);U+C`gF z*P$y;U&#BulWzo`tUM83h{ZR|HG!`jz!x8>KlI6OjnJh#^XO6lQwrXcU8uY1AP4~0 z;0S<_1HS&%{H&9l6@YT$2h!OnD6d87KE62Vkf07$&D4K!{uYmB*s>Pz1nm(@aJwP! zB)MTK3*p0cvc(H}tn9_D6p<R5w_*gpPY5j8`J3k0yy9LCzjX2U&zmQyQ9d7T?`umx z{?dFY0K3e#=~e}Y0t8RqKXQm4IK~gOE3~{)t?k=WYr?tQL`IYDigZ60d`}I{I&GfE z4}71(oZ|<+QU$3F{?i<RQ|h3zYJ=v>YnLL?#xa;~43JP+tMWoPz+3Qn>!qtX=6w?# zhr__1R2<H*Y4aKS;B)YAS=pQIYmlBMrv+^E4i76JxmDfinw7`7sDaA_SI`iQ+s1u$ zI3zNC8|l!7547_qbvjbQ#^=4V@0EOL-aA5W_`cZXTZHpoiQEY2zPN(7q=FGNMC&8G z-T|QxRal-y3rKUGLo>8Guw(Z-mPptms<?MUM>ggwuRqDcP4a@ydw>`s)UC_3DmA&G zOIq4&z_%RMgM*~u{7A^<0J~2C*qoJwhppIimyk^a!O0gPi~)gwN3Jd)7M0cp>q&?u zz<c<C*T3<ifADdh{EW&*;$5_kV%WXxRFhHD0sB%|Y&UeFD^I=m8dYHM9S%Yi6x$W| z1}RXm1U3NxrL|$C^$vv6hu?{9kqYdC;yt>pky>h?K)G}?08n2JCi6XlO%CvUHLE{e zJaKY`nidQSzThEaeD!c54%2CumjTDW0ApLrOv{+7qJx14g+FBuO7V>2A<2rPV5zh` zPp1y`@qd8KfxqfX(D2OI$nPYjefp48JrBPXg?_loUysh0K<CF!L|3GU{IFukT}-nV z#XbHc_04TmvJhE7L$&!GC_f0E8LA!c>g=Nl9DeaY=OSmK6!}U6gw9=)D2-`~K{kM} z7TOK#Ku={$#%<6;LJ9mx6ZjZ#bDVgaBsBJw9A?Fb8W|!VV#lmRV!@0jv&pz=Cf1mO z+m$J>pOZYcV{iQpB|y+@<&VX%2PQHn4&RgZ3?Yr_$0GLWg6k!x<L7C{`?`nRY&^?^ z2wR}#PqZzuuacMIyEJA)k;x^H_j7Qzf3Sz|J{ZRWpV<PH4*Y+~vBpGCMnH{;H5MJq zyEyq@q<|L!>}0bsGpL-cDPgPmT%?Y`2~8Qg+PHepGb}Nqv=SABqFb%WdIca>MaN1; zg^leHGf8MS0rE1~OL)~~IlwQV9(CoQU|i#{QqS;>=1e#q1FYimN69y+LyRayu^0F{ z!tPD3yVrcxeNJ-maPu<1@R^U`@*kP~8_(1zGJWN{*sZ8+>S!~8zln^>;LPl$pu=`l z$a13{gk0Qmz>yoDAK3B?Gm^Eb57<ACuA99K-<uD2Mn^637n7^iGliw>z^9~huqw1b z)8zQVD`h+yRshfPL?L8%6|8z(-*;>;-xK)4EYOeiyV<$0cNm(Mk8=>t{K(%6USpiG znx>XALZ0#DQ5D7NoP(|i+pD?dLQFd(R|&0{AGKRcHs>QsNvE-(XU?92PM?2=4MaNq zMHf*s-afTl<krGsdrkOo7cX`3aw6ZWgTw4%(|n2_8yT>LzA_Q{#tHo8h#mpoAlsaB z_PO8J5UP59sw}`$e;=xsHVn*9y`7v_a7#+VH&-0JY?TJ<-3I&M-sg5=(3aQtb{E;? zynL|kEaFJE^r}P7h6r}XfOpl&{quJQVl3{@W8(>~hP;u?L}VZNL&gSw-zvYq2B^^V z22pUe{jh6kysPkMFj)~a0^*?y5t7m;h8<5CoP52pHm68|s#abGS|Qm5sFdr%7df^l z6a3u-bH=<{M(x6rkk4kZ$9XyJqh!!Mm$JC;-~<rYK>a}c)teEI$uYz}k|_~zYZt_O zb@wBxDv_M)CGe`$%FgBSHFWkFp&uBa0zk9)#Zg*ICb8%=Y7|uG2@r2#71g0fY!b$w zYoEsrS00Dp9|G3X)18%<V+6jxM_LYJTE@P9c9{}h`$XM&0Lmf!###f9a$?H}DTZBR zZhE7*k0{gw@f;3~{9m#4<wsG%Nj!3rgk*zrSPHsM_t`?tbJTGs`9C7{B(RstKTVB` zx1Q&pLWg8Hd>_D0%#Xu*Fjw<&O*HpD&P^QOI#%Z$L<hFR<Jzf{7(QH2ieXO0t_%Qe zdf>|$>Y_m`@9(`4TtkT*Ha~;|%%y~rzk<FdAh{Xqd%$v)1g5?&THIzz%wm#%f!!pG zx0aAMKymsKny>Lb^i~r0wRpz-Hlz)+E-jo(Ly>WS`#6|Afp$UyMia1L&)=_aoomwk zuEtj*gg*yyvw=`>V`nK*l~`yVc6LWCfBo^>sNbO3=5QP1hd==gNlX@4FuQ4C5bLmd zo$oe%Tqq8J7jq`Dfv79obGGK@fE$ix0>A}$3fX_%5$JabksYlUdW^rlwdw!A6|&vq z#vY+yX^%hPC)?$Lt{p7|GX7BG>MME4k(T!+RaJ>H^f&#_tjj!?-SaB2NBO|4WzQxr zD=oDW1V`?wI6q!@9YGV^jnG!K4EFj@A)9+3fMx|scO-myJ@E3mOHbqmMi&~RsYr8` z%KP$`mv>Ha&$M-K<0C86oYB*x)i>=6Ylo5d_+}FIzlA@MmPpXNTozBT@cN^FqDZBt zo|(P_klg?4j(F|ya1$YWFv%_*sPCa?#)#hZ1~Pn)+C})-MZzy`Lar`iMFH!RLUW6` z&XlS$1!vg`SuKgpF9r3QcJ)FjxtIH&XwBHOi8f#V?jT#65_-|CWT<_PZ4uMOWI#MV zgHk85A5f`N^aKLxM4gg-2j!z@_&9CsRML_l>6HpAe=iVVg$%>JT_!*TYug4p36lcq zbZnJ&b+?Fv^**Ugg%fvs4&y_s63x|b+ACkv4ed-<)3DpaFdkaL8emRX>4m;fX}qO3 z2vnA)ho<N{8%&R~*p@;CdCn#u%N<G-mizTwnb*^hMd=y#AL}$XN`*w1aGzFpYNCgU ziV6~P82Da*TeQ#BQ9EJ0ARR-o^KjxRWW>OF^zA94zx9%c13>;baR#f#6a|u08}FsJ zZlJ28aSlg7`XW#91X2lZyu7@apqccjc^u8CqsB_ZqoK~*$T_On@Idt4_l7r)V9P#~ z(VtYEs0s`oxILMh+~Y#Dm=K4}q<;z*qbU&R3zIC4Px$n)9k@@e3&7F~phrgSyL1#6 zI-?mz)#Tow*B-Qco(}R~EswdW8jhg<T7p&u7jrSbI=JNOg$+p^>-UhKaV8%&+W7(k zOOM+Qm!5j?Sdiuz;9e)fjEb%+PPBRwDih5AU6fW&&%@G=bU$6%k#z3Iqr$FfIztWf z{IrrH+rAw|R=17IE{nTWn{Y3uzmiZo_7Nzd7hlkKDys3pVEUzi60C2P(REPX|Fq+C zyNLE(u5pEV;^<4UL&^<i+M#dBh|7#u_Q)!C71_|zZj(>&BlN>p-$yV|CoMC?pRk`3 z&e$hzRXUt)Hv0iI$2in*6aK4?upjP|Wts~Xy&C&ja;&7!&WO8<j<|lPO25cQ?xuPn znR|p`mk+&?*h&mbT0a#Dqv^}e+8GkZGc8hot^<GwT;T2dU5^C{h4vh@dIA6a6-L`n z)l}D;AH%*TXy=B@?e0`zg)bUW?zi5+u)}?A#nYrPi4!~YV!Ey6)~-f>00S)Z7UVOV z1>FfM0>W-wEYDa}{4*b{ug_`)2y_XRw6xu@AdqQnEtfnX$b0!2mvk2gxanGbG$|PW z6Cvc}HNrl6h2<FGnuR#%!zrY6V|DxJ;__k*0D150HGzkslX-GIlTz=E_eD?2iwj81 zs9~NUPA|C<2V?TrfmI8jF;XFH+lr!J#gJtXgB=L7LPhh8-6|BUUOYtNa$<Y(VohE= zOwo2`mxKF-Lg!Lrl#XQjIVu?x`z4OJhB<*j{k<C36^{Ihwd9^l%EV<AP2p}-GDwvR z8SpB;FRy7?ChY26KS_1Ng>V|y_Gy{t4w`Yq{FJkyXqd=4KvvOmXCF~%BUHEAP=ejS z!{X-@mE&>OCSWw5#b|jN=bS3HHcOA2cEuuI23VwJ>a&Of!5gx`FIw|t?9(biX1Mj! z_3Fr$K;jz=9EghL4;KHnYm4o^M_Q!Oy7&fxrjeyUv(XiY&`hmVxH_(haJg-a;DfiY z-P?r8vu@we=Y2#QlJ<D!GWdWmq)e?WzuMnz0>H-h1wG&h=v$kv_}dh<hl&9Pi2ZDZ zDnH4kRXW$2;*+DZBz_SMIB66guoTTc@P3$WB3<nsrzrGN!5h3YhbMY)kXqglqr2BE zFCecXjTDyf{+^b&8{2(5gkM>pM|co;gMBD0zEPC7zPK@GX)Pz6#`>3X!SA%9`(Eb} zCC=(-`QZOY*O^8`{RjU3I}64>7>s?!mc7AXtj%H>YqsplR#EmPOVVr@LSs!*A)z8m zvL%gOCD|&8vLzzPQtGE%|8wp+_udEh>6|n3<on<=-}mSJdc8>lR;pElr-O53d@W$I zUH63!MQf;NiGI}P_5&L5Krj-xE-?Gp%f-H;l>^kL$XCwmxktD<?3=H4lVP!5wd(ES zOE;@AcyNj=gzmQ<G6WisIf_lFMq}6+-3n_vc%Dei)am$LSJ;OghiB)(>F+Ind~!~4 z=YLdu-$nq;|LS+f18dEUqx=8W()chJBH(m~f19LgL;vbHM_AngE63NbTKoqr-I=?z z3fC_LG&}WY@*`jXWzl)JxH{`^;2XM!o~VR98TLgVo?YvxP*iv&nd3kWv7zXke+d)* zbd(L(QS8m)SRDw6GpR=7;V}UGYf*ad%K)Zf$s>R*$yU{(2X8QCRin(4g>+s@22mhI z^sfL){A!K-;k4jQsjCfb=Y*98{PlGs_cya7#TiJ4OU@*&=O-R1N#ghLF{H8|tQ@Ep zI=f>%l3zziTg_InGvSt0b(TKvw|@a_HTQ0Opfiv_dv(02I*zGv{>Ye-YLDj9t#2CF z+33nCu14rZg#|l<GXVlPH~}F~J%rliFL5X8)qid^*tivPV|qmF0uTD!2fnJdYLVSK zL{CPG&e99>0v>+8yo_@?8&-46+4ZZF<)>@u)_V_yk}mt6Js|SYUS|uZ<?#~b4TFWz zC)nnF65~7$dp$#oz=C2~9!=G1AwDqw?duls=1iFw@ZE93?PWRtrF?1pKQEgO5Xv-_ z2Z7cnLymrsNu@P^DDW*OARP_cZE;96D<<(IV}=zW$9w`l{^zo*op8yQ&31Iakf0q% z*k)94ZA!u-&SZsYjRFA#kH<?N#dmk+D$ax&)K$OX0yfk<1)`n6$~&b(4t}djvGI2h zqpS>apI2y<8lNu^8Q1oG`ICNt#dWFUqPyqb9c!#HBC0)#2kSGg?Z1R*d6b8ujU1qk zH6(PJmZ1eu@iG5hHs-5#Ty?zE&ue)*4t2lM5`G_aqM6oDhz?O#7*ikV=TG@uMwY_{ zMHv~b5grc}0+Ltgj5Cm*g0ivoEc0EOh@rudpqU)!toLvU7EX{LA2YPV(VhWi7Q4R6 z@mbBbPq)4^aeah~b1SD5_`}3AbeS!*OghH+lM75$yGgJ|j9%9A+!`tXrufvz_4YnH z=ZPO~dV1nc7w;r2496AauN(7~|L$~MDxmFvgkDl*e!IxCpIK!9xqHHpX<G)(-DYD~ z@pN3t*eZN@i}S|wZf0?AFsqX`r1DJiQ8qI*<Qx-2hCoXT(V@Z?2~U}hP=X`07A|bD zhf}K*x$~8PnSos*71~MVT&Q_Q^T;}Q>O@o9W4?ySi__(-*gW_Iv#diw-X=n)5AkQ4 zl#T0=&us>o>jRP9_=0?MN5;5wUvY@I^+c1E3DYr{jm}8D5Jk9ij<7NZu|<J_1}OZA zunpFtRfldrbw6#W&n1X?eu%dGh)<H6eHTPgo9j!YW*U*r-FN!S^XO}P7P(|zR3Hqy zFX#-VNU$JU7^ag+!Esm1)G|h|<iL4pHGFd48OOUnykJ3$;-6#$d{Gye>KB^?YZhDH zbcV(E48;4Wm1y@L;$8|ogG>r1dHZTL0dnhnx7f@*CqzHP@9HgHx(H*Cv5(s5sgP0Z z{qIQ{8ACTF4y3g)56-vg(c3r!FkCUkePb+c4enASKN^i9pv<zoP<qV=+ecclNQLHD zMw%B(3pYj%(P7Y2LnT(Bch0okrWJE2`M|zqa^~CS&?ts)P^pG{w;jzPn#FXZl|dt* z(cBz@3*y)gcyO)q`9r9z-{?RZ-q5|XH4D(GMinyJ(wd$(j*mW-Yk)dn)n*qhsHK*S z2GRP-m-9b3j*v4Nu#I<wxM~zgsk#H1L69ptuy8-&OXjc~kN|Fvx@!wNoYZh`hT7A* zpDx+WmUE^eWgM8DcXGR|pd4gfh_D7s)|i>FH_XPsUnE<?pV$_8h}M1`o(Yn+>}8Jc zTf|`K2Xy!gx*y$dFa6y*G#F!e5P6hQZ2PcQ^ctSoF!}0hWo8JgIBE0PE>3d2Y=p*Y zzERnisln6)QG$z2(*TZV4UKb-T50eh<|v11^T?l|%*fwYbp1H@LxufU9L(7CUJteh zKC8d&m;}1_d@y^yawyWq20*1f%}jG=rC*)ow*$awD%OQd7G^cCTv(+45M#N)>A|q_ z&&kbk6lMf0y#*ogeO>>8r^Uqp@lPiGe!vm>rn-_mD@ldfjAa(t3O-V|rn4;Jk6xNL z4+x!h&Q(eO5q-n8A`KGe^b4c&N6NfIS6gbg-w!_^Z3;<pB+=WL!3kW|_c@ECat@wo z;2A5UFYT;XLdOkvVKV`R^c6;u2f|04Irk`s*m?LJrk-D#<4}4`@M{`Hnb9x`a1XsS z@7rsZH@fS36%PAsGRCo}_U~ezOsw%}LZ2t<wdW{(&1RCZl6F&3_@oK*cxe;w^OrV- zZ?f>3r{Ur;I4*S9)iI&h48Rre;P$;_ehdFPd`~fo!i<R=o1eol@HCatdrq<42KG$S z6zk;P8_zdx3>epmyF&H}^x-Fk<0d6%;6xzU6|=+zIMNrAbA28QVQXG7@L*++$H8^B zr?cp<X5OaAOwgFmwkwJ}%C0v;fe7+D>7Z8;iRp1<k6qS8DjPbz-*7-@(M)Qff7ac@ z`nh6snd!TNetyieWe(>(xa2fp&wjZ5_U@n|M`-x>lJoDfRGbgd6d*X&q>WA=oyxxJ ziVDjcLl+VpIX8p{nB>VMmGp?Y$q(C>hS%M*94+1dn%8f8hTUzXMW!7;O?PPHbT}`3 zYDKd_L#7}p%`MsLSptVK@+xC!Y*1bJGmphR4l;n}P$hF}&e7pdr-kacyhk~bP@*rr z-3~UfN>XW|H%G?TxrTP|Q5k8DY;Y<In&6S{@;JAx5`6XfXe#Cjqk(bad@Ex8gQq<Q ztO8=Rk{;qH$@(i;^78RX3r7r=uD2(aQbRtEf<<DuvK|N>n8D~6zwXqU_huG--=46> zXWs_lVW;gyEb|R>$=YhAKDXNM%wf3_HS%ukB289iXhT%YrWJkD%9=x4rwnR?xnC-u zs@|K^bK>K}$@C{ihI^(geDB+l=9-9ZE&z30{`%BmBh^ghV>WEIboTw;O&6gIXB`kF zyvAAo_efSvvozySXZ^{Qj5%^$2Od~|<}~y0vI0ALk9opxwt#z?Lp;md^N2Rb`(2Bp zL(Tv6av)*C?%Aqo!4of}$u{f{BC<{n!3C7vRKMuFT2mO(te>+qeFR94sF{=RW?=TH zN~nHt4p@^3_VIa)f%%;beE_vIF98-t`UGO}3I_lZ1;E`PA?f~Qc1k}jGVT@Jjq?T2 z{i?Q4+IM{v!cLfL1kN^J_xL+yd_gdL^rUPMhotTuo%}$xzSN6&L;EuR;S+)mtXB+F zzl7H_88=v*Iqc`CX<_MH;~2D<J1Fe8eqtG9n!>!p^pg_GW;<C-_+R6I9$)w1R7~mP zT<5CrOAkj4&pT#i&(Q<Hr<pIH2R5f&$~nCVTylB=dQloiC{Ni^Goi%3)2JXia(M?c zFAM_YSLmuzpTK8e@EZ^vd}^d}`^DfhRlyy!hI#B5X9fI;q9sgWu{EiR_~`_*YBu}b zI@4&yld-wvjj#~5<j}!!P;0>sbMS+HJxxpI9m_r#$q!|I<?Pq8PmJJsc~7p~{!RiB z;sBQ!0|A92dY7w+5pNhF!Hct_cTbuYRO5pg$WvP<o|`zP2EU={Fim9CHLaKoGan}I z_x0=R!7LQ>vME#JNx`e+C0=NHl@yXHAn;?yFPBL(BDa7lU#a`0I^R+^Z(vus@zQD# zCsw!$PV`=H$yGVYy#KI^_4eHSoHvj#a_lDzH+j!3awWKqX6JU^-Goa=Ig@oEud~Y9 z$RqFonfmnK;%HsQ33W2=kiGKg@BP^yl@Mqg%ysuVXQbb{{FsvS>hh(JQei*W`|v|) zj@DW5c?Of#{+DKm2Pbk+4s7O}+t#4O6{rz1+}=@W;9{627`S#)1Ok4&;2o0rvp0k# z)+Un^y_psr`7Ns<RG$wLo5TE`J<VHNbwV3TYJ=`@QkDakmy}&PQiP)^%-C&v>sSjn zPD(<<#u5KFr~4p9JFxvc+P5o2HAPJtHNP3(vDBiiF&+_nH~+u<^je|ZsW*C|COqv` zLbeowG#RY@lX>C_-56-pNFzPD5YcAL709ARm84Bv5N7GEA&zjn?HbmQgR>gm(I}bK zSgW;Ud{~?my7Y^Qe|SOxR4+DEGOAl02GOhu%O0hb%z{(#QO63v01Ucx$2ErXH3Xe5 zpKg`tu_Y-)KG=w|WYu_TkUxIKLXR<{!%Rm(J)FquAFU`kqg6*kN1F7tE&34sq6Hm; zT6{Q}iN%9M=cB_?zZ(nQde2F@DUe|dGds3xb6o{uw*D@esjcUl#`t~4DuVZFp@?R2 z(}ord1$@uin>mVaQ4KUG?(9)Rc7}c9gc~w1z+;>ut{9LjV=zmQ)$hADJa(x0o99{s zJiLnS77d4D0rHxV63aXC?8$0r!Mp3(Lsaa~&ZwpfYC&9Ku-%CCE8pz$opv<nWz-)d zOsu$tTWTAvhH=K@!c)F2n{TBwM~&!KUL_0%J&!Z7;glqmhb%YGV$w9yU7VKaDm9Gz z7da0ik$b1IphpW%_?(4Reg5@$s)I)Ul~j{%$u(E3bM`6|d|BhU%c$!8f_O$lj5~ru z0s}c#1G%@?^Jg+G`Rdo~_$$l%1?nj4jfY_CV+nt9-;VM_PA>ocpevOLdIRJ6dG|H! zwLJLtr!NXe@~|FYoJU+Lg;Z(=D>?kX_<dNttw&jJ>Z(@Iy?X8kSDA$1S*+o*(j2}1 z9jwUi$<a}`86}f0YstM+KetY|^*g70Q^>9c(KuI}arVF5IavnzS3lEJZ#C&wcI=JW zdxm>7zTKD-AE*(QX<9kaIhk=ZV!s4V4}8H4#axn_ryq;#p#hOwCz#*<GhQ?KFJ<=o z!GzUcIzT(NlHd~g-+N7AqFPke<`QKXq7j)i!VuYe2@x&2a{kUl*nN&SsgWNAGh$D{ za(DM=@DvkI+MI<sHZnek&A9pW(wE~<X%ptf+Y?DhzKnM%EciP{!=F0c)Eq9(Qvj3D zxByc5zYwzdZgoK8jdif9O)&=8!v8-AnN3~}&;7iDEv4bZ2QXeMq3eT-;O)+ZphlGc zH$sN3s%Jz>me2xu*m5{_j_kKUIKP~oR|RtEPz8+us$H$0yWB<H&UAfuh>%@auCU;U z18wg7)cV+&L`u_TZp^hjrE!U9h3?I{9srR=xa6cgrCb_9bh*7(2*{%)+T?=RgTl85 zE3ER<JZi9CC+|yneK_5aU-jk?AxjDUs_$A4*!4N?eK{U>HP|HGtj%J(2<NY7ix#n1 zumrqlF7*xt0!kKdTVtvdN2X^|fRV$EqrZm;8S3^3fU>$ovg43A9#r!pn&3XTIAb`( zVMYPzOj;>|B@@aF$9J}PiSMQNP>ctEsoqH2IUzLBrYuSf@c-=OcG<r@z)^beUf!TI zOf(&RrTO}g0R;dvE}z}}SMk-+YskuBL%lzH3f`9ig@LQbPz8gkV-m3vfOkzr=9&26 z+)4x=IPtFk8Nc?s=bCr62b2%Cl6#e|pUzuCMgo&#@A;Jdf|m$Ivj!Ff@0Iv~e5G5( z@@fFSz2Z7mQj`m*0Kk+BG_?+uJJ}1n-UKIfGZ$cOp1>o>rSx8o^pLDwQ57FsRdna> zi^&WWt+?a9J)z;x*CO2^)OiAS6u|RvPyq@I>+l0iRFmH6LCB9@??I@}Il^!9y*Z5V ztju{inu{es>MhK3H#A!nWVYTBOgZ;Nh-<MEbro#IxKU@W)47fjoZ}6i#QUK?IEW9E z8~YLQ1z@&JO>&f#62&Yi>wG0*C*NQJ_kST|QGF{ssdj{lVJ33`ZLAn>W({VF^nGF~ zye1q3W=gNPe$zLvq)PAlS*3FlJV&2t$Z%0ofY*e9*!!D==b4;G5xl@tD3Kq~de(VY zB}KY`>Em+#=BUY7Y`|Rc3~;CSZRWxm_$%bUJibHoz?IRb_mj03x(s!HTgcv=U%O6z zs_`iDy~p$$x=JcCFK+JiW#7^E)w{_fSOA#Fama{i*8+}@t$Ptdj<v-QPt}0WrEpMB zd#XNc%agZ$>KgF-Y6jv@Ejmq+=gCmvWQ?QX%Dn5Sf%D?S;F5sh&0mBnkNYQeIJy08 zNtH(ntYlA>(rjeC9Kp^SDN>62n?gKMStzOsEn&|qA7YjiQF##PoKdH~O>jMw0{%OA zA-+^hwB{#fx0&bjsox9W2ZDQ7wm3RyY%p-~yz}XyXkPkGhJ1%V`KUlN^Orvp&S7YY z0#L>R=lJBbJk#})gi%Lhi88-Y=<H-|(P0TiI)~>i!d^NlwQoUM&HR<PvlBdpT^B1* znT2p5q+NEZ;3>Zck;5*qHsb0-Fea=EU1|5jd~;8H!!WgqLBJ2`8i}vCA&Dm{sNbhY zP_;Pbf1}Er(n$_zkO`kJUxgB|LPC#24sRC<%<1Iv#AM<X$yZARU?rH55nEsgZ^A)5 z?Iq@tf+)$<b_rQ?zBmkrN-<XS^J+wTh#C|7&z=8vL7F4b#vvrK!aneEJmZ(RC&BSw zK9^Z?nrpG*#J3bxyB=mhF{iUQuwd0|Jv)kGON<MMIP-6_mU$T+{bn8k=BX@yUTJ@4 zf<t$zAtUWt5vxMmyO|8sD&BlxWGT(>%vaMme)FdZY%*x-8DGC{j5Ya#syOkX+t#Ak zAGR{lFRBy|<}2m84pB0iu<e?CR3X;SYZP1#h52q(Oy&;!!(A_kd;CS{=M(#j8ikB% zaw_@HgIAK~je;lENpTM;99`i_=BJ9>Yh;+J0BjYqiD5cvny@<UjCHN41VHbi;m zNE-L^#{1pBX&~SEtBkqWBrC87;ZH1llmWWW>6ykanAd%B=b!?~xq8#diLUmc|FNAz zq_wZQjlfM-4`MA3&409*Wt7$&Q;O*~u27bAmt>UhCi#s_f;&w3zMwjNyuA3G`#WE7 z26Zp3UoFL?RjcTlhOCqQ@K3~}6h+ZPr96_bal=<iXl>418>w<<I9G=94S<zOXeqf; zC#x9jDmhl*jP0gH63h_4vxv9;v<}M)0x$ha&RIj6)=#cV3^qWJZ8sd!4+Gqn!{tOf zbmi`?I#i_Iup9{EQ>Mg-wZ2chT~<)(rqXwfBQX$_MfF|JY-P`ceeIY$ooN=?%U<Oj zG)$(>zLR9cwJJqcdhqbwBXc+d!Rdxm)#5{9eR2n07O<7gDq9B-TQ;W6jWpt!OHz5& zt>0BME?nz+s^-_gyh3`YVAI31v34?nDnp6Je0)F6KC3P;E6)Y5dauq>8*vc!&)Png zq_N_oC!6J0dxyKffl!UaGxv)pj%2%|Jfk^4oCh9mthibTTIAe|JfWtnt(-RgS2{4w z4Bn2<X`)%co<&|7HJirwrCo$tLBRRXV_p7Sd%Bi!S)HE*I|7ZV2#6un`tz$8$MjZh zL=o6dNRP?@{(qaAL_c5FMcfYRvGR#=4G_h~wdLjYH`s>Ox8j>^?GxQC(t3wp%ny=F z8fRq9O*+c?o6+WKIZhsnoQod7Uf_d=z`;X8uoLSPToT>;ycQAX%d)!)Ju)9T)wr0g z8Fd|0`OseZ(dWNSFkbWMKb3w&`S$|<X5Y3{)olCy8xETj)<$mtc%3|d9r{kLaJ@0? z2p`zu?(;!~X99zQyPDB1QCiVw!?%Yl^mC$<ogP7tif_WZj-fS=qrRx5Ge61uEQp!E zoyQLK>RFt5>?WRz;OD+z-N+l2OfONr+)>ujXe`M`9654%+ocwKrY4;aDeg}8E6Fu^ z1)h^O9K3Q&@+3S`yfQ4k%W4}Q&12_R;U_>iOGx=9L_#Po`5YJ*vC%o=V5*?T2bH<U zMc--3e-)ldFt9IveC)2d^sVV_fA7JKR(5VsCk}bCM24$mZ|uL|>7RS#0597li@L?m zuu$)Mv@q|R`ah_1@lOayMwZzvsG!v3MXTvC{%Gc6{DWiv=zadn>H8mchmK4bu4@{~ zt1qKdOqo~;A@en_vS<hwaEu8veKGe>mfOG8uI*rdSBfnC#hL5aQVco`cl)n*bW(`i zg5;TJ$(a980iPwHW~H*65+un@koxc^a?S0(dUIEUqz)@Pg!S&+sPP+ysM=Dozwh7b zJoP@gNssvLa|PXJx>ux)vjhwGe~IhG;bb_wP;sFo<0Xh@12}N>YGQZUy-o-=5-MlM zMPwCm$PSn-(WVQ%KRk6NL>~0)w-*YS`L|RS$?bD|Y<Jto*z46uBEmDmZss16D)nz@ z`^cGv&;4ebCkfD5n520?2q`gYL~OwS-nzgJ3oIaM{`YzL)qT<KZZW_SB$_<${Pzu^ zdB%GMB3V%`DamMO$^v$`WGw^A%*QtXHi|5Nhp)U&g3<BWuTk6FY@frZhGfNIAqNsS z!<g&u!wvUjl)L1w!LG{G_FV3kzuxzH3Iq%y`%wGcqB{fVp;4@lTo(wh!G;hEDy-lr z>lG59*7yE>1@>eHu9j|)JO-s+d7hj0!+z1u10@v&*%}ht743@+`gG$*vFd1rcj<gY zMw!8Y!ULaxgXaedS5OnrWEgD(ivTDB$f7-yff`}nS}{d|Hu~?vK6!ACseWZeA86xw znn^GOY7|7C3oufKs`!*`b1ztuyR}jna5P#jqfggM(I(H@c(Ru$$)T9kC-Iza5KFSC zs<dhl3Ru5-IK!xo@zz8_@0Rt!0k#GiY*r}`C@KP|(^gXu<7q|LaBIEfF}18uPHpn$ zWXObJfNPSuS(Uqv|Ft&NEPJe=uEXKF!D;u0pC35(a>@)CQhW^AQr=0>35{E3suK%i zJub=&5tjLfDTs@_xy}s9O9!gCK=%&u_tjTUJFGCjxpNXJ=WDb)ge7U<EM2}$5M1d~ zrU&Ms$xyAb@^6Gv=W+0B&#H3))<38ay`2D!y+Hri#dBK2?UWMMtT$nYx&xwPS$B!- zVynsujk#W;<qV<I%UKO-JW2XIsT^xYHn#K5&lq&D{Nf)Ad9*5`gMRO7$I<K=Ae#dV z$?5Zx>@%Gs+KQRe{i`pUk#Ft}>9gp=PpgCHmg1L})3a$ol8gtG+iD)CN$aF@)3@5b z9nL3I(^_B?R6#eb75}V)_?$lV1e%DBLXxv|niw=1OwkcrXeQJ!bArX^E5bq+gmwDR z2&$5pITZobk?oTw(n-On^eVB8<(i!6QF3`OVF#j(f~xX?RXcmU!PTd52R?*Sv3z}~ zFHFvTqo%+iq=gAFL<V#f&J#L&l*FK_9vnA>Lau3<%PJ`p-cl_Q5Omh;)A4*om;&XA zL8+=);#jEa$5j<DTjKpnZ^li-$)FO>`(<i2ryL<SgaW&sb7bEd%L--@E2%fs7)GNi z=Ia%_0%}!f)UMAk!$VY$Z;f74hKB1fvbCUC^LtfQ_wR!<&>gaPwZ8J&;PLEL!W_-0 zbW9~><^G0Recp4stpy!Xk~W@}ozrs-+#>|AS<@keCAC{W)tW8Wid-v*q3;M-8exah zloWF9J`a&qam(gGTh4=um2*wX40%5g!0y#bP;c*2@6@*`^*WGO2z6&QxpXc+=;Fx~ zk%Ufme(mC{WtS8^{9`dTrs9|g=}x4bSOQ^7WpDG>_BpHvQ_fp;s>liioORY1ys&;@ zXUX}}0%2$LZc^>@TeVJ0A>BH+<Co_P3wr4lwZlY}N7^Se_-F<uU#?=7hkw@E7pai} zw;OdYm0mz{{%DLVf3vP#w?A3ttg1O_sd<7~aP=1CzS$5OadR>}EcU{YYaYG0$hxVA zr!T$$E&C~68~!}?Fw9-6*O^RL-BbB6qB(2UcYKnh=4nCueEYbMCdE8-mh+*3K&keC zrtGxabDoC_oLce97J`~uOXJ@zK0X4meE9jK*76yxcPYJwhv(mNiq=Zn!<8JZ)uM;1 zx3s=iJ^cDmYpvzsT9?-Pz{B+st#5B1e*37kvHWmjL+ks`hu{BcZF1Ic3LO0*R{ulx z=$3N*me$d2{rYXQqdS)MI}S&8-RgHw9{qWy{%82nUl;0srF<VU#X~9e(jDr*Gi$`x zo#yU;|DB`qI4HcTIU-gK&tG$%K&DU?DIbt*Y!U&!Qcprr_PdS%azngW3Ra(eIp@2O z`B%dJ7r?s;c*F!J1VXdE|21P1v+AL95m4hQu191j1EZ0*$#omUQ{BK*kKt`?;C+VS z8*Jcvjp2XS!2by&@TEcEJ4WzVgWv%M&eaGP)D{wNJnVmK3m<6|KB_HZ&?s_D8)4Om zIIb<~-Y9xXTkLG3ScJBCe53efZDe{Q@~XDPwML2C+LG0clJ(kBt&LL8w510drC)2y zyla&Cq%HfUQTDsG+^@#N-$ZdWp#*i%7Yja#MN2=C(o@ose-w2}WlKRfTH%hiqI;9# zaUBWoCZ)hF$@5LhG0~E(6)IPCRP%LIt~DOH7@g>|rFyDy>8Xy!ppM3|0QIxcY7x<z zSE3X@HOYV3LZ0Ot*lQBMq5~8(Y5y`G<_uToc{C*bNcU=!Jzl5T<|GlWtNm+MPj~yi z$+oUl46aiLkPfSl-qtxEQy7rdH);O8xz{j=r0)oMX?n0=Tcu_s*JLQ7c64#eu9T#m z&@HqdBgX16WO?0}JZ1JoYIRncI0eB{c=cK_hB4cAJN^28-2(gDLYr(MEXk+poVnG` z_Px)%a?NVrV{|tG1dJvJqlvFmjvxc7@|v;7bmr=M_03i79&Osa#M-~?GsKeMl{+>U zL4uvl_qVXb`sjt!IzllChef{b*tC+<wa0sCBS8o}O`@{iwiTjoyXtDJJEx?}ub>w; z(081RAT&i4$Ab{-fa)Y27kJ<E$gU}`jfcywIjLA?9nU|<7FfrNhxYo6#FQ;R*8Ze- zr+C+HRB0rUCbtJdOo8-SBtQ74KK!ib>jO*Q8-r)me-;fj1z%~g$JrSV^&W%K&^x^$ z7xfI2;~K78O?3YZ%xVdv>jodSIs4(Um51GCbATa&q|y&ksqIli(3jfnPRn{{X-r?( z*;0EKXFaOar(rj+6Bd4FK+`JT`ZlANbtp%tV^<&=1+9tKS`U?1*evT!*J<pK*bOR} zePQrBM&B{AS3eTsa`x9blx{%29vLHJ5JWfZ>`j!zY0UI)nC}kxLhcd+FCQ4_SDWLO z3=ASkCJm%x4J4)+_VP8$vsUqBb322`Uc*v-<0%L&-aB!vcY}hUTyeh$V-sre+{2Uy zc3g5u`r9N&$DDz1@xHSpXy4qyFT){v+M%c*6pVDFn)uP9KWwKj_8*^&F}h(M-3l?T z>{agsNv+@$k9SKh5w+mKiQ6PoMsHlECpW@e0AY^6P-79IL{~y34;^_ot?-!LC!2Os z=Y_m&nyd+k56TAk*xYsy{Yr=d2G?5fNbJC%@=BjUFx?~;%*$p2hjCT<Z^^9RX6vLY z?;r-|vOZ%MeE%w<SC|CX-ion93&&X^j#H+MDru5ddB+^*M>1Xk@ihR|avcp^6rE5* zT!L0@0#5AH&#-HKxGcJ!AKj#s+VF@XSVK*`4Lo@2b>#~^>56RU@86pmB!|m=QljQY z>}`U14jP96h7U-DN*Y{=A=XL5AQ-ZvgtjG)M<4Vx^ZN`b5d9sxDDn@`0Pv1>E31&o zpL8GAK~j$Y4ul$7H_PjLBxy=_D0jAI_V!fw_GmQVG}>@LZ7a{|-h6RgWtl_*>T`P% z)EFi0s=Gj%B8|$>;eS69`fhbW0AqmN4wv(G+$U4$hLt3vP$B?jE7$g>JtCPPl0+sC zKcU~TP4-_;jB`&mjHMge^<shlWQRy*bC9I-|7kFiS|9u}pcnwy-eda^y;!>csj)gX zNIi(Ii&CoIH;GZ}i=JrubOd_6u*VG7OGNTD38ub16+e~^8P`n)R=SI-dk_5#NW=la z+f0uMd>Xv|lNHZ+kwrHF{u3D@8O55=t{Iq3k_;2*FJevg5D>AUzXmm$7t&vg&#DvG z?}!akwX?=H;8Mgr!ygvw%J|f-Ycw;=0iglJ5AD9e%Q;4e;vymA$LW(1hWg|uiU>B) zOlsyom38soDE%K9H~eTjsk@hAVnQ<7?ETtHJ2nZyu|qeRz50$MT_k|V|F)|0HUzkY zlwI3c{-kt4v}FM<H=sXtQaFVhGFYs138;AG(so!iydv~68*+_*zL}BaI1Ab2r5G{7 z6eUgCb$yQCK1Su_Zxun~!lxRZLqsSR$3oXyp1bImv6U0wHxw#Z6&##*uRqnDCTd(1 z>iOvGSk;LqMPc5pu+)LV527<|vFkffTzQsnNAl0*Iy8p&lWE-UaEAJkoW{1$S0xe{ z6l?Bn>oslf^}$Wqy7Mqk8I$U_IzTvV4U`ZEA5}>mR!&o|a|{1g?lYKcd(G7uB-XRw zzou_5dj%Z0<ZtV45EJv|b-C3wvztkAYwrR-+<N&YxFhxj50vHl`eH{2iD!>B7%pQF z{T+nSddJ_i^!%V9>_+y@1NR^vO+%HESHRTg>j}fZmv1aPdk5e47I5aeL5D@v$h0<# z@KA2a2Go|<H9xn!<yF&kPAaTnbub-BV-1$Xwn<b!lL)CD8<2`R7<L+5)){8iY&2Zw zOap2oc~lcuHp3*tyHv?t^uF?=I{!889k~(FG959fDMaMDMz67^3j**-RU<zEdB>}% z71W{ON6FI-gE+Kv1A3qXM8Petv}MYKPDLpI$bug^Qju+Tu45JwVUuH4PfJ`#8*SES zB@)wMY_94lq1-+Yquu7lFB7PrS!h-BQD#aB2yaVnl;Wg}{v)Ym(Wi5dloM+5mEY0z z{UMY~Ktm8V?PqY6Y@Qgy#kmZXq=$~q^J=uH+?ZCR00mAPjvn0>4{j>oDAb*a8MA-q zB=9*|%qtTqRXtug<0xDjo^~Tm&3>s|S^cF+a;U_ADhE^LX#us9$7jES6*p17pf<<H zYvk+Z<pEVfRYmk^l~lCEq5e`o{*$Td$tP1zcPJuNt1pdDr^Vi>4~P3sE#HV5@%&=> zUg`Qsev46bK8Q1TSuKkFdoUe*iyUq!vFNhiIFy4T&@NAhoVgK-_$Z<48f0%(5wMl` zu=LzHOO@N4LLHTPt248hih({)X5+@xdqtD33%t=o%G1_gq-vgO&207x9XF|Kdzw^# zBVy@#+VR8=LZgg2XWSoe#?bq;k^pE^FJPQWT`D~D)vZ%AU9cwro$*q8sPfB@M5eT^ zQV|n=Gz+J~33zm5*PiYEy75E=JgTrcTd?)&-sFjct0(`g-aBscbFJ~U+0S_kY)<CV z$v)e9uRmML-#VTU+HPAmIpI@NirR($eC@U2x|z}SKJ6HNSUX+Xcv0wTI&?^n*OSZm zMU-SC(){8(-9pF}uAEpClI-O*t4~W~H$cq_vePQ!fAL77P)?-ncb*p>AM@phyHU80 z{#*%t6W78j`O!5}sYj-xppZG1<hZ=QN9^hBny?V552)wCs1~>hfZ{#>-oe6V7mm`q z%JFS9O}_&zdViAWdTeJwyc=mbJbYA>*<pL~XN7bnEQ9<v!IHKf%Zf;Th>T?r*D>+~ zHxs~s+;b}#c{l#^4S^T3dW5Y7ob^5IK)~I$1Cq=rrYbd(lyI{AgI89xqA9`;*uq&E zv@}+Ocb<D=C+}3WIgx?j#e%xn&#waF1-Mg=nB;k!bk=#SI*(D5dY>?(-ZUoYj8KqT zPf{|ECJ3f`M#-Gnn$Ko%RfPAE6z?6r?IL=tnoaUG+$R@+ljy4=cY{OT(S+u6uGfSm zV{V>&?qWRuyL3Z3n0yXa8olInRLqfXy*@0fN7l|X3SYGU;YtRs#<6I$^D2`Vrrijh zH+71D(8rUBQO$*sk#}%+I&JnQF*U^Qp#siJ1#0#s&V>QW7v@+f{ROJ5Tr<ScT4EZ= zj4F%>71WB>wbHNg7YKZ~gS>4BlRdaab&AVa%;ahxlvs((bSa>Da2=}ZZ#87mS6*Ab z6X7!CJ)~emu6Q3Una7EBILoXqxmEaAd(BI}YgkH4v<?6nB!}cAkVo#!?unD;wq?UJ zH|vD%F%-u_9z~VH&`D(wz%dtY#0Y?SOAg{1#&TFq!>3bhZ}Hixy_0$>0=$NQ3vv2T zm>^>zwT1Ko6`)66JnqH$jrs&EdU~Yy-I1=u*Ur1%%c3792+nN|h;$~r<4wPD(xTg` zf?i8@Mws-FeO)#qog2{j(J{OGaJIr+x$7(1@N&mY*@C~yFV<Kg$&vG-f;=8@?RCw# za}>z)SI2|r6+AA1bA0|BG>IVaiAWzCm!|RJHLq67k3+NZ==Irw1O=%d7>9|1n1L|+ zMT_)+NcG=CCo&yLOd+ZDo|Yc|-#QGDeZofcDX(q-+nqf;fwF2H<KL^iFlZ<o#h_++ z4OBMB*$+v#bU`3UmZ0U#UW59)RIaZF>0YMo0wJwCRjv7J+qQaPr-stiBRE0Twc<1# z4>tI8-(r-hz*Y{J3NProKJpNI@+26;|2;NP`fSe3k>eWg#Om{sKGs;8Zh^|_*j`@U zHe$|F>T&*C^jB-RK`e7|9Dk(+DW0^MrRI6osa2Q#shuFQH;^4uN|K(h@s7J=a<12N zxl7NSsVJq>wt6rGD{%HFh%ocBpZq@YmfJAhFx2%)`eyUgtA`&0^k0mnWDQ6UnsFJh zUWJ}j&#AusHaDPe>{-&z9l7PXfuF>`797|5k-=mbKZ~+1HUIX+vWJ~?>&=Khy)@~C zDX&LlB>@iK@v_FZtx8WzJE+y+=b^`k^6#c2^YQ!YZ(;nz7v=o)KzHfzkMFAlwdN-c zP0rn|*i(HV{kq`45dkj4G~&6sBJr!GPnA#o65P&x+n7L-{*F@_Y9#UauIevY9G!Xo zK{cXK>kPU)DqgaM7f8fG0GxJ`MXXlQxyd@&zzUFZXV@JDFdG@i+$MBrfBBmG^J`ed z+2O@ifeQ_b2dFB5QzpO>-+Ek8J2-KoFsAPXqtcS<huHrpbUPu^zcTdqX{M+E2=JdK z{uudTnIQ-kxVSc?BzWiIXM$YPm_Z+EcF#nsnTMhYY{}h}Gex%k3Y=i(D%H3C{Z{9a z01TN2P{0(dfDY8OhAs;mg90;@i}j-yomSocZI{=7_gd^x9x#JR!xz%&huU~+9Ftse zT<9@Lb^o)$!SAE=%%*v@<Ds@pNq7J!5LB@bI;Ky$&lkJ%{r17%v#=eN?`Y*El+PkU zCE)YP`cI{=50DKY85a6Qw-htnYpGmjc>d<J8oIXouaDAxhd)RT1GQ)X4IV{z&2P$c z{ykuYqnpB^zMC8p4c3Pp=Z7`Wh}WnkDsO@MyNWYl|4l9`=FeM@)JK1rKh+#o^->kX z!jUN0%}s6@xV^a}lmhV7ZSuqiEH-R*^iU&f(akLwzS}G@FSI?a`rF1}%}kiYee`-{ zgt$NjvX*erw;9=7Cq=H{q?HMTamvEM643%bH2ekRd8uC?9IUVePn-n=djw0!@Dj4n zn|{t4uaGHJ<*7T;1rEZ7LT6w2OXT<o9<JsH^aKDD1c3i(6lKeY*%qjfHCvRPMsEph zY`gssi_-qF4g!Yf?jtJfx3V|J=j8y3OtZg8jJAZ_X@X)EcVVNGq9tO%@9zPUCfNLv zOJSHU{6nI>(FhqR5>mz|0Osz9vYjsfBiSP{-OW$0^=xRAo*%OuE|=NF3-Wivp#(Uh z{PV(?CEP+Z=Q~QjQN)c8_}C~XBn-O~tTH;s5zOWl7Pe~YR;nzsH|v#x9+jLF0wOi# zO`Al{16+(b)CE5-v!-LAQ4bJb6+Lytts9m8Q;>=ESI%9O!5l|GVWRJaloQ9fAD11e zRtTHv<|`<d75M%c@EdIrQi)$aA`nnhtmCs({zZTWgVTOjjBEa*ODxQH{h=b6ROF** zjq**o76R|{ag7;*$O=l<gZ99Pid;j<3g~D)tvcd1s?}a8<EDu|NO3;;9E?mR$mf(x zR1uCOYsoqbV%!_WaTvb4<+30B`@@wET^4B84>Xf1@Q=Vu7EnDpaiuK!u8PnfunP87 zk9aa@BT@<d(ND6Z?~CKMm}kDql-3`QFQ{ZK$k~ZJ`5xu2CDekyO!y-M>bQ>3(OH(J z!R$CLqeuMk0M?l>eAy^Xsh3^wKO$c76FG|13NpHqZ*+tx>9~o)95)e-0y*7BNywX! zSloag)>X)Kbz9-_D|F91{p&c#wI;K_E)2`<0)SJ~9}YT*LH|RUsnSdZ5xSOCnRB{J zY2Z(iI}$I^Vs_nl!TXXkkBAcs5-c8IJPp4DvUS^1JLs*z7NcZgFG#-4P8+=Hrw~Rn zj|fYIRm{<Q0}HS-SgV?K_{AOb%MtSCRfc<cc&A6KhWwZp7ErO6WBvkY4JxNITX<n! zhK(UVj<xL$wiD1qj{p;vB&M?;$HSUq{|N&C_h*>B@X<=_S*&ffg6s&$L1IFO(;n^U zbPqGW*h!TBTwr^1Q9=x2{a0j97%ShrhC1Xww#bfyw08>{<<eD^FY;A<>;pF0k}n7( z^sY`V%;v8y(YMwt_dIqIEurXwp2?ObY`VxP@eB#NwG*X2Qt=D^0uu|;Cku@p%x^-2 zB}dA!DNXM20oXtJZv7Q9>#m+s0cNiQj1Jaxw?^{O&3M_YH=d7oBTt5-S_;*j6>y)* z<k$qsTWB!=WzwIa-ZN*zzw4dObuwc?da0a$g-ZCWCtnmRE=ZIVK9{2PSlwLj6!!(q z8nn_QCbHB|x9PDT#O?Bws;3}${j0y<8=gHLF-}ia0i7cGEd;u%2{qEw4B#!Fs^g5` z9st~%&TjG}<pN0{y-ESEYkFpu*(bf<g1S+qLt5xy{lE`Yk&nu`K$+NP+?PyE@H2vT zbjv}NKi~2iD!4I3l<3tTprSw4Jkag(WX<=U*e@3A9AO6)3qq3%Rod26Pro|<%<cF6 z$6@w#0>n9-UBM%}44&7I&|VBZxS>D$aSjD8Qg;UU_32@|KO>*e4CdcT@o=9WT!8nK ziBD6d!J<)`zoK6S@YjTE6ir5I|B4~R%PUsB{Szatp&#pH5T{Tf*X9!E8*da$5g#&- zc-@U$E<-M<yPt}WFNg3Hv7@iolM>?-UK5Sy-_8oJN@I!=u8V8(g;i^{UKSt<6fwV= zH6%8+YJi(9mjk^LqGdcl{F&H`&)t^=<PQaqZxZsP_F9r>-Q{s&=#K<_5&1JO!F=py zgdyREN)K{eM>XNcC5|b1AGExd1NP%j#lz6$7M^?an!4J9TpNGhW<iw){)t>Tx@ds9 z-B^$ikq-eryig)s@;5wCBQk%Y(0Sk0?aG=McaOBsM*(yEDem+z+z~ONY%CJ!@w1QX zPmm(IFO|zpQ<*U_^29(9MSpt)4YqWMfH=2><LDd?XxymG5<&9CyngJ0$-7t$F9Z3F zE1q26wY{BxRV7d^ttj|(%WNLU$<UCpkL6=6C`~c)<O-KlxeoRG-^SbgtmsrTz1f+o za><~8o)&dk5E|7jAJBpf0132fa11(k?NNl6=dRBF>K3yZLj=4Lj?uZ=rWsU-MpDsg z?h<3y@E53pEcg7E?%x%Odg2Qb!U^)t&jr*x<kx?p()86x->AnIi5j58gQn<Hyzm@G zKDt{@pn~tf%R#!m;zWQyCf!v&r%1aSE&G)k)V?4(7nzg$KJMNRouB~G(fqt6%^QQ) z<0I%uyB|uT3-C;T2~^;bo{=n(fUu3T`nzXE=3a-xt>wuJ&PsiPAAX;wA^{WXWhJnX zFilP<Kv>dHzD*x{BhJmX1?$5jEo@jGR*Yc!qsi2NrP~z*qr1=K^~~yIQ;>I07*#zM zJr&eZ751kp%BcELljQyRJ8^%i4<2m-s)94fnrtse&2Ol#y_)MCR_6&!%l1QIwVCJ7 z<STdU81eTXcNoa=qKD?h)(NuH@eiIGVZ9q=O<HT;7@-Rrkb*QGVX)kYf9<=DFbj0V z8mH62%;>o_$#C!a^~sj7ba|zydD$iE>YwRoC$!*OC~mqVtRIvuA{C=L&%1#V6j<P6 z=DG-pOI#0X(lkI8;N7Rn{R#gy&*$>tmic6-qD2@Fos3Vt^cVM?7jOe*8mqL#{ik4G z;RehJoA+Yvj062Iw%&Z4_u_3^p|SkSa@i@%(6@6aOmzD_DcNUuv`$CIV=3Nx?@;(c zY^!mnMWp(D(53$WI%Bk(PPRplK6$F-6tv*qHhZy424nP{B1@a+^6Qn{E9v^{4Sh3@ zjAa)!Ej;7j=X!>cw46414yqE|@4oX|B5$4(U_U|c_eeQD*#xORmFP8{*>53A%D<F7 zC<SpQeeHFU{xeLFr1&FS0J$w&!Jv0^m(GD-BdDTy*;qDz(7S<4Ge3Ev6_4)^X88Od zo=1##cV9_<zRNE$eB*if{+!(^RZ0Iv-OQ88vcZu37w!8`9O#_2s>Cz(FQ5Coy;aU5 zNaMd%&VJeX>dGtbA%()(<PoPe?hRtss>$mUJR^<W$9MN%A3v`<%s<NQ+YDoa^g%#V zPc`q;vE$D{X)|L=GPj@#=sy?7wP&v+4MGt3t)}u9x~7x7UplzUCR~IjEll4;oDn~i zgSi5LGWFHC*PD<_XB`0d&Ca)RGH1=|VHf_sBf)Z~*kC`IsqC9cYD-gvzDZ^N?<a2l zeP3=mefQGzy{FT4GE)*%N!Ips`_m6ked~JmKJ;Ijna~k_{&!}~boR}q+4oOpXaCO5 zn|}O!>Er6tkKg`&{9*cO_tK}|Pe1+r`w3(=$B{C}-8IMmZ%(L7Q`%@=qHA8}-#prE zK`CWHwQE81--5Q;qF&0PVb`MRzeR%Cl10jrb=Q*pza=NL&nHqodv<;H{rB15Z25G` za!A*5*uUi{voCQeUlO~%T>AHgYPOP^vXarYlKpQb*KD;gW%YX3>dk+v<z`>+rhL8E z^;N{8p#_Zs{*UKV7vKf%LUa$SzXt#aCQWWA>!!m*)O>~-%6rq{3O1$W#)|$cNTEEH z{Qs}#(|pQ*d04?X^y|#?N7b)y<LNvyHq9yo0RXO{F@MP4(4v6?51OL@7as}(y!t~e zFD(H}ASxliI=&8i8DKk#fB_Cb7?}-FzyO3t7CHN}wf@sH3WQhIM7R&nd4?m$`C>!Q z2YMQpT80T`>(DAL2-)ktpgH;w%Eeu|&q>ce7W4pIY(lfisD|8$E=xvf&3|Z%S^N0v zN$dBIHdc-fGwqOITJC4bbuW?F0EVx2GA7jIu5;>}+u|l#@UR%Zj~o{c0KpQY&x>W6 ziuPsut^fVnTzq-^xLgVt0^nnV9U_kb8?&b^CoV6@RL*+-E1$eYJzW?#=eckRb2Aod zrZP{Tl{th<-o5!UpN>jXSzszUS5lmTWdpC2G^YVaE-hija)!Et0m~Da!oa7aBCjDm zbk(qdS-kdK|C248_&`(AUtP*~v{e1<xOWNoSil+b_*9OB&=-l|$Ns9z#X&_O%hx#{ zSK}d(=t%&Guz|k2ah|77xim&L^2<%07jLR=a!ne3xvj0*aHjZ3#l4k^Ed8%45ylso z@O(ib8<vl>Y=Z(ZuL7YAJocPkwS^)7tlX=qI<y7VwtW5ipkd%ZZLPNX?YXtOw&g?5 zXXnqaYxQhS_4S56vGa!so$`bAreXcH^+%(Y>ff3t-Ohh|Jay*5x0aa;Yu{Su($qKF zmWs}Aw69b>*yvbqS=)HBIiUW%bLZ`$=W}oQ!S}BHpKITr0bClJY^ZqXW;g6e?Pd?3 z!TM$|+)Cp|AHqHKM?dmx?T-QJ`1K!ysC133A;oK<ThCRh|Ht#$y1w-iGpMmWjC~in z{R;P`c6-F+*ZTHrJeTIqsLWL&>#&MZ&gmKMc=+mg+ylfp=IX9_TNYzy>L@~DJC5=L zCiYz8Zr8$o`Y`}Zn&^2K!l(qaU3*l-CEodpa(!vtua7A=4;q{CHV-sMMf3r@)yL!` z4{>%MG%C~a_E|!0qTwvlQDyK`G#q&ofWKKNOV1HTp3Bm9{0!90r>$~?1i(=xm70In z<xL?u_!Yj%RFmmV69;{WHPMI^2=Pl5PO5Z!iLd2df+9>uwVqnd6_ZAFeECcnr0`k+ z_Tr(hGHs1RRGU)>7zXh0Ec@^ONKa-2@TMHQ0?l7z3$)^i^J_nFgc2#{2f#0F_i#TC z7?MR4IWpvY%2hcDJu0{#X46p>!oXgd!H70X1I`~py+b>cHF4habU4qEXz@jW2vJL5 zU9$B+0hy7hkQXQzc%CfQJeSVnP%jN^4&V=P<83#&7g6)1A(2}b;9L9*>M?e?$Z#1% zTGn5ecOQh{6Xulbs27K-R%k)x`)(SJB{=cU5Pz~wCY};SmhuV2sduSWPy(lG$Zh<6 zO1hEH>njxsTz@&`v%~i_GR|KF6G|vORO}WCj)e(CMUo&37<ACef)?<*(OsoixmCRa z-vBbdolO-u&^@W}*{u`ZASC}Df)~`{1|;zFTvlv<cr%cSVS&(%b3ubAK`@{UBnUVT z9P!=ar+Gx2y>*xzEG-|iuFXy?oRE}J%!RiJ^>M>YV2Cpmyb5X_hE*X+?5zx<c^(Cp zJRoTnaZwa_7DZ!m73h!m4&cKQ=HcfeZ%pP5SWdhdMV-Wu6;C@dJb&VIz@9WNP$UD3 zs^m$>SYm#AHl9|Fk-QC6T?nA%Bm<4t4MjLjLF`vlzHV-kBayf==LA3-P)5aQg3TP5 z=1SnfwGl;G__PZ=48b@yL{_aa>vZH~z#evpCoqo>V9?Jh=)sVjjsUe%xSS*Oh1ADU z?xQ<!z)%||0N@!Kr6RxymENPgv|+5@!aaEfIe9OzAkFp8Su1I#vezGdi(6XBXK*AJ zo^%#i3(6BxL&J~Qz_EVtdg=3n_>%d_YmrN5sZV{}_=Tr*rwOQPB{DxyM)#11R}g|9 z;5B$C*n{D6RIAJoS|A`pJ-J(;y*IR{gxh2-V^R7GGRRh#hjJm3boN*67aO?%&WYz6 zd<Az`6gUDHsX<5ili@??=>J&8F!x~g6S?uOB)Dh`4N<Q<<a5-EQ&j`aAL6kVE+}*| zZNCED%kIMf4P)Dq#eSaI%kB_k{yQL)tnl?<Fn68{kO1fQY&+Ztl>BHDTrM0h15+Di zL+$(m1d`jnA<X$G#sx%F(cU8UY;wbAClXSPzYf39&F^%$lnF2u0a(<8ZZWkT*aXMi z_4BxIlFOGc*BgG;m}Tro6D*p8i1X!vftrQ>1DPQT$!<~S*Gs9b$RQrR|M;U2l?TNa zU~^JB+He(^1lpmEh%`y?{s#u=?sHHM5d7q!Ru_G$tygTuiO06n163Ssaru?qYI0#C z>TyE<mX8(8eh&<^@(!L5%+ojS8&Axc9locaHvju=_v`f0o=UDBE}e)(l)Os6xXq6% z&eBPvK(NK#^t$?I%I1<kV7oPF;*x;TJPfu^6*qykYVs^y`+Kt&P2pdp&3K`FFK_^o ze^)>dipWi+mX0s|1X}H#_HQ0m27KH=RNL>kn->F<MTFUeN_+0Z7~EO3hs$5RuM_+u zPE{qC+lCS~3m?2zgI+M|l<2#`*B<J0&Fh18Yre2{7es9X#X+y7ptKJ-*}hKQVW~S6 zY@w@$t<%}Lou0|){$^F+51fgIF<_Ub!bCCTGgRpkVetPV?9Tt8{Nw-8UuK^%xa>P4 zOJr&6V~H7KODb#D%DyH09vWtbv1N!tl08Hbic*bz50SJeTZQP2R9ZC0=X*QL_ncqO zKVW_^%j<f+o{#&Z6Urs9bRh-S@sTsWW9&A!YW$3YT%5tOiIy$ecx&;#L)s&G>?x)y z?l0~Mf`v~b#WXxV=Jo>t=svQwN?}kX4h_FODY%0<T|J94GhQE34G&0JS(t*pP9-Jt zF8f;UZ!+(ld1qgl@w`**GfLf6{u3u<t)UCIzpq0A?`5_k#rfB+bgegOUkRsGi$I4P zq~8;<6T)(w&s6X;$QMyGMWbyrj}DNqz4uc5);Yhh8#v7USh^t@#{v?SCT(J-pY8Q$ z#Pny`c4sbMx_mB9*pjUY09+{n^D;cA_lX@gdqT2_oHZ2VzZ^J-+2f_Ree9?IJ~&>9 zELff&*ABX8lgwqC2n$E9z!MP_ak)Rd3O%ql+Aj0WsVyydXL6jcUO?L(<{~4o9tB>l z2*58E+=@jiZv~*^czFpaDn+WpFS$n?LG?K#faiitojP<I{AK|@zJ>&V6o@AUY_YvQ zn`&;U=HU}k!-5~J4froTPA#2xv^f<ZhFZkY-`wZCr2x7)`$E(&>#@MwlV&g(8owv~ zkSEo-Bkh4*;s5|VM9?{H6Al9Bt%yjHXF_mC`n~(uvqP6S2_ZW_z5ImJ;whM3Vp0-s z%H||@AbTL4xq9TLb|5M?4qg!#yWj=w=Db>C+lvI&AM#hqfcq3KZIO(+J;i0G(|`x& z&d??ItxFk5y80Q%uMPrJ%?D2q+_QjZT4CnhO6-AHIq@?|F&f+yPD9HC%g2J^f|&;4 z=&D^zNiUWL&u*y14rzm{<#0qE_b8Japm6>87E?EQiL1p6#)}Bt!a7*;_W7rYdTRC9 zpt`9!%{>_q&#;9e?gJ6<z{`8g;$Dy8dKCuR3;IO_fU7w8yf!FO4X@q`+ad5j&=tDP z$n`bhUctvh)GbHDkkMP%fpYFe0`>qu{EY&B;e%n$;5i&7-Ubs<myYB(4`qjwAlp|2 zZSw@wPlv9=Q|Ws3Q)mlXniyJM!i76J9bDf^Tb<19WpQpY&-MCgE#QoyBy8*gl_#9D zVKN)GjSaL(G%5y<9tQ6<a}PT6IvsXakq2)Qk^ib)j_WB%bb|l((r)%=e54fk#&F%- z;&#;orvSjNnTgIr-ll*u=Ja2}#U66Sy@#W(=z?ZNywmdN8(}#RQe<p~f=?ZHc~L%F z@d{+yz0aJd7~~OJg>etWdFq6mM*%b^P>Yg&DjMEP%=32vpEP4zh<T8y0zs0H{-@Lb zV8HA*u8$%mwi@AZPo%(1E_*2FNIe%N(C-z%1)77e3&AUFzZ;w>>4C3#pRh<5^>}X; zl$x%c{4~iGkG|=b505Q0P+W8PX9+HBl@^%u+#_NmUWGu!VCKHya(zrJm<m%5eB$Bs zO0%>_w3N@aLLi7w-y9s)1mA^)?glEHz+I{Rl{P>rfyi)`&^f<@R84ap0PpJcAQzE> zN%srM|IQgn!H_1C0H#}S2FR}ul8%5RvErU$zLBsz=^%xTt=!XrH(}je|KY%20Hx3z zyMyN{Td0JD!@1M4S2DoTa>g%zFs_cjOb=vx6rRXbu(7Jf*cKHEam_VjoVHw)1Hn&z zU?KpYScsftls!}8C76RZSzHlsYW*T^Dzf#!)<7`kc;L*Ib?=r7G9wDravSjAfp}sG zfwkp~tG?@?MMCwVsYFJVi&R6MFNA3qSUI2<?Sn@`j)2!EF&A%x&xE1@ysyb#m8}S0 zK6rN66giIL5gKan=HpqT<lC+}bTMzMze4YCRbDNR$;V+nrepu?)q%DR{$e!#bq8VB zySMgk_%|O=SI`Y#u&C8gU#Na0Na6E>1K?8mUM#Xb=s;QLhQ%Q-jbM5~@6~b)W2g%3 zz6#?_nGm^)tw07XoUQ;6gDmHpo#0!&d-gB%a`eGwf9^%yCLoLnBMDWbf$KJLkS|e) zZ3?heFWhp;|Ft22Cj#tAbTB|TAc|F^qyN>ncxj*~w6WcS@y?H~LR#)&x-mbR;g=ek zF&r_xyme4dXzUqqytNb&&V2{dmf6GosX3TASOZYtVna>9WO8l;4<w6GH3E*>pa&3q z4ooqq=R?#sBDA>WT$cP=7`OeAlvk{bI~2FTFTMaP&QkZ_Z))X<an`!>-m(WbAAz-V z?MccC6Md;c&fum67|FcD!y6~G4b_>{f^1vCS`gkgoyD5qi{j4ve}vo2c;uA9F+A5t zr;aP@5!nWbMzJAw2D~2SLiH7opxuZHJmOM$JJgf<p}DNp;K?Q4jt6h^Ar;tF0E4u} zy!qT@!+s0?;4c-}hDG7*b(GPIvgpC`EMTE)M*P`B64t)39=Z*`@!M<vdnd0g_Y=)7 zUJl#;PQclbh$2nI1>hM>=E=@mR$_~FfHJ7C-ucH8Juu0+^*!zAHo~V0ncs}uU3eN; zLMr;gQg9bgOW+z}-scDm`CtIX_G6wAAA!8w@3(6BDlCxQi1FASqj$oCVPH-%cXoOQ z+%qKoQyl&eI6iYNf=Gp=Sf5mfp5%q<)d+!t_K<Ky?J{C9FxOaOz-$o<-M$8C;X&A9 zG~B_*v0$DX7|lc^0sUo>Hg{x@cpHd*BB-N0kZdjR4eWz=9}uA2<|-gt{*fTNf@|5v zbW;;`RT<Ri7l|OkPk_T3-v>*A1qK(eK3HBQVLvY6%*9LKT)7KB90?%}TCqgV$s(dx z!LcpOTbrI6iK7}*=v!DIhQb5e<}}SNff{(c$V`T8qn>C6H6((8MEG$Wlum}96&U8^ zz0;96uCqve2mn8s_v$>t3RswD${;I2uZK7Y=S4)6!{p0h3D<@p6-G9)U|wUxT;hZV zFLJe<yV7O|2*Y&${htNaMpn}2nBt=b;EuD$nu5WM3el+?7Eu6eb4)*hV?n0`>YFj& zS=_^!6Sy3{oHcY;)=-e}SPiA5j)*RCO}ph>X7t&%ggEZW-hyhh!-~6LAyqJ|a--v0 z2!~0#%jMh;hFCI5GqN1+9X8KO6JFF%ZXFYA4EUAd$E<*ELmfzP%`H7%RcN!sgtO{N zNXww**;#&G^ld?|ZanYF{T#C_kmqOBM{AGxtnfVSXh@Zju9@Jet(V|S&JF<BXYv#W z&ZdonQ@9~a3bxXNbLm07>e<R1vCNBD-l#3aXcyWE2MwfH>pu}ad$HANK_}iE)7_Wx z-xjxd(p=*)A6UyMI)!tO$@u_ec6sphmUBW*f*ix##hrc6>p=f<v_m=i?abhf3fKu8 z!iNCH?IO-6g*+|iZeTr`efK7<siZHgsFL{LIlFllnTNT%!2R$T_A4IyfMFok)$kbq zTnVO2qd!DC9_+~@*Ef8KVc-o@&hD)Fe-}ZLA=kx8ur2I8bd$T2TF<ZYz~M2tWd<*4 zMGtHW`VcxtC9I3^VG<);GJifasSe#T<hjW|1hBBFUE>hj_a$#y9>;-&H^IwcqTJg^ zhl=Oxjf|i0KupUUDXAA9V;=)}9$<0;IyG@2jHj(UzjUPD`@p<b1|^1<c}PZ7N03^M zuIdmS`ciZ-Z{u35TsRA+Ni=m)xYN(v5mN!Z48WAFrA<LW|E)=AI9&aufY#o@`D!@+ z`5CShWbpb&si&i@0B3hI=3UlX7@OqZ{V@R<Zm_S)yOk6U*?ws|g)IEnC-?-^!mg%2 znau~WLAVtN?_7JsTWAZ0$A45%{fvK@{h5n|l2+u995O)-45J{hBWsVifeIV2HEbQW zy#kwB#HiDGwvn3SnPW)c{66yPTO>8iX2#zOHMR2i>&I3m2DY7f{F3X=8?btE0ag(j zqz6`RBjVJY3zIiD{(;}hH@AroGL*rgFs{!wb6q2#b24bLi#V_<s1(8_A~oVYh?@V( zzKN;8{dYv&Zcz`>_7CG^gwj}e<dn80avr?-n2-N7#<n7D1c$Ba_)oMOIZ(E(_#dyc z+BSrQa_~Uj!y#kYS3f%&olUawxKXyFpIh^R^-w79BV@b2G9}*o<QIJ7H_;D>Zm<I$ z&eexcHZta|wK)K<KZ@0%qe^wX@i4vI-B(hW=fDb7y#^`zo!65Rv*F-$4zvx2UtVZF zcX>Q6y_Ywyl~d-UkS(^K06xWIBDOF?PepAwcEcyWKDh#_Sz$jM=Ns|?BeoFm8Dz-0 zy;s4OR?583o41iE|0(1pry${Lr+#&)1o_<qeZ~++<H6~z>kUSH9y1H-3NEm2SRwvb z<%fq+PRVyHSI(<}*16zY)-TEJr5eLcS{mAw0t3RzA0B;Xwz3P`{_^Z8_(<^wB%Eu? zL#t1XkHx+S26+78!u%V*S67Y((ucort1pzC2H(H_En@qRKgD;<_@BbqCf`&qGUeyp z58$Hq!Ne2*#8Uom=aWm)h$dpYWSS|cdhY+@e9E6JGcC6JXkt*QDCOqT;-r!i=k>m? z*#7gWvSUgAU}6rdHkD>{^Kbdb7ggxN4AEl&jeI?dHcjXHOB}zPxqJ3WGW=~j2-ITj z1?7ZPmB*>c4VabQ!yE38{>S;e;q>48$CKt9aU;x}?)d0_2brNkJISXxlE!HgE;~LW z?p3@u5DQ#D5qRs|@`wmA&lu=o6}q{651MT{`z&qTsgxL0$zEb%;kNJH^<W%bIg;*s zVN3lv(zglXto9Z-weajJR;63o315t`G1H3pI{)M{Qu^PWTa4BX5m?iAW`O*&{%7gZ z=l>=C7J+gaD&yz6wW-^uFIklDKH?)IfZv26KDl-8<^!>W7N&g~fvvepD<{`o4Or;B zlZi5hshjdzbgfGs#r8~=Yk$f}zYz=+g%R%|WLnI{v+Nb5Q<i?!mWp5Q3o@pScqx>H zv?(#9?%f3roKI<c^W#7P$8w3{tv<fG;30lRv)UN|SL6rgt1DaYIorrA-1licSw7Nf z-lW0Np&}IufQL`({&WbG!g6x9mWKk2!!nWgm#W#gfue(pXa%7*7^P#cy3OwDQ;r&( z5BK_tq%{1+w4JSS3EXBM#`m!#a>I(tU?D;=pvBg|=6j_hSH2z2W=Y+m)Ae${r6qNa zpzty-asC8n3WX`)?0@TIz{?8@wkHNtiJaO5SJ*n@&An9K2RNOgaP-6w6EJDfcm4ig z-nB`vPDs9Yt(_1B%ni&x`f*9VEbLMHiEMhMM-Tb9>NXc8`nzw@Y$#JQWHPN=AE9u0 z6GJ_l!gubBCw0a#)+_JAilY(`OkzkZFEo9c&TC)qD-P;u`2uDV{jzhTe-Y(#4IsyN zeJf<gHp&fTLvG_j#v~sdZnrU9ExIt<nZ@>|zNp5u_X~V$$}}uN+#nScZiken{vK9% z+Z_2jOCv|z?!jyN@_ksLUbVA9=&yrm1mL$m^~Y(Fp)ULIrJo||0{y|cM(zRE45*+6 zzEdr1G^+|O{A_}Gr8LChO4Idod<}yeqmD~VQO!4X**seLdlgf(rGJFaGlx{`cBW&~ zRf`jM3Cq$cPdRQrCdWG|2`K(JVRmasWoil2_tKi7PU9?r#&4dVHY-<OkxjmI)%oby z=^-Hn2%zV2%rZ+cz~AA;jL;SL#6O37Yi^}J&)Z8jx``?v9+As+`{-*2IHwXT%Lzco zJ(=)d{gOiq#+Y^ABLFL%_}m7J5SU;aSln5#m<1@8Bz$xehRfVx3Q$=81nz5<B;f9h zq^+sZbW5|w--R<Hqo7^{n4PelI;RVeDL#ELhH+05zRBT%h#=$;0{~^jAvu45DRG3- z(cjcpc`%%Y11mDw<6-J2#)oqhV0OeOLsmGat&;)~04!B|E6I{b7MLRHb^th@yv##@ zxxcx|KbpdmNq3o_K0L2z9B2n0OGoa24Ew}!Z@6dHA#G89ISz_2L{H|SVaIXad8n{{ z1Dy^`8bb%@Jja<F-h5{S<+^-NCYg#%z$*LkjTShnoG<=_T@Ll{GWH%z7;vc7@ziIW z*kKNe2DNZsoW#;0>~ME!zc4rfOFN?ex5!;&x%H^dbg5#?Ky7(9H<0*W>7fL35~khU z_mqP6LX_ukZ2lAK&B~<zV5=65ypv+8<2?TiQ7kcUbn^2Bo|G;zQ#;Li#kQPs;U<Po zel1hlOTcJD3njUdcW+Q-OkqylQj%+_=ffm7e?tdUVOB8hh={kaRDV4=K*);fpm`g# zlRYjed;Q_OwK|HPB^1Lkc1x#_3Rt>ItydTWHWxEa!B1PrkeLJM734J(^?uL7P<mGl z_bnJ}mi5b_aj8x6;|vy<o0~oPDcAsA?`3*7lJ1Kyyi52vpcj*ej0aAMZceVBN3RXg znzataGfdb601N%>$b<SQ03fI+TMuf}QZi*N&wcN7=`WLQsqSC=F19pRC}yga?V=n6 zebnYF;v;4xRui1kp=OO!Jak3y4zb!MT`z#d>1Z>1GMaNT0$YVC5v;PgKH5LSN<p0< z_CjQi@Lqo3t#x~`Ckp+jK1ad6%kQ1oRqLzJJHyXqT>HdLu6ee8%iocp+zCDV(S-gX z*y+&P<F`sZB_Cq12^T}A2DVY|q)ulO?5VBL3*r&T0h>c19w(_>!YbBhLgp@?6=d9Z zzQdY3GU@H+;Y2&uWfn~f*PRxz&~5Bo`lA;Dj`3N>iT0ePjWy#EhoqF%EWL5ppwIq1 zK9bkYe$@xV`1A=?$ar&mV&$PNZViOM!mQ=#&*K$Z;-0DUf(l|<Th60??ns^d#80z{ zRlRYfUa4QW=~STN3Ey@|H8+D+E}1H}WTSYaANgYJsmtUY+pTl!pe4bYr$#Vd0LbUi zIN`v--!3?$@tk9x{NL9hiDMUUf7|)kR15M0W9nu_;6r$!i6^r9zkjCV1{c6bIL$I` zpL~|sJa2U$f5naEHcI-)r{57b+ZMCugEt<d8gYNkEY)YTuSdV8@jT2PQeDIV)<wmy zZ`(I-fqdNVmme$7TU+v3r+}v#8{WkR3Q9GkZl-TJV+s^+hkgzE%Hqi8>3Qq%G-5QA z{Yb9+^(93{D+kBRq3j=rV(~qx5AL|9x_uRfzaDc}{#PhhE-q8!5_?)ZM0h|;PxjR? zSy1h1_%^)cqbKQMD~}h(PS*5MU$}(AS1|p$Y-k{Silz{wxmCtbH%D%Fkoo{D@V8q) z%3`wiyGfNYOTFocT7t|U+br#WhF{FldL|3aIGSdk0Be<c)ac}OJsJnU)CXC!2MVAD z?)w*yQU2RJ5pNUTCn<UwTaNp4BWs~7;Y$?~!oNNEeJ^f4$1JwUKdm);_W5M@I-W7A z%p+(oCxhYkAIH@`v?w<Eg)6vT@LX4#5Ch`^Xw1I#7L#@PV17U&Amu_b=$jG8K8YFF zUxMAUad@qXmFO$j4bh4GwuFR>NS(el=46ljj`@S*AA?%+?7(S!eUHaO#q=5%IcKI3 zf6d|(7GHiAOI4}h4&{v`J;1$7t@Gjx?|{k!3lr!vwy)8Pv@@$^aY{$ooEZB!{f&g2 z%HKv*#?fE=C`TMh^>?Z#o>kjTPbjCl9^8=`vZR#{8rC^1F69^!=ms|Qqk9m?=4V1( z#!k%Cd)sQ4GmUxLx=T}`EKWn-f^1(V=PONy-O$sc0N@Bv4E9nt-lht483RSn&W=zG ziSW+2E^*j3+2)>G%oI^PC^l!3!s19#<N%yGmf}*B0Du?I5C$1+VO)>cP|x*l=$IxW za5_uZ8wnm#J#S-N4W-CYAT%6l2$gC;pdSr`%UYwH<{;(*jH7c9)e@@RT&f{cX(_AM zh2v(_oY2q^e?+8a_*PmaFC+GCFP%k`wtO_gO3}hI5Gp2eQ6|E2J$idj@eNRi4rSb! zsYeCU-$r)0C?}GMgvw~-Mw+E48Vp&c6&j#q<xCC>pqxO)y+G4NJ2;Pe54xlv>5G}i z8WvcUdy3PI80Ej8hX_QqKU?pug#uB^X{mU)`l?|Kf6?vUEXU?*JcJTZY96#Zc&KsU z=#bQZzab;ujiIn>rxl6E`m$_1Yk%u^74xGezR}tL_^H{jt`dF`!UFj`9&T5c7LCm; zyg*eN;z`M7QHf;Qo{`WB)xeT^Mh5k&m*!<}c_L%z39IoS_Q1SqWQd2xziZDHK;;;s zd`wuj0OE9a=6Op*3KKrNsOK0)H-%A5u|vr)%C&<2WUX#0BkTO=u+{OjlawRDxZy`E z$mt;@_wc>mX%c{XEP@-6?8<Uq==`nBFm>olrO;8kY9~r?N?V6#P7K{|6S#gH(Y{bW zv_-$9gc>eTHTv7pe1b~%Ms*vY8agxUvRQ5*1pfv}jq71;j3zhsS<(8>gPNfZ)>fi5 z9;H~)mbiZDUFU#7DiNygK|e*{VW&7hG-h^QfdL-QkDBo&DvGGj$4!H1@E|RQl5@8e z&9Io3)t5ca)p`=rI=1}xIW0`b|3qq!CgJhHu|XZR=74g#nu^q77?#rvP|*EL?ML1{ zKgJ8!vm804(e^i(5gEtpQDm8^g*rlj=JFe^jdq`XtbK1G-E9(SmThjjYawGuSH)2e z{^9#KsD^mWcN{jhw&^w$oe|dfT8SmZk+B;{(+xO~c6FGMk75gqQt(LoHjLvO(s79H zt~gGm(2r8+@{Q))lD0|p=^WNCa`5Rn7(F3*8xK4jwpI&EvY<LYJo|-^;@p343;Dx+ zqN&eVcI==T&7N+P&0dT=<~<~54WaltH>5g`DkSAf6HgfQGcI#bNR#8K&bELD+}E~d z*@vDQHc2hFJNkV((o(Bw3rY7dRTo4h^J)IJ2IpXuvvJesD+$NAcy;j5yKWD+W;jP0 z?}aMfi}rp5Y0n5G@TlXujH^%36}v*jV4;%+cjl0*hA8zKb7ujDfo0#90}3qhhNh^b z^`DwlP|^m@>kYzf8MXmUjL?O&v&T+RiB$C|>S16e73?|+7i`=cr7=!Xx}FC4pm@zt zhO2k{+Gh{{8tPf@b!I{hXtSYpX@00qNRuOVVPZ5`-(wF-HDld2z&BdLX9^qu3jMmo z8TGdn>~+2J_={Jal~I@GXIl;Qv&~RpB6^TQM5;49VD&h_OuJR32ivH1RLOy8Wm*a{ z+(DEx%0314B4`Y%WNDIo#Mq1%wMk>>7V0FyUA`{dj(;<k0h_BfV+7&gDFKct1jE!0 zm|fdTs(hD=AWHks#I0tRgE!~RV@{V%8hj>=+aMHypwcW=)G6n*Q*>99=zw4S+e`pi z44<$ngm|th)l{A6F_@!jA9x3t%ZevUK8~hZA|692=kX@~FiM;W$|bKb<PxKE{OvD- zz^J@9ZEpPeroj|fC;Gm2!f&c6T<_jT49=HfPi#1EDF=l0ch1xOJMQ!aRG#?lz<#mM z%(0@T=rek~Z5Omr6Dp2DAnFJd*w1>Bs)&>>9%?4DmL+JtckIjNTn2p^e3&=q_8jzO z-=vqjt?YAizB@xDyq_{V|HF|H;Zai+sb6(~!sF;M#CMfUx>@7=`3~gdt}NavN6G%K zm+X;Z5Os<%_;d40$XpI?0Tu|(L)ypa7m$+UZ%NGvE(69LyJs7|VwH30U$q$o0$tK7 z&8Kdz(3Ebv2+cW$a?xjeh+aU7riWS{Afga!k4OAZ7OCYPs)Eo{&U2|uWF`M80uJus zjFkVHf%~5RZ$ACs$MpSaiJ^<ba0PTJc4>L_nou$$L&B?0H9bb|6+2CFnY8e>oH5e^ z2a@K}-4rWm<#7MDiQ&wQ=(*veF<fEJkLdyDU#KEKIikE2sd|<JbPvZs5t@2RCLe;5 z6jnxO&ZiFH&L2UEBhW{GEYG3R6I+mOmI5E{JFalO{d1FXTN0D3c#=PjQDXu%oP(d- z_c=^5O7XaLa^Wb3+u+Pscl(dMG6Sc3M>CbvP)Qwd7h<~e7X2L4-tFs(+Yj!@I%G79 z?(C5-PCt)Kc4f8F6zkxuO}~cm%ujlvv^k-IHKZNLwO!+PB2UDff(W%kjlzz1Mp!Z( zpDjx+X=pG`Dtc45;2!TWlEVj6_p~^v!s^%8NLwC@U5o5q=v=ftel$l}Ph=Ic*_-zm zo!o)+;hwBY@k$HfFWI(!j$M+~@u#6kN0aU^?_)%(rZ=_Mq|t4LLjpk9d-1Pz396Hl zOZm<eD!w_z2tL!Pf{A6NpXyqRkwHezrOgwI6V9DCF0-3*e4RR{`2A1HG=ON@M<;`8 zx1WpOP+!HJvpsW4ju!#YuBJ4sQgi8<Cy)EKCSNlQ3kr()Ky{`^yvM|s2X=)N1q~t1 zGe5V*FnT%90*v>S3(`GOqJhqWJ`01Vp9h)id`cCeJ-xOuz5~yCv}o7v`d#zj)900B zL!&cpmaa<0)_tb^+sIQ-2f_z&YU#dl@GJfP>@+5#UyU*N997Vnj(wDVsRQm@wmJPP zEjj>sagR#E!yi3=8(J><=&OJ4RlD=$AuMM`Qy(g^?rh2y679$sI`@@TpH8nud(3f> z@4k&@rjhX<bA3K!RA)HKz$G`J_7A*rDa$^JA#~!}<5T}#KQ1P{mZwwZly?#(1fT0M zKpJ0UNP(y%CVlh)Dk)6LrNhgu19{ft1@x6v=m9P|?Q!8_{l@z<3+EUl5%?W*M+PhX zl@UYqC~{nOTM{WW-umAQBh<JTr<e>qcN3~o>IxLmQZ1))M2M1~w-tqpV;a-tr0G@4 z5q4X!l+~{a{-|i1bkWm{gLzwZ;SO6<Sn#2af2I!OBrnQXgjQdZ=hQ4(G8B;sL~6Z? zY}P|say!+2xj?w}re51u4M|a3K$-V+h0c9G78`Y9EiHzbR)2P8T!`VddJ5<eHYG4* zFTYwCW84hcwKyDYwI(g5e(p?6By|;PM^sSJVtjpoirQMWd-&aI*!R2<L(YPcax9hp z<eQst%oAQDISU3TA_C&*@*lq2f}5V{G4Hpn0p_A95oK=UD?z{?y3M;o3{D{;kLLae ze^`1*aW|D11>oRh+|L+`GJhn+c9r__%un@-*x13?(Ux_@1J{(fokZkbvn|rtA_gG* z2m<D8Q7`}xjp`8A<k@30UI|Zs?X|tWmvvdlPSIN@_d$?iU^epCd8Mu~?qB)RqLk=2 zM+)_?`p5eZ2NNwW7Vhs|yB)6^?wWD;SE;n%^5)xlcVyP9U*!||(?Y*1FY~RgQ=9L& zR{1CBEQV~Y{Hnd4fD<i<1`wypc`sdb{Qf1c{$~QHhb&nQzM?i+%>LbaiwEVeZy)E- z7JKQ}g4U$%`or6Q9zDFIYJZ6F?9Y?Wf1dvQ^9=cyCH%Mh@ZTQYzr7ZJ`<(vv`~Mw? z{X3Zccj)@x;oE;l9{wF2{5$sQ@A&7x&wu`%K<-Zp?@t}xf1$g70C~<h?Z5QjpN-vr zm7di0U#i)a{Wtz7XWfUA%}MN&K@?%jSfCt;)TGQGmWShY-yKfISpnBB0Kh?ssO3M^ z)PJkD|E)j#_hs<k#;bpupZ|UR`R_j@drO$TeVDzY%l>A;-gRPs_h<izW&ccP?_FpA zy3PLmko{+n{r44n|1<j^5(Pkzd@BE&^C{EE;5%&B7_fb4AX`i~;{WA*juaemx*xpu ze>tCl-xQvg>c{SEtbIHDe>$JLiZ80Iu4`Oe-&LBav%78A6!iVbY@_SLh|Try%5%+L zgZblD+$@*2pwR>8^M~rYj)?X&C>U~MzBA$H&gPe&M;CGy@9&G3>f)E!eVM|VA=ZWO z9{BC7<W>1SSN}9tq8s_uI^SI<sQTP4l&ISDd8WasHROqiR=XF%@`m~5Z=J929>v;o zsa}eC7B(~T^5ez7gq@X<^Qj>}#5>j^MsM5S3)$E2jd<%NzH0R6{NvykEmx0*{_9$Q z^z=#W;i(Weos|Bm>3gB<r*7Y$Ke<}uleTqs4^6<Oz>S37C?m4{h{lzI<Z+z`q68Vb zplblX&$!m|uyLx$q?t~YVVq2cd`aArB~$Plk9KnDG6#G|OI9XR`%Rqe6@>5Hm|}I& zGCg(2gY139Of23fWyxlGET1R;P_?h6m7aXzr<|WT#QuY$jk+@gf3A@2nW^U&vQmU5 z>hv>TV9%N6|57Lo_e;A@3>k?(To%9HdH7b+?_Y<@Q!x696?Cx##mbET<$UV@R;<pm z(pRb}bWKpIEe?95bo*w)Z>745%%IZZnkywQilH?LNA5HhCe+?+8qrryUOMP9z1#UF zQ@QEM@1XO9Zj8aky?(I^^Dg&}JYF}6z1TW__M4=EYI`QvrHjoxdDGkvx7+wHv@d4f zkbcmoQ$4Ski8?f-c>c;CwXTb*2BEEs1>S?)zdl_+gufX0bCl&$cuAG~Szx-C*H1AK z#?xQQkMH9(*7@%~hCa=$WEfR(_t4ob;>abwEJF>u*Kf4L&MI=YaSgCdqGTA7F>%&b z$D;BRHJ_6TTQw(+{mh=!-4y603+2X5(S-?=VCBq(Pk(oV6i=MJoA@Hro?9DB4mSl2 zC8n(PR#uKM??O*OSQ<BqgVi25k`I=Z?0FJ3Nd7m;7$K5`3{0S^je2c*rC&3LI0-DE z)jNwhb(f><|L(aWiX)%vk9#clEAD%IyYei@X*bSwEJ3a1UBqW!?Ykc=HH#$zhoEEY zFA7?(=v|+G2mua(ay?j$12R<<@PJU%M}X!G@z5>~id;hBDg1m@Zlm(|mu?exNFOcj zbB^6-?d%KuV;#!U|LmZ7>GQ{8+~j`%z8enM(jq|7NK|$9HaqF;GvnzOxmbOm(DAlg zlDGfTA1MfLQEn`wSHi<&LIJQrnSrKaGXT->P$g2kV^Ni(`ju&FJ6Fiu*yXAnQH*_E z5As@-*vq<f12B$wSz=4-JKjS3_d~JZ=Bh&jA}F1<7VcD$)4VZ?sAIbv6ql7HoIArz z6=s4w2Ck&IxyT4L6@l)gH1T(n<_2?9xzPb+iTC)5y0XLVR|SzyFNe&Jece7L_Nhm( zlTdCHbd4+-lja6Fo<=MO^P>KqRIOW+A#ZR{lB&Ig0E!7ORs)ry!UJ5MMgSeWgxWgZ z1kA4i-L5$9_-3l)W*l9rw455)Mi#FmSJmzv9%X--w~~0dWp1>kKIq=)iMe3Y{d3PY zH_V~er-=gssBomm;+91qN_66j6sF9&r3sI+oQYL8kK-6rCJr1`x$_we3zL=HC?7b; zpu<F99sm?YRGrJ?4ml{nDPOOi>9FJ$o+V2!7<8j&!O8!ID@iYHatr}VHg&-S7h4Ba zR*4^`#%0JX;L?SPk$}EsrND1R`jM~OLWv3YaSH%aXSM|`B2W%|O<XgWpS%*E3cd7W zOyKw{MQ+XGWbyF7@5N?;EbU3KPP<pme@PQma!)yUI_g(CxJFG7Sdsj?gwhMvWzxQS z@{B3>A3a!Y2{fnWo*b@k1|#euL)eu!p&kcGNSmz7?{I)o(VFOJjD2ZkySvxhb4DwB zPaO8B(tqZVd!MGbF9bwrekWLJgpnLmHcW7?^5~lyD8LhC3YL|l^aeNzpVsmKE7lhJ zwcV$5cV)BJn1do1R_dA57qyrA1p@6ARCJ%(T#u~wwDk;6jc@D~D?Khj>N(;#9?>JV zNf^|5)Xf(pWGZ9@1N7BU6e}s(BU5!hQq&2%_G^)%+aCV>ewjHJhrIdKjty#!OmV$^ zKWo>ida9ZDD<`^9RvP{Hs0sv!j(>6WX_0NZ8q6z4FVS8KTacjz%eSGqd&|7%!o)3K zYuc9bk@(n`X2`<5jfo<Qv*$(L0hnfVe8FDf_nR|GcMu~UE>%+Ba2zU>8_O<@GQi1I z3;kff1(q`ec(DQ}wc)@}-s-dJuMe7x>(M}m7w)<|Ln>|$-?~%X1|6<9Y2J1{-q9wx zjo;S#-JJ@dkSxEwTgl=T^nQfC(6r`Z&H*dsiLREFW{a3`B!WD_iQd6Eq6h%&^g(md z1c<NuL;z-{0gA?BAuxmmi1gb`AsMe;bDfn6Z0u7Lsn?STo!^U8$Q*0@ZJpBf<qgH{ zrPiSCo|l0w;qMQITSIG;?NUAlT#+-glZ;<x&Vo%~fZ-YWd1eS{W&2@*b0O|lm<DNR zBrU&2yDQ0&&4`-r`lMduI<`4U22SC*)Tixdf9(Ib{>A-$9Jc%JcNXHQ+07-_K5uc$ z=rLoA34&@}<TM#Fth;4rKy&|z>jTZU%tse#MM^L4NSPQm%J{`}2$$_7wm()cG!x`D z)i)GJ>Lsh@dbCn#T%`kAvx#Y!53)%Wj@jx%Bg`;|U4{DmuX@eJ%n1|U6}i(xuCEu< zqE1sKy-ukbyu_UjozYw=G`T}c>nF$0^wiWCX^S}R!*nCbZKc0%L=p80G}T}w(X8g{ z%g45<r8<%qxhNW?|Gosyu?F|!()1RBqsf~`N|)r^*8B3p!mMTc6Tp1!7q&dgFaR-4 zy!e<c*m_Wx3I)D5-!g3L<_`b+SZN(#2?)if+m#;-Hk~pT4?3i6X3w^BFxT#p64Q9S zk3XZP&mfgzm`?O2@dh;(zt+zSF_wpbxWik$0<u~0Fn8Pr%8kABo*!*{wh?fK0;!99 z5tho12CbG`%4e82Z$c&3oYOWhmtOH7rH(<1%niGEzkE1)<j0IM<NE>QWFv+3kqBy` zYOEB?jR_1XA&yy!iwzC_Q|k8(BO?~c*5zqBVN`R0GIqb~-S1S!_!<2o=%t*J%tAN4 zB1yKo)o;?3hQwjaHL6~P8(<A>sFyHs>9)@3C6r2gz{u@^X1a0`Z?z@l69w$L*yUS= z?=V-WBd?_sTY6FTE*zyPH&S}_ur8cpR=0i6&dYlM!KsFxy_!S4{IECH;W%%Po-gS4 zcDp>1C{qV6Q#_@c9}AzAfg#Jv4FXL}lE@9(B%n>~vEy0cBO|4}u)9e`hNd?YQk<K) zh{sCFEpT(=DCprt`;`FrAqcPt0JwJ~Zm{nFjX2gwo~VJvwJ$x4zOn2vtTjX(YhiS% z&Z8BfpSoQSsad&h%8*vX#NId>z-)EH&Ss*ihI`_|&&}FBUmU&yKcG<o%M?ov7Dyq* z#hW70ruB|}!iQ-6a2ALfo}NFe+6X=Q{ZN&PmnvFT5+zPBbo<l9e!VPNd2X%09^I$c zjEnAql*rMPA9>>+-Fi{u_TEftX1>fY33~K?Rq00|*(Ho_@Vr9DRgE&SOHHrm7MEc? z@S*0j?g1Qp<)+oVH2H{P<u_tQQ)l&FpDk0O5?0=8%{V5EPZP9cO%YZn5?pnIdsXg= zO74<%7Tk=%g-1=x=dnD1$SZdNs^}0=BtYmmKqe^)n(oTQS6tg%OEC;|XAGY)45Pl; ztgaN1oESRz`d|@O<bWcwVOTYDi2s}3hmTVQ#zt0e>P$7AX~UxPgidLlzFP?{<ozd3 zh5|BfCGwT1^Zgypq&D9MnVR=CRFSV7yMb2fTc$wtA#ygG>X9bTsZy1(=Eh-}$}Eub z78-fi%==OTcDM7qez}|45jjQ^zvxo+DK$)Gj;Vxm4Y{%U!hN4KGoJX2*Ph(0NWn#w z-vDPp$urWYpx?u9SW97Ihk;D8h`zMnHQaIv^kE`dmoXk9WF@m^5-4XcXp_QMO`>I- zho3b)3cKCr;6J-~J^BdjZU9+_<(}Cj!gJF>+tQ83{2XOu74ABdev-^@NP6!{UMQq4 zB@MInMrat?k<~Z&zp4519DoP}*d-qh>yz#SaLzC24`6qr$a-U5{8}j**XB-T^qv-5 zO}UcU)V!*=-`nePJm6qY_L_g?T<Re%)1#KqOQ+Z_-yLZNS_P`8zAyczcP$kO2hLq- zfoMEcclG*p)LM>fX0k6?2cL89V^wwE;2K@gnP#4u9N1Ew`{Q7JxQT2m*Q*M`w1Z&c zln)XK?@z9dJnyT&!QDU)CMUSwN)<KLeNR5PZ)O~!?R{4wdDK`JDOH>c$|<7in4UMW zc?EWHC~66i3*-PpD5-#%X*VH1%UAngou25U?OsF{NjX4akE+aQz(idl8t(iEs<oce zLepYYX@^9)Nnz#MFbGiE>-xK)RV`Deyn!UJXn`@M3HJH6zi18lQlI^TMDQhT9eH>~ zxi0MWOO^uXC;8617w+|$wBA?l8o1NN$6oIqzw;!)N(xu}*)yZ<{heoaRz_Ib0attE z-<|Ftt0z*8J?5Ep5X$v7vX;lBo<mR18I{U%YIQ~`$)Tt}rm;fnhICsuC}t`d*3%TH zGO{zQ=MiiYWpd2McVr;A%+Okj(0iS?PaSo(eMDtK2tCx#LHywxh3?Y^$tK}m6AG%u ztEIkqIWLSZmNxe)na+y#QET5U_7(-Vl2l&_p~a8Ph~vp3T(kiQ(O1&^Rqe$q9S4#L z)zJNmF`-vkqT$V~>XpAe3Q;{;rFnL|WW+Y<;4WaETP=l=s&U9Makn>-Pi?u(QVUG2 z|D}|uqxR7bHRdIw-P~K~sP>tUjT(5-LxhEN$NVqn^X{FXvak10ch~>N`TQDmW#b}R za${C4W~f(qIJ1f1Bl!C6f2RhYx%58X+4$8V9@}n3kZ{MSr~z^t{~6u8kO)=C0Jsdv zy1{o}h+Xe6IT~aAy6~7=>W{|Az~0r$ykU%~fG4%Ct0yDm?l&V<g8-$UC4;Xpw0*GK zt)VHOgJS7=^X^G!<(99NhSxOu$ZS*6zlMw34{$YQRw8ZCAJ6}ro>Q@n$dnlB)pLew zJDg$1Y(9S~;$D*C6>pWuW%|o1tZznw6h}5BP=)1Ykg_AB`g&sN)SpWHjEIwPu$2b* zykJw7o6M!%6I_d$KhnkS6@~eLy3a)dOju?!<K`oJ8zyBCmXB)7=f2+B7Ri3QOu&14 zI{0WUkl&uVy{h=O*4l2mWc#iAomv6ATkrAW%VYoStn>oN1+LqAQCku}Th6n{;(IMP zS;Qgwk|USKp)c?(xt(bkNf`i|%`^23p<+a6vlsP|Mg$AwIOs~mUf6jS+*C{BP+Z39 z7C|>pSv4$>4qy_^CaT2s`zq)A^@>bHB>q#$8jBlhsEVUTe%zV<%d~LjAeH*aXPXF1 zAJ>9>8^_lW1!T>$IRpva{H1c5=QU5UNTi}3seo2>)KSx-pl?{1pl7SzD;S=F1j<RU zhI$cQQ^a?6uTLA<n6abx;oI@VUQxk(@q4WnyUIq$D9g6<!|GxtU8%pVOcC-0#ppKj zb(nNy-)mH#tPiZiNXz`FsR5-Ie6le*YkJ71&GN9RW>G51nObkxXZokR=6IjX97!y@ z&03jeti=lyk)+<WnFZG#-IWLSdaRM!7S;7O!rxC2dPs3S8u(#9D^och*t}S~!|6Ub z>o&5@B(YD6M1-6<-R?9BQzyJ}%5As$%f)+D+x2$4>pg9^hwX09wA}~W-6yoqzG^@F zLHpe2_H+MfpYP4b?Y5u$W+Drk!k{{Cw|XR_Cbj#7kBY~*PNWE|q#UudHOVRSp3s)0 zkPx2i-mP;#98T*11d?KKiT~s8`W_oXbr6lXZq31nK=J6r=8OKSuCy*4*DsTY=N`D} zf;yg!{3u%D+7H)I(!mdX*ok&t4`EN~pH6QxweYHukF~Yr)k`{JqBy@lP+gAB)wa1~ zVkkl77MWlM|8yo(6$vR)GgNH>o%q}~-a6{IIX}TC;?ii_F$pSHK~U1^=sZ2B=;7Vu ziMA%|UfJbd!%`MeC6Z#GrN_D=pO|7mxGF~wlTh1J;mMPE3&pN>%er+~e+!D>G2Kt- zAZMv-^c~F*|E@@k&E#zB2ze{>aL;m@BSNVo+dJ|Y2MH(qeE59_SsYpq0YsW_<mRSo ziC04j!tv$?Df(AB@{zmz1ut|GcdlOF@zy?5xU7i=Sp_*#N&b3xWfsv{x9GwSnh5}Z zw}h|9OJC*yKnm0Y%(}0qb66KGL6iYMmQ3r3@Q}HHgX$az>=ypkh5H!GqHy8gIQy&I ziuyXT`Jx~ItURdFjC_6Ow|3-)I}G;!#IkcB7dUtUegHsu0lgd|mUs!hR1`mCs1{#A zq|J<Im!g2Tq)ZV_?ykD6ik^$F2|)t&E!D$mF?FgE2hCdbv~iS%;cB>mN$%^h7OZe< zg+<PGB1G|woqJ~}F!a(?@$09F6znY>EsHBY#Q*1Ij{pF$3cdXQmj>4idN=gHrNNIg zdF>k9hwW-usKeePrN>)q$8QiK|F<-FLo>%zmF3kVXGhxVr*GR-S>3eKu9!;ax_f4R zr2Wn-D(Y!w&aZ{;xz>PbgevC(iF!Y5d8F{pgS+#O<EEb8boC^^KS+a<-GAwPeAgQe zS3WmJ@Jt^NKTc#Oyga%xS~UGNC&0nv(?t1T@*V(~1~Bf`>U1=B@2tIQzIwl~PW!>; zTk`ScQx|4K)8-GI1a6ne`(I?Zq${5<Ywh*^G)a2Mc&-(E3O%T2|Ka(~DhWX3kuE#O zh6Dv(Egc@PlotPF_2%{K(OZ|pY|Q7m>L)FX!2RSj#lPt;R%K^D@<nW;>lSPRXCMXC z-#OrW!OPZiR5JIKX51NZ69JF()EXEu0-7--%}|6y(}|%dpIfAfo7KaD%9yA$eu$$7 zZ!+Q~!6r@#p(GcKM;F}8;L0Pc<ZJ2KnxMm&4+c+R!+c7JL<KGRtL`zK&Uvy@G&!<W zLf|J0W9BCqjtXdi(AsSj5u*L1vd;`Vq{mE_tmZJu_D391bh1=H0YyGy`m2>(#h*%v z)q2R(GNdB$1yUqi=zYL~?`yD}a;P8>Db2KEmSxvA1f6DFa{((kmDrEg8y9#5yz3BC zO8K{qz0km2ZVtD}fEq}qQqz!vGJj)cPf%gwh+2bqgH}@5M^d%z9o`nE`9T_7_Bift z2bWCDoZmw21rQnMtJL^tYv9IY$Fjc9SNENP3u~5K4sSw>FvJ`Gv0z8vHkg>{yM;ZS z%_#sN7zu#r%*83U-6P^}o!`Ti6IeL#ztZ5w@hZ)i5b7uXCk>wH0*(}KFd3?n8#@PS z@Wg9|>W^>d!&LMD%A}TX(n3X3LhZK~*1D?qU2GnHpPdPDOmduoiq^Eh44vm}f8~*` z`eV-LAPxRH;MS%n{M5tE2hXMA!ff85hBs|cF+2qiO)d$u<$iuZbDYx!lEmfqOz2-u z5|*+w3p$ADJpcBVu0Ff?>m%vAEO*$ssIQ%(HpD49vESG8_gdYJWN^JgcBOw6&Iw`Z z6}<{EILWr@6`9y>gHjBi{*=lkZlgYMZ?UA=V~P{ll~Iie3!eSm=@X&*n$;@3kp_c* z-t&<9zo{i}0a$6CtzI6V<X@}&Jc+-yZeLFRIWYPm`S13JXHS1U8MQau-vrD4KopsP z*km%tyIa3^)1U1OhsGi0aDM<r7P@xgAm1Z75i;1#{qL~EBEZrmIx{a8ZPDHW73jxP zIbp%QVug%;HQ0+Ru{T?3gt0}gSX=Z33X}d})m)E_>BtE!Zx%N<tRPu;^j$=)hyz4V zlhS}bMg2USU0)@CeVwU-kuCj$NCoje%1l0JD$~8q3q4K%6@<cR4ssPj^@IUsBi@_~ zyX8_pQHQ|a+qsKiI)NC+ZO1gh^-oqD67J0Mb?_2y<7eQIO9s4Y+xd`RRk))W$AQ1w z8Kn}QIHah_i8S@A$uRlD@L$L6O{T6^z4KADRT{KOCNmpV<PQhxS-I`l72bn+swJUE zUDGtKcdk@vT-TG<!|-2EIk3Uko3ou&c1kj{&E)$QbL{y{rDA+)34_O<H!wkFqkx5O zpKXTN8U7nvZJ#s<q|BHoC~#G!Tw-*XJ(2udQ;8zsOL(qMjuR6|&uvEN4dqRI@Lj$I z=G2)Q@J(hy@~?LY94!2OPWPReEI~f`q=8*C2=!|&;6GV!<y69?V|*&`^gz84Ui<41 zT&?C!CA}WoD;AG5tLLJ8bXX}b)bH=sSsn{Ai~Kcqy3$_aGtS~bDNT=s2;QikGt=uS zp1GS)cuPB{9>b0s4P%mTuXHG#8tpzA8XyZgX|HOSd*+09y{J1se&<}MzioJSv*h=M zGLO#BgEz0)UF~>hZeZD+;k$9@Zk9ygv8;qwPh5Z8KjpS+O>({xQ(7f5j)TcbsH0D3 zSBfqNApHX|_N3<y%(qNG18L6J;%ryPx&?-hfcog$_xG)@q)J%e-jZ@`qfGeo>-v=o zzLYQPEK3CYDl6@~&PMOvm3$nxq4B_t{AQh*HU|Ub0(Bn={Ql9k+V6bI|4mK|g(?sQ zQ1G8leE5y2;=js7^7W!jB4@}_FPLdcmbTev;|?BP7EI+4i=6h&sgDT~43Y&YCq}D^ zb7yh@OfP!ReaYG7Io3kt<2J@5cuDMs;D9o1D%*9;NfcN$HMq~=_?5#O-0MIZ@2aCs z<9hf5>tIrU%XyMFsM6^RrYdE&<Dx>QdB7@NR#_(3%Yz^;yx)B7p-Nrk*S04&ai*#T z>K{Hf6g^c_Yt_*A#Kap4uths2(~UOraua8&q~CoRv@FiPV)V^K`p+a1;9lgUs_+4C z;eeFN20ht_oNe~;e)ZvFa$pcyd<TF@4kdmPxL5Ra#AZO*v?WvWL$B1UoAtW)r*Z^b zm%;a&^rJ;x*mH8rLZ_cEdc%9>h}GRZxdaH|4QbxX?)Th~5a>qkxDwN4!awbyetXpL zys$D<<OVK{_y)(B=ujoi`hvLA-}3&Z+5<kRc~7os4z83H4j|p#yx`*MoR!2OFs05^ z9>PJ9ExK0gM-RM@JhgQY*O#25Z1c;tWSpE#;V!Xk!3S;M)E+XCP9O}3{0MvJ+qf+8 z?!=-C$6c=A1yWuHdxNg-#X)fdtA$&(R-axCwoG_$z&TUYr}##_r$p%QXX2o>xi|)p zfdJywas3Ja4t)$S2_!H=`{<sT0S7Hz_YcnPV(-I%NfMto0F|^1e-l$cX2`M!yu@$J ze|-~%(;P#-Yti*dP$+82J_!Ztrm&|4$nB7m@+#DWa&_pZ^m&GbW=I%Bhy?&A&g=Jf zzOVGD?h)!HAYSRpp!F%Fjr_?zg#lvvNzjCUhG2miPMY<PGZ~SZ4|!B&_}{rA6Wqg& zeu<6ebGBPXTox>I^~{!U0<JS#L#K^g!_a2oMN$A190Cc(%m9W7?(c!^i2D$hcHz(l z5Z22UB^dwGM3F_?<ER?2$1lS?oVs`4ndOU%dd3?sOEmz1YD^0H!_Ts^lrY#V;Ogt2 z*i@Z}Dx%ot*+OJYKjYE)fH%|=equ1{5}xNl81{KN(i;FSvEsQbkf#?A2{^PzIdWw% z%=)%hdsuXp4OY<Hrpg8pw}tvWivm25IgXc8D9Dxt?gkI!Dg|A-aCz4OO~NORPogfz zo~VvW#E8)C;sgw$x!+Bq@0DXu2q!_h<A>m>rMid&Fgo8RO_Gpii$u&HPVn4A(17sJ zElkxGI=4KspBdWXVHqdvvv!6Ic!b94Vmo7FyPVJj=CPz#*n8Shds_4>>^%mF!|XF2 z({7W|GYLCD)q!$^l1Rdha-=^c?KCU?G!Ypvl)`jMD~(0yR-%D&bcqMzW;16p6Ye*O z9Vcd?2QKw85pO=)?xn>RQP8VQ<ZXb<boH{OGrGSSn`{wGeyDc?nla;?qbXylX698w zN&cqIHG=0-TFtzQMA+!2dE?Ly#8huojN(vq6e}}73=svORCf@59!QoS!gn&eih|tj zbH0j0<t!i{Q;@l)%xp(=c0Xrz80T$DtWGQp^BQ}V$TjL`o9CA!)|n^SZSs5;{m$9X z`v;=tdMfwfG~2<Hps*|39}#3c%o~@RzlGSTLm!HZrX8eVoql@j`y*p)JaSm%KpVIt z1!hZu1(xSpx*&^eunCr@hX9})j~x+#l`f!1L9`+Aq{wjIxnG6+d8aJ}c)YIp{cz;0 zaY`#=<Of*7y~`0E9`G}G*kM9i5FU2QCcz(%I5mkLG`sqLP<7sKO>I%P-svO+2tD-B zJBHpdA@mv$5Rnq9K@>t2l;cSwp%WApX@;h#sHljDEfAzAVpLRA)KFAV@k9<Pw!@e2 zx%Y>A|AqamwdS64j`5BhN}Pwe3{!;82cTp^L!1B#@Zg1nDk@(Z_6$Vh5yj%h(Lq#+ zSbpDjq<^364?ombF+035y$5=<=XevmKEm4wz3o{h{~PVq_llDNoZWm#DCXd90&I65 zBGrt!OAM!op}iZGYzlmr7#1dic|C98^56k<Xdyr6q%W$7jBKGuK?KN59^91xNhTvQ zH!<*o01#2JkBfoc#K`1J<d+0V*lXcuTu-e3@R|OWspOoSw4G7FhhHgy<3-SHF+5xX zo!{O}!PNm0D2WE2STXSxL*2yCHs$sN43t1db7-v$T23iOrc2s*^Kznj@J2i$fDUiO z$WY0!2^xxtN9*s0eq2GUib9EOpKkNwug^P^H2jz|iB0qqGesGAlRC2v8aNq7p+P8; zL!lCA#NDo~G-j#<y5<7iDq?s_ps5l_j>w=$0w-gjnKT&VIJ~qk=a*U<n30plhv`(p zAGuPCd59Mk=rwidbuxn6hu*b4^*tsyJT^pQrL$bKtZG?G1EL)DiA%amIo$Rgx?8|^ zra-&^_--+L{%S>J9G`+YOu@HD@gb=cc$gTPLqTLv>WFwqa*#}p7;%u6^ZgxyL2ErC zYK^AJluFJ9NY386i%8<3rN*)bKJRN<**!e^exLjzJ})_aTSeTth~>~Zj6#k$r7kGR z(kbKpDMZU%eu%~SRtroN9!hhCh6C`ee2C;HWc&B-)E8%V0QQL#cm^NI=D~C5IoF5I zZj2!^@raur&T=uZ5Pa_u8Y-7h@uSJy#8V+IXrV+_NJf7oBvc0!JpFm`u4%xWNS^c| z^M`BhRy@=h4-Lgj4_$2w3Wy<`PNhK1HxGc7E!tf_LMh}6=_nvk0{?La*(!n4F=@ZY zkO%utGRW|JGW_=LoKgT7sYKkyAo2-P<w6dCZx!<7SLkvpyo=wK*kqYYRIP#^>vC`L zau=jDg9Gs~G_W%t-i+#ox$)sYp-y~AIB?;UMZ54cBvxdQ2tYF`&*YGyIhc$~O>l-7 z@srcPu%l1r*V#BcqLhw^X-1R~;6#et-!6#TJo%SL{uc;wLm>YOkS7dva+?M&xzntS z6viF*`nn|@vOqfFy0iOEhhmNaywmxU=Rci+IN_!FU4t2X$Q}Ze3_uBl_MZK9S$X@% zGg~wH6ym_yMUAx5O`6OtP55@qEie(8OGDvF$Q}VQpFWi8K5$PU-!(~p>~ejhd5^tu z;A`Ga%y_0HJoP>R?7|gg^C2WW=fu9N;C475z8d}$f)_*oK5)ZL0wEHh#6IZR573_< zpa&^%U%>^}O!x&d{8mr@4<`gbfM@+2DaF9!`mRlUxF!XC<&%+WI}u5;11kV<M<73s zm!CDG?N;6P<K@nk!=p$>@G53+UqI6N09b6?X+U(HLSV{T{AKSB#Y+yw1s#*=g#_^- zj(AA9EX)@Gd;yq>+ezJ)!>&Kzopc!n9@Pb0yB-9m;(HhFA*cY*NJkXXU~*?sE_kUM zl#UdNPz@5<9y;nCU0x`V+SA)Q(wahUOzIvDZ*GWDgI66mem-{v-fG&?Hk2DN-WA?= z$qk2L{<<0tK(_F}+c9n`AI8XHm@gT6E^aW{NhbLNViu3`h(|tiMUXMKrs9#eHDL>r zBP{~iTnX$b9+59XRsNQpt40a?(6fYX5)JaH3T1t@l$Mrh8~eZ|y3Y%<{cHe!NKjy6 zcDeZj-2Omi@;Dz5LyIeJxRJp`ob(g7|3Cpd#4v&^EKPGfIi^1YU#i)ZRwQU6|Kd*n zK3hzOMvLoYzR4!hA#>I6eZXW=*2Qi~FV0~)O!d00{s~BKtj)P;hs^~1FD-9rU-bTc z;T8M?`CXL_Kd&3e6t?ZEOx`yfCV`N7V0)=!9Mj&qIGhN;2+bFIP_SQ>HxneN`=aWh z0MtPMmM=cLpwa3;hdSUUAPiKA1hz~=&^!_KE%M#Xk3LG|e5~Xj?;p)9Qx3TC%u#0+ zW?!)D*+7b4()*sHo$uk>>@Ht(g*r*P@Xt^Di3gWogTmq<x}U}}co)KWuvq$&U36IM zBInYFVJ5wfDayLe-xm$Q9#*vb9ETGGP%2p}jC}@<K-E{H_F*Q+=oh;Ma&P*`A->ai zPv!S2C+w|fr)#X*KE)XyIM_-)gnm}CfPy>WyWt<Mrf%XdhZA61fs?i?P*eVy?ay2R z3cQmA`+4_X4iAPaEiA%uIZMbxRXO<-8J!x$ksXM9I=n!$7obD;36Kp0@QoVOQ93G~ zhDiM-+l`mE_UTb|EXHOly`P$U`+H8e*6LSQ;2Le#;v_l~$uyCHH~fUg@Zr*i8{B?6 zm4Cza7sQtaw&@$YusHnl#XUXk{`N&!X(r+deY`jXHA+CG)1bnDi9+5rMm0QN01dzk z;{~t=nslU#y7lU1BzdSuBD<%1N3Y{KKM&=Mws(L1ncpM7p#3!QK}=HXvx)*dG)8iL zUnZ={1ykBw0SLg(G>GH{WUJr-2?O=qBumSQYpWcPZ2cqy4^MMm3A`n{?LMMTfP^)} z$%%+ao8xi3Yo$2Y&c3(kL=-?l-u@$7J|O?G>)CGkS)=*Li@Gr=Fmi9(M@>b)%Bz`k zyBD7Rc^vZdI^+ek&KVQRYmNafC~LMqkp;dj!#n{9>lUB?7?MGNh2dnr)hzjah8-lJ zI2ajIH$*1xEx7hRKM^MHg@^}$eSP8^a?f7Jdu804yKk+uagcuZkj#JQKRVnDe1%hJ zpe8j-%9=4P3vSFee@Pcxm>2+XCiAz7p|NuJe%^haARbftbjg$eD-yK4@<MG{M*2$* zcj9FDJCMob<IC~@6$6jnOoZj0dz&P9St=6u5dQT)7V&GkQ~%=J)(ewB(mG?r`!QM4 z3NMu7b`e@DyhPBv;}v<CS65$@`0^p?{JPfr&o7@5B@$#xFwoUAmz?-;x6-99u}mT! z$#FoniO@&Hh-3^Lq&oq!`8R;}wwphZ#6xtSf7`>K=n*4U1afHAn#zAJ8tK<m>DBn@ z{iuGFc>Z{b0{3VPt#TI)vd`wcWAJ{3@3mhVXNttIojHgqoQ$`un`>-8(08xqEOHkP z`PUCr7yV6wc%Ppa@;+83n(`g|-`asKFq+&yNqw-LWK=i*ZEh&Cg{&|~o7*@)PkQi= zZEN763$}BD`rgeS^^cF1Q70L<D>w%*#|&MLWfKt4%I;JNTz3vxDLAt;=Si#bPd72l z{2xR$PNoEp1}<in9}8>y%`<RB&6{n#qa72-%BUT!h^Ov(4(8A3m}}midmd@A*y?`A zEW%Pf>}}9d>z!b_#<q7MO^%sEqsQ}&r)VDeFaEC^yhhizDQYG1WN52bnP&8ds58<3 zj~l$(Jgj#xdv&*Bq)ABQrT!7Onup5HHage#kHtPDzC}0cg|A~?INYt$@NV-64H^x2 z*cn)qsA!n}j^gciaA@`mr04MAxUNrDM!tI*+SBj!%o8L14VoOH2h*0oVn@2l&dpmC zBcyn`CB4Pt$ghmgFP$&C<@!0c#sA3byWhH%tDEq%;KP%1N#kt^zrJ;+Bp<YY8HjBU zE08&T?koFz+t*KTA8C*fw{#;fINaR-FZ^zg@bK>g`<M6;Cg#H06eWXhY&bS^On<kN zD+$BKk(QOiHTS>)yEEi-s6$pS46e>*zZ_AW3##wvN|%40-nw^8GwWJg%b^Ir6T4gL z-F5aYUG&%c8)|2MglTjs!0?n(R&&HR89p5(GwY)fI=d~^Gq9Kav3ldv<0Y@q*SIN# zttPg6RNMi4K>c<PB2C{HUqIC~eNFe%FAH#$5hk4P@s_ojXe13-Hv;CP);<7k(~v~E zVR$rgKeDU2VML?$ntuC`ihpR5+of&cTVak-5xXKMuSbOY7P@1fn~%vIcRCKocse~N z)!ba}fK=<xEFZ$yT>E6Sm92IWVsC##!n&V<4i0dLRMF@ra+`)9AOi#D?}QP>bKNM1 zE>X%=_eQ>cL}SW5vk2eqX5E#$iguW^=Z)&0a(N33uAdIcGTLQY>KN)sVIWKfDJ%uQ zVs{!q@vqr_s)VFe;au;dP;q6Z>zwn@?;{v9H)0>w{}ZiC<FHmsh<*y1!EVZ|%9OSV zc?ms@9?3Q*kJ+7R>@;*B#OYsc#7GY#Z^HO(1b_$eb%Ji2M{Bos-JRS_JRsCR)mqqJ zyZ<r!Hr##B#c`ACd&t*L2P&nbju$Flb*v9x?cc4Kp_1hKdP#0;BC@8P6Vg^BxD{yo zDZNGE42&L;r~zx(o19HM=27}CrPh^Z+0@mM0K#!GNwTcN=@gWaR^DB6uJ)7dyKWZd zwMFWfJi8P5S9AW0m3OMI%0ObRXMb<L+B45Jy;Zze=dauIEcK9&TvZn1SJ01T@=oiI z&wgG~e&xR6(;leu#V{_@mhIG@atoooYxfon-$wgSJ!QupjOCm>;yNgXs9MJ#Ms`M~ z+$|3%NUe93FjVmKKDPAyp&3wJp>2iEws@}F%;_$j8Ig~v(fmMI$l|8<8-Nbcp*r~) zJz$&qB%`8b&YZi_nSDV#rXe0c4kbL`jEF|fUW=gw4A{OB=lgT!d*vjCggJ~o@$>h# z6Jb(aCbL{^`lxM1OuvDG5{Rzi1}5+TvQhOTu<{vtg<H8iz=$1lWs|f|KM4r1uhgvm zSvIsCV~{#R<uv%|*X=D}X^$owR_|%(^D#;(<NBl-s9u{mGn?fil>$1CMbs9}O<O<i zOO!kJ9re+i6?|V@HwlO_EupgEcd%s!y4!=$NM`6a4VH;XgeLk+hoTS*SN}|?aGe7s z4B2V|G5qt9OJY*I3`Emqn47T9RB53~hkPy*or6AB!cE00rx&1$)#ec3hVqz6qGDZk zL2A}cNZ7MRVSt{#fzl`TE|0ga4^FS2je5x&w;b(M3qy6Dc*<%vnbxl>>K7_^LFxSg z&vABdkzuI4eg?BD)}}2WEl%g?mi@!B_cE8|@skW7)o#k?i1)F05mW60nGn*&P=3%e zY8N>|Q1l|38>slZE)h{~E{Z1q#Rr@A*w&njVC7zz7<285dHmLw*A`y3JF43)`eWm6 zlcl~_#SX-)8PY_v1SO7#R22wRvot%+#?170+u7?lRNyt<7|u5E>_x-rT}Hl^oQJ5O zrFr>i!X5vlPS-;!D7E)%=|MjP2x|#QIT;Xa+UO?N92}n5y?69oY+8!N+5bL99^GsB zVZu;ZYqx>c8Xu0E7FWjwFfmK(ou1qR?K4lG4qUynH~R$BtyIobcTW5$ewmM64JGM* z6#0dZg4!}d42WF?6J{HW<=1aT|J7B_zV8L1+qU#-2qn-hc1^*z^M<?he=O_dVGc{B zTgRy7BPl;H@Q|nu`J2!0xKe+*&z!Si-(v;t+6%ssU2dpLpNL%mB;ouZ76u6LwOa-q z&Q)tXJtP-oVxm|fw@)e_qz58xJyMj8ZSWR(QN&ZjHJSazny>^MJ?YepW9T~Wj=;~O zt+^d;+~0s#K5XE(56&htFEmJXCI>e`%0_=LOF^tJ{JE}5Ngev#M`Nut8z#A~qYIel zW)g?|HGj;19}B^?leaqHEk$Xa$`O?n_}veqU7P3SE(Mf%mIhtj9>TKP-hA$MhzHeM z{e@_3@l)(O7+w8szxGE!9?1KdbR2U^=hU`Wt^;bd`DV-KKQtem^e`;1a)Ru*fQ4^a zBcl@eDK{9flYWG?hhI4|(wq#YaR(j#!|td;OC!nH#kR7f{>P;Vh`@C^qAoqBGjTx% z-~V_{>A+qow4qp<%lPB|LGL>G@K}<KcWzBwqxbMGhBg0tA+_l0%UAz+&C>wwkvzPn z$$Q@CN!&60D6a)N&;#8Ppf9CiH>P4w%?9Wmw5={cry4R<C;iYc0qA5wb)jG_<%$4F zQTU~?D1+dy7P^nfQPuDFq-8uTH4Iu&(aPa#0S*-;w-%yWAC;*!BRCs3!#w<*u^R68 zsUoBRta4n!4zc($->IylQoRRyquZ;{H<FfEI}jM|R)gV6tj|q%`*}usBZG>)F?yE1 zy5tBHXN!kU_ePS)$>3v+v=K6S%RKT?l;ss`fVMF<G%vEf@Zb5`qPKiMWBf(gvHT9D zuGq0F6(r@S6~2)Z#-kbz0m%oSma3f=5sxh6S;oJ`D1|X6M?u6E#SdzV<#?k{$%kZ! zqJ!U{T;%7|w+_7izUf7|mo@I>t^5iXx3lIG4kk>_fD`y&RUx75<=<bv)nyMW8C^TL z$7;B2%iKG82MSXSHT(VMzsdj9yoH)DYiiD3?rKTbhnXDx((_~d<Chl&MWI&z)D&5f zl-ZIh%N3Jk9@`#MCf$Ol^FYP`%eIk$k7aJ9b=dqk7xd*=Y39{usiunm-jrV#_`HDU z_ZX$0<pzzMdHd*W0RfRpK}?Y^C7G2KG~Oy>U76kJi5$G8@UX_(1?FJ3HF#rqE!C=4 z$a2G#6@VRb`0$6%VL)+%>8Be10K=RfY0Z=6WpVdI&>wQOevsiFgJ2w=Ax*{9D+jsq zS)L+@<1Bl#jfwP@;KF_gT)TvB{iILWLwjdAr&c&QfNK#ImMAqH25<{v;nJax@qz0D zhlh<Hck}w#n-7hH`{Z7^!1Nm~;94#u387wu&a*ph-XOU}<+n{8e19%Nw=TmRHRX?s zOp--tKsu?TlAMdd8US67$BLpt90#k0=(2&ukenff5;437c`Z{YaJSMOrTAT3LEsPg zDOB_C{({rWx#^U_^jKm67H+QrH?A7is2;UpRs`Je0&oo~G?+C3wzks>w{-nZ$CeNQ z+fKkPltG+rHXLSEY-5ikirE?ET<uA7osaA|GN=5Z6b{XNqzti;DI-%@_GHMWCBVAY zC%dCdtDqS^l7&0fG*)jk*<*J3(5IU`**ga_xhYf_i9J~+<XCOMQq9U%3`ehCcck1s zA$Y-b+c@DqdtGnoO7W6o$&6j?BFjR?{>Yqv)`l~^RK<U#EFD{xU>0zR(29Nm4Fy=H zSgD;CFy=!peKL>e13MOj9cLjxqpULz`x;bTC^5Xh)~ijNyhyxxW9i;452Y*%ZaTFr zojO=R=F-w!>;#j!zso+#1_jIX2Kc~i#7x0YW>UF-NI$#dlVdQ}FhtD8<JnXL``!|` zLuFYy|1Q1jb|R%de}a?O2q!lBe%{a2=Yd>Bthf>;B^H7w2X9(Rs)mZ0PEi4?wqs6f z$lGbt?^-J2%DEN=(?zMs7pD=46qkYkL}~ycG1jFhVAR)YG+;(9N}4Y)cuSzvo3sJe z-Y9bug-kd2mqgX9Umri2tdrlzi6}>&?%L|VqdsA9plxA9A1^d@fq2p&co&FM08B47 z*isbW39vjdemNhYnPPZvy>Mk+qyUR}^+LVGkXvZR*~<=$KSV4VWV;f$SR<doop#ID z0}t_`Q39xqlui(EX==$GXSG#-$+7mOdr7QCo(rO<0lC?7*MFX!Rm`%V#W6NOS{ooe zOc*V=%(RbbQzq+4yXP4|uI(*zmf*II+`~ja-gHdg){~+$!!TOfNi4*}S4(fL1apHY zSTt=PvtO{BF19=Emb(BNwcI@ka@pvG0J9-$k3;l({VA55;B7j8eqa4>J^V>LCxOSX zr8S3&KpH%T2`0=E3)Z1P@O@w{^1Y#Q+3;0!^AecX8hms2<DFN8{Uc9aHsMefvWc^0 z-bNv*;%!&6%B+fST@!XE_rZ&(@E`#+X4&{?Bn;p)f@m`#4O?(uBlJSHdIdnT%%l@Y z9pgX#CabVw+cMX7a76@Ihsv<I$<XR!I1-|rvEcaz*{faTM(o(XJg(Pz>&Z(`5*%aC zXmMCqtP3^eM-K#MM-erm9<FF{Hf_u}t0dUxrLq*!coCN4O1t7JU?&UMwE|FfdQ|9~ zd-jnF0ih5t9wJ|$nI*&i+hhB-sQU@U91;yYr~$Q*i8jVZ>kTsWv0%G(X+D?g_9rY` zPl&lbv;??(H!_S}VhRL68qL^epVaqki*@u2>=46%9?pdXqa(#e*|FRNLd0jE5Wn9r z_i}^{WstK7I|btA;(L<ua4#2jGQqBK8PaJqH}W-NqyK?Lk9s~1(G;y2@|QR81Zq0V z+Tj7wFk`gu1$QK{9O<C$n~ds$I)^=k+Acz%l+gmRm7lA%FJ{@|cRJpW18`H>dt6@B zRP@!nQXMjJ8i8*{65v#`kcuP23%+Fz06RuJoz7<$;JCRP@WAI~jU!M80>a#-%z+QG zYw{QFok=`9{^5^Yp6G!;zao(~V!B=y#E*9sK`k~w01t%iW0+9ESeF+iSHRdo&`B7u zy~6m!uZcV?Vtz-NJqTdtvz=6-gxOc0mcd@da8(DmcStO$x+0&Bj4u|e=H1RGBisp` zG%;)sZmP`kDXo`Dnhnbtg%{1jvoYM4ATFs`#e<Fv>0uszb-kg?e>`&LNWu;;DSQFV z{%x@R?-t}w*0ISNEejq4yTMTEd1GQ0hmB=v^)WkYsw}T5IrAZv?W{JI!)bF}c^meo zZaaIGSrJaKbLJrbJz~n-#+K*QT9zZ-jD1GZ2H7zBp7M%=#R&JXwhvwEv{+aQ9YGz0 z7UF$YEMGg|SpOX!j-evvX-z*f%iIL)f<B0OA6GOA`n-BYcK~W#4vwm2;$<MWWZ$^; zu)$e~TKDaZvond3vIsudb%XW&56HMDQs!KeRU$-<0@0&0Dj9Y6-#&7J(nE1&{NTrz z80-){)MvInp!k$89hnWM!~EE=u&$o7OhFAYNRZ)OE1zsV^)S#WAE582R}eqfNAWpG zWsWm>*STfn+Yg*#Y?;^>K_$Rbs4gq4;avdTi^}C_!HXz!(u=nF2?`XDw-y3`I~E>B zV5uyR{)pe<Aj3*{Y*#ODsBe?vC14p^A=r%-PfE)yU08RcnXrD4M$a287W`X>nfeU` zP{DwN(RBs9v!QK`%H3V8xNsZ_^p*J!zMH)XCB4}7K9&fG!~Cbkm*kWp0yv>PyU$aR za&TA*mRf-0M7t~x-3;_9XJ$;m<If-hk%&)5Q{E2nC_z~owJgb<y;}C*4s*t=hm~fL zX&o$;f`Situ#-s0ta9_F@?%YhA%Vruu!2mBL6EetYl%QQgCHy&)JO&6X^^UikgVJ~ zPlKw1u5ASwlxD*FzIT<R#ssgE;)j`KjfCdSu!qn_tmTVZl>eG=4-TFplSn0GrBMgn z|G;7fSqTBGs{Pb3A?Ko_kK2>o+X;vm0c$;&F~%9cKgy2w`t<Kp=1j3wy_^SiH{65V z^ziguVll*F4r1KLi2n_WyuvUgyi;}osZl@x9pu!9jn`mSf>_B7h@ObnOcULwj<csZ zt9(2pu)M;55K6-Anm4I@c_qCu_EI6w$x{}OJI;BN7^X1ZKr=I?n{cQE4ub=y#=^2& zZfRbD#)e!8vg3X<2`Ow8r{m#;8)YuB#1I#DPyhpr`V?Zc@~>Bp2{rv^oJkm^zNm+7 z(sj4Eo$1U653W?1_JNGa%uQ1Y2x|sB{KjzX13O`vL$TzFh`J1dbq)o&qzEO=KCz(Q z>mujk=@lp6<*S)izOY{N|F-z#9w!YrltzZ<ZOhHU7ii|*J$ir}CT*a4zAzGDt85~d zRJN-ahA;Pu6u@!ZN!RG%B(h7=EX=EijWY`>`Q*NFD9>C0VnjAik2|@tmrKHTo_1h= z{{wNOO*CbLwXmydbdZj;%C7!XdQ%DJ36Xxah+^Bl^sebRzssj-m~M73K)0Zx#BAh+ za|P|?T()t@KCj&4%iL`Ky6${y<1DAJt`bqlT|9|kp3K$Sn!G;4Oy`|&7Ww69PZe<{ z3tY+$2-ur3JwcSt!XHbHmiNBKpUShw3?#8Ub}>hsH&_X}thB2PB?6;8F&aw)JBb+j z#Y|H^_!_{%a}<DbM6a7pCaEphjP0GX&6m%9-s<_+0~7{<ilbK)iczoa_J1_<$S>zg zcP_<*&tY76M1UjbFgQwVIW72@L`_^>8gsk(N_7c#W+t)roqI^Y>FNhxEy^#fpJgS+ z4s}C-BpGNZk9GVY_;<#?CYU(O8jzby^o}U7MdOd^IaZSbBCq2Z^RNA9@X#|yYY7sF z{KJe+Jln*LHK~sB=5s2)rAnCwZ5R5FJg!#&|LGE2&-{3wLgzFBFin5NR`SPP^nW&! zCm@9sh__3!G3nuI@3v?H;s750OuLmJT~x0>{P74p_^ddeTM;|EX8liD<FppQXXa?F zVqNlY^nsko%pHU$7klGPdrAO+wZj^*H$dlL!|$g#DC9nQUp)JyU!|YO^XLC@gBuN= zj~`~dRI=N%+}G~HSTOMFb?Ixq^Z&WQjj%RzSF^t)`fAC@JwFpZ;d9QO%YA}(ADwx= z!p@%Ek}7;8r&DRudh5Un5W909RUL?QiOnPm-&^PfN1y3fk-EWS9SHrO&ah5x$Aw+r zuekr~`)VZ%udv3xFQh=_>j!$wq~Y1q%5DYI<cD1q7+|yH)kwX2NnXn2#39pd=lA@u zdp8B3UA-OfO8&&AmKz|kkh_af>u@=H^{3;<g4qwPtaD#pUgdomdONWC%UL2eFs-!w zUK{I8m5L`IqO*_8)BbU5ZQqA_g6FRcY}t8qT8CcX{p`xiJAoA5+2r$aXN3N;&-&JG zf)!&=sh@PXC=crK9j~C^H~2p2a5E4~j(JUAsJW{;7Y;<BJ0?||LJS``E%HdyKDAP| ze7Sz5i$MjtI|61@vB#*~Gy`KK15`J-7}hwt`N#wF4YMx;o=T{OJR<72$mdnRvRoc) z7$R^Sr4FOEH1sm39Wx3#rp#}k%M#p{v5$>`P5&>KLPB4J7+{o+P*PN5O4*8UO4n=| zP?KU>N{CM8MEj&=6nP$w1{`va$>Em)I>QM)KdKodx_C-E5Ad$^cv@{g9SBZu>Z~RG zuN&O(Je*!tOE{!x(Aot`R(3{rl^ayC-7L>t85*l`9{4bHHsf8(Vg>0!14v*a>}OWH z-R*0iGZ*sz4K9`@1BTlr3>=zveb<oMrbpC{^u;DqMqbC{Hr?}4ZH#&(YZ`{On^y(| z087=@OdrC`-I2`FXzo|!YUkXvE#Goa`_h!_0{ij&2x{M5%TdMPIi6lI&(`0lYJw__ zX)p)VdzGbb@JZulE4%Ek4v&$Zn~-6l91(F9e7`|N1=HQmwyXuaiSqW%n17R!o89N> zi}&rKrxc-<J0A+l4wTL)a<1k2wcpX+wR*`%|H8x<ww!anWK<d7z-Ox#NY9pPGl3ZF zb$xVX(*EA)qkA?-${%Be&27J(#rD}~g2v&V#(EQ*AUmGPL9@JKaec6t>)Rs-pc;UR zA}Qn^SW%c~e*q9olFy<cavnJaOtf9kpz!V%lEz}I#pgZTyKW1Oq*_PLOoTt?ro@)3 z79GXl7*l;Bt{BsbV0xO-qu>C|oZnyk5-YtFS?KV=cIYhdDVd`@+4DHq>Rxa9_x$Vq z5P`GG4zI0$j@DR^ahv)(qclm?T`^k$h?xMyJfr=#F~GAtSB{aki0z<_*`~~M0~(3y zcp^7%7FWHE-??Mi>`vrJe%-b`rbS<H<IXRLl|k4=RHPVc`ueiRvd)&UIDS)Uzog9p zNWlO+p%w?gTFep<K`sjz@MU#-HdFom^_^QfW~<Wq-C8J!fFsj$$2#RChD~Pc51NhH z9=ce4Xn4-u$F|0}a75!_ai@k~Jt9J2s4y`!X8MU=orWf<KcC-Gd?*)Hi0Q_D!XsP; zzIa7?bnfgGKus#29kIX+mn3DjJ?STNjhEk}qG(LHb!jxytT>UnZA9Z6pY7c1t$v5! zp^|zHy&1;q(0M7w<WBVjC$yn}P34L4BJ-(arOVZWKgL{}3gq_tkW~IH?$r5&t8@`T zbUH*Zw+8*nFwCO*H$s^wAn7icT~u4a8CmoV%V)QwYR|+zvtkL5A+!#8(Z{>7d9jWT zc!ok|?1<%S2?UE7gI9Eb0qw5{i-}}~!9L-Su8CU}G2rAuD-*vvv&cW`{hdS$4&K8e zvJNYv>$o9oJBDjA>{4|BdW4xzGGf0`s%i&;i=P7IwjMmJ4%WD9E_iGY^s=-y-Tdw4 zInLSyr9;UC=JrMcBsk`rg>>$#n<gejGVA2CF+!!<;>#oP4|Gcc5DqD)pC<Nh_UX*y z#Q}>$mLd%Myy~?b__t@aV~|31m^s%u@5-~mur!j6fxoHR>{tn*Gqp9q7a!AJ+gu6O z#QeNt{<}w(QM#i0E*`aI79=lsvrt3zYu5gz{W3;0U)lV)wrf_yunP|1vJoy&Md|wf za!EM;d&h|0G6Cj2<1NoxrtEuq_m+7~zY~P<k<z)d^Tz(A+($QUXn2FzPZ=utua-G? z0YONFPpWQbpU}fcaa$T@@#KJ@OrxApnM5hN^*R@Ud<dc^#geqN+$x-Va@%^kCd1ZC zcW>_yK&^q~fwhaHPlmwB+J21U15y&;tO?>)Z=Ntm#5P|NBPcR?8k=`w&&H)jAldN^ z*KGz=tKr`lH2h6;!LH+V)c6qLnKakOG>%r_TjVY%OKmCCFEqR!-THY-r+WgTUy?lC zNlwA8;>Wu;OehSg+L_8XHL3@8n)nchkF_M1W^br&NafbXA|m=AK(}3<R|q3BwdW#b zEoe;5fP-Uk9WuUGng+1hPi#As&n@516lzwfopz2|sL1kJ#6F~R%%GqeN{@5MLB6lu zi;rbl4GZdFCJ=YY0TqC<OQ-I~Sl|#tE^<8u_tXWd_pYMCO+?x40F1QciC+9wl<sLK zu0pqn$Zqk&$iEwT&)^SR({PZZ5&hp(+ItrA=`3xTl1+y}p>?)?Axm@7=H0%<dE|bp zB9)ACj=gs-I=&pNQ4%n=rA3h&LP*_pn+&s9KhV&&<C^wha-+*YJkQPHh;p=<y<8(M z7w6M*=3k^xY1EW!Jogq|Ko_dM{)%#2A6CB}%fVe#q^bm~C||&D5b*mxA5ZlgbGYp~ zJwDi;)3B)7$w!o2Nalu2bt=oNz-+=4qZ&sUSdp2dMHr)MCngWugI@wI?h=eO2>b8h zWUlAEilX>~W|bc>Mu(Y`7p7v+#)Bi{kNIp~RthGwc)Rs^3F^8vMB@}bxAK{0)eYC7 zWY?{wn^12Kfgt~-He9AwH(a3NgnTW53oJL^<yNN}2`2^#oYTG!IVt_wyG}{%1qUyo zi_%(M<SqT}!C$`G$fjwab1dXW_Y_qa5~pNs28^4(Lp0*`BmbHxZkwlbi9B!l5lq1r z-dV4s!C#hkyCQ7TZGJRwK02oT%4<Wob*rJd=+OlU%PjF?NraS&65t2F;+qUFD3z?A zC-`~+qRNvkOZ2*uo5Q6E#F@uZEk4!(`yy~|)EbKsJT)dNDC1Osc#!t`@R-Ik{Vw8b zkiY>NXVrMbjiU8cuI=@w8dvIx4MwwJFXw(YU-lM7%+s@tZMvQihj(F_8IiP%bUx0q zG(;dbpI7)fFhH$vW3W=iV}WLy`az`-a{_Et4thR!Wd9UW$%qdIH}4&uY{or6r?sGs zh+n=E^}2`?a^7Dihwagc=QJRB-Kt+Fl}uHHSKD!Di@3#C?Yf`aM;nArrM31zg1%rU zehOmK<*hx-v=M<1Tmjkpw7T(GmLhMD7S`|=&c{DVxdlSkC~y=y)=Fm7ru4Y{6Oa;q z__Mh<>e^AreqR+UhW4EASiQdXo;iUPXm~WzY831?H-ayxXnz|qi)AIhRnn`iZUGSt zwGHi4#`MJ?pqgag7Lv;&K@?e9&q097D>;LO1I7@WesvWelCH}=>shAfD9gdBdb6aQ z%Y&FMfXroZM5|4Rp1A1%6(lF3GtDV|&()6q<*S1kRy88Btw2_B6uo$mRU*SyMi*Eb z_JDWBB_!2`8v12)`DLe(tmd7Iwd9=+>!l@{0rXql%zFLfW?f*lsAjifwF9dhlOf$u zj?lHyKgtMd*)_bs-~V}XvYJg})}3+7FtI{;a&~>Po-_u~3Zx5d%IAk$^^okuXx}r@ z#!HoNXkF*$(9)jK&}#7y&3K0sR1*Nc9WlO8&Z<`tLWnFK7l;FaeB-&db{EqIx5JD; zOn;~ch)G8AB=^xe;b5w;RK{GJ*{SMdi-qWlDxy`wM}I7iCe-ZpWi(q6vE*T;2|6}@ z6NDl2b0>$<a~M;8tXn@ASQ17L#9IflfA_pS)y2`BIJwu!N0T!0Yc2!ymlm*x<bfgK zeMqLf?cJ{Az(?NNVzA9JGf740*s#rRP-qsyaxGorq@5~4jXrH<IYvdPD2>|Sh%+-p zmEW4_L30)su~-ZvqY?y6(6#YPs_VnJ8z4<II4c*d+S(ZPtu<OcPW$zJn-HcG4qEUf zgGZe*uo^KoGt2qxoll^i>+;!p!`n>6(jkm!>9Fj(nEPQu>+%uE6{0EI+iq^evrpaj z(^!i3Np}=9n+I`@CE+$yN!1-{pPG!d#c7cyn7*e^e#dD7bnJeUvH8uE`su?_51aD7 zc<U}DWhFM7CLY&`G~*R}>!YFi9^N=3lJ+v#jIv_OF*rUQ<V+=bq=8FTqPXYN@Uz}6 zO-r^?8zmcTJpuNr_O`{aJjx+OyWbaqfvS3zv&TGLb<~dHJxIA@{$J15wZ$jEFgl)y zy)mq+-JS8DK<Nh2N_!RsW!jE1|MrWp?-8zm==8XkK6fHt4?a24mRW%t8Lwvc22K0E z{?L)0;zDIPtqYxgfSm6`ps&n<zNBb32++$&nq}IHM!=3F4`|Gr(H<d9$6TbOf`{t% z2F~EI>XOv`kASUz>0_*jN^@1(lz7YpaT`$y(*?3@*tAfwCh77aKW8+3*Ak4$!mIO~ z^I&8(ATUI;&)xMFyr^^n0EZOCKWV`ul``*&A<m<uJ`~hmn?*1pS(GkY7(wi<KHAQX zc(RRbX%J^gX!4NZyX64aQd3g`i2o#RwL(^}ufmv@U~x!e>(F~83`lWL%Ps>WMZxfO zFhK<e((6sOQYE=95nYg@4GZ_p_9XQBeX5=%M86xh00hS==Xl}(;{fPv<;%@Ni0ciO z!$m#7VVhZ(x5b=!IrzCIlw>vw_L9!ki$>f^yOO=or$T&wPc#io_nO)DHqC&V`5-wq zQJ(N&^r1j0o~TmVt~~*qS{r7rXqxahk(#~nDy{K}ZvIj5MZQkRz+mF@M>57}C>t{` zIB&yq*t6s-e;?)Z{%&?TZNaf0v?(+C^7ZLg0}T5?hz=m|{B3L_Xx5t|xl<vbXR^IZ zkJU$c8&6n8p+`G3XZK4$CRBZk$ahKsHr_FxB@x8!dp>*2e~!|by4$UAD58Gm%<h3F zTL!F!%9?XAAF|7FOq|S!oyq9YwVWCtTij?)#A-fQl4M2gaiA^|%(5&1f`zv5<$g1u zZy5UCTKkUBy|<U^;e$E?`{oz1IzOzv+$4W<Jk~7MBIdKY%`p16K>CVcjbevHj|sTp z{q)Z&E609^?N#||$+yE-#BOf)hW06Pcb<D_NGyQ3SlMQ&Al!*8b+k|SlhxJ*;mb;} zSFiN0dRy#~zgX$*(a3WCog`!LliW%&JkrO%e`q#&M7um#hu12*?IgNXzmyG<HzG1u zsl-_|-5JJ}SD}bi=HEv@--=<jCyzb}%B5{EjNY`^0t9<)vhiikwLdnV>=Dfy*7Xq* z+YMj*64>iTePENVv*5)WZ}#u_3%0#2zYp%%mMo`7BSOGS)2MV6_Aq*Dor$r<BR`_% z4CwC|y>J)Bp8=~4PE4mIKcgJGJ$=^35J7C@<=R&^?!}}%yYmAm(qD6kbl(IO?vzM9 z0D`?1BI4Z0IZym1sidB|l_qrhz4z3fyS8t~yraA^Q@wFd7)_$X%>nn#6Eil>EIj#r z3EfH5d#_2PMyg7NcMy`?;zumHNZ*>yTTSYI^WEa|i=$V%m*^sOemWE-TngkDr1hnH z5FkdQ=?-`j9w11@tj!*PVca$Qn-Tbe5siOp_!$pLK0daBi$0<H=sP_5Oh)70`NeOB z7B=guQ-Jb~iUly?v%JsKS)}S}hZ|bB``uZ>+<l+pU#}!+nMQ$o584M`^>ey?CH|v6 zw+Cvw!RR}x4*LZIdjEC1%z%^B?1!7}tG&qzjuEENf+v0$!0=%CE00{Trdjs$;c;&W z5e(K+|Gjw$ja$+Vks}3!>R;Y%%dSvy&Ch}}ow{t>f4+;~H8$p9Hu9e+EB_esnN#4p zp7|`u9GY_D;;@x?z4bf@3lUgplfthnn$JLjuo)5Wl^n%%1#ULVIo{~`<CZ<iDm0K% zV*<;Uft>)9F~iX<Z%3X~%!C-drU<R0UhZv{+?sAT3AfKa#x}%)aWhu~tix9IC4{N7 z2lGcy7B5|p@wRn%Y}LyM`+fzx<!mlu-^&rL<r$&V;F_k;?i~SS!f#x?`O!M(&bFN= zv)WVSTMTrk2pBdf<2*O!BOVZI0_1+Hd37sBg7&2cXFFDhuNBgdv3FsaI0=`K=3SS+ z`Ed0c^V$)|S)^FotfW4N?SKBXjuk}eO@H;F-z}$;rS%>9;9o6Al4o)LmCrfEkkMah z3{wkrU37u)31|@gHr>GC&MOgm3ef$%miF-lJ+R2LyYI@%b{X%tGyB&M@A6}Ty|K@| z+p8kXp2k@NgrvRwBpH6z7B`}HjI+#$kptxVeUjOf_fZIa41Sko`aPE*?2p?h6JA=l zUn65<VRv9-kP!VS&Z%^6X!N;s^ubVzf1(}iq&f5023_}SLGDcL<X-!=n#Yf_Gvw=b z?hh~<`7;OxdPe}#0U$l6SZTCGMst9axD?91U`5izknH1G_7|l!>!(K_F;{QX+5U>6 zXXCGInXi1WQP35VZ86b3Y9{VT8TY}q$GlT&W7pEbMC=TMzy_&z1y?=Wrh<;$l6F6C zE_6D6L>X!Oy00+DX!$C4f;I4Y{GZC>m0wAOvRl(RncIa$*86RnNFJZOH3$$#7n0VK zy+_a5=RN>Ga2MKN+-rIRa`Z@)nr~vtR-dgCi+O<&I@-)$?sK^-eMOKZCCM;)f*9>X z?0s-JhVW=ul<Rx^D_-R7WBe<6VT+^a`@}vUqtVZm0MKj3e0kyKxfxBJCFj|)g|JIt z@SD%$2aKi;d#jTnLsv(yXZ;}1e?GVh1u&$6<(%p~pREGXBZb`Fo!<xXn~XJ?l^J(O z&3F*t5w1cwbiT$5m>GVxG}#kY@5X=q;r93Fyb&|>N!v$%_5WS1U%leTuC5-vvdX=? z3KrU={qrpSpMR2ugfx~1&s%c|GIU^wFthHoR%l^%u-mw#Do@z>cR7iA!pSA`&%*t; z&PQUlB}em~tG(ENJo@YXk@3}<d$lPe`aX)L@gNiO!^!#PIJwd2&r%85rEj6}!#QsN zqo_e%GKs68@7Lf`pW<7kZksVPSf4u1saCTdnkcXLKWrLtGV0o)^x$J#l*i(*_a^%j zPzM|vkhoJLG&}>Y>egW9o991Sm^FU-q5H1Z<#WeXt*~^;zfXHXxUZYD9uez+$Pg}W z8O(djGiZ$soAch=<zoHO@tBQX$i6SH-$o%q8}WoeYK1`~UfI<i;8!r=_w_?s0O~L+ zQ~p%qy?0YP2F@O{-8bm;Sk<#>JwEc@bea3khQh387m~-1dNvpBec7KMd3^-`KJ4|a z9E7@8eCjZ5z5(vmP&a!cwLRm0u-RY9>!}aV8<(n{YaLj8^EcQ<_aeo;?8VV&O&v>5 zy|5C!H%}rFfU*%AA)Aqx?$_uREeiPL86xU|D0>v`@H=l2aNJU@05J1Ae@)Gz#v!uE z+_Ifn{!t`UAfh8i6$4x32H8FJtXicVd%g@j0bGJlJ6N=zQob;|NiMelGM-nClUt7a z>8A`L$9pgH*bh63hCm46y_Dlw8etMF<^t#kfu&$W9SoQK-La8{bOrbdH9?<I5V>GU zj{$G;L!<CmLQ3HKhVYpc;~<o^_TI}uca^x>@(ETmB9dZg)I(p-LrXQTyO=$ue&*=~ z9$!XW&omdJPk-@S-Vdd;?Z^wE9^KK={=VrGfPJfzeFLO$qxzETF7<mphqLT9B$d?) zUL63lVhf_mpwg1wNR+qvAZA^-j)GG9f-KCHfw0mFU!BCT$@~W`g4Jyg5?$I)o(p;y zy8Tt*^S#fy<J>-sy(;0lPxEsoK;up6x+Qmx|Gh2HOk6U%DY`pTvX-pc8?o^Gq?VL& zv##$AqK-G`_J3jbr_1-R-DJBQC*7NfDL1ei9*Osc-`?mm3I_1=5agyvyma#>k3iF) zt`T<ivq!tL?xxIw#kl?TVR0+n$Iq{hmM>Mp>{^@7|8zWX$JHz;tJ*eIC8YxiA7a;@ zKI8T&7KYPISy*|OyhHiWZ2OwZp{qKB-kn*;@Y$cAWB|Xj25N2o{S_$-9Ho7GX7vxa zL;h#)Xji4H1XF%At!=*AyX9wf-Z3e&Aw!gZ&gRwn<B0IqZqiYZ|JP@(Lj@kCUsruG zDd#U+V4a3is20)NZ~9s7)~r=skl1{9r?s~S+0~!$?`F{QMYoYyZ8^=x2`|*Iv;b;u zFu1p_&d&4XEhX!sT&`NG!ztP2N4Ng8H04$M$$b0u<w4TsnUBxkY;w}nYgvtp+P@6$ z82y)SaTdU-!h_50>Ejj#H-%bbvJ}6iE9PM>8S%$fV%OC=%Kj-!&WIp*f5RZSM;)sa z;$$GoEz#VGz-iA?I>v2n;2J+6L**VniD>q1tG;}FxvxV-$o|8M$E}3UFZxa>ZgL&L zaV%w#L}=RrqLZUwdZ%TMoM!f00BPL4b9gRrTmNchqpAKY>OI#-htI}-8X-s`CKCI* zTpXwj+v+d6jDuxJ05_b5O!iI0*>kUx!N57m=Fwlpkxj^i3|5Gnri$(Hz|d?v!^jb& zX_@rVh=nM3QQ6UadxgtCWR48W>dsohFV?!$OLOG?j9>U4BMl<h+s?j5T^=3x90AcR z;#;N~0s5C=uJR%YV#29M085>$(n}(v`II&mRI%aJ`a9=8<CQ6U<Xe71I$U^<YlCKq zD&tfV{y)dMC<js0aN`|!CITof=t%MNHa)q(@u(6V(jJJcYcuJWO?=(0zaw()!iZqp z9kUH?dzNL~bO)-b(vxw6scg#8hwY2Xk90?~wd(Sw^UgPPTl>z~;Umwrd7RU<Ij8v) zl~S7*+bKJW8};x8bwR=Ws2JkQGn-LwD>&`{x`SR#I4LoY=4v}^F9OYb|AtIi<$~mB zGAy)2LjLK)*#fc4IwB!gP|u90bd{VKlqbsV<*{&t{*{C;P1{K|b)L>Y(%8%6m`5v) z39**Tme7aD6zC%MMl-_8=T4_?nE^8;t$8h@>`+`=r@CB+>;ZXw647qGwsgZ7AJ}68 z7`5-fI_~|3av<GUXXZ>!kSrI#lUIY*FkN_sgcAX=^YX_AiN~vwjP1-D)wXAj=kE02 zf4LGy2e-8gQlj@4oOy31Jn{_ZXS<Ngn`&Z{mPBJ_zkU4O?b76}ekZCNC3E%SiNWfx zQteJmp1nSktPZWruzV-p+@S-vws}8fl&{!AfhDmk4t=<Dp{xIJpmEnpS-)fXcfQCI z0g4h3+iRaOkLK$xVm&(UZjU!tv(Ntb#BQswodXYRAB36(-J5+&*EJY9s<SO_Yb?|5 zZ(qH`WyIUR&at<QnT94#&F^e^Ih$)aUlVs}b|iXW?TFq83YcP;qLNcss!Fj|hC$m_ zftOO!0Vgc}&d^%Ogl3P@LT14+t2wiPI0tWeCoo0JU#ZSzAh%rRLHd@M-7==Af~kL2 zO>%9tPE7ik?X>tpv^hvI0^}L+fJ@xRNwrDFl_$Gw>zZcn_-1!m6dc|?adyVa?Y(Oc z=t#zm5%j9|7f%&CS;x%~n5Lr2Jx9U3T!H*IBev4`tA(|5>9JR~%QB|6B*@-!`#p~c ziDfp4$S@Q3=?wedv+<l<l-=)?EyX<9MwVaYuEx}Yb4A~;yFOQ5+Pz@l`Xjz?KA{6O z)~PYd_rLA?Fw9y?*!zk55QTmDD$C4Kdn|R*wQzTh{{~WdJ=2M#y?<)_PjbjQOk3|P z8DTx~&9+peZF-A`ZvMh3^hB!XR6Ue;S9X8nc=gABzlS<1<Hs)C!u)$b3u1_sqp2V> z;pV?7Ss$hQIZ|U;p*yJVvv=z0h(Fi-M-10@23FW)KB*#MUcGqQF|V+F5Ug!+xyqHw zK$h+>Gg$37wQJd6Q$ZLYqv>#UXZu$J;s;j*Fo-M|R(QSpaL0%}&UeGt{Lb|=ANHB~ zeA#kQYW3fF9Hw?X*r@gA4r8!ql@ys#8UM{7LmIo0R-m00yxuM!Oed*Y5smNA8jcqq zXSMZrSGuA}yi81}k@bx5HX`xM9cQmc9Sw?m`+ja*uCG7d$uNkVi5mrYWuD=8;1_)* zI$8FHz*A!W8kl!kTSe}&zV}Vlqe%I`Hb5^*estqw7f>BHA0?bIQZJkZ0XHPN-K~34 zXKJ)wocn>60QF<)P9%f><Ut86GR68swY=sFpz6}ZXn?Vsck*-$Ot(B)^C>6^B{G)r z)uNeiZ&*p)#HDy0gaLSz^4L=DYZktxEN5LdW8FxHM{N2jj!UCnqyOVgPKE09$<#<> z?ya=Uoz$&lV8#0SqswwFhS)UyU$Ybo@8l07_iBLf-<9{zTfECZc(N9X{1lS)$EFf> zl#sW_&$b{W_(sj!r4B4-UTtokreq*D8u*V7>DBbGcDVu)mWwItR4-*<xQo}y8PQB` zEAZ~;2Xid>ljiGo<(_G6W|i^oOwx3^*7Q8ocX2G>p1$rW*pZ4xJW*Djp==N|uFKti zYt^m|q(0Y<K7v#L(;UJUwa4ZKm@n!KTkN)7I_HyB1S!=q#w%T^a$plIhj65pfo&vy z*zC~PoSxUY1UGTID0_u-*@98A?pMF(i$4F{j{g7|380V`u+$;$2)S3Qn=0>ONaW3{ zoHUX<X=<|}v5S4LO%KL`>~K3%Mxbks)pDX2!`H`TQ1gtRwevsy%H)=Zhgy;qJtdk} z9A(x*Vr{2(n-BFMY<#M3f5Rl<s2KGh?sh+bj5Ql*L;|;LgGBAST>P~EdhqtQkLW*< zy6h#>zYZD7teI9VXuA>T&x2%N)BSzQC@l;PdY5v`yiR$$h9;aJyJ%VzBw}+)$1dta z%?X0{3Xdqr|0rHAjMdT4am8=r#*B3e=9M2Y;?D>=G<zK^hBa%Mre%3se&iW!1|%!| z$}>)s)AE@|UOy}6Lu`u#>8%4mEkncLpCmp}Wr3k}S6_Jt$=pK!YL`(j<(+<ZhF6zA znlDzcOWi`p)oBL}WGl26gVfhX)tf5pZe4UJn#c6da|L*O$z|ui4jacTYQ1QG<AT@k zl9!zVENL}Sjq`5hpa2<t-5ZQ2KIhD4?`!r)=B%ByY&}<|GNN>lfZia~Z{QI9(9RzJ z0SSS6l%ZD2@jR-Jeo<x5<fR6H0uS16EjjG|^{`=EmP(|tJ9J%h_g=NU<fwIuT4TG} zUZ~;6aqX#gN13;F_mamP#>eI$pU%TFW**oyi0xmccGe>06(<Qx2E@&Rc2$$p>K6J- z^0_ufUFzU=?G~!mo~SLq?EMQ1{7+aavrk=rJukN)sA7Wj8X0np!x}MV*y(nycPIcC z)m_dcjS|h}^^eWSXADWD9q(*?9xE*okXFRdSdh&BP;@5#O#crY|1h?(+2)>mb6+t> z?)x0MkCId~N60bv5!xIZLayX2Ly{<0Qc>m{MHEs=?&~W_7gBzH|G~ER9-qhK^LoEt z&u2Tv-^<Egl6FdNSUl9*vQ!>^2=MaMwjmaTJ}ijtwu|jf!eW0ovOH3Ku^{>YyUCX; zUP0$_VMsh(M6b`I>rCC%7sPr@<1L)zJDjoGcdCMeEtRn53<p)0Z{hRDoAD~-m>Z5S zME@tNy@k1$!-D3AOBxN!C{}NcHi~c+i?BF@*TkEz%v&r$%@y>>BgY+cgH^byS3c9! z`Qaiy6>D+?yWw);1}~^Zs;U8tC=hk)^Y2lU8-K0TVv(k!!u5}AUej|{G{+*$-=L;W zuz7(u3M;nm8>!<hxNLfc?#-Xa5SwKYt73?6dGi-AM6&!*epp0qw6~A|P{bO%W3ynv zKnN5H<+^e4SjC|Sy;U|m9aB667sm=DMOZ0DyvwOwJo&$%Ks^Qy_I|kuKzr8C^xRc{ zu<ZKTU98t$j7T3QvLLHWFC4jxWt<iprv!Xwh^x@WpPJ4bPVRBC00oSB;f|o_Nz8~h zcTR+`1)VFHfxliP<dqrH%E*b~)#5Z$2#qxRCoj1O;_U^H<MWUXyV4I16B*fOBK(Ao zc6-EUA_YAe$l11l%wGZ5eg&Li5gTI!QdD?&7I`epBmp{vcagjCSHwP#)ga4{R)!Pu z(OFlD_^K(-7{=v{jBt^yDEcw%qFGh@)PtvVQAN|9I*WF3*8E;f`XCKiGH-CUK0(r2 z+!7>GfE5}G5j0xhDZtLgEs!`KlctXA!t@Y>=})3`X-U>A{49VdOJw(NIV8_?`?UPC z4z8^QJoXWYPC+j-LiBzGYV%Z%^|Jl+7uu}y6iqpEfPp8QAO@|MTeJNC^!l*c+3NI( z?_wf7P2=Oe(Y1n(P(d+ikCe<}^f=um{Ku7(ajE>ucb;O!d#pB}UK20z=0DoP2#WIp zdfvh}ixfu%lAT$px@w{yD3&X%fX*QJd+dpO7`07;TL1PLD;3oexYZSb)6v+>c+-S< z?@R@T*sb3IT-phAtd#CvR*Mef^irzLLcL3H$SVy0xVLa#5h$cqXw!72fKA@(9k!rW zYN0o&Hz<gY*uH(8HzV+7B0Ez668E#3{Q0DW8x}F^jV|*@5GxT>VM(|%6Obt&G`AoE z|Fuc}#?gw#r0zPp+KO&6c(YyN^cK*vr^V`6;3Zh)Voh6xcrDwV;=y#e-OJc5v{4Wx zbjaH1EGd25M09E5ux^=;WXiwgoq1Cye`0|rnGrAcKERX`*lmhA(x=SvnUx(omNnw7 z4RypV778~^`SeWrROsmT453xK&5VU?i_<z|M5kCRs`%yL;HJhMYqzhxe8m{9Wdd%M zkmv=gwzz>@?>#<PzC0E&w*_(08A?8-B!7WN_-xj7Eurxe7|R<JK<Lxjs(vg8C^vB% z(aXe8(2t$QmH&w-I;TBTva!SpZxMuwj+5rI?irMjgDtOyGg7}AB~$8)yN*|UjHK;% zN{{$di3?m0dib`NN*(??GoQyB!(pXLsmk|8|5y;<iKpL9pzlw`--+YjTo6GBV9d>= zQKncv3b!czis=D#$h-FHTb;aAr=fQ@o~jDBnTwUMz>n}V6%S3#J<jk(3QJ|zh{8L3 zzv6ERu^Rm&po)9=RsoK2GJiYacC4LASs+4vjqfy;{>Q!K+Iw*-J@2lkV6}(XX;ZO7 zwZ?Y|k23GWOTRi+UUSNskgqZ2>jA^46rn-jM)zgmC|jvBW>p^;O<2~9bx7`XB-X^e zm^+iVVjhX3z%r`X`MLZ#xrDYb_XW!Yw@mp9Sj6JI`F9D3T{4dYgCaH@Fu@`|OX1sO zh-#gop1tz?ET_g*jT4%8L?0~hD=NiVl#1uE0OJ&)b+UMosk`1n_YjNi86g?gD^l`q z6?fA3JA-Ktm%0AUyY}4`y}4ncXxh;7f%0X6?<kZZE{{bXBbwa~`F7`d<QM4C-eS$p z&o`b8h8RTWRuiih3SmFdyV#zEg(CNK@oI`Upe7$t)+w|2eUgJ$xRFOu%I~2CqTZzS zC7EAmfzw5G$%w*((!F0kBbLW__SIzIs_DSFh5qk=P*yRz**iS!U~naI?4}iQk-=lE z%U8`JUWG+q*x-w%anF^+&58#z%|aWBl6|9vR!g36XCms!|8^Wyw)>2gO<@nn$S9Vs z7QKGhS$;Ru0b>?^Bkbro?CAHZ_<R<TX_nLE@-c72>2g?3FI~K6HL@-5^^5t$p9wa1 z>Ec`PVMn3?ctDsn*lf&V<m)1`qH6Id;}vRu-t|iglG*c8NU#0jUja8dKfaPDnf}ss zw(C1#bZNn6$!mJT@RP#ISZvp`b|J-eiufW%$X2(mRMYIsvkQj`qVvp3T_07K7?Z7d z6xjQA4#jI{K94AiOg4S?u&iW)MbL{eso*{NY<BWoBKqIX>{R!X;VnyWy?EBHllcN@ z>Ad&S0=zmb<Q3?$Nq=((U9{fRkfb9m_E+V?0_Ph7s(o2VMT%>-hM!4Zcwx|AT5`^7 zf$w=GkLLn!@jt=c9z-yeFO5G(=igF`(SMhhboyUTck9G;oQ-1>60BQrzU$4+@#nUg zuK^nr`%y?#>2TGaQSY-*y4s6ALa_0o|M6{^(65zd3MQZnO!;?v#N4_*o-^%QBMdXy zqq5UZz|a3Db9MKec~^$Z!Y_p_g?s@fM*LN>OUUp*#*)jn-AO!);IIr=Fj&3h-tmuW zH;#!+=&*Fel3ssYKT4(-QU+dEY$$m1S3TeUwdkNrN7rUU6^!?9T$D%bRs`%#KZ7Zz zUJ@?AA~Fu)B^2}~MU*(8X!%*I;`W2d%;;h+x6(}BA`=AES0iRYXs}XH9y^ee-0*23 zudj*!IJbTJ_mv|92@uhBlt|(UsR4xxoyWN;fPy$z^kwoXd3I%})ePo{>L(mR)oYpg z(x=J{GS%;l+)zIEH1UW-qwZCy=H(AvnURtf02fP|zBT;ABl^3!Xdc_5ThCO#KB)8t zpAhdq_JiowmVNh`BDwbE!`|h-rC%6)v$K#kykKHiK~#wMv3c3*(H&Dc@-~Y{ri+>P zZS&=SUvV$u<5)UxJf8Y=`Z8n@J9Sw|&P7kgzdKvEZFRIl|H?nOUi<n)?Wq@Oc!bHb zn6>_B{n#Az#O3j7(?a|9v$rn)=vj|{oICrt=}gn{RnyqVj<}K?<^SB}nm$kf;(6y@ zj?wRa$$WoIe{Q%DUi8iW{d+BV=HBVYZjXXi<Q!$%bJW;3`Gp*NLlCjzM@Ryh6@e#E zz~UK%l*;_bT-Aq~OGoy)UrgR|7+B=+IBNFW^?f|KvrM-!xU}w!)L(U*;y-=I^0=C~ znCOZCZuF-Ni&oh63!IDaVzEP4pi^JTBv)1o%G^HmyG2NTqLF=JxPJHLiO8J@AJ3f1 zN1w2x?Qglx6e~deONhBP{-yr6GV93y+%-lduEN#vs-yiHwzO)^w@9`AadS7L`*FKt zLJZ~-mj#^rl4zh}tGt7*u?^Kp%>BVYrl^BK;o$W(Y>l8|yi>ugi`CSTdlK87W>l3Q z_Sz`98#~{;e1C@z6U#d0vMxV(x;=9FA)S6YSG5H&Z&a;=?;e*yEeeNEuC>=-Y39!6 zOzF{aQ)`2%w6{lGy4>z7h2e@RU=??2a^#rqgE6|qoy18qcBRtRh^+b-jlae8$`LW* zdhxHqvy>8{(qh0*Z<isJy{UBT?0@@fm-{uaE*bp-7qi0$g&+0@=+~Ako?>D_yr(2; zx?1fG-?!Ju-8SDZg{Y5=hvyi4N-SJFJ)c|Gc2kGeX0Jc6<6X=s*`cSayAe{rauw^< zUvYgi;Ul8)jn%dFsrPQuRARYYos%kdSb8GC;fowM=aQd<e++%W6+0{av(3Ib;^R}- z)Q5o7F0-zGms9Hto7k7&{(iM=gQzaa*Jg&l;jTgQhGXu!pW3BzPkMSWqI%x|k~Go2 zR}*KH;%94)Y(*RDBSua<ZtQ*doLLdUA=9@LK4J-3Y9aX+awW&^hzJp(KumorC!h{x zB})##kV!u{TTlEgfwPRyW29*CR@KBpGg|}YB`r6N_lXoc<FY8p*IFMMPvo9i9XviG zsYh>ls=v4Gz14`6&z87Ic0iO=^(&A}VP5N!LU#%0)n^$!zVKDS&Q3PHR*h`EWfn03 z-5IQo+RZ0FBvF&{L)vL?3pYRI#0^Jg$htxM&?6+O%oB0lhHqKh-$t)UY79u=u{i<X zGQ~$b2L%hhUH2TPCvD9S>W+M~2otrvbhL3+`zbazq$pK55|geLLx;P19V1Ygpc4fY zE9g<RB;u~g5-2Pme%_0S_V4S%spLbh00084Q8qEndVlU`3f~9xka@kedG?83Y(@za z#>+8`_g@jqDDovcMfUl@iL@jUAsn7X$9Y^<_+1rP?G+lyZJ#P?9}GTOM&XJeZTO#8 zK-laI@r;C|V|6|b>K1=P`#_iYojOxg<o8UppY~Dsg0D-Ad&8gp=oO4)!T`2v0nsTr z?{0m(%%Zc<sSDZM*{Hj^uQSJTzF6q2jnDm>+b|>mi=4d}sw}kS`Nd@x@xN8(Cl)C= zrv0p>Fh#1ek|1}HW*>HDe30Ls_~M`?1AB2}P+gJ2;pE%P5g7M+>jU%+xMTZBU}$zg z9mtTdb4%fQr;NToo6cdXB83{&p`8i3F;=k|b=Tm_Jv*=EvY38iq2yBSZ(#nKv6naR zbCi|F+&Bazxg-%aV_{rxIw{tB552)@t-F3kG$V(tViy3;j&hP)Z$&p9$HkT%z48Lx zV9~CgUWLhguv|7x@V8F7(Ka3F9(BTSU58zP_z0IKlt-A<MJF9L;{tzG^T^n7jVW%p zYBZ$?lzwTvWc*)gMB*c7Aa8K!=^3|L>K2mNa~G$nrflbiy&hGSqS?xQEp|5qRX5|Z zLSzFX^32;6O<DQuBxf@-Iz)T@9%#$9XZhCmsfOXqm5Ma8dv=KY>qo%UMF+~8^e-tq zzQ<$Ye^BOm0HYqI3zggS7F|pcu)kTwlw7;^`Ec`$%)38eo%#vLbB@l!9@1OP@(#6I zh9B_XImU_-vW(a|3!ei$Eky3?(NR*Jb>4hqPg!!KQ6QmpCz{?k1+J=teMT1ISFO8} z#i-~Nl;_9FG*S_pX-!5CJ;St>oU<8p(hHx4hvr=v8XmxKTZFb2-fo;-5pED0DzN%2 z+xo#6=&|SQK**@HK%gLV#8q6nrk(dB>vc2XH5`pps9&~Hwi7XmryAM?6Qh=wxb&*n zR67J3Tuo~FZ_ZoN9Y5$lJ??kK2WM+dT+x(h6EwcjJb0wjrFd!HEdFi9cKh9<wn9?L zFQh&jxR|nF?y6$}?>p#&$K^u^@}>y(e<0EMaqZ_UWZzV%x^@BV(re9|PrOP|>KT+Z z-`HLbuyWMJU#(fZH6DURWGd#0sbDh;AXdDddV^C|OC*!z4Z*Un_8)ApMw_8h<S#w_ z%oP^Cy(}^X>>%7jHaS5)D8G*8Vta0??J|Rg`UjG;V}Z;GN52EsQ-eBhn9+iL7WsZd zPqtFHvRzZ94u>=7aS^$(DD$WBR<z-t%217Zknlm*HO0^cMC^Rc!;5HkBJU@dIxsH? zdAoXpRV_4K0gfDKuDDqj!Oc8tv2jYy;my6H&L2^7eb{P~G_0`D*T&0Y1?S0TC|@95 zhL45QSZ5oa`(K_A^SA-!p${ZGv8@bOeHr<aFf*JyD}nO<a+Ya^e>%>NsqK+HubslZ zh@$mL{DX$?nTZ}d&ijX009TTw$a7LW(C^I&pi=m9fdqL`(;p_dLqPz=HVL7C?_K)4 znYwd;sl`B@P=D92lhdT;t2jMo4z9u}*_nK=KRrKo#G~$cFO?69a4XU@sSTHtQX8iQ zw9*y&^Vme*FNoRB^!*$lBx&Dx?@_PyNE6IL4nh}54VOZdBAmEGNHtAjFXk-J>fi2n zoqdkL4(W7pM=(j3WMheOR75}F2<bC~eB6WFBOsY%r1~W!ZvbpR4{~b<K1hJ46d@b( zz}bE>dDG|#Z#d9Qx#;UsNJqW8n@Gn(Pqc>uq>Cr;si^2ERY`<j^wpDlN*8+*%^ukx z=s^O`{zlSZ_j%YcCDg_#>56X>^f$zSPaV+`hTs-e<#FbBMy~b504R3x3B=#L(+v~I zFBs&1J1D`0Q!^$+aLFYm2?_OuxuQ79(Z~n9lx+f1{Vr!m6|#Lt?<on|VkWo=0Ny}~ z9vJwspwi3(E1*hfOu^@I2>G;7gA86Wz*#+yqVyP)K(kJ=0kZ&H50zCjA^E`D)54vb zU5ndN2SnUC;^?0TKbsCCRRuK+2Hm0h)#xD3hi4+bA-r_BbDOzSs-U-L4D6=ylO~AO zd0tmj#6vn_)}1H|M*hl!KPDlMZ-VJ$q+v7XZxV737x}v?=YRm~=t2G>Bg1Q9T~)B# zD5YZvWV;E6;X7+dCdU{{CQL(U1whP?OO!-sspoS5PM{$&1hSF0^-gjP$MtL)5&AQ) z(wTpGo@)x@6i^p-0EQe{1$pB@$JtG}3448qUyBF9s@~JJ^KuJdQ4on2WFgBkdA`nb zoo_{bYDP=~Cuiyrzp7xJ^JE$w`Lz?g6bCyX!CL20t@E^)IvSEqu`dr^gcE!|e}uT( z>;m~7k~;t?T0nJU0$<`dyT=i$WLH65Ug|tYsKQPAHPkQdo43PNE`%rJhDn30$$Z@4 zI0B>`@ScOfiSua-kmNgcVdhha7ii;{wp6KnkdjmB4IA!n1lOA@T=P2!CV|K#TZLm_ z4JNR53~V+d_ue?Tx*7SW2ie+;e1d`fZbm+sC%f;H&8o!*P(s5bWFr|u*biAhsYTnd zd}kFn$Lhw2yD3l4K9&-`wy6Ymz*8GSZr=Fo=%l*Sgn8?rjA4kM6YP>nkR>zCGQd00 z!n@vzbBf?vrlrm2e0p~r>Gu;Ez<*2tlf00wvNA3>4A34F7VV*q%9}TGIsxDb>9{F} ze7IkQ^epc{MQ)Q}vcEW9km1Qau$Rs7pR8gBGu8wftq~!i5|r-+N+oXMI6+NS(z|(K zoMST&iE9u_*yrqX;eJE7Y_7u{W&*Jx2a$FviBA5Ooh7&p!&)5ll?=}Z9QOyz9bQT} zkQaWsfosMj+`WZsk%ag;4{6`Y{Y`)^>qNHhpE<^M{2{;)bmS9&&f{7B8&mgT9r30Z z()|QZ{Uu5x3H;2rCk)&3PUv%La7>%zjRn?7Ivb<`z|f9?$K!g)dpK2xyIAj@>OzzO z3u0;<QZ7w!TbDIza4X9z_y>lQFyQ%{*Pt}dhDS$Xt1%iF?(i@_e)-)KFb3)i3Nere z??gqy@wuNmk%5Zktv$$!8?Yzy$bZd^ZBLN?4afrmveStuLxtZbNo<;gY!cvqnHgEk z>j&RN{odQxk~zMO-?@3?p4>z=!W)`3{(!!IOzVS-YChCtxx|w%ye622pDM61sU?!Z zJp{-F0I>2*f<gcrRPyvqw!Syo0al#P$Nh6yxesr0@7@R$Q}X+~BmAEeyjnLpwxnnU zUH(=PcKIo?IS&?sWB<2P^>Cx{A1U{D9{hl8wNHwe_2hV2g;1+O%uvCSwiSwx;AsgV zMV5KA+Lry1dM8*`h5VzF&Zia$h@ZG4w`VcRkAFdIFkli2e03ZGeP*3u6ZGz8$-NH0 z(}OmDPP=+oaAyVGe|(_xW(E-rE<;+t4heO?=Q-`~)%|NmroC*eux`^lRo-V?_nUNg zxEMK%f=-X$5Em9o7Jgu@k9t_pzN(0SX2N+f8lmI*2*U#9oq*oC|MdQ!D7SFQFY~Y@ zLXw5vGlB>^_Z4=B`J~6P%>iHt;ZJjDL|C#0XAc1p9GK^LM%3`F<d;0Iqy^MhCQ|NH zE`aN9+dw*<?QEXsRQ*$y1uK`khJ;F2?UAg0n-B%rBQv6<elRj5XA~m=0QhmeXc`vc zf3xxai`dMEf365~FIWt@q*?AAJ+r}qXyXv$X6t*LaKfqD7pI;rJifdWrTh~>Xe#g& zedm9D%nGft-XSAeO<;YT6)ArjKYwhzm<I#$IR62F$}8lPDkKb_dq6^m`{u5eK!%-= zahmP<Gq5<ab1wKru;~K?)@*6je($^czmMEM2Yelr2MYCqg)SqiA2rl8l-QuyiSul3 z<IjkB4c&hp1>X;{@N}Ddd%0i!l0ZIJ!FT^~1FxDDeoP0V7L};<juPpa`x^s0Aa`e; zYkOG+qdRpn%V2Mxk&&C6tvJdRj~l~e#9kFFe!i(7TC+?^EAe=Ry!s>`>f7~H%Ta$I z%7h~em+IO$Qn>kai*UqwDvynDzxjneh=hR{_oN*!&>A?CGd8kn1q!TI3~7WG=BdX| zYc;-@aNQ@v_X!!B^FwPok?;~&^G-M5)H%A@tL)YJ`COyg;ZO_5F#jgvu@iB%96=?8 zNP6@?kQDPj`y$$zBRz$2-;Ue1c;wfsz>*Q}pYw$U_g?dQ8{>Mz8rhQ(a6lIas@nmn zjrTnDA|ys7wO^~%Th>k`A%>$f-;-ZmFyo&G&ht7GUyO7PHzOYdu(WHv3OU_~{O)Gm zat)=vLjZ{PpigBXH4|Wa<4Bql$FPvl4HA?rT>LX1e9?_t-JRnZ*?9l*>p}E*6+YX! zo4a~S{;KPd|IFQ&tmj^O9}o1Z{5Y;8(e5?$TqAM+?ZCdh%>TqI6h0K8?Abez_|t^* z=`lMt%ZePG`xt1-{MefIUt`fbaCp`z%CqqaId?gjUUd(#M}qBFaZNQ(+RQ$0svd@F za9{Tjd)EP@?YIN>Q}m`pRml&Im*iLS%q;^rTV6f0F#$!8z@|?j-H9c>VlNvL2K%am zl0g=W7*P((J3p5uE|?)aYq^q~Yk09`zfA7Ri?k&-jjC=TAK=)T!gQsrsurR0+~BwB z)-YLrB<`;8Tr-@8x?l+}4q!18XlXZ{MunXH@a@Fs5jjs|#<_RD)1b5@uqeC#4yRfk zTjS58Bx2*|pvy_bFWPg3H8rP3{>lx7cjbR2DDE_eAXrR!_h@@nNR^MHpI^Qi<%EUw z^me>&ZPsmrCBT*%X+^Kv_IJ+olMzi5h-W?e`6U9Srz$Ei3Xv@rZYy870o?h1V%dEA z%IUw7&ChJGPnzpvk~GMWKmZOr|J*X$%o{TAR5CrZ>z@9m-|b-j&)S`pDp=J9YUaR1 z4dQXwvoO~<I_f$400jw|uLAPka0~Y#%HW@JtYj|1kR`~ed9L@(h-W)(d)%<ni1)$V zVwI=33)n~Oass&=mJ1y=4t}1PB6(sr8a7MWJjoy{VGx(d%ln2a2zo=EQIh4<<tfaO zAK$mZix2W|ad0N2-P<;SEe9hznpcCz8eeVpHq4{c;IO%XMWt+5rdZ^5J#5&j=@$<E z6Jz;$20;PLWTQ2|mM>Xv`Pk?O=HoeU^vG15-&k_kE{#@!J97;*+dL@yY!P%>6JW2M z2g?E-jolyEMG1{7VS!!*)6?=X3P@3|Gu#V>K8W7e*@zy!u>%ZD;=!mw)0-KC_{%15 zXDU9yHgi5T<w&0){;EReU*lTc;hJkkA^hg{T3{3T>m^kewsIm@y5U0S3s)SzpA6d; zUow2WYCZ*d^`H_0pg`)Fmo?ix_YdH{O(fNQn>Rfx!QVF{x(a{xyy9cw0`iX5wEq@m zCN3fy-u%IF!(a3Y7_U8<=e+7p2db=ND=(>tM>0{!PwGQCM6Odg5+%<BzBFFg@hUdD zAV?RHDhT~fQQcEx%Wl2`?dN&bxz|i0gC7NRs$o{{e`)UiNIHHQCpH^?mf~8AK#Y#F zvmEKXPA3kZCkyC}Jtn|NL2H^^cOM=*cbfG+F&83L$~Ck9>m<=-!Cd*}i_9H_$w}k? z$XtOY0(!Yixl_A>+-G5~9Ixm79Srv-RR4}INeo>x|8K0Jfvd&a1cXom11ileqVs3F zuhn57=Fy)?CR~lVjN7U^?hLLuCu9vS8u}I0Q?><<gJr_sYQRwcejR;z$!@}LoDA?u zE?bjsE1&zl^`r(0+|-X2nz+{nAxO3-EcB=IDvbF)j(K+Y!*lR1k8FvWU+;45_^N$+ zchshr73W*s2u}M&Y0t@Z=UST^Dt;d(H(cwT?>OA?oZ576Jo_kg<-^o}XPUhSa%Ij< zE4vg<b#Y~}zjEVo1?B->P*0J9nkG|vK?IbG)*=0yOb20x`CWSs@ZVQ1qZBR%btkpG zZ@ktOEMt?P4<Srh0h_^+r?e*K480D0znC+hdOx7J0-Y*4*G>Xw0iKZpd<$_sXLEPq znIBT9CFV1;)F<?f^poSZM??dNuxjT((>bC4L225dlF}Lv(>waH75`&n>fxo&bAPYw zeOq~b_o77i@Ole)pH*Py%lUG<;hJn2|C!W>hW`NS18JZJ*6h)saH%q8>@2M!0xvwG z{z?;esXXTN6C2IwaR$3Y>=wgPBFQ(9d2;&L)F_ZDT;P}E<@whBwpS?Ql4Mo^!%r$| zoFXd$gbojh2h5$d7F}gh9!M9q+i+aJuoJiOw4}Z-?OAot$3P*63pQg$ns41A?X^Be zeYe+HDvETVS4eG${uMX`AzWA0SFS$;QzWyG-!7`z8Nz(255Y(c_6p>)Z~m=enr!o; zh{yYb(xk3?wD!a-H>emeJ0UZ0#g}0%kR%>dfAY+sbG`df5}}k>{0<cqew**gfQ(Si zB*m)o+};ATG)BeE!8W2IvZFkrc%l`d@~qM4na5M!$eXq!+z{aVI$x|;#LJVvy`tW_ zpYgiHf`(Lt&%AME^zL{z7f9htu@J(q3@pbH>t!6y^@8r*$_VKuUNQ;S-B_OA%d%FH zXrhqcpFM9=rx`2xW=$aJ!ksVIQZE#RXwB?Bp;@1^i(Gp*p5ku3BJ-EICK}cy6S!7s z|Dk=sPqEaT9;8+(buMH8{uEvHoF06>zNR=KsNsIc!KPNF62v_40GDoj#K-pIfpZsG zDobd7rY2o_{eV|ht-sR@p@XM`7w!s$mh`>CAJmB*`Q~x(YnI!c3wKX8i{Zw)`(K$5 z03u2)PXnh1zYOtx(^c!_S=f*-P0XYFRmy!?-j6EiI&rtse04sp@IRgKK!rO`LWV>d zBi|*(&RzNa_xHWZ(@@c%1JZqC<3C$Sv_mpZh9(5$($kIhXA4!;{y~?J&sYLtL<>F) zPi};jyj>xV<24Zyo;y$E!UZ4&1N>+FuLMW{(>=!Du8>@(#IFRX2vxkq8_m)cL8}Y? zb0+6Ov8$Sqd40lx<0&x&Yu?Q*Gb|ofSVC;cHg{S&H!qCcv5Pa~t8+?M^2NH2I3v;% zmqdFo?6|$QyUz|e(3}kxf_o_)paB9hF8<Wftnd$-v3wfeln(86e{5+;hL7lSy|qSO zc*}Udvczx?7t^;zSm5Vt4BK$J@ia;|5g=P0;4M{LSWFVvt2G&%2($4PY2U6I@qz?w z+u@$INk<JjalTJ<kDU3=n-wYSmQ@mCmUX_UPZWq-fSrr8vGaE+EMKlIw{yu2spu0N z1by`C2LlQ03!I6R3q1d(Zg+Ah<2c_qYJ3Qnd!F7W@@db_+QNs|yD7!`TI4_wSd!hn zf|v~ifB-Z4^|K0T+AMa1hR^`%VAPtp5QmrHNWMn5?l@&}kE(TSeY(Iza7CJ!AA4!| zaG%%=Uak)u6F<2W((f1kS-xca_h{ddtS2M-@}9Nw@;nUK8ZSDssaAN9r)9N*0Vl_w z;`R{|yx5h($FDfFC;MH&cShQcxi@7v8xF%Ed?g-~q$q~6kR|RAxrW9^%}9O7L@0-Z z<(rKB;&%1eWplAwo6|aqG7hyt>!RKDY(OzL%q5Q~^ewnnDz)QUOo{nzmX)A0-3RW? zyJMmYd0>V4p4<O={DPC7UXy69ss~##*s@bT{`>`k16y|`20F8KjT1z3)>8yze?pB6 z2CsYBQG78q8DcY4H1{Wx*nfrTd0X6~w>TkU!%jE+qbJ~D2_WMIC%lWJwr9w(g6n;? zqVugyH$-o-jKKn%_-0GaQF^-j<7X=&VM+S8CtR#VcQNUrd?{UzKi#3*;8+Fb$E%EG z=xnk~1~*q>n(53qU#bVyufRMvG|@+Fyt6vbj<bhvqfa1yCWU)D&+hk~YOWwCIN{>v zi((e1dYKPUEsL6KY0yjcJwdcKTMy5-K>^Z>8PnKe2D4tLRj_7!P^atB)MtN>K9N-t zjjrAsT6Dwl*otyteWjQx&dPae4|aQ}fQ_%e>c&-W^A0jL=M20T_P5^JVA1({Og~8Q z%Xcmn5<O3~-;}>$oZT)gKkJZP3jez~{ra1L>wkC8^kD5XPC{t#ShuBODFsf<=;074 z@w;flsEsO6RjB>!NN6lFCbD9vme+x=@0|1x((S*8mrQ6=21dM)ZB$uF|DhjE*N(_@ zIx$^3iv?|?;{*dx-MD1}2PXw2+lylJ$y<#6*=~Mg7{e|+KF`;#Ghk>!&Gs3WL<EyS zKmY~h2>?Q}Z-y*=WeHa_<0Xt;AO`Bh>%QdWa+i@4DK<P~;d=Kq5MYzwz)NeD{X{`p zGZ?NW8bG3z7ec7E>HVW--}Ay;Ki7j#g1K)V!^tkxyWx3`)i@em*w8QqJD%B|4nqqp z1av*cEW$*d5=lYQOPPkE$w<AKe$F2`RDC|4p+snOTL&Oukm3`}`vnU8k#U)Co<M}` zod`R!jMr+f;hKx+dhp1hB}k??9MM$pXI6hLp3_F;hT-qSf@G0Q`EGyn$ABzNsw0-i zD4fHXEybC*&I@=F($SLxd=(zO8Xn%+7iVfL#8?2e<L;dPjIa3EI0WEl9eRT?&t3Ph zte;%C=qqI*8LR62YWYEKB-v+NFZS2#{LRJ!Cn=O`KCV=Y6S%t{ykd4YaYaoizW3a} zpwzG@MGek5roMuJw%gN)qn?|F`9z+(%vA0b;>}Y-CI|<BEK)X~Dm&?krQ@GT1189X zfPFs^rHvC&;T4JPAdxCph}!8o^_I&Ok(4%wPN=pSyY@%f6WUG7&XSw&sJ9<2(T=`= z{r<RBl1}Y>c$fI+(^2x??V+=)Iwd~2*WL+$Y;j3d2i0I+ngKr52nTPtFW>bcwe2HY zzF9#wn!ohDGJppc*isV!^}uynaGq56HKP-6GkQ!Rk)4&Hd0A}#35EBdF5}psS2#I* z6oXJFjIJ3ARhTve>Ixr<6`~;%o{)<f?1<j`Mw#Wtc~qsmcH{TFYH{r5Gmxv$()A~- z`Z(6u@l4`;I=DYm5?k<!2S==j!~@iXnMPl9hW<##wQnX*+Gwf!)SVA}AXm<9UOA9R zW{5oGI0P@w&@ilRGc0OTW3agdNJgM;i6~o`8(3I$W$M#k1ns59x@PnrdE^BxwLeNg zC8U=3)=MN+v3o&9jqBmT01y-a4h{gj7!0_$(M|!CITH|C8!bT|?Axg<WeQo!d#02{ zJC}uR+AG$r=nK`MnR_tmoXWn=bQnqYTX<Rd2M<QJNq@!C!qJe`09u!D+C<;|wBEsE z80XmpkvlJMJ@eqxg{Bzer97L{WymR$&6yOZnmli4n#sLWooN#H!0~yIKzUk%6T}Gv z4j@yV_uz3rYa~?lJK3s%&=GK06Oc%!vH;~i46Tou=K=bK&O5d#*h^dZ>xXzQ9|4kg zRdj&1bvFCOjN_*+HLM=uS|!5%1V%1xx8Y4Sg@S~1(*7RFQ_mcK$!48&l1?Ie1Q50@ zv8`FY3`yGJ)8?b4#$!3vv_nuT;3fP6oi?L_g7tZ}aw)6Ys<!yWwDarmbSHeC!Krq; zm&s;gyJsu?O{#mw!Ik%@9?<M9oBK}!P<DH%5t{6#m~=ARE9bboeonOBU~2Y`>cAn} zxe;)v6Jio8r`=e@?eaM659bXjj))nmdDWAw*<$m0+OX@XH_G;JgRz$ai(i<QL_)j5 zbuwcz*iCF$6ZT;SsBF{qQvi@glm`c_+nb|AS$VizoFOVB4Hxakcq@4P4mnpeaYdbd zUw8V965EX2%50h7`v&&gTMl2BD|LO%o8l2gM;_Ez7<#MVnkhLIL%3$NlQx$|JtGfx zB2!ODbH4^Sb`r*7DA#q<5MlLf_nu~ct?ziZoBK|Ee8XbgHUK=k|Kw}76G!EExUSgE zD^)eUNP}UOE)&qPT~-I3Cf!Ss&SE#gq|a@QI+w6%boC~#_vfLTc!IBAk~(qA8yD0A z`mc*4p`lF+RH*NhSsz5>u62?!bdk0!<Z;8@Wl;^xV1M{6)fttl**t9A13ISX#tNqy z9mj@l&c5j4i>(>%^|V;bb%j#rUm1350Jlq(*5yAVALzJ?uezkWT@6NE9}<`vg$0dU zHEE1OO)~g|47(aM)siEni<Nw4J=OVWXOw8->?BWpb&#FFd}0)h-vgv=8*0O#<18nv zc1p%<o574{c82!u?&sYb@eckr=pIwBW1L$+M!G17EJ;=j7EQBRw<qE!PN8r30!@x9 zueEEh@ANw>b5CKuu;V39F-7c8SDp@PI&Ep!uvWrj$1O?>VB`Di?$VheIiuo2xMmYK z$#(+mD9_{NM2lg9g)AF1pEwU68kJvri)dAJn30bRaJc;U47q7KKq~WHBZM1!BQY+` zS{@9@Q*G8+I^wcLzk@E?J0Ej1L+WWZLiKSgLO1Ut6Qav@xSf1D@rmgg!7n?`AESUb zUXzo~me{|s8?_A!fIKxXkUR<m2kf0nC$pA!P8pRrUKC?D%}9?UmxM8GHLh7{eX9{9 z_8mh?EqgQB+@armGQU>Ig(^To<X?WtKHJRo5gJ{^RHD5`^8+&(#LhIE9X23<YP1e= ziDS36aHe#n-4IO^H0uJV6f$SaB4;`vH4YW^Z34?|+(hG+^In67F9RaWqMIelF*n-z zxm-|bQn&%<s`7}HVRsMqi&fMwp41@b-HaB7&b<kdzalOr`0~A~#LBxSolo>aygqh+ zI==Wl-vA+YRu7L>=ff0S;@EO{(mH>#Ie82ZR?$76UBx+ly6;Qhq~x0VR;u1pv^Mja zWt`vsa>2sawXmef@d(SmE5qsA!y1iYcU(_B-mb_1Y!~yW6CbOXJt)#Qk8tmowwc9s z1$Qe<$~L^5iscIp&E3Bm64;EiYd?Hyi#F+X&d`y^5P@{(0Pu+ct1ecmDUKIx_KEYS zM`1=)B-8n!@@)J;?sRu0+KwO)x)2%p0rv6yAL)zAtsKOjlqeE}!;Qw-CH7vL-Btcw z*oU%UL&5ynj}dwF=}O)BRz+tef_}8O!Y$$)@$Kjim1z%->*N^WNBHig%-N6Z6qLkZ zZiSGGyK~TN`hp4RxkWR%wcLe#;-;WFqW*IqGHY$l?8g`rEi-n&EFFAJN<p4Ui`yyo zSD*zRO0ON|4d%E(skOYuyPj`HXKYF5d8f~~;1~G^eH{P!Ud`$QFH#j-Y3?MQbac9G z%Y1SVwRrUOjXs0;lQ)G2u7{6PO~^~Kp^Wnx(hY2W1jMSnp26@BFsXAgmI;Z8qs0XH zm!lan_6<mcU<9!_6!p?BX3@D5ca`5i?BD7f)_=HMGIX2~v{xLO@!`^gw`;FZNXA7y z#%CT$iHLFPg}Dg<J7b5LGSi~dq<@#lgTl^r1uM&?tFNfA^DY5CK5&_*=i}}sCfDXv zFUcbUu03CmZgGyY;(Uc)51=|lV^4q!d5)>Q<{1ISdj(Z}0mY#k4cx<bnAEBOrd`uU z^pV=9CYuu5ncR%kG=Go4n}{Gf_}29fr+OQ0AfqY<ldji^mos83D(|D;3TmJVznXtr zwmONY3RAn9qXBGGnc^)%LwOr6SMz0q!{tZC%QkfzRm{!%8#T9I<|Z}WJtnH7?U)bG zUw*!QS#u+x2G?|QT5Kf%5;2qR>;VqaNh5X|t?gW9<^~@$TUpK;^?eV>854tF8JWVq zaV!WPM|{}_0*f_*_$2S58v-USgiOoA-dJ%WLqp!*3NbNXe^(bWI~GE}7V>F3<ny-1 z$A2LU;@d_`A&W+#%i#L^w>FkTL)U)YeUKEoacldO<f-^|YExb4m$~iFj1$}cLU)d) z#d;87yDDMzy1Y|bVLvZ~{R$2HogB888@7Kd?4XXwSw%h=3;R14_HR4v=wBFsB(X@4 zSXD_NV-lMqiTxr897cj%B|-0QgEL5+4@s~WB=~C**NgM)GbH2@355*jmI&uj4d*ou z=W`6_zZfnM7A|--9DO}p=ytg9!*G!o;i9j@#Xg6Ne?4BKhhvZtScwQp)d(r$2y%Cb z^u-9-un4)U5%Sj~6mCZ-K8#R$5uyA#;>70&m9G)1M-ez=q?$yex@x3`aipeW<jISX zT49meS0i<<N9x{=)O#4I|02@hb)@0vNTaWj#z&DR$S6~ZC^OY4bK@ur$0*CAi&0i# zQPx+Z@YkbkZb#WZj5_rq%I<ZP{pTo$uThRiQBKHcXNhPR)o54aXg9}b_lwb|!=lez zjrO=6efD;==fmi8#y^HJoPl{X_2)lb<!BBqxWFILZV!Ek#xZ+ip}y~;7|)%4iLX~X zG^fY>^7~qA`21JfEykHR<KV9`VMo70AO4yRuj>7{9`O7aB)pL`hI_*~&{I4Y2)Q5i zZav^(?388YWwGFJn(&pIzxGn6jsJ_K++0mMBiJ|=l;*f+w4(bah^h{d<7TKx=ZMcP zao1kNr9I~GyGta8k*<ry<=u_V`rK5>aVKUSV!YQs-IzyF4}HiPUvfQ0KN$iX)q^>; zPy5Kw89tXPuA2M2J5kufr_W@S*GW0X`Y1Ppf;yXTf4zI_YQiP#Z4E2tbmKw85miH0 zqTVrVTMV-ANAiCb_c-)&&TZf9*OPgo^&#si!s{$j^ArsEkMIs_?A+c}y+4hsrG(&B z|1s+{g@NrL>b9Qli?G$`b!w$^oPOxRUvMnxZkF}-q(k%}X{|}xh(?@ek;m^#;Zjeb z*yM33{yMbUPyZ#QU`HJPcK=0%Hs{6ELt^r1{&DG^7`9_Hzy5gIG0Wa?{qNjoHbWGf zX>+P$efk*`_?@EwDb8*f{@YeD?m#|>s?e4At~^#dmh!HtKu}to$!d8Nm!^VA)yAb_ z)+vJ*VjZ&LZv`gB1ROuQz<zmbX1G+fDv&lQ)xLzPxMky4&rY6^cDi0`7^NBAurioa zryT|jaVgF{-yOZynZzp?Dm9cV#zKZGL`V-8$U0Wr-HVWUS*&ugH(Mc6cC<_@Z1L5- zNV(UyjIO5e$wkReR9jH0H5(=a@O1obGk1md^J?Nwb2<|fAS<%Cp4FrOv@{jZww`*e z_-XIU$HAB{Z|>Z`vo<PpvOvrJl(zCmCBuaEF14jg-li`Seg(fVm){|1C(Mp#Hrf>Q zN9~S<@SRa<a{(4dQV=H+G&kPVIo3EdeW)FpexO~Dc0%~q<#&?C501t{T-J|?t5!eP zxdG`jXgynK!Q&<o-3W*1`^D$4=vmV%29lOy9*F6C*G$&aYl6$VqF(Ua4_|^1Px$Rl zw_H=bnEWE@=ghEc$2|e8G4*GF%T4iP#kqsNU<mJ+XN9vMA_{4Srl;|`c+k_89)V3# zI|A1+0j-pFEKTrM%qQ(H+131T<#m&Ep){TF6v16zkV&L;vV3)}S^nG8`Y-VjRFQ(b zp)r-nJMS`a%fo$Q`u`C?CfY)ku48)tP5O-Ko^x=`E&TgKg9|9{Vi6asJhY@qznpwK zrZ@Kke?CKe(c^Aq>|*KNTYQ@y<)KNok1x6Tq_>UgJzJko;VnDj<H^J%$2q4W-X_*? z>841s2ZWU6w^f|09j8-e-yVX-l>F3}ZyD@1OChv~EWnu6r}2Z);%^n8T%8T&wrsU= z<+pYk1DYCeuMObX^Kf0aZU`NkXO?qrkyP_Os)ShnC8#T@rs?tL)ycJry7R~Eagi9j zT&G@0yMvl#1u!7wSCUT?GOhr~>JN%F#-3^g9+Wu=dcPeDBdnX|7<>ybgY=e@qlC0S z#kq#)j{fWv&|PB|zEkgmyV|MU$@3afCHWPOYP~o#+Z`ShFdu2XYFIZcyCK@?Tp{%D zW7}(EkXXB;<XoMK!wR)M=gldNPd~IIv0}t062rs!<7!7|-}xB$ZS{Z<25~0>pC^#n z5Wwa0A)!4@6p#aBH;$MtQp*X-n0=(V@2lhbtNyI+N~6q}-Z#7Nuhf;1Z+BJyHuuFP zeT(OPlDL6;?y#u*A3GohGmJrL{nuVd&{+vscFqW_$xV2SshfLRd3+>ZHjbdGA2Fd1 z6djG9h&2A$wtqT>*sv{>zJlkf(|_<^OT5R9tXzc&O(JH-bXXRb_QOu+c68@qMYE$E zU(;W{8mjop5A#*@BhstfJ5P%p#&l{S4qr4g$|3KJk0v2N65&^kILj8TaPchy*FE6z z0yn5oHr43eUn4e$&x>AO?uKn<3S;ikv~lYUXy8$n?CZ0z4;>7y2sHD=P3~eQCmm|) z^ctD(#Kv{+63tR4g>N*D{bcA+WsEN^MtW=dn=(@mxm)k`2pE<<c-JWhklFt>Q*#VD zJEq-GqO-U>@%k#9O|~g=n**jb$YLBCZ7#Bau{M~?M?_T-DSbFA)dIqh^eYTl!=snK z7?)~1*28wyj#WJ)IybI)(`MUe$YQ>rlUbsgJvt6X>ANuACE^OpW~JrM@${DJ45Y2$ zoDz%ZnN+Ahc7q$KV5P?C(!a%D8z7_ncai#|o(@lLKC7|l-4osZCHS-X%_&@fL0$%j z^cG-Jw9L&DTGEsuXmRH01&!SB#8BZQTTGgP77JL<E>&Ogvcum5^OnfTnw(;j0kKZP zkdPCWD>B23CjytsKd*6n?-h&jmnUpm%~)_8ybn{h01NyfCH~iA=<}kFxJ%c<*-Y#} z%u{XzNm<_9dP~|`f7AKhc_q0SitKva9k>nKU}8djdh=<^p0o~g@sP4Wy`_n|wAB!y zw@w)%V<ajQnkr0s0taLVyS<66C1ve)_+{^$s7buE=9^`H!#6p>QCl2e_BS*Su!xo) zObx^8DeRwbh@k!y*e_)kE*D(7>MKcfduOkVK{ztDb4fg5>b~K&TDCdU6tTxtGE$}= zPq-H<Pt~&u8#u#RSm$ZEuZ}=sKk~#KgCQb|=pmWcKPO(NXtf*u5eYnX4pEuNFZ$e$ zh7*>RwwWXfe>)qXzuD4Gs@T!949wMiMX$=CjFCUo56G_XG_stOGTKF3H&KZn*2;dR zhKdYp20Y5S7R>W>VoD|I;l8fxh^4`W(PNE4>*G+1j+~b}7U*g+n{+=GaSv*VTcsec zEZ2y?0jQb{*qpztQa!9-EB%9yxrsl1iZgdWMmyoiE6t0@VyHR#0l+5d#47v~zjkh> z1#U}bfzQWV7PjW+ud$NbCHKn%&TTCU9&yBY{IQE{cfIB9aoT=K4WmD%h6uRD6{5oM zz~hy2owc?_N1$KPN575>PNLB6Tf_Jbv!@f2&fNd!0P{TI&aIDVZ4f*A(((<6YF`u= zc6nn^t3MnQj7mj%AM-~72yFUnAc-Lo&F}{unY@)Mkvu(QD4c!W^gpTb1beXF1tA#l zut9v^1fsre8gQkA72QY%iI?`U8RRXBsV7~N7(`jw@b%fts+_+R4q7_XSLS$6zwT18 zOCdHTSGW)ZFYJuW^{^b33wdd!gMOm;ca{fLCXbG_o8fC`Td98ugTz=?=P--YL<B8h zkFQm81v8i6+T);j*%(B`4=epO97OJzexrtAfm|#xtJ-H=cWx*0)S6fuP117{0fQHX zRy4y&?<1tSoVj2;(_G*I26lF@PvUXs5dS8siOk#ghDoxnTfl$~-jF%6N|ue6zj5LW zjsdAXR@eD0{6Z)6rqv$~KfIJ&__hP#qxX3~$7El~{E<024JQ%*fvzl1VBz$aAH>lF zsyp&E>lX2LjwkcEE?)jaH2AEGkJ{D?A6FrkZ|zUN4E;r^1c_`!vd(pR=S2DpiT(s2 zCvn_V*LpLsDS5zX`+j!ZxKAG^yQ@LNH@F=kg_j0plc=8GllSQ5soSwsBVv`ky+Ptf zR_5r4p0p%<g+%gBn&B2Dx9fmk_%$#%6lem%<arBD?+qz60$@3O@2Oxl{rvbhSL%=0 zKd$yl{CgL2zAzl<76>Et$r49$!w4Xl<UJORtD}qcvjMgj8fXS-&TXD{wPI5n9qrEV zzSmg|OB1Zb_J==Lg#9+>EsWUA>B7ba?hz60PVCADNLZ5mWG^W-X3|ZS#47R16eDVe z4q#DgHq$EUV|kLU34Q$~c&HfXcCwSb1nNZDPhsr8msw_<I4o71XH_Sd8v^D$Oa{D5 zT!@gOGkJlx`Fxu<ABWn2Lxp8}v*@?|dE^}1`)_k!?^px|=AZnLsy=CXqBC8~E)x%B z#p5N8amX(F{gL0OPI2bi{gZmqR_HsP`jcbpdDGMHq1@a3`x{`Ly_b09!XpR=UFZVm z*T43W*?o7~Q$-9Y(oE3F=01+$N`sPKQ9Q$F-CPmM5RPKisx{YjGS`MX7-)hNj<?0f zXg`Y!I^P`iOZpByQco5g!!G-rNLK9}=~^DCf4W9)1phxauGO6pT{i7cVhBouj)gz! z0GQW}h36H;#DjvAPXYU<YLm^y3P9>H=XZwLzE)y2>Z}Z;@#-vCH+(5Rz!X2(ck;9p z{ylY~-6E3D&Y+70J#VkC<2|`Uwn_UGu#-_l2Cdum$<Fd9kW$MHM#r+5<6dXe8bLs< zc@ddG!ny9B&nXG-e>~hLvS+C#Z>{~K*kF%Uh)>d}q?f<h^hmA(?iO-UgZW;Dn4$)C zH0THER#j`ofpSJ)e@6R$E4t>IVIG+=pcibei%;Fg3+v5-ju^dy6=o`-to+9;OE-qt z7KLZlgf}l`$HNvs#WsP*>&N&6_`Y{bxPF5oWy@UFE~(gW%*vc_e4K&B>!jeBcBhNk zofAPDB#_Js#E`XD(`&e>0!I5$V^@-!rkrZqY4abZcC5r#zhc<9f}z=OuEUqDxy<0} z>@~!j3zI3*GpQ}Lee+Iz@@Xu>1XiWEVTuk`J1#X(%+elZxg0?Kvv*xv)G4XTygG@Z z_=6(1#SmAf9Dh_%CkniWEW&4}*5P@fH!aGk@W@?~UE2Zr#)B1LV+{w7l6up0ygun# zP<u;!n;uEqq#>db2iKU#P}AEKKF$q-OJ|}_x=ta^8@1~+q>%ElbQyx}?*m5qaPxrj zthw<#13AtR5jv&!g;l(YBBN}+6P&7RSsnmq*9uP6ip#WnpQ_l|E7;EvB2z>US)8>f zTr)kgljeFRZy#0Nv2Dx=bpr8sdt2Z0{^lhY7yyZ6<#MyNbe_R8<onR$rp6_y{<<_% z|2uAV)NfJdy0bL13eyw)wD)-kXI#eZ`kd?>D}Rh^Yg(Fmh52JU^HH%{nj62fv=4(k z(K5mC^Dr0Q5%b#1S77$3!a+-<-XqaT251m8Z#Rqzd8rWL4Q!+u_oOH_Qh2>6=<F0( zO%}KpqoL&Zw%GZGn!@+QH|KM$Oo}ZAdKT_jyiE@%zxKR7a!@|%SD#V^Mg0ee?YZy% zRBd`T>V_XAQ9f0eZzDe<HO|wC6to%KIB}=(HXbdvi7K>qLxlyH|IT5_$w*Zh>C;H0 zDB1O^#8J?I`M=semR%O5`7B*L$BhlDa};O%C*O;dIpIbI{~<$G-jw4Ikf;Sc7#|sn zDn8}rp4JcgMJlknW%0@sDxt|<=l`<0H|=H$OMJleDKE}3%M4d(sSPJ@{YlpQ!V3EB zIk$BhGW2AE;)>l?f;JERj*gkCI(B{NJZr6}KFx849GampLlawHJN~z~{Ew+~k7xRi z_xNUP#xCyHjV*UY?swVT6><xyw7HWs*W9Yj+;W|}klaG0n!BVj_awI@gv>orNRpp& zcK$h!^Z)m+@8$FTeBSTZ`}w4^Nls8y2L!%2*(a2}*L9*^+NgT)FixooFS!YXso-Eu zajFYkyB+aurj{4tOf_RCl_x*|4W$I9&F;mM38aFQX7-qWCUWdgo-A`&^YGri%>R@; z{8&igW>~jsNP$h&)`OBBi8kAhUDva@IJ5`4MKrEn^5{0wq3}+18|@j(H{lD<Q0vQB z%g{-mI{CX3r}|N|)HxI7BY><c5H<i1BXz0u)Yv&GS@&G`H?)k?Nwf?kibv$4>Cms{ z1MR@hW*eoJ?OD-wQ-9(GuK{YE^mnT?nGCv!Z@5XUe2+LS={PBl8k&1W9f8$IF%Pv= zu<QXzWyDJte%V0~waJ&rN8L|IOc_of_6Vf9%n%Lix+61;B6Q^^Q*}qbB}gk=QhRnv zhiW(!XT;gZV}O@Y_O=QL5-lR0olV}WmJa~%&TRmD((dMNzSS-(wgpf){k#(fMr2pM z%Tj7d-@(7@5{xH}-xyoHsd{cDZ*d=$V0D;iU>PS!a?~f7bO&Wtw9i;^){IrJ*k1{- zoai#Deqib6tP!qKit*ypCAQgj=M{nUhwvyuxA;UHI+?BUnTg&k11&<;AgLfSdhhEb zh+gkbWP*%_x(&8X6c<dy*Kta1;tG2r<{c<*VgBQ99ou!);JKNhvUxu(0+q37c_x=S zE=&4036-1wt}*SMoYCXs->o+xA9bpqGC6ZLS(5WdzK&nF*5yR+^e*o}>KV407xI~} zjUl|jLmRf!?M*u~u1N-{c!StHgKfN^Muu<+MLy7&tg9+UXOr7cJh23I%mwL0b|=n( zj7+KO%hRH5IH6OZcMhO``{`mg1dKP#wI;f+CdbL!fxgXK<y+?1q{)bu3|o>;NG6@L zVECQ&BkHFyzA)~lRlj$O{G_+sAC~gq-A-DahfG-Hx{jZT^quQTo22`f>kbb3H0<yO zVN}ftklHdMC(T%%PEptd>gR$K%i`FddLJ9Dsim9Q8nMQrM!How;}InQ#Zy!niEP)S zRf9}+*cy0l94OeqkmuP``+Qed{;6dGyMjS?FWEGt8gP=Jpp%rS`QMO^i;AWEvbbMd zh%1-xU)2ef=cOe9p9LBW{EWT&`n6^kZYUyq^y)ALW)DNCH50}TF6W-+RkYG}?K&je zu+0V}))s=Iw+E6xfS^^rsSg1atEgIpT&p{&ZnsTtM44z#m|R;lvFHbh&~VBk)R)0= z1|25Lr@ls>$cqkm<Z^8KhHR=E2AWg+Ut7=R4J)r>c9R5C1HdoKJ!8L;^$|OGkfoAk zooH9$SB=eJ>qy`S?2iPIOs7xX#~MRsI{x|Eeolck8ggqaAMdXa?_9GrsBucKMhTGV zO4YJtETZDnliAcQyCes?`Nd82VyVwIe_jnmX4aW#_L!V;6+08pW*BG;wPq+0x=^Gz zjXKa_(Wl<;QgP!V>fZ5p{^DS{K-FB6zKHDHa4I;V=ln~*C~6=4zoDH5_Hz;4SPDfA zF!t*$yXI!g{mTz@B0)0VB!}nJhdou(k9v5zf`aJFZcQd~8dp=GoALks82-qdZ!+nQ zx6+%!qpD0;>{oRikjf?{VVI#}a2I{`{jYGU!QQlLGMo1RIrd2xYKTE@;P^TlSrCd2 zu!he4BlA@O<>C_(No~g#w;}^ZF7LFoSslICRPgG)d;|T-RI5%m`8W5E2x~8aA(?`F z_567Cit+%?gaCiGyl39&&r=JQBD2T0#E-5Nou%l(sPdOh<c~loK)1LZKC%YnScy;z zVDDe(RvI!<nJ|V8kol)P(AyLP8r2n3S=o4SoMCQ$<l<aKIbCw#*APX&RF{))%J+0d z!;g(g(u$ZcEzKDSMIGu^@m_Gm^Fx1lo&4yX86x|<ujm#i3h+bME6~xXwJ_>GU2BlG zH&v@GPO*eVx2MWmcWWF0RW9Sj;<dFl*LOL4?+9uc&6=pFP~mNO%mP`lmQBLIM11V* zbG638`{p+;njD|%Nfs@P`w#Ha0^dd-L5)3TpXs5hOmsCYvHO^WTesWj%Xe$PHPM~e z$uN%H#U;CvP1^hqnsr~6VwRC_;-nA8yIz<`X;4{MRSX+QvM^3mr9yWW1Af|_u-0Av zo=x4A!gqvMDm9kai_<9if%ci`{kQ(72&B@}CALRKAMBmDBh(yXuoJF(mcE=t0c~## z`l##4)qCmGrF5IptZLex-uXj4vN5Oi>!!vO-Qix)wkTN&jahuJvP{vRWmCOOmEWT( z^svb;0QHxF>`|a$?Ca4;Wk4h-_nV2l4oJ|BqA=7cY{?LAGBzTZrhIB&jJfa6*{c@| z`iI9K^B&+&rB#Hs{@q?XnX~W7H<n@`|KL(hFsU@6H#*gk%=!*5*eP~{AB=VLhX*B( zv=%oczKI<Pd}N+XR}lUyeAK11jGuHjF*u?qY*Q?4yTs+2w~x;WAqa*Y-KW(}a6opt zsD{(6d!Ab*FG9ZbXoiU(JWTKME10vBcs<S2#dRb0I6KRALRU+(JQ`)wABD{Hs0#e% z^|8LE?myWS#qVo-Uq5Pp?+?G9UAdqV8@a8XX%@0PMa;2ap+N#?^1q*w61e6}Q(}Z) zbKz!zgQs7!#`9@@GbG{6fM3(}ORbR~hOIAM{CIu7DBzFz<-wr)4eG~wFU|_fU2XE) zJ?{Lg+WTm(ff!#EA=P@}hEMtFCpPbrPEV++n2=?#adMf8{#z}1=M<ma*laG+*E-t2 zzN~J*h#uGpe|G8IO!qH$+1se7kd=2)kG=I@YH45pvTj=(5rj5b{T!7o{^@$LK@>sy zSGSK-OV8S@=gdE$=c4GSOII64iq9woUZ;HBOYQz9?6$$XazC<`$)4#xE-H)G%k}Sn z&8g1E5-bfpGM9+mzn73Mxvc69mhCF^6b7{Xk=5DTmP&c~d4ShK%y!0A3g$SeYJs{T zJsVtk9e}aWmq<Wm51{XxJl6`&KOtA@whZzuIZP?xlO{C)31WKkAe?xpQ(F2UwD<1u zxl)(IVy@>Z;cmevl7>=zb8IH=N}<(~%aaOkSMQj?bjGcc3c!+0)@L;{pHvq|?~cg{ zYFeID;?ii_uDT!E84Op_D*vpk0BFD1pNn7Q>B{s~OdlUzR<Xi<biQ&cyhiHt%z8^| zQ&tVX%`&t4Lunc{PmVPLZ6RT}p6q-7Iyvl7<wbbH6Y;2cU6a!5Q`2A+!GC;D{&(Bg zqzt!gT@F#VUEYM!$f~;!GhD~(6B(o>tkdTXl$wRO|L(M$fL53tSVXmO!9?(a;tIIL z`bD0dc!bAS&veblgoMKAkh*5~RtMaPr3}M}JhOXZGu7y*D5brn<vvk4bl|_N<9IHw zk^eNk&-YT!zrIcne(ICambb12(<jPiIEFEMMST~eAR;=W+Yc4M+F4Z+*Q5I$%iJL4 zu9Z3^lJRxYKJsQ<Ju^Fr<q0?UHfXM_XfK~T?NL7ptsmt3p;W$S{a)y^f8yIq`KVZ{ zhknDgB?+}TzOa`~RtBUQzSC<bLK`0W=E&9F^%YNYaDP#JNpsq?l=ND`x8%*viIQKF z5G2&ZM=xtpAbb?xDgh`mHz}%}o~|+qv`as#ew%*ULM&kSg`9`D7O^HnFx$?XJ8WaR zuej&Rm)F~@Y08@75CpR-SxZ*I=X?9_;REsV=ofwk{dXTc`1hbqGFEEoCGps|D003n z0}Zge@^?48EziH(yE(Fp8j;95@bMdYng&6;W09dH86o7CU%+p(+7g|XQ1^K_whpt> zoO&vQI%`3)rNnfOhbE%^8(`o~wHKkWm6H1dy*!CHQPm*~mnA7de}*E@Ws?zOaQ3os zT|G?hDHc)dnrOH&mcHptzW`+K6xX1diQVQ+lZ0AX`lzA(-^z*W>t7a0Xvlr10D?&u z6aO=45n#8ai@tQ2JnEaWFxsy_HJ+R#Z;a(|*fSBRaCOtQwwEGQnV?}6=L|Y26`Bn@ zQaq2q+8g*x&8iA$5UmgEtO8Q1?cx_wUzCh#mJ-eaxi?#al!H`{Vc`OmDG{K2S(WK? zSKA*dVN<QNU)xvPTJ{FKft@wUSCft6T*W&*x_EHpd*ACyRi46s({97#**Baj#Rhmd z1jZ?rmq+2KI!@~8PDY0B(FycUZR%34LLchu0BUM|nKj$T?%hd*S_9$~zuTwB6H`un zyGx5P_kf={VB_j-Gd+{7+L~H^%KF7O3q#$RG0h$C!ismI7nHw_m5{08TggPNN#57F zHc866g^9X8A}_8#u018fWrkAZ9U&}u_<!_s(~M4ngYPfFLNDI6(hU*!i0&5qMYa$( zE{B~QAo8mh0)=f=$3mT!#Q7B*EcFi3^sKv~m2IYm*~C}j$K<?>r+P@ouL1lDjPBG} zFK;c~igZ7Jw)B9yZ?^fn>D$&zaF~IG)s>Yzw{?8A#_TsQW<#6007ZB**+M=$3&{eb z2;8EXYgXiEK%Ga$$5E%uCmj%>flH{pWROU8d6H@}o}g~oXE+#aqUP{bYt;`Tr=yxE z*(QaQ8G`6<>?_^`;8MF(#sVHa86s5omU^+(8SuE4Z_G<8ER&zA_0jqR2@@AsUJ3(g z?A-{OfG1_Cy1I-b<Mu)Yc!~fqG^J$TWMO!#N8>cAcH|-lP59eqz^~S49@$1!ivKNC z6tA{VRh`x1%01vv-VH|h%in#@w~?zksLFY@1a}Ot(doVQF-xCbQE=A1-BRYwCC{s} z8aE`yp2hCBT8Mv%w;n8u^QdHBs&6qx%_jGYRQ!=TtbZ%7(`#ciKS~WA@MJ|D&CX2n zF312(#17GYD*y11E4QeM=34&5pQ6a<CI)m7YYP2`NmP+u68aWtk&<lcOzJ$x@1z4% zPg6;|JzCK#%;g|-da+W{NG#3bEZ;r%;GyfTHt%WkoVuO$>Cv64nfIv|yqP9XIo>3b z?X>2uzpi)J)nSNjwK=M}l?<O2E=0qORlJRVFF{-?CCA8d{EIu*atr$ib4M9cunFIp z5(+{O!!A(Dn2cSnM3KTj>UCwwSX>jE-95hl+|}E7NbN1;y+7AY>!ZUV>?f0StZX*= zeg$;U+HBtNvyb=tF{Ew>QFMz0Hk@%ok~GEzI(Zt)Iixb(Kesum&zc)ljDgjyS&Fo> zIR0#Uyq9z(nnBDz`GyI<k?e`?B*jUWjB@Cg7~9`}>OoR7ln!N;YNy?P4?oX0Eu{Io z4a8zbjN<gpQ{5Cb*T#U|p<r*PcLAU(Nl5D_+KuZ5OJ}>2^cU?B&ShBUk6H+Iat!8Z zapi-?M{|P`B3O$KG6_qjKwD^#n-fyv9|wMiyiS5EUZsd$8|@J^A47&qd!lEZ4{5Qc zkoc9n^(^g)jqe3--Zod=IX-D|40x#g=jg79IA6SvzL?G)E7gN?pJs2~?BW@yN!t+L zE7PeSLyFolMK|rL470~ruUZA-4xmrB?@U?*iHg|UJPJrpvI!Mf7ZEDx*P8-z>JAXV zt@Qq#%!9+Fq1)a(Sr(GxqewX&BA@qwh2cc7Ev#t%=T5;Ji}*)N#TSxLSBmaf3<PHc zHhGHmmBpFD)vJ57cupz0_k;!p6t^q1Ei)nGWPusrl~Jtd1{3|-_F%GHVw@@5BXxP6 zd$#MO@*-1Y7J*s@iXSZ?bIZ8s0Q4b6tc{56G1X;JH4oDfw--d^%OS%H{6}Sy8w`nL zPJpY@GxEyk{Y+@Wan)&BSMj2U7-=|o!sg%MdPX%9TEQkh>-nRw`_X)*sJthG7Pv!r z2$bs5%C?p$A@Jywqec@Xh960gDM&CwV1|J*prc8)qQlsGvDbkw87LK%!;-Q)Ls)ns zkl&BMwO%eU#gst>0@W+?SVV}gEH)=VVzCU8OM#72(1#3k%MUa2?-#)3P?vg3T#D2} z+`jBOa)h>y>N-1#J-5CfS&QXaOGmXc6xMMf5ebas{u6Dzh7O~!;WEKG;LYK$=(=(~ z)KZ{ORiOssRX_lH0*JWF5H%*kV;OOq0Dcu9cfbM*l(%%0s4G^%{U4sclYm?$h>)0^ zoX2<s;rnqmLt>fo@io0vrSIZ;fbb$kkn-rCMuoF`{Hw4P&Kx?lf89{l63O>NJSA{` z?~#z}4QmG_xJ?p#q!TK;E&7Ft9@;?u!%1{76Q&qeB2vnL&Kn54)b0(sys8A9DB(~J z&n=g1Vjw+$f(``uIvJsbMNgHZa=lTD@05Z(y?Q8nvz=UIRwt!gpri~^4dlxIhVCK0 z8)O6l9PX`3-9)HKMP~^<*cSXIWls-wDajTTXM0FzI<J>0TRu0A^eK1vVaTEZf_u3{ zNncPNujV_UI^|*+SczS{u-m5S0YF5D*yJvc*2-2@doLC=9y)*(A7qF-9uwh5IEh6( zj|zj&566{DL=Kp|nPJcsp(m(jXY-|FEzcu63H*mdgdGsQh=Z&X1W62osq?}c%;L)? z%2&OizbZrm0<`iJME&rxOBDXm5c$izT+9kIxkl0!tlwHeA0WQc0>Xx_rEOB@|1seL zX)=nuq%+xP`n=HdoiLWeMUNtJ2ozoIE4Ri9S(o1&#edp3A<=|a()3XOw$a)_v6^R! z#Nj!O%h7cVWHN(~OaL#Gxu)$3PGXlj@oV{CW%O#$q@OTpqSzD>ah51z%z)Jr_!rA0 zb04yhzd-=N^$rCCLmyquMQ5$Y7M{Jj6CkO94Pg+~t?d}7=pQ`S!L!$8B3eq&e#s-n z&7)iR6{S)yG>@xx7%8s!88EKm*kvI=??iUujlQwe*U4xdAip(3pc;!V#b>XR#fI?( zS|0VzPclPP#D^#nB}@?qCTBiYViSN&qkv5Th$_5<7NaFzRbhq6qVk&B*?Vy%uvosP z(-eU;GqaU)NfvJa0h-Zc!YA+wPs%027|~$@(4;2c3dhvNatYYDY!{^-F}_x`f?}7F zc$R!>?S|{#If)4X&%bh1JOq%@{~x_8(gCtpB{N(F3ST%+-Im*Lu@LXT3Y1~^i}0!& zKy*eZ+Oiy(#zaQ1C6LTqjO8Szb}TK9NvQl)k!>P;rc7`ge<dByWr~5Z*;Z>Y;C(n` zBvF(_!?JC97z8@ef_1!M;?YX{Sh8XI893kW1m7!*o1q*kG7;nD@C+PZE>1vk)vXgN z$-aEjBG>tN71iPQOe4-+zso||+#1RE^0u<uJVE3|m5WQgj1U`Yh6NBU6X{#DNOV@G z1BFKjB2m5m{d-c_F0m4O$Qh!rqK*CVR~uEl7+(<cAC^IT`}5Rt@RYJh9Ftofi?(AR z=9vhGGOmR(u|vCRcRX?eFk{XX)LL_##x5OV(P}{g(-anD6urn4bO-XymU(KIPg&k@ zZ!SY@lygTc2o4iqtH-M+U&Z}C#7bH#yLmca0z3Y<j2Bz4b+y-)YU!6k4E%`a-B32Z z^m}9vvF;pCgw3A3*sv0|<-OHL9AJ@w^E1iv&q?j!3LZ)#B>>?vtk`akYQ2)sHX+ak zkD3COE@IcK7f;<Bj_hHgC$CB1JmKu+!jV|y1Rh<5<Lc=&f9+tfOc8U(hwO~Qj&OX{ z=E#5Aw$fPgu?znu88(ZfXqSuD;SGvTNGvji+XzF8WpbKC_$mcG4kY$uNPfnPg$PF& zf_+pgBnHaG9!JEh8;@&k33qqTmj$ULg`qlu0W}PG$urjVD4};&;c@r+@NWR>inR<i zC)e4QV}(gQJj9tI{H&aRqg;YSxq#jfwPqp*iD*{U^ogg;JbqWtOkCrem=8sAij24o z6dYI(-o*?0VYm(fA}T844NTNxIqR2$&L@iHQpmqL;cSt}Jpc`=Yg<hb+j}I5bLx-{ z5=#RLwsrDVU<LBYV(aCQZAPQpZ}APFSoCRezSSg`DZ4fzUembGGD`Me@?1&9xnrPs zlYQRlhx##=5|%eGzt}`puxE0CQJJF!@~I7UA(tV7pfVFJpditbfvy80OMxQR6tT<e zAnzSikk7v^2C9~VwpI~zU?Ad&B4>euQybh(XL0s^8SUjsF{z{+hv20bC5U5T6+U0_ z21Xcwpxk!AT0Dd|J7K0wv1%f`gsFcTWWT{cmjQLh%=08?Dl;lh2%NQ^Swr!B)6)=) z=q*=BedO9@?CCq8<9^fe-q-O%JfB$7OFu-;vs4>3nMsu?{xjtw?AW+1ri7vZGM^ae z$;?W`2WP6WQknn6*g6-962m$I%bq277!oZDCBB^k%h+Fawb+Vfl)*>Gcjf4|8O<i0 zy#GcVYMH|H1_2c;toAG~ohTMY5c&DmxP!$|28M;2#$)w7y+oh;vbmKvYXwXp*Al9v z98l4184u0ivt=T-P2w1j+}`yQy+HoIa(^sG9CH0bN}Hc+$GG($6OD2iP-ndGGc5lz z#&$N4^)UG`Ad&dzG6@vKJa^jfk&Fh$dmpUe6b_k!mH3W9o-G$}Uf{0seQeK(zx&AQ z<Voe^x5g(Tt@F!;2ct{6F|eUdm|i)*{A0)}zWPjW*bot2t8?@AwddEW<KOAaUhXfQ zJjcgMUVd-4!1|t>X5Q1=7qk`7YFMe)J`rBlBI(YA?v+V)GEXhUMBV=sz7KkujTcU4 z@C!*v+7kadzf4}<OQ@qLD~n4N;$&AwP=}C5RBWpZp5rG@_%>0}kHFD_;fg3n^>`}V ze!tkL7gs~SQ|&R-2P-vT5&Julo1LP1K+#zS_YAq`#qpmLd^2octHnn3LmJGU-;Xt3 z{dr#h#IM&UTD*T+*#BnTPO<fuLK8T+B@m#NAzqmKF@()*v#_AIL@YTtF~+L!x8iXS z2W%5BYzY)_2fE}?$}ci`+Qm}mtUi%j+$OP77}I}USg}vQN4`X%x`n9QSbPeJ`!W{d zjN`T=_EV&?3Yfxu(`I*wqWR?l3y&mEm2(x6p=?Zk7HV4=C=f;w$|Yzw15u-^#jA%U z^sN&SLe9&$!6dXSZqV|c!ZC{#r6V_}JyX0sp39hR(Zh>~xS$k;&V3%&652E^!1HBf zKTcRX`}8C{2fc<s3PhIkTecegS1!C!hVD7W7Tp56FIw?uKmoRYE-pRCT4$i<neUgd zA}nX`=W@Xfg6O|xf%!Ijmj#3hMdVqzXqqD0_V4*|e9A{WcL*6=2oTl7tCFzDAg07V z23$HU7Qw1O*#4JdsT18dpL}KY8g-BvDz(4Vl+0WB?msP4fr~W^LVAOUi1zZ3hj<$i zb4ke&--NcLAZBqcmd_JK!_MF<R*#bv0Dv_$pqMjIRK)S|@LQ1$@<TF%b(ckqUrDx4 zF!$zegru!sUPh~oN$jz@sN|M;im)O@U=oSmW+GnWOk6OK3Np72Lu8yN`knkSv<z_y zs0q;&TLlWg?iAW)2rS^B6~}SnsN~wI4YpT!v64DppO{tOc}sq^h-R#T76r!dl=ok< zf#jNL9)mCk;L%_TR%3S-?~!7-^?9_H;we0vFEyaS7r`;NQ=GJB(h)~w31y0~8eX*a z#=9wEP4E@5_z{uY#LjPvD7NIs;a-uFHv9I4;*(6VRlMW`89qZ6ZJ$RXunNbF%Pbe@ zKE8Li4Cao&tlCw01x`ICG&<a!>AxYU=UBZynk96jSSMt;=k7b%)1t4VzxCV#;To#m z=EyrfzWlb~;k)dev(I9z8mr$I>x6F1zHO`-d4Qwt_gFT`4~DE*rf>_NpB9apZi3!F z+x+-KzNJ+J|EFi@m&e}Cd+YX|zS&c5#kKa=%x$JmTCq~4_KitJ9g)*rSLWVnd)tQq z{&7j91*7}j%ofKEWi~FnihjG<tZzCf=Hhr~9DYeIb6EDdL$A!%x%Q^>RpYN$8gC*W z6w5ZQ-sNkOohWztv0)Vhwt$tGyk0|p?zfXPy6rR6smcKnp{s{g=QV;CF1H4Ke2kyW zdwyASth)O_pxo<@KR?$$Jb81s=~hhsV!KVw&1z@;z;8dljVNSa?g)2(sGhDCW7%+5 zJpO=~gpM!4-j!~)?ndZukxhnm{_}3jj`<GkWF~#T^&#EhxsIxh+FP%2E5n_s9BZQz zrxWk>egHhr;=j@zxsTC*y_U)oao?LWG<KJ%nP(0H8!S|YhSW3BKDoi{q7esKcTp}q zw0Kg#Wp=y>bwHKVr*lAkK&1Id%7*YaK`O)G_rmyy{ue(1X}fmXp1IKiU>jy7HK(v% z7B8geq?0WBxc01AlvJj)LC8;=vP5Ua`KqPlCAiLFi8?d>O8A9L1Kr8)VcoStkO&~c zt*Equ-lur7V$M%0Q^i(=I;>E3ImFiB&uAAyE7riIGQDI$$0jT?d}*Wcq<<B!?kdl{ z5yQ7-jY;CA^&duV^+qmQVJn@C-^wHjj3=GAQ^=O4@oVqHc~$3iY^K3@7|8Ykz$?`D z%oB{`i2ht1*VAL0?<HO=*V>w|Z8%&!Mc%4WnX9wPtzP}T=nl!PrinLcHpg5f=Yxc9 zj>qNuy0fQFg+vMVm#kOK#j4vFcy=%{ln17QZ478|$MfjE!cbdHp9VE+y`9mWvj&&$ zR_(rvYbn~*o@MzI4C=mmASnT(s$5#T(GP_#O&6*M7_QPC&+9)YJxMe8=+_OeDGG^y zue84xY5&BjG9Cdq&Rq^%NY2r6T#R$>7}x$BHkoGd88v*cq6sX`ZYoKo{&81(H=EuE zz!jWV8(8LrkM6IJBPB|jsJnWFaP=Xh=LQMsS|Yb>{hlnOg(5yp-M*44?%aV-R^f|2 zN7VmTr_MaqsB9}wQrWexane1}A_YIww(NLbYku#0j3!`x7Xb*P4`#T(?tkFe)im(n z!Jqg?J+{lu9rzbc``l%K9~Omd9_$L?Dg6x^jMSUbCc-xWllp#HNLvC+Do@Bu54>5R zYH1;UQM9aV!%Hc4mQC`jC4{mEK<oJ#i@u-g)tC<fYpxT6zI7(*^x4;tV2{xIoxO&; zV~87J1Gg(``^C>Ls`2Xa0uBIx*QI_EAhy2Pv%t>x!)0j^VU;M6iVBf_d4ZD%u!1nt z+*gB{6e-<}c8|0OYWS6=>(ni_Dw3_CLcHrgVZxv7mt<~k(sz_hb)2IMUE8Llg*A1H z4IbNNOB~_AD__fnZd|gM;PK7~urfhE8BNkVWTroiAHAu1_U;Oo0xk+5CB4WAJ^9F^ zel%EF<zH63>~g)}+4s8zof=l_9@V_2{*{ts6o=+$R+>SwvBVa^NB@8hlgjtJTDRV< z=5&x7m|GdjkhWQ~lr{A4JcmALOFHwNm-|}o)}?BXem#eX`=L$UdCKDuz4aD&4rS;j z@+4HRqV{g#(K2zHyC$)=((cKrfWoI@bA3S(_tP}?D(X<xbs8t~Y(^<!3FI{SU7pN< zWfS4A3mgiQP8qgr-En<1lvBW}Zdy^I*Oz2>&4mldaGq|Rc2_g?vN2c$D-c}Uuy(As zF_z|18=8FMrFgS-b#74#&#g1MNoR}vKD_2>c!GQMaH-G|ah>3q-ocJ>{iKLXAKpk6 z&q+e>mS;GYoDk})P11MH%Jg`sn7L{SIvKR`W{{Zm^cMDFY{Q3)+Y=zM4V4VN4}fH= zG!KCso_NW<@{!nqZt<HYb$%9~om+*}QJ1p%H4JLu*IaX(=nso75zQJydVUF(9$2W^ z1}FPYNJ%o6sHzSR;V+w|is$_x=-gn${6)<c<NBE@jdA!c_E+hu6SrnV7Ce9e67SZB z=maG4y~qFVSZ|&Xe9u`JT$_c+UXZcMD4aj!dwg@VcR;7FJe_w8FS5fEueEy|oT_(f z3H_Iq<8%$?JRJ~#UImz+0%J4LZ>i#6U`&Orm|9XY=WQ|Nw_1DIc8KDGp146t`<8+a z=?Zqz;^y^fA9Jo&trxtJVvCpkrwVnD)<M*$$dS@jA)$U!jsTSgjRh4~WryJc^$aze zCdCy+i$ISCHe7}E_|+)CIK-~}Gs`+_pPiw}LaB`}MzzEw-4^1*=oOCBGf)Jpmyr97 zV1};7!j8Q`;wuXQ_aHXw#^Qr%Dff|rxhz6K(Wg<`zE%1QVMLVt68tBxi~jBy_*9#c z>;Cq)UT0_882}Ygc;r#$;w>Q77_B0$8(8IQbFHT+OS<dbBeiu_{@wZG;U^Q~55$dC zMrfTBe4;kVFrEgJn(0Qz63iZNuxEr;Es4hZ4U5b$Wyk9D-Yg()-lm}2R=J91*Z*1B z^uN_jD-2IJT%3FH!RE)~hT^&9^&#IGJQu#FQnG^HefEPkt@2iP_m@Zu{ZnIHj>&j_ z!wqo7cblD*OGk?$5Z_l<R?^dBF3UZYwdO3~Lq?@hUXX8(^nXi#!&YIB3Yd+Togo%j z3M{!i(urdo<1-CPDugFRl8m0*&$xQTM5YEMY4<ZFg7yD?ZS7kbr0gO7+5X+o+9~O+ zZ%L2XbfZ-EwfC#fr-#dX!XCdbm+TlrMqA^Bru>rhgY576P8|QyTe88PbY&)rggH3! zkF+g7&PS%F8XARknppM49`x0Cy{p&TqA%A&=lqw(GM<O8A70W6=#hHSD{uOCCyPs= z3Z&*Gl1MeHI872ji&z0dwWb(w|NDRT+a6qBeV60QN>KpbPTg9St6oV79=`aqoGQVZ zy|upB+@nl+z3qAK=wk3*UD1?`cGDQbG;L9t(bg+G%0OILW@as~@9Vw}-g2%ofqBp% z`t8j0uQO+UAB?<lt+^u@M94b^$XnCZl$Pm6_s5|AnzlW@{Efz{+aJiiF1OT{$iPCK zdIxpEeSyzqa3%@iV+Z@o1J4R(&$mMc(;$D#;F0PI#|u2j?rm<m1xM#7f<@4L*d#C) z;da<c<t_B48&d>11&9LiM;6w}#)xjvRTg7;iJ+=)@4;7VFJDjYwTKrIp-6YbFKNKv zf27P1AQPj=p9?V47Ot;lTmw8lHD+N&SqQfitcf^;W-?XZHHlUe<E$fyE=cP7ZI=>) zo!N%p$8%1D{6s0#%(WyrVp2IMK2}6cI$vJ1(!6L}l;Z<sf&hNCjqF$9Iwo^Dbh6lQ z@W0zcc}GO;ZrsBh_LyzhM>=AKK+Wk&Zd!NFJm8OsO!W{>n5&k*q-qci08iN=wUen_ zuBj1I)JxTA<29+z)yU%&aG!ov2375Niw<+=Nn|X*{*H1#+vadALz+6kw??hbXkc4R zIKs9eB)Tj%*q7oGnPri5*C9A1#H}PWb8|I*cq-F$DkP36@!#&1Ty1diDDo>w+ln_N z4)1LDo3^=<89yH8y>d0D8$LH0uTgXN7{hgc8#zLTUZSzV>|yU0P*;LaE5ySi=#av( zj1>T%tRvzZAyC6V2NS0zFLffP0e<FB4o)-|ABFyeSC^#93;289!Dd;%%{60$5d>}y zmVpZsX|ps<ZD5w0znRTFkMDg(2@m0qv*8-Pke<%F!=tXz)m&Er+(+9^-+4GI>D&_w z+~b{)P%@MU3;x~!pIhNR4i_yXKe`g{Z+j4OIyvg}UvlB^-0Um$g}d}Z+BCw#?B4za zVg(btsuGNfyV@|BS9UK+>Norf7U~S({IDQ6KYIP=uM4N@^G>$7pSY<;7b?QV@t#nX z?5z%9j)qSYz?4yBKZa{(`$j$ubaR`dm4vJ!!z#DA4oK2RbmYG>uE`h38XByhaq)cb z#cyH%%Z+6!lpf+xM*yxTw9*24X@Q;0JsLEQ&bi13Eo#R2&@s11MJjPzML4br0DP1V z)4Y4dER1B)mfIq#^fSNgWD+k;3c0ExR0~yHpu=Zr_>sapu*Z^2+U-m}%fDgqpY0I4 z3($yB*iRnVag`ksK!!)!LG$e(L>{oBCak0k@n919i4F;)b3ELxWR=i<t5l6eA=?Qq zQ466pG)T`_)xYg3yA2kzmCKs|@h5Q*Y2YXv_yvvoAAp;_fV{fEr9oo<<X`$V7n-nu z_&y4oqRW2!Wa89Tu80*(FsYIB)m$XQOYGs%3t(S5^s^~;7vsKwQNX`dbf7ve<??+V z%`yIygRsmMaD231Lp4gSS;3S4Ca7zFxC&_!*d2w%m09<bV1R9{5*0|vC~}7md&<Lc zxf2q*08L$h#NjyOw%MIYFg*bG1oYvTHV$1n$E7l^n|54}?YL@jT+ch9xn%H70`z#o z?dfF#^h43psg$QiT!4p!x-)KE^zF(#GK)FEy0nS~qy5gqeaR7yK9u^hZBsO83h0EN zF&2B`^t>wEa$XwwjYlXz1sqL>cF>G7CR~4y7g{C@SpA~&aM!0pZF;{Ja$mZacQ*x@ z>a>PIuqq~@gU?;?<eVC4JIHTNDD{demyamCe*xCZgY4^s5bYolJIG_Z+S=^fp8<$X z492e<9D;$w5IB@Z*{nv{?qi^&QHa%clNEsX0{|XlM=##4iQdK_cWZ(OhF4e`+|J5& zX<=n)=x06-dpgI}ZH~vC?3W41eY))c4Y|rLLebJZQQYd9gk>%?9)BhH|NU9xjLQpL zh8Svb^=@BzPiH-@wkbL+i0eh#e^=&zU8y2n{LhN3DCWfj6=?p$7X>TOs_nLScI_G5 zepyx$SMZr%_U=XN3tFi@{|N*SH5;K{2JDOp=J9ae$8hzlAbYkEugK8V6le*qaF%fX zO$cHcV<@H$Z!Uv%s=z<cp*K{xLg?)3^jB6ia8emG9s@Z`XSXVov5aZ5ifK|Jv&qt5 zsoSxA|NPnt#}U+7>5JnmqCtDgAdLV};5Nre66B^z)!Q<}!LHfJuXe7E;C(sw8Gzzr zvscf{pbs$Z&oM$ipPR)x7-A*ONCymQthvaJyVtI(m-OOT{xYm<6na&>E2s?YOyHOd zedCScyuZzL9)xiZM$C?;ac}b953OCJU$aw9WsbHl(*<#kum=DZ&l~nx2btH&Rf>bT z@o>16aTL<I3(s*8$>4k*uxkm(YqRAthNlMy)0u@vEkL+DAW<~%1sd3o#(rm;R7{5s zcEW73D~43KYs6q-Jh0cmW~)wcBM$6EXFG}Eow$Z<A+QIN*&XP%vrNO!Ja$GMZzWo< z-u%x-??}la{B-ZV!s@`mhnGW=FP5y?A)i{`qnBjYqz%5egFUx{xjupTj6zSdE4qRZ z`z{x{hTdv0bbpvbO1F(lJbN;u&wm+(RV_e|Z_~j2JmL+(oS`(ZKLHYl;q(UpK5xEa zm7sdbFx!yf^|ay8hAT6@h)I>S<9*~`a$~&Ih|Wo*PI2S$0?Io?_%#pr`E!s)97tmu zOeNa}DuB+FaX$vYPZg!6oE_qO6+DM|BpQ|{a(_(pdb!xGysX0<n&Kl@-2fpyg@QkY zM&ed6JX*FOn@!U5LhUhadvzHIxEX^?<ZMV*^N_}euG+yWF<kL<Oa=i`sshbe=nFdH zwEW9S+vY5#Kd2mqI?X|QFkE?>&;*_bDHzU_?T;yhi;Kpbr8H<M0C1Z;StP@mK$xuf z40{duG=Y<lDQFyJhs9vPETs0aeP{J!5|_p|t`G<K)%aGmTT>^*Pki9ey$Qm6kb+)0 z$N7OCFSQer{Fm>$Dq>;5#@E808qaq!QDM3B1TNHRjV>e;`>u-6)g0JW2Z#3p;H}m$ zxxjbN=`+JcpIbI(nvb{|UVVPgGh2yKP60qG7dVp_Aeky$C3Y}<4x4Aoq|euogNNLq zcA#K8<O(T@Td^UAG|gwIaF`H(<{g4%QHUmR<dB>WfJ1iRdF68WQ7HHk)Gs1mO)*$g ziC=z&NAcg^FIUPtcF2k!g%mS+PtWfv?KUi=-n}<P(#m)#1n3lszYBk6!v)x8v6wk4 zdAK8Z?+pSt)iK~nfBj=eI=FhVd;8U5bd1fxpy&tM{F%h8d&XB!J>yH7K{S)V0X-jN zf=wmku%#VCXQIkQ;E1iU!3T?ig4s^*?YQ~Vy4w{w?Hy!-0AMjxx7rXx4AyNk+B`~Z zn-+ebyUkiDV7qF_asVXOj%&XYfhTeQqQhMUJ)??m1L!*1|Js33HVb6<s$pKx_IR$x zT1<w(f4_pdw%N69Vj?~HA~LWpcja$>h`WNvD(p3;7sKDv`Y(R7kJtt~v9auU;7LdN zVCT$x8vJodq0H}%Mif$L9@fP(eFMW=u+8~^4m-vn4^p8-x<+sr*Qldh;_J1z@h<}z z9{c@qcS;e*1Iu{b<)U|I64r3}gA3romTr-Yxo-AjhL^5)gKW0Q^q2G*{kUc?d$7*} zB#6`;L+hV-d1Y=vaEEPcWa*2g{goLS{EWY|si@#A$M-YS3I(?nKXOlp;3rkZVK+~4 z<kOH>N5R*e?<l%&i8_plj1X6IrWXjp#Q^Zfh;!mM`2K4aNSA>Uwy)~$DitccOTCAf zq9NXOa_0bEs~mN4#|8M6!v^i@w|LG!IC0MCwV=U7{3{)GO`@lCpW>(Zc%w^14|`4@ zDDoZ+>4pPskm1TI++kENne+0e+GU9k+~anFniue!0Ast0`?A64-yxXlAV^-Bb@LEs zT<7~^s(xGi=<nxcu!$#yH-0wqJE&(Widk_Wgs%#k?bs|f!%Oh+JYR4;51c`OUBH3A zl3<zu0ux~TCATx^x#WTBA^l-ycwBtelKn1OTlLl2R>W4^x}i=TG}^AY-HE$GU-BpK zJqt~2%pttsH(WpU+=-pTD&EMHXv;f@r2#1}9~_G(%W;#0uvlQ{Q4~z_J4}cJ&t}@Q z<htW(r;c%uco9J)^=SLnjgNVbk1pRU=S!Wp8~gXHwoO5koUQh>;-3rU5U^uY(iXf% zug`JehTYfNJC(4L@YYH$YWDRl5Y2wcJOgcbn_bjl*)m(krquMF!^+uwr7O2{TNRF_ z%565?=X>rsuGy9v-ulNrqc&?-u{_`pQn8sA@dm$x3kW-HI6c1bG;tP;c`|wZl6v;b z!yG@I+Qm+azD{~Z4&kd^!o~f*p{B^Wb~voq<%j$0Tj!h`r*DW^INyd#nwPllI8~az z%ad{$zGSTTx0A`S9l7H(eBY2|?LMe$yRlpSNHi`$l<!PsNe656{*w9o2iL#!U2jH_ zBSia`!4j7bwzJF81>)MapS7ay6Oy_MqqKuJK0dt)|LdwBLYkiH_4JINM=8ADEV<W$ z`22n5)7+bWLj=yLSc1{j|KRGI;d&Eb{JC{_6kxQk_AkOzg^_+J74Ramnz#gaI&SF% zWva&O_LnpWEYnTO27yW1nLYQ0P595(4eNyTd^K0l%e`nJzHC=jZ$9Frks=-?9krNY z@VIk1eXxZwWG<BnQ_zzx@Y+=oloYpUh?LH%La$c@sGU;^kLJ@|X)1@14OTH!q~3Db zw`V6>y&7$_zr_EnB>j^LC<~ghUrmoZ<)CJ3#N5jqE(ePZ76lzb!Cd&qZI%3r>oed- zMsg3E9M1jv{Jox{oDF%^KG~r$Au~<gtPNbe3x?T$ry1vHYutq^oHBd(v60mFNb{4d zD9Q<Sot~A1m}<EA<II&zGukKc%ezUX+Qx6Ckh;qlQ;8cBrdpS-x308Q)gPxBr!=_2 zH(O@EiEJho`&`L0PSF@AYZkMmYqq*S@M+Y(`a4o)tvGz~ZD?oIFPQ@^a4)vMB(j8P z&Z#!2!u~1*tlZ|2dYZMls%@WM#qSM&O}w0Dp;h;ZG(g-J@hQWAk~N0u&JNkW)h~Qz z8%_!m(Ia-%_ixNJ>iU&ssHcoZ6cSg{wH{-rTm%+V7E_i`-5&7dmR_Mo@Wfx&vWw5b zm*mqS4kBbf0HG4*U-M$Kg8n5@|9ehf`}zs=)w***uWTHg=dLA>v8QM>=q&leS@gc( z-lxNE{cc+R7OTB-SM5A+biB35^()zCOEId}twFUa$i3Q2?Vs5z4mzHhHqD7J{x`Gt zN_4`!m?aXdPRGzNrbVHLzuY32Nk4>sJzW`NcaFXL;FZyJ6+W5L6Ara;Jfmh7B~e?g z4+MNG&tCicf$v4DSbwEM5I9BbaU`fPGEUCu_Md5Ky@rsmz`wu#JlDEfYyz~DL_EWk z1q{hW{AWU7GYl(fh^<67kM`8C+=1DTl0E-oz#2msoD85FWiK^$Ag^Q0_dWHLUHv74 zb%1VQ9?7Taow-qoYTCKIPJ~nBgHN~>V~PDyt#s~uwT%-zk{+-`wdG!!03HZ1xKh0G zq=&%6T9KRtDe-B$PpR$}MG8WJw$pxgu=|Wu$B8m{5#jR{XAQ=&a?4n{$+aQR!?DcJ zQxAQoV?0}jv$AsTJ(e8v>yx=mGQU=@nwexOZ9Ax%8{$QUoW_{d;Cu&6eXiLuN6mE> z$EacpT^x4gJpPlqXC2zT#F_FCO#uMlyfw(jc9y7+X@;=Qrb_U0G88Y<S;021s0MZ) z6~l%BQVCT|LWL~LCZs@=;N}x6f2iG=h2*1k3hAksoPNKf{zv0Oai_q2oiqiC7dXw8 z_NV$;A1~rYiIgP3j=~$g!2Tg^so-mm+=;uo!(OtdwKf;PuXaUi0{wbGQviT&2kUf2 zBXAjxQpjLxKgC%i<vg#PCWdBhJYg)c%XiQ0i<4bC<~aBMhq`L+vvv=4MeV9iE1mFC zOR=_LsY}Z$<*gf?Mt!5nnOjv!TuuvYXcZHQxv31>ytBq3B_Sn%G7x%SgZ4-%&q{jE zvP$HTjjs&=qv{eJp6X2=5GM-74MApY_@c+zA1z%C*YB`Uj<Fq`9Lk07yr&e6TlX(S zHkrz34t$Mw>o_e{zjrc)>yR@&8G%|O_Y0uP*j(+G?&?)}d1#8aR%dgFv$iqF@k)4T zV2hREd+YWYJWSB34Agb7ZfK)_srRiDijxD!3+}O*k@$MAss5b)YB?Kh9VhlNna?BU z<?OEDR-;|IO?}}dslLM|)Yoi?ay1U1c;qQ|JW?DK$@Iw$A}p~%XzYMZ4+JIUlgUJ6 ziY_a7hrPUj6eQZ0&Az-^ESi9RU)u@f+<8#4>tZxg1po{aN5YdUz``^WqlR%CkV~Og zl`e#g9EJY6ZSqFQmPd2*A~JA_$-zDa(%-1O%+p$UNm$hf%t?a&^6BeEH<&l}EyRKL zuo6Ea7t<30l@DfCP#@ZG=5-VE*tIpgVkrRNa1<H1_vEdMxe!M~a0W$s832)wA2FD9 zIMrRF{|jIStuTN>^QYhEi_y$$$I`reJYiQO;`0WMR=*LbW;=8$x0>4B`R(b^oB(!< z3_EsP2?AfNLD+*gl=Rzm45)b4@%1XrSJHJs>|A(xV;;2=nbtu?I?%~Jy}~i7t@J(Z zZT0ZFMrlqX9VXm(lvBi83H4(Sq`5N{PA?ExOPd1n093lgHFn2Txj(Cq#CNLA^JZ4K zgV@C0HZ?Zie{g-Tn$_PJXaxcS3xZ-)(*`U#jal`PHa)2*^_v~Pf39b40st1*TRMV& zt_Obm{G~_NSX5(?BfX<y^mra7g(~MX3ygoxnWRHX>*U3gq#Jo#2g!%_eo+IJ=&eYd zKC|I_KJo3`0G%lFI1)P`SF2p=OX?LhkAk36awn}5qlV%9f|k}DQujuqMibm0dBn!& zn^;7TPlu5nYR`Q=pA<bY^zcmhW0$!Nm;UI<=GWoRZq9wX3W=HOJrmJTFt_Pz5i|4g zbwo?++}4exnAw#xH`_nWeZScsGym)L&DX!@e%xUd95{?3yM*VrlPqEv1>Z#WY0vLu zCdDqx7)1@b%<mTT$F6F=i5k8+|MLOl*1DNd^mxJiUX8`AjSFw0CtK%#Jx{u|>1`A< z^J#v+wg1-l@Ha8@zvq9yf!y9sFp6Ci{&LW7aeFuKP3)@nmp>y(xAz_z-P&;Za`>tL z_I~r5Ti<UQ{lRv${q7x+u4HEiVE?dlc(HUJrxXF~fEOSqHUQ@_0LY25q?a+MocxNH z2k7P9Njy?#FDDZ!dQ(Nz17-*6EBiAsCMhVZ|KCh5P`T(VaDc70$r1?qzh*KQ`fO9} zSiZW^L{(JNBS#8S(QkCS>G8)Wu8je6gU#RGvO~Et0L<picVIwmkjlH3r<anYJ38*4 zYkhX{p$K3gOP%y+?hP5l-BOH6uE9|GPr7%6umivVtzRNjl={9?u9BBsix~}TBT7*? z-ehOa^$)d<!h8SqVM@}YE^w!-&>J^Dx1Ba;BYRtX|I&$fw{Hop>$Cw3^TetrS1HJ$ z;-17}UbTl)@G9c*9;@xYe}MBikFBM)NAL}@1^X%wz24#!&mAZiw#9RiryyI@FC%Z> zm_j+W$c1;<|Fy7l8YbiOrBCZ>*>P|LFT|VqI)QNzlzag#iX&pZJe(IW1#sg?_{F^Y zKsW0XvS^P{fD>^_e1KD@u(L&<#W~Yt`NK)Qn5Vt_6*w{gGtcRi%Y#m_*7|di9jm7x z<Ecrc3tW^W^Hk!wSg3s0vvU^HI7}>onc%COTX5AwXaW!MV%%HJ4Vz@a&Lg99tFNj{ zEI+j9tA}<vI1jGdL9RK!9W6%3-&?DsnJfC2u9vUn+zT?!T`}>xsQ0y|EK%`sE+T*V zYi(`y<Bi94Y$Sjc6m?uiW`hsRklCKDKK}NsgYV$6RpY;zZ}c9aYn$~0vQIV}hP1wI zHYx}Lx0)uLuU&WEy8L9TWj5l{76<{rRkSYWU;F-Iz52=b_MpEX;4ioPPX1{8>!tqV z)xqkMAD3TkHvD+QI@|f4enskmDok_LZFj*=3Z<IYA8^}t3%CRZ2XI`i+v!8y+}!EM zB%RtFkWT6t>Xxag+Z{aBy1Dy~H^GyC5O7M$u1{sHu5lRo00wxk4^h%+?d|jm#k2EI zq-&dKZ-w>aK!5ipoGzUT|LE%b^w;F&n_Is=5t5Ylr@RWT?@#;HJl&rOY~9-b{ON3k z`8Cp~>#aEhst4vuH-8^*{r*CRC?71u%bBL&)P$ACdH_8At&6l9X2}N07PtASfF><- zxv)#$buGF$fBspoDtPUh#rDdWZ<Wn|{O(t}g>>{Lhr$PFFkmQX{F~F1Dt4<=yeeiJ zP^TWdAv3lE7BCW+;Mi$;g7}Mjj;uP|tl*}`So-J$CraL<KF|e3aK`uVr6A999)i9q z-?HQ{RW&zWY?S<SvK&Oey}bqVH^fitOPH77IMm5_jIX?;02z>Q62@wO1A6{!YPbE~ zx`C)qg#a|_4JpaC(La7Bi-v6*0&?*f7gF30z$jGW?hhUilpSz@W3;b4$Gnqw``TWQ z5aL^l{=vUsemultat<V55bU_WLTU`L*Vn~BJ5*JGU78P|OjJ)Aof)s44bmfOK%ziC zdidlGT~(4*hX?+#W$(x<ZfuudB9EEF>tvb*Cbrg80$9dDL9r$J#*41##F?Gs>Y+XO z&m8HP9k&W(U@uw6<5ffw&jJ>BG+3Xtuce7KyTkPhFmJ4q3nBqWlTssP;^?$24JRN{ z&52W%hUEajmU2#aUp1vq(M~OfVDalf5tn<sY5+b!VXX-o%w~C>ty3ev6Qg+hUQ5Ij zcSN*Ew}i$n^}9+>8gG;|-r%b>V9FEoft{=xWc5B%!6f`S<~%=eyDdV(R5w~ASuhcB zOvVcAKq0xDCz0dO34A<Q7G}Z{oYQP7@R)9qzS96wM$dGpXSLt3nVd%g<%qxu+_FSt z9Ux~;h32qj8H+^XO>VhX2-Mbgqq)>nLjs#TD%%vKxyRX6!kjQb@&K=BMLC6bq6QWv zFIIuEjf({W9xj+DxIg}op;Z5v6F+PbS;liZ%)-e0x~K6f84NS0U_R8zI04Bix>b%9 zY(%#XS<1)u08{uG!2yNyArlmyCG0!tWFa3evXV7_b^es_2_E97J~z`KKp9o6hybFt z0b#k}19rk{Dc$(0x?2X8N_Qw+kJ!lE0F1fb^2XF;{tz6z6NlE~=5;?NESG~`fE4YX zq{Nj~<i`^Fwc407Gzzt?=as)DZyQe^8;9URYLZ#%xw$)EiO+wE5B!jBm`nH{zRtuO z>iGZnAG6OG<73}7W6RPq_OZm+cUiL}*|Syl2sLA77)u(IEo4u&C?cusR0t8NWD7|} zk)_4;y}x^Y_nvdlz5l@HocHIP*XQ$ozhAG%<C*Ju74|t;{~PJ~Q9O)Bs`)n1!v=)3 zbH(2oT$bCw(5UNKxcq_ddg5G0c4Ti}U(ithmwHMKzf>0Fu7UqyrDUUOb)UtC0KKY` zYqQS<0D)tshus^El9`kEU&1trt{O10Gy;E`eBR)N;s@kuOVKrH)WT8@5&hblbMhu# zJf*F3JaPwbvAH(K$_FPlO79`$pj^E9NEPr@@39%7wC;@7Z97Tv=Zp`6?^z!te#+7T z!BBmcdCD`4GoesA@i118l~fqLj|)6wihD?&lD)U~1Q;+@_rgAYB4Nl={X0~T-;-6q zUH0Id^#D=RBE?X05!dQ#nlf}+`RZE@UttI1F8?GAz3){;*bNw<qwSXvolS`JGnLCF z(|FGA4L80Ey{=^no-{}pLJ^wC<AbQ~jGfW&S*Ryhb<Ig1$mBiiUl!5jSl6WONWW;B zo`^n1QMczI(yUv|p9!Ppsw3Iwy2Ogp?wAO6O~0_-wxY8wQPa9|+TWw3z^+ss2|-}? z7~Ei3lZ6h009&Ao#8Tab=^?I^=LU;<KZwX<D<Z(9;-3Z*Cs=;9&{yzRtq*E<Fg5}g zMLrUl$B&1t(x&)ncKgNj7O@NN@wYBja;u{Zp7b)^gZ?Znk(pg5?z7vVV0_P7p+b0_ z*IJ+&()bdS|KIs~GaoPR42tGBTgO>|w7n#9(^yZmJtO*1Pf8s@Nzb8Z*se!|P(l7G zCg_T^^zWR|zuT)&Wh3QcSQand-!{YJ{W|gn?TMO>soWu@AGG$aTO5R6-Fyj&aBl|3 zCTM&#!bz$Ue&u`a$5+FunXA;r*}G6rh;a6cq*yHm2ZUM&8hp#MWKNr{496Wy{iPFJ z;4PM;i_#)o0mIbkoMpP0V5&XSD9t(Z{z)A}_v@?=xApNAt-gjOC;#?-5m|!H>GNg> zBxgqL&rrq@`?n*<Oo0d?QVKJk%DVTbfJ2Ay($qw+{C4`;@%<)4fdLE0K^U-k3g7B@ zIl2d#?1)r848G~%(Iq3jSSOJs0fLiPxOc>+5Wp%Cl!OC3Mj%&z?A~E;p)dAbqUD~G z9dy71^fXgYjAQ4bO8rDRZL9tOaeUdqD<0U-9o91r7!gx2B0GY(6=D;Gly|zEO+gq7 zI)6CFi^~OT)u~oW91)VZ?|0m@qrg{^S24Dj@O8UnX}Fsy2xHRo7UO+Pc_(j*T1{!* zs#IbS)fVua-b9Y&22g;Bt7jzfP%%{v(a3DGkC*7kO1S(E?;|ARdKgtT3um&B(7NA* zUFl%{n8XN9VeBKWvd^7zC0f~2Oe_Y>pn8-UB;acV_J!ayT6nNs-f1*u7WdVcA=K3d zYfazNePHtA!(d7X=1~>+`i3(^587UAX(pHgCmEm=Pb!9<xw4c}mWfkG0nt0`w@j>9 zvR4JBXaF81TXD@>AO*4!XFO}xu@Wys0;z(|mi;_KD`{0;$}K+FI-4XBN0mNes;enj zOo2a}y$07yhUz7U;=wv{ny+jM5Y5tWM88{1zgvn+L)i*P*k?E^i&D{m2401i>EoXO zb53A)M4$KP$$h{9jCd*Ng+REFMImT40ba*tmRM*iv=irIY*n;xlr>sK<y2HOJY`)) zIgsPi0UJA!fW#7}M{Wl?j)j;S;Yb?b_EWi{9?Gf2OViyzICOX`y#+T&sSgB`8%Wrx zj>u=@9KDqD_EO+Kl&vZaSLeYohxeRexkKlo@iBBrbOO*okKeqAso+>5Usnvp5tn!l zQUDnpSI)fU3(CXUtE7(kJ3XJp*0HVwl)NQxiy!Bd->=i52f1BM>9eSm_+*p#JhMF5 zB{c%Jf}W{X!fvvGmOl(0+@Av>w;-daYZ{<M2M)q@brp6kD8T8mY(YW5)ovov*MlQ# zfPD+ZIXnj~P-!Nla6?Ku)mJP%1kIoXlNG%l?>CBEL;*juQODojf@aX5Y}X(9;2fiQ zOF}qy8&pT|;6OvsujQnT5Ea}grk3np9g~orbeeN31G9CpGKrhRjJL%G_4#g*8(V76 z-6ROtZ6igF)>&*(pX%pL_U__~P7T<Tt+=}bV6|L|H!7{u3H+r7W*ZtD-1`G$4%tR@ ztpRTu<tBGE-+`bh(;s`@#qnx$QM?O=)0+btT8i6%c*{~MT8h!s)8%)$Pm)n_&|A85 zC|+-5P?ZuN2AJZ%X~Kp*OT+z>19R7PHf(V8x8Nr!N`h<!yRCJrCo1hOakfdR8_f6& zu$&b+N*>&CUAWEDi~MZE?gvzX`=L52WOrUCxY?GeECY#rz%8s&s8<rip{#pTRcY3! z07fmb>cqlAvs}V&Lo<-}<HGTp*mjT8EGBKECAPZ*Y2uAECA*_5(>OvY&`$Kr5JuVt zn#sDuUzT|Y>K^qF1NTIK<}KJAV7AI$<=4a}c`NJ9THYQ&cDw*HFN0Bcl|Lr)-5BxI z@rVQ{wIT*?0T{q%k9W5Cu08bNRfeOe90;~NfvP;f!|W*qN$S9qNZ*MT;v!`!7J7ra zBQSFtmxy&(=g3K}cZzO-eAgQc)kk2TT$EOA%r{fGtE#zFt5k>c(RWGpPh>&$D(33J zHOBgt9{EIMEZ5V007V0&=GXw;tqSOY(P)EXk%*&|p$a_^XWldxOe;>Yt`mOqj*)RE zzo<+S!CDH)GeO%>H(E9XFQ!0&shk;sdf~a_v!4(iTTn$CL&%&iWCL-ogOCZ}(8|89 z(`t!i6qy|mU{|uN=1CXinr~5iarfHl?0q;P&}pYmI8<fO6Fdb%IclJL<<OHI2>lSU zXc!_M0KVGXr`n_F;CWyc`dJ>#VWG4!T4QLn4~p2{b@m=gl1E5gNbfyh7We9KB|vV1 z*fRT^?Nmj$`pB4Xa{-(d;3>Sg!@BpffCV#)<nTsatnC^AmYkSA%3$7#CL#D&v*Y(M z*RldEzI3=E^&ZMHxgLY;HY1Oqo=__g3gDqzaKNGXQ2x3WmjOnNrhL_eRPfpxGKx+J zx$yS%v7QipOekihA$Bc>od=#%aU<4=9l-R$j30s7#c<wB;I|q9z~<R=E!cJtT$c>L zMMQL$TXPx^pW?wPQ<9J=nB35WY(E-b1G=_mZR5d*6F5F2FaU(rvMeD~yFXE&D~J#a zHir_#AzV-g5BSM-=n+})peO%Nqn>4eN_}3h9(>G?5^^whCeoT+UCiiiz%6%hyl%F1 zd|_hB>OqW_Vm&dwKrbW|0vXjdUx$5-ws5j13A}5BWOREL9HZ~slmi{9uT8+qrW_|= zxJ^^#TA&>|dLF44noaIU5|EmBXdoW68El7#VwxJTCgDnMwWR!6|BTnz7^M0oBybRW z8J&B(t)KlX`JO6198&TeHTv9>k|XvW8E<n|x40ioO<MI(mR(T3P*xlF4!j5Lqf45= zHy%w;)J7=S;n`XMKs@g_H2~JJw82j!DPPfm$!rbQwm8GDKi&;OEQZBSXd^Z{896G! zv>~i#M}xiRhe5SA^6AGx)-XlvD+)*X9;h<X15A~cO?F--KawUR9f)yGA?8=tF*Fup zjDl_L0J$Usm)J?ch>-+k)30EwUlwxl!9B?S=xG7wus{jCuhxNc;(6KRbGYXrwT_27 z!Oz6b2Y$_KI3J}9G_do0R`>Hk%?fF}@hH0}i2>KJ?92DcfdWh@NoCJvMG%f{?t#x) z>ayN=Q8b3S39%NS(CcTUZuHgD>c(2&DpF&*xSVEx>&$P^a*{ow8ua@LDi_170X;9W zdzg(>T^h*gZFW3fJqIX~%$`if9)B}E4&l1@bk-&N;SFxRS75)*w@!lj2$Il*_5<0U zu1^8PdKlE;sg_!1xy@1{*ii6x<wsmwu*F9$umKY?59Fg7(;J4Ot+X#IvoxI6g$*+w zT=)&DWW8^X{}8_Mj*o=BGn<6pufAt5a>~p94pI+V<ObTV+n5d3z&tT~-j#Iw@F_83 z6A}E@06L(!${%6Z(`J@9fWL>GTenPYYRyreWpDnfw`+W4qhVG&IPZI~FN2(hzd49! zz+x*fG#Dh$J{K8mb?Oi}gjIf~JfWqC%xFLz5z`uBS9dO+Sn^>v|2cwFe8AD@fn^{N zI$*#$Qqo#W0jFifd(Tf9TdfIxCEl0M=;^Kz7%5bq_zBA@4ok%H)c3?;j}db}fUj)A z(1bxmNqmAdXf|>NGWsZ>0k&MI^eL}QlPim=f}|KO_!?kOS%F_dT2O>Qkqe+zI!O2? z?&Sf7jUXLCc=`Sa`&hv&Z+LAw1$Fwur&^5@DNoCtIDq>U&TEfB7%C3KH47`Tnct9j z^+EVkPek{g@)2e9EF6{Pfoj9EU%?M6c+QW6E2+(>Jz!x<h~S6~cEjVnh+e1$1=c$Z zT7dHa5y~EGG8|!v>s;BlLqV3%gVR_3y;uJOawzG50_k8m>kDGe%&r4Q238M#H6=F< zX*j@)2zreyYtm}9e_WN%cqd#|epFnLlc(^a0k&ivGhECe_Z9Rk1Up_L-=cwivC9}m zsgWX81N^N})@{dQ+_Wb|js6JuD}LFZU0-8xhB|6Jv)F@S6Z2tEQRaJ8AR5C!tki>b z`z0_#3i6N4ccD>sSp%nwig@vaU~v4jz$?}HaJTS{dPrx4{ui}T;_c=2ul#eC?}P?5 z8kS&+Q0aAve9IZo_H*MIklY<HcZM%(_)sznbp=?4Hnxd*cB|4ifo(P71@0mp&~{|e ztbGBXz(|~2WABF}xX}J&s9Xmuk396d6UFWh2Hv}H)Dq10%RF!YQgZHMT=E*k_8_lD zJP!ao6u=D16LF>P%Ps6`-pZ1P)cR+Ue*vKT<{qc#!b@J)OBcZpQ53(T&5s%Ab4Jkk zh+r#y^&C8S;r1tDI2Hgomw+uGBv+^t=8+Dj3m`s!_$ZR$KK6}Q`#RKhzvHK67<$JQ zOamADjw_V{z}9{4Q`cu)J!TzQ8>8;TxBs>_Ie~Ht`eHR-DhvI0G7w-R&yo}19O8z# zHgo!k9AY|dt*Cj!6uzVGJ-PpPGnpkwIWMR9hK<tqX)w=ZmG{LB=F)JXCR-c?G{F;! zjIN0r<vYlA`dSp~FoabXs-i!X<I*6-=@mpmPA_DAOTOO}u*2tN-Cc8j$ic^^G=A!v zTU(^Yu`Gngs}A=kYyaS)(O&8`P5}cEpPf834jk#2Fl{F;z&J&Q119Y9({EV16BjIR z)7asg;u&RJ=&EWch4lrvx{Xp_o+;V4zh`PIJ+fMrF3Oi+nYtY^--}MaQqiMEdDT~_ zJ2~j%IjQ4Wepu$_^fK9W<hqQP3i05d#%#ZBa{Q8tzGb*`uj_61e}A$H{M2vA8Nd9S zS1=Hnn5M&qlp>z!jS4_@E@6Bc^q8bM!(v%bi<wHDVLk84GiEC;xF`x6B^b?Do0ftn zv0Qrki?S#kAZoPBi1%E%ZSfoK6n#zUY{4o_!VU>ntLf9@uQ&9jIz!4t3L^DD>b51f z9`(j&3l*T6uJjTiXKC6^BXuqoE5RhjN<TGeD{>jh#QJmbjMBrKx7;5kn2*f&{4_hJ zz=j``-eD3g6FPo;;RRBt1N#Ho0=`YQ!{8<(#i_xNsAF<G{+I&2O=2MP1F&vnK02=9 zD`1h=t>WnD<oj~$+zc=)Wb0DF*Zc*W&qmSV?t)bs<R*N#r0YmNJmr1e=#&&py<|Qw z!P-jAwXH3)gwqOnU+P-s<z(r>uyVM%TPV_Q33C<{Q~z*hXSNA{{#+}B!@{GwEFE?6 ztFr!6z{cdv)qSh&@iRAKyg^Uig@*!qY<{^?Iuu^iS!xJrAoDC=!j6Q$$WrS9Pb}LK z2miUPR-eoZya(2XOdxEAsEnXoXCO7pKP0QEX`Cw@edn7`O|-QfEle6VeeLckqZv@q zyqP*eb$@#);I3*HbU(drb=E*8nFI18=k^#ugHUis=5g?&TEh9@2a_@@Dej*6EhVqh z!%fdW{NDFl_VG`d*hIbhr83+N^w?xE=?Yi&#a@ADf#0b+KJAM-^~~M=l$liR@S*FF zC5e*mw{C97mi<=1ctt%p#Ws;kGh*`W_knXZVwXgJdFO<b&Ln+lJw<pnMm{IectCYU z(=?H=rZdhO<v4F%tM@yh3lDwP=_EzJZ>LOip2mLXC^gPXND;c`bL1Ikj!E5Rc=0wJ zHy4F7VC#U!|9*CRBG<EvTNZn&%WqieJ`{KHJ*SKO0=MBG7Lq#tJqAH9-guLhm?u;& zP%vxkDKQ|g9nrh*$C2EtBtLNH&G`{}a4bS>k<20a_a6Rir=4<jXjd|eCi-cI9|#td zP#pIZETEX3(urn`HbBCT|M+mzzqP0EYnLEEq8)z`Q89OumCV;!LR(*_>GB$CnnIr| z;m@TjWM_E3z+Wq^MFBx7eQ7aW^pD(A&osdL1c>MCKfK*z^<SZmcnfB&b+fUqu%YM$ zsR31(1jbJkdcvCdT(6@FG<O>$SZ(xbVjeyBx0Q^!|Ha5ZPVu2Lg_gxxl0?oYuxyA> zVB3^&slFJdvwjDk)Vjd#=y~1#SLVfs&r^>d%}kAnKJ0|fTX+D=OzX1h5oPlFskrc+ z2#E6GSKoK`QE~W5q>|YPaSeup_#W0dhj|)M>!&FuU7<(ziC%Rxl}B=0ENs5u_8$=t zU1c7<tSH65+S+?;ulEV9n5PIi#7(%)!}Kj!5JNc*L}TZ%)Chh2A#SW!gP$r5uP5_9 zctB3uHY1cgULG>vvy1p7psnI9Hjz7L#-ViG16z^{kowFKKP-ouYB{4>ogXpW>PalG zD@sPI6;&~J%9W%9(Of2M8Z=eQs*8B?3WhXFNpvesIh&Y2&)#X5eC8nOQ~G?MD_W}B zPYG6L8o#PP5IPV-!Kpf+&fT%@zWZ?1Lb1jfl~G=Os*9V+$EX<4mJMWezTs0f3xVv* zw8EtFKHSOM5<xj*eMkC_8i-dK2K&dnVb}3E)x@DeQywv8byilU<`V0U!p8>dUCju> zhS@gOFAeD~N_7uFlpxlQ)Bgto2armoUHK7izn&)mrv1{1YBE$G&lWDXzB}~_tV@(^ zb#uXifK}Dw%!yMaK=@cxvVeXg8%0>d;fobV!s!X7`o#}y9r?W6;#(Jn9pX1q%`cfx z8DkcO*9Do{uJ`jXfhCurd5d}}jSc`_(k&yT$3Xt|*{7j5Ek$t`B;eefd$Q`8sLwC$ zPO~|KEzYWd_C>o1fD#~^DPCA?e8Tnj2d#whM|^sHL>*60+U85|>9Ekup?!V~AS-!u zmvr)8tD!@p_6EM4jL428fRV*zFVBjj)U<mVWSl#Z=1<>gu|IYNM4j<(S6JaY-6!w_ zge9`1Hyg>lcmx^4R|hh4klgLmsfn}sD=^!G#)IYozmw^&l7ADC?Hux^+)4uq*xemq z+ifMZ^P;lZI@n`9@&x|qqf%4Zj~Tf^loAEG0IVK*z(yaR6HO-{ll)w;!BsSfN>sW* zon^BUdOje{JoGRwFkxkMd;n0<&*b7XxURsZ>GIm=jgPn<zU$r6+}4O!t@U}eM?=;! zzrv?uz?cAO!ewz){b*{sz2pK9U59z8`^m+-vXymajKoMb0I`3W6f-L2z7^tbYw?B6 z!`;*0PrRYFpJ4+Lde+cTJVC{JZ9<3tAYuk=$Bv(9a>?k4Myj{7f1I$H>xY<iPw*;X z*_C7QzkLSeXBs^+w%;$~-}dOWDzc9JNaSmnPkBfryrVYhx2arL@7+N8JCtwZzeIm| zb<j&rZT(RKq2_DczaV<bfogA~rKra|5_t=XkGxUbHu317mwZ}k1(KJj{7~;}BhNYX z7a6O+tx4%R>{0_Ied^M(8>uHdKD?=7)st8CKDIfDFBU|ZcA~>fR}8c7It~9Qx_vaV z_>caEBa$+C<k{tncYMNFTlh7$4r~m>qraE!r3h)GbBTMuXZ#y+fEcpD@M(Rrk#_Qg zjUW>r`X_1Y)pDDSX|OG|2?|W8r9Y$xKBAe%zv|F6+Bm(jbJ8$YFu=noN)Q_VD?EAy zr@^=&aChM+7P8*Id$Z1fgYviegIN3e)A8SEvKFJO@jgB184Rld+f3ggKeesV_-BBS zNL4qtfx8i({P+z=xT1#bJ2)3xp7MaFgWyW26DbPK-O9|f%=W9$P63DG(Rjq5Buc9) z<F$9Oj-)E8>CqsmS(^mcL6QGaJ0*CJ7RsX}%QCe687E1MQv*siscmRpW-N$uHKlo0 z9j)|0OK$3yXCiquH0iSyhi@Fp7kPq#0ui~;{nM#W>`Apr06W*8E=^1Mm|29TXgcvN zU4h7`7fc*jV4PZ~ojnK)B6oMCs@ptf9A`eXkbr-@-)*)j9Zo{N@CI{Ph2HNT*t2er zmvtnwpP=r*-CBjtJUC(Q&<l%2TBhO8;tzHl%qt|CA2VrN>w16(7q#l(naIN`Mhr3{ z!W40)81}gohD$5{+6t$xu$5Ap9Sylo7#?zl@!3;^zt}Uc3No+9rjHaSBF1ud<(@J~ zjFaS?Gb6gfDcT*~#{=m7^mWE?o(XdW=~>Kqw!;MI&`2P`ePI+IFn!(tan3d^vYar- zqDL2GM0V()Rz(w7iBS@WRRiX}B0z~8K`33uxjQ4&wB&)@L-!sr&dM4aB)98N;}U($ z-smeF9MFScH)*Yj)&sZ%iqh`R%?u@`M>{fF1a$^zaKEodwSoN$Gz(B+BvhGDS!Tcp zEbjfmCp$?`ndw994O2l0teFU#BYekUdaW>SGjm65lF(in(-5UW$v^0HCrm-5LyQut zQj#1vX0yn2XM{yr$<cR88m7<h)BE+DU&J&SH}j%42%=Pg!RgIPwnzlh#Oc}uwNAKl zG|i1?FdD|*Ty8=oTLL@K03xHJ9j3cdn!q$m020S;^gNs*Tqh&g-VIK-OBg`4&k`BT zICFqPYjI=ldnm#4==pvm<YPLfuh=++oU^bF_j}!S)bO^CKaEO+g*>n_A4hc2&78F@ z&zf3|sxVzarY?~YsZ~Ey{_=vebs4Grf`>**M^ZBCIS)4sa|8xBKVPdgpnj=51W=@9 zA;1pXO(7Iu#pKOpgK^l%?y$*%Bhoumd@lQb5A%4{@P*Y%Nm&#j7a~_ID9jDx7h(Qg zJSi!aB=&kJp;b4*S<qvLwywh1<Yms$jhe?>Dh3EvFHr4<s$_45Z?wdq8S=`(!tjXG zc$AvPsF^l$w%wRcd?h6dRY+ya)n@8B4~_6LtLd2YqAJo6D7hQ(Ih64`eF<RJa6gGy zH_1h}T!$Vk)wz3E=5N<|;5CEDSm$LvA)<8PT>MaWA5@n~1QW$BMgSRqRBW}5c0J%l z*)h$Ioo601PmlsAC*mz+3sd93*VjoBa^-}zO(+3{_!>6uNFS?6Gu5$5s1F_j;Ny92 zR@My6CA@9Q2=dAR{L;GZ$5<}8WJ|**sKp!k#uKlw78B8KR`=wsNGRGF0&@WZC_1B> z>Amf<rWM5A_y+xy*(7T2NqR9k)`OvT#yDYw&6d^d%QrY;nLv_4{ZxTlI-=&+Xi)>U z{eqlv2N}aV6Vz5Z;fD3*bGi{bOFh)dQDu-yI_AN0q7}cPnGWrLpc~0Pc~Z_|B%>ys z#$F^4`@9B{!W|^MRPkav$qcI(x$o_R3T;z%ph57o_$rj!&Z$V7E;mNK`n=iAx}jvT z6zUF53YboqvhSR72G)^I0L5*^nck7)C+Y-rARI)Pr&)Z;b}GP#<?W*u7Ge?%;;RL8 znyTqEedkm{E3yuzf>9|e+H!S#KbgRCNm?n@T`8!Dd)W<3jShJ_WHXk~059Z7wMlu` zZFDGB45e80E}(97oR>EK$MSLUVR|dWt(9??;|1l9b3%ha5B$u0va^u?`!Olkgxt|F z2P@jn>ATUc2bO(XF=l}wDuUz8?FUb{f~s?S9qdUm`?QYnQa%(3H6-GAvSTF4trhte z?p*Wa%u4FXa)@i6G*ht3>0{4KGIJo@qoa)Uj!v>qFik9QunSrrTQ)lTSr4iiGWC%c z>VbE+<b(E}VER2taYHfUXOa1;s7g2>w^*?*#>_SU2$?D9v$9;5K$V^`R|H&jnm;;6 zGoo@W?y?xy_$GW--cO1ky;Wy9hegcKGl%mW6Z~J@DR!|Hb2|P2IS14}g3k%c+#25+ z8m2;nD%f%)QLv{@BS)Cu3X>gX&r+w(O6Z_CPQ6PQa2E3ODowWCX`Xwd0?)e!-#hwh ztZs6>;JqG@im6O~A&uHU<DM|`o=Q{_KR>^(A|oRE%W47+NLES0{j8`Vvr-L+Aj?<G z;8PGCOtL0QR|Zuqidu49(EpWd5cX8^g+n{vP|I4%z<IXhp>Yuzrs~ZUxAi1C-ls}w z(fU~4KB{s~Y(`d`DTIQ0*t~Cxf19vE<KJ3zvaSiE%suX%IkUk9gg|ZoLFf3GQI`?3 zbkDMpv$``$!$+Buv`;?S!m}`I<pG+TB11v!-A%cZ34-*fo$Hqe?Aiah`~LE~`*w+% zYb!g9Q|WN<I0#L_yNZi5e~P7Eg##{Aix(@;Wf71!wNMjc?+l0u_P;*_PB`>_m9QJ> zleSKotXrnLi^%%=B>g^TW}Tn{()M-8kB38&w5yUXlROzq{-+xIj!Ddnt(EGnR|W-8 z6(XI<3}}@G^3oMdds9*zN<6NnGi`G|z3;PYjPrcqltF_$mC4r2H`f?~bQ^KYKgNtB zFBJF%`Uuf4r;XBBZ>R&*;$eq2*@enCtLZ}YyZq-)pK$}C{YeyP>`~7g9ZXz}E6@Oc zE1h(0X0_Eg>-<e;!B1nan<o_<eWTJbUO!KrlxBKlf9V{~3iD5T75ySqjd=|GRG~r@ zBFQ|xg7L>MI@$!%WYz}Ld5X$VL0?OY)u;hh3Bh8k<wT{}mBdKEYsl|B>8`)6`x!bb z_zVH{)DWF_Va74=t9r`JKBG0M;|zB2lu}cMPpCKwkx5J9I|(#E5<S{JARfKh`Z~nJ zoIo@xDqonY_p^WlpYPKEwju7Pm@l-Tm2Z+Ug36!yABm<gbV)P9&8J>)(VU{`>+ml% zvKN2;lH`myQU^uOHGQ0~e?yy{J6sIao%jwrSFlurO!T)cHkzQ0@W(P4q4w+SPQq?( zs837dg3Vr7WN0rsX+{k-?EXTk%6Y!-&0E|C|G8Tzq2V_!6MaTXEfE_c&qQ*5C8iy< z%Bh%%x_?GgAna~l&9QhCk{@bGfo_QZka;Cy6zV}6z~QL*OA!ilQ9q8H%!a&pE!9z* zVa;4?HDgR6xF>(?E9Ydx-x*mX(DXnWo-*du5T<hHXMvgRmj^VBWnZc+!mHt{CNhGO z5k9>%qKAhY9707966-lOjlbu5Q4;m4LXU~Vis%Tt=o7fmO)Haox?;?=s@qPj5eXFK z8k>vOCXwFBuW6(Rje+z@1;j}}{ek(G>vm4mWq67V%4?+{k`#Fw`O8Bf>bTTPPxW8k zCciWdm$)B(^SKmtwDGCX{bv{?rEh2JT>q~l8cAZ41b~DLo=psH{S|z8TWa(}n8|j8 z({|*!?WjxJmy))lbGBpdY+r8Kj_u!$o4lm*Ix*+{_SLi3bdfvMeRgii9h%d%P?H_T zxt+vIJ4s19`^=o3<U2blEjy|GJ86?U*OqtEw|A~1cUc0v8HaZ>)pxT@c5gWC-aNOP zeQ7r*X*V}#H}B4Fe#`Ey{@sFm8OV{{qV3(=$jgx?l;XpCrRsZSCVS;hdll#QDlhHb zN!qK**}HpZuexQgrhl(?a<6WAuYP;)9`g6}_<F<P-}lvjKQQ^-<n+7w-0z2%ezzq3 zZq51q=+5u9mfw&2f45KmezF`}_ps*K_usDj*Tw91IwpT~wv_Z7kL&JVKfklpmJl~^ z?hoN`lF~(FVDT6I)VPt)-=AL!4I4lN?j%K{OlVVohPMCkBMU<|VRkFXL3NcLr$0U4 ze~tHtgf$o`6Dj+CE64>Y=4;*fcm3;O(Z_X(6vXV`ZDFQ?*T1EUSLRNJj07Y`H9(=H ze|{`vaFxQ_+wr{u%-*Db1>&KBq@>lBD~ng-)7SoO-TS+K@#|;xt6$V9PF2W2;NS1> zaoewg=Z|0AMWQ$ffdfG~*W3<9D|sN!f;gau$$i+a)_+5yFHKlIY;9#ja)2dal6fTH zht!K3@=o`IKmU*(%vCx!RvYkB#yWE`zxjbTC5ejPZ(t*$M(4T;%yX2^uWrhXSJ~aM zs|(zce^cv9$S#W-9?rNbkG1)^_?hqFdDDyw=fC_q`o1-6d8{sI``Ap)c>dqAQ<fQ2 zrN1e@Fa7H0T=y9<0?HTGb`%!}G7sDLP2Y6Yc<@z9*58DK{3vYRIP2KadZpFzYNrPm zzV4~6<t*M;jh(2SQd8F6<C8hOQPMrtmBe%W!XMI)MYTrHm&Vr|o?Us^;)1RJqxoxX zx+VPkg`D>f{mQlZ%8Wl~?QO13KDhYZz5M(6@hYyZzyEap{n^|8Y4T*KApS3!gr~xV zqh~GO5L)px4$U1roy(j=VDPy{6B302TM0>Gmv;zELJCPDSvo&jB1NvcRU-9h+m1w< z;tP`GHPz{8$#jj?R>|up_I4y$dKe9<3?tzfsZ2BZM^af<n!AgZ?+OsoHyvFAJV@{3 z4(5htVbRjL`<^KpGI_rFF*5l9)sJLuop0NfDG0^5q!mO?$1Gbe#w8xU9ly7`ocR&Z zlr5oW+sl?FPd~x|GqQWK<-vRWuH`pf&1EWb0^8*76kgtwt13y+l)qb%e_6izZgrb{ zO<i05YYlVhE&00UW2Bn8N2{2(vKpbUhtxa2X&z~eZtiwa@0EWX?3S+d`$*HMxz^F< z3D?;3tVXZLM_aC;r;p~Z+60}w&ou*l%cqii=uK~JTG56-ii0W@$1UH!YG<!z8@;jH z#k{7rxcPWYV_6iFp*rEeu+}tf!)t7~9G7}lljr7_<7so2Yh&u=8(QC$v5>UJ)YnA$ z<IfdOz_?`gfm!My^)*8uD6l+$<q{*VumNh&JAc9%=xe`jsP`|m{4ktyHV_j8Od%@c z&hm)K7|06)4y~#8qPCjvDLkrEe>8$K8ZO*r=j#5#pjm0A%^VC=>Li^|ry2(_BCfo1 z6SY;J617yH{ZrA&qmksx0D(8{$cv=Y&=3SL?)=kt_NK|wM(EeLvZG;J5mIT|Zyk<i ze9X>r7$%v_o!7MA$}QtqIvzl9(){{|131((A&L9MZ>wyj@d00l2HwF2_e{fnqlYK| ze)_pR;-vO0qeo;iA<p#e+6iHU#Ba!x?*pFkp8Tc|GB&JH)6&ZUJh7De7a3c2?Sv^d z{GQI=eYHHveG6IWx~0a9VvhHR3&$RJJfHfZ&V8X^=?ZHPvH#}5HAtJGNJ^@y2J9F9 z&qU7|%n`n0*a&u@-5`e8=&`C(rT=%TRAQS9m6`5*x;<XzP0Dk>zW1=pHaSS*cq)o0 z=-ag>Y9Rm+MXeM4C8K0Rlgfk%PM0UeUd_?Nb-EB`1%lOq4vU-st4pAKojry^qq%B( zH?6H>AD1*<dzm0&7}l@OWjk^$DuPqkRH|w;crE=(+)e3_^?tp|bHc)evP44wrmqyH z_0)60$RnpHIzrN325o}jN$NHZ`$2LWPh#Rw6fevAtV$K@x$@SclnKL|cjBZ&DYoc+ z=7E}SfFgZNPa5%kVC~SOKfW|OHZFZrDbAYpbmU}DLtHR-ZnimtM+$;uwn7Dpf+T|0 zI+dC2^UUEtGFMkKIMt%rB>TraLSd+kP3nWfZMlB6DM8L;L$*WJA!pt)vwDTv9^C$F z<{=^>fn{1MOT?#fXgwrcS5|p_8@Gkyz6SvE@^ct7Qtyd!Hr=UUZ{dj9Wdnn0G4{a4 z?6TBrz$+VKa7t4}kD{A=J$Su)V2*>k#7FE*_3L)Bovs565RlA-9btKv&Q&EUoaX5) zREi{hCrdcZ3uY8OO^miWzi9VSvg(>~IXl<$dFuRVdPqc>+vsEY=4q~Rr0>1~_#tlO zh>L4+TxqlZ)na+tFqOG8;Un-dQz7VE1`_Bg6RxfLlI9iaj2_Y#R{GLYHjLr&wd@hy z$UW@kse;1p>ZKnXx`}`dyE<Mzk6Xj}L=T2LbW!C2I1eRyv0)G9s+?-ayNU{ak$_E1 zZ4`IXWNp=Ovd1rp=lZ7GZb2pIqDNa$cJ6Y66c-7VYKaK)4f$~{&Oy;n#V_Et#}9I* zmh}e&_%%+cr@cwjby1XPpX>XW`TGnw;aQFBcB18$Tz4@n=jCRDJeGpk={~8K@GJP9 z*ks04FD&Z`zC{9q#c2`m=LDM0aPY+_>%#6;#TsU?RF2s_KCNe1xc>kJ7hwu<U1~r) z^Zqnqrj;l6WS3i_wDv$qGVaQBdnGwmym+N}bY{FkvR_n~c%&r1oc;KU*!!xaWxvkr zGGO+@im5K2AEBi%NO-YI3DlP}PU3smo#1KKTg3!LM_`9)y*=BIx6>*e64xqYFvI_Q zB@~;oL-29EGN_$p>rHB5;@0JlwI)X4-asgaxJ!m*Npl*p4bc*ARTerS)U)~mvV^l1 z*%?+|j=@rVr<Xj$-Pt^l)*$@siQ1P_nW5KihwYK)MiO%mOpbzCYe6U8I~o1~GR$Tx z-vqWjFfqT@80hg!{9>ggiVcs9k$pP_6L!reLyB)c-##}#uwSaV&c+q(;=`Q<0Me_a zvyrZkKUCQ=HAqRRPWFZ(-}Wpod?+2VQl9$oug_xpAupFrn3Q<>OLM05SWfHT$8#A% zN$P6G?AJ!jj{Ss*`^VAKqsph}9&tPLZ{g8e<VB8?T1m?g<0U3ja#H>+<6LuXn$f;# z8P~a{{^VZQhRTJvJbFS`ypuA*-kRJ$5;H&mI?~0XB*sauQ|aM4N1|GTiq=~{8D?+b zHshs4DOP6jhciQRTHRLtE+wl|K5<;y<rEG%2whlsn(N^>bYb_x%gRsn+b@D?qRRt| zr<Q<><dX|xE+4e!g?!YHe%IJYe+Aw@bbR-@{nH=W&$O5Jm7n259Zvr&+Sgt&IKDTU z^>njR_r$9Gy}gNpQ*!;)6KmebV|CGWB@dpR@a`ZyXkU1`eJKV-ivIe0j_28qN?^%G z)<uDJxo4(}HV^Bb>Tr$g!9+i;8;{?*_xGy;X0QHo{#r9U`dik1;-R8Bg~g1&KTP1F z2`PV;4SvQYuNVCV<pqtV2^_6KidojW3m+n1sAF^GJqqQ94gsw%w`v{t^<Y}~{026P zELNagl>JZM*ibNJv6u@ICS(XC7!hgOqBDhVAThrC&UxXuLfe*uIbr?G?TO@3^5F3~ zcCqn~LaMKY#|>Tzc2~6P9nGCpIAQoG*yC_=S0@|L$FXnz2rmrm;Exp2zH)Jkl#3Yp zCkTMA>Nrv!&VqaZkJ=_wtTty|)lS=|djtQ%VAgSYmn$+_2w)W-iuXLx<5AdDFy=`2 zR~c&|4{OxjhFHA<fetY@>N#K0a{ODlWSTbXv`A?NxJ2c5F8S+;icz)WZ`TudbCr(r zvf8A{<g)otU#Js{56>q*9_)@}qsU9K0crDceG(Rbga8LN!;aF*+JYlbpNC8Uz#{dK zTaMf}3B?4%Lt<<_M?4jeNt#9L*_zSCl*&||N&wp4Lo4$te%^*811CAp_a0?x)(i4P znt&k>02pXfyh-NXvOQ4V@p;WYN#g+v4*WiwVH0ihx%c5f16^j9DnQ1NdsIdWbn3m; zdJI(lENt>EYSv>F0Wt`XReB9{l*$kPAh*kw8r3h5r$>wv7o-j8+6^aFuK4UGzhpP0 z8|N=7RRjDD<vM#3mVFBz8l5VG_C~|yznb+p+^B?Jj7C+Nb=XIC%gzf_V{2T+#$5nd z=@93=Zl@%PUeDz*t~gRn!C00%ew+WArneFY#b5aJi=#^=?Y8qbFQFn|Y4>8+hZU!v zO1t${xD896c~fzw)ZA`H`b%ViJMN<-9jCcf;eqq(-Z<p>w8&H3?+d!ZORdsdN5;pv z(#KlH_f(~?yNsV-rQZdab5WJ&uE@&xCsz8W%LHUs1{BEzR#pbq%LF~F40<XP+*cVq zEOY*i-*~}0O~n5Jk5#Z;U|R*Ef&UjgR$$ub*&4$4-|!gPT{Kzozf7dsW<Ta%<Pg1I z#F^p9R$-*@;s2OOPcn|0{S!Ta$IL@bv*cA@G~Ip8R1Y_w*gb&9s_h@xJvo5KUKJmG zk|HL;bHw?+|LZF%U&bn?TS5-s=MZVBKT{n3VdleQr@Lnlpv#|PZtC~kyO<w`tp-W; zZ~IuUy?9-f4&=d-$AkE_A|EWjDmF+Jw`yzpd;pKtxDT~8f0=CXepzJo_~F-gt>Is0 zh90+k|JXreKV;qBy0I{jrEqq*{n5|mkur<h)=%2DzDzv``Z)aL@%H!G?$rH5C;yj; z^z5srf4@jxNxvZ!U4K9J&bt?|x1nc)Nnt|;-X<V4@AYlRcPg(>YF)8`QmDvNTO6vr zRR=@WxD=i_d$gT5fc{%xV5K2^!Jk(Htw!reBBc9E*oz6{C7GW*l!sG|;txXPm0nbJ zB?x6RB~NNzo+@J_9PC(CRXN_;rzs`QCW{UI`8lL!rRl;CytDD|kkt~j!Ks$>8eGf# z6>yi^SS)?)`eB6V=&-DxpSN{>V5OlosrQdT%ApNbF@<Tqq+xIMmYmS5Fg4}bA@#$< zd&Sy$`arc;PXB3sV%&zdTrPJ$e3;z3wqmCEj-vUx3gT;zl^Y7)&#JCgP|f>P3-dMm zVs=*(Mb?0SZc{KnV9TZ&6k}{T?`!LM!XBL9LY+V9Y?;cfItF1SlZ%{1cyKB{b4M*D zP&f2BuE5m3nULriBkEr+I1CfyfMTWu1fBVf+}fv=K@A_LbjP7Ozg#qSWU>-K?KK+% zz4^Gy4TgoNQj`QwnbdXiH@`Jo-J1kYmWTN9rdqvTe*ci?*hp`d%0@fw{>vlkFan_B zEOA|9qx?^hy2@k$iv|69<iQB<`6Hmh2@$68sE%Yjs{tqoPalIPNNyRta)5S>Ld~EZ zFHYN!hrbm%0VSW9DYnW`{Q7<^%5V(O+BSS;7=OvY>!s|I?T<3eQ1Uy9)+RRDP@u?0 zYnoL@(ziw3*jYd}8<0Nb21#waXJh-{<Yg(FHy{I{vHgFF=fBBINqHa}c;DGmQTD$z zzW*tn0u7=RU=FDPrV_jbhYmEp|3zMwnd)K;9ZhBh<l=S!GL*dPVBwJQAM&zh@}5Vx zaIN7;ptvNV4pJqlT0PYgvhbqN!s*zs1|%tz+jN07O|`1QEqW(^{n*AlATI}7H#$Ps z297C2S6_70iEQ95Hzx(nQ45G-)j#SAH2VK%@d*1iI|D_Z990i<>eXKOkT57eLZlD@ zq7~dG{r%@R|0$lCJyDADll307HL+p*6(f>eN;LP;e~Rbj{$JIRR{{};M~{6Kh$;LX zwz{dePd<D4H@7>k^mcbD&&44}K7Ko1q>Fk%$hLIVYywuT2`haE+r%#Z<jg6-SWd#! zY@%qC?2OXq;yWoPAf9$+m?RIuTxkmxpR6QepR9Law|3UBbIb0VGX?>JD+|}ji8qIR zq%cjEN9^Dke5c<|=*{YT;`LbmdZz+D-PCvVN+XAh&gFS#1IP@1VXuItJb!l|tmbL% zo>cM^fZXk#!?7uDXls+ZR226s*@npumtf`M8;z<A?Dp=ilm_6!%k;}(jW4rQ6$3w4 z<ldLNbrN_ln@%p5?ddPf%?@16GdM<b&v-HprKtMw?Ker@z4IpUOIkW4<fKvzp`2f4 zqdEG3ybNPnYqpSJq5|!F2jt~evz(3Qfgt_8-gif8VjRk))ab!TqQW<~N2}cmnmWA( z!|KpoeO6KXXZm@;qEXFnPj<p8aKN24cJlGHT<EYGWHgy&{cAYLrfXMijc79^*kpOU zL<ZKQKU2z9&o6yuW4#|=rsATvC{2eRLU1Ah9<&QL{K@RYoC!i0J^1Gk-)EkZlRDRw zt@UNE3n>p93Y^c-0;<9#k54r$Tr(mQ*G9yZrtna{2xmo`As|=@1zZ8L2IZ#Kyf)v? z{mVR33<)*J$h{#^-uP1ZP&thQVynpFx$3|FV~a1}l=f?OVK3<6JM>rIAy4Ee_@K|< zpDkSPlpKM^;|86D0cWB3BpG_rzay7n@fbP%8#4Jcy~xLDEPl;DY#p5Nm?JD1w~NUy zm3x`rv?_n^jcWmwl1-K`0DAV1RX|%v9l$D|)&eXBtXVP+A$z}nRhF^?TAz4t+w=ly z?Pp4PV=R7?lTe!)051+=dSog5;<Ji306E=YV6xFk>{8p5UKopb?Mad^VAG|y$7<2X z!Zcxu@BYg8%LI{@35&m-e!rlT1x{SV#}Bya4NkIOvR$Y9Va}@K^$$;B%Pj}J2U-%< zKoYOisiiDD=2CPGNodha><Fr2-ya1?3{a`aP(nfUfT4dQHvXQ%z=-}7QfS3689r)s zCt|ASnAdaR0RvNzF+h};W#MT91rM<az44x-sUe$OE=sv9PJJ`%H|Q{T@BxF5*JCfp zomzK8VSq)+bS5?vZNw+TAlu@_A9rzPdOX(KtU7^Aw(rTz9<Z)VRyXy4aP&p96zF;v zbvqWwGd2y>%~Anp2S<armFKQ0Njwp2`~al`F06g>h6@)zpq;Iu;m_n;5pgL<Z0X6E z_-<NXUUBr!qx?T|<(7acFPPxpPp#qx;w%rcEPt9OZ0d{MAtxHHnhZr9^J4%5pU7U# zV%2m)BD-0_Qg+8a5{5~#CX>dw4?`?~rdNe1D_kM2n|@wK3ajMLC5GcOzTa+(e>GdG z@^bgZUPh@HnnNzUX~b$3?Ss(GWz(ys45e&#<uznfnx0$D?e_38QKH`_zYfnNF=&<K z!c@y7d+wEZmhYv~6r%SJ6!1r-%0^5M@F7|=R^+Ok&#=ZZ`gZU1IPXA9FwUGm2E%al zLKmwbw{>nV$eiyTNGEh*+<X$p<%#y6g>n(PtkZGL^^_0hf`{%;++cY%P_2S(O#@g$ z0~F5VH1yGzB~vfNKV=~EsG`3D-wxL&^8NTx>;J{z6*s{&47*DeoiVtZo&Kvi)$@oR z(_^e-zo*U;w4^B>ljjQP;(6F%gmz;Lyr2O!H$vtm^k^^N7Zb1BculAFy9KFzU?V?b z-wg_HdC7g$^cs^#()7qkMv_<Y*4g(~-z|wjTxZuL_^-eCMsBW|+0#U5#&X?`-&V+F zcqDjsl&l&KA~^mD??^|k;QZi6SY32Bp8EJnqv+UKj4~a)k~PLRW_J^&T+YpKL@|z9 zdNGO#O!J0h$Hdd~{4Zg5t_DaM&}mtxs%TFoBO22M?8g2n(H~$mzNcTZ?0!EGHDKzF zX84f_7mTDh{jBcakRIcG!sge9n(vXbww;!XeMB&SV&%{0rB>ZT=*sKa$l2C<15C{A z_dwXnnOo(&s`qwZVg|EL>tiY8bwWESrZ@w?b5HW^?l6DRLF&*KP(|G+k7*oXdc`J5 zp-G6qn_{m}&GXs1tVBy~5vK5`LFs1llz`UjkrJ)*b4~AWgbkf$H}H=MIK`<UPwzA! zSv-=oq;J?>yx*L2FU#rfkvR_UC!3CcrPs8U5qd{{@OfPddMd8|t{2#2JJdDu36l|{ z^o{(p*-TW~Sfq#Bjv7J_h-tTI3wv+(&)~rnbdmIlO)Se(p*`!!#bE}u&eA_6i?1~G z<XY?yw#nUP$rVKXfCwO;g%91&gjT!BVwp$%l_h3^Kls3Jp~gy@NKd_Wn4W0lzSs>b zAGb=ey8K1N!xWA=Kb8{V6n=^kliXQd^d#MR`RLPx{-usL57*gvHrpQQyT_osfWl|- zt%2#{U6ypiD*WJ;%ORZ@(QiZ_uUm1b&rMH1?29K7pJm+BODq}o$a>QA-fr*ghkw7I zhs?FO^$^E5>$j=J24Yt^|Bz=kuHBh9(O7A!rJvt*>a4oY_u!9@JB7OHyA`6sy<}I7 zS)EZ2&x);6TK)vRW+52MruWupOij4{rO{`n=7_kFXPl)*j0Q2Wi>{0>w{AsSUpyy2 zwb;InypM?uk>?C&g2&aK{2u-0E8s3>Di|^p!hq%DqnI`;x4yerkFWu?Bl`P7naho= zb`)^CRY!k-mUXu3_V3Q-9=`h$omVfu`(BF#-f`%o9Rv%w>&WQEl8fuhF4i_OPi>GQ zQbAP>mw|>$>|B(ZV&1xt$b%VgxU-AJhz2ksL#1eUA!9I&0soKyn}33ktZM)fwTT46 zDTYBw*tmYVfe=hR8Qrdr-Zug7P|ziIxEnVUB74mnJ48roaqY9Xi%Qt`Or$B4V$*uL zj)Hj7ARr(`4=_4>)q_vR5bc8pZ-iWIpN-OKyo4ix|F*dnJw>1d5x^tb+1VwE2!7qB z6x^XBN_ah(SJV&u_!UVPl;TjfR759wVmZmi2wn?_a&NNd?1Kc*4qTOD!Wsjvu#o9U zVJL$c_=)|S4ESsoc}Nji(-C!JN2a`6!P{HJ94YdlFB#p7c6-fR+i?jOjk(criItQT zYl03B;cSp~jkRSr@4$$6W15k`vku>w5e%V<&gzfh@}eaPrnyM-y$C_vmjS!fu~)!E zc;h9I84D?4=l8#MQ<?-B#l#g`*Rhc8^B91I1f9TO6Y-DEe9O%Ahza(-VuP@dE3nQ) zM2U5cjfY#;^%O_z<^wP==Loz61DnG=FJ&hwh5^MG9l`~ShJDF>Q-~frq*I~8U*sDF z)5<zRvek!pVgtyBy(cpQ_!J6f;eJGLX+IkCoT#>C8aLI8UX#s=gyUegZc!v~8wfoh zOPdkGd9pXq6PR!k*iKGAV7zVv962MGg}6-je}vg2>sxyuI)BN;w_w~{z<V$e7|B~s zAREm{f@VaDjot`xv1l)5_n}}F--0V1Xkv6u<Q4;#fdvnrTv5F~Etwm+1%E^a&#%Kd zJYm2(Tm^)MCFJGg<rSDgRmspaGppwbD&Hua70D`z<C*_j^FzZ-dFF1`3gt7)IsbUD zL#g>K9=9aqzzW}UB?N0|$zcz<TUM|P#0EN)`>>84TGR#XQY`3sZqTt4S*77IYG$?F zz=^eud_1cQj`G?@6}s<Bv2$f)a}grvKbyUFk-DL%onXT?kz2&O$O)%%o^SzcK$K2- z?CFG}A3}D&0ru<3H(G(Tbz;<WSwj2nZM}*@NGPX79(I=^z6wSia8SDa#jkI$|05Sc zshmwCS*<q3ePtzNquYBn;PWm8cqb0pc=|ZJPzGbN_?%P7OkyJDR<l5niF%pD%~D84 zS$Kd{mJ`2DzRi7)GJ6Uqva`G%4cw%l=cK`;^%RqQQ(UzIl8Qap&`o>ToQ<haR?UYu z-a?N0{*$X@O0ho*VYh4ptuNs!M$f@VvjffTR~-(>TMj2?c+}-PXUYpJKZ9Q=q@GZe zupOF-sdCxhk~?b-h8IVqncFLA-p#&zH#h%oe%sxG>AOXHcZ-FqOEs&@U8^fES6Ag% zSGQHyPFL6ORW}IN+}EsWa;<rIxu!M0rmd}}eY)o9UQLH^ZI@<kk85q;<=TP#+81rL zgVVLcd$l9Nbz_=!2NvHqm+PkT>!#c4-cQ%f?A6T**UxL#FS^z*U9MlruU~DeUz@J~ zwpYI{eD8<my-nA9zb@a~$-lSPcJI&hy?=Z60FefWRs-yG10uEob*lmMxB>gF0r$HB z6lvtvYUDlL$RFD%c&kzPaii$FM)BW`c#-=OTKE44dvE>?b>R1Zzs<hSSSo9cR3tQ_ z?2KKqj8c}+2$3w4U8J!KX$X;}DMC@k8c~gXOU9C{HTJ!R_SJX#T=#X|*E#pO&$<7A z`)B8H&il+U=lyuTp3ld=v(*P8s^#*k<(sM%CaaZxRg)xYj%d}Wo~=2y9Z|#INY!kr z(Vnc){Z&Jjs5Q{4H9A{s5>acGS8Lu>YcW}C^{bX5QFl_S&h~8GnTR_3ygJ9GI;Y7x zmtS>MiTZ<waPDX8-4E46HnHx%us)O6^=j-a2{$uWcj>J7dm3(whz&o4e?!Fi^wonm zZEY{r&y#U)DA=#We>2RDMDzp&H^Z}?;i)*BsDH=Bu5mCdR%1RI{eyyynUg<z0yj&< zj!^JFS&e_W`22GG20h)e2{%N<{$S(t&f>qapRrhYZ>on=lim;&`-6tgOTpOF@p(=7 zIso%zR-Q}F1l>Dljc#T$@DI`G9x71Hc=nBk8)akXx4Bp@&~O?Z2hw-=!9e9j;9*q2 zo{Im>!oHz2xTE9Z%j<&Jm|t9cH|GV63*9DTC&;)NTD@mVogXc_`Vh8=`*Qmiew<nV z1s$g!R=3H(@+-w795yZzvPH*E6Lf#ws@o)!;!j}5$f&<3K&Ax9B!Rt1Y_MOef5*X2 z)3M_m_64rMJ|2FSgAs4W%2d>)m+Os_vBgx_HU|o$B09Lp4h{zLyKbI=?cm`%0O%MM zILyQMv#^uIwya+VPb+kUa9gyfKnD#s&O3F!xo(z>?I)p}S^Sk<*dH>s-KNDw0w-#L zav`JEDEMLu#y}Eh_`7ann}V4$MHNvnzNy{*uj-aK7#9Fo<aEYMG#X>-7s%M#k+}4x zp8R#&Tak6A*P$I8T)stb38sFY*<10dr`D<0>DMWKMsnY&0rINvTVA*QuTx7DSP=m~ z%kArqeCa%iyFfzKIQ5lQ)NN4Vx7fW9r#@E++;A#llY{N4c;(WB-Q;g!^InZ%>Sq-Y zQJns_7JaV2up3N72oay?Lm2d_o7LtIf#VFE2;U;>c<aau>|U?6fejMs0t>gj&VTub z>T@_QDX-EeO93_*R0RfIR-`}Ei`RM@ErIiy>~XfmiAq8O!#bnL-nr)W(@g9*6RUK! zQCa~fy**|00Rx!QAWQ->3V=p2kRWB$E%C;vl&63Ai`^XjE>ZkP9xg}WxkYiVK5$2! z3|6OrqdB<u6gH)w>2rzSbVYeEz^cF<{<)4<0VtA#(>oQeWmKP~KmY;2K{DYWuh8#m z>HRzchyeWq;EugAde1KHr-K7Pkdpv}LV@a2z{Mq4r>n)r80%~z2*dzuup#g7Ll1GZ z|Il#n7;lA*>SxHLJ~~*P0gDkrUgsiA8KA)B{&}sU^hxYH9&VE|zL$zLS0q%hA-DUD zj1+O{XK{V>+<P9d3!Je)s{SHr@_=JQeg8-{3j`v-HYnHy!YG+Ges>!?{nfBxo{1f$ z=K?J7QR>*v0+2fovq8m09U7mZwlz3U@8!M)XgF8wlm_qJX1~!QFnovza;L-jYws~6 zq$=kvf0|*FS#Kw<J4?WCvQeWq-v9K)*wDr+rrx|PdKLexA^Qe$fI0GogV!JeW>m}u z4Oe`qBr0WcXVmmv?5KFuc*)Gnq~XL26T3m34(4G>s<2y(Suz`C;oJtVxL0>|()Bqv z>hb$U9>$dj9OB@KiY>w-jnX>r^^^d8D~Cn;EC_%o{Kc8O)Qihczhl0y;7n`q@Jl@0 z5_#dwJN&h#`Kh*rv)G|O)M@^$))HxvZ3(X6;Jmi~o;~0=IZd2HzlI!jSqh{ry`$Ej zbzzrGVcnlV75s3EM7)IG^51FfmA`kxqi|oSnBR){SeK<>>cS`oH%%D-cB=jAYwQMN zHeYusP6<f(z>VH0TA+lzCoffyA-5IrRGo#&7oZI)mdjX>wSBtCSOZa@Sl#6<CiI0L za*KzfJFl*U<5aP4muPbu#9rzjOb&ISlZa(R7!>?|WBg<`QFr+dWkHp@5n#TmX_bFh zXl|2=nX&>8Sm74fA3#LV0Pt~b@5D>P7Lng8CQ-{lO89K*LN*b*NntNGEf?$J0{xck zK1@+-c^`3cvwnIH2G{Pt9@$_{zT19{RmINDQ1HQNurq(xmsq#~HVS=h`5kdacw}(q z6z(Gj&%QdZXte|oK~4RehYsJJWaCs{e$f25Ugd`yWuZYt0Q(+ibZ*V*YU3ub`r<We zfr1xt83&O*9lcgOM#OPhA0nv>1}>5VRE)kqwnO>LJ-7PL(|Bm**G2lI^`0+y+@|=W z`n7i-4l%yXQ?UcQFIapW_m5W0waGaDg>Sp@OWdy#d+>hX@9hr%hMCjOEitw+JA-f& zJWO^!>Vslw>S0YG>-yt&zr6Fq`RZ|PczD(Ak8h8!PU<XdD1i>@y{kS9)Z%gTR=+*x z`kuYVi@gLrKlgt0`R39#2{&Y&UwjDn^A9GU#e0H}tJ3>50Q@P@Q_sVXdI4X4@5T?4 z=3LpUv5F<*1X3{WGa%iXQx`H-t8-Qw7_Paz^dcNgu=#&9FEh@oXUsgi8X-H7fe_3t zE{F(CJKZYxM>0hC_Njcc|E&0m+b&b?8{ZJ0F6p1rxKsr}gdKS7)EJBWp?%5o!{pN< z=jTz-^2?sD{ocLqsM*JSP#dP~ARyS%Uh>q>b>m&fe^z|OR*c$1UQel<@pf?CU)t|z zaAE)g=1$mc%{T9F^F3;JW5-?13RK#s3mdu072Jl!;(W(1-lLD>3vV^}UG!4*3MqB~ z%RX_^8XBs-F}>pWop*CS_4cPTmWA3EflkXWuqV?R{tHRxx(b~m>_dc`vLtrl$a>)$ zwU#@Ud^J}$HYN?<p0SjmKU`?{y|M1H9rgFmAwRTdDW^8NOt<?5^0gk+uJ52;#?CmB z0Wwj>v=k!SPO6{-|2K-x=c8x^(1ZU^D7r}h1V9nUi8W8@`X8g*e^B(w)@^b+&;Wcl zh~4$SQ8f0Xc(-R7`Jf5ujQ}ZF{<Q9yTmOTiQ9i~D1>m%5_k|7=f4Z*fKPdXCpMB{G z0qPNn_Q(3Fpqgh3b8nx_wEaWTP6VeW8z6OuQGBfRS=GofT)sE5hW!exe0la3?5tWq z>VI;aqvrn40R`bCtKNgRERcaP44``I<pB)=1el!H82IF0j-#!i4m>}<X#*vz53`>u zu0@^g3jOq-9Ov$(oph;#Uv)#iO*$~M<z6<O-Te<m|2i`03Sz#FJapzF$s;Q=d*%#* zzZ>o;6@@vr%#Fp0#iEqJH@-TYUAreRWSB)>o=GH5c&2Ku09=$N=yFUCI&SmWo;^I} z+H*;&qh2zX`cl0(sdwwfB#hdp<>nbi2@hnFK|iX|y8#Y?>yaCL25RU9=o4fuc0OFl zcEWXZ`7BCrx@QJ+TP6)%gT@x__|!MrXtrgVaY&&4o$aad*j+X|J~gf^-K8HWE;4Ws z7kv<oQx;slp9)G&b4P8&fDa}89b0~ob3y*BX2yeEV!&E)8Dsw`Z|~KIKDv*ru9+zb zKRQ+@x;;`_ST^ci&d_`om`v7{3Nnj~w7tSd(Z_OdnoY;tPww#lhoV0ZY7jIZXMzE5 zgkV=(B<iA^LM=Bz;%yNy6^I8`zK^`tn882}hR9$==FT}nu6O3nE|wp*+y7|q5@{{J z&9Vt#+-DsBbReiwANg^O*JfbjMp5Wf2qOrgr!O6E^OF0yubr5<o?Z+2l1#zo@XQW% zA})#=i@pyKbl-C|=^u)o4nzZTKW$$JB4+L#$$CHQ^LcQ`gHQ#aO*{5R-Ht)JztOd2 zo*^=bGSf*8LVWHz1QbhSk2ENp!VG!E_MwCK;oNb?%{z2Bo#JW=46HSxxSedr+1~8s zkLKzpw_n_~`$;}bIF->d@cS7B*Xk$P`TWaH)j51liZTZe064Zptf<n@nnD~T*kGry ztvrwnqI&3O9ggG(9a-mhtDsjE;KX1M4Rx$3RjIjT|9#Qlb*LZbN&5F6{=TyI7_VAK z4uxn?=;k99oC6oykNo~thnqX4GaK2)iK&V=i8cN<tIPOGk5e*j2|(P^{r=rE84Jv+ z*J_{orEkaxpc9B=H~fGk!5xwN8HWhxiG$MJ{DXoPrR#G+*s8H3Iqu5Y2QOU#rN@57 z7^nm7v(7s#TyJ-7Vn6A)hj$6T;SV+vPS`3*%ZQjQGgSy5AMz60lBM;xM?KZPVcM_2 z91O&@JsHTKgd|GP&PYTVBcXqQ7(kDejA20lL^`pDJHT&Pb}H%2T|;d$^&2Sd`_%6d zX`(ZIcgz@(JXUJh$jOS6iG)V!d6b<<+YW#R-MG#|*$|BnXV0{KmX6g6Pc6=7tIF%r zX$dgtG$D6lBC%x#o0Fg8137Pc{LYZ&XrF+PZ4YBVuoc2=E+mJ!r`qTH68o3&hJ|6h zE@_D(=Zw0eirEk%hX9xXAV1hcHDI4B@w`3ZfJ><9zXK29^^QNHD}8?QOJZo7VR90Y zAii%s2imw7kSx6o`MN09tYD(KMR}H(I+*v}!eaZ;t!+Y<LyWpqAVMyS4AE{kQ&%x) z{T#Exuy4O0^dnU+@WM#N>76!2n;d};^YqGlkB3v>4xNyL2PHl#2gEe7nMQVx^5wb} zP4t*j`V6*dGEG>sO8Vf5&^vb&7GP!o!`UFRH@zk}w$$wL2~uf{#BFhioBrO{5}rc{ zpn>$z-WPY7me?NqO1_-x%P~gJ4k@AHtPz({Ho_VGd8qk9*Bj+dciu3RtQImnGRj>N zMWA~}X6}lK$*4^~d)pe-QG^$}WF8`I)utJ8$lE9hLnp$Nz7NVM8@+Z@OA!eYH-cSV zmiIL6leBWmt}XM$X`ON}kaNl)s)T{5L3`UqwkOUUO+T7+|7&O78;8}$@5*Bhm0SDD z-+gU37`{PnU|YnNEfYNm-89Afr{*1RA9$=K?EiJR<BsESDA3?xSb5^zU89-%_ob3D z_LZfbS_eI8R;Y}0n;lQiuYCsJycf09_kO|1Q%`=Qk`AptQ(2-${&368CrE<}d)cnF z+%BMhr0Cw8D_{1~f>{YtF>%Z3D#&aB<N@s(hGFqjX|Z>#WHF(HIK}AuCQenUDMyap zcdVAquIiB;YT?8dhjo$<B<)daCp?=_={9@4)8O~X#Hj;6dK4e#Vibm@lFMRtY{pk- z?*Zj_x|Ft$wm{^!fLz5qvAw5qy{RJT7M1{U8^7R+a2;r#t$gjPqksmVpZ3UVcF%oH z-)*+*HU<8$Ay7I@-3W5)%ji=RR&gLsHRBo?QgeY;cK67=Vga43{an`oLRIQF+Y3vU z{*5}I!6}lu@{aHM_Avt-C}1!BdUu|9xAccL$K2wwle^}xTQwdnm_C`P$#xw8Aq`ol z=53raEXF8>s9b;xNplgEzM3Iio9LW{g`%Ys$7;+vA|`y_hU==Z<8~@25EcyJ`8{P1 z8$A>p<){+-BDrzRZr@YQgWimOI-@L^eM9=ux)AVm%=lWWBu}i(RsI?$=CsHisl@!f zXRvB2w?fPq+Es5Nim5@JPb(U!;AnNlZG*PL#6E7i|1*-lc|maf%9iZe)*JG}t&t<n zX92>Ofunb;PJfM+aCN|phhnZU^o~81d#<@+eyv&v&?I6U0&r&52$@abMj2idZ}K%Q zf0qF|me{j4sz{<LNQcCIzAyUyv{~PvpYw@hDI5CEh^TP=QuX1hZSVAd-re)#8+NX5 zPH+Z#M5OY2bQxIc=FQ*a!V6QaAM17kj69F9PfiI$H_?>s-}2)3)%zssQv#?pMq#e_ z&T}!xGSsemzo$V@g=LZUTv9N!SPUI6&7On!_nnS2XAB;S+qLZVTQ>5VGfQyZ0%=|_ ztM6a!zV93{u)FOf!&P{(G(<1op1S?vucOa($aa5aV)HkfJ{0Az3R(NDm4izqgOmZ? z(RWTS+`%TEsIdoo&4U<cDx2a-C?g|JY$Cs#?hL<ot*j0rDJv1ik=`;zdVUK>Z=&y# zkr$#-eCqs#OV3+?XoC)fu~E>Lu)C&Vh^ok!ERpYUU|Ke&=nE{Lu&*i|w%&Q@1L-O_ z34M-%(afep(&708?OD2_YMGtD5rjju0ZiZuWGt+ki+kaAEt5&VOWoPVfK^aQ0`+nB zb%rI>9bJKl2ea@}{x6vkZsWw7Z^i)RoqOR2f9*@i%YuWYg>(h4FiS-sGcf=c9%k=? zH6x_Fy@K3C?-3P;Zl6hVeE`V^L|2AUr9kWzGr~$s7;Hv3oQ8_z`KSnmGIDI$oYT#K z=Zj&~^=|Y5LptcP(n~U$S4ya=ihUqzvmr|mIFCuS(+s4cMwSw9#$lF8@JwoaqnYEc zDrB9hWE(H~F&F-l3cpKAO@12o#0!5V41JCh(br&iN*Rm(tlR^?Qc6gL&LjftP|zk? zL@2H3C>E@Y31+&LlBF-xcJ7rWbc&i}@~&huu5a1f?+w-qBl?eACTJdTNwjA~cwky& zFk`pj9(Du>66m3X^zg25ZR1u1;Dm>Ey7w?p!JAD&CL^2Z9wxeJ>q=ebzCd=oOru@e zEu_^pPx(g<rj&+Pav(gTS?5rYc!yim2M*2Z1gIRLhl%$;a0z`m3O=Z9(sQzza00ZM zFcgC+r{gl&F%p|D`%h<0&qJ+PSsUNYdU!t4N1cox60*3L+{Z0N)d|jtLIE1LgEScB zq)?19=3vq7w5;@n>O&p}%wMR)#x&ZU;-Vm%P+tzg002(X!E3@0K8NP-0OsX_^jSIY z+WCjkyT5aB4^|F7`;4hz$ULWeEE@>s5XCw<Xuk3-y;wy{hETW{?Xm0To}&an?F8be z>ySsDkOvx3g{qm+x!DfqCTSMA=l__`#LS?-hzNS^D=00--)|%ssA3`+!O(42vATx^ z;k9@{fozfV+lvk+--(1?d%|s^;tf$j%-ce}Of>W|-ZhBujEsC*8(Gy-_<h{+FW=`z zCN!|`{%)am%IeqHGLP@)gK@l8EWR8BjB#(fe0CG^W;W6b!I$w3v~+-s#;m&SNw)nt zUI32HryM6pFMI7ZPCm41sdcO9V|ao1_+8~jv8|Az7xVYE`L4B0TmqGFQ?B@VCfX_& zy>y;%rkk2bK`#8m(kT|=$CXy|sJ7<a7qRx5*=KuCid-phaU|?CVS1p9pAga2lw#;$ z@EifR!3~67zUwP*Q}j)8oFESoL|Z&94cm9;8?h8-gMY_QY_<uAp-lfc@iU8owh$Yy z^k;T0;r~C1{x1|Q@nr0N-0?M`B?gucqz~HQMtJxwmY%Czo#Y^9gTwbiV$2@a?Y6=7 zld-$WsBNJBfo#3FAg-T+gE4>(UfntfxYSoKEO4|R0I*a5L3%3Wrs$CJlu(7`Q&bcc zxUBV*Dp41wCFm!CyI$T9Fp1y)xnbw!hFj$g*Cg<_QyK};ivDX)kz|2>GOC}4U*K~H z^s{2SdSMR6nF_?tA<H73K3OC56LE=WF)#{vi~ekk{jBj9VTRUBzXac;fMFEO3<KMh z($rB-;QP<`5VoI-gb@+hTF-^kvHjb863jzQaB$AQ8sDJ>n=d^tq+li)FYr~hAlHTt zGXJM99;08P1)mR=zx?~_B_PQL<%^G2V`r$iH5N8YjSZ2;Ey(=i?Lz=&i-IkkV}sV& zxG94-WbAJSnnh!NpkUwdu=6}@s3?1$h!e`kKLXGs$+mBVn0I8{kG1Ex=2jseys~5~ zX&wKCj2)u3fu;;(F_<BCoAf%~0)uX3@JT-Qz^j+g%WdcL+7uM9-+66(hX0q_9<mQx z+VZkXi|{c|&^4k)<2Tl<xkEZ1eTvuigV^FGiPOLUQ`C;Q^0px+PDi1QqR=r*#ZA&A z0a__Qz6suTg<k=HGXQXhg@j4F7_G6xo$#x?4&`RPIT5$ehUKzw8w}hEJscs32TS9( z2r(Ocqg-llBBl=`jjUvLA31^R+Qj`J<5#KZ1|oifgXN1;*BQ80CNhWw14;Mr=T^Va zaQ<Lmk#}q?MqknW>DZLg{4g6JA~jCn_?-6(3FSe;@dxB+_u<}Tcm@-*MUW5eRjP>S z7rOj(i6=>ptx*iJ{fEh!*by?qj|;m)!aj1sjgk4J5jO|0ala+k*f<v|zX=D2DdHCh zxKe$-n-e!f#_drg45jezFdiORgZOjsqSIKIPn&pttBT;O?&xl%?Q&Qz=^yCk{K779 zh8L)9I=*cNkGtetb*Bh5Eo)GYMW=;xr*V4cfkXIf=2#a_gZR`4rUE;|#{NU@6uhNn zC&o#akJF<F_-VqZRX_VZ0bfXkZ7@e=9>46G#C33?<J712{cP}{-Z=Lk%-=OXtlR$< z;#zuvi@dBeVsJw{;W^gBGATmm?axEFn>MgTVCYZNXaaw5Zyh>9#r-LNTcATIn}PC` zoOg5x`TcJvIk*r4^78b=11TJ11EF!X*+_w4^!R0^CCY``wr6@$z@pBXU03To0kZi| z7I34#S8=G)7al_&ZIYV)v^GjBnCkU?>$1(liuF$?Sk}?|m1cd%HW*_ymgATyTnufr zG<v!uu)Bx~6H|N-O@~qlkgqV{0)6^dEm)fd(I!Al0N^NV>JDn;w+wEYfi;DW#G;K& z$w?Fnj4umxU_F$GwB`GB76|x11U&UQJG~fjlM1uvzNgT^RWYp|SDL3e{D=O}WcQJV zjU>QSci<O!LzJLqMWZ@?I&hH#y_*X%F9b0GV47oaz^|}tjlGnQ<uIXUEYMye;PeFg zhtU6gABc}h4+6j;qU-i!>>7DMO}t-~xCoVAgv?`oa7HGtYWK20s&q&Q7fxY-9C#SC z?`ct|5)ccdu}z0nkPlvPkqp~6&yUSU2#|vuXaWP7OGKnHp!__zk1iP>RiyhG#i!_e zxD62T8$1kA8Z<z}ib<`?t1isaaMJ+vC;{TZQ#Pf853;2H$gE8`bWZazI2F@g1^UCo zyrbZTND?3_hUJ0_w$lH-#-8TjqUhi$UBXcYNSz4S@DT$S`;NH2c)hi26O%&(p7>#P ze6bt+<bVPnU@5(E(O1&x-sI;EPoTMJE7<^~<Q;BsYWR>NZiyeN5hMn29|0D2i?V7% z#h~90QffbbB;YH^A06qdn*_dG7xn=M@LsgWD&9M8hTF3Gn8UXN(-iqp)T$~Q#g{~q zbk_#?u?EmzL5D!Eu@~7NoN%A?3O)vg&q1Qa6@!`=PJFZhKJnrH76F#%ht&NrznrFb z#ASVnhdJ{S#M}LGfVEITTwbJqP6=<BrG8lC;8h1uus!$<&Z<ik?mY*47O!jIvUcwM zhrLwH&Pbf~VZe*_v0HHA^hKu$A_3>~fsehjX<yX*)+@;1lE3(i{zIDY4HhZ5Q69$W zHEI;VEdn^&VZefo+GHywpJQyX%8-M4+Sdm70S-Tk8KSOtJ%N_|RUz_^bHOV(N!%9s z<JTv=DI(s6wtVayev<Zq<eMj_F!!GK>UQPNEujD0_5l3DUyP0v&ik<TTNmB;yssku zm<5{T7U@Uh`=2w!KhTLUoqiY#3Xe;}EimsG`(uI2X;V-AXWIqH|2+a2C;Hzg`a8)< zJr2^}(<e=bl?N`p3$Lj)Ad7}?J`3&>J+)|Y=cw<0gmSM7-UAF_JJx)SCdjDv)0q$X zb)I`6)ao-CMC(VVAG<s@vsyb7yGK#1PGrETIk19`=pG!%*RSxMei1KW_rWR25nBlU zmU;^i80h_jeXHay`f>^L_d%Zh=Io8><~MWMCyg?r=HC^lB$%*K;Xb>r!K55Nd*x38 zIbcp*{?SWTipS4-zRsr#khksYw2-$x`@IvZ%RZs_!CCu^D(5R$P2|>~=jh*Tt+BH| zgI3>^XGnyOQMIzXQnMmut@|#VP<(3qw9w^e=Z$yGxoz4}#(J0cKNg$2^y&xs?&_ay zIPYZu9knVE_!Eh|KDoMS4iQv%xF|&nLbF;sF!G2Op4q}PxgqUhU3a`~XWI-%e%6qT zci6>UlEGjzWl`z9Dl7S!5axQmznptjSHYN@by;BHO8nt7_m8C3%e@#*H{EkL?udDk zCSNF*h7wwOaAm%#z2)t!G#c2;$?#NEcwls^<RxZrsig0i^q^t1m&A32fuVMlf!zz^ zFwNMQXX~AEy^<fq`p=M8xB0Rp_u41N;QQc`6SZ>d`B5(%qdP~$7iv$fums3rz^XuE zJ{R-sRmEIG%ZbB__xZad)}F@81I%{m#MhJNpd}O4SDzBjxF(*q81bzY=&d3xTr$mj z`AC4>?fF_GeatF4@?f)}gH3Y9?2)XJ9^=RRpE~89znqlkcWi4}68I|AB3e8p;sdoP zSr~BA@jYE%paiA!r2MurOzvE?8CG+RKWt!kPYw7EbNI_`vUZHF6<~|v9}6TF#SgdF z=h+rfL9Jn}Hr@pSrKk^Xx6eI+IRZlh%z`k2xas+uXKo!xl>7|#d_4ciLHPOYqN&wE z?|J?!=H=eYRYY!D$;7tDgWav7C!2a#O8105z2dj}Xc!{__|^)Ru2;SN8zu$(rO9pB z-&L8+i(S5;W&L$)F~Wzs7c?~Y0xsK3+cP=SE)q9yW2Sa??$`vaN4C^SIbh1N>~383 z@#W24J-AL#2ghUK0!gIRDd>%z=O1~CXN_X_Zdmv}51I78iNw2!97*)Zz6{s>KA}8{ zqT9<mB;{Ggd%pNFy8R?pI#nk0#g(;RQ7aO!%CAcSIbJVyBR78>+n@ci%T(`ARnI*b zpe<s@7s?5D?g$L`&egm2N9U;cE&eBvSj1LViL;1BF_2Wyjxm`NKIfzHam*{#BKoK^ zG)=ByI`n8mOFLw3TWN{hWl$T9t-8#KlWo4P(cO~1OpB2oF?7XvsHe|9DA|W~=u(5J z8}f~E(sKkSt-V4Ddv*>cN!sKZ_738BVuRO}GZPHPHW?2EH?P~(GIg2J#!6c}QREC5 zpl(8eWiZgg?rL%o050ZNruf@3RfJCB<K|t_zX9NgnE?H~T>Bmx#2r{sPB~xOM$J?= zGW;!Tq<PX1A01cx`-!w^oJIQHTS@K*I!wD%72+-jlfi~@>bN*}H*xgkwl>wq-p%+K zX#;Jnl!Hd!=8f|rPlA$m-ZwqrQZm5*j}Hc-kaVlBLpiN72?jd_01G8|AqKsD-`>j> z-j6;UX5qC>b!Kf^y+c&OVw%pA|5rxD5{MDd1^5F{|4S4F?~(o=QIwCU-+$K?l-)W4 zqzv~~Ac*bdQ9y6H%)#n84FG|Vw;dC5YxIZg7{MIB<?$+7A=GNBljKCXhwl;8NfvQ4 zzJE9`WFLwiGjhZHlu%H#5O6fm?v~Ok7~o@{sG3)>VRmDc>~l$WDDo)d!c@9y&$utY z(*LSSu;UL@(&q4gWkjzUs^+>FGFn**JN9+?=lnW(p!+fNNKDiez;E2VUWy44>ysEe z?4kvHndo>TOWM7W7!+sIW}m{<9Jg%?K5#IN*)WT0nbm%p#yke(k*XySI7v0yO!C=U zEtX_=nbqT1Nv$-ot;^A|0yO+D$6ptK=@-$>e_k{^{f20P{;zUWvH$=ifz1A2&073& z)PFy)&3keG%vvI2L<0zL;FO8nL7scpe?qn6H6{Id>Vf~vTAmiSu@Z73@-3x<Mf`G< z^S^RbDMbwAEH~ob3NtABpHMC44}x4go(|bl=G=Fz{Qv5AJpC|S6J{vx-e>ptKW44n z7V50i34S*6x=D4ce-G?LVe=-f{b8yU<=v}BemN>YSw_K;b7T%ytp8u-sM{s`lMjr2 zulrYynk?-9PF;_w3;tJ*3Y)&w94+(PvZ-S8UpdOUcZxbYWLx^5a#ZJh|LxdqIBmM= z$EW3{o3aj3)ZnixbA5O9B6WUz{m?R3$~S9mcYTb%%?bPU$CDe4NcK1vEhm`6jU||f zo_6t4{tN(DzwDpk_dCjj<E53=DG9#L%QM&IO2P(XM3MXX7v21RN61N=FSDuYi($kR ztVS8X-=W*>c0(0*aXx+1H9N!Qp$513!YnpSCd2m3!KwHI)$!5^en+|P2Ka`s_c`_l zf#@t$ZqnkNfq1|MLF+^=k#{%rEEa@SFLv<z9pj~9rsP4WLClBojzUw(XhVW2q{V9& zg$qDMJmwt;>e&}iXS5MLG7RmF_O^#*_hQ6vKHQ+Ay!EOWTNvPl!nSZZc|cnjEnCE0 zH5JcVH$ch0gc+a?QtSiGj&9K&d20b-t3EXkk7zNpM-0%br4JvOKd$XNb7G@<%p3ir zZv0r2@6!c838kk?0TLUHg-?DxtOq@CtgP91vgZ3@^v<D2CBSxF|1l8Og4KdZ6n=ed zI;f^!1CRu<l^}{>^8V=Wf@b3G#nFj-qPUxDa>bZaNHKl;w&VOI+PNcYK%8(*D=N@1 zQ2j7IPDKs8roeawnZ~Gc5RDa|`c%7q2etr`+B}Z(WCd^F*jnl*vd-ZfpEzolur)1~ zeHOe|rw1@cN8Ql2A#5M`vAS`Clu!Lr;7fss4xk;xK9WV>PA%_BgzRpRilTvh_E&ws z+^+JRI`m3o-pJ~;`ur=!G<Cf$=husQrb<ETx6wgAmSz}j8cTOmq8inU69ca-6<5C2 zT&cWmXtiGM8C9cR8L?Y!5lH>pxKdfVTbt)AyT|UW0p7_<Yl-~cO6$ok!({SKi5S!U zfRCgZQ4}74_#TD;DX?<5oD+v%7+6JWbng*)_PbGbpO(R=0e{Y)uW$Ju!Oz3z^tX2D z#qjXg09C3$Ru}o1g{2p#$VAyiI?0BiAi2SW9r$X3a=~80g_N~_Cz-T<9G{6SR)^q1 zs?aZX6iF=-s9;aCwnA;5<ct^Wpn_TQdHVt3TSQ~6ZFK?QBxE)+L=N0(^8NW{^kHnP zrX&tmh533KbpA-iy`4`*h2zubTmiYxeI_=k7jmjnFZd+LnhmCI{z(=I;qKsDDqeg% zy%(FQer`XFa^0hrB~)o|s+M-!SV??~0l6+|=$EMPEf<sO`T5?yLG@&E=FE*yr}I*3 z*ZF-_!CU&=_MfAs9f3J+fk_q*<UMz)-WPM1*kBSR@}!SDP7Eb#+McgeIA~xsQFT3w zWhipo=DK)l^{zf{yArE`eOgl`JR_xK9$=c4yYhAvCAo_|?Xi@a5D+R<H-fLJzX%wr z%D-A3xBE?~#S4!jNs#`6$`X<VuYc_cmWBfp0^3%Oe#3X`REuOxXRbR(4&d)-8|~jY z(Z`z>jE}aTQX1Wr;(;lbip`hMQR_W$@yh3-!F&fT6J`E4mC%iTc8PQ|2dX#LlH^Ww zJ*>8PlBcYU^`9~pkKv_WPs{KhrHn1i_YB@&HS?lfn%4RD17$sRl1bSQ-S?Y@w9b?k zx=C~r4{B6S^9?Tdkc+i6L;!6!_F^f^7qzbQ$HBzDJT`e$;IxE#8K^2FH0G6X__I06 zIxNQh7AsZ^ayiK!xQ~yjYjda}!PBx@@WGrh{ii>5jxZTQiDu>2*TfOtVRI5s;>x{T zi${jC{ahz`CJK3iDY{d!JNbOQ8xjpw*`_OCe~%^VeNBgv$6ADM$Qcrb2uE&2S2T#7 zXp@cJ(ctX$HD?Vx>e*w{J?Oa0;E2jbf7zk5-e8$48=`PIY9BsoA6ROc(seA^M*n2< z{lpLC1UXvOO{Z>yofPt#B*tc{+n~Nda?*Hz(nYu%ZMKo)Y;y2s=rl}k*>~df*wo?$ zT%Z})wx8U&A7Js{EDf0r`-~$LyAAcfyAlfRp>nCj6m_yRz5_bmbp$q^Cb)TCQJdv> zZ!#st+pq`|!eXqrSu;#dxlWQy`O_4b;C<j-KiP>ok%DM%g}L5~lJUd@W6a5*aQmpR zxNOVF_|sg2ou`O~yO?24a<G_f%uV{NQZM`Zp|!9Y&f~aa^P{h%e~oKBjh!@AGgS%5 zH{3mx1l9d4xDYu~wC4p6Ed81c*9<z}*AX_)GFu&bi5kUUFpHJ-k*Fq)N#oAZJA~HB z3G$iJ=;qn1&fhr}5Lx@&$OEf)LoFreJpAqs3(s#X)|29+Wv&cS;BulHIMZ*2l2x4c z;-k_?OG=ZlTi6QD*&A*ucb>m>kW2gH4KqfxV(iHV;<R-B?p;iSJKaDkCO6^v<AM9Y z*ru{u^eb};xDY;H$G)NRG|=4*L81!)s?s<8yyilNatd2g1OVqL@SZe3)1$99ldZfA z#CF5khbnXeR5&wOm+i3FJqHBZvnN|{&aBv7+V>ELGo=^rS+(s55`^1DwxDCfe0ChD znsZ$H_3qn?<zsYhUddW#%Fo}O8YKdB5F!q@#fEA9)8Z1`cEoVHbk@^v23u5$Z+Ini z#kYJ_vp*{=17}NU3IHl&1x#{2M4dmesHZ-=5NSR8M6+Z{bxIBQh+MwsQTO-VlXtqF zBiaiKtimUQHo~UAn`oEm(#t)iB!(C!y2bf;_vlAbWBmP3mIK;@<t$34YxTUR!er?! z$cE5X3CN6Hwso)IfdmlX{sC&nc53ukw%_Bo8L#eiANTlvPWcDSkBGqgqDyS2;6np{ z`kj;luz6Ru-{`!=hS=KI4PWXyV&b=9HTDi0SJts+=#pZU--5KJwTix`B`B*$<3hS3 zJUF4mThN;i5Y7y!_$`<-1?s{&bn__c5ed564ZcSOev^Q>+2z(mLh&iey*F3)c8g7P zd3IfZT5=%#<&iB0c8sQRG8EUrMDFHGSeTeQ0FXySW|_dZzQLr_U;r6z&Aw(5cFms_ z5V8aZNT?71dVy&Fdq3hL14^MmJeW?>aqx>|^eF~>m2A}3isX|SQ+Rk52fazaS*XSM zEsMT7<@Ml`;x-L8#WtH~gp7_}c_NFcB*V2DkTLcbE6Iportl0dB;e^alkeB!w#gB4 zaHC5hfsq-=D3-}BKo^}AIkgimeCo{04Bd!WPst=?h$ziJC)uya_QYH4ILVfI3Mcgx zd50DdXbRshg=Y|w@|bXd2D7F3{s@ix6MD^)8X5#3C>&%6k$;VWa6ka38L&8&FfXPP zy3DBu0LsaPL>gok0&KMVcg_3H0kQ9y$*cCe2qm`FMWl$G_~Z5|Npi@qWpGa}><>Jt zX$*Oce9>?j^4k+eB}45zBmBvTJ5*SgJ=DAY-;pdpfJTz2?Q~=ynSW_(9K+GMNWyfJ z2(cuLPz~j@kxh|NT8}M;*Y3RbJ)_Ufu~o)(nx)}SzSy+g5UW{+bYsGGAHu0Lm=*%& z2f+9W96c_?ka5j?1)|Bzto4NX(*yL$kkbGVMThbO0%0S}i!D?x6&6j0kV!X04N=Vu zOb7`Bz6>$4z1l}kdwd^jIZVnP_9W%rwy|*xeTZEnVJ{HlV!UqFj-`0=Zt3RU%v?+X zND!+Z5NmFZCMz@TVT7C=1SE}ky$roT!4y%Dg}i_$2GoUogD?0}Wu3dpM&{6Q??fS* z!5INRPW?V$zDdw&$PE|%ik&RI{i0ELV!u}K18YqL5O>_S$?P9s4x;B+lVA}{m^A>S zGT{R&nT8aGH51%W3a+yQtMkB&Z6boChKeFb$ifkIrV&=G3y}a2^wp%9NO%hdd>k;{ zaY5ZiX*!+A_uO2aS`44yT`bak8P3#ob<YUYd{4m*lM%lgV(+kG<Br1<d-8P;A^|3h zPwAy5ZoxDP{=xxGO5C?42$@i*L-UI`AAowuIQ1i`fCkm0!V(!UG9B3fQh3Br3*%-- z(=y(K`X{n<6l{@^Bvc<;VH(hWmcXQV3q$s4*~;T0Ok%$_q&Ujo%VXy2Ap!Cah#C{- zO$#<qhkRSgNz;H`AVXb<VE<%jOm$%a2N_336ad$6dWCxOU=%vskph)MDD*JkO=Kj6 znqhdw;^H<1o*HY>v(I3JU!Uh<ZLU1j9MrV^iQOV2oXzhEo9FDf0*hehTLS=z20liG zmWt;Z=Um&L96=?){2wLpFCk3nP-7;TPAv^0`l53ga-p#BpD;TvM5L%FpM?0z?<?_; zTzgO99k+jsTV+w;k#tYH1mxaf90aWQ{QARLN5Ks_TiXf#WwWogXp)1uugEjxhz7)v z3pS*I6#($(-bWy1h#nLCbg9yc1v$ckxRGEw6bOY2L85_>3DzmGEI(7kRcdY+1s=_; zcoL5Mblmt?V_7i!ad3!*qC2ID;Bs30$=sc4!sY6672FaJW;pg_-7&}c4$X3#b5D&6 z)&+piSHORt6`UB)Nj3wkkQvEiV19Q=lX5m2RuM-H#W<9bykP-Eco-cX2q<_VQKfXu zQ34vYcxp$--L)EYB<n~H+wFI!S~M?uk&_@V@l@Exa`%_3GX%VfI`-wG2Te)&wTN7A z4#b)s^XX2FF0sUr3eJ28)&n3%cwk#*QgTw}@sx;@NJQ(M+IH_!5-QH02;Y4RmY|~0 z#zZ|MKyv7)GB*4%vG_SdZ7?2Qp#hiArP@W98+K>}G&Kn;YtM5?g<GgzPX4-i4$m75 zaADqDnEE6{mr-+u(NOvbe2fDIH$i@f-nwBAG4O%~hr$B36Zy%;WrBI^DP*Y19oSU@ zY)J*xL`R>ZLMk{YzVt~G72dP2DW3u_CKdP5kwqNb{-o;WzNQ6~=Jb~){y}>I@tTHu z&Ifs<C#j_O1pEvaX3c9>1Hi{<;H^84bO6Ad$QbV{`BQq$n3;6oZMlqEK%gu<<Pq{z zPgEYYqKX35yrPrEfS)5mzxE*8NSI6#<~h0kIs1;LWAT%SO9?a__mL*Vi5+msT6MU1 z7(n>gp$&2$T>Axa_ipK3gYBMxJe032l?UJa1$JXx+u6%7LjZp?<L1^v_T4U3{#_fS z5J9IMcLdnQ6!=9t>M{wsLVo#}gpp`>>)U4O<Z!x!$;rP;s8MVjmz!}ivIlj~>}R{i zEC)NxLjgpL`f}`>(Fd`8&F<#V-a`#)?EL*qhzbLgCYEbUd$bdkdORh?m{F><8iJN> ztNNDYNw`*BimW5U!}!zYZ1_P{cpw%300360Nc~jg=M#_RH2iP8LRL4m>(!w<X^4DQ zLUXugPHNAcXPSKWzQw(KwL8BD3A5zFK06J(I#lV$f|xTQdL+mhX66sm0*qKA=6Zk| zgAv4q#_<KizfpBOmdfvtYP-_(P-rlj|1AJBe3iXS@78|>e`ANdQBjn`F->vAMAlf0 z#3e6jcQ}30xGju-!Mhx_t==3&$)xg9K+(;Q94q^gsTlx_A(m_1Sis*C$6P#n>Ue1Q z&m=1jD|D3~%3NOWimD^F4Ra5jro#dm@G>^4je|N&!&mUoR7>QW#CjR*P)e_E9~EKH zp4Xg9RxGFv((;-GaGOBr)iO*S8R|_1>oRFj3IL`;E4;zhTv!k>_ebg2q(&=9IxFla ztcZyWA;UKlOH~o~q)g%KcCTa-OKan>(VFlw7W(rq^eGxj-v{}ag6t$G_XO2Xro#SA zj;^)A$M|b1V%9v{w*e7vch_m$R>6*rCbsfm8joRW6oMu*M!T;j{d$BUyGEB05iIX} zfqbNr|NZaZ71B$3_XHl-X%W!59x_Hh5l#l{|9&SiKk;S?^-Jvb*Bi)SdV3D7{v9S9 z=7F6fq*%*O9hAtQB{5aYkgdG@2-@&~C86&SQc}La7J%`y)SqSr*8PvHRv>;Hlujmp z0l%iQE2Q;OsokHDI(q2{*E*R5Kh1`J(!x}b`F2RuOG0}vr5=-&VCplu?*<$RyPZQr zh<Y#~PpSoXrsO^i-)UaJpCcYpBq%W9*bldCS(%z-c#S5^z!Dm^ic||99=$#i>WJ7Q zd##c(dk7a-M+)%dp=xUl`S!_9`a~q5y+RCLN=Na>pd#rgGG<cuHC$%8J8&E5`TLk^ zP&*WsJ5TAYmd(R%@lXLwq$P2or>|M+S-#lnt?`vgXjA9Q?@9guqKJfPCSmeuFr(a< z0Hte{vTLoxwy$ciLb~Op5lk}+6RL{|<o_{VVGoV38$$+DUw-^EcwZHs__{xb^Ilq! zxd^N@opo%DeG+fKX3d1xQ3_s#&wyrNF7NVtA2wK%<I*0EYu6fn%z|g}dSbpqGMH1X z988VhHLC}P{fxvu5@v;p3FV+4GnSGtz)S8#AgO&M6}ek+xsO*R)88LP+>mz0t%$lG zv0<XzHwKCyGL2PQ4RQPy+5O)SM;klO0I)Mm*iMB3gN<u%w#6Fn0L;8aml+e(2uWdu zjT@%K)yfU}e?yIIX>$y5YxE($0#*VGgmO@sMCgMERLkFYBToHBnCisW@SX3iggef> zr}jv;Xa%^1G^;QZ7B?m8w94H+KisRfR)O6lqw=V;y}%1kTJL9zlD_ihGfYUWPlQYT zMayLm;wj7s4^c=nUsu3WnV1;Sq+tg3-j+kTo7Y+aPT(56jE8<qg1@A}O{o|)U5s7j zQpsJ@NbvlPeAu%BYG|8<+hKmF4qSMPff%FWc<OORZ@nvxH^!LbRQ)?-)Hp2-tBEaU zFV<m76yARmjcVz2$du(l8g&(1V1V;6Wb!r_DWqzW0CSuq;Jbd~?+N)ZRNmIKX|=I1 zD<n)A4X&S$d(;O%$woh6%vC;L=N*0ww7`eS7Wu1;)vSMJEoA7-_!+DG2LJZ}kQ4UL ztR*2ECGz&M)KP;w$B^Zx*ZLa+ffpX@|2tH(`rrMI-Nuf>k_|!Y#{@+w0KGbRrJ-*4 zv-#K=OV4AgHlOB?3m@{FvbQ<!VJ0kPt$P|oGXJnoKgQ%}(IWC>RhUpu{BVNhJ2A_x z=8M91X_AcrLLKqwt|y|EL2Xfg48B|%V+8>e%f=$q8`6n9jr4b~Jnbr-gAqF`+8)lV z$M<cAoR$yG%&!mF)E<0T7hHbCVEA=#O^)r4fW`g-y~N$l{7_9_I(BX}XxPMKy&_;( z#A&QVE#nwpz}|_K((!w3U$wRGudv#cXW2HY7j0#Xi_DH*x{zsVf-EiYB?>1>&d=t; zFpmh}>-UpixF(9cR#jO{Lm!&k8-LPvaJ{zwSev`3xkzhK##`HB-+Fudvn3fWtJ2B& zDHA;jILk~yE78ZAGqC*RM>5rBGB=Hm9N&MtI86c=8n=@17&<Oncww1qBh1}56Ciwi znG&0<yv&S69UWoLX>(N%9$?!fN8b{$-Wv|h3+dJ%=qESNm=szrGfMNW6Z2S41NTj0 zwx!$@8jD0;MIA5A+!b|jzt|ZwBVSPqiUW-9LYj%a6$86dWPHj^B*-kay#-l)<Hg0L z9R}^61oykD4i-!4J9t#vox27-X78H#1(~1Yz4;;kf~HMLwrZnl<%z@hvf7J3y~s~U zyD)!nQO_q?I^mAbgvJuP<Fzw}<U1d3m>UMMyuIH$%%NmQ|FNRaX?=3W4>HB0G>mJ6 zOto(aS*2e05Q{aED$6i*bXx34ig36feNuif_)TY!<9gmZla;tLz?BiBoZt+ZV;)&{ z7aBco$IpJ*>v5qlLDFY-(?eeK{^O7d?|W|`6ME67N`%kNY9u-ZPF(bq)Na!ct?KMN zn7CcwGk?!bB)s8ALjHrAnT~2#%HZvjuT*RI4VgR;g|+vaODw9Ma9rsaj&q8zJQ{zX z@cRfk<g!B5l()Cf{g?apLQc%ouBI~r4X$Ve@I$rcEtlsH?-T?cusycy8IGIivy4d# z`K;0|W0Vu}VmvrcTRK+fEA0gmt`VN8VOZ!}tGtxoqh2&LcoLx3W}Zwqxc}tb%QDm2 z22+K{J1m5@MCh70=_FxQ^_9tyI2T(vf^P`)VUd1Yc-_;C5~Sb!<68M=EWc+}${~Fp zyZE8nw<R;{wl)WIhJ5RdFwP9-{;%8tv!(q&7!o5pV}4BNli>JiLdcF46ZMklx;w#c z+fp4~(5&oxxcS_TBb_R+2LL5mD^h@3N}psW*uay&7@W^a>L;tG!#)fq_zRU|WnC^; zpMLmA=E^fOjTeHu&kAsN>~hFI&@7mS(1Bh3-FALwU4!xY8?oNW<Ca?9GjW$TD?A6i zxwk)aFuSMCqbMnkl0|3KFMmd=e_8IlFr?h-S<Djo^D}<G+<r52Y^BIKvqX6-W%zP# z*^YWw#BNcT{KwNr2z_2Xo&20Nd*r;k)o=H?OzE56K^sm^MjrB~8+#WUl4Xt!b!vKF zPEeI*1TAU|a6<M;&RQ5=Csr}n$<?CiK1+Lw=pvehRjEN<ondJw^OVncnc132r+?dK zLH3xawz;nN`-OGClfGi6d_B4{qe<OJ<C$PXO8$V1$V%rS?Sr@M<YW$Qkxg_*TW)-6 z%*fh?c#)xw!Vj|yB{mw~+y#h_ov!$K);?O&S&}tPHtA29pe7z!reI!^Zslh4F}32R zMTX`odR;DFH&y!i2nOtm)iA<o*dWj3)MQ{CV7rs=83C#$w?2-Tbw`c}em@wC`o`vC zx9b`t+{i=gcyF@t$rLM=HQxQ1ykg5|PKWP<op<D%V6hsbh^uZSsna5wnzwQdCfwq8 zDd!a>Y(j&}_J$9Tp?e(l)h5=@<1oXMmd=?B8+$iN;Z?->j(b>&pZg)1zM*a1&(Ud- zjEs;!&F5{8HaWb0_UbOcW0G=?=2y-pUsqXsbj0P}QR(AG)^0mWcDx<Wu*r|jT`{}o zsbF}pZohwgFPJT2K9d~5Y!&Tfwo9hEKGG=ja-A0TAsipf2wi<Bu?8Z`0wil!fOx2` z0Ve$+9d&+0X7?Mq_zBXa!`J$^&s)z=tDgM!V&-%A3#Y+$jqe)LpPdEkSt?V0wKf=Q zVDE10lZWKTCdAB+_8u9YirG9<mMnX3uT-;_Ux#=G%P?-WanM)L=zK}~r|a`OUU|R2 zK3<e43y}A8HFWCD3f>HLj}@Q2KkNCv$!+&Hdrjf=uIrOw?;U^0oroKoI04yyDkyO} zQ(0FE4#>ytQpq>8$%<a&0d#F8!q(oi#CNnryXHaLGNBzOaxAe&2)n&S+p*)&gZqX~ z-Bn81yD8V1#vDU_O;y_QlL}Uur=(~yqw&GKIO1>a^{zi7T{jbgiW9el0BStJ*IjbX zY-e?dZLH)Ry~pG?dQv~jO{|S=qWO-OtWyGJ$VLvKpc?(kx6h-0vMv=Hgk`0~hY?lx z$@(gtRQo6ex+Q+SfLWrPoH><jkvG<+3=rcFy`mxms^a#OT9QLXVx2x@1~qi(e8_v{ zFJAdw>2Og}xi>edUFO64Ytn8w7bl}PcbFNTs)6bARfLAKNwk;Fu4daonIH*gVN)%$ zO_EydP2osHR$hF+;2xzZGO>lKrFrlAML9QN&oD!wM|AL6h#@9`(E=M#b`zH=-K%*Z z^pyv0CE49wZH=|mX<0sd#btrz;v?I9bL>4@{zq)S&Dx=N<o&ijKX$!5T8zSqojm)o zEiAhQruA&*Mx0(7K4&bxJwh3-n^YjJVv{tzFC?kJu_^?<-<Y<{9~FDW6!r%Ir2u4t z6~tU3^3J(_y#T?Sfhk_%M+M^pt+f(wXSI9T2~=@IEx<inHVBgFd(cKqK3!I7xuGrl z$Dhwysh?N;gGC;^;Jv!=BsO&ZyNOY)KFW&74@u6M?CABAzeCt=O2A3SAIk<EZMTRW zuw}FeO%ZG_(5`1ss>3ye_FZl15Zrv*r5mBw+7nVy^y`M82<5z5dNRF8>WXcm@`y54 zh3d9TT=1Q-{Y=?KtH5*TcyQJ5D$Q=ygyanXZh?r?<i?6Tgq+L~&AY$5R-!(E%>Hl* z?n_LJV#e(GE+EFY@-QHkNeN0Cu{VYfQ-4;j%d`kZK9Wv<aT<Aa4IsJvC<~&#yg-D` zhHEO;#O;vZhwN+FF~PW9hS-iRNT(!)+)96bJn6bveUbpMA40dcH;}EkVb6<&4c)mY z2L{4ocTC1oyug}Xy2qKI<J9c_XhmVwHWd-M9F|}aF>~8ry&{+m<G)@8bDJ-Qfzi^1 z{6hy$N~WYpq36l?!~9vZnS{0@53YNqCV9b&4-zI+nxN}C?^8te_%(b4{*fa{3@`*Z z;N#R-3Ie9dVS}HQCLv0C4clyOjW1tn696TK^1$x)@%@uW!k6Q;movqu3>|A;&R#rV zHwKDm$aJM9(n#&pM;bTpC8*@7=aosEBgLtSLM%n&9$f*8g~ck2#QIvqV<clOIsb>L zbAM;@kN^0+%{GTIXEvwJ`E1U|w3#z$P9>o^HYI0LNjuo)+?-0K+7OBgNlJ&!DG5o6 zq?%)r3aQkm^7X^_dtKkZ;J)tnbziUd{d&Hhujhkd+Xy{j0Z*hpXbtU45Askq(k~$A z2Ln)m1Se5hgDq|rEiBxe?ZUD8S$iH*tUu11jYw@vi${PpnJ=q~t1(R57S}`BP<t*I z(+PG^W^C;kW%vOM^JJJUzT8q87Mlf`Tdgu{dzj(+q$1bQ@xsGj`D|Z2ED8^&2%#~P zwOPtc3o_fxh*@fA@NW5z=WDh}V^L&?ngCR5S5up8$Bs~D#ubU_gs})MjCfU%^b=4N z2V}tmZ%ZOZ0M(j|!~qPo)`o5&E92U&#=Ciaq$hWBpPC#uF%-|wq_X_*FbbX>No56x zbSIfJj*IRnLrc!JvQNHNn!5|HQH32QAp{b-<f&qB(g0bjL9cg6yRLUv=O6)~?%bs5 za6Ery(JjdkK$Nw)>8?(&JyxYQ#q;^^s?*cLr&I02|K(rQsDt@u!D9eu#^}>69{`9A zh3yQ18FUIFN3S=1>&y8MdUBI#mId23>E0>7^Uc5WW4_C|mSVq@fxRu>={^jjNr?R@ z4ch{?^<<Ll<W!WwKM48Prc{T@hTpV5`>#Uvb&MLb5Edm0^ACXvU16sO*%qDP6Dk+v zT!wn<DrTcp67Y!0x@U?`mwU3RSWBXM_eBq^GFCT+2pk5A!`QJ&!;%>0cEkICr#P!N zTWJ<vrs;0;?mu<U(Q0SD9TQ7i6*;(+OUZ+UVYUy8rQ^%q!v{HMm9?5*a?h{O{cL;E zbB8{jeWl`#qBc7-&vNPBkl$U=Hyj3%>A9<uu9NHuD1#kHV6RcomJQ|f-NR?%$#O?H z_({gDy@pOIeJ`A>%SeHo%ubfC9qf1rGztUrpM3i46V#%SesB_@DBd~lGbHw=Es{ge z5f+PG$EaSpm=Xeuese)d;Hy7R3j64ro<`S^hS-jR)LQ5kVocJcyW$%Wb%CR;e$kOh zh1d53cPzY&V3tg-!IHN*jCrhM`awsfp&1xh#3nS5Lvs@5j*@w&rq6oH)CDB7=Lt;X zC3XVF$SBq1UUOa#3i_q>s%hU2W7XV|-pak5bPbNDVGHesak+IeY{w+Sl8dx%q3Klx z!|Y2QRrw##nWX;>e$`q=!ocEI{SQh*!!~n+mzbzf@K!|2*@&V?9B;Tjvm#OmH5<LS zHLIHHb$;oaa$s~nvop_IG#9_buo@80yYKDL2{t5wb(Z$pdeWnl!MH4>$|?w$M0w@0 zkCWk#8ZnIEsVgSpdkxKxWIZ8~Lo~ko`zOPq$V|iSyNX++_X~RRS5J<F<w<FkgeCCX z){(m#up|mQs!C+{=;=7m&Z&4f(CAyR)+8^;HR_~WZ3Z;g(K+Qb*}t?4w?TR#5RFw( z+cu%k9On#TPiQ(##Y_#}p1x?O@h%H)Sp~oL{rNFzC`B4NF9KLnbVoM5=41wD4%HtZ z!zoMj#M@lLzM?dt$Zk$?c$I+@h2<DOxaGadWO_o7U36#V+_SqNO+zkvn;=_#5cf7n zrIV(j4AHY=Tt3Fg@_Z`xVEW7VhzrS~uM5}|%&U<rQ^%G>qA-vkGSo#nx28xwNZ+pb zI-zI2D3ijv<yPc-vgk;jf>Y-Mt#(P@Mv+uI_UpibSiXo?6!YPZh`G-Uqfrq<4nyL; zs4_s+wPRSW(rvTAYRZg5Am9vMYRhZ?;NN%h52x?Si#2@@)40MWQNaLLBnY#u-PY^* zhaVhs(|3ahk>OvT9{4x+zORMlL6Pwj&5hu&{j6ExdC(Pe(fAdHAq<$ijYq_Ql=W%4 zT)MU$!-mYT)eqC-GWO=Nw>bJlg}AvdZf83x9ws%i<1nw3U~g^gz}|My7(nE+!;Y(S zCgJI9z0$l6=<5WW=jHWB?@zkk@5_y%u!&iZ!Y3~gLg>yMhT)A_LMI(NN&{19dMzNG zEU*q23?zds0SJJ9XvAe@OtSO>=WXg^zi$7qisxr#K@VolP?A}8d5pl$+yi)+V-|GB ztS#DC-5X_>PKIM;;Ia1mT}x^S@oaD5rLH5QPB@#+kXuHZV}>L1&W-%-Q_}&cIl<sP z^<e)HM&J#;3o$pG0?&z3=mV&>Hx^FDO|5-mWi>`WyTY~^fH;mqiGOpA`LJ}Vd~e<D zfJwN4W9XJqS=_PJS8L_cX^rpzyy(}DK?(1e;aU3(-^JL6&=qfi(oAU?5BKfK**>-f zolS@zpYetZ)2RvcCr0Kh#;ar~7|lu^7hQ^i0*(}jzbDJdla;*+F>8b`tROnkD!-u0 zwUscPYodQH#)(%-zbY+GYm@YoKJ3&<hugd}B7yBYL5Np_$}N0<_ZOO?OrvBvLHd(D zA96sL`|d65?9#_ax*<iZ^NAd|zce%sci?~x-QJEBGypkDfdQ)`X`Rx;OGSeecqSK` z!LK!_@rk#QzTwVE=+uT*7r&h3Ip`nub^ZkD<7b=!>F9?^w7<quAbQF4bGo8rOTR4$ z$eIUP5%xcuuDh5f3Vn8QTk8Rb;#vL9%t$iJ1_Pxf1T^et-Fv{!8DQUrie2wmnxq%? zgv>65!knpeD=K4G4n({I1Yi~>Z{PtAO_@XcmJYV*q=yWsd#%em^0k-cz5qA<$=_i{ zsO7_}3_Cm6!BJ*V);&KQV<!8aO40HjTxi$;JGBv3z;PY`jubg-q+mX4$u}PqrR&(e zOB-=PNiSS5nby{iMcILrH)&@Tq4Lizv;|h-?b!V7oOAekaQf41=d-^`;k!AZ*Pztx z$=*Ren>5M{#>2N~qa*mY*@u}28{uKe?BkoPLtM)~^5CDpiRr&CZ+${12|`)Ud<cdQ zv2WaGu1wE>QM-?P)X)bh=h2jt!D<7LDE&_>g4}=<(Y0emy`t-`yPw$IyOARe1-R@H z9hhSaq)CCfp9_t`FHl-m<_x@#!>FdG*udeUM~#$2Ic<PMzBh0=RlMV2zH)pRSaTC3 zo|$B%Ps47`O61Z|M?V!VfgCZpR-258tj>flOmBYG#XTEwW&-h0#1T>W@x0YzouWJS z86-YCMj9I0!h9$K_&rLv?aj*pfN;K6{1RHHb_u)q{xpRhg6CgY9ye19L@hxa^r!vn z>EgyTIekDm?}!QqWJ!TodP1B4>V$Hh#1-YiY1OS|BaMR%Su0Ik#yuE7h5=NTffJLQ z%!&bk{d{PoG&8FmM==~bH~<eFfSY}|C+GZKF`@6UdV@yWP{b+}zXaJ8LN^ZwxBLO| zDrrtTX^MHYrC@qx2gG=Zp-E+UMJYRxMTtwyOdPzRar634C%sRsH2ol;3XX3~4+}}Y z^@vHR^q5U)8X=9C++pYFyVv=8Lv+)EZq_8{u^|aDtW_uh@E4B&r<Z^XJLyX%zZI#p zrN1D$62y!O-Wfu-ALXqG;_@xiH&U!_eE8$3vL5)mP?6PIs0{7tXGimyF?o>mrCduq zJiHSzGTD~n$%<)&C#+hjJdxZ=M}50hyl^O|sD6dQ#C_hT!nu&>wvGFKouLJu0jY#! zqe8N)!{fIvbK_O8rD!g0@{$)?lzBkZPZ^rOSu_0g&$m-ISC90ha#_)sZRRs8Segkv z3JdjQ1>xbA$*=`gNkfpR-^#eo)4fS=JCbL5^S28kuRCq{-hhv&jAl>rhcm&UuRd*) zwJ>KtI}jHJ73?f3fX%gDSdlW$ySF8h_yno5_kO!rTHfh1#448T^;<^sZN%!?BSw!~ zcs>7*taT^#^YVA2$(E?cWhRGz7*DkynrJ&>bVfBSb@pMOk**;caM^HWcE|cu=!Z7s zodXHKjJIs1_hh{!dKew(N}3<^uSZ}^?Th8!Fnd(bw)Mx-oC-uxpXS>3?zQ?``l4as zw46=kWFEF>QCh`*;m-hsDXZa}F)FP#n2&6TZ6NF!T&%DNx--@gcr)?u|B|&#e?-|H zS<A}@ufnLeVy?PCeV9g-jeaThe+SE@-r_QUB)@F>IieCKWuT35mG!R}c2mwTKWAI1 zs#BKwfb**G@J-4XTh(S>x5w9c=uEk+cXNBLYREjzD><8M4%e${&zq%aeh$dD5e|GW zKKlR2S|u5!HnTF{SZaW)+%6TKU79bhy)Ly_qei+`0_Z{nBCW2?-zu@$TFi^~ql>t= zpK}wlsMu#;$q6{``7lV+!-Rndc#6~^@m$4lRX{nyqL-U188na#&DY%%z}CqCm|-bt zstUZ^O5?s=_Vc25|BtNoC1fOaKK<LUV@*|xk~yzE1>r0ZzJQrb%$JIp4>Y?JSpNdZ zB-@wG`wj(FF<*?huE)%w!VderlF*gw-ZntrM7RuMPAriccbz<w9Eb=)$Y>@xTrBe_ zFgWC|s+*+^2LfnTX(P7J^N*W7{I%R=_Q=_=chqJrOe+s{oz>>9|5#gY$h<vbuFr5F zjPC37X%dWg{FHrb%~p&RT^|QOexG9}QQ70~`IKojh}nAeaJ?U8`qFjj2zFLpQ^Cu) z)m64}p5}e;Or1=B;bXV`Q>HYEWr_WJ&Xn1>zt0Zqm%(xa9Q)4zsY?HwNZP7-<Q(L( zTFCsen9X+~-FN4tXkqjdZRDo3>p;OuihEjdnrOAgFPA|T24In=yEg<xOtgKCSwfmy z-4IbovYQb>GpaS+j0D!pjf$L(Ja+qo-tKKN6iBdMzS{KA;nPc6!*>}!b<3y5pWe#( z;@pK07_iZ+<?ZxkboPMlTdRuakJA|m+%_$(ufz7$99f4$@y0T&?|z7sPOh23%%&X8 za3)t(&tOL1Fa|IQyZ1?!`Pg*TCC|gs?_6Tir>$R~9_`#}I?%q>x*}vo4{1fVN1ry4 zaz{FBn4)_J*d`C>ixa26YGS%Xze(rb>CC8AtM)7z#HTW?HX@}L1HlMNbh-2~Gty2^ zy6n90JZ^PHDF7&0RK22Eb8<VzEw7-cq65Rm)tz#8(v&Tqyjob*qxwppjhb4m+c%V` zh`7L3I1OUOhe6PQG;_zYOv#~;QA4poa$L1-eX%NC+w*mw!tYVIlQ3p?`_<QS3Azl8 z=6UV(?V-UTQK}<X->o>nUneYx?G4Bnj2(V#V|At1E1<3HOvOmxrLo@BWU#~nFA7J2 z5AO4%OFkEBT9(lYbLJtc@ARYgSj5|I9iwQKcT88=k3<#|okX>}s)%UeD$8gRp<8G~ zlZaj|lN}Pm_i}nPST#(CaXsYq<ncv%AlxLIgUrJ9n?_+DafCGVV3)STi>o6UQEuh) zE$%4SHEq^&(~1y;ib`&Z<Z+A^{X>?{zj_PXdum4e;_rFtD%2E*Zv?nhE6-r6an6QL zSeOn4tno9ie8(UeW)ad2SMaKK<jg3oNQ9zCM{DqadF}&Yul^tw71DOA-sVC4Kd=Ze z$Y0nt%EIKUXAnPBApox~%CK6%&(de8U&VVk5Bf_!jnTm;i=At$`hLzgzgD$xDQ`*j zJj^~Ua`%ZguOm79$Aq_Ai*QR%!S}o|O_O#_$zz+)+EG56=wOH-mIi5+&T`X=YMbnK z7)QxDS~K}>DxXDNQKRK8-~tQfgetg-4e0dI$*9V&0C^o|I4Uw6z|iW-vuzaIDc#^n z+4SVk0?FlZutAs)sT)BBauptk%7t#Lq;=GZ^msovL#75Wo!3qr=*uZMX_{X9)Zo&2 zqRLZ!i1uPiQ7+R$8EE|A1n?2Z8$Hy%W1{P|;}wSNv@Nf^G`w~HxfHxu1eqSzjcnw+ zmlgne+k|kpgBVSdT*94;C!QB%cRVD<l_PWdh#p`^S=-w^DvKObmSuC~1R*#2J?^pN z8YkaxTYTCIX|K`$;6Io(IT!Uy+QW8`(my&jjORF+Jh2!nL6yd#s<P^3mw>xpchGdP z>r2~PfBMd@pzVf+u9#^q?>t144FJwd?Y_1P9o3DMMZb;L?=w<~P3?(uwmdIbzuAym ztJ?3`WBtWt{7c6{MX5-l(-#^NsD`Mf_`C}?4!IMR#XHt8JRjrwtu)-2C>76j`2}zf z7)cwtqP|m<yQwe}3JCBAT+|{q_FGhIvQPBY*N&3drao7!o?@VS%dIb{^><%&xZk2E zj1dCrXzCZ04R;)*^^t}cs08Ul7Tx<xk%cy+b#8Jca#M@M`yaLNXL>lq7=Iw|X6<>Y zEr{Hxw5JsYBsMV9tGdWx2Zp%ZoYKC*_yD+?J-eCn_}0SpZ`Z#flA2qmS|I96GB(q} zrJ0BME2tG2#EDL#a`i`L?j6miF)zo?C>|JXEsH}O$ePtol4i&);q-N!Xf`_1&%ZBo z<4pjXgh1wwqVbiQG?eUx<2$s`*H(-6^u#OGVS;;qnr!fP-pPNJ<t_+tdq#gYE6ijm z?ATNKG#MW@jGaT2D1bwgD2$|5pjYJ#W*+<X=l<ck$j;~7OkH4xbNNyaX*Ahh{v+<` zXSsuBS^pMJ-}gFfrQ;xk-1I9t5v{b{kn)K##jj7=D#IVI7*FAm_s8dgc4Ikvws4fu zW}`;Nwh}9B6pENveQ&lPQzg4c*+LxQ#i0qX<SQuPjKPXuZ0a!>z_E#!?)^L?Br4SC z_#HR<sp|i$OIUvM&p+(f)||<Mdh{8@P3CMD{Ac3lB~ZcP>S*8CsljQBfn(Q`npGcQ zpja4TkHgB<>|^2@3OF9osx#+>J-J&oAc*N3cy9cYqd~1*!60@bs54YYo{?s98ElIA zlz<?PKeem_nTIjP+<N3+pKG}a`n)lsU(L8W5VA+~{H9vybaIg$1!Ay4(<NU(2+knz zazGgE&)*0&t8-JO`{i8)E4Ni-8_(ZMAuNgrBko>E9+lS6XTM|inyPNmttka;bBw%u z<oIfk;|93;bGg3f<q0yk1r==A$$<1hidxT}2Lb2#O4(`>!d@5G&t85TGz0E{f}H?6 z9P#NbSxP!Yq0UnozfXOhpdf<1e-Zs0*pn)d_?|3c&<=rm@wA+0AFNhf%_5<~7&`8k zN%jzx$$hvbfpIQ<7TaSz&akaJ>zC4J0Or%U*tpdoyDWxvm_TJfAWIUU_*nl{n(7c< zgD;ROQ2A@WPkx*$bFEr2h@jATdT~1J?bU&lc7IU!6Rh%SB1u6zLd)id=qo#a$2tP$ zKBMf<`HkCf!D|#S1R?iA&Sh)t4H=CqdVl`ol)WnWcK8-ZW4oGdD60Me)Dd7{i6dD< zkeVbb3|%T9yNsL!b;)3_UCGl_W9IVQudIOW!eHyMTJCZ48Nz^!N`_h%c!zI~xilkF zK|uk;H*Wy}bzlbzqGJfr2^KEul1rSH{Gc;#f4{<92<noCnhaw81Nik<!{zJ3l|{;u zo6+cO5Ndq7YahKnLv9IEGg#zjwu5fXK|PGu-kZ4)iaBjZA}Y;?SDQR3YhhagRPP(} zPLrS=6%3o+m|Md!yU=JSheGT0UTkjY?paXHADVRHiz()X`q%HCN;2iM30UixWYrL4 zAM)MzVILDs+pxO5+hna0W_<<3paNt~-r|w=kri3px>Kmu{BEmUV%T7@Z``}q#+vYw z_vhPRo3@J{Xp_)r7a>~=uEd`2yrSkW%btpKF;b?<;}#>_Vhf$3t-8H16`C^7L*xAP zGW?*y7a4MEG>uUR5C+lD1nWyFd~P8aHpk$kiB8!NYWu$9G`F~_NF^r`qvI^?dd2rG zo(EV0*`Z5Pgaw>ptUQJwRiV-tNk1S7K_v)Or9-5yh9~_E{^L5I`<cG>dHh9?9xIL# zv>Iej8P+FZ4!ANhb%u1?1fgx(Se%<JpQ&9xyEo=#_E>}O4n@7ynB7s}qyf;^6hCFY zy4*ZhF*|g{eiBEbyL=h-KePo(Y4Is`FU<WthV8w=JfvS4wRAqO$C4vJ^5)D%UuK@1 z2z78hRss&htBSJviUqZFPLDgsCE00-lq>KWIPmodTCN#i2D_?=1IemJZ_5`hH6Uko z7aje+Vs($)#qjrBL}sFIrL$qi;Dl+qfXS;PDR78Z;q_+@T4i-R=6M~gHrRBlj(@Tk z<_WWJhZqcKRBs3U8G}@v7Hpma(vz1i!QvITAjvwA(H~yKNmA3Gf`)6A&l6FDX5tkG z!#dN$HlcI&>GecAhJJdyKeKz=vM`Z5bG3zXBB$?!dtX~G#VF4Ef&xUnIdu0c8ZpS_ ztF^B5^yTYQ%csk>RM6wwD{xE2v!MG<A3cIx{^E@I5%n4(VaF)Eqm_+8S-bS`L?`*v zjUBb_)TZ->1CJ_t?us+RB%vm<Gg57;(tq?DKE_jJm1V;G)P@8{W}7r06cXi|h`Z>4 zqlM`(<6&|2;CO~p1pynvwe&pjj9z1(qvWHgU{I$=_3dY#VZI20y|B6d!odx$BUvZU zwlxtb0J>jkDw5O$&Qyfd53b@6E#)70`*VKSF(4y*+0)oV$BGv=lrY?H^4y?;nAL5L z>nRrv&VT)SJ3_BLfVl9|XPVnb*tKG_sG~9e>A<xnLh973sY?xS4YxBBbfyJL0Q`Al za|&00yt-wQ%jwp9cY3<S6e8ZOz2TQ%yo9#8c#(OQm`>OCeS7)#VxzlT!n+tTm+HM& z1jXH;8a~Lz-nD!Ie?9g5#B%)QO9M)tw4}R*i|QUa%ETD&`iJTo(`BYVF6}ejK{U$} zgb(%1&h#BUS9>)4xu@U7b7MCSd%M|4kB7JIvr8u_+nIHZ3y@1oJO4$?Z%|g$ZeIU# z_47-DdbU8_^y4>}OKwRyXlnlto7L-r08<d(GAqdnN1T)&UH<XeKGg8+AVcV!u(zFP zZs&T{FQJb`bRxSbc%Dn)nwZ=7N-r9&{7t$Ki@$tGurPmZ5Zct@cLjXb-FUSCf=oGI zc~1NGmY^*8;6$@2fNS+<PB?96Ew%R?qT@o^Z;IVSdAJM5(Qu7wkD&R*e}_Q#3s$bL z$IEkFRFgqULxMl14TBb6kVH=p<pbwr%++@)t&=WZJ5JkIGjHB(`pLl+hi^rV_Sh?* z=3Y(Oi^=;BZQ7p_rzGblI}~wtL03+6foefpJHK}6jIq~SkW4OU`tHE%SAvb9*4E!| zzc02LHOLvaKEX~3%DA<bLv-)o3}kwwSB=&V(Lx1wOK*;^qE?VSiGlc`v$OwDZOoJ^ zBIfhC)(OQ}^@08BA|G!aO4M94^5nSmg}*amr$s#>Mpj+%8Y|h^9E<(gY<ZvN&_78X z+PborA}OYHi@p?+*nO2~EYSE<%h>f|p5DB*Y;YMiVX*S`pHA80Isxoce;O+c3#qr; zy`f|7>WC-k<9o_Bn&mv0ncov|RF|DGJq4z@p`+iln&NfO5qGS(p!ipJu3ILhhN}Ic zC~thke;`vwXojj*G%R889c9*(@nO(Y=YE;c+se(%dTU$EB{5K&w0!}JpQ4OFCx?yh zr{R!Z-aT5Tr9=@hP|gw{H@>Y%#s<k>v0@v)x!Aokl~xYDJecF>PxQoWfHMuP1HWec z!#uO8hM0@G=!X$aB-&s*&2MLRJKkqpzP>LsnYBLoEg`iGq~f9RhpJ2&QMKCI=P!N* zf74nrObQsal3g8rZIK?%7Flv<MSQz`xM2j6qioLsYgP$@&ejVqYJr%$^gW3IJvT#p z)672%KN$!8y(g+?M?=(yDvYO36(>lln90oxFehC;DNJfB!8c@Y$9NAERY0seejGmi zb9{)&|08XplxeuhxETHlcDP1=G@$U>#J=37`aGjsI1~G-o`^OHBa#3yPD!>x0V}Vj z7Sbp7fV}>?a9*V=tge!j`|J!na!KB5wz<}2cUWe7*w5XzFJPr}SLUv`z&`!huqOrt zPp({&3mqCxemW*wW8|N_-^^n0A8mib>yM#tF3}%@Mpu$XF23Q_3%YW*6srFWn^yGL z<b7e;+Ow6OW!(o`Vb;pVOE7m5&mJGfZUsJY5?MS4jd_zs2c+$dA$pC6lg@P`H-oQ% z@XGUeoOrF?2@~1o3k8!Hxz*Ja)yShqZ`oM+7&+eMLc9#Yza6C^z<oL@9lTlgVe>cN zDR*K6+Jk-EGuG>N;`z~io@IVBws+Qp0_7pP!Vjb>I&s4?NOp4m9amAf5egxwCx8lo zWAVh!dpWs=g(DV4-4@l56LFhdcvnMmlTAgB<F?og;B{l@ndWP^6)ixt8mHu*%O_w} zKG2gV?(MN>+9mgH<7x{LE*f^AQx>l;7+od(i_?4jDg8ak2-woP8+#{(n|k?FuU1Cz zn0VL26XLOUidMctqZk*<tVl!A3;6|QP_~O+Q15fUkD>EjOy}#pwx4Z>wC+8rG#KD7 z4@WeltV>=Cw?bOUX*X&ByG|FV$clVQNp`tW=&EB!=6>xON_sq<;A;zHT3HdzHwl)$ zJ>GH4%TWi;vbv3oFFbb29KD;Rc+l0ad+Nv!7n4wzBrqTc==rCvujzKmR|KhzV+PKq zHq8<)v-jD@6VpeWrap<f{6*PUu!)-l^Q?o%?j<VHWL4T3RaFLsm;1^XL(m5|U93FK z#%a7%aMGW57oQoS>$<87n?I+3WV2~rZ|`<Ku~t>;+Zf++)Wcw=d$XrbJxtdgu){b2 ze1-<6+gd(YAeWj&@Y3%+`XcD<_5yK`{sXb{WA;M>Lb*PTKY&cmXUX~#O%tnghXtiJ z;tdO`w&&VfbUhxx*W^IdHoEio!|WRw#Bk0-;)=^;g`R1WrgxN#Y~b3SvrumSF(->$ z8=+u?=BQhB4*{m?U_dX8K0bCty}EhAV(|DirV8HmDxEE-%YfMj&)#a@OJpNezBt54 z0(ZA<rZMB4rO_UzH3%$u`?46Xay|e0pu1(UK4;A$`z!3r<93~%>5lEqzqS8P7LfNG zk~}PJ0Puj-3w?2WT8`~Hc$;_B5ABySoBV31KV|En9}q5}KR8}_&@rI;%&@ugC+~iT z>`_-x4Rlv{7p2PedCgg~a;E@&|Jfdo!ZSGkG1Z`=_z_b;TEq0s?dGwzG@!rW*4=Yy z2cKOguoZWlPyhJr+|5fy9cv_R^v_pA=b`u?_sN2|2l+>DTnHYnv#wQi{-b#}^_k)K zS$SBwfjuyfxFN?Bd)t+9J7}Wo>~A%LV>mBcRp_v)A5>xPH59dO5l}gG#B#^woRk0k zT>CKbXv=6a$=M@cxAv%$n08fBO!RU`gNuxgdfM@ChaR@*%S$vJ8MHrq&S5z(mZLL| zXCQrQxB>?&ptJDa1Mxx^jLAAaw%1{{#t1=|-<qo{8JuKLlmezcvL0dcjmHMGN`2R_ zG~tXIR8z7wVZiYlAR)&J@YGRyO}VwJgH*TSuBvy=>PV+0^IN~lpz`@SX}=25QlwOx zoq287derki!!O&MK`A%{Q)JkUOEUK@V^Ge8$nOxjkP1+Po_HBtA0P8Eue{onICyLu zeC^o^xjadU9()?@!gJp>+Oe$P^v|$JK~L|^)m-_7(MhJby`2aZ2@G_Nn3`}V{misS zF<MBUcj%%%`%U~;uEX(c{WGy(-r^JAyPsdZNfM~FH6=L=yEgJX*EE$wVlMQt8<L5) z(ak_-W7G4tGV52fBfRFbv8%#4q@l$YS|$Yj+57nog*(yo{J@8zN&OC-(Hbceso<NT z>@zdD6{$Ew%jr@t)7SImUhBnS#~q&J4aWW9>s4mP_8hqcTPRI39+{61b}8PFMC&1r zgtIEG<~cJQqftz0ewVR*>y7*9IB=y|J15cAgxV<KkvkOK_}J|PmMNckU$A0Z@jCI% z=R0~jM%9TU#~S3atPJ~48~ZQ^4g5>4x~m+I{CoFGrq!WJqnnwAVXua|QRU}}HsiC! zsBTe69<H;aFfFoYAk7T3$)Oh=SSDxs>2id`>kK;qM6MMZJ<juP-i~J|o%!<i=X=^# zbCdadTAbEg`D}pT!uvc}?cM`hZ--WkbKl*mPL@Vil@oF(5@M!RxHVH|aC4TK?qcU$ z;m!+ch<)hibMqVr%KI$M)bYg~n}2_OeSd22(bUQ$jMOnA)?GC!jeFESRz0Cg*6w%t z<z>kv<9Ry|vjLK{ANh$q^Ep_OqtpC}^w{m|e<jQAy=)u?Bp2E!;?k{!a(n$H^NczB z-@mg&wJ$9(^ZWyD*~-0%?F{AKDwaE!#y^3NRezk^Z%!u^QQC<r&O><$v2?rQKdV}V zjaenZlD7F7Mq*c%1YozuMme!1#(9Dlu6Yg1+j<LSfY>|r;UO-0+trEQPt=zy%*>uM z^qZZ*%A6bUCLoQ8*;`Dil_oc=E=v6nxyPycIsPCXg5E}!%+<4RR{N5uxhpWe%rzsw z-fpoYAVpbKMPvEWq>y8gF3O`MajpAq8E2{jMQdX@VT4?kYE!T22w~v8kW@OHzG&%V z>8|%HInPag(7K+0z}C^rd?WkKNp8rfuv)cue9eO}gR7;U<rhESFQ@`Pmta<VApGzU z-ENO&g}zo(fBil3-O0BN+h<LNuR%;dP+=Q&kvmlWo48&kM$Jf;Ij?Yg$?Y)MUBlst z%EjN~)=M)8pcyMK>C|tl(%YtzIagi%1m@P&=zlJ;U3Fg6!+x??+z9~WPLa9^AUtEV za@AG)o>c2rV!pVAC&AqkU7FWUVlohE(M1kEj)_x#MTwP7;XA~XANk)o{ZLE!>HtH( zO28_I%_#?>`yBbL9V6tI+9B2P(hd0!qJp}W)|(+f#7yo&jGj0!>L*3gwstyVdh!$F zDY;HdQ(O6(`3}Q+*Oo(`Hxtj?y7*Gm@uc#r_`F#);$4>hBw51Wien>4?zgHT6lK+! zSh;w6IbJ!YaN&%WB4yt*RVz(+AV8HExHj@@Gaq*2WvkTt6vLQW=}U&Lho$<o>xnoO z`@6@_biF;ItHo9-Ii6kMEeS5rIVeC(bk8Y_=6TrSWCg>N6m4NfH8WwV<bg%5MH<cx zJx1D+aL)aT3l<g{Gp|5R<?E%6O@d=ipjedf1cqcrqpN9;@7Khto<Grb(_Hz}{vxsH zixduOG%_GAkFIWfxF7Rq=EC23pFKaiFS$~F?gi{<4H-bUiP0;iP${FsOj;Eo*h9-V zp~Xq@-Q?*@<HfOwcY1<5ET+3%oYK-Y(V9@I{wyA`qh;p8bFPQYg|&B^bXdLSIicSm zp?H7f&zpNUiCG0t)fDZ0bD1b#`9-qBfyGk$88HY-ReWGx#6S!EaJ?40qYYQmqxyXS zW`6#;#r}4IdYLHexMgaw-}oFW=-spM_~o7pBPdSV<VQ>v`fb6v-DWTIYjs@bFPd$& zgWDK_jCMP7w%XsO(DGIVg{O6|J<Tq>KHK(5sX>gF*;^aiPGLB1Y|l6GbLfdYcfH}Y zx-+Tu!&-#zN;hX8vwG>sXERrWo>Oz9KH8i0wDrEg6pC30x$+MaFNdbf=WQp)$bS!% zKQQs!-^-xuwdB#wQi>{ncd9s=fMv-nr66pC*Wb*=w3l6jOC|MMS^$_TLQUZ|H-~Hr z@3@^hSLWf9O%Q*;TG@eOuv1rDqIXQW>CB$r8Mw20$?eYW-jji64&SG%FH;yM(*Sjh z9whfwSX_Hh_VQVhXX1QRhU*zDTSK`w3c98zUF3E#k|{Xr_n=n%;JlAm^z4>&6;Nj5 zPV;8K0}7P{_nw0^vYuhWyJGJ8R@U&u!vU(~Ah)d1>$)H3bejutLpcT@<q~@7rci;7 z@#za{c4dzjvp3y(jZ5wE;R#X?Hh&4HS_|>Xvj_ex^y+t9u@QW|^pl5m@-q$i=obb_ zO39nIT3Y*@^{3%E@p3EEVovfFcLCc~)vt16l)yZHk>tCXa{bne_PDEGlmhJfaJUqb zRq_q-_Jc3%J5ov{I^v$x^22xi{qpDC*UMW*zfRhj&Z@S|1Oj*kznMIMidv7Xo+YSO z7+8)PR0L=~?blQt0oiAZD9;1p4vkV$QT(OZ?D-?6m?3Ts7C8X?-8y6J6vh6X^W{M& zNcBbo>O2kI?&h0Wzm=X0-&f<}{ZZ9IGHE1MD`?r`RZ#%?u`MDA<u35Zo>9mVA}fq? z+NozO9zSdEp9u314@!PA5{=tzl06@}|6i@z2yG?{x1Fb|i;vf`nA60wILkZ~y?c!_ zBas6J$c4(9-anlgH$rD4{%G}g3sgJ>PmT+evT5R0w6s|^vcN55xl!Z|9LSj=jXlFU z>3Y_%k83AO5>nt_-Hs%8mq%Pv8w82gf|5$~rItWwKITFVc4kD|i|etJ*(BTe3>!s2 zH*yu*h>Q`fcdmJ20dP_~4(Ue-MRe~)A3{kH_5-AITMlbqUDnXWreZoH>`Tegut=rz zJPmgqbrg$a(WR<*a_<Q1I3`#N-Y|Y$DT;<(qDs~1=A0=i!Rv{8OSkz&qLd&&W{kgs zuHs1KQD-kbXBib#>d*cK&4&V&j!0==g3PW+=>nQ`4OZh?9f}%-rVAuFJoS6D4hNap zA3FX0b*S031F#v%Y@WE2G}exWq~LQspDh~C$gfkCMu}QAP)?=*c}c`*#qA;5!T^fA zFK*UcfK{XlG*3pN0bZ;HSlu*IzL6k1Nkz|MRW#={74tvo-cXYQ$(-ORzQZW4Vh)cG z88E2c<I}`tp^_h42}je~6k-ht`?p*Qr9J!&px<T;MKt>e)=@mo+Ehb0K@OM+bOOn? zV6V@D=s1YM8~?5>O=9MAYz0j`WJWw_L_!8!QsON^qTp7_WbFuAp@A5a1i3qrXpc2* z_&1xTA-IvJDxZdiMVg-!$k)v%L=cp%W)krrKuAOJsc0tymu49q22s^`U`JLf)}qFG zAI-cj*4~AZ>)Jap%2gO@)uKxRl!NlkGiE(t+qafu|Gr+l#zV>n%G9ox=B3HIgMe|K zB0#qGW!z9q^)k*wg9)sbK=eC|7LKL>7C60=l^g%kxY;^k%yV+2V|rN@fDp6LZ}Z;L z)z)}67jhzM2Dw#7kZG_`jNmEe((EFK)v9PHs~N4S(E!Z4igAr<Lf>}lX#Sf@*vC@> z6R`R;#3EUW!oR$nH!zlj!_7$9)mY2Xb6O-ki{{Fw0$uM`bcx=qFm^!~X&UYVDMz&1 z<$qI{#YoK(P>S+^W{i&|(-=lkqI|{XVimcygwJ0c^+5`zJcTpMQrGxaYxJ{Uo~W{E z4K{S-Dm9Z^igpfC>1q$KH=<;EpaG0xP&yh0+Ib*Ijxr<R5Q!cEEY)LG6MX$D>nhO2 zXm?&tHbMCYUaBleY1>1(AB)S0+)ft}U!+QW;it7Nn$*YxqXKJtn!>!Eg&|M*lB?xb zE!@@QcIczRb=cZPK21}>A8kdmI}jvgg_Uf>OU+ZoE4B@uG?ji(?~>adZ_VRCkV+dZ z;tCv?X;&p(Rmy2ssu0L?`C@)EN&tXjfl%w@y#_R=ChBg{*vRg3^Nm!gG5%g7B1^kl zB`CnBwKDYj_vnnJ6xCIgA<(G^kg{(iT73JJ2y*}UQj1(<9YL%SkM88@U-h?KC@c+i zQ3r&2*@~1?iU9o#h5hQ_5ee-q7tfIy58$d&C{}KWkFb~}OaAaYg~jR9BnG&VSL#E; z^^nJ{B`cmI7lrZzLix6U1gRO6w_>WkNX&v_Y0RPX(iXm6Sn~(B<+hyKVlQh+{sB|~ z4D5a>`W4|$QEh$Pa>3wdts&Y&2e3E?qkDhAD{&chepD$`AXSFl_kgNoL095{(vPL? zeNs;P<?1#m1zh7RjGvKhvpKv!Qp)|OENkXK$>&6+qlw3kva4e3F3oH5d1(DMBn&IL zM3%Rjkvs&F0{Bvyk#c|#$vP}O6{%K-*j4kwvKz17GNILLp_M+a+Kg4q5+IW+l}2fY zniK&k#q__JNQf5lJ~6~l7rBmCXtTk|cPRMr6jHy-DbISe7;YVEJt|XmYNXh=mpAtB zsl4wD@)ARQimuShm)bV8l?joJ6Y`!sbc>;?>_p=JL(^M!-MQ8-cP&0>4??tCC`I$h zvg>@ccSjY5_+mjbihfvBD35%MrsRi}B=Ka|sk`%lv&(b|-w*QQI20)|GV-UKz5tm+ zNH>U7D&Qr+4*HHrGUYZ4-z?r3psQMu5G)`1E|63iAk__^Ea>7t06<6$%(rwF_p1F; ztL`#e*nxFU4pz#-qWoqQ%LEeXLiKbkib7x`GnKPw+fS6uB8dMH;#TR10V>HK1cXJN z+6hvq+syY+QuE^pkAvj;IfX}+iuS!eDlX?O{G?KcRqO?%SP}rM=}b9Q)&{Kn506N` zi_GS!VO&+?zG-$~&mFv#5}*mMGu7H^!KyTZ&R-=YxAM+|gy*mCO92|64@#q*L24^l zWFknZ42xP7AZEAACP-uCmm-jr&Zg-ZV7-3f^DTc#ty3lbxhMeCQ=rhYwC}PpOFw3D zA4N*f?LWqw(UnmB&C@^wd3czW3oH(!<xPbh!o#u>U^y7k7(kSZhtYwWT@DhuIub1a zP(&7=B8!uMOVk6vLjX8V7LWNY5i=zkG9_9Bh!+W=0RTLJ3kx8N2VkxqCX2gL>zM#N zd#d3P7gqDT;WS>n03*s3*6ljad+_^6`vm(M4ILqnr`l`%1Atd{2q9NuH4cfXV$`Ne z|K_3x3A@^rbhapDt&S*_&Y9pc`)u19y$-^Og<EPIkkT|tV@04g^sD+U2)NHz8$q?D zfKa0}rD>Yd<hhJW|I1f|Qm*?I>V@*8nf%?3I1*2fJtLPTP>z}j6&WE){?~NmL`?dv zihlGf0FP)?I@^awbYrZ<2wEY6=2LRYA>%ioq7gn|QAD9uwvASHhelrJJx9%RldWF& zd5O*f#V-Oi^cyw(6YRH<3I%xiZ8q!f$XlnBBQs_+PJQ3~pcc`IS9nM!-~O>1!pJP0 zkzf8G{S4dWIa%KgE{Yl~bOH+;>4M#xg&j*BI@OW}$-c&;#N>Tije8Mg0Pu$_FY2x} zV&}GXGE%xj*}7vq`WsG5JW>YWOCty}@*p54OnRGX7B{UGfuOX1Qu*D9ilHfPM;hc$ zt7R&q%C_@NXR1%lsE_=TcUQW#8!P30PN~2SIVRj&%9USN;qLk=JMvZD5TtTx?OI3V z(dswRdfCHz3)mDFG}*-NqSDzJGOUd3{}TfnJKj0gsd*9vcoNX*=>fO>hxbM54n+<p zyZj!<BFiH07lz%B=RI)aiQ=)S>ibW2(-c>D3asr3gn#-eWwk|W&NuFOFjne|P`-Un z<krteZy-xIJVGyC7(SxrHFay%`6~KMr1Zb(=7q^)2LZV=n39)O&t|yDnt;1-!r+#$ z>6K5^&5QP0d-&&?PC~6_r>?8rGuv*AiK@#2xfsIzHSE}vH|k|G+rCc4dsO9D`%Cu| zPBu)dyY3j=oxJxHPa#O4uriPysZ_?sA~^!#e7tWzFWmmeR^rK-{TX)mF5Fp|z5^n| zLL$Z9;l=1Dil2o_ZCDvX{(AK;QN6nFS-YtJ!)p0G)c7a37Z{-)5~03~HA?Vyz6Vm8 zB@YZg7~nZc4e?Rco9b3-C=Nk^!h83Ag1kFY%69@d6`X@TC(9xz>C=P;a|%;52g&_g z$~m9DGhDBh8)m7{C+xJk@rV(OSQKBrY&&*3w0H)P%CS`Z%}<S2GxqI9Z*|l}fVjcS z!7BByzuv~Cv|}H>^HS#!loCNeYR-Vl8+FQzEEiD96Fhm3Lakt>f@trU&V$T|bgf?^ zeVLh+ZkIn(Z;7Ez9ATjX0Y4gQdH3J<u87(G8kK7T;y^`@3GYrH5FbTGmI;3z*;m3i zd7L&swD;u~uc&09yw>_N_Xkl$=Fw{I0=0BntJYg}^ncaypcmy>i7esj#DDUmGm7h& zTW)tsB{M5PcwsOhLCGf4LoE{iFf+_dx*fEIv7nGoZLQU&f@-SqDGR-~Rb0iZZtgrK z)E0|A^yGr}iLwx1@MC%EP5|K3z76grq=-B%)zVw7^R86ee=mFM*!mUUvm#!Xd{_v) z#ZjkYQ)y?16oLJ}zr5|qxLGK(zq9P`y`zH>s=-THYc4j3*DtSs$&&n*=Kb<&OvT`( z!NE`CH)6Yv-#z&$bMKW3XyA<)G4jIDgY5r)|CO+75ejl8RGf?KT4(!;R2*{<_Ng<; zGY$c|$I7@?Kt0vksxk&vZRHmiA|mbJ<zbHA(fyJ5x!NwZ;_#ar(`D<?^mo12Rbr9* zEV6fep6R*r?2Lc*&ngur*zIz2%#;3W0n9x{7R}+UhrVAM3^odiH5h*W`>OKv_arY9 zM~{;E&%bW#ym@qb=c9jr|NQsg7Lt3i^5nN-yZ1pac4?@^icBHUeaTy;hZJdX;vNd! zShm@R+;7FU8!tapCC-v`M-7)6qkU4o2)mI1BdFM*jFjG#XC@8P0paT5M;6`&Q$YMe z$DS|`FP-b#i<>$PVHSw}D}vj;m<I{^@7Z^td9i0g6Q9JMjmSB7<%sr^qf)@htRHNH zsH_T>Y-9L_u4?>wmxlAn&4DAfZ$rfP#oniV8_E1dI{0k&z+KU~!k^l;1#&gh-KPzU z#>&F?Ozm6NviPB$R_GX0;TB;Ov)blsoK!g_aV^mV!ao5mp~S}Cqj?>^-tn&B@Qr(h z^?U8ro@e@5wr0hMtNJ%z&6Sl2jX|sO`K_hy$zj-G&-bD+6F0LYGq+?rCeakK1<-ga ziq|;+28xzV#cNGd>SlfGt_jN?XF5gQ)8d4_P7^o%!7b}A^&atmQoj41-i14vZxzZT zx||Uyy|TM~*P_psj+YoP<RuV*Z-~od<kL_Q>_LS@ks{^Pkm%30t)}khY=z?tgoEA} z5x&W9fInThseP;3KS$Mk+9Yr~wJ`Wy_`SKKp^`n6Jw4TBaGhiA^e3vYn~#^VpQV>l zn=yNQGhfGDF8*=$TV%&B>pDKRKi+Gz40b5#p*_QcKZ?4p+`1`y+Ft2^{U<UbE$g~n z(|nzj!xQbZU+(R^c{oVvh>&sGD5ZMcEBFoXrPb-ZyxPGX6v^_f#|_owZn(kz%ii8P zpK}9aD>p!-tf_lnM^1cw2=B)wz5GLiyDPp-VX8C|lzH*-4*xj;j2O!<dx`gbCiYX8 zL`rPGbIN?3m*ye(k50BqS_?zw%Wn7EFty%_O{B5f7v~cDzM2Tu=pzO><l=l_b|&L< zX}I0}z7~;xi8Mq47h+(e0WOVJtLHEdImj|`q!~#d@67<|2mG0nPjqY5+bXj4<%dJd zQR~=kdtR^I<G0|G6}8x|FEoU4J5REu%Ek0}qkZdSQ_k7Je4|Diw$nU8sXxSBZL{T` zLvj@A=6;x7%!DLZtz>t{F|N`h(SF=AI}-e>pAfai*51k^ApA*^*eH^WU3d&kQ-puZ zWs)7$&QK965{q03;AF(q#x0ZJ0TmD}uKo5JRrH9-EEgQo3<Caem^$ISg8kc0z`ehw z$J`qV%(T6{G8%hT?OF>B$#glk5TbCvL)^DFT4mx>twvwo)3D{#v(%4sRZ}yC1W&Ev zl*3xUj~2|ikokR=W<qeF7OAOWR%GWdpF03vHYp1!ua^opaiDv;nWvuo-3bNill}HB z5jFk@;lRd>c!uUKrPpgQoUECGn08HMny}CC7nOxicB!mtgn-V<bln7vX?MgZn`wwY z&vWJ!y{PENWSb9lW{8M3n+u=|9l8f!dTsfMW8JLRtu!le6*l}pgCj$tRG;~1H?>x_ zGi6QFz2=$X9V%2ht(A46B~bB8n4a#}ZB=M;F2`k-xg)3)ehq}9RtrTm#;Ey*0Jq|% z)ug;c>h(~YpqdzyrhQL4Y(nzqn5}tCm#9b?J0MaF9Z!4vt|GT2rGFm^L^Y$Divv~3 zzTxvep^t+~f;m1)UnpYE>91~a-?}K?9e{58*!BUc3=PMo=MF~~#lu8f%PUjaMm6^a zf%+epN%Pwaapa;7r+8Fl7IL;@vu*lf#-010O{y#c%MUrdP?E?uk{lzIZkNOxPpe<N z%Z@B?PKKz?ki5LFJvm#MZ4~ljD}?#TVXR!?Bf_AwDj^osg4_<hRBZEvI&YRr)UM3k zx|7_u!>?;RGTr0RqtUS7U<vZIC{09`5F#5IYj{U{(xkQprqMS=`uuk6j{J=l=2xwb zwDy-unMHkwSMt}j+xZMt|6=zGPtHB+r^}zHh>HvkxsZ@KcVclKl~vf|nKsz1@Nd!_ zAV<#Cbe7wH4f_!DEJOUH*Aa!HL81j15&JSKLn_|$<?*P<KL7UU-5qlK#mx|lxWd;s zqY7QxP)Z3|_UFy0feX12HT^HcatY!eeT`wQJo-|muFMMOCx!P&g*~CRlh;?0HiHB< zqs4DbK6VB;1t$hH{TIUYwsu+>6#8O`N|!}tO~ShF>BFn!GWf0@QmsWd+OEisufk~e zRu(KyAA8k)<F;?Fh>;}H1$%0j3z~adWMuNYX4GmC{GwY}#L*)3c;#ZmV76USHAL+g zZe%y?NFz}X4IEg?GaT(=U0fsjf4*-OVE<%3kVIEn7P_gA`j2ks1@PnX5SKLo__;xs zPs{5wj#T^fd*$^j5wonMjJa6|Em}I~`=?vIWVk*TrmRbT7w@pn8ELkET??>;*U}G9 z3(s2!2iz?vkw}1i!C_5=8tXV)P_n|%5CA`&$CR`_+Wn?{Q-N6>#};chMWfa(9j$1R z&dVV&<g*(g>ULX%;?(rHTz$kQU$W$TGjZG|w4$Dnol<YzbX6u^l&BIMz4t{mEOhTC z!>Vl8^iuyEb(Z60vy|o%|A=^XR{UlPr`B&D@LIzxsp07ar{Lsf&%x!f%cK=S{=q-R zQ;RE1GefLfZPT82@i=#<S)Sx!&;83cb(>#8OTw==<$NcvL=}mR6(5>DH*xVJLt~Ko zRW(Eenq}SUru;C4jHpq53Gkc3Qjb2(Qrk0+W9JWiFmpLku2}Z!G4gNeQq?n6An$|6 zY+>1pMf@Ixac)2M9lbWarB9j7skv{h!FQ+=pkHLiPx@_Hy!v!%OUfyM&~Gl9csuTy zrf4Qd<RE+t&?l!H&XtJ*;9${kezNEoURGp1;pW7S?|8&awB=3)lA4JG@IlU%5fvLp zs&(il{(kv&rT`h)CY1UxDpidauX`cBJStJ|vY)h(bN*m3WmR-4Sr!@)UO`aVJgW1j zA=hWgF+MnaY!qJK5|?Qu8jpj-S3ojffE5K)FTS+u+FrvS;%)v%2M+3N=cfK@5m$R| zH&3_nklEeBk*ExEc6%wq<5JYjW0t#Bm!c#xNytT#<YyuL4iyppU6CYm3g~cX=oM3O zarCS@wfAvuB_;o^tkW%-ZQ_z7Ux{@h8cq;Wy|^d5s9>2WTLoF>6C2TSQnp#Cq@>)I zhR$=z&s>AK0M9S{kW)vIl?#3qR%!on#49Sq-<+{@<9V8|huj%OejSy1N%FhSkvei) z{Ypn(k-l3cKMG36%Pbblc9@*iFPRH5(pZ<Q_7q2-O*qve;)8*Y(ld3*X!Sbx^fD1~ zFrsx;Tt0+l`uyPcQN-a8Pgc9!g#h`xEzt+04J;oc4`U<*LgeW^F{RP+PJs@a((qr~ zBp#|%Cl&D>L&~dSgk%(7cnoKg5l~AX5B>aK9wlaC<%ftU*>TA+X$f)J>?jV*N65@9 zhv+8T9@&%77ljp**=6!vsxwW>=a|$sXzCp<`h1PlFDjy4DCZG*@_=;O(#tKsC0X%; z37N~*2b>`WUy>!JMv;tE<nk!;eG8&dcmI`caW<*!0$c3E9f>r&kIBba^N(jwp)eZ+ zl{K7bmkrYZ0+(T@sFm6R7_?L*Ryj(%Cw2QtQo};%-))-MC}Ow;F^tO-u1fw|6=PN) zx+ut>WQomWzp7rOrJlt9aC9b)O#lA_-@!J=X70J?zBBhQ$IN|XM4@Z$Tka6GgN+I! z3Q2PmMTICu8gu1pjwGpwkW`XNrH|jfzrWypzn;(6^Zk529x-f4;m^qHroI<KC7N7? zeiKDlERmmRkq>C>CQ+aYAU)6`%s)%pa*i%16B#Uc<?xl0PWj}hYcKOrTsl@`5>Zbo z4_+fD*g--`IO!uGXgQzi2Xg>dj;CrO5{0e430wyVHnm{KxrmJxLE5&bgA=%BMUc52 z8Pfu}zqlWn9C`JVNmN0o#7|P*FiT{&1@VImSKKark5;$n)G1@-rAGPjg8^kNLR-Bh z)4#*!@@ut6bQkl)-lOAA4+b?yigJ;#C#OZX%gtkal+R&c`$(-O5}z4C<hNb@Zx-U` zqQD#g&LY|X(EQ%~fCh5F-l9k%IlYE^P_%+|neH-<7vcm3jQ1i=(&!{d#Amd$%Bvdn zN0xVU!YIhp`;!Il=A1KXtaZ*eWNb*!yQYS(Toe435MA%oWd~6j%)LqW002q>EdD?y zpF7hbEkTgTlzh4+@HC<FF-s_l$nOmRJZ=$x$~I_63MRn-_dgzN{~h2M9{QJSyi3}5 z{SP4Yg(>ohi+Dpozrmyi9YV~{`DHw+vMD#cJ1x|Ogw5K?X@>HGQ)cEybLQ=9($mV2 z#7liwG|pkpEARm_TKEz<hI6-Z!FD{V1iwNrpF-mQCUq@%gXkmyGa6!eOX%rGL@iP{ z5derz0N*09de<W@FR`iyM2=UUm}A`AMqYbidV#cTq*en5m+Hh&ps7(M{k*(@?0C;7 zb^3R+!l%};+gaJsmvAGZcWdq_;DsL^F^`@Sy@}!Dac$!l1+I}1Pm$1%WS;x&{yHm3 zK@@s_i!Tld<=NM6B?ybUUj2&}GLDG4J`nJSt+LrJk_YK{%oW*eflsIGW7U9wjHzoK zFQg7ST#*>H)Uwb6AYr4d2ms^U*q>k}p@)XrF=Ltb5r;+CT&OTrHimj9Izlitg!g$X zAMq6`*@Dz7C;p!2u_+-VU_dRpeT;2v_dS4T(-VGl<GQ+U3%R{YQbOrBV!owA-&=it z8qrg!6CmE~^w1LdS_nXDeqwk*Lnmom_TfXJ@@yx>yA~Ogw`R|%Ok<>AJ4Uq=14|-8 z23UwWv@m&*Zw&pY<hAIIov<zEzO!Ic*^1!j_8VR?QElj^s$3ECRFQY>VY07Nje0va zZ^1jlbgD3|p%(<w(MRuHXx(OZ$h|H>U+DVx_eu=SQ?ngT1MHj20%c_;bEOmctH{C) z%*eu3{&1F1#umR*bp4@c#>VZJV_g(pU43M)-jTPOw5;LVP8Ql_!H=4yN=9ZSpRot< ze0ljg$>^ueho1V=p_wysBafT^`^1@b<-NLyxF4eOOUSGbcw;V9cQD}|t0)@)qivmN zVHxWj(HdSf(6EP(li}AZD=!_E_!KJi*`#A`O#~Dp@hnJUfGF}Fc}@2i{U28R_{*Nb zS3-B%AAb+`OXvEv2wnRr-A~aQ_Wi}l^(aJukA1)(*i2;Fdl^)#xl|CoZc7jr^vv8< za2z9Ogn=oS8)qP)WopIxhRNZvgLzH?fzcAHs{y|-`+_{--wVtI^(ANVS<$y3z%mi> zmRaL*WvDjXZ{qjk0k@;CT^fe68tBbqD|z~>TWMXZGBT4$gfb+XeJP0xE!({I)&iEk zC0GaG=jj^9?dt7<M4mQMmv5%udp7Z@bnu<--~+Po?}VmfT|P^l(%>NR=OkD>o+I)4 z=Iz>=bS6BNGA3BBKibTF@2|c{gv)(DBI%>|YZ$3RQ!Y<<_ErFJ2{5r?CwRr~fYw9t zITqrYYuPh0qD;dVJ$5komhon;&<0XuxdpEIE%VfC>5!?8*6+f}TPdNhPbE;osul%~ zt_Ej4;<|bkMm#|DYzaR9Ad`-U1}&1GUVfOpwGVxL5qUZs<`01Lu;s%E0%M}nnzaZ3 zQ{*RE!rgtaqO1M#iow5x(i^|}=rv7C36K3cZmK^U`qU~_#d6Lw9;V%yc8i<4k}fv2 z)iA{tNCUuI(NJ7I5@nAA<{^JW0EB5_0FtS-W&pm0xSDpr!L-9|^ohM`2ke&62G3B} z0)K}_FO%R5lHXJLu)~hcXR~2B<F76ChZyjM+d~~IEfsS2h0X%t1FVI6Bv|evSriCb z&l+cD^Nnu_4zvhnkdvG?u#fGsb4%o>fIYUp0oFMpT&Bo&f=}9Gxe$BA<7PMo^FUF@ z5%lkIyJ_u<7pWzvg@1Q)qNHHe%>4ykU3SD%kU>VCO6I?p_-yJvm?z%kwg{$?g`z$m z@AuZ4(mYV6=Jm)<Xoo2BgNu-eJpObXCAkY<<szOeP6PBEy^QqA$jzfe?_PX-XC5D< zri^@@fY>5IS$2yfcNU61Lz5CB>RCqqPsX!}eA&!}3_IarfFMUXo2HSSyKVdc`F<05 zjc-y6Br5agqSXhYa6^0Gn6_gNdWKhot73({!8AbQMzIIidcr9Bz_K4?xZ!63Bm!O! zfWN%6@Fw=zA$>?426k_&IvcQ_ffjU6iaV@$Vu&L0?L7R`*1Ufkd>ei4K|w)Ux6Ua_ z7{d-8V*m2V@j2kJwWjL*<pUdViV-tgaS4B7aR4KDs->TXh8#gd&m~+^P=-|_p^wSJ zXVD*Xeu^t(sjRmMej*_xGuL)odybt!-0FwM{&_DuqS(a_P8fU8I=Hdab2RmWVJ9!( zeTE_rtc)CAtmi_rk>qI=Xs!T%Hh_PTCe)uGaJFGdlQ9+7sqll8HS|(RY7RbY7hN$_ zMN}&}d|9Uqz*!|`%IkiS6!9h%dcGwH4s+?6+k#ZqmyQEG$}{Zie}d=8khw8%+M+-! z3vtCx$YWNV^9}o$%qw!K3<E^EE{^_FMylBhZZ&N+k8U-zk#3a`p()RYtGH5Mce+bG z7g==hqs<M#KAetTSJ_`1c>|q0hUbYRdx)@BqA&nG+et=zqKV}2&4crWzY<^m*V^;J z?&v5R8h$qe;>ZI%aAKOCW<PuCWw1-y>C1odGdD$rOBUu?1Nm(hzf?m`wD4Ic@NXgD zT=c}++1<G7-}||PR?X^siLf})v8T<y1j8{&tzq{s<WOvPc^KY#Uy<|g=-8*5Z9QKK zl$aS9*jY4K7a~~4h04dxRz3ec%thR9Rp(dnU#O0*vMZ^3;FeB23ZaF41_FMt|1?1V zzWHkB`)fnP=kMUtdh&to!gB(v2zVWduX2BF?Zn>IuRk})O(ZZ{>utw#z=MJFkQ)$W z6=ol<hK)F4kRxzrz$Y)^$c^MTBe~*7ypLfo%9zIUkww|gOl8MHwScJ=*HUf2yP>b9 zKDd_~hE3E5Os{%YS)_h(`2Cqz3)^7cI>flE<z4SQ`CHkq8D-c|x7{2Kc_A)A1eC;o z2sAlq6#Sz<WBFs-d*@U2SbcZ@D1?$n)k<(5L2#*!2A4a)@oiohI4{R9^aXWyGpIjb z(ja_c?pw%kam;01#!q>pNT;$izazr0v>NJ}9h13twcDHP4~xEd{A&GE-7xdT(Y5c* zp@4^@`c3u7uQisDt24d#4}blZ(*=t9D^+M@u|9dji-BNS#&5prIJNfn&EH>bQo0Y0 z-q?TjBO|p=P_)ZINTR)g!#eKwOCZo^?)TR^PTBLT4`0V8d*BjBey>)!ZM)^&Iqvc* zSAT_h2Gg57EP4tfECfD9Kv?Z;5s-w~kIktgsyeniIc;DWtHY}NfZwZNmW&tOUi3j- zPG7jf8y!wTTTx#Wqtp$(plh$DU|C-kuT%TQ^<%TDvx81k`?j0j{hV7W*T-%(n7rhQ z9`dMVB}Pbw{`uW6yvw2rnreA~`Jax@yb`I%nvdF+0}b>}XntyzQFpa3TE0{9bXQ_X zQ`lnL#oa}<EXBu7S^RlJ{Cx4}e#2*a;xa97KQd6be~o;VL3zbrbyCj%&Oy~D`0B{) zM{j)l_|!)Khd96vh??rO7dTF@VazHI$-h1jUE1PyHT7peWSzptsp}KoP><9WWkE$l zyu$73G?U{6T0}l&e%W0+3aCdm#BakU_3$&zT4v`S#Oh4O54tRFM@Pe7?E-G7%HitK z%c@c0htq@T_~yK})De8RWL8O{W<@C10ebcH{I~FH;VG{KJ6xS8^ed?h8UBj!F{@Us z(3V>batZy*30Ko}fIkn=0kbhOJ}yyfOElA|mZ17ehclxFhriLUW}Y`1QB2>kSldYa zuPNf#T~<_BsXL3vDE$>`8vQ<_t73{^cUo>{jbvC8u5!NAx;(1;`|O#om$jP4uI?w# z=W8A-vX#{|k2!ktka6T;f%izFOL3XjnUvz+K}r^UQx?#r1Eu0V|53%<dfd(b?Q~~v zOjRw|P!aM8kkv|Eqe;;-iM59XF1R|L{=jrkoQS&V^1S%dqbqLBGK{KFu<kr&rtZqw zKdux$veB6Iod(pI365w5cKciD*x(CosGZWCm)&g%kMUcq<uisx&w@Uz$*dor_m+6P z=5#tcZiAnvpxr6_bN5P*1Mq;-^~UML7wv`hR$Po(kE<N_R?WBkMb3Pl8&F<7f_tLH za6OwO_VI4A0_Y|&SGWI)BLG@ZlWyR=cqYJ`Z7<ihTj*x9^iFvb)CUU!c{93*`*r^5 z4r&^ScAxC%qwx+BvImLM8QV@@`FwAHQnzS!-R|6pD{@_Mr~DAL5SbVs(c~%`>VUhb zQ4888v~*P-@>rUO8kR~7-9QSy4<?j2+lTRg^bS`GRfcPq=$3>iyiaDubmsD>sD*^A zMP5_r$QjJUg<d#z46?qnQ>?4#Q(9*ddga03;LFZfNvGk<tv^feZKyXE;gVg{^BM_0 zt3JH@2qR9EiX4n{G<(L)mHtyx5Wh1Lu%hK`m}xwk(;qC8zQs!@9=XSci>GF9JDG0a zb<RXW6zY>02P)?f(Yrboz&`cMTjko^II%od2-I9}=3w0Fq3fAlaH7h-!0i`{9EEXa zfE9o!Y(O>&TERlOQvJ+7juN%vWlE0X_JVPMgzIu2w5ATE_ZGGj6yLE17y3+x;$l_R zJf}#j?K|FpNY(257b8#2dp|5(^=(l6M|W6-k>gXARS(4ZhqWZ;T^|sMADNs+pZ??9 zXrrrorU`~~1=jrW^KBA)bK3`83_pb$BzvpJ1dPv%*;R04U2-)Xenp}&C%!i)-)IWR zNViszA>0~JJ*@6<rTH=Ba7&o!Me~u?p_NVh)(h~ZV3F;)6Y?vfvk4m{{WAgA9@I%w zNbV7z*8;d_54Vr5t7)&`eaCJd?s#=<P#IHmnMFZ7xL+0*7b5q1pWz$a(e>eunIF1D znyl8@3l~TPvZ&H~hxrfe>H|tfk1ZdNel(T+C8a{>_^0rP4`2Iz=F@1w2m$~gB;Z;4 zxDZf~dF09aFoR5v?ul)B4(L07KG??ood9vM3&H)$w<#p{mHzPQK0n~>yV2u38&a=O zcmhpfj|6k}?-Re7kgJ~+Bpl(-o6k>RSnmZP8UFpM8j1OyS-}zw{sX$<i5HIV1*3-i z2aRtg7Q|(R$glYiS*<1(W$%Tcp#j4Ljilm&tWY)0fM@RENtdqeg=#qmj2ya|RCXsT zOfMo}^yq5Rl_z^)7)HQYh(>b7cviScL%?`Uc=FXZd*Rrj{eX$&o5|NcXGP%F0-m2) zO}_qbFTxHQ$faqd)WEYN9W(<cFNCMmDg29caSoiibTj3Kes+{cMBwz*)szP7e^Eq6 z;7pxH>MhUgXy1mw7fs=*O~?O5`ws=q-oKf8CoVhY*jnJruGQ3g+5cil(4%u4jkMN+ z?ATDvqpwE8)9zpU7aQq(bbk6~TF0I2xZqy`%y|vugF86O1csI6+Y{T)<NqcdWrWif z7U|{>yy2nI%eMG9#Z{tvyrOiR_ZQyKQe}H#>I}~oqM2^{KCvUUYFXjDhqf7t|B2?` zTc@+;^Nlk6hFp@5E{FW~vWQgOO791wZjx!J|CoG+_40^)b*15_SwP`(FhSAydPaX{ z<yg_q$a~ufn8m!|P*RT2`!dI8ahMnIw4=C2i-)zxe(Y%p=R++gbcZZ9f(lQwITD&) zeNqqXg#6~HQfG$=Vq<61jB<d|8FNtEpRFS2HtQsg+6@?-P%Nqtxht;?*Kvxyxm<ur zmZNUjFOA!s&$NrUtsijJVQ#W8HRsc}rQ1Wx89B+!#uV-ar7_NP(W1N{u<W_TKk|EQ zk?hj<(m(SmEw{gArtJ`Z{@Zo_yzgD~^1^e)8(ITmmjS1bbk<6glOg6XO}JY;N5y(} z*kY4ME!bhhtYG$r^Q{E~FJq2u-nFz+d|r54$P0C^aeqM9tS0~arKfv+i-Q&_vxu*p zrwV>+5Uqh4Z%b+Yik2p4T#MmFJUgdknGeT>^4LiUZO{|Dd^RpL^-ij;KgfU$($b<5 zTfoM{Y~dZSEt_VyrF;^@f5?S#5=PTP(oD9X=jNzBnDZk{Xp|N-+2!Wb&ej4gMl6<! zZUI~ISZQ-Wd>$j-ANQh0CV|<V!lH-I@wu|Vmcuk77R{Us)=2@Iw)E-N+gm5tTdjkP zTfjVMs_Pt|x(D=Y2s8r#O`FD9Og{xzK+@RslXkh7mK<9$Ewq#W>>|UW9IQs-@ewJe zT%aTpDC$p9%A*97Gcx@91JWIw_p5Tv)~R~sY%?t?me>532XbfUSh!HNU|<!PjUSf( zv>h~x3CTz>PwupBINB;#Pgli)@LOO93|MiCcC{8}>2oWY$w+Zw97*RlPoN3U&^+h( z!WJR1Y)D_e_18~~ly$~eaiLf)J&H*8gb~cyY`uk?APm8zTQ(jmv`4t#+u0EB&xisH z2HElZ+JW5x^n-JZV{=rGDxe&%<ED|K90_s??LXIINxJ|AtV01UPtG<%UwxPSdVxWX z1)1?6lm1{cEZB6IqJ`<Q8m8%!`Te+zpkYQu6J)j(QEF13S#sIG%8^GTHA=U!McUhZ z%V$S1!nXKy_i<oLA|$Nb;w!I<wbOPosM<pt3AT`0r4(9NGK{NmVU4+-ESi2h$T~7N z%paPu`zS8bGHctYx3lzi6FsP$;O_rua+hk508-zjsG)dg19rLyrT15yjbwCrKnp35 zU>@Ldn9p;a&lE-oE#)(3@^Q6frjh4E%5ybar~xFfSqoL233hMEv0{Qcd~?qb2hz}t z(zebcYUmiOYh=_j^cL6{OI4D{IWBCOrbX9C0b4ibMy*3LwrtX@pr(9Kn@RI90pa@Y z>hmph<5EWK3~%oNzP*wg4!e?yynSh}OP}_*U@Jcn%SdF=Pww&`#*V5H`IXTWgMA*w zl*t<x9nMT=q;nxL$f~m}dN3x(1Vhu<0`863$+9T&0FW#Iph2Q~R#D{9AXzrZ2m|Jw zx<(5~w*{;R%jLODFfe*RBvpe*RcoYSNT7R%a)a6QJA9sF_n%6{*jP0J6=5J{R!?w( zZHjDeaB0r<1-H;Ykh#Qa70^VetJFpEH6H%1EVH}f5G2^d$ukm?(b%1+HFRd$sCW0m z9FP&delTQ_rshvIaG@w+X`TQ`_&Q%iIU@!@rX7WvNYDvdG|hC7Tnh*=Ou=LLgNXF- zoWZnodIW%Ooek+TJQ!ULiN@sOF}(mknkJ8IsRgpdLLTi`@$&!>_uVZHEP`w!`TcO6 ztjC3uGgsqVAh9IIjmf-xG|m7^J&?}78w0U#8M&VGv`3DyR^b;2XROabe#ywE5h0v< zuzh1LV}*VyeM)y4c0Kaxn_d2t&M6rdMX?chw1tt*ghVtR&Sbei<In@s!5AJKat>@m z%4Kof`=X!~V8}@pJxohGhDA?{dztEIPmPA8F)cCxkSGAa-42ZF1Sxd_6?iNoKbp`B zqM==`)h-o>&53|nXegs&T^L1;{5N~6S<@qdn~cE4XMyB{aTrG8;-zG{fD-+HOaHWv z@&gj=4y`QknWMn2TJ#hql;u;ZH(LF7UyhNqI1z+_xR+BTdDu#q+>BjlYyv%`oWZnW z<c7X5M1ig6z|rLvufWnI0N~_Yu73;T42FHih3>jVQ%vD=@XvAF%5nAQb0qP##udA- z2WE4jk#qcqh>jWQki%$xixwb?OHo4mn-Xa#7iuUr*MP`xg5fuq6hB|57=s+~+=ZF@ zSDs&_$3`-OSX4tIEpTq6y6wd}vTpNe{$|sQi@Yo0;ev&w<GSs=w4fRO&@x#Dr`70U zdSQagn;_VbSQP~|M+;>$PP;HdVDuQ4dlQFlvI|t_g2T$`Np~R8dAWEt6uiRlBJ%OI zGrlOh7T4nXfL9XsWvbHry}o=n;f2gO!{(nMKz!_MP!zD{E=7syVa9$gwV2CW1^x0s zHY~cT!{wkiWe5GrL9Dr;IsP;f1ht#TTXOH^Tuz*$4>j={?*hZtp&C(Q1;*ahbDaf3 z(D*Hz3?e<4FDI(8dsQp{nsJ+=H8U9nNkP$lxc#T@K)u<Fta1i14?=6g`IG}?SX56Y z;~bL_olf#e&#|6?X60493~?!T8%Se9LIrj7CW7?_drtX7{X7OLI8R<)DzKhWNR5Pm zx<M8#AO+@_TnqK^+`IoAX~&Tz$?Q&MWKgaJ1%z}vTuzH1K}>gHt?ZD<8sWLbK_2ef za=(Ri0?SBX9iIxg*dh9GeO)P`k*-k8Nalh~0Xc<X&{lhv`lZ72dDl|>=_j@L_xIkM z8;1H3p_xd2CB&nMNWMQW_`-G>UG?<A{G-_|&{)=J*QQ3goPA<m`K>P7Bra^=z908^ z_=w$VD$|@UflX<FX3s&7Bl(G)Ic@-mE0HQk0;3YZzLB|yI-w?wG=CQ4@v+BXS)Jfi zsf<n_6hgMdK*F(fAb=bT(5Y!ta|@D4nhUij(p0|isJA)k0A~Cs0tX5b8mVLHLa$hZ zNnudal`@SkiC=~czi_IA3)LDEe5NxuD}hdgJxcedTaeyPym5;~(?j>!xo6mnpq|m0 z4_ynyYo-5$&MQVIM-Hs_+azkeJL3n<TAx3fNAq51L@~jpC=d^4eA>j(qY><}o~!=Z zy!I%nl3yTgG3N+sEawq={vSP-35^DTt=V0p`~vw~#p0IE{Vgl*PUdXn?SxzWrrgM{ z-ysPAZPhLo?hj6O79`IEnv)-$1xTjCAQ4RHejQ&$wFRlO{7fhGB@O@Y6<tPtHi?Ny zURLUwjS1KJ{G{5_Ch_6vUB~YO(0~Mf{4nF(7QZzKESE<)IZQib2X%*mC*Fr%M>RzP z8AA#Jht|QUaypaC`yDU5LNEQ$OFzrZG2VR^&xTx=)5+Wa#JqLh@&ZO!^uJH+yZlir z^!aPmyyvNjQn&Huq%7uI%~6$FDAw$kX)aNUbjG=Kx?ALEMPcq;M>`4)ALkDZ^c47{ zC%ip~bQHLqL>y>*#)rtEtMG$STR=aaAafY%VF&hUp{LtjhQ&**3gm<Gj-6zK70B^S z=3JzJUj`P8A)koVVkGjav6xDDh2NSt2N(RtI32wH0`f^~QJ#}mE%?Z)lcu{%8KOVR zbb%gaGeTISVVxiuZqA*R+)hVER_AEt6HPR9yTV@z_7b)xpmSlJ9=$sdoxs2``LkH` zvm^-OA&}|7IBN&iN6NZI^YG-uMdV(${d8a!OdxhW@8{j>Q@f9hxwLcT^p7Wk^2F`+ z48J-lGZeqlX_xqP%X8)iAaj!;-5*zm)zvhmp~*~W2pXZqJ#}dDR4OYsgw0zo`Bc(D zVOWOWBIC?3lp;Qb5vw1@ytys*Bbm(~(8-_8O(wN~P#B;;7aG+9F@b?2#_B%cD{UZv zQ)q~o3s3bK!z68gb*WE;`Guiq6Q3dKB2Xu9Z7TpEgG3Nb)DbW*SH5`M8U<D_xTW|| zdLy(v3c&bO1D0`Csk;wP!r1sMQmuGgY5@J;S^BST=vgfNtUpA5mtvg<4NeFy`d%K9 zruY>w;V8iHheD3A__Ov|{GlX<btF&$3p~;S%^>mXFM@kz4*zxE)obm<r!5ARQ%zaW zV$xUYEM!F<6t?v=3?WuEDfUV2tJp^Tir!#KXV2dYO%g}SlhSELFu)0wMQ}00Vv%|n z2C@XuZP`bn))}Gb`O_$fIuR6}2gy!=7K0cXLDh?Te}|AsVTqOTjnJq(ev^;$L5+;S zNQ!hhHMEhTdk1`QaRu~^6m={2Tsrus*J;2OFlPtS{h-9*tsiFhS#0^27gr>TFqJLc zPm}ZfGnhG=b9_-_bo-ZA<NO)stXGNqu(MvuCYg+m^GOO!J`x#>T1d+r&JD<8;L9n- z%pA6~{JDMIxEF?@-+t~miAE0@<XC(R^dT`kJ1N>s{_c=m%obk^svKuIUc3u6_NVzS zW|IK`mcqk$kcf&$V}de=j!-h2Njv!VQs8zA1$^YLe1D;$EtT(4qS~{9_k)R?+4#yb z^XZiv%Vr1E#w*QE-94k~^?bbA<{Zd#H*Ue=Ko(|+1>O|FM15%g;hySMt*Pm@yL9Hr zy+HFsc^b7Npsl_$?!)`y?c~qbY|i$*AGZXKR^v#?ea%+C;ACuK&_4B_X2ZCwWe4A3 z@!ik5i-UsCil=Y>zYnS{iq?&(TAolcB_Q-=+d5CJ{rTwq-A$1kFK5m9@7Whm8~`Xr z-M?_>=;@QmtJO>R0qFUgH$0pCny%<cT4RlT#z&9bJ7!waWnDC(_;}%A+Gj<>jiJl$ zOu}Ps=8e286t6t-x$no51GY6dos^WhT1}!DIrck^E<R!YE{A{sY;%=eZ9%C6GAGae zGe1cNf-phk>>p*tW^==J!l=x4&V<<_2^N&230f4h|I{D4NYm<@Bj$t8sv^v{$0)9r zPF3GT<Zt?_7MjeiTynE)LQT?BK6Psq=1L6CiRXF+uD>u_YA2jmXx#~UuK!CbnImz3 zXBwd!#GINq0Unh8;2Edb&am6w<GPBt{bBb-zYbm1@XSs%ex(~Sd>?MLz+S7T5%>QH zpvt6!QH$ios=9GY*yDDDnWkyxaccng+mwmWpNOD_2AlK=v(LVLP+eB3p{Kq_+5HK# zZ|hV9+8X=)xz#Muzb?O#zSG#6PgnIaPP?d5l+->~Hzd&3_{#&8H5^iC&JlYpS|zBx zbW!{yTf7MOIX2|rLy;f+6*s2Ii4!ItQc{t1pDe>;^H=I;o@;o)zKfVbmR`?UZsuej zG(RH9CsWV={D=x*;m*)AOj>!3FmIe&wZNPxs_Jf}xvBiz<i{8OR<A>{?)OgT&l!5# z{7F$6lhvG?E;3AAtQj|76>e<1xS;5JL45n-g+kN$JVI@)y{gG#L4^OxIJS7-5@za8 z+-O>-YZL)htloAurh1h|8;x6>|LLbb8BY5VN1oNYG-#Z$;$4OE>`)yy{?^>;B!4+z z8g7x_2cK#!N}Ddg1)3f5!tJit<;!T+s}$j~NJ2ZW^Iu{Q#seg11GctY>WI}`>2k_@ zfQv?vM#Qjqq1mq<1Zh^%#%;plRkJZ%A!WEO>eZwBO(?)x{hcFO$OpgmxA8y13r$mZ zO6Z#5fcyE{?3R#1lkG+00olo!4@aXqy`CdqUSQmhHcXS4K4|^Bs<ucD*evR0RnAwd zu!#2j3kpR?w{s9_EODc4c4106Sl*QS8mq!l#&qY%Ral((ORbdw<n4#6GPN0$Kgt4_ z<`KQFPb_;kPC<I7g8}3ZT8Oh<2~Ax-$6)cP^L;yC@WWH?RU;JVW5^#dOp}$<Bf<&W zy_=;WersDC%@yT>%+5N&Mr^M@-Zv2&R*l&d;jQ`Y#6ne;mp~KN(FWZpDwdRRTve|C zr-o;o^{6}UxpyJW{*q{Hf{R#qxs#Q@d7+$HvD#Xmb6>x5rS*Sds%tH8jrzy}wt5^P z02z#-h8CpFsY+`S3Amd<2<H-TF*9peykoj771t;JnS0)nH#H=-PLi5g<Wp=md}bK! znd6_yC-ny?tZu?o_zkc#RlL;(Oy!uYp=jF1-`flO6U+8N8P{J6Iv^54>j)u{PBlb< zXJ${Bm4Y#^1v@e>4LWjV(;FR7bH&gbS<mI(HbRZ6iUk$8s*3X%Xxse933}(9<6Ff; zTAPanNef<*54pVp;i7PxnHq%;TZ8K-8f1o!*N6}90S&jggUK#TJBa$_E^NKP`)~Pl zC2cU^eQ_I2CC5$O$c0hel7BXKBl^1PvbolcgPg?h8`ys?C#6D!55j^aRu|tYS(^2n zSyYj=hB@KhCU$A+zfc|g<AmtQDTqGyO)(B>f4~`d-Vzs5f;T>TwcWcQDjlf!V=hPd zJmo^l3eECWzjSD=YlZNEn^c--9wl1*Fny<(H+a7f?S?5A*#$JvmQl{E73GWOJDROV z*?KPXFA9&>_lo>m@0auV_9SjgT>3YcVtm-U2=-vqu}(dX^9LoHs5L4wULI!sWl2yI zyM!8YAvk$GLzRWi%DzSBYN`E#%8*nM9Fp@VUjakcfjX&_NN2OXz8*$9?V;dgRDQgA zk>Mt=aRoJWj3QuqI-8)_fp$38lX>EYQK;RQZHUrsa>3bSK_VWvoU9fo7tWPa;5&9s zBwCIspzEvm=Rir*F`{rrBu!yGk0V>fy6Bz)6iGB4n&%6Cr&ZQy4rqaBbR)TEwU(eC zcR@xQ%7{~2AD*7goWo)r7@qw!d9aufeShGO)?}O@{u*=Wkg!_of<=<T(oBxygUPZO zvscRC?Q!GF6uyHgF9bY*PS!JtLTNL#eBTowmUFELA+NmCL2re>YB&`71#u8<V@_7w zVuoppvf>1ms<{$W0PLCbjN5QSTnU1D?-A5_gkZ}aVnnhpuRIJcjUr+1#g|7vH=jI$ z9W(7t<~GS6IeYwM`%<Sltd2;xs`Bx>GnB@sB6OsFQ1W(QK~|%R((hfOO-W7R>)Og^ zx6Nj+Kc6gY1a*Ym(*ntr<BL>bwF;7Y@cyKjf(W}lk*|3}#+lwA&qjh|_g11?M|jLX zF$1~gqs_M^hm7QcII>n2vKIa?_j~)Q2{I7?Ky6R&rxRZTYG%s`#v{FjZhHXKY)`KB zf8QY14ysCRcZMu$uWg)-n6p3fXF{!UvmoYv5N!QBRoUb*t|z7G)_b(E;-1|_pSBQ$ zb@`xyZ?OglF6sAWp1!F^t9Vn}?e8TfW!|=Q&#<4sTFEo%skB7%DQA3A8%v(a-M*hr z0tx)!(oJ=W`OGv`W&SntORi7mXLZ(%m{?}KdU)&J7g(RjXMg7*Krz2U?0cnB7n)() zhcc>Txb>AU42zLgVXbn6^zFqQr#pI|ow5rMj}8p4{r!Rr`8E?dq7^#Ll=jRRK)yie zTGRRUigfC06y{x=)gj6vXZ9Csm458v^=t9M#V_kv?eB~`PQBp9@7+~MC)<l;ItUtE zq;Ag-|DL!rBw)L%{K?IMj;s<bI#ddhh@Q`!vg&ws<~pV7HJkY{My!%vv7)wy$}_5F z<$J^sEaaz>@fTgO6T1FR*sKcU7bl~5oVt3TQajBQK$ABi;1;Ns=?fxzG%YT{X2ISz z7W}tHZ01(wsa)o=1WgHzH0`I^c=SSXy|$qQxtu-~Q^f5ZdPO}&%YkqtieP{QNqBHf zs_cz~Ie$J#1(kXB1ssk^=LgQdi-;TwZzW)#aTp$Gz!=|5HzX^CW8(3udxu}Xg7h?> zfG7ZIlBiA<_WP(A+JR1jHGn4EOgGM2)W@EXsIK`)fxvPhHIg(L;VUNf90L!EkZ|ut zF<x$rhV$i|NT8oS&T!qk_+tm8l8!gwvTA&(GTdHUHSnL~v_qxnr@!;Vd8J0An_~7W zi9Ze(U%{|Iwn-!9U@51kx8Q|(9^hH<-_HR71${=o_V4y6s7|o{48fWRgdQen_R}mE z`{MqoymWkH;4{|NZEs7Y;TFJpRb)7`&$ioME(K(bl@%WtF1h2ZkOMOACzv(6@%Bd2 z{REr!K7%T%88feC?zN>B_*<2%o||iR5Zv2tK!8H1!OG9{7h<>vJzC%WH6ek#2?i3& z`^NqDN?NYgp*$H`pPmB2wvk{&tgGEp(5n<I;{~PNUbS|DX*~zikC$VUCF{YuIaHbQ zcZbN_=3dCvQgB6(y>dC;B%#ht53EhXYwppkt3WzcR9rfzr1;uMJIzQQX5K8)FB<CX z;quy_$ROjh2KdZjLYP{Y(3O{RS~MI}vMlR^g$ZFa5v1fo)7}B8_v3AcIdaD+CXMH{ z7D9~HtNm`O;T1=(mvJPt?cep&tYdq{tJoqQ9Ag$mL7tQF@$J6>Cwe5`&NZ;pljX2- z0*<#sN}(bm4;n3ib%eog0xrR6?ub{#IEftFvmdVZmy`Y8xLu^UONi~e;V+u?gJ1N6 zkKDWw_$A=9M;`+YR@WOauJ4uGBk1n|G>=VM<=ES<aCFxF%pGd=zG&F*I+}u{SK7g( zM<6{mK-gbOBNC61C;Tgw4_zpYSifX31J<3PXq5x4cL-*o1k*^4ye}1jp`|zW8DNoE zSea>>pm{q@14ghyA^w#`czWdP)%H8MfY^G&cU{+0$6nI+Xc`_BVr6;9X5aA`he{q( z##=y4e_!4$Dar0$V}C-DSh&26oP|TJoBqji@6hYNEB27@AJx-zm?+_0vSB@eqQJrF z5iHi<dKpDTl?^_xqM2?|HS6&hma1vhs__iP!md{)U31^4lxmaE7dH9M@9u?};R(Cl zD@Wqj3I2KHYhZM0o+QuAF+;<%YO~ghmv@32MWd=eYSZtW*EDfA<2D-f_i4{@<S+!P zHOIJ{V}e{gZF7`QdA086n_#hdvvP{&4A^Rqqn$+&uL8(*0(D6s#TmSb1L0pg&3t$8 z7{6nIu!|LumPPL~942Tdax4<SvU*^Jet@F#(a8W&tI6<(?HmoHNTBRQ_1&?$JyEO8 z9IsrMd5UkTL{;Y$u!hL#krC3n>!xDDv0xHj|LaA!Ov(}QO2Qy3e;#&^W7rRty3<Fd z&*x?|z59JF7ZYyfK~+EoUd`^6US}h@lzpSQ4f#b%k|eDo+cDoh$2^5FE2AqH3WkSs zRDMvUc0r25l=<{!>oK4~f9NeK?Ta~cChPqsrSiiXo8dWOS1$9{@UO_BxiuFN#IrY# zbV8`>!1%UH9aB;7Cc`@UT}(GY8pkMB^<V{Ipk_j~S@Ua)S+M2Y<p(aGpKk=@qN6B$ z!(bzKYi7NI3mz^EM9Ej&@u4d5ac~k~Q&N;f9L<Z#Q&;uLmjk`h$|@>3QBf4bO^Psp zV?y$#odEe+%DWxZZ|zpHYx{WXN6ow?pWw*6W#}h;v8m6U6a6kV@PhvETR9W)_Mfp; z7CWLa&!yWJ?MMCI8t>YpnUsCY7LE+A7rhIz686RAfsES&jC}p$4O#Plq%P+W7QH#t z1*#6J7XiDiwhq+r2RUh9F+RpIN+0^^nb$0kqw|J%<*ge|{;o6@SaHIE+|RL?>6Le( z$<MJ@9)SN_U$*e~PvhB_QsV8}AOJn5Pv;Lf*cHp1@NDa+DLm=3*!4GuNvc2o;$%{Y z>$Z2?0oSHqf<-xhdB9Pb@gheOtXM$VNQ5L7sDz`bRuF8l1QTXeY?P2|Bm~T<HO3bo z!It2JgDX>96&vjr8!2kMI{6Mz+aDy$qv7u88~PWStiQGJ@F7=;&6-TKMI&@0@p5~1 z7`;Z5Q1DKT!oF;~y_Fh%f5P3ik!rI-Ig>!pDNfjVFSO@Lz?l@@GTX|G^5>+?npAOh ziR(354Hx2WJuF?q#&UY=2an$Twy8fMVNX{IrCq=rSE$FI2lYv==U^iPEROLGPr#|s ztamo*_>4x0&z6w$=6olN(;E)>0%foiL?qRy9-<IwFO&>Y=ObWJ`ruE&rYRem*(IlA z9jw%1tZ)Q%`L}yL>f3G(xE+up3#bd=h#=3K*zq)M_S(WPgZ*_&-V4=djmsS)EdyfE zg#Py})AeMq*~*n>F6C$&*a{Q#1eZ6}=6=euq^6yqf03d#OnZ9%;047|iOYnGwWH<N zuJ23iab&td==$EUYyx2Z+Da$Qs*2#3_K~v}d;8-B&=s(#@u+3WGyQtJB$gt-(`N9A zqBu;EPv})(_NjZcYNhnyV5ZhEg0UUPl*lpN;!5t25oDk-E_i9i7pDg{7a`aRQ{km! zCZtxYsy=lj!Q(QWa5AQ$^FnPP{Yvg#99aL1>v@i(yhZt#Mq_XB4X{<@%;KMBf}PO` zUCz**w?7q1R(qNRo`Tfsub8Vj+h{R0hI_%86cUwoXMkf!BA6UpwptgrYE69|J!d}F zRvsV16Ei8O;d#O@VPPLzEza2+PGVXVsZzYc98hWnD24{Yo7sYSc7iUHeGwcG<zlaN zuR#W`=Tr+++Tj>$;d!|L_C7(E3p&80;$VhBG{4@)Enwfwk<<rIdyB}zj`7v*`s+Z2 zb)YtTcJUSLh*?|kCcnk5sWR-B{mbERI1~KF7p-=1V+O&7#nIHGiRIy~h<%bX_9d?Z zZRI(-65%%8oT5jO;N<DL1O~PrY*x>IWd*Fy1!>e%5Ibb?SgPr6m}pv`MhaEVA1~w& zyzq2ak%uTE^&O2y07x8_0aXo>#M%!Us+@cf?PRr1(_Nuh_N&!*u8-Hkrc+!T;<=~Y zkEj223`!kxo1w}r)M^kp7CZM(ClJb|`}?}{>|$v%tQ-5M>k0bZy<#y3O|psUU&C=O z(ZQNfBQ(cKt5>m}M=r)Er4e`m(j?FKKAw}}8&)^+-K|ZUJ~Irao-|xA5}N=9;d*5N z_IfP@+dYo$Fs&h`a1}skydpr4cw?a#CiI<RxC6G@#0y}7-+eBdun4?xV6)p7#{XHp z$z!>@e_(`L<Cbwy!QFZq_T_EsX@8E!dan%Yp`rxAxSn&IkZiSE)N%A`N7Tgedjvz5 zJ`});E*Nt)$NZA*;nPfz_6)~7uQ{o^&nh<1lGTUi@odg>!lpSz^R$I9u<M~b`fYtT z+kCx}veV5h<;}i->8a{OszN^yMeY^H;`dQ3;BFGZm`F1qat6%_Lm@bgnO@}?d{URQ zZ9QRS1E8Q6qOA~o=ERSo?heAk&z4qs8P6s(Fl~>XCOzsZxbQjm%7srR7+#;@BefZ7 zeTluHFl|bjV94y#Vp0`NT4iJVHtx{OJ5Nu1$DzN^-e%hSU-33yTyFUCNZl6{9RLY< z!b^doZ0%^@eHa|iU02!*_Rw5TvtVl`RUv`e_K{{o0%?r(Dl}3Q^?Jp$dSyx}O6?$Z z367BoZTb>O&4a4$57I?(Y<Fm;2~^2)J5hOBO6e2^MYGAG=+qP5g=)Qy{4ypz22bT! z=1CvBdrw5<?|Lm7ZR3ND{I(yAW1iF@#Kce)cJZ1>s%&E~suQT~0owKZXWBq;vU?V} z-g7GZ#`hbpSYOV$Y3kYIKnx47K(g0e@7H+eVuIxujYy?l%!NRW1TDvwVmbd+&@RhU zEs<cG1%mpHy*9u>8|(UWv&Me-yqsm_9$CflwoKQNeq6Ru<PAr;teuU4t7frt_k3Co z{s{RM_r^SN#s5LdGch}l3gf8R_6+fegVzj4%dVykF7Vi=eV<J-C8B(8xK|j#e@R5o z)OwvN5kHMMW){CWcPHlM*Ct%XbpPO`m-pUTrma2Z{l+_Z?BFf$tFs+vetmh6UhUKY zUK~H#6S{5k?^c+$;EfXp_iqaPgTz-hX8u@s6{8s!@7;aX;`D>783!IE)N(2=yuABL zm2jQ;rt3&W*)5+N#A|L-Dy}6mkG$LGrfUb3u%}>4R~ZN1S)P1KzoFaVCE1m^>2_5W zUU@g-vqjfH7C-vvSTg3}74vh7n!n2pUR?q&zSUSLU+gUVbkp<bgXmY?ao@i_l^Y*? zb<6q(*9wWR=#OeBcbpd(x|+0Y;aGhz8VEsPZ)2R0KJS-qUXA-Bnp=Ht!S&|#(@viR zG<L<ZL<cJct6J3)dtR+prA=rLUUJ>*9FofZ5_MOBq}Lj1=6)hStRiT)Wd-5q`^s5q zbxQkYX-d_yvr_7x*5|h;BUARZou0P@LCJyZc>-6B-ei3@-fTNG^2D;JB>5or$FcM3 z(R*7>m1*4G57&*Oi=l`^Np>G3tp>$3ub!>?Sg(}2W3i@?$f91jZEgML?jfA9+=hI{ zY!toJCZ%^kG9dnu^R<*}pi^_ojJ9L_tCVYZuBTjn#*sYAb=8$CyUVLxd0ly&SeXup z)T=sGdhK#xXY-T8HmKGPDRO7yKdFXO^Fj3$$=w#t3Mnfx1XKp5osXw<BswX^?_@fc zrt^(z9y;ZJUiWAMe|Yq3s?dKo{Syv0(PdAbm|VMz?U`d-4`nKc$(+16S+bnse@m?h zd+gD`Xli4?GZGoDnBLIPuf5NZ%UEwzSB(4b$K?-IqvDc)@sc-szPMDy^s8x3+BdI7 za|gm4GAV}qg_zayI`NDL9|zk*?tYArJiYPzrtHBpv$5-KiS|+^iQPa_Rr1Co55>f> z)*;1E^rW-YxxFY;5hLGx&h_ks)`n_>3)WJfapTq6chhG|HLq4nUC+8-t@l*^ds6#o zRr0v@b+ZGummp}R?3Ij=$|%q{Qov-aB~UJTK8WsfCgoPc)s{y;a1H5WKvv=Nvd>k! z6LEaaUCC~7Yt302qng*lf}<dEYwzeO16M9QmnV<rMik4(J^p>`ReX;jad#&*I?=<* zyeZk^hwY0dPUS0^P2tS(p#8OvT1n~4lHULf^Y+OiB34BDx0dr<;I`tkB{eN$LnqU8 z&8Mgi5gJCu*#clJk(PH)^K;~o<!lYSv(e#90#K>q?X;rMNRIp_8xmxqERv7{jxd-} z_Vm%XUMAYiSeUP=CN9H<KY*pbr4zc^YT)<T%20O~f^BDUfr|wVwa@0a-1ycO_n}@M zEUQvQ^&c#SJMuh@0=^d|5sBqU2G*nwnXHAookvjYOQ+%bf{ah`$6ieHI2JyraRqO$ z&Wu-ap2U4SpSH3rC3$<vEVuzqQo{>5L>@Nl`=;!@!%_IfbT(aS)Ha{>)_C4BXd(9T zCPAa{kk6~xL-g%^w}Bg{w16t3V{XH|Bq=E`nMXa!&37a9!Azsl>kr&)6|iSd$iF43 z%Z4xV1A{#kC-R(ZBE5@Fr*Py5k1qSv2aScq4>1OO8!(dXM#(;fhgQ~|tjzFGop~5@ zZSPoG>?^NZ>&8y6m_urclOmz9--WY0^0BktMYeiDkYIm^)dTOsbiO*p$3*CtZqc$V z&`jBX5+7Yef7@^G`p9kb+M3=k6`ZE-ByWx`ddR^JVROOqX~R$>=48=cN1fb<UHbOL zUIxZNS-3TlVew~DAagE6@<*P=nQ$Nc)t>yD0oS60mdytfFB0Tlqdi_!4nJrrOgt0y zVIkmMN?G{+F?)r_>kPHcM{qgHvb<s!RcsLh_NXVERIAMeaaOG#oOQpG@7KI4c6GR6 z-AFMa^5XchlsRdYsq2?hr$<4K7yZ^%l%`o!XSYa1qCZDA%dSt!qc}&4Nbs3x91EM- zH6Evz)~gf<q{*KdDeLzTD~TL3>jWZ9+&(?ns1rIh6#jZeBU0<_x|6k?C?ji!hNxQ% zA^({}c=+NGd2S$a?p9GqCs^i3-eGLMy~|bXuSW;J$-GKBdUE&6miDglN!;VfYrBQt zdb(1-o}2vMb#}pCnx~aF840p~bgiy2DsRBHUYRb#!XuushfL?bU7jRE@XN7l-Zp`k zV#`qb$9|?7%<ueuk(xtLyw~{2UEo-VobC<HC8V#s(_~TRPgOYsD~3gLZ@xPdujp9f z96yf~JOhw14z_<+5LEA{`_Sw9mkgPJ?bC?ZoZ^unsr%lG@1=UHKoa|`KDE}_#Ry*& zcs<kEV*Z<ORQY>BBH8K4gtD)M%?FBW1}RN3vTph3k*erVk?mZUQHKj)c?pSNkLDNR zo#?=Ry{;rmXJv0ln$F~RUkHjX&r7yQ<^>;JNc&gE`3RdJ+0Sf<#b7HOutgEcMTJ=q zb&F2#pv8ij>sIBOFH*~wwO28pm0Be)olFxddubnHF^2C;E#=I=JmFkeIuxhyaa{qh zpAIz}d{U59^jG0E#@USf4`F$U*r?#J)b8ss<rM=tU{op-pnWy^Tv3MBi!CSX^m!3H z%-*x$<0+!QAtML?(EY$XirXp{%xE_=Pe<pP*4LPPaLmj35xE|!F-;UJB%HDSmbThm z43FBa4eDV&8oR3eJ$RuTbuZn;F!-CGp|F}c{`t5%MVYRKvR-GS`ga<=;kPP92Cm<J zSS1+n<II}5{4@X{8Lb@SvM;x3exd`rQB&AB8zLQn?nkZeg(a8PiE&stro-R5q7&+r zI@fQRR0ri_#z^L_WUwYH5zeq4m&o_R#dsRRe0FM4UFh5iC8P7+%v#hX&B1-6|F#%) zLJB*sfWdX?=mEMb?Qq?Ze;ZLB?!Jft%bi2g5<Kt)bkNP%Ln2!iR+7?z1}-vQOva-< z9%9&5`oLSBN^GO}Vpg-d92LM3Z*KK%(GNj<+;y}>pZ#@ur4IhxB@p*VStKM!S-5-) zEW5$X!Q}LGc*#A%z4zY#^OU3aukk7DNz&zWd;9yx41OFal+X#1kX;f*a7AR5k(+4v z7Jx@96VX^g0(ud9i^xB0aYRi}KPZ0ThJs~LhfAK^Y&eN}vnM+ESKu>sk_f<r@_8a> zHofn5;d2PyEw0=^W)lcF7_M-$S2%?v?x8}|qDZC(q24RY57vD7vtRR`rL6dXvRq%Y z2g;Q!>=(l>DTg8ug=)e`Rl!=aKs#EP3xMnOHnyXY*ro0Gc(F~k@Q58^8V$e876B;3 z4<v}m-a@gKBrBI>{YU<T6eB+=%T?B(obaNGHKH!~oDzD*JTO|UXx^84hEDhJA9f5} zd33B+(>GZ5KMF#vMzJTB7QF>IB+8QFQz*gT?ys@=QzJD)7Br*iX4N1%dqplQD@@d! z=Ow_g%BcS5vMQdk4vn(?_A*w5vKN)5HUMz0$iH&5V7r}g2O7?0367wV!a<@MK@zwn zQ6xoFum<^)X;4`sty3dBiG<gA3%#F|T}xE_rwL8kM+?q*ZJ!U4Lr#h#gCs61M|Cfu z)W3=RkDaQ&;aeP5O;sm(-Oy5(Yk|z8rc@~T>bGlTe}*XxFVWkUbk%}jg#aWSFLYu_ za%|D0d`*uFRH~|xSsjzTth|=q?<|N%DpExE*rM#opcBd=Ej0-)@kZP}ts*h)f)d@% z_c9wEvdv2}wLUrxK02Q~4qsf7xv0Fh%NCxr+ji;|(ZFZiUXtrpmRYhBE(upQNDB0S zpA_4#>eQ;#0-OSUwo`0Oj%>L-d;5&ZPyu({Hg>dSvqb;;rzF0+zo#z9TSm)2#<S+} zB5bz6TY$hSTWAyDrx7H^vlPDvD7{5X^zHi~ohV{~6zR)A(<@7(NJv#*jb>?$RPZ6Q zm>_X8<xZ1cGgIYGHN41AlEe=?bM+dt7`*rdTg0+gq{P^QH+DOUMi_8Gxyj<Cy{c0b zh504RY@qlq$*Q*vwF0a<5xxWAZLk}U!tP_r2E;k*^jW+jn^ZKiG@9h3^B>1{OHj8o zV!uT1nFH(|yVrJD!+L1!#t5Qa<&J#hxXlP&&#V_-3J}ie6{uh2@h9yWy$Zf~g%V|n zJp5|<G<=67zQabmWg{N5g+>-Z21JnwHat??DK6POB1L3}?R3i5ffgeYoh%+5Bug@| zZK25KNXX^*%8gJIRwyz*_u24fG=ym<$R@$M7vWkI-usUnLyCiXg*EVsJvH)wn&o*A z$@<<KdJ%T~tAUYGa>Mq@>tk7miB@(Ya`7wCnSHuRYR}lU3hg=4+3KSD&$lu6P}o7R zbpGVj&S0M_)Lf@ZFHU})Cf6d4YP1uZu!FMMPA}MSH9S1!{}?;3sHVE8U2jOGhu$Id zB4FrU5_*^3K1F&HF!UlIBtSwBy@(hD0TmP#0YQ;&6p>H`MJ03*5D*lxa5B!hIOD(j zuXD3U*2>PBbItd8mIMlY*=o@|Au-%l^?YR+N@7tm<r{j<{+X7RdKD#Z3j=yj8r>?n z^zF<n4yL7E<Am>L@aWVFwH;a>r}O%i-akZh>16PF475<uPo5p7w626gF+$m`O1w{$ zX)8f{*1}U5F=+<YY?NsCK!E|wkS$b^jO*@ZxL7~#Wx2`u;M6(u*jczHLzc6clV^Yf z&VbOFW#+nNrs>OduHM2RgXa*<26aO)(|B{6M1A(To*vy*X_na<5ZkL4b)Zc3A1Zd! z1W_4WC%!WpG~O~y;EJzUAx-?mSL~LAWOCM-zJZi*E%er*m*lMSC&rj;+q?EdN^WXm zWfmfx1G(+>f-M=zHNNhhWS;1B7R7q5+FAYz3B&`8K$?Vmdp$RgvB1fIfD(gH2Aaib z_<mXTlg4_<-&1}@f&UqBNta{T=$e$7L4J#&l(6N>J_heoK9RwWiGU|=55M#HHVKB& zc(pLxnKa%%Xv7;N$L12-BH2pWor{?y;GLnQ=Pp=&`cTx~UuhL1DDaN?5I~498GNqj zpM&OPa&666It#HTqUyyn>EgM1-FXRNS?T9<^}?Gp0X3RXbfahoP2_HaEP~Az^3(mH zU%10#-DF<@#Qu7Gpw>K1LXm-Y*N4uX<%<7#M)INP-Se5@<^K7;0uCAM^S8y#D>&}< zbF5;7-M}V|7@?;8I1}rBkrJ6LeBDgHgKU^y_5}Y^Op<AcOhkFcbVleM3qjnpdBk@% z+YZ)e{Ty$Xw3QQZ<@Ex|zM<ndqn{eFUrf9f@xp$~Mt}HF9W=cOoUp+Ws}_TP7bgEl zWt-a67bWw%@|zynIFY#l0cyI?dyL>FAYF6Xfb}*JYpf61@D($qw_SXNT<)ZZtHxG0 zdp1dYZ1)wU#|Ox?^;#|WN7AAvnAMI|OXES-qG6u-0ilX1p=VV>_Xh;m2LyL@gl_qY zZAt`vOB6Wp6|kl;{a8BFt;VK^5vyPmVE;B>$3}=6>uMZNF|`z=cL>cN@>%){v=5xW z?kf<h@;$r^KTH4hs+VS!dS*>qjMKulw^9}cr0-9A|7H!IBqog!r&>pXp7@F=EwDKR zi`qshOL-FPL;m|JA&$N$@@bGtN}}YpvbXvwy+I2=bw#u5#r7obraTnt7$_>j@D$Pt zHwL1v(|F^3NjAO$O1^^eG=7q)d-AE7SgWs|4wQGeopmamb$y8rToE8L<idn<i!cba z0gi2?+*mbPIGK(f5vcWbxt$?;OlH4J7FcGmy@wI{2MCa!Ruu@k>}85{;zXM=v~n7v zt2L|i2iOnj7ztm!s~WE3jCnC}na>#3u%i>tHnYcuynZx`hGj5Y){Ad%<(c-B+f&Tn z`*seR$I}KCJL*NdW7Kd({3i_3X#--rG`@acC5o|7jX>^>gkUESrhutE8W7#1iHQj1 z-jEP59bgSfXKF3u_=9Gh_F-3}9Z1%Q{iz~@djD~G#QvI=H>2n+(D&k*_Kz8Cb!hH? z85|u;@ce-j=}8_-t1;PAyF1(gea4_OeHmvw)Z&~h1P6@8y8Rv+$+r^E$a8rlwGNs8 zFg@oNlHEjOTJ%xjK77o;{FD*T_qzU44NG<Tj^Hz=nAHsDiFtpZU-ZI&czYMm>jZzj zrhkV;fshY^vJ9NBQ9_I-qWSc`(k-#KjLOTj2+4hs(d5>TS%a3{JmsAn15@nVWTq7K zi&Qk5P`r<B9QP+QEGUELIGyP(S@c4fXgZCf=Iu<{e<da+7(}+P6CBts?H=_{*K3hg zijX->c-$u;-#%bCuvA^MnSd0LdgW_WbN22`Q-zjUB*j;DI-PgaPE4!*Lh!6xT$aD> z;C1X1sZSX~mKhrRr$|;^U;bo<CwI>)y{-Q@DkPu+x^_>*Tk{dmB)z}e#LF_kUYpJw zAi;l_ZL^CJcf*L<G6=ZLiLGPAj~T@G>bdn8=zm2Vk?Cy45^SV?&L_U2yGneor$vyS zBNHpZ>$v|ej8ZT76~_M>u4#+7WIB8w(mGb2=4>#<axt|of_^^B;DetF;J1BMFX|z| zRyQzK)oiAn@tbNax`?r)N{FT~TpKYK(qUlV0yy4c{|)=SzLODJSudC^I=@rjc2VkW z!C#&*DK-@b{t(*uFJHbt7`|E`)>br|bcP`5W825~nxyAyDN%<r17exdLZ<ahGi2B& zBwIdh-l51q{B+^5W~zP&IAuE;HQ8}?-|6#rQTyYM(W4AJ6F^2pz{M{Y6Yr0RXjFva zTBnp?Dz|<KZl!bc{jyd0#VYM95b*T;xDfwhjrcL0){f@2##mmEdhh7XPojyGa*K%K z+8n*bgFXpvE=89kSqgnvXMFgQ)5Ibr1m)}5OK4oX_4md_zLfUegAA~LS`?*bH1zhc z9o&W&`UnW+<2>&9tFzH2hNgk7j6`>_Fp2tH9^PK>Gz}*dTrR<_MJAasgV24pBKK_* zhO7Ms!kbQ;Wl)}?iCKHk)mw<pNQgskMzR};T1WAF4{$TqbEQnPc>z+jXeJVw)d}<d z>OTSEDGfpLg>igN&UF(5$a63(aNR?!Y+=3>V@Z+~n?v&uX|Oc1SO){Zsx~0_b$hZ- z-JTgg*YK!^cR0Z~hVIhbOwU#*`FW{DuHRQg7SBhO2yMj~dNdZju4nH+Hhj5)88zk( z!*H}B**+m5(PR#2J(sKm;slM@Y&X5rPv7t_B7EQn0J9I~$`1*FU0;DXb|e`yRyiRy z5c_v|q*Sh;z9as9XT;aJf<;~Inp)jh)#UZA=#QPQm*pRb>81Rsvb)T^HJ@XD&>0H) z(fsjcG!VVD`08=<#7#7wS=73tWwODtREX_m$DQeB+j8q0cU|a&(bc}T>ssrJPfuHQ z+nhvgI$IYWhfK3SIcdAm^WXYh#AC(6JFZQi`-;c9^Erf^o>L-*f_4{Fbg)|<$!1D| zDldZ$&<Zg&bA4lf_Go$WZPgEger^5zYJs|Bl)3YM_B+(x>q+#|qln+5Y>VUf9CoHY zUaSn&eJVLI>z{C5Tms$szSf72L)b2KYPfCeUT4qI*ZDi<5K?dNPwe6g?IVS>tM<)? z_4n7>*sdGs)%b-C)jaR}`}=tM6NH0Y)0O;VspP!=OqrCucQ4JAT^I21XB7%Tt67Vu z0_3c7C&*G(pmK4AX1KMwVy8LVAvKY6FdSna_9989FnqnNq1^PmV7E9fw*1}2QyeW| z)yr@za|)^!1s*b2-v_w!&Q1m%*`+y{E8LFPa|>N7_qhAA)PwG#8`nO7e>b<~Ego7c z3u(I3<kgeo&#rqwj<M0&*?T8*1)j`puYXE0VN)29dHmY&SfIoHGV7~pc5@Hir*;*z zZP=YcgHI5&_VyvStw?jnBvjOD)Q=hUwF<vd)6&E&gD>dZ+Pc?1s`$0FV@~nw`DLJg z{OXgAX*=DOfX1!%VZIOCc&K$LTl%B<A*wblWr$OkW{}Ko(zjHaf9|J%%Xz~c094!& zgp+>T(b;rwx2HW?`lJ3d1)nAO$TkY9-e1L)rvU`Ss@RW0mD-(3`NH>32MiyYT{pN+ z<t(iRStzNdt&4^fYVE8xoLBpW3UD@`l~1-;C;My`>Kz@bmuS6jSHIXn6;t~D#_pq8 zgh4~1M4nQ(juaaTPug0o=H`#kIIkhscId4C#9&---&X2vN~~za(Ja_V#$Nj?KrYnp z={6bHpK&NH%I?ADMeA=QPLI2;D=BM_Cylt~aWxM=G)FzK{7#^n`YRvLZf0mFBrJXj zNF1PLSg>pD-q_DI;9-mWwPvDwyWIW9BA!**{n<bpX2;+#u#nJv?#|#9#)eGAORIi) zL)RXIfVirS`@d7SN16L|D#N6TWKn?)Z0)^rSK{sg+asd7>s9`@PBqTVO*?!Myz%}U z?s>wuzd!E>X}rz&Mv;2S71|ihGIOo!QQ?c%FVDV+dp3LJg)47XQg#aK+i$1C%q%dS zZidH~GFGj+S#19DB))*^?PVbH$>5)OHkyJ7G+HN1ag@yJT;(Tq%2E#>E4lw{_$%wQ zJYfe1Y3J<0+I3AaeXsecD1`f#tz%nx{A?Mly12|T;A8%~@nK>A^F5+vneVAzR%uLz ziP#l{xqhcatF%{f!q$7HRC;wUlDwZ+@EY!>_J~d1dqC`x2VVWawLoBPD;FCpQMp^m zADwTKSVH8`R^felE+`mx1>A^)Sy4VNT9J|#%B4rqIj-9g#P!p?25F1#5%+?X!Xr|q z*cJo3l>I@eGeZOalPZ-4>c-WD%NEKlJ}~=CN#3S;6aChxLj8<`ii69p=G{&Cs!>CV zuEV!c<&xIl?u5E6_e$wE(K1a)l027NAgD%PHf;Ens`=sfg`J(eEq@OR7FgvRTq>`R z7FgJAsy46pMe*LF3^9f346Dwe;Gtm+H<oys&w-%4_k7me&-cPTeppez%iG=9m?=r3 zx`>@EFJ`vsA2OKRg9bWG+tn$xn7`}LxfcSm4Mspu51vkz2)!l8Th|`+#qa_FCSpNI zV{zGJNZvV+NK>+tRRZ&nO3>Qv8!eFPPRjHxuYFf{35!$hH*$E)d;^<LdyB>)mu-U= zZ(ds%2TztF_bu<Ed;8aUQDgH2F4jTOJMuU)tH8p1+)-QTK&~5;gv-ivru&IUHzVIX zWD9kXgkM2h2*>(3Ue0W2lODh4_lm1EvYWsjr@7=OcTZpa?>*64(g5!!eS8*WA~dmQ zT`6zl<);=R5?yQ|XR61!TK?mS+4SufjhrlkN)qCoR0cz`b74$3Z)g7zQ<aA5Q^RD< zZi?${d@EO1n35F4XwxG2EU(wF?9U#9rvX<1G82JeDY1X(e&V}fPEZ_3WM6)OYpM7{ zXnI4<U*QLdf{kndeI%;udQr;H>#|uREHL%-Y|+|NR6!nHd^i6Qnh<lq7T$pvKy(%j z*3rYw2os)6WrF51A8knuF1#%umZtioU@!i7_|TvEG7jORUrW9;hu*(j{fNKqQ)M)J z#lyn!Tf$9?rEpUsG@D_mfbC_%%fyk~_>T=a$FU84mW9zyo$}|RJ@BHgNMi%zeLT<H zPm0sOyB=jHPI|;L;XvlcH93z&YrUjIZPFQo$B`T>qKV^|j`nT72yq+yPBM(lR_EOG zh3YjV)n8M&d*S2vY`fv%0U!Gg`fyF~+vNJUv*?aSo1PGP#`I{1PlruyIOli|e<n0G zTX5NdBRbK)<JS5ei!n;@3Y*4UnyjYwR7Sz6B62`5qCJbKcEjnyH}&fG9$`HGlFHn| z|BWwy(9|ckgOfWl_>MM5FN^&Nk1CwJaQ=Gs4A+Mp`MhG`x&Bd(iX~PlWP{lH-e}aA z=v$i~d1nrMHePIs23;#L5q@4Zz_m>$=LY;I<d?7UBI?&fG*(7z)^cgE_(B)f#h>3M zamX+llb=jnwW_H*mVO?~9!RYhU8LAh%-CtUHh3O-3hLZkI(uRQXiiDI$+bPI(9Y7& zQSog2+yDL*bbErh4M`v)9}FqR)F8+tSf}>iWIz&j2<=$;@I@PEUe$Lg-g-`g=Ho&; z5qdwZgams-N%I3$uZZ;ZXRxdySyCydD-C*q`YOUey14v`Nby#|Cr%})FGtIah;E$H zv2R@KpZGls9+;LA0Eniad?0=PcKm6Vh4;b|+taF-y6gDXH@_bmmUaEnnjc^rt4Vu? zRJAblC}!lU@@4++L(u5qJbrg+UvWER6ap+|>V0<J>x1n|#X7NHq116J=wu+GF&y+; z1L2djl!KLb4X;2;tfyr2YPY_>&r~kSEhk#&+txF3*<$#9rQ4ewc>m)Mf(Y~L^fx=7 z`*!leO>Z4wMFM~`iTQ}c=4@v2PurM|x%8AsfjJnQPF-Ws@$~X#exeOICUHnjO6g+g zjS|mQL<%n=!_A#@ksFs6mv+iJs(B5?DBTV{Byp_m*(^5U_J<6m6M^JI8CnLu%+=;2 zmE8}^;7nrKCvhwR>>n^`=tSMGR8~PWkVTHC9%ME`5|xKw{Ak7jlt>dU>$H@A1H~p| z3Ex4P_z~S_s4~4=Pze;|gvzl%&c58DuXez;fn^J>%AS#oO`tfF+PT#x*{>|6ogg@R zo3R;*x^7YIGbFkvh-sgyQ*i8N;4U!H50XYR{sDlz#GF^(**+pP%iQ5RRD)ZIu45Yv zx}50~4j^YF!%rkfUpuGklUxt=<iQ4}6BtukOKMNc`P+;d#!HNB4tc#l@k8=D8&tNl zM^O4v7cb9#x`K=vZ*k-SfIBiU6*MCgiIp`YW+73tfuH>XCaDwvnAbDcs_bS+Uhb$o zrgr8&<7?kSG}q|tGgC$=ifMmOYp|-QbQmWj%VCIuEFCj(_}hS!G}ZudvAv>klSmE) zdmDK+MJiMpm9s+?1|=2W;R2hb=NFQ=wdG4_rjqZ-j6bQxH~GR81yT5JZVLdg@BypP z6(D}a>bkZ&NM>Ua2Nx;_%3ES2C{yVG_x6FNw}W&Y<?^e_$eC<^rl5BKK!U{0U{%h& z0#5URW$KiB3tEhI6)ev|Uz6F*euXYLRB$#hDz<YweJR8ynaWjjOJf<pD8|@3KE4UM zs-+Hc=>k=Q9Vu5rt2mumpOls4E?DH#g(ORGB7(0-5LHKlROZ<H-3vV+bKgkPzpjgF zb*gI6HC`Z9-FeD(CrPZ?Qz>^TD&SX5M~=^t!}ac`{$G7+o-SNB;Y84%?H3pl004jz zC-@p81Hb?Pa4^6C2LCTUxWy34pbyaFfACX)0S-n-k_Yf`Zp90f_WB_LLYPmayKQNh zD4?FrZQ1s@GaS$g5@AwZ91Z&WFQUQCUiwuf+jYkkTJd|cDjkl<%jR$US<1Cym^J6a z{{!7bUtt%08nvMXfs)c#pYk+0w>Vz@bEeWRbe8zJCUr>2)l55V;dSarx9Ww*SPx+z zCMVl9t-F^+wUomE8#d6vd)`u}slZQJ+<_Ipv|slZN0fT!$ZQ;8jiX0Sj=skfn&RU_ zzIheO$IP^Z$Ft6Vv53$x55wPiJ{SZ`*9}|0V6r$W+`kmx7_>3>vAxy{xR6(%n7#8M zYMFy2jfYKi#q{;;<IA7lKEG;Goc;U^d00&K+41+Y;|<y&PKL=*do&QD>l1SA_v%;f z;cGX2QvV&d@r$Q|UR#h8cd}+a;l46#B5|?`-9EStyAX-2kGgPVCcjq|ElmhIfAK%j zo~|2F@=eFJfd}LKpN&OtS==HB+<JE@(3MRdk@7j^`;DB-M<Gr{C!(=$b=S+L{fhOc z<jAEqJpwYNE^fL!ac)6(ZW~_@uMWg)w8pRl3=IE&HO~MbU;~uO`2QA7#IpT=ESi+H zON-B~kvswQutmzlhL=T1lUxz2M~$ya<(=<dc=hP^SS8B;eyjZBAWH}$-0uR)xOt*V zKnK{|d;EV3ImL^wJMK6G8aMS^Cy}@r90xe4`}GswEW9i@8-nU=oqrrKSz|XA-}c{= zklxofY`X4$>`jDCi7@#2e14{4H5-TZ9fI}~xzBjN>3+EK(wY+~e@p|dj)`(y8L8EP zZcM;jeHiR|Izr#12m%6!LCDGJcK=gT31RgjNAs|+pT<A51hN7euLR)Feh#U`NV!mf zrS_-_*$|`iBCAC7J%c9tq8a+1&j@B^KlQrP*!v0!x^Z1@!Ow8X3Lpn0oPTj{O5;ha z8(-B;=7BTUY!C6Ndi54aD}Pb>a!!h1rkNnKxjfCv9X|6u4EEe@DnTtI+AM2HcM=9% zvRXCG5>hE!&Q$93xa0<&^|_I!F{e|^EmH;%&{uh81}@2ZYLUXgzNjVBXx2jp5Wfnz zvB1IHvj)VDmdU`BTHRTzpu2CXxzkx0i4Fj2FMwpM=O}`CV4Io2eT^!Cz}iKJZrr%( zh|X|L{P9H+do6BH$PwuS;7DLmqywY4-6%gmy#I><df6{s-gtzwd^tBQe(Os!Iopc| z`k=T6(IBzY)r7{!10v1v)KjuT>#e!4uWjAyTL`$3aTwxOB{L7NwJ2D)we;oI-R(zj zw7#}lzdCnjr(?z~ubFYvm&FwX3%I;w4fna4-u>R|^6t~kre1HeQoD-uTk!f^Cq~-c z%io?KuiyLD_vgpgZ!Z9t64naC8ooCGmwQuXz^uK!H-xZgrGnV{<@ZMff?M}TMH04E zgZ~o0?^C2J7x#>2s#*_TD|KxjjG<oA>o|>f;orw~Hd?>GHTb#xeF6<rKBSuRM;uOC z((AY>TkW00X$K4CqZyZPS1o5fg4>SfE+p(6y`yJ_A4v!*#}rchn%g>uVvaLl3w-5| ze=Nod=fi-wnYN#wL_VL6|NNY;FG4|wf+LS<z=w?E<@|eJtyV}D=XPcpT_4$=EeXC) zXX_>G>SB^=mw#?FR<f`0rt(CdY_)!H_l?}_Q2D*RzQzEkbZp%3jf}rQBcN|?tNhuk z9Z+^q8<u<U$Ila?@kX&3-udTnW?EB6j_UH@?+?2*JH%NEe3%Kaz%CP1A7UT;J5eiE zV+K0ENm5Y>V-x@W9ye(8p(owd{QuEU5EfHth`JA>Y2%XVF=>*SF6iTV-hTlM>F#ug z<8je~MO*7=#8rXS=&B(yomxe*7ch+j1fYKwGw}OSIG!=2?>mhsjMgjCnU)nKCNhc{ zz~Z<7GFbLhl50>{tu5R9LawZaFBJEzh^LV{g3hit1~gDPt_^rKRzHlA;%z$snZ>6l z(U-Z$0H_97o;(xKh#Uq1{M)x6#gx&T&y2aBB${O1rQg)eM@n68^`BUcM>rvjN#`ar z(Hg$SK;{4;0F2&-59av#NaD;)1EvJDNGv6iR-d@xqMCQOQ0p+@%k-e&bpOkYL~Ke0 zc^Fl}Y3U?Zz(3v(#Y{ElhaN`fb*AJ<G61%?4&$uaDn`YYmO)Fs#)^TNg%zG#IYF$A zVv`!LWP!bNKw~(vmAuT$;FF`MXG&O@S<r&)lgt{OrH5Q7#~uvB_(NPpwTn<nQ|PIw zrcQw1TuQKIKV|$fzyoY|_~|A|kaYg2UdCZJ^j|z=2Rcm1;tR6CCvwgedJvfH8Ax2n z!wN{jAUE4HF<u!tQGPSQA(!F0gZonjh-DJgs+u{=5@9`DPZ;X<JL4gND5rzA^m|*( z-qM9~RGvGC`XOOGOo3mbx-g^~ulvdq;o>9NvT|=(W&%E2Q%tu%pkA8Sc)4Y3NQqhV zQk-Xt%`>nPM999FBca~Oz5~ZSp#%23X>6H6YG^x=B<Q|<$TlpwDsn#1l6S)=Ggcsg zs3-ze1mkih<JN@1Ocnv6d1u38@f}<XtyUi~Gdzqw#9Fdk*c~nQy;A_VZhxcAM7|j3 z1oU^czuD%A%hL>`m<SIW60a1flJspEfadvDT|&#$s(sr-&_cEr`{j?gKgP%e2aJOK zK8sCHJW^@o!o}XPjy(Gnk!@Ev`<qwqaC<a<WSMu$jqHzq8JBwdlqv419%jLkkzCo9 znb*D^f6Q=+&;1=UFAW}mzj25hz=iK%TK+S$C;Rbpfkh+{oJ=^h@qoZwK)Nmq@PH9n z`s1Fklt{5(2745;O6M+`{PeMzWydJmo2ZypTnPPdd5BxdOBVNL74N|ZY+1s@D?*oK z|4Z`HkPh-bbbK3&McoAD?3cg1pi#*Mj;Y&OkfPYG$D0bAmV&JOGh-@z0D0W_J^VLQ z^Lsoo&m55*1~o<d7xW@({i_;GDO&S2JRFQZqO?8ps)Rp&8lS4DRehzDrhP=zu#3Wk zhsCvhw;aTQ&a}>Nm{#Aw#suB6`^?AUTCZxMBL{fArPI@35Cl-wo{BYVQgqf+)~z>A z0wWDfRI5e8vn^}5RoQ9aX61pf7Xoiy?#@fcT`t-(&J@WSkDr)&m>)Z=BC6Qhf}VC{ zjyL+n|KW$GiC=C+CE9KAmtvQ0(!>0q;P3oEXX_dG0c*U@@bm}bnZ5+RUIBJ|JtHI$ zFU$(8pR4JWwK^CyGT*gQky?zfgEh!F4NE)!ejjyOXolR9mT~2g<dXlC=tT960va2H zh~>Dz-i)Y%kVWLfs--L_=Y-5WoPRGz*J(8Uihot_dP@XUzi&U36u^bZM44f|RqHY= z838RUNI<qR*Og}wK_uxqQ4C)!q%jDqLw=ba=<eX!Q;<fMPMA3#h%To*yN#Bq1Zm3T z*&{(yaa)4wTjhdB70Y6buZ;EYigD(Dm{@%d*TeLjBLPgN_F4jXVW2-7F7bd9K$}V^ zUMMr>8RV3Kq9rN})?-_S1iHQ*FVkI5(fNxCcgRpf=`N0RmPU-|t6=46fr<TN3#6NX zaT0*a))MjONN%54daAap3Ie_6o%nk?-F3nfNt6^6%DSL%=tzq1IFbCKf3&WtO4OHS z+BYGCcr_-o<*4;cCgk{^gRorZD2<=7n<Vy?!>a<2B*tR)aS&kWuEpqh1?<aA!$8zg zU<*b-wI8Yn0NOtEk}`pgA7AWGXAFQ|`l-H;jwxA<W&g>thE8%C2(895^RGd6`MJK9 zBV3TMH4F>|#Dh4~T>$8U1){{<c>hrSpgr+T+||<&2c37kud!@T_A>KgIN0VmjJgr^ zU`~@VDA64u#f6jeVLXRM&>R_~r!2iS;<fwLV^N8!vFTu6ygkOEGe~D>?;^DFA}fQq zh^i#iml1_XXQY7v`f$mYj-V+X{M=f|PWlB?7q0WD)GJh|j}O#F9ueKF87Ir1jU>eB zBx<;+&+l<C);oXccNlZv2#e$2KwimrX8(xFWtI@&+e8o(5&6eS5e{P0l~6o4$2Wpz z>r37Ok^>`+&XFQ&Ip=+T%=#4wouhDZw{ZS5*RQ4DlSN6d`GWiapq?&MltcI@n&8Mx z_EhOmImEpXb!%RZu&lgTPL7Y{qKqN-9c&g?{UszP2;>I>8AJXJK<zXTNm7LZ((pPe z2|Ssv)8Ju5E8_NL6B5)BeTAqx&f~)1WB|Y#O9J*%f~Xlv&PCif_ze=2HVKZCN92;> zMyK@LGBtBp>KeCdDn|wr{<hu+qAHal8SQ~cs3>Ku($GSIw%}!)lX$@uI9CoFw^YJB zXbMnq12kAJIo7WF%wHelA$OjKB=d~UigTU_Em8@9g-j<f$|@juLJ@wQs-z{@2$nr9 z9qyHcOrZO%QAPgMXRfTWPGWiH;-lI3!3w${B|*BHipiZ?A@aDg(Sc)TPd`IJA`1=A z^)VpioLSoorVo3>`{=*L>H}yN&4G%L8H5o~Z3O@*v~=A*NNWiag+xSSLuEls@l;ki zQ08C>=9z>fAraZ3rMI6dZM0W?2Y?4i=A<PU1q2MB5NT-Ed*~>oQ(6_veg$I`qYMC& z-K#KK5(IOCtNN3MJZlYofcT}#^gE(AlMpxh%O<POSdXv*Xsvss!k7Lmj5Np|lDo<i z5lY`Lp`djIghe#iLZOzwqIyIS4D|tmsO)ujL?3n`a$|!}t(0G3S&vDDNj@C02<9z> z0gD9t8k+rM6{qAKgq8ziodn1Zjc{3l&}&hc>N))F%8^$f(XD!9%}p+@3OPmPdc?Ud zP)=S)L`f`SVJY-hAh#JDP}{qG@fO$y4Y`Pbg(7RA#SLsGwd4KuHeoQko|{dMP%jeG z#2v(TK(S-ZnH%j@w@A$GIr`ls!{H?iLYwt38c}r`;-P)Q#bsR&Dh8XsgIe^cMc!?+ z2?GMD)%J?QB@~1X1n^sE?v{iPw^xBB%rdd8-een&kQl~&_M-L6b?bNxze%_vLK%^6 zzzmoyiMwDSc2kAWjB}PJO;9ROtH)fo$1&bs`)D9J(1B?x3{i<Ve>?2%IF7uqV!%4f z`Un8Fm#%be-3DQ*FZw|o7BW(>cammRBfUWSR8}Y!yyF9nr=RHrg)hf9|9<rV{IG5D zwNke;qIby=ptdm5Lbdd`zJQ7&nSh;rkhM?UzbHtTp!)DH<`D<h4`fCtmA-LcukQ%& z4qKO^+hy<SryOg4!?J8TaNxTMXHWAueYD^W=va1!vgAsrUJz4UKP&`wbA-y_frJ<N z0NxI)@u*u*Byw8Z+kfFW2B<aAD7L@A^&<zzllj{+`*{3b3Mmv}u}lQo!PW?9-OEA~ z8@CK{Q}P$s@SO)UNQSdiju%71_0~^*aj~9x4}H~tnQ_31?KhXfT!xl|m?}^WRX|u{ zCG3F*#=UBV>F_k5g3e5*k=PzA!D6k2QntE&axs6Iht7H;x{%zy9-UB$@`A)d{VBfy z6zuK@th`rEN)~?oGBgkgSMKGqP<vul3@s(Y8+!Ext+l^nSwRD_0G91O6R^0)B@wHg zx&&U!=mgb+&o7DVouWjTFwkus#J4TAG!pc+ReMkIvmSL1vudrkUs?UT%<`&P_xIR~ z!nooz;mI4s-CsQ*RgeoQ2$aE$&*~lZQq%qdXIHXiWPs+UC)eNO@^XOASQ<vhJoZrs z4^?s$fWznX5sz8QP>6o8FGvFkQpaX9PBL!>AWVDvUDb=~Te!!c8ipo!r%SPHq4QKY zjSsBqRRNHMJVF%-f+~QlQ6jw2zA1Z_2}neMOh+*If#+j*{*r&C4^JR^NL%W84kwGI z`}3<qtbX|hzmTLe56u&?+DIp{^9Yb$`*k&}G>8%G@XIm~3<UGQ?rI|3!kK(gu;^aR zy7pAy6b&yzz+cf3`T(=Cs*d6JwscMmo0s+v1jkhS3xz22_bg@Sk)Z4Ibw)^#T02-B z0rdg^OT+`ZDuyk)H)QX=$D$??8{7cE^M}r-bB2&W>;|6PUt7Rti!vaIK5HMQwg7~g zP2Z0|CbKgLv#apX*z=)+vA=j;SWQ1z1OqEQTyxgylr`-qBZ5g!wI87Gog0X5$Vaq2 zqt_1<mz1$se-Nb<b`Jmq4Y;6x)Cjy*A^xv&IE}x~vaa>#eR%A>A&<zntmI|}vhdIc z1_)b{`&}RX`m)}X7#G^Zo=>%!Y3k09+X79aI#&WmQJ4Z_OUSfbxjG6IlMbCeWd$5j zi1B>-ll8GNyz#`B<IvB*^%M!tXL_Yf!LJ0ZkBYsenD_hHY<IY#(+8~#K=K+0ZMyY5 zor(YAG#KL+EIkgFxPB3I8!9nlDP!pPQS<W&;oJZbl@1-VL3pwOwxnt0_`a!>5$460 z*B*EI#JsJYWO);4C-O&A`XV<bg#PurvPVs>>BBykYy0lJbPv~Y>*?ZE()2Sx{6c$8 zlOt6y?Bf;Bv8bvFyD>=AWJ&;2N<StJHSTQC!R|RSoub{_qnSpXI1HI_nO<P3$Js4( z0!uxN55dMcv-_+Qg{BCTuZB;@rbmLpeIGA`eb*nWvL`5WS5c)aPoFQM$q;Wl1n&+h zv7!IRGp*KlBeZ9Qu|wl>xlGzYOwmh3{lQ7b0Wj&JOPSr!)wcJw$S$ri%|iMx;v4OE z{Y9xgtb1O8EYCi#U7nbJ1M9FGG6Nf5Dvi%Z!uidwHVSJ!cL;>--#<1)tVAGM&>vDG zm?+Ahrwz5wLE!;-a<~hN`w~lBfGY>*+?e6Ah-vt`UB`ngrr+FfkeF7kLlG!AUOT`j zqU3Ea7`+gI_<2M7VcRS$16-*HN$7v+^2YD2XrXwaYA-sCx%dNvG?dAJ6Wjk9psqkv z-z9T1NwgvQ><p_+VCj3Qm6hjOv5;2sN{t4k$mP>&0iyP_pQ#)RS4s2Ch$#grzA`_| zbMUq>X<QC218D#oT5SkI`1z}kNB((Q{FDxo+cA@Rv^@Ui%bB=ke|xo~?1<`oOqB!d z6ZZ%}0$GwFaiS0}0L<t(sal)!Kt=UngC(R8le)9@%zNA9J8OBJeV^EN+|IUv`d3L) z+P&vrw8y`G^4{T&(w#e}Hd$zfpM9;1+F=~n;@Y3cZ-DC>?7Dvc0-M~?+S%b}7$ug% zx6gdDS2z7fd++&n_n-G(U5RuesuxcC%KCX5db$^H{8=4Qd$P+}g<MA5+<&eLH^M>= zBN3nP?;A>O0INw@^s*}gdOz*kmdb&F)aF%rH2!pLjm>vc#Yo+v(1?HiJ?~9KS^I(Z z6}4A=h9-xgD`>Yk1mw-9ouz;DL(d`Ro9ej;(^sNLhIpu7U(<7>(d=HqPtdB{XLVoT zhp!vcpn<U(aK!R$&r|G&6gOtf$Ec4?C1!rpy7@V5^#>GBn~5-OB=0e1yz>}8Xj?o4 zGi;wLL#TF`=Rf%Q+i92O>(MV~n^|5+_9etKF$nH-ooRo+@WI*T$n&IYMh5Y}zym)n z6+qi;zsLOaGxx^dyrevlUftV2`uZP&t!P^LhnE+6@8LC7vw+{fOnx9ZAqlP%j{PSu zUi>MbX+LZSo4-VOj&C_Fy@X_dr6>L{eUD){4PbTuyT%s<yX3%hJ&<Yo8YlNK(+C;+ z{+h~IIt;G-{wKGI*>9NC6wL4}f_37TX+H)~C2*wcrQ9MjAfNzX%OZL%Q^0ZAG?!P| zd$`JR#k^3|Fbyo|v}#!*V^?Qd?X+fHp?vX2E(A$^6!WS7>2S64hJBr3s#l6EqOn4r zr5flqS?34NrED3996N8h+;wg99;tEt>UQ7dY8*t^ZF|0sAmS#}<G@m)>r}$fe#n!~ zM_@bq<HXwSn|EL8-+vGhk1(BqEH?4EP*${%n|PiOgtTGrT$;prX|&e!d(hh(hS#7s zbg9PYg7_5|EqQ<vYTLyZ*`ojb2!H?N)TC%R;9%d_HU#?qFY%q$ver<6xWy+;+4R7M zQX|4{u}I8R-nFu_!LsO?!iokK*_HOOgoCy5nC-xmKgkEH%Z7i{rN#&4TMg@8ztvFr z{jT)*6h?g(Sfwx5f7IhitlIE<Iw+x%Z>%h(ynbvfKc#esT_-nF9dX7?$aAyAOwqd0 zg!_DE8=7Y<Z@ng~$q`lQiK~x52rfB{N%a8pIEC&l5=%YrQFK7PrHHSolv%FGBP+R^ znQC%T!x_Y?&`k!w2AEqSRKKrq7;I_S{moe4a@=l8>Am$Qw3u@tQ{7&7Bm9op=Bme_ z1u}kxLWE7m67^@I8=O)4%w`&=j%EzCT<O;(bMc+ttCDsUQFT8YG3&qsPT3Jr^q2a^ zH*z;e*3wLKmRRe2^f(IG1d9<&nF8yR=x><0tPA07eA%0iilj7ltE8yn5>7EgZVx5F zb3v6^oeovE{%+s!5Y=lc@Ou8twM>b>Bv|-upCYB+9m)FRmWZrU1rjKE9xI^{?^xkg z$Lbg$Va6IoA=xnQ<GC>M54-3JJWYXzS7Z-B>7INgs{+8Mob?Ne`j_RKv~35ZJ<gqZ z|L`OFrxdYV_il)i?>(MZ@5Tw%F49(Jd{)wz%CD%LeGv5esldiK**A!o6ni76J{g@C z#$<<TlpoBm$+Zq>PHpNr-MafF)l&E#NF4_F)jCqEvq<{~65f|$2J4Gfo^P@!qZATu zIdnDkMwXB5HwE{;RD`A9x1yEv0gIFV^$xkv{^}U-Bi75d_m8Ds5^nkYmdKL-&ocLR zVS(l9a~A(`gshR=^Fz6zr&R*U*d$7I2p=xHDzSg^>f@>tG6-;k`sp?3T0+TC!g3m% z!yrKI?*r5A7RjWIo7bkq9!{Kl_rzN$8Fb%(Vei?kUC}Mk<RNx5lU!pyW7CwQch~IA z63Gnde40Swm3n*cuV$)(Iubm<k<#)-jE08V4~8I(?+-m0c)R;)=@LT3Qc)o6onWik zTZvk<i9i+UJ`s3u%HGoA5+@*E@f`zZ3f-H4yLKDDrAmn-9L;g7s<qiJG=IcEt=T4* z7+-u=9GFJCo~&ak$!LxRbVkcX4%niU-e`^E;fQ{B#I6IF+f~Vr?@6~AXnZeiHOlMJ zp^1XZiA+YIslO10i+wPBRrD2ch~*WYNx@p$ST~;)fX^Cf2CZ@DSUQPAbSb6Xn=CxS zpbBynyWA9l+u8X8CDWA2)u8cO;$ER<lZj;|;uhSc3NJ3kkdBU?Dy#itE~PxhniD>y z6OS2WTglS3!RAWlet{@#&W<|&n5ukXYSn-U;Peb#77f!GmEZbV+nn;vNqPmOxQxor zdy`T8>=fK&^}7FVc)WUE_zXqSV4wYa`>klEBt$5gk3KRyd0k#%(ilx6K^X=weH)fz zc}26nbRmGN6`XF+jS*wFmbT-lm%SowoST9Rh~?NfH4uJpk^qo}xocZQ2&-iUF2=(7 z*IO(|#ah7LnMT9ymsSkOd_to?H;_KcdcI87b`c}F>!M&`%bc!*1OaL~p9N#|Tz)(s zbY~wRsCjph^3q^%{}N(Nk2d;NasV&OWTuIvqwD><bTYor7vliOj>SL|;rq7iisX=D zx7ax8FEJElfaKcs=z-`D0B!V1^-Yf3Hy-n24i424YL1e>Zrp8(yl<8VWX@mI^a=jd zhk;rc=fkZB8KD_d>x-lJ${%v<<K^#55p66FAK#w7Y&o<=(hy-3*mnGCvc9B&z6e%s zzClqe?DjCJ;_JE^)2jG6sgs?P1#mk4gihRqxpW+L2|Wb^X^9gXX}ii_5$@;4(ZsX& z<IR|JjP=eA<`Loi4<{k%D$kIFl=4SCu|sCohSw*~I1ET69S<iTI54@0glSgdB;gln z>^QT`XWz{B7*+KqL6rpl%!?F}8J8^m)eM$q04>9BoO3>%Bw0?jiZkO>a0D0uV>{Ga zt*@l*cy0^1gU}%@&C1_l8G|fIEPzAtr5tR?qwi*|648rHm|C5YxFO?n!KaAK+&@ct zpLGZM0pwb)Ee&$k1I`Yxa4PD9nQh+=#<0<*r7Ejk2sbQCUg7h7k^Up>3RwYwLvCyu zja|16o_w|V5rg5@W1L5pXr|A4k8*cqT9f7K2}0JniV?uJlcOlC#p|5g@C!N{Cfn#w zn|=`za1$k@8?B81FQzuvaidE1LejDnB>PC&3Ut2A6|A|R**`P25?Y}%mGJ>vJY}84 zC8prx@e&}Lo?*7lF=$N`B;SwZ034*98{WUSOKvmyx3u|wiIJbuuMR{%CpjbW&u}K$ zPZ|2xo!<-$mcfe@4;+?6LH$o7L`f!fhRkiLZp2$H1FG@K5vRBYI2pl-H|1haH!^+C zzqtFsSFtDZLW`i}i>eM&=07CnFCGhRAzAsVtUJ>^T}yJ}PQ$6i5kQqBlViFGUJ@sz zQFZGkK!j)-_-`L$x^G3SXZ0{3{R#6k?7|5|@j6G&?{2ft4RxSmU<UUxcSCfO&(miB z682j~n(1sBWn3M9IDSKN5zs;TE^L#WGYKyZ-oY)6ek&b%e%$?<lQ?#T9X4};!J;_6 z0O3}=a@BHpk#Hqu`9BOaVHLy6W=<#AI_48ee;&VknkkubHR0{e5GZRxfeO}u^T26( zaTk7KyvoLD-SV3YA$!PQu$c7z0b%WmhcT<zqb;NKQ&EkqW=rZjdvCR|S&4}8p^QmR z77e4}=@**&#$sMqx5S(0xN;UteVuEwsK)#~#G&hVJd<Z^yjLjq|2+BPo%%y+V;!Fu z#r_Wo`}jhZV^RAYV4qP)ZtfcofoTyOAkQ9kQ7*p#nW85IT8Nf76j68HA<Ih@HT?aK zmjC0}24cX9Y9XZ;eAv$+%@X<j`J6oCrBe98mQf6-=gC$0zm+V;6$v%Q0YO{#j*~Y2 zGr1m=x;aa=tKEbP9>jZIL^4Q^F+hE0Ovl^uc~%JI?yUj2MmAmyN{0jjEV~8M@iLSf zxs;wU3SMUkC3&cD(|X_^o+x9WCGRryzFp}Q{1u<&p=02HQ?4a)uI2|=8Vq08k?A0= zcn%qXO&?j}H?J0?A`J=h&-1Ut$GY3lvBMTKOuP))RUS`>fB~_4c#!gf=+JfgU)QA; zX~Y5EZ3%3vlc_(bVCgdAs=?&c-&1sqS5ab31JeJa60)#_{r|LOYCFV};cN@Vr@kY; z(xV0Q&`_Pq@;su)JczrU7@^MUl>(nMk(X|iO{s#*DUC*~n&-C<SX_ly_rfEuj=Ug2 za`w&+KZdcoKy0bzbAz`c%U&kcDiIL92@Dnw9uH=XSvdD|dM>h<WWwDAL^@WC0?3(H zkBxn8%m`FQdrQ1-;<@BTO2n$xY3`CmY9{gOc3w;)G3r0!e<7v?s66Xq=ApZkvPJW# zMtCJ2?z2RB-ffmjf`r$O+F(_Ru+7%<kTK_1H^Bo{(me$fy-PZT`%HNOKws7|qi2=e zfm(L3k7ziMUi^oc2!7q_GW1Tdec}T#ExH3kGJe=@MevcoM1;f<Z;q>FoAkfVZy|)W z%eOU-8O3&JQ}8Vm%RGQ`-^2Q0Np@g&TM8(>w8OekfS}bnHqwYWj3!ElWaPF#%}VTk z*bg(vD~s2uSv$^*ork>CtxE`aGwCwYw+*-WDm>Dfd;1yWQi>AWZ(Bl@<y7OiYZ>%) zCQ%xz@t_s1O3ZqfYjxVzPY{0u0m#<85)T$y$JZ{5q~WZH-HgBH?EsG_Cwau@;Jg@V zbUc=rdtkB_@OJNyNmK|duPQ@j)efMP=4BGEfLW5d`(9tQ*>5}#Ud@Ko5{>roJB~Wr zA}s$IXa8{?e}EW0(V&8PU{7n|stEjkyYX;UcY~@1L7obFLfu-aJ^-h01n8>DXOEv@ zRist3$V}#kz^-g+Z`~8U)K0dZfj3uo4KV0R7-Zd31ns|OVpE<J&4Q;M*T+{$L{w3G z^UhPJwFr9;^5_~+Dx<OwPOg05syqbfhb=hggoX6vRh<`eef0>O9!;4NJUp+n*lC@D zlMny_0+7>JF@&=|gxLAkSR|T27kyxfzc_`jkw#0f6S;d<Dz2~Mbzp;utrC#oO)ikG zhmLKc0)PT3VR6D$;y{&4uKd^q9gAzgjGbXls`V@DWD|9P?355_Af-+q8t!tDc-3Ld zH4ctko$;{CG5<1(0f3j_bO%mjq5~a?4jV|ybBlxH7ITNnX8o1bO>V%~uR<(@tv$P8 zsSc(O<(=p`Ik0pVhT;aa)MXuKXm97SgMqzgbJ1;j*~xGx637YO|3aYPB0?&r{2h)P zZ=DE<7<bd~mk~Q-Urfp}yzwr*+~U8Hr&-iFbUI_4JoLPLPU@Z|fF>lj5Kz4Hr@0r0 zl4s}g3$irQam4v2MDl2UV%|>&yH*k=&uk&(y_=CprUzx-eG@N9f_o;xQ>t{h4JXTH zJ<+kA1O(nOF)JmD$W}|t`E8TyFn7b%3+ysu!SWs>?+~?RpVQKEz0IPH^WE)PFQJqy zBTJAf8jpc{VQ-ihk3V$vAv}No{)wnL&lo&5WHzqlNm$^A9>{<+`W<+|wRi19l1Sz+ zBGHwCfBf~spv<U2y}^72ktQN?TugM;5gIDL0PdJoqA&`2z@02F5UDLW>De!97O8FL z!fZjZ4e;1Rb>CEC@}~1-+{e;h@YRs)XKSv+)Q=w^m=JmBu`c8J#K)(6!ylLI&>vIb ziN_adX5K;upH>4uy*&f<BO7eg$N>(p?kAtNTtBYQdb<ciL&&n(vlmCA7k6YX;l6Xc zzUu9*gLAtvcMx|;-6Xp{VE*Ur&!xY?x7t4cF?{m*2z*^4+sfn9_UvbdAf-6;SxXXe zUuFpse`Z$Go8IcLfdJINCFXU-IEr^-$R(EbrEJ`XEMnPK7Cb?xn_Y`m`ly?zLuk^Y z@kO@8lHkY~nqU)6sFPNL&bE9?6a683%g##-x{Tyo=Jsxq(DJk2g60}7%ZN#c1}@8G zFUwafD>N-Db}pY8T~?Y~R$gCL`LTQ!x`N_cQI%a$(^^qCUpduqThR<!(TZQu&R)@} zSkY}-(d%5%A6+q+TQOW;Ij7|h2GaR00VCOf_bm(%`Bl?+HniKSd3*tk2v}6CS~aa& zcdpuuuG-G6+O4nJ|5!Z_U31`DbCg|k(pqyiUvqI=a}8Q^i(hlkUh}9}^K4r4>RkJ8 zbnU|2+Qs!X?;mTIpzA(->%Ow<$|?(f=Ia5w{^5+x{%%2bpBhsSX690ZLh9H<N7ut- z1GSceuv6;}yX)A0L0I<SNU>o1zMycoV1T?H6Tcd*5}Yu%s!+d?d_Op;b2Zj&BQ+>E zr7j@#(?)n?@U^)WEnIM-?55SZ%}DzY8}E?d$Pgp*kkgpLkgUk{#QPx@O|Dm)HuCQW z43a~N;y1JQf{L}il$w7jbNf=xJ{%JCB_VsWvf@j1)0djgFV{!E)XsgmvHqp*$CsPX zEi&I$z3kR4t*vrd*cAanG!phyf2%ortEFP=PE**8bCoJU@!fyuD?uT(3b4B~TkR^2 zf_z_<#cWP?w(hH3u0YB`WPA#}FV}W6oe%U$E4+MGh0yx^vch^;5c`+s(CvP{?E%^F zA{CgN%617l9BIEi4E3XHEWW*lYjMGz%WnVLVT$4;l+?Y80$?(oM825q^t;RvOJ}@9 zBi_k;oeA2Ri{E*dy)*wWPrPDB?Oyim{hh^sff4=C(->gqrmbV24B_+KPDOWFa{tba zzuDMCCHhOt^h{(~dp0#<Yw7-0o}kNftPCrysc$DcoVt)9tN6B#s339W&QkW{!rhJj z2~wM4&o0ZK@K04LlM4IWSY-2&1GL(!=zAJ`W{zc-ymPe6dLnz5B9phe{@<>2fE_6_ zD}DE<9Us_2h(dh3t78qc@AfIfK;j!$1a?cw^b9p?JQ6mhvUrUWas?S#+%2)Wzb6HP zwa3GcB3HZ;akpRRGkOY~?!v2Ut}{&djVhc!vpJ_fnhpQP^2Bt%h<M)KhY&_CN$w}{ z_+&NkL@TVHvGO2DzdcZ?P`Ky=yNnI%KaM`l?-wR`$of;TYIRY&E+Fp92WndQY)3|p z|KO22G563nDk%3OsZWKp3A&&CBB?@#0w4(g%7F{voi)_UhmbP={jU7mxRCu4)IFB7 zNFk#qUn*84q3N+Gn9S$AxE7_G<PTy~&`Eo@DC(hF{I0=i9%E9TfOd|JyLdR+$K}JG z<|vmBJ=3m|Kk}BTaYi!U2YXrSP$S!y@v|>~YGm*g-!L+lOh`O;Qe0@TQS@JqD8XH; zcR%h<XApc~PS@CNk^5M}aAB6d|Jfp*ex*3~p|a(o*YU*Q_Nb)h0f8REB9K6(<Xxm@ z2fj<Vcji%!<sBy-NEj&^kT}K}Jv~)q{Pv$_4FP+Zm~bhnKRY9V7`$Mbzp-?wALR$L zPJku#Q?p&fYyDIS;YLaC%xa0qUzPlyo<e|;bT~qBBC0>Grt8D6yT%z)ROcmd5-Q<l z!pD?rL`SFC#?PPX9&8=35*l96bOo}19{*ecu+3dPRW*ro@%V%2y4H;o&RjxFB6icN zenT-kKK*2)g%BgK+x224%Ht>tyZhjU?{n?q$;3q6g=7sqW})`XL?R(P<mCH&_QliM z>R_e5D<yuLaeCD$m=Zz)=}KhBk(<2?=GMt0cOJL1Iaq9x@<}-LJa73o_@t4HrSV_0 zS6>S@|BPSzJIMCueekFIPg749CuHX~{;slBR-FF+{4;M}d^8z|Ti(c@(q0*M|F`iV z42w$Iy!P=+^S`ez|82kfx3lqY_h*{zsQINoX+uw7S9J&<M6L}zACIppi9`NA{Ol4h z53?bhYWStOJQaBV;Pmgc`$hm<6@YRnh3p{*Gnx6-!Z-IMhKXEqPOTyPlB4-T+R@va z`%)B=q(zBR=z;X>GDY`C8pMf<y<s#bKcOnH-B_(&!ol{J?{ZYKF@Z}t>`;EH5j^qa z5CX`(&2TJpY70A3oNM*!ir(2ey6hCHEX=9Y`E^09J?!11h_64C7rUc3ypBelE_6kH z8cpR+u%92aE74$@GyRELJ{`{GSC8C2R;5HwQ84$zf2pm%snL$v&42U}6VJ5pe*)G6 zDg34LZ2C0n)T&pr?p&_iIHmx=jXQX59e{XB%K>=ZdbjM~!iN(tZk#1K%0|r{*NUf4 z!EVi`Q?G9QI(FgbOoe#^Kv(wg;>VLO|1ccxg6pK4&*{xt`u6hY)30CrPdmHzS8f9a zz|MXF3OFEvbcq8%EWVuc4FJj&7*aXGJvbqS6<SD?e;0}bjyMNWQHF*giZ~*P8NE}Y zNYkLWB8x4e=#7LfTC|OfHQIP1jydYMBac1$NS<t%%t6VIMH+b|l9y>?P(1^2f=L)j zN;xH!RdVIvKw}KV)RLH3LZp@dVTw5>nK|)>&^hwNV+=;ckOIJxWy(1xoplmK4L7p& zGmtUBJk!iWwAeW)p@se^T`g7&6c0NzhSSY~0IVaSH0+4hP&4^pV<@McdfMVl4N}G+ z0NyyLpF-!H16ysMy80@t?ST_3t+m>EE3Ucfx+|}}`uZ!d!3sMpv2#XREV9WeyB3WF z<v~z2%St;fwOR2|Ew<Te3)CxiwX^58;fgyhNT4BfX&R@HyDq!!Ml?+=0H{I8CYNd< zi#qY3>Mp<iiW{7Y2Hi4HKiT+uFv8W&`i+EI5|oTQ`zAaw#l#+X=|Q1ZyfMeUmNTol z1L>1YKi{0$G0G{^>W#$zD!cr$tr`y`6U;T+d^65D>ug*&+=#U^&_N45G|@%7^|R4Q zE4?(+O*{QG)KN=4HPuyHeKpouYrQqsU3>jC*kOx3HrZvHeKy)@tGzbcZM*$8+;Pi2 zH{EsHeK+2D>%BMMef#}4;DHN1IN^mGemLTZE5116jXVB0<dI80IpvjGemUluYrZ+> zoqPT{=%I@~I_agGemd%@tG+txt-Jm@?6J!}JMFdGemm~D>%Kehz5D(<@WBf|Jn_XF ze?0QZE5AJR%{%`*^wCQ{J@wUFe?9iuYrj4B-FyE%_~DB`KKbRFe?I!@tG_<`?YsXz z{PD~GsweZ?e?R_m`Rl(w|NZ;_KL7(LzyT7lfCfAu0u!jf1v0RK4tyX4BPhWMQm}#+ zydVZMsKE_#u!A1_AP7S!!V!|NgeE*83R9@U6|%5}E_@*jV<^KJ(y)d$yde&AsKXud zu!lbUArONo#32%~h(-ilhs2SMfB*m?`2+=I0000if&g~_4*(PZ00?UU0SE-(XrRG^ z1qmKpI1teyh71KkO!#UY#DzNsKD@|7V7rST8TL46C*i@42ID~t0&&qsfhZZiqy|x< zK~e(4g&e3zU>5*>03b3L$zTMHNC%o3Ww7VLMJAIjOa#D=9j6cxX?5vRU_bynQR0i2 literal 0 HcmV?d00001 diff --git a/images/demo_online_gmm01.gif b/images/demo_online_gmm01.gif new file mode 100644 index 0000000000000000000000000000000000000000..b43207a93ef5b44f5d37661cb9cd2c4145dc8091 GIT binary patch literal 83631 zcmZ6ybyU<{`0o9kVul_-x(1{}It3i0Q4ncCQc3A9VHjYBl%Wv?=?3YN77!2#r9l`P zL=^EM44C8ZUFTivoU_-p*N#7T+-tAv-X9%3ZAB#q3|Ihs4oCqc01AOoOFX2ZqNPVN z&~r;OGqSJ<qFI^Q*jU)uI7Qf5IoR3$iIZK`m4l6ggN>7elbe&Bi<6z3lY@&>T!)K| zjhmg7o1Fv2#)jhJL2+G2Ng44->heh4;gPz>BW=JVZNwvUk4Nqvue1TLv=Q&avg@+< zu3MM$@$&P@+~t!s;<KsZ*Y*)$VG-aH6wvh()bkM%5E0V#6P7{?>j#L)-xX0d6}b~A zdN)|?Zh)9!n3#30xW3N~F^L;DO=P5G<z$uQ&7&2ytrf#2l%kfEb?lYzc`9SqZz`$W z#ID_p-Bh(nM60Q5YwGBmx#`C*-O)3?t8Zv<$Hc%U_#S@B$Rpj{)YAIFL+gi+t)Il& zKD4uS3%3i(dgSof>5-H3V`mp1j9WyG#}gmlz^DLKbfAAwc*#m6E(04B8WSBCYiXSn zpO~DOl9Kc+rD81gSsEcNlklo2&CMgdaWSK)H76_QdH$>C6QqLtS49OyMa}PvYkNwI z%PQWVRF+j#Hgs1uk5sl!RQ4=XSJu@0Q^)(->bly-&bpfVx`x)e=7GB5o%-;o`r^`m z<Hq{N=I-~clCo_+{_U+D?H>+1-p+N5tad(f>55P8?&|4HA@rtY_ICI6<-Z!}?H}kJ zd>e-!%E%rX7#hyZ8JSug&3ZoC(KR|UHkSKhZ0&G-?88I~VPax>;=`v&e9~lE*7Vx? zr&q<Fre|kA&dm)B&TVWh&Mz&kZ>%hSURhdQUH<%eb)6U$Lu_a!t`Rq4@f+z`8ynl( za|_#h2RokLJI(DoTf6%jy8G>22U|N|_P%^wUHgVl`u=J5`?nv*arongmLGj@Pk#OW znf&a(lhd>R&d>Mu&;L6+|JOM^zc~AK@#pf_@87>JuYO<r{`2eapUbPizyAFFefdw9 zzppO;r(9jdC0up(T+Pg0ZS7ti9bf&uy827{A6;INoLots-Xt$Sl5YShFq9O5A(d2+ zhDS*YE2PtN(yu?H-&dr+S0vJ35{bk^qBPVpHPKKv(vrR*2>}5B!1D_Vd;G5z`&WVg zxh4RD1bn{S%F?CI7Dh0LJREH(dW%P1*MF(oSUjA>BICX~+IU@4%$?@wx5Xr9chIqM z^~15IviCWXkH%l>HJ5*Qq3Hi*b*#B!>J|FQl|~>eo|cuu*u!$XrRr0KQHg%Oerxqy zjb*d@=keB>h1d2ay~lLh6xC5jMr1bc+v--@eYVE)MRO`suQ3RqrztlEAP5YElIw0q z!^Ycq22tCIj>fHbgzI+-?shiW^@k|{&zllU-%J&1BykyZwH$n^G^w%u(A9dl(D3Me zfx(+L&v}ao4_AW1>)7@F7)ox#?v5W@qZy)hlii&^_ohqkyfVDJfKa3Bw@+T4wVi(_ zzD*)=-|OuT{h=rS@Y|pEra$M$Tkl`p>+5|wczEd^`Jea0H$MR~AtDCK<Vy5F%O0~w z9(~>;#vrwYHeydyQ3Fu5%INthc+ma^9)%Nfbd#2CD6khauG~x%YuhglXEHn<WSZ(X z`53RbTe<a2rLAoxjKLLEN_LIPZ97d@psF;DzI%T=!$><}6T;wu8V=fxn72uN7<90c z1M)&H!kDi~YEsMfOTNwXXgk<_;WL=9i-cJcqBBEwt16yG>J<)T6+{c~7sfJu$;-v0 zJ;2c2{EC6lC~1lulxCW{AC#u<HbC-&z8xG?6e`c}y;}L~x?fdUP9ac?6mr+3kt33j zhb1k}c^Y*cyVW(d1i!F>%px+;+KLjedv*1wK#d3f3%}KFP5W(;DjH>##NDz*WBn&I z+Oxl&*bCE$e(Mlpvi{PvUtaSq<U`wUvD%q&WeqB2&1KiN3vKqQ*Zt{--}~tD*!R1j z%pS+?M_pZz+SI{@801Z(8V$aj{b@+=>3ofN>5H%xiGCEG<5mAVE{~HjGQq!I)H7Ce zdcrZTjSwow$|en3*7wyv>Yg;!elMBTUao_!gPH0_bp=1Oj0q_m1$2o>hzL_zeVu_Z zI(}``pfol08yaq+0Qt72B_36_$f$5=)G8fQdd29!6K{98d&~3uGftcOi0U>K=_8Cv ze71jR!b*}?la|uLbBx#gKa?UWdx$Cq8D1!*%V*xODmBABb=0|+lcp@WR+=+evX<9| z8sfKVA?{NtwG<BX-=2Q+78MwOAAVhVs3C@>i?;YJU3KP1EoN_y`)_G9m_MxTO;2%l zHI`d=_rzE3A>V$f>*ESvP`J*OBvO(&IJ#g?Wt=Ed{hyB}zhlcZgdyJh+uxa)J<|98 z_H4hCNRW>!gN{DXJ`fE&CWG@RY#PFod7J9)^zAJQA>8%&fhXTfZZC7ROQiM~M4_Op zByD&<ectiSrT3t@+7YN!w>qNfrxi6)0U?C|h3Y7RuXjz~eobCPUze0QMao;~M6%tt zye_sxo-;bM@R-(E)rWPWr4Uk2z3JTZ3Hw{pMM^k(kpA0>2GX}MW~cLmtIy41wp&?4 z0$o2+5KmHTOj(3E6sa5+5>2PQ_~m)}0b|9GMVe>!5^Y)cUAZ*3*qFyg`r-`}e3BpY z!A2!{CXF21tXLq{#5c;t<b;)R(9*Iw2EHnhl6-e3V_9g-T;Eug+7$y6vlqy|oH73a zb`tWI6TKUqp2PXLA9jVkWyaR5#f0s@ZZkHapzVn`AJ66D*Z$y^;FmYMS|W5fC)CdP zGne?%NIGX}!mr@?xg<uNYJSX6w)0c|*W|tBHS&9*gN0--n=rg@$4FC*DH&nARQsgm zQ-Dko1xE0HOlKOO=3yi+q8g<Y`J*@U=WlZq_(SEvvf0ctt{=sGvz5B}Bli(vqa{Kx zn~YJVkJ<8dr37+ACqt230iKa^!(w6k0C(<}&)!#rgN6BQ^i2Z?GAr<D{a_>k(+{*t zky`?WFJ?`L#4u9#vhJC}o9A+scdO~fzc@BonaS5*E7USL?6Rkbu1PeLB-f3mGHyUM zsA+>Gke^Hs5?QFb%_M`$QlXi~pSrK+B)xjvGX4fwUhthsMZ=QGE|ztjip}bB&F1f4 z>a!4YO~KcEz&zST@E-aEaMWq7F+Un%;DN5Dmqa6130Np;QC5*WB$_MT9w?>QZ816Z zGzhG=%4jo(7|Xfw$VRWO(C3s#76a~o5;1)H8?d(1uP)5&tKWWSD)xUqaKRt0QX|M) zuc7-ro*X{>p5ERl>9_49bH~oq*A(pgxeg>moP|oBDm29nF=7c&Y81L%odp1=f3aK1 zn+2@Vu%M{xW~jTZ0~b$0LU|4AuweQ2Fx_KpREz@|DY%0FnP;pW1^`}n3=4?+CX-%l zAZh!7c=diD9iU(`0p99gdV`yi?AY4PMzpy6QnaX8szj6|(PX|@-)<|^G4rstEs%cs z-W1W;)N4O!9mD5Cyzg@{jvTF{67ax?PJl_2YQSADosBp?zUVj7DTkEC4fYf)DDph} zAC4J7?9i9aHuyXg&u_m&+lQG9DtD(iTQzMm%$xG-4KTT+a#i<No|ZJ136kmAgH3f# z>IqG_A9cswYX|{JSo)hNH0;4j3)`&bW$j%J-1<2}J_Lx%R7X7`T8HO?8w-xBu6r8a zX17{E5(7P-=6j4=nf9_!H@8{H?P|VK8Zq3D5%^7nLR|s+IoILq7z|)NRm@n4g8Fr? z?m*+2uEi0soz&B@hKS`-0t?J9>TB$6qBR9sh`L}N8Y8?I-6LnvPv$I@bbpi`1Z(eL z;NbXy<&GFFo(loX+5>_ZwwAx7vtTgdhL>N=OC)!W;;{JIYM$du`jWy6GRZYRL0t@e z<vxT7@gv?Zyc@Z*229HNA_QHR$fF9OLi$OVgefp%R3Vz;H$YZ=69h&8x4A}+0uZHz zj21cP;}A8U@YHOio?Y0d*A#(Ohef*)gF(9OAI>>HFRc6-_NG9kk%^T?(+j)$i?$)5 z)R;@yt3`10BXP)sib7;^-{4ywf}i?3Cd!ij`a0Ty5V1vvraax-3|Epc7M+K0)9(%L zv-ZVlpgD$xQBRR~Uq@5#M^eV=g7*F#xkbX2t79a(*@R}oC%#{8kf*9NUoQw30|qEx z=?-*ekr3R;j+7RKLnOv}9|S8Bdxl>`Qy6W;p=NFW1WQ7gUi$1o?%18NPY(-~7KW;M z1C+M*WQ2Yf0&_TkgVEz6CN09hyo>y1f!Jk?`kCWSd*bvoI9mB6m|_n~hUW9tqO2<< zuOV7N`yc6{0f8)6!9_1NA9yA}o=1Qq3w;bE0X8Be(#%ir+-)(-n$jgk4S14gPnIbO zQ=ESwq6=JU#emQe^*LBsL~KKwkHNk-<#ed{u8V<BL>n0vT|qv27Ng*5FF^>Sz{TF} zh+E!^t3i`X7m}+3&`JQRUP!K1=xP@7q{<>r!X7XN$O->W62ZZ_BeoC&i&+d|IY;DA zQ?!uK80STosGtb7MQCU)ID8TM3I&No#A6k0LtP#$;i5}fc-dTWWcGkl8w@=SHAedx z*gO9@4asl73TTBs39`Q>1X5(N7O;r0UW~b~3sOUY7%C_$F+M6<&IF5?I~Or}ME856 z$+vWqWpv|)g5w5q<3<FNOYEQ4UjT38W4b!9Xsr}EglqfRQ#283c#I2@rwGy}4|Yws zEXNy40)}XEF&v;K2@6HRG??P<<c9SOn@Subd~mR<Y@b$LK(Rb7lO=8@KK1uL4q*?F za^WWZzD1+PWi07j#nA-qs0MSyyaLRZ0ESLOD;r!NXNOx)LxZ!O5k46jq@d8U_Rzmf zVXG`j#ex}A3J)qJqn=Ku?Xg&t>SQ$UMYipwVJpJB+d&EF@BxJgwFEzO6-H~rr^g~| z>Ya<UUIur0hB^^e*>Fv$lhua^d1dcXWAE~c2#LZ(eo>(KwGXY&27<Do&c{B8!i?%* z`$AMaS1vdKaIu!8czFRfb94DP?5&E6z++&BN)JM+Qa>){IQzguEVys;rx%ZjJ!%8= z6)5tK$xZj5cu9%`6k+ZZ-W}+4W{xPGdpNieR45sI;AHca(Rx142I}JTE8B->-pBXY zO7FREFy6O~JeVuNQAd!_MV|k%9NzcKWwF!mY(DRGCqU`r?N8Ei<_QiSo3pE}A}>Lc z-^}sVY7g|)MFcFug^9jC!S-*=u#3W=Fn}We7;dLi&{hSHDYN?<XJ<%2<YOqlE}8Ef zge)sLu)zI&TwV(9zxb;}L1HbWq0cM%RRoIF?>+-dpxnyZOkTn)a)Ma!yAA?b#X{A^ zWkF`Qv3Bej=U87?fy5`-LB(!lo)W)pp23}Rb{)jsjc;|iIF`ADYPsj`S|slX>M46B zpB7`J-1w9oO++4`hf8byTn*()4XxZ>@|VSE6^r3YnF7sA5XD~OH!4e=6ce1dep!0W z*$Xh`N6+zvi#+lwGgXMI;0toZr9Ezsd+cdulCW$SOLDJFwle1)F}2^Rv^T4g$+k)A zs(eV66_Qt#>TaPYU|Z;38NtS4-&%F-#Ol!%?7dvwK43n$VLAk}yvhHtHSAfw9LsW9 zdAC*Nv{OyHzHL`t&7erl9->y7vDQ7zdVIX*D6n>7`N5kmn?$SH$*`KL>gwXr>iXrn zrUCPGx(C8?^+uaTYhm>*p!zhP`t9ZV(UxkBxcZZ7wlB)H2?O<;>2=lRvcD-*ca>iQ z>^ez5EEks_i%HjQEY~z9vJk8)e@N9K-qcsO)%07{oYOV_Xs!Ff*6`2QIQ?yn=C7D} zz;f}0>*DlrCaA<<#FY9Di&d~?l(LDnc4bCUlME@_2@>9jHs=XzZ{%EQY)G^gZm`~E zVqrrU=i*!je%GwS8uhZC^vtt#R$1#AwWKpXX|J$pY_+Ayu1#mOr4+SQBJ=c>v&h1k z-L8Qf*thD170<}oeE8k=`P6nUj3wHw?WaTZtvBt31LnMUQuGS#^#k+rj`OnQAJep% z8k9Yb8TZwicQVR0Wf1YJ`rUrU+#&9qr?^0FkYf}7#Ka;lrku?QA<$teS5ZE0Z!Br$ zZ;{Wwz>>`#Cypz`Pm{k)@+qq+D}D0l`fjBHWtDhRL0#yp%S4v2_wC{D%|DhqQ80%e zoPudWU||@a27xCt=1<z^P1~4SqZ3+8%qo3Jt=ZodnsANXUHjc|9EII6CL*X*fDw;v z>~<sTA?q+5GcS&gE}?4&1sPqlJVty8j?^;>m+&b_XzW&t?-f2qK<1&{Ibec$#wf0R zaKxk7+4}5_vxHH5mxynW{d3ZLm*G1Ks!81fUun+EI@uBf%oO~ibA2j9U<nPN4S6qv zLJ;~Ku3-_tuT#X%TyVc4?^%v@sH8(zb&>%9GR(CSStS?q2rM}slt7cKBLQ`yyDAmM z^nsuUyg)HI&wtOW&ffQkbtqV&PwQ?k5)DE(fYi{DI-;rOwSIRa@(dq(2@?l*vI(7_ zG$yj)s0M#@A^b7C0JB=43iop+sSHUFMjmK^)Q<s(B#dA`^xd~xkfVWZA47#0umzy~ z6_I&HUL$)DJb}!bK$b{+N)(LLaET0B!k*|vnVy259(%vmA-A1|+xDk6i*}~A^%i{{ zE2N4R1}I*2!(tn**^@^IH<%U*hE0o3#7*NHTwKbZ!<!#wz|Y{)$FXu{X_E1<=+H<P zy?5Tj$t3`pVQ9`+1mbB&>LxQ3=Zf)#Vcd=pPy|Jz%ad4_kgvk;EzubUe)jEDlZJsA zCPcsMcL&*Cj75Ye>Jjkl82ouIIKMx->?=h*n%wgOheqK8D#_7k^0P%k6id9&BHuL> z<ad&zN%#96F;{-l`{d_~<i!ympIG`zh(Q)z<1&Pj1wP;<J)V&hK4Lpi-MK8$o#9da zj(-#>T;JKs)nTuB&RmU{I;oRq_D4I#cOu5)O>AbN{iebIHV;El9|!36d=%h^I4akY zH%xOrZ|A3)xfPxmnh=tk`)moHkQ)w*B|`H16Tcx+^-!sLXmWI+>&@)BD+B@ji(UNk zqfv*C{>wSDYWIY;g|Phv{edY$!cas=T%RJL<Sy`MG51z(XBsEL=I|rF2&9eznNQ@3 z!l98>Q=%@-<Tkj1&kJRo|K1>gH&s8&QL=9tL9L%K|2O9BPfFcI;#F(f?>5U}%Sx7D zICjyRkpzAnlE3h|+#!^lqJ3oSpgr<Xw8xMbZnKnKNPwzOQ~2rS?4M7({N*zdKCLI5 zG5i-S9%{4wJ~^%`b+;$-$Ra$0aUEG@>ijFRyeFsAj2O0rmu7XNFAR$eg?~x2zLzpB z|9iktIQxYI9L!n-G0Y8BqSzCkIH&+|uR@(b<X_q|^%_<aS;NTjp|Y$NvC~;&zkpw# zHzbZXE)B??3pc0@6o{N_9N~7q0*e;)KzGiEUW6lN$MWhApvUCU6ISR`^jorpfZh35 z?A0huk1_ciUmtu{$K9vDo<slB+o?<l80l;?`qCv@k>4TTV!ReZTMY^;ECRkfPO05B zB((y@_C7upPHJcb0R^KhjC=4P+gEMJ?CPyye|$axVQBH9J;As2ec@}^mk(7tuOIBj zeuKJ3?xX4lgU+8XQ=}W-c<o_Ut`XLvCgR!r<cWW){mUH-t&iqiI15*bYF`@`yt6d| z9ofF{pd+%?>q+x_u5y&9nQ&JRzx!9U@v`3K9@9h*y_K)`gw4&Y`2Ln1=8^?jc71Co zFZB#BiTKiEqU`9}^(}p;DyHa=FR$Ie_VDMI_Nws54{#YBfsWaEm8I?(+RhDnPL=d< z_=2ZdRgLM*I}JJGwb4!%V{;vT&d1Mun`~Y<7rX)a7A9Z&ejJtLlp<28M^>Hho{>vR zthSSTOt>jcqB-8Ds4+BaP<vfFvurz(Sfi&^C(sHSc=Gzaej~%3|8B}v1st|I)>s-G zn!YY$S$|_=@aN&0T)S^l1D>(%_{VGI?{(aV67IFU{GvR$6#Rvvt%SIrv^HlqZ{0^V zZ=W=tIh^tu(w=`;J`eCdJBkLe*z;tH+r+=RNPG=qL4#6A7tc~J==y;)+FvQJFFrc` zN=yCq-0oMw>tBRd7lou>rMG^U_x*bL>UVYD?*v+_+Ns|xqO2j`?*(&Sd|tlMTnfk@ zgSY{3FX;~#^6%iSzbMJSgZIFr_rSb9;6BnHJ^(z%eL1!McT(bV^xoy-tIOW0KTD)r zm&>F}BJE|L9eCUBYWwx&uJ_gctE=trmmj9C_Fi3zOoP~n%t7DJ-(ttwNJSmqAfN~{ z63-w)#if#F<S@v{YrYzS_<<W@WMsA-%Dum({fzQXX2atB?a^o426?j~Cy({BxF58c zs`K8CfzzT^hn}14O}?NHxq`Bp?i&@z@wgJw5ABqK4f56E*v!6|R-4t?4(FL2n%CR( zM8eq3zgjj~DlEqOY+(E8d35Xd?Thv4__V$*+wf}kQ!ome+pDm2cxw+Jbl4uUq?c?m z+_<dwc_}HaH=ZT#Qd>Fr_HGIKDgEbPtpB-wM5pkYjkkPtpRcp&!*N=lc`Uk+ylor$ z=Z{7i8MkkMxHuFudPG?4>L*xy2L`A}&;D9UZU477T4(oN_qIQjJU>bRgHjK0{h>Cj z0oYkxh9N34Zj^D_T}AvpJzA%Ia`VWF&2#;CJvf1%V00S|O4vG7{HhHefFQNe6A(Cq zbfr42JevcQT$S(*O0I{fQb#iJHEJHoAJT{y2<Z-}Aea#1AShCosKWH_k;J>g)jQO; zxTB!bx;*$&{adX8f4;YaC^>w{H~)DeL&>*^C|+9K{u3Ox7Z4pwuQq)`CME}VDCSnV zKun0gDfKI6*Z0xYR}#IM_9kzfa!Lh?^|>C$7Op&10W}WUh`WZw^pgO!%fGcMKf#RD z_c-G=>C|{7hGk6*6h4pZUj5yoMiUXT(|Vx7TCd3@5#H!TEu*Ea1O{}7Bi$Wj(O?Ws z0s3(kx&WXnF%Q3Fgj!LnJEaNAmV%LXuR4s(+?1+ihGDLmsAx8ROEegDJj=A=kuOx5 zVMyWY812<JENso@(A}o(IhFBaO3$E~T<(t2PP<(csqWq_O1~1G*w5P4K%9uS(@DQc z%AG)~K6FD7jd(I~5XtU=;7jHiL_FSlc8g{k=gL^Dh!n>Wc?sN#yMqYv+q)r71n+&c zV?MKT8uprkWI*&a8fuAn?^}>%BLp&JBTW?R3Z}d%Z;2w22f;q0am=z9VE<aIS^$W` zmM}0CZtzpjZVqsM<JrFc?OI(lOggtImf5yxR*+}yIS-wwq+=YUGJXihE*3h76TA`1 z>dRQru#KlFhit&#@sI{i1cOpm$%d3}$&B|J%qD{=xTZ1bW>@{2sX8wu(GXqjCE_r( z5UUnL!1JJGIGE}pD0-=iD+g(yUBm~|H*&})EJROfWT?GF1Miww?)>R#-Pr97|4w4e zC3fj`y>RH^X0lnP7db9`AR=<XlP-CIxSl?-Q?VXN^Gb9e=3?*l`sE-H4_rw^xv=F= zhG|Dby8%Y)4lsYcPn>4yKOco<m~wUpEdg~PQN}4|G6<<B2tz?CWc`Cej|o5#rz55M z@t{zIBn3jBfMs6<n7Ro#9ggv^^Dy*T*ng_LOf&Il3hvJ|0_i6^b$a1<UcLP7h&-P` z!${W)FB@3UGzn<wtPDG*)@vh@RGUtZXYIiJZT)2KU<4WsLt>}NS&@b0nbY>{8Ayyk zz$Q$V;x<$`?FNKTok7&YUNEm;NB;stubp%qsg{NnP$_1p%Y~KH=VYL`w8C|uPC{A_ z*gF%v6FA*?s|w<K;}2?|29Dl_DHHqNKNuv-3xBvR@a~qC8c)viKdYOVPNj*Xdnwgc zs86zKv3$wc=XoI@kmd#0vj@#!NFoSu@gSiPWIx<eQB(E>@WEXqJq=x`$$-UBILkL7 zEicNsYufc*1{iym47sSCvbMjNsI#xw))irQ7BNlnf?Z33vOPPFy<SNq!^S^nl68h? zJQSl!>Hz({@F}M^@}OgW@qCn*O`6Sg7NM}RBej<~!K^4lUSnTQag;j%ll8e~z=B~= zP6Jaff+)XqgZYN4ZZnk^BCP=|v+@SSNV1u6;%_YN+5v>>>IXifX;1LH)2!Z4E`ikY zVsN5;9D8<jCtE{{&wK#R9#Lps({Bb3Iu${y3|QVGLMEku&UcM$*To<2Z0%EsW$7oS z2=B+tAb8%XSxS<JT`ZFd|06)bDrZK<ikgCI|I97ELPA)f03;tEH=QnKl%9@p+^NJ< zEAli~7D9jQhi25$G}g2aAJO$GtHlaWpdoRNqSV#|#>ZZ~JS^()K|Tw{fc_3k-e@}( zKdii)TaMGRG2GN=K4GX-DULrM9)SbRCb&S<R)BWCLXb)sGx%C1XV|E@{Bgh?$Th^h z_T=nA=G^)x<)6?7<fqtW8^)U3s}^32-S+LQW0@oe&|0j_%brDmkHu~5u}b<zW&{z! z0W{vx48ZOe^uOgcBG=}Nb<B7f!ZX5lA9v?C{hEvBh^%cwicB~7`Q1VR$*>s%Og96| zuhP+P^f?4yQWJ*S@`z&Nr63{c;cK3$Hq~DrMPgdJoeY&M6TA;FgZqBWUE5lKyrMd8 zw$?eNHuQsMkUx&dv8VK=bJBZK_vOw@7uEIWA0o<sR&#vZx_LS@jn@t+<qLErM*)Z^ z7FgHUIU%%oSX<UISB_lI0e5KUEt%bv06yL{x>c0Mph0{AIoS1PGusr){nl6KREKJB zeowW~$ktoe9m@Sw1gn{+W%)|WYn16M77oZ(Wc7T-6u}h0KO~dOR6QTL;h|iLjd=A5 z5M4ZKW&H|hO@V!LO?t7qA+OLmOpWz_{pRxlS^Jwg>hIp~Z?0{gO~3B(|N3I~egEHi zy{6}?J|t|P_AR6<8Z!P!8K<ziL5mL=;#c!cv{>C_eit$#*X#StnvHm*JoOIGdyLIl z-L_Zi7&Ytl%WhxYkr1RFyQk)#XU)GO`7U%au-CsJReM(s9ya|s%}>X7bzes(>|<7M zK>3~3EmgZ;Q*mm68HW`D)7s}<t-XQu!JiN9n1k=iw-ouhaDH{s316POadcFQ_;O#z zr@Tt-Jlgsaqzm?5(?O=;GxNSzPX3XqY5m^*^GzFhdH80QXK*)stuUf78i;LxN`Hcp zYf7rafbSQ*)Lh~`g4FwgykV8xw%-zUda_y9xiNlg%Ef=;DR`%1$wfhmX7<s$Hng@= z=cG5|g~EQW*oPrsLqE1v>8Qn6&{lu87SvdvF;^eG0xjLKRn%{|r1yFKD;GmlQu#(d z)z$KAH>vcT9(CNO@pkQ{X5wX>!qbzTKH^S$@82b*XvDZI9sNzyJJurcG(NyGgyw6r zD&L|SDLf<g7*Hru<MPiqe$)4!MTH8HdV4w+c#=tY%kaY$rRs`Z93!Vj|I0H#-2JW< zB=!AzG*DmNN8X)$7Rsm&WV6RZEr7VzCJ@p!+xR#}28sO2juaYI6+uHyFR~tlV$qf` z^k~+Z(x9EX6iaDF+ZzVRBG|N{I+7tLWGp)`Ec#xd7zCjNWx?<Pu$mKv(?1;~Mvno7 zi3;Y@+v$b5%JI*WrCu7xv*OZwv>L#oiVzhHmUmPQstIB<dY<|Kn)ZW*K*#z*`1#A{ zZ_|!dD1`W2^C}u=*p83cib6q<kZ8k2urq~{^D;Q}BhXY-p6{=r7@%deEdJ+(W&w!q zdP6j16s*w!V(*B}l>)=vz;_lw0*a7Z7_bl$NyLB|jyW6?IUZWQw7&h4UZ`9sZ<wNG z$oKbk3Ljb3>DXJY*je>BwSMp(`MU?XarZH?0eYAjHdw%25b?*z!E?cv8C@1b@4h7r zKbW97B8Z9*AtL(#I~ryo6sH^V>S6|~UI=+K(F>{qJ7;oh387?_OGqFJ)c5OsdbOI6 zX>F)|A@w4bQ#qEkx=7TOlY1X30f2o5d6=<0q52?BX^8GLU+$ZC5wl}$OFEIO@%zQR zf||)ZA=r#!)?W^~cq$q`OKtWBU5LnaP%-x%N!BOZx}rlE4?e*e{n$J1FrBax#k}hQ zR;6mv*Ze<fLwvyhCapTga^8>SXTFa-(0et3!0!Vhm@-Hu(8q$M5CX0@@J}s)c!act zLUc7eM(j4V?65DbyJ7_kM@E%c-&|v=oz-`z&(pyOin;RX$5#dU@x9c?=IevBlr;== zqp67#-n@eHDs3Gv-!DyMcC}0-p@rg<vDZToNlIXy77*zcR1;qdRyPIniU}uKX(pbq zB!p>}%+{p5)bRLkluD#p15+U$Uu~$1MOnt7gg&r3j?oSlX@>AfpyTH5#(w39YY$Lb zD*bSAjee!u0Eez@5rMUdM2jJyru~d;qjxlq2V^=_)y2TPwLowBT^h^Vq-(lDnz!xJ zCu=m*;G^TWl?R~6x`n}#Sul2(0;@&<tscZ`?$-u=)!$wMpg!38SaIqW9kH8gze?}( z7ES$*pi+2_7zHvCjxoE%(I5^+uu}g~Qat+wKz{!Qx0$g5D+5PQ{2FEIxkf6ehV#ry z;s-IWRO*F@c;*FLri7Cgt5!Fg+$TfPGKrXvq&P(>n%pu|e*)Zr288M-|J1wM45C3O z^hrLWrHt;AjBo3Z+{fN<=b5Gd6tAH*n`~sNp=w%7mAY|AF2b%R98MSYVm5e;L4Qu^ zLgmxFGU{kOAese)NtCmG(VC=aX8T6YtWFL)O2ycq#?R6$m8AP2gXZ?pJ8dUZEgMs- zZ8L`-bDF1SF}WDgCpj~RXzlk5Gj|5`V+=4qO^wRTV=`XAg@AeMPlx+&ILqP{qNz-O z&e@s8`|{7*r+jocG7Av5_>c?OU+<OY`}C=1K8(LCuK~E4{?xj)5P51rk7;aNLDG-P zN69V5sNVcQWE)IcxbwmyJZ^ERGJi4zAmNfQNyCfrZx>TifRvrZq|?Pz>Ics_mr~^N zYi9wfX$-m111i_0OwX>|tOvMeS)Au$^Yi)mxutqt&`W!OtYfK=ak+?b*>D*nwz5>p zNy%!Y_?UmWB5t|z=@cp~T0Dd-q|l;l&Z-W;mbX5rf~_<#uACx@$&W#D7<`b?O3>nR z+fE`Ms^B%}N@v+h*HHp|5kQ5+MzO$yjjY>Y4{JNXs1OUC(1o{Jt3zh1!%nLsfvfN0 z{(W~^9V=TMZ(V&qygD(r`r+wn34j${j4QKW>F57kZ5j8^kZMNAzj69JpR$}cx*}=` z3t_?covzG?e_jp5M_I;I`~Z<Sz-vUtwGIBYO}Vu#t+j2lwH>Fm-N3cIxV8PPwS%&? z?WZ7a1XkD*cF|z-&(jTN!AB9}bc|xea<M|W*q<rbQ>XQ_!1eRE^^2_aUuEmRTi5># zum7D}zuZ~BI$bBhh^GeY!lPh0BdD!z!?#P@k8yDS3p_j$XT1osDI`*~5h+KARP#jY zT_VjHk(O)&$+STyut6`s!JxfyZJy{9LVS9k2%G%u%YyfF-C%3mU?17wnBU;s-QYUg z;3nHdF>Ue)Z1T!)Ue|U+jV#y3ZG0EU`{iy3W^W3YZ;G^SijHiG&2NhDZr(WClpx!Z zWZIGv*piliB<8hAk~QCwbKa5<+ET!6DQ0gem2WAxZQUH%QkmaU-Q7|<+qy-zjb_?b z7udcnzpbIYt!cik<-DyOw5@~N*3I75E8o^{+rBfheRqD_V0YVao+88tFQe8OiQ0*b zr&uu~GM{bhnmZYruNZ%WhhX5w**h)yn?_f-hx0o&WO#4gO*k3ecFoBq($Vr8K1kB} zk@=4JO}szmpLXoCoqdpSUn0&~4KL_LVeFOYWa}h{+cB4S3MM)SBX)f&caQlUJ&7;} zMVuYR#o+=L%7hDR+Y2vnaUjAxSvK9z_Iwqc%a3>KjjbPeQFsCHKqg1u3o_qDyb;&F z_mwTl@)<?B5ZujtpQC;+f{DxtfZg1Os3H&2=3`VO-NGB-VY%=y`-AMDgPd}Fn5$c+ zyj!|}+f5djQ{kSSB98M4XFu<Z<+3rp0k^B)2(EXr-H%aWaVu|w7+K;%3-;LScUy~G z6KsjDG`k$y?x9}psy?xy1h=eb2jTl)!rS(q8g6>J?xobbIQ7FGj^bUBPqORrVZf7$ zNw=rFF6>us0#{rs;!eIH_8vw!T|$g=Az3K$FwCCJxxpnw02fX;7zu)^_PgcRJNO9U z{YKpTpYHg2;eGdU?9O{m7tosoh*BY$Yc75y@@tAYS%}c)tAgE?5zke5cOG*xl5_lF zgf3ZVAv|v~Mh&y)S?PcY+L=jl#R$6wUd5@Q4_uAl*82_*>K&qxWS!4&xnzgd`-f5c zI6tp%Q|0rI1imuOlZAYXxru>UR^mhBaS{En;NA`YMUT~Q*5Wsk#K_j&3!MKglVt-e z0u9gXjZy1}`&j<D#mQ^+h|72v7iAAOM36<~l0_ZE?P+$a>m84Kj@T#RE{eyureTpd zxNq)`7tZHry+tbw51%A+*oT^9;&QKG&P3Rg{teG*9QOjwlVz7j@Pt?4<hqU@->Y34 zGC#KZ4Hq9W`qyy%MSRpE8P4!TY~e(F?}X<&&J6<(Lc#(=h<^QKB%bvhp>LbZS}t(~ zWD$ipi+CJ4Gyaj6FEeSjFMkK#7H5z79)1z$a<QW>_}}d)Vt^~oLGnMXTbq#tm^KOL zi`ezQAX_d!b|w6bIwpJU?5i^6|M(l+JA};MmCQxgo4t*Ud@at*F3<)^rf&pMbd7mX zacb3mYW*(IIv65nAM^11)b4wryibf3caU9hj3f8iBNvGLXpF2-%-#J{dBq?%(&^)S zXYM&?PZZ8PD$YD#ojD4g$zx)aEMrtGgRFGUY${^yreWs6=XS)nAiF@@4j5Pa#?xuM zXTSH;W7y4Ud=$p{=J|gz{7&A-WKRjOpb(;6A<O{-b@+ZpvbG2g3O-Nt4orG?kyt@= zuqS)a4}VBFPj)$_D6pppI;Z0LMUV*1cty<WgE^pZfyc3q1e|4jTu?hPdBHwkCp39I z^wsy!;8d6c0jF(=cjynzT932C1S+D>9;~0briM7-p$^k9jx*RJ4BoBb=S}XAPO2mF z^El}S$W7N6CySUs?{n))GHqJNzXJbJ-`jMtgxx2QdHek7W_EnQLUw1$f%=_8$S6Ka z=hWKgv^*FhZxn9R0Sl6Z#d&Xd17BZ94P(#Af{tN#k6~5_Jjd06`<j!l;v;ddU0+H3 zjkVo>(WlUGx78Cbe72|GzHt-;HEh6#+dE9!UXo_^E~U+_W7gq804_Wi=U?f(kmKk; z^VE(DZo78GW*erD3{pVH+_j96ZHTe%fO)t&jHgZojXDSC;(R*D+z~j7Y3N~_L(~QC z=^}oT27jRdf1JJJ!}Z13@Uo&I%3l&51;j@lEq99Udlf4AU;P&MSfu6B47n7Lju5(U z|Hh9v<a-VNoqLo(YP;N=dzV%cdWI9G)SE_4<Vw4ItabY-V3^C$6Z%Jx+FUIdb)I#Y z)3B}<bxc7cX8FvyvvR998bVH2ddok>T`K0&hyjPy)RpQ7w==Qj7WaiF&%-nE)egVC zk99Rcg~NW_jpT1!rsyivI%0n;3!F&aA{Fl_ep`XR78;2*pfs-a=zKL%ne)RiVm0ki z`!rtX$=2}Qr3#hMZ;Q=%npfi1SGN<{UCz&z#~3O)trwC_#2tAqpE9`I`11H=#!3q1 z!iVENmlvf8t3gR0Dx=zb{l9;^ym@iF`7WbEiIrFDo%y4!67AFi;rlhWgc$_BE;P>k zJ|{6SpGKL!ik2Z_wvL1C1N&Bkll8(Bb9J7ajxrdibr7*19FoM(jYB`@3(lym#b(@- z{UFPbAim5YPZQk+x^OgQ_vNFP8i^lFzO@m1eNurp>#YM`okEE(O^eNq&t*?2bW)T2 z==!AV;@=ZWsq<MAT2%|>Vk<71WvN7I62-E@uGGb6JP)=c%gyfj6AF`EiT4;kd<^Xx zh*IqP2N_zq3!)>XOkd%zG~M-p41$urUr?zH`=*(puGu^Tl~~wU-el?KvZ{5dK}|<T z*{``WDVlfPN*C@rNp*?T)OGz9sr`mpperi*#o$`VlrD5n^=J3_;cJnlw@&%POf`92 z!k{-_!|9C`7bP6l;G9vM>Ori|jo5cDqfrJ7cfwDmP4;pe5<}~s_Wj3$=h!!TG^IND zx5V`3wdb%&Q=(Xzc;DskKN9_NW&%%o#3I`cBFj=bCEuQtzfJB&{M2ELmZ0JAA(-U* z=XQ=;E<MTqa5gUJ(YC!e<)P_xGwlIs-ty;^!iv3$%m=v@v9)33LG1mE-N&+%iX3!8 z*L76&Iq0V$6sj%BT2lN=CS#vfwlyKbOZRkiT;jjau@s$7$k(ZuJex3i@l<}<Z7TL? z++*eN*~+y6#q*?nr#C!zjSs0ymsfq6W_s`4YF%`>L-}+v>KkAyx2_=mGnLi2zxjhg z^!Zbz-RDo%vS;tTm<zp|E=TiwH}FV2!^=Cv_S2R-lsK%Lm7{j^sC6ZB{y=Ug@(n?( zeJ%_DdHhI~Z~7Ujax%8w{rk)KId#PG+b7K_JCoK?s%Md@G<^FXT%zRvn;|_)`LX^Y zO6~VS&G(C2^>A(#7Rj7Gwae3$sHg+dMxVs6%<vZJ761`KM;&-mxl2OCN80m2(hbox z5%$5D3Nk?`hJNP3h;;Q2YJ^`y4A)=Op9y521{6g;ccCd7(3nh(ZHT)OQ3SmDLFHsx z!uUQ!9WZi8p>lr|E%}!R855$)+Ev2%YMPAQmYI{AqA|fRqImalC8e#<KJ&m$vYo=p zVR641=k<^g>4zgp?yKqy#1NcZSLKLYQ=^&5FKwlf#$>y{k62q!WRxqF?^I9dRPH@U zlzXP0WR56dyZiMzFGH1XYb6E8T!^+@SjVWIaZ|ct+Bi|HYRtf|DWl*opOA*|`2F;z z%yJce5tFKMv!<r3`UrlpN5bz(4?Z?!w{`R1@UMDrbJCR4`<GubMtH)3zBzY9ML;^E zYQjmn`T1mofNY8I2RGy9y!mbc`R1w*o_@_Q*8U18z7?MIO>cg=t0JiUscJH?sX6~! zgrLfn@Kor>=7O_sLA9S%Q%_HtUtRqbL_<WTqv=};$y9}IGgME<Nw*ZyJQdQsE;5r~ z+)~WcBcv@;J(J?sQo?m9q^lwFF)h8NR6tc&-=z9uR#Qvaji<tQABlW={;{Q8zDL;5 zzxq@DNlS&=rLa+q$ZQdPYo)fTh;c^sY?*XxmEltn(-M)nD&y8_^BxiN=IXgRzt$St zOA*VrBJ+*ut+mdoqE?@(=Ubadt#w{cMIUa7EOdTstq<xEwf$MW&~wuII`UG~9wNFp zK;PDYQx$V$s97AAZfkt@RP6C}(WNotwx;YJF=v^Yr4N2>%>|cYt{S4tGwE$D<*MTD zCN;}*O>M39PsKeRiLNYtY-?-l5%==1S^0d@*4}$5?h_-rx<TLGF`|0IFQaC4N4mXp z^68C$64B2G#_e76JvV}yYd#<OwZB=ryb<zNbnQoad-txYMA)aAwbQ2do^MYjBDO@= ze|>E4J?oK({8_VpdD7l@bt!>?h!H^y9sOi#l30dXB21=ZfF@Eh_PW>xxk<+$Q?DdW zrgnqczvC^}m1Mkz*d|>@#}G+CO)Al(c9XHWWB5j-RPrOSE!IyRBl5jc&-`n*IDdA$ zQ@fHP#E5P4Fm#S;t4XJ4)Nb?3bdDKDN@tdc?FgH6j+^&NXE)dGi2HZGx4n|ieJi#r zmC-rjtR|E9sdiVcx$}cpq|D1Lu|1_vos&VmG6g?t_f&s&PDNhH6hg%J)fu{`acZ*v zEdG5hnXZ{<k+P-N#SipMx;|$2%9hL29T@m`eJZ$;t<(_zazCSMwp>lF+NAD_S##H1 zeWYCNBk{urpStGTdgbc<>ke&xb}jT?$u-1y8fnt4aL5YF7e7n!cr^8RX(BtJIV;7( zjrqm$P+L&biyjXT!Pu3lXCZnmt*V~B7B5y8<b&IadOQPyUwmH2>2=JhdWGh^Sleq0 z?i%RvifDha{#{<T`&89Cdf^4}Tt1|CqsKe;{KW?8hHgKjnok1r%T0KDN3%@*j}-sz zEiRJcsK$+xw2ba;fm=%BCiN#-&D}dUqLd~c-T3+ZoeJvzfKg}wBoG4f0R0b)0zz=; zBGD;W2s22M&j*i+{eNJTl6R>njYJOerg!}}z^R1)14fZ?e1_Gb(N7K_M~iXF#ZYkS zw^YuQaCy@_jwK{!B`T-=Zx{u30C09NZla{1W{#Y9+G>}Y*;z&S7h@=`V|6%;qZ>7J zQd(Vqe);@9r<}lI1N+kOMgwIZBYe0CG(7T5;neu8{|`oy*5Z(KL_e(gwd)Av-O`Z- z_hWbd!6>gr8WpR*{Qoe@(MpH^;o65c?ce_|7)7T5HE{9|M!AkhMPvUvG@*1@pS*lT z56r{qNs`lapmTxzuA24^`yO4RZ(Da(QU73+RCd1A^{MrepI5+HMRX((@o@+M2~-lX zRPy`(8%DWi?z$1j;#|3b<M{tzlrJ##c)k&BqA65hx&SI%f3XtJza}^k1#}?#DIo*7 z?9ZgW!3V&G*T57!KqUeb1j)}`;n6x1S_;-QZ0)Cv^`IMKTAqQUk+#>;Z+qF<f}j9F z_Fy|qW?WLA9t54yqp)Lo%;kmlAiia^Ef8i+*Zq)tJL_R@73h`NuwFI@tx`<Rbaas5 z3^qhdkBc;yq6^S9`|`YCcE0FgZehN{(vk(e1`HI<=Rn41r;i-+P-Y@QK``{c{iiSK z#`IT~-i8mPvIA0aoW^`Wbau~DGz_rBjX!xk%|nDdA6BDePf?oO*W@ihZpKzN-ab66 zmH3z13*>3EH1B}&5U^B5i8Wlw(5ClkJuU}$Oyx-z{=1j*)ynsN6ggGe093H{c#uj# z>?52z9sm&6VgRYz%r|R)XbJ{I+}7mJY#5~Ait7F`CR9;-GA`Es_2fN^G<oyLJbmmD z`Ug`BrikufbZdg4P7=vXb%aku-=D0ykKEwV6at>}mcoH3fU^b74fN|^@(_G7fR0^e z>_@t2sWdW(uw(fgBww;=I^wZ|2Atw#F;JT}UXyYKkw%h4a^FL22dm#&oM!mUd}_MR zm|(dbBcK<dGrbUDXNpBz5w4A(Wfu#PL8+!R8PrTw=s4c{b}fTD_K@4K&!(uR@p%!% z5qm1)EZS%bk<^=Z1dS7$rUq9T5#VL)+;l%~0Y+~;u9qA6e*pJPyK2q;;i7}n@o>|h zFXJVyF1B;LuYT=UyuSMVwf+0mpW}BDq`&_yc#|&wrBwU8BE>)(seeSdfY_0^DJ@L| z>;ahm#%+Z=*XjkwDT#rGl8Uhtyu2<(aimOuP8ujiJzmU1=Pl%qXz@`OU1$I6ifT;q zLGrqbj>4~l0Cr19RN4gy5#~SeM(;Qn{DTW1MWQ-W{t|Hz;Z^GB^A}Qje1O4)gNcAP zVIq2)r<7H9MjOF#f!?Nko$jbERus>eJBf+^gVL%*lLJsJD#<bqG+fC=Pv#pBRp-!Z z(nc~O(w=>$8=wIZLG%sZt`pgbXf=Cj^n69yv*c1fLA^13tCRHHiBbWDu`$E2lZ-;D zG9ewkapSy`%*wlEA{Jxg=3OUQ4asF<E_&~+mQS)fCdzIEkG;1w|Hz5-!%Id#Ksrzi z<wDeV$1|T#I4FO5e&nj7G)`yWAMlp@GZL@Z52Eq(GkGB<j8}M5W#CK2m-n$$Ksk<_ zHbm1TcSdDWW>4>)3s*+&#L%<~og-<&?Y9YPbz49;k|!ApMzg>fN2MZtld*^`X5eC2 zUf%dwG-m7N<!FWXS8_~P*lY>soKT!%BEi>kmKSk3ED`@B;pSZfcOc|IdmjXZPQ;)> z0kq-Iev|x2$0CS&r61wfOfg$lDc{aL70`5QWJ?C>`!zvDe(-(U|B5QWMZ)S|rI7I> z&|+J&Dhv2Oj>Isf;#J3}F|5h_J@T~DCq+~WGCS}8QUi4<^iF~IHdQ{oCKvQR&Vt<v z8Fir{F@uV~3o4|>`n;{*!?@hk6k+YOlCM8soig59qD>feKw)4Qai1cp*uRe?z>M)q z*QM|OOCq%XeOY5I@#fw#Nlm8tJhbBG-Em9oYz*oX27deOcZ#RSqgDXpY1=!n>Ydr# zx+LTw2S_GIn_dH$Qw;pu-+WHZ+-mw$BxV7U{Cu=OC{I$XyOVp9COG1}q+`cW_Qh{g zAXWo40ASR<+$8MNY<KT**07&_Bm-KC`XTB*nlyKjWTG8(5GLJdMyfROdm+3`@{%~} z2#18nxr6k($I+}Dj?|Qzm53P_#;iLj9<#;1b-X8ga8OWAv)v0-Z$uMONQDa)UIffX z)9PV{4GSxvEzpEcpV*G(SQ^u_JwbbcfQMA2%*9&L=_OQj0t)|L3X#&c2gP==ga>0r zXD8X@#gs)|Aku)3*IP`~>Z9n&X!<@PO!Ml8qtAq8+v0O?7s|mcrDhQQ;3!P<@(<f- zVk`sDArSWICY}C^`G0{0%1%~`i~V++xx2q5aPH9~>?jzRiI4N);eB@ajN$dAYt8+~ zVvnMyyEt|w@yYqWHaE407{V^ZfeD^xK|{OqqgR5!NaF$)*}imbMg~y+;GobD{SF3t zr}+4i<Fou6JINl8#x!bS|2}F>Z55EG6(u}0F=^s(D!)(exH3s0v+$P)SGWD@ij_4- znJ}EmO$>Zno|P#@Q6ESNr`tqZD))3R!m{ebk@4jgD>Wm}B>((KnY4;&0DOjK*~VS5 z96{W_Nu$mR0P5Kp7`1ez;;w10w&e@`@5N}@s6NaOA8qsqRpIIK*5#+U{rD-bX8x|? zc;|=6CoxREJ~3>lqU8Sy{;)4_R^JS;{@`8NzW%dASnL}Le_zv-Z@r^)*(BUJt#tM^ zME#ussDZ|MsCawv^k<-OcwX@e(}u6--pI_-@mns9Pk1%lKM%q;^rOl2yrynI+>B9p z>{HY;^r#e<@_Y<iCNt@qt~&LXP=Mp@SLi_}I#%`HPldvkx=Wp>w4%?R%FZ>MZwI;m z^;+rZU3h-%qvLWX#ioWk@{`Xr?A803i*K1RFKkm0D#+@sTK87ePlPz|u*)R><XVl? z2X~U{E=}5DYETgZrmFQZ^8R_Xe^bPs!FTbMS#_D#E3neLk9Ai`)-BQW$H%nm(-A8J z_t#-YAVzu-7@a-ieM$s_9zW+#7t^;2uBR?h0MbC-B`~v)Yz~F_M(5qcf45cMV<_7n zIzuh`j&8ZsFHL|(1RnF=*=C$6YE>#)IymZdf#&YJfK^$VKkbzGY}@3V=#d~!I6Nes zA9*wsc(_f|>1=UFmo8{0mJRk`ufa5ZhxW2R&X(ngPG$H=TI~7b0N=pq(f=ZBT>?E8 zapo1&q-okbd7Di%CND7d$kc8>7XR%UPKU)B<4X5~Ihw+P`-IFjP6)X*P3>7p9ZCu^ z3p;)qicAPAG-hxLYzN>|K3>NFPS`)50hCCKHT?7+t`9>Q22eH_(Vq2FO`whXP?mkf z#8WhFLqA0tnyT-ZcCMf71%l?XO)}FdhIKH;yq!wiiS`Ubb74>U2}$F{k}`*)Iya)7 z_Mu&qq|O^nh+4eP#-I2fE}jb<dmu;Mh^C%KQhzy4J_w`%TY4PuJ(?*ssBj8AKvK-0 zsr(wKz#Z<6`*+lRqkpnsNSNgJqg2pP8aIpk%!`DhS;A#M?T#e%UO&xDKSi%S{1e(E z?0@m~7H(0sfBWvDreo1542qPfV2}y}(j_S&D&63qs30gqHw@j~AuSCKA+3Ojgn$D| z3O<9P63T3z_xtYm-TOH9Z~q7DIM!PCTK9dOpYxiH1uR%6LqZ?zW0whtY-{ZAI_%~& zdKE~xaFB>@!%hrgh5@Jx6}~{*2p5oJ(|?WqOT{jM=>1j<;}cKzpYaS{fps5D-oD4K z0I>%o#8U#|n2gp7O;(U&(J>7WA4X475tC$$P{w`t=~!(G&?z#k*DPQe@Z6>#OY>oJ z87Y$WDSBryn<bb!Fm;`RULkv$xuouEFoSJgKL^p&d`yD@l0?BWY(#p)S@k#L4k&PP z9p+dP9q5}XP>{+wo4RU^Y9t^?6Y=KU8NAGT->xKOgQ$HV`TPNiBO>sWjqdn+lVt+t zh=T35MrEdlehbMww`{UN#U2q5g(U1T!SknCC_kJ<;HSqj8IwiEJg$rE7s;-ei=_fF zvjFNhHEDqcVuDh0&M@cvrJ!HCpk9(u9@d%T6*=tnCOI2%!v;A*o9G<pTnWRQL5^lL z0y>L|b<cM_vJU^Q#r$JBXTTTHjZ0maz>vgP)x!xv9GK<�nC2iVPVuONBpW)_a5@ zmt!g1;p=sI%2H;1P2rz@VYhGyDg{;|M-;5g_nE~`_~ad3%?-3*`{iB0E`~Uqz<LmK zWGtEc=kl?K*a*1-lU<M3E{HxV_V|fsS!8Aq1pAqa6@H2>d+o2J%^p;mORIy=04Med zXa^N*kygAeR6sSz-o_VGC(vT^;W(a>&B*j^cx*cb;twfPH&0#1mlfAxXcOohT6&3^ zRN*(#e3~TMt<wKKqD*H5Qw$V5wJbMhP81tK71x#1@{t6Br;KZw6_00@e3@Q(lDSmj z#1N_!U)fI0o!}@$YL^uP1?%KIJGu%QzN*+2?MX!Uh-T9w%eN)VbXUvOck>$MD;Mw; zo&=<4X0iS%`o>5_3FO5MuYw8DiUosgPtY|@JB@Zwb!3oZI#<4XP@&;dP9-3QDaC8^ zrJI>4w-GVFwu+Z0BK@9n7#(7>B?;l}rH7T(8XG1t>8Nf1dq}`6OP2ZymQeACF?`~h zYXvGRz<UIKIFSm%Yt(lO4-Be~2$+~z$Occw<4yEbTZNECy#eiM{pJDofDC8h#k__? zXWMIm$gK5ztWzaM|FDw5jU%WzcfdNE&8?(N-dms|lS*l%86bxz(hhwao#`sXhv8oV z?9zk@tq%E**2^yYwAUHfto$r4M76z58W&IgwNdmEsOOZ`{71fad%jBO>r1D46Zmap zH;~N!5#y&&uHakndNW_&vN`A+OSTw`!xs9G1aIbSiHdHHx&4wQGk2NPc7#ikR^aB` zXu9iamg7(o^wd!JtG3<|wwqAPdQ{Z}X94F}zPdJL)nVkd@6m~(-1AA@_G#<Zm_G3$ zA7pJG9J`8h6{@f4%S8Mown%eyB?H8d5R!v@2`??WKqsSv+a`^MM@}0Mrg+;GKVmDu zZfPX;BNgjf7p>EwBU;tqrPF<S7dviUB;i#+tHWebuq~q@w0yJ&HL(7pc7A1IDG6(T zu0=@Dk8YuE28kUY)RulUnN&cQWma_wRZT~?a*T4GvCJML!xMPZ$z0GDVt%_xU4=nO zwL+VNAo-DHahr=BY97)d+SDeLqflK`Hp=O))6v}V>Y`btF|z$)C8mN>qAS5IcCA|C zPYgZMfN`t-hFd>RCFU5{hW2N3kZ(U-Rb=54LT>G%8HBivcC%Mui637kNp-yJXm9PP z?97LZwj{N}WBVju&yK#5lNcQ3Z9AfEns|;t1T@pGxc9Yw<cxExTlO;pK;j*3STZ@% zLaV=++$Vi|Ks9iXPq%(=^-;0`%wM?ga(3gEWMzwAFJo0v{87_VeqJvV*5?4_3KEOQ zv>hrN8?0Uj^S0}_qQXD+=!d3F*OBMuTSU*DETUt+_0<+%k>Qywd()#DhXazl?G)kH zCjR|)^%grI(Yvxuec{dV(HqhIgh2PE3S!gRpO?*io?Wh(h0O3fu9aD{uH|y$G(6$} zNM@5@-`K|5k5+C|ux-CgJgOl>2u#l(ZAOm?yjTI}dDb%{5t;MVOVsL>JuJx}^Zxe8 z8TWp59fan&w!sCHPVrP98jqWg%e$-M{olvlIX#__yxvk!6<~4Hp}&=Us|@KrG5nFE zmWUdlkx)0?Qo^<?V3U)qQXL~PX{$WMk3g?yzCXdgNOZLKjNiCv?3k>3+rZ<Oo2&U| zqY>*6xGM-9fxZoiYA|+x!(y0g?L5t7^AaVG&a&<p^+lc9huv{a4nep%Y9mGftV~RD zibD3!8U5F77#_d(1TrKNh@lc6ZR(bPI>P?r_cF<fZ4ZuRgvR!XBahCa9_Y=`?axKW zf`Naq!3({{r&#@Wl07mo?<uJ6lkgS)Xp_lqv-%yJXXtM}c6u)LHs6bty(ETf@T5Ap zD-qUPmp!^ZbB-2UAP%3#R|KmTn7MDDVhtea`S9jCAE~v)!E<ku#Sy%IeabdVo2KX{ z3e3m=(oHJeH1%V#{KzF(J%&R>b$%3-(sN5E<J_UnlF;sn(EHagE_xKFoGkH-!JbFU zY$ayo^t<zt$PbU9H56n60nLXr)s0=2z__(-E_6SA#l!6O^wHGjbifBkXs;xCzb*~? z*F0cx<-*$)q3wm=l^JNU!jKut=2=w6zT@x{%oGl3eK4_PjTwi3vYfAbxK+|kKy03! zX1k`>wH7u_KpHMVyzt0gkl2q$zoDS8r!XA)qiWqb<tXg$gTPLS&RrAC7{|&jCv*!L znL!(Zco00A3}*1$$TuMB0Ek`3VYr4?wW2!jjG%t<S*<_TTa|p}J{yqr*AWV7YM};( zK1V(ykhc6&<jX0(HMcewu*sR&_f$mB#FG0yswLkg8q?H)M`mq=^@H&Cw=vtT*!Ney zUP@T_Oi6t^fg&3qrU<A6E@)95YJ|M#VUBLcql6<9UlGyAl(<jC&9`@r^f7ZZJZcCB zzaR;HjE6_&qegMJUQIxs5TKQs*zX|vfPxNtoxRol?ILugDsCgI%O$xEHBCi54#&Q? zHlEW!zi~#svTlkF@8Hm#hGAI{_x&>+xA4&$Lp-tK0So8DQ-is`3-q`b(Q+d_2u_{W z=t&>Lrsl_IVLz7l{6iF1ya-z@b<wv5t)7-mDGIO#<vw=z@%I3l)C0Vvn)i$XKiwKc zzQV)Zt$$R$buus8yQRb$au?k>5lFzD{QvrB-1})4&&DfCYyzOsan1#fkLHDc-M`3s zDerFB^_fQE4<D?ZUp!lo{>EpbPsHM{DU<!i55J$s`;f@L=*xe{(OAsKqn&CYT3yJ> z8jrM-JJ)qUAUGw{+6wNmxj9$5jwA2o{jLaLTf2japMW$0;T{4<M)hIIBuI|`f@kfK z1|5cOHaZ@NH5d6~G?|n62j*@t(_i~1?4L)GN{`6p&F_@hI%^@(wDFR;`)pR0f3kPx zZ2taLv00)}{!H9IR%c#mIfTuOAFDDScluaQPw1~+q+Owl`D}0m6ny=pL;z6ys_6#H zDq-kTiXmKvE2>fK=l^>c<<xcc5U6MV1?hOz=jVPKu4<>AztbJUZM>!%vD*Fj98^p1 zWdL=cr-=Jx7^P4xmfyod|BI5gt0?+Un8|++qrkj3Yoy}`{@#c*JsC!Ec=OzS29rCU zKv>x3F{f@@wLjWP+?m1Vwgybkl9~7KFWl)3MGK^gHSkbc#h8`C_$<EnG(pC5z7DpC zjn^ez4}d%~6Dn5u3!_KpSpM89Orf(shQf`;^Qvhcp9Z=b9?1FBJB_|MWwlR@6!hab z)U!Hxuw3)w+s@Zy+{3MD3$w7nollo#t_9wP3h>u|eeB<+#DJ{L@%gobjJ_5y|I+X9 zXGMGWpPQW7uEzs!S}x-0!XNBZl~(UU`F?)jty6~Dh>Mg=I`+Xu0fBzW8!@RoLoz{Q za!xNgQSAmdSg#7zo_hH7qa&wHT|o$oPy4ROi<ci%%KKTLxJ$lx-n}xAuD6w;!Q$I1 zH^}!8)y|yT>HS4Y`**HM72o}1Lujh=-mY+*MLP4UfM=(#r!ot7@+G~ay%k};XZkL} zc@J}4K63}`F^A?5IxR-kFVhi?^pwMOMh9x^=+<btfh$vk0*3Do!pEM|pK3DN+G~Gs z%6QM>J$kQod2dqlV+Na^&dsxL+n&Fj)Xy;az+KLB^L0P!=Jm5BY^HZSrra_E-ff1S znrf|btbN#f;FNB1oB=U2eiHhjx#?|NVve3H+DU4!KTzbAn>6#(ob%x7)sBE!!O)z5 zrUMOhD_e*N-;TbPu!7d`>zT`@ObRlK+;)CZA3Hmjlakzy+hRuiIm5;@d@fy8Tl7fJ z^bio48DX<}rYezQ6A%C4HBF#QuA4gkG!Dj%ecuY_^@)*M%X`N1ZQU+w2QkOHBW<&m z7n!$QD<WccJ$y><d!)&7R+{uV`yGF+H39w4N3OID0?EN~PFlmh-K}$vrGn$0eog7y zfYuU=r2r%DwY;jfU-I9MG_T4C=oc?taQ6DMJDA@|vJYo{cIew-*M=1lw|_OKr8eF@ zwpKOV*%WNyn)y)e+QZcE@=mt;PrKdA8ZX|JTz+<GvW$B9s#Dil;K$Zlp8deuUP4(n zcc$Gfn%vnnse8A(9xY!t`e|NKdtO6HnsP9ZS70H$@J8>~^7^H*@WJP&P2nG$SRen{ zJQsItfb{(y5X0@ameS~SVlv5#v%Dkiy<3)@Nq6?=@pJu~*ZE35LMdv;VONc^V_4W9 zvZ#Epz4kP6IN&$Zn(<|t(#yy~r)M@drk}3JbY0t~2^_$t20n-=v#9jDG!)(GpxDNF z=CA7tBG}*co2u}L3#t9J*2t}4J0q1d%6&u~V0a?Z{2bg4xT<RVw#lw1p|~0+xWxfY zD2~_N4tCa1J&k_&OZg@_SYRBy*Yehe^neXvOe1EF$)>7FcMCr~+7B0d?-du&s*F=o zM(;fyjOoy`v;W<3mp61!t~yjpi6D!fdBA}gc!t$7XR`-5E3o>osyKSB$e*G<m}sxl z0>=dI(bE>a-(PO~+Z_#FSgGSguEsyK`Jwjs7}jFgeACqIGn8fvg|;RqC{G}5Db+q1 zl<9Y=udJp!ZGT~{>TKkl4sTB$dtH%|6H^<Y#ZW#yejMvlA1LxP(D9P5S?wpf?-sLc zOTQFbs{^jBFmLwceHy!};IsYNwO_SNNQ?_3TY6f6>Z1+`R4G~ae{E^?eV}O|ecWCB zAAuQ4h|5wCtIXOMZ>;L<2>tLxYpDB^uA^{CqcCZ)c9%>|q=S^)NOz!=5#i(?^)#b# zDbw@NyXXBV+GkqT9!W%>a>a9udYY(S;VH^pEG*G)l)>wl&>J;IFera(;dmbCty^s5 zdgCI4hT$JpOyfRu(Nnc8ee*_=1sZoU0u@95&c)Wqq?92k>O+Y<n=UP1jki}Y?y}*9 zX8_l{`sV!Ax04Ak)+0ji?r>g|xBPiGSg(q92dRma4e5LC4-dci?n&E2mF7nbR&I1& z2@M|hQS6g2PDhiiIpz7Ep7ErLF?~a=0Nu}gIS%K4AwFWYw-_+vutAZhUh&WOHHuo_ zc(_%aMP9sen(Oxlx|fA({EPa8h?^FJD1?QD&k)i!eQHT>g%Hyi*b=*=$$xQPvRzS1 zvu-Wr_IK~)u*OK1?yI`|X1Tuigw~#PeOkT`|J(5iK+2}j&PzVW>QWdr2xP!h5)k0C zVHx4<VS7wf@(I-Rn&s@<W{vC+J+uLyJFt!8(UBja@n2%iU!UXGjk<Tuj%Q|eKxV)z z?op>5|L@tsb1A#=9UOv#FyA2xFepQyIen>d>Erntg-A;K6?1=Vh5PfYI;kYP*5OYd z%E)|1y7^E2g(^YdF03(i5cT2`6bIZUHe}AkR7!VnznwS#o?T?>q%deP?(UhE#q^gc z=*z))*-B%62^DosAoFb?#~#;vYlvkvvNtZ(C~KM$0$f|=9yM3LS{UP^{Adnky{{oi zPYQ7&7P7aS50q==lsa9z!F}T1xpWr<Ow7-`|Hw5~J#FIV)3m}mZ{3&C!YXKk+?wi~ zeSI-x7bzo9H2LP%l(eD;+HJd#$9JP&HrEC%XUBU(@c<$_Ko{rmXGLJN^|chr;~VRv z8Qce1$azb_7+1!uC0B&j)m%d~#$*5JQ_$(}J%*;=jv$Qx>+8b+7=S|8`acnAoplcn z<p1F7`!^z$TN5omQ#_m`YW#ou`jp~?%IzQk9)Q5v8bnG@e0~3kNOeLWHf#$8!RBYr z1Hbk_+5YnX_VxWNs5DOntmui75`d|OHhsD{!Exrle0@4IxVXqW<q>CLX9i;u6k^_= z`Y&If;3t@1gb9u{D5f1{Rb3~(GMawbP5PRs?&m<Md||%Zm4gYnF*5)9`hHHF0=}{E ziSgn;<<LL+LQo*ISkL_H>$_V&fNBO7dT+U1mLqZn<d{LI#MYl*XB&AJx~Pr6{>RsM z@MB}D>fU&F*Z=tX{vPfB`1)!5)hin9OV>mK<3GxH93vn+%P+WBl1~ZlK@*8;@XoY; z5zx_x|18hr4I4*&=kLoALaAKFBEqGu)ATUR6+lfdzkDU;ifstMbpCN7Bc0@jjnDCT zh}ajBD#w3(eP0rFr8oce^@*(}o7|c+jb>zaUQJyVj3`M3h+;kItTu9BG=R5uOt%dZ zBV{tRWh7*}A%sNId~Sv0GoI`xiFlY$ofCcF(lD6K=t36Bu@S~Q)7u|!I_4zuh#TfP zCT6Uca%vHYg?Bx16eK-836Ho`Y*3(*UMaU$RklS-=r4m@AmS0lrILaGj{&%rRcl+J zT+23ea5l@9C1ewC_q<Z9Y(l!fjLukyC4>%i$HT=liSGs>Fj?gx(Gb}{V!;cQI&u*k zj@m1tr8!&88t(m0>-1W8z6Qu(J-S|GC!Bxr)w=6uc`6GSMXsU$o8j2*XLO_q%BX*} z0Rgtt$$@ZLsVGS;t~xTZ2mn-BwIoO?g13e0)dVY-GHS{%7E{-eIZfFiWn$MJsDXOc zHsKJl{KCt5Y@N71Bs;?0n?(!OR9Qh>v3%G7^1_r`i~g`Q)N+J-7$6AgQrfJikr7NF zAffx<Bxo)eMy_L$J$rc!E@_K|!)VF95{)tRk*ttTN+Xt$3kYH41@yl`qSgzv1oS29 z@Sg)&3wuJI>3&nCN6PL(&*p6u1Xf)9(z93i>{vmK-?0eYJZoE35s1|z21y6yGzB5f z9<Vg1fp@(d+H;;L{AC)5bSKe^-UR}g#vroF@Uu#+hxDTI#w0St+$Uk+OuJ|8WkxZ4 zA_Q<XXb6NnNe>KV)gt^+5%6x*FDujkGN}quFOj#MIi(qx^WgyL6r(=J6^QB0`&H?o zm5xtjp3vc3fqhkkQGTQ_BTk)O1rOE$a0<IV>#n@n2LGgjWicg0;eiRlc@m*rt-?x4 zq!)r{0GAB$5VnO+6*N(sFr0e<yIDCeotp+7y_K^DOY1566=?*wKLVyD$#B4er&GI* zGR|cou|mMp>yN0x1GfPXh6e<!mYLs9<%BRkZaqKtf{^3f3*a>x&S%G%HGl8<T5M1! z5QL6N``RzgW`Wkseru%Dp9G1JL0)8BrW31U;E3^om6iao+A2Q!L=x2WnODF!`qx}J zKopxhz-~?X0s-=eX$c^}tI5cbI1zIDIz3WxwpaA7LF)}`I){yO{p^g~&@AQiaJ!*C z2>;1&e$H1<{KGkkI%_~v{hc<8IT5la8Fed01xqR9Y!god1lZ_VjEL{)!sQBXot0o} zcu>f1gs0JUIcz@!PM){zN3h581>pJuUzfobMVPm{Rq5ARLG=WfN*pU&&VDfKc3C?@ z8AS)-0>EQ{k?#3rcNP$Q^Uk{}Gf-cT{yQgq4RBdAC(#ffGc$IIiUZ{%_!gcBjhm~+ zSD91H?#i3Kc~{&Zkq~7<I&Hv~GA*KDm>+%jTE*<GRZ;1eZ;G}MCg~TTP?ewx{d?Z& zFLYm*5qA(a@s`Bfbd)-ECRc;8OVhoDPlYR2-s^i$i|>G8lH}*iy5dz67CXPH{&Gv} z`JUH|2G3sZ`w*%7;1WmSiqPy^?GHALmNSh8Ml&)Q9~#R&B3Hq$Z{n-rFVKM=u1+6G zbTmb2;f9hIp4>)3ONX~`I9Ltg<PugeGcB*qYZ4TUW){BvYGaZM^e#IGe)-khK74h^ z`zCQA{t9P1<&CaOpUzU7d$Uco{4L*^+sRjB)4HhBQ5l`d;LV>`yZ1wfeFe{vy5S+D zw{L2RXITORvprJ*aKazma4XmyuVY?mP{Fs7PlsG*6fy|Ji{nEz-;2;&TdE0gG}HuA zJp?o5b3C9yQ6XRGfHTch!Yu&6F7zuhIdTEALL{S<>MCHrS0zaDs)?=-PUS8v$ie*- znjr|GT(_&ePs-pE`NDb$goVROz*ELA201gBl7gq`f;8K3()-HhS7LJMSs7_|48xaz zD+T8+PPO5tSWi3*h4oU<bw&|5gL11R$UA`pv%G%bDZ1dTEq0)iO>;Qa3Ka2Q8DdIE zi2VEK6uz1=76ocTbL%2F6#Cy2Iflf+T}J8f_L0<geF^7GZ1{&WaU!`qWz$Jpfgwaj z`hy<)Q#4>L^9ADI*r?)(18uRT<Y_5M#&+3zj5!zdqTaDolz%v_S>rSF;Q+6ZssnmO zm(_rZY)<fZPK1u5=6~W^I!`jZryq}&_TRR2|9<n&^P{6r0JfD3)u#sW{-MBbw)S$q zE%|UM`??E8CqpeZ!}($VDAwuCX>pa+&{+Vm-|&f@{`@JXHhd1C`CJ8_Q*2W54kS75 zX`XwmYZDeR^d+o<h`*5F2=FaSVKQWuL%KN&o>((o2|KvqPk5LeFbJ~&83AYOh(JmK zPR$xtNC$?!fT~PbnKO=DWPKRs+%9<b$)OFup?k2XA5Ige$qr%Jisk(RKW9K!VOEd{ zb=JbVnqeE2NH)QuHaHz3Jz^eX70AU4-~cl0^hHt{RMGMb7u}c04pJZI7Y1D2wGGq! zpe4l2oHmxaI+gS&u>aXl-O^ozr{vMR$f;i(kmmYNaYsu>$G^$gZff|=KP$Yn{h^!P z-_yqbtSQhACgQvI%5MJMx=lNr9q<0tGXD3QAMGStdPUnGym|aRi}q*Z=BvY#6OmsX zw7=B&SAW)T(hfh;j`zoDoiFHsJNvI_hnzy50N_3WaVHQVyGWo8N#}gJolKmaAYQoy z2k^+{eDD(vvq-p4n1C=W2h#ThFfL=h0iMTo82Vj=o(6bK3S5!oS|?!Gm;<qwFyJJ_ z1Aw+zgJ*|ar~vR0hhpe~Kfr+<xS(Dy=tcF@pC&>+S%V*Nj*Kv1P!gnA2hr~aSK`3$ zlAxM7S1Z7L007O_Xr&E7AyM#~0mfYuq~XCGWAM7H^_n$Cs5Q`F2>A*Zl4%&~xgW-8 zg8?svGZ+R5`9uKJ5C~n6t7bq1ZC@~)D>B|Z$V?M-mkeSl$0dqJp3#he7-BMDxU8Wt zia}JVc@(2zqyhx%1Or^SqJB(bc5vX|3G9vmW``QYCWUc_0<`?7I<Dv)e9%#TG(%4S zLKGxIfl*o8P6O~Hn3^Vp^=(A<r1RH02h%5@>Aj%z%GjScus5HmA{sI*3g%lQpUZ+P z6Hzne{0$ozG7Q0>jAmFy(+dV814A|dV1XR`Pb)v!96aR0tk(suQ!r9o@d#hc>d7%O zh|ZD($0^txE>gc>v;_>yF&xF<0=_WEWXUE94TZfPLK9)YBmp{pl5!hFbGe*CiA7h# zqK-AePc-WUigmEiTvFmJ2HtiO9Aj(uqom+`JZ+%TEaor3oKPP2jg-t_lY~$XGV)E% zut}NTz|0Q?t>G}M2GNoh5%IH;wX#W#vfw%)kUjxn?t6-(BA#J4>;^nVeKX3T4a|b2 zxN3n^V)&DT)Xbh#U;+gYFiX@RzYOM^k!cJ)=!dh>aboEa%;~v!(0Z8Ue{doyP6J3N zFJfeJ8;{b-39EUmxL3*{4kQ?$iz2yRmd97QgsvMz$8NHOz=0Wqh}uZ*LjdbGmuxo7 z5-0~cgJCtZSzd<O7U|il%)x&MVe<fBR-Q4E!Co(xb_E7dsqtEJ*<v<1Of+Q#y<o<S zFFR^D3QiYMU7mv9janjQrTOHV@8$r+aQXu5x+Gd}INMw>_*g3s?}edp1x^CMUuzN_ z59^p%1R$DkS&u0tV`$X)X6}^oNcJ*PBFMvLDVNI7gIUZ-wPMD!$$_ZZ0!6_TJu$El z2TIGPBDYvyIv3L0AY|Ht-&Yh~@JeH}<PtfI2PBEtMp(=?<K9?+6c;w>!}N8@oCWjZ zewWziaIEcIq1kR!NMw<WSjh#$Xr6<xFL3M~vD{m`QBp8q1c%VvDpB$ZBOtJ!v<h!5 z=Pr|T_hCTHMyYUMsme&slqC3a18XY=>bSCxkP`hy%0y|*<p&$l_F9}YN-BL|UW_XX z?rFTeZ`Q+})E~YTe9Y<lnib)`+(hS!{6ps43@pbcMm4hFvSpbG0uafp<WUaFa78T+ zr`C(JnOTH0Cgd~h#xzGUj}61Al38KeWrT#%Ce3Jb%WBTRDtKnr{%kInHs^9(V3{@Q zcmu5~_9A93I9Dsy$G3bSGflv-Y9)$!CF4Zyo9vs3(mu@3nyW!C=jm-Rhl?gQX4X*P zSl{-reR1Y*T2&##1zkMMTO+mCTWcYcDS%}i+^g6F@giHBS<NNs{4g_z--`#DK~b93 zNm})z?bT#$a0CHtL^0RQF`Kz0c#4)cn}ermE)D3(;xC(6_qhg(%ohL!O`{-PH#1}v zm><mLBp`xuk@=G&1sWY-oH)3R;G}Y6s>BL=5WoP}%iiT&`mb^7Utc0^N~<SxsM^iU z%)uk=$!SsvCJL!{;DAX*v*l)Wx?mk+J+^5+g2}7i)eSWE<N6|p?$i#VP6R8#S_5^! z-OWa|f{dp+;Awd2PJR>>z|f)^`wj{jY?>u!a~XPYQM0Yco)Te1`^IoJlVLQK8ZGG7 z4$`&Z15-UJ^A1JhnWQi=yf0rLU>mhM)OOPt1S6Iw@;>Y*G-QGPqYc$MY)|H}POX?M z9OeiN-l>S1f?>KkI_VRdZ_|26ZepOqXilwV%lo;mhOcc_%v~~(LES@LH9FwMtk$KE zpi)Gqg<y)xNXY{3glUUd^L>TtDG8q}WzZ#K3|~$tgog}cPR(^9okNjdyY>(@Z*QkG zTK2FfRM5F6>}w$lhO-bTW|r*QGZifS+t?*)8N8tTEDC`90Toa9h05q`$uy>d=n>vN z#B!Tndp`F^<^)(_g(QlhKG+q2-x=+R<;_QRvZ!Ue$c0C^|H}b{)qU+lO=dVfjmYsW zOxp-w!C}y&ui;Y7kJ>?JYB?Z@$%-C8N@b~zq7QGg?G4543`O;x8#MXa3w|7A-|b}F zMVY$};J*%{X;Rr3c{VQs^v6N_Z*EL%c2892kPCN~#cuE-IXOfd45}XD*98Z8UvMbb zDOiGpeDJ<A=9t*^jcY`auMyFM-ocek!`j?t!{DMIE~38%j(p>bxiycK;tJOHA2xuu zDITFmqC+69Bd>sn9$a~(STx>u%%^HBcr5vy8|F<`pYd>{%myS{8w?W*Ue0gh`WRd^ z_J)<NPy`V{$c{jGy=^DwFzhzSqkuIadoVk`-)f9n%^W)40vNm*$^h3Sn17j9{xO(1 zFBpB^HMYh8<a&TI=m2}I(KK?@iezeo#AKsR;YV_iQY#8V2QSkBMfb7yeL^$j-wDyK z2Qw%aSB-%`@L(_DU3f;@XM;BO#o#M<rkD#LReve~Vh9TzW<#N0{S=ET0{Fu>ZDrUF z22S5Xv&m$ECp46C*R<{RGybwEb{=e${D^s6=+48qTbeCSi|kX}GnNS-yq|I1dp6_U z191g_PV)P$iW&1Bh(v7C#<^K3y1wU;v;6a*$g|m)^K8$~had9Ixs55_cc06=BaoX; z&U(f^P(GWt$P#azw0&*<zBU*dJ0F}gSN&}6#(W}eV!HM(tJ!{q<(-e`moaTSE$wJF z?NfuVa#+3=jR#&|xLAPHj$JT1(d}gykHxaM%zm6a#X1fE@|KJ57K0;@2`8>HmU&HB z@889ik;Rmu$BlYRAN5MN&};z{OV36YlVP9UoCnR!U!~}MDsWvgS%ge&d_44Eq1|bq zQ+%;-y(Po#71Q0NUtQzG^fBby;E>tqdDt?uXIi@g_=!@RB)fEY{dKrz={G7?VJ}*& zvx)P<azc6=je-dQ;51<Hdsn(xcSY9F%5**?lhpQ&)Ee!wJpb%7g^IoCwxTHZ>FQEa z#@ErQeYB$f=c~D(%F?HgM_&wbzg+HKG22JshPtlut%~!nJk09Wz^pm8Me;oj)%do& zr<d4vXU!0^k|o=c*|COKT+qhET=HCZzq_c|_T~BTx^?cl^yvCC{x4@}@QoPf)$1;6 zK4OtX{b`*G8(z5^zZW4hZ#pcFSCLEU3C>CHG)rSV*UjVBOf1%upRZ><OFQEmTJ?9s zA?}Mn_hy7!u!3lC5oSF{|Lc<qO4#!aAN{Y?{D>Ctv(v_AZ0<_x-CPCj2)DaiMdi!! z-PPkY+d>wR<K`Gf^w;dWlm{20$<CPr*`&J4uS>Zb4?o7GMlUb&Q?j_?iL;3`_wt3@ zZO-m(57Oe>s+4;*TjkdiH*~(Cv^G1IwgA%9w*D6Lx1@Zo*!vM<)}1N86u-hheU3^W zr@y!><Xg*j?;oo+B5o*(N)8hm4;%jWPtluyuJeD!Ib#~HV<b=gu%z+5`>Idz=-%wp z2Nx+PK-knE4)qzf_o@ypMMEpUi8`$}G`W*>e*^N@03$VyiZj5Tz;Sz$*dNx|UlY(a z{GOyo*K58PYNzHPN@-IRRPF?7ANNB_3B8X;*Mg{KYvjFvS-Xp~|I{RmkRjv@Of3=P z_7D1~4!b}`JD@P@z|^56>X!l5*8urf@+0)w?}$^84dv010PqrrJOrj}v|i*LqouIe z18dY%GU}L$-4UG-8C~F2%2_%Azo_ktgwFNKT|*1Zk@eUy^;aCw6WO+ttn?wvys?Q9 zn}I9jsQezQHQ5aNdBUY-6A(uR1vYbsLwEiZ{sS31;e7@S3ih3&TLbFMo?>ovV}Apv zBFe$lyuXRF$<sJ!Hw8J&6U_N^HE%STYE7cmVF4R=<Cg)S=T9+`{!bC<b4G5XFGKO) zblbnqT;wC#xZBtNSVP}cN`mUq%lfj~YJ099OX;Lwb6Xz&)#O*pG}$yN{V!kNPun+z z;sK=z4mD2NS#pb}*U}%%zj{P=?Lmr6i2@-;i`}8TX5UUC(#wza+7dI^{6E{4?rlA? zHBVVM?76&F<)q-_v7`8JL~1{hu>0%B<G54cV_I)0g9O*QS%il%|1aqst1Gv@9_t0m zJbdwa<mJB+Y0l9v2T#EM>i3p^9y;e(f0WxE+!0VP9y|8f(YXEFdu#f|J?I=eUTM~i z`1PpsI#s=QsWrn6DzVt@B3Az@T;N{!pNH$e{_2#x&68Ovj=p{6ji^s6d{E$?zAvWf z<(l0|L@E#yRd={|;FRPKP~wH(u^f)KhUkA?&nAfOy-r&nbJ><{HVLUy<GdGQSlHQX zQG;>}dvH;KgI#;LGayEpP=Cr!s6q1#uWp4RkUnfrMm^dhoq>-RNY<}M$zRer-;(V) zaMqZP$a_B(F`<ED9ZS%;I%Cgz;bI2!*)dd>e0ldX@bV;YfPPYqo)V2QxkyGU;j&%{ zOy?^tkAb#1zy~sfUNO=-!_zb|7q%DCEMM_wQngP%>xzk?;0u#6zN2l;smfl%Z)09> zml0EjP9;|dWIkW{X>_To;fIFZ@#JNBcEcAh&Fwz<8K*uhHIx*zz2SOJTHsm5D&IzS z%1?8Tme+4|96n5}U%Zo(nb52E-q%yubH>3;=3=c^&(*>K4@5uVicaXM6ze;6cTRkL z=Y~^0h<(m%q8M&iB*1ix<Q!#vFWd;FD{Zwcc3c?DR=0=$c<&ys^1eGD@gOBDL%3Pi zA*G~R`=#6(6?%=y@K}`G*=g7`@9B8#<B%7?U+v(tmfp|%Y%BVzxL@C#Mz-GG)r`CO zWu=+40)W@UJ}yAz+Bz<i^H%-fs_tZXo?lXp{7xmqwpOxww!&>!`KlmjcAj+Ptij9Q zrI}@jb!#Ypap<$CW})Q*$qaj<Y1;k4vR{6zhOWv<gtEgioi@Gfj$dBm#=kzsSsD%B z_AI4W%{-+)D>u70eorY?#D~Hqe2@9(bL8iQ>(|?yW&;GSmUvRMf=^jYq`;Ti7q7)m z2gojGf2s{ETN)4kR-~HbubJliw1n}ShJZdftMTa%x1DtXt67*6>oXHq=^8QC-`?ZR zok~gpr>6$hVgod}!<<$$(#HPYU?U{u{<GIYKJ)ViA1#96a*a*YyJ4nBYx|L+cUj{G zq$X&=?on@*9BrV_+<UcJgGZGW9}3))_-4F+WQ|%+N(?X$MjwH%<t2lATlbt*KL-n7 z9b{Eu@cWO)NMU6mqU@@2DBH?S9COKRVIBDf=VNQ=iBJuHu&Zr<-v2F2nXLMD$ZDXg zxrTU+;OPr2;N>$T{fa8@)h~UhmoIILKOG|&YYb3K?*-Zz@%$>not=ma@5i7+dmujc z^un$^w-9|Cs?Y3${B2e3h0jj0C)F?WXffV0l(z3NjU6&GYseNhmCHDK`8kj<@miiL zd|6i<eOW#FGlyH7_TApsLYrAke7#<Hx^E9Wue+L(HfD7k->#<B+62p{D=SOcY)Wa- zf~FNEGC1s{r?PYoR%HMn+=3j;b^zRx5&13}>t3my+ps3Hda`j%{w&Z==u>*H-1Dq8 z_#W<HP-(lOGj`uVpm1Z1aCr4**rin=s?XUA+M<K4J$2`4K9KXrhRL;3y5@O-(94>J zJz=SA+23HJO125(YJoSTD{NzAb9dus^F4C>T?e~F?GXjZ7fHfQTQ|yA@IK`>v8ik` zH`(dqUsOC)kY)e)>$pC?hiSU<Y=O4Iz;3(-z86o`EzxMN5Vyaz!SmW`!*tp;f!1nQ z>6)&7R;+!D-&Qyy<+j^hIom|&Ko5JAc<~9f(Ddxui$_n@s@2~;iI)9Sl&Dd3j`l<G zM!_G7Xm#Z4ZGHaPFhIDEGu2dF3oN<$P0YnNL(Ss`=6k$rosC34pOtgLOYt}EwlzU| z9tMJkST)fVk@qIi?vG49TxK4!YkRY!OxcYMsI%c(2btv0mXdp47AewNAxo9M7GDZ) zwM|F#T`_6FR`NW!(2mrWZ~J)Xz30n-b@OBrE{XG*5h>Nhq4sXkPrNq1Fd?n~pW7p> zn8y)??ua+{pKKx{jVYfSFBV^D+m6ZuPRsVRU4N5vh(lXQ2FJGM?1WQ($ImD1^)9WN z$}Sk#N_h-6^_~|!tJl;1Jx8{FQf2hP3A*i)UNlhlNT)4V<PP}JCq?#FjVy(>8>4q+ zrJ6mq4!8V7;B}z%h<d6>Tt_{hbjV7#B*!_&<Ait%ORmv$k94IPLx@Z9IkkikZFkje zH2t_afyVefV_KVQRmcw0=REi}iqFpdr?W&B>xS{q7z?=91girO|KNjPTV+2Z|8V&& zxm?7W+L^@heHT@{!r(P#2Wkl2w<gOUmpJUK0#yt@vNwMjJF_ns$99F^yV6unDZpM& zPCM>rl&iRe;BC#Wc6Ij*!f@DIGLP5`zF*1Z+r6Jpf2?fMLSHLhhG|HA79c<WRmXKE z>ryPYZM*8rmwHip2(Nw2Wu_;sYVNPJRwM+@bk(-AMvpxd`pov&2cilWpQmZP^LuOe z!MgkB3$vJ>KDK?pM|R~pi}ShKYlr<U8JxLh0yQ@{M(TnuAQC;lNBDgZw1bN61%8V? zBdsNS`L5!89V~!s$H!2cF?_yTe3i7K&U633v}!i#$}s~=D0NtdfHAiCr?Xm7!)@Y+ zxL|k&$m~iUP_p8&wNdDjqy^u$FS%>9=*v;$n%}R~Z5UVbNo^e&8T%t2vsa&GG8Yme zDu`n?2)2?ta}(=V^VM^(xw_7nu7vT!^wQ%5KyfRW^H7NOQK?_AP3g*?rI7UtkB4L$ zS6GeS*S^jD^-^a}Ls0{{uAnsjec`9T`h<d>)J+xvj{RqO%X?dc=02sdG<Vi1vh@nw z=rAEd?-Vyy<J+T)YVRkVGXqcXi&;FpG_Gjhw!6j7>!07NKUh@j4d2Rpp5M}_Q~tta zb4|SvQUA^B)zO&lFflc$wm>xxO{!a$hTQea60R11cFdmY_p0I?;$XDUwICq?RD5w8 z7B4TSJB-wyV?32vL+9NF8pb^nWnP_td{9xy-0CQ0U>@U^%IAtgG~v?}dI;8N?}RHV zxRA#N3VL7VW!)kgv_r{RO>9k-HQdn+)KCwAgULSl4os9l$$wa<Tvc(UVWO~dMfr*X zD(x`b&l%#d4;AzelO~oBRhUBrQ@^)fIdP_ZH|iD@D!Q~8xz`G%4ODbqP<<8djATwI z@;H>bVlS)64d!V=t`p*j4X-q2#R>Vzd`IENnqgn?%GXrSzcPfnQbLSpFZG}6C5l6N z7>S4F@rw;%dggoxi^yws{k&f@739MGtz(_Jq8t4f{lsB<pAlZLSA71Rm-$}H_ttMv z;g7A+=HyV~A*1v}h#jna2k8Hln0EXzOUHgdXYUMwIN+Q-;F7KG1wvh#)Ctb&j-6ua zC{iX%IK2(jDL>4S#9#|TWDQQdN@05z5Zes~Yv(Ysi&VBHw<jOe_1eI*FN4qb1_QPS z?-SL(K2*14?W})TLPS7slcBEZP(M<rmMHP0)ksS;jOJ~f8UPUQ*L6SM6?IHjC!)&j z_L*!XwNBhmw)-L1CW2GFhtooa(?f=@Z7|%$4=4Qz#eC6lz5;z{kaF8T;sH6|t{UPX zI^xE~q)^8oLu9;*iy)rvwv&s{X&QiT4SLiKpJ<&7TZ2<O|Me!hlAyl%;ZM`U8#<v5 z`=R#?bP_v<lR|V_y>%Qx$Zc!Q@Z#`>F&%Sa=(X11n+6aY+<={ssv)CxNUN&zA4q`p z81Xyw!+dD}Lxu<MhPjJV`t56;y$`G24pwMo=pGw=N(y%#f?7#xHQS3Pn7o<Z*6<M3 zvTY52O47SdV7yCV%8?lJc>iXxUv<c>q^AN)dk703Ly3CiGs#+?d=*1S*fc#Elf7_n zSFCidw=x(LL+gtn{&l1G@<Ae7xaa;`_fFL!e3m0h|6!|YZ3W_|cS$8%_<e(RViX#0 zA7)d2BDV@XIe!hR)BeDy8lv^8$Cy8;U3G&|)h#_#)|x>!KXl}p%D&JLR{=U=>!$lY zlhp>pL^agW8gduxC036-*a&y5j_UJiEbFacxr6*2Gw|a3cz|lUcPrGJ8hLLb^iJ#K zor%d)tCPH4hWjS+`MMDgaQcj~!P1o869L*?*wC7UCR7<F{wLgFgHfRl>Nli++gz=e z5$a`-uw<{&s*|uQ5nky(89-s;*PEhUSv0%@hV=(C2&oxKJ2Obv8Oua4=!>4%c^DK@ zrj(dWgdQ<m$QJW}83~?xce*R|c7(AE!K8^b?6!|~Z-~LVKh_7FoQYs`CWd(%K&NE~ z?t|gE63|-17msK4HW=UC-w4~drha$G@YFQZU279*uJ?HM_qYEV%itAwcP6E~nC`Sf zG)PR|@>8p>p-wm>RkXI5nz2l%v4-BevpX6D^Jy>28~5oC9v%bcT9LcDlRr%+U(AQ! z+z9nE4;!$$;6=XW7?V;FqmJ9TIb9uQ{g+8E-`MJuiLAjp^PK6+iy8y|V?-l9L$_&D zwb_uf>X%9MKC@vr9Bze@bvx!XXl|`cmLBglN=}qYq4$8<c&0hdMW|~;7->ht{EiVH zJ4Cb2^iGQLqlMYq)LG7FH}^x-e>V+iFJ^cG<91C<=02f`Ibmb7%3)OLt1#f=P_IXX zd4#pP>5c~PGvlif#&WCEv9YH7)AKJ@=WBk>*Z#G%Y7Kql9AeoTW(B*&Hy!%&=lsi) zb_BGEOPA%nX+z65?KxJ{9OpG}M7|0<W9+t|;Sdq32!ps1!W@mqqh;p-81cOMeCZ1q ziEXI-=VZkTORN9*`c|!!)!wN)GfEg}GrgISCd^r}zd!nHF8$Yx#%AhqC904s`=2B< zcyNovr}^Au)SSfNO}#_g>Cd>YU>Hpdf9+s3xCr?hY!yRLH!U$w3cb7W6Q0={Zk--_ zKJ>0z*WB;z4ra!bvM6*sOKPRF`s1G(i9!$q>*1rZcXnf38uf!wqDujI%M%k?zyzf9 z&Qjd0x~bmmiLVcUP~5lQRkBe4juQ*ro2Rq&nmO<7B*NV%!r;>H@8d|hd`6y&dP)y& zR%V+8T+_O{F_tPZ`c!lDo~EA8_E2FC?DNZelA^GP#d{yg^)`K_7D;_tmnNljAPrx1 z<TgSaM76N7OYw_giK@eP=33W>7&In=eOqt(aY5P_Zf5e#KG=Boxo&adfz44$kdvf| zWX|$X-Qsij4PE9>H0DRIiJ1^9yjp{VPWPT}T2rtgZaA_3b4$$Vb;UOh<|}FT!{<t% zqPfs_{Y+NY5C^W=XI~(mK)6=~hIzE>0zbo5$>7`MPrZD03-}C0t<QR68cyf+v#z~K zj?p_=jgH1fO&wQnIj%M~h5N~dU4N^UFs9+$sVe$j_3V|gICHD3gdjk(!^u3%p*(Ev zqdk`)mkARfack`K@!-JTpmUQt^Be2F`o*(+@cWk;xGsbMnn6xL=&gxRhlx-2Zxi#} zVT=CiuHH^hgst5@92fa|++9i_-b&Fv5ZmWr_IiN;p2<Vf(PKl?`<V4nF0cPvo7Pz; zALmg035c|&rDe=hqu}m3SD&!6uk8k|hkZdCM618>5M6VvgOrUi=mFtQbr4dsl<E0! zFK|VyE7T6}nELHPb|b_lJ@ghB<|^u()m=Bs1$FZYbHzF5e`rkOuq#%qZ$`rY7dOM6 z;AWrxpST&Whx`8zH<MWrmA&-;!p&~}Drf$mdRW%7xIkORtq4PdL1xpEcEIPMYJNiQ zf7ipB2A+j}+YppYtuzF<=qU2#$z*;#x~7SzFaJ{y`^aY)$9kUe^_3UigmZ8BZmc2x zs~$E@g@a!!o4UFDZ$0dV>Q$#3qrjLYPkD(NhA&;@-+I_9Z+WgD*8nmXS(8rz*w#em ztKXXX*T|70b@fA#)$RU>^WfFE@y>tiVHZ|*0>`sX>S4Ru|HaMRKE3Vg_}_Zi|G~}t zs7SCg@8+kDm^iRkhpY8fH;wkb3!o4andpcRMqx(nAe3V2J@w4w-&(<JJgL2EdfrAS zMvm^{o?v$U+2sgR<%v8z<B&)KD|6z;N;D65T>`7*2j|bR|EY)l_5XpJu{=I~11BwZ zR{21U`(2XU&Xd!ORuAM1(op9CAeAL~E-w=D$fe|ln|?@%iidti4x@E0o0A?KM<Qpq zB8t~?ct{ye^nUNe*3tqV90+Hhr~%drndHRR9}BAx@%c~GA<Fb(L!_XnfWx`<bVqG+ z1;3V+{2G0BH?_A+*p-G?&WOs~bO>OhrWsV+lh$4>Ke~f(DJsy<Jn5Lx-PHtP2Bb|J z_`hgbq-?!Y;j9X|GWS1d848!j2$N0F6v+`f9ZGj`gE^!%1!L(*?}AXhSYLV?cP}rF zL&33OR5}Z69<X#;q1TW3uEPS6J=(S|Eu{{zD_YSFBViL6FEV*sGgbUAdN-)CXnCL8 zWmmou7<!7QlQ_Zw2q~8_UL2yT&}Shu!KzoMNkN1Cw+^if=~JpC``V1S_sW@0_&z>I z;&fec5wprJdw4NnXQ0#-KP;Nbw-PemICcpkWcNz4{sbih`x$rvYiU7V91y~vxwqU; zAC93FE4MvEsn)Uv7<`Z9kG()u;g@l%b__5Ez(=g;b2%PU@4fzI$zoLGa)g-+lNgcK z%5d>y_j>Y}l?dfKr?R`(5JZf)!UUSLB?i&y8>kGkX%SH)Lt4&tWXNrw6ZZ)xhxauh z7i&7;EUz;moZEatw)AU&^|nvi7x@GYR%POCxxzHN3ps_1-ui8QMQRI!9QCw<tD9DS zRaz``S9Y}!ViT&YhcoaPK^)ACn!`H#@)cXgh*gd=(|JWT5+h$c$BX=a@hgThVt9HF z#{3jUf6|Kx<z7_1+iUhqVcmNb@p4v$09_(*0<EBIm*{nXAV~zbJ<53Y^bC@AWtow_ zF5)r05CzF`(x(pQ+s5bLLH{g~me>c7O!jGEuuD<rfdaUZBtN~sWau?bK|A5oHemcr zq-j$<4{3-!@4}Nl&M4t9NM<N!P(B@lkl^!damK&R`5nKcY79QHo)*oPJgK5Q&2-|a z=CYOPK+i5CzBF<PVFN>juJk;L2Z-2a$tX@P98<WcreF;aA~tKofW%p_43MCoy~h2N zbuCz$C6N+CqDB{*>>g;A(Ou6kWG|ZNgTU}StZHtSA+uR@^5LUOYADmo?{6SFrK9xO zg4AIOX6@DNFI0pYJ=f^TqUFDFlXFO5&19xz4~WwL(*p<diC-}XwCft1Cp_o=4G={w zwMHb#I6N>N^mfeDqaz#dsgT*dpPV-|h0_OG-pR*&srNb<v)h}0KYq6^&yUWU!I=l9 z1y@mq$FKn~^E=g@s*>;_Z3f=+<*zX9*?OCBK=`U&-L02&vYLVB9B)1pG`|!H{GxNy za>UFau$?I0Wo#5mU)i0hU0wO^{k?-t-lDCcsmWq*-4S0<qGIh_S<r=&&hIH1;OhJE zWHBSppT@QL{wrM=9Tx|5weqd-vzZq>&f2qA+u9k46t}}q2i&O+kR*|cpA9x7I<Ua- z)*uTBFO!8n??h)1^e*!juJ9BLZlnNCrQ!rpt(vx%b#6z}TAQ2b<pMpQjDj;P_AMg& zL+)-!{zV>DCh^%xLgc7bu7p{wUEzFcrp}#pbyZz|c9`Qw%f)Y7_8sU+qdNkZO#jJz za<;8dLUmt#T5U%Ur-+~MT_0r`9eCl}K~FT_obFUYe6gcv{tEfl2-d$dlRpRc;4%69 z2qLFGl63JJ9bqI0=&@kjj90)~EzC5m_W-1&Z*@e(UmhW5HvS>@0VGGT58dek6Xx(I zMM11WPjFXS>$L&q3=6qpwbc@;$&aZJ?ktg3egJ=}0U%<8e9vUf#l}Nd?gcOC3fgw5 zh@PTn)FzD&%~&X_c#bi}P#grq(#IZGWrI&Wyl6OP^P!+GRv>erg}f3DCg4sD48#?l zt^y+vif$wk33~Qx!pa2XXY0^Cx>v}##Sp)rpA@182O!+a%JTVk5np_nZ1pvBnN))G zk-{!pk1GAgn*^kWrM$i;1eTd=2DVzXUoT3DfaYdrL-4q1ZhhnDrAPWr^p9~Boi7`B zSKK-|gc?TUnw!e>c3f{C&CkAVZf<$A<LQ@mhRvDWGI;*>gRI-9af&VN$i#1tI<h+c ziIee0OWZ&4qAdOFVPI=`ct83Y=O+SlBN`xuUbz?|%b?uLf=gUzZ+eXD6drrU$zo5u zQTiU?#RQzZxAOZopO7+|Tx^CUNoqPym?ofEbM`oKm2P?^T-j4q#gml8VEx`7AmjE> zfX)J0S-{3wWeN3TP~s^ri+dkq*$1Bbn14a0xu^U(3czxutuhz%t3b$Wg;}Ly1rWS3 z{fYQT!WQ>jG=haIaZS*<hXRmwxP~y^u?ulH(O>c|+V$%!_JQAkd}Sy=T@Re#1CAiX z0y^u50ON@<CO;^tf*8T#R*4Io@_X`Jk)(+1|5tL4Mg)a~n4JisV19YmCHKe8x_$z< zJsaT~-$j4&4}Iwiweg;$K4b`k0M|~e92mqtYtD2QrVQ`(<N}pDe$7qpsc2s$oyMQk z5_k6?n#P}1-upDK^}K<${p#j%+qGB!N8Iey@$Yfk@ez#%a1rVMFTUP8sHygC)LlR- zsZ?oV5L7@^Kv59XfOHkX8j3V&q9_O`ASHy5gdPx(PUu|&sB|gPi-6Km35Ya-Hx`hd zllS|5-`Qu+nZ5tbOeQm#$y(3KecjikP6Tl&Rv#iPiO63~M2>N#6GW_7u%LRda3SHl zd$1S`Em0jTH5M#Q3l<{;%f<z>*eH(szaDMHYLZelNm3mRn4%B*NUsc_dCfxD0A`mN zvdgss<Iwm{(qt2&#gyE_Mg-8Iehjj4A=G4pY|=?K8G|;ull6R%YzFDe0E*>~UKzlw zVkxUQteqjn-i2~9Ny@%6<N*Oa1B8IGP`Wg(fEl`Oi}^#R{>G!YVvM)$$VLW|D|_!% zrUk3hNE?XW|IGL}1k4%(8f^>B#3LI`vEP)@T7(e$v9P;Ilxh`9#sWH(fIg&-JyM9Q z<1T~(h<qI8R}(d`8g*=pwC5hN=T55bB<<ml)pX1t9uvC&<6?LKk@SrVW8o-i>fw&C z@S8s)(+#nX3t@d?+*i;nI%y1t%%nqGT`;|-v<Z5I;s#0rMrN6!r?KdL3nAZ3(QYu( zcUFj0VN_KTDUgO)Afnf?@K!8Z9)@0ZkNV(4>8DW!2tpryD1bY?uah!CBXtlFWn##6 zcT6u1xrfJcnUx7zuw5qwyBVrQi&7gyr;kPM8^d(LsC?zfzqXiY7Q9Ls#o@4H=UE|r zF7%v2Isz_)@}<j%#qBXMGu(#&Jd!dHvp~d@E2F-;M{)r2!NunzE+JsEkOw{?7DiY| zSArI|e!Gd;YeIft#iV1=T#jsp5n^i?e?dI{j7q$&c}TuGww3Dyp~rUHMsvL!T<mKJ zh7Mf}rX?qZ*Ca{7$f0mDIgGUBj%i@Px7e63I5a>Hi&j8~!GTEelx&TZT=SF&@wmr} zk$ML4`AK0cQ*1vLK7>atGSSlmvGiDUpE82Y!pgfy<7%QYMh|mnFPb&bjYilp?v8E~ z(jAK#`d2o9s$@gM*s!tW^og4E&*SM|H`7_-8DBVXIF$`60N|c<Zu1!y2Ea#?VWSEe zzce!cm}jmlWRjWuJ?_Yz@yxx=%nl|B5}fj>&@CN?`A$#Uu0fWV!eRh;JOds@1P=@# zB3PPKHgpTlkebMn-payBWFIU>wlI*(EMyb|-H$_dFpvkgvXv!rRL|xd=w^`JGh^tP z+eO$3*z-@P!&Q9{K>!?MoEu8y@4+KmOc81Bm?c|u^`;;P5Sj;oWjg=&fmCogX|^1t z<eH;foU>blglN+<s~;TQ#Pqu(Tiua8jJ)ez=w>`>sR{L!%NI4Fxbm4fTZ(E@3Q?kv zbha>KAwkmz%@vm{<M@}kMv||L5VAy3+}Wad{=zbal!+wl!&?3`#px?unY@bF^Ac`q zg`{sx)J+QnS8Bp7$^9HdvvGy^dqQ!3Txmvf5d*!)LTS3t=Vd5mMc8cxr0zsU3qC*F z!fn?b&E+ED7N|59cW{oGVudPd6k?K7L<9=Qjf(`vx#$sQiO$bqU{<O_;9b&oK1Dcl z>=YZJU!2Jo8}@WPvVouLi9vIfFum@iX>5s}c@eKB^LcH^bP6UL0Olmnnw>aD_2Paa zKiNIEQzAtFRtRVs^%=nYAaYe1z$f5^M_2;Lvf{8MeU$qydg0C%W_|)wnSxtU#3Gj% zbdEbRRU=L6aN=e$CY6af{tVsVS9at_q(E}0F4sfUT{+Fbq%pX@nhIs!=iAA!66L&C zHI+6nOxO~l%k<@O&DY}-WyX_{N#-cvQibu41m5zHJNJ>?sXW`Z><sVo5;k-MNRfI{ z7-oTZ$HqJ<4iTHg9<~hW<;N^D&@9`61&Jc31v<u~P^S))Hc-f!z=YhFRfUCgxWjI5 zV^q~`AgP6^?kM&^w8j_{px3}X=rP-2;M%yArqY{=)kc~nPm*5}C*GP(R?T)-D_@dH z5f{i(EDzBr9#*U6*z)g&*IIPf^4q<5rP*-T5}P$CXkQbe?u+Sb;;L*=^&E+Mjz<G> znha`2yfDOeaDO2{?bo(S4jq$=t?KQ5TbET4=EvXOR631lkUEG2OhZw2C^EgOv&RZ@ z^kuf`%iiMJoY;n>?NF}ogp2A0-G8Yg*^K8!@$tZi>6Jrmua|B4mzAr;mm6bvn%OwC za4*^yiz03p_HQT12~v8OO8H_#EEKW*OxOV>^h`uk!#1W@x$%>GjXYAkXcGMeTUCJL z-&C$b@5nA1V^fq-)=43Kc@^`(>s)M`I{d}@C9yjS*gHO?oB_n&0SreO?e$FVx&rnI z16s*UIHhC`kwnY(qLUQf-__dZXoc?F#C&2Pa#@HSHfEmF#ME+;yN(3%@$mP`^?YV+ zP_=5RB7K<&w~<88urT&@wNF2bJ|HA=n8-|9%t8~grW5rbsa2<<f>#F7PUN4*#dP(& z`M!kkYeMh2qo+*K%wD08h!D~wCchr_fdv=eMAeAZzW0~=nacm(6hV}1O%Cm<{PC}s zrvP}(0penmM65PL_t8k7u!v?XvX6+FXJOb(OtEGA71e|;E_X7(PwuixsxR%V`IiQX zW+Q5<Te=P3oo=p0NyaGnAnOO9#mh*4tAs~Ic@NY-T+8;p?w21o+|TT8Cr4t2n&1WW z!p`bwSf8NS(GamhQa2Xym=(X_-g<<yky7+*Q0$A`G7d{uPWrQ!cpMQ~3LyM!5#4ms zgiF%OK-@VObemQ;r8`7Jy&6}YEVTHs(H5cdB_<&0dG8kLaM-7PyE@BsWAn*7H_ml_ zV({;b#XM$Hk1ZrEj$!@~Mq3_)cr^rT%aiNz+;0#XjmJErVR*tw4+|6Q&yBR`!g#{^ zcKkb>{Ymq-2)8KoV;uBGVfch;L|WfCkwErxp+@;&xDb$nPfzzo==!Dpme&|Aq)cXn z&4+erxS%^9pcM*{+lHv$c+5*5=u;Lsnu*ACBj55N-z0=~u%o=?!&=la<zv*h1Mf6^ zNYRT!&63^fWrTc&Ng)ToRJd9H{@l5*Fjz^R+TDb#CL#_V!?Yw(+54wr)G>o}%#Z!F zxoXk^EMykZ3~HVTZ^Ka8&8Fw>Ub;g1LXSyrU@5quT<)WMp9Pnsk45)cwXk7s_3yue zS=kS;Y}>efK4^-<Xk^z^);4lV8PTtdwsni+l#P9DgO?zH7-Hqnt@dwMrmw7o)Zg#z zVPl+dU=9;CiEAI!M`n37&AyGgUW{e4zqw)oYvtJ~#&iz^-pzi<qKE1}{0`#z&VvOk z@!zcjZLgfib^vhP<%i#GN#E%(H(L^dXU^{Y+@$Gu$A=CbM0@95w~)(lF2XsP^igFK zV<tUk&)LIFn0`;x=jUxsJa^?`NIl{K8wQ_9^+f|-(F?ZN4^ucdI?yDQ?sj0jo$G$6 zHT{GxU!)xe_cIryMxp_(qso2mOiAS=C9S>*67NnjeuynS4|!k<dCkU*uz$3MHnO=y z6CPW2erXu;)f~1ktUOCTUP_S$Tv;HVfgk-$Wbfvp)UCYHfr2jp(Erj6Zh^jN@hLe2 zd*LA@JrKr22lWH|Weh|QZdGb-!L5sX&WD}OaD#6l>-R9tS^{h~a%vA*#zdaL0)-6J zboBCEXd%x9_SoAf5Bk#1aRCGexiY|?$v{28eRoxyu7a?$KDe>n>z&UFAUTbQI{Ifj zX~uyd+rL)W*4nu-(cdEFsHyYmb*3m^2K*ZvIl^8Y2DgPr&RO1irX-!#!$uVNBY6Cr z8@dvC%ik?Jqgs>^WjN&Uz`T^x_h%V_EL&8+DQXfM18ra9Gi$t)`E;S+*X4iiyhH(K zVSx437tv|&8)}eb><40|oN6`y?Pn`gjNB`8n8@UYHmUagCMpKU7&yLpnitde63Z^G zO2NpT7o#YT{mSCVzCkdRlVGtyTbjIo0$<IE{<9_5vSz^_63Y1b8Y8=GS|f43I=pdP z>)>D5(%<Zp=;RYSvi1es?FlODQ`f7V6WMt=?r$nj?C$>+3o!X@Id<z~k7Shzs2~>F zm$M76z*M}eRdzweC?^d*+Jm<wdi4JN!GQ^&IkLYNuUT?N2HF80JPS_(qyEoEj$`XT z=GkI$_kng_-Q;WkuaU#4_c`xm`UAbfS@owU1OAhT<r+Eok#Il?xKRj7{NejQMh?Gn zo4$Nwp7<V#fAg@8eNJ8-n2e^op|_H?{)3y{eS05@D{guS)FunbukOn==vbE4Pb2)C z30akrOrr?jlrf|<t~#cf|91Ldo|&~3;+ol%l71yqKi%Tc$)E=^0y^Na64!};akJAK zk8qkm>n#CN?qyv4$Lgp91|P;!oBTg)N$ISWu2s);mDzLzig>;=jmj3NcwM@7oqWGC z(;zb=uP%@8_js)EvZ%_VvM<S>%B(qods35#oxDVqIhs>S&<C^P+C5PRW^?<5fHUKf zPq40#4(ONjv4>K#%=eIIyalh_0)6FTP29!h8*{ZB%Jr6Y<Xpt<a0=u&XMj#g2u}1Y zH#l(p*=22Unc!JEYp=$v<G>3C)ss(6wjSZ!qLWo(b#a?|^`GgguZ&JK_I9T~wv}^{ zw4+>}jWuAtMiNm_ekky$+g#wX=08f|4J68q>wQN<H6W=w!h!~;wJ>_8IEAico+xEQ zU^g#C_ekFB;;M{IT_NL#Mf$ZN%pxvsc3bgCOK@#Glz3DkOg8pnpt#yCbF*5b){`Zd zJw*c&%^`p##8_?EoO)<PMip$~l%TWaf1}+^{u+~TPY8U!U;KcKLxQ8Rs{F*g#$)SU zoOj|%eNJ#*XnRMK<I}OiXfV!PXGH5c<GJ$vGgIcxi-N?vamQNA?q(c{I^w^kSAC7y zn|jS$&F+UcBM)s-J)_%kFUG2+;!b|wD@OL1eQdLmvz<fG`(Kiz?rFI63j@lgi3dCd zS?ij>tKpR1EPT?KSQ*f+<*xI!W<hi<UeGoe{_cfKPUaKl1Vw?bmUAhC@?)QCnYhEF zvRLMDqGh$;W54^AYxgk;27zYgIt?Evb??`2E#@R7fE6_#HoTHG!QHo=)MTSy9fu}d zRI0OZZyVg>KXt?8*AtJf*pi}z^QJ|j#a(BvK77@felW^&Fv{~mQ40nW;5B^z$K;eQ zKE~gB{Nz#RV{SuAMQh_vry?DnAHJw{|0~s?wBfEbRgkD1=KS^LYxto4tI*I#@BAth z|M_+-Z{*Fp?Q*~3MX?1)_vEwRF~#d*Y62G;ca?XoKUJiDDab5-URtEIw)OYIk`Z9B z8KSl)aA;42DPJfSx`(XBGtzR84&Ai{Sspz6#p}=$!B&RBsv3WR6&Lt8(A#PBI`&vK zaeypeGbIa3sup_dE<0k#1)>*pBuwN&k1E-qyj`%&NL^p)&vw|AwF~J<a#WqqS$yf- z3zW=Y7|d*DJwv^XG!(6{Ki6LLI+TCqo=U{Qor_2JRM0+BgAwBOHpu=BJ%I2{pxg4B z@FVqh^|L=Ihf42ao3EinKB~m{frzIKNgWrK+!e^mNGw7@o5^T-=wOwLzFNUw(0d~8 zNMyIl@js}O))j$!B@nsnd82(>{ZVnQ2Nf>3bc;ooKQBI≻i^NutG+_$cQ)bo83; z(K*4W%f1l@1IFJ;3)&OkgJkwz|HNE6SV{ELnRQI-!gI{x=$|<LPB_Hi<yE`NfFoh~ z*0qa$zcrlVn!S2!+l@ZVg>~8NQze`oH~&z`dL?(pa$c+CX`C+MaJpGn!Fk_Np#!{4 zT0A21KTYBqZy&z#<b1FAro_@f)1pGqu#UW*^XPlsNVjZ>;nchA8T8>NH_~+Z3^ep5 zMCyq*+<i3QP#z}6^A8vgU@3SX9>rjytkg6?;p_ROkNztv0(lZK_yry%(z1O#oENWI zn{1YCv3wZtA-nIWV!iQLpc%j`$&Dms-SWQm!$SYy2Z4h9&3aP#TkRKA9q4aPT`6>m z8aLjbgeQ^jN+~8NI-wJh!G)cNeFctKA04?C?EekJ2k+vf%B9c;XFG%dJpB&0fe<@Q z68xrZdX;2BPnZGA0WgE}u#Zt9W(k!a!v|!?JosBO!f}ymFl(z@*J~wu9Sfoq?QJZT z+D$?PLq!bLE#4D8qsis->QMU^`;r2yBWqgruf9&2hQ(hVWw5IsKKT+V{$xx>gtGvN z(G9;tRiASN6@7APJ6h~r@gBJdbWq5XR$&{D3^+9U{dvnG^#tt$)&ZS<U+!Cy79h2J z`TsQg$HF}qLS%hZs2X4EqHoAOt;9+v^i=<h(Qo?Mvf}e7t=ALtW#_%t4)|wQpsU^N z<JN|`#g7*vgRx>ANk%`m7G2bX<0Mb6H)u*n$K2(3N2!%wY?D-YtVx{YPMoSbjIBRj z1y{iT@tbW%)Tkyl>V{|I411p+^t?<gi3!@!!F`5>5&ItuH=!La8tSju&0ki~s2bg` zPoZAeQIP;}8Ycq2dd6V;=-$bvxq5)g)WfMRTF16zjt0EK`%gQmM_hjwzdqnw)0|UR z?9gz%z0&gs(iL;(F4}iBF7MDUtCOBOZ;GANB3M~5s$#FZpIdjiG-$hiVXBQvlc0~r zvQkG9)taG`ARu2L`XOa=Y|PH{u)kg5HR!Y9d4{x+P4CzHInJ%gF61l0D{<bjTf!U` zCAp`MA#f&Jpv|eIRJLWzWA$z)n>AQ4AGMz&z_}<IMH{%Po&AV*YV^Rap(1sBP~t8| zO7q*0hYh@i9R{3{iaT_y=2-N8n^Q9qoPl4|(TnAt*sVU<e_~FYO`CuC%BtTjR3n7t zVHK=<_><~le&VrG3`k9Lel!?#GR`v71Mywz)cIOJ{biVrtk{BXPgP}3pxBLSUf`a- zaXP8x)>o<43ClAm6|`NnjAUNw@fX*{MM}M2XNHQA)jN709sQN<(6IVeqf7Q>GqM5W z*Z?u|Y}(v=`hiT|S71w(uSE(QJm<Dke*Kvdf0gW}K6Bu0#*Ue8b97*O!0&Kz6}gdE z5#Pq-p@Q3e7ihsW@7E1MW-6yM)G*t<X`Ec{-yoiWmoLPJ|NeRk-D;q!&lB^Ie79T2 zZuv)*tN$>TPmnjOd@vxcKi~oB%rx`t+Tx5D-RIkZ=m7)OYv~0SWJOmS=c+d<9}DVX z`GB__YJYyVeBD^J-t%k*>uo@pCo88bH6TJX-am~TSw#B;<)TZ2%~Ae#epP^W8nPS- zGXv$F1l#<E(US}3Wohj9O*QHeJwwF+Lk&I$n(7j5@2GZNQ^cST$ljJJBZ+cNE%fHq zzOY^J$xp}(RwJerS&xP2(a$`Te;4Kx`KS<bc&k8aOS|0jB`f^G!JROM1U1N~G^iSn z8G`wS)8vuK@$Xw|4f$^rhH586ID%xDZmMFq$NQ5~2p?rCLI4)nR9b1PefBlK9zHhM z<z1>IzrdgOZR#!W;?C!6R7hN}xu_KJTpg5mROw;T`(&SUIwy4v<q-GP$s~eK4x18w zU)Mwl(O!`+_q(pB@K{K-&UJ^X3>sF)mNJl|)yfM$sU=eL<02s~Y;FsB-xL&#)d?JE zQ;ldU?AEf8iWtOE&L<tGFX$z*Vq5O&m#fzsS-h`cwA@#Uun>dXBj&vE(R=hd8pi`% zF@+ikhd(}LkPWClB7&T&%X&RKA^=Ste}f{z3z0!+hUfFYg6fQomVnp%-f;y1E~vYm zAV3*P|J0~|3gUCJQ#mZ0L#GJ^xRWW7bq4Y9y_UxCR(@Lts)kEjU{YO@y4FzKnRvd& zOTt~rK9O%=P%b9pW|eU-7e>~FEeLjkBfB!`Q5J-diV&lig?y3Vm%+&HEU~gq+H1PH zaTM#sI16O?z_=Lq<`fZ5esJpXkEZXPi1glWzM+bsPV!{}+HS&#c<^GuW><w*-FoH8 zuhsA1k1wfSKK{0)GV}SRb%f@bL6o67*vPI&rME|(T%NmisZ{x`0~>6dL`k%SzY>1m zo{M;-9P_QEJA&Ek-)+!~M4T1^d$W227<D9OZ;DV~O*O>0v#1<od_hPtBVOq4kM@!J z@EZiG0U^}WHlH*8fHwTORBxy+<a2~}5!jR_bRGV_)uHcOtA1}MIS7bau#@R0bM=t= zi^37tkkoq{Ayr9Yk+=`cZvrxZJ`}^wk_wBi0_jfn@HMNe>t0a0yk4+r;(~|C3r7DI z5<yFgO(%wNKm)~Nx<C`<XRBm|KaB6(K#o}1p;<_>Dtx+?28tTU#5FE;r>JkDGE%N? zboZgYoUgsy6ik4AF{NB2fWOfDBTcDja;c!2S(3}~7rxc+<m+a2LIV$C5(fq(_w$3y z5vsqbD2<Gc<S1^gK2b;M#m`H<#`*`rmqRyD%b%;Ol-~RZ#|PP#$h^5$>?7)CJ8<pU zN7sv`oSo7^6%hmh3oDljH3K3z8wCr!gTczslh5^$-k%a(s191-0I`^xhM=;oqmx4h z;j%ChWZMNb{?AL4nqT{VcT$cH7N>cXY4QQ#p64Y)hq4KXUOu7=A);O^Y)8f*RQ(ue z@VzN2;-f3HT?_WJIqeloW&P~Sz#0QWo=9sr(w|uwtSr?kP}byH<N>=%vi)S#WyaP~ zf({oXEK#4}xxHzy5g*ZYgYR9-&7$n*i;}QHR@G2ie4O^E7Z?#~^x}#4=+l7PVC~y- zaW{j<pdQL503%c<DO9p~m}D4wpSy9e@X7REV~~YHhv99GA}z>$j2b#dOBf5w8{>rS zLY`i^EfjZC+Y{-j9;OYaXkuv>213kyAp3-18n^?QmS+yc4kJC26-sa26Q+9kmQc7Y zPAnz;ySd#)=v}c;&4G}tzK|@ni5xu(O&~OF*gXA<xiuj_ykRU(Lxv6<&sCuL0YrTo zuPP1d004G(q5};T?wyN1b*12i8nmQrBqgdOJWnw54&`cRNbtWkONvtxl}ly5TeJKR zK4}TlEm#@PxCyahhWgVW?{+7-^POi*s+Ro3zYyryxXl=a<`#2YWimh!_JA96>@2cm zfQ)@WH`FNwDOr1XOS0a`<3a_GB!XMh=bF6FTJE58T<Vif<$P_Rris8DH^7cWYPjCl zFt@SrVMzKL@V{g#o!Y4f?fD*RL$mOZ9}^`(K{e*ol^a0=Q4iE9Q`LfR#gFd!e5q1O zs0tuFV1?dgg`Q_vb%Cv#+rU=xUymnWd+t+GRWY8jU!vyvDDSP?n#&Z<E(L7O`j$ty z&+U71*-UO!6APgR4EG<(;10D4yP4XlH{jw(S?#He@PZ!%8&xH0l?ZI`O{k_an2==c z+61+vf&V5DA~$V3<YnvSlefLZ7Zh#jKGg||B2U~#_a7Hus?HDfNe&w0g1Hb|0{GE@ zvJ9_$SjvGYjj6ZduqR-I=bQdxSEfVO_6LtqICmC8H0f4eh12(x8)>^Xs@;T=hU?E6 z(OTzw$@DQF4a$G=uou?N?cK-j<3jy6ppUTEWh7oSn?5(#d=UZ@=(`r#A^%POb4w5b zV%o{~3{Qo%Lw@Sjc)|oc#x5*aRA0Cr9v@DN-rVOXHhUrQ#rg8@mhIoIMjS5$gB~bf zxTk)?z|Fxxn&!q3Y*`SB7N8Vt&3G*~|LmDn_ye(IKwM}L@1)b$Rw)mOFFk=UH&H4` z6#8gU%pBriUoCpU=(%8x;5l`&RUpbO`MYnl7>!5>P!Dw?Kp!g8UDvK(RE3EbIa)*F z{ocOtYEG&On+tVXpjc03AgEpdgrj%-yW7H5in5bqq2tl!?-v9dqUMVK-lb8m#O}bj z`D18&V2QKLqK!M*+Eztzztf2pF|dlzDI+J}(=Ii*do)}<c|pvc=;&J$C#bS?YC6e? z0$T#0PO4!(SBkt;ZTZ@nZ}L7?DN<>NAl7V<0b{yzz}h)($xDM4%_HUzJ)4^`|HkRZ z+b2J&C_nJGAYRr`b9ZuJXV^u8vkxWdF4k4&a1se`&-=J1C?M{}*`mu2sa~jgP$B^@ z05NbU`!T6@g?jtG*$J=Z<APrV6Tb&-M%@uz89co5@wD5WIhQBrL9!a5SL8!FCMeFV zgbRVRH!hfpnyc}bCz~EGaDprda_!T!-ETI9d>SqgmxV8Orj$UyCNxb`<$O+u*z*s^ zBX(#6YPJ0nJk)D|?*=QOg*5hffD&=X)}3uf=Xn|F-HE*W&-%lE8g)ifiMQRGrXik$ z$+dBtg^)TusO!R)nFd>0z)|Ej)I4-mC+-MVe0kG}4SDKb@$ftJ1sneK_7dYuP!hzO zM)|sb;`|s`vH9z)h{u-&8@9BE+gRw%Es7bFZ)?}Vi%#`nOwXU=7NDFW{T3RxFCV`` z+aEL6wnqu{{ko8D&8<aeHT;|9wNbWuf6gl7JJ=%$n`Zww^UbgPU9dd>&MNz?SslW^ z`sLjl>NA{m<`>8qbndg{i+)vo&4vf#XZ~5KdOacXj!jFa%=At98&alrC(r-=?TdwZ zF`@Xszt3YnH@AiM-h>p82-hfMk2Y*PlWyO?`}>n;nRmG7Si*Rq*z+p>Re^#rSGq76 z@TNA5Y3%VE@P$no^BZ5ad(<m`Iq;f!)VNp0%QlFTNrC&*fXRq-_wgH}bi2v(>5Il^ zI@RS$H2eO@UtT_?2h&?KB->7&@%Qf4T_=40==}8Uy`Z<FYr~bSCkJ#VA6<x&I`a2} z@?XzUr2n*s_nD|8-cKj0dwrmBA+Y}s>_`Ak017;f!2jgOn2hES*nhe8rgdPDL+WXU z<=Jf!Vkccccb4ZE1Y>y&h2^sx^k_2R<HRP_LtU{4?MPnYzhygVr#+WGcU2y_2<O^m zl#>B%-ejb?=nyXJ&?N>eGR4Z&wCGatfds*{rOJ}gSGJPJ@$?xmIM~547f&C!*AwS1 zlsoVV6b#9GY*SA-YRU)Zm!&3NUfjpjE)%?h)?G@J1M2K#FJ;sV>F_Gh`FT{9at8`^ zOroW|dLC;J=D@7ITvY+>E|3Y@d&$c%Jb0fU>9w@0xuWUk+VK|QV-<yFByD)y@i5!& z9314swG5L6KT9|)cPyFLVFh7G@VDXw$CIibf0X=_uUzJLDNatf^L(vfE?iVo;#%ad zU+)w`_qiSdv|YE?pm<(D8rDPrmfqaFX`%+6ly8v}NcR?Va@jBEB*y~+!vr6P`cUJc zLia8nWAYrz@w!ICEA*=N$kWwhC;ZQ2Z2_#{1Kc<Hpa(<%>*w;3DugK9xJ!SqX6N9- z+|}+n;^*SdLipCx(<}u|VyWUer#!MK4vC9GrV0ZeyX66O8DY_QhEA6#0sK}f*cMdY zCL_5p55_)wXG;`{H`TE*J3*YW7Id+n){}_wDOh-h$OViffL!e^h{R_*i0Bo$;1NVX zebY$#e+k<%3AFfRW;>^L5Rth92Qs+}LwZ=kj@`jq^7emuf$Wy*;KNry1G-1@4`W+J zLeFy7WsF`!;)P<oK6Wc9Tuue?=;w`xA1-t`DCeZcg=-8|Kfg({iciXNK6<<Q@Q;QK z`ysgYv#2;-z=&wC2)+#Wo@bgM@h<!dxDusG1m1w?6Z5BL0)Tg}8Tt^EpG~$Qqe)=w z6)ps0cHT!Jv_WuVVCb=8V1@CKk{f(o=C9^Tet&@dENYfnbu;TkfKFvm6Cnmk67q0O z75?{y{#gb6Pl#Jeasj;ii`%E&RKgi2ge%%c6lkzkVUGvwre{V;cGL;jp50PU?(mCN z(Ml^j{0FVSoQ9L~ypGEt83uMHpXZ8yfZ~hCi$C22{c`a<5h=vPCf>0RiLf|k1K|*F zx%a_&NWS;!?)mblxXx~gg~6EvCa2hzi7&I%xs)F;2*p0zUU@d<7%aDJU3karphr&_ zh^JW?&uC`e*VYyN1B-{`keeR?VxSu<q2~Yv7?^1NtXz$ra3c%WWD_K^v%MX7!Eu5Y z?}nwiX%q|z-XiQ5xn?Hk+kMZF7jLVrhu1OsP#bwyI&{E6`v)l#WVeQ|j?6V6BzNKe z{EdIF)E)x%y=llR6x&M1%7~;f_`OF2XXPOmWxH5cZyCOq$e_z&bf-}l2m<fM+0?+_ z(_S1hto5L1EC|A*4NoNSl8CG@oO&nUSsh(ji=W{~I%nXpme#|+a>H*UbHq9f+f`fm zBh|$F5Q8r5r}yYlg0We5rDxmEMyv3OdKm2?Z9C3e2*h092_sAA;DP#1x*`t{v(wqB zOnG#wTRam_Ql_KW%-E#d=>q`M2w<1v5<$en`XU0QWYy<|f9}YDABXA!M8Nuz98iy= z?@Pu2*Q>+u4)kv8Ur1f(_zS!|PjkrU$G95;A}0d6dY>81<KFWEDk8dA<NBsU1a&gr zc%=8?yAvL5$mjTV$3xuPWNHo}|IFz484Wb~*u;)53nF;s$;9)sVoBM$uSYqu@F62# zNjeOybWeQN{VH!@O@Ypllfh6>g<@^|_d_u?1L4N`Sw`iB`e(Waqy7Hm;7~<|2F4%b zQvT%1Un$Z)*rcCOD=d2~py={`Qb+Q{kgQrmk%^k%r}QnaXpNmBQ+V8`EC~@Ay>rFa z4v>TM&Z?2F-YM2ikr>V~;g(9lz|C^Sp`!E8OEgy$2$%eZ%Tv}$U9OZ^jGk?0RIHV` zN0nI38;{mbtiAN<E3y9DJ^F5I?G+JKY74zI)*`Xaq+Kbs-`6wNes;Z_9#!ga<kEPz z#d<~3u_DdWJ>wtz)+-rn51jghCqAaEzs>{`HTCa5@8bu(VMdibFuQ~u<y0gdtn4d$ z_;hl7@+`Tk33c4frp{t&BC)!7*iCbyeEfUMw;DF#rDpeFOrTPg)J*4b^`<Otsq{?U zj97<PkM`GJZ@<;_IX-laNj0D3AKm}ayF+8{8QL?6uYPKS8u+(oYH#ar<MtOSvBLxX z>*0FM&!|_=A`s(X=<V9?E*<Jk+cs`&9WgP{_7hul=(*YH_c(Mpb=%#}PKxh+qdFys zr->VLxhusly5e}rGJ4;$zwKW|I-fvirfha}_DO$uzkk^d<11z^J=8=!X8#jmt-je+ z&-PGy5FFzq<}3Y2S@je{2CCtrBVLE41VVXZ9{KO<P+xWO9koKA;jQKz>@RFr+~S_> zKj%oV6WY}>w2>iAA+r61_LHl@=z|wq1cF@JPPWTn_Y@Nw;NukKM2|>gOF!`vT&o7+ zv5BFuu}}(=PhyscHZtTDe@YD5FFy#sBHaCnj?<NKI(Pr}X*q${AG~GwZx)Wb97KEg zfDfCXh+2gbL-C!L4@&a@PIbS=-&z+ci+!9UT#*FGF6**yxv--%x4H7R{e-I>{FLyw z&&C=0r^f^qoE_Aa#2`clI4a6f`L5Vc8dP$OyKv?5O}ty3Qm>biOd-BM+xzwO+uJ-u zW5iv_=!cyr^|c*b3q!=_#5y(D-(vzwWe+Ui4P*j;I>)P~z6Lmj?YWYDkM}0V>Lx^B zPu4V}?9^MN|6)5X>`cdaUaqdiANl8Tv#J-MG<skJjQ_~P<|cdifKN?OHKG8@e&M#1 z+wodMj7B<G(xGnVScjLRl~=*!L9u2$^!y%AOpwEi`f|lu&*^gWUxDAGrZ=FPtAj|_ zF`dS3Y^Ogsd(G+izJ*<7XpVTr1EvyTx$D?5ZFFNy&}BZcW_O6@pY53?QE8jESD5O* z_G0`&IpUvS1{XGdTD4T&P1k$WFlf{0L&5Tj*aWZOKi<EydpJa>ci<n5T00xh&fT?u zOYWMhJ*ZvP5TSRS&%WQ8>dThR*y7jNz$*v9bd<G@Ebm|CIF+P6by{fNx5b8@S>E>B z?%w-d{#e<6GI-<O!a0djTLbmwshHEE(tCW(P7iJgIGx7!6Q5}cSc1&%d>!zAGl1m6 zSlk%KA*#TyQSZDqtDwZEKk)pi9jJNJJO5Dq?Z`eM`|MT#^d{JLd)VuHp4TqXw(|%{ zgn*p@0cuGC{OVYhG5;kdyuS@qJQ`H#EU+)hD*ConmbcF?7Two@&gOQKSg3)Uj{%sj z-tD_4RW_oDcGmL9dIoAY)Vq@EGg^S191zen4D{_l7cqi9v#l}=NFpj$M%Cn{;SfJ( z{$&93Ta9X$>;0Wc+6uL+Z?e<X$NVwHL=@8gaPSVkc>BX|ZNA~}I1%nFwwVu845i8` zyDStpS(V20WpoC1J`F|MS;PigToyxr0k||FKZnbancf+z(qWHczGH1ua8S#)w8kdn zNE3;}Ks9&Lh5%Fw9_f2Kj5cbnGKYRM8dmUzxI5tgj*i@8V0@_IXOpmc9ZzIkf-4ST zA8cUCU3{mNqZPgU`@fS<?L%<GW?aaknrXA=?#+4=GlQpXzxfZL$o0~BvjMMxLTm3c zSh_6=z*!>`!-tcs9u#6YP4G?S(B%aY>R(Jh8>RKse^%Y<0SvRu3ig@D+%lvdo%J=T z`Y&XM;kymC_N4lRaz>rF_~<tlW{!oq)&VbYM?ZWT23s_bc=~vscH9*)v}iK_5+nBL zqR0b+?}j^yqfGuvuxxUSzT$%xHR4|aFgMf_PMz}l#;|$Q1Xnkp%>bASHC8>2;V)l= z{SqPV;%v=p(1YBN8UTD{VpM$SBYE^RFy`JpR1Aw=yk=Q(Gj?BctfOzlIhm(*^3iVz zWJH!_Czval^4nGp_o<3i9Kx752fkyXg$YjP22{^`{so2BKlN-vM$wNpF<Y#EA)}>z zA)aCuVKqq{0IgAoEx(z-u|;+%NBl8Jwk;2n)rfsg^`9T`=L+2_7f{A$(zQJOhu1K3 z^ru@KcYf>`db$a-1JLRU$V?F%8WeLD`Y(gm{2~Dw7LXpA#9<`8hsCD*Vl!aj+%}Z& zW^!`T$p$^EkLFn90*X%&eZ`lNVua--WQqD^iKS%iTT1Aw!W3}PD~3&EVshw_p#1L{ zPGdwrDDp3t8^s45s<lW<NSt5=yjshIHODKuA`7^fr#sp*Sq6UA5^QGeYZO0DOU?AX zJ2jANvXslhM_xOdcf%rY*BdoNM<?7yeWBlR618hDdgcrBnuB3pZ(s%i#4?MUx+49| zW2^$0Iv6I0$^RaH&kA1PLrB=B!+W|=e~vt>AX)ILqp!L;?ZJGaaj09IZku`rq7M6C zu%ks$qF+%`O40LTM7gp{5)1jm9nlZiP66p1H=~tl&;N8_)?Z*!iK)LGUt}CAaHBrs z0I>qe*t1LV?*?+tEBfFiQcF5BG97Ix#iS_!fEwhDxFf2Vh|wlw6pNe0LDT|8+`^w5 zv+VOk+2<w5SBaN1XJ5`*yqv2od)Nf=XoB1xfF-jaE&~wOM47uX!oJhjPth0ZL9t#8 zU!fz<8QU&(C8Q=K7B;zm!#_<mDrMaC^69{E>qx1}sQ#PikTY3vW>4Ln3!U^MFNhY^ z;*ebX*F^Zs#U;p-0f-|LBHsh~-3@VfN5q5|)ixobIDVDtNAryGJ?EP|$JnKHrj_Hx zFW0-DuxzO;vDANj&<QVcJqSsVLCbqxhr1PHH(g(p5dyPWh_AS8;UqE-0o}3XrIl|J zqgWyL1L9iu_I?Q@o?Sj#jHqJRY|!~P7#NkL%J*S~)QPIV?JA;Vbzth9^(u6BQ>s(q z9qeD55j?_!0in|qUl+gPpN=LMWjCFPaDrQWXIqh3^mNJm+nPa(hp3}IL4o(YAD)SV z6RbkS@<2cD${^s!kG@*uhqnMl+V?B3`=JBGQT2<cI}=qB{7;>(-5CyxE+QuEoT2hA zB+?m>7<yu>xCPR~e?7EbW`VNoj(%fE*5jNhsav3<!wOIy+4E~*f1#*AgZQmBl<3je z5lLUwvv($rVE3J_a0gyKWW8;~RkjwA#)nZ;Ow_6-s+ueH1nRk@>kRHi<2U9Xk&yKl z=mvba4?O6t8qMttI;IJdW6?0DDR7x^=X?@BmjDei<hr{H?)f5(HCljfX67&&f7Wjg z0P>;8SUhr=X``rK+u&^xGUmc5DdQHXs(b1j>#C+q!yb&F)e;l8-k`Y5xh|ys`bOf1 znv<c_`m5D&QKL{+Pn@BcZ|h?0LsJwR*CJuoaz%`qMofToxBT!;g8qdmLel3`OHkYc z<S=RrOkV@IR3W0*5NpG6wXG1z+sZ>#(py!w5e_AHPm4aW@5uPZytC_waPHuDJ%iF6 z$3%+eZv1M?6bpZ(9(r-C?RKio@Bkzyg(+zl;IV^gI2&OR=AZW_b3*rNjq95~5pVv? z$7xkXy|?`@lAh%daVhL;o0InuyJ%#WVJX7xua_dMP5-a6`|Z1m3pR%#{Jt!h&uOG+ z*ORNrJNoxJwC<8@H!-R7*sGe%rw<y;Bzi7L)xNRn4H_%h!lI`plNpZ89JW{U=MML? zy_t@M<B`$5rWk<R$Q*!H<G58P((cAUBer2J9HsFYbqw-Ed7m}lWY>d*=jx-@+%f0d zZMwEDzTL6%;rzuE(2=9n(X0OLuM_%RP3gPK3BPapwzCkGg~iAGZMoDOW3o0A?4@8x z<${dYsE&Th_Vw<_^KX&7KT$%?&?f_M^=I~C=lHp8sC)onek-PBpmI|^jn&kldZ*Vf z38`P!B7T{AnBPJ@$)@W`i4;!<FSiQVggGjelRoUk`!wfLm${i_Z~Z>6d%ZRmWyr32 z+PWz+X#i^F&O_if<MO#50kvC4blZ;H{$h9gi{p^3<1eD;k#$7BzxRp5ZFgJAYWpLc z&JKvxg+L)5t~jU1cLYdZ{QrbKohEw8ZkW3vfz%NZcsH4s=Z^RhblPW|9(Sk*9#YFh zj&ayXfaTD_?TXrBBGfTmbWDpa0_|)s)=tudx4E58y6K`vE6C2p`cD&I#4k>kBrrn{ za;XBcVl8}BxmmNX2KD!|cw8u-2e;J*@vO7oUK_xmY*Ud>KxS!9UQ>C_{0j9g8)3!a zJDBEO%=;@XC&$Ql5X`FZ7pjC8h6>n-D~CnIdfXX^wA;n|{O(4+&FUrBvu$Iuammgb z`N(t&s6d{Fa+ShEfu6NwZvXO?BKee$e_Qwo>0T~*NcY$sEB3isy+7{_3sDy^TVMLj zS;><_FXLc8J+kV}gh%8udTvXn`Ukj`KYpB-l7rxX)~3Wr#w8t%49hK<^WoG+)DJ-3 zi;wMD1$vusZ<sGCp%z#F!tS{oo;YG%yEXq+msK5^?sF_lr*{-u9>Em_KUx)--PfPX z?G4`R&r9fV(5b6a7I6Jw(is+eUH*q$;1V~*SRB|W*-YVf-{fn0jJ}vh=Eo0v{7{$o z42XRF#Vfj(*z&qCqdqjJt{M?(vMgb@61&$x+ckfEe*eHC-TnMZhV<-}u;_0uy}qwb z2}>*&zgwN&TkTa|l}njpc(301>lSrorO2U2F@^s<J;AqO)c8Ys<=^LEh2@7GOIsiQ zaa3vr8p9O|1RB3yf=u~mGp2R|`hVZYCN9Qq9{M?h|9S1*KjRAj`0ck4=Nu4K2|%1p z`td_IFz@!f&$$`UKM4=IF&j+ZqVs9_^;o3K=Yv<5jI5c%)9A?oC#esshd7JDdzjzJ zE#6X5*=-rf@+r3?KUpT9kFJvEvA;T3e(+m=YYh3_2TIPzCe-(>q5i?niY!m9E+7}; z$@{Z*o7k#{wJ-d0iN3jHu8^ha^4Di-VfR5xm%@@aawBEqVt&T&E8>abH9a#g2H=A$ zzBbFd%0nE}St{m@R@ti$$2YufR$g#06r05EGmWaq<*y$$HjjTFZGw-7ZMbG^759(T ze%*Q{{X<uM<8b55itRsdGX-pSFplrGpQLS26W%0E{b-w7h1&IeIlm0%G;hMRS?IG1 zfsM;IV+i!FA5-^tQ02QljdP=tg=4hz&q<?s=eNmu4GAxhJw~gPnyvqa9l?p)RXu$d z-1)wo^LH^lNDSO<3H{Mw5`X^DS4DjgU^d%HA|KB9-(bh)Co7<qkogsxcUL%n(l!4M z-sy|QIv%{yNoN=)iZoo=?g$%i^w2)KE^Be)$K{uI8Un$Rr%OM%FB>lYfS$U4EB|Ed z@dwpIU%FF7>UJ+VEl<7k6nn)#RC{yT_TT)N$zuFu<Bj)wcS<`)Tt=&m@7^NUpZIjO z@%A<kT1(@&{l`2m>}Wn}Umf)R+HUIH?Z=Zj9F9+OIkIx5rmY}u_uCw*z<D5Ro>wf& zV)OBw-A%rgf~&%H?k(Hk^>B7#O3)Nxq}5mG>x_Sz|9YAH)6-pZD_<I)7HwspZ(rK; zZJl_zFdEdaZ?^j~efpzCWcrOU?SCps(iV?YH>AnRI>9$SDIB==q0;rj-kt(90{|~M z*9VOxud0*`ed<@o?2G5R^#pQE)oomPh^a_w1zZW!VP2k>;<HWNe|=26|3HwdYNtBX z#-YNf<p$#F0h2Km=!J=QODb=qz^WDaYhygCy3}|OoT&qBbQr0PrY$N83=4pPfa4?s zZ6+OL+XSzYGJMBdAo<EfOPl{#F0EZgo}+PkpQG@hUQt=c;)f4gD@#1uHz8?Cs1~6N z4?>T#VbFuf$g8R^K)|5>ZATGcSdr9`7Kug<nJ`Ps=Q7>ijSn%xML*5QJB`4h#XGZS z*VOM{Hm<zsyf0wb#AifYwfE0E#rb463t#;-H#uHohUe-vNRkW7SE+9YcFw!a6<|V` z&hw$C4SWbEl{3?{>Yn5~?x|el_j$ef_Uf~?L4_2jCS>%K_f=FF<LU3*D*Mw1isj#W z6N|tZ_v(3mo~T`JTeMN*WzQTSP5wkmdk{W#M7v0TJFJy*P0lm>o6_94UaSu2xUNm4 z_U*KkjmWN9fOkyiw)N48`OF3ryF;7<EO|vWqeE9GYMfum2#2+_#SPvq4r;A2K9+m) zn%`o6)i@+8C~-6Q#j~9(<KA--J-#@%caZwFY<Z+Xx|5cQrPR&8iG`oePFhbOV&2=e z3q4yEn9qEt-lsDD627G7KA3<|Y78Kpl=AQ@5-do2fs5J6wD2=4I1t1dcdqhWmlEz6 zup0IAnodO^uLhcMI^0cMW%ON(PJ#=h77GfbrQF|X%w;}*F=x&1)N5CG(MQpH&1GQZ z(i?LCE&eXxZ`{iKclTdm5DAwpnxo|W-}#`R-71?2ZuE#^x$|D)3!CaZBw7&@|45FN z6!8=Q!a}P1Nj)m)jBXY5{5UV?zz|GddDfk3BmZq*3*L@DXppM45R9s|y$B59LIKn4 z3;)KF-exiGPlu_?j@yDysJE{FId<+FT~ez!7~!OxBfXXcJ(p`3BR`T8)<Ot9{gDm! z#2y5Ud?4}`SrLwgY&ji)t~^Kuzl`8uRKCphqCNZQM}PXGw=4D4qJJVE=HY<Cfp*o> ztSFCClsTp*ehb1|Piq*Ar7TWn(5^>^6Z-vTnj8-2L5a><Is3~N$fxa-DxBkU_D2p$ z9Mnk4cSO#L#gGr#$LV2b(m+>>6%5o8n<MTp*!wP7w!dtzI!%+i=Gu?fllk!H72))6 z<=9Ag#)tAKXKaqd2#2Mo_G=(4z~!h{=e?27x3YR~YRO)5d`vqzEH30C2$G+6wTf1p z!FYJ(NJ?6@pV;{sX(=Ca8>F3gI=VdkqEvR;g0YC;E3fC?r(YkcJSBXaJ{0W=yDM5| zs;|~Nm?IK^5RAcr6fKhT+p<1o9r1?OMZOnFT`7_pS(rW3YDc#LSORpc{(hsg(OpTx zc^9sP8CN~gkKGKXzWqVfSk=J(V~Q;}3vN2&(=DCJJ6wGBx7E$^kypP~6mG3xsTy)| zFvA_40;Ksp-B-1@!eDP6o!`yJiypz+!)67-0HS$1RQqWYpXLMb^2Kvh!O=c%+$6UB z=m8n59RtoCcoULs4@usjy`2?%m4>@(semoky?SwBXvsk@b+|vvq5PFnl2t4L{gHC( z^((b_k0BV*P3f)(nNW&Pl!+WdgQT<^S8VJwt&)Jj{gSW0E=B(w)G4(WA3sW4yR|*? zQE;@jS;+8lE`<1)LBcu?XZ~)VHvicDy>@=s+!!Cu@43e(-RM?k(HCL8l@EFaF>|@~ zqi(7N`PPhw=YLm|4DpowuM!sS|6an9`Tv!$PA(<=FEz>aLps5CK+?fx?o_mW!fRmc z(?u5jzttp5A7Vi<J2ymn1c{dbtOYNEWoQIk0o%Xne*0f)5(x(fdbkMbPNDz*l(0Jg zQ^HbARuX=!JAJ*Ct0u{iI@5cVa_?`VgdvzR*b{$|t0viUL`p#}t%|8vQ0NuTJj(>j z+P5o{)ki)$ToJ@aHu43{H)(5D{ruMX{3Pfcz2?{aK+gYNO)_;_n|Gc4?RwClS<6!x z-_M?@{wbgEJwPxK1PFr)2aZ4vi;eP1n5jz3^XqSnK=x^5g^|Uad_F?f9mm2bxYgIh zKwcC(L-&fm*i5*RF}X?q%4_*=k*EI8Y7)3W7@v3H>~ndQ8X?d%QMu*>p_>{96Rz1S z(4TL5!v&wO2g4mnPIJ14E(*#K@x1p`UpqaQFl;)M;C7IGI1wqDdkFBj_4;tKv#5kX zqPGrCI}?0}PC_cAB@LuoS>L<IdtxCL#4Ay{xPajHq_RO0E_m%=K;G|ASiYbOHq4R4 zxpz3wlb0VT2$m==!9y;`8e$=)>=_vV%iF|FKXHX5RCS*D+;|-(G2<T@ZtLm_lGv00 zSNGrwNu;<!l4M9$SvIyB?wtDF^?nKd$He?xDo7>8_4V!bEf}+Kb?F4~CHmlHK?t5s z+7E!ZyXBI(|5{0Ge;VfA(?>Kz81L9$5$O+Nbp-_p+wR!^WUeA-+B%+GW0R04lxaoX z2MW3u!bVyyPvM2V41c6QfoQoiIie^ikaNn82oeT(nt|*1k8ByNjTx-X?po~vBtBB` z<^POIwO8MBN2Pcy<^gV9p6v49qtZ%5^%s7{piT}7f8dGc&;0+WNrdfFsO`M>(pQCj zlVVQ|>UG?vrC?oH7ljz|Un(=MFQ^;`2&UZDm8FuY)3*(ai0*ybupwn`=Bm7H_`fn& z*FU=+la~%jYl8fnxoVx|<^1IRugulG|IS?L3Gq?5nX41^v`1CGrvzG$faWb~VtoV$ zT4&P_E9)J&rp0nOK;VvI4+#IgSH2D)VNdu|Ty%hILk%F%G=JU6NyMpGklULsc+7(C zQ5TtF@Zn$pZYzDvLOblHi#;EV&MVig4_F#;Lsw&&Ir4Up?Kd<0mo#m%3Uz}8<6?l8 z$2!t!c;H-vt*{XckLBoRsqniHy)7z50j@#>k!Q=tBV~Jp8}7nkiNN{l7Fmgrum?3A zb_Cj(aM!S&P#+S3r^P}(&+>H|*;x{Q1*fwUs;-vmkcNr6!M#T=%9t7PX|r3D>YLsQ zGqJ$fNrKE<tf5Xl5ilCKn7ax-bw7#}W&*Scnejlj_uKnDss74SRUNErbpj4~rYly3 z*L^H96W_}XT@jT-)pG$}qo%K7znDCm4J^!;%9yr~N#tX_ycGZCyL8b!o^z4^T1r9$ z>PFPgb@stS0kBLO0PvN*dKO<QoPP>zWOR*jKSiEgnV1A~SG&*i#UfEnfK_Iawo3RJ zIj4qE;e;F1mnU0qhX~y$P>+J2w16lBJj4MguGKWzG!7_KUgy=^F92j^e=M+nQgT#^ z_r6uOL#d(T0n~uOjScOlAkfS?gJva{qhEkpE8|SBvOfetL!LriJ$l4Jm0bN(_USm+ z!oOlSaqQg0;-NQh)FXS0<iZsb#9qt$jKfVIZV6@#IUe<13$uLGay2ytq?|u;N#^z0 z`>J8Jmn$q5t+`h`{^f+?9fz`urrt*_8gp;I8yPk(ku_u#zrOWWLNV9y<{i5W*_n#R zTFWU>%NKKVYZDEP%*^9Ton$}0diQX>GL}bM2alilNWy~-8J4-~DIXrFJ$<P7<_iBU zchUrB;t9AkfIF@0nf$u7&Yjl1bf;eWJR?yh!;Yt!eD|{Ym_`Kg6#@RHX7qhGb1Pr+ zHhoViNgJ0~L}1N8P1O-eLOxG%+HBy`20b;s`M%7^{!YG5%l!*a0Knge7tjK}M9~jv z285gG`#0e^gHKN#F*JmOvg0Gj!7{=0Xe7S5FI0>7prV8!1*0V{i3MSgnsN;+mjsr0 zSs=vAh=aG9twl-!4NXbB&JEq$=%;6z!HfUkZxFxHJ_CTFX|PV95>{H4dc)?Ig8t%l zbIGR$t%5Sgp5Zj<D`z*m2_GsFt9rj5f413Ui>^%SxICwty4mYuQkgQ^J9oNnlhfxO zU76NDOFblC*zWl-f^O3rs;4}w1~TUr#67log`9oIt9|OpOsaF0)@_+efS8GR47oXG z4u{L|J%eX2lDsT%rlS2n9}X`R4g5cZ{bgK}5B&EHAJjHrNlD5Ol~zEd#Su~>f}$cQ z64D(aDZPzO>69)R-7rGBMM41yrO}}%&942<|9Rc_`QW~<>-k=LuqVe}$LIZhztIhd zPIqMuC~zr4nu*ryFQV4%Q^@n;sV80%N<_(Re!*V8@bkc@$TJ!Q4Q7Hz=DMR}W-Qgp z7jbV?1%{R%0*n)pG@U9+;eaW?&Id)Y^#`B$^30+_492h#S1wjjGwGU6_OVH#A(9(` z`bubh<n`7oZQ*wnOzDI@yDmM^<GP)HB2#k_l6VJ0%_?Y!E(H;passG<4TD<YMj3!& z3p~51pm`})%3oca8gPH!2O@_ZViW<2IVSCgl8%Fob#5{VQO{2~3+WdveCD0v2 z^9Qes&o}-(?N@!!JefSYUnqaJsT<QgRiyK`)aY!>V61t%Vf60@pR;WfM9XZS&cEvP zvmNUPEnj9v|JApg?K;P_%&+SlG=Dw&={eT2crbd<escCJ0MWWc{t?~9)lLe2aQfz2 z`SQ#~6)t^T-HMg!3wP*c?gXa^=~F7e?bN)nH|>uM8+FW=+B_a=+1o1(ZilXo=G;rx z`&(dT7_gDY3n0~HJzI_!Tg)%fKK&!DWey)r=sRe4>L<ZmA<PL)JZE@C;M5d8g#-Pe zeuh)haY~<~A)e65wvrG1ucMqJjnP8}cQ<Z~!Syt(PQUR|N?5$)ZpNPTROx=H;^5Px zlb7dz!2w5BJT(XY6gA2I1%K))ADTeN1L=T7s<%}502b>2TE0M}2Itw+KyHJ;3mR_$ zU2l56APxuzk98o8OAzU4(87Tag^L}K4&<>$qWgp50s|OQf<m9d6=s7KHQrvw2VS-g zcB~2n6?^|Qfq%C0TL<6^B!n(|=tGFlD%y|I<N$m6-_i)dE(aT1`-kE}NaEOa66~QT zv?~^CbI3?>n)IPV$!Pc)61$5D%(p^T^@Td}g#siP#gNi1?fcW&`v)4XSB$7agDHF3 zA92J!nS|e`*ha>oQ)qA;iSd|n6OM+zhJ?rzBl8Y?MvHKdsu&AB!&?Dh8sn|20gWRu zP^=G!80aE^dx&S;Lc%B!gG}8BlJi>t=|?UK&DUUeaE|Q9M*{!#z(4>JOzXnnZGt$+ zfzB==$P{-6A!-SL&u>KO;-gNS5kwL_<wTyO3pa-#G(1D;XOVdZk+)Hy05Y^p2H6Y% zZ*o8h;`EfYimdBPqHJ&}$oZ%6U2*t>L&T~<^a%;EN)bR{aNU9^Bf*$!RCvykIKK_t zkTmif2|pZ%5J(Kp0gweW62$>$lErHE`_WJ(P~<M;am4px1d{9p@7nP1DMnuN3}ioI z@-Tp(q2bF*u>bZoBAmL)9{}iEq`j}x`%U0{==9#55#z~3cs>wI(LcE1gV;Ue?)8C2 z`@OR~1Bx#Akxby9NQiAB!@VQKA|Z-mC$QCp0YD_8D(Q@r^n3tLnK{?Ru`EIX1_H({ zM4rXuP--f~GJv2287Te*cOm#WkU*^m8<s)6^@6|TNTEyt1#ePB8j-J_*^Ybq-tr81 zY=i$yr2HHR(l~4#NJwi+RbfX>^ue4{8G<<Av+F4godJMJ23P>T(izxxg!oTu5gYZA zKIutnIvZ6&&e4BsYjBvKf#6$29BzvI4i}}C_02Q{=jENIk&-aSxV@CrX&nmdOomb= zO!UReq%s^~k_|O7;Bje6UMQBvq;&&WI%RYvP^1~Dk2z5N&$6d4_|>H#=1UMvN14B7 z-G>0ap-q1c!Q6EseEbNpfK0uFf5*5NhceBkjKKMujCJBE>*Lu9slga8=ikIMR-w4s zCi){v<!~HvX(Rb}6G~J#?u>v)%|Uc&<`o^eXG>pP#f229W0y()y<0z{Y{h^dvr<q8 z236FTN13YH#ZwINxl1;ARB23qW}<<m^j_z}TCenJD^$xS@~v!c1~FEHGl?}U&|wQj z1}7{pr58CD&LiPZ$kv%Z1W-O(>G{Y^(WZpJw6s2=XK*+Qr(Uotj-}=+>Rl?5n?ppG zGBItXk9)!2F%;htF4k!($q@E8NX;w~FMZD7SHy{GAx5sz=Tf_5KOKY?Vv-k;ezwBJ z(7l{$29#5{H^#8A-2~2NSlSX^`b@TbexRWLOW1=i<pL4~MKf>>iWP(iSEo;!5k^^Q zqPo5yj?oMoT4^7SE0#E!R?<pI1o}j|yr-T;oO@*mzH%ALN{mTfXbu|mu4FR}v7<-S zr9cNTrFW0BZ8qWkLIk)HfsA1|@hbmo>v?;#9QqY`ww?@#m-`J?Jh6$pFci?f^<mDC zaEGCqL>8#NV#l;9ko%v4gb06TQv?%v+cHzeFHgAfwd$5#iCtO^I<9hJi;>wbH`2Bg zxQCJ#L}m)rbZOQghid<A)pAUfWC~_{8OZ!Z%-QBd0fXt9+f^^Qsu@M<RZeonw$clc znUJ~Sr(De3j15u|Degn4S0cHinv}^u|7x1IA0xAWORekI`rwGVV2yX8N3n&vHRt1q zHSzo?JJhZmDkg&PB*H)8E6QD_@a6y%KUB@R>@zIftVvO9i>H~0G!+fiV=t5du?=K& z2CETD0*~rCj=gx|MITYq)Pi!iZlo;FEMKb?_{zULD+k64;#yicmy=(dAWEDGXtF%( zR2eh_$VW34eUY#Ke!=gDaOLK4rCSS=sCRLK4RkHNwJ^P%BhZU14lP+id>ATZMYXV^ zO4f<=Gvi73JX4Ojn1)T@fJu=%9;I6x&CQpaFZ-Uzm9+7d*mdviBI#Xz4m4J%^PLZh zvW(P_5dBSzxn)Ju(%3pmn#;szt}%gUr<1wL`>9qpG_`s%0!4EK)ssVBg94oC$dQ%; zzyzAtjPMr@+$-zmWiKTy^+4zHsh^|bHIa9>BQ?vBr4b2=TFp?2kNVu@bH}k6q$+Jj zrXM5(WrZLkdzaVYJ1x!QT*RCB78`A(S9xZMbH@koT6R<)WjB6J7DXKhAt~9d4x_re z;l2I}$epr^V2;K_ZWJX)L|Ju3eS2^9*C_h<7;?A1gQDgm24;L((ua|m^PpB@S9e+P zTcJ|==FZ}bL8MY!Puf6(T|eu@fFpr1H!^KI!e<@R%NyY>I5@-_SGqU^jScgfYeDrW z41KVw_ROdV((WIFj#P7Xk<ko^hIJg_D9a5{PV0!@a3j-k(ppA!f$(ULPXmw7=!f}Q z);+{DMVU@Q45kO;X3_zZ!e<H@Z|%oGd?N{*13KX~M<Rm<xPJFjn7YP0v66gk@Al08 zamjn5h=u$(`3a`Leiz+74!`WWlmeptyGrOJykhJM`9<FH=D@C~f0l6f=(F5%L*K@u zCUhq92G79BX@1ZbAIn)#?~Zrq7x>|`(L2qJWVtE6-Sjp4De>Jv1QnvHd_-;`Z096| zG8WAk)jhWV+!i@j*4&BW3Bg|IYj(c5M4DnBhEwD|BvO$$$0z9SkPmme7IcQDDe`Dz z>XnhF*YI#~YHL^dG{f>xg~+T8Pe`UVeGCw1>gQQsT5zrO121eYa%bf0(IkssP)9My zWhc$(7-7(g;A*XZe}C#s_d~vTWeYTbh24igq-Ujcw(kD)r@;afO=R`$ujIk1Z;Vx) z{f&zBS)i0Js{jHto3Rs1e*%29ZVTw=nWU(>TIm-m#@Yz@nF0R%$v=JV?Q?H;OyDo) za-e%qFS)Ox%{dfJ%_*{Wr2>U40ew32S8iVXy@jZ^DTP)+@3xMsh>Z+5Gstev&x;nj zK<N_$7Uj9-jpp73Z^8#{kQB)j<QlSSrk)|IcghDQVpP|+fTZ}4Y)Oc3;vomm{3=Ek zDI${d()SAvsE=i}`7J99%b&^4i>uCEG`S)B_fo$+MTSxCd74)bc3^zX^e3?uEuw?? z1H@+{C^MrF#Q->MGX5(Ir`@9zvQP(`=`ct56*;VuL)B05Sn?967KrnR@R>&=>(DUm z0oy9?HS3GDwL*2l&*mSG)SHuK;Pxi4&Heznc4(A1xM&HI7#nVU>KAZv<C^V<pr+!d zqe#m`NSO05O)jE?1jUU*5@NwK7-;HSrsRx9&geFb4l+~LcL<Hd<v`Mq3<+q)RJ_-T z?)SR$Ek@I93`N1T)RN^`huTAU0ifl0$kaKcOB}YnL_bALoJZq~y*GN_c0S`sBgVoR zv=Why$S=-NfCNqx2YJM91F;mv5u(nyb(t8poW+C?`SCOZ9K?ZJpMfn95Hx&HY9&Z9 z3FftgrrkpflIYu<5xa!`?Dk*WdIdjW2o`S!dV3_u$>Mwov3WUkks?XML}A%uvBo>> zm4mBV*mg2Ka1a3ZKr{A`plJm8SaHVBBrn}Yn9$jOvn_?18X#nw8~pezG<DsHX-t<P zk;G6w4vp6Z7l<>okf0qoFriaMOC&gY39@g3=nhCgYGyxp$z1FV<>!Te(*5%f8MaSB z0|KCX!2eR@iHGWR{1fT?NnO?SjqrO`Fx1PLLF8qp!r?&xnTgX69y$wKBEZPwW$Of( zDu<u$;o4utZ!w5IXk4@*9DIlOI9Siy>nI{8=J?UXK#1<L#Lr_V3AhTJUVQPm_8YUZ z4t=9jU&|P?@(0H2A67fBvv#C(6~650d&yexpvU&xsjey3)?|1o=VUU5IoEi3hMav? z>3@RUJp1<G`^t6JwWyPcm*>)Ya7)icV&(a@xKlC-(t#k$^L?kp+U6e+|M8Lms-NF( z$TXiv(EtddG8V?87{ac%q8iRBX55pax2hJ+bNhdlur%VY+<zM)Krl?VA`^uaI3BHO zr`>W`>`8sJKAIv#uCPCfU)QCmN&YKg3F&2vlof<D{oiVmExn~0sRyB!bX@;SO`;cl za`50nMvmUd|CF%aQ}^9A`;_$4xZUsUJQGqm-|@m;uz+Wsjbzpv#q&VyV3+sGt<UFv z_YMsxYLZN!_h$zidS5ED{!^2DF@1CkCsBswF_JRRrX|CYf{Q%=IWD$UO?xm;9XPLi zOqjOZeAwW!Hj)`*Ke#6JbDdJc8iUMlcl?-b^Y@STs4yn|7?Hl9G54kO=lVj2x)_q_ zau0dwTc5w-@6#druj^oOOw(n?sP;)(Rq@V-CC#0p>E{o{mFc^gv?ZNMUw-7!OMllD z27Q_gjZ&wjE>dBBP;QqaHSZbTN!AUK=&hM-z7lOT>3v^~=M7Y|y5)CsIrl}}Wyw5H znU`+UrQ}ykms-$Nl6_Z;L?04rJ#1D{we4PUTG!?GQCdT^+rRJK;Md>mOdNf6Lv3%# zQ)^IaeO|n6@R~@1&h0V&KfLF&UvKEr(oruVj=!_qBu^X|$d{|$<qbuM6-|fKPX5_x zNw{}U`b;P1&hw#!M|xHXV?<r`yR5f7|J}It_$kilwWKoIw{CjDU}*Tsiz3^iOq}<w zX2Azwq0S&LAk><hZ^-mXe{8Ieu!MQh?fT5O$5c7o<C80F>Q=JHu_C{Vue>R;`?%?m zs^=)XcEL1c`7W0u&%%a4eWIxJ%e1A<TMZtQU)GWogQ&2a?i)&;7kzd%RW4A!dk1-j zrG3cXovia&+C0)ENIk=?kbaHTmQ+>n)v>4(m-cj$?`lSEv73fjwxA7*d6ZL@Mn>p| z%(d*-4>{C$9S>~OGh7;}z!`pkMntAhTJF`Ptd6KAawg)nUhtEQ2GGD$plf+8+fd4s za?{*yv!3DRdZUlKu5wqM+iB7a#N+-}vy9i1U{O5NSsK<Y`2l=TJY%;m)qCMur)&}5 zt4fFBY}c-TI3AOqdsj33PF-4g2ByR{47=3(HoiD_ZLYJJkM8xRxB1txInH@y$#XuL zI_l$Us}%b(mZk~Lx|BJyxSl=KHn;B3E+6CT;eWj8#bcs_O5*}n{v{}e1g$Gx`qXWS zO^nf7H!=f;vtKyXGzG3_`vjomHh1cNwx5UgdY!xbsR|h#g$}EK+wqu=aSOT6o1vj* zc$jzN#3d#WI&gp1*A(ix!!I2xpFPtGZoqAfkOQiVKMJud$Ge#j0_U0Izbtja^)~We z|J=YG$(hMbovE<79roQEw(MeF9On6H($7b5x$WuM?VWF;R&T=I?Qu%r)0xufJ6DR- zr}TBmOKSAVGb&L^DAqiHC<6xruk%-Uk7d9|-hWl3s9pG%%@`G~;_pHSV<V<qSC#)2 zcKGKj^PG>rxbwELSE{<ocnrd=;Jp?hV)-GOvo)`Z;(;*FsN^l$#wluaMmsm^#QsFT z;`?Kb8awNTaSWR6MJjb-2Cv0?KJVuvsS@2zgE=yYW@zx7svhU$CF{9Ru4`^G^u`hq zAAGOWJqZlAPmQ*zGsxs0>KigXW(r4;Wi_7Cs&ua$T?(8hB=IE3mfAT6BcF6XxfAIL z*AZXkT^?UyE_<dC)^Bz5x<rOtcP^s3?FRP>w}5QuKI3sBjU%OrC$t~eN_p28{wH5R zsxKE*D|k8ECIo!v@5I3TDI#8qu{gOEL~nYk;^FoPCp3!JY`@L&e)<)^;YB5Skk^#^ z`Z(@R{4%3wKtdSb-Op$$Qk1I3Rq16QVEi;ieo<+%;JVoN^=Q*<xN*E+WY2pxDh7R} z3KY<#(Q~KAMXZiBhULg)>wysU<2O)Cv3+w0?5GM+&FbQ0^kXaQtzf=+q$T$q{q%8- zz!uEP<E%d{8cOF%b<iz|H|r*S<g5Q&G;b+ORt7QIzT8#m*8W|YaKA!>i|5ObKR3S} zc*|&qSorBt%4&*HYk5{qW3Ruc`4jUiIYTLY;m?0NUwR;R*$}PtY4^n+Z|C5m@wNVT zn_jjW2RfqU1;$xJY-NLO6vX*%7{{$d_gVs%$r`*L?oXJ?8?{Kd_gW2aaXF;?^Od{T zD&C>+3_Y;s{%Pe%pT&@zkInO>%hnU=#!_25sCPS$<#nuv4yircIZFyLU!1v;J$|++ z-=H%z3R|G^FNp$u$mjZOdGDQTurF7bI3*g+c%>_`19zgXs2Vr%hO@r=?w11X<h>ZC zw<8uav$Sjvpv%TuGAciiyKh#>;qztFm&&Bt_o5;6qGlN7Fh*H*Go3i7zf4N^zC~Wh z9`-xlFeT}1R{g3JXTM;!O){{t{f^3{#~<I7x%L;&4E_@#)tH}5;J2eAS3MG4{7g~Z zF>xIoLx6zpD8}>a>0Dn?4Gf<q-cS7!{6k+a_w893PVHulDwmb|b=t{RIugJ9<dZss z;{wZz5;ult<y3HKnt7J)C4R$8+sABO@BX>n>SPQcp7VF#Wg%3Ag>0+cF>HV(-Av@C z-nlo%?9rBHq^Lir`%=V6ZFu@tzKd*>b@1_}skeWvd95Cs`=og-p4anf?(U3M2TzX_ zxR(WwO#4obCzWj2G%fQukp*n0CuUdj1R-TxzS~`&?db|;9EES{l&fU+b9+Xzy!hfH zXGGvk%B<y+WH)Y<`-H3$vS_h^ief*_b9@`WX2&({;u#gwm*lR|(>j|#el~DNVP5fu z#4~ayx0-`$Kfi~lS;l!Vvo%lkC|SZZD`xu3wcF3f$~|MT;qx1$0SN%!YTyVzPKW-& z`^EUqCOaPYDS=4aSI_>^?>^K3EAq0`jD#^%Pi-Ugd_McYCnB=)JWKk))qD33V1G-w z0F4mI#=HaezT~ejr!|%`>0DORe)3wJ_DzoNz3KhdM~r_!Qr-|{uprWm@lGgw)oXtx z=d{A9;Ap*R{xg~>ioB5Qu0wa@Iq&O=6xUsN;8wHz5yG7P&!^@XB%jZn$HxDJqsVNM zUv4=0c9MOwwlD78vYc;zrE*8<4h#O**I6l}_l8T{VYgLt<cQUB3oEkH9YN!~oCE&x z&8au(bi6yF@Ey2-#%iN0a)zy^G_kyfl{~@eytZ7qbF{^u+9L^-Uk@vOCCI!EmuUZ5 zJZOfYI^qk7{V-tm{*zGFD-F=cZ7IrU;>|?A-)qRZC+H`0W0tcML<@Yq#OImQ>I;#) zIe0rd7K);PCg@i9J~oSr)4!R>;~R6AUml)T<7~pm?Rz^K!>E548f{pX{JX(aJWv0V zl2B`mW}5KjZZuiPN7+-jV}~936Vh#a>GJ60WvWP(o4yEvOM)M|bGG@rw=dm>1f|H) zzBd+D2&ZYH``-O0;JwOH{DbOtCeG{8a@}bJ730zl+V9xgzN&vP9h6kp*1hz?Kl~p> zRHHT8XH(N(L#q8qEy;{`e=Uh<$>3Zy#487+ZZs=o&Z_1-Dtd5}?#;uj$K@Xvk;0xP zmHv$?9;+dC;_2%u^x}5>$`9KJLTdBfjj#5j=L{j6)og+*#cM;ty5;ypcAV3A;`l>V zW63%~n3`Fhn$t~$$urQiW06<%ciL}sKc2$=9mjgOtLsT-RJ!oEapSye)qkNc=Ld!G z+!MDi=_tBaMt<yzb+8V#62v();!WIfq+t0|yZ-Ijf;MVE%T>*EM>XjWcKg{!o*Ohm zhd2jPe~@qA_E$0G{EzXz(Sg;~_w2e6&xKZo@H~%#fy1D*R?Q51euaI}nK`cEKbq^v zQYTN^0bRb7oVul8<<fjeJ~RNBr7k>;xguKMNu9sFTv^%!U%WRUVRY%yrwS%!rAXjX z757l}JV;f7m~pe!znEC-dQa~aWLFmVVlZQ+Q`SAPgLiVM?GzWd!=z`J#p<q^vNO;n z8qK7wIdF25ou+N5rb;S&xQdo08Qs5QmS;8J^4?cz)E(Y##wppIGi}pQDSBT@Zlo$P z$ckNqtm-~87(Ak#cz;D^Ak^e~S%gfczR+))dz?F+{u+Z-&;SWtnj4KMhuJLH{1x_u zsvE-1t2Z^V2BG5NjasjUdqm1d>>*Y9Gy;%-ZcnU*0oK-Fr0-M*p^rOc=$ySgwkC*E zMuO44HI;liSY<Y@gn=oA|6Q|rOsUyeYh8(yF&&m#jQ`jI9p4f}#oJa%P4&uiNpksM zkA1OG+JOLjs6*p}pFIP<U&hBDan&jHB5uRba@ZVN<yV2VlKa?;-FOzdfF~Ov4kp0> zDJakrz3l#xeN~tH^#h(CFlnt2E#+!PS3yqsGV1u2h+?e8Z0HN;<d^J2=9K53WK*x; z?t?v1Wf6yHJEnN(>%1mYuny(xBk>N!59|ma<6^ABc!-N9$j;=`w7!@StW7NO(Hi?* zEHP@flZ`(JS7DxApNM~b3UYXcjW+~&?A<$yl(8BF56Slm`{~aK#;J@y^t>#^S);MW zB-=^An*UEiXF~@%a+8xT;E~uMmqW(myE@WAA8Z3c91d|;n(vEFeOji`6)3^7EPy7C zG^D5>4Dn0drWP{46_q9jQikwT<<(T&i?rcs;-I}j(k~(3)NyW`)KjLD418~v{`j>Y z-sy3J;0XBnmTq6-%mPMJA46BQa)I+NR$&4BHsx+ce-S|wlyvfu9OwWy;fT~TpsRYA zofkhV(ly=GLeHRDcBN)^edEHLLmGQXTS>mU+Ky1u&_p;o-|Pn6yzJaBB$I;%ZBj)O zsjEw0Fddf}mR6@aHu&t94BnrBRX0G)FQtnHgDu%LM~1_!h6=Rr8J0o$0p01pDfc`L zm0rs9rPe|GX(Y4e4Ogx6ZgD*Qv6RuRlp(?ZPOhM@X5g|m<9VSxt!HRt0nPI_D0Fy; zx6%LL6#wk;XNZ}roQ-}K!-<iFeO{-y!OxWL`QqDewy+-_%|`$aUfO5a%~kei&S<OP zuWx~2RH9P@-6^koy7a_GHu+yW-=5=mG5I$tMQ-vA5gIIajr{K!?!H{##uUDbCcuv( zOP%Ku2zorv6D=hiS6GL=a)R`L5VOqg#p$*a^fI3Z<<hjhSPzY=e@tKGaFtAabdHj| zzYF1fr{4GZ66vqeUS^ciactoW2p?Zr@=}qLYg25_1Ut<_PwgjC!M9m!quN;G>aXc3 zpTXr_f-P6tjF<U!3}mi$)zT<FDbrh0FUDTE$IqyhK~Q4+ciX5@D93-cdYefK_SRVH z7-=v5(q=%;laTqkpU<x%jcQWvr8q9&Z-=DY^88sYLT~!%-|46OT6DvZx6t(dYU!EH z8R$i`OV?I9$3e>0baEM5I_5Y_YixW;&V}c?WvPQ%rhH@%V%uBI*@TR5!dDI0FEIlq zSJBE4yUh~AL7WMZdxg)uG7Oz;iql44f531hJ9u^Saf7R1+!GUs`?6_rRi-s0J(>z^ zIcFNIe8CZq)z$z5XlZEm3qGCiGK!kD<5>PEBl|h7xBZtq@L1iP?~WWerV<MmByL4B z!axdi>u0JM=a0)G79!Wg6R7h-#c{kV(F|RWz6R3WCWe+srq;@UEXRY5-wLD*)av#2 znqFN~3QB$FaML@3-IIi~!PEH?xZGoDjMzgJC{7y#D_?8nOLy5~_bu-_KH4bF=W|Vb zE28Tt3pOKyts8N^1UjSG*5uS)zgy#eZ&!V#VC3EEPX#uRkXRmnQ#R+>c^gGYuO_e4 zV=hx}i?Ao(g=#o6!@@tNY3cQ%E#@wnIS4~9+4Q3p@KT$5yH`?#LKb07Q}Wj?e!1)9 zm%rb%nQ?9@&&p&bNUQEqyibL8Yss;Z+<KsFJD0OzrwXxp1_}i(iHNSg;mYY$`CgVZ zuW~UGy95S^6*Kpnva{~gEShNj$YuOk=5w*2G0D#Cr}P^P#Lbp2bbJjj&MTeO*7kP! zjN7VVoI}2vfAr6lo~#+;G;_fDar3aixupHw0<!^~EvdWs&CnWhXG7Pud=)8^v1yxX zP|{_4NGF%=TFA!KliklryVU1NswP9mFB(YOsSX(*90qRndyFSJ(*hP6V$xW<3yh8w zmQ2dx70{1W#?VPC<5d-2RleU{>)l%ad8JKgoPRg?k3J;XB<T*n#m{N06mP8^A+SE0 zR^yP)GV{Xa7Kgv}aMNq~ib54fXo?^j`<H-t`|;N(^n>g?*4!XeB_M<h3Sbm-);M+C z$t_J64S|fslv}<kwS_EPOvGyZfD|P|CP1f#cyFRJ{ZR<k8Jnf)0?#eg^V<W2z!6z{ z8n$IF<9j$F9k3K)(&&<bemaK4UIYUa2hvN-PxLo>Qv;|#G7XS}{cPfTnu4n=%@=+e zdyW48P<FrpB(Ov^^Z$hab2=aYKlRB3{vrE|O(KKjqKkz;(-G78siQ(NH2*(+vKp(q zMg_D_sKsfBXrREpfMwQf37-AG`(&TXxZOm{Lwa-Ab7`%1HuPvP(R>D<N?#292LaM< zZm<i!x;&gj8v|Fkq?)VU7(l~F>61AtsTjHv0fM?obT#mt18PfOs8oTyVYfKk<ksKr zMy2oquX3|<lFn`iv)xp;Jwv#)8sH+iYyd>iCH+L@sllh{Ee!GZTO0RQZB!6FRKBwR z?-1Zvd)vtYX?3XRnz`a#dKN%~FxGMB<ia^!F%K08VxY^M$zHq^1eMxY3P!34=K5!A zTQ8d+cchV27d$rjo`9@#mMMrFX*o==u$Te?)>Haq;=TXBAV9BNEDXiLN~?U;i<y>V zGUSyK=hfKQIH=xS+&eAH0aU_6hA9hmAxslM4dT-bq%~m5S9)usEQ^YBuoWs&eaJ>l z<O6(d^pcP06GJc>@v^#?bRZNQ27#KplAy|YJf1)!D<=@*&(t+d4PdAP5Ht=sLP{xG ziOR*aKQ3Ga{Fy=q*%<tqwlItvWLaGXpb!wqXP`eG%5OEKRbmKzzTC~~;b<aI48M{S zs1i>NsAgxfrGU$6MkK=vKvyuOn4y1LyZ8U6)MZjdtOw8~rfJnzA0pX+R+9}@rG5sW zmR2*oj1wdq=a@BoHRM+V?K)#8qrVBNhs{5q(8*ie#RxPb9?y;!(d$KSVE*X{jS~^K zj7a_Tt>RitRJ0OW3`O4D6Ckl}236%8i0ajVrvM@JDhFeaa2;q_fTo}J3ItH*7jQrp zhT5Y-E`-_>sIpi;&yR!XlqOx7?&C#~pUDh8C76^#LtWm-APJ-xlSoA^2qL2g5e$)u z!zAZvv$!d#F_JHTtfHf2#TL1iwtnQ$KI8G|2T~waU$u$?UQwGCng|92O24|Akm*|f zQpvj=?WHuNEG#!i%NKUUNS|}$73XKREBBp$Z1H#n<khB2`2tz_Ely6`LuG7liR`YH zikxo|qV;EWWx&<_@4x$>jy>wTp=W>g?~C5p*+H)t;{1>)5FMnn&ZXaVyi<wjIw1uU z<Nkf0c`(5s!XDD0B(VR>pS)}LO-<v9;t7Yd_`ZA&^|vnBSDJ{2y%Yo4YqLgL9a7L! zj>X@XO#~UuNWpwIOBnRsIu#8nDmq$IZ^!X02=vu6gNWom&S1ex8wj;um%iV{AX!$+ zb+FjwNn!Fhwj!v<7M%$gDFunk!#oi-bQ3hd#r5v>Vhr6C5{8cUcL=<(FLb0!na|h+ z2wSK?YiUD-jRUTUi{~3Xro`LzW0^6nph$)}(|kj^=0L*4rCL0{y8;j(_bQN2N<4;< z{=HP7yBRKxkdbpr7oc%1B>tjm9=eD|HP$*1ZORUT*%R=yqORzu%XntnB!G4w34}bt zGb`??r?K{!rRR?d%jq#F&Mwi=DA59I8gvwIB%j7mHb$2UBJ4?d8PuA$mnJSIlo_rf z$=xq7PZt1Rd#G?^o{P~EkL5ZIh;`?N@Nxa7krRHzm+4z%`Fyt3UsmEyBhzw+r2v_R z11Q$C(t1SO5ylO7@1fb|#w#_clyaF}j-tJ?f#KJh2shk+&pz`1N7<qEbZ|1Mxz=0A zchf`%2vB9X%!nlnAncv#fqZ6wepmapY|!mgHf;1ASPwJkQmTf2Pc$Qy8G8-`a1@10 zS6k4Q(-e;t8N9)tnO_PMr2-V8J*8P3TgsMtnz+_UwBJyv=`mP8&|n4Z|3&E~_wP?1 zm_o{b?E^1DkCA9y<qxx(8>m_&J}v3t|1_a4K?1G$iYRRzpbLrDsaLCj>OEH>gwJ-3 z>p%8w>;zZq&IKwYpzom}EFjm}UNUD->ct%DOS(!KU~7m&!N{o1?R%q00Ki|=?X&|2 z(XKtAfV-4>MSi-jviDNmbJ))eEfQ5QwVOY!tb?+d5fbhUR8TJy!N+etGKJ*OzPw_u zT_>Nl#*h!$U-%9IoP$~S4?4aNJ8@Tt#O^R05+OQ-pbNuGAo;^iWHcc}Kzo_N=&*}@ zlz^2UUWWS|{-^A~t81??r62YP>Qse49bRE;Is7OdT@`7iy~_FZuvccZD*Dav>cx}8 zJ`B7%7H4lBS@*90<|UDMt5-3BDdq#$nfmSkOEGSkIh7y8X!&`*Sh0pYo~M@g#HXkL zPr!uR)G;oVYCPJ_K$a{;PN^0ImZENgd%5jE0kXtMZjX#$E+-H%Y4<eub!^bM=nCll zg^>+4`QwS$=-PY%7_Vpf+~k>HpCUU&!J)tboNeHekF+=U8)-)9=2!ubE6`B)Zr*}_ zF$z#+m^DO|V>U&ynC|xvgN8n~W*xlPZ>3mgh$^=QwlBwzC(Cd)5dG*JTq+NPJ4c#x z=U?kDTz~?OH%{c;@E~~;9xJJAnv1#c*U3!^u}<Hgp-+K;s*c@ET}Tg%HqP~qxR|X6 z^Q)m;He9OoZRA~}w8go-yDi`#Td4-~siC!7*<!b&6>3%&ApZ9&6QVZl8EIDm&mIg> z59KN7&ErM}VWdI7f9RE^TsWOO%n2TWyRm;=y$~h?xVJ@{G|cmGjd_{|8C%A5%W)^2 zA7QfM;%?P+vsg&=rHAR5#e<7yWXS3=CSop`=9i~>rEUlf@4&=;{Ca-$yZWMkM!y|z z8U+Bg)Hm0x{hhw=PzTB>6<^yYo^oHLC41iK+Our6>LJnUy$LI#1B5;-{B*yHe@}Pj z*7H<#z1Q+h&OL>gpxWj;$A@5nDTyB*`>X3(zaVStVn`=qW)IrG71Jeg)bodS2N>^D z7X9|7xS#tsKnj(ht@g?|^&8oq?b&(u&8O}(>yU;+F;jEI=kr&di-o$_)YNajWgE{I zeo6fycW!4fw<BJiEW8{V8`=B*?!v26rjD@XM^r#?-pRhq1G3KWomjUWe(pa{{A69M zKLxlS^!XpZ@p0_)KGwCe1iK%tGvhqo=3)crt(i*%kk6%&;eBkUmJ|+<+5f3OsMF6u zFA&8ZbgRlfu+TRUWiMD9^r#cgDd;58$R>{Wm(*ZYmqt==Fv~)M<UN_^N#0JV5Fwe6 zTT1>x^_CndY#PNOx>blLS3~qsp%3xQ&FaXcUJqxN;AiYiCelvc0_-?8d(*}s;*5V_ zoU39Z)}|OGr*7W_4hUWLa4}$BltTWo43+DAlOBNennkIC{V6fzrzqQ`dYqyRo|jzZ z;!|vAvWAnL2&B&ST?3pw4}+s+P~9ZN6KqgMKhjwc6|U|B=u&V)-^@nTvaVI3GwdPQ z_E0(;qz8L5<FRRJe}rZ@$AnfGFdq@=t8lC+0eq(nvvoh-sS3_z9Wl`OMstHre+IEQ zj{C$Og)|MClVM#HhtWyAUMP-&c6u}STf*1bc5-}4OAg~2(N=Gw6J(-wbDbZpMHgs9 zGk1n;XoM+t($}ne82yVrPC;64#9#!SUL?oR385U5+<mdJHv_{zPRH`?#gYgvOq(b! z3h5LW$Eg{^TV)U6aTiN)>q&7aq4<lPL3MB9Z&JmJ2(g}<#II{akjcHV;sZ!Y4uAiC ztK28P6gf(`daS%A@^)&p+;XVKvyhLTiOf{54<K=h9IQ_Dh+wNAT^p2zAZwXAlB@CE z2MJr>KA53U601wXlQ=7ehEQuSlm`TGJWRA@cdxqur`tg296HMhB_*wUJTPEZ!uh77 z;f~4ikB^cV0|Okx@VXL#&Q^))o33A^e72=n$+|w@OprK0FI*^!!89rNYAQP)!-WPr zuX>8CM05<3oSlliwgIzLOBIui1rE{_B)sxdkwb-Hv~l#S*mSh1JrKrR{|wn45ZP6N zdhKBoa25G}HkmQk{v`<ElZ0#}Wbm3=<VqtynZ%bCxzdr9pol$3%9P2rXS+HR2g-#} zn+mxt(Sri*H@r|>R+#`MxJW2=vIO}RjjXT~z_I!+NV)zXq;HfsP9Gw+#hKF{!e#*A zfB?_#MVvgbgp_8g3gG*t(vZc-3Jh{A2MPqhXe2BObKsQ**-};Zmh`{?$sQyD|13qx z$)JkHEv$N7MF-v^_S}*hk(aH6x=1h=sT_ttOOB@4oy|N@m3^MgYkJdHw98r4O3*4a za$?-!houd6Hebi^-M%KW3awqKixfZbqLu)S6@vfjBKMmtcP_-68ZztChEtm&oET8% zhD9k&mfxQs$Nt&!tGn`U6+No5%vH-<A!D4y!H91J#3{kTu{SX}toY86)2|{Alkk!o zrf&x~OKeQvl7&jA@NRy#rB8F?Rt7?EmzEMZ%c|wdY7NWky~`TY%9@+YTECRFAD0n1 z%e&;tdko8az03R4$_Javhrg7M%JDZImh<ts@(NV&x#XPLR3PIjzI>@zEalKYuJ}*c z;mz~m*#{IAJSGP;5&nUt6ZBIUMZ&oLK)Y&RsAS`FSm&%<KY}*bR~~W_m?YrMY8BK& zNUtZV;1(Z75!Ct|0k%g#%4hzPt@<?Q%vOec=xsUAS&4k)!cm5F0THUbJvg?IOl4(Q zY3sf@6osBSZ?0<h&ZvJ@BSua~Q8W*ijmo6H*4#GwpvYCLY!v=^rYdXDQ6;_h)=B=6 zb!|$xt(INQ>-8E2iP+xoTD|l->FtzmL--(Dt*lqc_SITbqjJrmT0^@UQa}~awpeAT zR+ghKsJEWzUH`ny&Bm^LR;&Jv-J6H<b+;m_B<;%nco)<2J^Ct9WdIYuO6DxS2I zU6O{Ia5b?@#D<nJp8kdz`ILp3zyexoGb2!!51`JvFfyS*$0$3Lk#d=lu62SsEUXms zsdl1o#+}rJ8M#u>S!ZO;%a+;}k<zKs=H{043QGM5fOkeT*4j3-91*B5w4{W;Nj#}< zX>kePC~z0H7T|0iCEJyzr&^5MtD~Q=`!Q~_B?4FTcF=!@%n)g)VSrCDW_oUT{6JbA zmvwy2>G&aD1O(V)H=V|}DY+r|lLnFBCl;I2h$W;|$2iz42kh+(euH7ij|CSIpvNt# z%M9&n5yj6f3()g5!2<{vOU4llY?J_}SS31$(0UT|2nibpU=&%$pJ`ji`f%T?9Xibx zwgRsE5p7H}2=W1R1PMJ_f>9z;C-*#$TmE-f(Zd;@Rp|N7s>ie$>%nEa=nSWH`zRoy z;Zu0(THU4${2`mwHU(Bf!YD*CHq{&BOQb{fK5Igd3H13z)|>xamcgEse~1nMyqyd% z<{uyoQd^dX-YaV(@7mWC&%h)4VH7I4*Ti+1_;GFnaZZ2}m*|h2;mhN&mtQ~n+qF#K zEsFz?x^`W@9JXm0h(L|d^aG2~6f5atm`*u-#F-(t4~87@sAz45HC1VySU652EQaBg z5G><F(NAaie+)JS{}yK;FV&ZG4|EL-zq0e5E*{7yg|UJM8Bp#m0nxt;2hPyGh7C@J zL+>x+9&3v9_S!QH=e*8_X2B;w3e8S;4-vhX;ndW)e$m#ACj0qUt+$4VjA_2nJC^5o zC-r%RV?BaI9HDdpL;8k%j~W{1(x2Bue+F5e*hi5}puNr$>&Sc<Id?*fBT?shFNHz2 zc-r-0K3uME62EPk+d$DjB~I-i57ioSK!{Hic=<VFut545Th~xiBi<<f7{f5Bok;xx z#R9Xeok2i$8Pj&^mKB;2x2Gtma(664>gH$Wz0q~MQ8NV?2?;A7ck6u~(ahC@--e~x z_wLGkl7paHFylF43HH;7v|)H*)A&W(Nig?pnkWPLdHl--WY`O&s`})5&ftT-nGMU& z@%D2Rv^SM!+^u33rZf@bz+l7<Pm*h`6smO;m@R4ha&u(v!!9!XkT{IQ-<6q*JNcB^ z-_Ts~1z7kB+xrSbC7vHpoE#bR;~p@v3<HPu=H0Ooa@!nqk8ylq6yr5Ysp}Qxyv8nk z6cDSLZJBR{EkaE{A^8?^)yL+Mnf<V-;*t5Z`>1^$)T!^{=6%lzp?aex3(2ziWS(#D zW}Oah`})0T8C1YCd?>l1uoO};mudJdxM*Ob!j<a9SAnp}%LfqY@H#1ZESU%`M9ygP zFtIF5oDk@5ufrVH+Zv*X)Nw0~BNJbSq4~h-@B7RrNuLVE9RbgQqPCT1b1T=4=kI>N zr42(fFyC!=<2;L2Xf!8)jlO*6DdUA@=Di<Nnb7#QZ=D<80e0{Av50f@jNV?j|LNEQ zI=U-$#YH~WoZVX}d<q9+9nWC6AdtSw-GC#fdv`)-jsqq{HD}nA(t%jt(X%urhjgy> zp0-0o)X#3WD3q$Y&y*hniQpQ4o+`NeJ?(rYGb@FY5ulK+C0v^x>YfKtYx5XC)-0Ux zNR`sPi4OwaGeEfKBJ%PKs8xI$R}?W*jL2|yA)lpvAFxnl-097LZi@X-J|t2g+d&=F z(Atm3ir;l)f2cnjP!w4p=RkXkcjr<%D3I<q-zKC+32A9f{q}N87B0QX?YW}u<O0HI z;qwLvbu`52ApT3X&ylFpn@+HqaNLY74^uruP?DK0j^4_UUydZina;0ic;1|`Z$guO zEZRYtafh4(k31h<Yj>NDt;r=fR~RsQtmpV-#Qxe*NOhk{D_Q)prtKM9fxsAV(wgSm zk{G|ifBuCBCQ0?i!uF`{uc<)15*Y`k9rv>Pmp^F`5;634EhL=$(ne+~70)VNll|Sq z-wxB$PWQhf;ySu=K#vNC?av2JOwv9y*lF3s4Ph-m4*eTbAbmRh4Zi*><K8bup<Z&p zP{z;S@<#_i>FVc2OX=(0W{&%bP{4s80&d=^9~k?_wYFYV=ToyCdusI>*cpUR8i z#psIt=*^^<9?H2u=!3uV{f_fflN9~VNzPDFwna_A;j^E}B>SVc&`(#3_9{!G1}ejv zGsjb#7B%}VC_M2O5~7d%4LNYVmqNfJvfmX|{xEPFy?MS<9O=lm0as%H*Tgo%c~IY+ z7N@SKU4I!X?Y)UC_5^Z&y%c^;ZvDGG^MMDTK!D9|2fv<V_%ET2-Pd(j)$mXW;SkTC z+yQ>6`=Ro)PODl;VlUc5{!a){C+oJ~`OaJ%-(_G`!K@XJ%x!Qx(mwkt5TC1@^m9<t z{?9M2$w<ji*T;enb0o~kja0hy0m8cV4h#PS0XDyOVW`-G=P!DYmb_N~#jw=)UqUs9 z9FC=>+mZ)e=yXR#p0?lX-W;l}eA(!X`+TjI%W&WNKV=77)KmT+`RQ$E=1B|}8xry4 z1-}#UQnGnI>BAa!z;Jnz*sGIz8|N%$OMw9I;4WtVlu`b6@u3=f^!GbDM^It#$izaU zf1+R~7j9p;!iuaAacA(B&w9MTqie}oFDZSpvvhK^PJ8XYqrQ|^!?pssq$f37*)L~h ztVHt9z0|lpgUm-Vk9vQ96eXR~NT{OJFYgsbN=^}Yomx$;68zq4T@yPzFX@FjoOc%I z`d{lo-W?KO#qo|Vid1Rv$Eg06&2w$FmSK&Mk4_(b^@>#QzmyW%5MisVCrCWkygJC9 zaJfeN#@J~|EVf-aeDL_mDPa)rp4<Ok%x0@vWc0iVn=n_XdP7$U%#+xMogC67^Nm9G z3sfAJawRcuh)3#C=Fa*KlFJyQ#Fp1fREfHJ>R0MimDxFQ>eFlHI2Mm{4#`Pee;#eT zKZOPvJ7O1$NSC=sCuLxIf2f}msHFn3?jsl@IUWv|juiMuo6=mA|Meak@F7V~J^TLt zoamHk-<5{v_2sVpqY;S?V*J#P_C~pC3k?Z;T60K{jD7NgC_x_^_<DG3_)4Qmu$3)c zfKiJp?gc)>SBzKhe4<aB?&&2&{GZ6dTVpI^^y}HC4+E3>gCD5L{!poNILxDcEH{*F zI2!l+X;k6kyh|!pgP#WY+A3u9PxY@hZzx?~ky*Cmbp&4u8I~x@mi|>XLtYel?NV<3 zqMK(ZrNdrI&c14dB^+s<%tClneY$+LGncDb>w=7MSHd!s$8am#S0-?9rHTwX)o8sa zkz}!>PYc`_F>}~l^xck*sjjPLj7+e@uu40RNdIzL?@#wV8WML3)t^=&Ps|!#YspV; zq|O`8aGSG=88vtX>l18oB+vE8zr1d|`Q%pp#M4L96I<$+6^{x>UVX{NE!N&q^q;-X zI%bMX_-O6~kru64lbuL@r*)q3X7#nA_urXHM!is$>WePo4<w4x*}pwGOls=fo0ob! zaDhIsnMQ<AH5LGNXEgXyCFpth{%Nf3{5ub-_LQ7{&9f!FqIf+vFDe8%ke4=B2Q%>w z%dI9PVulkWvcdyxE<1j%jwUOxB~AWtaAJvIJy&j2xmf+(9?k(*7~SKvw5K*i&O^Kh z|3I4SddxlSGQ+z%;g4FwU2gZ7vGH_C0Q%<l-wE*s#=GRGdpSoG*RaYw>AE^?y)EeJ z!}JE?c2{g#A|g~Id?@L6+I=LJOKb{KfbLYiHb{S0J#{`|DK0W~Vj?<56;03ayPNS} zH+SX)jzKS85et!wvQscFj0H>1ieER3Rkc7o`pj7cm;_r&Bnsa4650D6cI8hXSpH#W zG%KIPyAJ*A%T&%%?J^ZFNgMpYdA}wwEQxKDe|1l4AECz*VoN0VtR0g!)Xb^Tvdyph zUZM-SpBXcz&Bb4xp$%62Wbr98<7?r<>F>1Hjlw3wqD2c|`m2pfAF=HCT4AjEK0X!{ zRhaX-|8Ga-`rh|HVY;HZa`eA>ZZJ%}SKHRu1JG~>A-l`en%L{Zd-6Ow3{i3sh4;|^ z5U*p)%>r7jwZqi9f*ko{NJ~?BkqPNS3!4#%$23<cH;W#bH`F&HXM2nXwNs@&KlhyL zEjj0l#_mn|lAY0_thEJ;jViFHXFoF0HSzDX%ALet+ZrMY)il*ED*=b`*Z)f_Y18vP z--AVcS^D^Rn(4i>wlKV@=t)<SomB`yNaeIE)-}<bd3$_|{9;e5#I`us)XDw5c-)2A z1ZX`W8}>xK(OT3+0~AdE`kmyjncBrAEK`W}%7x`T6qoSlxSWq-gb*_pJLDzPm5rf0 z!@pymgx<KKy&Z*4J%kN#zb+5>{Iy1IXlnjRgSP!mEzgZDL<enQR;6Jf$MyHm`!v=f z#-glyvZ(pD3}@P`<V34wwnm7x4At{8dPaRl7jLDgJbsf`5x(EsP*DG;4czYdG}1Lv zmF1@7z;8$4Q+9qmDQ3W1kapqWF-HjP+Pj@w;z4({uWDXgd1$Moc`eX|qP*?Ct*!D( zeo!dE20mWH-|G@bn!LlLwfVaL*^u$YtI-KbDnf_!zp1;)O6Z5c&Ata$tGu~`%3YnY zDq{a|LH|~e6j||;6=&m1G>tmp%5%e-4`Vo;1fIX?`72}SpxK*(&vJR<py(@U_D9&; zQW3Yo&wcB<iZy@leFO8-Q|Cq5r3njVqIv0A-cuRsM~vzVjbq9G#)1rUuPSBdB@U3( zW$>*ANfys~PaPsdZ?4n`Sr+>4esnMYLxZ}-+r@Xy5_f%{2(SMb;|t|;z4gzwBC}!& zWA!<={M~K45xL9U=el44&Qzw59>m2SW)GjKe$&^AQd4x#JsR`)6Fpd5S<V5Bbk1Zk zF)^4|q>3$cNxW0NBhr$fdH2q~sN>sU!ABXOVVU<-5#%7qjPhG0&(^X|thykSJ6!5s zzl?->t=fZIqYfS&5!htgjPSgDdyv3J1OGYw9=9JK!e6K=&xJOfc@pFCx!S8A_x=Wk z^V<WpMw#0mrLJ)1;?+zFZNIzj7jUbF_VF?(y;^~To-8-&R@<mMPHSoP3)<RKYKwm> zW==h2?!cNkT_L%aGz-UvUN`Z4&+Gm3etfm=yK@tTvzrQHIiPz#EK&MkTrbAA=~3)- zr-UcPCAEuF_gx7+iRuc@t8&;<AL(>VQ>I=*g<|L=S|_62b!j-`2p_MvFUNF~%{UXC zJGl?3O4VWZZuTtSx(BK1Jn)oUph@!zvw!4E2)X;9;{r$}s50*5E0u#s1-9K<xOv?{ zkKb;~v%BZ9c;)#Oj;=<q+>U9C!p1V(6$6&ra*44IP=>|ePwFkeCou}`+>K*xD=~XM z3;RllgAVe+?K?4EQ^6O{$sGVK#v6_KFGAB8EZ^9nco_OpLsXw5yZ=u!gHJoHF!(Q5 zp#>&1XDh@C(_p^T_EHzi<5FwnMJq+*oP2iYFFV4S2>bYn5;nOFYy>N8D5?t*$z@<m z6VNwiB}yIWo^1Q-S1d>$WJI9z9asFhO=FDgnoPq;m0+54!jnEhi~&G7C&Zlc7~m>( z5SMfz)rQ`q{Y}KY>qOwK%fEEDk$WPPP^Yx=jdy%7U`q6d62Q64qBO~+T<_NDL~L_H zs`fIgUYN(K%!3>bqk77)rY6|kKNLt0myEoIoki`Zb&bbHT5+}{>Gu4_C@q(^x@zXz zeu`z(ZtDIDdQK_U5P}tF6}?k%*8N~pBHhZw?F;TohpQityd!KpvF<69N*CA^4FYsQ zNoWcmfW?|t<PG*9k3do~wDTq(f?eX#6R731JI0ibPJi$&R|lm6#HFcVhr&6{g1&as zBX`17WoVVrEjrdAvNCk)lnu%RuR7irmBRu=sF4qGdiY?AM&xI{yHctOrn>(XbktM8 z-WZ%hBwZkhku3EU^tu-Q-ZsqK8E-MG{vI8k>q-08UZ!3g?5{z0J%k=t)fDg@p?nyk zs6l-L3DOy+|6nJYG(LcF<IDU$kTu*4j)=_5W2tAxns3mOm^*w3AG^E5l-ctW=JDnl zYFJ%R%zSS)vCSsslAa09Zwcf`Z0iyk>g_^%%t@xu#yJ78R-ShSOoDX+X!U`BWtt=l zBv#p()~6Wf-VZj@z4>WCtKt=;M0B91R^dJ2UWRU7XN`D|c<BdHgqv;yOHlc$@Ky2O z5pA(@_4@Jekf0mlH2ULoxpE<IZ!()2V6BR=Rsdk^Oe2NIc@~En7K2QDu~uj-%r|68 zo0j|@GP+C~pe$J2^$OBGk2mgVd(WS}{#_s=fLFt``PCs?{WGzcFr9H))SriW^M`cu z0l_*Z`0aEhre$>iuO77-a>pcCq%r8cCRlBp_K&BSmv)Hyf8YlQx&I(IF>FO?sMd3o zI&_q@2^r_WIhcdgNpyZGQF1i}yWdBdWaa*^&hGpls`&By|FO-C!8l{z(h#zg5TVcz z*@f&PvSumD9vREb*o}Q>?7PUmB>NI+lzq!iQjMr+b4~B}?fP8b>zD8McKiM|f56O~ znRD*1$MZpCq^uz=L6+4CL+eAt`L4=o-OgMxR2mAu?&Ydj+7`8K%!NOZ+dS!<A=K0+ zT}X1p=dslVdqp}M;ss=&dhH#qMLqCui41HST6PgvFcH?PSe+)Ey81wzBVx&2(U(o~ zUR0zx08z@tJtjlbmx>H1b9@1D*^9A*Rglvn9^+T_S2CJVGw|5QTu|RJ<GU1A(gU>+ zyXrvA>?-?KRZ#~zSuh_NX=2iK-AAcibnxlw*)=!ACvA9#dWZ@wbONL|*6kOK<a#Iy zb+N;nr}QXQjz1>9Gtz)#(Hbo|I193pl_TsmdEA9@%HERHe+{BzNF(nWVf$%XWEp#2 zL#g#pyM+kX@|JzrbKA`jkFx11qKSW#JFaiflO!eMbpQ4YnW5)0$><Dp$u-L9IMPcU z>Wr2j4mex)s?F+R+R#0vwdXi%64qvp&SsVF&wUzs((IL}2urD^7KxdBE(G-&u0R(T zOm5;t(pP#ZFA`Go??YoNCnd#9Pop(V>9jTRB)ml%&6`fBZzc{!C&`~RE$C!!&uy~& zi|)ywxg3$!)-`VMaTn%Abe9p-A_`~T&c12{t2nSc6`ZFFdx3vV;EsQXjZdP!i1$W; zE&UK{0Ba6|C<);R^GPT7R8o}ZA5Ci8s4Kaz(%JY%JeAX2d!%}~){;Fi-U`6oI>33a z&UeGCK4jkJyNK85G`%y3y@tWsab36XfvjD{zm+jWFI)9Yc5t#udJ^drj!n;>naRRN zr@_U3RAl+7E$9hPPL3EQwJ8tuL!6>$%W}1>$*)>2<BJ@ksM+Bb*OrPbtp?-GgMDc- zu=D-b7JUSToye?|^8}|a9xu0pN?uXd*Y1rdOhtT(h4|KE`y0o-Dmd?lEbq3H`cqVG ze3um3u*>9rqpr&?_oW}A&G@4yr<X4iGjnMV@N{RCPH6hRFuXjtjk6))q~sRgiqCLe zG(2Ql`M}QWuRlNUyR=Xm89a~NmU(uv3k{LN27AdaIm~q}!al^)M{?O7r(8$=ru%aP zfBFl{FQnSS3N0pD;$kYke!C00)jZTtvOT7=acVR1QGK_EzfZ>b0ywK<wwBJG-i@nX z*7QWjyL}S20~^ZTAsWgcnqPLcpH<FVO78jFPPV_LHBZc2#!Tf%wx4a3iWiff)I$xt zB5hpP?{q0Ix+|S-@87sXr-o{}u1KJHQ;ZK#u(*SQxF{<f^XmL%k`_;>WLJ6RnMpUi zHESul_|O&4X@b+Nfl`LCK7V|%a;WSi+AFs`r1f3Z`;*F-*bV2^mqByA{EU6-!Ye1q zaX+Ga==1MgPp?e<gN?SMdG2{_38fqWsPWS}QEy&%B|;Pp(Z3fre|_xcWkgfcIt3Cn z?r7;C`PBL@KUe%FS1M&s@4U4qqtoKBq+k~zvUSgU4suPo`(#6Tg{J%chBDZ)X|1?X zdu^>Ls=zH>&VO)QRm4tU3hs^J*{0p`X)%6avGbI46<2E=CXfun?KoB2J}9BR;$``y zd#GSan@s9B70O<0`t&~H>2r58SDcCo1{+Ns!V4eTweq}+ow*nKZTD%6k&yLPQvOO8 zyQ63N)*!D&M$7$dE)!3#O^Yjz*DtK)K=#tLT=NnluDH53GVPV*M@QD->P=}Bv{Xye z_cFD1LrK^My4lJZw+xGg;@?=4`MvsWH=X%A4OiT=eU(%%xHsmzxl74<u4=V7e|!`G z`G?XKI-1kniMF^<DH<^h)N>B<V#Ph<v%4G&xO5EdmE5ma*#}^lix&I64?HSy_+gyK zD9*jF&O^L=Unk6C#B4uqbAKX#<;~4~5(1E_faS`5in!@Hjq?x-z<GFmnswfqLwu69 zqba>iq#LZbzhtmBXGVeCfDR?`XhE^ux7To=y06g8Nd5!cZpV>k6tLaqx%2(~vd8OA zga5#63y3>q65@*S#L8<wSF8aEaz)Dn-fn$_+i|mi*m|u&BKI9oo<Hlh9~wSrUBSAI z&`>(s9g?1>+Y=9cySy!M%K;E81>7eya;<)w{Z*W$E1i7>?sARSbqId8=Hu#L^1B4a zCgJAP|6A@MfF-KU|0DP8db$7K<ev1psDez%Xo~3Vsyn04OUE*#RKHgUkc`K36#g@| zRemc&+J~|sgpNZOUQZFXdDT?;t{kb0Sem?Hcfqt6kfJtZM~j(Ob*P=uZK;`Wbmi8e z^NO|;lh$iuQ%Y{BTkZ@v><B*RxQfia7W4f~o9VN){wP)n5iJwV*g{PQ*ahDyJM)Vd zAFYy9A2;m0A>L?RGAe$Y5LOPQ=_#~aMRb(AYrRhDkJ?>qd;IZ%h1LGTJHToH#%Jx< zF97iG+fH-^er~3|cCEnRMaQ>~bB*rrCth^^__Ep`dwTX(ch||`?z`%{|B-t$oG8q# zm)(ED!2w+iYOVY96o81LbW{N%l`73R)Q*M7xJ$G-aVm)pEKqW_w-UQErGB0w_w03e z)Q{Jqgk(zX)D843{^k4BRU`8#|0FdGnp`*H6}Brj5|qC0ZX}{1Vw(hYj{BQQS|XL3 z$$BF51vdn*w3pDDP?I;c&A(3FO$U9n4Ks{*nlNc}MwY_BZ*E%WOhf0?Ej16F`!=EU zC_+!p*}>@BdH(Pw=g3gWlHME^l-+LLulSSA0=t{31sSY)qhQG+=hm~-VqJv3Xrd|s zT_z@E=R|a^6C-4qJgw4Xf$@p<QWtce62+)(+|X2McG=n=Zd4$Sb~DP7=c`JNldLLz z=@pVjD9&y2yz3}SUkxj4e|WdKenFdx`ciPRdbpY3>VQC=Pcp3e(k^lUfRJ}8^D0Hu z%L{%_E56TWK)cn@Li7%_K$szc)I4nb!wv3dhot35jEr%)NyqU#g|>kIIUQ&Xu9KVN z9-!ReUtf?$Ikbh0b{P`yAk|qd<_cBe6&_TWQPA*T$ZsjDhk>paexdAa#-1cG^!xeG zqA!K)F+F$TXFPge`)aF#ER0fgLWs~I&-40m^P>#YkCuc7c?@NA&f^Vp`YtraQAe{v zh{0H9S}uT+yaz~E1bF98^Y9`e3JpEf+=!B}wh%_4s{e-kTtDY(PR!JuY_b8F(mJfV z@~@?*AiP&KR^NoHj|{*@(9xVB0jl(KZDtQnCMtp{A~D*7Kurnxg=q*};##E@PSs0N z&%1<Cd&I&fR8PfWTQXUn`7h+h;r72ne(`3Xm!SJ`9DC~g`m}4FJKZr%9glqyR0e4V zL~b51RR1^_{OG?ub}*W)r3Pe^quEN(tomH5v-@n35+L(~OE9}|+pS1VpCa}q(cE>I zW~`avJ@)K5fVu>TZbbs-Y=qv}S3ksbGS~cS+tivDcDjE^4+r~usVyHlW~O*EQS(ys z(w#!SU4L-DkDf*==`&c-!+8OKK~NaxIx=iItcad|!SWS_eCyNRa-?MRGH-e}h-j(O zd_Cx8`-;N4X``?b7Z#|mkfKee8h8lcT+!0-4c;K!Jzg(+mfRjClHmn9j>BaETQo*! z*WN*6gF}?COKVtSM^gdxe?l~bF$rA=G4EM`u!LcSWT|c^0syDx!Qc&mNUuF|OP~(G zhz(FV3hVY!@_k{@sKnqcYfF|EG{Xh1ReiamjYs1*=?#z8&;^wltZ?aCIxZr84Wsp> ziSRkiG7PozM|A<WCP0j>=+6C!X<5xeJmoMUP)xFoG~m1$7AJ`GoWk&<Cr_iVD-_yZ z%3R9h!ivyx*#YQd8n%NYMW?+oGll-wPw#C>(cUQpEgvrwdze=L4bZz?ByLiM=20}% znD7eXVFj)@30od88vUl9EUx=DB=Dd|&rLA%hJVUM1MHBiSvG}YNr?yj84U#uD}z^^ zgk#RYO@oa;pb78`gQlalQR3{T^n2$4Ennkn%au`rQ)9U|Vdkzu#?N%Hw}Z4J3(Kui zpOMu2rM7nL-Qd-wK8={4?C$35C*rwBI&;r~minkX#5<O;xvtdJ1_HYly$TTiDjfZs z5aOZtb8c?JV3U@}bWv4Cf<TJl5Xt>k<Hnk@Fx~O}f>%hb2lKmy`O^gs@ett@H0_hc zl`Fz}UEgXk9)@QpApWI-LCJ?af~HJxd3g!27mc7O$f;pKKLSR_p$i5fXxZsUX#kcV zca||606Q6jt}qPy1)`m8&x~;L7>i~pnxky(v{q=7bqdmFFN-UL!95gWPuI6;As;Y7 zOkZhY<_4~c8|P|b(9uWi>h~Zsui*gtPB<eMaA#L5itZi_50{z}VWd8gCoV>-Mor+% zZVxL5)k;(ahL+lrPB33;mAjZ41W;7r*NdU~`U7c2EF&SNHD{=3h`rSGy)fFZ5xfI! zC<Q+)=#?4*#5#latZf`EQ86j*t*OA0(^nrAB4Nxe^7OSECEvHBw{vyzWFlaqG5^Q- zj>@l-HyA_{5vsqd#`}{LWzh6rxp!4I027Y+e&{-|8qj~{ftDRCJW?3#*ppG;%j{ts zu7gjbwd8=Etyl%G9;?31zoNy(W<-zzvIe%iOV!2+>q0pTVwQ-<_XSwoBbKsJ!I*Jo zL1|ET$*#BUJ{=%>@Nv(h?S;_9k-7&dJuIr@V(EhfW-b|wkjbyhK5Ng>eZ(Zzb1tYb zRFrQ<Kc#H)c?oay!%^YRUI0TRgjzN7hBG6^fd)kpGYZ|`UTyJ?Kk4_#|MBu{(L*4B zNW*aJLe6~6>Y-YWpce$4dBgDF&8pnS+-a7~EAxr3>7Bo~q!Qc5T?`Jh7k_UnylJ2C zpE%6_^?L`++(E({92N2Y+12|0lkW@JvkdH9YLHC8{&x6$#!d4Y<2s|?(iy&uo+q)N zSC}4i@yq4{Xa(Bq9FLp&&rpX!l{g;%2#a*!NptDimVa|H@#OCzk@>~0=B=M~zo>x~ z%Geg9$lo8`ee`X9ScSI8f8qMyZ?xVoKKsA<wesulj~?c3vOn{$jJD$MkSt~3l|aIF z#Ks8;|8(^eb-)MC0>KxTG`|&GPw3!OKburOaw?Oc`uA(j>F?cJFMrOy`TIR3ly~+L z?CZCcpBwI>d^4dV@(BWr_v$xz02I?0nsKw0u@9h+Cd1%u7{)ma;ur&Rg|R4vv5jD& z37A9zjL^gI9tD;Iio~6uApg*J<=}?-)3JJZBoV_o5>6n}<Le<58C8ykT?~K`P>ko> zo{rgZE)pX)&ojOv(T5P|Qvl#&Phg#Ys7OVGxM)~pJ^Y%*)07NEJqkP}Gw&E8kL3}z z$5^{v>?CK1Jq(92$GIxt-r{jK$JiB3a0LbSt}?`s?@`+$QfB=K&;UB`a52{iP8fYC z3cEcUfk5I%e_&m-kXzu><kKHfT$53NRA8cLAPUKp0%Kmsz(X<cYA9fx>Gy|(pa}V4 zGM+mVW8{h%TV-aXLc|{j1B5_2qrd`-Gfi#5xvorrVa&bRpj85Xzzb8Q6$K9qT?K%F z^I&%-|2r3^L_123CGM_y_<J$~VHKw68bvc1yd@RV_5(FTfW3wJJ(CZajlvL!jCG>m z!ujYiO~Ei|`~nJG%k*t)Wvn1U6YCk4Gvg=>=e5hZLoFD2#FtEDYDFtGp@l}<;Bx7{ z-vD6H5bC%}>#zz5MM?V;p)bh{)J6gT0V-q(l6nL~dg9H@neyskkG%ecYQ~6+XX%px zL*{R%Xl4Kttz=Be`N1m)vA5&{`@CS$D8|2}1p1^vwXAcaS}^5+SUq_JK|X=t#W)Tl z=&}Tu(*wq%KA$mgJSOc$K%(9w3_!-|wZcO%@CH%gLzfu*D)S0HSp9tTuotXCDg-(& zRO=EGO-OIi^!W@1Y+>M$m^3mvUhiwhFqrAv?tf!8DzF{yKbw)Zo=H&5R4)(zR-u<I zmI>Hppv@6PFv*!-j^NK&>EknF2)k64hG@>N)%Lj)o%UQYr_3Tp;|J4cOx7#)oC7GT zPciqeQSQ+Fvm;r#M-92-C;ZjinQ!KEF^YLpCz&(!XD74rNS1j^^Zbh^dHbix{Pjxy zP0RdU@BH2S{1ff@n+@3=+xfd;>0j^j-w|W{7R{fCNvq5%SZOGDwOg=`3;@K5>q&8m zm;#76{~{SiZY8dT<+alnE_ySH4P~-fo%xYfxS~q@JzBV6lnIbw;`BxH_JuE8i)I`A zM>Am-Vp-y^_zpP((A<e7+{LdanL|j-fl<X1h5li9_$qsrN)>O=EOYfNb10^ySTsxC zs)U$?SL+DYgO}c1KvYASL+ucSuBDw}!4>3tzoY_h?UmxBLqFL?zac}Z6tkt=%JRd4 zDJo~x6k+hQ%qxaVGp2-$VTwi}0xik{gUX)lAbg?psQUq}vxuHk#R}XSr3{IPB!wkp z^NvQrEhh`o_PE7bDt#x5kq1l!f^vQkFJ-bS(6FeqgNw2b`?jUZ**o^59Rl8429Sxh zpnv^Ujvrb~-~m%AI<=*~+C|k9@JgmxOQe`ZfE3~71*I-b83^LIs}0sjf!$YYoeGJx z2Taxh2<;CsWPrX2VAij!^%X#z(PB*W@?R%0?~qD&vpE7`@r?@4q7R^5a}~!y9PtY9 zOJ(VQtT^KpN@;R9eW6J&qROG}9AW;99#;#QtU2PNGz%0P?oUS5S}`3&HMl0lg`(5> zV>wiR-s8IZTu-(9Ozd;V!si!0)&o+dEWe)XtRXT^;kM^>8<hp3Z)Z1N?PLurXNp95 zZV@Z5SF;MnXj;ri-F(udAe}gAk#5k*cBqv=(RaF3@o#q<Ef`o0JDc?vn=c;ZP}>)F zjWpjIV|j<qbjfK^ItUsDv7dJ-F9<&u%6zI>m15y3nrVSKtg6?V0)DmLVgP1HX;eCG z@>I=yu`MyYEO*@#6M0!ptrJpo+W|wSNrm_f2G&%1`mVWlTLz$-3}qJYkW?)X<Z7uH zL&`HSUta7$Nrx0;8lUH|I5GeWQc+?-og!;NqY8+q_NMM?mc;gq7uH>k?rm_31dZyh zvtb#EBXOi($olHo$e!2+>lYjX(Q5Aar>A2tcn{)VL}h+!d$I109F_ogbGku+B57S1 zC*^*M5#iF6z#83`6dFlfEIX-w$$$(fWeEMm(8G9;lXAW!W%wCnA0$7?j#%uu<JuOA z@(hDku_z%I&<VLYy&Tek{?<MG9-tr`-k{jWX<sj@hZL9SlkiAn&SGCBzr1vZkUZRT z=?-Xk?WN*An3mI}+yy#Tw_EcLAPO7)d~8$X3lLx!xS0zIcECkqdvE1};Ku>eToBLO zVc7-V(oUC+>wCsoX0bH*xVq2T0~D_wxOAsJcx*`GLeIn8A-MOTWY<6z1HF>o@Igg8 zUu?hX?;!kQoBi)TI;#<h@ocKo=#kcsK`r=_gj_JiAJ#Q8Qp-EK&wyC2AFc6!B39Mo z71xpUJ10)Nl1dSg2xZ<PK~<t(rvGjo6RoGUhgaHxzMN%AZi&w>w0s*bKP3iJPcn`Z zn5hLAhcOJ)NeBp4+N-G1>5t>&9%ev_sRzw8z8ce%i6yTxbLn|*qYyjU-LZHqRdn!{ z*MzMl;%#m!;8jc8TR+G<dT<q_c)EA>6oVChbe@vNedhav5kq92T%8cp8O-}QKA{9g zS%fkQlvu)m*8ngMFz-n9<7Y>oGcbEsAn3wMzTrtYIDjQZG;$)24M9{$`xBn0)ZU1V znm5m2KvZ>r>FFE;^(3W(Iyww}lQ+gl*|*%-?|B9#wjMKWqh6;(MJ40Q0<FtR?7(n0 z5ZFU#>41U9xP$C>(|axSo`F@Z(+twnQp(^Yz%+gpktRR$z`AS{1)?t^Y2Bjqf@0sf z!0D0GHos;7LI68e;8;)2gR5XQ=TwDDV!)^FnA|5Fvu~38gNUw_@1W_h<>nF1IgZKv z*LvADL4p3W(~;G)`TBjG(QlvOgVSBXuT^cgLgtHW=Mu+D*6Nx3TNlEaX5K6<fRn|Q zJqU>Y%gooHwL)O9ayHZNMgL_)P%Wu?nDjt*k)wezEV}U9`M^(H_#qUyM1I?;*Xo_u z#&SwEeoko`^e&z~L#Xateqc@9xR`YSU*Y=H(!{j@7g%9d&5nWr&GiA5Ax*!O!LNDX z(Vy<MIfU=<BBfxv%Tzs@hos_1W_Dq3dBzqTzvue6#6G#o(p!$P0<8n)4#nU6SsrHz zTVwS`5P#PG&0DSJnLwznv#l{Lp+V`1rRzEH6JjcxEhuUG{$W+BP|dnV)eLO|Gy38@ z*s#G$#Vp-D`#EoeRd@65>nz5wO(uc&+u+7k<>&H0rwk1?m{hkId#93>=DA`=brCVY zJr;q#g(AJ{vN=JvPvc}>*K!xWVfO^xRGv{T)Rb`TLEcMO?pGx?(>tpx#!u^$P8p{l z7c0t^YbqmODTN?oGXhdv*28!{EOe~CxET5{CVh2vGSdL5@^_klrJeyXo!lN&3lB}U z*~>KmIpg;XY^#!TgJ`|?p5;#nE=RQO?7^jHV_GSceWh`wej=`njIK7;i|t+kV|O+R z+v1Kp%F{oAk2<hpURSrs(XSKsXat_c`o|7-S8Bz4oXIasDQD#5iCH#Sm{57XW&6qg zZ&_Fd%xM1eif!zr&K+u_m8E+B<nx=f-Z?AF$b&j?!?u$0!#K(R!%0H?efm8<qt5{F zbhBpcxVzG(D$V9h#-bN&nY<#9MBo2+qR^n`q36Mx*Lwz|C!<jnf_Hb&r?!>R26JT8 z7e?gn*|i`jGmumNMJmX@`OYGnWTDvF%GjsTg{!YjLSp^S>?0?MY5Pd;zlVlOho~xl zNhUn<Ahip@^0juEs}sxd<#T)8e)|1#r93i21N}aT&zX2$_$OojFSEK;L)j8?EB>2; zTLwkR37x)ExRt#?h6TQ4`9;{#eKVpNRB=UnTRiNLrgK&G;`@TmU_>H|e=F(y%c^9i zr(60<w_<|zelz~<`J8tOPIw%gkeM%Be;y?Y|4G~~Q7pv-m5U&Mc6jW!$xjrKK<^Vq zEUA|}k=*v<=g>sf8pR6#I09B<0z}DS@^2-=ekZ@IwvT<CB}$GzZQB<On;ra8Tv~hN zJ(u9mxlY$mmK@9KadwmIQWoXgYW6xvdy34q*`;1%@Xz?U`|3A9g<icLM#scY>&3`| z@rF_IeXbyXmlrVODKl4RqyGQQ_x;b<mfzGdc}X!$`YempcNWYw|0{IgB@}M|PrmPi zaT(>W%H|1SQPZU2ubk{2Q@(1p{=c!UfB8P05HqDVIq`w(?`?n5f(TE`4&P5JgE{ga zX8h0$_h_Y3&flRVvC%*2?26Y1g#%Um&KuUDZ_~;5P3Ktt%l9Rz;9C72^wvT>ADFZl z-f<ik6nG{Fo6B)oXg>9PKg87F^WiDFlUmCx+j}UUNkFXHva#XgEDx6dD98Gz&)#&7 ziZIh6syuuRCU54qTd+2B4%+$-0o3;%%`CsfpS`|*CG4}>bqML959x8ad<TsiyUB0v za;3CB0T>W+d@#g&x*0*q_f<A-qb9#Ic$DYMTIp378QQxlqy=Z+RCbDF^;Tmycbt@L zrPPR;!tHWmt^qv19~9xLsL{C@A~L(Fp>5t??Hq~fGNbh<RxMFK1$#{to5uc*7=MG> zXj$~Qv?j_(=d!W3^svxjMa=i4hT=1-vQ;wcuOcrSD87!}Cx&{^e$XlD%Wb@M{ZwgJ zJ{DK=Y@%uA!mCsLv18gMBTaJ;(WU};42zI@gGV&mJFbwX+qd4Q_|!h`$a+q~OJ3Z2 z$#mVR*>vybJUn+KXz|%p)X@~ZzPbNa^OYM6GBq!V3gP92MrKrKvpkWH&6X~QGBs+B zy<+9hp1Qsr7O-dfS*(^J8_&@1LXmrw#%p4lZ+8Jurk@S@b{pxL`}3QS*Vv%^`-bgr zN#~tCbGOePnJHHYxWi7&?qWF&;MeS)jJ*+PT6jEMZ+es7sPqZ<cH2f#P$!4LgUH2n zO($iF-0S#@EN_~hGxAvvVye=qB}ma^Sf=@Jw->8*(E<4fEi9$PT`PCjG!>8d5p>=Y z+*P-IgzE08ll-9mVS$0v&{RozF{E>61TI!lSV^nna`wT~cM0Wku@|+kZ1t7#dhEA+ z9XflLc2C5$Y`OhN?)zS(g(@J<I?>a?>2k~*7JR|=i#GP+d2&|suWawv#Wy+fcjHvG z&e;e0==5h@Tkv~4orgU?Cn7w?0r0;3;3C)-@SKY+ti!C%%TM*Cx9^&=Ep{(_Lh`CA z&_<gq-9zQNl^7U!*S%$~U-@Ccr^8xu(gxGnsHR^YGRH{wx^UO37i*K6b^EROvv<F+ zvx*iF9i3$sG^<9rTIv)=hp#(t$PW&_!6g2iK4;jFDHdI9MU!K6qlzlpVgJGTWihRA zL5FJwXGo_JUB>z7-@RP#NdtD22hBHzsEAJ)>s^yi>=+LR%c)}e`2+?g#E&o+0P+oU zW0{2xM}+~KZ&bh-tPl-3zG3&Ln2*?FVZJn#@$Q3!FVEKz_olW%aTX)JOVnrqR4=2a z(4+v4e)0la(na3DV)>$v_o`b4OSru!6Z{8?IWDqkUV62Ilor>@AlegT_)B=QMQ@yI z@lJbuoM7)h>L4VnsI9dQjSabj>;upYe+ASL0P&`3zER9|VxQ);71vYIb{(@imK4ow zb1O!{ICw`jU$K_@#j#$^TN-6)FKL~H?uwP?3c=!c0H`5iNMvO+`d)9OGyfP>f;Xl= zd-ild<jU{?^Mgl^Gqr<kwQQSW)OJ}6(oCFW&&}tQ-)YQNw;Yn*RD1)UVG;ON^G4p> zk-`y*K`vdh+^N9f`^L8~B%)o_*x{HHfhmCvyKI&B{kI}_!&&lV9b%^xU%Oc~W^<Q{ z0))qzT#BiMjCp6(jCGP9IGYq<-VU5?v4a9W#wxyFw^lzZAoATV3pKI91kAEwXt+8T zL~%&V_w756pw#kPSaJ1IpMs2*C>83_{<Ga6RDb+Z3DWJpMdt?s0iISUE$Al5zou~S z_j<KtWs#7+)74&^=T$6f8>;#C&}-x291MzLc9l2Y1hLH2k6F<5aa0*bvQVq{DeRrf z<cF!_qnb;XK|D>~u<lg**SdTwh%ic(A#C8XK#RAigK6hN<jsLnI?J0L*aHTeT><9S z*Ae_b>tpBtu5-RRt|blpWO7s7*N?lOuP=Hsf2+`&yJD9{yb3wFVDY_~Z~msD)!xjl zxn5)t5vsf`%^Wlp!97mCDCrT#>_%wiUoVBq5xt>`!D`%ns~X&$maiXiwI=McmDyx1 zid`rS2ct2OQjgYCJ%jsunQxvm$$4u6cR7qpJVeSZQYA{NrsmAA(n)q(CkCpYJKF-@ z)TJUbhf>~yGh5rzPgUcdOl`cV#|)nF@{UV?)E}1M=v26?U`L(d%-x3>ILCLoh;)An zDJSJhs8tQTzCR$yRZqk#Pe{y^eV-lsL#OF{dGW5d*JHuuT%0&L3~^;lfJ5oCNb{Bb z_NP74iAEyNtEI3Oh2m_zO?T>5D+Voxj~}&DBhDx-OulxC>*L?`!l~HqtGg94Tnm4f za1;G~sGH5lbD42CXg&@hA6lHVRdLw!IoBn4>l-gz<bu#tj3MnQb=;_+k5+ixuKqWN zoOfQhbNk-RA(@Je5UNKuH(I%Jj<%(@r0`6gfeGJ?&vEreX+&GJ^bLDhC3ZPCSL?jf zix{|_uPrhlp1xK)BPTSAOp>r^h7CstOz^H5YD!gvC5FnfJj(GaF$kpRK2>;Lo@c`X zyOtY<coIw<y>#a_B=l{f1n!q*P>u6!Q}2!@YJ28O@Q=^~(arN`TjiII@hS#X@xF%Y ze7`bB^#DorWbn@PGK5=c!U%Eu@ngOp_0aPMVUN;7hSv=v^lT|H%DW>!--K~QsY3bf zDm;wd?XH)}WK(oyPcd)2-nTOAJ`IJ5rTHyT^HX0^qH8@h#~T!k^%LLM;*4tBMT|#s zT33w29bf;caILQDzu=Q68~i;as8ZS5kUM=9Ca+Y8&tav&@3{DE)>fGcP8EJPp!nl2 zuPeQKw(_OtBi}qXkebTj{vz<s^xefHoQfKfiK_16w2$Bk`pxCbkUyspXC^aW?5s5~ zhqDDA#a(t)B_}x2mjB`|O`1+IS5{ajm-vbP(2y~fJY0ON{=@%D>N)vOC-0%BXNjD@ z4&?ni98fKwsO-qKt!14$Vi!lZ!mw=LTKkgb)~}Q)j_@_v01*0>rrQSwl`m?<+<w_n znX)NSJD{Vi8c{ZT?xjAU+zxwjdQG+iPESBWX(yp~iL~qI*a?AM5ZauP9(dWiYl$hz zyAHxT3ed9)w0=_1S}i%mW>N57ud*ADdl;8jMOVLdNwanx!dSIq{_=K2@A6uUQqT+9 z-}u{7IDyID_6^l*eT|ZvQDQ>Z4M-|<jy=L`{Q2TA&ft#c(S4`a_Lv@`6%FigPiZ<& zSrwD7#iTIckxEz@2E4wm>SadWCGGyQ#ZL5wn7l`!7lzx9r1<Jr>ECLhy~PxbYxw9k zyq#88x#$hmDgM&OFV!rtI}F(=_KEVp@xiOK-`7+&iU(q7qK}@$Dl*`c>>&on&_5fp zw|=8w!4Q*x>sO*X?kcv2YT;Hfimx6IUJatR^r6pz;U9~(IFjk87Bp<*1Z3mTY5{$Y zg=xyap++zwl}vX_VdqLidh`adJ@BUceL^T1YsHlux~uLXOXTqAu%ao>I8^f0!XD;C zqlKcKFL#!ZVC|wU`Y>YB0Yg}m=Fo>{L?nz;De}Q@=&3J=O?`*Xc8{LD(ehcB-Tw&U zr$y&?jE@i25?p|JiN<?Msk6PJ4*}^?)U}H+vGUZ~#YA>%S-JpJa**CAjT>}?3h*?< z?JCkHci|paj4IXSX|Qq$^CcmYhC=5eeO;kL46jteGh?!Z?`B3|xsu1JyZlTNqIdD3 znOHY20laMVN+$jKAy#4&=f0$K>21>^g&g-xn%e<wf4)8|JjT1YayNPnE00Gq{=SjW zH70OX5g5VWRG@3F(o%@vE#B=Ytw*QoLIl=ugC67d3!|Z0Sa&;$hNMWswgIx@qt1B! zl-STVoPLiQk@59$mKtp!%Tre|tXIv>M%n4}RK(mA+<9cAz;S%>i1<)Q#mxiyz!kdE z1-E0<SY;evsE^J%hB~9L3wj1yvP3aHZU^$Xt_SyntI7(GU%wuicsw`pS>1p<AhaE+ z=|I+gY$%(*Co-*0_em%H<5b-D;9Fl(->58%hoWwUb7h51z6o{3?!K*CZDQI%Q_Aqe z#}^FiJi4}*BHiq`**x&~1z|LYZ8Jx4^6HAWGyBWN4KIa{!R4^N3Zo0$jBO`SPQBKb zQ$w97tv6$M$^&E$&q*#ptyBlRz5?BP_1GCl*cuPi&ga4zn_Kn7v?^IT-}<3kK4b2$ zBe*&I6IYxA$P-nS_cl{x4X$Alpz!Zd(6in6nfZwgAMoO`vE(O)7_VD?0PYDH_c);a zhkcZ%+M5BjLKxG;6{l#oNA+UuS5vL=$pg0+Yi=J4jI3BFIWW@E?sqiNWF50kg`#Uz z4CU=DgwFF^R=-FeP>(yjFSSczJ||4a?WEP3YqA!o%(f4Ce;IO30jqHijrNFxT!hm6 zItO2WPMxHaD2jKP!&wI4yxXc~$4vcDbSb~}G#rMln&0WWH{3gzY>9;wZA^K1zJ2gW zHL^;}+P(6O9KDbXB`x_+_gwuY>zAorpr__J&9C+``Zv(V{!6)4w_){8#&#v2mtE8M z8_zW{+D@*OZ&RW(&oK!ZN1Rf6hXH?ZOsuH8m}CK}YmcU91%j9`63}HIh#L{-5!*;T zYF>V9@?Zh-BO>yKVe6ryNdkB+fH?OL4n>($#o+X!C?A=gD0<5fH-x}`yv&A(vt8SD z64v-djF?7e{m(%)i`V(Q%<8Y(^S0(MNI`=$l~a7cy{lG9&FzPo(Y2`VJC4un0_Y4; zkRO{O>oFs!aIOTI+29LC^uE)5mXOd2i~Qy}_cjQvc4uR)xJZLy!;NceeGn($s&WPP zE}4`rSm#~Q_>_!qF1;LCYu#-+TV0>N4&d`8ihG5Zq^0m0rgsE?wM4&z<$n|jFvPo7 zK%b06EdQkY<0f`0&DtpW;n_n_G9xnbx}p4K)@si=I)yg6E2uktY2hv;$a=`~8yVRf zhvtoka-?|kqYh~cLWF?@?k<-FS7VJCG4d9s(}hrOKoQCTO;#l6G}C{Jm)OvHNM*;0 zQs;E&vTZ)Aq<AbgSPK%EiFc-eH3E$?#_s*z#luoNTM*}BK_^F`zKq5Na9z1a!XAco z#+d$xQE`pWRpG3E-L)0Eyv|<j079JVv2H2QK-e=r#IqmCP}Xxemo_>bQluprTCgE~ z8Hfl){i9Yc|D{%TYaCBU%6CP-Xx!zZxS{o%)--sx<25r2948E86gBTQhbs{)z4zp| zjMQWC2V`k)vX}%vUQlJ0Ld+@L%!muR`@*76c2VxT`l&0wm~Jy=x|q3h(##dB?iDe) zK$ou!QT08q+TvJ_wg{+zyyv02hWgjK4CTU7uDau0j=KE#hoFhOR)bR;_AYAX-naL+ zZ8vH&%iKVS6~$>O6qx6nkEV6DvUTvP$GM<4+{Eo}Bb@Ea);ll4Oq{kk>RQo=XbkXw zc31fU1TgYHaEsQ^f!G@XV->$MQeW7Q2hZu`YBdxM#&TVDTN-I79!})*#qeoA|G(gt z!>j)$*N{*6mI@;*gf9Z$cWI?)%O{JqC~zytq@+}rIx&h?iVck@vuJc%e%1W3PtpWH zpMjklj;p>F7x3TYnh2K9$b#)ZaI3Bs-aLgCmkQvR(rv3>>z8tY)d<jHroyh(3Fhmy zKi`U%yO%pCaPs^g+>+qC(9!haUB&Hc+t(fcl4}lQ`TCvzc2^&NTzTEu`sIC31jAW_ zf629x6p6bNUG0bepS!F7JGoYH>!pe(4BY>in0FRUy?*+~-!K%eUH|?O1D6oWl{VRN zRh60N2t`Mu0W*$(+WNsnvB5)yp(tS)0vm)Y60Lr$(PW3Ks};4v^BHBTsa>Lk(s7*6 zU9%y85|GWxdH*>n8cMgep?ZGLn*`wyt~eJ;oQCzBrC+Nc3DCa|Af!O<6IMBZOsZ%# zJ$NeahKb4vPX=I-#hG+FNSY-VhD4D<1rh4yXeSk+Fy;qv*|O|{KN-*me#S@IEPgD} zbby6VI7lriL)%*r#=?`Gt}jakBxZ!&C#14iXic)i>;ubFq4%@YS-q%FsW4|k5Syjw z`zo@r=q$IGS<#>=H|{VQJ=#50gH5rbSf}lIFpj}!mk<UM;)#5gs$D63Z{VwV5-o#z zz<xgbg<+Mdo|UU)RPElV$PGyND~D%u>)#|J(nXpC6S%I3+C`>Gsy}=|OH+@I;m(2! zsKYsz7JE8X_sIh{<#GvwY%VniLtbI42g5XJsOKZpA&fHgBD}JX=;@_<4#wDP^<;qa zQyz_InMTH*SCIK&>TxvmqK_8{6{qT>)(|})-O&C0AoMMwN%ozI<|o5a8mQj48ET^_ zsxF9P7P^gIajk@T_)+b5w9)1E+IWZr3{!2-;6q*rph1UCYdts(^uR;9m@qZ8$$9d# z!Mr|NaEM)4jGAD&C|E@;r}B!y>MTN*jw4itK-lLOYF9l8<muSfd;GwVWlM5kn>~>) zRdJ8+@byo%Q*AdxTIir8C|drG|7ZpNP1=D)M|?m5IJ1Z7-ECwjXlS}?4%>^!7}75c z123R=qCvy@-pRL@mjT-8OG<W6b(oJHp12iUM=g<OAD;d>-g$QV_xF!46gtR=(iSBF zRND{TAT?IhUozV0;LKqNHmlIj?7hu$_2Ge?D98b%m+4VW1pgEl?1okYGMQvAq9o93 zT%qRCP>;<H5@2-E>gQP?;}lZqhaQde^Zz8{(TqjlDPC(pkmn#uORtC}V`M<&>Or(& zToGHj)}Xl6L5#(C5l8FDpk&ZNtQ})9*Ra-*O!h&Xt6nkB?8wlSj)QowxMIE?t>LQ+ z2MGb=#r!`;hE;wZBw`p#P*Cj=HJ-18D7_Lv&e4%LE*fBoeDfMWO7LszKhr2Stng}5 z%lqgC>d&zdAUV%t&p418FB_#oD~MP!j3BJqjVS8TB*xFt_@rzKifIOF>m@wm+o*?$ zQxO@%lx}bh5aSxT)}w-eRW2qfsDc7LCiIv_pn0nFl0zlZlxdSKRdnFoy;i*ebV}w+ zAYb+GL1Ii(N<5a!M8h}<0qpmm{ZbPpTUvRVWbyfN!5>-xjZA(M8C6VV7Sp_TVx)2R zieoMiKr3+NtAV!#8?ceNEh;fTmhk;8s(YYBQ<}xt_9@%Bb{{RtMoRW)+!*x{y^CB{ z)yKx&&L^dQK!?xk#6G1FC{&0NK4X=g!S7fEkV{0*3F`PUM)KZV+Cry$6NVKdQ?^FL zMHEkNM=Yrc{FTC63|nc3rLs#GgD_pyprl5)Y|g$#HP}v%@q`Wd!$vD)8?J)wkVb*E ziZX?ny_vBnYTzfS65SSU9#?aY9U$Y40yC$veCG;6UkE9!s=mv+mnwKkSX}c~2Tzfe zgJ5Uw*0uMF^Sm=YC<0|2or=U%aS9hIhTPv$$B7Xhv6;!Y_rV-pv`zT(IRIj3)D8f| z;w+lZ=;{lb@2(M4fSy!R7Y%UKvm6swoJOv2lnniqv#vJ4yA&nK>^n&a8ac-e^w3G_ zoy2}rd5oHs9g(;CfY{A$D(*e`D1Mb?j<v&q@9H;vxU#Y3;nkgH4IiitvyA--Y~w5_ za__?BT>Bs3w`W=&Sj&%%x^61#XO~i|m{pe+yOZY%8+02Y9&?Q=iCs}Kj&DGl?DsoO za1Bdw>?VXRsX@&xt}AlLTngDuXrc!AHwe`}P8+YqzTgJU^7XF_t8QLsb#Ao%&+e+T z%$1h$dd17xHpSa=jb*2=ADA)aZp39PzMGfz>uz-YTH`_@x4*%N%oWg3;MU!Sew=}9 zVMh%mxn>pB&39CMUjKv6Ez4Kw6S7bID#g{^J0v=NDpE3j-|tG@V9uBPW+kb(CYoY3 zZA&F(M)ljx!XG=himI(ut(|{#RLIvna8%bUXo`HC)fmTrMPIG<qkzN{i9!`vM&2Kf zvVfzr<#f`C)p@BlLvQ`JP)-+bzw#_Yx8Fz^aFl=bngh0&woLXzGzp#glAYVQVyXD4 zjzjH1u!~0P-yv<OMeR5XT0RNy)gKAW`Rw+WyMzn6G*oZ@@yg_L(EC#7F?jdUXya8M z!_gH59i0o0O7>+kiKn1<oo=_sA%E7EMD&$(MTWy1RP*-Ol_)vBgu@KS&K<dSMbdp4 zIFk7v+`2l5V)Q7j9_Z5d57LF~yHyrM?wGy#>1bQ$n`qbmQL<8au-Cw^EbhfVpZCn{ zWOtGosK!e}uef;rYogto7eX#CJN-2)e{?&P@^CF*nECS;3}SsM(5+Nw6_WL%|B~ZE z!tluAx%bEb^}Mf{q0y$7-vnlO8JoI)`K?Nn{29lXe|SOV{H*RvuNhtS&vg$&Hgs=I z4Xr4Arw<GH@bFDg!}-ml+)J7lmJ@#A>f1gKp8i4KRDLqadaq~H{I3lsZ%E{^@$R&L z13D)EPh{7Xqrpp(r^lV|f6sliJ=)su{yF;)Iryym*Ox?Pa_k%9{l>c}ub0==UcLG0 z)mSk2yF9cMdaujn>Bo}LP^Zw3<pDdIfziWe)D@xYoEYRtU}oymJxy~_5zGc!m}w+v z!#r%?1#vhWI3f?O7~1X4`oxe-PkM~cjs#ASnZr!Olgh<AN)gLHthYhLvLU7v>II;~ z$x^zM#Yte50WBJojRkF{ts2a=3mw590AqED+32iM8XIE83tX~`NaEBXlMHMWg6cSf zK7j~vQBah_w!O*oDQ7tC7E`0TE&e<nq6!aj!bjrqO>*EqS$mH?@Tmg$(GD~Wz_TC` zx^w>6Qy5U|Wc}lObdhFQ61)GO>4#174jW|SU<<#qZ90jmft2fDIVq~HmANSO?zM_& z!Q&X1G?N`HwoN{2(k1qXIj#u?6i4}S9U~i~p7dr024(tA`aSfjK<3!R4Q^d)Dnq)v z`cAemB?A8A5SAKB|A0eR%k=hWRN(lGCCysA^oZZA0w`hb&W%K9jl|{oGEQiD@~K8^ zw|eG%kLT>g_FFvaDt)Sy?*1CW(ovDX%jtQ2+LZP_(km)fE+g(Z3i)d{z;D;&mWc14 zITq&8M<*F9S$4PV%wsUZ@p1A&TcXGv5K)ktMD-)_t1HV2Az8THT|A3rXEnO+*z3iq zkK<+TCxq4%q)`e@FF|<6le&TN6f~BO2GR5YzBK+EeaIRvRha6oCa33^p_7Uta<U@y zofmi|D{cR~c@C7t_*gq-I!*pV(Bd`|4R?q&SNw-G0)-o;Z8HBMVNXb@ZVFh-U0s{Z zTW*;l#)C|BrgjBw-s$BS9_bYPsF$&m&J=C>Q_V*^sg~OJ6Qm&eJ6ul%eeY(DJe9-V zOV$o39MX1B%ubp2NQ5N_G-uCqh7RszyNP*rTI8I%fc5t=P-Ifehk)V1oFvXW`x*K- zIm4c3h4g&z=MfDb6~>Is=lq4`)%u54NWn9-17ozc>*f-2hxK2!c~-b4z)t5utu}g! zLV6*ORMQUFD`m2vP7cE7pA!LV?QAABqaSh^-yh7|Yt>E_0#oaseklVt#4;ky?^3Vn z;lsfuG_1Hsn_wQ?g&~@nI@LihzDYLu2}RIk=e<+C{r1SbeN<zMw%~$H5#)$*jhnY! z+Z5`}NTM}@9K^~b<-UC<@LdsU*<7r|lg3Z?M7g8*`d-S^RPo|a@kN|bPpaRm<nu29 zeF~U-<@Hbqsn^p~GW<a`1c1Cm-XfrGx%nj_1R@#3OjX^ARMhD=*^C;IcLpP|YzIs^ zCEm`Ph8votOi8eyj`E-?Wbmu<r$5U>f>?sQM7z8g`%n~GLX<e=NibIQnMeg&q`<FI z%u~Y5UjZfn1*JJ)cu8P-<aqC=5P03G)I6xF;%8K4N0qq_^0yFTjYEeLC!`SvzpjG& zlxKKS%w+%&V&~N^7wIB&`%HM5UN8PN9gtK7ayEmfY(*XcPg1Jxp0X2MBg@O2!Lc-R zuC%DAAH`PR%$GsL*ZFi96=7EKcB?Sxr%_rKY3}7*<4A8)IK@l`yz)`tr(@>pX{K`R zsn0T^GuU)8no|3Q?~P7@Il^Wx)0z4v3B&bCbXQr6o9n-xJoz-B?W6qw;SRbqTLvpy zwJGX0%QDjU>dVc0-@mUB=)yGD5qfbLzrD(oBWrd2bPu_>ZPZQYHMI#V_+~cpJ<dhw z*?Co+KXxWPfX@3>T`~9CvuhRNi_D)$K9h6-Kitf2Y~AFB=*#Z0JeW><-GlhT<}oky zTpFKR{7u^j4!nTttP`JCRBEU@2XK3v1&@N_v8>`|W{z;c=0tmqz17Lb0F+BVm()s+ z%!FKJ6~C!-VF*qrDU6cPv}O-gAJfIpH^fP#HL~fZIGLz*YQC{+gM^i>RJC6@XqYdF zEhp);lwu_oH6?gb|I}yD*qhju<=rW?ocBR2+dZQ$WNv0d0N1oGJwfiE6AR`!*sUYO zN}0!Cz#3rFZXNs}?Up%Ln?bDRGt+7gdy~JX^%=&zotE~knz6|gbL3^-6(Q?DDVe*> z8pKGnF{!#2{zBf~WpY?#S^>>cs<pn*BZp8gMdz81c<Z6LPd<Y>DRME>)t&a~=^xVT zP;$o8KPwbI8XA7n>gGjUz;;9n>6{SpKT+L6RLzTvNGHp#M`=BQQ_U`mZDMi8o8Nox z-PHLa+W@gI{-$e^u~{tYZMH);A5?H=p#%xH3dJUMleBx`!L2|KB>~p?Ny5Kpb0FcB zc9UU}B%_76R@!Ec&gRV|`q%`}gKKi6+qK0k;uS6}DPE0zC}t|1B*gf&gwt8VY{q}c zT?C%t0^SU?HW+7d?o9Q(2BK=TQci^nG~j?mI6RDzlg7H!`h&B$vxyj&O>rz|N=+Nq z4^dPR2^b<;L<JW(+!^#nBZnNir9iselD4mnhTH6gCE*&3uK8U#WK?ynPrJl{HG$pL zr8&*XLfgS22}1R9dD{-Z<Z@aK0>2ENePdKoVo8(L{glb<rRUl`X3V+WdH&csrv{Ah zK+bwt=YpxRAD#Gj5b*SHXzw%j`v_n2*Sz+<3-tKY)mrZs-Iwf4ut`KXz8Neuw~T2$ zzA!*z5BL67U=yt6^%0RnXZn-$YGj|Jj&*&^k@h3Fv1BGqPYhi4LKHf-1eHCPqksNe z3`FIbo_qiWsr!ZGD9N>k{D~#q{+d*p17=}m6Y5$=2vsrlL2!O_Pj^$py=Kc0hH{Z* zSHaGypIdKJB0U(A1^_9e;nf$)dO8XhNrpqls&vtkgTpD1PU=Z3#aBATU0|+>Jw<Bk z=uOxxGjDkrQZk;CWH=-&UqE8`yuJxzFoF>aCKrXj&hFF~rR;I~`dH4wh71NMSvHXA zo^Io<Z5(aw{p%f;FiWO>ANVB+#4qCT_XUG(qW0Aq@ODnus+{!zNKa|?O@g;qNKCi$ zI-~EnR(1AMuQ8u^fzRoxpuGj}Ht&C_o`88XB&^bZ_hKF++Wihf{J7?E<EIhI*?gQ> zL+uUCCg=^nV?Z`L>MX*6i5|w|Bj$C`N%oJ&^^S%dxq<5y-~j+k5i4ozZTbxFR><nH zWrMAD=AUS*Q<mN_+qgB9-2TG^P}bYWu7Xo^x1kM#vBIm<%KcK%X}E+_d!GSiCS7H3 zQcKhJkDXD+;4LQPYFR4G;VV;ncJ(w{p^f>o4PDO^MxDYE!#p@WOEY|oa<InHyt%2w zETi)ZBeHwIV1YanDP^#6)P2EhLhF2R^|Zmhy8hS5qLe`ERe}*WR@-l@2&_ow$J%X< zXF0b$eW#41qWZt@bFl)H@*?amKn0_f`p<nX=(^TOy+A+ZcsZYuX%z!TUXzvwIY-k& zH0HZZ?JDgBRg>nH;LdF*)?@+{aZ*Zxk!v^4(5PDRRFrBU_!Q_UDeL}CL=xb3!7-{B O_qG6$b(IkYT>D>m(ZdJ; literal 0 HcmV?d00001 diff --git a/images/demo_proMP01.gif b/images/demo_proMP01.gif new file mode 100644 index 0000000000000000000000000000000000000000..89bb8a03e3ab8f39f0a1545da612b8840fd79259 GIT binary patch literal 479562 zcmb5VRa9KfqG*jv;{*%tZUI7YcXzko?oQ+G8r(y0ch|->c%X52mtcLrz4tl)`R~iU z<JPE$RWIwM#u{smsyU@)rFeM1hrn+`KS6(iLh*!xKtTh9p;5J9PzGUP;o(t#A)+TE zv2g$}m;mev02Nde3N%zaG)znxOe{i7c1=t<QS49dpD?jM5%uHhvf|+o5a50OjQ^RC zl$y}uE750SqR%8mA|AxrI%LFT<d^^|G8$SsCR%A1I$RlgSvPt|FZ$vRMq>bzf(Nr` zAhWayYp5V=YA!n~2bZQFmvbsNI>I+8Wgc!7eja{7ZX_YG7h$n+(f(lx9$g7Bc?of8 z8F6))V+C1h6?t_eMR_STg#>le01c}_Ej@m%Nj+_y6kU2BT?Q6iV+%b!LwzC@!$LhH zgEwOgcw_%`6VqZ-dtbBf=H`z17I}kKwr@7JBewjA_BqZD=7!D&KF$`X&NiGLu6dqB z-k$EBUj8{=Bc48bg?^SGp!W+fD+pLn4eSQ_0|Ns51_K#1LW4uXQWC;4TqDBLBC_)% zBZnfh24WbqVj8+*zc9xRCd9jBCj@aP<b)@tCM9tqr(waTg{7xufYQ49f6)8<(C7Q% z>XsQCn3-3V+4(ao>qk~@PIga5j-^4)542njpWN(%+?>a}EWUz*;o_pg;;x@Rdq5>6 z<rP`O6=jtbWup}htyRsH)%DHQoi{aAwKY{kHGQ*nHFb6MO?7Rp^|fvFbxrm4bq#e5 z4RwtTbxjTREsga}jrA=}4K@EPnrm8`Ynz+vT3Q+_TN+zinul8c89n2zRSj)b?d>%+ z9mP}~ZS9@yzdGATyP|u$L32HQy}iXfy@S_%@s9mx69cwx1Fh_XF$IG?KS0Szpuu4f zXlB?zaiqt61T;F%$v&P}I9^&lL5wnq1T#50Ia4?^*W5cdJG1!vdhyTv(!%OW-^l9m z#h=4J>jyg<;H{0r^-b{J&erbE{?6|9-tNxX?!n34&i>v%WB+J>Z+Cz1Xn%kIVDF!K zc(`|PxOe!^`grH?<N$nfbaJ|VaC&liK09_XI&yh>b+x*BT~T+vaehliaC?3CkP!AT zasSuG`sMlcT}_h$f}$j;p)M|}BFVwZ4hszh1x4`}4xR%F8jAU!XQ+RDCQwKaC`0>p zk@~`cP^3?c24nR_Ly?$Na=9`M#lx`#oVMVxhM%K}WW4PvyQYyi_+;GW;QrvyiF9_e ziCo#H(&-!?w^Q(VQ`u~RNGO0ruDSg8PnlH4jlc5;6BtwsvJ_da7L%p&O|}~oEmbRZ zCPOhKIqsqGN!AOMhLf!|>ut_^6aIdlkx2M_TBjS6ZFO6HL9i&K3hnhfLs6fYjHcQf z_C}Ma<ntALt`G@*fam?&&5cL1h2pWKik;0T3*{uUhSQxbXDjt)llh8sF!5bn%<f9l zU2Rue{h=sij%(p*B&@aA#xva=cSmzS=}HxQI>k^{o9wn`db+$Wm+b-}WXiqWfA2Pi zs+_EMYEiIqe@zxB_w~NN#@3l)?(BI2-=Glaw}aqbS~r6mz6S-%0eqJW<xZg=$+fx| zcqruAPb_vqv@F`^BYYWF(jt)3b&}vI=B_v46E3v2W7$XO_kaXpg|KK8?bg`|(KkGM zi6RKdg<^p0%sE{ty%G}`jx_ecR23<PgES2-<O2Y*jtmhZ6_3q9hDij&VWz5Sg+<D; zuJfOmu4wvVQ(^$aQLg*)iFQ2ycDb3t<PAYtUJwFfxwW)qB(xzOg$*VGS)nc#0y%lT z7=R&7#OBwJ^um+UbUk02vRua)hSK!fq+oc-iPCkXG~cz8vaATm3uASoEuU>wLxe9= zMa!w}DSRZKULO4CIT3LLA-qRXO@9|mF{Dr_ri<p^OWtM){#f_M7L$CB(9MexOqcCI zntgjDG6hWL`dDlqmCD%KNy^ZxWjoB!NK^J;6h~koeb)^o+*R-kExSz}5?!@3z%n0s zy%HeJd;`LvnsQEuMIj=JVLi6dZJXqHE$!nHz=pB<+zEoF=?2!bbg+*y-<d9xR_(P> z=7PUl0ei!~M^UX?-nI%Pz71#+ucnWVvy;?-6>w&l9~S3GO4gZ1uEoaD%S}y=;r|53 zGu9i&#v9ffMb;cru_~|+=$7aE7lZA(RQgxTJGWa}E$kqXt)6iDnF9kkjfAJExKDZv z=|tvlYY2uT6L!04{8@GftsJ?~{e-g-#W9pqXY+{NA`7i3bIqtbt#}F|uxtuPRgLg+ z^g~=r?MFf$(|oUQ11uxp#+Hf3x)PRI0N=3a4Rgzf@0A}5hQ0jP#&>S{+#(S6BZ}qf z_HVFp`RnukC)=d#iQJMf3WKV@%$_qZuMVDDFY<G3$AcF_okoF$sIpw-QM&2jC4@Z~ z_7v<9*m2=`DCJ19s}*D^*H(Q<LX#F}4N35*%awx^Giq$@#D@eCP?%#(+)4ak#4j1` ztPM%(_-;B!q*}~5e;tX|uLlr<g2V&E$*qVxQPChJQ2g-kDpn`O11w_Ny|jE-Dqkl> zqF6CQ?thCQ{~Vh}NFb14Z7flp-BpPXD#xZ^EQ;FR6VXI1Zz5!v(_vIkj>uo)e|t!X zkp>o%K8+Dng>U0=(f7jv3!~BIM6lbE;Ly0Q0oF2N$SHFmblQ4YS!;(B;wZ`G)`&d0 z%@F)VnKi`HFK8ArA*zW<Ff@D(u=O1#SZ&@CuTs2dW-^1!_ypl!rgmFM>h0}5JqOXU z{gIUj;jlUVGq>$JT#4V^FH5rxVwK3`k^6EPRxevro|^@O->YJpQEWL}ofS0l-7TVe zCv%kiew0n%7R$I@5((%d3xBbVGeT~G#JmlW)iokF<WD*(c$S$9*^KlG><mIO#gbW6 zY%DN%HN58e9HOBXf+JLa#O5{EPLf1fu<*Q0WxdUpdUKcYd4rN6UKBaQfBPq^KB-{a z<Lq}iY#pH_31*Sc>Y*?9Ww5+kWOOH;G`71aaw6h%5``jU;6cPB9B3Mu;;{69eu7iG z69m*?4KqU%7>ey-7`LHd2LdxhA$o~Up+YzsU@*=J;0)%Wl#Pa9$k;a9RwF%psmHOU z3i=J-gP98&ZYoHF%3F*&VE~!J{S#`hcks6&5W|Glvhy#-BVI#T-l3X){DoCXGfoR# zjI{}QL%AAT!DBHkNwG%dN*oKb7O_Q0r;1yy_>rAZTQNrTHg1x88Me|+h_sRFr{j4z z*{G;mr9z5|x}fy47^KBhy$l{zuzb9CQLhrSE6%Ls5L54xwr25UwTj_Co9HVkNA1;7 zk8&pd{R#TO$i;?!mz6lxQadj^s7G!N)HZKL{1i}#DKov`f&V5U3^VT|Pkq3Y)&SCP zhw{Kb3`c>|4O(G|9h&`FLQDOZ8^?vfzC?Wxj&&QR{`V)s<tV1ep4Q;vOU}OF`|B%L zRDP^f9m8>rIRxZyFccD|05R_nDx*1Q3TLs#Y{Fp9BGf?~ku0@o31Y`@>)AM3r|`W{ z;wc4S8ploU$^2|rdvT<}MLk_e;|3fjfeCpSy_>p*bt^c{VTqmf438DWk&Y8jw-sbd zi${cRE>bXzA~|^nyBsvaLJ#B$V0AG<ooOx=51r#pQTsf%s(?f(c%l!C9pW#n(^>jK zj1|Pw8-H0Z5GgmV`z?EE@|8-Kr9PN?!i~Jv^S;T51qS6=1gAQ;|B-vzK8u$pX=FJJ z3AENga-5AYa=gkE!eZyXVTuT^)4cv{hD2^cR~;-tPX6P)^@WiF&I%P;$EnBEU+@at zpjF&9z;cP4w2ml(p2$J>3r5Rg7ny{fGc~*(g&towJ10mq_dA6iMLQm9?luU=z+3Uu zTX&)>2pTR7Q<p*76dwzc!9m9^w1(Yn@~JB*9OU&qUPgdoPs*ET;=4(egU%3sa(P;+ z7gls`896qympyU>dc2Ia9DFI^dVv>FNW%A6(N50+dcKHbZB9b)OS+wGkaP2iSlu6M zWk1tKJ6y(?CB*J)=olQGl(^HibFb0u=5UrR$Diw0XL#ecj{$-~AHKqW6Rz6q{5eqC z`w=6?tQ!}V{_^Th2dWhYW0-ds(OlDE_>EqlmB?wz*(c+_MdUfeJ%o!zrSx=&eoMML z{reGu`&iE52lt@2v``jMFj6dfmdxM`kNa5fvKfxaH#b1}TAWk8D?yxZf?%w`2(Rod zM$9A1VE;@BP|k#flm;9eEdhb>i{67M?3;?`p#!K{Is<@ii~!;C{)0bTLYYl{vFF0N zFN;?GtVbxy<ZyTyFi=Q=x6*;i+lXn{$d*Co9_hLqTpn%%`U+u!$e^z<H+;h$*oR9# z;^zE$Pu}5BEN>bTsoFlw<(_$u*Z>c^A8>FGNo<jNuJ1oIw?ce7lkK1)3@GX0N3M;; zxxy|zjbAlFUnOPh7kK1!H1{9;2rz-hCP)koAuO5U@UA}GOLBA;s44f*_IogC&fgQA zKW9734sfZFct#LhBXuXq7%a%AnV`l7$x-7n(+#6cTmxi>l+&A$V0ZXp>y_QhBTO^R z9FZa$xFSU%hhK^JsZA_hR1c|@5cC;>(3a~_7RZCx>ruKy&{j<t;M!r-mKjN;iHt_r zi^p^lez`4+ps`)+Dx1X2Xqaa?qc&v1#XrC_jyd<XM+<*rU@HV7k1}qM$1S%7w$kgO zW*|=<G5A{s*I-$Xn&K|~loY#z<}XBM9#$pVmQTe)iQkoH{-H|E$)!^se(r5(|AhS~ zicu&D5v&uLP3}ceuU69k6<1P=*#(+&Se1Z0VT9cXYMcXJH-UcmGpuf8Y!bHEC;mej zRVqz2-bSSEew37c)w9(EQeCn`S5ZuAQDzwCcsFR`Ak)88A}Ap#PgE%{>cWw(DMz8g zqQ6oIAm%AwJ5reEQyBg#yDy3aHz}kKA-AkTv$i=WTf{Jk1R*@b{r(2eb`6J?0W%WC zgm0!)Nx%!M6NFvndWxva#2$?Zn|}6W-fI$MgKXJd9w18_ZQ~R7`UE43;EEW<qlO1B z9l^6N9lxaGadwZxcqgeOBc=2#Zs#tMSt>>LCv!T2j)y~~=Md+sS|;6|XO=Xq610$; zd8SzytB$mEkq?I{bvD}obEK{`;~v+nX=cLTY-lxlS8;B4b)wcRZnZLcObza4WKoz< z5+`-cb|0bG`EPWTq)oEyqtbd(r2%q>acJ6>QoKK0Oe_|Vb+yvdGc_5@)B@aYT!!i4 zN+CLFGaYHYP_Qfb{s&obb26?7&w=pe{-}2_+;nj4h53&sNT_c4D`gCi3~(CTNK7KZ z340liMM~QE1oL-flbos7Jc9L~i?R{2LLc!bLj@N?y}KT1DFy}Rn=;9<g~q6aNU{Y2 zRjJviiWmt=BtjH7v-DZAF*i?mI8QO*8J)>7qg5^8a!t^FE}4sF=!sjUQPsmpk)v?6 zq0rRBB-aB|IOCg&6eZ;>GjE;QN080_lx#M;=N85)KkA8XBf9@J7uSp3*f;OJ25jKK z8#1D($QGon2C(D1sZ=nm+!rIfU?H7S0%LGR_GpRMl9~9*)nK!%jySbMDQ@UFrXjbq zf}s>a6J-g6f{rQWNsQ%T*%f8UWw|e`1SUEuuwt`ZOyOph>o`gz)Qn!8KZ;W-b2u#Q zr4-d48Ca$DOV=2{)cRTo{_8eYmUz6Xk!5)kSbmiiBQMD~odmf))l(DFLwwaqgQ6+w zdMyVu>~M<VR7}}a9;y>RkUr5MtLx8|iRs7aMJ_NL*y>ltd>MSHCQz-OCag=dDo<gk zd+ap1oTva$GHh`vsW1|)E!M%T*HvZL*+JJmW!IyoSH}cb0AA~ZP3sW|Yu<V5kyC$s zn;=XQXWTV!Aob(br)@w)$wUS;(CVw)`!+J3Ra4pp%g<BG$kK8!(a5jmEkXupICGl# zx|-xCYFT3Okh&Vh^o3CQo29Dwh0hw37zvfI%;CfYF0z}ku$rayTR7F5wQ^e6sao)& zNR8x4Pj6aG`CHA2xD8OSPjUFrt6J=ds3X=|o#k1q_}kp|+y1VR;vd3vVzmL8=wE-6 zQO>o6*wK0Fw@3K3=a~_;H?)PWw>zG}sBUW}@OKDP>O}c<Wae}%c|-F#<MUl}k&1N` z%abXJ!vYIG7fu%a?CP8g#s*h*)Dv|zPGUtC6H)EJ2smR;eCn)T?*b)LsHkeH@4$o} za@n1AjlF)J*nu6V;I>q6og?a*=kHn6?^*WiS<UHL>*@io_kd$lXdo2wYV2rJcHNaZ z-N!kEw)ft^c7%!k?z!9Y6aK!68)%<?SbT(RTX(LvDyfh4KB%`o7~+07fqn#oek5Q& zAh#d2yB{6gkNMV*O+0`jFo0(;KmZ&d%pD-^9v}q|kiQLJgYASRVEMKYifG|Kt^q-Q zq7-+7?8HMH0z+H|L)^e2p4=h6?jZs2kkH$Z2r)=Z03=}mk^+Kc1VBM2uyutP6F~?c zPym)(kcPpq7I0W6cUZ4`*Z@3iWH3wv1Vq#$s29On0!OTKM{K)C?7<_BZzImcqpkv@ z?gpctz)|nqQQz)SAb2$3Z8V5@%<mjltsWtk9ANcp@CZ_fns{v>unn6;Jf0#jo@Owf z4jj+S9nbC_&jpX?zl|3XPZSGGlo(8u0w>CICn~!qN^&(q3sG;$F_fz@&Q0WG9>%J3 zCp)_*yTOyaZ<GDRQ-cCi)wvpp?0^PmltOak*tw~hx2ZYe>3M<aMT6;O;Ph(l^jh~c z7(BiCHoZ+evnw#OZ!mKRoH=Hm$-V~EUjsI+u|Kxa8c;Eo3sE0|v(LG+FWs|m;MtG2 zStyb@7{NI>!#M>1Ii$QfK+hcN#vJ<l945(c6bH0x6^vVU^u{=Z7bx^w6^wg(RBV!Y zO2K(*!+Bc&dHTG0#-4c!#oxCofFgFlPiH_KL}h{7e}N}&fv;ylU}Hh(eL;j|QA}`A z!f;W_e^DlHQLblEVPjG0eNm-mv0Mf4Qv{HgG<G9^u7`$kO^#u3v1ItZWJ<DZj<#$m zxNK#(Y~8bLyRmHZzHE=S;z+XMF1X^!vf^#H;^V*KyRia%U-2VZ4PaRf5?qZiT#Zs( zjqzWNjbAmWS=w_(|J?ICDQ`8-|4(|}pZK1C{tbV!H~tj9|0%xsQ$n)#OK`0;Z><~+ zLr-vt<9)53WW7;vz1eWR)qlM`Z@sf;y?bN5_kF#e1Ux7R1{s1!{J~>+;4wu&i3&g) zZFaK|UC#l1(E&Zle`7UoW36Wcys@zfdEeM3+1wS}+&A1j^xr(r+dS>rJm1*7eBZo& z-%KUhSTNkU@!xvR+j{BQdfV9gc;A8|-M)!OKkf(DvjB?87Z8k=rZ%?GKejPRcd&(a zaEx~F0(J=UcL;lTh&OjgKX%ATcPWK-sf~7N19pi&z>LHjCv&?eh3M?0dmKW0Tt<7` z0ed|8dwjin0-Jk6AA2IC`(i@-5=Q${0sAuf`*OYeG6}z%&e0D0_tk_BG>i_k0uFTY z5A=Eu4Dt`?KMqVt4^4#*&5aH%0}ie84{d69Z@>qRABWDQN3KFg?nXzRtQ)Cl=w7`? zz|Et8kE0;cWAWO<Fr(v$fa54g{&7t2aoh~po^&IG^dv>-B+cj~-Em*3_P1}qN$%!J z{>Mon>ruSWX^GKkX~1cD{wc-Bana^!?Z;_7=^20i2@%U#Yrt81{#i)vY4_$?@5fm` z={fbxX{XWoNWl4+<3Tg}$@u2^%*Xkh<KCdq#iG&0a==Bb()sV+3-IPed++%s>E*7_ zWk$lqVZh~a{^e=H&YIHY<;Uf<($O~Q)xFWxqtU@x{?$wG)!XLTMZgsl*)`17-ks1j zLf|!09r}CkHR{$iy73_-{~BBP=E~?AC-8<~_5!2thIs3S)M*E+;D%E8cG&TTI`Ebr z<BY8DmU-(Ih3uAr?2ZHCbV4h9#~pYVba~6ycPF5H!Jc?0LU!+}be6+<FBN$2xOpen zcdsCPDx7$)LiQl1bgyRopjEK1Sn#0N_kfwWG!^h*LiPw(aAa!yXc@R?Q1EEm_el0} zZv}bOQhsn2elneX^bCCRhHN`3KLP)F^VU;P;=PaXbJ*;IAK7zM;%#8TbDZ#9IOI8L z_AYYkIZgN`*7$E`!A)}C-`uU6)Plc-7}ptOFC|Xbd4VtGvsVSiFV)JIKet}$$*wAd zUz?pStH@s4F)sF0Fq#bRJ0P!nMz4dyZ~XzU{ef?ty{|oqZ&P(QAjsRC@#)Cc+v3&f zMBT|!!TT8LI~cO{9wqd?M)tuq`?|{ZamaSIS@3b{bhsV(aS1tEF+RHzh7|OEJO)DO zHb3tBAa11p+$kt+h=jnSkxFE$?1)96kqCtmsP0O{;IbHjGFA7a5=aCCsBzWyWm0Gq z^Chy>4&>5V412>qs~;+4e|6XdWvL%2<qL{?a<q!a2s@F*lS*c5oT!y5<_U$rxElys zSl=VZWow>k)f)B$z@sc5=`>nQ=S${jUFfws_`u-Gah)4<dR%M{=REB#R%$<dz!U3S zn+!^AkV@t1+?bBUlaNL5H(P(7_`za4V&IkA-K)bHh(Mxue;k#lSRj?B_h7rsO*KhF zqW@^W76$p|Rhy^(<hZG<4?!R`cy`|9HCDdNGx+Ozh~cFF05*7WKkbM$9?ds=eH<CB z3PdCmx^wH>oi30z&Up2Gyx8b-IuU#azC7fmBsv;H0zPndAc*WD(7~y7!mt<;*W_>5 z=Jf;b2x07E$aE4_B8Y4t_HKC2{d)03dblqVSkeaLVi?L2F0E+l<_*KMGGSk&K2vc0 zmLzgQjbl4@-fxiZwuIx5p=hZ3Elrg;B{zDTWZo!S8WF}J$DqhGFUwRnB{Tk3zu!1H zUkb;m@MX4gUY>K7OGch+#XPm}%T^etQuc&>lM>xhGp921!G4pnuxzoqvZxElO-0=Q zjT53OIf{C(A}z>#uPUo<(5xmOZtt$9_$kg^U74htOG8z1>Rw&_O#enh^OdMYQyZSy zLsNG^-a||Ox8GN7!<E<vE#n_m58B_$)?0MUBF{W@EHwA+M=c5rFLi9n6j^kw>qzSU z&@>!)a@+R7Yk#rpqS3B5nUs8LbY8LeR^ze|uFdJt7T31fzc&1Bt1TpD$|%qw=gBx2 zGT&wrYUS%?5}tMH{ynmbkH<7xQ||eDEWhouX?#w0yIEr3E`DpgbZ;V~m8=wRMWS{> z`)-=CCB0duRcn+*&VxsmWgcRRk5vItC$F`q+sEg_{8*_q@}i87^y3m)p_h}AtkM^V zPT8+z9^2}`+D<#ey3Lmzw;`!DyC!}39Q*K5t@Wd(tzNE+R)~e4WA@I7zG}xsZJT4S z@eKd9(9;LMVIK;euJiB?HL;5;hL^$KFdatI%~(VD+ifJnk$~Lf*FbK!Io!+cdvaki zf1Mh2x()Z0?-F?)#@ZS0TPsd<U(NSzw=z99&xQq`k<B3fnp?5T+TI6<)TBP@iC+2O zgEC0n-{WuLAHMb#N4<h)Eg4*X*98~7Zx_8}5S5z+vSr{?op^!2sANXqpQkH)){mEq zlEA?4H;5*7_ea9q4~ao-027$1UtO?+lR;={KVWE{Goi)i<T0AJD`?vXhBeqBp*n-x zh=RkS*kTdElpuqC6{H&MR%aGc1Bz5Jf+6XSxd?MU3bY?BLL_{r5yHeMsD7(dr06ax zA`-hwVb&lb+~jB<Ia3^`Mi5==ShS{nDo#sOJ+bL;Z`$>Ae8m<?j^3~s(=Z%@lkgGQ zAHU;iPAQ25JtTQOPvX4<#y_8VQ}A8h$er;GGh7o;3ce(Za&qnGL-ERB;&LP-itSV7 zHP@=TizUUSB~j6g7sxnb%Wm_*)0BQkm2HMe#hNdnyI7Fbq&(FxOA7n?=7J*Ey_+@_ zYsU1qOw3U1=0{?E#MkYCSiMaSk&1H~U!5!kqF`676OmAiH&F#qqxsBD$RrKt?`8#u zMkIqeov?4qDnUgmciC5>mfviK<vsGpv$hH7c&%iS?ebIkPweSDUNUDtk=Wt<M2cqA zXh3oUsplUy9|<;%&oW)477=GJ3(L9y#QU3|@PE*;oMovzv)mUcx*kij?JEbRnBtV_ zgh_t!Rq=J@;(x}maTOy}N6?fjrhPwRaP(DAF4XwN^dKt8bvmCgV&TOFUqP5``%7My zE9s|7IK8KyS}^uvA^h_o;aq*Zjb2JQDELIpjZ?j$(N^`_k`0~Om!%}0mf}4FSWJL3 zN}!Gz;X;rU9qr4~n@@AKqQ<Fl;-ZFTw<&HC4~T|!0Fd|5R6=J6g7D0-<0#?;AzbSW z5#C-SDW-+g`G2i6NtV$1y*yg_(^`@V2^twx9D-ZveQu`8hvq-FhjorA3S9_|He*{{ zQb3brET2Q^h`u5e<622C;SvQh6~nFGK9R9J!w|Rsim|^qN+p0|F!wmwF2H!{brfo_ z*cj4M?LW*^ERU^oD~27e14q;9^80&hTGs$tjd#wN(!1J(GOu8`Yt}2WYWZ%;8E!N! z=?#*cbus3KHyqpBchuKS?V!O6wur%;?>G134VBjLOz18~daKxF^jPL}V!xx6n0IkM zGDj$R?7qMGW(<K2uHq>s$^uKZ8Y0VwSoDg(tsmSpAtfLx0AvS2TxD>KOG{D5Lm>-I zIg8KLwVK}OcMP;RB}hWZ1xQbUEa$#Eu3}^oPy;Svtn1*_5wc;ziCxucHpMAMGEX*! z*%tWe^Ht5$Ey0!e7*5fqGC}f!Q41wnz8j{~%2Br9+vyS4dgdHD<;Aa5PFjfqv6&1g z4i@VofU*i-D#7wSBW%v8SYO4cK?I17@ZDPdC-zcxzH+IH0|`UJ1CDU*5S_`{s@}r! za+gqIZSn=nmxoL|DyefOshSu{Y5aj<*2-TQJ!BS6Ib0E*_T<6u$jWJ^UG})+Ee&YP zW`3{y8=hX)gNtTZ1>ZnXq{w<h-Ip1y{F@8GPko%Qmyl?{Gv+>POTHq9O@NiYIn3-s zB}D=gh2js~hX^=|*0?MGZ(zZoeD4$llG`g(<gGrV%K`Nw^<Xj09a2bppX_E1_pE`T zO7XX53M>>2di)J`>9Q$@+MH~RJPul6o1hFL`-+4?FdL%p+>-shS7PqzZy4-i@#;Ij zPhESeqlb%i=+0G%J>NtpPLkA>E^WE-PEQf|8^atu=W+5b;U@W_zUR3}yBW+PM!16y zSRcD!tIosgrsEtd4L|{uxHUYIlRcYS5h$BG(vkwx7zI9m=mT)@3+^a7Kkn-E^JUzQ z1T10lU+R;r%Zg<#qHtpY8s%NLrF{Zt7K|<%bP!T0YZ7=jHVS*aJyNamEC26W1;APm zQh!k*yu0L%ZaWbKIA+z`;a%|Vq;6d~;V|4J4MZB!+Is086ncU*0w2VO|LQpo`{3)p z-N7R5UnC;E-pn>&Zs6Q!L~(1dSG)|-46gUh&h^1+09HbKdP2ikhAR50M8Y{l;Jf4C zn)`o}V_p9Ym+T5FOX){05pkI8M*(+Z!=YlHG#kT;+^X|uFbQHUCcKJ^hShfw8uWj> zc0V_@NplK+7U%(hMBR7?D7sN_-K(`!xTIc1USP#4s6?r##lT5}gCc_>YOGM;_Hn<# z%uj=iQ?W#FLkUqyIUH?^d~9q@O_=9{kk1NzU%~)i!o=fML^1Wnh5-#J&jZ}m4UswG zJxN2t-BHLL44N|VpcuyRE<qt?bi(RE5gbqqIcU}_eC~|j)=c8rS%Lx7FB298{bfi^ zWazH5U2sam^HogwEk;R0vM@P`f1QsOPE=iBSP0aug^HpDk_@L8uf&Fz05uU*4+qE( z8!iG2xkf^vhN<70ty6n12&EoZC8#7u%$cK%h$WZhSoGqg^qWUI%14|uA}xSl|8#}f znhiOkCfE=UI=@M|O0e*naS52gm#dGG$BDTpq+BeFmg|f_V!0n&yZnenh0mpve-4H& z##rFA;kmOAP>+RlONMtRQkKX-lAtgp%;0s@nK9#J?wLkn1pqQQ<1RRu<!WMX_hX6O zy-CcniR7}$z{HBd!2{D~fjz18YOYYA?60Wt*xd0|TNw~xkNcwRvWYbDn{3P*M!b2r zWGI}T&QPv^9HY-repu8mjj=*h<bzJ0AH-voAnAP2L~`?3BeBHuT&M5ZSa6A4!+Bwq z#AN2qXa}`;ONqp>8GJ!3OFMBluvtFAS=tVD;>c|b|6IP$K)M4}fv9?NWGbpOZj_5z zvd&L_n2RDKY$}>y%A8q2&U{c_Bz%NYaO#b71gsEptYG#J`I`?$HY@z(nr>g5TAZ2~ zZB~RhV+={Ksf#s(a;G5+)ze`6s3q`lA+a3({^UIB%!14WA(xT?>V%pIy!`$2r2Whk zoWkz@RMWna5m<3fpia|y@cb?QNJ6wmU@QyB+L|kT&ZXQYGK;M-8(@!70}Jm~t>71@ zd?cZ`Uajm8#6X9We?FhZf0<oGRdMN_P2u2y`9uvXsNy9%H*GNIWsb2K7N$-=iyYqw z2%kcsnL?eO!~=8W-Ok;?{T{(lou&RA0Vgt+I)^h{wDUF-7B!<~Keyj4K`1$ai#A29 zIg9|`qij;^N5oCGF&^Fh`)z2N)?@g>d16i+{<G#hMvE#v3lhbH1m%I~a^=+Lo_YUq zHI{=cx~~gi<Z6(+wGIqw#XrRAEt#{Z`|~me7-i-x!=}t%;?-$j)ViwGMZ1+(-DY*e z7KCbkUnr=DBP|Md&pvXEM(?Ui3`g^}^y675Ug~rk3-DB6OUeD170#1a5L8lB?Brda z`wFKCz}9T0);!@_D!Ok(H`D~xYrq3FN#Zr};MDbMmQ+~OIj5H>HZ<i8!udl-j9Zqp zSSG(;%$qt4_~i&$;Nn{j%UQLkTTi#Ymn?(Ymta9!qF<LNY2;3b`W@l5Bn>r26~;U~ zqRtCtjc|LkuEWG7wK+7ky*AXimR5q>7f2MuZ*v#@zEas;j7#MW1zLpD#KC_%P!9PT z>$D*p7Cr>w57*EIsz*uAnJlTrkPPvM_h_n&`@U(!Um!;h3n#*hd&k$rPA<sPhu3rc z0eo4_(D=h>{-+iPe#L$=GVf1n&7YKRU4|*$TtG<%$#n3$ZkouSM-*-8;e_LuN-S8; zUxs?A)_M<qYhg?1P@mwT!r)fB^#BJt^c!n27i;SATD~nS4F|=I4)aa#tB)eTCEfLb zG?M|Em{$giPxb3v!}_#K>nsQBTo3yFKNbpcWjhRYK_tY(Ju)N1x}yiF)d#&rU&SVB z490%ROp%C9|M)aHEi^kUIv4-xw}sGrjp%{}@r<U-lBDRe|EEPop;Z>qKNdJEf->vV zB4FH4khKfJ%@&cZ8sd!$>2Vsp-8}5=CBgk^gM%N~hZcfI?*_*Y#CuE9r!0nN;n*jN zf)|E{mn7I%2LjjehBw1F=eW{$J%;y!BoFUWj~9kd@YuK00y~-_FEz%`EmCiSBJX)v zuaW|g4PmHsENE5%m=R&v1T45-et1V=gb0!kMJXgLVPsk?#8Q5gLm^aBEHrL@^cf+H z8ItxM)xRW0*pAcyZYi7@W86|qOj3UQ4`TvSQoKz`LRJ$Zp|77llt_$BNL#;>9V(G0 zm{4$YQ_?C?^_oz#_5+vnX)jIagoJ2j6tOIY7;8=GFSVJKgjj@ViAN;aE(O_Jg}*pT zLO7NMIcrI|v?RY;3UV(?e0!AOQ4-{h80;o7SlV9+7&c?uH}!8Zn|a-<M=|&Mv5UoO zo+PmEp}5a%WF8IP%VaR%j5n9fH<zk0XX)8bx8Ila-)FltH+|dZLOb9fJ!rrI%L*NQ zRXPAqniFrB)B9WKBv`<onEBTnNR{l#5bsZ|TWBy_e4n=PLObkRG}B@|^bkC}lsgps zumIT|4mX=Z86NiLS>o1M!uMDXO&_AHTcTW8%6}Y^p&eo79ni8^xse_wC>{|RTJ6|d zHTfT1#aS`u9kth3U3MSQ^jHvqt#;3?7L#_W><)NHt*ZpA@X(II3fAE>N1q(6A?rYE zEyH7S5-X+J<I7_U(YV9Gb?by)YmsSdJ#?G3xMMO_8xNrqTapu1LmO{L8>fq7;kV<i z9GmO_8|`=-zZshg;Nd`zP3Nmkp^=4k{_!I7sXN*!z0&El!D%bKbtV5Xf5K_J;t6Gd z?O3;Mwc{!4=IO}!DQM%w678&?*sgK<lt##|OTjLi<;>3EtOIx^@op=6X%kR;)|hGg zlgPGd-LALxg!k>N0mZ)Y_^gQOyo&#voY0=fz`oMXzCgx4C)WOFj(uVLS?IJ~@Ql6i zhJDV3edLFIUio=em8}@7!=Cr~7X=3sqYF6)2X>%?O~M63_Jwq=U30es1dQ%bv~kgR z?yxfEpoHpJO?;Wn<B(G2kfe0kW_ZRVbeRuyJnprVAa#hTz0B0POzJu>T6er;b+nyw z{DpoM@_sSQ;#4l=lyQ6+{py%w=k!E+<!Rtlo9~qF?GzPzl{M+~UhDL$+o|EhDF)g3 zIQKGx*%?;(YE1Du#o#(^)hXD{F*o5_fbaSq=$zH<Ts`gl0(LGuzfQ@#4y<x6CUp_{ z>&%DdQmSy1On>9e@6sROk{spYb>@^(<w9h9BTwSoyy>FW?&36glZ4_*aphw0?$U;S zOR?2TS<p`9b!!po8kKrWjkrQnc1AmT8@=SZd3cL(1;*Q&U{7>}K+)ViaNV7G?sK)x zeigPY@^pg^zYE-4_iVXi!oOR|b3>?c<EJwafLI9%yTM<$p>EtTNVhWL^N3lwseHKZ ze7K1StBdwoNGIOWC%EtDyUSVK2M)Q*9hu1|9;o1Zcs$>Gb9$&MdwA)4C=1_XDc-Xx z|IzXKt-E!%(ej`${2<mgXUMi>6zHyw;HiWAsDNmvHoLElc>np^xsubP>B^Fsu!qK$ z`)PzHzmtcPnWsaaC;aSV;O3*lnWqcH6A9x<pY+Ls$;(673%%@7-Pp_A?n%efb41C@ zFT>L`-b-ui$?C#ONBdE>_DP}FYkbBl6!K(`_H0e|EXe8&(K7OOaqxBud>)ARwhr*Z zs`Ga1^X{4UF52|Qzw-8icnd3eTL}3WD*414`<OZUBnSFfCis-)``EMk`1koZ&G>|G z`M6&CL_>Vy(S1uueN$O|d4+w`m3(uAKZ{`alwtf7t^3PL`j^AWx60TzYsR;G)3@N# z_x!`R2i;G)*Y_)%pA4DbtdgI)(CarRKT{*W`2;_&e7}oYKi^)zyBR<KO~1!WzvvIY zH}p5MeD87=U=1k{Mj6;@1SEF?o&*4C6M=U5Z!C2{$6g@&EYM{WD0}sW>F>vf;g3h+ zFU;m2_W@K=_D?bLw|DZ-4DfeO^w$;y*4Fqp<@-b2XZ<@i{k`j4B)3{ZN6#zq_t&M@ zH-&Zf3-k}#bPt^jju0=mj-I#6Jjw+9CE7j=gg4JK9xk3dewPKLAVR)pyq3+n?cw{~ zm-(J(U)_wp+)8`aSwZBr1DhfPn=>G`bOF~0NNO;M*v!_~<bz=Vd=C5LYYI>lHl13v z^$q1n9N{<D^W$U<Iy3%~=eyEN>WMT)?MC~PTbij%4y*ZUn>*T>Tt2Vc^OHNexk9nX zN+LSt&xHQlQ5+7Z_Y8~WYGrCQwz$Wm)p~8N7pD(QtM#U%o~XQy`%BHXD~%3kk1XIS zsbt1@yC>GoZr`WdCD})|?fwwNPptOOb-Iug+E)(8^XD)7V}eJthKzqX4yUreH3^>o z<vgA%mQL->Bw#uE=a{w0ktEgCaHY{|p?12B>k{1Qb$3~Fb8osn82O3q5~tN-Zz6-! zX><PD{qcO6IvXmO_wjtqfokjWo!@(WX*8A1>7#q-Y-gp(38Ss+_4)RQU(yL8^zqiQ zv~YC=fhg`Rifg+<5qgt{yfCzrhoboolZ9Z(@e~BXDS1;w?C`czM3VT9VTOH<;VE{- z)smu&VOV>lh-K+4H;H1L;Q47uJ0eAuz$^4fnJD-|U>L^-;59ek#*?8=kuCKAq$=|L zrA||o<E8nbspmtJu4~&tlVRxlmnO62dkimamPNJ?ZMFhJ1$B-Cw?#>g%LH#4y~mml zUB1t02VH^x%U`;}U;rO|Q8=M5eQ`8nC;iWOz8CtE<mHNJ8ES`6^wKQbPKL5P-xr4R zq8L8LieK5jjFlCYos3mAo&N}?4HJA!HOEQniC<*>)tTygUS62$2LSxc4a0;)RVCw$ zUCd4Yn3K%SzvcK@O49Nl;(14HyI9&bd|z4GcL@FLYG2M7SvyZEyI8v}I;(6&{(mMj zKNKod4)itDzf5KpxPHvS|Fg*q&lW^1+gLK5O0QmNFy8oUGUI<UnUNbLf^cYxojH)2 zO%RePeHaZVnk&?!ls%Kf8Yo4gv8k|MP?Lhl2g?3sGNXJ_kfqRV8)Uy7oXW+~LUAOQ zZ)4rS(!Ze0E!9X*#%0(hMKjr{+8l~<I8-#itOa!^@LIBDJ`HPz8X|IRPGueJ&S28% z_Yi(QSneoPuQC#Bx*s18fv2@l>}tIjLRQ(@{BM(4J8JFvdT%UMyW7Oz-zKwsfl^QB z!`XkC%uiR_pH3l2|2CPA7pjbBdwX7=uJ``SWPZLo+nVj`gFyacGUHiq2P4szZ-=0A zA8&_ZO409x;b>X!gcDen??e!L9`8hwN6_y^QKwt)M$?y;@5V5<9`F9!WRBxnw%&{9 zIV|5x5O_TPm&weqpCo~2v!5(OTd|*_z<sj+-zKxo!4DnFii30m&y)W$na$H}4zsLF zD-N^mTTc#ioJam`GTR*Gc^_6B<pUp2jtc%UnU4#@@NAEZqG&6Ri{lR6Cw?YLF`ks9 zY1!J8#7BIcpoe#ODQB!MZ?u8RNswbKEA!-wp)XF0sjR3khMY#zA^uR4E2(ULVXVxW zhdX1a%ym62t?9m%t1mBfm1C{}nVvJ13H)O+*A)()H~l88vj6pKEykuU0dQu++`X?R zO(J-YInsHCw{zJg8TMNo>txx^sq=c`thW1X87rdiOw1LDtqnwZTAmVemQs?_csoH; zP;Gb3QdoIAPFHF`Jjnv*R{f<Z-<`6NKF@%%k&bA~^@fF!|5c8euxe_Ou1y4HypyRw z%~muC;ktZ~H0$MLpn86Avg4?+o3Si00j6T1%=?yMF++~fez5<rGKQ`giD`lckIdDL zpa8Raf~o8@`)gGL3|ewo(&5A@Q?p216B9z){6rg*DrBN!u|MElmbn4cRr{rlAg8LT ziMyw29q<4=WolbB1koko<N}7eC+@2l3y*xyw|^LOTy?;SPd4u-(cN=4)S;4&93)|q z$}?&g3{KE@<@l=a^(zqu(M_ZTMD<CQ)ZWbuTCRCQm1Z_F9GsE5B28w1C;`XQWFvo9 zm{(lJI^hZ^<>=c=Pv00yy&C~6+;sl2bQy&(7qf)}?_5<ouu~{3@n^ZkFi%2fc}#dv z=6Md7hfRlBgSxV>5_CA$<;pe1xM7$&B-r?ZF33sTVxP21bX2R|40o~1R`s9WxER%v zOnu;Swh%Orc#cHkH5+*F4|N*44wmMWoV%7DA$p=HXS!@I&vzSc+`n2h-s~a;QJ3#F z%^98YOmVB&cOO&+80Qp!lRtk#Uo?4)F8LgXi>6_m8-^F8RZSVd`Bqd}V#df;8G={G zlhJ=X^6jg?ix*wmR^{O;NqHViq6g+Gi*-ZK5yKY+O@;4F<fY>ES#@r%Q)2*K*s7*s zF?(4v>KfErnJ*ous=q`^rgJ?epstgWP>{{UxjV9T1SfO~!Q?FMPXinWF?cmR`P2U# zvJQ*Zq;2o)uqacs?y<P~op7cu+#`%ij+m;mPL-nkX_}HZfx!-Im&6E+QeYUCa|#A; zvphy9I;6nlpfQ(uNx8I|h*8>9_2<o)L_=u81mz-=tcNc(b_P9LoBVE>sTZy@C#^g$ zT;7SpMI30^Eu*hBE~k!txjmSaGmG^i$tCDR%VI*Qn`PFykoeeKx|Qu`G=GkjE673@ zNYk)pxQ8-G<m?YpSgP8a*bR#ke^d7wiS!yNwifww!WckWQHY&KEswFotaYQHa}{T! z+9td3)E|%6Jhw;jEHh!mC|d|0ECHp06_kc&Ud18ExRCwONLQScr=*BY2<sdL#XKL% z5MHHvv{z|rxSQ`06^<1AAW8LWki1}(NE~im^QB)7XSDGTmQAum6Qzxlt|pQNlieTf zypSTw8rTijAKFwunl)4uku2^w8EYXVYSj{H#a1rOic|Bu<kstX;?@9d2v>DxCFT~L zN_+S6M--l8Jd(@TwF32C7;N=-`uc#yg^;&pa&H_*$?~oO9S4lW_F=o^xz_c_q>R?C z(_JR#GO&DoaR*0CZH?NR_76+ydc^F_Ayx_@q1|s%7r8%FP{fe>UaEUOXRot3%cE$d z4R+9REOCpvB*ABl*_6QKJ)}=A;!8f^*nee+QP5;Q*TV>|4tGBDZmK9&<VlVkV_~rp z$W@J}#8o$Rr1b$3ujbVkKW%(Y9*(NK=urT2%TrXO=jN(jOn;&Zur{jz<_z{yhQchY z3w03ZVur9LXB@8$uq#;3WNJfjBueNhT$upeZMt9cZ?hPsfXKo5_cPwCKZg2=Ra8Gd z&pAph%{4OXex>A_t2EV&{Te$eF6_&xh}ORXdW^0md7jS&<098sabi1uUi{ltL|;AH z^L?CP$=s)DND391RPP@N+lGJ%-A>R{Z|QgYr9uVJu4gEnV0Az#E+bJPN*k5yPenBD zImk;);~ssjh;}F04IHEDy}P`M7hBOTbs-eU2adaGRC9Q@b+@b3NR(@u4zaNET9BOg z5r8{<13UV0(r5{QTQ?;Rt|VSjaZ8~p%LWXue|htUQVV$vU5GJPkYXebWj}vc@`*vs zXCIea_BK4`wUt5Y@Ir;)`zR55#tdyX&A)5?o%lY{Vmjng$B@xcXKTQ$v_g3BWu@at zLNJDk?dy?PL3EXO`-yln;fZX)IQX{5KtF@)bk~!RsaNaN&g`9m7~i{1{No`oqY}3q zs?xv5$g@eCcnVDFwoZ~zY3`7diG=n7R>o$krIEi#2z}X<zCFy(0bYcV0p$|x?r|C& z%3|t}!R-N2{o+Ema`^X5i;fq*X8APXEp$A8@}6fy;T)ytdNvh}u@~>MGk=lupK%IT z3Yy_N|0)oaPTvIN{PG#QC>lQPYi8`heZ~G|(&Z;ZU-qj2rfVBG%;;M8x?x9Rx}6(- zTZQq7rctf{`zQdSXwL9)n*(_}R_=RQnf-X|g1lcR_Pre`L&7iGKj=CFeI+E<_<NKf zM+1R=u7EUlv~Ce(C?rzb2f8wH<mGLQwxFQ%WK(}vK%xoSG86`4X3!>uzb_?M#2mWu zHtfegYV9?EJR(q(N;P&H%~1tPO(g_-ESQl8t86aBP6dh`DL73e_-hna=`A4E1f91$ z^h<lNa3+?AInuUDnABJ(S7sRM4g*hlsFrsaHhnmrXt<(vxYjZ3gELABX1LxlU+i4C z)-$|a5W>1j$R~}6PXpn+?Fb?&P;J{7%j{?iP-xlPoX!MT8a(L#1V-5^P+U+LcH0O( z*GT@)kwH<%T(RtEFHjgM|6DbxK+Qp+#TFuGvjf$vgBP|jV*4X}ph91+k?^G=5{@}j zOhUrzk<#kX_{PwQ%44clkyEab(h8Box6u;&Q9evib=zaGzW}o5kaHT5>b5Z!>XG7P z;&5G5)2@-iw-F*lkn^D834SA|kt45;ajkh{QQ#!}UKMDyCW40kpUjQ`3K?n(*5Tio z9V`;D%>N~`BNvbPA2_v9%fbmJ()pjvj+lOMaOS@=J2`Zz)PKY2LIS^|V4hq{<x-Un za?G<gMSnOljFaM|Tx<28CO&Z!k^f|N$a3$;oV6QW-gkhw%715e(({<dFt$)AcCi0s zb_8^*P?W47dxeh1gDx^uHI9*nssXJG@jYU!?O`N}E`)R$3ig3DQ1QPqyROH<@jR@6 zG5d9H0wuEWB+@U%VWRWU9PSTbq65U$>7Viio2{%Kzm-J>b+CdwpeWeGR3I*(4gUMH zf5WMfC*qZM5p?)NN&5}lmoMy2|AA8_crq<E5jf*u!q0S=t{Yh2R1kzN@VEa1rxaf@ zGeXettWtak{sX5npChRlyp02B{{yE4Ij$W4JDj#s9N_*Joa&KN{NLf!Qj$OS{{>FD zPmljUI6e85X<2zvn(KLbQdStjcv@bPZhKl$URrrtS>1YiT2(&+`A5BNUba1}X+Ny| zhbA9S&+7USn9l1#cy{LvW3*N0jZ@rb=S_3}%Ip@k>@HeXEvqhC!JcOqZQK9K?Do^` zE<27(t1dgwThA`Lu1A=zy6>0mu6mvitFC(A9?!1&pb(j_`{D5IuLu6g?5+n<znxzX zVg5U_)3(1ECa|i$86oyMzZoTuWWF7v&al57r!T9%onUS|zn%P7W;eyPVt+Tyb5wmd zBk**7H!Fh3az7`5?{NQHhOXv*Ug6ut{ep@#%fq6Ew!_1cj#bUWvVqsd!-`2H%j2qf zhQs3@>#~~1HT$-WRr;SvVgN8~k?X_;Ogv>07-1ZO*0$x_#qul%#Bi5`%J&Xwr;kJ_ znGmVtGE!l#1X2Fo&ddq>CYpFOD6f`b<;cwdn;bC5QU|(~gQ`Yy|7+mJ%Q_*`5R~o( zRl3L8xmwd4@^lV!poYm3IV+g7`IA`bFWnE}ndDuV9~?3C1t3!u=JYMWZztnhBv0V2 zE2EapqA=GvnuJK9PtPttZ==N;x&q{G{c?=jpQVqK=1!q;un?%Bqr#aqMEjx2DV=@9 zP2>QhJ?fc*pM0B0#p04<bwS0SoKbRLt`WI9JCrE8MYcppy}qeJu?2JfC1Q|MjREss zg+hD7Gb0Ut)_}VVAO?SiJ@N!>{SfoNij`!9<d((!EvjesAdlMEO&`jCXMrjshi5^( zjnRk-391P-)pd^IKlUF9CAFuVvHs2<f|?w5=eMIzm@%T<txTS=T1a3c6)R3`8U}Aq z!nEDW+pcis3dp6Jf}+Dz^`?yV!WqNSY!G~BIdqu`l^|{z8-yWcO9}xIY->;ew9>u= zCFD#qXt+e{P~Tu@T*EOaSc4QiQJr1)s97vUla#?Besl^*`0vHvun@LCMTQnq8TvFB z(z=pYlS?8?77el+9Xh`;$!xRBDnwgcJ4fM+F(Iug*v8PNLuc-aK()tch^YE5pc;S0 z(&9l=!}8j$+G3^Sm}-K$bS~$Vc{+T82wK&qn((+&Q_JHkdo!Bn`-h^4q1}pzeQ<uy zs2ci0W!2}qh7fleSHwyt$KKvhkF#Sw{Kd>W=8w-O5hv7s<_LnI0L!$Wk0CTCjn+I$ ze9Zy3&ByLS6=S0fV)5(;8JltVP_lrAU;b6}O22;&suxmbBSLS9g}&5|V3`I^X%vNb z`m||PqX$vN6@Qe<X}VS<;c}t<QZp<8lw+5;@H3xv*8T<PePCnP1yzE__$WF_YF&=~ zh8YXnS6U`o3}xR=XfjSIkr2oOBFxUeFMQRhZw*N;Zm)<-<DF2?Rm*|fIWzD30V2aq zz%7G1GfSS3z51e7_H!EVT4;c00rIy=>WN5_srpD>g<1*MSHQ-;!=eWkd%rb@g&u;< zi{IYk*}f|$iKDoxNTT^I_r}hUsR*TZGg+yb|I`d>?r3~&FuiMGo-qZ0NNBuV`)f>+ zt!Xi8LL2j{TQH@9o8lGlHldxwK>|<B_FYNk_P%cfh8S!Ot-0mG5Szp!K~iEm2qM86 z=&?PbZ+wn6BW#ox`I?LW<*mw7=rYyw6`MgNHX5r8x0f0LPx&B<roUz;<0{7x#jKhs zaQ?p1Z_4ERwEVBZgC+9FShhst;eM!0b|^2d{U{m~Bl53zIF8k@IxYHhG*>a0|BJl$ zifXcL!!|=nClCbbB2_?9=^YHcLl989G!+mqG!0EdNuh_{G4!sXNKw?#5fCFyK*fNF zU=0WgSeU%;_x&^f{IfA@W@C0{t!!j7S$UE?=XqS$aTm<g>pb~%Nje(Y`Yx~h%A?;+ zh?1&9{(?U0*Ulj$_!FsYA^@?SJh6Tu!|93t>St2?;s>|6gzyT~RgV=DxLsl=y*<YC z)C1S|XBW5l3Ip&VmtcWT(Y`lcM{bt7g*nTEX*V?$BkHwxeV?`mhL*)Ov*-7Hv>Q&G zG&vDaI*uKkxY9LoUm)KzOVnWSu|j^9<8|se^&!WaxypP2$3{Oa<Fez)$4%Bjci*X{ zvb(!GIv%~J>ij3<UX<#56m3WR{cAa1x2)IiHTX*;&EdJJ59}|ST)O`*M4mPmJ<k3@ ztqSt&y5**AO;oiq<+U5rv{jqIe&y!ioSCLgRa65_fPYYKs=?W$h(Xx)-VnKYJ#)gH zmUd{szjHolyT9>b_%YBkc;K6D&8=tA(jolZreP^2UIow9yZLr(5@6P{;W>s+atZE# z<j)X7v#PL>(_cD$lG7IFNas(`>MP{nhbm3k+x}C%p>kVQzHiA^pCqU3Zj@d>7*2XW zyYOncF117IE4zZuy!4#+gNe;SHd?Y;!q=NkjW?Is038*9;tHn+smvf>ou8273Qnnl z+uk~-mpO2$ie~N(sLML*{mJW^f6<G@?E4#|PDY6vi;mUIq4ewBF{klcxj9#kH=Nme zY)s-Cx&Pz{_q~G=|0{jxfBMDDt{jV#e)e^^%TKRnuV7+S^SCwph;~T+J_h~B=-bPz zBZu6)_g)-WUUJ+eNYoF$tyymDIy&<0Z(ZL><lNWtKL$Y`8Z~*&BdV=d_C{sIFFLh! zxPTTE3OjVd1aLM|Ud`2-O=~tEt|~~5;7r2Z&US_JYF*2dQ+VW;;K&}&DVuN%s}KNA z)EO|n?qpV?o=`Y#ERRj7k%qNWqwACs#YiV*g_1PeeT7~o>INvxjV76{28(kh*M~!^ z%#)osE)<R?8??i$wN5_Ov|9t??cUjMa6lbNc&kD4dMe&y0q=!X^B#*J1E9<giI?|O z#r=(l5|&eggpeXtZzq!$GNB<k$k2tTndA^qODrC-zqN-Ko`prpSQZQT<BQaU4{O|S z){(9)5Ht3ORXA7!3PPrY8k!OFwN$SP5blr(g61iAEL6QMym?OqGB2mrTO5<yIN6AW zHuu1?_EJq$(*m_pDoANc)oDcUOWhl3hSh0gfQOK2dgy|FLuYCW)1OwK&VN3keJs6G zi||N3<Mekz719S@l(B?Wc`Zb2;m=qRlDH-m)wWHlkRiokGx?`=W~8I2?3xMkmIM<L z6CyEl;S@XJLKw*k&6)X2OZ2z}xokU2s+MHAo(fbDy%vz!!mjnDfz)vSD$n9^H9Wbc zfGF_PUaUAfeZ{&#E{%4dTrg@sDVNi=6<x8aDJM)0tI0X_G^ffimwITFUGpP5%OzLC zRT!{w(iaSEqa;i8-a4mnOm_1mZ4RcgssFa)qUFBI;YJ>pus{BNj^k71ikg&<X1V7# zbKO&ve-^>a8ja3t7bx=OUQ8))Yb+2{)h7v&J+OIifravenedcAba6hmSS4;2mXjPP zI-l#iU&vQYwht^ML5oCB6cvqVr7sq(x<q{?<q|E65!Hn%(AyTf1tr4D;VC&A)mfF6 zDlrNq!D7RDR}~D$?WVwzR&5pU1`>@gr=wWu9Tw6l8`k?&c?5f-XTKEUmu@yzGPJKu zlXn>`Dm&IuR=z==ie?!f0>5jOi*uwi!5M=o<$rz4atUS2hsDZEDM9a`Wm(09Knt_; zFUvoqoXsMUN-V6dua|yPC{ZgSHOQ2$M&CgWW&on|Zw?y$*t|1bZ1|I8)dBFhDP0PB zpd@tJh}TT}+<o)%J<4HVM&KSS9g7nhSGum1>SuvMScOmTS8i{UZdRu*EZmWQP`vpx z_G)z1*^;w|Juns5RP_U;*Frv>_-tKRwcT8Lv_QpI;hJy0MvtU(D=$zi4$giiRmW@; zAK9-t<{V`*UTGdw`^7gaF*-wMycQ<yt=?1QezI<3y1MVFmUC(y8(&dhck0S!9q2o$ z6K&4cSgU4LA8}NxEE1B8az{L^zxdHIECzDF!!!A$(#)Z>OG#1Av)%@c61yfPxJi@F z%)6Q#owJRN6}hbc&?ff|3UMD>NBMX<ZV2WIgJs7w?Ib$5$P|4PuDh$#2z9C>dPg5~ zYd%=5bv<zG?yc`@I*pTWu34z8(`lJyC)CrSQD|^OXUVuuBVj3m<aXUyt97TUMysU$ zMPuu(Z&s64TK^ubc&U!DRDaL1q>b9VSyJ_M238n!ci`aeP*8El$Gblc&TJ{vlHKn8 z5;=`)XsQ-UH-k~xPElv1Vg51>;iMKwDfQWrB0V{uyj;}NlWpThb-KNk%_z^!nznUz zGg(;}P6S?|)F4$_x5-a>xezV<uzlo+S@mp2&LOA%Q~3_*w0jS=>NlD?ex|lP-+=O7 z$W(@R(gre^f<!V3(wW-%Ug|EUsJS}1%p89IA-m?q$a?N(!nr7vWZM0=+a=pe5qxIw zsmu3yPjx*ps(X_f82qy%IQI0GYZqS(wM3_THr%x5q~&~L=Edgj?)JMmJ1yPx0Nlf_ z#8-YN4;*hKTNUv2q@|roE+r5#Jr$^oT<dP<LcPKhp4FUP(GPn?V@dGd)E%n_Z;ZMe zC-fw=A2gLJ3d_KL40lSGII~vnMvb}}{M$&)4=1b|WjZ^TPxjK>GteexfdM^FV*BR8 zS#jR#d8+=sPksHdniV@Oq6e+>zZ7L2b`~67yEHQQXgb`s6%Ff?^I2`awdVf#O*OPh z!sqTM%9l@yWyvJZQ-R*1UAw0gsct4yHy#wmx}I2i(k`l{=#<oVwWpim5`K*~Fzx(q z7y8^y-&8Gq1m0gP70%J<z7z`;EQ{A}?tjcqc;tA#69eClP0t>DB4eY7UW9d19+@l# z{Q5L-_VX!hwY%!?bJ*JY)Y8G~cKh$ru)4g^+DKQ^9hy;J=4PZ8a}-vK(m%>I&_>s{ zE$f85rZh|3yMqL6*1;5-+g&G5-FmOjl~x~x1oa`cvDFQi%T9SW+}Hcvaw8Jn&CumB zq1cFxHnrP7eg`dQIxTRF6s?;*ju_NB{5%@9ovfjJE+yBnX%OxM7>T06Cpw0hb2agk zV<AWK<oeA|UpA`3z<a49*CyfJ5)JATqr#t`I<yZ``gjpAQ`vF*6L|x?1>*}5NsHZv z_qZnP|Lt%_B%q>1UYWED0VC#H`>;@ckSPsbibZ8AP9}%La=a0LG4MRhGeNfIrtdIp z`sfG-p8vb0DQ;pX?O9SdtEfS|0`T-PpB*<mx0XI-N`2mk*3K!=nTvqsblKF{j7xu> zif4bm&IB4Tcy@nZ6kECY%HO&h39rH=5t1}zmZl)(&;DBnG3Y<Uj&O3)KEHmE$Nqeo z3Ia+@%ji$=I#iw9f2N@LW%{iC^fK2i_105NE^f&`(@I~SJ$*gX5k6y7J|n~0w?mv_ z?b`tv98AVDl{d48KVKOBnZ85?1yB*(Z=lX0bG3=H*8rSA46C0(%qSt~6sXVX`ReVN z0Hx{wmO<2i%AgX!%TD&^GpwZ{2`E#79SA_sX)jBVL$?qL_oxt77ertJUy;F5tvp$% ztc)+SIjmv}4Pli<ub9(29@C{?W=kZXakfxA{ogJKGueh+s#7^vPKUCgVQEa*UnN8u z71Cq-s>=wPg@%N(dL-JyKnRA_1+f|=q0ZMyr{44on7Ns}!SEvgCse5ofB^b9LjP@p z&T<O<KWc;iuc(qGU9u;Q<Z-PrJN_eG`Uh3c)T67d{@Vuq&(bApRvT0(I`w}@m&&cX z|80X<(xsoFDF6j4lNA#sCXI_7_`~x*(xo(mMc|Q<RDi5iy4Id1ik*uMW&U63((y#7 zf`7zSAv3R{;#~Icw9dwePb^faImlaHX*Z!TF_y}IpBGG(SnB>qy7UeqeqUpVF|Qsf zF7(^<O5z=3>;FiX?#=dxj+SZbKAq}${x7PGCww&zwGWlVt^WECs<g^O#R30kR9WfX zqptZMRC!U*rRV<+Rf=xn{y##M|9@zMBF9^}BH^cv<ve*6YO$*+)BmFligK#=_@@ox zaT=Gmzp1Y-!`33jYJ(2NCQw9v6RRalKK7rlBVUI6e1rYa`g1w%=i!&1Z*kx=dyHhk z(7hFs+}*v^bj`1O@5tt7_Sf<*hVH*Fx_Wniz3k@K{SOr4nS+g*!q9`whWfh)A6vS= z9(<yXp855;^JVC-FFhab{`%VY^Xso~H1OHq%%NOe79*ZBB%f^M{}%dv%KWT;W^13+ z&z-LV8GnAfzWMFXPX_Vq-@UcM>wot*>hJwM_}u;N?=R-)*~8yEFRvf|+52!jN8a_* zw_pXbw&~&T(H6EN)C=r+7V|njG>-O<SayEKmQ*;*%4Sd~Z_JJ3n3l{1l)Yj#odPg5 zG;&B^J=%ow0-Pv9vRMs?{AHMew6Q0lQrG#*(fE_0VQEUUY)8m0z*C1VBqW=`fXF<K z$fap9XeX<be2?M76OSdi4-N2*I#wES_K?Ej`oYR&K75+P1CHs50-X)U$5N35`=No1 zM#gbIcWkODb`Sw18wp)fHnVPHVs$)BPjMTL8ON;(*f|a>@N1jvEQKL}W7X$EB}WXb zQt?&Z%My}dBpoI?JH3SjK&&8GH=<c8Yt^!HM+Yvnu#=)79A^W3V2YWE$sCeWCSGk2 z3`035$7A)RWK`dU&ebD@8*4ATd?twg%4xNGC9qE}R^AoU$4AIRU}A5>h4w@;xyMA& zt8yY8J(D-TW2i5`Xb}n;FGa1bop#%r%$$8uIRE>f^_{~EAr*Q#A(5ecwsOQiZXkWv zqf+2>_!N5!8wA*cKi8t15s0ehV+)W&eMz=-p!*(;(&9v3GJK9->L?7LSD%2PIIt}~ zh-hr`2|&+_bNVwy<h^8(EHfj(iOw>ZPbK%n9w~5xLp;Zu2!R0*0g6?8B@iFmpF5-O zsjEi=`5U!}4Fh*d@}%nJo6d3dKi6AxIG!bsH>($^Z;DYW)0M3k)2y<FSQ!!i-Ok~) zl)aGC8Z*A?+#xb`5u;uR2L>5_EEyh_vggYpE6BoDGR&FmrMH2K<{e|O3(2|UcTNEp z`F=SMNfos5<$23p&`mS#8#q4Wl5C?c>auotI-EbbZ%EEba%tqpe5X(XMcCOe#hiZt z5p()<$a^Q7=j>a^dyHzQi&BPG7Kum7(O<*g=D9h@%#hC?`xsz;e$KH-se0y3XzKYr zjT*7%f#n%;GCIx1jCPsCk0HFVxjAn3ky70s=6uw?lwLZOo$;hv-}F>PEW{~KErHV^ zIH5Kf)^V)1I)E!s%R0;jUy<C#cje4g@Y2(ZEvp3_d6?9Bk=2gZ(^R)doF|bn(gNLB z#nJB)D!RgH7aENCGaqf$r}jRz_gLj`v8W`Q4jb8%R*}g)$x<AYRLP*B5$lm$O!m{K z;#rB^E*cQh*`1X1E5)a^y)b&Zy6gDl{lm#y2P&s7@cM~r)I1Y8GOPjKzM|zQn>Jbf zU6TCt%9jTlv@1VUUAy9-b~#RcoVOfajkj#HE0yH7T5MzeYCeSIR6WnXF|PU+W?~en zF{b&zB-Z#@e&&s?sd|iCjjOHAl#XEWjUUvEGs+j;x^<H487h(SEyl|q-OL1jsJom& zyx|j#HP85Q_eWmq(S(lzGak-c>3im1T3=5WQSAb{ua&=Zzm#}XZTUsTXnFqi+p1-S zN~RAM<Dc4%F7O|#6MuBuHptpTYG!HqCd%2u$mmw$D>gx`$}<S4%<brT*zq1fFBcS? zrn{Qzi>;K*+%i;tMdkUXRc$Z@^ALAm!yg`CzsIF*8!MO9K(9xaCD?}frD|A67WT#l zE^q9w|1z7I?`=r<^2V%McU{S?lwLd#T-p)0`E5<Rs~NW2kVT#VXhzOm)7`2l^?h&g z_MoimH`Jo&!Jv<z?#)_*OKu(>U!3v}Bvo3+ItSm_+8+0X-DgcU-hA^SraSiSOOtRu z*ezzDl&)N$!}+1_DJ#Vq)$iUJggF$&zsr4|J94{XU+4XsHR89pA_F_P9MNm1x;}a_ z{#MLv{oijbw;z0Z=@l&@@L;#&!;y|fMcAEf{hxjVGV>jOVj18|UtLEZZMDhF$`Sci z+AsYrHhX00!FTB(<lx3`Ryz8<-z6*D5AVaCw8KAV^W7i2o;_D;@HKdsuVSMyAoAeN z9c<N4vF|(fartxUHuu(#+l20h_RPnx{k-iI?%0ZgXh%UWnMHy2Vq^<pD5uNUf8xAy zZZ2O<upYp`1j2<I63nHpz9Qb1Sdg8SJKr@LE!!YlJp$96_ihEm0DBT`wrws6_?2`8 zs$pdlo%NOHVc)xwTnCIcP6SK*3^p2zD^rJ=S=gg)gj-^9WwkI=vJGl4!C^ysR?wbE z!=B2+D{8?^7Xk)PM0*Fw-gdftkC|kMC7{oH^_vljPb7uz$vD><FPmEI0`XBj2`tx< z0pxlEB{6<M<~e8Vu?=?@7n0I|(ThX%TVkUmNqIskr^!esDMv{9v_)77DW!NUFy;sB z9KRhmC@^j>#U$s-*}W*4HC%&M3Wp@D0(l;M6{hw+<zA1}u)qFRWXg-eG*cBrn>~NR zY;3J}Y7Zn`raeu50VDf9bsQoCje<6MV~{seUo1$6-X}cTOIIz*P|NXK-}NkHKwTXZ z7!7z=eo}!2X|o|S{ls~f+4yfosh_kglD++-erD`8q~z@-y6pP>36R0brxN&0UTTu3 z_p+Y)2i-$u!S<ySP0x1<nPdoN!yEnH;+@+F>Ay+YvggU2@|QV<QY1E|*x!2w@xxyh zrOOFRKHni-ThBP#D?PC5w|xkSKjE6I$ZmKK6Jqewk3N=rcG`t~&G_;~eO=2ug>c7n z`<_VwUYEx5G}tw=uw-!)qSIzp3l4^H2EV?T<E|j>Jp*e1*pa<$UTPKm4ak2T;LrUt zJ9uBxH4@f<gts}}Xl9Z%dh#NAB}Y~LE(yaM0l`m%_$WULZ&q6Ctohw>Hti%^YGoIt z77ISevsCGI%zhfeJ6l|_U!3<89pqeG!)8%WE{;;NmN!Gn%tB>4Z^q4^)8Q=Xw7e|K z?^C0FoIM$4-)Po{^z0M%tf%|EP`6XuCtKXe)aWUrMV0hg9yh`h?=WEovmB;qPJMFu zQee3cox_J&{`RS5-vbF#J++E=mKAzCWxHX-bTy-TVfc3^So0jTg$Zk;z|7Xo^w!K? z$d>(Cywew5@?+ENBUGXWLjf-p3!9cg`LFpzAdh18P<4?&o#T+0O2Kg?%nf;`mjd0< zXueP>kXk8ovP#~lN<OISL}HafQ<d~U)#;B_671E=C#yw_s%2So^@-KOP1U;N)!>iS z=TfVU4kS?`Ri-+U<|Q@4IhBgzHB#rR(J|H9I<=}nwP$sZ5~;PK|ED-31ONjdz{USp zaQkUEgNQi&uS52V6_>{U;*fR76x9;@zs8y2CYw}L(ebX-WB<gNj(`~gt@vMutaWDU zf8$I+ZNK$D4q5F75YZm05BZG2s=p{suyc?seOw^Su>Ji6Ho<#&a-VUEoDNKdV46EN zXI%EHyq-Py$jKWIWOuNdG5YjMnGY=VEZYpgl@BJ+Z2NlbU$M<kYfSY;+Z@k|<D|== zb)NA|lwad%ROm9}5>T=^l-P^@^@W$sD;?Q>%{zskoljBYABSv3KO(4Lf8+6C>SDY( zGW==(&K(zT%yu?%BZFl_096X2K>6=)Qj8>Bu&l{TBemByeNpnhHt#Y5=J+J~sYU=M zP=b@o2)#0vdYW)$l{I<kLe5YOY+y}Zo|rXEJFh>&r)aMS@nKhD6a3#NFHP2*&Z12G z3q%a%$;pa3T4+$$zRUanOkS=h6c-fw7zCWp2%i7%<fS<#bM1YO?N^2WPF@N*kXVzK z|8tya^y(~*{x95iaiu8yuW-8sbO`wuZl9{L@{#z|`Y+seJb85aF6|$<J@p0Gf?@zs zpWFY1+XTd@^nc)Xz$T63KXBXnm}<s}I1A%{;r1CT<`^H&U<aaNum6SSNPfJ{{B#}g zhyC|;8YfRMl?D+kWA?)|Cz*qAa~3~G+6RXX3puuI4U2yI^_2y;(~oHF%1cA^w|XM% zw59%m+h5xU?X<T&B2)~%P-g6OmHvU-^l^_VtzDEOmp-$vgIo7g3&%fj8__(uM)T{? z*ZTB2bMpK@aJ!rvk)=Lt;b^btuKK34;$1q&k5`ycTe|kC3BTux(;Iv|I@YWms;<|p zIHUezMlIsm;uh6!<87kmSL~S4OOHwQnC^}nmFeeLab|TIk)@LR@_XiZ**|gS8PqdV zYnAQ@(ckMEY@Z=^JyQMH^WoMt?f0{)&(@ffXB%4k%XfcmjWv&RYcYG4xeV4x5&Nsm zU=D=drp&!RKgu*bxplUM;(2sq3swJ6KGks8Yv+8Hdan5)f)!^-8mBY$?pi0QYP0#D zlh@gh2WyY8@dUe6i7e2C{|JoHjN*C3%}#*~R<koJdqdEDaGKVdPll$1QV4>p60&Hb z9=1>|G)M*O4e<h&cvEj~lFikZY0zNKd)K8WE4iy{v?7D6g@!R;gF|{4_ubQW;-g9& zN=HbU0uL}mbh<AQ+pQC;^p5xB+MPqL{LGlo16;>FMuD{!BPw1EF_UD8sWJ_-onefK zRUTM-DqCB1X)E*DKIm_e1N>+^H6!`s>KTX+B3La$?CoH+lwe9pU8P^r6Gv$XLe?yr z_9A|REDR8S`qa*?E@X*z{CH}mQGvn~IxcBc;--(Wbj)@>l{0-oD!R*7{A7GVx*xB- z@PyZa${C|;;>a(O+#%GYtHf}kAh>@#jJaJ%Pp@+w5-`LJ8B1)v$`x91K&bAm99zW^ zbyeh_g_lH}RLK?o<Y7L(yM=Jz6su9BwyC;Te6QFGw$i5Y9vWPEofN&P1+H2!L|rTL z;b!7SHA{+~6Lg&9Q{nH`i?;f16n#rc4hL&KLqUS${H}hbzBV?uI$zq^dS{X}s_S21 zt6!USY`KU-GF1VID%h#hQisZKT};2yz!W<@x31I43$^q%7K@x*Q;is(t-Fz2qMt!z zek|m^5iETqf)3J{b}+Ax*=;`RAogtI#msq-v%ScDkmP!=dRU$@#XF<fLvUa^3c!q* zv<TFjRL<;J4NRIRD`*LgKj;<tK?Ma8wHMg3uB<uZ-&zp0KaSd3M@EXp8n;~GeWeyb zkrux{c1@4Dg@~x}OH0!Evaqg1yl!zl(E3eFaA}iP#GzVO%dY%CansE>Fj6ENH+12p z;nbo?VPmEuIKUL1wNsqb-7uFMRKG&B2rw3tJpDDS`xm{g_M2EnZ3Aqd;9$7xoL{zJ zs<Fm)@#}-`8dCb`X_JQ|ro70WZ0|SjZznDhE84{~FB9}X_CMK%1s!A3u50YnzWJ*o zRH7m+5s;QW9iupZ@5Vr_dea0VY*M+rEuKmeE}lZ9a*z!0#K3CZ2CR(MkvkN*i$1!m zB2QF`_OK?(UlSNdI~Hm`zQV`|=%5w|3nLb1qzxBWxcLou#Fx;D*Ac@mRkw^pPu>8N zJd4-Pm~W9+$HH7!UU1*k>+TM1@rt=OaV`P3a5#ba8?G~yz%7^69q1w8WYOKvT8m)j z31xOr-pi?CNYdhX(#a`-{Kp?n2Y8N6tx@C<rdPX?1`Jw9HH!!ho#RqRKFOY$khcv2 zsT7M5=i9va<fe@Riv|yt!W*x)J~}e-Zm37roTA!dB{aiV+{t~T^(u%*S<|?Q=Jh&W znim=>KO3TPw5!v)+aJ5IKfg)wd{yOH|NX)skMg{5MV8)|a4`4eNCjhletj~A>~1^L zdRK#S)jQ&qJLc^xSNnUF15HiO#GdC5Y1GBlhXq6mmKA-_EysQ%+=)GQ*ECWUtuY5s z`XaU~&mm)!T5o2b#7A?fR6S-F-p~7diSMwRsAmI3MYUIQG0}{2WM7)61ict>rgy5^ ztUFBX0g~@#8>*L(DO6C&^<^)heQs9GI<ZeQ^yp~mO}pLtt;|XNTCno|C^sM{No-?} zQ~dEto9?kVLF-8K)n(7!uC(;1J(r=O`{_$k<L?B>Ohw~QL(cUa(qhIhDX+jhs)=rW z_1|e=sZp1q>mE`9-!?Aw^Tu(N`VE$-%l55Hj%GGlmWjv9)~|+NAsOS6j=|qVk?lVH z3`wp|`AS!LrD^{w`2DZxXGP|EBb81G0ePZXT0@C%Di0)tJ@Ow?&%nQX{8~?H4kY}I z`|R1Pf)N`)HlDlks9x=j#pl%r0#_d&ejmNln(HWZ8INyO?G1x_nP|UK^P16FbBNfT z*8Z^e{B~!NM<#=<T-@z~qjbGipEnnL&g9)lq_RIE8^AS3joYigeFUPYVr=fB8RqI| z0vSOR(%_3^)gO^3N=&#vI!3f(Ja62;$=8!OBBkbY;-<Wx_GXRY1`|QXK$nn-Qbl${ zS1l1eh*buHV<^#NArU0VLn891a`+bKAqsIx7WqETwN`fu5Ubvp_KV4G*i*83et$W+ z-$gpu)VUM_pv!cV4nf%;gYaw`^rds8yAZK&AoeZYahhVppc_2~^N3-gi?qONMyBs6 z4j~O*{y!{M<%p>PC-FZb{vLKB76z>&Ay6_EvEj}AN=~*<8of#*lre&J21C-cQfrO$ zdTtV7wL}q49=i=9PDtpL0DmcjCtCvkqdu{wD6KX;=-f-LpGp{o!B8dxVejHr2TTib zym78ycbgelM)fMLNqV4_QIKQDxX;ahgJ@Z=L*9Xik8yw56|{A9o~Nm{1@KABBOiLF zeKNf|yO&wMn&`EccG67u*N`oN2A?8WOk)Kn{4A4ch_4jGs-7dZe6i&Vghg-TYETxp zs{-fI*hPq|0Fj%6lYAi01K>v?iUmU)dHOKW5A-XZvV3Pv)0Vrv-YZ4%EaqfP<Fgp{ z%SgRvM|}#MAa@R_=(kLLv3)_&Avm6ypfczTY&>$UfqZZ@;Y@GdEytuA5Z94vn?6d| zaiNIYhNf#0`D6?(u;@stF=-Q+VWVA;HccY^Af2ppaW+MbP{RDX1KW2lF!Et!M)3L= z-)DMC{0Ks0Hr9W?Fv&O7z7d^z*-b_@KdKRp!RB9g<{^7SV0dF4Hm_|ufd;r`1ue=l zg4M7DhqU6d&0>mnNsVhsoofjjvgFQUam8W@`%3Yj;j|+^)4m|n-^ufgQ^LLhP-%1d zAuHMh9QZiaR-cV$1p|)<-HKk!E^(D_Qb5*u!^#w3EC#{~HEm4TQVMLbxO{29d?^}! z?+^oTlc-p;tXPItG*BxVD6m;!SUKR%oNIYRC5-1vhRZ0|QcqyLOg<I>g%=o{yCUd2 z#J!CJE4>Ui4Lovp&4#H2R#4!1yjT`3Rnj61e;*C+MnPGSB?kq~K~`lcRmmJca+InF z-jFnMmBNFnV{TO^te_<nXr4DrB&PaHVYP@Gyop-EGCIDNWo?<2y1%<JnOjOmaTg?A zy_IbTbA|-d5ZiQaSz$gvr`m!96ak5vw5%kC!|rSrzl(<FC_%0<fqvdVTRNvdy)GRM z^hX23Me4&()?bUM$39@~(A9@E)m@+iF-%~9QbT|Q@RE1KCGV;}iHf#EG^|{ygq^L1 zbToUHe6e8<AuR|Xx`OT~#o6SNA`MYY9A(AC#94%o(}^1ybbB?=u6U#N8hcIoBD9)Z znMDH!&^es};7l~6hXzlJfxnD~Q_)CGk(QyRN-DV}ZAnl>1W<>9s#rl~W2(~75Ih~6 zBvH>|V`(e_APv5-538k@+|j=1RPB+4;pv1DY*I@_z^M;sgJKe53eliB3SvpZOgEvn zkQV&X*<=OMjAgH>U_d){>h7T-*Svuj0N`{6tcOy0&l@(UfUHEaM3>ET!mth<SO@aX zckT9_MQ8^KCT=ax5UzN)4`VUb`wU3DM7<{+7=5Tz)q$yAe9AIovM!QF+u_)#d9DVn zWWd@TfJj7WE>8TZOEL~Lj=L<N#;3v;%LefJOl|t~{@k!R)zAo5Pbu+>foI{s>hSs; z0Gx`1H_(b}nO*m^1*LsTSj?>+)qFM<KFylEM%DY1fdQC~9Qv(=Vp!)vNBA%F6<0{s znEUUhMkcOk|A=eIJ5S%v5SBx>_>_RkcSH^j*hk?xrlF?MuPc&YyDV3GYx91vRC757 z)>Q)bW&$7RKyoqFEl5}`vi$n5uIIf+Dulb(C@^SqWgi-@{IE5+1muc_WYJ-(BJi8B zci8})doo2P*4e*5A|x#HFORrvAEH^P@iEl-@%vY2w~>!GU!7%QxETQMWd`CKoVz5} z5dMH~YKYsund>!<Tlr<y=`ijVV+ik3ZHuTZwYbFlRLM#cG>ZYcgl1iS;9R9PDjjxb zzpEme`p6yjM3k=yP$yj0c21|Rj{(b~*S&rKBG6#`rv^}^v?ns9DD%>kq^rS=VF%Q~ zT^1MxAV!#jEIc}o9x~G#qAMZBsY8}}h*ubHU9sT<iN~Kx(QFb=zPUd!Sh3llKtqrZ zsvoL)o;uQY6%`_6^`~0}H<-h&#T_{l;TDH<zhUJ8YI=}Mt0Iq9p(?VF{SQAv-t)q1 zFg@o!K5TL2g9hIP9j+9&&^kI}s(Y9a6?pw62}l;YLf9P^raO3a!Go_jQsAY=I+}-u zfnb@?J~B9(#dKNRls^9QB(xRK<?{=cLk7RJY6wL`asU%}r3O5s@>~m-Wgp@lb?`5m zXI$?w)D+Du9WIT1a?B7z1l)g(!S(bULBM!iKgDY})g*FY?7l|<3c0tK2nLnAy<0VP z7qNzRD;#qM$ek||1+*0!yrrU7%+HbFUEK^=JRNv}2Fb#~dol2x%@SZ3jOCE!^5idh zT_TcJ*@k?YP6maagfwE{0`8B9V%A2f1&gZO47%<C27X=w=z{4O(nE|+4(=)quQX4p z9qJD|eCE;XLl|%&to0E0ysMt{O<Y1wCIvxQY}ty7rBp{KBW9di8h5Opl>XwiYeM9q zL46WDQ$HLu!fHRW%yi78uX`4_2shh~5Y^L<cae`@b3Iw6xj=_?U*4bJoVfUjGPxqk zZPpnQWK8~m)vFMOz21aj06>n@ZQV51m%r;?3X=N^-Tp=K&?ngYVt6Kl8i#_e?Kh~z z`I&2FH;(BYFc8&DVBItLTczQNKE3B$&x&=Qgk}tL`ct;5<~5!TzF`cGBZpe)m35EC zb7<pc@$eaME~^Y~hrY>8IL|xele?bJr#+CV##ii{vjCAe?d+zxTCeQ^|D3~p_2Sr< zlaugzCbSz3NkDQX(z(W{TwiQ?rg2>TI7mNhfkFb3NLl`d<av*2S;j>Dk$Sv^nNJ^f ziIl-Q>LYi#G+6`JNeHkf8I+C$^x$B17%H1Y_wl%+O;3x#vD9)TyjKDmb^t6n2A}<8 zsics*+NpNnjmRQ{L(!mt`fS(9i}V8IZCm7z=3a-4VT|p|cMm7$z7HBs!qb@JX_WCa z+CUZt&hiPHaPgcMJNw57Ez{b|-S6@m1-;agEefT9_UC;5q+FDzhINF5mHQ<iA%`gN zKAC5V%<~-mA^b1b6oc!F=Z9Dv*G~Wh`<QD2!1EW$6)C}T$l`d$Uvur9hTKQ;Y+ZAH zrL?(>>s_CC4SUS6pIL08z*wc;T?{l(2^2_%-p9c|1U(A%c~t+8gSg@@3Uphir%|G$ zUINxA0ZTI>CRsk&1#sh;z)oZinZl(!dJ*FA<i#W8IQKJ#^~>{<-1D@V8B|>w4)pQ? zC>q(5r!;AOnn%y$)#R7gFBFmWvM4eRJW3;;l3C{(_vg@l<>r3F@AsMI?^FJQGc!0Y z5|d{N{Q+>u6-x!%Avq)f>^w|>B$8c##wLtphaG2^KyvVZ<8;G8IKFYkQb3n;VZ_I* zCy+hr;CCG4O9td8g{S_aKApZjPvw5!Vz6;|4g2FWchSV<67e&~Zo%qsu){JC8UU{Q z3hVz=opMdEhP+b43uqSymZB@_kgz#xWSN3#T3W#}mHWUOcAgGBKqKn(5OBP{+Lq?H z-SpHkzy<Ng-SONGc9W7#UqY#%t1Pvy!CAe@`3dPKp-D00Wbim;E^_^=yw3w*O)U+O zyrNloTs5@L^!-aJXbi9c_{M1mU<abMK$iez=h*m|00AaI5P1N7zAwSpFS^7mu-^hQ z+0G!@`RD+?EKXN4_!0^nivmYdKtH_^E*gk_03?;lRYKv><%`gQaYycGZk~F4uZXcW z{jr(>OFp(^d=6HNp&qN)i8*AetH8j9U|@eLD3nrJDctqi-fST)bqUS$fl|d<tm;ES zu;jU~SpMB#kC!PwKE0X+RNi~j6-cKz<aC~RUSbqY*Q?^R748h#-Pvpg^DL`b^z{T9 z6TiCm0$4{p==~3etWC6CnU+!ZjX=Jecf~A=^yB|>ia2ect4#lO$Trf$mTxSF-=AFU zh>QKfPlHtfNIVk0LzqPWtlX=Y?|cbcmkC}Fl3Y3&#>?^aWtXynO@NZ&wFIQaPSAU% zVRG6r6qz1o1h#C8p6MEnO@{DFn0`?SdOea>sO-m>&*0FvtJcHH+Y>;KoLCOoR?jDd z*6`Ve-0DNSY?1tr1=R|ED!>NQ*e*Hyla|@3<sQ9OtCgrX1H)r5eyzKqjUV|Lv*BOg zJYqRymvwb-t_=;Jn*F@obz}LX;V&s@b-QtNo=+_Jy61!0)%+5!R+(88$EfHFMx(iS z`kBO0k%07KvmE>hfB7mGCS&+c+S&@WypCr0?A*=Q{UbRRTKy@<us62vnF?M?4(pAY z_o*KNJbnQ_Zdf<|L0Har>?A>dYROND*97HzMm8TMr6^OdHvm+~#;`#QH>jx=2JDr_ zZ9<?4c7%+<-bc1aMyy`-fo~B7AjnvfwA9|D4V478BwWo_<bP^}j8n0y9|;7NUnz@V zS8P2r%MJ3EGc!Mq-)VSvMR$td(Mr-Z&s`&B0A|LH!5?)z;f&9>u)iGG<!ELI<o_fj zTn*O}@0BgE3zq(><#hA?{fn2<e0RkDqz0Oa#4hcR+_9rmPe^-7^h+O!?@0icU%DuY z6bpI8TVRYm^ME7)QQkL#YAm>LWEf$K&5BbscIHJnIMhPaMeUP_<=VmHW@0x*9%*<d zfHkZfun&|ug|Ei^W}Wc0u9DV-zr$Lz$8RnW#dWq_LA)`a*<_Ai-RKz=k11I6E54f8 zdsRry1JVx^AwxRIXMWOh)=`h?{dgHa09&%O9M!v-0H^eWMG6XX*IirM>ZEKRLrf0g zhK%g`V>iZyuZrG#1l=qH2wlEvmVZU9)cgKR?jQ|o(-fe9W{ZS$!Nv0q_?}$5l~~=b z;nFWP=etyQ3#=F$QW@sHZTVVH4heeUPqUiZ#KM@-$;G?d&7+bT3}ph6t2es-Smb1} zSR)&B2PAfMcb`ybUH3vxG{v`aC__&`Ia%_C!h?ni&P4^Kp*f=}UQsK%Su^pR18e=5 z&HmChG0YAxxL7itQ$(>{X6nQ7t)IOgD$;H1KKRAmt^6P!!)%i)*|r|JTAG@)4?Z6E zyZ4IlVRkP;Uo4qxSZ@=44dpE`kfUnK&yF}x>Cf{;3W<<#0q)Qx&Jzp{3FMVSu+1w& zfv;<bqn4}i0MdZ;S_1b?+~6_Wz&BOw7@de&^05=eUflMkjgH9!eBI>aqb=wZj~c0? zLtDx6=g*&9+CXX~z)=b{7BJ_$0i9wT2Y(By*~NPx<q~H#EmW(@S832iH32NLP05O) zy>k^xEZ?*fG@EN16fKnCJo~sm<A%2_R#4g8(5MZfNnuL}B@dZ&v7N=LT}JInr3Q?% zYBzal(d~w8-2fAFyBphbzj%pyMG26m^jd(CThZ8ok3sBjsQ5t#NzZI86GN32-`&gA z8+l>AGFR=ufDm<=FN`olgW^BY&()cgRTzE_;pcfH1g4LwPJ<yL@enyA$SqV~2TeS3 ziJX{M!_SUn-R=u8P^Dvwb(*|pP)v3|_vC#9W_IxSE3KD&3rdKvv1`Hp9LR(N<Fobx zJMtZdrt%&MX=+?PM~WNpr!e@TN4w7`mX-VpHDj92k!nZb!&OH|m=KTGQv6-L0angI zXKxgNBTBv#bdhTy+dU33QEg69tRzoRJjbyw0i#y2QX<y@FNC)DKxktl?ufmaEP+O% zrc4e}Q!Gc2UNq93{L%txXfLleJtAv2d#^3Uw&CjBO8Q7xuer^z@Wo=9d#sbeWf;$K zl;^1C*b5`$V?kmYfM=SIeKINAa$@h~!M8i#XGZi$i+|QKKQyyY%|r=zi0*Be>8-9H zLKxM;{eUm}za?E`C5#YrTtm`(6r|dujh(JMNVJNKuXSdgIX^(-JVP-=5Kx?!x)d&d zMuNNyn~*^72hqG=gb*@^$@YdUO+013!){!o*1}ZrBpdMUWR*a<H}Gx4!?MM6_8JUQ zLGbEeDogm-_sug<+bEISR~Rn73K$i^R`UE5sy6ubo}jf3f15k`Q*>zXUHpNCM!x^2 zIy&&BhKx~)@%jqyNWlDs`=;mu|LJ3FT43EZUg){ct2qjmq6yB5)Eh$_;%`~M6J;x0 zMBDer*E+yvtNnM{%1_A8`&!=SKUxym;ulQN2__jHMsQPteheq6gSF^BS?2tM<3H$h z)6dy>#fAh(B4f~K4+oM^Ivu#kc@=nCD?!bN!LHVW;t*l5_cIwdd9?(j4Kw+=PqJV+ zJ^2K4Ed!8Vr$%~X>C0iNVb-b@E<BgXdy|bQ85bl_gEBo8npAp1$4$LM!BlSQlu6Er zFTYjr^?LnBA7`I!h<;GuRNdgsGDv&}zegX{U>F`Zl23Bu@Cvh-Wa9~mlgeW5sV61% zJ>c;{Jop=6{!qLhss4CCM5qz0^WY$-e5}(%BhV|$RsXBwGl<+ziOX)Y?QL<Ke&PoW z1==HF#$qSID1=4@?ypD=eHLOU63C<3w}m*2RU8;+rTCs5pA5ym8E`_w$DmrKp~z=% zumOEtFo2u@cagA-ZuDk5f#P^;21v*fN``vV6XgI&#>Fd>YF1TJ8EYnDDI?mwhgVY3 z9s@@`g$7TAzkoV-O7)fAxHpyN`^JGJBIq(J)q1{vc~s%e$7`=-^+@VGvB}1TmwJG= zKW&ZtN%fOyHYm3+*n(W{+Z*0M-#{BV>Ye-ePHd*fRD7Th5|GXzJ@oyfrHFcNe6fod z`BBX3pr6KzPCsE4@ie}=ZFubLyJIo7wvQy$->{b&Q<Fl#J}+1NGlr@gm+6YfX&#U? zKs(<zrvdI73K9>w2(nyAfY$)*1U(KVIHag34i#$H+bcAn2ooUU-3Hg_#J#_Y1Go2? z+22-nb4WeRuWffvQHYe}yG!S6b_v^AY7qHl(DqfqN*(T@ckGd0z+p&N?#}m@ho&F2 z_*+U1vv>vv=Y0eb0a~1T3;1q$inC}}NDtn4LE#PzK#|IdRZi`dR^v|4>~kdP_25G- z$YFr&NDE@FQ1<mS&LC|)fwm|7{)qcI#A^$@QKiaPH^6se!B<3!YEObi*qQ(qU`kH6 zYt{Wo2_gW~g2jNN!?FTV5(G3k3WHR0VUr-U9_+?3i7VSUm0Y&kr#R#S4kQoYL_R)- zWCM`^JWQMb7JQA8cql+i5Fi7C1C%91!S|>2jwWY2GL!Ab@P?F3zan5&Zq@dnaTTP@ zP6_YafOp3MwMgt*@{QJ~hAcU=%1H*k`$B9<M0JSnPpov{{(a|PTsQUz_pd$Vu*vKd z1w&pDE{-LgmFEo50>@KjrTH=<76iR5c&*lktBQEDvEa)nVSORE4wi74q4PPA7{$=! zb`(XLi2k)efF5>(bo1C31zwPenzTeY6o=~q#E*fOCmXG>v#XI$^N{33P`ERZ30wiJ zH)br1VdF#@^C_{Nqk+yTCEY3mP18jFP<UfLnSO1^)9=G8mLz+);O%-42dBm=a8e2? zz>6uFhss6l7A^Qk%1=l;7S%=2IG5x<zXXqlCH>hZc=8?dV@S_zshMRHef>~1>@8nW z8Kp-ms!k@K4Zxcwf(2(lmfjVms?Awy<N1K5^<prpNcnyd%)bX5j|C6F`t7RBu6jTL zhQ#m<LMWXOLI;JTkiqgva<oKwW>PQ%$d@XomJU$$=6LlT#~A?NMFBwM(YI-UIJE@6 z05)$5C<zU^2GM`PQB)m_IIjh?EG@Mu!aHqn+I5^6icCpS1UhN~ZD`4OUruEJhdC~F ztY-4X=M+(q($+z6h_$o>@}YemOR#z0Z0m`&x9)FmVhI-ydw&UjB1sRE6hsFfV#bC; zwEB9aZN2>aVv0cibPnIw9KxT7H_3Jbu#@&GQ<vXSJ%fm>hFrlI98AVrP@%ynaP-1x zzABq4nNwpg@fgZjEuCEwc?M(wQ0}viHo-vx5;S%uR7p>BDZDLuQ<Xi4i)g$WmE8@8 zcO_Mwx46${3!M-f0x&txdyAO~C7!|I-7SE5iRkGT-Zqo0Kc$-2=|pvMR?HDpc?>vI z2->4-bJV!YeS;-SP>_!0rCV5Hn}KSSWP1ju-53EQ4=!h<@YI@6N}w6p%Jq?;o3Y>! zz{!cl6#idTpSWPZ2hW8sjEk)ygGo;f20)jY99Hb0cqZ5m`_J`1Dksk&+hZQJlK`>6 zA*i^%Nt~)0n;0`mTZ!Xj14uiVSY>jag0^w6z}wIh)o=|?Bq>h?Cu3Q>6P?p#fm3oC zbpbtjp5#=Wcb2mB01Lr|Fo}3-V~i3gfK4f^!OHxhWTd=?*BA&ZK@^JO<>BDPS|`e5 zIf8LuqffJzLr-!7h&Qo%AA+YgCV9dZWc13;3Rn`aFW64^D0ov?M>Zwc(?Ib>9C151 z8RmsJj|2!7z$t$*Ix;~mIDrp9xceDI7s`%mnDSQV9u~u2)B=7S1EMz?-WA!zv`#wE z)R;>^bGp<;viuqvxb@KjXWJ*tMx3zZiNQ!7^38FoElhceqP#E<CH>X0Xq2lyO*bw( zGy)t#<+NiasqC?HvJs{6bQ<f7r{?Tp`PTJFEBzku1fP;vt%(yCVE>5X8BZbxN%U$G z2qq=-VFxW}AXSVt5A%XB3cyXXkN!NtM_=+}&fN}kdFNu|+>m@`gTt-}=rDHlsY&KN z&y@6!l2#a?9WF^?gTo60Jg;=L%h~YD&=8hk72gBYBpF0A@98a^C3~ym_Cc4?gdo<z znaTX+Ldux$#ESskc%001S@&e?xne5FzlYs7l3n;0c(bqfvYuUegXCr&v_rc5CXyIG zyY$DO<2b{bm8dxz?4$LJTi<gY1~UjD3syO&XWyZL4mcnhmuS#{ccUR5Swb!5+!v89 zCw=kwrex*4M8va9+tTG`X&&Bk7uyHoUgX5*t}lL#@lZUKt8yUT*fxN-nM6b$uNp63 zwKJ<HjCuhsc19>TDvLJOvpe*cAc&>T-Rr;cH_70zg?_fyZ2I6i{?4IqlOXRRkT;E> z%Cvr+za+rKLB?>LB*5~VTiqK%xDxozAGG|cX!7M`1x#|KHQo_JC;VB4IIBBAfG$dS z#goY%s8__H6|q}qMO{sAEa=2C&*`2|yy9S~1sgtU?3?ZVI(WhAbsR609}&M&Sb7Q^ zK1Naxa6NQK9Je7J1{?QpNfE;tgqR-CX;Pzb)06&Y;w9SR3)y0=l9xQD6$!K5q6ly` z{;mz}f|wSEm{NkO|IF+6ZytGE4BHc%HJnaQoHR&gH>2U*lz>iTFX;k{1bv{%GoU4f z+t~uo5>cb=Ubps^WtXYnv>;x0O>$`<-avzlupC(p0tfheBE`JL2ZX>q&Rg3Gt0BB= zKHy;FDLV!Mv@XK71-3$Qcp9%)HOz(4lS8Pin+oxG9P4$07TTtVjKSeJuCk1Tb<X5y zoaa99{bLbu2-YucfwB0={Po<MBW3_0W|Ar;IS9kJW@e*cv|vDGuWZIUapS<3-*>fo zbt~f!t<iWJArAR5P7g{l9zRAjXjTpf+YEv8T!=<WpsT#)e_$!0e=kSNf_>Lr?&y55 z$gYWB!LKWTgVY=*jv_EFuz>-h8<~I|^Zj_T{d$0*ZckUjsjIc6*%&&}7viZ;V$-2> z_*03~l3?UcKqNpb0tpUjAb0{m##bCU(Y?Ks&wuYs*x<kmyYFA<Wm=1Kp2EprL=9#B z*eGlmJMV&bX5bB!*bTG@c1ZlIg=-&6c-w}`d|k2(f#BON90s`Vo#Ct?VNKs8f;|A_ zUwp6UR`y!pI$&Z`-2lq>2!D2iU}lv%a*7b3LW~?U6u8hBF;Bck<+w!xV{o*?19wwD z0H=OWV$?jxNYDE?pUrQryuablvH<VJUF*i-(Rc!YGax~gaW;Z<rMh#{t}9cqefHZC z{C(TtO0<pDGrT1(Q4Nsq5P*lC{+74IgViGX3K6b&uU>DccX#19=ja?gmbGTqOa?Ul z*h{t#c)0N65|gQfoG2V9b!OwiZAT^fNN*GZnvkU@0;zq`)ghmPI{`{ytuBtsBE;(f zLFEyO6P4gI0d~Csc7bDAmwz+2xl@YigkU9bhnX?*?sEtZ7p0%@_K(6sy2XUvvH=(S z=+HI0jBk}F`HNwAo1)BzSB?^IZJ&~@xTBb?GOhSL7c4sqIiPX)p)?LBZ>aegce(T= zPZ_Mk4>LoPSeKvG?`MHyp3qq@j)Mx+goHpm6&&WMVCK^@mPmMgB?Kxs9L3bbHh@;d zL-iknH#tut`RR}BI^EkZw5qc~aBO_!(br$B>!ZA-&sxZTT+8z1l$MaPwZPj?g&UV= zI8*Q*V^RiV_)IC*rx>*vm?zMo@;lS=MFU6yMQpPU{QmiJsRz>&`Y1sQ<AnwHlva;D z>MiMkDiK@@l^iVPIsYCsJr^QUt`Meu=0(6;BH8ny8~AGt#4rgW|JD1Qyu?r}@e<_C zJ$jO^1mWhG#*Z(%c^2S>qr_l3C>T4)vwW3JDdFuL$Xng&@SUlbixRsT7XO*~5_brd z*ZJl&228T$Xz)I|M!%MERdjnHCB_@%n?ii(OLSc~xy?Llq!baP45kwhbomTiW46yb zg1h|s<<V1-JUqWHi$@EI&fI{~>0nJXp23wW>I=@l2b_Q#nSQ7desL+VM{yfRyfCNj z-DMh1Cz|!J>i}53{KR-BaXJB|m$fUrIJJHkEJk<Z*}w@f-f)h&9m>pFcHZqbT(D6} zH1Hn#Oyl3yh^7SO_ut#b-?;wK^LK7H?}tFp725Slui>*=z}r}X!SVuQNA9~I#2@v% zYmz)1XRj2GL?1SY-}53`kb!qI9#;wxdCw->B|{I}+r*A3fMS&%fz3_@6%)LA6!(LE zM8D-3sN!6?%ZBVpJhg|9hESL8#1$0rTK)jqDfz1<vq5OqkPYj@$kdRF{pmW(YjYRf zHj+ixcRyW)Zh8XIV|W7`y8#*K98mR>czB5oa^v%O%HYoip$_cUSS81YZ!bh{k4PA* z)FF=PMY3tI9I{)|V`R4J+Ss4AZz%?Q<HdacI%LIwAY9?;dD+X%$Cphs?M~1ss=#(f z(zEk2c8f!mr{vUVTG;u=Wl0C^9@;mUw~mSm-aF<J@u?!`^tB(GJux$pu7elz-}KzM z`eC~Dnm}+*%n-?=mz_PO!fbE3(%5|F%<AD#s-Wr(OJs#s@GZL{CY{|d5dyI(+mg!+ zd`GW3TBwsh?kp=GAO7NFWRsKm`5LpCyCJWBG&r<#6wT*N@bYWj^T^h@ANKRh+IXR= zAfmARq3>YHVy;|hS$9nL{6?vKN+BzwUaS9gg}b6$?O*^Hu&B5GJ><?A+jpRS_uj2< zy6tc(x0g)&=NyC{i@6J-85@Iek?kHCq!#e#AlN`S0XTn4INT)DDa|8^$B})wRx;&s zf+LR_ZU<;|DRIMC$YnE6OFARXXV*@50Ta&7trQ6`=7gefG`_MpUxZ%xT#rAxy-{lX zR4M1En|w`;RI0p9Q1Aan(V6%|*}i>v7RxMV!Pv)`L5zLLPMR6J?1V}hTiF|HNIf(5 zecuuqYm|yosnj!LCoz^JNn=eVjiN`TpV#{*-1mKb?(4eF^Ei)h^Qk8z6=&2A?i{L1 zlsrkrb{hTVDcH)0r*GFyz7)B0$geztk;dHNfP4(k!=hNnG${6Z;x2tM-TdowXkqe= zjjqxJy+IYEmYv4#DS%UPGgrQBqjA-St9{x*XSYYR(DZB5d_mqtRVB3X>M%H8bA~I5 z%wRsXUol!9`(bsCe}*HW^Rr6<X|}cZSna`?-hi`#b2YASgP;j?5?t9M1!3|v?{#?o zxdJzs>fNT2Y~d?=6g$<XvgNgK?&udKl_z)Z+iTKDoug{r@<Z!AKzOoe%?2$2*)}#; zI%)E$MqxsFH1MdfmXz4sobk!HSSM59&XVo1CB60_zpbXvuabA6rzNuwy#3aY^co>z z;nfTI3KJ5KH^AdAQK1SGW+_A;Y7O{Jx>)Ay2FNk}6ubHM<m25Tq{*dynw5}_58Fyt ztfW-V*fsacJL6v=O%qaOaWp9qnnVLB&$X|7oqIK+^iHLb1sW}@?s5xy-Z*n??{af? zNsbmRxHwy_GVi*~QZWkmv1S|N=5Q4DaK-(!TN<c9CyhsWVAK$_P;C5d_^9oX-R|j< z!4u*?KR6n*13nn)U&uOnvMjn6YDkzB6T4yd@(9O7*-6xavTYmbd3tbXD*p_Y{5LsZ zrRT?R4*rm@)rVh~Rr|R%EmmoExS|<?+Ff6NYR=6}7Z@*I4Z9j}&|I6b6?!{sIa~R= zlIFfJTE}^+Ut@<K=8{JdyOiq%R2Xh*W2Z`0J+L{J@CbQv!$S1jaE30Potw0wsV8;f z5I!UnnmbT%AGI_4{Jj+7n^I*LyZe>%7|(3Wvn~Nj__aEK()~nR5#jAYYrgMCllW4k z_DF*6TgvSGa!2gDs>M6w!j)efJJl7TnPyqrsTwm(fbARz-@SB)p=afOHo4JeT)2S7 z1<Mrg6+`jNYs!0m=x0TlGD`{K%Gn_CYVBUdNFBIy8i+2#sKhI%lq6+0h-M$9Xo8Az zh7PBY>SB?mL@#8*Op27#4A#`CKUY6iA&v2S(0Dlwe=rcJ9<Z)G^jSd1CWcmQ8TGr+ zFku@?Wd+2%Pa3*^+8TYzJLfz<Y}IG5zEG>*{{lEWN2ltNYV5E}(XY4DJL|0j&eozh zPWNf4dxPnT$re~W9U0?iw&+s37Jk{*ydpFpRlJ5Qw_O!vW&wHvC_C@4QO&1(J}UbZ zK$E$OB?68K1NeRdVb_`IM69F{-MFifQh&p<+HW-d{e9UL&ZtC!D`IkFMP~mKD!}Q| zlvpoN?z^O*)?>cfc;==khn{Kd?I~ZK2R?5H%rNMm>>RKRk_iK3imb8w>&pWoOZK78 zk92ZTwP4v#-a}btze}`oR%9c(dr@g|>82hBE3zapHSB@PHPOASh{!Oq((3t>-AR1D zw`|i1H?^TBXHu9wOJRzH&ro;jvVG+$pN0<`wt|0jUo+d?WyN(gjkO}HXlHYJmXsZ8 z*5Kcf76Jg|NS=A5fW0Ewf5*+c+;cKZ$sjwuF;dwBLAWTZ)ac<>l2blND-sd@B#=|x zS|lz0^%ikzK%Wx-udn>0<BeVOC?zylexEL>Rnic&{Sg^Y?UT4LoObN}8v|4zMQ)g4 z^EWtm&aKS<AO8e!wU2O)dsc4a(m<U*FzX24=Uj2g*BhjRu($uKxhW;lK4ff5Iex`# zIkiEdK6-Gw!`^}NR7WT*!ddl34J}ps;7O?m;vXaYB@zCI*~Y@sdG&>Dp32yB1Q-_n z=%!!S5v-9X&t{ITW53T8#0Qg#|6w~F&?SaT{s<X#EEOJ2VDV`Wf5bl0$&YAveTa-J zQPpPWYO=`1wGjS_8g+7lm0p9_sFmDPm+Uj$DKDU&F*a~<dcp!IW}7~A!!NiXiMI?V zw9h3zRgvx+R*-lCIR$&)-|D;?uRK^bV?w`;i7IOh=U57PH-G03&=Zz}MP;g=#gZA4 z?YL2DuH%o=(`JGIt?yNXsH~!KIlTs4Xj9xTU4e=lwe|dHIvcilDTQDOlA(q~+d!eY zWCx&QTUGl%jQoEE>p)^m`az5Ym3=Pd#qHAhiohC-u6?naAWlXqlRa0DQdyv+?b_Dg z@>1)|13nZfpKDGI@zAZR&ol4-GLk2K-opuhvaRdd8N+=7#4_z$_SW9VLTJKM#jB07 zZxZ@5d;O}C)%Ke7+pLSHPpA4!fOFbS{`>L!M}AU`A4L0bdqNihg<}Dcn)}M<Vk|y* z)Vzdr%~@*P=Ob519PSzNNlIL5+SxJr6CF^}qias2(Pk^@t1qGeu+j=G$p(2-!jl)K z-x04JdxgJKZBCHXX|WunGAr0-EB;Kwz0f3?<>1JGtkZ>I7zOk+Al8&`Y7G+E^E&KF zhPh{SWJRZf%sFB-_(0Mn&>ygJnA2mjBq>zrQ1h5yC4p@2hc^6Le&_zJjed<mfS`AK zujnQ4-|9GvoV>d!5;Qbey`#x>;a}HvH`zA$%8n?1HU)M=^6X;UnM%<*Wo$uJno;j| zV(n}PcNFj7Y+qF$H<Kz_3>b9d)JZauEpTZ!GW6!Ok9%ZB%lcmRT`}cLOeXFAZ%ISw zK9*9f11J$D>kjv=qve+R`HlA-%6_ps`Jww8sb)Q5K6cj?B!Md%5=#ApQ!3Q=I}$1Y z&XM30ttPU>W{Of1XqLgn923&RTbe4KAVMuon6{WXq;o7hqQle3BSj$%Y&M*=@G1+T zJF1b~yY%G1<Ib@&*?MDl{*JrNeW0ZacnbOI*!G!jq!N01Z^m9buqq&xS)A^vzQavT z^ycpf8Z+gBVEX_VhEyyJ)F#c@b~ESp`AphnO{jg?y(~1Ij=##*Y3*Iweht!hQrgK^ z18{1W{8mY2O3jobs~}7hu(lJV#(JqhS!Q)r8FhcKJ(cx$rr#i$EVYq#C4Brs{-ASB z-|lNZV@}~^^%19Ck1ITv{QV)#O^~)nsww%5e|O%Wv*<vFfoIL0gXM*!syu@Yx#OFb zp>}fq<#}d-U<oD(dzFQv0kzPB9}<^YdA5G^bh-J`a$^9<2q44)D0rW?f!3<v(XjP{ zUL~Jwh3o*JhWHGbjbH6m@8BLzRn1Y;jjv7Jn4EZU2W%2<K_D_l@jeml?@<B-7k2t0 z;^aRI6<=wonp<a0Sbchy6h*UuInJQiAXATMsTx<LxS6M$;rG5n&Y5Gcw+FuEs^C8W z{mV)<>;l3L^9O@*aCGYN8cDK%ka7HBOcqG2eL{4YUewMK-6`EWQn7Ums_v2^Fq=YB zI`Y4S6r$0HIt!%UnxXXES~=xN_l}L*B>4NaOiD(eJ}(7>c7Keq*2oZmu`R5|Cx3?6 zCHsK1h!)vj32qg`Mm+gG4J+6D%HOZ}|A;BX4X6HOh>bh+IX;vGj`(C+9`ubTgN+~x zMQnbv?i2$NuFQF$b}Le-^GJ92WER!x=ciPKVG<tJ01HepC`xs5n&f0tl(G)rl$WwC zCfvFpJgYf8%?_*sl3$}(2c3<60sT!%Rbg8Qyz=+%>eKV+lSoc6UzJTh8{|JTajv(v z=;27jHb{pIYZ`;tWd+jC3WmsAyLX=!zu&Yw16HNk9E=3cY)F~$QZy|s?kD#dE?h_` zP8;#C5D#wbU;;#YQqN4fuudvh?)QsFSPm`-DU(?69y&k>syv*UsvW!~R;I>cV>+yr zAx_-j*661vRQ6wc)@3W{Et94;G79=8eEMu(TlmmD0j#l06$fO@OrN1ke&Ups#>w=I zzj&-SIL&JPD(&<?U8%{fWjayA2EpKpMS=Hh3$1Y>8vw4AaT1_D8Jp#-%TG^fXRDz@ zfSusWtW-U9iXMH~aQ}QzeNoDNdYUdkn8_mSf#2^1v-I-nW)=!bBv3a?w5(6hJJl$; zT=5vXf|a5e+kEw`Y@-NL`4)w^K(UGdsmFp+uDxs3gi7HQFT~}QbXn-96^VGHrnV9W zXGDZX`jmt~`e|cHy4k3Zz8}J(7B&4kklXxQHhmmr9$=~p>3mGG?~T6Hb~3qyi@IH( zYR2hhoK^}3hQ=}aOi7eb1G>R7In3nK?eSc_+5@s_JPA($Kv^vG7|@_;RC&Z&HTLiX z%MOjDJj)90$;qF7?WJs4D@jXXKYbas6WpsiB-sl-hVSpS^uA5)zjL)$2Gg5xi|F6u zzw8}iR8!Vao+X|Q9&If%2=5>JN|9Sl_X-&{8Sc{@PI2p+8C4xL>N+<#4-IVnWKDA+ zB)}%L16o)Xdg>{f9$AURmrt(X%(x)<J`3bPg!c@a_KS>os^>SQnib&`SS-<YR#Q9+ zT?NEjRV#jS1~oH|Rlfvef1Ml7Aa;N>Rza}uDPaq^#jPPpYbzn~R7!hl3$ae02qq9M z2p)atMeD!AeL8att+YJTnW+-u!3}5ga|Xm<6Qb=42tkw*HeR6kI~#1=Z6RhbDCQrw zuK02ydP6!K>|<8={dK>_Mv7+eP2*&X4A6Bw9Uv?i01O2PW7xgwE8M4c#L-mq&0d%# z!-PVD8i5ST`rgD(*4Ad+k|rN%O}YC1)oF9B2drEbdJ3_~PC}^n7E<o_=}l4=_?XXl zFFjQz#7duJVMVkUs0oayDKp%Q(A=;v+!>lMu!(`bHHi%|$g_#xOp&1%XM{k;cI35P zEFNR({m}|bZ=q_)Z`MS}kyVB{zWB+Oz4KiQEgnO2rq3x)Y3#3?Nmic*697NVc2);8 zEJMtSCiY*9TnGjmU=J(=o9OfQs{g)l`YRdnYvFCxCg|E)iue4r+en>mA<UKRUSfDk znMW@zjq)TUDk5)*=m>7(g8$Y84whN0P*VKFdzl;oJLZKWu?(&Dq3L#71l7tTu<wW6 z-9+w`UK6_`ejfBj0OJJiOHVcExhqxy&Iw%V?M@ZE#P>UyasGGb?HQE0ZOXS^uz6a( z^5vPAK8@Rv8sH6W9W+GdnocD?zizV^O`;$6h6J<dGJ9a_z(C;Iph`{369*86)vMHW zO&u;IF)g9mK>^7g1?L|b&^#2EO&wjlsH2`&W&X-|Z$vMv;P?VXc_tO`Ox~=<;s^_< z*Tf6EDh~bkz{VY+Yrx`+xq>Afz)ca@7<DBxY@enF*q~<SjaggZeTzTow0!cmjjg*H zQ#*4!(4#w5lcXUX4gMbd-iYoh>j8iT))~wKUmadnydQL~+Za<*HU1?D_Rt|?ba)RN z9}fCEcaHB@xoTc-6`LV;92#A7&rZwk=yc_iK#FuXBlgh=eZgIy<Ok9yu<D4LV}I1Z zFjyM9r~>E5rLu7sBQN(q$Y@Q6yg%!`(WkSq?G!vIUnpQ_dFW=gFiv*7#g5$3PSw-9 z=u%^gBc|5oAlie|iC-wTv#71ta%N~%wFh(oEalj+ozIP<?qLv5y>zoZkeCYt=EA_3 z9nirf){&gl6X|y*iJp<H6rGP=fHX=VN{H3ctK==Oz)exBN>N!=aJl#MM3oSEu8*uf zW|aKeIXGQE?Z?JOAGGgqCwB7Kr%DsSAa{+Hhkd4bl^$iD`ihHicB+;oTc=6;<M2@} zfi84VoC8M4gfB!Vt<bE<f(W$oZ~#m1#LaYdXtK0r3_~88yft(I!8`!K-`a|;lMT!9 z`7~)vTqXv>C@NyX`x!=S{{>$vp~q1)doCX7NO2S0>sfGI?4ek(K^k3e--j9{bNEcd zQ~3wL=2___%)UFGmM30Y5U`7<O9uwuM}?gPc|Aj>DGNH^$~m2d)R`<YRzDcV1V$PH zzF!`@sqpVZBTEPo+W$}-e2kcuy#bak>%EzUAPO4rQXW>9=Q$F8f&v#o!2m6Y(Z?dg zY^^~JKQO9?4l|>_W3jQXrGaf11KKE|_#dUz_YsecONC^Yvlue1+=IErJeY|C>$=%o zD*wsMs`(osPT;6}k6VufM2ESScu=If9vJq3jp@HGdpzCn0ACg2GaCj;;w6j{q`Rs^ z6d_&mY60BN)OK`T(n?P7nZnkf=m)HUgp;u|@w4p=U%$OI0-Ev9QP#Cg@&$HfxbD*o zZdtrDQ1b!+YDAafMcq64U<=53d@_pInquv${BQ!&!?zh`0aU0uc<F!4P5kDcLCL%P zj(Vjki@Db;QZOls!~gm3F$*qeddS)qDi7Uo?7Nh<WjAYqyKr~;sSvpIj($;~;^WDi zXMd3LO7v~P#~cg;ar={>`=o<G(J$fcfYa0oywPU!>~5y%F!<VqI-57-V|jdS)0a`! zRq>Y?uvYr~6iFm4H8}E}^;aAfXmhoAJL}7Si5dE09tD(7R`0l2Vf5UFxh=A!71%%i zj|Vua@TNPf?`wQmuqD4yLeiy6U?nfB{CC#iH<m^+sjC@|w(C0jJ+&{73Tj#RDqDX4 zk|sdRNj>Icu_rlp(E`=j&L|r{;e0<;Q^-PVZYJgG<sh*P^63LG+=H~PL*my4YI7~r z1O8s^F4uBkqvyT|jj_OzWa&BM6IF$ra!`efj&orOkt6Xb2HFD%S9a0azx8PA+yAU3 zSC>48je_lcy7%g9-x~)D!W4u9xO=Fry>-=*cOL}sAF354!P?a5wHIXRy%aeA`51Je zoF#?Vl^l^AGi2D;mR8$Rot|RWt5B2tpvH#yCvsJXkCX@3E~1iC1%;J7x{LfQGEoG1 zb+7SS)9?gUbs~#O=2w3U>W0%b{q0JXU0Xb!lmxvjU!V8;u?Ba-7@};Av_TotJr_59 z1jJ5vc(i#mNXEVGvMVPZRxtCWP0B-0-uCJ=PnLdou+i#r;--gNxhkNI;rgKE<g*G@ zQyOnWEHp!_t~+Ied(vGX+v`{faPU*i(OZkgw^z9NxB1q+kI~i#J5N*=X!J*YZx>!Z znJ@D!hPTT86zy=sFlJp<&PVX#=_cnn&cm3;1+tt+z|rgn%6G0EOI-WkUCajJ)uaA4 zulq7yof2|qcNedOU64uKefVW|Ah+^Po`ApyiH^B)1TOB&$H|-b@*?GXF8yxcBQQvm z0=>EUD`#%L2%WhJc4r5n4XME9wiM2?Gn-$k>$8fh2Ya<bZ?M~{3}F519vfkt40)El zdab4E@<R57r}Jh35!DuX3_)3@`8y>P&FrWav8wl=jSqQ_2hDsM#TVL97ovCD+N5e# zstF$23mxkCp_Do#eO!Lh8XNPo4`!=!FJ!$o$tmn+Z3S!6M#OM`JL5hQek&gv&rP(H zILl?*jH$mJiy_P}Ox`SjsqPgpVBW*)*Q3K{+$XKvuiH9I<Vg~;_@Y4y*ytC2dd)Z8 z?D#7jnN^AaS0@##X?NG4j#dw!5xyL9wA2wXg!>&aV`hJ`^4-PN#28rycP3X$0xEs8 z?u_`PvTo&gh(XP{rR|myb6fC*SNxsNj?xK7mIgSn=u{iMbDx2l!=DH3Z0wzUb0hGZ zx2oH*3F}L*>XHT-Z<;k8bgXwH!~W0~0kH>BNVywa_Oz$LBw6{;wS1ZmMD(%-uXDx6 zy;n+R?QH5ITU-cPQX<17$UlQpKNj-gNjcL_)Tl=IIX$~(kBX@A#O9kGQvBkMy-5S* zE)K8X23IKE608>fqWH-tHZ4M@J8E<cES-=R`sfr*J0=i~>wEHuJv}Q`axZj~;$|1R zx;?n?1N|<eRCR#8ry5Yd^tCpvO|?|SaEE-yVl&i2NY40E+0CU!nY?frCD31_i__<j z3sHkQ=Zs{d`#%ll;7zJx1*Cni2}nQ7_kCFE@U)7rqS0x@=jU5FkDyYYDLPof(Oy67 z=Lg|iUu6>Ss;o<2`7EC$+tYF_L+c9i0HM2O)?<fhJ`Y`<uQqRe{jsxLX5vfnt8T`} z2b`yKR&}&FwV|iUZ}Jso5@)Y%s4_<hFRm?qPV`)2=I!za4_kx_QCv+z8{zgFAh``r zVKn`Mtj`F@g`dP?dZVFNypeIjJIs_RKV(#RAIuYdO~jIvf-UQi@l)dtcDup6x*J47 z_R5Ii>(5YI+9!1!tTc4}_*_^Gq7SABsH2yV0ofbU9QG?x=rr<q$FTASe&}3Yy81Vr z6JhIzV^;!`f*tx{y4ch5ggjtgTAK#q1;@t7+W&a$mGH<lg&|{?z~>cuaNJ<<;IS7# z)Fo!?#a;A(v^`jRq-%xtbmM>@^lF=;c;3o*ZZ2IwFPaTQgA9^tR+ZJjH4))p=~G;A zGZvku<86Wa<X@vYT5?$2B6y;6WQkF436;eZO!csp+>{|)VO`|H!?xj`O`Y7Zxsec2 zV5ZS6a?=Yvp@0vqHiWyg?9v(q>{o4@tl!$ufSEqo54M6PPSebsj+QfTX_>#I1v1I8 zjS-(iY<ztzaIC;J?5{6w7rA644-s@CxXN11xUAtKu|q=eWtnpJ+meive3IT-bf!3( zVaUBHdyu<f(-v)Y@%IYc#v9nIh|f^sCzVL8l-(qiXG_H|V;=K;a-1&Bab0i{qIIXM z<xtdW8tjeTLajv)9LqFE@z&lwwBkNk$^D3Ab}f0SMS@MVPOec%1F1Boz$6;vfr2)v zG(LS8xQcOqO?R4EQjYJNh#`J0oTm#KP5G+_t+FqNIZhb$PYwt7#I&9a@iyZDg+wh2 zfWjP-qS5EcUMKM*H`z84w)h+9z(?4ntibWQ`?ox3{uNI+X==ft?xT0(i4+ZfRg*Oc zG5MA|B`6}3Zi!4BOBH#UCm8>8MLdBRpw+{%>GPb`P9Qa+cZWS(SUQR}F1K+&dY;?A zqjDqEL39rwV+}2ewDFL~e&?$G<m`^m4x@1Q>k*cvsg?gMzD!TNllgk=jnRbB{rcsE zt%y_62i}PQ3#fE92`o<qU7=ZA2gK7TPND^RSTesc6NB1uE&TlZwdZY6gK)(%tX6>Z z5M>Z$`KW~8Rz=CE<)uq56y<g{?e*uoSL3%BX7iX6xXa{5XOZ;7R)GTQF<?6XbMeWJ zL?!3%t%FCV=1ACx29yI#B*|U$$m1yl7Ap>0{QMbdJpV>A5>Q(Cc3CN*KS2C>mVkf1 zpZVUbBw_AJo|Q0_O}@sJjcfdI1OB}Lkk$xyDWZ#GNnqjbCGkeypn23f)H$nHtYKt8 zslfjX>0%P0W?qHZt6RbR?KE98Xdkg3VrH7%XaLSWY+?Yj{r>iwi4ul-=D7C+4z$v$ zk$RcnFU4>p2YHFbuuqBiUr$CjHrDcN1$|#GL2R%VIPP4Wuh)ZITMrc-($pIdll6(e zzXq?A92>hLn6>WyV8tR!D)aiEumaEP(()g|$*Y>Jhm1&LWK7F{juVIG1uhsFK&K%4 zd302hhtLe~e7?`<OOJ)S@I024YRd16`EqF&9*M?FNBUVJ%9B>e<ha;-gsjW8!$-gH z8VYMaYo^Yf#to91NX}DVvb|#@LTG$X7S>-NYL#Ryri8S4u1IWRzRyaxeiHh@;>D~0 z`OoLGeZR~jZ#%E)2AMzLb4`=H<RUNq95NL3$mv^cUtfa^82~Z^<gv;Z4%lTOC8kdq zC=EITtcYg|_p=Hw?(-E2OQaL2OIezM4dNDR1Hzx~ZZ~i{MC^6Y>MudRhT+Wy^Y}Xa z1_LELe&$~0hUU)IE9eWesUkO81;-s5e&|9ki{u;U8+k_z_Fz8AZlz`>+<bqWmM3L= z`;^wdZ^`>@7$oj&$>4MEh{$%2h?)>V!-$zRWP)iI?Yc9Bs<Fg?Y#4*0Ds9ZlzFnzV zzb*SMs_%m=_fmOXAJ%(oiRjs!eYPxKyq1{z`#_`1o-Afh5Zz=U0)doxD8TV9?K4^G zYJK+NQth~35s3N(2}IS5*380;c>aj}wSwq^>I5Y6D)QVM+vcFIf3Rgqc#5dg;*iH% z%jx&ycVE$MQ55O+lSii)wKkmE_>Ai&;C_F);@vmK_tA3>sI<TkUuf?cWdBc68!*Sf zb}S*}@e`mUpfrHwDtRm|5*9UjeSv`OrwXhpD0k82_H##ct-Dm6MYSWU`q7;IRE)`y z?H2mB4*@`7tbRtzC-8n$wEed;AWKDv=+W4t3@iqu(+)&Def8U0HSOxF>O3}I43NJW zeQbxH=$)#y@Cl34m=^#_=V=`CY?SutySuP7*B<J-4#!Dv&$oQ5o_YnDsFz3(mb;}P z1fG-~Bg=L0Ocyml`v4ifHc_x}rPCpZy$MlD=Q}84;yN1TUwrjQwiOHfB56=Bu4(zh z!C^WyXUhbM2^<kd_6Jq#94Q%;&SBs_6L3n622KIp5Hh%vY!a`LTf%>j7=@3&i;D*$ z139uBwP!PppDC-tWx!8^WNt4*Wc+jf99!n8I{rT^`*jw|l6bcR1gWpTE7AvEvc@sl zXdeGrz7X*Sf^_w2^!%jkJh>Ao1k?op<*Dc$G8R20@NQD-%Y^J89-_#F#8L%pNpLPn z;t_DlElACSfC<d52wtLWIARqpR$4BJt0OSh{OD9<I1NXTll<WjM9u)!Kr~Bgo~y zERggcp2bV(-^XS+h-XC9IHispD1pU`!GgJ~G8{(OXTQ@1Yzd~H^c10Qb?GiWO=B@c zVxL~h2{Bl|qp^Bhs_x<yX{En&pLG|wOg*<FIiKGrbt3-WSyk$lU1f;&Poyl4gVzBv zb4$uYB~`ztWF#5FgCwCY>H}L6a*&xmu5wgrtvRC=uDT>PoFbe338U8}YT}1+S`v!{ zng$R|&()hgKPv89-x8{-+R$Jk*wDY>065hw(n1xb`e8iC>M^DG`LF82gq@Z~o+22$ zO_k_oXv+u~H`?2Or{ei23MY7cY{vC!ej>*0*xbmoWwy*ANB@)ni*G>B;!!xi!(NFn zlP#?)r29bLzTFRbU}PubqoT%gfSiby4-`2|z4OHWhvH25rtke8o-OGn`pM3ckSBgZ zo(se?`P++OjA--X4J~1~+z$D0toz#_OJayEE~A)X%@Cvdq5DZK=hwEG6jga5*~3r0 zph47@ApYowc*2snUcCi^jTUF4arI7LXPi{XqThGK_sX0T*%)o0sJ}8fbS%^I@a>aC zs06@<i=7zAbQp-+B%qt>8D)`<Xq{O-7aX9AF#lOjuHg+Ia*oR88yeA*Ry?DGc6vlU zdY`<w<0t(c4}Ad;@2$t}5c=Bvq$9}|x#2RO>*qsf+|?*D>WtD30o#O`BfXCQBv|2_ zP{s$N{pjdPRZz=SG#ER2x85l3)PM{AGh67si-9l~`Y2fclz{E6f>2!%+XXR0dNJ^A z{oh4~To)Ho!1|_0720G!7z674SZy{U*QpZ3AsrZqeoE5=Gn;zTw`F2DvdA76ejkru zGGW#DfTNFKMvq{_%zzQPP&Et2#3MLdxRW>n$8gqRn+$ZhY)=qPmMYI@i1?7r%P~gt z1RNi*jhWNzyLHH~ORUx>x5o~{mc%@#2(fpu3FAnNo~{(1DYapvW=Jxx2^YvGv_KW% zj6UcADv&L3I}BMS+rs8(-_;5xh$^#x*b>pw&DbS$Y~eOX^Hv!W)rbCvcKuDh>`kgj z{rZD|ezJ@M03^cwie}o@hDEwso&9Kq(-ZPqs>g|>UT-I&87b^N0)+San=K2uPnKI{ z+b7UmlZOZT0iI?A^S+r>@t-DtJVbB=)C)kM>5edw;rOS^`5i_);SB`@!00jJzj%lY zA2P92G-WI3U~HO77I_+*VOt-JjU$+Z%18(Ezx%FXD0aL(_QWj9=#kUU9r9et1a^@j z^}27(+u~>oLuQ{KzCaRFtruy1^`HS}i@QTv^25w>g>CDjn=4K&k!9o=r3EU!nJK?& zCJgs4STuy`9i*#5l>aP*i)>mha`eCV*kRlK_{^995eeXd30H{To+^<MI=7_roGi8A z;jBUyi}aJ8&pkF{FLW$`w?`H-GdyRE7d%fu<uTj?JY3Djgj={7(z}-g^Z}9eqT+st z7u@*Uc!Xp<I;-CKb=L(GKXE-jv0J4kHjKO*%NQ4+m@m-mS&XBapU?}cC}k`0Y>WHC z12~p#eB03P-WxnOGiDUnJ;N`ZRw2>B4(^jU@-MS|w2}`x#W%uFxYA^?OrT5(;O6kC zUWT|TBZ9jj+@_@Mt$^Y%F{)j3_hm2bKB0XoPagc=U5ettun`Dv_X}*hLl)Z`jS}m{ z1@%D%UnYk?k$OjvRUZN4nLso?>Ks6(-_PNIuB_YjQ@rYs{AGe%s6ZDI*ag7vO^0%r z(p%Zs_Vo9kGZ_bW3?zl*`l&)Z{c{>5WC2yg9(=-M&cr_}L)K3y5I9}499OuGJjTW- zYKW_T^&eqcoUC_zT&iyCV0K~v)9*f|d$Cfz8Xw4i-kj~PPsnj*h&eF|RlXp<CP*+@ z!j!wj-&KTLdbdUgFTW-lw2lx)SA{*MJ}a&0(KSTd!mQ+GOw6}IwHJ;igAl}e++c2b zcTS|Rh1_9HN6;GwqF;2SoQ-D-73t%q8g5ii_|989%&qFaV4X|&^=B+o;?GOrdylKu z{E&wO(=b33fqCuTYPR-}PclX1Ko74V&b;?`{@$~<*Rug4x?|VnRdx+7`kKC!X!R56 z!VB(iK~|ZlJ%UM@hVxbt-oG9N;S;R}T?jieV7r6?#AR@)u#PGT8rjj#FYlGRn!3p& z9liq)H6ytml|mOjPXxFCEe3TQGFwq3q~FQ#X4z%j^UC0Vma`-p92Q7Y9oFdDpT++Q z@FR9^PNWjfaGvedOLMs5JAP=Bw>_;K-NE{#n)&#POJ!iU^4q}MZ3VQgCyMJZ=`Ds- z!%La(M@~;SIxNP9Jh^)$X6ICUEbKW{rVao?bAf0Q0MFv<AYeCK<EagW-b|2o+dVk7 z&$y<~xZ(N}rqCQ!<^WfUy$b=9Z@ey8icvTtvEwJxl=|=M6(kBJdy|Q>3};%Mz7U#& z@mUi8%?y-6N!-VnKP(|cLL17l4UPUx(`sSgfi4d}m)cAB-NH|HcfzBAm_YundtUhN z3<<8=sh-#EH>7>0kXpNB@hQB7ZJ*5Sf7l$UXG`l>3@zmRfe6c;tDjWP&Rrt3woo23 zL|$+)!;fCdQ=X3jL~5SM0%lh^<bSFdxLXLBAna!l6(Q8vUOx1mBQ57K?J9dj$qf)C z`rn-ufXpcQ_R%5lWguJ|S}Mr|C;`CcBt9S3VfKNkQ4g@|$#oS!={!CKc+Gg)N0}Wz z5ndd0xsdOmfGx*r8k0(MH$xVJnWDtg@lEcc{`DdaR3S+%F%layd}ZX-b1Z6kp|Yl* z<By?1#G`>QE?pv{<?)5f5A~Xe9!p}Fd!)Sm;r#0`L1Vc~K);;#q%TXDz0Z^Q2EIeg zse1LO(2AB6AMQR`WXe`9(ho6Kk1Oz#Fq6{m4tW7S_WZ=Pa93l3N22r?USxIYnyhT? z8IUh4PpV~U7#H;7ZSO@z;JMM?)<7?tD>QTEW!ZVQ1kx}{lnOARi<Sxd<`3rR>O;k; z_oSG><SW2n!1V)ZeoO9W<7D7fuAmDY-a?K*E%q-oIV6$m3aQZjNQ5{;WHsJ3!Fu7q zk74ZW=gBDz+F!vSFG`5}L52@yq76eYUEdQ-9@!LZ2VKYee#!J1K*rZ+wJxxgoH4q7 zaY6N>|4SSy?;=MixQn?ydG}H=LmlM_WFbJ$r?SKB<K}N^$aZ8-pYiAQw8{1?iER0Z za=2?(fa2aEC1)B|Z~TUz2I3mh`zpY=cm^7O+wA^wRZSeuS4-wcf7A=Qb;j=LmxMEq zUrU6%>dq_{HKAUUrA850YvoQK4f(7m39|FRSv}_e^eNGRXZIfb>T_iZ0Q`X&0{k#0 zY5NeY_gWmRHGO=ywjY2|JKd9|(>R!qHBH)w=r&o!Z;oA?_Ocr<E?2ZwFFsJnxM3Wr zXf@ySq!`oY(MEMmDQT-vbGvDs-<z%1X4{Byj*DI!g<-s(m^4qdVH(Hp_&h6lS`|9e z;^V^Q!7k^>Pq&A^d-~P;RvFRp+Eb&HBlaHjdl&!w{tK^CFwI)$s+gu_R+>ffrru)> z3u<M;cqZn_dv_K!O$(Cs%_RzC2cj6o4HjNT@05L6`>qtQ)<T!#i-q)`rbw*WmD%sf zPu2=$jfN%OG?yB_8q-W%=9J@}+^xHRd93|)SZ3t=ryu`ee|kB63-_r>(XJr%V}V;& z@X~7jN96Gr$+;_IBaI+3DP<pxvGk8D2>ub}<z&2(yn-|fN^oI=gfJZkq*Q693!kW% zZWM<sr%k6Ih}t|d8IiEphw9mIN0})(>QQqwOLiPh_FVcP$JL8F+#J4g6q&hrsb*2< z4k1vwR#~^(sEYS5$tu@oz9M_|a)(JPmxs(LdzGg4feJ6*$e?27*48O|B^Msy1fa3T z4OZ#!;>ip#>i=2Dv+AG|%1PV&7j9fV9gno)4)?(ovp+TF$Be(#D=-^ftuHjhCsx9- z1z2}ylTT(dD>uX*1|Ut|wR`59-(&ZU>y%>~osHfBE8ayucWgnKA^5cyqn@Gf!wo*L z+_^F9BQcIg$2h5>j&&Kai+YhW0pphqLx!A8Hg-i`Delp49c<oTd;z^>^q$2ef&V}O zK(X&>qO98=lul9ucWv*}1;n&jB!01A7De*KsJogWi`PrZkW2CggYg&+E9-dIHsr`_ zdZ?3W!Smcs+mBgbl=)s(XTON1Z2gMid;c*p=O;#PK^oPqC7y$J!p-)|PlR;&6uM?a z=q1TpyGPy5B|WLEw&BO;cn7kha@BxlAzfqtXc~JpQ#Tv3iBWd1;*!_+@hH8_o_fiE zn@g+j<qJ2!NanS#{%u;E62)=qhfuF7gU*h1>G1EZs+SCT`6~!B-eH#qH@i`K=2^ay zVBWp88h78DS89(I#QukIfAwgyYbEl{&J{z18AIOcz-?fQlM<1F%0@mrC!TwoBFMjK zNP7CaTOnc-TOLzq2oF6R4;4b+Bg;PQogO#*W;Bs+{%yuWNLcVMYYC;V?SqCKndM|1 z-?Hs0SbOm@yu^H{HP-Tk;v9Q|vDrNx=hGJ3n=Ko%s{8V!`HdUGwMI~}yWRX)rgpXu zC&ca_De1`uae#YIidg$_n%H46$+bxyP)8F5+;~udj{}L9RHYQVbv{JhLaR)w%+z<g zK5j}FLW~v-4QMu~l=1<vyR9>d1%$#Fqd~K8)#prmqM!jDjTd+41~omK3nQy6%!}Gi zs)$Gcws|y(^Hl-{^CzE7)ih%Jb!W}E#kHJ+TCJGJG>fLP=(?C4|AIZVps{DxP+<|D z$9G;j2tzZ4td7I}hxWngh!iFSD!~5akbpl=0+lS0vKX0_kVEfjJS$b^HNaZtDjkH@ zW?ISxdy_+XV9iyE)NJsOMbahP<JVHLNBz(Jp>Wf6SoadYYTtOg`37o=kaun~8aVjg zUGCmQ5q$;#yPRhzY5*hbgf=1iY&}Oo{}_!H?Q~V|PN;WTb4a~*`so7k6D+<q<y3U4 zmflj13rVAPr`^^B)+j{bvL(--!8nai%UoiDD<rlv%(<S>iM&2i6Jh**C<yhsW6&eG z)yBx6*d^B_kkmJsX{NZH?!GB-AblQ?VbssKtu3&Q-KA%Anp~20yrZqV=xq@Q`Ca^@ zJ3#ykH1qcUsR{3`N%QmQz{7{617qp1{}p*0n{Y2Q-V6g4E=Y*e53h%(SM@d$hD>io z2`VkrTQu$iA>y8ZZ)cZaKHUOl{hgD{Ua0I^Yo`7x>qSKZ8?KWmSU9txQak4?THXOy z-@4#n<|``JOr#$Ekf8rNo37<kZ>yi)@+$Q15zQ7nRbxyq%ZD{Bk1P8!7T*B75nC@Z zT5~?cQO0zb$C3QKpSHt+3?=n|+>GvIk=5da!ni9kA0Xm`w+0Gaw;Mbjw{94z0tc3c zyR2ltBBTY#hw8Kd+3f?#<v0K9EwC2*;=M~68u8eWwF{=08A7$p26cvfXC?z*q<t0q z;D-!%V7I1}vEUs*WDFoa9eT?eqsIjDVOYM>MybbNBrqTNt?CK<&M^2~kMd701hyW= zVL;sI(mqRq{c}}jw4iem#uu#h-Rw?Ou-@!VrbX)>hI#q3vs76AqGmelK>;?7K`jl} zT&R|SP<D%4z^weWJK<IaG7?W><!k&mEYuB*CNLL*YE8F53N%I#u)+Oh$L$I~BwOHW zgX?WWonV|VdojN!AN7K1jfTg%J$nwvz3c9`yjYw$NA-wYg3NqL=0nEs1xTA`^&0FD z3NG?7qjz7~AFTVFu1$)qv`PrCh`F3ATv7x+_Sw%F{qKqM0PzjkZB~XbhAAg#O9HC0 ztc@3=o?2K7;FMZPd}vzF6)TX;21&s<wo2GBBr|c~u7J*bQJzME_htPm(top~{FY|R zvTKs#boZ|kqe~WY`!3nTJ|d#AJloKpF^5QO5geB*-}&)OuIu-d9G8V|c)&2fdT4!4 zn67cKL|aR##-DPfn0~uEG%Hm}zqDt()f(=LY^U#_9G^LU`zCsIiQ1O3W9P8!u69Pf zQ-4*ww~20Kt91~up$%KDAX}D_s+D%8K<4U~5)pEP$Zk}w77L8!1id!e+G_z_Q^3ti zS{fJ~Z1WH3Xim0X%{3aeUA*?spHwq-KD`BSXi2bOf<>W#>>Bx8(QWP0Ya67id~^VS zi07X{3*Pk_e$BXVfh)`+r4&j4MFAFaKF{sEjy9sM(CRJm=qQ9gU|Ev-CvS{kbN998 zvw}Daq_0tmga`?wwLy{iaqQd7BSmF!%aVA#i|BJ8q^Y1%UhLMe6=n)umJphK|M;Ih zeFU;aNi<o(tk_D9E?;)j&sR}GV!-<;C-Y3~GNvW#@At~)&A6)7u^?>$gGI)f6PXc+ zyayM?RQx$-Id8`^2fZB>o<3#|QD9%uLrjevWYf_Rqpw84dmXN*T^j5h3Cb%{DRw;w zG4jLn0EihK1ZPU~j36nTPsQn>aCxJ9^DK@Te`TW)l?MR)Dh5FDm(J4>E3`|h{U=ws zNUn>3Fc-*b0SdD~b2K;AOi`a*!~zF7!V$>lK=koxUR*yuASf(OFr5iqq>5nY81nTh z;^|&>H@$oT$4#?TzfC1e30~>s>K${(1PG9<7_fT){y*-AI>tkQiUv`povAn_x1`8q z!5(WvcuEpU+iA0wFv&`I2p4jTCg$?v^kpNw&IROyW@qIF#H&g1#cfE~w1M`etNNE> zHkQzpA2pa$W;bZiQ5V!}JpURVX>}8|c36jd_z#bXsL)0zKSHhn4nkf`LV*zEyQQ=w zkMJLO#26LzEhs557Wa-T00f23_-ky@HRgLYpc~>v#km>X!Ye#A4?OU9v0StlbdG17 z5G$?3Ku`gxdm=!_1-Gy0e5|l=Tr=u_EVzO=SU#Tr!b!9fjX#OTpW=e*Hb9CH^CgCn zH#;>0Sc$$o|Aryd0!wmyL*dnb$&;0^LwV!9|HyW|qBV!M%A(88Kg7}{CC`0Vh}ON_ zNL4BWz@>Kzr3vSmG<ZlyQbe?#TxH1u*?fp#5Po=@V<FOq#Lc<{n0vVCT>~0TXa<ei zs4CDXF-eYx-(U*;W+6_o;JdVcmg&YK>+*v@vx<%b?9Ljpr%&d^Htc^q-^eH=&js;@ zWxQRK^OoSXSS-llMFZMQ+C>p}8?zZ?>0P@2Q7I8|QM@4&pa21Yc{W$@sMVqrxmf(6 zCGaXBm9>7@@&diaBbAm4rB{&O0EkO~G#_-KWtJyDt<Z-f)YK|}HAJ*Q2f58cO>z?D zAMn{|3+&;K3w@IR!UyZ1s@!A3>a>e>z@{!Ou*103E^UGHoiI;e^2GLKZ-%4nlH!A# z(DEsM?+0XOrHsqnB^pnX+L<t*Ve&0wBj_@v7*OsV62hY*!g#(-gc!Y>D3%pskAwu5 zmx28)7kSVd+K2@nGK?wNvVpMub)d}cKm-RGr>~&ypyOsID{r5|tpQL!Ik`J7s8yzH zN4as23*=(Ia1`cTT+=@bong%#h$X8!9NT7=XQNQ%5&aSV-9^XblKB=V^dkD2kV^qh zJK=#xLxiiGKo)A32e%9^^g@Hhi#&Chf=K{KmNw!mntHRdUaeZ#|0D8$Xhh8$b9n{9 zr|849zr&nMrB{yw+<8HzR>fyUFE<~uMV;`oXu&5PHTF{(4kESD33_%%#jRbSchKV6 zZPh9Im+x{R)FL>ON%qfZ-tN4T$q*dvuv=1Y+C{^A(uF@gzPjat>@K<S9q9TN4ZqPX zQ^=J3PvX|Z5?Y`^I8F3`UP~8v+#!Q}SPf*=AzM+~oWg5u6hOHkLO*|l?Y_C~zD<_q z(FN1FCli0QiWQq*V*&(S0LUT_7!3?aNtM$>RtE}bO9D|Y1xg&Xg(4(8U1nYa$>kx_ zY5ZsCO_q{ienO(NDumb|&s@2!@(aC6b$P*U{+Qu)Sdsid_3bv6lXxRqh8MWTrG?G4 zboP1s6&G(0*32oEez-5*z=TN&3f_LKG!c6I7E3pGzP0tg_GYqlYA-yE2k{;#ja)iU zn>DT2%fU=u{UG8yvX*_&hB`z#c1g@nRGpXpx9?RO?;eT*=`dh|ntW&O8=Cr-tGQR` zX@Q3V_iPVbw)oG*VnWU*8Gqy<i#JX#cig-B3%Q6#ou>f+fX0kO@S~Qx7Z%OGsZe3g z;o1ghL%^y3Ay$iWZp=&U>co6SqZaXqDH_U$#&0JL4qoHi+k;nA5%H_-g}>3@0n{71 zSM5g;U%cRM8xx`?7i<Ed(kM~Foo7WAE4grg4*xej%riq;WRl*0*2)bo-b+o&g`vkg zY02AzqEgrIhx?uPw}6nEawa6D!it#R$obWsSGVcLXZtSvwQKudkzg1XmAZ~AHITdw zQ$9H(b56VB8&m{fg&N?|3kbs0%eEmF4<rboO|$Md1^%UsB6&PWKlkJY?TN}4uO;dM zU&M6)5&(D*4=!4-kXx-PE&`Qa1FYmA=D3JW+KrcLO+~`OB7R0cSl#(yg-)bGeqNJH zlJ(udhu*(UJ{I9ST_Z2=`upXexJB{*h+Iz8QADU=!u=g^Z<QlUB+e|ux{CxXis0q= ztcwu2SJyDppJ25v63IpIdS<3tXaEb&KZL*7f2POfW$6|ZHAsUL@^ZqJn*6{jT!8dP zfa;Hsn6fBmslFJS)$G^kV~?rsEf6HYEJUqI1|c1XN<c=$bcwm*F{8Ny+NkfmHiOan zP@#sbWE@w!A-M8iJK>n?BFKOfLT_0S)4KykYLC8g;i^o)p*s<h41lo?Ai2dObriof zy3aHfghm7ZECF#e0h&JkaOUSHOK2D`#O8E|iGgRu!8%-_BpzgkDyt;?atflb$U?<; zco7c4F(tu$4q}0e90ZPlqaE#Hj&|OL4wNbOX6rPUAKD|2PBe`Z^y*$HD5g>=HsAF~ zd5P0fM@j(~^HgDihNCU)lUqSTK{UuT$t%gA8$^We(xjHSRWGz5R?v9eANjlsw|?`W ziD+a;k;|8ooJ=#uq6_Lf3l`kro0sZdSynN|qt}IE+h)}#bg?^r|F(#;A_*}c$wJ)# zCeY<Me}wRK9|Y!71=0oxQUM|?$Zveev9B5rYLL~P2OwE4(5Cry3>`7HBEL$v%l?Sk zp%*%#pS*Oqm&6&P(@+MIQs*2*V2Q74l&@=%JKh!{m$BYgvW|yv1+150_V=H@^uK5m z1w(#>xOYMyYM<IqHov6}>)=98b32?YTCe_kc0`Ti8$Kgje95dIo<M^{pYrK)2)O9y z5=<2m(I6gqBh?!hZu~4;?5OH(Hez_2|2+%pf<X>EBrbo^IEeuq>N4*DP#;eGo0D9> ztn;dqPwIQo!_lw4(KGNNI_e8Zu9_nKje7XBqZB=>8)t>TF;RgufJl*t<NMKT+J>E_ z!>vG+1^|cyT*6U7*I3v;kCB4k5nnsHo#zj_lR5<P+V}XmeB(6!Vb0l&>-S^+BH~^p zYLY>IqbPmjagF5(cC2z28lY`~+1%IMsex6J-dfG}rFCcQCYvV;JDt^r-eX=a%1<OW zz{&vvOwL<%r^Qlv*&qN^)5fmJtb6mCVCpuy;0gS=C1Q(iyn-J^ofNq~Q`QVdeZcb% z74@f8<P2Lo_xX9f3zL1mGC0f0{Q=Mj;ftpIih~emm$cz?Q;0armrc2%|M8(#>2S(l zWZB$Gcdvyb4FKvGh0+c`EZ-azc?J1l%|&Mk0+gi#Al!H*2<jW%4cs6rLN>4JLcBwx z{-w{#I~3wO1jhl8VX6?b@nGHCUSz-%wa<k6qIH>u9eXtAnso)2by!&u)E|Ai5wM*8 zRi$SOc8$t+1wR)~S!sCC*#>~!r%HH<OT0ox8&tr~H$bnu)L8xaXiFGuL_ptiB->%A z=?=)9Xy=YAF<Vi0dtb@^d3)pVsF_HEKclJaRr+`84xS^yc1dxYq?{kjir~fDRd3?X z9g>6e#yR<ORpB3Pqbe3y@a`hJ$h^VEaIA71Sb!;K7X%PMKYnHZ`X4vk$~1CsDSl%a z=)uVv@cf=M!Y)`^{f+;eM4vVKha3D=XaWG)!K3B?Cek$}_pTyWT~JS{k(%3r?|nK9 z#}uzOU%cz$U0!sc+^4xrOigOy!9oCnQ*>xMOUe0ut$1eNmCwo2A0fU(=ULyVub$rZ zuc6DI-hS{E?ggTt2&kASexlgmG1c`<|LP-QU!JdY<LO(|c;r0qK}pAITD;UxE38>R zau!|m&sg1;FxlTpkItEEmDqOevfQ7erSHPz?xn$}T^=D9SCUuZ7}DYS8W0h7_!;?g z7C-8IP#$bXT||E>MILI$_zha^x{k?lAh+NrQGa;wzZ?|!g&@uoeVO+8B^~lF5ovj^ z`Xe1>|F4%g6_}vkvIy9{(ja=5bl<%Q-i6;xtKD5J>1zPMt6h$GPM$iw{4?>^!NvQX z4FGf%^?(tDQ9DU@YqaL4&T*D3vV@N~HF-}i59Bo4H-9d(%Tx5O^(dCNgRLBfd!4)+ zm>A^)pzS7<Gs+Nk&j1^zPh$;{i_&2{f9aUjm(^ypbx_T_w_WnjqBb90dD@is&hSdv z>|S(iyKi@_(?CI-6u@_)hPQrJ&HCPAciiUe9fdP*G!GF{rqnILyYCG`x{{Vehw^2g zJws2hSK@Q$o<%P+UpV-@{q7XAzH?HZL}DFo%0iM^jT7&ly^MQVe)&zoG=v|`cQ`X{ z_2ESP$EudPECZHNwDIJp>Hi|@>W(?p;01w)GSy?_Kh>}QL@qw==y`YsIaGK9s})Tt zg4{dEy<ymw_1H$S&86|ScL8&CzRCWzirY=6JLlSpnp9n>r}~AxNvDVaS7iUN;{QC{ zvIwr0!W;Q^LZQ6gmc^I>38DZasLaE*mu4v<MQO(c1^>2gi(%eZzZddd`%c|iCF2a~ zgr0h}+D-c!NL`z`t3chQ9i2ghx9awq+WXiaQP1mWKSrb<wYLpnyXTEJN8nfHZ{y;Z zCz~pLd&#PF4J{dE*^4xG`fxP5G4F(l`_$Lkh#k9tt_jLfI^BNt*Ltnqm%LWlnAL06 z3?$x`If+arxYb10U?&Z^oXJ?1m5NgW=wmf=D==jk5ig)zH)2zG^$}a32C%MMHh$38 z{b}8lXPd=_Yi)8rUf($s@?r8V69<YlH%?e#gfFBIA9r)J3o6yr10DgK#3mIT6Oam> zJ(aZyKJ<dB8n5ALpOOnjkb)!4rRZmlmwa;*!f(oE^iE!AIT3DuVO-+Nlk|H@S-SRh zV^gnp7UO&BL!}3IT&-bFN+VWswBfh;i~XKzHX4uC6Hj;+sF{Y>CjHdCQyDBE+U4>r zVRgItQUZJ6snLnq#I{R||3}eXM>W~LaR6Vj(H*14Mt8?Z7j#JqN~bg<L_qKzFgCgb z845_3h?EGZyc>;x0wN+J4nzb+MFhoq`R(`r&Utpu^W4vKpX>f!pNqajUgYOx5Wz-` zmbLK*ESI~+&V7R-{7AcXSrFtd2I$|NVHJ*lZ$Dgfd2o}AFvY!=8FJy^Jr=zP7_vgd zWqP$v)wte17H6_|K$6@;O&-%zsz%f~lv9iixXA0A&4E{uo#78*blDvqAM(JR-_qd$ zFClsM5pi<mF6!@NUnd1r$@wmR9PqHaRZwpu;oxJ>C6RvUWO>VHcy!T#pr;3`jS3tJ z7E9^pv$~}LZEq?g`17b=>Je_~g-0HQ!z9b<V?P8Zx14W6*j~`rsa_7&f3F#qQ~Ex& z1+enpjPaX#OCX4IR{#Kts*{&U9IQRwzEnP@@SK<d2?jIK4VuU=jFn+xlIfj!Fz=I+ zqPFk6S#W9u&(oYIGCTFf1lqgw-1Z9nlX{K=RTMD&+SuJp3+b?2X`#Al3z1*`ye=fi zi?XFF^8UbVTL^={(`n(9Ri$ib-aSyL9eMp-foJ8VlyRSfz;yvGxxU2lV0pa^=H(h{ z^rG<y=xv0d?m*9ZREOl7<W=|XOtNm2wA0p!CHM}ttfk#TY=T$R5OjI!+MJvu$jf}z z`#YDePiW{qgRB(;Eq*`5Q^J)erN@Z`0@7M^pxqfJCsqb{twPD2Fp3_n4#0xM06fN^ z`XhAB8nu0m?<G){r%3}lCRXlOPGB12i`+JjE^?H`NrMBvLcy~4JZg{?DHf4CqN5=0 zie!r%lO7#J3rIN28vovVF_%;j=sC)X*-_OZ+YfHt+>~u~)h*BErsIU#BHv&8e6NVw z#LEAMIQ6sow2B(L{1!ee!}*B&+k@zJob>@_%HWR{tJ1!-(<XE9mahBLyz0jCsCG-! ztqjv)|7B^)SIcw#gu<|byDsl!nhkT}`jR>Y%cUJ0<ajVZ5C8-EM;jxcIoX&fX{mlA zH|sf6lh|H^k$Qi!^<<^Lh(KyYe5<QV)NiY1Ynx~LIX#8=&c_|q4_45fm<|}ha;GD| z@%XN~CtnQ_I3~0Uw!kOUFq?yA*nCRYs)Y#Spo>+>yt;|7CCR41CL0d&$(H+Qp<9-B z!CFfMshs;z>~_tS3A}tVBhcu-^ObYKlhzjP8+n<j)Hd|Kz%$0=CCEy)Ee%A{k-P2m z@@vm&iglJ~3@XH0<JHaLuUP&^447of#j1&iV3CK(Fr)F!S8rC1Bux8c7XeQFPfD;- zJ9TPzR!fVRF+<+AM7O9VVj;kPCc|-pt6`*`D;oJ$R5%R^)obgx2+2Ym@WPZDRZ7R| zf+RLd$E4f_A%^`<Q3p9HHI7>BXZKr!$Cl12hdQ%qg{k8@c=yrSRdvxx83L_%)}Yhh zyk+Im7rGecVi@T=%C)Q7oC%V$Yl~->V<@-uhMm!3QHp?JaB>eV+kJ#@A;KD4RLco7 zSvc_;r;UjnDNgE|+$h?gp`y&<V5<EzO6t*%!3rBS^^OE*H9z^QXJjs1JhTE@3ZA}a zcBvJHYRBoZxH$mbXwapHi*7ab*}<O{tj?5_7PH$<8P3yV&64?wp9lXO2U^0+2=^cy zs+&CjFklB}cG9y;92bPh-eT<AY|d^m-SXs(0ci+_O(Okfon3-Oa&myC6G&LQGwP0t z&U858y7(c1(vq1XqQ4hZ2eV_xckgy4m1K#O_^aVjY-EF|EtMW4{qu{!-hl#p^@W=L zvy*gfT~D@iujTV&1_O33`?uSSjBvP)33Ce#zJwOkSw5YlmrK21yY)#E${8pFU`qr* z)Bl?^Op`cBku<Oyduf#zQzhXhN4cF?M?sH%_*dZRyVU(|tISHK8b4A&KRrrf=W*}J z6*B^1Tk0YyY+mDhF?Oh08br=>k*&JV`}r3e3%NQ5-nY_xHz<SMq$4ipY#3Nl?H5-p zGt+(*2NpJnhlyqUI+K(ZB!(-Sy0nHWR+LrgFdJ}7ylM96!_46`X;V(an1<Z2U1^@L z({t-J+T7;!-;xQwsSjFz7ZFM_K>A3G5VIuxI!$ET`$C~%o-PYOktye4nq|73iw<me z;)6yim-l*#|LOh|CE@m0r?#gcrN3A5YuoYl$$&jbpZl{pQsm}&9KYz!=x$%A!uhk< z+;Dgn|L@Z7FOP)o1ZAK^>blR~t$D+bIy=VuZ~=->dDcWgb|8k3r*}*y_f>DD;YDxX zd3*nz7OR}S?mPng!(<!FZG%r)2MMxQ#m8|O(BSbh`Ek$qrQ@#E4vkQ?D8i+bzk5v7 zl4~QtfZq_7fPpCw-e?>avs@6v=rj!NN+ljp(mly(j5@CPM*?%OqHlv&+D(TvInt~( z^%z7sPmo`@e2yzEmr?J?%e!h+Bk}8wYY8Osfa2w8hA_`5WR9_^FaE%BPfnse4g-ru zLi}(#d+~$R)oimtzWO?hI@^ODS7-{WN-`_Oftq1<!mhETz1PnF5vZgFMyhk%3Zuc^ z-G-gfu8RAp;EjYzFP14q8R&+WGWXSCcICF302Vj^c<Kaz?_#3;Z+&}KJH%U;s;GOB z@Q7<mxoeG5#BsZ)13v_B`l6{>{u^vTK>h25`>~qi#vrK^M7TKs%`&$=k|B|-?7mL8 z_jWxl#A2rUl$$q-Q&k!Fr$h~sJQ=M9ZheKhx!zPJhD{OL>(Vm67E2^QALdRhp~Mhb zP`jDU(v;^^-K3L&^(`5*G>d}38;NL+>!O_Lp5QPHeAfR4I9NT|lOkeo*^^Ud2dR8B zLlVKr0f_)W9q6Bu;eT?=Y^3F*X_PCT*cZQH=>*ti#pzR{g4<)TR87N?(yRb<u?W9) z4zFeSSJo11qjLf+9-gE`3|Q)b;umH1=JZPO3AK18SF0k8was(NZV(c)dv^#<OYOsm z_3%Z|M6`}dkFub?n)sNLftZqPGeXvV%v9nZjn}(~qC-U^`@Ssx+wNgiF$7BdG&r(E zlK%p%^-6m!UvpjJgWJz2C^TUHtsM&!B#~~_9jc5ip)fyZT{!X;A}kti(EMlGSsS*l zqse=ac_s&XHB2$tjppg5U_}MZXY|~R?5sM18YlvkXg2=dM%PV*XZYqHRI?@lYVArO zH);Hz!Vu=7ce2h4q*mShcmnaACd+V4#V{aNCm>!Ib~R&4d<i9TL2ZLy<@&eW1mrb3 zFYFO3#?ywgF5U=2f+gq73!HuwO=rTXe>mL^vnkak@fQm9_@4IWQ!W!6)sF4~H~{H` zWQSMcvjxz94#=^qb00s>)vjkd5a(x==k+uzmgj8VU+Fy2ya$nFQ!1EO{zJASLR@}f z^s@3=Ao!N#UL!tbY%WVs8`Nk^L2sMH%#aqKZtd7th5AEPWXk^-YpLJN4zpJ3=7rlb z#zev?5y|c1k+5jlv+;RSmP7yxfXKYnLI*5Sngz2s4s2t7TcWY$sJPFnE;k?}B#->+ zpiz?3maVXQ@1_DzqY_k4XxYu-Z_a|Zb(T7V1uUv6r&k&hW!acW(QzoKRfI2nP=H1m zBXu|^Hj6UP9HUP?5ypV5tJ-$A2FYTVI0%5cH64R}*@9R_C0$MEw+H!^XjqD(3l+3% zzV3R1|KFfG0DB2DWB?GNK@%}t{Lu>bDC_q!@)|xWyvf8fnmlQW7U!aQoE2Go(Gm~X z0j53+761w~`x&g6<iR@}pu{r0mj%iYKIdbZxa#!p;L~L|<;|v+#Aa7nK!F#7#ecAf zgOegVLrOH}Fqcy~FA5X8x0p(ER%3G;4uU;MfSKrCt1Ri&^R&|bh!_s0N`$xv<Qb$; zGta*^0S{)_)5!mUJTZsUqd~CCXzi<Ts4o!6KRD-@kIk8HiQ5BN4KmeM*4XD0VKwI> zDqOFhg3X-kP?d!&9`NcqW?1(bxnU0KeveZ%zRbJ_DrcBS0*ZWN1H`T_M6{ia1MvH; zLZr(0VoS7&(j4ugp&O~IYinn20Vt`moM)C^WN2|cV5lcyO0AL$DzaABZgi#kL)?s% zS)4NL7bq)_-5=;l_m#n}dft}H0XpdLeChM5Y(!;hvK9g!r{1s$&vr#01CjIRU2=G9 zKY^)|xN~=K@kEIA0XZJ&)nmPuu<%0cD~kk>qBg->1*|=r4DlttNZKU_dDdPbQD4?r zmphZMbUUXFVxDt(E)VBsRxH+*Q1pm!`fIjZRB|va`wG36A-TRxS4by7*fjyxr)e&) zrpdpyeFL;rl5@ysoWMTLS;C{RSOB`nXLRZgYT<7+p~1VVVC5O<nT97=cNJQ_45=yC zs>wD~oc8mMdKSFSZ@HCiw*bZbE&ODWdoe#Zgd?xjq4IVl^(-0^G*~nNfcYKxc>d1g zkoRsQKC!ESB_f^T%dAqPM9=zcL=(Wxo&mWFxe1C?d~(4*>GntWq)n<;j}if(I${CK z&3{w^G3*ag(d*+rAU&ErA#Cnf4X)DFzlx)DOJ?5UfDH8kBNd5W2e3#gIh;s#tTSNT zyiQe7D0Es135NMHvakG7|HLR&Pqe-42}Ahuxcnk}(tJ_|ZIf6j;mqehrG%n^tX*NT zOPAXS+*Kr4+rnk#E?duPqx7NRMK4d%tM2>{k9=bXMd~xRl9bErF>;C(fP!P#7}fWj zu;e%f7J0HH$G91wR|tF^_&Zyk1?r=D)l3Tk)3tVRPy~pb<mydlSuH>$ZFOqiov(6b zsp48ws-BOngZPH2;oO>Tzg1tG$u`?{sIsZNgqGqG+Fa><5IenwS)_QC@a6tddryMd zg^*K-Ooe&-Lt?MvyIX?|H73(m#S=1uY=JpiD_*s-gc6wTU<R0I4h9f)7hvD+HRfEE z>RW>T<NxMN4lv+v2+*OaLT<;KnyFE{&Jo?}Qw>cgQmjt>VSI{!Fe2Gv0pgGx<oE3S z{AM-NGL*RSGPo0$$ZWA!bmUmk66*o4I^YK(4_+>lU%g|Yr8g6ZP^*<n6J%}LNT(E; zEOt-3*?MDgZ4tpm=@RI!Jjjin&WfQH^q@lm+qeV%+a0D0q*F7`*bpI}TZX*l98s^a zJCXcaDzOaM_hS%mH}MR5X0G7cqjQ++g+pGNA0o&r;Ri7MN#>B{d}=buDQD&le}oM+ z)7z;NikOe_wTww7wOICzTjrKMW<hJ_U5%i~_q^lF?QNHX1eFX!521e6{Ac+oF}%^^ zBcF!Dhp#5(4-W1pMGPm%2#hXlk*7J%A>Z|!hUU6dP%00R|NSzW(BER(yozX|{hE>` zdTg%b^?_q-k(LT2&`%Ells(D1;uN6U^Vz@PdS(7lL}s{jImEYwgxlSV))Y!Uv2bIo zv(98=d9$7vvO=-Z_16TFi4Z(%2rxF6xW<BJA_RNG%~XSn0Wa{3>{Lx-%OprN2Py>( z{oEN_u;kGfO8yWIBPO2xE54ek_pkeZTqNO-*-30<IdVsI9rwVOA5~q^Z6KBsz(NV} zf@JxXiuf9od?Ev8;gsd;n|W><7EROsJio6?fc#$F*<B)8B|~iMn12ttehhnO%-CJK z9@XJ`8JL|#koZH4_WK4z(%_Fzsrhp!P<J9}MJ%p>)<BwxMi25eX~LwhKYpV~i8+Db zouD5FwYIxRShScbP|7BmL-On!z`~R6OZl-*A5%d{jSpwUN4Tl&8+wG^S1WAE7`{MS zR%93#&+*~%3};F=`H3|V1TRF@k+D@q!EdT`zvc#LcEi!<9s6LP5$mT;EX=^QW*da% zFLRt93(1q@aRB?00;y}cKea>}Ipmej6y`2gM=oT%sw)WTgjpw(ZWBM}CF{3ONSaYU zD2&AZAJ&JL8QJ3RlEG>IWz=LykNihl^^I`!Mz7n{yH8NW-);Yf8Y|?x&rx}<>ZB9~ z^dtIv#9eXoQkdUq9TCiXBY%QSSZJf(Pdc`Sr7=QAoFQ||_BKBrMTtd3EcyK>)c&{R z8;$_R*O8Jdwaye@FWLo_z*#sh`TK!EQcg#A1z`GUQWTXl^HvV0u%gv!cB7&@L%y_@ z$R2`>`ETp4ixlbWBA1i<Ztr~l-pHAX744LQSCI?Zba*puFZWi7?*||D6b4J6A|z0; z=t{=V+SW?r42r!Iut5m`+-?6YLy?_N`_f^Qwn{030`*v-R|olZd=kPkS?rJ>F5x1i zC0J}rARX^_mPdxB;#nHAaPs`BZ}5p0Puc#eG6nCxKHDqzo)+={n;1c(91q9FQ=zJ) zo8m#+woLy*-tKNN9vm{r-@C*m7ES)JseWOqtuGOFAuKXw_wdawqO07e;!ABXnv}9D zN+eRce2AG)9%=hF0&0xRErlykjFX<o6IL0yJ+(`O06-FOWMi?!P@>4$2K)ASx!LPH zFMIG5?pwMRzU-bS0tHeg@$XjdBq${+E@m}ZxAU{)m5Dp{>9Qc*6F)3C!_GR-KW2_* zYGl@5U07iDT@I~-NfjNJqV14oM;YQG#McJ+*g-mnW=!>5!`@PrP9=Bsh&Q3gnPcjS z?5q6U)k4>#oJvg6!NZ>&5UW~r=6m+kXZJ0u9!|FK)v73bxu6sN{R10!YO4Nt+`*IM z)5nEpC5*_VZ;2fWKeqgmj?4K}%<bP8R6PpE7puRPo4fo4E=oZ90{}v+omsz4(oKFI zvIay5Or2en(nFT~c{!y~ZBO0#;$<Qxyi%uI<vp}yqhuAA?HAOF3`0g+i8k3PK1>8o zsomy<6Ww7#ZFS)o+C2|bGNZm&e|P`6XV`;-O%A=!-3dj>(9z&3{Yv;~zR5gYfLpiX zh_A@xeTi!z;9soFQ-WB>cA)8kZbGraS8Ah3S<B0vC#s7_TW?F*UWU$#-H$$B8vRVx z)mrb1?vM5I$X-J?|HDK)5V!^;(72X~KLT%FIo#t-{m}EC#1f&XeM|rQ@leav_EVa) zjmS{glDm?(7PYPU3PLW=r908t2GEeEm#17_R<_x!{*xBq4Xo>PFnv=lBj;5wx|6Th z%))3O??V7Q#w83Omp;hnx~PQNFSjS9Z<iBhWkze*`GOC+ch-vEY6^d{eO7eMOXH;c z+q^eNVdGha6xyXy@AsXSbExr$YYhY6EMFBFZu-l-2Y>(o8t>+|&0QM%e?uGmTB`Nd zx`fiKUD{i<$9^IsPG#&$;Ev<&NsjAcm`2y_CAPL}MX8&UN{{X-8=2N$`*h*Wa#lm$ zS3$v@aGbWeh+K%`*g9s@zVW>AW_i{VgG?>`B9nzWjwdrvt=V9muQUOkyJt_&LIeyC z2Jtq!i=;-+0`^ZVPsLVfL4D>y!&eF~ZFv{oTYvlVcCiM8w*&+Fd!hcR{+EKr_v=|_ zj|)wH{K+r}l6=Q_j0jT>Cl~mPZ`i1Hd3(2S-@KJ5nAzSmYC}SK6==Oz+O#iE*oBa} z(T6k;<xWazWh(X`AoLk3?BK8neIWQ?2DwQK;=bE{c?gOwiGJv4)Zre<V}cn<GqT4h zaqyrY`48RvS}N0|tDC+1w$S2O&4yEb_L0oV-WP%6C;Go=SRxQ~@G%y>1NdzA=k#~3 z`WqTWJ#!PmyBi#!n*ax7_qKU+g4hMes`tdg=-J3=p?m)0f?++mO<|{>GvA%}F&uU0 zaa_d;F9TdZMSZWlv|z#S$yCP&zjA&06vltZ>J=L$LR{FU!w1*kedUWy(X=e2aDlV^ z;LbhOnX&K)o#|Lzpjv)481XFZmGN4=IbY_Y^va@@6er=#RY`x=V^&Z2E7ohVoCNqk zb$DP&UCvb}u+(QN$H`hU-`||fGyF{?6%bL&_2<`rTEi@qV}KN^Xq+p`UN+j=8XiQW z^NsL28YSvUN`WTxNtiL+?hKK}pMe4ut0)_5^RCdL`ZS)b+~@`vPaGiI*Q|imNqDU2 z)1@yGZ*DgDGB)L8a+L^&n4(`tixV0y+BeurrT%ha0KolEfK%lIi`rj`4o@CAOPs*T z(t*5SJ<cqt2LZ7Bhd<{jCYqT75)&wg?@#Dz5dz)3U>O1*(W!i^wjz;xE~(VUPqx%y zr&~mB&0i*_zfr;XLI^t9RhL}ww(@aMEv<aK=?XyxAty+UM%(gHn;In#r&+F#0@Y7Z z5Q+IzlIld0h5Cq0?t-AA+#T0qv(;DtSo19~jj#AJ72IM{A)dNTFUGXdtJ$By7U6?# z$z`C#%xZ>5ml4_}LtP|>N|m?ValiAY`I6>Xuv8H<d3n86a&JLWtURN#Av#N}qHfo4 zJ*6a$m(1T}E%L|(e<xIT4B;%BJFv}vFPiEm{a*1@>H0|XBTp;@;fJ~T%rR9Wka$ii z-7r%3&1PY$+vruqrla$nEbivAr0bs-qzy|ofjB*|RF<emlz4-bJI0Cgx{9Rq6+4Zt zG?v6FVy3))DZ8^<MA@Xf4I2kL#U?7g@?9>UNk2AMG;dcN?>gywdDY{*-njlN&n&;+ z+lwpPi4xoJ=zi)%zE#t_^Z<QIW<+@4Qk&AFd0eFdqoX8YIVgXeI>~H>e6=^q<M4}M z?v!ohCN5~B$-6;Ke>}k%{09hOae`<!)xX;4zkk16=Jtg4KtM+Ngiud%@OiiTJQ0Cr ziTY9t`9f!&SaUX;lAbxmij2Zo&ld3qZ6xl~u}$f-M&o#LcSFXDW%Cu;>lHH*QJHeU zqCcT(jRy<a>KLGUT=O8(T-&80^7`!%ro0ZC5h}9Ckxw}pg+c%{06!A&@ZG32w(HwN z{|42xBOG5Ml_*K6FHSDN>yy-{^C(w(wj9M=&xZ)g)oFS=5vAR}&m~%P=D$uQj?IJ@ z6@@G~=V&kR79H$DRpsd~645{DPC--pBi#@6BNZd8=Ij>pgc;^DiDGvF8y(UOdb6sT zSH@@C+-F)Wbki&!tehi!NxL86a;6Yz)|&zRbx#BAL=z!|OATtU2y8I2M4efHMql}O z2zB_SYenyou5o!b&CRc)ZDSOY7Ef8sI7RAM=>0UF-r+{kJBXeHQZZdC>`&(t?PMBG zk3r{(%V`v^?!IIyn7}t`otd^{SN?6hM{HbqAmG=Cp#L#F-(s0_l_i|dc*dS1?Wk#u z<LA8cMxJlBHxKz%Hstr!CBjKf(0Zte3_z9_V(Dr1{;U*_?MG~}KLFb?uXqbRt@X_a z9DkeiaCHTCm0ffU$lgs*Hw8!3JKwKyf6^W^w_j)D7Wr3Ko3G&ZtP@uXNyVz;;jvAW z3`;-DNYYeznf_o>)C~c$NQ&o%1%vMAWBzvbLS?=|n&ivuqa|(jbCWukZ~Pcy`zBd6 zNC$Eg|22}NLA%>GJ_@<b2A(S7;u0|sodZ5%eAC-~^ncNf!~TXIfbz{pmE1^!QVtok zwD5wJg~u1OznPxBnpGyysI}I}U3j6yG16QVA}xR}tZopwpJN}}105a6y-vAz&adK) z0&OL0=aVzTu-KT%r5%l`67%)9UCenWm9~K$SaS`!=rhA>BI&obAA$`?cwTC$)7L7X zZid<1dFTeEo^G#$90Ri8HL0G))p&5|n)9mXw@*ynbkxJTl1<-|ylbV9Q}HdsQHhHC zVe{shsrQ_Oo9Q5aIbA%O6>4GvLImR%*PRShH@JI>YyqXRj5jyzSIUqp#tbm$o(o_a z%!KmphSjXp;ZIGiM>T`l%z{f7O7lbO=YRH$8LbOy!SNr55Io%W5uPypb->2a?5Ec> zT~Dy_+$|&y#=ZoRUf|=0jF~d<#x$qH46pGhkRVfm#Y!iZ*cJ@o<S<xux6!t=Y`(46 z&zdU?%_Y1_{Qz^%0}p&t=7eRpu{R3v(}nBu`wKF@=6)$-Vo2xhd2&F&%g7Qu;6&=y zG>eHKNIT-G0F?L$?(lyZ5g=J+A@gz>3=ym8Pdld*z)*Z#Xjp<rM}bAlUja|ff66B5 zC^Z@llhEb(hZgRf!E{Z=m_d1s$|Y%+0+8Z1P6Ulp+h!2Wv-3CKx|OiU$Jt8JMwJ0> zrz&f&`Sc~;h%UGPz2W_br9d;kk6~e)<AJ8(QnK;3uY+*Y<vTunbeg$vdby!JkIi{Y zR2?wbVgt9CC0kOpWL^3M$dIuIYnwv)6yaITLFTpgmVA?zR6hOVS)g0Sn`t4prAe;W z;MGU4ubWwh<vu0-US{t`1&`=zy0RX<EbTcU-r)?mJ+Go*fQtIMN=!}B9=O<fz4#H{ zup0b%J1`M_4uAuh<cK)tRo@9m)%1*`NtUSfQTr{*O3s)`KRGZvi?cS5sx~SjXmb(x zs$T*rmE4HVnKde?6}|(!+5F-r3Z{;h`!x7&W?N8H0+SsL1C(T(S;iZCZ=6PRvwSbd zn_A;FkvL94fHZPUrXb|}NE1el9hdZ2rC%=2g(d!xkLppzdU}a6;g;o22=s;+E}IgV z2K`)J7kz+3Rm(bdGzEP=>r(S(jdMmsR;COt5c!aNQ*XubDlpvX)uP&XAB$WS@GRTQ zdM2QbAmI#KJfyTe9rfChE<8pvnlv;)qRY8fVH7^=QRyhWvAqIWAM%|DHq!-512PR! zc+CZ{nF+T|^{#QqW9%qS>VU3hK7s#?%xfXF><S3lkE#vgl>D>V_(T0UbH@vB5qM>; z4rZAtW}ygK_SIQv(wMJ1&b0is8}FoA8a8}A%q~pPs2t4X=uUNmtLEnOqiOgs;oP51 zaQo!aN1b@%U7W$yx7i!@dUZgm-1u>SR@_`@_9!@%Z4Wt`bw(2eaFhF&6R?q(RTmJ{ zxWj3jTpA&*AdSWX0T~6*ivgcsO%StH&>+G6%!GTMB@xQzC3#nwNU_BFKZ&FN#x>FS z<iiBX;(vVXE}Xx60FteCvF(zzs2D5ng#@T(%BR&Q(nzWUc)e~*lLEQMmCBIqj4(^* zo6WvP$+b=&GG}MDW=s`TJa@21E&y40m=@f8(WCPThrx0dMGRoIpAV=L*E26QtPXGd zzGO7GZt@2tO~h~_aXOuR=mDSj{|mMma)Zj9OCL|o6_tobK-of2Vnv?ssPq+nasYFw zh&}CY$kJZt{Wy2w&nMo_FcoJ-E-_3N<T}hS2Y)m4Wqoi*MtQkxb>Vl61K`tU)N#9k z@{YHKZ)F;NxcBywTu0>m#|cZjFwIe}60d)E=YepH=`Nn&^2w(EHaZHg1<B$Nq#fvG zUHW5=R+s8%!QFAB%hE;@&PT2OI(IHN(@Yd7Gl)}`9q%d=3#e@+OxxXDUx=Q*ct=TP zF4Us34r|G>Z?PO)=^gns#{+3AbGNNtZ?&_}FwmHWs`?txw|L7;a8xBNrv5O%HOBud zr^3eJjP(VWo;BuEz%zg~KrsrZU_P@Q*mfE>nWc*y%g+R8BSBi$JcmPSYatc#aOn9& zT>gyuxzar5J672{lTOE~7vS*hT{H_H<7#0I?-%Oj5}e#E?Hf~QMZ4AH@R{bU0k#S1 zFfht`>LTW;o_E&K+;arWF1jtC#)b4~mBS!a#@126go!EJpTi?Nez~;~CS#62=jJbW zu~SPS`zjl4fZB)P;0uJjF1+78B{_Wn|DRC}#+dO@XI#c}McuqsAMRI$1am4#Im}7Q zGXvHRVq8__v8*v%&eAx*N=5OfqgT^yt*-4@_kQMWt%dT2XP)U?4~MVC;lMfzSq8z< zPP$*ptv>_q#+WmLow&2qk<`;5JzoIS>SAu=#~nA8H<~y74~(6_FA$jLn`b|<09o<p zB^AtDnLz?o1=e7?hIKKTu(d)DQQo}<M~|vtZoOtZ#4Y$E>6v_PAjP&(m1+yxSH?$s zyi|XMS>l+%K8xh<sM%gwPAx6F{Y|tWZepHXf5%em=!;rmmT_`u!zvl@9y<?3+$GE} zeuk=NYYiRQB6J((J2|R1K_A~O%iVe`=?WHg!wL}~HHolVX6D+f4?DiKvOcE4l%&1s zqdS5!8sEtDcP%ua1Y>lX6nm`Bu8@P3KxZrOb|_w~Gn{7b=s`(~^=8__x27)&lktGn zi>h}?OZHiU%T1?@NA=o*U{g*=-lt9Dw^o|2qtd(yE8Y09aqv*DonKFUIXwU}8h3KE zS+%{4E9`6T=Ki<~CVbX{aXjbq$D68#Ify`@MPtU+V;ab;9N?&iCSGLd+eef~hY?6N z;BMP%wdaTl=R}Z(CmmjH;mON7tzVrFAqyMgyk=s%7QV2y?`b5B`O0YpJv^{2XcuIK z9W)>!p+x;osLs({v;X4BJK3`E(W{oEd`7%(-OjBim*zFQ`7yOvct;#_Nj|vl6gdke z<EsgzPh3Q>IbF~ms4IB3_Ci8y@0c+!SUU<Ui5k<G%Q8JFk{|H#RPay^#<ixEO!*#9 zWV)X!=Ttz#ab*{JksG{N87;}R{zXnMMK=&`Xzaq>Y=aX#Lf0WkGha&(uVY^R8~Xh; zE(TRHkZ7l0QpfbzGczBL4Yfc51VI^+HV;NVX4<HQ`hB~Z2zHjF@kPP@6{E>^zH(jB zx=XA!g&ztb4>i{Dj*`mJ#_<<+VREwDNE%KdIny1#&8iYEvq(*7$DO-)@)1ZjDL<6m z#{C31Ho&>6_ba@@+Y~nSEHr0D4sfEgotq0|NnoFgsr_GGPXbh$&HHogt-%q{_XgDQ z#85Zzm9gLn15TTS?7aMRtJy!~LM~=&$U04sQ4A(T%he^zydkLHIWbHCvZCpy8oXJT zkO(R4rPn|E#+~MFlhI}}EWGNYf+l`Hj*}j2%El}77*j)TtvjLHmgKXo3Jf+v6nW}* zR^uXmEPHa9|3<v$P7o|jWP6TRR}A~A`O*B(q}s#h*Y{D`wram!hAMhopP%4G+-ks{ zaO#yY<NZDK#YNpeqmoD<D*z{>dZK1{auo7-V>GjL61P|Wp7lyL_k+>P=WyBgS4}V8 z=vpNk9OQUq;}cbk+y^h^i`$e${hm>q5jm=8sN_A0x*vFKS$w}&QzZAv*F2y;MRzw7 z)F2yM4|#TDk5IRIad9W4b(n^9H^tBa5`fOPPmxYSkuJkYBVLAW`r7NjQ`TjG_G;!U z01r=Sp0a<YOfy}Lgmdvskbmm)W(zlw?DzQW8=S&rfx`*gH&eJX1{!03qNbN+>gYZ^ z*)4dymNj@_<<E_RubQvW5aWhTOqRq7*vwx2(tE6mbr=>&&74VOgQoTSAB1DEBeq0{ zAb@KQ!waW#Jv8o!RJKP~Wt`&Lq(?Pm#~Rs^p{bb)ij_H|qd&;^SgbDnAL547kr-QI z)5HE3Rrz60@4*xv6b9b}Om^Op{gsKo5tj4pO8s8PxcIx?$nELNc0rabfD#cMAGmA( zUY4=_kZtm`8mDrs#kVMz1Vi2L&)-naMw_y*(s&iIAl3>|Ecn!$n%=l|XsU}7ZcC8q zymP;2%sO2vXX;KsBAqL=mF3EWlJ}@uQwF?E`c0%Qnb)jH&8<@Yem>{amP+~7{GTC} zf4@8*6KVTw*GlS@m`a+$o9Nc7V<&Z;GPMD<B~uVX0Ldg|xM6clq{s)5%^|9vxJ&SU zr15OK(5{Uj@i2Tm$KlEkZr=w<dx-10Df}U}6)NWk5`XfC+E?j>kLV~o6=}3j8ip$& zk@O7k@<FbSl|Z;lvt8A&$>lCd-GJ!`LBJ6+Cz>o{qksHMNY&mY$R?Nno>C>;>aI%$ z$i2hOb0}d?S<*P7T;XiH5&Z&0&Q;9=IK6e}3jFI_E63?n4TlHYoL2hVr9wM<0m<R` zx8s*?yV=AKHdY3Nn*3n7Fj4h!r4--luyHSNX`ikl;xD<^B1*^VgmTrsE6)da2mRox zy=TGlu2iK<(EE{NioCeUOjoUT;GoIKY^Qiy^4GWYh6D+2zelORLaj@X7$TT$dGr$4 z;In?p-`{>>A|jt91I2(%M6sx!*@!C}d=$O^Bpw!Yx>yf27wh`JlofKGbO{@SnI`hy z?J?1M$Io6k*nQoN^>@icbB>*YWWrjCDwp2@y={V`{X2BhLHTQQEdd0#8k7J7tdL5p zY(*{c4LU8<(5;MC6&cswFo`!r85g;&1ym~{EOF>memcMW@$?O5tK<}VU;o2yW9&#@ z*%PBr-r?1;BlXP3iJRb0gg~ehQt5vJ4xgC6OMN^@U{t-Y^osxhOa00g-`6AwzV4SB zG~biGrq0a53XWQ96+CnMq<s6XLnd|mx|=<)8SieG{-L^HGQ(b*uz~7wOdKhl(pfkH z!fMPPwZFfvr>tDo44uj-tbMs(s!$DepPv?2<NI_dkv(S<1D`qgDZkz<{cG!b&{V)R z$&7(-IpWDX{X%cjE^+*5BxGvR0Bq1?B1~+-Gl(l}<auR4MS;ruo55FKHW1ZR|4wfx zix0S$yZP5Q<=Y1Gv8cNlm<^#G9@)xOIQ?clonxA%Ly_edoWCC^iAsUN)|Uwm_Z_!K zzb=ZTd=^(YZ#?zYQp$$iP`@SqaXZXbY12^QOtjED{p)WsvxMc|F64$GBRPBRBX2NC z*lT)!zJ^*Stt{p=e%7}8we#>e=|gq#i7X8OV>sbRKnP&4ER`l2{iX2yZw-uB6c7mU z5*xaRxbh{s`bm$QGs_)y#^6LnS)_dSw=`on3qdERz0p$d2(A2`<uluN%5+nGV5>%k zD*FBNw3dYGd#@MFr3Ss&J#MB3NA6r85c>2Qqhky$0@S_4S~ntPhsaXNb6So*DV@$` zlCyKOF&o9>FW0}HxEf4V6SM=yMU3|ur*B&!vS@(tl&#g5?fXil51%5&sh+?=B4<Ea zlccB$G9PE2cdj2N)Y@h)f&u0`wvC1g^b5?}#<5?I!zD8HN=3&EBfbwXOQTnir!l&+ zAhB?7{BP!n#?o63&MlH*gBGS_k1~n_m+cbOCFa2W(MP4X=Ph(+Do2|*`qWgF%rjxk zndj(PX6<yL?Uhy92~H=5)ABt5#ysud`9~4U@&#B9<~QI@SU)JR%ydR?qk1gI>!8;g zVAkdhJtjr1nIiVt%4tBD%n44QIe!*)XSv?B03>vG7boQp%(HWeHyO^fS1&U#t6NmE zJlG`{7u65O(=?n#_sD_+^`|$=PZabst$7E`ai+=1Z*x6l$^<1x#o}cz+8b<@R+VjW z{Zp4=w1HeQ+@7c@F5xME>Gs@cX_G5<8q5wZp-Hf4vi>vpHsZa1i@vGsy`(ujd^88h z`q`f&a1Jbc6eMkYDNFfWH%{oDr-iz?2#1aGc<`Tf9wo=c9$Wi*9_6_boJM2cI*?6b zbF`u+-dZ>L$VtMp&pk2bD@!t`lHAQ1N3GpWuFHds4zGT_6L_a38>laf^25pNe#qeY zr4<q$g$MI#;SA7xF0O*^5k<>Cxnr0*1B~#LnNtBvu7f02RxL#<JEY=rWH5z;VAesT zVQR3W#G`%Y+*DSP>!%?&&a7z*1s9aGbElA&kjaG7(N?ZqB0oEGFtW08j>nA?0PAO$ zY1hDUZo+}B)N8_2O_RK8a@1R$vU*Nq$M%kU6CkdE#GJU5MebE^8QyuCmGLyn!0*Br zL8tL)2a$Zeoc4I(7Yh{Q{`=+kUXOA~E2$;*2hFo=&UeoUJ#`%kC`!d(6+ygNJYgkS z5GNwY61jD^-0nsawNc`rglYl~&$mmt7}ftN#&wbzbES>)Te8~wIBc?U4G|tWv?IOk zGxF|>)iWF4&DE@(^GG`$a+rgRKyXRlujmHLV`6wilYA>-f6L1Lg2D)Or+?d&)PI&8 zs<ZW#JKa$0bf9DJlTDMn-nZjS`)hiXRIkzgvL|YiZ0%Dwcbg3%r-SO7OV>=au~5sL z0QRYA42T~9V1uJ1-ZIon-fvMa&y5L>VnC+Rbk4NLU`d<iUXQS(O4meQ?w~;nMaO#f zM+GTLZJD!5zi@0atVzP1VHQ<iIWAHFSlBhCvJl25hk^B^c+10QmE&66eo+k-NfM!B zIZefSBv1r81a=QZFNn+yO4VkOS1$j0@7+6F#KLa&OMZ|{i)NvS-vP9uKt>~EE=wGV z?YfmxSe{t-_RR4CrTbsaY*E$-W;GpTcG&;aSHVKI=mtzHsx$|*{7m@7<a5_8HG!LZ z6GC052NohHwA}N9Kf8cv!hKg4`hP8>LIp&eRFYQy1!{v3tEuDzk%p}C4J&U0EhyJN zE9WI5pkg-<EC_RaW7p1`BXF`EID{}?5HfT8015N>2mMU&E;?#|)xP6O08iRrmY(i8 zw$hc!e3K|Jg5hsvRA75IiB|T;(1Y#omR2Nl0|WeOgW<Mi<G%QDU9OXjf-YOk@gp+W z|JD3r#q7du?!PZ^a}^>8-^_DMZg_gm$|h&6GuN9l^Wz|uMF|(s$7|+A|NPk9Xl*ke z+utjGLp!-BP>>jF@(V76g<bsCa$5tAkDE+UlG<C`TPv55w0g4^5{r#k9Do?EoFGom zY`hTM(~IWnyN)nfy|{ieU-DS7r@(L!RUD*9GnLKZ;nLTNN~anfD>@r_wnyhnd1K>$ zJWQu1Xk242+7j#>%$BLc<U8bmNUdv^zlvm5x|TPXr|)LIyr{)K*mPC!1}h-&b+e8q z1TOU<>R`jGsgLwU+S*SpZKFiDP=mHEy_LfqQPr~ssFR77f12ux(sS!VN#pDjRU`(Z z<*$=-*aP?&s2#D+9ZfQ@{pp8kisW2?XA!m|uoyxlLJt{y>?jd=Zm?9K#7Wy8DS+d# z9lW0lu`T<Ev*gzSNP{u@F{yz=oBokK>a|O;s(qV4Je@1mNt3<csguU%{?lD8hQC<Z zdymy(i@@!jBA{;Owm1_YjVf`qR_^D=NigUL2>qFvGC+ZcYQ`-;IU$w^Wd2^fn@#C6 zUaAh8a|CRrwTZ34Wc5{9?sQ>S1ERdYKw}uJvNU)a2EsmNI!TinLGg;poUfIRCv9>Q zHD(XOp=V?H&o^YQ-4@ml5E({t5wLh!+5NUJznIS05`bNqp7p`@*M{T!Ep<R>6F)RV zQCnH!pzSXMB@rJWl1J9Lpn8cKD!70|tKWv_0TBZr#L@y5^BHh4Z<%WTZhVLO7%H`$ zaaEmgB{NSFLFekg#zj4D>i`BVe-N06;hjZEj0O}A*CS+4>0GiIGZGlHX(mEb@_OXs znG2eHU3Gl27ZC)9gz>ME4j>I2O3)iCpbcc-ju2c63<c3t;nJ*E3hT```Qw3{ok)RD ztbiv<hJM#gY)gEa&L>|lzKwMhl=IMi!l#@emNQ*~z9>nZ<UOQG?bpK*_4@H~y#?c9 zqWFrKO(9z~C5Nr%l1A|nD=G6V?vRFLCfI3f%fAekFyE3Gg@_d7zZKIy9whZGVWk@U zp}`tJ2_%qFr#zD((Wd#{TMcj$hA2bvc{>SYqeR<2r^A<29U2}nk0S@4d}J2h^?QGv zJA65vS#ODDDunDzf~{8Lmy!1S(PGpnoloMF?mW<~8W&~>1uEq3D*XukKNfpfDw+qZ zar&%$ep{&~2M|{*w}3M0#ERwM5XmY^W>3Wq0bC6w+N-hvW!^`ueVPd|)Rjp-2+edu z8%SbA?^3M&AsVGcSLXsGY4u_x)U0ob$)`OT+MK|xZ*q?HLf-Yl5_DF5dX^hdV-Dnw z7MPA-AbDp9j1w>FV$a!Q-?%NIaMx};1g_flS!jcFRZ#NT=A?o#y$v8MDB%9%&E~eR z*s?OOun0ZuTu)M`$S_c91d8M#NXWnC8>tigKo8rHGw5ias=j7g8WRoAfUJYnFA|}` zSg9hLMyIn^y5vP=6`1K>jO?j`=pXD0!e`5~(l8s8kR?iBp-A8yN=TL@gL?LqKkt%n zfKVr<n{`&;dj#8^&$M`~?mujBuWgBk0hSU00&Q5t;ai8}PzmW>(U)>5YZ-d7PcN?m z2VBPFaQ0GN89eqey|^RWb8ZO704_x=qU@qWSkaW(R!oB~@4xj3IJO#!WX;4th)6Jr z#+nHbEXs~6DUvw4%kz6_?JDL&FIP~Qrp2vqCu<;K27ui^L-;~l(9)e(xSlgQbY{wm z=3P%SThvKM!q6!BVtJ3TES>R9`3FFhueI!U6Cw}Gd$1`PW|JlsqmZkRo*W>^uDQ2D zcWtM0chxIi5R%_NbwXTs<{!ZF)XS+(Ob^zTyE+$JX$Npl6FHM<Vrg{%#**o;x^h72 z3#Nm;9iSnAjlW9FkcDa1=(<Mf`af_(g~|zq(nXdq9BG<DUB##<KDx5CkkO{FBC0z+ zK-j2W;6huslg1gLQCM=FvYNC<hr2=IBwunIf<^Dr$Zd)33{f%=v4NE;M{$hiUwtB^ zBxxsFfV%Qf(_@sxBY5BwJnDNEc%!8r5g4<isOfs?QxG`rfHd!<xXA$xka``&FG%rC zDb!v<A-3oeli!d^P{=RsS<QDguLk74&(bV`g7I_@KjuPHyqFTL>Qpc2jS~LlzX9nK zeyHIvajJf1A{Ny|K^>N#A?fORDM_r+6P?L=G_1r{20yhP5%XDmpiK1N*$8pn^oPvU zM~LK&DKWuK_@8?5hxPjIvDQtk2oOeK1j*C6`Q7@3c1NY<UA90z58ii^HwWlaWti&k zT0khOmxgMrExg*vDI(jt*0BZS*5(80+!~n;y5|x1dsaxXKKKDm#JgSqgb|XtW}DCZ z2@VvAs28vWp7C%w^D_Fi^<~tBN|T%wKBD<w*^|xHddY?+!~jl~YAHzl+FIUn`O!|; zxlHkoSTQCzeSqyP^EjqqRqoddtYG+?M53K-m0sw}j@w^p|KhXTiWtV2t(QTXFj7aS z0jAxobaMDXZNuK$eSjE}gX;E5S4eXB8^vohVJ%YxalgLd%T&~)p#5f<H&DdChd)d| z#G^+OwQB3FCc{*Ze-T@s)L#`P>zR-09n|wS0bQTeV~5+r7l`yuh+R2WbYR=57%X{$ z<=B2Mc|qk03YUL`{U-13mq6XxZjsEH<q=KHcRicaiu^9?4^G3dm1FohH~ENT>R%(Y zevw5;z^nfdf$RWQRsGsFNBM8b<>G;=wu(aXOQrEB!4DB-j8380dj2}1?8VJGGvT7W zZSjpwEqS2zBwdd^N3XM6@<xXJ{-%EFY}H{M?*`Oo3Kc18D8GtAbk=97ol2*l`)sxx zB)0C)<%U&}jGXYqPif!t1?W@ne3mr1$03Vkh178f(^<k8!0~XX@MlS}#@tIS#f-}w zVs!v-Vx?5hhtQHb4l%j4+iLMBu1TVZI`F5b{*WUIAUwlLA#xU=o_f-o=X-DbRHwMy zM+|B<Jxq}#H6v~SOXh*gs)k#NsApnF)(<Vhrcj9SOSi&qC$DaPPi9guo5KCQ$$4$q zuKORX#lT-zwL0k{X`ApSq)3y0z&jaO8eMV(7+#Tg^JAIh4p2mF(^_B?hE4?!Fifri zZ+!sDhL&~u1^(+u7g7&cr}=lSB^OMALiOnElK|a_f$aEU)aBC~7Edy)$Spi=z({R; zggL9^?v!{x2;mRkTB-A4ScZ*(?CLI1f-<lAvy(-)${t|_7V3DDBeWgi<2#|z26{cN zyakTB5f_oH)Pk9vF-iVAT|aXd<iCqY4W%0zK?WGe#c$!CEYgUEL)j@rfrP|BsF0Xv zJ(Ik~(1rAVgoM=#FnwJ1@*C-`5>M!@a^+<^#Z=$lLh^5u)bmAzQ|<=@-oO1qdnHH= z5#Z8nkhhf7KRV8%m-TQ~{K@|A1Brtn8-Th111P`gv>hO(^0GiX=mu?CqKFPhOY@cW z1K8^x{ObiL0wX@M7;1Zui8l!TxgDac-D~iw@MpMc*C|hE0FZMMDF8x-u5z|KpSNpV z?lUE2W{?m;hF8f-<|%JEpbsD4Ij;205Lr(dc<|>N1ABXs$lqUf%~@JCg*tU5ZO&Xe zeFDfX>u)861ePOVx^#mM;5$Y3@VTr&A9|p`Cd<V?;D^R1)gQuj#-?`D<V`LL;uN^7 zFA9dXOur1jTc;uNUtr?7dI4*wx~=u&SNd~j4bVx>+QXZQ{p-VCUhIK4&kVK*_D;2w zjN-pE-ZI|wPwqe@Uz^M^@0<lrDAl|%-+FNU8S7*?fQE#HVPFs>Ocua?qw@1=_*;Fv z<IN{`vHp`jw8h{2Q(EtK%rCsWwl#H`mwnw|gz3Nc@vv#wqXao0v)B3amkbFwPGv_Z z{F|`-`0kF#^Vmlv!Qx>`k~82JmwbF^I~^5pu|pb{?|CWZz~`t;!&$oI3&~^Zqs`R} zzD^`pCWfO01x6ruyG;@N4a3ot*&pTNVi`N)^t*<`z-gbL4B!jQsQg?&lj&8tZf-R) zruq35PYYE2s+XT~+g+3T=Do+}4F3`PiyJR>-qP_!XF9_0GO;i6!&|Uy5lSE5Z{cl# zd7%$vb7a%CrBf7vgR#tt(7kJRDyoG*5e7*-&2u+{8fz1)_Ag_Vp9pUHc;=ipDR5Vw z5fJzu$kXwOyCZNi965QLOGLH%?e7hBr_*|Yhz$Qle}O<$mi&y?*9UP<@Af=)ghQv< zIaiq<wrk&Qzc>D&%py#>&Ld7}eEYf*j#uWWJ3?v1{Rs(b{NF=j#ESY=u|t2C`2oZ# z_6FShNBK3wEZ=Vl>i6aYR@zX&q<+9j8g$eJ5pns6VF*<?OR^3qRuo|Jg#nX21?M0q zf!Acr8hoqY{(6}&xSt>p3`8z@0)>cfO3thng<?WT+9;V<#<tqJr(q%=u5%#`PP?Yy zTI<rB`7V^T$_p5(#Yte7R&o&wdR%SO*D`+-t;Red{T67Hu+KQ&d*)C(829e+vG?PC zCCAubfi@Yi*lO3Rw~Ul47PeI;r?)+(GG;rTdbR3hV+x-s#O|ZJwO-r_Qs5EO@_x4Q zNPzOW<ITTBFbBeZ@L=iw&f3q%n?y)1L?q38v%<FGUJ`*TvgKsp+u-Fvem&d%cUD;- z77VXV`L1Jc%9o?PbdRpso%z9pj~i(p+&Ubqm@yu=+2^yB5|?9lPRg3wooZqxQiDV6 zyS&@Yd)NVw-P&C^ZmLL~t$qLGknd%Wo$40{sfdGx8IjA}kN!40rKEp7Cv^E-?EMnZ zyockXcU;C%4sR#LZg?`oWBcp+0>&R{I$T=g+Y=7PJ4ct^P>^KBtsJiO##K&!PD~~r ze4iO&RJL}?H+$QJmv-E1dggd){DI{_*xl_pelE;wnYacyLnzJBw3o*hn5{kh#+*T4 z_v~e%XQ-%WLPsKqL&9evK3}mTSvv2!L$=jp#g6U<Tb1s07wbz!`=A=^jA1|jjWpq; z4a!>xi@e@(!B|jwdc&TB>HRvsa#BXfy?K>Z&XbjZz)}`&xiG=ZGBbCdJOSfl@0?2C z!xZXnN9TZYVEPX2Z9d;Q%;u<;pI`|VB)jdDYsQdue`1(3%)VG;cq8bE_or!_IhpbG zuiyxlv=Z6K8G!54tS{ptx6&RfNA3@Hsk=Q^>Kfd#lft_3+bJMW26@TbzPgW<ni5AJ zt95K+TUGDoWPXX$6mlb+K4N`#)SAA}wUn)KTrJ=?Dy?qBCB~rj5t<I766~7&a`T>f ziT1I~XO`RdMFV0|c0|t|uU6Fi3b;mnn@2w-F$Y*vU7u>1$$s6+=cYBBMei<HX;F;i zg^JLNW#?ogxcm>sBnwx!E*O6yphK3@k1K+T3@g*$#ML-ua>y7kNmvC?Wnhx|=B4<@ z)c?+*Y}A1{Th6fwFvrEoZ5DPO>Qp&Pd2yx+jJxso%-ebY)7LI}9vW|C&jEO1#@btf z#I@d8^^3vJ4G$F)Dz$YDKL7f7N4}!N;6L+H8YlO|6C(d%BKV2HHt)v|vme?obECi5 z<JWjBTP(+gJq5lMo$9|#6Nsrew9y?X?7qyi8rRX(V55E$vj_`G5-C@h0AJ&uRl6}5 zz#>|{j<ZuZn0&BPyYa?;FrMp*r|BrlWb*i_X5^5C;DEDm5zra~5qs&$0IC`ep+a8e zIc2Dl>LV7StYDn=tW(znLvouDKFADkJd((!m;q7O#4(+zVgjU&nBMz%mb6T^JSpM$ zA6sV{4%Hw3{WHUuG0Zsjv5z&8vM)n5_BD-t3E4xkXG{IYKK3D7*0D>`D1}gC$yRDm zD5W8xl7=Xh-2VUTesDjyAD>6(T<1F9@A<sn-`7h+`&`fspilO5!vzRF-HmLV|2>D9 zp?4gn;Fh0h<*d&^C8S0>_k(ISR{ZXd=apm<)AqWh1Riz?@~!@QIss;hp>#|o#7(3X zVL<L>K2H0_&D0CPw^N51&yE+`<mG3;#JQ4&r3KV;qN&EdI)^r|aIt(3dPKR!EXL~O zw7v*NCKyWCVG~(-JXw{TJ)LsC7@(d?=7!x(J|AJu>97ppqQ8g4>(@J?NDN`Qhl!Yf zvFQoeu`%zZWm)7~qmxt0Df?gUXn91vv9wmXXG2=L-WF>pxKfhooDJoLtN9PSYZmf8 zZYdF&QmPZgay)!xNFnQ88sFcwoai8HMTtSTbDTyB*JIo4?h(hG-b1;s1sR<TJHel( zUZ@a*+pZB*8L1UjNmCDyL{hqFbWwnfV3R89`ZYUVdx*nhc?t8A?D(^#s9smbAf8ls zZuXrQt;}G%kw?WzG02AFB25zEOM{)nC$a}U%H&ge`|(h*-VTxIoXFiygE@KLZ`xV3 zw_H}|Y^O`+Swu;Of1>%yq2e8Kd^yEKx>C=QbW~drQ?|Z2h_SV$^B&8ITm{6mGhh32 z<A;mn5UuH7!}@VvEiHFRN^-v$`j-DO7o$%h`&nW=Q9hVDVTS=8?-${wA&f+h&J#JH z2qWoEej|#S2%oj*$ct@Wy_dnis_xWpXA)Jzaa1Adb>)%DJt3phf=T_b5R+wkw;$=a zW+)p`lj%fF;X`C7-MNn|T}m{RpsqnRf@0ATGRBX~e1sfu4rX&6Mz(vw&o7#r2!!IL zxh^tT)am^KPoZfBq7}EixHuO6iIaobTGFNM4@XO(FR&0HLO&-BREaE|J&Q+9oeCM# z3%b1$gc+dg-Iug_v$0n6&-g?n6g=a=O5}88upA4?&%6eCDZBV0C-jF#rfo_R-@RDa zDcmMP*{X(pyXOd5Fv*@I)+D)&Y$r7<V(ye0ia!BZhI+lwq6)X<Ty#c+XNYEU)tx>P zBII*AH;>1yUllG4OKy7HFAxQ)E7#wDe*1AzpW=M?wN)_d3|pcU&s{8B3QzUHSmlPk z9zJtqLAx+ulNZDX<w}iZJ^6?VfP9`%?A&Joqo4J2FVaMqyYDLdvqT-%Yk7PzP>ERX z_cA4yhARor{&-4e7$npn&k<RqQ*dt%KMJppvWaMrdPPgWZ5a^HE>=-5spdxReiE>y zvgL@o5tO-9llZ;v-Lf<u){BBF?8w9QZ|C@>el0om+&YFa-Y#I;%s{A>_G1m0weH=E z0Rsl-9hdt<W1Z_zZgU3tDb7UDZKA<>o~>m8^7R1c`~fU-GPL%}O!(~0L!c(rhfcD0 zyIj@z`R?Kg@Agjy9sNj$*ssGECEtJi=jib_Sv#I|y=Xtd(9wpOdiJCKMpT~kS=(5c zQs4r4-2J3)=a(1Gk6O*tDTzGjDfsibuYzKY8z(CT;NpHScT(6di_B0>v<1R-dGxRl zE^NPGEd^$IG+O$rlzpiSiSlqhj24fTKlfAldy-NZ<l#G7n#SY)lF(=Ar^0{i8wy4s z9lM}{w=hHCFg4unL_P0GuI_xT^Ec}?o62@MXrrlrNe1s9A$`e4KuG>4mu<G}zKp(g zzk9J;VBhgCyC%0OfJ#+p-!Dw}N!M8hWg<|9jJ1rvgyB#KF!O$%SDJQ9!{lnNI|(D6 zVyc5j{N1>xa2(rOa3*52REW%&;xg;$ZLprMnjccouc7OP^r!B_6B>A%A*jE(8X-}N z@)jM^>x4_u%h#PWkPjHhhoI=2M0gw3-asJnE<91E*r%O&WEw>_G1yCE;&y)~?n=8! zjv_6Ke5gQTFNn;enjP8@U=GR%Zz-_{#JE%bM45<dR*Pz{nGTshuW4#)f1z;Ys3J+e zvTUgd9uQMp;c=2Z*F1$Yj|}IOx)QwUkKhAH>dtXCYG>zCU6asN_FNP)3%r;`j~IPw z37QL{=c%Y6Z$B#=y>B*t>vYr=44O`c#UC@mG9f*$5n~L)bc&$ElIOS2sT(Q8OC9Wd zelT+i>qSP?g<^OC6Ol$mWKok8&DhKE?4>{=&nQPHHnUdVw_z7qw0m@k?IIKAq6~8< zUJj%o^57hMJmRESY3)(oF982BL-_?Dy&J=w$HK+jLGlfum87{%R*zgmXrZ6jEoIa& zJ@YV7_R0={-=|%~CH%T+%IQH&F17%@jOFSES@p53GM+cMsEUCjEIL@$4Nt>oQ+#@c zmJgSazhdAqWXon77AZ!I8=3Ph{^CP*yED)W8^>}Zr+ID@I6BE3g;Yc;7+9o?@Wrz= z&$5bsNoqD_J4aAFIysrY7IhH|vmwKd2Nu{8**xhm{0yrD9e&djkxE5$%VxT5M*JC! z>mMd}w`b|pT<ZbgXdd*0V;=q%dEXPoe8bK;<a~Bk)pLe@oWh^IgWd5&b$TK=?jy!& z__v50%P#VdRcR*nQl*Kk<=f)%eCc&M`ie7GT$t`jG5`yMT+(7O2hkg0=)-mVi8q40 z-jEz!Rn#<qn!$4#(T?N^dADo+`!xa^BBQ<odY&Y5$Sr3neeW6~(m(*XM@QZRk9C5_ z8g(*7P1z~*jIyqzQcU@+=FD59oAWlA;8=Vs6<J38ADk<{pig<=wX(^qPa|;JuEhYN zF#UC*tuunIjN<E1G9Kl)=ZX5q#LfVyP6k^Xqp}mc+M!-rp3nb=D0%mR^n0y}bsdav zo%9NYD*+D`qUH)Q0bWlCmom%cCRhq97ki+G#i|+?R3VREy7RkKBuwUp8B6XhFHDjG zLe?BRQ<c$mw33^c&D`9(e-=9zabgl#?~<q^mw0z1UfL<~@Um)h>F>l_s}TaO;s$}d zk4;g@v;YmBI+%m%IurS5r7{o8PP(0W56^y?3{MTK&jTx`UHESpR~><&rzxE2Oc_)| zoioym=LlG)%%X#@UU34rXpn2>Eaf0DPe)}N;>wFIk@}ro;*cfs?A6AsXF(_{9Ezb@ zzKVqRf+GHnT$JKi7X^1En`EBJGb+PzCXQfgrbFr`?>?2?lgRbeulQ^Lc9n@0;Hl&_ zFStxN0s=SC8R%<8IcMSK!SS+)!i&RnjXdEy*7~_yo~RK|RF5*tpSTiUCJ=udszYH_ zW3VN_N|}_D%9<13$vLE<%5EA5+=4aQmE};eNcaYV)h!HhX4~?9Kk6f+)dC`LM7Fr1 zb8RKFc^QXM!|`5lWlyn{Cg3V$l5r$fu3_btrt#3NF!X|F>hExz6I^MZj(&ctjZK8N zc`$SlpT>@bs$rqL1i*J6kW^+lIw~39iMmp%;v8%G&p)$`44YDDef^m7`hJrXlO^X% zQ+vPCmJNCxcmUUZpnj*#RRg_46jJX=xanQws*f}7Y`NPa@_{6IugpcGyklg<<pY`3 zfC76g9Lj6iC;&oF;#rQ0?G^y5(%Vdrau^=l>SfuA!H4nE0gbSSy@jwCCX7bpO5788 zC@C@C*b#lLQ?tG8Ps(jeA^Ah`$SVnVgsyX68UonQ+sY<pb>hk{EgUg!8Ehx9P)Weh zSE2oj7DN&Yb+TlsnD166Kav8Vtm(p7DnyFF;>F?GOGB-JvP%UznIb*+%emuqdoDgg z^(E?L+;P}@hHH7)^XPdMw=Gu)qk-7it%h~s)`f6i07PiLD4=h`QmHfza+31j)c7Me zChQH(HT+1KF7m|1wP#7uX_vJt0ZL82+NEdvq+P@j;(2F=icrI|NP0e02fHO`y)UvL ze?{7B|3I)H6o~7SE{BPCpw^V_!f&A&-=2Va70chAOgPJD*mevtn?~MAb7yzD=<AP= zSzXDjJBm=bgn`48<bi!lnp{F(#UB<I=7}K!qH;!Zy%;0<z8{y+$$R2Sfs~nfseFAc zF6|E2t&YK%a_P|gOCLPb&rn#-P+2O<2g>dYRQ_R6$Fp7m5m(5t5^_$(c;ubTAz!x# zr$u|$iW0cq`?e`q`Be;^-3&{NL(?go(^NJKEX)>QP0+hPrGU5sjBYai(>3t3_eZ1k zhC_Qt@5c{65HU0D%#r*oebuJxyse+b*yxw9Mov(fzd`6XWMmtKy_do{Osn^-z&w{K z_3}$8`#a9|ZS+Uh`4V0Qo!7$v^11pqBiL2hFg~vjP?;}O^aerNXK>t{@809y7naAL zi*s^)0EP~a#va%6Q-_G~S-O(?vlsWj2{FKva_Vgn&$5HZCstmNUj}y;O|yqxeLhX* zOeas6MZJ7<=f!ryD_q%2^Q?qn&*wL@al^`kmC<*1-RNxB>9nR-x|YvVWX1xfa>j`8 z+c2)kM7qHBNsO2`@;dcw!WEx1*?Jzj`Z||g!KB>vDft6}NM&2#`<GuXC~$w*@5rB0 zcc0c2Gf-5z^DUTjT5s$VmTQ>M;21w`<o?>EQcdTexhNUwbnDW_x(pq-V|x0Hz5AQ% z1+QJo_$SvVFDLL97?~4FC7BE~f6yEM>oWnT#hqL0CP-JDlL%itC9RkA`739lug}K1 z2WN?z9a^EdZdpl1^y}DX3i|X_#a*8xRnDol&wO{$S$lqLos3pKt+oM{%-@|Wt$bTH zF}L+jrJeTrbdFrTD$3v?>N^7+zCByk_wMeMnTqelYdgrt^KXcS#bZQ{6(-vE!@J%O z^8p9%u77hh6{G|t;oe{a-R<;3*XCb*c&~|i&p9?rXT0J<ajlwjy46XGx=~+#_^@#O zC0#6+{Qh-^`}}GK$JoJ#uYC&$v4!rgm-~f=-@_K%Z=!WxEbLZ(q^>V`jJ|r^D$8Ss zGI-{-;W@W|oq>2V__y-*>gD5tz0xr?f)S+*K99wX9tPXoBzoc45LEcTOmxeYMX57O z7FmmjA7-a&#B4>S>}|KgWd1EFhYX)tcO+g|xG}ld#caCP|3PKp)0vl5a&57r$Nahe zp_&FzVq2dqo-7LpFS|9pX{YmV(T`cYKp#<sOt(>f6U%N3p9j~L!OoW~OZUq7-*(|S zANroYu<<!~VTJu*bann!NYJNqiJx#DmqMym<6mC&d=ktb{OXsD^miJ^l(bc9*D9%M zEoNr5PVTr{O^>KJFjm*UMoZ1S@ujrNIXmQ%d=>eNh-Au1D|74BTOMB<bCt{6d=rh3 zdP;52uA{|IS`7|-YV!E@XyNSbe}v^diM)RwUA*O2!d6<0n>#($htay-8-(P&!CvJL zksj|4nKV>vyX1(+_nC#$V;k0Qnha(APzR8;)Irrqw$fRTjg{Qj?G{%ZA?T~YDB+<+ z>J5&y59rT$&D9$}c0*3Q^>9p7MbkYw7tkA@z4)25C5H&~Qo#@8QzjYr;Nag6NVPmw z>c<Z(*U(EQrg~HLE0f!M9CH5axyfJyRgx%lOZdMn`Tw~8pluE|HlO6mik%GnMKtfI z+S2^*r*-?*xVR+vQ9{Q^FqO<{<9%BD;<gDF26xKZrGEqX@iSp+kvyZZ9=&aUap!dY z_A{B|zlApw3Z#i~Rn4khj%R=QO7J>AH4jWElKYQe*OtrEncye!JK_}grD{{lzQxvp zfWu!WnUNoV3tjw8s9&_(_?>cbw+*^0{rb!0(B15hyIP66lJ+|HE0=OF?iD}X49+=E z>Dw*&xL0*P`_@O)muGv`7xzoJ_C9=?dl|BS_v5}<XiYBaOWWB$9o4+eKXC0oW*$EM z(|f*WeQ&Uty5D#9@6cK8%I_-W7yphw{o8p~tNYdO=Mo3GAOHGA{(gPzVD9Ok*LiC4 z=!3V12iKn-Xx8l)a{XKRxVKcToCrmCQupfr`^UVv@#W$vu8-Rb5{JA0ZT~!b((>a5 z0118H1;9|^Mx}&BgEW-bnG}r8l2InVlE+Y~%_oywvC}tLg>0A23S`e!8Qrq|Y*DP_ z{v<`n?odwqmc|t+(UA~Qb-x)_bgz*88ll!WN8Gr~{)=tnxym!C!VWD4Wp=G6Uvy8G zo=?Kxy8#n%Tz9_jH&JC=?)d#(vBO)1iIy+<ua5fEPo9-K{qT5l{oo%=)R}75ne3ID zEJ(B!4`9BG(-3vp@*OWyx;R|17wR=3{o`bsV<>j{Wy85@lS<c}pqZOGolndN;sJ5) zULS`mFZ>Q!=(}#0a3FFA?~z4$^GMNcFJfh)@@zU<qwDA0tfH|xbKHLP#)rQD;D^_7 zkwdEiA5qmF2l2nYe=rrlr`O~?T>J6kNcF|T8~=<x9d01i|EwF_JIlglq^u9)|9h{q z!rzCp8+LfCo@&5xDypsj!+nK~E~pBtiV?S|jEyoXQUoFXP3A<qvEaoN6_Y0GUZrEP z0vTizp_t`%Q;Gj7%uHu&)t5QA5{*>NWlM}~&E6ndnntB>)!(;Jyyr$Ye;xdKXcW@U zs%E7!vTSWR9b9-{JhVXi!8xsuDQX&OY9c7{Sfq-rc<7nz2j|ZovZ~+H(e2?yRnKs$ z+ZYS_MYZTFeY2=Grq7vBOin#hw>#$(|5`O{dr>yeV()#2z1?|ZjZqZKZefYR`*w8) zmrD%}GuFpMnyLtkleZl&{s(iMya4}ZQ57hzb8N=5#P5;IiFDaVRe>Rk4^LjY_e}GG zcn!amxW`kOqd&SUBeI=tY~hBSWv1YR3AdP!slU&J97;9Y`h9w)b@6&#d5K5m&<8Eg zM7V$J#dwIEwpXfPbdFcLL>k5}S-P>yJIlCY*E>gRCH85yE}M>T{&Uf8-<#)uVf>1m z{JVSdE~M%B-`b0h^Dhq_*1202xzc^9I`7@yrJ8iP_y$Ur2`;cf0~a6IRGo&aX{>8} z{I#~}5$<wp=y3eydrwWeFH=Y4uKBb-H_^S4)~8~6rSs!PoJbU-@!Aj(03`QVVMn%H z-~=}S2e@EwApqhKU_pqQQ7Qe&2wnxZQEJU#`u~$31ic?^uN%q38fJ=`->)CLDR0-} zHfHOE;AGS4_`mr93+=@i?;@#6+!A4BBL$<^ncY-yAMdz5-9$Jwp7PjkHI+lT3E2xi zyfb?bYv}eDC|-V53&}2afBvY|ST^L-c%^0MhLukkOBnqdA?3qUVq8ILzzOB?>L3)y zUvon9(unwR^W`!^3T(7g?eao4`994W`Y`D)K66niNjb)B<%RJ5#u;jUahPb&qro>q zF%^#{dOCkJNem&;o@<@qk8hmzKvVzj8V<j#J8WqGvt;>Y?!jfPu1?S2iA||mhhh)= zdZ)g!Up%*cg3xQS6UBYFT{PEw(A>a6sc!!B<nXZ71vK!2^V21a)UC+*Nl=FdFaa=` z<3T~Y86Ql?9JVXH#aOA&IiN?!&VcZ+EofB89uE;bkLXBBNfa~VPL^`R3TJDttnq^d z05=fAV=f7j1q6I+RN43==xG`Y&7W?{BsPMwtRYbjk@Ig>F&a=8H8OVvRhEzRPF(;m zXXbs=;QDcPV|zX?^k-)_w|2O!K4&IuxiaC`+hSO>@Um<i&!#Hfuk3wNy}mA{!|W1w z>q>ofp@Mo~07koO0WZPnKgo7$SSu-k<zRc@B>ds%4C0hreM>sz?_r8JaGvs&oAcC5 z&C5WpEO4{2C}fTfr#S|#w|jKYdH~~cGOiCsO)dx&zjUZA&Qzpmr)J&ik}b@HvoC@e zEPHq{UKz8QBovAHJl8NatoWnX6H*@7&bes$<H=uJnKu0!#L>%L6{5VrF_ULs9Avtt z<jDQ_G4CPdWj6e=$o*e;Hit!H);C8YZxh<_9Xfgu0QA)g)h?*DVuo<)l#xiefWGNG z#{<;z9c%3G^`EcsaHS6O2M_<gZ;R{>CQlgiioK%~OqF(C+dCa#CiuM$xP46g!dxhh z=}N!md`qrGo4ZOB0lk+xzyF#K8&UfGK5F*L?+>xBDmQKIz8_Zp{z!zM++~RQ81F8U zj<xMBWovEhej=Nm+*>Ym3fcQydZ}%1r6OiyZ<UgMa(}IUzSZyx;`=k~*SnoZ`2lt0 z<e&A9S#%Lvch~dJM(^*9o^V#=)*t4OV5puulOzpFY_F-2^_U2m^8nN8;_024OL+&s zW@GO4{eJ)7sT;e?$)W#tS4;B#?SJj8{`Y5n@W+k6+Y+IN2fMHQ(AuAte;ghHoLJMD z_S{guWwFm#3LrR2W5bcLpAj?-R$H#f4r$;kVT46%v>(kA8qcCa!42o@bCoeu<V7o? zsHxnjY;uZl)CG1svq9l^1nG58xDKmr7V!F$*eZgCJ6zEm6cOGenFS-%*rswZJd+vb z*|mIuX816WRpQ5J&4*0wXD8$HlXr+Fz#1ekx`IXQqE(&n?3`K@`IE?2mx)T7jef*- zUQX<bI`L010|_>)*fq|2ESz0Bnia^6SYL!qnvI&^w(_5jQE*AxIe>bdID~|i(Ha}G zJ|mazs*b=pVzkU#d`K|;hGR}+<2}aI0tjhD_kAMz<P)W2!|VktQ8F)_Of8~uuFR|N z^+q;tWqcxu-%Se`B_My^qF0njmSFN?JCem7rOe|19WcC*C3BLqN&Bn`{t_Dn1D#~k z&DGJ0K`f)7HVfLT=C5)qrAe!tG#y6GA=(?dA$q`a=``Ge9`L4C2m(mzZmytXy66?K zoMt0g8S`Y?U?oIZhQT9Gj!=%M#i9b^5OefU`SY<vJ5!vp4j83wQ?Hy87;P43%(C=7 zSLw=#f#3La)j%3?c}@BZrhB@xhFg4^cnL81GTn%Ks7d9d=|Wc<%t(U`f(b2-ok1m> zj|d{uhJg}4R?uLY`7P+@7T4MRBJKenoAqY6_Fr?Yu*^C!7r#3mzlHhB#ZR_CAq^&b z7IOnzM#<xaEgFjPS}ZU7>jjM9?kLN*<Bj#1Jify`CHq=AJW{}SWm8;O(A%jpM;TUD z895Eh(;@Fr<*a)qI%e12y*qptEj`Z)*K6y42hbmdq*Wx>;4=H?g@1PmCbHoc6S+A3 z)j~2*raDuTxe-<Z-E$Ld2B7d<?f4Zmw7)5O#Bw3kK1}S@RS^ZRy~*w3-+fIJ-|)0> zi{DjONX`30wx2mZ{uBQ#@C?63ICpENGcF_J+o<HZgXf+DZISnNd&_ak!Wn=ki+I}= zY8uC7>nL<REp)I^4}I4viWD;_KXdsIPa?$bz6lXR6ScC+mxP^WQnAtHss~JTEM;&= z6Mf&YbL>@8y-$Bsa;fI{B>LZ5r%{5OJmfzSAm;9LPsH@FgX!p;{57F^;n$ROwOfp1 zc@rgD&(f^n^Pf-k#2wbY8DhXDg6*TX^N3M59#rXc8z{whiF5lmYx+up67Xp1HEVVC zCec1qR-(`@O?g38G(+|H{uFFSS?@+*r>?cMRnSYXT$OV{jthe#|5+*5ejolMkzO*~ zkh>$7k-fIox*sZ0^sr4*$1mx9od|XKf(DcUA6<!`9gVJ+)Ns#@<ebTj=wYZ!*#yRx z4py33KYGL>l-F>BH?zR;lzwL47b}mL`L&H&k+=EI5(RY?(VF#jvvJ?3I^lv9qilLi z_Q|L}*D^l`Z18MO4scZ)id|PXefn(1G%k1lBly%y2&T&Qm7Tkfx6w~%hWRMmQyrio z@Y?V5S4rgw$!dqe8+gvWD<5&(;_t!Qw^R9xVJXu6`<%bVVnPP4mL_BQXOC4mAV)1( zu`4_13!QKS)W5C2U*vo13cOvG6UmRVznaCr)w~|keC<Qx`l!O`yXLueJj~Lx8|AGD z<u<MV9em%jqiEZUTSkkzV5R>y;(HTk<<3+DePH@S+c|#^h@4Me7eJh5=I4sV&%XRm zP*}S?F;`LK-`2n9UOJ_^<Yz%(Q#~qjIkC9^OL!8mS*Y5IQ)q7nN0*q@6*aB92cHW5 z-2HFz6RR?H^6Jc=Co#*V*H$l(HqGz%VH@=>JbA8eeyQi+H$C)2Ye`kV1lKR#2V7Be z%<SB14w;XB+kS`JBR_g>e;OpW=)u=n0QMi>y0Eh{Pyb#P{AKzyK2<n74%oiFPW4i| z(`+j@>l^*kiP)U%tIcmw&c<HCL=6dQy(I?;`4Ra@IHs~uIX}Sd@80<<!SJU3+)x~U zF`>>OQ4WJ+tvAmV0Gj>Lj7Nqhg3i9lmLxXE`&W~+5ja7=|Dc;8?2~8-ElueZi^ooK z?@E%*N_8qajTXWZ=U9!&SWs{|>ZQJ)j(#MB#t|-sZjx~}-%Y()r*FUJwn4K^^^Y4- zNr9>uwV3iAcaBRNV(-Pr;b3Xe+B&wKF$U^rq$7C7(ehD~P|P;stunDri|5F&@aiWj zJvKe}uvBXYt{;<*_A>*WXVacS*y)Do^K-mLUDvF3NVTQf_4bJ0N5feVKsp&X%9sei zNu|3YXNnWdYEbW#qv}etQtbXKe}ndOvUe^?6Sj~0kisXO5+J#n__!-Ol*Jy}o<u1^ zQ)EtO4VWEU5$RGl+LtxJUE+-q1oCO@o*EX3quDDMO(u9+h@|fnZ5m7cPpIh1qkccA z%GI1$o`hzr9(-I|bnZVhtrt58tGVb{_!Vd(8q=8Fn(w)!d{r00H|30O4^w`yO6>cc zchwNNXM=1|MyBup_dpIwA%OQbcRRM=9uwIL0?U&HtSZPFMm}^gU--5cOf&o8p)VNi zpZciA^_-VGYq-NfdVV^KB+Ftz0R^P*%4g9Ek3yAa`Cu7{<j60uwe{IlzWQ3)<#H+E zgZ<Gx=a%IkHC0hxN^fdI3RUHV_M*Lf%nGCJZstmXjv(OR3C5VSMIQ&_k8}Gfv%)rE zY&Ea|EcizsY$A9x`I@uZL^~b>W5HAdqpT;1=Scqe$~oRGnbWa5USa0i=7C@v0c=un zgL;*9ddgG7IH-X5(RP%o%yAEbgh6s33`7{7?Hn^3LM~+uFB+ANSxq6F3qTL~lGD{K z&dV2*^9yO7S1Qu@E;(GQj?=2gi|^G)uyb>CGV_J^@~bD=D-S_r4Iunh2efwqk8FAk zbYv?H`NX_zUnRdT4$Pt!q>U9out;clmFOdD<ZMXns@v16euaS|$yX7OBRd)vy&jfx z0+N)*M<^aO<8Z3<VW~1V0F#x$CPsc8vr_VFHHN#IUH@i^RKYu;(u)K{Uadq^e|51j z{(dSK9dmkE3(WG?H`VleGIX;7V!cK6)s_ruiqa3h?f0Hk6U|$8?KmjgU0oN3Y{J$a znAa-U+@z@FcZP8kGU{0p;nwjS&Mi*kg^7+S=aw$n+~_!s>A(3qmiPOkTj5Ba5c{J^ zxksvIp;eHkurP2gtOP>f=w%{XlsQ^}YI}v+>_gW^c@<;}qkQ%)`)xY1gCgEZ<nUAg zvnWWG#b#I8Fcy8Zc!R#9Zy65+HO<HzZ30hRMLVVhjo#)<+eQ@-VbD#~!;-5=7oN=6 zs4+E*skuAXzp6<n+=SZ{+@n>~Tm%}xo5C&yZ`#WtWH{u=EJi>!NS0X35+<k5u6UxG z1%O=tvJe7jH-d!FS_QpO!VO$6)j<C)@M;jZp|5-ORq`aSk7i=PTZ&$2pyB+o<>G$b zCj#{=(WxvQ&DL`c_B=gW3p6b@B=WUwt(mLFRdVRdH|RIWwd7+t?w|LnUAm1l2?Xzf zwNCHs;<Q_yX*j#kST7RcS&Yn2hr+<-zMjV(m>OQ1ssm;*5k2kla2u}gns;Qljo4D| zy!`2t@R%n^2W&pZbxO{7(Y0fXX4{ftr(bBr7nSI|X1L{PMKp31M4syc3T9o9oZR;% zzwtNd%hzF%HWuK$8i$<`cerF7<Y=L);~FnSYyAPu6dxh-Godw{GhrO&8EluSw{d}> ziRC>nNA8*wnU7eCUQHAHmd(yry#8xbX(6B=L?kl7L;~l$C%StE1-xl=XauXvjVMSY zg^^!N>&&akufigQ_wFJg!g2~W4f5a*Pm@U@K-3geLextPSDe_@bK&4R0lQZk<;kAN zmPIZk7J&@x9lpbUv}M+V{n?n5CLWbo@~tn%q$3N`CMSf!iD-wzC7*7QA3(jh_LUvc z`gd&#OTWi))Um_DXo$2a_9q#4D<CZ_lQn;IK&&faEk<9+8QuKLW*kf{@<or$^DwA} zjxv;=k0}nSU|d)mgn%f=-P@r(W#cwH{2dugqp;P-s7uyV-LkGQCLfnE?|9Y%hdhOH zv%oe12w4)A$m&7_|C+-$MJ(AR(GqaW@hJVBuxC3I{Yxci?m|cSV|<M#lBHeg-7Vzm zSldIJhI-FhPdt0mX3w|y%K!GQj*pg4mYeTy!mcHmP#t(>w|&!$`X=qTHe0R+kl~{6 zZq}ntH)1n4J<5#U!)@{yZDx^gubZXrYw?ZX2(>94rGPLZC=e#Zs|<Or0>OF?Vevz3 z`Yc1L5EaJpbW3oQ!Zw9<$R6T&{DNbFVN@o=HLcdu_p=h3U&W@vabm2UGgzb-U(TYE zuYT*rPDh*`rtcH87AkqG;_8!gizqYQ0khgsR*18UBA7z#=H4biC;N|wH^nJ{Z}AVE z{EWJ{k2d5_4Xi*c2v{3DW!>a7W4wYc3JQUM8F>gxg9uP@i16c4Si~<+Fo=lwuGyA0 z^*s0;e#Zr@#}~Dbdrs+$wD;#rl!0ALWDRk6(YMZOw-aWA2__6+R{3iWwSv}x7aTT- z0LnB@47gWw5fPrEwt440ma8Zx`=1D&n{SeHkrl##!Ye_W99EmKAr3D%Y*D;j6lhG4 zXSD&4P*y%~@TFTGi2@^mh!e7DoHkdV3?i9A!0j+_{T5B(yQoI@@UST0`+}o|az6)Y zMRJ-zdX<4Km;*KRUpvrW-ed-No!i@sQ@poM=o;t+ub((=kYm8Qj9T{$gtfoo&*uuF zy@pUZAylqiWqqjR(`AKHSUX$7(L=$*ui@d=6c}_;zJli+TMetRt<0zQDNxA#Yu-?n zNmS%#n+HYI8>S%J1>A<tEUOJiC!M`kxi%tUc4V@-<&bfkC7;b5%ifefg|)o-+{(;u z1T{PKw2h>2Yd)tG;{Dw-tstWdnmC$AoWS=!mEnE}^TMB>*Z)ug)}pxYw#LpXJ9PGP z&C<AjD7TH$x&D$tn+7&(8cUNRXrKyOp9TlSfMjl{0Kj|q1c;;PvLv$VD$g`KpQith zybhgo2h9lkq+<n^T-T1cO@k=2g9&$?#y<>Cev-6kXr>?oMF2x(HVAdu&SH67?&7zS zfgM5y)W&OHaE!Q^%+il~IP_F_2U$QIg)ojjCC8+*W26hY88A-&IQ?5W23JeLS6DhU zoNJo^zMOVTOX1p}qc_R9JJ>Z#)3D7$hV>!{(4rsw#-e@$r`aEJk-|WqG(<Gv$obrQ zMhdj1va&8NAta%kS3m`Ha9LL07s6E?fvl_t!@-u|b>JklKR;sc(L1kYsiRhO`{dQV z+f^yP0)>RjfbhJs;}J!A7-BZhWY42<ytGSt(lED$1NVs^18%GoxPxqa-Nj_<2eKdK zj(jJJoO@KRYaZX(O(H)LgQPnQ*}vV8`D`8Z_+|UI3rm2(79Q;fN7GEe4}^!>9QSrb zfPuOq6gSkhU6hLsKs<-wUQlxo)<a;{NSCw$3oMJsGO≪n?N(-(ZOxvj-nU_so=r zvTPAtTJu+W0rp(0(<cwRK1Fi7mj7Z$e)WD?<nd9r?Q<~rR=kXf<Q6iD{9rmE9qW|t zXxLHo3YN&FAn3aGun`P@gjqJ34!Md-wb2RmPTW8>3vkUVqj#14`3k}ECv2DL@@9C+ z$~N$+Ef~u6-;~cQC1Vh!VR#UG{`b&l2Nq%UU2)SY3EPkpo%H;m-uu@&3@1_vR^MG0 z0E1_VsM9N@BM`IqAO{k6+GOAD;)~Vq{)o%Oi9dhB)V0=w_wF6U8g7v{IPx7TR(dfu z-RR9a?5=I{y7k#k!$I2ZUkonz=C2tGP?Z3x(vCnLn=rcQYaXD$vz)btb1D=?_c!~^ zhfdGYn!}Yj9%9*w7}K{Y!ztAZ+TKXU-nT9~^0?SYGG9h&bYhkjwzvKc%S(|GJYtw( zyFR)ika!-bIR)qjKsb-`190(i6q7Dln7&bC@c+pVFrRO8P*<0<ljUuSQ@U-$9*1j8 zw%Rpqi0XtdL0@w)Ca~HmS<JmZU##tkG6JVr$@w750G!P@g*i9D&}nnO`XpQEf8ztC zDqO1agnmc8S&pzDz18LM)h`1Y2ra(jPV9fiABs3LJqJ=zH($hs<@d*~B#FzkoB%{T zAoOm%ia1~05QzAJ(TKHrPesNvC`^PxS4=r^#7_{!+XB{a50|ei&W2P5O!QqpWE0oE zq?7ghAB-kQd5^1TNRE8%u10&D{1wv}sfRm;i)C`+<P?5jg$>!}#R?ZcF@&>J&m_>h zT3w$-tXF*;IUgNDY=8*BM`eMoU(fI1dsZSY3pfQWveq~+;Zpfn{x?2oid?6}F;&vL z0B;>LAp<BwR;u#k_QaW35^kszc+!4exu#dGnLm@(ep2i?dRz_=vtd;=lQhp<Ez4Ys zYZAx!oKSiw$t#7bnR51qA4`tq@DvSwBAHnMsH%U;P_3Oat_qS-3rJ6Xf+wYA1%#<d zUVn*4h#arHrh0yWVbD<cl=Gc2ufw(sU)=!%=Xc1TLRtGH;AG+@3$SxEbW9nz*ygCj z@QgD-p2a;m;FyvuN7c)54t%*7%yQz)^+z=%*<g7cdC^D{Sq&%m<3m?xzcRNGl`)SJ zHD0H<?n)KxVc9*?n>iIe<s?htDJ{TV<I!XRS7n6A7?Nj4bvi-TN#>mOahN3Z`9mh% zW<dc~2!yZ$nI|<fWQ%O*-knErgwLv8@;dj(bHJ7zaP-q_wR+=m_#r^7IAx2^K6X?E z(`A5eIX3JbAC>+%TvD!kIe)ajU|G)4_EJaGu-8eVyBQ}<ld=-9m;sEFjNWBRjS?Z; zoGk)1$E@*d<>?U?tEM-{jAaV}HzA+H%yZB+*2R>W>p1P04_iZg4s3m?oQgE%=9~W> z`}cfLZRS0ubMBO_NpJK!$jtXlZ#^@;^is>WS~1Rh(3{C!+@@N6g6X^BczcVrN?={R zxuWQx?{8gMsfVf529yjJ34fvU3WGbKndo_XQb$wx(a3i#HN3S0oXNe{O2hf4-|SQL zxd$v`_}tm4$Yg~qOI!Avf=}Ws-wHM9Ca?9ciY9B`u&Q}pp@j&GKH`vw)u0PT2S1i- zUizD|tTGa~@sUearB;=b#-3cEV^%?DNF2A%Fxs&_JyeH^tVrgK!X-=a)rzN#GF&ik z(+F}?r@t~o4VpdA0lwVC4rlVAL5TTtc~T7MhLPcGik&?&a2g<uPibcNzt&%yZH-BI zmBe!!OKOp%va`W;zsD}dI%^O8U0x1p!6E*kBXVMhEn*4MQYPN=vRj`Ubw6;Y>m@{h z3iR7j_j>Srsf8zPwym?-A~-z$8s%G4k}h9L@$q6njITET!1fYZ#W@F1KR54*R!iGx z7Wz}7UxY<KF!p{+U8DWZW7zoS>R%Wao>vV%+H5usc`{98c!*KbO+Bk0qLSDft>^GB zSp3}ItCrXl9x2(@viON57OuIl_|N1Ez*771T=r}*b`GXTF4gT*Y4RIJ;w6P_bI(B2 zqaa<ZS3I^+l-IU0gu{Bj7a(*jB{tn;X5B0>;Hb{pJZQ+XIhGKuA`xaS?+zDYJ?208 za<zVd4>F3)z||PU|5B6YOiZV(d6AC~)QQLHku;gZ0|ry;A+@TYrt}uL*)e?LYi!QX zh@=;>43=BjZl*d4LEP!PymI$yngv#ujWbK}l4cw<f$P3gWYCQFp9-SySCOFoRFtx- zh!HTwkiWh6x_LUkG=|#rJX2JPOU?2<7#B#^_dlWiVo0XdHZ><Y_>`oP<hZl^Von>5 zOH5*7N+yRL9ed)<4R-x>TCN38MgoiYZIM8ODjp&$!B;afhyBDpPl<XXNR8IdQuK}k zotQtVjNn^`ZZRnnfbw(fnf$x3r#7Hp*r4t*K7EHdh!*}16@m24kFLoIM9@B^Mo7zz z*$%^RFnltz3j>WsBW}*0nUPk(DQe1>fQW!^QhqyEOffbC!00z@s8xtFqZa8%AHakW zp~PW<53axH*dOxgVkiTW>Wgd>{^jcHk5o`*@`e&5yWGSMuM7b25ec6Nc29CP9Dj69 z%m`AVJ1ki?=Sr4k5|;JbnC`CyN_+U;qH!<0azj1q%EaQ*38Gf#V~T2%;fb*S;`crK zqoja38J5WNi|psg+L<pVQK6aPZ~fV5#%$c9hbKs41TnPuf1J78^NC`?CK}Rl7;3=j z!vWE|a=wEHJSd&5$2ZM0<vJhlv}G9%kV9<vG0NWolkrK(j~gROx0N?VDAe~ruif*+ zxH@k1l7F}MuZhP#==01?p)D5;$#?RB#UE$ufUemG$*kzaH~P3M^cMXk>dR620S@)i zx=xJO);Vws9V71&x*iY#v>ho3ebsYy5<QFsM1ddbrc*Khz8f7eE<~+3B)MaM-k92H zx--E$lXmNw0#7do@9f?z)6UdC$1kTtc+jpi*xakCVl6{IQn)g_Rx@#M8F*3iWL!Vg zbl@F#L@Ad<d9cUu-TplB>c@TwimX~FC@C@eSlEbohEJEunPMqc2mu$&<gC>=B=~j; zkcK)H#4fA@^_a`-t5yAH200UA;h{_BOh1Vv^zS!*?`UHgJNGv;EP>>7r>~*@Q~H$w zwp5*WX-s{*j7K&pdKkJG(KT;U7Igm_)&VMOLFOhZjefy0OBIF;YkjU}cXUCBc;H_S zIsWxrJ<EMHQR)g3r+8Y~zd{(^x1kwRZz$R+7KS4h=o?TITZ;F(%w8THMRt3K|H`yh zFOux;Vp-Qyd!DA9geZugt4xBJJ=Uk&<QA!gh<!&C<?|i>RH$3#xj;AM6pxG2&pVJd zTrrnJFHHrq18tG1Z8?|P?+wIzJZ`o(K9-V0w*UKbN5&_YgR7w8g6v_vs&tUn9f5Oa zE$a}O(_}ZDKW7A{Wlr;$$z%lRRe~#|!ReU`2@6$n!j(VP-dq}b-NL;!@#EtY=}UfB zjenJ~2P5j=J2nN%Ew6J}gt^B-wa%Kqu;K<`0RQf*rxERWLOvQ?LdVtL)}?wEg$Kan zh%6oK#K^TSXdptjfK;K}`;nCL6+_w@BwcV$9=Iu$icOEi=6rt6@9WwrahaX(b$Qxj z#1ge0;LAAFzmwUO5?FeBFrp1`?z;}b3-e_RlySI%2A$pTP_Td7vT+j$gy1{-V;fzC z3W|T;y%4V7Lnt~s)t*PK3%4W9XTmE99VcGgT*RaY2|rX!Y(CWX&W&W|o}iFo*1!$j zfjrN~h%UukELzP?l3FgD)-(8+TyiF$4Sdk2|N7<>wF(oMRuhmBk7p6&&ad8O3peX7 zP|j&ISNv1Ty2&(rOl$5Pgn1H#dpBtVSn9zfWnSla7G5J7FiZ%5M<9$XB;h{!DK=T~ zV)_~Fq^G|3>+S80_7Rv&Pq9=&x=Q_V2QW3^ajNxN3b*2LyBX{pcv^Zi)zK`q?T!hS z`>21`mHAvg3`E!{V|=KXvM%|n45Odg2-_@85A)Is)Vo{V#zWLx<U72~SG{~%rNB_p zGhT5fJ28m?k6Tm!QYupnme$U9{8VmCcyZPcNjwxV1KjGKY_K#f)SPt!heBnt>^xJg z88E~5DG5AdlKSbr1@MSi(^Pu8NbpGUZev)0koPu<O^*~vgdb$ITd8waGGwg*HV6Ha zJ!{g}0OJq+%`;O-|7i*6od(6-L;y$xx{`D$hLxqGMcar%a(Wn@r1(HCCBMX?8AcX` z*{tQwuvq3{4Q!QR_FX2E97HR^33l_oE>851%=Gv*a#%8d3OHU`%9BD&j>ogNm6FMK zgbJqhd-l7peak7Xxn(bztME2waQo;DG6-vi2OwCN!J_N0%NyfJp#$l9!A(kdX!0&Z zhxOjY8nd5jO|h8XEXJs|Yl%fE^iaE0=v;v8(`<INYgsPMFymU7^Jp24!{Ae|Ri-Ce zpC$7o-?I|3xZ%(k`w1!GG5y^Et}9FBd2jU};FD*my5Dv?CQC^kgyH#=(hBO6%+hqh z?u>;(>umBJ0n+1UJH!Y=gTMnLbd|+PTK5v49~3?}Pt3BFhuP3flABrM_oz>N=?f%y zcz88;J7;X^lQMOZzVgtSp==V4RIFC~pC0GJ=v@+kd(d?|MTO)^J-5d?f-y$K034zR zg4yHum6{<fwiTS;NzrR{yZ|8?1KDclya$y{VSnk?bv#IYDtEU`T~(zp0k+alS8T}o zd%vPs64|=+AV%4;haqyfN$0Ly&p~n$&v#Yc_nv&wOksnFg@@Zs=!pME?uAyENjwB6 zDKCsM8Zph&@&+05Cy3wJi7{lv4_3Q<pmMC=GMR2Bw4_~XDeDTt6f5m>Ms4l7nyg1t zDEnl4v#e7nhj#j)t0$YkavrZtridCMjv@VuGwb*X-f!Hm3#fU)0JkU6KAeeuSr5k1 z(^UGJQ>c@%UF9#|+g<FxnS^<0d)Y4R@i>5miq;vrSK8BT;1P7Tv!4`G5oRU^r2sce zG6NSH>`;J7wP!w5i8UFx{~*@*MNA!uGlM6YJPpL2g2`m%_cy=rhG!+9?aQUqb^0%U zMr7kiX39#3>*`rA3eupyucp<7rb$9Sb`=w-&s?`ULOyi-eC?Et&){4vPR0Xw*NTZ# zuOyc=oSRScd%r1shQLij`+`qYYGj=$aF|Wf%{E5_2S}NVWi?7xhBc=E2zYFO9q9mJ ze`Gb<m1}szS^4usmKcZi0n|SW{j0*!GG9GRhs4Pz{fCjJsZ27_Ao()zls<&FtL?>x zcQ?#gJb+Z2-O7rF3)z%eH!~Lb(Nt@*AsWmvS-HTp7ZWVZXV#?>D}N!6kvXJ}Fb#uS zmb);HjE1ASI^W+NyZ>SV1OMI6W~7^~L5D}q<y7Bsv&eXsHvqTPwK0j$2^&>>tH*ks z=y>?7b>3JS9Y;?`ZEJ-IvnCG;-^jFPoI~6l#5n;*RS_O!PdN(NVXU2JyNvBP=q@~V zAr(kp>C*khH&bBOn~p&t_tIt=PhN^;85|ARV?WL*6@CxPPV#&NH1}v)$^O`d@L_Dl zzo2&;=Joy*yd+QnGZSu75|?DNd<2IrswY`l#g;hx^)qRiJC&tUO(d=@;SEDT^uA?% zx_7M6=dSFXRMHp+=Ql6K``P$7W}1Y}yw-u7AHLD(bapK#(9Zw*u`OZ=pB(;Nlq6}N zNzG#(l!Ww+3*!^_%iumcuB+#=2^SbVWE?`dFS+>~2b9M3v(g@T&+Ulll!qPK@80aC zp1rH~sfa*|0tKOe()18O^!O8+=R3BF6kUC89gS{+*HR9RPw!22KdI&#(80d+V7lX@ zS_OM#7Zp*F;aXO6Cm0AZhIkvdYW?HS)j;$HPhB=AMRa-X?%e^JVF(S)^9zVXA93xl zLdR&o)Lpi?-D&&qk&D|;E*8!4_BfQbgW3%Wxr3$p8zet|j5U9j&6f;h*|Kz6X)jOa zY=dlJKzcC;(Im&)z4qDPDTbVW#*j*}MJeQHcZt*S8<r$LT}yT=g<a=fbbUk`$SkxD zOSKwp1Irg&O)^3=;p2Y2A80)X2k7X4GE;H(SmraN*F5oDV+Kv+FieTlTG`{UH477z z7EOL9K7K4vPLQ)BPvmC$@Y?BuRJdmsNvC$L@GAQ>-TExzLF7br=zYq8S*r7qH4#Cy zz?8=|u4cz_sB;j{IQp5#HL1?bDzF#vM!QL{-(Eb8I3D2cvEVdKlk?Ifmu85Ek{W}Z zbzJ^>MZ}}4^bo-$#X`loAyTjR=-devPx%L2MjD7S;M}?6AGD=V>^@1Ea}$(eo?;+# z9Y+${<q4Q$vs;l!oGx2$v8A!GLyxCglVGjMsZUUgTK@ix_j%ep;mQ6Ff9^V1M{zpS zacLn#TYeYB9&=*Wlfwc6ABR<Ep-tMU;vKE&QQC0pH~oj^|4M${P6sVBXYu~gUKy9> z{gcDy1ya_tiNK5`gcXyNO#0sB<wt#Rwjm^B_*W`W3a#GYfWsUrC)7$hM89Nl2aMKj zG1Hi`N-0G1RL5zbzd;R&wG-~EG-mFtvFfiIh!8cNKx+CIs+DpICd2%)XjV>dnza3$ z=8!X|_r$$A#sHq!jWe_~;_(pdt;ysyvF~ZY&e3f(Qa-d9eTnwKBf^v!k<D-}t^Ncj zV#t8~6vwDcM-Z9xSC#o<clJS50Pl8aHUm{W>X+?E0%ZlCzn<{*W@_82@&y2FcvAYi zFt+b^fLKVfveSk+Y%!X32Kc(7S!kX}zoGf*@D&Wc38q|t-A^e^<5o$#Ktc>2IVg3~ zD9Y(r!R$zqcz^{hnuUb|z+1(#X`*Kfl{h5Dn*nNid~;8iT&6-3N3uG?-8m&?o7?<j z(W^>|RqlC}Cd3j=!GGF2dCmI|#^l`7JT*f^+>|gF8nUd1Nns3c&dh50vUe1@-Z+O4 z)Gr!T{u+<D$Pr#(_>cXv_IIyslvsP<L85apIon@Z-Y)ssBX+CE(I1i)oWd@|6e4R# z09@Q*C$xf^>B&`%p+D;noMYLMtSD4Bs7Wz%dzM<2Z-KrLrIATzy*{@|TT9lJ*bW~d z-J4;vs+YLTa1%bo{%=G4_nXMPQRhQ}WfEs*RD=#!k9A`xD0I01(X9_bX(Py?Quchi z-ofeNa~}X_2=^{mZe8@EWGbM7AZQ;ErgkV*&$|)kPAAzGu4P=jfv)<M9x}&g@H8(7 zgx{I3K&_5Kd^U`<5My0%XUL`OFczg_C2scv<Ave*76=r{`y=d2^!dg}8XMgannFqX zYV*6(ti~RX*~gIxqn`KS85$c|k79o-YrQNKO1n^LQHag;(;=Y+CzF|E-AfT~&cM|+ zm+G4u-N_FC%=XWG#iBFrd5Ssy5u_)Udj>Vz047bJ+1>R>j`ZlyQP3AgUIa=Ll8G$3 zZ-WaaAKDTd*b<WmQNZEj^9T0<*rmd&*AL{TzU~kEYWTC938BMvH6uzrh5ejJVP?Il z8prGe@=S`U)!J-T0wnQM-@+MQLrnEZ&$WEe$9D63cMFi>2{9w43y=Sb4n5#BBT4y{ zzjN|4p%1$>eO`c*04SX2M1V5B@gyYTDiWVrNK1zwv%MRzDK(retQE1omM^V)mBHZV zJJwe5xbQ2~-j2;2`xuy>q3QnSt{YDpVJ#Es+>)bborU{f9yv+u2B?S@-Aig~6X9$h z_BhErUx%)Kd%~R!zxN*3Y}j6KFn97qb>hc&MOVK4YBfdi`3$sP{(W+xmvCkL$VF^O zPW1eHRHyo_Y<idhG08w)Rm4j;bD2uE1@Ec)_hzzmB|WsK+#xhb8N3MIR}V^_W=-P2 zw~6+UR~arG_|Z~)8wB^|@`0xN<2!JN+;bBhKk5M5(nGZof!DOK{z_p%dF$Opf5^LM zh9y7c8om<d7e&leZ|`njG3Rk3=zGTOY^_c=Ik$=KA7^_Ocg_82ghDO2JRXvjbN}ss z><V3;$0-TF=Hy$*kFcp6wT9Nl)?&tl(-4ZG6R=JUn6-n(`Mk7y=5WbQ1H!bm*ZqW% zBb=6PeB=tuQ6A*lUu~%8Ph-vZ^+^qNca|yOOH~JvEMu}{T?ILvBaW?&Aswmi3(kqW zCU<xh9qKm}Adf+q`5B6BQCr~gI)Z>)ML1OBt$agvapoz=2_B+6&-mV|-*pt<c^!!M zXTB@Y#YgUWkk_9?yce^1i}ALOC2jz-UX6}LzTrhjH?^*$Yns`_3zn|rBo{P@ei!oB z6+_E#X}3blZiT&<k5jzY7a!~Qe<(T^f2RNU55G6VoMvO@G;Gf2v&`|klViv+hg6$W zPC11TwK3;IBb87&M<GN}(lDo}oDwBD7LpuGr;nfCAMv^$kJo)apVtM12ZAiY95M7< zlkf1g2Nrcu2;UJqfhc}^#4Dsh`8Lgm2MJ;?jt0W6$7*zlN$uyBfty82@P!T}YhWjF zw><o+ftPzo5Txvc;q^4Hk7>97-`B?LWxdh{`_=}s0ioZ7@bVuxn_wnhzowT=-;Lt7 z>j=4zEQ>_G%EHZcV!RvuRXTdl5Dq0=EA7jbDor27HP`tTuw9@CJQutcPOH+Fkss5@ zrsWUgv#`qg6MT75yviLcss&KrIio+NIy30q4ZbaR-QXoll4ZD+h;uAFykRk}2-+B5 zsQGV7DHC6eTF$N?4nSqfd@GV-CEcV~ULTp~X|=zPTqIrm$ePJ&JC!O}m3u6cbU8j? zwQ$0Vn?s>&)aWx?;Fsdvz5-tIao?_|i4dX5%)9k(auy8wAhfGg*-hoqXMdtxCQh>( z$ZCX-)|b6(e>Ur#GVpyNCsO2|mNFN#2`S4}&kx+am~n$7BKeH7nLplk{;Hgh7H6uK ziFZ%x_A=grA@}<E#)q@-at=B3F>s?;(j8mP17@1tq>s+xQyH++wFbbBhy~$KgX2Za z2{s%Tsh&I)kf@B=$z`;!jp)e?Us#-DuTT<ZaCI_8%I<b9Cho!8r7f@-{eZ64G&H<p zJ)UzZP7Y9Ezq`VCbfa;SWQbrKe<6#9cdW`uTP4bR)`|i=ka-X&qT9E|=|v5l9(J2n zwqB-e`2@#j46^Rks4=j_dD@}(tYMpvdn+Hfa!5#qSh?_y7e|IR%k|h;2}Um0M*ej) z`)W-+_Ss*X!O2pZ)X6<cjXwX{Eq6YSYE@a4uTr>Lef6zV<_Vt)KHIGnd9}<135}Mz zbRIGUybWk~Ap{TGs#|Vw1`X8wHekv_{kS|_POnK6JdK=bDUvbbRK@v@Xs<Y7_9zbJ zTorlb=YE(uqYR~g2U0N4@RD_`)miy&J}aB%Fz2AGxxJ`CAXE;x9G8ykBuTkm_CxPC z$(iI6Ph7RG#)4?bq-64wz@|#Ab&pTF1{JXL%DzVcwNjjrs#A^iiqr%X{6+}+jKjXQ zQZf=n&_@6!@%m;xYff?Ctvq7&5@`v;W4_{#%+BRN{~qkc3>6f}Z2F<iwuj6SkFX)3 zOsDlgt8(<1Lqwsl-jpQt*z573o4n*}hpq$LgJ9zCT3<IgW80I*Rl5N4f(?{{=Nw_y z#l;<-sF&7|e~ETtI>RR#d_LyfEsG$gPrI3aprqmFsAlF8eoo&qY!0SV+M|OfGV~Ya zj7y2fC;!SDv1kLf{oH~P4Efsp<J6f!ko%L_bpLN?jWec~io(ekPO^@k^_>K!?sJYu zO&USC|7P^75X<<O=jW{yoU`<GdY~+O`_P2AT(HD`;nCX0e5n7q?MJl|DNq&u$NQ3K z(*kpOy1PNAoI-d_y|0tSK*2^-VWeY($#&?2)63M;Bj{AKr)7N?5DDH`PTEZnE(9o| z2@GtCW_^biY<Pp5|Jp)j!+3q^*+E&Z?G6}lmbTAHe`c@c#3gQ0L^Z@Y!(G2c{m^WA z)aX$7#@ieh7uOgzX4yru<$4PG{x|D?k3oVLXdYUfgQW1V9MPFOB<bd6v9$eRfUfLh z$lu%ak7y<R4}yWpN6`83mb^5tVF!%H;M+29=kuP#kqnywV_O4w(jFPpod0ckeyq6= zJ|&>>R3{RBZenATEoE>2>Z)@8nGa3NQbiEy+!`gB$b*hcF*Ah-gN~VzcB;f<1N%FN zb`(7qhGgmT-oMH1yzu2?fDe>~RD>tfw@8wo%8HoTg=ywhW5Q+TVeMfJE-Cx9@IA-6 z6M;|P+Wlj`1_iFVnaOsRv#|Z3GTZvM!+Gy`ml5rBD-#F1O!FhFU_sVltY<)d0Gq{e z*Vt0y%sM^v0VP5GfEBJEeLFt^)7G}rHESdr@;qXBN`S|s4PQG3^RIs5?#oM)e;V^W z)0Tled*-EbSLfE%!0PlD($-gLk5ta!E8yUTegnQJkt7I>?Kbw=L2&%lPz9G1B+S8? zx9y!}tf9eDfA&eQ2U786kS=A8>ad9?5xrz$rZ9Db9Te*rE8hp}nw1gxwVfNjdedF# z;z9T|n1vyaJRSs)yt-=l%kU()s32nD<u8-(q0JB8_U(=jd)^_@O|;U)?g?@)LOaYq z<kwPX3>PzBKPy~1<NxPT(C3hwg%qgFql~msYTQ>#QFfL#?alO|meqNZ2!q3tb^F4o zfbuF^b9WeWWG})<Of31Szc|Ky8m+`^K7IA0IQ17fRsvljdtRtspL^4(x1w1*^^w_n zUEE1wok--YCPO15us5rP)RHpn`ZJ#Xfi6JDlz}*~kQZAX7pIhhTsovu@Okq<O?|KO z^t}SLt~Mq&5#A0*eeM3AFTC;EC(LrY=mqrDRVYLs>Gm;{oE0>Iui^};<w$_sjdUHq z+kGo?n)&>#MUViQ$#f5hLk9pu-{x=P2j3moBW*Tv@amqx2<TW-%EA8KQGokW^l|to zp0GOJwt5^G0rS6iR(7<Mar9i<$5@PzGQ0;0nnVZc4lVf3vvaFSA(&jb4RY9NPHu^G zjKM&r0K}la#60JXzeg_`&NlKcJ5?_V?M}f3azYAD@dS|Fnn+h?rX^7>wro<ma{f;R zJVZI)beb$FL@f<{`3}Mw93+T(u+ls&q_Wa4BjGBA;6toq(U6SQfeRx^T)8wE<HhJ< zSYHjz#}x@dq*E_|`sATxoVuW+&f*mo>7O!00@?FGYydsNS1fgFFW<sMgkSQQtmA4g zN|q~ri?W;q)vg&&qLI?$XoUHcZitVP?gRlrMxqI@oa?Jj&=O{{DnB)~;kEn^n;}nG z!laKyAkh{<R*&vUjh_sNKJq$sW0ntzMKKlPXVQ%ar3tGk#b&n%g_2gwp2qs=<`{b! z$Av`iR42B*K^y5mR|a-Z?vnBuPrUr%b&EbYqsr-HVjLy7j%-|JrNu7MSGfHX4-htF z%K|O<wh_1kE~7+f!t+n(n|miY0bXAAf9w<!S}&jTki4oep%g6Ue|jQuScBaoYYMiW zV~ds%2%SB}d)L)Az-U^x<_J+~a!B8H#B7!Hyt&+U8X-LhHY69OA7pItL(o+|KwOGG zugHPvb^oCot~(!%TDfq3E(U`yPZz#Kqx+6=aV~^rb^PO|q{-XO=IOMY(T~A%Ao&QT z=m~FO$`r|L&%$`t>Q&~UxC1XE(jIbdX8B5}rG{S*o;=H-yz)hoQKd`dtU~8RNX;tG zTx5lZ0oiu!vwPz;QyjNT`(SYp$qra1G^I$6On=K<)?Q3I@yg$yZJ*u52&)HW{+jbS zNhYa-l?u=|L7Z3~@-0uUsz7ejM3OFwXVk_*YmcaMzPPiR!zK=Z=mTJ6Hn$@oeB<>< zr)#=CuR=y)SinnL?}=Rn@j-jYd7qPgO@2wGM7r~<qd2Cs5L<3O89#VeDLPp(8k~U| zRE}N=V<h8O6*I*lsh5w_FDpbeFmf0WEIp-czS~~8SAvN)yDm5pnWb-VH=&)B?tyx| z;0m<n#zY^oMO%qy8DH$1a*k!BT!6ejJ)7Ogl6E)B`fIe-XfU_5PsB0jrxp5iqVW(U z9)Qx~O~*v}AubK)Aph7ksd#W49nAt!XKhszk4q$SS$~u%GqsoR3LrG~;1esg+j#t~ zYb{y>3Eo9Ud6Oz)>%nursw>GNrH+B^wQjVlYKu}@2XdDnZ_o4gnQzV!bm4`jm{Kl_ z^wBfU+75ts<_Uku%_LCfTaKt;2&eferLjOD(5l8!is94Wjp^5ZdMn7XD1wW|jbm|O z05BY)nLnIgm3=9Yd?#VB4pr1$yF#`Dzpxu=sYzew?-?s10{qyHQm{&q9Eg*p(Rr9$ z9;;ABObsT2!~>PpT8TCv!DuMsMbv%GlR2hH3LwUDY;wvz(dPn;A+>cH#}AWxylz$7 z8w+DU?y2C8WLxtyT!|JH%h25z)WXaMs7Ow<k7XQm=~TNP^mUeh@NMDv*95V?w$}cp z^NidyYj@B3f2MDr3b5s^r8?$b%Ik}rKE2we-J>xHR-+{|Omp%4{ua@4Qvv6L3W;j% z;7lX9VytVG&_+rPDZP`-j!1EhCqKOJjO?KYg9RKBRtYS36VB3*c3DSl*rkY|lkEc7 z1JHcyH*s(tft5C-njslVA`>mpKg52$MK#q10sMIGS`o1yyv7@2<j_Na)geTPJ8R9u zaQ*wKK?>ym*(L!MkU#3BI+^)acQ~X5BsUM%90e;S^cb2KRRnw^2Wo8PW%nWmQ=sI= zw?c>Cf(X{77+KG=p`#TMc2-rjpWX)-c20>%aL=t+K4tmzSxQoFSnf-ZW5BP+Z<F5U zTkO6P>#p5Mwg!h!&si9s0iYj^Kn*%n(ieURL>Vu?niB1u?V6ZO`Uv6ud(;?AdFoen zDv8trV_-1ots$GWUpy0OLjeHuQ9NHYioDgr<BiJ}X$OsGfK|(gZ5jDK%G3DeWJ6xr z&0oHbRe_uT82#V)h%je|`G=MOx1z#p1)QxBnxwGGsWy1XLHUtyJWp*Z%w&5zM|MhI zukRjFEwNTiHH6;AyzCX{CtoIB=i6yIqb@lVNft0YqC&H{(U1#C9JpET2do=mRf_`Z z-Gsq&1=iN_CmS-o_*D0r3Ap<~`s|c;@H<81Zr%{*xjD<l3C*e%s*WN7QePRzjL2xV zz|7RFX5m*;!i6F`qt!j*#(y}FE0rVUu7_9!a?0>5m)Q-WesDQLt?cG|RTKTiAKt}p zgon=~%Dg#^*ra#}>sp2;0SOXD5(w%56aw&0(g=T91PHg{8@m%sZ~cR0G(SVC@{@^U z=6VLGn8x?0v}Ze+t~EkbZ36RFrj^WQmggNdnRWT<I8E<p?o3nFy>a!bB4o|Moj00( zS0Os-%oHt5PzFU}El)7CUforhzrZQ;(7V35<J@nW+OKM+$XdRt+Mq*siYYw$QWFaw zni6ookbu8%t*Q)<r0EMX45~O}jP}H~PZ4k|#Ps&Szag&l{_XWTLVKlZh9&RaG*z+t z|HW&YpM7m|lc>tjaM#@LiFu2kuFYeJIc{AL5GJb@U`B5tPx3%O-?OdXrr_`#1$i9C z5u)RSzSj;68^;`f?Oy#!QUo$2q16(LPf7d;Su#>wPF<^lW1HY?07CoUU^RrwFdgij zk?%9qR<~hB1CuOq8Hm0hJGAuh#M$QT86mdNsxF}_JXtv{n5+JO|DvyNX;#9>i0s1Z z;{Jd#FyH@F%?30-V=|Pz1wcW>6dQwkGb4neaw~jqb>{5F!fhTEJ7+(w;HuuVLfsiS z8IbD_khm||nqp2Hlr+u3>1%qo?%@9xTkyWpcJQ*w7C)tZZsoqbh^cLdDUx8CGs9*B zm!Z}#Qu^n+L4srfS{R_ei=THfc*AcTSAZ@pPLCiZxLe_z`65Jl!UZ5|Kue@@Zg1*0 zJY)E|rDGhw%VE;1?l8F8ke1`%o<(A>Pi#iSMD%r4q~h_^0CTX!tnb-qfisRO-zPb? zEcB;X8_$M9>7o-g>_Y+p4*=T9ovj81kfG`5yJImeorN5|iGzkkBqQ2If%<3*Z|K*& zvEO7-!|+|Nw9Kz;G2aMe$81#S-87%hU5>~KkuAD<#_4hL!HOM7X$!;uZ18xF%ZfhE zq}bX5zksjZtU6%ts9#NFr5I*J12lfT{l>Z2ac^>FSxGiQY{BRtuBdh6K!Uv#6>I^} z@PR2U+S%ONfLDX~lQY<e)=ws;w`juT2Bj2JMlbp2b*-W*d>owssH9qFaAfv`EyWkq z{z$#a72<NgM?9)J&uNWjiHpVEYZf(E;V=#C^_<@)^Q&7<)1RWp=_XHt(42-j`}k;U z=V7b5#KX+J#Xhq^$Ywp`$sb#tDXq124MYzh^6zHd3&4P)|Bxj}ShZYGxzo*0)`dbu zAv9huNLr#1awrDaB8gw>wtUdXyq20Ky$%A|s=`(OMaq%oU4n@O)!=rqJ_nhq%m%mf zB_z)>d-f@k#jJWs)*wgT8*Yz!4%1fQT19=rp27}A#3rX)9r^F)W6p>otkLYH)M?wA zzG~Eo$~<94pf5=u@iRGNGzV8nh=_88X88+}8-yWdlfAJgw#a?`>60WX9~nGIZ~sb) zA5K?EwA3uhZ&QOR84m{vWwdBnD`8#*Iut51UB`I_S_wB#E0d%rQw$w>KNi@hvkto* zSUv;Up>;Mca}V5s(1^Df@AT=5QpG8=L9oxGJKtt?>x9`a&ba~*^<`O`Uv@5lDczgg ziRYh=PGWa@lllE(fytg@=r}7W3*nlxz_iY-XESVyHq?D+91^NV&S=Lx3w=l=RV`{1 zIc><nmCt({AlQvhZ5@6cfBEaK-NmkgP<i9o^U=+y3HRUrp=S-qZYI+ZJc|!LKZy@t z0@q5mGpVF>{uxfp6Xtkl!peBVrS^PZtE)1ESnmrCRI3;zgzUy!HCj7Ui`rjkbS>aj z@#keuV7`nhAHOnU(P|XEYI6}fTqJ)V{t=(lj_Tj4eJEvF;ocl@J!tc=@-aYcOFLhr z>PB*}w#}7Lxbe-(9mIxgS!B)=ovYq|mhzZ_*4q2;bD?I(CMmt?`;DjW!4~kQ&)PdC z@4peyk6S|(FFhR<y?Yw;zTD)Zrc?kMb0T=pxM>dW%fDh^9{(F#4*V9n?|ZS4`hY&) z>LnS7Xt#Wy#;1~f-uWXr@lnM-ujq$^$gl4nHXa}NfCU_;7pX7q!%iRM&VX}#-3tPZ zUx8}kA>B>4<NkPd!}fYcVK3+#-&0g_ZG3DvHQK<fYuACNt8$`_U`K`SqRppjfUWt5 z!5$tXZ)GIJgnzqfitD#La2^t@`oPp~_*+#$T>fzJG=PjOKhAY1qznjguLtx*KFvQT zn}N;>N6-5?hhif?chnTcFN3TMC7X4Z6~e`mx!eD~U(CIoT+9DRjuS<!HP(@dQc}vB zC0O;<zh=KG=K(8IDlfcLId@E7De=usAWtlVp#T<3kxA@|zxF0ox32HHgY8U&Q{H^h z*Lr6~|3DIpLiZ_f@$UYr3D-MPoYTpO>Pa_(mlhD{eQH;&0mTmtr*+j0h#KbcV2*7b zr4EHD>ld=hBP947rQ!-!pjv0o3*9TFm$ueOUkLV#QSK}5NxzXAXsWJc+G_7Obu{`h zG!B%6^9PjFqC61&enw9%<~{wQoUx4RJ@eRh^@~mWU57lhyMcRr7<y_W4{#@0?=2(? z2regIx4tV9SLP-r8{@{qLG#Bl4W!jkY0jq~_?;J#NGB5u$GH3G#m`?pNgMCh?FSf= zO1C3}??gz&g}DWkdx@_1qmzzv>M7EO^EZYP2Au}yu2Utfu(7kxHE%t%?)k0XIFH$- zr^3W4s_%QA{&Es(>e!Br-sw!}oJ3z%qNSNt$N}gDBijx7%&*UqR}wg*U!)#v4-B|{ z8)RR1<k*UHcGu^jWYGh7FoiGOG)22xY7SzNEH1&X4Rj%QgMH_2&k1I5t4-nOvY_{R z^GC&0r<Z`O@U9SLaqJ%RL!K1W!~EI`V&oI`FnC%bk?1nA`7V5|_VyPrMdkS{T$o#` z;jG~ZIy5=~TCxJkJM}TO)ApXK*&~hhzL?o<110>K`{(}d^c57xH1$etveHRE^q`mV zq0Svp0QuQDyUkjaEO{TUGTH)Hi-3ic6l9BW9qG^jNA)}?jl;&eTC}b=VSid&dmbV2 zm?dZ45RaHxZoUOyQ2{>F29AMgd>$I|XuditT$4fj9qe+#t}{|^)#++Dpq`3}eDf3b zs3&!P5x#5f^zS~dD4~;dBGIedG8##1x0p}*qRSsJx}E1UT_KYzmLbh-g2QnH!Ar{h z`m_U?+0<r5`YhD^ae0a2`*ha|_~8s**@>^yBaeitcLW?oY2nnYWCclV3e;2Brmlwp zIykPZ6m5A{T*Jy6B<Iv}Q#w`syB;{cx&;O1p_EoiH|zTVT*{9V=2wtmp&4)5WlMed z*=Tzs7m;_EVLDKM>h^Fx<;<j*H+)GdQ&vW`x1b;3r(l6Wc5&FPmj!H6>5+vx@`x&& zi(B9YMR19tdWaD)%lx%gLCQRZ+hIgjq~d;dhI*z7%Y!P+0rFHbP{i8UVMQTQQ1Z{U ze0{$+LE_IHj+KbWga+knY&@8W>Qd2PDys}k@Ew$oo$R%^aa@^m%$X!R-bOF;tyy`H zE{VQzqF9HVIPE&HbJ#uxYxp%$i4h+NKmxS%!6m6-K9}IVHf?XIbkqIyG(U-o^rp>j zs@-{2tM&yZ;TyNiBH(d?qbl>X9hPysWSO8=)ciaeQh7^Ogu-S)y{mkZ6U@GnP|>QL z(l?H+iw_jTsJU1E4b<y3OOS$p$s%sc%bpQGWBPt9Ppd2fyH*=ox4fJd97@I{`cAc) z2DhTRmuO?+))n(!g@yd&a8|saZ_v(%NL4$4uRLwe($_LkqlzOc#M*6Hr3iHFfd{Be ziBy%WH{Y{NlQQBqu2ru2pFou`=kryi-QVs4;wMj)fW^gRk$_Y4#b<no6ovKUlB$nu z_;I>5XF9tNivamBr?rEHPvEWG0*prC#+Fr%>kqpKx?JZue|{6!am`*bIb28A%BZ5` z?6-J%D38Nn)tyWL0x9EAiW}(ttRTGuTtNRfZOs8@eq7*ZOW6rWhEXJG3LD%!Q63o; zijzZL+C7C=R901#bp(7J7m?-1nFHpA%v1F~$eSDUkDLiD&qsa^Acq`pRX@v%oo8HM zZC|6(++G5VTwBU7MwCy2-77Ft=ZUOp==W~^d@qsfzvCG4>)VeqMk_?2zEjlcNX4x? zs8{i^86ex3f_VXk9e5SbJ<=q1VKRF>G#-I_FD@db$Ch2=*^Ui~J*Iyis!`{08o-xl zDIFf~kr1qjN;l@gW)WT@_fl=FjL0a*WnwdEzN%R~+lWg5e68_8w1-!0CEf19B+1B9 z21S%8n;B$r(AoO)`BSMZSDATyRLTs(;1a)*((!LUUh<X;hPO^#+JQDvUvI;_*{f0( zofj`Zc!r2L5qxYr?%aho3E)a%WpKyJJt9$ZDi7y-Zw=d;(IBzy`Bh~0E|yQ_%r-P+ zBt!ItLkpFAp=<}newpHus@jtHEpHk8-1yx~-%PLVuk5r;Zb3V83xW^LiD@wLh1zo6 zGXBx2D~G!BQUA!YmWSQAbn;22F>`M*;n!ceN81-j&?dNgyp+j&ZF<D9g2@Xx9}dln z-!2euL|V02_T4#NVN%>i9ZXyGajwJ7;PK@x?&`8qfm`&4`L{9ex^JS&U50Ce9eyBt zdWwsm)Q3$kDBk1*1eryjpPg9JLu^L`n(HDA=do9@y33o4oO5K>x>}U0SgA5%a9cta zcH8HVg=^v~eY5X~2QAsyB1;(|!)L^p_Es#fcK0o(t5QE&ttDrQtPZ(ksrp)ksVr@s zV(m62ThMQN&VvN10)9dE+thE^T^3t%?)WpzcvODZy5#(jaewx`icRzRRF7GCpaSq_ z_6_t{dpUn=IwP;dPml@dzBIqE)GAwomouNI|ITR~AK%1Imj4i{IvmBu9`XlKi`9gM z?9f85EoGT<cR=3tJzuOb5HM@-K>iw6k4Q`Xzd6DG{w|<u)px<<CSG1&P2Tq>Kf4r! z`~3L6>)4~yqXD5No1rw*?fCfmz!d%DYA&Mq;OfcwGND*Vrn72cAsPKyAZwX^uaoI7 zMmpK9iEat!xT-o|stLLmAr}?|p(}Bnh<GDi(c$3doEZ8Y*N6>{C=S?a604Py-8ROP z-6VoBVO%aKL3A1udMdA5sERKUdtuP7tJKkVeEz?FHNg10;Qx9OXkqt8L3)LL+D(3< zl$X?50>^ibaMNLT<vcx#Eqc~>;)e|eY+sdJU$?Qs*RBb$s0W8&>ynHGj*shXN;5VX zGBM3L!S5sRHt0kx3!4T=BGm;=$amS@3X3V&A7OIIerWdh`eZxU4U7y2>u=HKTQMFx zuX63Y0EB5Xz+V8(-4bCsY8$UzW961T<=_2%-#e`FBpOOkENEW!k@W3R7VA;t*U{2{ zg<Yl}0f#WOz_q`lg_nCF4^~m9e8Rbi)^TqtXGs<)ti)D%Myr!nI|FXyT#Evur4}XE zbqM-PFJ9{8**V+&@ROP=mpZc{^MfK-IxjBKEH}8I+`T5rDu2e+0~TA998Ebv#Qx(F zLeI`)1a$xN(%h*hiHMc+jXJ*5T-|YwbnD4+3SJO8^uTJpS=UGeb?s>>oAt0fh8mV5 zU}q}|D<I-^%fe~r^rB?>Mwu<VM;GB#FWpLU!H_X9Ui2jvjb>_0g<_e*+EPSp*Hu{E z8*DAsEG}!IK0t7SApHaTz5anJHyE<P#&$jEYG-hOS$sL6Lhk<Cj~9dm$GPXbp$i4a z$}0HssKUI*T>w3o!DPKvu!h=s##6j7egVn0GZ2@(0xo;eg5@ANYcUyESHVP_{P-M1 zLdf5%xJLkoRXWNumGui$)5W8&R+$EejOtmzqP1(U<}8nz9uL9VZg@1Y(M1`y(PS_e z7(6H+-j)2#FZ9OI=J@GQzjO~z?C!u}ZRU}-&lI&Nn89#kFg0FK1V$;6(ssfX6WWgH z2<>~rvh4qC`wQ$qBKqaR>fu=W*D18VJf%sB;w*nWf`wWfvvnbdo-_FK=qJiY{9!e^ zK3&JN+8h^vfph98Mo!)+#8UW@BxKQpy>nBMzk7P2#|lePMAZ+w_owAL+QB|MShXRT z)TV<#bVMXm(2{58-xL7lok#ucmZ+ghlo5n2u~r<F>XdH8v2@MELgwZo(xIE!@~Dfs zC)oSIbDY->6qyQ7W>q!Ye)Bb(UNECRRCqrmGyFw<kf2*;UE><#RCU5B0kp|<5j>GR zYN}^Xx01+&X5Y~y*JxE97Us+CEQsHrN>A$(%z_oT7df)7$#4d2_k#o$PYCnUxaO%x zlmkI&?1d(h+X29@UhV3VjwHT4qu0^}JK>pnKcXi3B-l4Kth&&8(S3&aF^&-6cvast z*l;{h;%Q-XPxht6R8jfz^fFi0=Ngrx8^xMZApZ~5<z+0Jp2KynzY8lJw~S5hmM&<k zdr7!wO}l9O8Hu7w>=C5p%caO=z>xt)x?EVfO<N!(xt|Z^T>hnJHCa>nm&8kMqo@<( z>%!yrRVZ&Szmx}Zx^?)bEFt`851Wsdtx@2zi_D|Qf{jjBx57ccXUTfQWF@8Z9KZW9 zT3*(g<F(5NG5&{Vu3;zBP~7QR?;%FJSm1ZL^g7kzX27$Nat{uc#qogcnr<21a?4%d zzx4%#2mK6puZSv@SD7m8u~2T==3VqSXz2BkxEVW7N83H5^lvV5{Wy`J?)L!<;+92I zsPLzFnU{o+(PNeK4!Gpx=KA!<^(tr|sJUvSN<pd^J_Y~t<f;CJ4Y3~1FDw4s=K`dO za=|Ti{OJq_f{<4uoR=>2xEr%jzT!&oSGLja3Dr~sp@>Rn-9JY=-P~~QBXBD>+;~k2 z^3jKEeDE4l5Qg-I`eW`B(x%R1(Kng@g<)9>HfFXa0d3eoWy)KsF_<RSa!-m)SG#x7 zxhxBOIO>nxE2m60`<?OAJE;#Wmiy`ji>-AJ`q0ic)d)*3Ae0Hhyxo%0bkV=vV)6?C z^&DCepxK0K)0?O(&+WeSPnc?mNnsX_w0I{X_QSYhF%B+L7`^NB-D+{=>M^{?bpo1{ znJ(cYbrP3@>@{kE*l14C`eaqlU0^hGk;XU?!u7fC{b83acLR>a5X*&m;}K`NWtubt zHQs86Q5PKQcuJ--@3xOb5ilv^%H!XNQ@h5GN6+o-nNJbSxO{TjKvJ%Ikzkg<@&f&V zweoCj$eZ<&xeIcQHx8{G(Ux-A+tZd)WY9+8ugAGJhdF6)R2$N$*a#dp%*c-Ahdk6@ zK=5`8ymr^X8ERQ#k%^gsq|AcdCtXpm3F2}A_E!@_Mdf>{Uvn*PEtWr!CU(E}B)2dB z$$DMHoqov!EK|Ha#;yoBYA>&~-xTHK=cn0i?0NPM-udV95gLw(j=(1Kgjmvr<mo~= zu4Vu0DS7d$>G1`O>VgP#SbH}`5;_=LeFB?yBCVnFR_Wd=yc{#h@3LOx-LR{4NMRCh zbZRm9`0oafkYB30i|FMA2^jrWBBHWyc?l@vKvFt0#Oq8TJfAseygkK)wtP;nO0`>+ zeH(tfJ(tJqOnh=Y@5%d~h4^T?6qBoNamhAhNo4m>f6!ivzX3@HJd~yhT|aD0^WnhX zjps%0VFk+w()y1z=IBH>iTg(K=Z?t=Si3gst>AA05dJo$5L63+_`vXerExJ<H;}ia zcEE19Ui{BNA}6|d#<-P3s%t?=8r!|cFbVj5Y!sJ@T)L+~EcX;s_!|@UJr1)2*a&@) zv-PRn22`VZuj*VP)?W<!tbXU_2St{wL|g<0`sRA&vqXK#qx<kRh+6OfcF9LwmMo^` z(DNo(rHq5kdc1(jGEQCj;${thDu|mCBaZrIHAlBSG<hifnrapdLCeM|&!&oXEl9}{ zpFH|wzRc(nomFJ*bejb~>o7?*zBJ+(d6>M`cCW6<{#CZsCAXD$^kLXK;(a~(vN0-; z8;3T<(=1O`1Xkr3N@<FDM+f^qcQl!#)_&isRY)Z65vE7E_>Zj9SI~npK4O2VlC2AM zR43k*kh{u>&y4?63P4c3*{4o$z!DVBdYN9_dR)7*P$*Lo_QKnA@?c=D{oxCL#qxVt zCYzE<x^xw7zX(WHwNT!4zBXDkJ6(tqCw9CNuF?yBN#~1sTIN*fy4%<frwBe?J$1H* zAZ<%Z;9w`ym)fX;(oqi$MyZmcc*&oCag+|MpEvkQC6=*yli$bGqgSl#=VN5)n-eLg z{Q@>`WKDhdHIP_zeB6y1{$To3r1bH#u0f(7CJ@^>@daXc@^GFo+S>#Bk8KljVd_Q1 z?b{W#s0yKoN=hMJAXK5yW>tFL_g?*TzpY<`n?+_63%6_Z-WTBaF{e!jtIQuOPJj8R z&A%_WSuXvQfK`rTlux;|8NVRYh37GVDiwt?dl8HI?>`M-r%HcxL0B4O);jA!K<inv zMKcW9qR;f(dn7d%;5iF3+{y1!Y}5C?vC~T2lI`&OAK)blN{ixHhA{vu7o#mW?j||? z{_&+RWor_ERQ3FY2Tj`S7x!7ZZvPxeB=BqAFjf1u@DID_6pyj}Px8*kp-0;Chw`KX zYqBj#uDyFv_*l1)gS3xaTl43JxTVGrlfoa2d$Z-Q4uevxY6#)%Q>(&NVcjcropaxN zlV_zCR|F=Y64g=Wj5Y3aT}40Y0|i`^yXkhd>XVC)z7DT**iDRsq_$XNcmF;4-|QKW zObM@_VndfF+ZW-5<+U#f*EwkV_Mck1ZCKl8?hhO>+VCeFf!H%k4IKDzuDe^`Idh8M ze2n^Z@X+iQ2j$iPVa}+fT(un2(=mGD=YS7Y(;`4?ENAx=*W;#ns)Vc7hUI$#>32}d zeoR-x&6^pvQIXW%Z*}jm_kBJu6k$6Fcl@*j0peL82E;32nxRc4nsR+;bAjqqurrZr zUY!{_mHoMBlb-AYd#Ua``Qyc=nYz`sDYAV1CWp`-N_&)A$otNqZ8redWSyz%7Cfn3 zN_HwRj%%$QFQ~HS(NN}fzpDwtYdlZ5kdC}EXNekdVV*u-DmzilxAm$_D`aPsy3+pI z8;Ir16=8h&f$5C=GWYv7F07PzQSeYAZ7}cS)8u(rn%+&1iq{37e@pNE)NFd!TWWGi zab{<U4&n+IEBs^Bw*FQmhBL#xsBNRTpq9(pz%_7U#=S&w<(tt>g5wGLy}9=yr7YdR zFJYR$8|Gg7g61<5!@L(-Z*TRKlN#WcVslqsCaDJs&dqFlylU&c2tV7=iR`<U7<l*j zfB#fKwYXPjY2W}zj|}H?JxVf<fDlcquwD1CFj>ep!&dc$ea5wu-gR;wUaO_oKiPg= zGjK3oWgOh{;ZzZ3nJltVG}Em_VX-vHF%e(FD<t_^?vW%GW`wgumQy4%k1+1OzXq!= zM-7n#h}`UUd%*Ij&K@BT!3dbIRb5xOQ~+WAf56noF_PLC@5VS<^kYjDuvX0crLs6- z^kkdw>+9(nDq}?xt(=0Uxkk>nO_L*`wWaWnz7A&dwbx$z<azDgaeMA+m{;wA@O3xY z@`w$pyF#}jkmql`T(|iemv9Eq5n)_4X=v#$OKC$^eQxOTX_X`*{xhD7DJ&MDnfHjh zE}qNfqQQ)t5#wB5apk=N#5wgJhoOYa$7VE)*5lS6G$Zm|#`Gykm-3Cj4C)DJve9hK z<{!n&xkQ)6Yu}##=R+3O%i^C>={W4FwkhtF9?^Du;_t&&Y$_XS3hmEpI}Vg~_PYna zv6KXIc4#wl6&!RiAG3W257^VuQ4{&*-0=eV9mR%F|2|{iNiDKl<I@YHS+$4>nLk^; z{#OZ0g)dt;-wJ&h|8XPA7HC9Q*{V8U3fM>(macqL_3`)q21!me#T_s^DMX82^XATf zC3HhhkhoGSy!-GS&yDXjrBm)q$z~t@so_&H4v1tBoPs}+F93MJi3^Zj{O@wgo{WPX z1&#~KRCuz2>P~i4srXZJ$cN;t_W8Z$xAY1&s(P(hDk;!LE$`#!2%J-wXN8<tHYn6r zs#i8Y#lbArLU^eP)z?x$YCP4Ii_ewu!z*&;;*uUv6d6~IK3zOppz6R482ozD(_=*t zynp4o=en}eto*adU60tWv*G|2B&H`9$s$R1O_M*Axgj3%_gxgb??kBTu8Xu+j?T#B zUrFdTy|Ju;h3%m%$D2*!y(=;8Q1P7kdym2=&qs2I;g?}V0+Lr*H(rfJcweqB9xN|X zrI(>bEGN0x_o%izdBBe+*VE%t1(TGmaYBUxPcnKVID>5XlU(oY&Q{uPN}Nibj)aw} z$m@KH8!Y0NMdchKE3(9??k29$<g|wMR4Bq1E#eB}LiwHK^t6I~w???3mkBTqziW*F zOxFw_YFcN8XF-veIp=%`2+ECHEnsi^4QsgZ;uWf{<^Nh+LJS4xB(Lh`i4ft^EA7`r zf4UetOK0YS$~>9J0udeY{tRY&zsY-0i{<-a^aELYK**8lYi(O(E@Wl6w;<suvMk;9 zQe00fc`(G*8d(9w_wX+AIv2@$yf3v@R1kulI=!tCt-~NhxeozFcG4@gcDM+h{N2?^ z{C>sQ$1`;@fwMg+lHCJx-W+fK=fIYb_P$5hS{#i^8!F-i6_bCGm`Nyx%%{<Q<MxYA z84SI{sy{QiiiyqFyyewBmgQBBH~QXaw`;+O^I6@CyJq7k0g>V$L%(UuirHGPs@E(# z4-%8Bi8O><K7#+W@`7PrtL)93gm+@6gYU=E_AoB%9LiU+-p*__Vr(-6ja%t&nk1@J zo;!aHZVX`fYv`(I^sV=GE~X_9E@cMo=XkzH2%a~MPUMcye-7ag>~&i^FF+m?)+-SE ziDpa1Jd(2bEg_wMFr+DyS$m3uJe>@%0DGF1yZM8=uf)mzAZ@W=lZBGU6+iUuKNE2D zkT58SwZCd`<gqxAzez&NYrL<8e3%UoqVuo1MNc5Enm&_|Yd}0&=x{l6Od)U7xk|eB zaO;ND_34{85tWQb{?`|IWslmb5w>&2)Ob(dUO;(Kdf$5B<76>!gNVFv8_vbq@6X)p zjVxp}>)SaCp&3T>Qst<Etx2dGJd7oG%&hRW(PJ;6-1RTgM^NFNmgT(eAcjyQPxG#B z3o*pOuO5VBLmxbP4xG!x%*NH{aI&q|wm8d#8rY4zJtr;a4isbFK4cqHv7Z2=C)n#U z|G<<NwvT(gJG&9m^PaaIF6#o6l?>~r-FNlx?}U30Q=TXfmJ2`qA#0bH;dUJNkOC7w z9;Rcpd7pJ=>`eIUJ1X2a{HxQX>b{W#PM*CiD3mQDk^csVy{BC7%=D%$A}hB94o`m= z8Ijk_%yeK#UKQL$96G@axcr9jiTn2%aU|!{{i9a3CWs3g{!(`}hvw(0Fn+y+<n^tz z|G{@~jE%5&9!6HMr4RgT(9GuA)MPnDQfM{g_zO@|j~8FPACCGv@9OfMcLkn9R?eOV z5U2DgnVqqPh8x4Uc#COp>rLXDe#z{f3{u59l`nu%Ug@Pn9@#Dr^sPI$s*%9~^YNsA zs;V7?cGnkSZ%1jjcPc*8r-{tvKb5FLRW!BI6%rgW<{!G8tT#BxaxzSdh&L;toFZr@ zYRQc)8EoUNjP}g17j^ry#Pj_<@B@e}Dx)(@MX>+;vX?Q6L69(iY8!p{av&ap*W7V= zpbGJ18jjixI()HamJq)s<G&*tOtkG@EeiOL>EHRZKXT$b*VVA)9=`>Oj?=-D;&YjC zM3QrwgL|ktR-se=taaq8#$C-orl^<F`qNyW{<##BImP}8o<!sh>`9eZ!@b&K0;4i3 z%;Ahe1|vnC8ETyS6%`g(H=sE`$_8jlH8ULrlzac>JHPM_C~xM1JRp5lY#96g?P;E$ zOqSrcfGXto*Xrp$Zn?~)s&AEVVAM5hfWdnDJN<t#ge(yBwUjcjIBH;Ha-}929pCWb za~HYx`F}rSb16F~dG#SCQynte+LKB)W>YNLe^$s$s`T!bPq5q}!JKHDLc|qw+JQ#R zM|_0R-1QO(^yQ1N{V$iVY{RbHJi|+cg*-lz9vX7dq1H6G%jYv5sh4>Wv2q!R3U~N* zZ8yK4k+FRVoK)T1a=JTJUgIMEOOuINyUfW{>4GR(G7cl7=$a`6to9(5%3N^17dh#$ zMR=mNGG=N19Ey6`s|bDt1;|9e_qSkQFv;?qNcU?x0z2mZ+-V~D_NCf<9`_P7-B2<4 zTp+yE{MIp}TA9duSCah1C{C`I^TjeFGjs}2L1LJa<_u)>|5mllWtw3h1_-zoS9xVY zS9YADXgcqBaJh%{q9Y8t!{-hc&S(;Z>Skdr93BCO{w_?#@;F2?gtNnurzH+~u{|MZ zJHZ4O)=yRcp9g%LpduA55{8LRr^6gQ_#c)_(^loc({RoOiR~jqTqRQWSlnYAb`S|% z;>v>~qCk#7h9m!X8s?L=^8^a(sLg{vnTP6z{`2RJz@1uSYVnHzmknX0T871f!0+@N zIcly#xonTG*gB9pLV@cOLO6b*&PB^7FQ5=OJWkX$mLc_ldV$yNDo4RN?rqroR+gLx z>W4qv8UP!>f!$;hPmp!Yb-qhtfVW}69d{m=QSP36zpf0oFJt6=yh;)=|Jb$$>PNbb z5h9g%En>myGFV)hBa2mj0ZoV9bU&05KIX4bE=a5vw7&>%Z<2zq6v}xDf7+qLj(#w# z>p@1R9{OZ)jzPKT{26%uwJ}?gVv1WNuhhHClt9r7CsA`4!72Eq-xMYH8Rj}Z^U_6F z685H$Q{0>tQg&Ol2AQk<BNa3*nhFHiS%_|y!7klQRbCM3J3#CtM+D!(d>)OK$3RX~ zASsKs*E8KpL;*Mt6y(V9g2u1WW1E-Z<%7|wfX9k*r@R_Ghl)XM4oVK}B1DeeQvEC* z#u9NKlhZmz?Zsg!SV5%##D=5FzP97Vh0{`4%hS=YOFt3gJS7vi;FZ_mp-TeH@)FJK zVORD_oZT(@Rh$T)wTqh$bvkv6<Z7?7n*%{p+>;1cYfVm{P-cz3(4SlInrJ>>Ph=)t zQ%+vs2mS=LMM@$+3<MX*h64wb%pkImOg?wbEjVTG;=0k@n(?Fls*u-p6TNfr<Oos2 zfpggm_)Ot7<F(7_vG8JAjFs`ZO(vbg$0<qt`Z2m(r6;m`*YPq^u|5Xz5UiW}3;xnw zSW;efiI!<-EWKs`bjM1J)TEAB2;T`TxX^vhcAbQ8_467m&5$o#(MK)C!#^@Z#1e#3 zDh21LwcnD3$9BvfxK_6y^bEWZK@dT4w%|?&BCttRdom6>M$N*O1@oel7EAyPh+`fo z_#!yJ1(&Tmyb)ei7i@s6afF}7phr6BUUE9~u6)Phf@=5Snuc&6`o+K7aFLT2vuzPU z?-;o9Y7-&ByF;q72)n0n0bOvaYBz78F-&$Uqtf>N%$Us*)QGcLp)D0(4n1*ETslh8 z7k0s5-L}fh+QCbX>rSCTYU@2}pNV@<QO-)yT`C@43=`%>NAW!1?lsNNf}d&T%8Dw7 zcJpx$)-NRpy~{M?C~M>*NV#z5y<l<jA|et$Yyaltg85X*O`mLS=P7p&GR*MW2dJ+j zn-%E)vx$2o+Fh=kAMtQXew3*lBW!%hMKDcHa2sB2NS9p%qQxFyI!+>%Y#Oe;gXYqb zp^=9gV>gheN6C#8-lf7a?@P$y2y@i9@s;=1z98bi8(gs<7}naz?W=nZr{K!bdiZOT zxfr0pE3rNg&(*nLlI;Cs(c<?!?9qEfzYim|t<kXr<J)`@G!IlQTxGXDA{?=N<GJIE z1ivUmR55u+UEtTa(p-Jvj*dJ>6kn-}Rl%36d_l^T(PQb>b{kls+A&g+epBf-XJCR* zST}Q@;`CG22I}<4?t$kQI^USpW#+Ja=Ft?uf`qnku&w%CrzDg2u&qM=+<6EH4&~eq z>64^9U6AxjaaKLz-9CLl{mFZKH2zUv!U@K;k2D!D5hnXXtfW?^#xEc*ld{ot*zk%~ zVcn)UnNInFhpGAD=9`-S7o}vmSgg_FG8!UxL&s=U;WFjG$>UfHbX!(!Ft8X1y0wMT z`HHl*4Xq8SQVWUYrPmDTVh<*~ZXL&^uQuJmh1&YHZ#u*8;AGGpLb0Mr70KP91*#z0 zHR#x*yo-svV;vi~9<lU$ZL62vQh41a$i<lKe_3wVc!<-t?mqt@e$k{hTJ5C5wyLTh z{9qKejA`7+*J^mwS`e4H!9-1!RUGLWMia_E6(@%?dTm05zBpQPm79T>?wmRb9gc$j z-h;~er99h5DWx7=lsew&A*hK*D=vCwsw#TWn9$urTNlw(Qqfe!3?&@qEZ|`uiZNfc zJ9zYAzgc{s2*HkPLmZ1HqY=`9mNM_k1P_=665Hqm*NWG}u#%8Lv2h_S5aN0X-wso2 zKs6$B5C%p9L!%vB*qGGrl0?h0nrpnbM#=tQrApC+hj_gRCf@@`inY$;cZFOsf6~9; zr03?Neggq+MVPoth?+gVcdQB_!-1y4l9jpv&hm=CqemN7u1#bnH=_GZqU|OH_Q6rG zH4qNQ<T?2F*ZK>Bw)nI?;X{D$xbBeiZcN2jUM33QsJ`cL?)9b#@~;G?HAG?M*m(LF z=~609<2fSe=J1B&FkFZD4lcMsdu0wDDZF)@tC={-s<>WpDD);0wLkv+X2zIZvU*ZJ z>VEH;(nlPv^CnrBe6RZRWx~($miO1bRkP&f)2)3FoO;S0kpQJD-nsbBstS9rn!MR# zYv&E0gTH$nRmc-L0$wx;iSWcNR=(+zf1!S<i!)CBu}VauY|woKeaxTu`>hAjx9lt6 z$l}nX!IQHh1;-lYrky>`=^jbyZvTAek$TG2S1~J8F%bNWX0PN{_|o*F*rh+Hju4ni z+W&ZNV?<ubsYPK7-pT)A%-lNfY5#8mu?@c_I~Zfjt~4WTY{C9SmtZOI4gaphH2=pD zoLo9u%kPGtq10!Qyq!(youfRfCVuTJT_^PTe#be{pC5|jh_mJ+GH>3AwKnmcKr7}h zaD9Rxvc>LtMDc1(Olw!cf^>-94A`e6q2x%Vq=hGe%M0@jn6OA#_JLx7DC|o_8dxcf zn;-~C=sLVpJK@ClUJrWoQ8q;ReN45soQJBK@CKcFqbolTZC3w}-<WKV__jqJcq`!0 zD6|$K&3_s0D*wvU2UpHPd;_)pI|_>g-Lq2@yR#}=6trkxAa<_YDa_NVb>N(w4<8Q} zt_RkDeu!yodd8{qV#Cm{h1Ios&HVjmXRrg@nxA{L%=@nr=5fmZRsvLeDsO#-XX<ET zKf?JQ0wdGEmbHBZ`b|aeXdv8^xpE2N3o-D26^BzHni#qKIqpdM_Z9de#g_}q&$SJE z^g78wN4$*kG$)p~5&yIm;A;b3idygn7A$k=K%K^Q63j_6uVgA!%0YlYHzs$MxFVjf zb&tgq2R%HPZ@oLV-q<DcFxlqG2A`0&1W22s;HOAG>pkyHsGz^cy!gu(kp`FA`2q_P ztQzernA!*rc<mogx`ybDZdBy)Z+Dwb`US#enlp&6R&1mYey;G|2>yoRX;e4!^G%JS zyv?gO#nvgXc}Kzj!~kxL0G<Z-qofJRkmbgTh4MddiuyU`^OiNKKZ)R}$85cuJZ*bN zyPC#pa@9@3xzXOw>$fx}|Fv@cxENCIaH0RlBudUu<cy)GjA3z1t1d#Y?v_x<k%e2u za(T;IK}ON1yt&fG);`cKh$Zsnvi+>fmm(#>j)`x|(Jh=hJWXW=M{z7&HM?M0-t$n0 z$Ev<dOp`pO)@2+9(ha*I@->tQ|F6li&+hHTp4qFO2=9l8{B1ZfCVoF%&Y7kt9V@j1 z-(*FPg?^IXoQEACL*W}I*Y9+~^MAh0M<vOS1IJ12TcjFVSK3*Js$sQfkKL~nVV?Ad zv2|fJjF|C_zkNcopYF&>==6Vp3tXO^FrfZ8S?kG-NHSLY!@Ub|f&y~6_eb_r&m<io z?>IJ%1p(U{InS5B&##U^;8oU#oS334ibQgwBVBfSbb*wCP;jX77+bW+5jXHDMQXBe zF<8SqdC&aWf%G-oM!y*$pTWq*MKkXw4pqlXk>O`t-GwAHk{6*rMr^hU&EqhnJ0XK# zy@2SIX_0ELx9e{8o^4?oUNBYLMrz;ZQe%UPCgA&CWQyU`w^QxnoLtHxc-LOLHt&4Z zw}zW%S;+WQp=wpvkE~1)lbpp-^jM$x+gl+XDtKHCDArQ?l*1WP(0+fj?~_{>h9Z}A zr(C}@NVfui=Nl&YJ64pF&v)0ABxpV&MQ^>FF+V+f5V?F(Sbw%~)@V4okYhwHP>sdN z_&%TX=lATN-Di)Y5LNq!!IO1PYcC$AD{Gtiq(F9C?p=LUFc7(BcP0JHSozD}t&5sK zJWD0F9WXh{M}E?l&BcU3$F179ZJafpxS*eIJ&0U(>c>6?BO}Q|bqPv<E_9qKDTOws zFaefIzS-Qd_psaI7bagmce3SC0PMlEN;BuliS5=7H19a}B-D0iQ2d|xmu4p1`wimk zy3;w5@^K$U+AT1X_~ak>Z>apEn#e&ZHJjhEH0X@@IjKjis6dwH?xY?*<~7~wZi2)j zhip=3{Jm~7j^nxd;h12IlXabK%b=^XX931FVoAsO%lM^&iT%!?fpXpa4~{Ysdm+NE z$y@PN;)#rF&DcXDcYi_oT<fJx36sWdCG?tpa*kAzymQ07J8%JBtCJ-$Qw=dAI$y|{ ziaZp_3ld2u)uW3V2A`%`YQ%i7jz`vN9+w#>i$n=eJh&nAVP7*FXgwe3{U!E+{h9Q= zZY7#=<e!XT#I}M+iy)8BeW_De**Mwp-~^~>au?#>smpp(MOAmW&@>FUG%Z6a-0<~K zY3yIpaao_gbslfi?58dix+2k9v{P9lj-M+`BUe!wkk2!?OV9aKp4P<%DWl&%7O1O< zVmIF_kL%LO#(B?N8!IZU*uGbiWKe8CvzjfceaT$zNL!rMmi~Rd{gX=Z|50@2;ZS~W z7=LHXm@#9<Yu_3B*a@LjW8bqT`%;vwV_!;*ZD#CajV#$JTN?XT8j>XuDItU?i9#DK z-}(9db^bfob<TU8bDj5j?)(1Wuwt&TFV#UVx+GH;I(Ct{2u1RRp3RDs0lZ#PB~{O_ z$^4a+5)L>fStafj6!O(pc9b(|aN5Q*I;d4yA?-^uM<>O823a264yRZr%X7gQRoLZL z<)j9-mC`)rU;pMK@QTMt!bMX4<ag%w=6K5WSmZA7{m|s~y30AbL}jDuCsq@0Hc~-( z2ZH_EdM7)f?sPT6$>s96;N^pMpgG@2w>|(NHW7GxbCoi=`ndDmZuNyhPA>?zRtZK_ z3NTmmwiEzK9D3_UPYqn23z^-vhU0h({72PQqVy>^a<bE?v5KY-&E5!`;x6$nEIwS) z)Vp5ni;n5-xe<k^CPS?qe?)LlDyzK&MW3yYpJ{17qkQe3YW$Dx)kg<%*>m@8)Bhg6 z;n7&rLmI3beO<vmX{x(-00Sgo`k4od+<>D_Hm<)oRrYL4n@z&Bg0d!7XF)&P;yXm> zX?6LqV~r747)F8goXw6=b&CLJVDgZJ%HiXjkw>YbxFl2Qjo7gt>mP4$sCi1Uz0@3x zQq-zxoj%#?XKrP(mCPz)2HY~Fx%yw=DdBP!aY*Anarz^TFH%Ug?N?cSE%~NyPpSm+ zn1a2huSj=<nQmU3r9a<C+129Pd#<&zJ86a@uPdD;mG-l_)irK;^j3&u&C>?Uj-Izc z8#*3&<4=t)M`V-8{@*`N8hKE?Pq`$|S2In`?A75>7+smu7@=Z?tYmq8f2!yaNLbVe zRuF24&=u=}r)eggNDQz%86RUyyMCEpP7i(|(|4S90akG@(eBh>;&H`_F~`s`7O7KL z<g!)_Vs>{oO&xyEH0oKOS<8fK8h`*qhlKk=7pX`IqX0Z4oF<N{-54er;!lY>1#8Im zT?H3oEpQj3>`&?zO1H!h@>J{!8ZFjMMnxCOC}xdM<Dc-vbJgZJ)qZw<J_C}nYc04T zrE~)>a}Lhr;Je@J-9;@6-@Y~!OADfo3RU0t`I08GPC|SW8B8UAx6au0wj>JunfsB_ zB2iC(d)Vuwo0oLB-;cC0A3vZm#nK9!>Ry|9y|3=kcK)1SVqL+-$1`_-ND?q=xA68e zDj>_elIV4_jfuUwRF=silEY3I<-)ZRamE*y78H$zB=o}^Tk|{zLP#b)8cD^Hz(;ld zU_Z2c#G^2tYTFP)Vpv8v$~txD4mETs{NxKyS)hMlT~YFzW!Z_#@|?QLiOPChix>jb zZh`>x6Vc~<&B`Vglzxis6R5~!*QY2u$GNMkU!ULMjXo-}C{!(K|CC8yx4*p6M4-`G zN%!%oVMgpCMdb{$2iz+A7QLJq4r=_0EKg<iX@BxCpEQ*Vr9<*d7x}m%3H1*D1pT^X zunE#EQs2BSopQ(MDp#2<>NVZQzrFWR@WVSE+XgxEA=B>wM@jxWv^!<m;l3?phIfCZ zN9?cs;@`07kwNypO6?Am;8;x(z$BXTU_92dvrs78gO-<2?}t*F_k<s2_|{}`x7<xk zDM@7*O9kLu4bH{H)D}GRK2yGc8yG-lcc&^&N~wMaYagHa0JF{1T=6o5O%nyP8uMd5 zwZuyC-LW-s(>s-C>9O;cGZAq->W#9PiQ5u~ys7;nXST81amag4ite+$3!?X>L?iPA zstHrH8|QyK3|2=}SY;@AJvgZ=82)q>N=I@x{B*%$r7}b8(7W<~C1)m|nNJ#JX{3Fw zOywO{G*h1n3#8(h4(b{f>tPb@PxYdQR#R_vPiHFzmNAz0QA`6GAP)`+uLxv!@M<_G zbS2jd)+2N}t1zPBg}7grBA-Qx75$<a@S<9+fbcLKS1v(|!ay^X5cQ0&_20JOcc&NR zsxt}oSgo6dqY@DnoI!j`JJY9SPO!cK>(fa%g%!h7&-7(Z|H#3`__OG%1#nhbu@bfp z@K(RBmz_Pj$|0k)>tmj`{~ElNa66wmr}|>AnwlcNE5N1Y{`*%lmgfiGyosS_#jU<y zjT;V$l+17@*RxRh84k83BUR>S%Nr69X;5(gf-m+CokFR}9l7iqPf`9$Xu$5t>hIdN zTo$`wq?ym8nx8rI-=V$x7z`5T_Vh*cWYfEd$2ZsJV8y(I(omU1*O!wg5^Mr3@t0nf z$B-mzuAZq}YnGpap=k;TGk}63*;PGekPx9OLhx23<Tq<cc&VfT;kOR_JpLX4R-W}n zp7ps2AmP7TRl(YmDfX0nux3&n!J6NwN3CEfpmMaFpb}ZI0X+@Qs1p19Q2z|sczyI| z?pVuOk>?PG6w=R@HP9^mE3Gd856etyNZaf$eZu(#S1#%}*rJw~O6-<*R-Wv8Akc=K zZOCx2h4U_|gJqA3>e8YsGxv7k37f3CJp(k!^usDtuoQBdsHII{X%j45o<aRX1Io;k zgK()QHX4}HaH=|*q*4r`*wN8C`Nn8~rww_;9+9p#;*y6ac4tsx;S=Am=e$$@**8DX zxT`{>o(!Z;UX^l;M4t3b%N`I7q)|fDPLCYRuys!}_)BZD8-|zY-M7{Bn`$S6l+{h+ zD2J@?pH%SdB=${d$GFTRhr?oi5jKtLh6X?emRd)NXOvfe(+`5NOMS|)S4*`xRG`GB zy6AL%CD9cQ1Z_$8mu{JQ!7?NLdGzxrH;)W+GshhXqQCnJE(<+L6JRV&vnT)6iez+R z|Cp@Q(Od8j6#A$k{%DmGcZ%PReyuaTx~_K)S))#*CL)h?qi{R#r#4J^v!K7m*;h=7 zY6yq#$9{iS4GnCMuggEXo@OqM^t5FS7|<>XIu?dRh)kEmYLIhpQN<3FeW;Fm1U0C; z2*6V!S0qYGpZy@3dq(B~IwCssB=JD%S=_*}cFVNb6t@+4W$^>MU6`G%@sg0@j3MFn z5Sv17pDgznwHqGNc1)_28vh%uGLWheAxv-_M;jt2+szabU~<8#$s55McUKv>p9Yd! zd=WA9VMJnE72RwiGviheS7#XY&p1^(AoW`*vL8u0Z`<q!2zhqH55uWEoXu_w3~!nB zL2^bXz><}Za2z;J#r1Gpqnbt(KelbBAkTc%Y&V%t;br0yDVu6sE4Wb}bQFoQAO)Jg zF9jHqlw!o{+_N^e7l54{JPiJ|B}rj4sd5HsJq1I~P>u1zxR*nk-&N01;YWeBpIglT z6?8r>CQGDIBK?QG{;;EmsGNWFHJy_w^s@|t<b2bVzYrxJtR)i@VJjr;45;h!ERBYU zH5<;Tdt`KCuwLLU&$($jo-4X1)igH6SWVV+ZWut0rqPqs7pMwE`&J36Wm;+<i2RPX z`lt6ila{R?*F)bs_9a|x?Dv@@I~D#Yq?UXN*?DHjpF87|m4poaj(^ss1d@w*dK?8v z_!lty?&VgV;YX52`dG@7C~fOi(RH*FOluxpCAf=Y^LgOb%5yQuGwaF$jJ55HEZfvI z*yM-x5wTC`?{y;64tA=KsF1{DVqMqVs~){#R)6GE#V4Y>nd}#xAH0lxCCi;Q=1&zg z0|pwK$WuwfH1V4N4|NneH3(1+Na8r?D;Tz*p8I8`gI6lgqE05zT_G-?mq>s+R!&hj zA9%$-Nc7hq3_5>&aW+0K19_w?PNukxCUeRlZT{)Yr%+vTN2-hSsep5=b$#$IqRkG% zPXrp$2gz!Pz+EzB5A%-k2$*XU{4RZtI76XUQVG_b@_cdL<v3+$_G2y|onNQdA-*0p z$fk6wyTLd*nZrefQkQScY@4Qo)&)^YQ39n`MhO%;iM#?ya%M>oFiomE&D}`tPpk9w z*Gt+(gaC%0?FG_zT&%*+H@|kR;zrL&IYZs<YK%>gkvwmwTt)+^iTevS4hvLgTZU_o z{@=E|6|&I+mi$SpYsc-Cy-PY$HFk9FeKPyDo^XlV*wX{rk<Ll>59=rII%+Hst>h%L z3*oq$Pr*Txa8RKG2q%z8l0t%Dq7do-X~T+|6ekC(k%XlJsQW|^nt-N7ywdDE!eGkK zpKsO(;%C`FK{QxWla7>B^GIU={up3VCh1!|BIozuQu*>op2x+iA%mvoya|+wy4zN8 ztG`S88nckfMw(@1WPe*aom5PM9+0L}sc|$!JqeL_==tZL{Aa(h;Dg5BIILOsJDc}h z0{UV(!N}@zWVF)Ci(qQpC~I|FamA=OP~m;;nOE}SJN9Y2-`>sccf4O2@UT8hG$=>% z<Cg$pBIrMt);(KMiAme@7U-8je=*0{xiwR<##d1dX{+c`x=R=ZIj~5^&!$hgr<>Qt z7gscJyNQKds3`Gq3@SLbuuMMy#a=qe{U={sorOpwcRr%VP$}GFd@2oDLwDAc&R#s5 zxEAMoq01YkrJHhbUsB6NdHgCeZj-H$nCh$};%_E!*E%D1rE1e3QLO*|#93ckpNlfg zlvdZ*qcajn(bEVeC*S1W_i4z2m}|(GZkk?-b&8>{rPzj^kMEO6tGB@xNjUO_I3xRz zW6v1e={iLeo%iSa{Yum~ekHf2aQZdjVOzx*_aY6OwpE|gAB?6q-fQUkO?j^qiVf%5 zTbq1+n=b|Sf5^1`@F@8hRQ*F29;W5PcX8-axXR@Svi^N#q0m`Wf+0^rY-U9E<+$UQ zgZq2UggF->AC~qu;=WwI@nt@KwmUe(hRuymkYLUBLwEnXOb+n}u>PsS$g3APj3gKq zFFh!e{#kcDssCw(jtVNizw904V;nIJt^JU7_DbQ|%lS*JAr)^w(wfP(+<4b3rOf^- zk9Rh0##f>yQIgkCS3<PP!~&|x=gW_`tNxe$Rsz}ii910tpe}oBS1&*ye{K63HX*;3 zT*vx5>s<YR0rb18rX5?2|6zlYmTzJLJ3IqrYPZmB=GtNzc})^lmje6xKSxCbLdU%m z1UWZFvm%T2a)$#4Rf52mpFcydsNdl*(x;>z4;sx5>M;mfJ^@ct;+(y6acntgve{E& z<M`$4*nl{MaOUU9)4{K1#hyhsjfimS`FO}$2G3XQIJyS+Z0Wy&%P#r|*VhKW`)`N0 zb%*wBSwJwT%$wr7kAKe^@*yNdlrw~8;CJoP*4Ea!kNqLrvLc(u@gu&&6=G-yrt6n& zvCw^!>>aUt3vWx#T;N!UrMxw|v!5M$c)jRbwyfuW$h}K!_DL3XQ`?9Cg#vH#fA`-B zZhZX}oALJH0^mhtmCJ=Zu9a&GVjcThq_g&oZJPB35%Vh>!K}_vfxoIE=2dc2@C4>E zk;i6lZIh_jd)c+9-}?&Xs_<pr2Vue#G@mw3B`y^|lgZBkZbWYgi-${IuIl)vIsRX! zvM#Z)SUg~LUNR?KUM@|9QaTq#|G~4DMWe*5z%K%FVU>IG;t|Kh(-dw9+n{&W>%@~3 zBD8NrD4f|pp3CjGa;wujyt$H3=Uv3<8)w5mq*`A+ibdW$t@{1gnTVjsuZzshV8hVw z+NO~f4{4^wCzN9%Elq>Xy2@&?G)o*gsM2euKhjS1tJV3zuPnke<hGqxl)UPXu7QZ= zU5+Gtu+xJd_?Re}l+$kSen^Z&<zFd?!GM3)qb|H4dTE!G*GEd(qt2;DU)KKlh(+kq zwdjBcKO1$T<F4=^+6)4}Mu*;3>}uN%6^{u&)81kEGu$R7D#t3dji22sCRRKq=p7%z zZ9DdHO!(~>r#PEyUw=iuiE&CBJ^3ppsVka9DaiS7#aT6$e10$aUA~F_FY@i!3pWnT z*rL*3#0qyE=-Gw(y@{oThGf6Vm3tD-jfpFG_bvB!Zr+=Yf*Xe>UU7&VxDt~RSE?OZ z@;I*iU0j6fG5x{V3Xb^g$wMG)I)^{L_HkgfYHp29{5{0yI}dVFZ^Spe+pdere(wLF z{y}`R_IBg#dfZlgOX%(cZS1A$ru*VoJ1FtXdASj;SGzfOTaOY=AiujG|LLf>`taS= z<d0V$Gq2vCy2=p0=EVQEx501F=GwyXzg-8m+2^i}-V7cVM~}{ZAANjnwBnkyWqJF^ zwHK<FC&ba+f3CfJ@t4+HI<1=UdgSxeNP2S!)zCFz{>2}fMe*eAghla<SygGbo_~wX zf11nxNKsViUc$<m>vDYmnI}`B`qw{>T-msB{gchkCUfl5<NvCf|0^O=Vn(iiW!}8J zb2F1d`|(xv#trO^JllwGUN-_wZulMTB=hpGuKx}mFas)X{CUC59KP}I>kSeTN5l;z zv2sXS)e$A0kg?(hnfNftr|Eo%_`bR@sgZ24GfC|7;nHJyvNqLL_2Dw(MJir{neq{` z6St0su04-atC_4geFKV7h{R7<o8(AZH$=+M+&!DHe@!7u;dO)4g9{T4QHpPxJs+d8 zP|-^Bt(RU@TQ^24zwHchOHWXYQCaGZ{<=2N81vw5_cbOIs}!rYI!NXi|B(@^{(d-H z+%Q`y?wHB5BGrqNO>r6@Cy(=9#VW^ZetLP=h6&G#*ZMr$?DZtu+M#26p)>To>*Rf5 zt(~R*8!Q|u*J9r;59LVNG+)#Gc5ArQFh?cf#E&gVh1-kfgp<F%RJB~?P`$2qxF0o8 zYV+XwsXsq0ru%YKZ=C-3TdJ$7?ZJ&R%>Vuqynb==1`C&t$5E<=#32lR41fSioB#sg zfX_n!BokmkikQ(W2a=K83htxyswWgs%A(AyrTS@xfJVULXiLpV4$d%L#Jsh3EFbUC z;67%*O2M$|wwIZ=-JK}aVR0WF)9^{F5OY8(<*vz1)tKcgcsy&bpSfqN{453Ku)@kN z;C+^tD$(%ffw%tkZUIT9vD@;VFtvcr`)|8=?=Z?OyPB8!Gz!NsKt#}!)>szwWY6oW z)&cyDR^x}AE68Em8H+rBeIIIbu14VU^F!~A#M<ucb+vRKrKFPyR$rc<2){Q=&&>vf z`hGrnEqG<Ob)v5;v`*sh2PL=7uCP9p(-$g;dTVPRroMjB$+8=o+?;C*RCO+_BqsJf zR%P;bJbL)@JbS41ke;oP>5u3e{hOfoP1kP+kBhK`N7Y~c0<3cjFv;!cDHv0~-4G&} zFnr!{mksY@IR;-5(_adMIU5T~{w!8)XX7;mE*-Q&gCp#?8E9|h_qmiL8MEojH+fm# zXX#wucp`NgR%vc*f&BiSpef*3tIoO+HWee`Uidy=9#cY-WexF#us$#8n#-6&YEBT; zw%3Ym6=72wgq$!*SuNFqv6mNBGjS=!hSNoa^V|9^Q<pEA*MGcC8jRAfKqLs>GUEJV z#HMN{^y;F14$cT~*f=k+c?a!s!q(}{xpnV+fv|u#DA7^V+XTP6E93eO56=xIAUl}& zsRqB(2v#|9w!Jx|lpa4LLvZ_*{9Pwwo<aJMY-7`Tey;V3ShkJ%?bcVFg?^FQi*lD9 zz)nd_p}YHk2$Zu9^wPS-2WSlh0|pMpo82VLsC_*f`1O&OMB@xx^hB*{KY-B7<wO`8 zyv=|MN@NuG{pB%tE*nZas*{Mo$GIQ<R{&TE{8ii?!BLd<N2U9I7_bFZQFmSC(FKF! zo`PC?U7CLa!1NEELwtksyC-Z}3*+4Pr;PZ6zfYTa4K>;+s;2CFTZ<R$zm%Oe34Q5& z`Tmbt_n4ic37*8ATsxtN?H}|0_wN5(2)g~lksdsv{A)4tP4KU!*pK&rEngdFE`4=y zU|agNlENQyunKX*>8xdHe>r$hGgUcUFE}4^xKW(^H|9fG%$LKDl@yiVo3%GXet)XF z*Bt-xWK;80VQHVrpY8THp5fcAa{N_04}X36^Yx}ICrNsQ!SZ)+R4&KsDMQ#RXMf66 z^;GD-KqyUbA4d9TFdusRl-@gvD(%<nz|d=luk&9#`niMv`v0u8z4-6&d+CFIgQc#c z(>p(&lkjho#p}P>kEad<cN6|YR~~L_6aF5)NPxC@0&`*6pImm61llvSkx4l*naL8o zO*kYAZZI{4E+Hr4!^WFuz?}!Csya%rpD(8IwW^U-Y9$PUs9==uE``9pX2+Zxz{YeZ ziy-!@z?-8(vL{+3KRY8%o-U?^Iq#)A86o*v>YgfJ+QWJNt=1njd#X-u$?!CK&-Z%N zSgm3@>q^Rdp^Z5cjp4nt*ylB3Hul+xN5hAMVKIdHsDXuz=oWrewK*{-w(_FLI-y!Z z&V0<GVUn_<wyY#DpB-NNB(IYF4*sO6F&k<<zsBm0!ud2ENsDmY4q@bkv-!B|f_;dQ z<J!$;yPO!@vGgwXyK0mx?fBM<qAU2(lh0bPj$GeLrZVq7qWVAmh*=l?QhY)1&e%jq z{5SLWB*ZDybY|l7{nAaVdnYEiC)1an#2PKWJ^sf0MZ6O>mkLG3d!(E`n)JM?=5 zghdaDPeo+ImU4#e*%TSuEC4ErH1lmurMqf|oZhY>EUN3vV9$!J5fH|z7BBN;l`9~z zcL+ndw*5a|)T(7&nSIqVLDaFwiEX%vPfN^H{QiE?NQv^JIFaLhmDIfx))d}vhckCi zXt{_tA--*K=A4DLh0cNXgzVq1n&Wv*AG@3CV8UMy2!3z$w{9eXhXXg)SZD!RjqZK{ z9AVTaB@q*ip0Cp!qZr8|Y{pxj2+KKdld#)w@Frm^>e((u9dufjl5z=uPHe3qJ#V7v zlH6Ff)k~IY=ppMRZOet1$JEpH5<JzP>4Fuves<6?l9D^WU1piA-t8?D_d{+_Mo-^5 zCf0{(CgzM_Z#}E&T;Sdz-W*?iC6Pz{=<MS+KJYx^_^;l%9TCnN=j;Slk{~3u;>7N) zrTtsy!>O<%-U7sReC_AM-7MAB*($qBr1N4G1rM(Ovec0ttl|3^^-d1*>>X4%He{9; z8Ox&fg5~7Fz~zYhgmfW*&G2AQ;HT?FjpwUasU6XS?jzf%)f(5Ez*^qpE$Qd4sb()1 z)hlJUWcs}FE|ZNN)|uQ(xn=Gt`sZNeVTq((h?TJb%i*ZmC2L&+5z^Jj<N@uotp)d< z3pkLAo;gqMdlx^?jAc9#`TDxGc;s&Z?9Ig|zGvHRJ#HNkdvM5{Aex|b(}h2tczY-- zA-hYsHi|{RJA6UvM_RKGXQ`~er>M(ForfoBs;0WrwCqUZL8VU?ZVR}#3E%H%2Vc2X zoGgOcXs<I}$_}fHeN~s;9+g$L<%GD^+nn9eblEykp|57NWAewXiK@?@_u{H9eD9!B zthX;9x~7KDMrY3t`1_qaIh>i$*?uorEV8mj<oeytPIOE_k6nz2?uLn3+oPRubiqq4 zeT1%%h-G-`pCz{pNBtxZu_&PJtzOy@K>RKyQN&?p7aKd<#E!eW_6OfLI(&Lsd6&#F zAp&_Sw@T-<q_~v@Mhs8OKzA`QAEmi2{AShbj^E3Z+L?}JQgIKu^25V2%jD;2rXxPV z`?ubY7n6T>1>W}<wt*qVp201W+6KZ(h5ua?;zdqhX1n--EpOoUaOX%^9wuGt&!)3i zQALyrxYgUuewqVd+%QD$l)TTMb+UNgrqXM-ZHfz_oK#%Se!m9u7T)!z@ciqUxR;Tz zJ=_w#5GRQ}z&{j8s5tRfJtiG!U*o-}!$TAOcOhm|3h<lLsoMJ%Nqzwnn03GQk-Y_( ztarhzpz@D?^i7|*t2GVD6_WZ!A=<&ChK<!RqC)JgH_2vV{pg>+s2X2G|Kj`QynkN% zf<fGNqyNWOxjTI%uKP-U_~F+^!qBNN*sD%`UpE%!W0_hoj)-izgu^2AQ^L=-+qNmJ zymttriXUFYo3*Ur>IFi0SWp}{jwN@zt2Bf`V#{-{%o-!T0QPq{M=cZXdD)0f{zRKr z|F$<+-r8%AIsLAWaI45B^1X_!0nvRLNW>npogt1$OvrnUb?VfI>42)QK^TR<icep7 zGqKzdHFqy5ahk1xh?aAfL2=&5MF{EP&l?zn%K*oh${5vHk&i}fM@-!vQX*a=6&4m% zpJJ1w6|1A=88Qo+d`NJ(n_ND{R%3eu;e)Cnrd;K<?Suz#S4rQeU(Yg4;O9&>jC9&1 zq;_@i?9;<LQ-X&J9K58Bb>QafG;HjKl^@dxYg%YF9fd_1lYg#9pAY~Vy1)>mpfCkh zK~GEFz`$lnsIWLpVmf5kmnBR9qb@k>%|5j&Ls+%>cN{c|;em7rb;VvQ^fmrSFxLF8 zHy?o&=85Emaf}&(CYq=J)nIc9?9HUZq>WKo_u`;oLM`A8lWxHVH89T>egt5*r;0&r zQ<6Kp%X!EwobeXj`r~+T1<YY-(T69V`ce$e(1o9_vcA5|iSbWI<(icuco~(L+4oo* zGjm-(_80*m5oBjo=YWuqqag5<mV;Que3S#v3DADDiwF3l?%JXj1q8#ouHVr|ZQUb7 zr_($;65j4&joWED8zz^Sn&9`JV1o`9)Lfor50kW>sx#ofV2eE?X!U}2r0im!Tw!Nj zEr9HD;8qPa1gvX7RNYY;kTY2AFZ{p`%wI(vVb$g4&wV;lzjWC<I{MG~`wR@H76}B! z41w<f>@r;+LE*f4kAj-EO5g)x0nF}HXn!%6USXt>9JOl5gCY-JrGum@dBgzva76zI zZGME69zBXrT+M#Fg3S~FKG06@t63WP8i^Ma6s4g353;6Kqv=QBpUOP7EB2z4+>Le& z1i&KXu-g9I;=ZYpx!8}sF^eD|dWBmQ4<gwDhCUe$UpW=X0M%*W$vuFBsLV}NW`jWa z0H`{11xjVGB3dv@M5lB*`&O7!R+6+|fy410(+*;3{~irK5MP3KK*K3pkTR$b5@r_- z<1DwH&gWUpen`w%*YZz^2_APb7xdFRL=>_?l+PYfooQ7tPH5!?Py%ETUnxgIl%a{R zr-a;D5b$sTw;83KJg5qqc<38(L>Nl`Xbo&N5H*bJRQ3CBm=@p4Tb$9WTHtqoZs*vH zKwWcpXHMP=pbH4R5d<`M;YSSiYu=#SmJ<7FIX45RFA1s;5G;voED(1W64I3bZX=Ck z<BH%C_kg7AZbIo50$Vo`T~4@nY{T^yoppv(`H#D5q)Hm5eh#XiX~taOLdav?5Ej$| z^CoAIJ?{uk4Kk-Vkcr6eMDRAM<cRQni+<Hk2=K3zHUmrGRV)x&3H22m`;i|y5_OLt z233c_eQq!KG=|?|jphe5P!9X#n5~uUot5;5B+OU(xsBWm=m2XR9Z9BN)ojUNk-(lF zx)ooGHMaoI^@49rb0NF+f58R_cwu_V_m{1snnfXm821tfUQz%RPk`+fpo8m!_VhYF zNl+Ysl5%Bm1dy=Oa8<JjYR3i}Xxy+9nwA5vc*C7=ph}$G?o?2TCTM^Z^@~J8eXw>P z>^yo{Lx`u?eA0Nrux+)p%2&>zy$HSl@HdX*1=E2e^hd({`so7@yK8%H7rZe19?P48 zSp~5RQ<wvw<}H8xQ(`WJ-i)YXO~M_q!dR20PRQMQfKrFZ#&az$=+u$GTf12mm2_xQ zTCE!DUL~sG=uckgNKsgQ%rEB%0e)r;V{eR<A8Be%wV&5d`)G?@-@UIh(Aw}l|8ST6 z7d>H50o?P(?x|sSz#a=;;0wWHeHXJ#v-+au`G(J93STfS6a8rg`-9diaTTjFi}^WP zdbr79`pg$LeFRN`6&zh6yYPFzImv&DDH<qx9NR0q78cI9z_(=VAG)prc+vYI1Vq)S z#f%49E^1+gp1KZm=Lq|<Q@ktgGvN>E`e9QY;5UCT8tw2@hT~HP_>&m717LG4!Sh4j zzU_`NL&g_iAzA{h&=#ziOaX*;^PM*b^Pn4H7au}H_yaJ>u)@7Y>^rGw-n(`vUSped z?LWHU%{Z3N=g_~xQNKQ-*wkaTe-%FYet+0Oe=9MD*Raw}rk}ot`R3xYNwd<9egI3n z&6`_xquYX{)&}Qn(1T-Z4xgMh=R}=znSIstm5xbrjEAVPACM}stBlfpfNzDLg9!4{ z!RV8ism;*mcYC((+6yVg9ln9nLBPjFIlzqqS7(K)cjBmnL+f_mL5?ptj<>#gxN-Dv z685~H=mZ<hHU|8Uso+150xMAfZ~nq$9`fvXV~a$9Iv(RfKRv0g@O*YoP8<s&O!Rp! z0Of@8uR%EJtgS?lYp8UaLABg4Gz!q12n0I_Y;E;Q0g7M)?P#0Pa36R~FRIGBanZ5& zlTg#Xa}G-);zANl-sBi%(RT8P2tI|a?7V5NZfSJI>Ox0|AIu!zsjo3=N2!8UKL<6{ zlp#}35d)YLdLaJi-3Y@Zs2%zy+lZV<%*;u!2Lyt*P+O3sEypm3cQ%B9rU7F}`6uJy z*y|;&9YN;n3Rs}2)icos!WMG%gJCinoA9dVkuGQl0yf^bEH2=4W&;EVW2x#8oC0&1 zB+T`dXNw}*Jp|MrrDL_;C{AI(NexaUKHOYyg$<PQeq)6mHK1-CFH!?Hyu0~jX~~v` zpH^ZPclB?Mu&R;Za@LV^0s!X<ge@09dV{jwPzVtUsg#UMZiFz9-89s71+^3Shl2rN z*9t0B#QN%@(_|1kM)|ewgzzv4BV}5kWA~)dG4;a$cGo-fZEtuPgN;GL90?NDrl8Wt zW?`IgPC5%a4RS>kU}FF<AJ&SUYQ2tpe-<>v<5)mOn#L_u*OYh<h-N5R&l}}fZl-5B zO_x-0IM!iZi@E1_&%f~H7@leRQ1x8P-*$M$^mIE~Ta=AKj4PXh1~E^8gHqrnWw7DY z48(iko(E|321{zxIxtu3uViZ`b($vM=Iy)FfP2$!L}MxL*AuF>!HB*l_#=b4HH~x3 zZKI!=EhbBc|74ZoI_|%LGrM_@<IgKBqY_*_1^T@N;C9loE3?QjD<Nx5$o+R_+%aA8 zs4_J+=qjqalC5H;v+<Q_I~sfW2OK6Bk$O#JSmT1GzQcqL7`O|c=Pv6^p^cS`TdY?? zCCo){9_h!8uYXc@vI0LSgMP}|JyUF_CbSwE;w20OOyg}#u({~w;&?Z!kRZU}A?7Gx z>*K~X5eb@DSY>!9QwxfUt_2%YXu}b#0-Wa1SWSGhRv6P1)l`XsO&~kcl4>H2{=i&U zNf(Bt7GaR-@>R3=^K0_C*x{MNE~HvEW_8A0*+hC=zA&1#5Yq>+x6duCi2|}D;M09$ z*O`sr<eK_jRIm~V$r?$4xkCuKYczAFGH9jDaW=SaV$aMDwvM-RTIUB!vascvANi|3 zCF)1$w5}rtcDN0UfT*E_kg;7_%c;|!eK8Q|^uoM@JCm&W+D%hf3CsooB7MBZHwO(D zpJH_Najwkg+73s~$t7aC2ka-CcLdgVWi+rypOKacz7qx5SH7^QBV6*)9V@6Gp2vPI zqki#s9X6#wh+k8N*uQymAkWcQAWxvoK?kE(%Nh`lba|{+=(iJscwIll-WKKq<6HdT zN^vU|atD*i%HB^~g{Un<AunuH!OOTl6LEYE@q_=9EFVv>nz%{!O&s5R@b0RBjhsF5 ztMJJe+<lebjUFp)nSgr$_BA`6ZhdS|ntIyu2UKDWnaj3#^jKou<Ic;Iy@IOS-5}?) zZgKAOr3Aer86CF(&;A?pFbqFFU`6LN*j&k8TNZlhsf|^@E>&W_(%5tuUsyOH@BxSO zw?)ZbD7r2Z#to#u(2j638~T!)m;#Rf#twh`E&c>^ET;H%9Ovg{;h*l`g^C;)1UL%> z!vA0oLYx^+9xl$yyX*aj&K#o;dTKWk&~2hXk8M#ZjN^(Rz!Gv~JeYE*D+|vj60|vY zggKiwwo6+Q4_2^8zDZ!<tf+3#LaQH|B*icwWB8LCKH9DsrSmF#4i($IH_7HR&kd*x zkWi9>gur!P+ih4BDSPy%2x<WJXSq$shDsbho~<~Q@XV2tU3J=zy+b|oz~PhqUEO*0 z#X^i&Z!~)Tl%H$PYVTbSw+kNl(DD<lo)Z<urA|Ap>Aq4$+;8qzQLqq67-_1qN-y%$ z%N96$w+&!j4;42Fihd>Uc+*|EEYEr0_gO$ma3NBj!!UBA`#&Y&XxE<FLhH+!T{H($ zy#jM^$o0o}*YGyx<@{6HlRrb2dB@|N&SNW7$zptxW@>h#Czl?TyIp&##()3Ti~C>2 zq9U9~?nJ)*ed(>=vHNMv_&|RpK-zO|IW6DA^SaHMvTpUD$@XI0{o5ZOODl>-C@Aba zZe!$*5a9Dkmesv{y^17_zqyEtNCP+9)@{D<r*!r+R*HT0d=19cwge;fr<q%vBO=6h zSF=;(eohNxVXcO}hPyBqWH~g{vEBriVDPb2BInu_(dJB^aEbRq)ob}@o7lVw(lVv+ zTE(tcn>83WHsB^%tnZ4U%8PBx?a*gqITB{hH3}rziG5Zj%|cg=`z-|z+eQ|of4A5a z3GuW~r4~H2V2Xx`1mS!5B-sdMuh^G9NfqFqewS2c*;N5-?VoABy1U>@Eerdbv1c8- z&K@bpZoF|tYw{?uUeR+)B1-b=y8K5i%^QZ7CxJy>#OzH15nmCVqILYqOV6OX)U@=S zrum!pNyho9;quQH3{0(3yMh15&RRb*j*$s}28k4j+Bc-||Ktn!c<wyQlJrt$WErxm z-Kpc|xY3BYt!{#1Jf%uN+VzJw7~z3rh2iEDNgLad0yQHdT&fpUOs8l2&OtZlF6PSx z#8$;KIP<vDy3<teM_xFs3nU7p`||6s;1Tc3v%~QsmtJUwR|N-jZc-GXcpOO?U|T7V zx@OYLd}zGHM&d@+mKRHCG%WjbkxgL2W)4ubAdrhirzI$KtaqzS{C(WBH)+1_Bjo3Q zBR|%Y29{Gxjo((CkWFB?P#t5Y<c~WlT#YQP65{JkI?@|+%6%OjIeE{y=>=5>fc1uK zer?cDzW|1N)Q5Z%zMSYMVLKJQG}l<*`$nQq@H)k#YN6^-PG>FGw99D;J9|%y(c|)J zs%bG>%OU1LFPTlC!Q^a4&Vz)`cMFGTdjWjjh()ckACk{1vo57*WYiP+?+Y)xOyR8V ze0JfXx=i3w0gEl)FDOI0gQq#5XE%NP*xejr_eBwq<t@i`IxW`S|Hk^E7f{ho<Ao8J zVh<b21)!B}u4T$6_xo_^{*a8>J9L}RqoNur+(7s%<SFbl;`wZzZY@&HLm=74!FT;3 zVfDRD$BZR#J@*l@o#mX$;=~CdejuT2RX^5+`gp;oKYyt<s>j*5Bn0}DW8j6vM@gxh z{&tx!wNm&Y#lsQ>ketw0Xl10{EBI48<u<Elw$MDJPIq??+kY3%8CpvDJ!{PlD`4@* z=rcZ8=y%RVN#ttV8>jI>Q}f;PEVKHoPW{fyj&dfdYTl|odm<)xO@iwRgRzK<tL_2Z zSv2nUaaJ>0se*!2K8q}@f!8+8pV17(Ap!=5$7ql@9v37oNL@-lTg$d4;KSd>G=tYw zA4*)+dM|q5?9}*Sw05!FSd3aK{$cS)eq+IVYGSd;spp9uJ3r*l{3Rh;$e)xS>rG3% zHgi_!IxOR&hDfNA+$V-d>+}61D$zp5a<LGE;=?3fnX7e4lKYS2uNjJd0-fx>a4Vhv z4<<4YQF=VSkni|Pz}4>O{&6Xi+3Z}25?|*oTS1bujeTk)crt*ey<N8Drx6L_CDK0W z&nCkDs)~K6o8}W-doK3xl5&63t>fXp^A=&iQS{VP^%1Cpu;`u;d+p`<VLM(PE4l>3 z%z3}aRZvQ%NkSG$LV~;Sa${_1#5r3u|C%jhpEYK;o6OFir|Wo*1%uZ8z%*EFeLZL) zebu?pTo*LW0sO=5yms#$)r*D>s~A~dV=0SxH<!DkS{G!yB?J9Ri*JF^o%vVJ5&hFB zf<HDD{`T&ez!vgrdF}|-@8w9t3U3F#ViB(`@tP62fQ>ki=|0Ju*CbX@M$W9MUEZIH z8f#<IQyI!!JH>vI0pW<}sS$ix<7Y@3Y4iTa*LI>ObmHZ+NwQh8)~Xuc8NQ8P=BKCk zztZG>Oa&GpRH7N#v_ueGAps9bocmMcq^#FfaJLbw<U1aQu(v+#cyqj3^-8M2I4zP^ zLw>hpKHxMa9CxW97k#*OD*Mv8(M##s9gXA-K1nDgXgW<%cF#tLDMA_^lj1T6HuF8- zC!^6b$V;SJ_3Nb!N}nh5NX`#!56}9wxjz;C0-n8ac~elAO(r?*BGGWNYITP8(gKW= zXjm4muM*9+oL<?8@N;R4$*u8cFTtsQhvfL>9;)qor?h9khw56tx5ZEJm;`cqntmhm zHg5U?{`#$FZ~F-a`DUe$4Bpx<@oR<9-I5lM3EybBYn@y<+^}C-6)l#lwX5cth>E^@ z)(Icp9BjrVD2e@AbW52n$pAQkgFy(SQM2juLa%0(FaI*hw;hGs^-bhI);uS<DeyTk zy_)Zq79uGxcRFX+uI}%4iKf|?nd<{Zda;DTyV$)Er`=N_%-d7jY-r8~DUnNK7XHTo zaakR=vt}rb4Mo6X#aJ##c(0r!C8i~0S*qlLLEkqP)o8XVB_(PxcL$Ow{V$sy36ZWM z{oY(2)O@*L17Y1vg=aCyId`9jm3T|FV(k)rr;X8gH7I`vs68!bn4YCBy=Cvk_J!{p zHMMEWkvs0<{pFo}t2zD4D{3;K&moJNJnX~xa9?FXXigzYL2}}=*rM%I5}C*%racmG zb@sY0xt1ic_;g_ov%%`sojIO(CQES=eVFCXm(8ALiYes5S7JP51R7x1^&S_UI0j?C z@YumVXg=!Bd85685pz255S%#%gWvYXtoXd(Y8_%;MsYkNp%-cDXTN$L`~7zIN!DY| zs3vV7XtD4(!{B2_Y)$W}_KC*2s=_kyw6+Q0o{q`mN~&i37nLT$3;u9qg3{-m@sIy< z*dNmbVJn#LFW(4AV3{2{dVti2Go?O=MR_^dnyQRgjkYO7Pd(R1?;`z^dEpA=KsrK5 zfsr}NauHv_QC0Ga#Awi`z_xpTp&8lu3~D7g-Hat@O54IthfJv9^38ChiVBt?uM5(F zl@q;aK&C`U<l?D@-l{f2&gu!w<5Fta0fT4y4y06~f|Ezwy^rb)^C;G~Nh+w{L<_I8 zozx`*AQXir?YZ!5oy_kS(olhA+5-fpaAZaVkP*v3)Cmb_ucrDWlZ6a39(=}}Vi!8S z$kpVmea1dbIDKHRJAHwHfJ+XcUjh^`Ka_;nvNx;%>p0B-ei})K%A>KE=SWQPZ!{X) zgoU{va|MjaW}v+*b-0Apz!@2W7l_+6GSoj#-XyzPaeBQiBu*J;#6DWa4UE<wO(>)5 zGUynT)=&&ZswKflz$FX3z8yT5fYTXGwe3FPr<vi1dqCDPdS+SRs8Dq35KY%faT&;I zN1D7PRvPR*h`|*VPx0}@A-s~SO;fa5*G#h2%70%)TCBEn%@1D>LIt-bIV?VA81e{& zQ++H8Qf<lFxroP#AXCaQ-K*gK;+|^7r^3V;YIGU9d;yZjvi5>66|Fg1to9TrP83`L zC}#JS<Me{8QXS_CM%>0M=6MDN$B66Qjj^~`x+WQ4L=B=iU9ACAdL$OjvjomioKs8* zM$xuI_X<wL?$!e<LqIHvyeW)-n3u{<vYykV73(xPqAb<fZK>>Pt7jqtk((AGnR|WV z>F~SY*mYk-W*O$&XL!cEEZ-bF2oPIx7#CAO0E)$U9W2{uBH*n*@Q~YGAZ67sZ5uy2 zw3rs)PSq4(>73W8p2-TUqdcgtjK*OWkt8Pv)8_|iD=w`nrKJG9rd+42PA{XlXHX1g zPLDHU`ne%<)}9x8Q_!4v^;Z+{xYTTk@wM%=(nusn+@$@uaQsSd%HSQJYi!=1JC_3y z;iCho0$|oU)#oIJT^`}FA~Tm#eIW>7bta*ZEI|ah%}6!^3Q(+jjC}@-=*dT~oE5G= z`*$eK&Nj7lE=3-w0R%Y9w>7W!P~vezt(AFkX$3Ln==&?CvkMQ8>k73jro}7em|G!M zENYPe>tjvZELs+rb$@@0+cKOA4W2Fr;dY}p)k(<@Vb4OOiUYl+5(p{-e>2b5RvXS+ zHeGuFJG3q$*z6Om=(#2sDlCDB`1Wu*b;>3KX=l|ktsIqRk885VpHBLdMZVI^e1+n< zNHUIhd09bqC{G_HtL1G_ACw75-CM-OR!UU~*Hv;m6dl|Lc3J(Wk^t(M72Ayd)3gy1 zi<-Y)g!*Zo)EeziRU7RCNmuMSH`uH(40dM{lJqp%{|LiC-7tIY`!Kgt|J*4V1v>#L z_058b$j;HhChDebMP)OhwHbRA$J3a#0!nVa%9v&Y%<9wS5?)ufAf3)}mX$rcl#s^3 zQaJVYQA{1`cHB(7D>@>!^1M_FGZ8@?b+}DTu67)kZUDGPtG?9Crl}!f?^sDs!va>| z7PhJOyIgKr=QE1C+qYA!D(xH#dSe(T)6JaQV{dxNv^e#sKM<%M^G7hR`9JZ`YX-a% zVG;;s<8x85lt?5($PdXWa60)>o;98IMmOAonw>Mnh5Yv>+ZOIj*J)~`EZcFd#7V~0 z)yV%ah1{AM11MGH9EtdQr=E<oskxRR&o8aa+*y)+KShQlypA|vjbKnTE2(*eBhjww zXClnJjvP#*T(eHA`8{2-M4dNh`3j~^OSfGNr_|S%GUE^?Eax%^Jsf+f@j9=i;v`{L z7H+Ds9!HY?IHDi#b}-5m3koPEzHd80mrR#esVkHkTXSCdl$Zmk_%5RT+}knH8S*H9 zfoRu+1ESfvs{mG7U1p%E|Kgm_^lgDbyfHeG=K6F=c9k7q0&m}*=Y8_dgZEN-jt3qV zN=$~*lBNn%HmSEeWIQqn9@S`Y$=~CzgQ5p!dA@EY0-c%XhVF?(zJG+{T<QDd*I!FQ z0QsaN0~bzUGS!&#rb|kUb28N1vnXobK?h!P&MT{Xo*B`(oQCYVHCN6yRyLYi^Cu^y z^1QHoakl20p-s=aAO-te*JBo#1hwSvmhS*MEU0^hFBsc=ZVsaP?xUHRv)S_B*Y7?U zzb&CH1CvzO?m2j4WvzEU;N0awqWn29Uf!VgM^OhS>b(7^!F9N?Da2_%RBK)CW*ik+ zA@0WpJUo$|s>YIVK<2IR<gBJHlyl@M!y-tlOo0#YnD>2zi;%Zy)U6%07YFQ7brcB; zkTVD=Ih-c<rIUTZy`zqzM`B$(*V-d>!BR#_YzB9C&w}i&KNfW{jUi+LR?V<jIy-P$ za-|vXk~N*)UrR_mUg4Ww3D-E~@cnnj<0q&%|0SF!o3ztYA9X^~6Cq<K^bco22GH5w zC*4|HfOVy=$3o-$bM0rTq>EJ08~O4#heqxsK!SQr6&V8v+gUI1I!aNYo9`qtGrTkH zN8j6aWSs4r7j7P>RXP%p(iCIvB|qdyM|vj8{R(7Af-UPYK&cMS4&8KCY%Y(YD<0fY zV?zR0ZMk#qXV!)zf3;k){Vz$2kjxB5dSrdORD{pGf>EimRl7*!c;}9i!kW35WXvSr zr7LrE;k*E-f1AMZykY7GffE1XMo2OVL9I=Vg$5C>?0c`1r%*cEpYqeFF_o<96-6F* z*r^fl02Ilbl<H`kYAitc>%oG<liYR@fyLx2B(g~VW}0pDqy_wjvVwUC(rN=;;pg<m zk?rX}gTuOIce{`9fpWGYCAHacA4MMu-GVHj?C-G-2tYXSBp3n9#)-J}J}<i4#+q32 z(487iK>U`G>I<N9AW55H@`r>5`?=y#9peVi<PWb?pp}qV=VUE>it#3_4IB9Eo6FmF zw=98vR0vzkmEwW?944VZ*C>q|byBEz6;m8SZN$}|6V$pjd-1~Wj4QjOhsY!Li_*n7 zrP46Y)St!unq1e5k-9ob<_tvi0lDgIraD9FTx?2g62jaW!HEa_No3=xls8{KECYpq zuq0<vaJHEr5G~+>1WZZGVebPAciV~tGJz>fZgh5y{>fss5JsKK&g}SIF#UMRsqzL? z(B?BJiL|bk$g^E;>jF^xiywDCT}W&I=;WeE<Yy@k>NnadcbjoB>kYLO)j6`Bw`W3Z z3a3lvXXIQ7wbv~+(+v<*cU99cNDb+G^2c_oh)9f4|0){rl%9|ZtN;9LYO3^>;X9K| zwwuTmp%NxT={%ZJZDvqsJRSJ4TlZ1jBmdrXVsTe@2vV^igGv1WY$m(e!kL9IPg=_C zY)bHyS8VaBzh5eMe77AyylKX!#<??Bk#+JF>)yFEZG-_!E}BXt7LtyNj%?RzYhHI? zZ6`Rs1|bLfYwxeCJS<LrCsW2_j*1!v$d&En(K+c9NvEhE%ib_EQi@}D%2`^9X(i0U zY}s@LenXAbV)xyl8GI~+y0e>NDY2mr=l_BvX~xzBcYVK$f8M?IIfGGH3!I1Oou5Hc zhS{PD51`%BQI$CKeupN}*;=S3rIfT*zH*uoj_|@K_7S!rb?A$;H^qy;p%>;GHustF zTA<n-%&a@bau-HBYWp~+oZqEfDYmel3jJ)G3guwOudw_zhm(I6L3vYK$&u-wzgG8h z+$4=VYKdx@qAi?R;%pIKqc>wdewPYCYJxFsI&Dn)f+H_#d1)o{CFM2g*p+WAo-QZB zu#f3Fduerva0V$eN|9oF|DW9lDV?M==iftWnJuSN3~k}XKi)Z1rkLVk+RiE0yRxs} zp{@nKDtE4Pr$dR%GbL}XUep&qUkP(iD(P2k_&NIaCNVHmKsxpyGyW@E0~f-7ls{%u zcwAe6!N`iJqip-Bf2771?f(5DF94xY#~gFDr%X+YsFL1L3hl)h8}J~M$|T1~5R0`< zRw!*=)HePqZyR<EP7c_u50)gDlYittVYmeiX0ZvQM`KSqmjm5#9dsVGICeXB^&G*u zG-~ARu?4MN%8lE|dwQ(yg0zUQX&A>6g_4O1V)6vijKL^BHd64Il?p&#uqpZP;s#St z{KtYecO{0XTyiK)en#mLBZz%X%4|<+l*Y;?(NtN58wP%N!+}enF-Zun?_1zP6gruE zB4&Ske%Jj`vUHKi-W8r&yd527aAK(89LWx0YK|dp;b*B`_E{(HSe%=sI-2Kl6<csO zxwAH!_zC}1c2D+2_bO~=<Tcs{zu({a%)h1*vKD>XzGS~jm3cY=`U>6ET-p2h)DuxX z?Xw=f{a(@<z9TBf^!!<u3g2JTtYbXqK2;NlQ3dV;)6f;EkGl6hE%ru5yUp$Fg*@g( ziM&E^i0Klc?@F%n+u%48)dCqo1oxGkm4yg5O|zt-pXH90pR79+F~tA{+Yu1;Y^T0) zRb~=HLKP0Se#30Nc2op-AludEj(-H_Y~`R)x#LRipG;pTa(<C}p}kqhmv`((CJU$P z6`g8(?VVbwRnrfdZ9ZPVc?wL=z88@dJef0gaVk?fsn*?W6Go~gtX)ek&C(xCEz#xM zv8Mr8q;Kk(<xTv$ok|r;P8zgIWAem@ZWa#h8E=Gx6?2|9vRwaxe%xLC3OE59;D6o7 z8^{QPvPn14p+0VVJ%XHZ$DImiL3mHc$7?0ET(6Upxq3Ix+H9>)+K7qrOh#miNptAr z-I5*Sf3Q6~NrfyrOp&Wx8-%iX>gA^tAm6zFy_Mns`TJNOK0*wHU^@kf+D@;hc1ZH* z18AB&O>eEh@GQN!V|MZ+B=!o(a)FPB#bAA1p(*kG%0+8^Pc<H;TSV4fbBCRdJNT~f zc^!Uy`CqwVoMlI8sm$NPV@210by}*V?&=8T-GkJka`pDQ-wR&)^xR^Ty#Bip%we6D zveDt_`crMFH|U_=%$*^^Xn>k~PmMu9>99Vg5N--E*aAvuZJXD={g1Qzexy47-v<6Z zgEMd(dmWr}?7jEs9FDzbNcK);B?=kGUdPBLJ7ktb^VlOKsU*rK*{M{@?eo3A_Ye2@ z>HZ(y^Z9ySkIO8RMlSX&P&fK!a%7Gn(9&v$Pkc&vQzvAs+-~Vhn?y62*(<uK+b(D- zDwPS42IYSbd-pFyK=vhzJFiu9MGM5ag{Pw7!k~q1e{nJREyP?cFqy&Hawq?(N=<<N zy?X=%;6j0E+;p?-tXnV+^{Go$5RjvNeWXh-D`7jg6w?@*^$CPw>U&l@^Sw&4pq7r! zZX0<aU9=Sz8Ma}-D`f&?HRPtbfZv|iNX-^GGCNCv<tvc3I2oht>+Snr60!U=Aq(RY zwNHCtIi6ZIkDk}-jKMiOpY8vw5VWMBiSAb;iDu<VXkO>c=k0<|2u!J*ehfXepLAi> z>*F7y7Trf6SV4xmz?G^_J4LBWHlD0yU_lCW=PJHYb&eHtfIP3+9&c$qbb*w|O)k^5 zj@nOz{jx>{qvKif@?Z|4ILfM<o@cp+gKlkM-%YOFSP+&EBqgNHXiJ5DKpSerM?4F2 zAoC2cq@2(*Cwz4#V$)~c?T<KGfmjioLMiVKCOFlkL5H;henG@*qn-!_*m(y$bfp_A z0k=%op!sY$Lp-{mJzF+?3WhRBLDTt<nPJi?g^O0WH?t5m<J#LiPnjN1`dN8j*R;vt zWC3X4i`X(Mt!8e7jIyX8&&!$-&!GeETkzU6rq@eC(S6LPPG;`RVUNk8%aAUIfaLh6 z<P;}p{2kXx7&&+pojt|@s8piQi`<{8rubq*40W(;ewpgj;Hn4SYo0;2HVZxp*&*{u zMKC7=^)YrtG$zDrPIXuyZ=*UHBT=#LW%!!@aKP#H7nZ`QI_@gy?RY<YC6U`gY%3n! zwSAa-RdLXX{)R<G<u{$Fn<kp#Ut}|%4Po|I3seFdN<;i~9XWC<lvZ)p<<0a#i4k?g zsH4GD;|4%XBSlN<_GAsf;5e(6LIWnSkfS^?EmdN=)<UfbQvyIju#GqskJiV4nOl!H zZVIN^HjnpVkH0ML#c-tqwIbry3}5ZDtFwYvPct}XBZl2>+{h;&y*R=NI897fOQ(J< zMWcz6W`cB{(z%j9{*6BE@$aVh&G~J)k;B?F%dsF%5|5hDOwMmkcD^r5F!La9Aj_Nb zu35J@>vj_1pTT2be<gWJ(?*=c1Q>-8wUViWLZ&%(PNN$^Pxpo7?$l2Kfy?pU#Cx7% zP80*6hA;8qv}-&<Lb&9eb<*2RS0RP!msyeu`<14|NvqLST9^T#8cSpiN?5*FXfM3U z<SNO`c+<JR$lMPu)D>JegukW?+IJ16HNnqa>*e@*AVTO_yA$)vq-(TpAqO1PnUt#{ zxY97(nKs<~!x~z^{9q)t`w6c-H~B37BF-tvZ_OBL%AEBeZg}n=J3G_o&>*Ct;r%Jx z`CIM+z|!Kr`Rwbgil!7gwtpk5q^|sy77;dw@*?}}ry`B)UVT;tA-YGLvD3!&<-*ES zokQYos$-sQe3HpWO&o<m5w+;OScw9Lco%Z>07fCvTEi(2&AqYd^8-sOPiCS|9H4UD z5QS<{h1NK7+!_i((s9_h#RaD{rboxGmgME;U9~SagF%C$&6tgf6j7BYoBeXlVH?;u z0pICoUN$*J3xBIdoXcL@b`J4un3rTQNxXhQnYLmy&j-M~XS*qyQ=o)=-3Pba*R;CY zDSxumaf17O)<#1OrncXknrBbxYTP<l=Xj+vd%fu#sFZZG?aAx(t>L=bp=dPUZJFW^ zE=?v+?cGOLFs`3iR8jSBJ?68^?tQvbPpRPvRlWHhL;(QuL;Eh_v%++!ynTgN*5#*3 zD0pgI4V^V3?}1w4WAq4f0T!(`W6b=lAwcpU;))6JDCps}!FtbMijD8e#`aN0N;4P^ z-mw)@p;%;)wwIQk!T|TN>^Brnh{wTQGyR-J3J4s_kS=@AemR|z^}IK;LkbF=r22>S zUZT833J&VT4{-9DF5TM`<ao$HaG9P<G@|x(E8Nx4nFejYkPXHee$Gm(jFDk&{3Sn; zbep)v<fzJLx*3~I_u~|q3%Kw=2N=$weSSn!%%!FImZ?4w^|j22M;VP-mnT%HH=(!h zMRg{en_``Fcq<2H?V<f`ya$!1yVvvQupmTF*yrQ*5FUQqcF+^oAKcj^wvT?{)Wn+c z1;v+GA<org0X5Z)&&$8+Y-1m#C<<tgC}{EFk`zE}ZnrleJzA><1rA*tb|1}}lYcsX z{~I%s!?<)&<Ol_*4?J<a<5~+A+U|Q-ln9oG@)6=~c=-%PFaChW(&$&}Qv3hTX43M_ zqefX_eTixrT>rM=e{Sn*920eb+}A{YUr|0CR;mJ&%7?Y0oo3Z;z6hLvYD8^iN8gE2 z63_hN7|A|t;Ax+vssn;KjUF+^!amSj=JNLYfHH<;5IN)On5O7xk=8OH)RW-xI;r(Q zZ*AM*q4yH8^87n*9aV>c=5m(dpid$Bx|_Ty?mI-b@8gzhx<t2rb2Hnk4q3#`H!+wh z@%b|!oWlWw6Qnf~3M1Z&=o7`bA0S@NM-SS6D0!vix_KFEADfUmQW@?xAVfu~bdI9j zhvpVj6lEb=<mr>a>3jPL_?;olG%pBBxQZsjkw!4lSQGjrQIEucacf=Geuh>T<9Qbv zHV<NF1@AUOlnTaRr(`1;1U;53#uo-mK>}e6t~7?yKp{9w_Z}NrwE^e5%0qNcEv5F` zTs|ElPGJ{QTx`q|v=?h&zX~;HF1S(?<Stg_e{e5>r!tGZ+~7^oSa#DXy9hkZ*Cr>3 znd6*m<72`+RdNl5I{WJ5Rt9YQ9C*)zhjL{C86=&#p57*kZ|PgQEhfQhDJetRxGCPt zuVC`D1yF&XPmKY~5!Y3+94nO1rQFr3fZ%meH3gzbn+nF{$nmXQKwF}up=t{@m#*oP zXAEp<sQ1{Q2KpZ4TB7htvP`Pi6HZHD1Z}d*C?t4?5aof0f!q!n(&k0fH!NyaLsT15 z2)6OrzdUz>?hpnNEb6E94xt);IiI)jGS==b1S$fs{!=xo%T7`dC#kyWY8aj_2t`9u z|Hg4pCi&aT2o4o-M|7f4{xjBJWfz7qMT>2}6squgA~<MWYarq$Xtq>FoXT?Q`^c1- z+$^~s=gjI!5dMaqPg}^@oM6Ai<>|`GtZB=yuRqda>O#a)G>Q_`6<3R+`fZG$?%-^_ zz&b)uECIk(IWH5b!j8KJfmkTBG_pc4F|1@zG`}y}-cqbqM=A(xj@-DATX-?xqbnv? z55Ey-*eh&H%P!aN-j~DqZbDX3$gFR0oE2d=G_BE4u2TsK%{9y(#69YSNaUV>Fq)tx zOAe?=jhgh0z>HQI4&IVBj^5m`#oiVti3&Z{c|pIC1A_1olDrI0={1GkBs<OO?#E^4 zn5Mp)OiNwjjU4b{EtgjI51-`3<I@Ym8p)Ljnhm}>1ETrkqM28QgVZMCkcf(~MDoJs z<xec%^eUA|bNLjAX0ZRC?(BrgVd3!+H9_HhKNgv5b^&8!cVqFoDG7HD2UZ*hSQ|bQ zH%GifUfTTa_u1`bxDh~n>L-~4(L7qzscfV)d@1>t$by7A{T8{B)=2J-dj=mX9b)#$ z&%1GA38eTsZ0cI&8hb&Tyk;`xgHlUc8oswD6|?GFjud?#m{sjeD2{Hl;uK%Fjc+N^ z^$|9i-R#$v98g$=@J{vHc>C<kBh>~HZrs1iZ7cAoAs}n$RL`NLwwXB%=)0g+1yNy5 zvbj7woKGnQbT#sQi4BIeb8z*8I>J07lFwXJ+%I6AR&KFxasJYi@o8Vdz$=>&H+C`! zNjf*Kn@s~e4$pdk9S9K9c{1`fcqd8byUw<oWXbV-IX6FFh@@^tzkXG!{L_B1I7n9( z{Ycc(KlrQup+TvzOlqL$1YgSXAV2dOSNL?AGIqeH)zYiXccbjAYux#1Q&SvON2GJ> z4bsSA>mDHkE*O|i{5>FuF=`IO)vW69clV;CzYZZu&EFSC<t+wD35q2{m!9r?2q;{Z z11AzBzKxi^4S6-3mGROC?}~jd%=&%_nR>T)aKip{_HvOCtG26a!zF+-VcLD{#g`$^ zBir_*41%P-Wzf!u*K}Rk((5ZDT<dX3Uea<4Mb=2NGWG40v~hiaHBg&3zR#?>*slb* z*Q935mJIE6gK5L1_jZTl-F6!m^w+t@_YVhF-N&;uccaD`+K^<YX0XPG-KE$x!o02= z99q4L_TYkA>c9H_ZyMMh<Lm9uHy?kUv-i)rWv%m*(tg4Oxh3j~fh3i9BetYveJ@JZ zgIm@EFl5X5WOGPM5RYjyXLZ@#=IXCbt?>eX>Prx0y7bN~gLW%$A5QXQCl})zp?59G zj#~pU<_vp7D$Y`~v{Zdo(k0o}(m=t$-P3lp4k3&~(8Fkbmta|a);(7eXBKDc6>=_7 zRY$0qs260xM;j}jG1l3TaJzmAj~ECXfv7piG4EyOb_PeJTm<NKiD5aT>X%!>ydqY0 zZUnJlE*Ut|0Fkpf`5jOpul{TJR)Sk4tu!*ImLzQp&cD&2-VO2hbC>KfD?T}pF#_mE z>gYm4bVlO1XDSGrx|$8LsYPCa0mBQahcU9%E?)aG(Mir~qv3Aj>Q5OY&krSX+320f zEN-S~bQ%X_CA9sxKT;OBoOoZ<wSf=;Vs@iLA3{_qWeP9!nkR=Hdg|qW(%kl^+@APK zip~IDB>w3%aTmNirRdDHM>*v_g?dNqtAxG;SrQoEKDe@<a1)Hy(X7*kb?%*%sTPGQ z(~+7U_Iqc@K7xOH7E7zBm_S(U4;^HVt36O<Z6fSh+Fwz$uY98-dl6{p#r)}4M$2m5 z?1UOL+(RCIHu~V%-Odo5FTQ7>HLt^$A@h@3jeZeI({fuSvCtTjrP3^VL#x+vm?o8% zEWMa8F;fj*=aUMuwC+z-U5=M15|pxF9Y!{@Gn2h%j-p7rM3_MsEfuC7HZ^lqj)Sbx zaLsNnm2KRSD5>x4Ik<?lBQ8P+pOu*Tkvt6Wy;)(kH`~1q2^wW7{l_nTp6Wa94Mj9| zSlp%5!@Z6FJWS;yy-Pg}qVrTX+|CorHddV<@)jw)8~DK2gdAq2BSm1vNj&(N@;!#y zFSjWz19^4H@JQ3oP#(fK<s25F6&`Rpn72yuXMA*%HWt4RIp?QqO7}B}pR4Dsh|2RH zLM=$X>?>Z2mIghke8Ij%N`kg+Uauv8*vHZXKQYYC1-3c;Fkgm?FRoii68{2KT7Lb( zA{+u7T~Pu90@Xj3ZagGZPJPZbB<PSdAz7T(&Z!rf|EycyqDy_PAK}p6kxwKFJ?(R| zIVJ_ghb=cS;oo|N4yD(!ww6647a2>t3<xD|5d92eKGSKgnqG=ip$}DUIibzE75co) z8>n2#k{Ng%*k>Gbs(@*rxy`vy;is!HF2yc4PTcMaOsDsoM1!8$QudOm;+G22q3}+= zRkJEk4@ksMhZ__@*}$me!W;v?v+zy-k?hKJ_OU3xPHxX8wT-4gUU8hy5KtmX0M><! zH)f~gGTc|OSWBsHFoop?QPej|p7WLhql)H_i`Npo;i@%mZd>8!2UpX|FTp%|buawk z7)pFxBQlU#_gj~u2&04nw!c{HZKR8Op50du79*9{+g;_MiO3UmcI~)W4dFrQsOCE& z{h0z@uT%)k*U?(ltf>2j3F|lz0TP|Y^&aln*fBkb_;oQJ8iG`i-UZXgz6pBnBk{sP zgQEMJq|wt0WiXh=qG2Em!52IAg^lcHt>6B~WFb(Od2L$=^k{6mrN!`O&=GzR8>JJg zcFr&un)`_SoxPv&2zCB^vE68KWt_M@BW5H)V|?%auDp(EPdnUe@GOsM0_Wi)4V-;z zXdhQH_E*M5>Ny-YI9@GOaBbLWufJQLIwDZgeAdsrexOd~0lp1%?-9@XUpiz$N>0Yk z4Gi*;*-X1TMXqmD={|T<Zp}&hWEaJqQTm}Tc<3aGlEI+P8TjJYO42@<!{l%H)6j~S zT92r@F6YP#7SBkXnmUSk<#JJs;@}Z3(x*_jxz-cGd@mV+txqoojWhiIkgQ!{h<sQq zoar?C&6}~6N9CWsCh&jLa<%<SJO+PBf8JcL)3RKyqH#mEylyi6i`o;!hhOmN@ezTl z6v42*g?SUT8N-Si-Mg>}j`Pfj>KJk$M(1SrQdo@E=QMTB=7|UW*|sqcg|u5G^3Qfe zFIGk(v{7@}dr1Qku6_xbCeUBW!;UPkRBKNg8~VGRBDKrT9bQe&v^gscybx!jnk5P* zU`s85;%Wdin?u*W>!zE`h||wk&GFDn=aBQ6;l#cr$};F)W>w4eGRhONs%JGa_BJV$ zaaXogv03OX{z5hK;>`24xO0w2Tys{EpcVWz9Bd~(S~^;LvgmK4emlVK-g(#O32^FZ zl}zNPPv!mU1%ZyapZ1mhK;$YMANjy|o7c9mVg*+Z)(7Y0Vr#@;G9BVd0r?l7CEuDH zS4CZn4PHU}(u?da_JnTB-v7#u_4Ue7T2eacvh3K%Ih4%~gjqHCzi)Ft&$d71JU#m; z*kC|%#_h^y@g3%WTJvFz*0Ad|i+TRL4J!jxHn#NUpL?~3QT6w@%5NHnZ;dGlBHOP0 zOe%x~J~DjcF5?6<C@nn4|3hWx=)l!1`mB&3c}Mi4%(*w#qe6gO5goSn@h<livBCoZ zq$N0iStV{tUV>*CafjUPpd*ry4{nf5WX@ebYn`tR(t*4l<Z#b8P!>e`8S-BpICVE5 zaJ}3Tm39@i+E?q3khHG35b%Y}x|E^V@*p8A2ZlMrR__{}IOPii5u!CR+3YsRy)n5q zs2c#`{!JNI5=raDB?Wr2NSwFEdAIj*=Z8+1>my=~w7xB)`GSW0hs(l%ohzl`@2swB zhYyJR7Xf`nGuE8E&%(yJHJp77%;G!}WoU_OOa*4Yw;#+j8sFShpR|oKt4NlQ7PBYg zGffT1kLhC@fH8%u40$v3v3Fd~o7sQxUSJk^>Vb~iEWKF#UF`M>T;RSF%>Bc=yVLT4 zBRNU*&)z<8!1jdIJ1?1Zyju#8U#;A;^f2HH`SjiXbM&vjlFtdhFTw8sW2cQRp9>w3 z=5Nm|kgTN~zp<lHZSWMVO#ho6{p%#<KV4N9w&Z@w%0)8}_=1&{EnITDbPYI?mv1_( z-}5Q`pqb0K+{qr*X)R)2D#omrpCpcO+r)i?I{Bk7w2bf?hI$T<HIeiKpIkyUovm$- zORUzu74#Qfts9m8Gabhm^6f=PxAGsn_7$$TuM!uu18ohiAb<;+Ukh66MIfs6kAt-* z=y=1XaR=ze>D1f(V^R2yswT#J8>M$fw-d9|7QTE8%?tQ9ufY4U)x0|6kMd;I>MDD= z<Yj)RE3K4&VGC73{9Cls!yX@fssQ_&qL>-0fF|4uQ~%=z@h|CM?%|ZvM}GDn8?#eN zlLZ_8$xd?x$kCmSNQoS8Wtw<z0+JtUukCzRx4WI>=F49l%vtR$6OrFj5t%Y86@m%g zuBwxY_KZ60pw+Y%K1Y*F3Se9^2A}|dqz}A7SBCs43eNVhYKvmvB1v!h5Swc8Yzs(0 zz<CL2UsfHCpSP~TKzQVCCtz$?D%68S1ajWiU;aj{FcRG8d$j<=BhZ9Rasz94m^5%q z)dMJ?=dQB45~_K3;<hOWb)nbd9ubgGXDd!=WkJl>k)=yhOAW)tev;>!k=B6%3^xMB zlDyJCaelW&Nh~u-Aba#XxewE;Wyj)cMh3eHeZv*|gUHg#)4^ZIs;HM`2TJRrZsD!A zs1eZwE|4E`j}~gImo<%J)Pyq|eaQ`PruD^+=m6VQy(Y+DVx#S7gK#jNRT(&Y7C~6q z<|qzxX!N{F%$FOgMuj&taKe~iW9uw}$tk&#*E`pg7T)y(=qkV*?FD?op)Oflup&&j zl}-8(HC%TS*=s-3dV1<6SN3D_JCQREbrqMw<bmCN)@XKjc^w*-aypX1zUfa2mVHL> zGd+OCgs^h7W>;~!Pm4t$n4S+<#C>;LR-MR2?bw>hCH5nU7vx#IXb2epnHe1kClv&S z0ESE%nJVaH0D&N=G$9GQ!vquxchG?>KhK{Aapwd|iIG9=6ugGPL`16(%Ns8NNA<j9 z@;`DADo6jqWUul#QAAJFOk6BI(mq`k2fTiqtlfFYO95YQOsXP<%#`HV`1RrJ5<jc4 z!Lz~~d|JJ^gf*jvUnCUSX&W-JC=3ahpAaDRk!;nP{CGgou>fz~V=x!6KM~Y=-~Z5t zMuN{e-DW<u#>j5ahR6DD&%^MzWbQ1)SBKe(PSFm{Dtn-!P-$r0hnsCxlJ6^%W-Htc zKt+tGC#6sNYeKmOWEUI~ML(`|g|j@YY(RJXDfyJ!Q1LgxO08BtzuMG9`*C^U&Fm*_ z!L~+x`kYh{MivlUR(Ov7Rj>64clvxkU{B3If=2Yyd)Ji3<tIkuHpi34!UhW~Jo}ty z*q<}|DlZoJ@Nz#AwLGOizrwq7=C13_G70#3ups`)iYO8b8T0D=*b+V^G|JZ%jUSxf zSG4f<mF)XswTRWE7=m9JSL;8$-!cH-BF@Dv3-0Q$Fbs*grgO&{&)`#;q-*R#6F$b= z*DbAYge{uNqa?!3#|Db^DMRdDxaW|_jM;ftK6%-3;cJgy1ij(qKFo6L4bEs{h6r$O zV<rn^fm_9i@V877vd4!_?f!O7m*YK~412i=?4zdo2})87TbPoeSF&y(wjX1~?i++; zhyAMT7M*?ECv0-IXGsch+KmOeDh(umj_BE~w$SzXb);uMLD)CoYw)K19?4t_6ntdI zv~s$3g|ADl=xXH8S$$1u(=ufX=!3UbuvW*3wvv<f9@x^?r;|>N$)rpCZ`CjyskM&* zFFX+35n{><qLU6~DqfULemKGGpAu0MT;FOenUuJnfE5xMqZ5Bz)1Ot9<;CPc2YWt! zSs@R#2x17<)%}49p{ws>+k1T|F_x-$+eT)3C2PEbOWHbMg?56=>X;}x|0<FEN2zov z(bO~~v$r^G{ZsXMT{s$GCV8<`@U2PmPN%r~Q>qMLlKjOaPA`5h_9*Mxfr)8`7g-bQ zkG}lU3z0W)=&L!!px&oz);8t1yTSNBx8Hp8eugu&a)JXErwe2hJu@DkD|mubmMrf< zHH$FSG^*0PSSd|+0=tN*4&cJVpI3w?)bNd*Z0*t726SHVbj#k*e9?#7ONvkhcGgV+ zYwe+wM9&+Uu_^Ygsjpez9d}py{oov&4u4NJ-7rhb#>Pl7UJe!MPS;EQ>e?m~9xDbo zYNtS;XiJ)O&qL1vKfu=NtzvClFRG@64)j%4+nirT&^jhCB;NGwuMO{9gPK|b#jOTt z=M(vY#<@||axoHre%INxZeTStY_3!(v|Hq0jqxKHo9vq>UXnmaug+w4dS9!B8(j>$ zUy(3)=XAfCudf%g%cyb%#L#SxuU+CT5<Q9%Xc@vyPoc!gTYH@CwozDo>{Q@Dl^z)s zg~2Pj$UXrBtddJu(O$OIy^;pgC%JyGjf50TZ9sR@M+_MDBmt&WeM?djKDy51v5u{* z{LKyCvo`tx1`uE@6L(c!cU!eBh&AZzSELxZub$D(oy{Kf5dTF*-iswG?$>OBHXJGD zQP1hr2A`+~9tH_kz(B<)21cKv0n$4`JiL~aLrVL(zJpySN*v18Blj5Sq1oHZY87zg zZ!Cv>Tw9h5-4h5#akr4xtGQkPXvLvX;Ioom!-mVJXPFKk58i1UUz7otpohY#bP_Wc zEe&JePm~U4CsRaqGZR-63tkd%28GWVg{6>Xmhr%05?e_CmxT`hV^Go&lvmO6>6Il` z<kWBNeyjZ5oyA~(_AwAM7VrUB*GIWu>a)FMEdL~O6}8;Z-M}gh!ZR*^28Rel`D?IF zD*-V6W!%{23R@*kvDvKR2!|;W6}Vil_yY#6yRyYyjm|QsxxF5gg~kW=vZI!H6&nOD zC%2)pS@<RxA8s`6XE4)S#bNt}wFIh4(4>K0F(yy@DRbt06n{gm5KCR{oI7SUZdwp1 z76h+o!^A4YfG}hH>QYeb^fiZF+*U18Pn1KvN+854Wzt=u1w3(zU6Bgb%?0wrYvsgQ z+HnmyV7Zs~I9Fn=wzdl*XeJ!kN1Hu|^L~7Q15ZhIjLMo;T}v8b(X6`BNh9z97G%#< z4jtgH2sD}X(e_wk%a22-RNn*>I4XvD<JSc3I~2Iz$khk~#tc72msi9sW5{v#)0Y)_ zmN8$~+4NJH#n(8a`^8IFH;NRRrrbdvF9}Q$am_^T#~^;|H}<i4j)9j|I7HRnG9Q~a zzt9A+>4Ve-tXYS4HPfLvn=&d5ReYObd(I?-vA91TZMYiU<@&GKu{Z^HFbDID?7<sN zL23`yLjx9iA!3?8DwpUvCi@$T`d1BMTmL&wi?iruJtY|;_mN+^J#YL_An-1;bGB(9 zL(2>|u(eDPwBI(s07nxjV$7XIAdK*vn$L}gaD#DN<}oJ%T+DG=X6u#M{QTvOP40N< zWLA=@yXMzP&Dzz)m~Se4OW4&fI??fkXZ>)ZB4uPnlP?gyD0lj_ah#7XSkxy&F-7-P z6RVdbLp2sy2b)|Jk@+BEU=yM}uV*f3B~f8eJQJ$A=&l+paJ~XwCiv3KwKjOGm)~b5 zyxAy3T5iN}>0!a47B-bMIwZPw_g;!F>OBd!9LHQ##n)$~0FqY@3DZ7ewV7Dapud7& zj_3Yh@V=7%=bYkm^C}2WwGL$~)CZ*3V~9MxBBTCJ&a|e6kNsP22Az7t{m|V5{5%~0 z&RU|Ia{i*1hO7yIoYvpM={1S4jk50RD*^UZIKMb;qruDFrgjhsSspxad4MDHtWbI# zI|2$l!8yBnV&-Lqy5iI?#9z;Mmr87!9=~nyR0dF9#0}Z{$R>=7>b$R11YN)VK-HLT z<m|^F*_C6{o~b`(^RA&^e311J?YF^8VK9}Dx4#K#c3NV5#_U2E+XlaH9+3kWAG9Af zoQKy#H{sp=WnVqBH-6Fm-j9ZV4+;5u3Z|f1$Lra~!7K!+WiB=wdS3huXJvbFHeTu5 z0p7I^_D7-ISp0fi)*&l{)e<fQ$9B5=&3%Yaj`9#Q7!CLi<~^M99rohw>g9aXe+d^K z^wOhv-ZD^5XQLSrqPOg@z)q^f!CVM2ItgDf-}X;dSy}ac6sy>`2h{T5p$i_E%}FK< zNCTc|h7}MS8of5LtReb-L%P#i$}Utz<y;p8)1?IBs~l>cHjN~c0>1k@W=c25GI~`( z`PW~AV=dW?t}pa4?<)E{v7Tdn7od3ASf$T7rjwU+Jt7k-@`METsl<f<-C!#BZi`dI zeLUY3Awky8IV;SFc=H|&JG3aj`=|I!9A@7rsK9p8w8gGDIFC;!yQnal?tPm44~CZS zIx&@aC$DHoNFx}~(?F9??-#m?$BEj#!yz3~P(_kxqg=9zV`tYh3{71~-?MrN>gMZs z?{JKht~oFGBrO;-{==AW3b)>c<Bk)FtGa@#=8ac0aXr9d{h^>bR^T4{5rbXNW}+jF z{OV<<SML6gyb~_2sHD?Gq`ylZhGL3F!n|@J7;wf$KL&MIZcM@VzSaA8(~;)`3_FgZ zow^P0C*o-*(|?U*MeEdJ@z#$ZnZEQ2KU9<W#s?(dWqK>)u~>kw61!Bz*Y)-mXTmLB zJl8so$B>;Ycg>GLWCy#!{c!AVCOPi~W3yisTujNi<?%<EY%OS)XW`*n7m<|6MG}@l zM)dNQt_tCF5T`;q5}%fIQNC#l`Lf2it1Z_Pebc>r5)9`Mt}=&>rXVNJv_kiI4Ytm# zEH$CDp7IY~0Y0%mz-};EA&-D%Jw}hzTa0Dh?z#&FM$Q>wnO==Wq;y@-qvl2I*7xoy zHQ}y31{(GXB@Yb&Ft1>7bui=@3pRqd#jsE?S#MONA<4o<0x4Bj)`<N7inFF`;@3<a zhX<q`s@YUMuGzbnzTK*F1wTkKsIgk+QAE_oamy`&^e`S5N8vXv>KaI{d;+WC13^>W zaXk77JWk}s$lHwe`Ssr9LTAZ92O^7YZ|UpQyLMoCDtTu<+%gJZcGT10x~d@*pTz@i z`L--~`VJ=|+k)dHC_KdRbjR`9d)|&8E{gmfHFUsBBy)(mJ8)OC9g{n*&nX#aHgq5` z`%VI}9Nr}st#+*#pE`!l96D)_Q*J#2d32`{9B=E+T2!n-{}`WSX1iNWdG*0)7xG}V zHr!Jn<sFrwvN!*nnX1KEKRk~<U#yO|HRd_4IYz*nJ%DbvlJ+<fA0^+zyKJEz$38G_ z5vHcRi`U_cr@XoRK!6?dF!_<*GFu4VOh}EmVE1HgAcFldPPTFtwY(Y<Qv0nsdE^k= z<%X|)9W**9yjf~%iDNr^^%~-?x(}4C(LXb))@ydp|M17yrI%k+Q<%9^eENKuyk_s| z0@!LM?hh0j!-xlkVS$WZ&ZedL<u9CSi8kV_KbN;ODzXN8OId5hfGH}I2QGsz{#ta+ zg@IpBC43|F%gj2*6rW=mo#({s>3HKiM<eGY%Q|rH8gTE}YM=FHj8^CJEJI@4sJtHB zo$*#>a=g1Ly$nv<wnVm(Kc2K#SSb@D?g{r3n)^+vX>v4H>CvJ|X`Hc-OddF!V+BOs z<v{JRc)`2Q_rBoSfv97ysWhfml)`J?6KTI2tfXGHkT{m6#pe*J`S=Q(PVctrt5<sQ zBptiBc1?f}be|=icj%``cmz?6*HYh;mj@3;zpCNsdvP-o@jwnR{e#m6@TdPGl{&c_ zdV6Hsdst|t0rnCO4;<^!go=|pt4<ZM?_<?Bj{u*AL`8RQpUlYQaFgn1@4x6~_kl3X zFE0t=k?7p=7M)tRpLh}#*ImWa>CWTj-0+FF;%>R&dK5nJH#W>kW;2xC<qv*bz0vui zpft}X-erSm=GTymD?KYgNi6=nI>Jn^uq*hco7G~EYR%d-0B-k*z3^p1g&^l2_Ga60 z{3_d_FuR8Wht%p4Z{Ie)b}~5T8@Lh)rmlG`y*@tqF6|=l{PvBACAuID;c6E(f%x%D zpA0!YF-@Mdwivwlo9-7vaihdqUOW|7O^esz|Mc{$nTL^2+{>Yy(Ni#$VTyW*-JQvP z9XqBCY+(elt}<XX@K=`DEPJ<q*DmWye^oderXeDys0UW~nrAk<QbLl9%QVY{P`=n% zjRDDjzp;c$+Jc3=`?O^!WUtb#T{{|eF`~-=<E#W23I8p~w=}F)&C;q3$GPGiDBV2` zOWx#Nm(SLdRi5TowgqZvW3k_>wuN|Aei`9oqwny3Q5a?HGtRSR5yb6Fc$l_nUCk{M z8rZ~|)4hUVy9(uwaUS-QS^`pcFSoc_%=Pk|5VzzBjUaq%A^@f1)=ZJD>Pv7=!8Q}8 zs(P>P&+(pBV=eS$Vl-}?z~yU4as*9EG*ji*hOHzmn7mGn(rg<oYxTLdSu0t^;-#&E zGrp&}H3J<<wC$0$b<=gGrRvco%oy9O1!Pufn$o>@EzXa0B#tvLzVGmQS)!G$++q}c z6`30pEUQawwA2;NAGuel89hJM_?J$#eX$qnsiU=)+rB)Q!8k3HzE?UllrM3Cz1WmX zGjv7R^{jrbbMrn|zujMMED_*_@@v8u@i3yw_nAmk&__XdJOQp8plkX0$yIn;6HoHV z*5=xHsm3i-^sklH!x6m~Sqoy)9#6N51w@sf93QNL9@uP16P^K@@Hwd>w?1;bD~5$! zsBv|e0r7Cu<}^#~>*D(PNLs!Ww|Hcha=HCiDfsD9T%;qbdm_8bYz`V0Ez1w1i2`_t z+M-OctbU?1JWNV6vAslw8Q?vUy2yf3`|QXOtM=J_#4}s_Uy6GI0p+-4w}B?n3l78< z^5mFnb2-_4VLB?HYkQ{r`Rr-C+Q&!;3Qm>-p*h^tyNRhjB>}BmMHCy}yO`3DfI3rP zr~A!n*^OPbx9YnCqy6+3TJ5KxH1w-hAeK&5KfoECugCu3DTI-@IWX#5Uvg!vv9v5k zeD-`dtDt>EWks5}QS)e`C5RL2WSNdJQ<&G->wJUKht!W<YI`oc`K7JTL&yg(K&1z^ zT?<&sf%DIxbr|pierV}zL4^Qdo0@RSr19x~o_Y6jQfXk%dPTZ@`(~>~ZsYcI4PQIB zl?j?bZhFxhh+~B^YW^M(VD#NbnFjTmHC_tp+b=5&>en_8mo#|x5C<RJj0*jFeLVt# zsz=?Tmmh&ApIoW{JzbF+6?ffypVf-BeU-4@*<XCQt0g0J@@rPJLIdA>BXo}zV|00z zI-jjY9qpR2rN+{(Vc3jy!q~T&&=Sw}TQt8|7}bR@Fm(A@7pJ1sR6m)bL)_aYl=JN# zwfJi6_L-@KyS~r7{^|X*mY><*ommL-k<UV}e@^1hidcSr*b<Swm(q_)%(O6%Tq`&? zdc21GT@$%caSQc3qBt3~kN~m`Jq=NNk~?|hYwL@ccbo0W!i-a(<8S6_5B4T+?mf>I z{Ii!<?2MZ0<Ij#dY=*T(Ik~vjjpMqV-&~EGaLtbXk*v@b?O1;SX)&;nZ4vWJJ@l&f z`8O9zV*c#DI4Api|J*|_V2!Gq_5Iu4t6QffV|y>^@^wQ%l9eDvxFCQJ68y~c8O#sw zg{PUvvo=@K$P@|Fc*x>@f2@R^gZFj#$&x8_RS1g|o%)QR1O++*%m&`iIcABIsKu%v z<Fhy>gOW8(-5CUqc|9t1LlVDMF=fMh`SmFr^M1*Y9QdH9zGW(-U{Y3^=%8f4L9{K& z&1F0oC3z({!)x4yg8|+xf7%qBxuf9;SPg3{j|FFqg?gT*>0#8jg0r7J@B~c^3=@#@ zVKJ+&YU|1)B=P&fiISh^7voUjn?X7G&4LTuM%v-qO}u-u1)NfdG0S!Oyq!1Yq86!R zjXBd%+`qiUT@fbXE%zhE6buhMQeQeN2Np~ult|w~j2{omUI?bIm&^Vo;o|e^QXZ*Z z;f|V!_rG1kN3r!vZ6Cx~w3$lhw|!`BBKj}i2rXM}rYJ@mWL)OFSGFDKOP(Cn(41Wf z2JIJV?4`ciq_Tv66E!?g&wCY%>{R=6a$8F#0TtXmbymdEpv&)69DgXTHZFDnb$Q)5 zB_OQEF=vy+IQE*77Iu2J#NB9Q@tB%h9abk<e#iI%@=a0rUY&ePqgkTCo6@bYyDcxp zEN&rfU;a{TAV~#$P70W*6;}#0yx3%ON8Px=_*&EGC2_m9G`lcIrF+gh0c~AdZ`;$9 zY}|P7IlfA(zh8Z=C2%dr=_B%eH-57vq~+el?~(7HZrR<txpU8z<L7%SGTbJNx7nTX z-t9hoct?g^ng<WvhmoY!j@*`JZzi1&F9W*n7cVsXa((>pDlNRdinqo8kJH?nrgyE4 z7h5iUoSS<;_O7|3yyfx}r;i`E3YvNrTCSGQef*4k)X>Y@8XV~~zasvqe)M8%sN>xH zhVk{<*X6C(l$;j62Ar?_Kv`(LzVKmTFYS8S5^q~%o8zZ%O&rBvF1Fpg_2JXcF^+<R z^0sI_$IpMZ3UhxgwB4fl@c9&3lm+5zk9+H|2$66|N4T^n<jgL@Od^t*D%umHBbMk- zJNvkIWogy6m(V8Y0lc&v*eGzB^$+8q_!YSmhwWv~QpO?q){Y;3fh!n^S3J*WI<nh( zGJXDW)`39(JJOA!2>|{7A>Hn9dRmqLg><_w&yU)8BjUu2Yd4KL8(#l6((P}Ek}uz) zk6r4cDYBw*2^xEN?|lwVI_B88tNFtNuiKRuU;YQ_*2rvRpvJZ8G6j9x5>jWc?s#?< zYZ5(HXm_XN3tll3?dw|_rU;l^>2`1viE|{zU<dcviA5UB7JLkjEMMLjny~6ma93|; zXlOpFFngkG#$C)G1AiIXjQdDkTK>MNN;p^?$%EX*{aH3yo2oIf==R*AK89+2b5Rd? z{Ihm~<@sregX3a&=E{qEu5G!YvHL8Z5AIl;b|#{4F|tz_bB4$nrwFg|i0^EwEDYct zOLRCd!+E9zTJALyKt~fdg=E?t<kthG1re`so$U?UXc&S?K%0?ZB0)^tff7Ha3av`U zX88#i7K)LKVt5>{&1d@kJ<<W@&__1HavphomXd#2ZCT6cS@Q{8fp&ZpFb$`DnnU=P zy7TAoUS`08(ZEYWmVbyz27}aDbdo;Rex)#sS<x5Zag(j|fJ9Ff>P7B4`Wgzj6;Tqw zJIqwK1g0Z$HD7ORRX`@Um?c;iF(*W3h_3unS$TGMMXu8jnso1`H3itXw>r&Ou<)G< zl6Bo;1qa*`d))@;e8%N$-LF3u-)<i`?7UlXM?62UV_aEc8h%fSEw%PFZIG$eea?=) zT#&8*{Qb!!iQVqif=jKAZ>0yl9-E>DYjy5DOSh`K_pEY`P-J~=_xZ_>uX`_m^!!~X z2nVSx;1HSNNTpZV-tR{nMA`PSThUwB=z1@5mN8%7KKKvPEw97QbDPjEaJTtzO!Cq8 z;Y-<J$#3I|>F`}Es|Dw8lbS!bzrA8|p*i|*q+6urXxjAb==P1Jfz<aI+w+&dzx`iG z_xJa1KWlYoy$Ub?_-~~9(aw*LLH`HR{quC^=jT|M^zr{hx>H12kN+>E+qd=C{{!j% zz193^_xIQK;r~Lqul(8R-e~=^`(H>m6()1CKfrPIKS+1m$>F%l-pRK!r2FsD%=xQ- zzt8%%{rxe2eedtj#blX($E$@`|NYv$+xGAG_M^RjfA)uEPEU^BUp@VMywP_0@8sv+ z=_x>83BU}gVD9}`xM?MrV}wepz8{CqsDz3b_9C6mknZtHT9uJr)Qz*zKYbP4z_5?G zWS=Z*T7^76(#QUIKT$TLir&|-pL=dUNp-vmb$z6t@ArR@?rQXDvf%)p`yj>8w3_+9 zknV$2%ZzH)yM}|}P6ufY<JIhsMh2yC9HhI^*KiIS4#}4sWcZoZaK9fJQht1p8I)0j z*)SYdpF7Bk824OR%t2}WW(wUpuEG8X>E=G9q?p#?IYvkH)emzh8MT7{LAoolO$x@n zX3gW$fHIxD{~+B4Mq}0`hxrZvLApoBlA@V$6>2mRPDU@QtvtAgDhDJkjhdunR-1x< z35ltOBCRtvm|>BLg3U|W7c7_AUXYj6>%}PH&`PceIG{<zQ9|ekI4P>0w6yY*Fws>m zhGGMqW;q5wMX!<_hh!B<v8vs8E?apJjeM2tDf)bEJZp{Wpg^-bL*%|rAvF-EF-t^U zTU=op$Bw8mgR_&wt@yx1h@R>@3TF`#!jb}lBXyFs&|W<Il_@H)zN}uoH+f!<>1BS) z(kei)^zJExk~ASm-FygxwqL#U_0c|plL9bKNm70mj5b^ar4<rINTva35%d6!9Cb3% zdA}?!;|QY2=@0NtiKo_fV!s0OvbQ4BtU9Y%3T5?~9HtWZ2-T=Z4T<9Va^p5fGdx#B zV_8pvEnhsQVD?jB#JOHGzbGOz*que@s5et`w-;eZO;3kcv)`k2Lm;?OXlMsa9Zf=~ zVGZH?_miykpa?@az)J!6NvD1wCTNw&f{VDR_3_)b1~`p8qL++=0vv^#Bnew9(^%Rg z*7W@$ZY0*BikU6RfFV{NV#%10Qd4JnB&t)^LGflKKmA!bTm)XE|3*t?g855b1EW6z zv4mz&Hvt3($4}5wUqs#fa`nA>+64@l4%7~oamz{D=(<fUbB3zcn=JIIe|szqmC<Wy zydXWTi+v9Vv~{Ag<3z7vkKLLG6dXF5tP1REjW9n)1IqNZ&%t8QO#el&pxavuuvk_E zO?3jxj#NpK-k{VLItfP~$MU2|4^UMwjmLgKv(#TnY~krgWhY>B;8cyNUcHD#-GK$R z6pb?`JtFM<DgSrBWDlCYb)XwExXfvwxs9XvObPI@NR6c0j3vhbcyuB=Jl^X`w`-RN z8>JhX_eU1}22Q5h2^(7UGC4?{f7G6&<&Hy!*vIA1adMh9s@qEq`UhRdesMG4|9F79 zLhFWE<b<h@bbP&%yMoz(C#$}zLS2n=#2yfmRTtx4Yvc(4p(uh1beVw-R>>b{Y1qYf zm;#V+bm?6mMQxWZSVb(O&rZ7u0Zf3^w&I)74CzFzorD|Coc;V{STS8lU_2Vk=+0-D zTs6B8Q7gdfzW{HiVIFbe7~uWOH(a=eVT?$DEPqNFR_^9{ojg(~;CI|T<FbXY=&WX= zoWeJFGEC?yw9h61KaM!w#U@=wcd;C^yK6Q#x+mn{STrK}o|_TN3O}-176m;fI%rWe z=)5p%hK-ujPM0s03KBpm)DeT;G<)Y|=H!Nc&Y|{Hpj`tm`|6N8)-v|OaX<Hz-(CNZ z=e^b+A$<Frky;TT1P^SHXKgc*xt#DR&aWS{DQj?kCJt45OKpk9N>i2kdN|7=86<Fy zM#{k|Im`fe))ksqck_?+fusk<kF!}ANq|KB=WdN4Wtn!P<bOWF26}X}ETm^&g%b9! zEGZGiulioFAT!+g{Fq>Dg>;%)MpINtoM1vyLQ{NC8~Krrn>Ir<RhM}iO*{ovf-(*K zJbnl(4jUsp=yh00UyN#DcU}-rMzGKDZ!CwT?FG^N$BX`f*N_$ah)s6b5F5~l2I>e* z^Basw`!pXZu=qO0?DklZ&QL@SY%G@HGv(qlMds+4i&x!n5AbNppkg%^Ie8v-&C=77 zf_NBfT2F9e3P$Eq>2fXM>6M6&gp2!@4#H%{wDSSrU}0$0RqG>EngKuD*X%wzh?MIi z6)U=wkCrD06>Z1|u3f93gq)GQrR|6Xs}TDFOS)iW2^Nt}K;&D(7xv*#7a4n41JpSH z6GQZ_E&BT~X>T6|T8#S^7si>$u#824EF*o<KnxoASIJ0s>JF9<N`zBE>JVAM4MgWY za%vcH2bO?@+syq$Uw(@y-#1AQLjIFwNXOn3hNjR~G3v?dZBkKZnYGUZpFixtt0XHh z2qmTjvxh^(`!BrueoagT-MNTpJ2I+*Gc6pL<nO~17ip6Sh|LY1+e&($3F)r6=^JRn zBvHm?iVwuyW|k`dV%6^+5DnU(%U?uBeP=2sAadO@eU6C-i(#&0)Y@WNe=ft^Vsg5w z{FjkyF4qy)*?>F>vZV6Ncy!)<oxy5#Bdn0PvWT*Ouh%3jy}fAm7NCD($-rxKV@DX7 z{VuW$pxLiOv`(Gh1u@^T&0$nDqZ**kmJ9b!r(z<o=;wv$*3eu1@+cUGANHH|MGpTQ zOImOoT?yLxnKx;%G8<Y&pNs}5c(nGfIPa=UJq?UcXJrNN#&=Fd2FudiMgvt?q!->) zK2<k{o$)a{@X#>8q49PQ4)y$}EX@aG8-Qq~oaw%27&}5^(AirjS8Im;@{hpopI4ty z8Il}OYXq~Ayqw0o+pM7cuw}nj*WsbEG@y1w<Gw}3Oo3*Y{cnIDjAPuKDj5@C_`S$b z^h<q?QiuS7U>z|oIya)OA>pHR#t1!5PGHx|ERs`e!7{I9C5W!-8kor^NwxHe8nSZ= zxmkdK$lXj)BYh7_h6cke)>0-;1uFUzN(T;2n)i`In=znDWPnl79xnOJg^#^k+zVmk zFv{;u0AR!{6`fqMS>!7iVrvLt{Ug_$l@79W9fXef;a}JicgE9JK!R^7TT{R|B-}9( z1RyUDmg=u&gWc)pVo^KTa<nlIUnQEo1Sc4YbV;Ur<KfLOo@3xehQ?KkrEy!%f@lt) z_hS*QUCB6WO0z5-WicigpxfyxH|e}eMhis#s?-qYIt<E!bW}rn?}!8y{B@{J=CXuw zA%xw$`^lA70}O@^bzN2{;m65+-C_8U)MiV%;qEKtlvwHE`Y3Uxn-2BJ-moM0{N^Bp zyf`#i7F|IQhMc<BM9*oT4}$5jpw0%t?(BD=a&Smh%^NGq14}wGfUsGFx1vqGW*hu| zH|&0c<Z=T`*lKxCTksN01P#On2%wXYBdiDuH`<<dWFr;H-_&&U4f00_-Kt-wxB`=! z0>k4N+JEzIs?m|r2pu=tM_BLokIuUrHy=EpQIbU;bSkoP0}@S)pS`g!6zLu;!W`Ua zbEwGi!6^34S{<(_M_c&TQRbMFLUCoCh#fz8y%e+$wGE<^x{DM__HW#3*;z>jQ5!WL zTuoBF8>NR7i>M{b#)B4-<=EyQTkUH#cWC4oZ?BaYJs?k}$<T(>*H$7QQW3HQM8OpA z`%{Aq`~~e6go~m*I@#@h^Qa=*1@sBmU8yDvG(5yr1?B_Ll`dA?<-V`>Q7evgAG8l4 zQRojV>zThQY;gdtYUs7cd~b~5WJ}u6MP#Sj6``N`HX8S1jv=B!XwJ2A!*7A%8WM0U z*eXcsYj4zzHCU)Dyo@5?`@8FlZq~UefPNohN}!*gLXC|oN=<<tZSfYb-+#D|EZC=Q zcSG!?cJIFdAVm6qu_%(dl7gH0XQErPWdl4CUP+*vzmZ*iQ+qg#29IF;tFFkR*9eJg z6r&(!DVJX7#J^3wl1zZNO(8SXy%}yk`J6`sS;9xLw^%4ppg9Omp`NMNyxFHoS6tsC z`_l}mABmE&=;f)0CN_-4v5k-e)b5OR=qPuwa9a@?xVi{y#Cms0JX`LsqUmMWram`S zfa-dnm6gs$&VJ355V4<+t#2BXh%;_HA-bwPf-I%%Og%Bwjhb!bE5mtTCBO?}5umlM zTQf9ZCe-#~FMDUblK`W;hWWBO5B<&PHUh$;J%!v;kUYaM`$Xoknu=s)Z*6#|O+RX* zJ%%O$Blm~aXA$<$lCIw0;5UH!eve4PqH9f*ulqR*aRLuLs7VJV;~U6_Q!pDWT|p)C z6&-b>1{7MF=&L{@Ziy~Q>)$;vxo6q#vyUM6*n~Kbu;3Uw@Mxn`H}t$AcX4<$NEWVz zIlF+3SOQ086HLK5iFc;VTm?|MTwMq>#;yQqB|rFp>ijx=bS&p_K*9hdjzNA~saqc% zsR@Bh_355)25FwDV(^y57tNa5UoN5d7H=BQEAgVCAS@W=M!PUbP0oqGHGeN&viDSD z{6R3|`zaK!qzW4Wy%d-{jXBeKQA01e_tYd@eJ$qbd0PuqxUnjVZv72a(O1!kLd&M+ zpwT@^E}U|i?-A{tLI6*B$*jly&=T>S9&!HURbH@%`y~}_ONKdg#Dx>32o9j~gVciq zqepHwIYIEYcBCTw^-2xH+EXR}Yp50KID@nBUNN2i=_1UnFtuXQS@a^0kEZ_b_US;Y z8+-n^m{B8*i`pC~$~EKM_3p5@zpsI=%~&s>L*;mUO5;ChzSUrel<;^}b1+<K6gzRR z&*|bjS|Zp}_Ht`8N2wbW6nkaDL^vzpo%POm4U-T#opRCOUD(2VC}_r~>aGXnRSr9V z)p#FMuIak15{0H?yvSY~gz)7+h^dTRzCHW4A2{IxK3EQfCb%Yph9S7;g;U7CC$mKt zHQ|*Y%<)99F4;tDVowZBiKQEJF#T6HHxSxPv-BZQ;5LK^2FrEcki%W2B5qu)Nxt`S z;tf!msbX#bmX(@MvTE|cBHGc>v-1~HCgvZXhWgI#(@r{~pF}A;azQ(IIdA+%#Gs=~ zhZh!h7J63BUhEP@zWt#<%cq+v1{BEByS__**=i^+{L#SeXvB|!(gUf_odOL|T$O}4 z<2o=OszB>eN#pX2qq34R1$#R=*nV$(u}h%1i?)4z2CPvy9#q5VgogH+EzH#}yU2Z{ zMIjooNbK%?ob>WTNEiYQVh5vSO_il+I=~0ZQ|qYz!QOpEHQfgKp8uy8Ao<fn54{K) znsf{hx*{DElp-Q1Vvw$&NeCn$B`DHFq)Jr*MG;X$2L%mH5mAFm6%`N_QD27l?7e55 zeb$<_&YCrA=4S45k;~+HKF{~Ju_-YUe;QHuVdv8iotNI~xZ?G`>|WsFBeOuCFXAag z0qVX7k^-{=mU6{UA|*6tNtfJ57=WcT&N|)bt|kh?2V}XhVpp{Bl!P}G(?pAO*@>+t z&pka!%;q5uZ8gozRMu^j;b<1t8T0r2oIt71yBX?`motdd0P3G6p*hz@e_c#CfZ0sK zXqwM4<(2koSzaQ7-X{q2;N5337HcGw+{!d$1v<a6c;<t^AKq!i2x`Oituv%Qj`ub| z-FZcB_UIS!MJthTd4QB<nsZKM2IOny9fAhB-~t<Nwi_+;aBG~iFkQ@_z$;;$T|CKf z;+5=>N0P04KMh^ydmPLkgQKsN7k5*Hpv|w^ifZ43c$>EpxKYp<r}ai2_=A(&{wuFn zJ6$KQR1y^Ky(0hmQty|QrJZp6BoES-4mb~ETFh5Y+Prz~{n<8`mJ!LXpkY3Gs|lY{ z{<Wn7Mm7mV$6Msri51Y0-}$c>ziodT_Mb(d?H`uPEwitQ3*HiYYvpH+F4otFTjlTG z^N%Jtr<u)d1_WtPLmE_YMZHG})iHyJ4VP$;?}8~#70j*sjyl3RQ7zOg2~T|HFH8IW z7ML4;23V?Gg&}5sRy_zfw@VxISmKNms1u)4<g9*l-l`}0g!FUE!khRH)b)rU+*c59 zX9*S>ZCsGM3CoR-*}g)?Nk+P2X5jr_2G@rpiML3_ik{zBQULTm#3rYtu^cyBhHL(@ zfml@!jzwkdSFgSXsBG_sawSrDgP4&`M9T-ss-O9fEzmjuqzs56|H|Dj{d-I8B7Ee# zp(`vv5IWP2fRuR-VN~o_Bwii@Kg|899~Z*CwLJ2=3)1wr(d~QLAwY;009a+pnI|kj zWhsTOGux4FIZGzNZ9CG9lR~VVCLOWOmb2J-2fl-=c<=@;TiP~b-2Oiz-5zs$iw#e{ z{m)3ZRH*<JSG&K$HcQ^N*t2dg1|_HR=dR~*N-X4wNuygOzy?Gmq-Bk~B8F8}`ub$Q zVP+a`pM3KuRmSIwe|zlbx4l<<z8*je-YR|2ey`?!Jmx-pqw~8Ha8qDWj&jU}G=1g` zPJVE}%7qrR*@aE3<V<WoH{5s4?&`ts$6wqyB;!Q_g2tFOTLEL*NlhbNNUVUI%CVKZ z`v);O=KeMJ@G8t5tUWCGL!0XrZgm0urB^GNH3F}~w+3#ObTIdDb9657HWPn*e)E`> zbLVi<=J$OM&Z3|F(;d@mqW11qb(VvuZ60tMQ+6?BCx%-EC@@LZ7_+78S24SKnrh)8 zPdSPJjEhoKKkiyf!>O))Z39NfW{ZKY5dkp`Jrj+~$o)OK_7nVH^(BlLxSoTenMm0# zW{={r0pPCh5Qf>|?p_{dfF(k1gQIG+ugg<CBD!G9YMw^FivG?ROPJnOy_Z9)03bqM zpeZ&wopuPv9c(P`HE2f4|2=I!*8+i+A+PCtZV}#6G$#ge_Sq|Zc9bQ4cdONM*wrh1 z1sIogmp>~H4a!k`gUMAq)NbNQ@`sWT9zFrd;>9VEiNfA~3ROBZ7+60qcUpTwSI!Zp z5n668t`%A=d;h=yrBjfy05a_!v`+bL<vl5|iZekEKX_L3m6+S8de72GUlH%?_Z@&M zy2Sbirw`-Y@A;qo`sR7zlxu^!?A8h*!5Am5*Y78%b5h+o?Z<Ww-3`x}e<S#r$7ZhM zu=6$#Ju$Q?+8*S^eqC|+{f~>agIRmKpaXX0N3JFl6tk4IV_ThxZnGje`{tx<S}RKS zx0SNggj`Zz`00DGO9ox#VtX+07;)#<%&o8n{fPd+%ITtC$8Q}HC(;jzIu-4Ukjj8K zyv7|*&^!1j%`Ec%eA>7S?R6jL8q)#YX%Kd`(u~@92^&xCu7(l;sEEofe+x?N59*+L zO~>h{Z}e%d4gP;!J~B(jqaIqR!)8y9?f>ZzynXr^&QJL`vN;-LVrpg?Dtxdj>_z<i z!}xc%M9GSYU2bo@C53~h6syl4dz3hT?OM`mk79x;HY_T?7DW3@7q57NE{FZ8QF zPWpCM`uCCean1QS=8uFqMS;}F=aDC%liHuZ{hWV%eoKgD{{h#6Qdik!y+F3NSpUHS z{1?yTRRSIojjiqruMnT2Y1g4Ng`eY@TQEWp5n*d=Es_s<tehptK}n5q+ITa=Z`M=R z+b{CGzqpR^`*M!Ab=#+RE8qw10a9%zkd@7{7nI$#UQSZkt*hzcmt}g<vn{1(mttpG z|MJoYGBe>>dcd+2E*EL1_XVC*SLY#~LI4=tN;!!$uIM6PJJS~<+41Y?aB&g5PH#<U z0{r92e`fQa$uT9-<pD(TU&O?OX3LLd<JLFn_=KUT+yYsTr%;aF-Z(wWC1Yh~#SH#w z!f2k;`;VGl_no}&>Y1+cDt8?HwMXOGXufIs8-HW3Cw@xJvUEjd%NH-5gWsy;_fkUl zX8i0uC97ZboEd6RZ6ch|*j+TX)f2kA^_Q?#<k*#W@EUC)fM!4uDV(7kGo3ilZ4mMW zf=;&q1W!Nv>-ClBYK@kCd4K;or!llpx%$=|0k-qUSQ#qoIu;t}C|pmcZ>v9RRa4RM z!RQLSnBN=}ynNK!Rag=c?y|1i$0>duHa-~wSYtZ<^T(?-OfOOse!0(Q=|eEQ1*3ze zR&t}`HL`<2W`XM-3#!C~eR=j;>Fu66a!w)XAxmFHYIu>kq|>OyFwfRA;Kc(m4Gk${ zkVp>aM1BsPh*ng1-0l_8VI%vwR$f-xakTX?4v3zz1CYNSt1j%9-tY}SwCf=9XnA*Z zcHj{pPHXasZbO`s*!3+5DVfpT5qD~~yEDf8nJli$59&+;%E;K*s>9;NZOP01Mx3-s zAn*GfdbEeN#BXx-qaS4mdcVo<%U-XgcP3vsD1&&=$$Kkp&<f~$S&XZG@o{&2{0iGi z^}e*hytkz3=AAE=w;>bDaXyBAZg9PdnW9%`UUtmeo;qW(BZtdOk-O=2Drwd%U=#T) zRyoAZqR=nkpC9qo%cPTAD^cPbn=iR2iAn2^%|73vR0-#McQRDXgH|XpNkZNB0-7B` zxW|3_g3P$52IIxgl5B+J?4mLPu!J=@Y`YU0lIUfAMEag;!p~IsyPz=aCXuoI{>J{~ z3G)!89NV7RD|kJ^R=0kb_^ZMFY5R@v)|y|erLIEmo~C7+cRuqLP(6UuSJOAWb|&O= z(q|27;Y3GhdZ1B+vE}Vl-OCxCRK{@LrEgcyI>J=DKgg{(d@BxxTyRu@Q_t9~3!iUz z@OQ$d<;8mf0}5WC_)Lu^{1O|m7NxoPAB^k`Rz78+BkCe<|73p0Ub6kkHww2lH9ncp z;5e%1f@1lxo3%Xz?V01Z3{$ea=313*f%o^MG>Se#bCsafg}?%BN`2&Rm-Z3nyyFW@ zmT{>$h;DL=F;%?DzB|azou@wkC_BT=ktp6CBpy(c+(2Kb#UHB(fD?_lJAZx)-5em# z|5hfyO0z5jfGvz57xHF=Ww!IIsp{(o#6xLb8lZLfd7qNR#C-$n-ai)tRBRMhNvQiz zXVJbYPu{B^JJe>-ZU$MpE>)L*ueBqY7+N_!cS#>*oK}p<(51-#Fn?3i6O@fkX%v7^ zQ+FIc7oA;IS@}<Jd&BVqIeT_fYIylqbf%7;2pRey7b#afSozPzgV}Ncb1Tmw?MK=J z{xB$zFpA!}$%74wua|We_X8w(+L=t)yZBvW`DyJBbcjrX-tB{0WX1H9GU&>#&b1G_ zjsjTYz_F-$rsWR{;}BU(4Y0pJe3RVZ=J0ks2G(sB8(Zel|5@^kF<S==&W;wldaTXz zuYE|#S-qL9O8LBs<A5xQHUv8q`8{&)Ls5Zyo*}^?s?HX$Q;d4+qY$tJJ~3WKrZSnI ze|-r<nKM2a1`*4FyJ5`vS>%^f9`8248XdR^4NPkLoTi9qemLl4g>CMBw*_2Kft9ra z1a6yfS^)1_WziKE8lq1C*tfBVxo{6Xl-pv$)^tr1L<1AQi(3z5+Hou>6*4kb9D}yh z(Lswnj_BG-uCrB{y&qZ`&3e;aV1@={%-PG~Chg_9R)m6|0<5^eCW$1mXp$ww_rd*N zsbEND>IIn}%3T`F%eDOc6x!{E`wRuNmE831&Y;w*xm_gf0&||^nln0T!CKd|du-|Y zmd!zQGN^NlzB6(2f#IF*Y6fcrOEa7_Ok>}-A2eh0)5cGCnZ;Ds^H4TnY>YuqdM!3K zkQKd=cK-xg`c8pCM30{|HoNZf-gV3=4Ox^1`Br*{>3WX~LrJF#&wDETm)$X^M8B?4 z>tWFIGnk?%EV|y#zMois8Z<e$tm1k*|6^cp>v7gzhm;f^<irXj(A+kZ&H8(~uLP)0 z(I_!$l8)Qx4L7fjBcs~i+ZFqwJ}XPVdMYn(b(^Yv{ZEQmji%YB(Y^-7oKu1Ju}NZa zlbxGwwr8s_P7Zf{axK)RHO{GAPtdSqbQBkg4lqf!Ol{F&vw;~R>tu{W5jt-xZRK_p zVUJu8kfxFOqQSvuuzSOypJRYM+EkF&N!eng=%Q(RYY{#gsd{H_mHBq=Vd63j91Hnk zn<?V*McvjPZ&h9xbfKD?G02&(22-4v>;WNpVO(RwEq@@@B}|Werng#<P!f~Vb(T%F zVx3vvRVWDjgsH^5cDT`#cli&4teg9#*6}y7uAwFMdShBkb9O9<#YLyO_?nt3?P~3i zWYn^#MG!~=?Fs`bzv}qY0Zw1e0uqJ*U-8|W`qUDVPhn~iOeJyBzBBV;6oGX+F$12U zzE;b!leS(mMjl8<2NTn}1{6PWoOpMJuf3=5YD0Jq*b1hrJlAAzJ?|Kv*;^yzOIhJ| zrYEp!H_{TFoWFO$4=O&>FetA3l{S?m^o@otgPYy5Cb<aGtgk#<(kI}|(eI11p&J0x z0scEBv&$DBuuQs3*pD6O&OXf^pr8{uVkake!}YXdz-P;hRG)>rn-t!?$t=5CB$M+z zsml^~;gQb*bJUq9p+bjJiM3~+wKa*^Uu1`%X%0?x0)`_uMD{b=XsKWkPPK|X>cZMU zMv?o|%tvId)>52kvXk83=IEnM$YxoAkr?z}e{?VpHHgk`>KRcxq!r66mLjtSserr% zyU`z;3xg>6vX?Q2>Ijd{`cdTR45<a^<j4hS_TH@|clH_J2`P2#M(~Z41eh?NOmfxk zT#!i(D~jLfGe(TpnzBwdr6IlUrUc%3K+1hfr85VR5d%A7_)o~yo+*0TU;WYF%roi< z?0gU(DB`|pZME4rZkXBOHk2OCrVLP3b{c1<Za|2>?0Dmy(tZd59WS$<7W`UztS<_* zWoy&eCs&jLKa*C5yliAy4{b7Hn@AnHg27=@r!W(+Ps1U@l<2ZNDF;C44{@JrMjy#t zA{lkH=S8%T=7X7(6e3-a<6h~zpBV;#Wsq;inNMWh$|*0C|JKD2P>E&8JacyZ@o^>y zkvC==@=%gl>ARcuocG1gG`XFtp4>_?MNxU`JH+Ws{&sBo<*N(*Ib0w|yTqVmGQ;*j zdVNdw)lsG^BlHhr*9sa$)1@aNskLd-Q!0wiuSzX+G!g*;G|eIvP4GY~@!gq3ROE`s zwb+AwElu&s7cm;Z2klYz1|yMoS3>V)&G&=XE{-P1O@S*Jm_k}^GTUO`R0==seb}?( zf2Z31)*W$WsBqAd07ST!o^_OMqmgD~+!4QhXU*`tZ|GmJDQH1KKe9zjmeEr-Akx0C zQxaHRF&>KM(?eGqb%I#o;AARi0w|o$I)fUdDR=qq8}@orJ>`s<&ikE?Nb*7(DVaW; z&T~BUX8N<wpS|oDE?zjEbZC0w&CFlT7zb5nl}j|>|0yLj!xBQ8{Ff5i#h)IGK8mHQ zy662jB{U$UceP8b4FW@ME1}^3P(lhj)BaNlRsWX~x?Cp&=tp!nZ!4kCMHA&M+e!$h zYOK^W!?~z((3KGU>3=Ap(6$7k<_%?&%wWQWG8ct(^$Tg!;djETl+TqOmeY-~lkV_+ zx~+t+3p^0E;rE%`b^ZK~dMGKz9MZP>p)WqBPs3V$ZJt-D4A;BN{{l4MQWjTzcy`oB z@YKGo7;{&O{p#DX2A}&T+_j9Rmrt*qI>TU3qSSj>ZI$G{CozUh`DA#Dia#(X>?voT z;B_aEZtEt>6$nIo5}0Q`+q)gj`kp$&BAU*2D_g?L9BrM@G4II+gz*Yp+-C`EFU1#O zqZycR#ydNSK-ZG2h`)ENfk{vTP=5d?4-43|cuoo^qjObU>s6b?6UjKw1HQ(gi?am* zCN(?*h`-th&D5<+AXCVK0p<&(&M6kg^yTrqf+LN2nS_}G^Ny+=W!uT&Um{#iiVz&B zu7GiyL@TS9@=~Q1^3<>5^~AcW&&Mr=yJJK`O5=o5Hy7&;{bg$%hwKgKlnGgEK|};? z>eb+a)~+)SHwteoeY(Zf>Rm)ghD?DqooWq@j&ikgV(PA@J3s^5&NWJvjVd6D9N78k z^F98*O2{hCu<#DFQ>(TLZ6a{OF8wfpjOF0+I)mR_Z20;gN=SO}Q$821>U63~tq!UF zUrK05^ue|g8V!6Exns3Y_J1fLvyf)D%V`m7gBt&n67sKU-fMgL){yah<F*oFg>?>F zpmhE>l#rpbS(46=|6d9HzovvPoai@Q8L)raT$w`?torXt$bp|3ELKJARkl^k_)%7o zTj=knqCYrz?`nlbsIG^)J%;4g9<F+*1+B5Ih)%ib0iS0O31Ui5ayS*@5RFvpNL}Yt zKFYkBKC9*DI23YKuOM`4NX@5ZFMZuzBu(SG!Q<E=we5qaY^s_{tQ2j3>3cCV$T1Dm z5$9CqoOm-ZPaZcJj!PR5zZcfK!)^o<ccx49-B69?&%v$d=Qh7x`@KA8>7|SHAdHK_ z5_@;_L<{)HdJq{TxHTeJEw24rMPK5q6<5E^$8xO_x(Ii`uZ>(RUawp-*HrasAH8I^ zmYbUtem2iB!<A`GoEB#95M;0bnsr&_cFJBMeWc<aqy${C-r7s}g5NYl(j~RtqsD2X z{^0leeZyM2ZY_<c?*1;mnVD+c@ARVi?t8Hi+Xk&jh`_3=5^#iQBl?1mb#u_G?l!1D zjK4ibkD1#Z8~>zPTrA*|RDllCuokw2U=Ba35D(UA2vIlNeuoAX;h=2@OJ%Qy<6hh@ z6FP|pU#IkF{kT&jWE1XTHl?)AZ?)iSOA+W8uPrpQR)6@@;rIvnKhbbW=0mv3K^f$b z%XiUx8_XS#H20>J<kiCHJKgq|W8M6>Q#&g?v3piC_OsuM*0n`ycl}OxrW#3HGwxOA z{2s4WlYDS3tp4;>)5F&*;vZgfh>$`H0|!0zu5}2lxECL|{-D0=u7o&Sx2pWWvo(gq zpw3tI-8OGv0^hHJt2Ja`>bU^SK%#;>uenn646D$l|J%S;W3QFt{=881-ddZTVTz+L z`!%uZ0o^a-<=HW4xEv%f%>YWwjzU+-!QA>(pG=lD52X{Ig|RI}T7<$l>59vNEVJpL z5M_l(F@EDwV3RN4K;11kkd><C8x>TJ&D*+<K?;^QDq;;$Kwm7)HiCkk^Jr3f*5cQ1 z`iP#Lu)Vbf|D|l*vnpgOBP<U+kW#89l8>ixp+vTo)eka?5d#|(bwgSGK(`&W8x=Kf zfyx@Yv4EbJ9TOAkdofAUug|=f$S1;N3%T$iOW(rwtTzfzw;>XnHG)#4?7vc&0Z^or zT#N_g(IQYw1bOUiMrY(7QK-tFT3~-RyAq|e^l11Xu@Q8LC?s-h;QVGq@7q>*^H0&Y z=K7Q+5IZAeXqs^H?LNeF^_1cE(`=XmoX#?Wl7w_R41ox}H1kJMw(85Bh%VjB<QD2l z`W>_t${MP$K>AEyQ3NZtL~zn@>-yBTvN4A;m>TvXf)Yk2T0WDBF)|;r^bf8%pH{8q zBs^9jb7-hh(^i9&i(RKF;=a6yNIa1HWg22K3Z=(b@vS1%8AQeBz7CeymP}w7rmzkU z=sA@-(HqSbP0?I>FhJZZx_wwIi59`uxJ2SqBq0m%$EW=Hl`^Hfhwm&9p!~=n=$W`# zmjN?k@^_tQHpK9G`>C;=oG_In8Q3C={73gA5F@Q<PQG7-IDLlxF=%!tNEhG)hIjl~ z_ymJkPj4YhNrLdYf?waB3HT>;_utvQD|MCv15k_(B{97>P0Kx2AQe>EJq;L2%(~?O z<FJ_n@u)4cDaay~t1LgoLS1~W%b|u<%4`71z?Z0;GhtVWrFfb-)HRb{YXve$V2~(q zw!oNA5rB;xhmH6&QoTp)!M<ZjKh>N9?P70(K=M%pWW`km8Ccg%|7`@msfo0OhAeQ7 zy2c1W%J8rt+-hLR_G-1sJZ|>iL2IG6fyofwkp)-WJQcS@!@VO%ZLdZDyIRdl{(Wql z_TXU6R7jH$g#dJdf>>c1cGY`(wHoz)_h_rs6ER?V<hUIfyh`=XIVL5X5W{m5XrqD! z%~Ibz1H0!<X3LUc<tf`5B%(=qTL$g#VQlYH>kbHi;2%9ScQk#Dxjpnv-nxrhqT;^r za5iDMw|pV7e!9R6Qob2^%Eu7(1KYrl>?eWmb3Jg)X%Pz!9Ez*@S{ejETu=w|NJ4#N z4D2VZ;s~D8cMk2QvZs%7L{cyug<s$@7dg>t<!nq88!nu<3gX}R;J<>vS7NFrgecB8 z;HmD1=OSTIO6OjJ^}aDjyE1m!x^^0X-ek;8lF&a~fjk<vl<EgRW-=xD?*#P_8sA4n zKTX5+wNV_vxa}MKcY(N}fq#dmaZ-S#L?Rp#QZT@j%T>p44Q{Jp?;_+mAO_lrk@QXY zkq^!$B=sqJ=(b8#y9#`TAjVvUR){%mDvm$dCaGJsEX0h~`2ouFP`ra$?x~qfm=zA@ z#ujTvwpbh9g3Gf24BSoNa@CRHUQj(fhJ8$J&KJAxDPTW}coc{tgE^<XoMQ`3J_GC} z<Ym!C$~V`n_vGUjJC8`X3H5OW+(@7v0C(0uQA@+>tAoh^!t|(*Sk%RDR@iGj*oG$b zTRsv&MEpY)!24V-`G7ke4xZu)tZ;>Xss}!8V?ek_5(p$}g3f6MW-MofmB39N#<wVg zT~t`Lf=wmiPPhWOj`?tLmJ!BeSM7O3ry9%+_o0vSnV7d2#opT{kf{XDmc?$bLf6)T zFg74mre}t7aek4|<cb;Y^FO||0s2T?=`X+7dLPXPirO`c@)EI+>P%c}FF{u&5#=Qg zJr`d15*L6F4iY~}j+mW8L4b>!e7wL6WQVKL_QJGOncj^iY^Ee|)EG31&Hs2H8$69o z;|txdyYk=_wzx?)oM2Lv2#TuPz60<ZnhMr!DKM)j?Mb#n91@cYSEK4JIL5-P(EmsP zH_F`R97}tT#mG#RD_|?!`1q6+bh9G%y{74QvTv&FTwrkCp1C7-Nc<YefGO_Kuh;+X z;ASH&+~7-;UD}3P6;5O!R{(X+!DMsMwy!py>t4+XtyHu*0h>A1y5d~}1_#s%4|`r8 z&Aq-{cO`(I{(6g#=Mw;!lF1Agw_azfwxRQxocyXufJ;595FL1jTg;G3r~`co?ZO2? zwXBRPL=%$i3f$x4Uyy|EEEyk&t3W88Uvb5E0GLxma2f;-N!rFqYxjrYt_|wy&1S)L z;YIw*RWxjS?JikUTo|#am=?d%gxubM&jAE3fj~G>zFy1tEr>@!g#OI3bg;!CBPrcl z_@F1Gr+1`W9KohC%uNtWId<vqY3v1(&?bPt$i*qS0z5$I0uOWYrST96{{zJJq_GfI z$)u&5XCU|~KzDc?+a-SaCV<@&TmJ#twBm~nYZ6KXi#Au#{Pino(fHRq+#?5&x5Z^` zyGF5>*EGV+FCRCRNE8-W)ci>i5IG3uQ9OWe`~K51k}<E#t}GLC+^{ARe)va*;3mJw z%Fp~I4ZlFEZXOeoX#j<(;Ad$iv*O4C;G#k$CWna0BV$r|LM}`Ad$le#RLATw4%AAG z6MF5rDDKIIsnsM1l0Y~%Jj7Z3iVC)ZaB;-26kmzyyo0{Q$B#9k1+Mt)sWx7rw!t76 zi`nWy*tu=5_Ef398D00OO_#s!_<#DtW;1a3h4JrxflYGT6p_=bWxfWapSWNaegdrZ zQ@=yK1zm0YeY{9!43kI16qjMzy>2qboD)f)#TL7Pa8`EPCP1mz9_tBI(@R?foRw@% zs?H`)uHfF2n?IbDl`8{RKdCya!J`0rl9sNjsY#Dx<j>!-&!qr)SI~0>b2U&1veFvR zm4D9*E1g;bg<wdhV|&kX8|gw4JHTINpwufUQ4_a-RWb>69jXUaE>M{H9r6*<A6U3` z$E!%U+o1ccD^c`6s^IOWXp&hsWe61M;9@&*??1_nu$&9FQ5OlFe_}g@yvGkf+t?(# z3}_hd1w#Y53SC&`U+`qIKr0vPU*zW%vB!tI4Ur1WyU%GRA;%9C2Uy1@i}yZ1m~_H_ zk71eC1n-iqC`LW7e`rT1;dF89mTUdBkmJ*@`#*ex?ID4S#BS4+9;mL$A=5@hJ%Qo5 zTRq1pu58=K;J{3oy+broc`x{itRVL(N#wZu7<O=_GPYmJ;P8tML|3<kDMIN$J>8Ic zXUOt1R&ZkSh(k)X4H?8c5p!bpZ~H@{CMFl`$-rC-F&&z_lv(uxiOdz8ASIec7z}EG z7X)_54P`8N$5uLml!D=@2urd=7t9L2hl<`@!Nn9AERd7A4&YN~;$mNZGfAM-)sX{# zvg&X7ffk}c8bn$pI@v@`IDjTvQ1lAI{FNMU`LdhIb%BSLhcloESC|GD(XoR2N_w^r z22*Q#@@6$PCngZGwbENi>QUTh`Hv#lCx~au8tQR!*G8~6A7GDN9$US16~aMq`N?~( z8jRaNw<dwRxahSqq2FdQ3f0&fG#UiJuz1+zy$>BMEF-l+jC<CstRdAIEa5V=v2yh* z+dJ{J%$`xno=8+swU;tJlh@04RugS_hM2+Dlb#;6u*^CJuAAL)hauATg3;9G{+V{= z0}jJJ`0PVgKkor>df5W)<^Ia#%rf~zM0L5W15+fu;*Hfp;NZSW{I@6Vfq!ItK4I&K zrH~|hK4;?Z#b+l{pxRV$8F=j!jhm(3{dT%^chM2JI8Z{sBp-DsJ~@rAdTI98aBBXP zIQ9)?D^zxP4&4I9T3xQsDVcnk0)1UOepDa6u-5Q6suLQ7`O)@zA^9DiE+nD{YPy48 z0^gj?#SYI&|2E}rJhZr6H%=9pcHg#aAZ~^X;&^iPt^&kl{-@?w$0{Mh4=VzqaRGjW zokYl~<<}Kfg&c0EXXea|4IDLcP1t`o=$Zy{Ac4SCi*P$kH(MJgH%i8T<>PKVoPl@F zfEfOPOYrxcl*W+<7CRNR5{zDN?A8Y(YgT*j9p&#oCvCGk@t7FO=qI2;+W!1tu3PLi zA_%|C^TWxySu*0fp$}+6pLw`@%Z6*TkQ&F=H4vv1vPSUVu9I&q-qAjKe6!EpntW5) zS>us)KuE*!hsDD6)$#C;_&p7h50Wtj+=+{kmNw^h<B8H{_d*WwkHd6dFy1cK?*tv2 zq+M{Bb9`(8=Lq}Z(%mm%M#pA3Zc7|8`cLR5?oMG5B2qYV;iwx1PInGuk9FQ$QY1sK zuOg310JqC#htGXp5Rlp?sLsf=$#WL39vVeb1s>m&{JwxSQ$@ntL+<u2zdL7+<^oXN zj<`xK7Cj^2q06o-OJB3i#rY5}5x*KZccPmOE&oIviAY(g<ZvfcUwwVv{q{N9DBk5g zr0K=Ua*QJsMUw<tNzQ+8t34iow2{$4b%>E9fDVu_^O3GDog*(zC~ZAAU#Q22l4f7w zj06(lA*GT}^RQQSkqRbYqtu%IW3vTGz@+%<os-DT6(LTTkrf%H?+VVB%><NVAH1g9 z-!eB$0P!Fs{DROIPFIXF@-%=1S|qRVP7S<G@Ok~cxBH0Zv<ifiyPt@EPhO1tfOn(9 zO+Y~C^plh2*oUtXMN~{%QwUx4=aVBVFggH|uYPFiiMVa=VLGD{iQgbqA6li=HF@ML zMe^Npa=&bJiY^6Y2*u-!zLJH4IpDQt;+GxQZ-Ab$EocZ>TDwcXM~#GO;=XqciSrnN zP`B59p$Z(>Z4L?%AyH1`Q;%Xu`(JW@s9p|41n_>m+Y-IGvht4f@kr_MXQF$IK4kuZ z<^rdw@JlrOGB4~z?!NV`$kLY9=`j?P{{4(D?%DwtK$y%YGY~@Z|BDh5*E!r%sH=F_ zSY8%1u+rf^I4!-elv3nA>y(eX@vAt5deQQf&Pi!8@rE232bl94c*d%?t2?|LzO957 z-LLPHycu0jEorayx^cL-*z41as#T<t0|;2rBq2RfwpYA$o=`WI<n(I=0`9d+`8A6; z)Q7#vtMkorI-^D2Vdnvldw<1uHMoylZkQ%}U@hc{Q8PwRCXh@sfpoPV@iD0sU>n-* zf41DPron}J&_x!|B2~T>Tkvb4fAlYND?6xL+q)3q59>Tr73@p>f9;EZ<U~Pp0wZV+ zYdzI|rH9UTszMPM16)xn+3m&y&vr55glY%0|J38+<MDuHNho3i6R>q|=7W;QL7UQ* z4do^-ba;ey2_S+yZqtV_!(@#5v{N3Sp}V)tmlU4WRc$IeV1&0<Y3^Z<>g(EyD_-g^ z!@;}y<iw?X%aCHneSsA5E2a!MJsTV-8CaKg$n%G<Ro8Sn1f3L9iubG&XG{+uC>pnV zPManEdD`N<D@A1V4j@lNUyD{U5Kd(rM*~bi8ciGC<+T=NxC1soqWzu=!AMwc!Sh<E zSX0(hGTv5ft77=iB2o+gPIq4J)(b)MFn}d2pcv2S>TaxT!2OOoY(YiTj5|5Y>4dIS zwYpg(qs8|fr?-0h-58zsJ`^O*uLK%b`ekCwDaT4;hoWl6m=pqf3}`bx?ZdQIRfL=L z7!O~j{}C*c(1Znk_6o<hNBc)VZ*`ETKC`;_Mowy6n}(}J$B{)|3x^dm2pcmfa9WUv z+;<DjF9rsL*Zg-;&VIE<pfKbKAMfyqLl<`S6;@FDf{c#jVDk9HxX=5VZ5ae&Egh;x z(2z>(%0&f)S7M0cuF7YhUp^>X1kHDVpQ*Np+N0L~?=oAzYh{51?l5Y&y`}0lxT&~> zy!_grR%N-$LWwzcF2k0102w^H%k4+7>B-iYp$|USTJL6;0ON}Hd!j@n7P5_BjT@w; z%n2{Z+&^*Iz6$67E;9E(dDW%uzp$z_1O5i3%-J+za(e+~z9afM{vz-e05ld>#UD#K zd}Wl#g$dI$Qe#)>5-#X{eLKsA{6YP#j`(+)qTk|Y#@xxYl)UdPSED$18o%0c!G#z} z^yn@74y`>$e9M}DboS=nAC^fqrgj<|J15*W6~}}h9x&e9BDv?>uX}5upMHHkRR^?* zUN!+%PEf6_fa^P`LoP&~0GF@;Y3&_S2Qtxs?q~}3kC&?nUxsbW8_E8DfVY)GiROkP zE3$CU9PzLd`S+_<D*?|7#M&K-KAxh0STZl|iCce@d3CqU4^Rm(28!SnG#NM`XTF}N z2NxkTc{A3pX>ZEI;@W<!+9)7AGqw2Y92?JPtbi&(5y)%~V-lZvEYsma4_hM{*r|x% z+1%)%TQLL~3bi&z<iEEOk`crR-{~Vn{An7U<3ilzBbjk*`(OebgVOAQ!cy%Sf-451 zVj*fp7cFa+EAUiZr4TOUQCRqB9$c3OC*<z1Pacx;CpZW;Q=q$eJAu0&F39mg9aQOP z!7E5L*;rF5v7|fmF}!kBa1FPn>cpCxL|U)&@2TRd<WFp^U)%|AVX6{ciSN0y2R(1I z-Ic~lG|QD6WusgIf?=oHrvicN_Mlp@4)9FlO$jpf%HEhDk){NABCpSd;a!#1`eedP z;Ec^t5lZ=k;J4PLoi)nmj$E^69}e+%ORuD!C|77jn**=%5(Y%7)Dcclc;Eo4^+X}8 zS*2`QmC{Gq83BC-cZzNID3#B+xc7+MwG}H4I9{h~^d|L8T=bRF-QT?zW0wA+!)ZWB z@HM;Fuuk9nLC<M}`T)cU-|sdwfLC3#(Dl+xu!Th#u_ay*-S_dXhIjk9#qwCW!!`&J z+@-f#6}bDyGwxV{lJ6&)ShmYID8?KryYe!{Z)S@;S<JbZl*>r(jR-Xq5UUrtNK}64 zyR|gZPd8Vl`RO<qH;v$=J`V^SzA&@{${inm@#5~i%V@7RceCT~e5ipWAT32l>mEqg z(*B^i?~RE?^!G3BKTo~+b;=EY=1Wk^0WEuzk3l)WfFkfTD>5PeyZdVXOR`I0qiD^G zJy=B_;^E&Z@x$9n=tV)z^T}=stSJ-lR|8bPgKOh_L%*q)Twm)_J$`4_WBJL>bh`ab z5k0r>!Hz=sK2jcSB)jhD<lR~Hv7<aU5sdR);@?8nc^|kRgE`r~D=kOwEqxzBIsakT zuW-wCzns%-8@XPc+@xWjBTAC51{5ANTh(rj`h3pY7}$SzK=&S0yhv*M@n@f&H{a@z z2K`7aGTpA}+?AtxM%Sh3JEDuP=!ugLr6?G9N0&@MkD0uD^(_7$4fBhc$1L?fvy;<w zFWq`ys|YjAnKwRh=({j}O?v84R@{2ZPk$dO&t$ZqFXsBgeq5Zn_t-ULtjAT^<L(7h z<0s6xkWz9Vpt3oBD=oJ1R|vw|v=$HH7Brk+^rrWWkF_A<njR;J<<i${hzV6qmmfx0 zXc6=F9bza!Y10AvW@Ak9?bfrt04%}#M!uScf9uKPiL|rR?>**@{`v6!Qt|KU({~lj zS9}-Z&+eK)fV5*W-@V?C{~ntPV>$di)VXzdLR|i`oN?)GGq4C_I&<~)Ug4A;kAOY? zW1qy>c{*>+K0vsyU?bm6b`8-5P-U$$^S3)@=-FY&K#&B}dtwm}?8sCB$_~{^0}@%b zPp6+HxK<!h?wIFyrsm&YP^%Jnl9Q@nF&u{GGKx^B#5R~LF5YzPV{=yg0IsU`YQl@L zOa~Pa3qV@ZY@W8jyVY*?dHd&>sp<0L=$=2HBaegwVuK#kmCY~qb}H7>|NOk;=5>Q< z|7VI2Az>a_Ve7j;>7!d$<e-AD%#oW(bC>k!P@;|SC>LecaWiqW;O%;i<cT8)M%a_e zx8HBEl9zKUUtZk}Q@E6${3Z65cmi+h%2k8=vtLs8Bwb%VMcffk`%Y~8<kR!Y#&edX zEAgw%i-~TzXF2D7wC)im){6n{wsQwo+yp5R@BYl+x?%cgq>fBfygu7xwmG|JD`Dhq z9@^dxO-dC!n9KZU3q@uOn1x8!uT`oIFIEGdTtq~Mn<#pz*b*7D^W7!#2JrZ5*TZV5 zV(dq<$3aajK`W7jS{6|G_=zhz{jj@R5Yn_KdTmc-6k?x-y4bX=NLA-+YsT7H)|oJr zOiY2>03uVAJ#fEMiBj2d!YV+|>N-R)GFL~L*`*PJ77w{%K*Vc$%7lXKPu<oTJjJ3Y za`gL~_di(&?nu)!!06`EU>w?3@2JWszr=H)ro_6t;y`&E`o3wVmO6o$TxQ)`&a7e- zo*uD@k?OYYU{jkQ`=qrQwe)~6mD^z~!6AZISPs2RoN}k|+*nTr6(ui7+ewsz5NJ8I zaQ?T>Us0kV=<VP5y)Gr!@?Ynk3bXLti{2uk61U%Q8Ph;_wetWfZlD{xiJ&*3E|&G= z4CVj{)_yU4!@3F|K9y5WFwZXN#IU(>Bg}n;4ae5)Ziu3>1IjyP&=g{tu53qURM{aO z^HfZKbt38%Ny?57V{%a?zlp6{_k6UaBRW$(i9M&PWS9ihowNPBOi*%NERr_*6p<CP zEF0p$1c*X@WvH#Q#>USV`%<)(Q$9NQrT5drY!sZ*>;fwSCQ+D_ft*2RjyZZ=vw>cQ z$%%1filMtrlzm0mA%SggqYwwn;AM4#Yf?`RZJTc*WCx{sUo8r|Txu7Fr2BTgU4$C1 zWX)+kX_S>Trsi`@dVg7^>40c&F?Kw)@tsL({`eE$gHQcNP)WqfznZ=Nt_2%2j>q3S zUXdxyYHtO267Ifzcg2QGf=~%mR2bHlK?NYxtFu9@2$kZ1S_s$%^BZ{jrKrIZJ=FPe zFD1$*>5rTr865=(-7!a;TpSvwi0%Aj%Se#^@(U5fu6wy!dJsT3gY2?D4#l3sJEinB zXvnQwiNkL(jrLAVJ0d&eW69F$C0#zEQJX?hW;2$DDUPUUavKxPXcsF@*M8iR+5XEd z%c#)mm|)-K#%FTrr~_i`-b{rcvJ1VCGGHLx<M90Vkcc8iEnu-!p$!@Y?6>f6$r5z< zW5CnagbT0AjmV-Ss-DAAd9X_59s2Auh0X6Y@7+)2p=Vt;k6+Ntg?An)j^po3@HL58 z=FMY;&TGJ#{C+VxHqRIp8;F9tu}8j@(3vCi??v`ccF7H+sT#T%g3CLpd?AE8=lz|P z5N-eHI>5C({t_*R|6IkwVf$1wTGRFXr>9?ZrP{6BcOdF$deU2HkG(0V00L}_&ZnQ` zL3IBP1anz?m>%g4sGXY4Xa2}0ut!bzY2SwL+jElLFF4*><j~qx@KDrq-t>Ov%$?W- zx1h0+=WaWq`NOueqN2SQ9eO>}(QbOJh3RnKhfm}4XIOSR6VKBh0|YNsXRkwbEUK^9 zUsAr0VS1G{I({Q9*4P6>7fk_5khi^jXDA|4ok14q{l3y4XUc{?rBtq@9-u#KVhk?B zS(Xzx7h7*8Dcd?$a!Jowd1>OP-`D{j)2&RWr)yu()C=_^uBnCUNpAU3hj#lKBitq( zhE6|;i<OL!6W-^BK3e27dK>?TtCKzGes1<s6yc#pf}oz8n&q3^L?@{&Mi_hqjx?&+ z=MU2zYe;pU92%-;wR=oP|Dq&vNFok2I3Iw3DYsX=G0myzd&_|^W_o7N85)b4{O}+l zl{2iJK<K;pU5pB__(2>L`hrU?N}lqZPfH7QXNMHBA_(bw&hD<5n9}=3*Wjl<-ni8L zp<LK`@`mAS*jR2#+xW+_11x^psqO;DzYknjYH#cG2!d?cFjv_(I1@Lve<JHU3_l!A zRJ`M-OqqBos0|ILL0S+Kn3BaA#rqQ-&gT9G@LjbGe4ZjYfuJ23h)OEzi6g!qdz$LK zz|?s-JrRq3D2yCkGGNd=&m6tG6qM>&=>6idH7Wu4M+~(!KIqarDLw3kHb(>ADeiB) z4(sVp0}g(S!eagn0S8-jvnM)+-IPn<&CVW1-IjzD(iZ}o0aDuWvO||hD55|;qYxEI z$al~j{&G1$*$<^T<~K9|h!fb!H?ToEY&_u0Sg4dQc?b2@7xAS7f%y_j5K=9xa5e)0 z6b2Zg_l!Hk`T{jl3h4yq_641hM*F}9kWyG0*TxgHn^6})Q74fn&@>5gbaAktaZnK= zzciB2DC;yMcdkWh;sH}*v}y&Pu${8+oC0{>*D4W0Gc%_m?hp^B_Z#3&qu**by){&1 zU@hOjv_bri2tK8<tHT!SqI`HjM?vMx)Yd)cm%D!SMX#7$FYIBK1*WvY{EctNJH5a6 z^w91&yHiAEkpWs0*RRPV<BsY_hVSFgvmb2FHHV#n(Wwv-noTt!0OZo72ZEbDUGu7a z?S6!4f0&>yqy=IHq&3izZ2?A9*|IR^Zetbk9_90YKOVSwtKZy2K4I6(5}J)Xno2_r zyr!k_kSiuHI;&@o^tHU-1jeOj=qnIaG@wZ{O%J0<Qz0H|=s+&Z$}u41$DD(xl0fZD zTH%ot0D3h^&f&o8Q=!KQHeL+w9KDHlIq_|Z@4J)%MnnQiNq#c!$1xNAqq^RFd=t&N zlg997BXIm&Zl&YUhx2J+f*xr!6&@oEq~mMp;L2+TH`U$&>Cb!6RrQvw7H-&GVU+ff zQ3f%tqALIl2FWd%gA&f0y?8equb&-FLmo9`YvX7IYUr4aG$(QNskRqa?3Rq3i_2a- z(2qupH@ZfLp`ruzpX^&|$k(qY_J3q%L~#o~^(-}gxg7=QJnAj{pHUhCKm#a5`2U@B z)$%}4_mcwBktZdNx33RhF^*oE9=u)i{2Dn0E9Z14%>IZI{4~00ymqX{wbJRTQ)~T1 zg_5@an}5?)x1{!Ppw9oMtHQ?WEgpP$F?Emn;b8TQ`^`5G>}-?9rD?m~KBmE*3ev5b zX1dvCUmS+obRF+0>=F|crWJg6TDa@p@X&qzBLa$<LhEjYbMWW2>7(F6Mb+E!rXyD@ z<j6g#?Jd!t?zY>AaDY7cKi6Ny+*>WlqeOR5JHM{Z3pv9b+?232^l?NeM_a1>=U4tq z(=GLdBXboi3(mn@p_a3o5BA3;Gn<vj=_1O4PIyikb@8WI@`?ftF0nCsB1Ni}&k)=V zM><%4yr&>&*Adt!t2wC-o)wB)m|>~jmmH%J^TUE2l$Y%%49o_Dd$5`zZHEF>O2a;6 z8PC;z$absq^-9Cnp+oF`VXEE>{1h4w01Vd_K3;OQ)11u{|5fXq`{Rw#M~B~04zmS; zX_|9|A?~f!4z^EfFSC!{U7Wi@?bEFBz$BQ=Urm^+n=eiJu{eK?hSXZP7Hep-P|jAX zU#Pf$C{Ux4W2d!PmFInYvAQs{e(`!q+|puAS(?^TZB_p9rMlYd^-J}QciTC*n|)ha zpBnGHIR5EI+g$ypn;k#?MQO+#+vzHa6U)s5Y7NURL%TmM-{#rv_<U#F`^4wg$<T(+ zcc<h23#DzRtG?V{xZd!kefjREFArAwc6{wve{tgL!;QKBLTLa>dxZ;^j9BSJt2eH6 z{b#yLd$mW*Ct|giaIEpaP#Q~nZ9t{qe?e*grmJ2?d>j4`l=g4Biu}KY(zer8tp9IO zT8@_aBH@;K+miPGWxDDXmHNKm-I8W4oSO0Lzoo18?DO(e+#Z|Hirw1ctTC-#pt#Vr zMR6E?ua#X87x`sTtZGHU#>I+^Rf~}O5N2-%<z<G#0eL>?V1f)5bl~lT!K`LrB)yzF zj!la71Od3{?(8`PO=`5s9_Y}uW^z+xcN-jnYzcO$r3VH=bpb1@g(egu0wxb3!<9JY z$Z$Ac&VurKbHm;Wifv3>Ca}d{&tw5*l|;^f&2n+rf25ZN$cY>fma4G|GjI(C<Vo@j zo)!3mW@q?lF5Q*HAtoE6VGn#W+%w;Eek-xaSY3_~mVzw?*?RCUfn@5D*c+M-?$ZRC zYSWw{8HC$dmlYVInR<xD566)VxQZZLEbz9qB;S>@zg7vT5A4<S?c~~TK23o%RgoLr za?TJavOy(p^nh|3y0J3wv-Y|nLN9$6q31H@K&B3C1p;#Q02|pW>gS|r6eM4`qt-@_ z2ub(jS&PAR)wp?!TirrP-PmnHV+f_?(BCSTA(~N^?TTOsoF@Gbub&KS5@g7x5S>>- zts)lfoRBnRd8QTGlE|?<n8m1d=p~l{B>+!fFt#mK(=G~|y!j~;mX5Mgin1*!#bv-J zP?r1|9HUEF{@FOoJVP2d_98`Y8EtRWMbAlPD9cYoAT3rDadfy%=060seI<cy+o*`= zQyfl&(aIX!IOh?VXX-oMSfpv_HAqwVL-XUft57fEd9O6{Hi&I3;cm<#)qd@*Fc4i5 zCHwK;LXul{RER5ao?vg>(~OJdq{z;oxu)-<a8X<vd5Ff6k!3<Q58ETt)XTD3D$fD7 z!Y(P2HSB;2PU->g&tf-gQ>_*-={6-5;_&pc!!Hr|YiblJCKt9Jae8ugpTupLuC^zP zll?KAB+oZQ8FvWhoHRH^z|Ew{jJ69KG`$QJV}<~Yfe5GR3LL9!UhAN4zP%mq@RlG~ z4RYnpB7&fpW>IN6t&5`<O2~gVuD9-z7MX$*p?be>kw2PobY-EEEaRRXVKeEH?VoPZ zvO<BoZurB6uEcj5tc;nO?2o!VvPa>AG(yvDmo})RT>i1B1CSv%je_o_mXH*w(}BZB zg|$EVvd9r7Q=mIj$PJtl{8fN4rYPbR|A8O2FUM|O48A|7*MAAKhNLI8Yz^Yf*++Hs zgpMv-V=FcB&*cwfxbUHpnS^dpu0P9n+CxnGu#fr10ni*ylUWFiDY3a|e(cc<1_E}G zRYq>xrzwfuWFwRtX$b2isK{;N_1t~_JCh1Oq(Hb0R*y!e9Sc<CK24TsUzY(+8tVf( z+&j+4Lg(y9?_6(9KuD$05PRB!B?Qga?#FB{rF2*sG{oM#VXJp+JlIC|Q0uA`l+OYv zV#kD4dNtjn()~Sy(VlH^6>qDdj+@fMZ!WG|-Ff)=V$z39%gZXq5m21inD(1v+t;I( zis^deog&Q(l%m|}ubf}&vcu6QhqGlnJraV&nu&15x4gLnwKDHsZ)Ko7cDyxW?kHeX zgQ*&SXtVV7g7=fsEVI*@U{~DbS!(pJA_bGZ-XK&Y3hW|6IoJapJD%w8cF0za$Xq~@ z6{bkayp%7e_3b%t&Jp2O)-yWP#uDNaV+!z5bn!<2zJ*@z?Q|B2sX1xxcQA_;VtWNl zdGPS0^?ciwe^mOPb`J@yUT=NwjzI=l690goW^Cu1t>L#_r%Tc2LUX7`aw^1cp>@@V z0#oTLw{j;o8=x4a9EVRb!J|Bu(Z=wula1brpz%O4s_$3Ko{Qo)+L)?ymY|RSi4i0n zInXW~d+tzyB0&PZ|AEt4dU)YCLHJ+AolydaCtZuYdi$+b)Y>O{h|H1JEZ;B6yYt_^ zz9Qbp`Kh=B(j4JLp@yH{A9RrTtJjo+(Nu7@hGcy&DCZ;Q1`o@k#vC_7YO8|$cpc@c z#PcXgG!6J<w5^9op9{heR#pYB2`sX}XBCh=uYJpho;d@-Hq%kv$A5+FEwlGm3pxKH zSV}8_(DC9wqdnTzM{$+=H$P%3nrJU8PBwTQG9gH=(S+cg445!Y-4z3I#c8&YO8c?p z_WPM+fhUR}bew7Efy-56LI4=biY{amQv)*A#Q>@**yn>CaX%5lmJADn3Uo5@-yHPp z1@6!SY9xSr9EY;)w{8V2<I{-vEuv<*s-Jmv8lpJ{>Xv-ccsmA#UGqV;k^~@JXGmZY zX@IT12FoD;Gn~|OqvrV^|1I_;q4nq+SSEVA!<BNqR(TJ{1;SN|NYFUPgX+-0Np41w z@!qv~bUly(DMJ*wvf|n<sI?#rT^-%yG^GfDb}gP4quZB8yNkxGsrh%nu|FwUyWP<` z%&1PbMiDX9g`#^n<kaK-^!1+1MlR+{Rrc;K--Gs=#^0k=Y(j69(LN?%R0x0vAW#Eh z7eC}IuAWEh;;%7rg>4!W-kDCLx_*QtrR}5(2lGHY>t-NJLp`^No;y<Iwr%tzUY#kj z=D>w%c?%5jts@Z?E7-dUG1wvj2oc%T<f64GH*Av&UxjTadQwtZ1r?zX5*6N@CG{ck z3Yx`o6;M6^%K7F!h{9!lhi&(HY7NijD>;T1g+plDojZhNt8S<oR;d>ISVaLw_dgsi zJNpwR#0B<n;XT~#EAphjcA-=D{&hruZ!W5(44Yn1&_D8@ah|XNO%+FQ$GUDL8*_~o zpeG45kr2r=GUu1<A`_7U$A8t(oF`ekYJhphaz!*DKJAiN<$hFR%zD-3Oc2Nh@@h0? z4v@g|Dw}~Y%>@$ftt<W<H^t^6rq-}f+9qaI{S;>fTh9^rs0@~q(lo<$q_+xo|6A<g z<X&;#j%U;0tGFkUcCXmFl|<|fvcNAxpCdCaWv*DbSZOzguqzat=HeFWG&i~E<7kK- zNP`6-A>_jQzY<F{7-@DF<6dI^5BBaWs;PzV_x((7kW6}q(3C1g1O&v;n_}ollcs>8 zhF(NTAdt{QuOhvPG(kZWLlsaE5EK+KfCW3Cvec!E9iL~vXTR@0`;2{V&bivxTmgeY z#+={(=hsY)=Q?TgU6I?Gl|k}_0SCdJ1^l%*<+tqf7!s5ia7wV?glsP>1jIFy)92^7 z0S*2GrRL;%LDO~-j{%7I$ry_+iKs7JpW~hAlkb0{s-{_km`!Z-r^vHlP!b3lX#IpI z-fzMVDT0|mVBo##xf%ioymHzM4wWtK(T1NsE}?FKwL~Xq#$))D%h)6KyJ@20nngyg zs!ml<n1c)qLI^3%A44XLDEeR6Ez{oS;1GU(&_R4KHoKNxzx}4ZToWWURA>DZDb@rN ze`4fDRPy)Yw>7D90K|lZa6EoFtp)ov5>r#vm=RIh3$2H4Vd(XEGpq{B0!+ekKXce! zjTND9VtagRuWegnVz013uhJjQsScIM&bm6N1)&6@zyXqI#l71Xx@YQp09=P=G&O?o zq{_tTsfrLsm7pzEF4mY3jnx#V1&*~w4$JkK!IT8GQ`1-xLcp{>c%w`YmXgr3e)1d( zkkbSZw1Vxp<|hXeTghz@w&Pu$thfLR2OGm`1j~dA2Wi5R#PPhY&BE8~TR?wVeX!o` z{QOg`%Zi<DyJY|YL2!o`TRctSCKWxt2@rP3r7u_8_QN2YYgt0T$4Sk*s61I+fA*kb zFSqzKgWcpNSiUEvo3RX=Y-ld>dr(i{1(EoZb;Z;=GKs6=&`w^^l6`sf%TM7>QsB^9 zs{7k|SSPNGRek=xmd7UaAenWq=;l=-NG6v-*qw>}dNEkFpXSAy?=a0EPIs|aazB!e zqt%caG0NZofJgw(l>99eYM|B?B{HO=R%wN+=E83E+@Q00;^g`I3qm~Xs->B_UVeOy zlJ-x92zE?lCk0ci0#aB=c4WT~4G`yQg1$9(!tp_F+K=NfU06&L&=zZO<$<Trz^*lT zyI)mpvIem0bXV?CImtaeyW=(sn8d3c1mW_@Hy1;&O+@TiP)coy+l}`FCJxSA>Sxvs zT=Y;ali(Hu*P#w~7Q~LA#gg6$149#$b(&d$SoXnHJh?8!Xs11bk~y!erWOT1$niXw zewFWCpRCf6?{JiUi}AUug9ld`PE0^eiSU}kzP+7zOB3l&M2?yWZx*W^v%6i)qTZJP z$^jg|)$m~l{43v++r6gh9l^anRJ-dDCcXnO8sVjHH)cI<QYq0^5~%L?BTEXRiU2-p z2xq3da|r*MlcW|8_vZ#f0RA<r9!$R3h{SwT#$IOOE>deFddCcRJ57#{u%WZiZ>-Tf z{FZqQ-B8(y@~+6C(cUzZvGc)WoYQIW)hp@0_%}6q70GNgJ6Y-K(8xAmRD~&k6IA+@ z{{TSbo>ITNU+LIh`Z1DN!$0MNm0gis4(O7X-fJTFfCKVY@NUlo)k`1#g98GmO2XSJ zRwvv`sj-DP?-|q&D-~U(&fqY7`{W(*FQ+2_2oLvZ0F`%@HFa+dH%|q>S55i)mnjVP ze(k@Xl5yGgL(lR9T$SeVvAhQweB4nbJy6qp<ur7j6En1iHxNqw0|9N?@cdS|?~$Wm z63F#`2u<y=e79@JUfMy}Mk4k{<4nbN5q;N;SAz^najLi;P<VpS*-_BzD$&-^!MPe6 z;7$z4wfS<AnO!~i<0QQa@IswYIrR>|v8+da3F+h3$^ZmQiGob1`Gg8Nc@vHIfalmZ z-vx-8$A(^4!9MGE43#+hkJ*Fbq&VuZyMowV$y&!UcBRzN=~t4Xl}1->9!&q^IccyO z^L{Tu=Z6T64JiFd=Kuv4xp2VFhmvNVi(L+t%eh~Yc4Uze7zz)>);7(bZe7&NHR4eO zvzMJ$*$*jP3&`(T-a+#lzh(J-QJR*|^klI@q4M3&<{9S2!gQ>u1Q5-}TqoDQ9eZjh z3vqKZi~W}i1lWK^H=Z@_UdT%MIlHoTntf5Af`vRs#6eddN^N7CH%mgjp9boNVRA7h zhEM0b1<*hzgoOCXPKe<mLF9lBn~R9BB}kQ340##oTH+!>7$d=!v+_#nqCa193Ax&# zlovk^3E+tU2mqNx!VAhm49zLo94zpL9bh*QDOsK%;QBRz69z|yH5pZ73c=w$+!r!) zkKu#%c{7MY-<wh^0>^{as9IEvJ&2eA;st>bHhz;+%jsOQ$i)`29qYsa<4<ZoBe4~d zfR-c>U=V4wPhhJ&>X5ha)cyfAAHY_jxgu+#vvbKzQm~qZz0neVB3qrbgc_>%tE+e| zSKU3gt2IESJ%<k>xF(-%B;sf`_>GF!-zTB_k8L;z3|A4N?FIOh&NJSt=aXs!&TS}d zEp(nm&J)LCJD+Fyf}tL;crw`5Ch>|_tGo<(5yY9Qo^86s5BN^NRu`93#6FPm?YExo z3BO>**K)0cIV*>)t|D1Ve^446=2Dbb&WXOIysfUmM*mdzW#N|3JX!pQkHCJ>#doDy z0<Z^GV0;5(kWaTjZi`%F?1wosr9Q?;ET4(ovlhcWWpKqCnUNlHK8bk}-_{8Nk(VTA zS>ShYUL-%blVVp#d_?T37>xi{Ry*@5rFFc)c{X8_^FeahUgQ8{!-t5h{KTbu2seeK zKW%<ORO6mg-t#*3p|`fRKP$Z5jJQ=OeZ?94I-r#{wj%N3u+Tq}!p9Dk67h!R>UJIQ za(izh2r8OYdjF!jq`?j7?p>2B{4X|VD*VhovZ8>sXAlnJb;hehe#O!fElWvTCY7-% zmn4M`9h&cW{%~+(i7M^l0tQ^f{~aSRKtv{UKa(gGKgm{a_D%3-hp^yZS7u*L)^1-< zl~%cdl0Pr$`0I>a$I|+UK-vV_e7bPa->Ix>CEHi-<IKmCIr4AV1T#Md=~T>0&9SyB z%mDdy&+gt(xD;hqAjjs>99}&*T3XWhS1c3_b9g^cLYSU0e@Y~@AKF{BOMd)x?y|(Y z-!munyaBH)Q_0w{qcZ)Q(X=O|FkA?LdZY5sqong4;E#2Uy~4jY;afZaACX-Pd>bhh z_^));zoImUbxST?bqOx!_;Ngp41M{|{7;mo?ma*k`!95r;4C8c&5YP^HFV*dd0D}_ za{bZE#wjf`ZbQc%{vD;cwt3&Vgg6s%nH>&!jq%z;c~}V`#G~`|&V{=Fi>|VB$RBdR z*yK)1xNrInrSQsFa>rQps<3|<B`@w{KO7N#1qWm|!%t3MMg(=O2d|!Z_}}TOckRES zzb@RkXXEf#WOo;C4RWH-uG~3us|CIXP;+R8=j~kf`Vszm>N3s}b?n8L44-JHdzHWS zIrLH}^=X~$-?7`Trmk4M*xb7g{17(?C?|VSBR?+w*x@&eiT|hZnAXXrB7lw~-TwH~ zOw)vW-U_Nk{_1;Eolt3mlb|j8ox^y;CmT!%AE6Xk*j<T}BZOn-+$imf;~S;hb2e60 z@$ZhKyXZ+6U*p%-?wwZGO2idM=>A)s*77;#U5$P4j5iWzrIS#V(Fzft2!>E!4IA|k zgOt3G%xXA$S5!O9ZvR8`{ZlKNw{r{<rXBWA=i29vh$o(_t}EOvi651H`SKT9mV{F5 zp3!MvW$bF3iCo?&uxMREO8X22c01Z>jLy#l|JvH)bPPtBuh2-?44T^|O(<5ACx3Oj zxSdETyy@p3wcv36u@WiWaaf0&V*T96clBc^-f+LI8`@+M@TyzriC0VtLO7+@GrHnr z`)G7^_~fK;!{OWRXqgzV508&n4TkL;Hxdf3*9e_Z*IRK9D0rfHpa@OMni`<p^pSrU zRSVFrOj$eyPKO~n?plUDIl+)gU0gjLmDxLf3MH(MOKhe2=ec`f6sai^ZM}i{7wWbG zS(^(MSL_iUj<1j!W4(a%S6VG$-SS6<VCqSvK`?<AAZERVa$Gl<sbL4HC585&Z{}Th z*lyOjUlSGr>j|$*J(}(!%lmYA&>R|lt%N6}<HR|o*$$E0vAjfV@934YnQ14*ZIeFy zd~<Ub>2*L}()Q>3y+T8Jz{OVH+jk>oXL|CX!NK>kG?JRk&$LUtx&39%8O@<Q6sif2 z+?Kp-DHE$ev!X)_sv9zlu{zU{&(1$orNPF>@{E@gAL64Du_giKM%bA}v@MlOSG9%X zsN5(o>}lNli?tDRM#8g!60|U%I#OQy-n+j_nf64;%3Z(ZNRufy`+O^fS@V3;TXA%e zM9JKjg^pv4697U#4~_<6zoV`0BFD?@>*#_Ru_=ceWF<q+o}-D35G}d?mu4_^yB8~m z88zA^WlrC-_;ZxZWslTwA6Cw!Xk=QS!&A5qHo;I~G?4AvTgIQt<j(^v0Pgcf7S|B7 zgtI|tM;359C*qvp+G*$9yiEjA(P3l_-^T|~GVwB-Rqn!WFp^dg-=#kmlBUirLfNcN zH#$e+mGuBDR8#hBsN}QPi>3QM_~#@>u0RCy@cLnG5*#H-BHu9DD>x}LogT=6i{(5M z(#~USAr!r2>+GWE@~=FoQP6cTBp1yUG~TX~IiA9$tL6%8Yt7ZwzT0{{o-0yGHrv<Y zIO4f8=MLLEsVS9*bwEEV8S}Ri$@yU`e?$&wCR*T%4^AC{M96OMQsfRCeT$n4c~stZ z`q8t>ouhTmH6%ItAOn<(6=cJnb>e=Kz<fxd^VFltzaC(3QeFxt7@sWq4R6Zf2|ild zL*OgH0CFV`gouiO3P@p^sx`(TeP`pc$=}E<7LBYUbiGCf(TsBvcFglJFIDuOw~+X2 zM*atHy+(?%MPv{lzECR_t5$l^pBtr3Hb+8&_nIW9@_4~XjmEYXD*CgJUZmtV3)K&5 zK!KbX_HeUm8A7e%ZE<7tw|bQn=@~#)rl`i+=$k^G+rq8KOxe{c%WFP)93o4#>)ZKJ z5N)(^(rs|Yjw~<q)bd5A<$!RJ!UN6FlU<PjMv_h4Yi7DD4<!-03JzGX#gY~IaW_sK zaiN!gJ0+JjpVmzOe5LA|sPTO2)1k;(jLD-Ml0w9STvkmRGz@X(<SCcu!mqhR5=&SC zq(aa@Ngtchv*XcbX)UjGC#B7T`<`rL4q^Xn1|<j(X%Kxj1j-eXI9uGw*n+N2=GCIu z(#P*^{8f0wnJFc^lMzT4Y4i+-tL=H`^G}iX$=ez3@&?bc!_{K!qNYYe{_f`-DuYR` zg6LpLIl>|FGp!gJ<6u`v!#+4$2opeILYiBXnsntp2%K#_4FZ2yq|fN}(j8TQaWltZ z%t3a{D<LMJV0I(9%r-0K*F9a6-oSN)vkGZf7DKD@A3s)E3sK@w`&3>6g)>%q=_x$^ zXmiQKh5151DH(tf|74J^oah5#z~nWwqr1z(R2+Ni00cD^Gc9NQPU|ur$%eq#;VFKK z3(e>B?VHC(h;X?ohfV&6IjL6+ro*zsA}19vA&oW9XYsM_+b-V1=(Fnup3w)z=NiX2 z6al%7BZ@;#^~BLkhePiH=_w#b$W`9|?`C^;(gb7?cP-`P?Kdic*hxxZV>?JS91&C6 zCTdh?=C|l9%Q1(?c0SI~vPDJS<8eR28*cAMC!c(_d~-kQDoQ=mE%)d0=TtrGwoO>j z6~xm@e}wAVozK(H3tsFZV{eNIeB7mqEOV}{r5eFaH<KT2EB(}@n>9V7TwDIj<=H9y z(U9ZTFtOw7=N^2&cf7e((|^1R^KQ+?Vp{TR+j8*-qE?>%gtH}j!Rc9apVro``p$}9 zwV%h~V&TS-ZJP4Z1que<^Mm-eXgaYdDQ+%j2_G3~^UmkEmElVDr>imEdm}$NWcaT< ziV}SGKIp~7$ZVU?#UmziZ^(Z?edUuI`#s^4!|KoH-|+n5%=pi4KR8<daG&0H%YUNh z*iN#tV*A;CJdkntP@S0f-Tl(4>l^+n>g|Pi`Bnk@m4po#*_xjxW~%0%?LN{hCZ|UF z8~;ov-s^nfIEp=geb;ar2Bhe4cBNI@Ht0zg5C0XWlwdR_Vl7u8#rM+fiO}`lkDFqL z@frJ3;*YD)nss+Ce%f3A>NzU$`~K~Z>CP_NvY(arjH_MR+5ZM5WOCQTs(WGQ$z5H< zcPc4#7Cn)!@4ka#KMDp?7m<6Q{VQC(r{fwBNP5I-wQNeI>ysYyv)ne|`_GVG$kU)4 zJ{lTD-_#k|?5wpZ=g~2Fev8^MsY*kebi^KJ{y}>*S_}upLp7v9F4vQaSx$#U{;_)K zT!CrbL_)`OriJnD5f&suQ}r{NwL9bshBh3B+M7^ce-0?mn?7CxxCzE;m2^8AlDff) zX}YCuKKw46ri2D|)n{7UL8(aQkWQW1@LVTc|4;`R6}Bjh3A}dZ@4E)(W^o-z^>wUS zz%>^($pp?O5+P#N=nWevjof#&$!Nwy(K3{cevq8PuBI;{ZBGwgFF$zn0m)nqz-x}W z{OX6?23+Z*)%iN6Jk$^}TErdA#~uXSVHZV5-Qi;q`8r=6dnJR>_*kkD&)7-9gW}`V zNB4nK1(xaZ5I!`(&#uOBzvoQ!C4Z(kkhF&f@G0TBT0RzGe(mZcO)C_Awg4>?h?eV3 zR^udTl%Rt1GX>4=T?|w|!$TEAQ$b&=bYH8mg8lUGso&S{r39)DmXGA<)BW}7`vUUq z0>@o5)YNjE(1~75saR%A3E#!4+=C<IdCRS8573j=dJ#mM{79P{W!>VA=p9FNZ12#L z2TGroTa++S3BRV6&=%E8h#@hfIW||!C#M`41XG5}k=*}#YH;p<N)7hhCi*82F+h3S z3hU0A(G1c3r<cb&YwzU{&C(@py6PtKm7H3<Cc5hHr%UMH{$HjB|60jPb>3r9HB7Mm zS8Cw9*GK#6X>Mw8W(E|!oi6n!HOQ8<y!`K#EXw+=`awHxY7pChi&}QG{Y3pf%T!*? z)pl-b5SHG{>g`;=Crcw$9ua$`nwN}9M^mnLy?I#qHc9$u{5G5~3IUyne`Nahi8Tzh zn5hl_@T~XwEj&;Z_2~t>?`P~wdFme8XxKLI^zFumc^P$IrRCc{NBAH<nPAr$-!ws} z0DX5V^v>-cUnpWS1)*Q~e*UGb@m;!4V&H^kg(Y^-*xwwJyog{y0^Th#9MA}HZfdZ9 zDO%txkEPNoop8v6pGOrA_yDGCB3vjtuva!tuqb#fO*vQJDM{(ZhQEzeXs?jY;lXWs z;;teGM5+yJtmlxB$}d^Y6XOdw!3k!a)h<S`D)l#S0qx8o{*YIN?x&hx6^R{EcFQOK zY@B0y6@|Pm4Q^<D?e1GSADC^}ru?QN@^Q$U%Pzdk|CAb3(S=WMR6|d?DAr`^zT2o} z6`dNa$^GA?2JhZo?HJpA_ZHvve^P`0&sMS?o;G~1^x3HIgVF!vO4f^O9=cLivvRL* zCe|xKql8Hk&|E%XAH4b)zw$LWdD6m3iEiS*dN`?KO|ag&3X0Ii{_gusdoTeLMQSrW zIiCe#vMEQ!^;x^TbbhFswY2oAw2#**!D_Sx)S;6NP`Gph++JvHFX&2_ORgK2we(Q} zkHsd@@H*qTU5OGimnKue7IY0sGK^*QwSB+%17Ds-(F)I*8iDIv6WTq@JhuueWL$wp z!hFr;r8hIhoh?)xwZIK9kXJFmLhT42;J7)HVp~@uO%TZN?C2Dz9rwdVEMi3Pbu^~= zOY<6Q(19tJn-*E8plAciW6f#OM>uNG4jXZNU}_wiebRq$%!xH57`a@lB4dUn_@t)Z zX31Fl90Z}+js*~6l^VvBZ98TvbeHFpsy$zZlc<)^9UiJGl!c_B*Z5It2vvCAuwmPF z8MBX0;*NW{CGZKMe>CV1hOh(q6?mdRYf&g`8fd+ae{W<hnofGC`ITL{75V1SUunA! zrIqMZ(XYe<Vrf%JYp;r<jL-^vrNgPZg3JX;1pk8Ey+76q``3sf+M0bV!IUU1HLh$t zYegGbt5LW!YIS(a%qd~0zG0(5-i2n8Ek2TqnW{C3i5K>lo{<aUX;GGXI&;O=Ts^=U zXQCcwnUD0%G?l7_z-BN<Sf&@@HWspt6C^2ZHL2HBlmV2@69Okmu7lQw$QqurE7K;o zG3<nW{yAxUg8QTc10>!zrNOgJg*=@z4q$e&I+0ake=S-9Y`#Nu=DI|dixis2Q6}?0 z>ns7+1_8QU(QIk7XwexBbAP}w1Z1xXUQGV&_H|N=HN9)33xp`5WjD!&dnE%2aEu9B zw~7vo02r(?aGpiF41Ewqv{o83YVhNoN6uv@3Rx(BZ2{Zy^ZozSoCTKU!B`%1Tmi_` znpe#^e;aQKn@9>nn8IjGlCCueX8uV6&_M?tgjM5B0_8!GNLONsrl%y<l<i0%_ag#Q zN%j)dkd5Kn2pS{yY%#%nCV)#AvyC@RK#usmy9g64(?}3l;yw%q%hZ<U9n;BQ`SIRp zsshhkx`X8AErioOvlTxd?Dccf&>xzIjgRD<5rxZal0$)i_<&0r!!oD1Ba8^sTG}QN zM7~uEH(T<5ngGD@{2h;(8$&WX;k)RNSh~bbC6H$<`otO$t&esTIoDbkwGCPy+H@eq zlsu985X^`hhUCPe=_8xL48v(Yd?;OB^63WBxGo{*!aQtvRMcAMs}_rlGv`eL&83%# z=#=><2zbL&Ddo7sNh~*FR4?3j*TUy~>wy_qvz0{WR(5AivQ+MY%LmtTU9B4BuYFRo zIyk<?d!9Nh`Kg3*a5@YhRkbehLf;Bl?#zztt(6|acOM*ko^_5#LHgPE)DBz?!7txk z&f2<NZ~%PYGTSZC!@fc)i_0*BvpG$%7NSxK&kY-|N+!B8weW+;jjG}CaS5w)5!}bl zz3b}`&3o=os<R_{Yo$25x(vPBt1F&|1NqKSlC2+C`B%6Ibfie41>ugx1_=eishLd! zBS%^LP=Ew%@cS42HZZF(O7a~T4y^Iz9DA}Zg_Vu6dFKSF=v>mDlw=BdyvJB!e|z(Z zFpcy-@x~r8dh7o@!0<6IU*yb11&l3qiplhr@AA*T&%+iSGiJE~-WlJ*zxvD9e4Wm% zRUa1~Uq|rg^m_*K3a>4Jd~sOU3V*>K_dPNVo2dXv4k+F<vVVKhgTAQ?JVle%<I-78 zXX?bqI2M9PIoJ-ISEv@905td_Vevz&8*(wGwgkdC-;x~_8`b6|AQ|}JLp=9Uto&|C zy7yy>&jYUiQq|`Po-L4HnmL>{_T)~+FLa%xXsQXWBk?-(^^8EnhTIIs5!ZY}_1T4J zFtmyX!sdk#quw_1i--WP5nK_()A0=o0%9PPlV&g+S3YR|%Q=ef%{j1d3dZ-an5w>Y z7Nrk<s*jQ_jyArI#q2Tfw@gyoAJ<ik@3qkBb~ZB*+P9;bq|Ma-Ic#~1a{}I-{G1>E z0i>e2j0Gq8FjJ2c6+e2<IIx@hvq?hBp8U79QNNdf?DacVqQ{p)Dw?;4=0<SVc+=g$ z84?;o775c!O^}bQojJ-qT!S*Ko(}PR@g=O1Jk_khI7<fY5y`9WXs{^IS7p($dy@Vj z&;27Q(!wh2&%hTsFt=FCHdyOOkXuYte6l7SzKYq2ahq{u_C<2di-e*Wtv}`kDH-;N zx3lq&d4Z1AdQ@;RfCQGXJr=ZMkS0`l0lcoY=87;Mm$%>#_URVYGJ2Va-a0&9thUL@ zgjFX&`BEh#&I=|3ijNM%W~Jb>7${=jbv><ZQh2|pR$nm4j@B|zz{bW>peC_A^R$Fw zb@?D>b}siJFM!y}7X6Y0_k(A!aF@a4>6$FSMw}~DfN@$e*4c<$<cgm9d!by`>LmyV zf-pf`nZYc4O9vy;jrU+f11Uq?i*S;<T5#z5jokAz-j-caK;R%4{{$+igg@)9Wl)C| zEoIyzf>$@OKO?eqC$!U2@s~w`FF{~IlU6IapiL83N(Ngu$+L5K<WfQ0R=Qj>_<@=t zR4cq}p4da=rGP*;E7?CykqcE6<pnJj$vD}7qkBQWx0*2{*j7qBY|tfQLh+AMA&U=A zQ(9|?4bn_pXw+WP1FNX9jJNU!h`tNN3#I&+y_%)l%sjziGYheN?ud;gkRN59RhlMu zcoPQ8#V3j>pHv3L<OtiuREaOPlvqspJc`m>(2h~KJ5##KHYyKC8rpzMR4s@3oPG0$ zm!8<bbF)X|<U~_1<>q;QVQLFnfLC{C#JmA)=ce0IGqDH5<KBoD3Q^9tN_X_vPPMVT ztb-^d*|wEdPUYg?aw`@maDvQh?pj#7Mu*H~+BxQnJC(Xpa5>#qeqkg73iF}=!ByP2 zr@X-mvUUTvl(fa+*g`>IfCOqBte(=spGkpsg@6{1l|Q9K!Tq4uX}}5JY+?jyDFzc- zfP*_+Q4^Q^!u(HSg>O~BMi~u-;J%Is9l^5P>)NZmpo5j0q_RqA-YQMIn1VqDagUA> z6u`pcv=lE9JPz<c$OPY8%4@8kRZZ~!Vk<tE7LkO3<v>b^DByVzBf8kY-mNa#Q3Tx? zRab`2t`iBlRaLM-OdXQYlcr@cVN*^9k58(TTXc_f(3AC5w%O<lrIC+7APKD<t_+@^ zAocIiG7ZF1PlKPSuFZ0UppFPBBAk2QA3;eX%9j-C;FQIILW=3^!Ip>HMc+2lPJc<j zk-&e57wT11K5kxy=0c`owVQ~Ud&B{6HqIEiPau-IoT|4m(_HVL9d8A0ztd{&s9A&J zX)TI8ld9ayb<`mKFN0=8E>xA=4$VC)IUHm3(zTL}&G5j8P82+JyoRvTZ4?K*(p8;6 z;OdgU+@qYzj-t3;EKIhpky_gKQ&edt>U^218Bu;e3H-P_(_SCvjZpw8q5z#*2CMc^ zzo5NH;zeu$h*i9pq1OB&_EC3}nW5NQMNrF*R{2Ba11V&coduGhngB|8Qp?Asjo3r` zF|7Z1QdOJ`_5y@b_r|7hd=W#6%U<C2;Pw9&X0a{iT2x}bmb;W3ekszEXaYxVwKsRU z%1HcqUn|BEU5ryrc!HfjUXmft`*jnaud8-OLM@}bLn+^^k?nz32J8RUvwv*3f746i zi>aY%@y}sa@_oHi7J;_}P#yr1K!W1Q;O!8tHc#v|N*gK$d)>E2=7LyLiC(ke`5XB` ziF@D*RDhoavnoDocVBbR4$QFbRT;*2@7i$x`1@C@xNqWb3Jk|&k6^iOS<^vuGVJD! zeA%4-*yU0!jjzpj>M%|$O!dv%D|XuZSh)7G8{+bpky=O!6?a{Njn5R}OJPDguig)Y zS9M@`f3YRkx!@ThyimmahuZa)L4_{}E0(NsZEK1i=-<)M46qd*=<$oI@qUeiRiA-y z(BuwGM^&oUves0jHs1%5OriN<9ucWCYH{yGT1a(6Yu<mqapm^}cayJLwF>=lF{*i) zo~qx$5tZahFP9N2qQ~vF@PDT<Hv9XN=o)5qlecQb62=_)t|Q{q4m|6Zj|h4xnw%AT zE80j10i2kWgGhhSF4!%{YQ06vNaX7UjwVYAW;YN{%|sz{@AUGISh4RxW=e=(ny-V& z`5bE++&te)aI3>r|7XLRC~&HZ@PZV6PYwwI;X35&@Gv|wQ>#BZUZ%$)bRLy)#-`az za4z}}jnT*C{R9>a<(<tW{?RcC7o7HIsx{s`)5^g%+2BOI?%jJJ;LsSW^q?2A3Ew8- zx8JLN=lo$Z9@~KvX#;%g-f#=tO9e0wz-byy8xMBCX#l91xDHGXcHuvBd|<Qv{F=xe zD&Yk<uwH___vZyD=6>WPz$-Xan{I6g9;5R9C81_|supen?N3no;AC65>YZwXZr40o zv&+KeX(9%=@EUn^cX?LV0smMNdb1Rei)*}-p!P@30BsjMRQ_lgU`q!r*8YAT)bD<~ zHioCEJ2@Y}xY+`N*Vo?_-<!Jzl|@-;V!pHSEDM#_^O9YZ8^Zm{LvhLBT6lT=A&Kj* zVH`+8Ys?-J@7gB*+!3|MGp*dsNy#I7CHfA-J0t3<hoW3lnuv#Q`eHBsEswq^KrYrt zSH-M-hw4wLt&;q$j)S+Tgikk?JoB*bll-Fd*vyVzV=po4Ny=dz%k%2fSNtOx$-I_% zRrks&6n_i<-T^bzWxu5_dW1RhZ6A*BiHL9&J4}ziQYAdDlMuCMye6r$Y}ZR~$rajH z0-!Yk0kPnnP&GSE;oHBZ&nSQiY)rXe-=(nVf(yeI%1Fc1$pj@8tB-o`i(~?%v^UK# z8E52db)GX<UGlEgcq)S*KR!ADX){m;r<X-}IsjV_7_LfAFdVKT1y~Wmj}HV6e3Z9% zi|k`9h0l@-E}+F@F-_bFyM%21PXh0YmSukjzacNj(x3<j7)0~<d6k!Y!{P2zyvEZ4 z&AwwAYcKO<u^Q6rm#siw)}uBmDdOV#ek}mPAv|Y4rEK9}Z{lYp0aN@-NkdRe1$;wn z-qdonn-(bbMfv(>Uontvs=|<-i3VBWt^w;OJzjMh;+olOUc1x$Q1(6UebCCx=qVZ= zm35Y4%>AHS??tS`X|Kr=QSKK7e?FCCN{cirV%?NCW=62t3UxOgSk_i<C_AjYK8ncx z=XvN>P`fS21C|qs0b0azHxRJ5#4Bb?`1pdXa{>iyjQd$iJGJYP+$);>s}}s>BML7% zd<54{y+03W^DqLrWE-@IXB*_MQ?)$STC;J$WgF3;T8|zjF|Pp_t+sfza;N07kGj<z zK|;W(=OW!gH$tUhtHv*pCZ2D-#VaZW>p9rhk@39$s3j_veD!H)i2)6t(SBYMXy=ih z-4I>(jf<haHr-cVmI8MD+PWL|0crwG1c6&*!t(9_zil0@9j_*Exa8YF7xN9*9>eN& zZ|TZHAmmmUBdu<52BNu*7_4^#Kft$MywZAu$^RmBCEn<KjW^r8**ELQzOSm)faPIu z(bs3cjL1hScM9&?K7XpUgYEJiHP^deqTtvvX`pH5k?#rqQ`Z*js_~98D#cVxn8sg6 zTfYb&<F2`9dJg<0;{cfNO7Q9B9N>7uWdj!Y3gKGFuT%n*Ao#TV;jH#wX)=~@II<7G zZY;?O?!#{YMH3OQ#Q2@GY83m@+c&u<QG*2A6J?CVZ<QjJLn71WU76#xz$?GZqFw1( zD(H&DPxxro<$P<<0G|(fXXQxGe*WIN%M9F+#S88Oli7d2#d+R6_E$p&xb*P1iGLD= z#6wtx$9JGcHF+H^A77dM8%p~joMsISrVA-p7w_vd5TZI$-64`l(Zb2qCI`YF|K@+B z1`1<g^8exA{O8mlbi!KZW|aQLe*%vWuL)IIWSv%69ldWBZDsb9mVdw6yz!5JW01c# z;?QU>bX#Hay@jTui-Tg1=6jDD|6?WV=zw96Tf12#e(LP~UPiEG?9so57G6;%_!;3J zeugU@ptcMbs-L)IJ*(>OfVV5;w^*v#=q@>WxFF`=D_M7i)21Xp+}zlGis0<Ya|4FE z&!(=&XwgT*F0P(>r;T|mZ{1?v{7uUH*2Fc4d0JBBMt)N|K{0yJ{o>DMyLE1AaK+~$ z5GEPa9)ryZpk*EUGNhOG$y1+UCAz=izL1*=%|Abbe@J8SNsGX%JTojm?iQeL6Tkva zzdd4dlLN6bBOHcnne#olDx1pZ<cPX5Y3ip0Y}(VqG>}?xnypUrw)Oc(pzbe+cmn>c zWHA)Fte<Sa2CZ{mini@@lYaV27E@R^w+Cs_Jex1k7_KOwg``<@tK3t#e&kPTKs}@r zzek4Ag#jx5o~t+`(6TX-f9sQZbtjQ~fHIPA*eI@Z%#2{6v+H2tXNMX;w=Wryt#ghR z>|m#UOZ&bA?2b~g{XWD2X9p`qmxg&;l>;s=-enF>q(jFKxE>FxFFX>Y8~?gGoD<jn zxR|^pG<D?n5vJ2oNsp07zQreR91l`I^XA5m^sNQiz0eY3Eu|ym-sPaXcM59W?HjBk zI@?z>ootCXK=?>MOwT9oP5qPlhVEIUM4+U{b@?ChDO)*!KE;|7Pr$cdbsCau5^|kO z`R1;v&|IKO*BH}Z&-fM=TzdMD_CCvdXdl}E`T<W-Lu<*@#p<KC^mn}TgBto?yHE8^ zU13!AJ+3(v->^-%7n<$1-<3zsn#gn#)1)5twMj9oX>7Q)`_Ak<?nl5SjWSd@@HEXz zN_0WAE%0jj0r3#)g4DkXfn^rfXKT8l|6G6Cg9Ej3na;y_MtHyH<8BR`pMJ3tSdy?I zj`w!hJ((vxdgCUi!?)d08n+F`)Vco6)$`?_%Cp|Zp(ABqSwE0?Xfc{_cKGmc@Rx<4 z#yioi4L#$LDnBqw(dM2(644_9ZT$`}a;#QVqDIE{izhlCTOo6Ja|Ytyx3^;!RN7ai z{?=&}i79YYiW(P;y<>Iw;<v0Lp}&m=MMMe!4mCO9ug~`mCn6ZL=*uhL2zj&O1%1pq zs9@e!=JOI135k6x83C=5oTu<z95K7V3+JC?MKj%6lXeC998!MWc1rK}29x)~b3ci0 zAQa$i91?bKm#ie0jt)$24@OuxR;M4eel65Yl(n$kZzd-^%XGKN<Z?iAy!_e8sdg4B z@rwvcj+_vVZ>^xH*J9rgJwT~~qxlOW%CK(Bc;CD_TfxOgY_&wZDdy_X%~G{W?n+kV z1O&eczl;Eq-aSGX|Ew`Js%cDHibDuGK{AdWsZKwpV&U=H)!No|Th3LV1n_UNj1#7E zo?Ixf+?*A#Yk9+B>097&=nRucKan!PU-_N8t%oZ=R{Tf6*MjdXVI&~)tGQlQNSEZS zqAik4P0~<uz&XJml@2<SfI#M9M`I_0klkhCee5_!-<>IZtm~BiXD%cXs11B(HRvz& z6`4s7`Gwe|>`9PCreAwh=_yDxyY0%qf925?{aMc5E;F2K-KbDOY_0tAo`yu-ub1N0 zsKA4ztkbU_((wn53TT+1X$hwonHx}fmqBu7k>Eurg^l?E$q6rUK2R1istCuX0YtiB zGaDfZC35H9<{O_#kbrZWAoV#xTIly%zd37k66h~{kVjU79f9*zTxc1;zZa<a!SeFS z@lEf2cXDViOWb?N&jFs&uQH2Gp)XwPF{BDji#7go*}P`^agr1mkAb_;{ri|==F>55 z+;I|3k)tw)Cuiq|=1vN7PuF%;CRM=fBVC=vhsup^Y~jN<+M7zE?8GttEZ1&mh42r) zU>CasK*=MGN^f;9b6nA!54uMv<LtQ*B#=>3du0V?rFZG-vlgSGR$spjk9KRX*V7Mx z2n2^x?kTu_qo%bc%uHNc)=K#3ll~Wo^DUwZj|w~GfS9Dw#-V<nof~fP*nU}cH94`o zTTceKBW9T$Z%3}fsr)xv5ugK~&HdNhl`Kn2<e2!QJC!2Z3FB}D0V6-VSNTJay(q^~ z78&+xH`yXctuhYe4#@rbwW`tJ`vQQHlC!OcT3BY50wj|iP^N9{A7%S@RT7*^fQ*l* zQH)+1se>0*<hm*)cf+OH=g}hBiy?XSt#yz0kN_aI?HlM<qugF+P|2Q?H44M^4JFaN zE%#>^igIfO<te3*pn_W+&mZvYOvTuf$?6{r$B@1!zM5F7Z*FCWi;6uIJNPOXe`kZR zr5nc~^T|QkCr?aFhv_O*$c$(frdZESXCl8v-W5HaJ3n)a#TgN(;ZJ{spS`BA=RkAU z2V>K*$%U8;YUzY9CU9g`w&n+=HHEia)rn-m-6M4j30n6%L6<A&G*_UL(`3qq1S`)) z-#DH;&2W!<IQ}<c|Mb!uhdxsQ^oI&J?j@78(V%RbJNJR^wX@IVOy)i}SsA|OZE<)B zog}<H_q;3k-L4(SAFnxXp<(<jBwp{Ac6Rjm&9lWRjKxzfLSb&eGP3X5d=fb48hla8 zczeuXRRnL+SnX7psu+==eLeW5ScB>LFce$r?>&89nXp?9dymcSu#R2tyy)X%o&;6_ zqt-p%nHASlNBH%r@FWjIkq>9i&p97#cBDzdmOeh#)iIZP$Hsbi?OkLPjXk;b^y|>$ zTh0Z{ycAKNo|MQWk<eJE#y-f^O5JDDAN=}H5Bb4fVi2z?3xonS<nHx5oCJ?;nwi)R zy2d|&b<z%J8g74-TfzDQ%Gc<|&WtbDWs^k@?d^%>m%B$aA0o7oExvdE=6&nGvQJTq zVU(#!h3W750>V2e{l(6m>z99tM?_s{p5~tZ_Nk(?spe8XCK-!Yp6@&f!nMLk0S^zX zNq^?HWI^?5N0|wyFOQE3u7DV84piuxsKL%Fnc{gk6?)wat~ITU-@5wFzP-+{M=3`K zgzcy@ovJE-IFW9~qRuxRw*20i$!6d?%MClwaU|57XW`N7HGTWVzFuH@_akm>vk^Lj zHTtM^HfsL<AFkz}{bC|$fNQl>$?KiaI-K8kAcJ}1LzUW~!64Bq1DSwsPL{NJh8p-@ zB-JVI^1Z+o4Or^a4K&ek!6DTL>3>%tpYkzYmJ7L6A#5qkEP3%3ChU00kh@a<8>-f> zTI6sI@sHk8bR7*_q{q(~mxs_#QP8Jg#rvqq&x6e<Vl~|x{lIs+nI_Y`Yd|k@<O&t` zb8!GbAG*3EQXqihttfQz9m*`NGhC&AU?Q{=MjVZ>7ul%Gs{_FI+g>abwxTSMbWr1K zA>?fx5X<lAZXBoFVN6BP!uK|5kNS;ZqN%8u?>Lc8Gzz3ji!p}AZ)N6MFsep9WR;0s zVy0yC0RwaYua;FM1`Mi2K7^j>aI?(j8Zblu(3}1J@3EKy%p8Wga#h@qvOlXCLGFMv zKr?!ufc|ER6+7ia?BPKblUQ@>+{JnZ6&hS3<{Qow=6Ww1!~2XxcPA;uTAUP<UqzQ5 zq#WmH4QN+b9vRPj$&A!wNOX(aTt^=^7afm<MH-eI0mqdqjNdfj^K>RI&og6*wefZ1 zr4AZ&ld4k`g!JEV_`FSJ;N-m@G*vKlIGJ%ep=j~G=nrM4cLu`6W3u7v<jT+1_S=Fi z1@4<P*$lq>-F24-n3k50;Hc(g&nkrG{fT7f`~9urvFKYjM)rF&rFg5NExYZ&Ggz(y zlQm<0I{~*=UV7fW^3;B&_k|R<O?X(}erK9cxzmxbwflxwQ|`9%S+)-71TY%V1`H0N zr7l0O_x2Q=Pc-4WmwQSQ*w5FEznZW=N|f;wS2)PiX-w7M%?e>mCtOc18#>ktAN-o$ z2Jf_LD$FBJWB$d%Jdw=rN~qa9ZvTR((_d8Qy;oMGC?kHO_EM`zZ17P_LtBd@wviKq zdKXY(qE?%?d7{ZE3fk_cAfGY(2;L**TI@p|vo06qsVM6QI48!h`D27!tnGNV0eSd6 zTiwxc2GNrdAIq0bMU8dOJo>I@*_-0glsx0C=y!nu`AA+M&j=pP@oGXOm6$&JfPX#G z8P-G=UO1S+<d^g&^!|doY+@H7rj~ZP(otDe5!UjB+1%gxaiU#P$&n>okA#ckt(l{@ zTISx)z(45IojIz>FQ?TI4?}XPVlxU_E?HzHrQHTo1y}Y_aSNySUk@=BY5F}p_7uls z#1!vm*=2cUvOP|cQjBRVpxQJ|x|8YQp0Y%DIBRNWe!!7Ja!@=tC3b|K!?I#rO>yu| zL9RLxEs8Z$oZrJ4KXmfAej1CK-ynhT(C^VrdE`*&qDY$}4|hK;(70c*;LV$7$BQ`^ zi~2#H;?A6A_A~7_(>p{RUM8dv_+5Nb9)IDs!tU0N{rQO(ggmMcY%ekX%!OdYlZ{|N z?+o0tgY;m3JD`tnd!>c1L43hHiRI-(ve9R$0xOw4Uco8$P0YE;$=-w%C*Vd<;gh7Z zyg0$s5MS(#{91=z{MpN<5y}q92)A8SEVUpU9R^AjN)n9FRAVglD^HIH2VtMm`d)vZ zQj|ney}R@%71hfOS#^J~n3PRI#d1V9&)nLNTX5*5dxD0gd2{E_9+zBzFt{iT)4rc& zerGjxKohk&{N$7!!qr!^^KUv;$h}DYDM{$g<L^`%Hag|ExC){t-5SljJfz7%ynC<O z_R+)ez{2AhROFiOjanw79?_XG>q&W3DfhJ3Wez@0g;SCNs`dTvK<0Q>bS%T;tS<W_ z)`gjJjEQhT7gX9Z*+R=IiZl&0RSA@Rz`cJbqsFtA0g~&&m-O5`a!~TK=}`xM3KO+h zx4`AYaAMaLwSSz>-ObcT*p?szxRmq-W+&_U%Y~w|-zSDi&&|wIs^LC1CCJ2Hgl&^b z$%f^t(OHoa$o?qq`WjlA!nC=T;diL};~|z+2l5OH<x>U!b`<mD)d~WUIoyLTxrjc$ zSyb<GBs+oW=1vd$4wczNeXoD<GwX>_B$GQ<9(yRoViT#S1Sof`e0SmSG!T*?ZjhbS z14>lv00%zJ@%BbVp&3>-j*Kc=28AX`LF+Z4c6-PK<SKZ>7rxIgz313@S*h(&CcK0i zTIvEpG9<=U`BwZsU8WI;Yk>Q*!vTK<dw(gPwP_*9(<n&E!V45W4LO4r;ZC-Zo&w)f z-&`EtRmQI#*ayfoF+5rDm*3F*18ahp=fyxs*5+Dv@Y4+LtroZ9;&L+R#|@+aHRtsM z|0EqCC7;#zJzBMHfPAti#E*~Z&l+C`K+lZt$jEfzc0o=UuzCPUg7zX3J5obRkiq&z z)<uEGT~dJ=Xz{;^88mfCU!{}h)qxJ*qe|RcIK~0@WK(ze+l#M?cojvanZl3Jcji%X z`i1?1oRAq*EDIhD(x6miusi(d3_Q^ORQfA&PAuU(zzC~ajcGlVs7be+PR2fFSS^l* zH7thpR;?UV&uBu$HZhhoQBk_j?>RqkV!?e_@PG#TS+rj)2Vs392r)f>20$BJ#4SA| zO&}KNR<Ur~8M^64s+A@(k?6CY6}%+H2vb0ry3CO`;KIl0Zkvn{ce)jIBY!O9w>cPD zO}A2l>$$^i!8a9q-X;0i+p^%*mXB*ro!(qtUOfA*Y0p^aCf2R!-PJvL|G7Wo15f}S zasGem&s4m|JF18OxBZ#pT58e1shd5iW%?0qYO<OZX@Um-qHg}xpQ-RptiGBnhiZBC zQXVz4ady{FKR3`G86|iPbNe&h*1Rq*b>n?sxUus(M1Leospi`Aev?5{oz$D3AMhdK zeoFD=<(ao)EZm6?{`6<Oe7Fw^Gb-bRI?)xm*a(K-c$LH%?9p4nn8A7{vtJcq_f9Qz z1l-TI8QvZy_(UWf(CLqPc1v0W1%B%9-CEJ{Il%+@*8Ann4B?Z$QZeWCvbB}Pi*wF# zLv8|!xZRO9KBK?BY`C1lb1v4r|GK%Je*;YVJP7?PJ6FQWO`K1CJ+YT)r-OcJYO)Xo z_p-p?^$Rp0=q)-)RiEj0N$|(sA;gX2T<XU5BazGackIa(gqFtonxItH$;lGY=(S9u zLj$O|b5=(vOs8n{5e^b;1|BQzWgf+nI!E%4IZ(7&$Dk*vg|UaQFR!@mapm@Bo?A@T z0dDoprvX!Mm{8xR+l@AL*8W<W={05pRzO0jCJ}-*J2W5RrL@Kh`7E-ZsQ|Xy4xmCT zX9O7WaI=&~WrI2rX8G&hVqV>^gY{JI{+h$fED=%@K9{?{W*e8*LN+pqWr29wE+h}6 zVvxyv8YNmNa?)(yJ1%uo{-{1Ce3I2UwCAdtjeJ#uvqFx61Y67WkKSXAB)+2jkNq{{ z(}i{25Cx2L9=3XHpJiUn&QJ)<MVxf=<?DY_HyV~3H9{1Vt;(G?>pTBk{qNL`xm0NG z2vHg9jLhi4{0DU-Z@xvwd>8+(`)g`n7~h3oIZy5X*Z$gHp|UQ<|F5W<9(#lTv%iLQ z8~^`re=XVSU;As#|BL;#aZ3aKgvQu9g}vN;HGTy<fwVeBy}tGx9tB~=g9sI9l}#o! zFTaV$O#n(vb6Xw~YT2Y`b<1IPVzmo<zs@TlwXqJ}qlNyH^_n-oraMH+mDr>yXfq~` z9K5W3WG1vhr(8E9plvSznVVF-5mM>a4K->Z<M%b#*#AiICmuq>6wD!&q0)+%4{2KS zy*^G4f9gc)>>X8g4%@}L1iuoz!mLw<YLY`&)~asn@7?ohg1pgWYFMX)IBt6obavMP zo)oMYjLl|8!>h!m(0~zJmKDx3BFa(<Kq9;5P)aYwcuTEJTeWzDbpoZ{2j4R|^7G#8 z$w*y(#EO3WBu~hqJg}mvY|1got`v8WhMJgFD)A>f`281QNYJ5$v^Y!7`JLMe&9wxc z{s$|RET9Z?Vn!|y?TJjBKUr$KmwFIB`wkUcwE!5AT=*epOddP9X6Kp_Q@B_TLM~+% zPCR;h2Bp{5i`q-9-lr-zetcV;swj%qCxIi<8zj&~iMy56bYI+Dh)-dcC<{cAOfP`d z2y<|xS=eawn5W2G5C4exw<d<k2<`D6S0UMH_i=3?%$a8Xm-JVzFHzCSL(^X)UOze> zc}@ZV1$6-tC6ce11h5lLDeWu|HRY^2aD2jKcB&YpHa;L>Q=}g?Xyu7W;-PIM--T@K zGcDRo0XqDMFH=I3LpV@{4^hXUeA5w#8W?}b%$4p7?@4PWENd>cBsV5!w8;lt+<?if zqN#@O_;O;E++?;XsI)@605JkwW=+(}sO1??{K&c_(&4H#jLo2Ny@{j3)-+20(6PFj zs9av^LF-m`TI6xDZ4T0X!Q_;Zy*w}}WNomRn;ltFyL;_|Buambh7T_Ykd(Z0-C&Fl zAJ%Fn#UVD6)@WQH2-flm%?_|pW1T~fNWk!<!_aEbR`n$xglQ_=&}x!igqK#99@pnF zMH`j46HjK>gs;z@8aww=(i+c}c^?YKWO@)|ea>X9%HlmQ$V)#XD(@%q`(#&DFJ>Jo zyoi~5by9+_;Ww*U|0&-a&+?HagiQ~LKkI!s)kQipC9>}5+7-Z@b1A^xyZFwsm(CX` zKLO9yo1Fb5Zy<XMHk*2I#t(n32`1Gi-E$Q;_nGv$Q$E(8O$x7t5UL=;pRSwUa??A0 zMnvIg)2W)It*tCz{(|~T^tZv2Y8z=Cve@6d5u@rV5QY*@60y-2@%Dl2<9vR(XZCgX z9PVm`-+OsW?h$!xA6WsE`A#C*fa7@msR3qoIPn-0W@5y5D|Y+|F^-JX9SHjt$Oz1t zyf{qvRb+Wg`Wi^<-~3&o$p}MM30)bsy8A>5(AF}XKayZ|cRfG50!b2X#Pd7DW}u?z z5q@m0Nr9mK!13(tkqdj7M{#oziUaFXV?yM%>U7>PW&kmIFIv-g21+j>A=9k@6vgsR z6_O|d?c<t1vwdw6<}#+~at4c9n~;m^*W@g%4k9&J=QHI6()51);MjkAd{#I81?P9s z%<R@w(fW(x;+s1t|5U)&?Bdh7hTYd|gCA+^<WEk510UC&@tj2YZOFLgr{CnC-+pxQ z9IF~tm(s(>WM0S!NLBfud7Lc*yz+IFL-O<kJkT)ch8en;qp$xh46fz-4Iqq>PphA@ zSVXF=v+xOf2qO$*?os_fWCR4TttFE)Vfa^8;3NeNp(wooTw~uvdC`K_Nq9yoZ-}dL zH(;xcK4>9Kh!h6yxPcI6^65c5J0^Kmz{XAZ;1oF^Cn~J|25y;%f8vJMk22bIGss1y zKvyB(8bK-ap;}Hza;^JMirqF9FO_06S4CJMrCwd<eFg$Nq5$X%CI*8C+z!=kMkWVD zLH(Sh55zru#4ETvZt!w54nj?U@j)ho&cXcruP_)B`HpWCzz!?hWGBL=9>^fN{bU<8 z2OC~cz(3q;Tuerp_3BSX;r?OCFKeC;`EIy5lh`TjZ?^{@@)#<`fn4HBiYx%`KycGP zq}-$bQ1Co*9N#}qzeK}#r-ED&DA7HBkwu>i;GqDBqq-><uU~@t@jN9mDuT1JXTxw| zY0qG&P8N1}L9bd5{J4>wIeY0@47mIq-bKX(xyDTi(4ec)ba{U|M{d(S>z9%Qdgf4d ztiJz^96pS=a51<#gP*cK)CP?Zn=nR}g3HL<!7tcu5Qw7KU#H+M62WecoqV6B8wEw) z{Spq{N_m*f(mtL~_yW@x1EflIFjdiTTJA_~9uk6rLU7rrg4J!<J4G-kHP0-WcVpa0 zxzMqVgd5-#RA}OAlnU3mj1TcRhp98xM0lWhsIe-MJJ|;7#DqJAyE&t^qwr5%bxNrP zuujJO@G<x*_S9RAk~gkaUtC|@1U)f_x`7J;ENnXw`#QFyaytX5MJP|nvJUufyxsXb z)PLar``2t{!FbtsjeU!T>|0~s8T(#ijn<JRq?%!d5o!pbXe=R1mh2It5XqLL%^GQ& zl+x-<@6Y$T&i7o`Ilr9iI_EE#UuJu~Uiatifj!{6@AYL&Y*ADZk()EYRftxZXL$2^ zgX#T6(JH!vH<Kl!Ok1yTg#sbC_Tqpo+hSGl00BM<MzE@M-Z0Nl42t17+yytKD}Y0H z-^#925)V+INQl=BUmYS!9fgCs5j39fUdHIC=FZ$yJh1b>fjn$RVIt~AV(Ini|Ap`< zcIo69fSTdgk9p?%5_#q5`Q|ZLr6+|Da)v4sJ&!;9+=IJUm1UZXfHlk6ZWr3a$p4s~ zNyuAmun6$_{KGV#jro>vDO)g9Y6yyw#X4l@Y?HZ&B=8f-Bdo39$qdpPz!3dPMI`n- zjs#yU(!4A9vPcOa2`)H#R%Y0=j*@KC#9c8^p7!O`)?&GYRr0(ccyk_$I->KIoXSCT zmT%|6%*BsI8U*3MB|^4h?6m;-QrFr`FGCACN9l8Cc%_Q>rK0rrvTryfTy?iR{XcNd z)^3z(yejySX7CfhnjA5=!ht(cdX}Ipv>EqOkb2yxa=i>PKbjD}AEAZ^Q<uY^tD0JG zV!~8wU(55!Mkyj>&(6xnz#%fAa^3pU<*e@+)Fj<N73>yR{68*^e5dJjhUK3`J(>|X zPpA&MoeIyX1p$bQUtX^{s*%X;yIJ=fR$;IZomQ+%imO<#fMVHFWZPR)(R@!Q-9i_1 zg$dw~+VJdJ-IiQUh+3m>OvLF52-y;*uGr)`c!&{cqp{9~#zA33aNuT>ZAI84BYg=X z?*idueyy%nLE-;UH#a4)(8JBnmArpyb<bB7W!7fR0(_tF^=i9gB`5O$e^z)){B4J! z8z(BVMj=WGZ*SY2ks(L7I*duf(&f;SlFh6-N8>hLb7<&d<dj33|5XXu#aj?!Gc%YG zVBF40kdRX?VOK4R9_lBuG49;r^<Zt(a}yqR<ulUlqcIi!U{lN)OB4$dpj>q_HSCYA z>e-`~UVdQ0bG^t5Rq2wJyyWV*!4L=m8X*Z_n{H?R>Xcc<HmLcX`jQh~mj%J`k;b}Y zVksX9-eI<23@cw*LO(DGZb$-`m~Ayj%@^WN990Lmh@H_hfuT4qe|GDo0nEv(cZNf= z5L8~^wEj;P!hEswbZ`nCjlOcT=fUk`wuX`4jYQt=7VizqFN9L7Y;jymi&*P3qNnP5 zdsf^+th-^deC84Q8~uEojmu9*L<<x_>jl+)wpVVg-_?Ne%@CpM?e3Wm>n}v;v&Dc@ zl&(`{=o|#!J~0ta4YHk~_K$!8FpFPKam<%UV+)S?l0FUb$^af7#_p-p+g5_W1|SD< zNb(}z^Tm6C=9qWEg@5m;_5L)y^R<l`jg=Q`d^B^CW4^c=<#5cGH4^r9fZpAHzDo|E zmN*~ZxX1@bu^fy5EV--7<DP2t9X&W?v#rmnNFS!cXXp+F+lesAD1MdpOR~3uUhr$5 z<}T{Lwer(s+0SwoP=HTCUOqiq2@xsXeF(n$rDI|O*0O7|$f!;-ntM&PDA>=tU*_5V zn;*&D>TquvcKWCo<D4LG@)6OsF0^WRO5zLolEuLjq#NOhQlsj6(Z__YP`I|6x>iyX zNAz>B6hKhj&m&Ne13r0-+=76PjVAJgZReZ#OB!bS*s15hNr(&dVOcZ4LxJj2pgjG` z*Hi9<=k)fps)dXpTflswp{!50Z7&v-5Ppe$IR+jef<LmZZ{|Oy+{5NQ7d^SD;d4xC zb}!iBWR$CN<VBX5w#m(5Cy~c>;h#XhRbvpd{`lzCf;YAg*0m~vo4KPFxm;45@0FKt zTr)5GVK%fE^knf}ER@(JpFO(UK8YMqrpF->&hkqEB7c5mjBX7Jd-5%TQ!iEkC;$OC zgKPMcy|N)(4&YKCOqY2R$1LC|El2XR-7dQ~P=*N4c+ZL-;8bPOPbY6QPp=CD9F}F> zn&&<F9Iki&8%6>YGN+pn)+BP^H0J*BXWInFCkU3;T3WT~BWal+kp$=d2e<of8XdtL zk$OX(3Iu@zEH5A8L1fvX6Wd)_3#bS<z!6u{orO4bQ!^5cel*X4HXwv<?H6a6z0#}C zQCw4ZAk1)CTluPdaNqa>s`>sm81M|uDJtj72C##+;NL7Y{y^|vuQ2~S=J7+Ky6FK? z6EGhK4);o**wy3j%a*ZSL~z!yu8@Z3HmbjW0q*Yw=b0}jwaAbUa4AzT<Cp9o5nj%g z6^BEaV)1QX6J~rLm!zG$cevqX-Yi_ULZ$^#<m?Y2&hIJb`zZ~qnu`7qxsjkV1r3>a zf4c@k2Cn*J%hmTd6g)%aJS!&g$|LqHviRB@z*$_V;$IuR5}DC!(LZNiJ^3lSMGQhg zpr>_lx@llHf%ns-Cnt5i+#wE`IDo{1+ssv)28p-0jQb=|<sdjH@&qflbYgZyeTh4D zQsqX2;5s|ioQHq}0L6vd(JjFu0xv^2IU*s$?3ne*tT{XL+0upsZ^&;Zr#wEeuEEQY zNxMyR?wT9D!AR&5LV@HjdRHjBJj_hhVnZMIJcwZTO8&C+d2W7~<%H;xv?L@OTqmxW zH&=5~XeJq5PDa<gG$$OFeW?3%!*U%$hAFozK3an(vB9(JQejG2&}R7W2I0z4R8Z4f znCz^?EH(=(@R7J_F0|HrS8<Wq%y~<$^Is#K5E9UJ@n~8Nuk`vJ#Cu*-@;3>*d{O9) z*vJzN=cj)Tz)8S>!25(Xo}DV*<^C%#WY_&67~vxy$34~_o8NPM1IFcF=&G0Cb9$A0 zRj7l>MFye~uZc2u?amv4I|bp8rq35YU*K{z=OO@gE$1w6fnmBIE`3IZnlCEu_E{Nt zVO?ba_4D9o(ua%Yue=nIjk@0ZU0pK1@#^mIK_N@er@To51CjoNFzO3SSNp9dJ_wU< zgPOfP`4QhIhTpRtmdSpUhvnqbXP94Hm|t4l_#l729%@|jaCQ09J{i{*bcXo-e)Oi- z_BV20+aq0GQNPRjx4u1ILilfgymZwsZNfTKLnNDT&unHlrSYBL&=-fP&y%0GQ^dbt z;}fi&aC#>r7<R+AEd5={V}VuXO4n6hXxV1<At5dN=k#|!8(oD2!H=Pmd?AN^X*JVw zSGV>@lfS>PLXPO}EMo7t+KxW9mAkI<SePd};z!RX3*28F1qxjB6)&IRAH7}APj3$Y z)DHFMq@8n0e_mX&*uiquHtPJ<S~wp5cm04x6y*~{64{xq!}pkPanG)NULU~OU!wx^ zLuLPW)J=1FJKa&>!i<>vs$H()|6PAJROGSlQfe9wCGxXMT+6Mq&4!*H-*Bt?N8Lzx zZF<(G!{sVD`)mKGn+P4Y*L&ZVaN$y;aPJSC{;Xv4*BkGTf!%R^7&|8ZMHjI7{_p*_ zqU4#@R1S4BKKH`5{-wYH&i<OVB@7Tyz>_Smcg0>dJ*x0sTzLT~!DQN$`0F~JU@y=E zqyxSkt48m_;UtBN`##L?eA_yaQ829&n(Gg-E&aXUI3B$e<RugI^J@+Otzp@io`O)j zp+f<+XIEA2=YD@KkM;kZ^zE3s;?TmuzsXM$`G^$fzK_=d++R3%|J9T5nZ|Mtk>&>y z36ma;1mvD^^wrZtQNxndMJBSe6Svwl*w@*7*phG9UoMTtMxV4wchL&tz%mB=OsNu{ z%{G$CYN5rzWTFes7MgJ4nq<0yw)%++zaLfr>|msV0?c4iQXj*Vv+;yWgy$)D)Hi1X zcd5#E0WLIB=H%RxwzKYW%)0c67qVpMDgug-b6~@~xlzuMdWxT8)KDDGpRm7VW5^fo zx?6hEif7T*l%KBSo=3}Toh~JQ7Mvv1S$z_AJm9S9l<?54rj%?1<Md}f*+&SP6|=E3 z=HX#&bE86W49|em*?G8w=bcp_s>1T~%}JLU94&E%7*=jlyp^7RRP|ZL1kF7;_x^zl z#kuq(l$Z4w&{Em{qM?O<CNRzmj;jYsgT7Znm5A`7$gkq*(;C5R-!gS4=iivjjAVC^ zQu%Cr%a9^a<>1_JH-}4f+Yqt;u`_#)RuyqcIJ1PF2Irj3wS7vS&xi@j_mCuo=Ozm( zx9a%84`-|Cs#3TT=6oxd)<*nSNTh%=M6RnQnjn1TN<?>5>eZ_WIZ>Nb+uhuFD;0ux zB+rzUAgh_D%iG<KpAlL8*v9yHn52uiy{AmkgFTkOM5@DC8Gh?LH;kZ!ud85+_3;7Z zp62j-(&hWbqS$`7g*--9tOc&?K2w^EpY&MEV-3E^F91;JMFBe~d4)XVdLBG7&=90u z+WtK`@UpE;87-GX(+r87&r;PnXcw5s7q^t|`Vj!wM*Tjm_HF6nx@L-Z1X*5wR>J42 zv{rL2{VEj^aAP13B!4zFu9ixKqTVdiN2X4PxYN#5g8DpVVWf#i+iNSIzpo!?e$I0s zU=W_d5Sv8vkAoM+an_p7cID?*mk)O7K{9`BKTZ)1%iNm&wm0mn?XLT4$C3G#yn?s% zqcLw%?kPBUnDexAsGC)Ek4QORBvnmA-pLN0qswrbT^86&TXKSnS;;wAr4CxoKtDaz zm;SqHdzBricEP|}%|a1^#P{FcoVxf;w?VqGPDqg2sV)!4iFjFsN}SG>>jB8*55%Ax z_Z*Cir&ZR>g%oiEE$$mP`L(0JhT^VUrDE@`NV9>8><9?Aa2i|obk>}B7B17_s~hvm zP?&>G;gx|WgZ6>${+jSpHVlHce@y57z1m$4-sMv=`3}}9GUDw@3r9d`bC^2BgNND= z^Xje_sulU7Inyf-bX&|SRTe7pU)1tHxdYFm7>dDNZhOn^8d2a_^3^KYGWS~~yZyuQ zc-OV*;+QBd=5(A({PY{l3;q$=1Nj%4v%ip-1}?_$?iqw_&bYsfyf<y83M%U?OF(mw zMsuplK1_{ZyZw0wo<R8s4m$4ZsPv&$92MXp02*TmGuqd&gy?lq2tI;WJ`O!)o+4a7 zA~`>+Xf0=Cqqk~TY5jEQ%JB^t24MCBQi}j}V^BKS!WZc#QKewBDN<rEB)b)laSyv$ zV08b8w|ZMP-FKY?6CT-@TXrd-u%bM@7^i@XM!T`rYW?X)1E0e8otAx{jES<^pXG<m zt&O@?0y3nv`MnBSEMmO#kA?`3DaKIb4-_?}?pm$}%cl0aOTFnYD0X)%)O3Ohq?4l5 zePw5)jAEK+>}?NiYmd+PdrGI=M6SqfWk-J%^lb;MfS!!3#GX)#0ttHcG#gzJv@BHL zq^9Bg+<&d7pzAT`uA}c6p!~r*(Y_igK_Z9eJW8S3Zu2Tf>~Sur4QX9**NlCB`Qm-D z7j9c@*y71^mzp(XaDW|3OJI7|0pcy_x;S*$Z|cIT+G@j>k_nKX#|K92hmd_oAZlfN zR~@*;fAaPl?nvG&<RW1poKz?>$JIk~en{B`D<&cWq^w$`_5GyFz(X==g)34;)}E>k zWfy!rp*%FoP&9X-zffa!rggiD+2*eKAPY4FffeGz6XV>EmI&F^N<5b`3{F$FDi?IG zKa!MV5}~bZBfV}gY_J!Opf9c!e2hez#Cxa*<H~^cNO+o$?mchPJ;9SWE1jGE%i5v~ zlj%#57L~{9Yz!2f3<@qA*biLrv?}MB^rWlRE{t2AUYLm~3kG=lovF+P?|VD+46%DE z_WZ|$%2_(Hgkdz%u36~YZ=K_JufB7t@|5);+HgUemc1Ss0zN2$d?e3x&#t7C4JaL{ zdc6F>IxZOu7J0PJ)R~^rCToKl&e4cV2bcl4FR1>Y<J<02(aUIbS+!+!@9|Muh4ezz zcf&``8vu&c?Qu|#$vmRI`>1)AF9$?vLRq2qscP4Mq;(E1w`9^fbG&?Z23n>{h(A(} z2)#LLEnOc1_nlnU`EpB0J@3I=M#qcrMErwVS{XAnR;sgtq^}SkoTj>yB5-SQhT0X2 z_OzN^v%Nl-3G2^H+gNd~buX}>#$miVmj!5q1b{r{T`~4nxKWI*ER=Gp@=A#ho9SyY zM?$C9#M`~kN9hacvJb6gN6Lwg;7*k(a<KIGvs;;FJWI@=-4e@lZb;*a&)FZ%tX|~i z{%mfUz2MEz6ku^v)ZLf9gGRIL{srefAATk3CR(Op@!Pe_Azvag9fupuhBn~POvBug zukEKk5)|8mk-EE110Cm4Xafi6V&l-W#&Zab^6qdg1*?MlyTT7KyR2K5*ZB|kIT%jV z)~;MycG!#9dasK-8}@n2K62TV{X8c_2W5qvV?%y;S>W&V$<;#esr;utlOvK2{$+)v zB{0%=R|Mkh<iwL;#9(Zkp_v!ZH`Sct#yRq%jwq8S=td!9Np0LcIdR0>u4P)WXD;s3 z7ULJ7Hx3%(LB=In$>%EsE2<7(qQ-i6KLVcr<wu%WWx=YEW`Pl{{tlux$^1GA8JC&; zR`Q;584d7-OO`cLehH+O<*b(X2wh7FtZ7ro%S*63pdq!tBNV0LiJA-TcVn5b$BYgV zB=)^P?_%EF8^)!72pyC&OiRaCM&tFqktk_+r5gbfwMXg9+ZU8oO59jC4eQaZmb?O1 zR)%g|nxET70*d#J8gg_b8bQK!qtC_!oi~c78|1GoTIre#pOeg8CyI0ji2oF%`+-(` zGsduhTW<BJKWNHS#r?pq8CFb2UJ|yxN#lyW=C#n9MmRX$4puc|U9i&|o~Mq_;{Bb1 zN-#%C#}<#??wd-4;tjYsyKK25H737pymPInJ1Iu17dN+tp3D;xinR{ba~;aO2lyg& zjIZrgMR*eFo;9!ol$0pRD?m*(K4u{LT3NEzNPG$>M?fYNK_Cf~F-poh{{CY-_^!$^ zfZAzC$18-RuaCm$kC$m8O{x88p!e+o?pT{d!aW*KWwIN-+<`(jyq+`yCOc+@QqnST zTp@TR{0}Y}@zRf1>ApDlK^9cqj?a}%+w{oxB9GR<g=Kb90#uCNvdZQ<TTZdeXWvSC zpeQ~ybUQrEc9G_}LHopSaWl;E%>r;Ql_#cxak?K93)-@ys(Rnjd~0AzJ2Y22x?95a z&z6mY{j>lIXR?82)Jb>6SGUu~m6s~z?HDIf5Bhc>8HD?<Q_7;%5OpgwGd$IhQ5(Rb z_lma)ws1QhQJ_;CsQ6oytnp{9Iht~MR8qmP3Wd*(VHK&fvopH89yxj`knTbl2UJq+ zYG4mcoLd*K`gvyd`Jw6<oW||I!jOv`f4lmbtSnDdB7i>5G@@IeV#QpR?YUc`5hs7w zujxGU9Jw|K<?#iK`;VZAcm()x;!ofWo1?TNcBl^?jQA!SF(ZTzPz~&)1V%nKT15DR z2ro8mIML<yP6~Yk?(8U$#?E`U`k2p)UqA&|7GxazWz_&?$uu*<P!u9JfDlkPGkui? zjD&<ad6FDl7mZr%Cf&LbO=qr?`BBgI%Y(Y^d{NHSP9SX~=T0m}GK?`!W1Ixj`4tA$ z1SC8*+~~e_Mkv@p9KP<9`bO*pxamHsnB<?K8@ux19!UEu@DXb8a~CR+>!=FxI>9cT zJ&}e>dz9ct@1D_7<8f!h{T8MJNH<+oQt-sO0F=l2SIki07@bk&_OSKR(HW<FzBq#x zaXU_$L@^L%MCf1)JyHMQDS|$ZYU9*WouqB4kuwpPfN<-i`!ag*JMQial2zl9hmT$e zpde=KGMz#h0iASDpe$u}HsZ-eA}=5iM-ktECMNV$*FZj91JYR%AM;dv>WrxKG(arH zg5XruL-So6Guo;5G1%u3>7d<<CidSrYcd4Xq^8YV9bWVKOctUh!1!@`!ad$K9OP<* zD{q=`Kj}JPhams-2~(u^n49m$)8R9%u6A)3dc{S(JLzl3Je%(9iTLm|H#<9qGyDZi zDhZ)nrZFE!>_mx-WBpvWEYiIn)ixU<%-js9VyQHPdLIJ4X8H+I7{THft*%7hjjFp8 z{xmk5?q@(hW4$j|_gS4VZ`u3K=RN2?5>ogPDqaN{hViU#ag`889V9rl1$76aV3}Ue zeI~8;U!XflDi0`(;2kB(66t%KQB^B~)X5Z@*i(R$feDT8{qe+u=o4gGyy+>CKeRBK z&Fk*Wm_3sbL+q&oo&$?e%}B-`0GgJ73^do$_#x(nw@+IvGKs{Qu&41%npXmy>lAAz z)}=K85tof<t#R3P?aH-IpjoSw&`A5~{d7+?-u~j+mtOP$CRf{*`@sadE6YewPUGQ| zSF24gfJLC#H$846kUo;anCEJeek~|3yAsA&<VR_v07;M`f=b<wf@zazIwab&o6`1V zmi0)g#YpNdFNs<MrSI@tGHI7Gx&lV7-L>{^3s(*LK$Rmu?#`xvhs=FgBfS+vet(z| z$F!UaMrq>GXveR&<g44?Rx5OWN=xVjD2Q+&MnxAL*<jT8xwyv<;amf=oP2`A!jw>{ z*1V}Q2Fr40%QB>8O#7nIPEg#RG1r>st|M2S24CKLzo=1wjbW9E+X2D94&J(fKKg7X z4X?24A$?miiSbT|US)-F2PF6(2DRe%s-JL>&O{7d3yC{E-j_vp10=i`gLMCNqT(h7 zq(+jKmu<YU+)FSjj>^OKyt?>^772hX>Nxym>2WtNt8RwGI0JWutLxP(Yi_Ta=k7Ht zMx{AieyhImtA3@Nf)$y_O0yMW&~yCgAm`BmLw6FX?3|&u<9r^>>F!zZEeQ9Ie=}>q zNm=>agdy}r3KF*>k?Nk+518f2+V{9KJQl8z-b9>x6EoqT-ucGW3#G{D+t*3V0;pgO zRoa(vL@ZyF?uOMo9AmS7zBK!|v>rE#lA4b?eGDaM_k@N+o?tm1{&+ZoYhyR#9FJlB zDy@)$R-tqxGxo<b_7$enQsi}Cy<&Vje8J}JFniWfa|4{8%la6>z;Dn+P$$HySf0TT zb>C8jM)JPB9W>xlv`fh#LqL!!QS&D4AEXBVlawBZo4hvnsw86ddi!P{E3Y+xQR#vb zWkIMr5DC`Xgd=vfT^-k}j@0#Tw#jhU1gA$$hNp?W1jOF$OH9A-i;3xcS66kU{oB#* zrePX8Gq#Cq|JEv<%sXB?4A?brPQG2Ud)HU+zHcMzt1~hq8rk#US>DHYqu<_l5z^0U z`aX^b%lP|##^%E?v*VP@hq?IU{fv#L1s|TpXNr6!E<E_~;@gGj+9O;qza3vjqX5|- zaD+DJZtvdzN#l<Gzf9xg(*IW)_l8ar3nbNy-d-OTf;v{JEZzQ}G%o02>&+Ra<UzBS zcruKO$MXi}#gA6b3Y^@5Kpx0{D{x~D_G9f0&pXJ8Y5|gz+WEAwmCcv$JnAgN#cjna z9(LfZ%i*?S2c_I|t++9k<Z!31mbEc%Sw4lfIE8dKo>2atw}V=5X7Y{84wl5iiE~Zz z#S?a^J{+1YW-K;ZKZNm0cT{BB+2mH{r9fq&LlenAuv22zFOIqNcE`~OSSTOq%o%sL zr-SOdXYaG;hDM>*u{!(i_MXXS!3d4Mzk2`ts#9h(oh4hGWf%)Fb0Xq&hh)y7T4Do% zO@1q1+eELgq!e2>!G3NMs#1)8=8tVoMDCCKOAH0GwLy6^ILqGJ0oA%p&=C`=(85AQ zQ@j-4L{4X-qwc-75h1azT|5qHvjFB5L;&SGaKa;Q+m_0CZh6#H7_m{YNifL@Q(5F| z63<zIBRN-3>Oja!Q&fGod)(Q)rYYbRo+2f=q6CT9b%Jlvk0pYB$n4=#<$QLEg*ax_ z5wMlh1I4Z-E6_sZvlcf9k`d&~*ArYAqSdrCwOV&xfy&a;y!l3(wFh}ej~s;r?nX_P z@tQ&ecx>+~!Feo*OLn(Pdet~9aGHosglNJhSaV<RUA?_@&o?1uPX~2S$A$yV-LO(5 z2y=~_sekPJZw1aeiC)+Sol4rcfwFfzYIE^~7y*-y&4Yw3mB0Jc_umSf#Is)o11Q4_ zjW?8fZIlN<+y7SJ#szysf_Vf&UY<Mpnezwr-wK>@<!86zg8Hq8dpq85jp2v?TY<Y) z-Qr^Zr16o-e=BfTA_peSMUQ`-vQuvOI_;$Y;p+_1R%3hC)93j16W_xP+jD`ZKm4}> zr{`##b^P12$m)h~3&%P>e0xqF*7*J+_UZBOFB8@qzQ0QTzWd?(YYI~H|1+Ac@%Pra z{{Q0&+`hj%t5;6`{jpKq`1j}kWd&~c&(3<|?%&_vKke=UJS+fd*AJCoQ&3JUsOU&P zml2x^X0hPPb^{oHc8b_Ii%WlG0Gq^4#qpG(Z0+s|6tih6PG$dprf~`56*Av<I^*k8 zFHvTtjG^`;77|-bhEt`S=qM+R+sa{PRVs{DSK0e-<ra=tX5!s3&Pm#&Rl^agmBj^b zIP0>w_?ohh>Mb=m3GC>%-s@t1VJE@br3a;`e)@-+Ee}n&j4`GW;%0wP!o#U`V`y*x z7omxo<-$p+d`%C2;EC0jVmHbADt1(dA9>co%|JCF;>Wn>_^|N2lk&MqRi>QKlHe8m zCDoGU2{|zZ9@GA6BM!~R3P=tqtTmwfnDKLeNtOdj!4YMr=1CuBdeQGJmAH0sipO~M zUQyu@RXzWy_csQm*aTakP&ON2gi1l9h6#Dm89FwMy=NpC`z1my(T>3+B12Hd^Gn#% zETJ3Kf*YqUi1(ai=m3v8hxMSqMRPeTsn_IMfhAd{?(ZnMkRJeQFOVW86vh{ev(xu9 z;*SGYFA4BI!;NWyUkJJYL7Ky+;jE8L2+6q^jL4t_QV59tI?4skgDN4Y0?$oAi_Y*w zhRn5|%W8lyFB59iKn<b=j;x(#a<|!9`TYQ5*e##X!uFvKG0eFwpnEo&o>JMeV3iS8 z0-jP!-|fWJ+p%Cum|TQaBo+5|gQe1KXdHoBt$`M$nW;E}2?V_hIJ=SkBDw#kn-={N z*jv#SEHQFSusoGBV!{PqRx`(t{i(Pzn#KK~P{A#1t=yH&@2p`H_^F_CfmdXn8lX%H z)R^Z`Lwgi?3BLUIVDtW7IBpR;nTU5#{!Rex|7eU^ZVck`o~G81lo+6(*p&G+$*{F@ zlTCg~(qe_oM^2IWV&GytQCEu1NO$-w8=7Alid&kr(Px`4o_SFrGcIkX1DCr52!-N~ zfHWMJdppqclzt^a>Ak``-h918++GpXzNXLEobu3WPo5?-u8@lfSrxm|pYg~**y6=g zd8tyb*<1$WOW3$dnDm;#u;DEA;z_bM?wwt_@#es?(wN}`=;t&-d-MhXmlwknwODAX z)A#KiNv(+tGITd#3W%<P$9DLQKC0i>?SM%|zZo&0{G92;(yEV%yfvDQ#-45+oP5Jh z(>GA}OYa<zKPuK3>bD(AQ+V4+98bT|DCurkE#Il!tZNbB%>3~{US{vDVPhy8>rhQ2 z2+v;^K4`lMj111P@egD-B!F1j*9^PDkAzpBd1E54s(!$y_rt&!KLo5Q?-j(@{?4ON zbw*(PzNvdx_0!_|G-aS#ZRTNKCskfOkx|n%2<$WkPw^<s3GMo&HUPfdK4B?*9tkjW zU;fwAZK+RQP_4|#6GMqv0aB5@Sw>beIY-1&Mcu?0JS~ENY+?Ju&yonWW8xImLMl#| zuf#az1XG_4m3d*e)nb`4t$Q271+nWU_;<s^IRk$(^Ls>4(USnpH}*vQY4b%L=Bd3R z7e3&+6CyO$gRC5IYplII{!Q_8PjLvZ-5x7f(a`M1SzOAYa?={46YvKA2igxF#29LV zF0K7=)aQPT`w)dEjFtSEPAA}^Gwz(f_zwB3Ubqi(X}qs`5)ygLFu@g!X@!Yl?4g@a zl_y_5xHauD%Vn}qA|F?H?e>P9t-%BHCrXzRaP9svyT1f#9UmXRi~F$CB4YV4M*D{$ z0PSo1ia3=f*ng?ml>pnT?a)PT8r(V*7EwR#0j0VteNTMd!QIdF$m%d-vSM;>dvyAM za4x>>er_f%X7jZ52mQSpI5HdHd;Qex1`G4p6A2BLDFKh<tni8*{->wCkPVevI}`d{ zh@zLw*?HT-oqM}NgaFjbgZ~+7{ob?spnL&MKT_l!%Y6Z#vLP6v;brLX1pCMaoTMD# z5NbUgM<T0CfI_1Y#92fzbgUZOjW;b}5;MP?-R?gRVeti5lOM+L?ohBwhmBvdcp*$Q zl>an>AA$@{ok>MkF%2MB0$E70*<C^Gytgq$2^`S}L1r2UQ#%JFov}03h{Fk<c1VZu z<=BBtf{)~giAj}l1fBO>f*B{dP(c|wKj8kk$bhhTzs*sH<oWJIFd9R>k3Hc%6c3e| zgq#!wI9M7dF6r4ZNe2wO^N=t|q~JWQp!w+IaFBC^015)%l=*V2OuHtLHchA}ItDj< z!O(Bm<$l^cL)@JKM(vnJkvT<}Q`+F^Ea6KXkYs5T1V#8qt<3@F=PaF}11=0pZze(B zc022DjU+G9Y<SYZ29YJ0C=r?fu7i96KTIgTpjBJWyU=u=Dc`4^CJh9c^hx)Bei{yJ zB*ZBh;sbU8lxIvFR4aB?o)&-lvTzI{5C;;T>Tm+SLLbvs;yLIPr;fv1R?b^<huw1L zmA2L0qU4r}0aL!*x0&cvc6u9A$umRqf4DRWKOI|+mDZF!y@DnffVc5rD@lK4#JZ1? zzqDxU6vH**3qE6-R^VNsW#Na#@p;>)Z3ew>s*qmZ#=MzAut4q#R$->9+Fc~i%C~cl zmRPfzeJd51(|&RJoYgdD+*MVjr)l2DN&kej?R>h&<&0K=-090#$Rx!3f#Qan@^ZSD zI3unH$f%!etl2Z24Z=03Ib*q^=ne~gt6#j5m^)x7cTxmUVHI!%A94vzgYHt3<S4)) zLeldXG{!LInW55V`v1<NUHyPY^E@jpm&4`x9tsrKP1gs7N3Wk8%JQQmZ-Xosd91t$ z7Pb`o;T~#>#rv+tw1il|rKV(E#QDNG5u&V{qQ}X^(4B_hwWf$(eY2v;Qx%J81*zAi zhTtfzv;OjYS(6lGx{@8rjFU+=0hpq$GPFQ8a_Qnx1Kll7I|l+B>+H1w7y~9R?&r?b z=1_4mde02@`|;UdFduIN;7felN)?`$&vE5IihRvj1kNRDNycTBo`@<r8uqxVu8%v* zRNQPf4;@4@TqKvlDy|+)h3+MT@5$B9sn=C^o1jUUs3rL`P-@}Dl^Yk-%ylGyzeRc+ z*USb7UKcSl>cChP<5ZX@#tZc<aT@<PGhEFR`BbPIw}gM~aw@Ng1;|GP&lZ^a9d@`% zs{0u22OY@D0gjUfvFn`qEqw9+AZ8PzrtL_pL$!Jm?2;j6y>&|Ng(au}h*Uz<)kDzr zEKGn}{jw#8EKB5B&{cbK6T$>QcG9eQ;HHE0G=cBaA~yD+-ZLW*GFEUzzVTvl<3T~v znad|)_QNvhO+*j(?KYce7J|eEIQw!4*(=~39gJi|(jfE>g)=>fy(q5dr~+CLpeP)~ zkfNX!e^Z*<>NW1R&+Z@=?#P0$n*Zr!gj@U1=zQw75og9K#<!TCvD$s8cV`pYMNxWM z%-Khgw#T=5zmsv_4&ciauO-~{`PIfP3kd<r^f>DYV`2&*Q~?A)jAVaeJE;yzM|Bvr z-aNm;)xj#dQigfr&@q<^@ZiAi1pN?V+^yvf6HkZ?z!8b~q@L@g4%I`O+Zf!IHy4g4 zRWu6_yYxMQ@;LoGMM$48AO*r9z@=-B7DiQIIJe$HJY3>=h<Z`CoK9?Az$Iuf*H1R@ zod|uV1pI?8=ab)NI_M@5-qZR{CteSXKHP!-l@fcI9)d%X2)HZMo=$U&WE=)-E%Q9U z@%8Q<XXumOHU;o)aSuUI5iZNOjBh=)@=pfaHzr!!R0<)ZJBjqB=#q*_bmJtZo{cG) z?7L`=&YMJ|-V>|w{hYIBt(EB9MX}|)6bQ>%IJsow=zgXVh-#`@!QV-m>Q30QoviK( zCGqXxN|PWJ1!YQeL(+LHw00n|Xc8GlKp0S9))biOBy8IgZu%Y>(T@t7L}n3uM!z9) zLGHq$0lhD_@||^XDsM)u{wD%2-55MtCpx4C+H^~Z-$x!IaUCWP<}<ll$=oeX=UbVW zTZ<Tu5SK$l=McDS*y!CM?q(J`nCNO{63{_#t|kq*NbO(a6iVP}-rc9<!}yS)cX}nF zfGr3p;6!c{vJV!Ea5l5PIf~Ovz;#DN1QD4IaCcEK<pfN5lUqeUrkv%>ncplWV|1#W z{}}g|Gcn<bm|!CE8Xj?|3EhG3U)qn>o~zrRhn=S=jj4bjL7mE(Y&9H(<^ZS2@XHjw z_n;TaeB@me`U(}Z*8tp-0CI`QI5wrDAM@u<@8`G@b~5<faRic#W>O}4Rh55km=X;S zUl}+HU&@=PaOWsz&Cki49*v`%T?){jTjYKa2tIhv`|*s(&VtBqN4Kh`$It;31joCP z#mxk{Yj8y9_NcHdF)A6A-j9wT!(@&ZRKxCR>}p}<oGeh2WQVA{vx3-t@j1vTUUD>w zPYgJiIklz^mh9#2piErHPh<CbsvPGRNya$aKZJk2w~(q~MB{xAg?RkDQfDqw_7FT1 zrF;Dv=C}lKkxgmF=O>k+-)MEWQztldWb-6O$zVj>86<auv|}knKOQhaG!cIpsx|R6 z^rk+qg_bub{Qt+J(Pp?$HHo%+qBZg{ZAj4tnnO8``()FJX4(XB1Jig+U}2TmDhlBH zIloFWZLQAddnIg5^)9^^%xmJ>nw(#dKb(`BVc1&*4aV99=!ZQN9rv7Qrl8lKKWcS$ z<dV%~f9-44c_Lrt+{VPv7Lg^p5BF422BO@b=gGcmtmykHSR~B?hPwwk1^{l{b=@X_ z@3OM=4-v8kxcXA~=`;ITRdE04v{lK|8t0LDUV(+#T&qWDJe#YF^>C&4HP6=*U*r!T zb_REvTGOIA_YVJa*1(_~<TC9P7B?ok<|N)mMz<tzx3Vy|O-3I7;a_feSu^?4mC4oa zhS5IpsxJ6d$62G}>OEcAW_cg@UJ_=K&9PPA{*%`@mj@r0ijBZms+<pbxs>}<R1P{G z;PMezJ!n2Me{_7q=}dk9#6o2_vh*c{f~g`uy`=%xn#U}ESmD<x{vr=FA4U9K<fV0s zZm<WEtJbjk;NRU*L>FGEL`;-N^=5MPvG2bq>64g!AJO|u1&&U<%)uj~LGC;C=34+( z;;z|cQ$U)4IREkaNpo*QU66-afa?#|ViovsT4x(<;9Z@m9ZaQ!s3izAQ6_GYF^|K> zip~j$WMMYnB0Whc2y0BD_3VvTW}MXZz=O@CoC{Rre=ggt-2YrQO1G^?-LM*X_MJ$} z4yBRx=FQdjD$NUx1Qe6RbrRT2t$!_Wj?m_P08u;nXux|$0yqG|Udt?V4R{mOWgPyB zygMjz@)}nNh`vr**jM^m7cy48_~0CoD^wNZpSDgn(K6;0QtG&NUkj^}h=dSfxLXC3 zT`%yLFz|YELopXnU?U+c?rqiwwHz*n^O>y^LgGR8*YMpf4DRb7@%V(`f>8fUUalMh z<|biF(G`DH@&;#0DT?&PGf6uC%@$&*XT$fTwWiEL7C8J!Es8R{SDO2l)E?JEg7uS_ z)27JVij}-WOFI<+lFB=S{F*$41x&$?ziLMhfiEZ`DfJ!UpQ{i4$h|_G<~sNlFFUa_ zwwM@omzDM7yI|2b%j&o1t}m5gqh4Q9Tt>|P7UAG-%um8lT`maV+9Jl?isKxmaH=43 z7lY`NY<SBgx|WE!!E*LJKzKFDW_tivpJ&}XFR5B}PM7He9|%@-56NuVf$jdszabtA zY2276@vENYNR0rR9eZnJLTIG)4Q=x6S)9a6&+o~CMavZIRG=-E@QjnjvGn4gyfRk* z+X|eVh3Nrkpq4Lb`M(vo)e+a?etD>+)Nc_M&hFm|T-eQri&d6P%^*(PF+1UgKP&gb z{=%#a^@>?hq5#R8QtEW|FYUiH&Z|MmGyUVH_bu+Wc!Z?)zclXAUnd-KARE}YTS|ZD zUPMslc?)N?^1kfsJga=}i|BFLK49_HPwSpIo`XJ2><tG+W@HGX(gLxe0E*NA<q8LG zNcn$_tWCGi{FaV?88z1s)R$HQQp^*VcSA1E={E*LOgk(yFL#i^zLT%#f7rZYSFQNe zTP4OXB(<13%uaWXDyp42_3>rz`CS8NQvJQfe>B^x#beZ;okhmC?y7g^K^Tfwr|@a} zP3aqc#*BSGZb5?ytJ;3GN>>j?(Um7{Vu-j8(1c3K^FM1=^FPqEn=JWw1=#gLKMibf zGrllo1L~<CP1d4^Rv!Xru_<Lr94V_#Q|kQk8x!M2k{0Dd=ku`3falG(Ro<~lV0(#+ z-%#=KlnSeSce`g=jv8mx_=i5N8Xj)b_(!u*Ul|UM7u?l8ESVO<c6gK>%O9DcXon(P ze4gy*hAX;z2QD}q5@jvyrF8Y;u5MXr;J+r1oi6I>`pw_{aUTJ5y?^)x-7i;Dc+f z<`&f@K+-W3{4nSr<(YafI`W#J<yd8=Jt+|`;AM65tF8~W_Qq{j9F>;uA!l{*f9B!r zlzA70e5!jl1&%1zy3HQ#SSwI}E`*T-j^D{gm8L0?MoMBI{+MkzN#b2(C??0;&v#(q zw{TI1-g)8NeY>oLL;Qlb?s)J((w{~A=|cFQ+H(ReLmt0S?Zx0sym`Rj68fQO543#B z#0Zn9kW3ioT6S#Y-SV9R*kq-!|B;`oxo#Ja=e~9*bLs@HmmE(xbSYh_JF?=EO?TZZ zsp1E-QJ?KM_~y?ENA8NI{uI`5qn>!8Ae@rX`&Q`M<rO@|N966Zb-JRkQB=pCiLb}I zGW95wE@}S<xU5NDT-xESx5p)q4fVA5uj+|w>&fey2j(eW?t$m0<f#98-})qePAvV? zo1U1*2cBx1bvd6^rW}iXw_)RWN6YTW-QfQWyx>h^H(x*N0mp(_3BxgA?>oSrO|(Sp z%A@x?32U5<uS@A)(aKhaZNcZt-2R3m-aBS}c-i3t#>?;Qn<Io?wbPBdleGQxaNpVM zsQI0plxr>{iD?h{dp-7bTOxW&OO1zQO&}#74Won(2Y5r~02=hgy**C~ALy{kGOl)U z(zqcKmqw&o^t{ck2{JM5qS!R{bgaV><sYe~Z~^VdCFR0nhE_49Uy42^pOlIu7bsx} zu=x4`-b7!k2pt2fe>B^PfMH_;)IG1Dqam~$3FMYSn{bk*c1QqLVJNNUn(7f1WZ;m_ zSI8yXCQCSi!lffphIWoE&$Ok5O05~#8a`RUxy+~j5zDR8&aaT#YO*bb;_m+ur_oEs z&^(Iz7`HsANi!qYY!XO2zFOw@GXd^#(c0D}#VV-;9<E~Rv8R*&fda&?Ox8U8zN10f z>GPWxi7v9}gLWx=M_;5pUX@k#Jm#L)2amwh-xi<ej4nJz^=t78*cnQ1DbVXf){~Yk z#M;ZvPwwh0s_4jO*fuqTuM%ilzstJZg~)|{VP)Ej1KF0PGbNv5(I#J;`O<!8W54c* z{28z0Qmr*leELhG8P|MaRQ#Aw33)|D<TK{HQz*arkdlctIx9Zev0SuQ?C-=E;j^<F zIA<Zd15gUDYspYTYa#uxjX6ic;`ZapoKw~L%&_PT=Fi)(`icMP7~T`=ZH%a``x+&4 zn)vD5GBMpS_pqvP(#nY-v7wx6a{Dbd)J`?9mJ$;z(6_p^Y7QZe`lc>S0EKlpWy#C7 zMaazY_p}>&%_8b8wKC-l=lUyhQsF07bwb6$Zk|T$HTl!2K_)mSo-MRs^2qHU;eUT) zgTHv!1$K1k2#S_>`Tl#KsajRA=VHv+glC6`xb)m=LXJ(19y{`D%i~G=T-zR~`9s1m zcPhhKs9|qG3`%V3={FHIwpi^+x^du-!V7IOsn%m7@}Rf&Vd2t6jp&t5zv-HZo74Ai z9hw*zes5#7=kt!jbU&#bK+#Dy(YFlmNDi}aJ?*W)d_055-Q$TF!m~o}a|a}%j{bDN zyNe)Gf;cOi4=8ZY-)U}M!-mi2cm#SfZ&4IYf-#oX4VWpF_&<g`=R56jKduIxL;PG! z@#ds)HlJOwAVs+{qPOJ<!mL%`P)A~lP{W9HV29X}(D(Ua)%JTAX5^S=q|^sD!(Upk zcbiF3f9r&q0ScGSn}n-zZki#V6`HjUynJ;~5BSOp^q3(hrCtvSDc(9&{3I|Kt-{g( z-lXdljvKlr-18;VHIF=f?{DE7|M-0T$OXuUX2@OLW05jn!`7l-Sos)2pe)`)gq~OS zk9mc2L#;zypGP(eU}d(uG^?K^Q(!^_02!HL(yg_=-F_v;CGEw<C+eG-M=GQRDz>j9 z2qf)|!LgTXNR#<+6SstW#od?N@?sv14q%3&W`n+6;y6~4%-P;FNgF@EmxjY_7H2fQ z;#<>4RjI39FO<`C03ky5_Rq_(BSb6Ug8$pD8&KA>+ZigAy6<9OUuM{Z^mHUYb~o{N z+iR6`!^TQVLAqj^z-zBkb<I%c4~oAQ*M|lJhdviL&<ugVy9t*}Uj&`!qU?F3cd!JO zgg$${{g^DDqQt|86RG{?G9LkCYp`Z;;;|L!RUq-?)OI?_%5qQn!nc=p!H1J?ClBv? zov89Mrtl)N|Am`t^FVW{Vj0oowd?T0+}emsEa&h&X}Wv<iOl$k$zM<A<u&F9@5ak@ zE4#!tl7F*Zs)+cYGY$PkMAqH!Jkx<v+s~}Xu`US@_@-{3_!L;udrt6UkSjY}GI^z_ zI{VPkbN65@3Ss%pbF>g3eu2qlHgA4$^JV8-g8@IH=7H0XpT7DQD$!zY;r!yv;;y{R zrX>CK$(B3)hwk>Y_Hl^S&kY|e%zoUWe?5~SzrOkMz2U_l@W#6azZ}BPUHs8Is!aQu zymh57()QzvMk#cE<H_^i{#uyvD_=hJ<>~9c;xV;fK6zj85Hhx(j61MmeD_c}J$2;D zFH3@3E@eAK(7F?89CF<~0c&AEdmkV)CP?^nS-#$g1~g>=i>Yv-fnfihJ8DHh4f3>| z(aPHcZvAF%oia%No|sdWKqov9*TFwKU;w4S5_EvcJL4_9$tqk{{j7jU!*4Sk+}F%` zd2V2wG^vYO(v|nr-eco-xMI+71+oEECB4=0z+V{4a$eXW#}x8gv0eaWN8;aA@6QBk z%+>QOxr^I3#_EH)fiM&#n~+9IM4AN35bY4p{jtN#8A@3P+)@xjMT0i2xNngfHCh%1 zQF}xZVg7aq_l>?aplAQJ0Z6j4kDZmR!hLt4Oz!<CW3_?GX7yAOzhzegHCSNp4=W;E zsZO@<<^KBy7>oB7eI5LgK47^sg<d*ReyvcJPPQ=GOa*+0hMwJzG?9S-0ESYW5-`vN zHCRL2P$R{CNeHhIx#1K=ny-yZ5~4QeL0r$(X)T8B?ZKx%E#LgecR~SpHpic%`zkb# zQo3Vk@|+z-oqnFku;EK14^mC+6!7;>*QCeWjoi73@MqD~)iJv-Qt&&*D2hqB0fic9 zK%fhaR#JxmhV7Gu2b)D;>Lhq>+%AANN?gwK$J29KN3YV*r^j(uu3bAXWi5v(01{Fc z2J8z+TvXyfIW4D=Ea7>qfuL>thKfxUv+bI`9lQmzD73ion-Q|;ppDi=8vy9S_R&)i zUWaS7tNL#4gN^SQIg#nC7)P~OX!;DYWQcWSx}i%z$+7TZ*ELiPe0(n&Dam=>q|K1n zq5nbw(UIwg0!ss<c|0STFHcp6h>vI2AbrNhvC--2JQU4BUWga~t%IK>*D{1|K+V(A z1yN5tOMNMDDr>wAe&bYqQ_hUg%7&BF5_b#}xhpS5fsrW?hS_<5L%NT}{6tWj(hty_ zCZ9cA+q!)H{iAoS2Z90#S(t8{PNbqmx)+btdxgjDo;i~+H58`{#c|bywXSK6Y~?+c zPDY+2^4p-y>HX>S%Qe$}I`eR8SqDb(>_}bn#P$?T#sj%2kzRN8G0P~uu^(CO^iLlA zZXy?EM*|ETIr!iiuwB-HzSdH(pf)L}DCgsQORBOdmOP0(-tbcg)sj~e773UBK|jk@ z;Xz1$%7jxB5Th4HWij@FHTby2OocNBCllPn5b9<j`mAMWsvTD<!{uh|1A9iweeKC? z6JnAO!+a5rJMJhnW3BA0u_FuFO&Mx&u1VjIxM35SCcNzS<}IAqRBV6(w6jDCS4Y-z zGKz&@HaL+3<};R0gbY-Q5GKxU7HJwFW6ne{8X&&0r<0<@E&84JnU>dV_WQ8tK^cSc z*0WEik;!)1A9yI!<A}sXSEE{Yhx%!t-_c-tW@1P1x{e&@C7b|vwD=QuVQ;=*WCA%| z5B(^W3_yHo03aR@x^n-dO8`{kCc2-lT+IwkAe-K|IxDwD#|oiR#OF?FTyAM?bZMc} z$xeSfuDAGMXa<O)N%Z%D9*0DFDhqBYEb(0D>G?G*N?{^(q}T8#B6!0hwPt25*kUjG zAuvKa)K%m?j@$Lwxg24FB1+?gj=ED2b%#=+kp>wlx^h~-S^ztmjR8abc<;Gp2dZ6t zDUqI}A$L%NAjv}^&R^k9Zv22@UfiB%IUr+zAvy}`lU>29dvCvLo%|8s`eNrZ$L8Q` za*IbV2<WERFJ4Y14yFk=tp?7sUfxWYd<6J<69u^P<J#jH-rOPdLpRl^WV(6mg#*?S z+ud|lPe$^ZU-Ndr4=`U-E5PL^hdbn|LTDBo--G=OPc3v-H9?&(k&N5hFVFz<RUvG& z^z^L-N~yvZjLPG@<`MZ7R|abx#b!nttl!uZ^*5k4{dAHc{Ae(9qAlo$Snpj2MiTp` zyuZ$Feq;cT99_VaF;ZhbT5>gT{%LCDi@Uuq*VitR@q4Lcn0@D+wJ0P@L!H9y3XMhG zc~od+kMJSZCwQS&b?>jR(=B`%4)lXx4KBtIk@0vWMi(__EI0k3a@2sH?2Pj1EFIzP z$SRYjZXi-SUo1cl#S1YX<ac~;6CxAU(YR;w(-#(daZ2yY$5rSg=L0lw5>UxQ9JGx$ zxM-OoeE+Q2-9@Ksc>q)%-@MIJUz-Z_Tc?UGmPH{ld;C&a^pKcWjaKfbor|SjS!b2V z3;Pjy4!-#Kyy!}HV3fU0hpMDAtJrMB)~5y*{b6QBekpFea&3uQ>4a4Rn|`0O0xC1l zCB5-NhAUN-;R~}qbb^W?88UnmI89GT)LyRS8ZVUI<ya7Gd-zy3C0*oW<y~QkXnKnG z#&y~4!nb&L`VPEkBcrNtB{dlto!~{#6O8<@%Dpf-ttGreR@N*I7I9+qn4<h69pyzv z1+--Z4<f(oTK`cjpVmTt_;aJBtWTE*P{#{F(!`$Cv6^llEO^10kV3Y!2nBo#Gi-i^ ze{+r3G|(%z=3Gv%coITWgfTv^?>m<}pibv+FiJI`Nnj}lm&e{EBmFME34~cvJ0t2l z)$5X90EN<zcc$H@uzo~T9M<dX{^lf9dg8g9Xv&*}xm-yX)ajkHINZvvOB6t#<UP!# zUW#j^p_WeA=dHD*1Ty9iy(J*O4WIki@F-6(#y2wUl|W>Tj7Ug8^K`K{t9Va-fGdG+ z>V4Uak`hr*U*n~isn6_MOap)wnGhx#6?NrRPCjbwadU<9iOh_TYx_1c%0(D(Yqt~T zEB*u(>WG;~lUCkG4M(;>b$ig%ag?W4KC^i<SOD|Tb2xQ_W}8+R;7bQaWN!6_jg76& zrFgWtG~Xx?%#36(?d@L+Txj5-s5S+kj}|UtFP{9SsA!I`)QX6HP#<l8lv8^DR08>1 zm!U#=o0oCd@}rQaA>)D`!^YQ#M35GYZs!ryjLON_Pk9gY(|0)~GxC|1u3<s99>b3k z!u3|T^h86F0h06ZX!)m8B3nhkjsjl<ARz2HV^h1C&ie>Ojf8&^VI)zIwG)~#3-GN@ zlV-P%e8C7Jsf&~426eUKBHpYepZE?%lIKlPgrZiwXkx-hlNTSyd`PoPOB~_ykITF- zqgit&7r-OzfJmwK)y0o_PRHo*&jfxm`l;pjzePUJv#BbJh~k$8({F<s2*~FL_lc$~ z2W`O5Ncy<mq<i|(dtZ5^CR_|Ty3UV0^|hZuUkv|0ID5~oCIW`-cG3%^(0di7Yd}h< zhF(OvfQlH3bfqI8Xh;aX1Ox;G484dN6cGhA^dc%%u!p9Ar~w;d;mv(N&wJK6U(XN7 z%F3){W=&>ad;h{mWOCr=D%ZYO@LOmJzkWz35Hh2c=)OY>_@F%J=A~Utn7c}+r064$ zwwLnCG2cgk-P92feeWl+medb5vl@Te-C4smPd`MQiI@`?6cx$5B2(%)zovFb*kNc( zTRHX?B`8(?*rmZjcqH*e7o>Pq;BLZg^w;5Ik@O6!%&F{tBPV_ZUF5YMt+Xx}d)l)7 z#bx&XZ|*pZs-cmlFOWt-tS`Xh2_?fiB4SOkqvC@44#;PbN{%+Uja{%CK7}5uX-8mF zhO|RZL}QPhi+4$i_1$IyWW>H}r*-?oR2cUvRD5o)p?-eMUn#n`=}$k_EWA3uh&{lz zH~SuR?%Y@;1(CTh<d9W+8lxp)lF6n4ky=4#bTrn|46T>an8I!m=f*Pmy;_;H%o<>R z{u+<}%Djj%k&8~-7CkSQ7v_nyJ%fy8C?7w%Ahh(tjgm_%3rKCIIc3sayZDv=<(DXr znKnEPZVAu2`|CMT0#ud?*aDXXk^ar;UGLEiewjiJnTZ_ubpm29_>)}Nj~kmqDMw(o z+~-dzSPg@17Fpo*WyaC?ZNuNSSH#ZGd1YKX9Ao(m5ScKUVh5*f0|Ta+IO@phB}Hq$ zdVndZ&q)KzmeQJ+{iI@VQ0Sf%v+{YRT^>-K0K4^Xv;AE1oP4SX5)i;61?546=8R9W zc`$<XoMUEp{Vb!u$Hf*_F7Bqzf%p($4g~b3Mdr~2L8mW#FHv;Y=Gzi#<R@N1yCL_A zSQr1i3(9NO&g7}oU&lZSy7PF;0ojm@w<nFJ*H<?q$!T~`Di-5mOZP7jbyuM~s!Si2 zFL)_K#}4hV5&ypKW<>%SX8`;U5#$SMUbeN^m_G9CDtvu3dq@iQ6$7XMNcCbcJ82dr zq~-<^-Jh(Rz0jP&uk6|uys2oNgR^Q;8)O|F^h7yTWqY*>tGWstycNE-wRgNsJ7}sc z<m<ktm4@fGHrBo>PcY3h1T{mysZ7<|pQ?5fV@nS~53A<$0R?Z4B&<$odFy{ypJ(}% z<WE^f@%MX!&Ym`IXmz7_-aKC7K8W@oqt|&=Wv`s`+n=Rj(;{i5#<t&0j{|#CzoDZj zJ^spWH^P5uzaOvAkNLdu>tJyC(Yk%7o1TUM(JLx}FZ|l!h1olu={L^&)^q3s1zvv> zJ9&g+4*AIOwN-y^>2}?xCCOnjk@BcOPBW<kj_Fqw{nFPXa=4_mNOg~Wb)vZb&bRfs z+Yw*>nf%!{wmC8GTv275d(JCqX>8(AG6-EZquSQ2U8s-_<&0P!g-)blbVRn07KvW& zc9Ftx_G9xqe+Kax4EJxNnwOKK<?T$W^yPCj?{6#SYK;;713$#>@i6*Co}pama{oGG z=`%@GDlEJ%e#|cH0rj;%OCvVtQqSu?1*?j#BD8l!Y+sd?FJZ<)e3zWPwqk|Q%Xn>m zwO){-Rtx34x3Cd4P_Bx5nW$WyIP@X!5QxD@b^mb$5QXz$vM2SqtIf)F8j|roi2`xA zYOmBL)E4=u9uEissuTR|RVq}L#ZH9%`aZgsPiACafM7!`+JdELsDAy<%Ov$1_k22z z01+C?VAOsGkv>a#GH?R8;UYmX-ifSJ@7R<{9J8x{%U`pqXViZ(R}KmLq}uFtzOZfH z`uzU;Ypvb;yNj>aITGJU_cPpeoR`h9eD_>%p_aN+L*_d@{S*3plXLs~Q0hH|evHwd z$hyXR{dgRoz~L{@jN?$O@!zK%sa7wS?=lR`;T)|2RrS41W4oH&f3(N7Zt|5_$p!!E zwKP=`pa{=DnIU2J&l?F4w$r`}Khaiypfi2M=&#NU`Vfl&qh)gh3&cUagO;m3{*Hz& zIWn4${ja3xy$tCmZdzF!3@`%;31_>2G*1^kG4c#)(0iBi`>#GHmG5ml@IzCn4<QP5 z2H@F2v2nm5hi{I(pyl8#PI=fvgAY~b^RH>!1uqCL>ZUpOTXh*1@$YwPhdeVZyJ%|k z>CUSQMxU!wZ%^cjpo|1CkEXd0yl^k1z;tWG|7q_%qg~@~lZOwbI5by5Fgjv`qNL4} z7Y`DiyroPVe_y$B(R62R*W_uhclp;k^&8&q1qPo8UuHsd)(@TR{P*|w?(Wx0S6og< zzxvXIi(wI*4bx_&Vw0KIhuXWd7!azc&NJA-=3Y!RYcB}&{{_j#VK4rFg5>{?W3|zo zUoU3;_2})UXIDx8<5+b`mG%)GRK@qx`NWF^dm=kpXRqzG@cu)&6ZTBNr$1YyIiT&u zZJuM*Dx@tOz(&YqdmX;}*@;&Ueevd%phmA?GUQynQemjMfGAYmXS{2Z)DJd7xl3+A zRMYSBbXDW`Vt^yn79TV~UL9-nG~Lf5$@lMkoZA!PoW5-q=GeoEnXCG!6$QMzPvbl1 zK>I$3zmlPT>c;tDvo7etSLq|yR#e{4=Sezkhbji7PV2_+K689%Jo*^a>EwNe2a@-S zny;F8QA{i)C6)Odp8kDs@ya%gV{SGPH*mrV_V4bc|JAFiG?%6buZdBRV&nT3(xv}( z(3D6}#!E|Aq|PE~46j4Z#_Y|kNtYQ)C<;KkXuq>|0xA1@QXb$bdKX~~yX^UThWTMi zgR{ACC4YTANy7R2n|#sGxW#<0z+=Vv$YVn6IHC5D(-t}MI(sczdYe}&Ff9fW@INAY z6Ns*(9iYna3LWz_l!?m3eh_74j^xAx-1!BH^j1j?dns;}Ui;=J5RCUBYYj&9jKapU z`1RSc>UF3%4S`y~i_4=x9w7wrO{zqU^zN~WD>eUVeCr&wFTBz9WBr=_o?;JorA)N? zgqHDtq^j0%{7OX6KebOCGag}|?)Xa>%@l%yrGUFO(bpKPML(Tp)&YhdqYh-5^QoIV zr2eJnTj=t2ub-l^`$JZ;b;2I}7bJ&@NxMH1Rp2i=WfRDlFNgmRNFKgvj{aE;To*gH z@qa<`%i%o7YS7vZC;RJ_{|k~!nOl8*Li``c>c-b+r2m&=_08I0smQkfg5+`I4*Dkl z0m)_BvB$+`I%ZF1X#SWFaC>~T>hym>@|aZ`?#zEd@<)y1ZxZJI2PD@lH3qTw;Ebt4 zrU?K=%rb$)-Tt(_#ISLkA{Kj^I$B&lwg1=q%5$F+&DPWQ@2u9`_TO1+Zn}}Qe)aC> zosXw4?e8{hew;tCvCh8n`*V+S-uYF~^4s6s0kNy!ztq;9{Vzy<aI4SgKaKCEN~6!S zK{x;Ykg<?6`N_#RVA{!kwja-3`VUB6l~iClQg{2n?w|H<IqkJ?Jdk|$ZBF>_e*iyc zl8Jcq4#fk>mnF9T1U-cEKytzf&foE$yn7Tb_01j*bZ;gPBq#V`UNb?5cp&-EwTmL- zWaJT^WA%7g8f>7NFUYq4M2K_R?zI~1xsk?yDdQQ&{I&Sqz0d)<8<Cl|4z-EIU`q+L z%`9hOM}ebd{VKdz_VwPYtKuV;8cCZu$x)}!>TnA}#b$17l;R)iIZK`Un|YqcIO3Xm zR>YT^`6db+X;lv!<DJa{-QKsdzY;7+Jdj*nbqV)k-rAA}lFQ$dh25LCwdH~2A_9A` z*D^;PlWr-f)GPfnwHtHQwk(wWSgYz8GG;m@P|}vWviCdD7XQ+zv@5xOpZ>3h-aD?B z=?;7M82ozdx6_^+>Tp^+Z`6S}rJdf(bF8*^9S#<ZshIEa(`jiQ3{U!+bE4y<CdT7Q zM1@e+O3(bkXQPg?jhC*R2=F)haL>ZCNTBrFcn}|kxa%0b=ynzO#4#+n_k<#;llsLy zXfJNeIjvQ&dh=tDg|gZssiCjcu!d&q7YIu``&geJubXXWm51nHhx7;1E%w86lfFL1 z<X!I;hu-05U(1Vqw5nPhuZfLa8T(jjgi-sx96TL{-l#D@vc5$m+FeAuwm6@bbve1? zS{A6&>h;&##^m^H9a#4oIj#yGgLb`@{=MyjdVt#*1N)BqN3S`Yd~a8{^Zfq$kxS7S zar^Gjxrd!kG89t8w4bcc_2px3n(jSij(I%aq0o7q&=5*I^m2a8^m=`oNca)W$H#7M zUb=BeGbG67ym8L^J8j-{jSx@uJMH^A52~)%k&hjI#oRS{-rVSN-4QDB=;cm)@TE5& zLt>;(RE+<)J2G1ya_VvULTf<#Xx@!zt!pRd0)8k#N^ZnQz`Z_X4|Qkttj7<Z&=#iZ z>C9Q#C5=Azq2_aYs(ViwjJ3b|-ud&PxX6bnnM*Gxp6Dwt4&J1UCgev=Og;4d^X4K% zf&(&|Z(R#U7)~g7zuymkxGzyIU2fd>W-ISG8wIh_r}|=1P^?$sMMTD_bJ<Qe{AE_; zZA|K2_|9k2q&FBrS+wa>Lc_}sie;)-(j5X)y>7@Chpm=~Zz0nrke6x?XBe@2`2*)6 zvK(eaR!Z{X`dC2!;GSD$!^Q!7<X(*1=_w_VqS5Y9=I)@#u>sZ2m@1b{Ug*B-cJ&wI zY!?PqI0de}Hspd!60Vb&o5;|6KAAu9z$@;U@Fxd`-O($q&t#Uka06seS5m@#*~+ts z1xwA)gs!FO48BTZkCXW*PptGZ36bmXfK9DjlKvE&@xEF-2S}h=lS4<ZB5u70Y!~I} zUIXpZLcr13+Glmd!K;%8!wLCMV{7_{b+Z*P!EFD&e4mW<=8r4wI%P_$kb@gfLHY4> z7IM|q>Do*!Odxde?Vt)=o0^*G$1AP>wuYK4Dj?0E7Wg^BuwFtGpAWZBhL@Nkk}x>u zZvVcoCtnkzALPeYmS=R>(yy8<WVux;z7*bV=_IvY-=eXkO{PA_C=+TJI*c0mn_aNV zFDgdy9Tu|Rg5d{mfC?g5OM`2qsxGS_gXpX0l}+An#kh>$8|$@@^C}qJqq3QqOxz>q zb8hHhwZf0~OMm6g<A2LC%y5RprB9E!8K$LXKTjk3WWP6C_wt$MoeS@mdWHO>H>Kd0 z8d(v^k+&^Bj66d+41dWe=vh{Nw;kf<vqh=aWB%<)49-ymu6kOj-@laOBQ=1Jc{r%P z|6sOj*F)htXRF7Pc7`)05b2#R_`z(gyreQ(yv?bMy6MTYkv%V^1|#%Wa-9MpMkWQ0 z#fI^Z#=6Ja>lUX+Aadw-{#%Fk$OXRZ-<9>lL+}(P081e4D6=noyL|PJV<c7hmi&dy z=>^$WU4z=IEdC&5pB&JIqfq!Cv*17QSPmKcoD?xZ#ytG#ms=N=eU8+{Mc<5+X=S2C z%VKWg`DB7q+woL|`Bd5FB-sS2TqadEIJJqD+B%#{*rqCOqxa2G<+@Te#Q7xW1Dk<h zo_29o0bha#jz-2n70`90=tg`nh;aV9j@O+J*eiiJo?~^xIeCK>%KUNG8yUeHx}MxV zORJ+_8wy#PI6E?&>}P#aV>4E<#@GFWenFt2R1jvEfcecr1pegT%($@j6A;5g6gW^@ zQYP;Ly337!N<zf))DpWCs1^ex!GzkAK^yuY7y%?o2EhREat8Dm6MBjX&+X#3W#P7% zxPOrtNG6gJiTNIhUFBe=0nE4e7=zM)rfFh1Eik0h<Q~9xlaSQTjH!@E6_Zfu&dA4J z$k9$@Is=jDjGXq$n@PxfUY0l0g?v4d_qYo=`aYL~%wJs1EnuRGDfy#a`5W{3pE7d` zCQxg(C^{bSAm9hPk}h_}*jXN4iNtd8xPCUjPcts>V8nDJ-^57n=zDlDCzt;hvWSK3 zVNoU`^})WF=aF%zkP*~9xbFm_A{_gcksc=QEeaQyK?qI2j5avfMMm~GH-$5oQMC;U z*$s*(&t2T*;(oFCf3a|Xf#Sy${y%vBr_SeEGx_b-_(LOcU)X%H6sRp1w4aov!v$R+ zf~4iarVJQ~1I=xQQ+aV&0Qb)snaL{6oWOi1B~z3W1g)_pLO`QXRCoI2xE7<!cp1_N zx)>;+bKtz4wnJnYhyu$Vg=QxrKaAv$h?k9umlqq9mzL+RH<x*_%W_)EtFvHP5^yhP zXog*d10HC|Dr*^qHilGaOh7b96;{r0uSkdm1CbWRS2gG7u<AJR)$bz#yT%E5O~CZX z=bdH26It-rDky&2h;v^n?+^=ziDkiD27LleXIEm^;B+Qx+Bs)vmlW}efR$Mbp;|<( zlZpmy0!ShOkQ%?e?M2-d23&beDxTlr7yq&+AV-QP|K#7Dz(JF6-^k2w6BtQ5%qu2y zhKzZ|gJdId!bv#6BwR0v*-OUlurPnw7vr0<ckujwhBLFBk*@MEQ#J@k$&zRBjw9rl zbEYi`5z6N4YR)d8AX6DIDuCNygzU{qC%w$E3dASgGw7l46*(j6qu}OIXaYIBI1+W4 zi>l?KFh5Z}TwWhGu$_XwPG}4`-WV9#sN+RbNZ|8M;tL;(3}0^~so*7vNga5;%kpTC z)~1w@h6`g&lq3{`+`yYH@krZN2D+Vq4A><=?O5<%$nzIGXkg#y{Yuv5@o^gfCWnDI z%Rux@P`*4blru<g+$r=Xww_uI*&t&U?IL<es2mO>jD*77L(bhp7BD2lLon+Tg*ybI z!m)ab*7TB?vzjeFQQJg2W!yhThX02PjzIjWVSYp?E*cTBjW7Dl!8Sg}Hd+ujf%;F* zxNRm6GsZ4(L%xXOHW}C-B-~aKZw5mA#=JVhME(RQ*G4iaBt*YFCXoVn<xT0?Ah8KR zR35AYK#!3i?&UBF8PkQJ6tQ^UM|c4qw>K-fxj)A`FnL@|U-M^B!vtE<uK=9NSHLb; zbmdD(YLG2UW&R9T+Eqqh97=TTimuQ<gRDtpUQSDh4@xXWx5%Sya&Gs>N2iqDHaMR+ zVcqoTc|sE-H5v`krobvDQuiW)OG2Za9v6r&n*=4qy^=@0wTmDlLqUvWo1M-e+oBM0 z<0@<7)y~#eoYr&xn7f2R?2DE}%C)m(WKJaCmUVS&c6EPJy2W~RXuZuP(YU@nDb@XF zU&coS+g#8hA;{-0&T}XtbJ&p8sA4zrlb?QN?~^yuDSZ-#S`t{=G<HQkbP12$<ns7; z>{~qU6${rtf$NpW{NtYe=gc1pAcxQMJ$FVz4?`4KATa_+A+kgj4b^Ui9-F}YX~h*$ zDr-qaKXylNfTJ$wDC;?ep__Tb6@cgZMWm3f<i0>X7(zz|2F=wZ7NdoJoe-SfClM{l z%dx<6<k2Ujs5j<1APSxMWm69K+H+QAD+|-#ntc9O4u4^Nwtk@EN6b=W%JH&lnHQ}Y zd>En8p0iwJ7^M@Zib^+%c+SRtI2J{Vq3<&Y_$J|FML%)>tKSME`w1c55x598tNBW} zu{ePp7>;#RHX4>ReEK2Tkw1BZ>stfqzShV?-LdyyVW*w>yMs>GRg_YguuukUE|M>d z33KK2$gxX|7`3O^@M0BM0h;0!g!yWVenrCGDW%g7;%y{#dyb*sETBUGm@^)cv0IM5 z7Rjfuy|)q})xcxJ8M3(yxCR57U7p*<NxjZaobm|g%Qb?F0z7B(Iv070iTc3Ac?S1t zDg;J<Y+o}V!cY;f<g177<p#5mVT|x#LRXJ`#28SMbs{QlPyLXg-=#QHjkWZmuYU4@ z7`PaJ5(f&yL!M4t+T~*5<ye=Vfkk6Oy*4aQWzHL3!1V^#DOhP##N9A#Hy@^-%SU(S zC$wdUl*3#p4{o#Ik+}+@K%FZWc6Q>fojlY951ZxS(r#mhnEXp2_u~@{DSx6!ZfE9P z(9Ill0T;TD40gu@bWY<<GP<7Kk<!Sn-0b+>jIQC4rVNRYT^<R`t_X967ZCU~kYkJu z(%WhFP9)#8<hYNco<<6fqm8g}SF-ESxErDT(_FMr7QA|g(d&)u-{|{doId)x>qy4T zYJC6onAmwH?k5xBH<uM~7x9zKSS4d+a?dPz&vkwE6H1R=Bb>S(_#YmcBcE*Z0ecKd z{LUPF$LbzqBl=m$etGPx9Jn0=YR`cHRWMTyn4iJ}Rv|8A<QNNc6@Ykgp-v3UA`2TO zksy{gsq;13_%XVTkaQyw<t5M4Zy~!Vd<6CL7dwN%lUHgLUY~MBH*wHlm+467f{b!R zIwM9UC#d~r2ar}&N5d{NaZC8T=gc>lU5)3~W&y#$$?<$e)#-7c@Uw0wXRCHv9`wv& zwx22(5Tkf4_A>&JD#yn6oPEjS`yKg2OTKiMh5H?e<1#Uv&^h$}r)$7d2L}UL8$*#{ z;<EhRcO+D}d|najK`G&dojjzr3!=jT3pg*zGJ6)87^ewv-~@Px_kk%`kTZ5}7~A-G z_-ou{LVq;lHM(8C;55(>5XpBhGRXL>?B%HFLuIc)69HMr;HOEbb32LOrNV#RCiS)8 zdbqHgWQOz~-}822i<)<H>*%d7TPIsk<FDR6wkzEF(RZquu48=5uu(wJ^4^vHeyO{d zzfA}bC+iun+Dv9x%?0yaSmoQr4mx`q>V=c<!f_u6ODjxFDgxK-40ocy_&?#+nV2F5 zR91e`o(VDK!esFvg}*33g)eYoJ&i(XQ1ff#d%W*<!Q3YLTV|PuGwL1#4I-l(*b1s| zCcEVE&SY4zJSKyJxYB|uH+#K9Gm7=X?vSs&Ig`91D(;`3yw0c=`AH9c__q3f<(Uh7 zohrTLk(`l?-t8yjoRSY8N!Udu?gux1SqykgV1A`^FA{vQ`K!R8r?G!IpFa;wjgNnB z!^}=#_^&2xvG^L#ynMmLOp{UC@(?37E0_y)A%ivLr+U#CY*P;@baKN{`@#?OWd_0l z4-bhf06Fue?M9&+okzbcOw}_|$<)^%0Cu&Pk3mM}+VS0gk#@!A(3E4w_X+GHY2v%8 zB44GqAM;zC&S1VaGQt>@<0q!RJs(>|tx1Om2>FuJ+{h1(8aKLOUpez<k`QJa&?E}~ zKQ5Lh{l91JyR_kYLX_*L!!3Im+jJY7mV*6CfAfxkVYB$yWX#J*EN_RV$y#(GA-kQC z_LNNl4k(<A(wz9EiAT+IF&90nSHiTMJ|;Di(aKG6UKB(L0P|-fQ9b*R;nMy<+GPsj zwDVLOK6tS6wlU14sfS0fq5g4K3}1_1+znM~36=jve?`tg8{}23zn`8UekTXK<>2df zr=zA>7!I&z;PIjRQrNsa_A7u4vAJ-b#h)~R+hJqATA3YJviUCOQm12={Ai$Yngh6C z-w>%wGcx>QKs7Py<5bDPyL?_sjxX2OzE0QDvqb67M;HseG>LHH@yg&{)CrSP?g&O& zjPhn2&^`0^e;unS|DclYtIoAnXNnYcLuXpt+RiTYg4HP{6*t@qwg1PldOjab;QLTk zkx?dY|6PsU0@xQO(WN~9<5>Ol_Ir}^m$$UH-(U<shpYMzlQv~dc}=TlRA_G^1mRR| zTzc`Y8Ld&(iK3gRq<UrF0g_3=2R1CT<tvBx>YiU&N{6oy<1=^9yc?=Iq5nDlJ?n2n zT@VhbMEQ|O3(Eg~fAH??o8_?EiNN6O^;36EV;a8?!Degx#YwV;vGa;my;1LT52X-^ zNw$4MG*o^i<<0$)F|W0l55b?|1UB%duT|B<PYar3F;rGt1Q-g?H9^Yt_$Eg%d$3Up zjbic}`z4+hcCoh$ExxN}sbwYNIq=b7@Xz8(&SZ~okfEqsPyT&cx|#}QSh%81cC$^( zT2Oz2w5Q-iW2%i@B4-n>TlpipNhZ8C6(buPaKHWVfk%~i85KS=>jH7Vd4C+~eIepX z{7bEk$E)=x_>GLd3|u-8>$8(?9QCl=K`v!|avvbw%m(ddoMgQif#S%NUTE=Cb~-aQ z^y2|tg8s?P0XNIUl~Qfiyb?gvZlSv!U9xXzIexZf6n%>oOv8IQ*{!R!d92*=JhjyK zRO+HmR9zJi?7lJgdgGhD+YF~2_0p5LT!#<tl$f!Z@q2mgZh5B`qAEJxz0*5J|MU_2 zh_RXeEO7>sT%Ph)%ce3mH^uRVG3M3XQ^rBj$f}5OtsqY9Vq%6=(w)g6rD9~Fxf0Hi zRFEyy+6$LWn18Y5U9h$_Ak;1&QkSa@CfAEJm<CETxw)?mlpH6fTI85=RhA09tS3cO z!6)E`!J_x1hOb&ZoG2s2@n^dQldt!y@7r>`-Lfki=66h~K-VYaR!8jfmNogUA+098 zpemkY_1>67Q}wxTNcJ0(Z)G23QXbl6cr(Ah<uiQn_lG`ry-((MW%N`FTs(}@`<}n} zeGZ#;i8wkW8P;j`sq*%$Xa%XEINM5aAGdk55YTa1DRw0uniF;ouT=w%CmypBb~$^z zJnqf8XNTLP<|l_S^)D2HLmI!XRH+1>%h{-nVUF&>h1sZ^8d8gfP0z0msW!=;hKBq+ zY4VMg;S)PG>oeTA7VDDI`}dP$Wn^EWvh-KMqt6~76^UzULW;dZm)NDIrN8(!oP4S7 z&8|6)j6R`5d*quO7P2dH70_OcfxYgN=+5Q+yHvSx*>m$Q1qa&9<OU9lBG2D42J#@% z>r4lI!@>+J?xNjW;@fxbT^6N0;QI>``uYYy1-yMF^i*wtiQ#_M_q>#usCU1)?%4Rs z{tH{&;RyR^K_N>3RI~-rYxK<nSZ87!Hm0(?T(X^%RDggQs}^sU?AaOthZZDBBUF)Q z_}WjDY(US7KW$@P@zD^f;4Ayb#Y9=OC?)RryIaoF#wlJj!7x_3DW}lFCcen?D>7d; zvpFMWMiW?_$8H(hHQAWEW}gRng|YWw!-Hu;K_k$l<M>qQw=aHYwV$g+q!k}EZoq)b z%*B#jvfcSz%hXzz_D2f<BE<_rt-Ezg2k)phsmKn<?~rIp-#}Q}vU7>?_;hw@qvkb{ zKFssx41<^L181JQ=`XDw0lq}hfdMwklL@)PGk3dHPghgI-l?ZFiAN#PQvcYgyZ1*P z2@&#TK5joVg9zKYh}ZHnDCR(XJIa`9RVN&3uk6~MV=oRuGuT!twy~}i`wwfiNemBd zIcN8}H(k;gDD?4e);gN(E2=yYeB@qjf5k0pX<d{hU?~CVQm8!(Il7J(*s-_%43l}e zolfj%C!PY9p!-M^L~|tkU~_;>(0Hr&+uHk0GreY@5txdh?^M_OAqt3KrR-jaB0y_! zP1i=VcJ9yL;L>#u`)BMLPmr>z8z%}4v{%!T?_!U{Tl;TP)cuc6KYVzjPWmk{AaWzJ zk+ZRMU^T(*jHQ$?U2Vu|fw@=j&m2!COWH%^+87b_UfpkdiVv5!JmOb_!U^i@OZN<D zE^?_A?6G@uuraehSCdNX_*+Y9#}&>A`^2d=>VKFRR(sCMOG=AZcQ{&e`u3RK-PwA$ zmdc_rnB<)7JEuI^^6A`;8}`>5ZK2O*0RK~FUI_W=gMUx5K!xTGUL7F5k}~rn&IsRu z<+E{3+yP~zLK?tN6{~9AlkxZQ<tUE33|8RTxl<~qbn?ZTyBAKxmBFzouNV2o#QD90 zrB7{z#_mJivlaz*1%Soe15!|tVdJAcLZ0w0=|__Yy+4#9sKW+SY0}y_bgNPIYZ|Fp zWpJ<Y4qSz>D0%})PaDe>cdc9$Y>~GV)@~cVqZ0o#<s>F-KRUm>%U{PeA??up1vm4z zqbVYNj-j1lx_i0iayZd3#-Xx3d1zf=dfpre1;7{J99jQ=w_SwSEx2Twkg}~X*f0{T z23W{`#(QeGoe{cQSzDICwvbB)azfzpgWW@i)kz?f+Y6<m<jsS(bSw7f*Yx9ODH(<d zf9U2E&uNF(V%gGfE+>UUFhk9V*|)zxee?ZLA0Rqx+~sVE|8o#{!LlPXT<`hWu;(tw z7$Tx*L*I1>@RvG1w)*f`Z#E!Y%O8kr@$wL$1b^vPulCDPbqEwX#+h7H#(Z;_h{`$~ z+_LYi7wu4>_p)TuCG%Vl3~{*~qncnLyY8Xer2i!PykXjfM_u3^KQ>(*zjStDYH~P4 z-73BVA{!s$%_q+}trqNm$<E;pC{Yw}@m0VkU?^(EXRl;gfN>FJ7PeuEXt&(I<#b<! zabqgt3=<;#k1!y%UZ@{W!#kO+%vCmzFNGv4XqP=5&ATLa_WZx$j4ufTBIbGT)c;U< z{cYR6H>SlGKB>xnA30rX$XPj)S$F8-kJl>4Q%iIa@<O+nocEj2=sU@^nEKnO{rjWB zU%c9lI)Dus)|c1H(_EtoCPiczEaW&2LNdJ#<&sU#wx=J7e)~osHrDN(8qN<&=5qvk zabRxF-!V(0Tc1)IyR&4X$O2O3oKJ22Y6S_E7sh1y>$MIF0MjQ`{zhvSvLJL1`7~`Z z&54!e$5*}!xx3E~ai)uYm;;Yp)zWFsSpL|3&&$+c)YP{7p@^WUo$Wo9V}`5K)$d<5 z(o`}=%HXq-y0e05Tj%q?`jeiXc(ksPp&zBYYeo^|(hL}M6^lm(CmsNib$6zruNSUK zj%OeA&+!U|>{HRZ!iKteWoP@Fze#N<XCVB$^v<rf8_$>Bc*(x6(!c+gQ54_JgWn2w zlSq&w$Xgpbq>aa<Gp-r`$};qvHF>5wMeY0Nn6)v^wHg}P#*@9_w!&)LwL%HtQw#*v zUiUN~MUNmuoQE9=Zba=F=$dD`QJ{KkaNy$yyq!qrE6ca3M){*~V@g^?Gr|W6oFmm3 z3g5DRDJ<3^Bw}V(P0@&FfWsIW6ZZX82YZ9E8;qn8DZy!y$UBl<;QhAn<b;eI^By;7 zrIZGLY}wUF4pf{1h&QW*XCmab6gK+0jMZrRBP;-*hu^Zk7YtjWW&<4FA{}hHN^~K^ zP$4(Yg-dkh@cU4p@~_el5WAuUjRz<OI?Em7(GO4Nng)B(ek=|eC=KnV8LOCGE9|U+ ze)-s>*+mU>M!xK725k*HbPHt=G5{n|hyqZj>m%5PA9k(*B>J3cnlh5o--^=tIDAP5 zUGG%~u*>HUikS3eS3vDcRdeH-GeUSl^ojJiZLpWS<O%l?dQV~cj8%AU{Z(hgBVJ6n z@7{GV;r;Yj^$Em|0$dTVi<hUWcR^AT5SN=#NyqKgK3;xCdnB|<K@w>OnQ2qa))lU8 zo+@nq$8^W};ht~k26E2fOju<v0~zDcxSS*Dn{kGcc6daoszpO8q_E?){Zz6+jxd_a zOXpJ3$uoy-6}69lQ>qC?gw0dswn2(JAfCW635nPuTkH;RNNwOVc~s?)oiNfCw7Ukk zn7-R(Z*tU`?wKHCL4YVwXph@+T)c?4)oF(TqxdwsBjeyFjmzT>h}Z<QEti+)g<j;s zAO0SjG(Ma@FtoL0f0KdWZJYqS<!#|7c<RXAuTD`38G7U)aC55MJoW6nQ3kL0a9=3g z3zaeg6}M#x5#iyH2ycswSlf)YF_{LQfmNLDNrY+;s1@WcWL{1qX;_;ga;h2Si07OA zWhZvpwyXQ@Vc?e2gwe|F7GTh+nve0};FS4tyN&!~RfVbeeyeE*vp5w*!Zz%+^qp55 zN6rxu$l1xsTbJSi#8)CHLYit7btPuCZ1<re{tlr}84s@hGt~v;cu>-`M`%tHP#<F3 z5hmT>WQof6eTxfpr!u%t*+@h0$fWlng2d3}ul5Iy9Esyvk(Whh(x#N|SOlaYyxFdB z_LF8op|}J`672EEGUaeC{Zg5s<2*g2tf@#?vy)6e?CfG=3-k0ccN5932<M$03^dr_ zLyJd`qKrQ|BN8ZZ9=4gdO%1WtU*UTicj?HJbrNo1rk0qucBu$-S|%c;JBE@G&H)Q= zr}Ey*nvoH)T9Bjm+|6p1jz?J5P$P^}RoUq(2c?J9VD5m^LFNsB3H4-8o=lm$x?S1m z1v6(;%?V?`_B0LFvrb0rp2gdqCDBeaBckzBA+zWsB6olDxBi(S`Hn(7xSihLy2Gz4 zgQPNy2%gS=L5d^k@!W!&T6S4SdW_5vlYohkGhl5DNr}vec2~o-(w$UjB4sppJDDoY zY@r1vz?#LiWNmazdZZo?)69+HrLeo8{(#eVCAQ$nJ>@Dd#vtbMm7I6&a2=9uTfIf; z5wj<W8QNYGxYd3+A~b1p;(E!%$JK%~WEZwf*LquMsP*>oOuB(rD$#5FIOl;h?Ddth zYaUFxur9Pbbr4V~85`6ZY!*o1j5{@_A3$2(YjEl~YH@!y&##hCb~??*_So!`nb1#4 zc&h{6@?g<s&@LQFk(00b2Yxd*fQ<o6#Di0@38~)+_XhoPoV-8>N9dWFZ<!2&YcR~C zO9q!(;vk;(@#L$G=6NqlS~wYURJ>_P!u9!?llNz_uOi<xY`t`PrS$WS%={hY8Y&`8 zWiG}FBus3)uY}ut^WtNI@jE8iHkER41m;7|h*fd$%}!InQymx*?noswZSvI-84uR9 zHX)5w)~K2Qb8EhhZOr)?nc-Q?=0)A3Z@n2ZRK8<!M0Mr(pN54_1G;hZo1B?<!b$~d zi*OAj2i^>dS)rd}_f#JB1sbNLl`?)>;6xHq6^NiP+syKgCe$9fdzANKfG&8NFDS|H zYT5DK7rz+pC}7V#{a9Dk!5daxzw<+hP+I_@!-6L;oNnKFxUX-aV|L-kNq5X^zQ|^T zzB7D=yVTLX5R{~`JCo6AnF^2r#d)e>b5?}7xdD86-PSvWOIP4tSCG$AGf=(iLO0Q+ z>M-bY_s~wF*^R+;;S{KMLY00tooIwUSh})%-)ynQ#+F0(;x1gPeD*e^LE^$YdF;v8 zPtc;5jC3fXc27<<w+H$r<;N0ud3icuoeD>CKo{Pg`nS9uoDs`TKN$=Xccv&a!J*r5 zTVs`ao@1Lr*GGaKk#zS+o0z9rS6xh4ws>>$(iJX|(rG$q%ad)xM+dyZf)Ts1<o5>H zfbgnQA8c!~|II&$tN|ivUi0(e@1=vz9$P18@NOygV9AOAoH|v6|9jea(kxV*x<UsL zMm$N&eon1+o{@A1B=zPMdY~F??C9zM8gMBa*S3YVA6_?CdgmrMVr&?gy>G1{d!}t) zKyc})o2BbFtPJxP)*sySU`*!-8154#18@>Zk#OHMYyJ9=3b>A{5c$EnEj{b=n)#TI zJBjYzMc=;)F14qpRfiq)Cw}QUXnYH7I!`YvZy7M<EJ&X`O@x{UBP165S)~@%Vashj zW-2=<Nr&8=&eex42zzl@wi46k`TLHiEg?t_OoalFKpF`l2`Wc-W8S~GU!P8)fkc>8 z)yRQ!tV1?qGWEo8F9uX)1nQs!dt0|r;q@6{LmLLEo!hTXo%z<Q!;H#NXPwhMbl&$8 z5YPT?n3+!H>OHy{|AqCuJ#IZ+(!i`JPd$z?7)n@-#F9nl4=mV+OLb$93$Ca-1LES; zgPb#G%+ZG6bq4~~v^mXfWME)xWgTnONHEev0t3&vG3oV{J826R2otPnexvXF1>5m; z)JdZ=->vPoS~FgxoDn^>S8XzbfCMnXVVLdIF8I@1@RLe|W^t>5rxK_OLt*4JP2Z$Q zzH>0*D%E>F?fg(5{!!NIVEGB|BfOJx0w?`xv60+`n%&Kk%~_ad-rHcs17=(H&w=@L zwfpaNFB-*1BJTBnf&~Mwu@LfvIDR&IBhqlM92M)#wMs=;oY?z*=mUVH+HXUR6$|<2 zqOWk%JV>zgl(fSI?lLWT5xgl62X@i9D8c-zxvb=n5dM;nTF$bTeI$+e$HVjL6m1oE zR)q#b2Km^4mPvb^evX}E6%o7E&i$YZWh0*4-eYJ_cjTn)&xAN`b2Y?%RM;+k66GU2 zddORUjsJtDs2C^8XSm;dHr1wm^h>D7m*A_0%CpJO*RRE$xM=hsc)@}U5@wyjkWvZF z2>VX~7@JvjK8k`kRhVbk%cO<lZ&PgQW^3eki3IR5c~$(Q9~5l8hb_Jg1+*Xmf7`yT zV*kLX!t{qwAHc$HVm><K%R+2SOu?6K{0y7#lm1m-%YCqe7Zd&Wa&>;1Jefr7^P-?t z0H0kjxjCcu<n-Z3*u`J)QzL1rtAGjtY$L8*9<Q{P2J=ct?Z2Pq(!8hsVS)>xTOSFO zZ_?xbM85mSt~~B>dP2~l=%={ni^4adKS~p&FGr|;e|cbj3H7g}+9|MN>V|OvOqd%L z^_*hZe9Yp+j@hI9xYc9fEUK7uszL%dlrXWYQQwcH?6(Cw;$fa_bUQBU(3Q^{qP~Y- zLR-qxyn^>R{WE&7oqjlyzV9CFU_|2X<#)e&9{sMk%=aMTT-+m63K>>)E+FaVxvj{I z$PswW-A^?^p!>r6d(!@_+dczU;k2te3Ym~ZJc8|XRahK)xJzdG=eI}Mc%wnEy)9i7 zwpxBwD54c{TPP-F1hVf%3h?o74+0qnhQW~pF7rMWEv6m5%2lwWBLyTK#5es0vJe<Q ze&9=vZo-mbkw(bYvU#4A%YQ*~ht$=vg=?NRG&mfi!$N+=`T((n{|l1ij-nlcK1&;_ zS@<-I3)=V)W9;un#}Pw|%@um~mm6ATyU%rm&fPlmnEUa?&05Plig7K@61E`2d!Ii3 zjPPufLbdug-FVZvYr_V2-0n=5F}kD1CkV}T;aX;Xc$&wb`{L_z{?fM+G!s{8_1H$M z$>WpZ8Yy;pxt-)v!v+f<qs;dI{B**g=4OV_fv4Iv<d}`*Bki?|usvr!<hmUQ4za9s zf*tn!^7*gPkQ>Ogq&Mao`3Cg{m?4P!XOdjhrkihZ`H8r3%#N3fVU-6VuH;FRfMr#x zwSZ?^RDhtQ!r+{MRgDSJ7x+9td#a=HI{gYfE?_#}sMm$4m}TYrJpV!zzZMkg5nG5d z{!-ch)bL|*nTK#;eG&TjsW;nu7&Z?CNfH&~gA6q@H3@kNGOyq9!aDo*kd9(+paA6! z##Wwu?Ckd!cDtOJ7<<{KJMneY!;;EEhM&7GVT439oB@dOX_}*NNz1*aB8TfSSiR=~ zMd@fWQlT}G>oBbB(&8>?DRE(@cH&s>@uU#o8i_hAb-Al(%sknbHyRw#vU*{;gjB-m z&{vn9q?V`LU9rDdwIf%iJPHwXPI+%1dJ54igeBOyvw7!zcQ)1ZWt;zeIotk(wA)Ii z|5KwKwm=%xf&}98SYsVr>e!1CumjpCNB4K*c6jVeYq0=Z<4$;yY{RGZ^W`n&0*!)3 zoYhMi`*y^G6-%MkkC!PTaia~@wtpqxUpQU+!@uIUy(q<Zlii;NzpKmAAgrXRR1T>k zt_cL}zAqDUlyqxmQgddO#n`pKJtQeAu%m(`Y38lP>M<+a2Y-!pa$$gljpTzb$ylex zr$o22d!~A=k8D&>I`;QyUq+ohGj&6u#on*q>9E5*ac58hs8Z^t;S5!-rTh#<nmxZ| zu;s3uCL%}z(VrY&Y5O5W6HfCmGhO_f;2M<z<LOn4T{7eOdKJ;r49F`&;L=P?j?};F zpZ4~jz@7_hgJ`Z!1y>kvt<P~%Ji0%qprGZ%%W2*~Mrp8r^yk5DB`>4(5h0SKGqeUQ z{E$8EXsGr@8ki3En!3IDMriLZ&!#T@FB-L?#Y*Sietn_TN=-b-RsSB4$4Z;68r$jL zZNBPr=y2<;+e5QYt!rAW98y$Tu3Wj53NrxR1dGhW^pj4rQTwe39|#EJWG!NEo-cm8 ziyYt@Z=xtb6%jU8uv0o$dQWK$A50z*Pnbm2*5HqbprpcD--}z7pf4V;EeX~Bv6sG( zuT-}-u+if(plfwK9q-CZ8iI0F+<~)u{LS=OAVuZcNP<wJjZxnMA5j{V<i~^?71tdY zR)vZ>12hFNN7j{9nB(~Rh39dtoFgR*g3RM1_vibGMh}&b9H~8SV!fai>8%>x^7T00 z!i{u2@A_VFRKH%)UCTveAwwW_JXo|#0qV}gZmDD_cL(=IuGZn48I&4v0o-oPyvpg? z?L8CU6d$@bMhA8Ou}nPcYi>_Uy$o4?H>0-oP?uzJ;rF%KHus-~k5(hj=ogo`3|MBl zOkhnz4mMf{_F*Ho{Zo;_Wazj&Zavj4#h@4=J;2t~BGrgBneFYq(Ub*HeDUGp&ycT< zS&Z^bid`G#z}W>fYsQ7?4VnJb3@?z0PA@VIP!!nHF{)r#R3}D98P2!o=^`yDo!$GW z(iKI0ZFMrU1T&Z<sR^kB65oondE;JT^qlNW^P{X_HeO(^2Zx)$eEX&RQcdF4W+-u$ zht<8JP{!hmLal@vaV1a=N$-0N(K6(^y`iC9S^kB8_K)A1Z{tU1cAMpws17gpjh6l% zjZ@j3TD3m1_0YJu&tbBy(NSnIKZ;DlW1+GTH8MP$StoO6V||I>pC8Zh7xXAomTpe1 zEsj#gezo^p>OvnwU!V#m_MQfk%}}2F(H&<uCH2&`^P@%}n4^ZT4;zk_yx8iz`>^V| z!IT2yN!NJXpWCxhQsv&Y^$^)<67A3WeM2_-oBU>^jc)<W7;4GnpD(KpGZ`+9b+D23 z$M*~5127_IPu}dbxUibm&7&+E#zGZm|H|o1FTxr0`n?15t1l;u48<^8W!I0joG30F zsgwOqL8R@`z#$*k^>Mvq172#G7^lw06?&h2`}C#AqzF}Pck+8a^_mgBKtvrp5=w$P zFfeC2>STa?4Y$_!Ia=c}{FB7IJY9H(J!e5sr)Lv-EQ-&f*vzP<*=lbtkaL77I%?t& zm?5?gpK7Nl`m`f#Z=rTk)Bshmhmfw_SQF^;T2ZVg;j89+cwTIRzf}CgV>Vwu-0Z2g zylX9CW6<M*3of=hn(UKv^=Rmur12WC04W?=CXb6^F135?KOX(9j_;c+Z+kakWBgX@ zk;^?l6YDNZ30Z|<5AP&u1Kvp@={@>kW-q3jaO#>xZhwL6_0TXR>a1q@WG8z`D1$hl zTnx%OY`ZAHNPu=6*vtxf2No>thsd_pkCs^SYfE3+<<Go|dQwNS*4tSf)cmuMu2%j{ z_g&gX?O!ISON7#`Syt^IlNZuh29e&Lf6lvXz_lC{)h+jysQLU2cyG3Nb;ID+!!Pf< z+=^=#iWvTYo^KYljCDugkZib{nn3HQg+v4Ij=2AUNUTnmtWf8{@w+a0XDCZjZ?}i^ zdR$_nlKYRP%j)Y2ote{cI;gs8i!i<4i@3n`!vq?};%;yF0&drbPG?daK7In3k1R>a zIlai5;cbU<efe$V&0ZW5_jb*Suz{_C_i!hc0aj9!?C$-CN@A3_Gp%@W9Pp6qSj=#$ zQUE8OQqb8v?R&9Ub6Ff=ur4a0Vuq4EfByN~-9XpR^QHka_uuzKTiqy4vh~Mr%D4E= zgqFX0<0Y>vIJ{qxyIPJ0Ni7E3IKrOo@6CPu?jZwmcUeCD<jAwLrJ?7|q+RgF(te`* z+-)u5-tF(25YQ+p^Hg`%lBGKz+et}R$!yt&2lCbL=IuU?nBIM5j1d2JHRzG+1sd+8 zN}U+*uMOXx3O}pc!armazCj`{qmn)I5>IslxrWIWoeorK=~O7c^dV-yeg|#6W%SsF zVCZ$w1LLb8(IX_@MR9_PI(iJTb-0w}WKrxsS|vR~FYmUy^e?e6Hnno5-Rf~Y&D6o- zfOx<EGHT|5+ys5@a~njDHw2MC433-=BJcJ?Jva})m7e&Nhu^wl!0FE)O@)q_edF{S z71M;&Mv<qf;?C5)9U!G#Frt(>M09Lu1~<Jn-)XL~!#h9fl50igDh%KZq-|uf-^Sh% z>F7BjoFrA-d$sGAucvdtm2c)cZK+z)^SI;1W4a}zU~%O#5>$!epg=)+LG+TZJe(LY ztcMUg@*aOXp{nR59A83aT&7pfy=bU1YLjU>f)*a>lj4AsEN2m83z9H4gKQ?bQ;YJu z#D|3%Et>&V&=c1or7v(P&F`K)A%7IEwo#}(PJ$b-A*Qx{imPDbWDDQbav4Wo;~5L3 zKc_&(B*6+2(H7C&F-t67q_6GLOm)PKXJ{tJ--g4ac3TE+XJYpNaww#nG}q!n&s;+q z)to6gj1v6b^6Y!%;2V^%R~xw1j;cbE){>O{SS5El6T8-fw%1uwihdGUEKFqer&)QK zW~b?MpIayRtV;Mfba6b2U+HuDb-z(X-R*22c*vFR>A?&b%|HkVBr{<Wm_$JZTM!xj zvZas1+xuxp`ir!VNwoE@X!PmCLek6>_G-fdk}Zt67Lqz-(QJ@u2SguV+du(p2oLP- zNLAH&x|H_JC#{bkMsa;(uJO80eV~v0km@VhD4q38B^K<j-KbRpmufz4V-8*LT^d0- z$g<2$#826Al<cE-;d|El_3F!Yi}&fM&~#ZeQ{#E#{C)#|u`blfv5?}>Gz+3FO=cV$ zYN;sq`D)nFD*ZALREce<2tb`dLiP<ExdZmu`;?MX;Tn`!$Dp&za6VzGws)Dqgc4D~ z$uRegIJt)V3v3!mGfJ*0YReJd26w6+JrK$-)84248k}-VqS?4lQM^xaL-~UFE5(GR z!4R<j&<pP^FabQZ%w(XnB$Qa@Z;rgTx0`Z4?oV8EmSqNM2{wez*yi<=bgj~Kjm@Q3 zQq{_=6xw<vyUYU92TVHOKRdZ(Cz~;|8R$|EIdjZ{_i)z)x=@n393h!b45uMT6o<Vv z2<QG!Pj;b=#Zm^v76z*p`gn6e+n`u`Wr(+GTrH)vv{xq?Voaem7zlr9?<WrQlVp1Z zM|#C6$ICvWn%TWlk$uV6sln}stJG%Ib*@Myn~BDPgmqFe^CThub*4vZjij1{_&P?% z3?G{+oD8ae=xi2i{>=TV&`G&qvt}FFq5?_FSqGZZ3}nxfg})?!VLkea9az%2FL)K= zJVG<wrp2iCD>6Zn8dRH()o_=(y#g{ff}2k;`-vQgPB2JwhIdk!y*Z>3&`@H$VU7Tp zQTdbus}^F5ml|d=-K&?BReHgkv=Y~**lc!*HtB3|h?E1(w5wl*2Tov4=gpK|-r9vE zU0*3kv9R@B&D(G@3pbYvK&Q-xj4hjq>hxm7TQ9oysZA*NU!ZCvgRf|9XfnWijm-zO zK|(A*$SYN(3uMvLv{T%xFah=nT_2&(=88_1&h{&k`cqTnZYz2oohmg<2JI!5875db zJQXDl1eiF^s4{~e_tCBm1x%KoYEt}EEns6%X>o*`D#)SPc7znXTo%5M(yOlnbl4Ci z08Ie&$h2JYwT4`p(M<n-XMrxi7KkRm*K@t}WxAsd`(AXaLMF|4zPa0QvP@0>5b`Qy zELDa}Bla{r%(qn)KMExG$uGkY)V7WuXCXFQh+rmTOFJdFPd)teTly|ld7Q2s+jp$Z zT$Q-$i+z7ZRYY{aOpMw4jEl61FK`D<Unmbp`?!s5HCwJuNH&kXt=1SwMtDnDn}l14 za;b-6X%3z6h{-zB;}F&5UdbM+Zd)U(Q)+3ird(&iX>dC0dB3i-nI^{~lHH&b`X!>Z zKft%2FM$FO_CjNUXllO^8BLu<=mguwj?LWlpumOAWPpAn073|8D-9Jx4rq!x&>|Su zwZ4DSb1#)1NrgaDrAJ&NW%g(BkBVEG2TaL)Lv1vu90i2k09&w62j~`zq{)SScL}g8 zgIQI>{ENUTC&8j*v#%R&$^$i)wRDwnRa9u`BOv0Z<ZkuqK%e61aN7F*XqWWxqfhi~ zQ?*DTc3G!BJSo**_Q$${C6{|Om;C|4)EC#r*?r=y9hhM(?GU$D(Tn$!ru~ww6>^g? z>aj2;TOjy9K#WO$K7&D9S$E5?8?mxcoV57w5df5B*wvc;0HTxu5*xVgpvA`h0R%Xy zck;`#ThbzZVG=rIvwV>0fW`Om_98Awf#|(q|2PQ-9OyE~%9$fO`&8WJmi^KSG7*|2 za~Vpn5I>0TOVv+@$^_`<g*)15=*80-mmZgDp)1x&<F+Oa2R?aeJ`>b5a<GtPf)2QU z2`t@gtls1dhM#iB9GEvdV9A}F4Ul|ynMB@o-j@J?k${mo1-t=foU~_`(e#Q_A^(S? z^NebudHe9D5E4ofdP^Vyr1##$gkF^<prF#5D4~cnHKB!0s8SV>4k92TB4{WAB5Dv+ zM8$-nh^PTUQF-Le|2=0v?%5Bsb9QF#{oU79>kb+qLoz`4l&kJgFULC&`7f5@`{eRL zpw@RA)d$jCwS}E!L${WU(=87(I>e0VP#H+8GS%kdB>bEO;6&NJLx~@%ng|+IH?u$< z89g)vR(E=)?iFM|U!>9qzJvvf(m_pp(ciKPmBuX+g9^SD+>UBa7ygCQyP+BLGHdVU znAp2feJQWgPXhsZyFPnV?Cz*zxolgN?u^RJ#X5*tWSXcIM4hG?T6Jdn@_RyQ_~9B5 z6ixuk*MsBe8ctP`pllTw-6%3zUY^1o2D}oXL-%e?WU8ChSvpME7&|dJqa#&!09YL( zfJi@4B#O>@TK>5SNXa2n(wG4of|&v#8b31~a4JXa9K@h<m{i9zVE3=JaGxC2RU*<7 z+**@b$c}UE245TkNr_V|w1T$uJk+M%t7oMu?sY#la1G6Qrn(*yYB6(acKvf_T7}Z_ z?FY@&Efve4*uy}ebjpZoWLih@mNf&P6#88NHThS~LUU(SKkj|xFNNcUo`;&#%)H0W za1+iXf0dYm7|a`{<Vke?8G9K{CcJ*!n||(f6NEarWMO-)G{{ma62yZZ$vqV#+6U4Y znl@@ov)EP-DP1#Vr(v^t*;|%I;@^t1Mo)$K;+Z3kv9=nJ$Fgu;P2mHuD3j>7?S!*F z<JP@+hyWHDqT?EERptds#uQh&E!5B!5=t*M^e?=wyYOryO)4n#Vu@}{lLO_Ui}I48 z4X(ocXj=OkMZeR~Brk$%`1Xs2J7=<xhlDxXo*#aci|O0OLG@F&|6Kq>>A<+ATwHBQ zd-jugh~@whzklXcFuk{eF0l?Fc~t4@aGB`o8A9oYgh1?hI%=LEifJ-imB#PhyzG)z zRZLepV|lp7GFR1J`wpcr_E=bvLlUQ1$Jb(Iv)`x2;`w~)p>84?t)Fc6p{&DM)y(3m zVu<@Ejrl|4R^fjBpAy*t!k6fl(iIDOCVSOsklE2OmAVnRp#$)2f3y4j-_GWD&Y}l& zRzXL0MtfdOUeS#vkLfnVrh@rG!FndppwxxYBwF9t-)_)FL>vgp(RY)bGvuz#*sj_$ zO-Yt=6@O4E1Q3~i$k0MV$r9)syZah_Hhuohzprnc+4AHn%=Mi#EgAJvu=o1=rbbY5 zKM^yWikNkw$#JQuNr~hEGMlLiY&-aer_aI?f$k9*<ygeVW8IL8vg#HmDtqehTDPx5 zD$TINQm$t=#tbgTDtF#L5gUcQdV3f(Y1IQV-@JI`b;|IS|GZxa8VnJ+`2bTS{Y+@8 zk#9#;n7Dyo!+0p+(UXPD;Qew;t&!1dtX~X&;~!Dq1CZE|C5fv#{5tx?U|Pgn$Jt~G zW<51*`M+YEhm`PWBJ^*olC~&A=Te)+>_skYI9Pt~@D4F3s)bJy29y+azr4u2_~jnU zKScNIIr`n}-dof6I5l@C?yQeQKsa@9I&F5kx%=gAn%bOR9z-rR_|iI(Z@HGRZ>0dG zpZ=u}1?U0!gGbEmbj!yKtSD%|07wuPoB$B4rYHEX8O3d&6+8yCSSHl<smIlmYm+ER zE*|ng@0#my{3f_tNCHQ{7c1}D>~XI+*zu~S|3s<r?L(FsviB~ngxVH}ai1P%r%j%d zcfMg;)c&q)BL9{_!ufj1jF|cPMz5Y;dF%Fr;3mL(x>eA6qg3%2XrRHlTK}_>yL|K` z38Gs`hnvUE-k0|czjzjR25`}TC==S;Qv?(}hrBgM0fU#pSnlUlQVCxsM$$JcwoXqm zH|&#+M`6aEDe0!AwM4yD(MxRpEXR-Z|C~{4sA%?HqUM1aW8*|_Ij@XKoOR*Hf}!ff z*iUNKvMJn}?o<#+5H8NZ7d(jie$@Q?Ci2?QIcYOo0;7&d;S&J+rE%Y?wJ4rG*Sqrb z+o>CX&t(9ALvmn1j@Nf1I<)43m5%)o_p!7Ye9;3I?0VQLEiL`fD#Q9()QjjaEL>;~ z+H`E%C|%UkF6F$K7MQ(OWUx(M74bZJAQ601^th}l*;Q6zHAC-w^rO!91ShwSJ{ljL zrUT|>Y8`6p)KOjQ)@i|B@+h*BiP8x~98rCg9;tKo0d3OYne+}!KGE((V3GUkY-o+C z-0i}ir_w$JPL&gFpUMl^j}J+n1@FPyv=1UnXJV!kTR3g_t->HcIBR9>BF1@I>TGup z6uc`Kh5`vWh4~MrEqEXvrsoOSUJtjEwV;D*29|Tq><fI-p_=f&dim7K1Syj^MGMS^ z>eN_W2d0Qe7b?}1A;qrVk2@ZRpIQ{X3e>^r0t(XuYm>_V{rOSq38n`lMPNluLdOT3 z1>e#aa8A=nzt2S*o8PL6lnmrMaJ9J>=Nr)XQpNC#I?D6Gy!();y`-&7Li1w?zuUq+ z@f!XAR=>Qw>?LV?E&LUOTZYx}1}0yH87p3`wD#ndjqaxqDGppD0*EVqmKzfrc2v1G zPA9ECtx3WT0J)a|HrGEdCaN`ioik9xCS={Se2vzMVCI;XQbHszzR;#(;&S?R4C9~8 z!elP58l|2v-ehuP8&01$C41NvTNmqS)Efe0cXv$zFYtOmmeV4Ax!BRocum-?-Qn)^ z48$+E%uYTLkMwf0H;jHHl&sUO>>Bmo^t;}Do9hmH;z8?LPtp&2>nh)l#J(35JyvV_ zrLz<59FX>Dg?V^xIIN`Xz<=dQQbG1d@p{V*Q&!Qb@Bf<OXNp3vUWYKw1BgsEx0L#S z(o}5164l?MMTV|KfjiNgYZI8Rwu@D#gKJ{wE7;dz<Dy+IkUTODmc)RFeH<w$%%4g| z%a&iBAsX@*0Z~aS)yn`?(B2Ouc-!x_ht^fGhfT|(r^GEa_Gk?!nNy_Qh)0J=vsAH! zCLw$$^K`Rdt|ecy))Bqsmq5HoY^NNinlOgjA?g833PJg!&x1t$^Z#i-PaTt@MtH~O zYPtkS?Yc;RtNJw5kLX120<QH*(fLVMj>&HwmjzUn1Y=VyrRQA$V49l(Qu2duqq&Xu z`wgNZ(~7i62a;fi<A4B1(G*OdFkBWO$Iv&;rxVW@uWl8bp^bBikGvECwvboWEv1i- z$;B=;%beeARFpSL#iWn&!<4_NlW@iIi$Jz#x1)MX$JLK^0qNp*>iN0`#s}>t$~>}C zg`(gV3K6Uvmv?Jr=MZ#NkGr?dFBc`Bh~U;|cEi*gdP-=l@)+<1UVECtF$cG-a}Qbz zlBQNfZ}r$5-k=~!^G^BC(<TiVOdYFUHOx17A@;rTGnt%K>}K7Bkco?Vu^j>A$(Y1n zH$+Cwukbm#1M&i7;O}9I)FPT{FqBZn0pH25aT?9{S=RyIky0FCRC9^O9n6@-(u<V> z4z^2W;!{?n_TYp}K|0ZxDOYk?C_~9jkk^t)tWdK+===wx`l^9>YfWoDC`IQgT2aKp zj5l0U?clO8KW>Tyl^Tz+V1|2RQgEMa(+<04ugXo{FZ0gD2C*%KksCtAMyC&_+h||4 zGq`BbbMni(yZQP9PS|fWTRj6jC;n+Ef59nxCO&pyP{YRL>r^^aUW*K+K>-zZhFO-y z?HPuxOf(sQLTPT?^7O-?FiNdOsZA!M^nao=vu02hfMa>`&5uc&Y$Kzg<kXH!r_Rsd zN0QbpEOApbjs2edsQsvrQ|n`jY%&$70E;MtIzF(;T=bp>5ueBJ3etlQ?g73Q)H<@Y zV)q|8ENJ2Wkv|IfI*)OfszwNx^K?*(cE$<9lUpr!*w<s`q}*1CVZJHI&FwfvatI%P zEzS0@{M6Cnia>L>&d%Ud+*KA%md<NvZu6vB-m|UQ!`^94FTtk%ovkaFxh-n|`sOx7 ziNN(IdB*aue!)3!OU#1{i&0;wfYK3`<%IoA%ySAlzSYw62TkLcScPiH!Wf2kqr12y zRVHdZZO9Qv5i=P_o$Gwv_s)%L*pDJ;W@mBceTSy~>Dg?9R=BOncD1UwScV2EKs0Ym z*RlCU&P~D0uImaXGUQYwet1~$vgk3!rWdReghi$MqpKrK+ZG-ltdB`1?v1MdOqnQk z$`qR*PYS+Gocy-ijAqcN#?W?D*p94ZNl|ofbj``R3Q5(o4?d&8T4a#N2Eg4KV``MK zc9htTS*?p!aA4~)|A~UYN_6PQ?%Y#B5UJ00Iz9$-1@WaTrsE{0NC3nAFaSnRO=TJm zxgu}GNM+ONT@J5*<PzLBjuHuodT1a(b|N(J=Xuuu(x6by?6NC<eVxBz-;i_CJC)zU zZ~U(K{^tRkg*D+1@2Q2w{jup|0$PJx{n(6%YVS=^`L2q$e|BDHq(tk_!L9M{{P+tq z8ZpEEutV%<_Zv(4le-JiH?0Mg!gm5B_x50KT`YdWckK@X%nf<=z-T1T=BA0fHUYCU z*>?F{jLAz^`p^}hb|`@$`iJ(MNV;8lp)b(<I}V23A$8;#jZiw~ZR@}O^BUBIDrUXN z5G!W`$j<?Nue-cd{QMh=0$Bq3JEt3Dh*p@{nTNazj}_JMP+dmqg$V5ntz&O~FnG(4 z9T?;o&$t$zs>9D3NFRQ2<y!TN?i*+gN8PO2>zkU>a`Np7&f9v%$P~L9;y=+;;;YWc z@4F!a&ybp?3|AyhNYQnQcrLy7-0u)@$|zClJnkI~0EAsYI;=PJ8>h)!m?4mK3TTV$ zc$kNIcb_2BH}YZhmUd~xw&#ji+##0JW5jwL`e3^bjn3%BSpz-!JLL|pTI0Mtg!VoE zf&$2n$sv&xB>-8^FU=A<dNg_v2k3#srv0?6>i2}H!U~GW20tO>W=G8VJE>t=J56wZ znnRW5#=<CO9*^-G;U8pSzHx+w4Bk71Iv>NGLloK~RsuKhz{!#8%n&TwUpm5HdI?q3 zh5GBO=;V$5$}Yq-<}XgOg7ehwfO~j@M~QX;@M-6F<4*xTvd{(yBTe(ELrKvIT%{qv z<y>LBU;k;2I?7KB3`o;L_#ZmLumR+6AapqqrG=B@!NCIjP(PVG-&i+%T?OxJl~+v5 zXjvfz{lGf%-1#djd%>%Vbo9Z4&r~;-K<8R|`{=JfT$NhtLW6#21EQL_bF784U~3QJ z7FzJW654-DNg-{$fU>{Ovn~!hJMUkoL=l_%j=l2Cz+3@XWeIQ7gO$EZRS_j4oWBiz zauUqJ>d4^<a*|0z3A-DZyfNt_m6r<wWH4Q7)t?8<<h-bNNIHzq9_t%^lEK0*;^jq{ zK&m6yL7StO0(blOEqy1JpT{sj@Atx_zY$P1Oiu+I%!MS=?k`r5cCH{3tByRF*ThVH z;oQ&IBZe^xf&@ctz<^K<BT9V47YE{1A_{Lf{!R^6eep=sFA6<~6Vf{O`!pWl@#i%y z<~J_Z44V-<Q1TZ_x8c(-=6@f(p%lo!N-^-I;@8pAvIQ8W8{+H!CE_t?<r{LN<5w0y zi)1IUWq-^A;y+nU;79SHqsv$we|eDKJ3%(^LJ<RNKV20m)$Pw?w`Fil8x(SutCfi9 zQ+>KGz!V1`Q~2JrR4>ly>;~gl1OlOWPNIfWq8)4Y<ltm2>%in8I{<0~y*k563(Hi7 zMb3hmvo74Ce*U88L8ws+hxqY|y<pWY9#I%kKD1uQu6|x}^I><+;iuN>j<MgY+%*Yu zVhZ(AqyAX*N8S>o%#T?^JBpr0$A!$>dU<2mA(mtXG52z)rs`BsU46ced*KXGrVC$i zkTYf(y&?eFIn=)mfC(TFf-~9pz;vU*C$2ASFoP_Z2NTu_0f)KKvYrU{-~oDI$)FNG ztK{j)ZOK0%i5(_So{rp4x<uZHbbmc&g7pllWr$gp+OL0Z<cH|ik?zOKhlPlZM$@Os zg6*>xB8b8+@<13K=xR^yALVXy;X8j+*oJsyIQK}PKSJuJbz+PbBojM`7gMR1DtHPx zF1#Pa?<_x`)r`Ep!II7yky`f0PW!uY_eht5_&1@4tWt^K4B7jvH{MO(0EV7Zr?vA( z7#{(ICCg7g6=PE5=Wn_$5T*NAp`Pw`cmgQyHsDF-sn~sNWNm+p@5ll48+K<zrg0uo zgOdv&Q)+NBH6ZjRQF^Dv#PYd#t-}d}0?R#$Oz#Lb!Nq&r4?Xci&<wAZ3p>iq$2r-E z4Dk>OvxSl8gn~eP7@|nuXN_0UcLGL^yytPfaoppLEXM*N^~X<)O>q<v=}~*4@N?7u zsE9j0Z9=fv(`3hB5MlKmNH(#TpJGiWQABgbFgPyHUqJ)`5m`<xQHczmRzD<6_KMo^ z>IgbFGa@-SQV0-e|E5f&35G57A3USiN|AVlTNXR@GMFhud8}CVoEV5DT}PA}0xkBx z_!gin^`cL)oDObukZI2ea;q106FTJZtkWe_B&1#=_BryP&`!h+Bpg%Ei@}S!)eAe| z{Y756V1N3bGYAOhlQf`s;eWnj_lUHxcr|v*gh%lwUrAThi;g0(7}>U?o_^9S$K|8C z_|(^Nc*#|~T<8Tk!}w^gWo%Fj3XZe!iUs`i;H?yQVCxtz<47x!D_#@~kZ-`++<GD4 zOhBp+gqd*)w9LfU-IVOA7yU&?(2B(*)+K6)sBiUNG=7z+QEV?!F+v%pRwuEW$=F!a zFjEJTh+Y30F1Ue2JXwMZ<XOr7)Gi(p*HzMwxif_uqQY0>Yt!_^0t-Vz1xJZkXbDAG z<ZM!!;AvLiq_U2YnDiz^!s-iF{=8LcZ2ke^hEM`N*8Y~%22oOhbzNb=Slol+x{Mtl zN_PT6BIrYKKlms`D&?gsrwwsmN#VIIsNWL2;S3bq;R54IOgsXq)_CYqj64{fQY1Dk z2Cbos9Z>jFVSi%!e1p52;+Ik7WQawb#FjsndG!pRq8QslBqm*+S>j_r%$Q~heDfL^ z{KNpnkQhqb!VB_bn@c4vGw{M&hYE!{bxgd!kZeL~@SURIffz*yf8YA4uQ{<#@Y0P$ z$)ypjl^EZd&qpy6Z%CgM7V3j*BgS5^^10@N)DwSWR<S8Wu9#mYT^xNMfb<TuxEX|T zvXIEDHxWf=ivax|5j;90r~|vv`ft%WLKe(!BIYAr{GY!>zab!=CC2NAy5^7iQ!m*^ z!3xLaIjgJOAxiDBcFO(0MgXH>L}rln@6RJ&w`K0PFd+io*1KNg2~%@Z<bsF4Fy9Qn z%1Bi5bJ`h1(Gh<&;d>#<M%rO&7#K_3*V)baRSu@qe%F88BmU0dvo<hYdi%NKu@j9u zApSgJhES?inx$A55yMU_GEHjuo+hs|0>pTMR5My2bj(tHxr8Ngn1YGaR}dr70D|F@ zNxps7rTv?y&s#7vEo3f_h~2MDzOyH>?T`97vL&7_{@VD+yOBKB8}N(=QkWuRR#5VI zRrCdb1Ovj6w~`OO3G>5mWPYm%`4}tITqk(CJ`Q=8_GKeZwBJ|$WDAj$X?jD`kR@)D zTkQPi#*w6ikaM*|j@ZZz>?RSt36h=~Y0c$WVknc0F#IzLcJGtq9v%A*Bv<chq*|4E zbxaHi2&rp(xh~5)`Dj}-o}@B8#nA5K&P~rI`MO7>mRPugkIJ`?VTI?7az}h_<tF#s zF}`mkvkekh2T4DZIG^5syR5zTx4*c{ci2@XDvl!44>Ak4adG`5e429jZ_>!Wq>w#f zVNPd{FaF5EllpwPHOx{3{kq5hW50-;OU#HsCSMRK|F=$Z0yJaX_j{K2J?xafl!`;` zv2tuDOW@#WKv`fF)&h#1*OUw+s-8`LOi~-T8fENO0;CvUgy1f=5uH6u>?i86{lr@p ze?prhLo-zYVH_|6TnLAGdh}xYSl9}d1Q_s1oShD2O7xk@B-9&;x^^8>QMu<|&P)Vb z(0RLcx<vL>Oepebadn&ey8klOJSc*lcv8<}5ffH7ukpy%x)2Wq?Sc0hAU!Q=)ly8+ zcDo^n@t5k)3ekQ`tbF=r=009YbM~00bRA`UXk@H)z<j~KZ<A0ER9Od|Wdx45oO?F` zp~J+9&XQay3a_r(>nODFwQ}J=bb?IlNU#F5RsuTH=5^@ph*9;({YwHq5I+<Ys(di~ zSK=qpn}Qwx;xH3xkNii52KXTcg}QEoE{A<ozno=l4&vp*YgMJwGnyPbM`RTIg_6QX z(0^~fcobuW7a7RmECDZnY|dYVV43w&n2~@n*74w>5P`!D7#%<<w`Rtw2YET9PBGXi z<+Hf7w4W(a$G3U^(o-1+kSBKX%j%@uWz9NGPLd{6$c0+u-9MVovrp;UXbTf;xbs+U z+BUo6PBM!20x@w<26L+~{XJ)-72_-fdM{ZHF;S$?QV%Yzw*^(7wik8_vfiwax=vG* z9+5<6h$*pR{`kIEg+GA%kL_J@l{D0rkC##y5u<az*xkNyanT>AU@$ghaiD#vhF~ek z*#&Kl;pZo;?y~}(yy}mw`Y@KpL6pCAO_dxao(*_yoZe*{Md$oO04`4mCc}U!f=nD@ zBhXp*14^cXC9_SD?-%pwc_~(lUz|){R!~#9JyP3K3#HMWt}dmW-rw|E)>0Zd8N$*~ zyLq8%RqF+dmrR#QAnNtIs_*Yp_m_nhnC}vg7@L>}By+emlVUK6<kIO1x%WiZ3sT#J zs_*83g<;R%(PiZXyX{8rje=xGiP{Pm8y<n=mnf3$bXZj#0!ZbPuwjkfIV*;%AI;#C zGD(3K`J2Y>?!4Cm05S-|EgY1>2Iw>(XeV0LOQUwWOhs-m<p81EY;pk<axL)n(VBt8 zCpCv-dll)|LZ1tM``n^QA8h&(U~-8^f8$A|M_X^;RetFs#*Q?a_wu7$%;gUQr^<2+ zZZ6)53^Z4PgnN#<p8L{;wZ2$%SD&kKZ^invaN9`wS4s0B5{Y~)0eL4P!>D)lu};Uy z=1oTR1Lu;_HeEwq|F9WX^=k8*q?!kA89Nj?{<mx4RW}0P#v_h?kPO?Nc-ob80ee4Y zbwc9bCDVH`nVYYg+^=>u4CR1!+Roa>-W!W!7Yx^va6_pO7#uE+CXfXp7nZUuTh3!l z;*`EzojZN<JqLd=`=;Y3%JuoCwg>QgH5PSvS$-9H8L6UoP)+(UCG=Fr(FqXszQRr` zII(F4mkn=#x*&vkE(ijuoe8oCX<DmMg>v(ZwO5ua|IeJ$DZ6XW)hPna75V+y+x8NL z<1sljhk&0x@%?RbzDCvb<&!4*>Ii>l=hOWRBX*s(bCmbuou-n&qaW7{&PK{f#yB;^ zht#;ZiU39{d6r1yC9=Cu*1L5}Sfcp3AhIpTM@t7>{C+$&{q^|wypv;F+B2iw&D(sg zAfu8(m%n?l&l*E4Oe9E~Gdua_``++TLCJz$XM@lphqG4QW^vPp62t}Rf&8rFs#dw= z+kt05drIQUBa-nvMG5HM$Ubyg;#;SWbjy6H`6;1;0%KaaeM@EegJP=rlAVvlo%JsL z0y9P@Yq314!C+(X!%}wCFs?TcS;s=~kZl1Y8o`!0FG0Wj(;T{HvK)2;b+|S{lCEnP zK1Xury&JsPw&{H%S4=x)?UCRWy2=--lxDSq3gS*Gk9@F;AYHXnURb{S=SRCpkok`U zN1#>devHRc(Zrx)Yg^t=C9nF0kQlDds`3NP>WwF)`{pg5z2I;Avg`g;WhK+R?%oNN zMgQxMn~J|j-Z+L4M$-grg~hdiB(V1gTycSZ`{;F5M-z8bPNw(Rk%RrY=jMn}-DhrR z9bamjuBW6u*H<j;w0V4*Z>-Qj`l$IwVZFlQ1D=Aqb(P18?KP>d{Y*4xVtdU020QsR zK8%Z#NS|rg`Q|OFn6UWj)$LsQ-Gq>}w2PO|T?o6AXv{CkuCe?R=FD?Y98v7zRu~l_ zXCU?KqvOwK*TYM>=^!ZDFAVtloK<MF;5yv>Q#ZQh*ukH9A%Gsfnd06vbDTj$rgUzg zv`J+h|NOXn^9sm|(bfP)I}?Z;4bDll2Bv9fPl5u_+ad5ZGuZU{?>gzJ2Bt;vPPPG) zB`Oz(zr4Dp*PfS#eY+0(Y0)?KF-$EfF2e3SM``vt2t_prvOE8-E-$I(W_Xdr8KGP7 zl8Zx@(l*Sghgx7VRCp7JrcK^^MtRt9kdcY~%+8b=@h|w)G@Dr_$8EwUqKsQvAmq-d zOdL`4oUe7T_qdain?P>*rUgDhpdQ~%n{t;|jl87=HG0Rs4Nmdr4_lZxV<KS2Guq8Z z^?sznb3*;|sgMGyu`~M0`Vf#XhPnO1Z3na5q<<<Zdne$~ulb^CeI-lj=gQZE^0KFc z%!7`cY=k9_Ldd^rZ8?WuqL3_w|Kbp&{L@^$PD?N$KFm@zr`v_kA*8p58E6i|tr{vq zxHDQ)(;NM))%aYqj`^mF+@P(#U>DyQ7WU&ODACpTUGu}8Ad*$<E&L^=JZi$SMc?!I zMZUZcq~a!xaBlWS8$F1#^t6NW7TJJdHT|5J+Oy}JoSLt8_P{@6eUF&*4Hi&scM5rs zCb^OrlE5e_GT*b5>e~rkSj?Q84u@cUey4dkh4k{<7d0A{@o5Ui@Ve(I;jd<KDTfky zYRgE$Wf*SB{f2BXgNzL$SxSpi8Wa>Bcj$ITv_-Z}V_wX+R&2GJ!(0)U#9JCYlkLuL zYvrFh+LiL?MqtXj;~M7pA4Yj=9j7i*537e*fT1`KfFnrbWEhbk4&G9;!>Q?7;Bm*W zGRVOcDy0H~y<_z?=)3|C`dW<e4_}{x=6Y0uT?1BD3DB$SfjjHzl|pBZpLa}jcw3y^ zoMhcjdxl4yiIg?hJ>Yt6+4>1K6&)Au=NOXW?VZIw5v~5V<owYOt|*%nfjkHr;8LP- z#Imo3y*l3+(tFyA)QS9(%hbbzu0H=3n}nNO77wKu=1L~<*X34Z9^sjNY_?-9QwS#< zaSpRQZl@=@??E~lc6-{R>ou|Ysp#Eju1?=g<P9^#t@peaU;J~+n7HMlnKSlsTBLd* z<rDc<%2*&d9l%9d*1-%hkDlT$&Z%tf!NwZ|0N4Z*b=qZ2#$cX5O5S@qvZzr>-Zj%P zuVK8zG($cCpKT$3QOZ1x+s_4bpZe?$pYD)E<&VJkiL<<pAH%3-m}owkj+kD4imh}% z>)FWK0L}Cj^+0NL{yphLKiPM2=el7$^8C116~<UN5&1J8V0gw{7roZ@KpUB2b)yD{ z15t*D>JvCowVUU21C%IKpfmNJ_1KgD7ZHY~3TCh;<Pung??#a08Z$S$lWV&Oyn`wY z5+%klD{u#ow(fyWTZgF52^n3<T$6NaRX@o1LhOAFi;4J!^DkzufN+Pw3sdNB|C3Q~ zk}o#P+8Xb>;uXF9=za*;kv&#^R31l2bni`9gu;+}T!T;*TTAdiko$mJH96-uR0>Ss zJ>rf@nt%WE^z$HO&Rzg|UOb$sa1;G>fMWR6@#63)@3Qz|$8M0;(I+o^*As8~CYY>+ zhpru51wfcO#Jil|FA61}MJ1%k%(_^@0~q(>mIG`1@^@a!HK>U^?i~B%SS+vqKkwlP zx)fLwaXc@db8Xn!>xbT2*6RiCuTdD*I!q?Q{LxQ?^rTnG(upF^&(FaR_iiKiKNLQ= zcuP65g?peH*gJe70j>DMyoCq6B2eh36oB9&;ROFNNxjEvc98y$79q@IsKWj03H9T@ zOtekaCYDchxcq*jxmcdpyZ_0s(Se8&@P52Jbo39+N{unxv)%AQ&vun-@b#s{b92)3 zh~Fh5U_WvziXeB$es}MO?HWg&BhCk<NS?pROPF5T{2rS1HNTYSo>)p_VB~;pq=Eba zkD}PAN$$%Nf$q`0N50lcmNDU@Md4Fkafn%a+K&YB1*?YwP8Aau6Ca(Xy}t4@)dtjU zO=6q~=(}vlkwb<cUE@>x0#vqbuW+$J(4R@a==ipYEBaG@$_=U@9M8Siz8pux(<VJ{ zlKf6klnzWv!CSve7?@{pv*RhthKUaH;WM^`u5rt=qsWC7%2C%u!{cdhT9DuCB+A(4 z0i^;e1pbqHX=lAv|HKjy=^V!2Njo;-3Y!0jQL^F!F<na+QLhKdqE6#^=<$f=?)2+6 z8Tv2D20BuGR{Uu+-Y2@3s26w_s2cW@=gP%08|{R?xf!TtB(h%T<PWI*5jcq5Ch!{& z0F(>B(uQt#^M9uy_29XV4M%i|$ZZ_|SREY4P>End&xrE>Lq}&UTxoRS8Qvy7>`flY zl1LkoC9#N(+?jLwVS&ZjE|5zfV+`atn$u$LZ$Ms8me;L4%5CD|TvA|YR%Tgiz5yKj z7mqql0Cvj+!s}2c^-ljaGTSbf8l$U_?fj6T{Jmw!7kig)FcC_j@B}tOxdBZ~rQM~3 z(6q9z#Ala#7pGp7jBZ46K(Q>kruM6xm0tL1qnz;8xVK*Bw!%3!ikFKT3S}M}c+|T; z@B;*C0)QXaA4cvvP)a-@axWT{Lx$dLf!*RZLCqbNG3J>TJkax|$*X)Sa<-RfVI!iV z5%v~(t^;0|uNE$PW!&D%?NdU`YYB{rCr}?raVx9O85ZtrTV+2gF*H_8Q7$LGi8CZf zOZanbGn7`?1sQFau2SS55{d)&;D=^)Pohw|b}}c9f&AdXTCx+|m5m_8eK03G$updB z?ovy@-a3w%dg?vE{Qw>Hrv9Af%Y>xIdfoQK`C^6Iab)F$D9gJF=Oz-?Xua*nwI(2~ z!sI<!sx_Hie4L2f=;nW=#pj+4jpz;@K@&Y+A&K5;(IP+(2_8w~`D;~MBv5{rntt<5 zNqBt<AFI4Vys)`PW}}<;9<!L2lK6F$cWJUZ(e9vvFzIdmNh8cp<9Bx4gE!ak0g@lP zk$pyn&sTXlaLGA|`X~M>D{&}L9b6j?F>@&s*g<l5uipqo->>rcB<f21Ml{gM{omA| zWrZe?5DiR(oN>^`&#Gaog5Us54TJkVowDJrc?`<W2CgWVpL7aR9?~jV!WC+5l^EvK zz~YcAOwNpuhLV8eE;O$8rtmohM{WEL8Yo9(-4f&515l~yXhNHK4>_xcgs@C#zCaYa zNzN)JCwqnFtd=xAwY7Rj<S$`fVlvD;cHGYT8HcDSz8x#aPFbB8lR}=9{H<JZDJNUG z4V6bwf)YT*45`E1?MNdbFM+eJ5(f}2GPLppA4M4Bd?NoATQq69rDIUEg~3xu=I$Y- zn=f8-Yn4~nmH677UAv%;PW32{;nDpqnVeYsFubj8RwImd6+M{Zve8jrRbxHDKTk50 zA_7E)x{GMn@gTwmj>Ee{<={GQ|KXkjOgvvzI)@+oeDB)Jg|4$(Jc-jqUz4s2M!4M` z;4L6r1y8mi>Lu>uQLn1%BE3^{#M%OMt_wuBf}|S%mYDwmxTWw)c>o8;TPp2%q8x;J zMdE#m2IGLNI4!<CKmHYCLWV?VFug<NuQ1(BPG=B(_eIOs3vG?{ogX|=WrSFRmc}<* zZi!korB$?RNqtc#S~0u_mjiFOdGQ>b_<Xz5LF8m#-**Tg=m$76QPINvJ2oN_DyUy% zxSS;9b~{X8HA#Ii(=zK?B+brXu^%a5+Q_k&dvW`%>450mr_ewQsCzOyC&K$qMj3V? zn7^Q#_uY1@p1#IS7QaU|&F@QTarL>WP~}n%{*-z1T)-X5{ifzEj7)Iu1xwIvG;;Uz zVC_kxuXX&}1k?xz+`$Bsv*7y4#)hsH^)5VyvG8D~&d6BSy|d)2F7lZq-abDfLK^|1 z4NN+idCBG}JVJl%<u9PsbH6dDa)l?psqXM;JKf=WRotn1uxBgz<_pz+gJ|UIVgzQ^ z97donHfrtp91On3Q`qPRZNDp=F2O4<e0yks*Wy}tMSKUYQ>s!t+@8LpC!64RNwDAU zy<_cm@tvZ!&O0C^+XZm~ZhTlV(R3B|lGfN5)7=Aq_(8Jd+ber(uZKUC2c<Uq|C|W= zjz(r>3$TbVj>x4DG0upP{0g9c)WLQoA-_ndw`9~8mw1{zPYccNcRHfIZp1l~+`xu= z0|*ek3c=z)I_u?A?tDucbx}qA7tYV3-S(10&AAx7jHol5DfH5{6LLDg@<oFk&~$in zoa{6)S#*8+G5<Cl{#_TSu?Fojq%JH@{p>(;Ls2_8_zZf80K~uMpmxzJ#=MnrkA{QH z4hC{s)mqzlK1u+0&_EwwCAI?_yN}KgMPBMgti$VwiYRm09Q49qv~O*W*^I?2jk}yu z1GH-{;Lf3;$IBHQkT3tP3zsks1n~oewcs3zFEaV*(|1}XL{t_4*D>wL!twWBkZJd= zh`Uo1s5X3S)4#nt{yLNAjbooQ>>hVc>+%<L)c~T7(QR%fWFls*%u6|9*7(h54BdfB z^y6!PG9!5D87fKA^0($eF=CgQi+#$V$RXhvzB6J&adq&gWYkxB>5f|YPp2E$o3b)i z2-%byWW&LX6vltWyqB28A0r(vE{Dl-4c;;>_!;x?=ZU8RTV~oR)s0WIFy{_lglS9t z-3nqcYC!hV&VHy5b?vV=9oAe>Uwm)bkx+jLDDA_~zdoKmaY{Fx0lP{=pJ&WXRdvGN zbN&YLmeB59=DT^yZsEv(Z8!G1y(8Mf<>T10mtOhK#y!=3IfVR5Lb7luXA<xs#qg4o zBbNWZSrGpYddLn9$#N0Uevj14r_qRdV_q;~U?=6R-A!~Ah&C)BdG8gb`Vx12B^LQn z3Z-W!Wbt}3>uc5T+Y4O256feC=c^WKW@buH)dcrG%>$$b3DSao)!#|fhT3P*x$uXC z22%p}NH_nMA99TzL965eeB{RlC#ubO;zaZiMZ6Kd9|(_MUvj>u$vSX-Pvb2kHxB*w z9>VcVVjg_Uotc|i=&06roj)b;Z0c41)0HaoZGcNEx*tY>$zNKiR#QgGA%C%XN4|jD zuzWvpbL;G-`S5}1;_}%qgTraulT0-Ee&OKEygZ-KXFugiErhH!GWe9@E*oCm{_f@B z*|NFv8N-(^>0_Qx8OQ?G>r0YrH1k~=A~vuzc8>dF?-}PvNs2r2dLDdQ9715A9+H!G z1Xd=0BQi*cQ+c}nW%>8MAkNXz?Tio3_6#m(E3Ih7nL)$|9}-;~JE-mS;N0l3_p1n2 zd$0C7VryY5U~N5b?ZoAPhZGwYlYfi7Ry!=P5pi;jK7KCw;FaqP7Z;9`G(m1@A-{cH zToh;U*7HbXcnjZ7IsAY}q7ea1_|VrC>Gn<+*RbjVUM~On-bPdyfkk^Jf9(F}E1b3U zd=2A2c+Nz)*tgHb{n^br>wn$m!VJy@9Zpy!I2E!<`~xn0({M1^g-@}XLc90Y<eSdC zV~U{71TDHMmcd2p=B=Wc+}r=K%rk$K_2fQ-J4-B_y1PDK&{r%y%RK$G+JLpxb;ld~ z?K<)*(<R~81wfJrI{s&~%T#I&efJ{cnNBYJFAn*k?(x@qL<B{zhrtt&@!XuZ@6`fq zs}y|)y$-LuiMs6Qf~Tn7L&PQiKtvnm(xv8V4=^RpW6psd-nVXUy1->KY{KI{;~(}4 z^dcvSu+x14jJEprqx8@R$Tc!j=`^If0G>tT(|+Hgv2r|}z}s4v?DPAFe}{NG4iV)i zs|nfTIf(hNd`k4X7OR`TjK-_?X8lE1*tFVq;E~3y^^(bJlG}BBY#n!*51)gcpMKft z{&DGj%>~GNlA_(SjpEnHKLkGQW6&J}O5@u1$;X_p-~jgZ@kr*cyuMG;9Xvy8p<RA3 zd&0>W*DBw_>t#)%+YJ6PKW6Z{RXMD}^NM&{<X1_V2iFdMABj{hM(41#ZN&@!1Ru<P z?0))yBw!=)Y>z2fF}%T2Nn~sB4*=+=5eMWfN|^Le{O4C(ehUniWtPC9qmACP%hq`k z`XM!3XJ3?NR+*P23U`RK0XJ;U1-*H(=2)Q}Y$0zQQL5tEa#BAfAl-esl9+)!l;ir| zwb8y%G<ebFv-<_D=Z}B943!#+{)|bT^UCrXj&`Uv_q|(C>)vWV*>$NRKHTQ6#$@zU z$W7@N+2?QcuDyNz{R~}fSN3qIhV%_7K>$<74!-)}TqxvNvu~yUi{7=>LzeMWT+x|d z%<Qvw8QbCWBJMZi)>Y_=X6a%29+itfzgDOmt95J2VJR9Ys|;6N;Q6&Ro%T!idG*g2 z@|ybdkso)Iy@q2?N)>cWcF@d8$A0(9X&y)np8hCR`%onB+L}?qt9N~YRKte9JHL0o z-)-Hm8N9eO8=42<6DOoX&XZx+fM=}l#MNud->%uvl;{Yn%k`hI(Ts3z3v~4|q#V$Y zXlpES3sAQbg>-yYC<VJbDim3U`<08v28DNvmX#>i#*bF6RwRvTPvZBQqi<Z3dvvy4 zZ5uOsZ1TxF6GwbbN@>S6p9j3ECd#!pVw`l|NN(1Q&eXRfcrfB*FeHx_T6+<r_TyRQ zwUeAM<qlqf4CZ0b#FLp@3_UZUb4nsv0V6B4<HBXa&5L1DO+u&Z?BuRGTL}a|vQN%a z9d8;>Kd)fkMrjg^U>e7meq)ert{rGTT0UE&@(7}9>;8AF!>gR$)<QcmRvb3%QgXas z{q8e_B0VXU=0}FKA6lu6BAtr&2`O<96bn#m#7iV^5Z5iwZwbo*f)J%Kns>@=z4zx- zgO$oWVnC1_r;zAFrEU=oS0C=iA4-_7o6&B$=KCjX_vP1(>|g=*GxuE0H9iG>&SrIP z`*8f=@8x#QratinihHx0rXHlxh6{ou5x|i1>l0YqaZk_DrzWa(bpan)-PpJb(zk_d zp9}=+R}=J2W*r<6xH6w5Z;+@<UhdZC74u9N$9zM#forE!-f(qNCydYXM=gxpS!rhQ zN?DbvZvQ!~@uRiku=Ks3$$<yMOWKMU8>KoN1sd^90TbW%_wUiB36@4B5TV2@ICB|6 z>uZpCeQYCBDVht_<enHUOgStwx0IQ#Wm)E!=l;HbVBxQ%fBg(kOSO4Q_T*9d-C3*e zcUjUK=dq5%3#||Qm#6c+>Al$BZ#s@RYsN8*TWT-1-W%a08*r8~Q8U>uk_PK_KGg;R z%0PC|y1<|6&Dl@SivV9dwD6e5WBaE0H^*$d$PnRcge*@j6`)0^?hNgM={x>4%=@Wv z`A(whq;|UL85h{%e1K`aOQH4j?PJL?hsy7rf||dbN;55=?BO<W$rR_UG2GG4hS=di zNV1UlPEmnLWoV{A&bxz<%K|_uE>+y3WYW;Y&}zOS6@O~VT9wZ=(|i1AJSbf@#(NSi zH(t+2^Rrg<9DSrA$feS<{8DnVxF9aiQl^XqUFpk^Pb5J2`9{lDBb#gt%iGS!OUW-C z^@p>`ZHeJQt6QbI$e4;TF(N0bDK1AjJA4C^KhFQW*q>L!w@YArp{CxbQc}rDR*V{! zrno;@rFrdz&d(R)8g*zu*Gv{@CU60F6`oXBp;IZCTw^AY-!?KeMIs39rPPy|^E)~* z@nn#czqiFlk>W!JoxD=B7EXSdv9_TmROSXK0|X}k@>=f<-uWX#a(-yqD^saUTf9Ex zI@sRO<VUju`R5Nx!Er}GV;Ve^N7Oojx>o$Sl<%Arbv&j%-M7#XC2CnOULu)hWMjl5 zB*5wQ=Pzbc4Z$vEk)u`>s*q5F1EmuAn;>brY5kT$(%fIYj+!O7EjlL4Xkt7q1wGbQ zNpnL+`^rf?Y$ftZj_}owjJd2UsrZnD0d1|+GCrd9@hJCf9cZ1%E%t_ykIBr{E^B`e z2`i&jP(hX*QaY?|d?|9HxGZO*>qNVP(+)n{a~{(5VLs%<qtBvBpmiyWRH0>9U8*lS zyET)){_eyq(qC^>mmFqwgleN_<?5-_KEU<QMi#-9Q?66ymxjmTJu{U&?&$A|S~B<Q z4jzc=V)=BdJLJJKiHx$8J5?c$+wHHHx6AsQc<L89>q{s4XXkCMb^Vt`-g+69GI@Sb z1e6AV<~K#1RPxbnXJ6eYjg{*6+Ym|j&pivZlRhwua^>5CS<3HR-BovxT4W<KrwShW zt3)PgO_yd&jY(b_IBKK-zJ9NKRECMufa}W|5|7?B<_gI+KU&0%x|TNv`PLBg!XJ4l z-I7aCi4JLR0^7{5V87HUXTP<SzALyQHaakBensGTT-?-z_K29e{1()<kCNBvmt{pA z65#qdBH(QVRSk>gY1z8lFoo@L5**5R2pW}SXMKtX*A<$jd}>VI73XnJnC<I7xc4Mp zifZ;i>!bVH&&M@=-`p3Xkr(5}#9R`9ghK=hWG0|Bxw+MZF^`NL`i0c)&QLGkLngv2 zXVvX9lse}!^wM`lI;OUpeNvC8xyS-0Jw1g>PFDQ4GfW>;q#K4T)=8eFVcAn-V$6{O z_V~To!D&(_!uS5iS82jYC0*Ul@2B#(>|_GO>3}qwT=8Z^<}DLlbq(9xo3Mi&Z;j*o z=JGjWC{S-*>Bn8w2A&l%zO!?n{l3o&s#6~b)q{SdT=i-rHJ`R{OT(eo_yS*|Q3ZbK zXf;MzTV|x!xMkv~Opm5h^i^*N|CQ6{W4=C}8W{?d+O0^1%CpJf3Jmh#ZP(mnlW@76 zVd|vMLi7<9@yOLct2z*x%hHocJ<(|JNqp;>c=+uPKctP0$gbwvlw@OLwR~lLSsB84 z+P<L|zYK`n6&cyx7rd~*;BU8Ud_mP18&PtSIn^q<{NOFu8PW}G+J8o~<6CMmKlZrG z6b?0iPX3v-*E{#B(n69HoqZg#B%84Jy`9S`KwDs_L_9RtIJK15^Pa<o`z@;eD-zEo z!1Rl3^Zw;mO1}$|F}FsSxg;BZU3g?j(prI2jivxD5k4FU1(2bG1pZ5X@0LiyRI{wD z$5sQcMMtwHO?yLG3#L{PU953l7%11Hb=jKN>JKBTo=1)ST*&m(!R1TZd;>4UN>t-g zyzk3^k%?@{<t3Nlj@+*y1Cj3s*#48X5^<&7M%oFf57wn*RsA{CM=FN{r@g1amIWaO zK)$%!ri*<fA!>9--)izL&gsxHu>l+jhe>id?t$@ez?sBFiRrC*0`)a&eVxShrs}4; z(7=vQZd-SzLu<NlnxaUt-0^OcOEiTv%Hf^AxcO?`8?+AnJ)Y%a)eB0MXsGdUE9&la zIwzc4X99>!K~orwp*|fXJ6NUT1BcsO^(@+-%28@-=@L2JkRg0}J-xJIq+YHTn7h^3 zLF|$`OwW=_T!-1Rxk}mzxlEpXU1%(#|CI4VZP(HH1Ixo_5N-Oc9hzHmZHur!as-1u znKeJ|Sa_Q+spP#W8o?fog5SiuS7g><eC*6K(V0PP?(<qrNBM?ajkr7p(jB$Z0A?Dn zo_<Z0Af^UY3CyT5;@Z|dVs6zTh2h;}XAsF<oecP1AXR?~a<-K_jy4+NepqV9@@CpN zzZ8|G0ySiC$7WgFk;o5cas|-2oK3iY3|jZa^4fJ!9i|R*lYsFe;0!tMaj$k92NB7H z`NIL9g;XFc-JzNaxLE$WJ?TD>?vaqDBc94pg9AYA`WS?xFzL~eoBwP+9bocN%XFGq z;LA+c?y$+Hi(Fx5Xx2ev-;CR>j+-9{Pe!lW-!M`()=Ag&6TD|aJqHI8<YB=B#&vpD z$wQMZTHG-eawTu^+)8>z3pSmk={G95LM2oHXPLQ>I?M~4;CrB-;*c$#;Te`;Ne3Gl zjX0wRZ^vfX*7dq}j9qy<HdkUbkDGkJXeCxa+2VG&T9Zj|z|cD_V=J>5<m6p4kX_=m zYs5n$Q<-k#M%(lVEm#11CY%ZTq{{uc2y>?fKdi;QcLSzc2MCgY?~C;qyR>jZma}Zn zay55=9n{}0okJB(&$FY}wa?YSR}!GQK$=F@@MQ#GwmEfN)m}Z#>50qZ>29-#iu6+? ztuc@KI5rixn!!j@RXS)xU7tt&_r-pCM!~;Q)qW4}n`j$=%M7oeMiSt$%<1Kw@el;{ z$>xx~OG}3udC47Q#9`2SsQbE#$C0V$v@#upGSyotrhZvL71ppf&vUd2a#J9mr3M{H zT!CikKpj_>%EKRvR{Ok@KWg~ylw=SSDw1a4{%>G<B#3Ytayx6Z)ZyB0&5Y>#ZlzV8 zu)S0-1~;`1<J+2<C0~^~@1i7I-$<6@;OICc-3T~<NN^s<gCH&x&o@HTFGTMJaGy=M zwbV(GWDxw>)QfO(Ji|V@v$QNB!#%-qe?-Ql&vMK{ZZJ+vjbP@nfDl$!&2V!i=^fsP z9OOLk<bmbDw;8xk2e$())hFvA8#nsb(F13Vue8f~vfrV<Fk!)0c@E8;kT3_}jw&^c znw#eAmr|1|K%n(W2NN=`4#pv?{#Vngq&BsO8}oVxMl+q4<PV{O?s_(5i~DnZ7=Rj7 zKr%VA+J&ny#bALBwoAyUaS_;%<uZwcTkSr1+kNzj9k<>an5|K@Z!*ewF;m|=?Yy`} zsjQHl)AQ>XH~FU%r#i}F(bQNa?ijz9!E3s$Q#|^Km6uoDKs0g^gBn}c-5`s?^$Zb& zUuASsWJpt199uo%#qqMamY~{dZ+%)P^uK_*KY}LC0~tDWu#GZT@#<W*iN{gvW3dN! z@?g7}*v1LJoKb*H_3=*gq0g`v=Bp3)ho-}a;K%LvQhngV-Ft$1+D}u<T3P_Bv)(<I zHzzp}ZjJ&?|IJLbg%A$G;oYk6d(4><=7Qi4E{0K4g-;}#VPPg*cJwqO@pPZXzT@4g znFCOoS-MwP#uEFGsIQWqN}Ke1`;W^gqv9J5>uKki1K0I!*;5e1ZdlT#ahd;Y2G8m8 z%yB<|0+EWDsTn>Anm!qWrk-cFy?*Cbnye;A&e;C^(x$j3o<2juWiF*WlJo;K7<66U z2ghrDUN*r!aUDhQ4#DFYWp=*PlIfXr@TWs>+<vH#_{mrrc;b-PqW$~11Ja-`P?)`{ z+5|7G+y~pYQj@fl&+@pHTAcw_dEyh&H3v-mIs|3;-mjiIwHsaT;Fm79fEQ#~h!_E; zG-^zihmwl(lP{Tlj})0Ar!#yXB%&o}Q_K$zKb>pK{~t^@3u2U&3bbZ$u+WOtT&`1) z*KQe}3;FN&UWpSCf$OIyg4>=y;@`xi-_{l!GFebvyQ9g>C~hzf-DJ+YD>qi~CNKqm zUJBSdw~YJm%uaOfVh8sXX1c_J8#i3IWDd;X2D4V=ec$MBPjz}ZK{*6eSvc9s`#~fe zeL=T02Kew_Cqm)vln!ahiw%_^zS~r9KUI<82tRVoNB_RQea%7dTT(Fm&yU$A>-<~k z873#G(5FX+X_!kDnUR}99T~S9k1vLL@G5=_GE{;-Q-8|S5un;7t!&K`x0jiypNcI8 z1QG~J?B^H7sqxk_I_ggWc4oMD`%;Yy?`d=Yb<+!fVSk8AUh!G;i2@%0E&&DqOcIv^ z<AH+IYIRjUum?6<@bqAp&KE6JCkZ%{;CpMm6B+22K^;`>t~a{M2})dgN?cANYZse8 zU=@b%`EgHqI|VbSl`3W1acf}@0-6ZiF>EEdtoN_^N^x07yhh${NN{J2%tWtve~1j! z@PjX{!Uk?WiqaDH@m<f!VgXqh=HDPnbs1jX0##*)d=E(Z0O5_JmQB3&yF}J4?}*TM zvcs++1*jtK3)V*R@yd$f0pHj|u3Wr%UC*S1&ma(}sRXEA7S|<or@7#nG8l8J5-GRf zCP)Sla0=Ltj7dm4L7{H<$z=4HrLSiOGJ34oPhqVTnt`J~kg3=CsLg^JGw`%K#ItPb z5#X0`HWR{u&kEPvbgIa|`Y8QTInhR1r(Qw4;aliGyDSnLW;>OhK+u%mSGXs*sJRY3 zabaf4>}&4dcOB(&2?+{r>p~<gnK|f}vCOr!+5$Zn5Zt@v_P=Fr8X&?*J(bWQu~sEi zg2`~v@=f?ZhR!>jsyBe+=kDv`y7tz!_ulh&U9x45j4~q1-V)tw?-gZcW-F->(zS0W zL`q3^ghDpucmF-lbN)EzeV_B5=Y7B5&j;%06|eg_7A69qOyd&;;2pHtp%;!i8dCPx zb92r&mH{@%wYr(%{(4?4#GRD$P!n1>)Vdeb_RiLNzAYov0I6T9N3+L#Bc(*VIjQz_ z=en5Pyp~xV+qW+~qMW%Ud-hB7S`r8BB~ArUkpKdFK_Qh0p^%rTHIeke&+p0Xw|LI> z?!$LrFM@cTxksB>XmAfYvM1;`3-vU4+MDt#;VA>ex!eEn8>%-#?g6+JR}Cloy|vR3 z|B`KEv5L=OxEktML)AFmnhY-0R`|Q-#DS7q9F<qb;m#=u2*d1Hjn8m_{Lesg?%(%; z-)&JhBkd!}Aas&xo-sgG2ki|)*eDcz5TMK#xEE=2^B)m>Ot^GGa5sj))nbwye9Y0d zOI~Z0&pM%YB=Ti#st~{Gt938~%BkXmwb$oL!pbd|R~JPuL3yUV7(c0j5H|H3Fa@@R z8Tg+LVo=o`6hc2iIw0=W1R@-{`h#Sr@<yLfqZwHc%l&f)BK5*>2NBF0c1QcZAJ^w4 z_cG=q)6o-xq*pvO3%p|+Bm8Z$QtL1;0%olePyg$yevhar7G@Rk@WD0hjq?txd)vW3 z=tif8oeWek0s?72t-}=7ugNb#>C&xl^3cnhMyS9P$Z_5>>yO_XhCF?eh;9ug#D0p$ zNl6m8$PjZj`F0C-?cuTOUlY5A;x?ZU;Ubh!j)ANFTHM71!jJrDOBA7Vax)}JnQ<~i zr6VD)<#(}IoW*Z)kylX>Ps`o1Zo~Ik&t_pNUitCl&}VGUQi!m6cslv{>2>xGbsayF ze>g<|N&jUHq+J)GDnxrnzC$Mg3<ck~%!yI~h=w}{a=RXg9P!&bCK_zEZjt~T8{3_@ z973(-yN=;EiLx9Yyiax%lL0GxAw9T)uHH$oL;eR)7kEfmpRfIhPI3y%M%-F}3<WNj zG1CR7|7Tkldi8PGQ@eF>gpDdkk{#Pw@wo@LbCRv+-Snde1dn(rB$#<&NAexv<;)-K zdLl)A=8?1Gd_U=3M_l)#3EblCguFq)qUEg(jKW3aAJmbcL@<nL2+V8%aSzCN!q7X` z_UP(F{3<O$F`(Jj1tz2%`giRFaTOU3APDPLhSxg)I31r!UBDtf6n&{dUd69OD<ZOI zt^qOrRV9(<Kc#piy?|jBA8#f^-@>_8F|Em_ggoI&xUXQmG*%xhJpM@Q9+*}vL}ap3 z)2wakli$}ib}CN;>|!|yg3x|n`sc8@YVwKZyFyL`-Motbgp}s37pwZ9hW~ykpvs%R zC`bP8d8w21giF0x`860V5h1f!R&DSa6|ljO&*~ENj3E@2-)m8Yav#!2vym{g-??iU znwq!TUuagPwJoW5<;^|*R+er*XTqK0ptl$5cAq^7nPLaNXL~Rq^#I~ua9FdHpn9~# zCxb6FPgU&hKXG>-e-f=8{!6&GP#rOD0A|392^*MW^;IHIf39x-yZ=o!3`BaLIJ{|B ztQ*eo7r;A8`GD;BGLZf6)Yp@%9$p*i6)KBowCu?CKxTX}6mGa1WQfrtfsKL3*+E9$ z)z&Jml2sEy#_aYQLD^!Jl*&V@vRk`DD*0~$zu8vHbF@Ye=^5?S4b0G2?Rk>bxTM#L zc8-ajv;O1j+_F?90uzS%+=e43Y&8Y$xm44J8}Y;MnJjZ;bc(?mE%Qvbz1(Q8dWcnX zs=N2{o2mTa$|bWnPEXi^a6a@nxxR}V{j@531yh-7(b~tDM-Sal))`e?o~gq1A$@O| z@G1;xUe$rAZZ!p=eMW8(d4UFQaNk>B8rt`&tKwZ8QaACqB8ZuaOFZLyH3Ol@T;10h zR#_TFceRb~TcHx1EHE|DEUg)hRz1;q>j4Wxms5u)uYRC~KByePw82!MkOe6yoq##B z_0+VxM4^-Ew6w~+y*mxh8{{bj;`<S&%lA)^KTBhW>oz(&ztZv9(>5NxB9Q_gw{&)% zyj?ws_JZW46k&%gdZBh1rc}}P2wOd|N^JbI22s1F%_lQUcQN({CQHd$Yu#0jt$c#j zmYOq8A*20bFdL7TpB`JAX--{q>?R0(dE`FVv2w`O_Sv;D?TUIP8}9%OxI>gkeZYd% zM$eF^D4vr%ej$6g?b$2*;pgo$y)d602y4c`N2Dw%T@kIusIAhrQurtrCD;RP>0|U= zsGxdVYVTQ<k=qzFA%Ms^9ufD*+a(J=E3ph3dNHqY(x4VT{O7al#(iqPqsg}7R;rYj z+pJzBDBZNaD7#|(LY@0d*~pdNv^Kcpr=sb$;P26e!ukAHG?(Jt$GZGF9sMJxJ8J1w zT{EBmu-_xN(@KZaIOsrpC$sC8ep~A}9z^JC%vsd)L`oCCJ<CtgU?uRj5HTjCJ_(nK zR7zh)7e#|}lju)%WV=|Bk4FOH))lFylYVgpec!^`gxf+&s_dQ1;Ti%D3fH)+B}_X9 zS@(eZfP}QL)SThtf+{+6X9cAntgmTlS^9M2N`hqx-|Z`v5A(>&Z1MrP;`jWNm&c3p z%Z@L7^tm+V;5O&P!XO1uSa#{$<sJ;^MWaHJfCc=e-`R+wxy8&Bi}cjk0d%SwJ;4YH zpvy=QmX`7qU?5hnN+sdQE0EW=Wr;D8ga^E|sV$t=u<Ta(&G1Nm7Ej?+cVmQFDhzS! zMU_`=uPeG(kj}E)mELlXgUMS|*GJRn(mdNB2PIfpQ1I-bj)I_k@dl%K?lR{J*$v(H zx#spzJ#gXslc2Dk#9ZZ#$k;&=+G2WP=gpUKNd8#u+?@2mcgx({UWn{9)#4oNyTVhG z4CWpTU?3w$leT_YfZ`B0tekLrSx1AnpCJ#9RWer?f7BX`9}&|Vc$iydFtMLAR<(LR zg6Wk9k6(pkz|IG?(Q^ZObxXQvTtCLIJU)cHHz{4;TB-I;)L=UQGV=-+SiMSw%t4hI zRtOxYn51YoEAFPe{;NAKBa#7u2&waOb6=`nmW}|G$h&czI}yX`3&c#^o<ehM#bw}w zOgyl|2jr2!j4ZpU_T5Xmc_!?F(!m9Ggch0z0+dRzZbrsA<bil;iE6=z%wnEep?=4U z<PU9uId&yXt=%cvhlJUZJ3EyaFO|!dGrUr3tNSet&2^ohT{GRSD;e-2<1F8FpYD5s zS*AWGUbB~{4?e#wnkNF~0fbdl-OBF~s0mAB4QPa>$jipkCuUB&<irNIC-x%o0#}Hi zK0sZbt{RQG3RHFKw-E2QAK%!hiyE1ewDnmo5Wb<UmYZNwt!i=x7Qa$txn<h+d}QNc zTemiqg2?18T$8`q<IQ=5S&k4!HR&S-(g|dfU@!l=m2jDx@&*Vb$8R9ZN<z_YH(brH z<}X7T!ji%nsyJrZMwu_|y`!vt&oT3|h6amNmK|;th!mKBj<(&51voeI^_bVit)zO( zJUmlF$DkO^Zl%n`67zEz*Zcaz%Uc4r5i@w~QA=ehSCoL`*G>a*xlv{W{|aGr7p`6c z%eXwobbW9AVd2u*>VIF+g3B^V$}2>;va3D(GOadP%A7zmhDB~?i^WCD<%rKW$4sdV z1$-sJ@Nb_1QZjS3yE~bwIJ@^Z;0lehx*Rr`tGw+hP@V!(Jl;H3zB1cn3x8GUEfmMZ zKQ)l1GMnZ!9qS1a@n{U5#%CyT)`D!4i;hN7LM*k)Q)okao62Utfj-(uiW@_WZ>h>4 z?Caz;<yq{WybKfvlOp2)Phdkj2zy0?JSch1LQnqUh7wLL`O)Xyi<UbJeT`-B8!Avc zAZ!U^ps&G@!hA1n$d)fxjA!_B(G66>0G_dija?)&JqehrWN!GJE@r>D$yw;b)bc>w zc{d>WV5m<n%0p>bp3(DczWqnDVfe%@HQIOkh-Ja;!BEuTHmG)G{WKe)FxQf(&-I*# zTFLz}Ggzr2j@y|LouuCRjP^DS9x8y*rhEh95Tw5#f$UzI_`{5azXIIk+_$O)l{89i zu9AF6MFd0G74{?@e)qq6A#ZpNhxwtbPmz~}_14ULg$g}D3)T^X;uVHcU%Q^}(4=e8 z6Ko6mn5b4&S3rOMg!H~Th?%L-s+ml|cerwVvApKr9YadFh;Y30@*(sf0)!5>8jXDB zulXl1gn_HEDqKFo5x9}<T5D1+DNx>vt?87~dZ;UO0%KrwJ%uF%SHK;7je}^zKdKj~ zNxR4nUk!HJUkg58wMF96{XnUJSD!?SP4l-RfsWJ&)!8sYZulTrTq3sFFjl(-zco!G zDv13@Ke#D4?CFX%?!DSJ4N)%vbCiQbed0cfjPG?M4xJd6nS4`NVCR@l`4~ZEkqmvT z;*9uN{>QLD&1JBP)JM}{2%mE-P6p<fNme36h7MwXI^(gd?sUDbQA8Yv%{5L;uY(V; zIEiDK2T7asE8OT;F0fHmf!dZsR28lnY-5MnEidpZAgL9w^bX!_CswwFnK6&ZJ7Mys z{)*^+Q6h2)i*`$d;)L^Jf9^Z#{4L|9%t!11eh@Di(&t(CUT_{Stbyk-$rc*GOGLzK zv)OVoB*O0u4!OFl+#T>I^(!#pWxs(<Ot`N`^fT#kGxL;2QOqI+U@9%JLU*2NXz7)5 zK2Z+-usUiDbBKgbEPpq5^(z8of<R4jKJ>lLzy(pjLDVLOqsPAcRQIb?_fNjg(`(V; zyg{_1*S4)^JevgS13~ndIG*0P>LyoNp5@HfCHhUEJT~Yi1<*(Vd<_@~o6k$`^hsh@ z@InIIayOg?@wtQKgbEPex>p;wa^ZZyx#a~Gj9B5{(dL)c7CtDxUSXmIPZYg2y0^Um z5{xg05wuDu2H*LQ>~W>YvX6OHJFkZocHDR<xXo;Ek4Y(`FV?v7hGlA@jzM}<IfQPE zpzT%gWfBM1z#TG^Xm&`p_&Ajb_A*@~b%nRarVv4iKE85dEj{tnb=6johJFqt%LJAk z>sO9|h*#w3;Lx06kI{!jyn?oi5{TWpmv#<dO4nvVCIuL1Gu<G%8}+&wQBa%OObXfn zbdAEr;a$<@)#!_4$MYty@tK>+u7W@;AnJH+_7MC7*WA$rhRuUj^SWwUyrZQadO9*r zjSNv0)oEuN;0R#75S;7dGw9>DFEv>O%@`)>mD3xR=e#MQpmUae9DayuK?CY3G&~#{ z=K*NofDQt3jDQRPY#j)RhD0V2(9E|R>P`JhY&vfw@hq5LwGTL20<O-KKs|xeXjs-T zV%BKUnR>Mnn)nS?S)wf<Ffzz2eHX89*%zo4%UiO_r_pzng@OyrZjKajX4a;cAtvY6 zH75`aViKJqSK=+fLh)dMZ+*f=1|pG#4|&(krfc?g1!Eh&pwx1t`gBP4{gN7B!5iz6 z$JM`H>m!4paVeL|GNv9OukQ`ATh6cNf2q-FiBs{?Q4Y~znjj#dICuxHF!Lr{VGeOz zO9v1y=tPJC7!YRehk7ar@nRX8jAQ*r(54vXO>`7}bR=_i)W(L?_C+4ZeHY=57rK!w z#I_<@hrVX`(;4&tZ+q*_H!y`bE3AMOjmL|uJBcpj*NF+#_Ta^xmc;itYS)>4_@FR8 zG4mC#vTtiXhjm&1D1J8Gvz2Pbnto@YOK-|^+A|U;kS|4_eiajl_J=}t)oV@o#(V<h zn2u=slk`=CfV@FKcHof7I7cNCJfQL32V6`lDW(lZx$<aUm_9(8<%Kr3pvV%l9%M42 z2IO{L7KaaANhuh569a9C_^C@T(d##oa=y8B7uwYKv**`9Q{_zN(9h=Fv^Q)67x#Mg zLKr@)9HjJ@a9i!*Q$qS4G--<%;Bz%g2h_Gkv=}E3(iACV+zw)5=xw+O30CsMMyaHN zKqz|BcyGwNt5ckH1$0$0g(u<io4QfY-l4zGBvvBlGh}?GwYK$f5@z=G%{&bwsn#J3 zb-kKn)`FV~bz;&bkA*bwymNi=aIq_Q@_yUg{5Z0$eS^s;JwdA*%yA<Fop<}ylg;lz zo9Mj8lCX*iIM6Mpqe#$E8GvXGeo!W}AC7IWp!K#)Bv&1_X;rtU8j1{fbwe1$RW(fj zY@;%pj)X{@9EE^f5-X&I*Wqhay!#+q!&S~ha?SGBAJc(vwmRmXro~|Giyb(wM2x6S zYQ#neNjXtw@-`)XX)EH3ZRYr8>3@J8`lxk3^KElTX#7wrjCg2><hu=+^oxqb$+CH; zu+<BR^o#C*t=Qi7lg<1;F9pv)Cj*-gem*s=c0E@y*7S*!!^N51S_b4PTWe`Mnlzfs zULi)m_ka3Bjb(f*;ZSuSrpTw~1mA222xa`m()$$B`}n<L8(8XPckoDviBzm~v{%!M zjZLWIZ$n(>n=Ql7dxn~7NYw}($vaPpmH9N(yBGxQkYU&4bNo?^B;(tD6rE@;hiG7K zUmyqMv?q4<trX*~A#p}}Mr)IP*^dtOCCE!+UrlDvPl~N^_ku$_p8k1Yr{>M`owxn_ zrHT>#;$C=W)_Q!=s%d6A_g7iQ+cMv262y7}4=MxsF8$<{-@|n6(*I#6=6vrjDQ$hw zcVZMPkPgma!HeJ^VtJGYfV77BP^(YUU9=De1NhCJ@CnO__wVuk*9tWjR_*OqRY}(% zNlU)~D-7UsdcdODI|^+5;wBK1j}G7^TQ)77-y_rfBuK(v`d??zKchd2W;+sgPZ=+J z%Va){b6aQn0TRSf&bt1nlzg-If~vl1IlA?0+fBaG!ANm9So6&@rR85L9s1d}i*M)g zHxu!^Ez)jW@~!g$)biX+Zquw^|I95hDmGRgD(&mqNndDLJ<)njFAaSx;Dr>NyP+H+ z!|1=Os_{HrM&YviFQQU2tSZFVuKBW=l-?U%wUTc)Ri%lYe`KUW6uLsp&i2iO1x<$c zwIEa)*|IAxs4U>XQa;q`ex>>FK9d}^nOQQg`hksmsI5Myb*+NN@Q~r{Q2Vq4`&wqZ z_EtN7_qp5yhv%V=#+g_Br5*0Qbm$6o{(9j2{ffp^sMuS@Yi9@7A#Ha_ilc|2FdYSB zM3|fSq1)|Ym+LZ!Tq=9{!y8s%9$k+VSi^2@z4QnUyBT$eS5bQ583r>xyjgtcT^8mw z8r*D|%;qS6t3S-gvF+CN4bO2!o6#`8O(mBprL4-?i=&o9KkB1^Poe&fKfJ^r_%a>^ z$%h+rhF=$J_v8-`wh9j&-V0t{3z1&E?HC>&6|UnRuBE5!y?hv6d=&XSD1x&p%s(7m zc@))u6xt{|1rCoKK8jv$|JM+13=hBkH9Q6qK^WhT315g1Rt~3*pok9p8C3qUAFJ~p z#~L5U^Lxd~mszHz*jODW1|MfQsI0gi7idHz-H%A|e@Sy&g|4+d<#|M!)u*JmZ>jzB z$z2f{UscR{BgWr$xa1vXoE>NVXP^0;GXwHX19FnXubM>_+4xcNgTaf`A5-^*Px7oz zv?NvUPqimsgy#oGJ`|tGhd5-74rfM178akNEc`F-k3Y{l3%^%(Qr!P)kf54Hf0Eu6 zS+X4Y=;la?j(zDL72WSoA5ou{pP|aSSPL(C#50~&%Adxworav81kOcPS>1W8?&xIJ zY3Tpzaqyj5>Y=JjES2uHe<SbI7pvVO+;K>`V;6s1-*ws;b-Cg9bi-4D8~vxv%XjD* zm71U5;rMa-6ryfGKGjNzOgO&N!XMR&AhoD7X0^O()rorXkm|X-RkiWiOZT$_y~dX} zquQg?VP;!3_s%-*ceOoj>v$N|+1O=n9u@C#+Swn~eWcsfh-n`^d;L)TwRraH<)}AN zT|H5BZ_dt0*VReE<6Vq*`_8(0&Cq?~=l!GV{aLgZPj&7N{^%TNFYb3dAG)VLw46=~ zzDq9a9CoB3r=7nIS9_brJy>;j)T(o&IBlrwe2iax?98Zf>hAmSbJ?Zt_h%YyU(Xx% z&&L@xUm&6_i|<Z~zkYa0^HE(SomBL+c+`}>lA`g0Y4_+BtLVh9ly2DHX8+e&9f!~F zMb8G``TQL@TKxCRCzUUpXH(Ck=d$kp(fn&P`uCe%=hxq;e@oHd%U*B2?fy=!mAm;m z-2U$Z|G#q9e}$ksOX^yWq+=Ya&X%ou()44Pxnovu#}r=IiZuJT7WXePTr2)w%zAN8 zY*tJZ=gG$Ne_6FLIrpPCN41jPXk|V8x3wH|_ft$|SNO%RGp&^0F;B%$e>46UgSgjx zDQZ{z9^ukG-tYhRbp8ugev^3^v+sB>#_Ymu&Ti}ay`!k`Lw%ovsEgw=<zsir$((zq zn=u7xZ%(`Z3oZWdPxr<7z3}s?i@(Mlf0r-*$^Ul&(FKSQDi(zZj4M8Ynq4X67~`g! z!YFF{B7)vsFN0GxZ2y@4hCvR$;RA(81`j=d(W`ACCk&n@h4S7rFCrOlUMW?NJlsEF z^fIrIv_mW2Ve+<oY+R@mddhUmy56eZ_V3l{Tei)Pufh&anSJb^xxak?Oa18M@bdO- zTj&{!pVO=0=E}!Wtp3+tN1YrVoUyiC=^|3GD&1uZbQ?_bWk+z&u?5|DdtcP9?QY?= z`&hAR_~AKwh}R^8VwO@gN9e7OjaQQ-zj1{5%s%)2)YiOv;QOsB^62oddXV2je+sK| z3|FMh;@d*y@PAx)_OnJG+qK7VM;$JHo$x;T$9*?qx9UwH=RKb2(^3!!;5~uD<Ny#L zK?5KFE|@O}Kwbb4B$q);d2bw&QOt?lQqiA;;WsKVcvd->#wLGjj{K}@n8>A-%4OJE z{r0|yRfE&p*2kj>yfOrn4%hzCVwK>ZbCG|*gVcOJdt63&H&QAM?yu3*zo?(8HLo%% zZJ4SVkHa@xej9n&`01%jJrAvM+vdksuc-#-QI_W91i8!cUdHWGBUdifge?tDKlz>_ zXnD?U($TWmpUn7htFhzR@^JQMCWh-(>*{EM{O$R%SHbpWtU?iq8es}+-0E(H*WPu$ z-2Bu+@0gr%ypH;kqQ5x*u1i^OvM270xid%~pq5McB)N+}xjyv1$~bGAk02YX&}8;q z%f=Eg6(0|}kal!~DczdN%|!0F#b-N1Ak-#U`IF<b<3HEeLQ5AU^9DAA7tEJvKQjkI z^WpStC3gh|?(nCVm*X~J*&r{tXWe3=*E_{eMxY>(rR1WFfMOiCxzGf)3$z6vOr^=o zK+|p^1f{{7FB)WkXZ4q|aPUY*xGu_jCCBoyh;8t8y$D7@{K>?^l@<-&MGLCW@!CX# zu#MG+E{UQwmRF3JT>(*Z+ePXtSG=-QWjw7N61*OXn!}$5s;)h{d${qVjKHH?YZs?y z?SP{16lL(xg8y8v%GMLxsOA?n%6ZI_k?{CIUf9o#+VVs-(HaA1k)QQ-H4Q%-n%aK; zY-}025Zk=PYdM(r==oa1=9BJ2qheUcsn}M_0L$&IXJnzqt=2K6&8_DXdg9wJrfqL; zzx?dkxZO4vwz>UsC|dki$I64-zg}^A9-%t7+BSc6JrboSVMoZ2->;9?8h^VSe(C!C z20+|p*8q`pWP10oO)WS$D^1pGI#!y%J_KWv`5+9D-7-Y2zO^&JU_2Ml&l=UeGsIcU zwL8L?<r9c!E1P>ZihaJdhnKxAk^Kgi#lJI-LzEVbYsu?|=;(8D<0h#EzwLi8&}mkf zLa92xoHny6&Hm`<{_W+2OOj-p@y|Tp!&$G|jKj}9?b~f#H>0ZC)R6C-+rNa@mL7dU z%wBv`p1-%rt@0gy;;gceME&n@DP8&3@p86)PsCiVo!`l7!ObTpYbD{oPJWapNu91& zKlD4@sH=T)`m?G1*Xd@<u+-Vsi%))M+Z{iioc-!P`gQi3gpfYp8DRB4-z5t_J>MHs z{(b&uLSOpt{<NL{--FLLpZ-0Z3;+H1Xdy}Z-|@;r|9>azwNL+@ZngjZceXPueR013 z$^YW-@sFn$|IUwoUt9n*<p9Ef1m@TwAWh1_tYi{gZHI_SFNX>n^r9SgV%f$hZEbQd z`p!-qmZk!!Z_vk3v=c94Qh~A~_px;DB*>&!(A+fW=lHUds4`Z84k!2XobDvyXeu!m zNd^Oa9J|Q|CY1~i$pb=ayD8@Bl}xn;gJKSpZOpMsmUi->)ScZl7n&-zVS^#LqTO^a zlPZo+<RPWb-Hd?rDy|;}!)jl4Gb6^Tc#g=!TBo~N1e$6r!jO#T*vn2f5ilC5A?q1s z=47T<2fRqUWME`zUyU6U(X&Xk^s!_DUuC74BxVMh@8y2{dV_A3XtbRZo0R7?thR4J zS-Qs6B|%x>ca!K~nriM97yfSxb|^E7547}n0LMdw6G;@78-{!@ByKD#yOJ3sl7PRq zd+Fb^IPUcYcFl7|lm4r_9uWE@^%!<KVs_Q_10+fHeXo3Iy3PYI`>^T<`U@ZgIZ*Z& zy1sL*-YAZ#k{Xf&m2lZb*&yS~Ymp>TAr6aFhmcA{iijT40T-0V7--KlpgTZMa3n4L zw`Sn25}JsKQIkg5h>*oScPFfT<nFURuG3Lyuu4mhWg4Ox)V(IEb+r}3(?dg0Naf8A z+L`jN)iAIo9@At%!IySE>uHZIW&j~o*j^?ci}sULi?LXyTJr=EJbkLke04dP9wveS zkG#4Dt(tD)5g4bm;m35aGX#AKg;L3iqs?m>(AP;c)ETm^2B47uz7;D?)PPV4xC;KV zt}3!C!sme(n?$ZZdlEW`&udsDOLknf`~U}-t2GC`6~!j)FH{tO2J=DP)uL450-m>O zM;9=#K()hxCm;H6s)KQsv3L1_d2>V`S7p|nb$2W>?T4;OWbgA*eqgf+$$i*D6YJ83 zy(DK)#Z*c6Nc0AWIUn+44<|4T2g<6tU}AiC(x%`92C%3u1$>B%TdTkzuE@l)HZ8!Z z?RnEgbmLj+2~>2tjCm6tx<H95EnPKLMDki-ma*ybmEXn3%t))NBSu~#{T%h&JK8Kc z2q!JwE_j7MJX*;(b)^dXz5uDYHTe!8EMRl<B`&`hGVYVh^=q<D@>CB``-&EzgSvvW zTe300g&p=9#V}04CCbUiQ#pCY;-;Gzv}gn_p3-rP@Ar6PBE3R+Ck)Jh^2suQWH*j> z?dR)u!kkIX-afNJsLXNF-*IxsPOlHyz2*R-2oJGey>4p1aJ)u5?#JH3K@*<4WOobb zmP6}@)tI6%+`(wN+ah4<RG9_+basZah07Aw!PM98x_x4Z9uze&_W2}N&0MaDl>Ya8 z3y|m{voRZpNmZD{eSV33h$IPO7gLQRy4oA;6PjU`i8cn-%0=g*7N$)aOzw8<;Hx@7 z&|>zT<FrZSiQnBtXN;1D8?C)9IgbuZ7tnI2;ZOg~EaqIgn{&%N`$$qKA~x&J0za@z zK7LFslo{00O3{)fsSou&k0`3*n!g}?P+X_aGNgmjmrMEc@@Qh{?~=eQ09waK(tqe1 zQ#<<dAZ}=4)p($?{S6wY1Hsz8x>mU%2=WkK8VNCXIKdY0LmgosQrb|Vo8;+gF^x#y z6g`C@aIYueP*J?_AiCqU|Cx3h{r8j(C*G#aOKP3BFc_7^ZfK4^c^QPhF6Ybj(>_Vf zToV)80pXHzE)sp?_@e6c_M=}e`YJsfbp9eU+%rg=Z0xfv&vo~uejuL1dOYoxc}MH8 zg`9TZ>K{rcs}17akF#8yaCp&I!>@$wa?CYUeHuRx-GB<Z5iOSc|K6#QXwsqimfg)M z@JL1P2OiagiRd)r`a&CYf!}g{8d4C~#i8A;-C?X4*5O`S<csLV`?W+IZ*hkTlWQTA zpxOQ#4lpkaoWqJ;V64`|7-9+9ked)$*!Vz5=kBG~t9J`5P<9Waa?7czCa%BL)0h@! zPVtCliSvhRyE05l3y54tA~eY@m^elBx;a|M0=<euuVkY)TF|4+fE2UYCl7Q}810}; zeAdL3GhqzE0AslT-h?Uf01&w#<VzAYW4>K&xgkXMZgwvLNi_Ciy~&~w5M+nBuyFCi z1b|(U-=JQwMQM1gW)uL1VPhb>=<nHR&p0>gBZlwQF`ymOoBYPh6Or@T)*kLMOW87w zL*Wn$WY$GM;3Fla*9mYQ3{Xg-2JKMU8JIS-7&>)uTvx&Ts|o9?LeHDirQc*rkHBo< z!gp+MQ1vFNRXH~vYg}=`{GKq|E>ChKqStn4*GXpInIe&PbdjvK5ZOSkoYaqf)Gx4@ z=^IvMDjWfVsMjAgW`r@b$E+5Q?UzaDSY^zY1G!dv%!#mOwg(0}h2H8wf7iX~vP(p1 z+iwAe-_6r#w4>H6sTnR4pAn<V12TsC4IoDx;z-Y%$N;~I=pAfUpL-H$0v*C{Oi7*} zbi^dri0jBu6#}M@Nht6lRbK+9a=ss!7zOFgg3F@XA15@rE2Y(-sS9IE1GAA9nVJ`N znO_XlH%Vp{tjIf9j6n;6<_~(?937jF-XdqJh!`86<f*H08|F(C?xa@$sQv_}54{9i zET+R84gsO;J{uNR=TkxoABgE7Oc2!~JW<9kiscU1qz(E+X^B7!UZl}2d<fOH*W6(D zlDAP{2j<M_M-1Xj>mx!%#a?8iN>;Ltc-=q~`5<$Iy*YB$(~rsH!BhA9bFzU!-k9hb z*=0f&A_txR<5pI`Sr97(97y+j2Tj=$j$SX!&{h=#(e&&%R+0R>kHu_Ts6McuN~=u; z9$ad|Ss^Xp?Gq@EdcS8=v?CD$(s7C9kE7v>dA<h4rHp|Z9ZAk^V9ARKFo*ydVguF| z&<piq-YwJ$p{Sv^yt)UDh#a4(I<-`rY)-sljbSR`z%0YgOI9Q<qN70DN@>0P0m79o zLDYj^E}x&dykQT8UoALN#n$4i_*h_ZE=YSE)zb;8M{JjCR%lJ+O9d}0@447Rd5v44 zbPcmAsV|-0FBE|nOXo28{CMTNAI%OFF+23YiZ__YJOu(GY-k%%iN!U<=JH#j)`T#+ z2!sg%@lI78J|cWtsQROv?gIu03BahKgbw8dRVH%u8Zz&(Rpl+A_-6%cu_0jX!ew}F zKdjL4MzLR2E`&aBLqTXAXBiP0FC3s)2B!W17xKD{D!-UEHQIr9V@w|fRM^HpD08m@ z$WGfWkDU4LQL6A?Fu*JZhzWp`0`7x*>-8;j%LGvWyrJG0;N=49%YMoAAk<_Yb@DCn zJ0|LifCSe(1Slz@ZC@$<qZ33MVTTR;lAV|7CVfhH2nB&)vNhNDN}5QhSv|}v099Fz zibxgk7DQQ9`ho~lH8@8pD%HVGu{{#{v#x1OhsxGEX6C2xQaSBs40_rnWz`##gQYW} z2xxCafd~i+G4@v>s`Q1hps2+YY$13NWrfJdyVcYmU)r!FAM!lg*xfAsK3a(lxYGiI z<)pDZPy2l=9M24VAv941=By)x>dlcJ7XTGl+o}nNdbQdT5Qbtl#>lok@o_iCii@Y} zDciPXxb_>&+^mWTbKcoO8>PlEQ;8srl)nYQ3j^RcF#yH|48k_EQVBH&P`j`L=A_Vi zpzNNTQ}F=Gt{wRbixOmcf`epb51_v%zp!V7O~@p=^=F!-B87}GKtbAiz|)*Q`Rh@b zr3K^Fi6?kB_=Ds0Sp`v!P~z(ZREem<PJ!8g+S7@TVwXPJID}IFb18BUhW&WibeTdD zjYVVXF-3{RdSF;S*7s4JUs+?FZUU;Hr5Q&5;<9?qxFTj%2L0t_XOCQg8zV%!Fs*eX zt=8>&;RM**f!2D{;_3)5_96xKCOlz7@5Ob?+#&(g$1u!hV*9aM79__SU<JOGH<ZP8 zfqOggQ^rtG7c?jByNrE3m~IKkq~gtSyd_Y-&_i^qg=)j!Fr(_Qxos$!-zpxb-m#}= zVw~sF9&y(>(vbHar;SCtS)M>oh?_w;1=4peH7!&>ip{lkfikA$7e_qXa<e{AvDwKc z8CgGt1i}<C5Z&zbkBtRQe9hoMFg+Ht(IT5C&et_sTPKGihao|vl4vZZwVacLQaG+g ze<!3=sbNI<B~lNNJmNB~H_Q%pyc~guHv^f+;$m?Jv=tmwkP5!%-fuW_DRZR1oS{~5 z&;u+B1(kEyUPzEnf?kY&=nZgJIvzm3qA==S<;7@pLAP2_+HrI4wbu!Qx<{U98ktN9 z45KodLtLWqTq;mU`5*uRp@%pIbcCG0F2fs9<xp8sr(5`7o3PeT7%YAkx4oJ`=;7M= zP6yYbq-vcoCn*wY8zYhS7+G`3=t$N<`6Gk$7t5Gy(7=Yc$D>>fi0?VCp5@v?h|j?} z@C#mRy02ttFKv+xos+zTNt*OFCK9#_0n^iMe}4B2AGaWZnHIx<HTa$r`b!zcUxj8+ zuq)PFrZn%QvMJ4bsDlLR@|PpXzuWh;&c#+I&@#ptVtyn9{18I#`}_myUp+T8ka)~M zJ$G?aQvRzH^NI8I9mszHH^4dGU0xC*YM8}<t_~B<&>h(AG?UIja&u+a=H}BsiKZ`a z<sQYRG*r-KD@$gdORCh_zcq(I7RMRFuMd52UoA@CU3hyW>lc_!$@)vYWe0po@Mkii z<MDO=snSCMRE1y6^fe`9PNkam(O%&lpdAXJplh(zN!tMvayZ%pqVmE*W6E>;#>5Nr znqd~yJs6pDJq(YH<O1gNN6Valdk~R@sWI5+Tut#!Y}{fwriPX?nnb1W*w6N_82O;t zC~0ub;YQ1X>zU=(?jUDrUn$o5tGW|_n<VBp3B7jo<rV%qD+0oe0g}h!hPFAzFFKwx zcu0KN4+EJ~wPT;1^o@`2Ie*=O@xGH(VMBjUK!{)f8uR8I88qgL#7YY7+Rl7OpyLB| zYG2N>a4`wF<`NKqYH{ga*&CzZsIs_W{9g<3s+R6|`TV;eFb06c;EF!%hM6NIOIil6 z9!o{agsx3|Yj#zN*_HD-l`M4lej{T-!(KA^w5pqaeAAffiTT~G48y1Kxz7l%{AZ-9 zI^iepmR?udS5AMN1}9rv0V3whFsr`dzFR6J<ZLuJc`guQ#Ci1xRed?frYn`nr?D<K zx5ww)J=t&z;1l|alvT>=hg`%^cHdNM>o1wa|I7#2c;Y52Y5(CL=}dsvF2>Lo?>PID zs2<7Ky>XP#yVC6jPzQxN=J-ioelR{$`NQJ9S=DUf-#oW>3??NqP&aj`8G%-Ojsy0w zCHMdwu#Kv4L5<h1b@R1vI+;RbLzy)xH-7)JWPb{*j^m9Q3NxK>1(Uv#GZWyizOTUa z%cT~%v{4z3O;mh|n{UBJtrJq0YZguSon0}&!E4~ZauD+M_sQI3u=b;_-I6a%rq7C~ z`@AKkUcY~d8$7WZPOSJiCug!N2&TniI`w7h3?+ZMppOZ()+8R8@}IY7IhdVH<8b}Y zzfi3dZ;<8eJhD;GvzNu4rG6;$Oq;T%f3&&NDWQKEbL5M$6PIkdh^H0!_!KM)!~Xg? zorn6Qg6xQPdbGbeutepafS4D;D5T$A{xH(J_&aHld+5D{MZzFS7hOFtGr339X`zlC zWhdwRKI^2;CuQM(OT2#UIy*!n%h_!GlN7%$QSFEE$fixb{bN+l?9cQegq{v~!k#z5 z)r@QWT8WZQAB5SW_^yYta7zAG_JnJr{r{7^^IM{NrQd^wF6`b>1YL#B1W3k(b`OhY zc)OC~y7avd^=YW~6~HsVJpNA3B%VNh7z>ZnluBnVnr8TesGwWQK6$^FN&W&B!vNzi zXtlT58{$#m`u(*^sv^SOZkbTs!QFlaldZXjKlrAm_J~dwdNS3&#kT^`O$uL=n!c&) zpwlwho77Mm(syeDPSG~VhybVhY%1j7^fbelB?5ft_ZdKsTfoJ_XnAxC%op*AwA@<p zY!*wpskDm~^#vBodYRmsG5adNToQDkABnn!ma9e&B&pgMMf{Ai(U8SL^$p9~Q3r5> zZjfR&Q@ur17|-P*YwuyJW+~cq8|s-FApaUnrqg=U_KDP|=4F-zD<HDF^U>wvF!7E% zwbMNbob46r@dw~)M`63)*LtMiCaSCaa=QLR2l2jvi8LYH9?$)so})Fk0>}mDiHV^0 zJm2#SGBeFy-S>L9CzGpJs>Z9<iW<+i;&u${4{Eu%8Jr(lIPE+Cn(94=0oleZw*Ky= z@5WvnY7yY6dg_dlMzx<G6kC0LoTD7V__kT{@EGpSlCSUn`0}`rae>Q~Wwl5n>=War zR`++P>-WCcx*-nZJ$goEzCI;oeYU7A^&LAEBG}VdH)tR^Pu=j;+P7-CgBfBGJXF$9 z3W5<#z{iS`kmWoj4Dq4^@fy8Z*tbsA&#KtZ7?X2PQ6o?FF44&$YW#i9o{=96O%59f zszTw^aeWSQM%gp&KT7WRxFwZR-xOG<#hbHx=}A2nVC1#6rx(e3rnZ}awHetD)F9Tp z)hRz(7?3y991cd50eK?HRK5cz=4LvuTay<^hEM!RZ9!QJk9Ia;%@<=<S6<y{0_;Ig z%FV?RWJZB*s`6|m?aQI%>Q<6FBXJ7I@>lq)l8nW~SQl%o<n8GutR<4^xxPc%+%~fY zI0B}}^PP*Or#FPwWyZ7iv8_^Q&xs$_9zq)C_HO*Ut1d!wC)18tS<s(vt;cJw=h|C3 z(PH{E_ER6Cw6WbJ0Qp7v`+N@`d7l_|a5NkOP?J*mUMWZslp`d>8fB^H&8{V$-p_N( zP`*N~M(lJ=Qp_}Lyu#}X#zx%0yc|;kWSP*olCYiwS^NA&PO&A6qC3?zMySr!sbZ_I zo?g)zzqVJhFYA3F(ZY=Q0jeQ3<qIBaNiC#FQxQ6_T@D%~SVvT&`s4g$mG5ke@3o=6 zZ(rS}T^w>Q(=r{H2PJt@U-cHe`F!KhcPO3u!;MrYoZ(|<(n;>kUFw6J_^lXjGisN_ z3E7)ABRSL=^p_1=_>!G|s@85}rXuX~jU8ME{hO4_GK?*xnAb&#Ljf{`Z`YDuALUd{ z%^f{17a!(`D?nmPB9fV|b%s0fd|K5ypRKvf@t<Kro)z3*OX<_S!6qhyfAa5<=1Sfj zXU)0ih0~ww#8r(g7&)45kn}AqqMI#+L}HU50f?#nPsMFE;BfOa=8@ytODEU?e@Gtf zL;J}_U>eT|qG)QvDpCft11>}<N!lH?Kg_|D@6v`0w@#f78r10<#50|u?!W|sV&Z8j z+7cg(5a=P*0QV33@)$1J1Y-GH5yt+CTLIR(L|g@(orM#_pZ(IIKm+U!*%)xyd-1%2 z->^An$>>-i8^r`=+r#R!^s{kFeKEzpA|)jWy`Uzl#HQTd=Q)CctL#m{sA9t9FFVN$ zU2}YZbly7{of}Ksjb|LkOC0K{N|+<s5BxzW5<AUOwb#{FWh-jnzlq(9FsOxkY_}_5 zO%yWA)w|YI&N^#bNJS*`MK?oJkdeVuI>;5qHclkZPl|2|TF!OL+8}h_vkuN)ozPKD zR#|5ND4rI8_JWP9zJf6Q$Rz`$M?6w9nJun}=woc##0&JW5Y7UE6`DHY$F+D-Hc$iX ze$Y+5@`}=ZHh=8pvqa@0RWbj4@f)V2DcoBX4R`$p3}?8=TnoGCHN`ynpllL-C2J<r zt(zkI@m~ZaIEuqsgRo3o-pTg-auF{eJX>C(CT6*E$1vPO<kgxAygZd9O!P7Rh6vvC zaBA4zl*Ww>2MoE;L<US&Rj=m@luy)9!2hMX3C0#YA`kRws+pPQpdtkcHmxH<#%tJN zoY!Q^9gXKr(5w1t4Jz4C%nJ9<fKA8oN<qus3heO&gB)b|iO8DX)9Q^ZPZ9}1oZD-G zUX8mjy~N4-)5Q-voSg3>%=rnJkOk;SH3&EZU5GW4DtpnTE4N1!Zz1EMu*e6I9G>jL zp+@0%N_=cDyK<T8O1HzV>PqYfPJJaw*HX#;8d{*wxYj{rJ;2@YBQApIG|GWcT9U$x zx-yBykD5s#bgCaXB!5c0i{YC3pzv5INxap(?a4ZX-k6ziRbsb2N;XwY4@3r3+?w8) zW>sNx=gt~dILF7tZErJ*Ux5N3DhiOmjSt;jP}@C0-=v{%S1j>^FHO)oMC<)-#xx&- zF`cUn=jr;v(>c_>EaJZB!bAd?PM~$tX7QGK@O%naIHie?i}>Y;4tb%&L(76x`f)Ks z8%W@<n*kwA99|?7^IU0P@7HRauDVBL^kzUrhm{qgN=zs086pf|niq{_jpzgs5T+Xc zD<S*5qr=kAFyV7w=URVfZ}z}8Z5Fj0tvgmg!RgVAA{e&{q!%_d5mUUV`Orb>%WugR z`kI{}`mPu6g2ap&qG;vb&&rIp7l}<ALFH1fuz9=>&_Y&0c90I?itpQ9R(wN+G4rA+ z{%|TIp-!1(r*qS%)sHd)7mu8YOntNo*y0uk*^F1Vx$c|h`oSSNh=}U`djHj}w_tMu zF`dN9C^#LMo|YLnU6spWPttj0YjneIl-sAm1GvTs+yiz#biajOTFU0U(3q?AhmY9X zK5-+bSQBYX+4^YHWhjDx#>R&r&fMQ$JDz|Y6rq{#S(&JY9yn_Ng9>loz4%J4yOBSP z!6XB9DYQP>EK{n5o(xb1e>wa>E0g%s2Td$c3+if~<x<+2y^`O=1;!M(gBc^VHTlU1 zq70NAukBVrWoo`e|C)=8`9P@D2;9(Wv`_Hd63rX_3EA2qUQ)THhKX*04-?MPwK3mD z!pJsQBsQE@eIaeAu&u*)8752(_K%YQV6YR4X^1}Sfp0peH!~zE3j=T<aAVIHZ6z6& zYqq;HqnJ68@2BT%TBY~3m02bPs>z<&{%QV?&aDG?F2+A6c0r}@i%E{IkfG8!{8#%G zr}O%LG(#vshi4u+9&oh!41H<EdATF%C8ls8Ps<D|^DqE#d4%g9t?~Ui@oR1<;~gOL zh!^vhIN3|gMBN_aJjWPdzyZ*%#bs_DyNpl=!E5q8vm!8S@@t|!RG2ruwj7p-e1J?Z zh--;Wi+Xr14ij0y9V=7sv{Pf&i%aY5{3F72<f@gJ`~=U|8_S!o7TE-&25x0595N!K zNr~af%~|&!$T1+3Ig*D88>KmtkEscCNPuY})_$YwX}}9_s@xIdSIY(oc5G0hNZhlQ zEO2400vYOkTnKpK?#Q;Kn5($l&;3MckFw<eUgZ}YUo!*ARLvlqx+pUAb8Xz`F6+1b zGGa+w@xT@b(#L>q{xh>b87^$`1`y$Y#Ge*a@ZXF~(hnj-Ttv6zG1zG$=|xeY<^W?D zSzT2nHhMEdHYaOw8MnE>^JY){fez1TGR!(azLKp!1(Seif-G=y=A|+`4{UlH1PM0R z;(l@e)e_PlQ}K)N&}OmcE<VZoCxBx@x)?mFz|(4rBQG%}vn;@)F-a7kptC4~<rcjc zGVT(Nc!^ZQ5z!5F^fOnm`BU(ZpS$024xTT_dw8c~@-n2@;!Ij3jo8u>Bh@lRQmt_J zYwd-vxx<>pNU7{xzh-gose%2C!LlX!i*0hs*1|xd0qO1}EK#Sk^(O#3mH^f9$|V;D zA&1&Uk@9r}U5VsQYQio#_h~u$h*Z*DfJi(>-)>@glM6wZGh=mVBQ0Py04z%F!NT+B zU&#qX5=@*ad8nK_dL?;ly#X6h@J&WIwq=B>7h-LE$!+R#lLG`(q%(UQd&gijrG;i< zz1kb3ew$R;&+!H@XfWyM_1~vu-PfkYNRAY|EvzmK$-eL7g1ox>kSL~RGfRF^kYg=_ zHpKF2h{QSW#HXK(%o3g{e;vzG89|&}(ow^SMkcfe>!b!E6sV-!s`JCT`iT)HTnv4` z8IgLF${|K(Ga0a-L`13-UU*PksJ9^AGVr|}LkA1QZBC@~PLiKYlF;3B^48$h368{g zx~k)`e6}*?2*{WiBOYm-&WLQd)0C*2X%PUq=W->F!VtXi%r&x_SU!3<CQQqV^r8VA zQ;at!2*Ln7kZmB@g*LLljE{yO-VuB0Gx%;np^f1cheBu!c4V?;WJY^@78`F@4l`TN z-_}jBsDmw;69Ka3)_xANNrJRMvIvK$*oUm4$tTsAiY@s(?=Oj$7;5u<9)qxkd+J#} z*u2+`O@Io!O9v$0#iF~V1PRMG*8r<8&_?dU)UjP^1qoMG64C@{t#L3Hv1DT$Oo2Xu zCX~uLo9-EV@`bgR(IxHssRCmDaa2kzuQI&ZZ`UOWsJ?J@?U{`)MJ511L7Yxs$~0E- z(m<kw_o&+4M@9|Axa`E@<Oeh-FRT|6{U;F4GRXmT3OuXn`fQEOKWU^k;++EG0CIep z>H|Rza<j;&;8ks+y?Rp+ouq1l^uCqK#>4%HcuNC1&X0@{pIOZku-e7|XrV$Iqr1tQ z;VZ)NpM7$L!*r~DQXr6in}U~^NLmv~y64U;(gY>p5gS|7krq?!8qhOLg54@jnrt<1 zd8&-;)MF7CYX-wE6Vg@=Wt{!AT`WGjXhtXJfwUJaf`C^^F^wf85o|8`yCZJ1#qI`E zjAw)kHYZyh!Q>rIWa*|%B6l(^eL7&!Cn<xE?db0&W;%t^hjpk&V?=^hsnhCVdPu^{ z+o{cyiqkS^nPeWJ4y+BOG+SrqQh2#KAPsR&XV>znGg2Z;Fe5C$A&cA_+hQiip7g3A zDHL;st1`3pZAL0LGIwRDd7JuEya=?e0{EPr{mL*CS8>12G`=M%Y#lz$HzQbYPCRa# zPBtR4K^Jb*c!DfC0GOh4mz@`^be2Xvc8bIG+1!qFWh;+<UD9|z`Bm)f^9W<j97SR> zoJe-mXvhqiNK#s?AgX-(8X<$=ZwF+EKnHK2aY|SOB3Q*f*1it<fvxe?*N*J0i@Fmi z{<uiq;_+;9EaVnM!X%^obB3*{DMU5nb$+J)1i~c)^A^wk?cEar)ucMjtORD{gU!U^ zof&}!bO9+Dq%sprf^X#0a!x1m23n@bNJ+{jb#Nz(vnAt$ubWRIF8`r@E0Emtjp;)H zn~WjEy{-@NO0Xqo_By9-k&<gAzPwgVZY;3VaFZZn9cRni-W}&%3wp=*Hf@U3vlDIf zq3Al>Ei_;bfH1({xhKnYNns*#56BEgFN**iJadEboECVfi8k=+w|JNO?I$nME6%u} zG=U3-)I$lRLcT|JDGiEA9nk*POrwF*ck|`$zP!dJmW4JDBbpN+5yXpLg_`-*G?u!> zf7?hQrzFc;8Ilu_STAQHveuOzD?MR9UaUKbaoJ4E_*X7#-vO17iFXuPdWX%np6DR9 zxE&`a<dQ!Pa}4a3ev#nG_(^*96_)e6E~%~eL1Lv=8~{Kj9Ea;N_l%Q$ae9xDX`V=e zk0w$LNidGSMzpsh7Q`AQ*FNcU`yc|bGStyV6XcMwMx;kJQEpPdGN$rYtm;0ss<FjR zxb=0Y<(sCRLRSA4G=7eSug40JI*1Svclr6(z~`0EUM1NYsli_L<6epCLdk3xBrXDR zuMV+unR!+bd6(QZT@Ia7g)T5o%|;jzJ02Pk*E-Dez%@A+_Lwo#*}})~YBL?YsJkkC z^r-LMD&G5;<qdofUEq7bh)_x7eYGbXt3rS*Kp(<}dMMa4%s}&TYLJ&`LdP=gjJn@Y z#Wg8pOPbjS7YiGs4%DyI-*5YX0tjzG>X0PHR_2v){aU+&SD5+6YysRT8&N)k$}wQL z?|?Wur4QOk^kH9DWKbyNM52=8hYG#tDOij0p=!3Q9tb}U31A8cV9MCbAS2m6F((Q! zao-@e++Y*`IqAY;{D{_cCn1oSV3B?6Zv@OhB>uXCK}$-4B3C`Fx1>7gc8|+wR+Y|| zfYs#!0Y$ySwj8)KP~lZ?O{bRhc~3I71H>7ExXAg13NdKp_C!Wb<bIq<`N)uTryS99 z1?i%aC^E&+FLl3)I(IDkfA;S4t;vVq7W|zMNTY;~)Px#(=v53!=tu_v0ck1%N>xD- zlMo>E&^rdCg9umvMGQ?)EHn|6AJPRx4cM?U>}Nmc>@(MyGc)JiyqLcsSFYUa&RU;u zhWeV04Y^~XF=xhgYa(*t1Cujf0wyZ8?qQobsl}&jcy<Ah7A@r(!`D)3AkN~o`C{YL z5ODmSrTz?Dj0RKPO#h5nwX%Q}+((8|bVo|Wjxyy;W;v}xlCE{!oE1a<Nk>y=eJUO> zf-LD{esZ}m6l?aG?>aX|gnpCkO=Up8=E<IC_a!xYUI{_HoypJhf&!v2CDuF2MwI2x z%*h45kRj+lw9M-6muI?@CnR7Wq>~>la32#hx}BfhUd=zYJ(>bavV5-e0)fHgWbjKj zZAC_%gZu9P37APn=X3+?nR76$oQy<k*l8?1uKk=GoZ=kA{m`7#riANi$#$1+q4tMN zzXU<GI9iM6v2sf0p$TrM*$r{!q#ZRn6UAYNm&ph{8yRwXwbA=S`_2k`W5Ibd0r|Cy z0hA23Db2n}{KbWPL65>8JUgYHK+zAQw)>>%r?IeTe6{TonX=L4907NWqlGqd#gjR5 z5rCRu=%`bLml&t}c!6C>@N;WUclxor$WI?wyHZ*(6}#||ywspZnlJj@2Yix>?1ekI zjBon%3!iK8**%nQ5N$5B$NDrSL^1;F_Q1dE{@i0JK0x{+m@;~v8p3$3n6FSmrhPZv z=X#Ou>IsR#bI7ove(ma$^fI8E=Ecf14wwr2gxnH>b*f4re?ZiZz&>X_NI{@NM<Z4l zwBzl_Q(<+kDKQinG@hQKDVb^lt$5QX@mCE7#sS#w{%1~P{4>Wy{!0^BQNsyNO*BOe zWwBkj=Zb?wL?(e5;HzX#TY7S;2V$XVzzaKeY}D%3k&HA-vOx)i4?3p3m~1yHc8p1T z>_-dK**Wzg`@-qZw?k9H+M&a@d8Nmci{AUsR&#MWtx;ybQ#QV|;Ug&w0Kn4cKRWhB zLNAV*9Df1*lSP@~*{05NowtS>7Uba*$+TC{i-s{hh6g8+lEA>_tKFRYwvid<u4W8* zCiChEF8GU>MbeCtmfv{(xOt}JlDn($ScC5zX98M#GY%6Z^t&6K8m{$mEsXvI@mMqU z>!r;vkGsmA<e;{7OrIU`?Q&r5K;fVxSn6z&v?FXkg%4d$o?g5Z3DEU8xomeXW=u8# z2vP0u4K`+oE}&$oCZ__lB-dIyZ*T0#StmESDAV$qidvkj37z4ayK4j5ab`^}p3Tz) zEs%c}b@Q{*IFpcS7TypkI#Fv|texC*zzD>G?y9T3`l8}`0W|*@$s7|mjoo?_s2=t$ zd?beV;QbAbT<viqL?PStJ3pZec)N~B7H3rroV;xOM9@G3@Y?T7zv=+v$7f4kSrAE` zZ)6u>BEe7*?5N#j3#}mak$}b4bfa^T6*9Rl(xnwpJ$CC<R>RX9c84NVp1S=qVE5!x zi`Ct7y1nkduf1!RnV{SYWUQJ=jybe=dq1d(`PAq1VJLE`_R_J@3jx$!wU_3?4ehg4 zr%_N<U6Gu7mzL#=es>7^M<;SW$eTM=5pVfe6=XK;3UoY+&814`Y7404udbylHe19A zOEcs{1RdHS=tpSNvvGlui^|hS4achYCW7Pb1z7=_KWW)+daq|EqXd0NvQ5?sl5$K; z#7hg(q4?<<<LyRzMIHhh%R0_|b}H*~v~O4SiMNX}j==tNQwUYiDtmoc0If@M0QRDa z%Lq5sY7U*Q0AXI3H_*QYs-2YVOefSVLf+-pWP&r~&#l(j0FtF}xA0<$bzTJG<ri$d zXOsZT$oSOH@%(Eps}+r;rlg>pJ<>6i7B#5`-uQVNBY=|!KJL`0StE!yc^xd6E9fxP zZk6yW);+kz#^~Fu45)qcRD3jb#j^55E9H^?U-snVDt&PQyRMRSS%g|rY?O=2^~Hj1 zt6c3N37hRF_p2IOo?nh2)h^#hDddeG%(}M{IG*=CP7iuT+7cVC%sV)%f*%AKvYd{U zm<f~hrFlFY4Yq~3rv#9X`N>B7^@<G!;2R(kXuoSO=$Y;me#!<|s)~cD9`d!trnh8e zgotO{ixxa9b1iRz*!yyK=fO|yKf2Qb{H+Yr4hLGc&qs?Zt41&@dEVRlm#);FkUAU` zZh(w9Iw9jX#B#cIUnOo=cAc4<e56bW&tV$Y>O3l2*&0^+yyjeNI<~AJ8lh}@<ccnl zOzqa6c2$kdo-YV%>+#)+yZ0k)v&1zTIPAi6mkJS!yi*!<XDa*hr>DeR_g*UR#AxV8 z>+iZ>S)XC1vO)llZbnF6^|Sur_v4mhss-K?mgi!{SEj69=spV<6Tqu>>73>5L}cX~ z-Dj_EUHP#g8qRAJ&ILSwCt(XDeb^`v{Fb}#;=avD_?ap9a(KFd5rU<0oXVTh{p}13 zU#r&n8Ak%d+^T#`<uMExfYH!G)Lz+&l)hbcy+)+`2)v!9Xo`tmP95;TgiETZ<p4k= zAottOZ?@zGfepPEJtPNQg_(1Y2iLk<Q$-5^Nrk&ws0(6R@e4gdmW*{x4@2im=-xnB zb^YOwHyFO3P$$aoVIO_;JePS&*RF10f>)~SaVW}Yq{soAdW3<d^URH<>F&_2oR;Ye zaS+Yl0o*pRnn!%aNI+;_nMWj!+BzUBVnI(mqPLq_)GM!uA@tctYs(86<`9HXsgeX9 z>96#W_YQQc)VP3)*EdL5ms|9G&%Ge=j5x^kCqx0u*Z@pQI=w3HGuGNtAoQdYebqR= z_AD(a>q&y5?sc!CgBL-(vuNMxNiBV$yGJit*&ZdhRU>RoW%=SgAqpYuQZC&D5{Stp zMT<OjF??=0q_#eyK}|g_<Wh#Ej_ChU9xuWNF}Zx{pk}u^V00yUw;8EhKCBvJm~Tk4 zJ*xE6B8~f{+L0@sbcn^R!^94%+`#SS!#h2i?t99mP>YNy{f6holeg>Vy($SJTdm~R z)7IyMM@J88GqDBgM?{Z4)9f$3b{tC+WitGMg8_B~Cd=v7doSAt=p9G@YShOqWlx#O z@%Fqst)6LO#Q6{pA<TXN<_0(Z2pE-p^dlDI?#6KAz-MIQg<ZYwEKG%VzOZd8tPf*A z9g!`w!=0oC`4()D=;wl0)z>YL2zvo+^TN@On^c<K)Cr>+_xdz~;_u9DJ054m73Kxq zcVTDYK`_qn@FWRF@`pf=CX|5bs>BCuXu#oWlyzi#l@;QH`@1@Xnj}@E`$`k>T8j|b z_B*Z1ML@4FF1t<P?!5%iIDyd)(W7Nz&hxtje2q;@UTt+7mHIFe_*wmvWj<eCwPvF5 zLE#NIl*oGa$)~US4HSY74)uh&{|%e*Xuar1R#2S!Qp?arE#Cs9SH$ZB`j98;?n`Q{ zIZZ7M@Tpo#?3X9MA?!Kxh2QlM(9JCl!GzzY4N-ZXDRd~jVxss~x<^WHQ_P-HvY%MK z8o{SsHxcsjOWsx>XAV;z{w(zwCuoPFE|L7ABwfEMG-g`<jaF1<(W6_5suo;2_K%i( z*vi3=L1-o+^p&@5LSPc2wDW{|(z`2OV$Tv&>LtKH&YQnKTvbLj0z*AFY7>&4Wn(^- z3qP9!d>8`u$N&-18=FUS)}L1BPl3*jqa3fkR)TWn&j=wcKKe4^OEta{1Z3@NS;nEY z>$kHbe8Yq~6eLfWX0~1Yz=&Y2h$n<t9~YhE`L5;B%`-PuHK7)e>_eETv$jyu265T2 zmR}D1-Pi9%KFb>8G?~BD1TD$?2X*<Ng=zZn4A#DXSUchCn=8CzRTU6tT-p7%fB&)x zf1I;`*6XhOf9a+v)u?~6j$xK&)2V~T8I}R^E_#P59t3q9woxAPEhpEwKe)oq&9A68 zJUc7;*f~4;(@*2E9dB;6@i$VUMS{0BXb>bnnd^J`JE_8FglLfa$f2%P%OjU`&6^m$ z9rN>%=ja2X0y|YT8AA0ao(Fc)$V{DJg%|I`Ji9Vug)YT!D+S)0gYy>t(K;w3mOS|* z`yOda4~gQQ$eKHw$nTOF<})59IXmT7en{`17vZA47h#quKqGGhU8{Rh=Mie8z-DP} zFJ)w3<g$R3K1py&zpD<T-5ny=r~d)_yXHOR=cGZMbjGpKEwvj(FN^O<@}1}=@T$?@ zO<uwL85;Hd6F#q|Go<$-=<sgZ^`%#e*R)T#;cx8SkDYntz=MYMQ#jb)fJ~Flz}bWo zVbKu|Bg-f$bxswrfrwm#hks7Zwf_qHeD0LoKd#nTJTP>e`*L`aq^oB5V%D{56Df9D zFitJ7##6W7>SzwLEHfO~p~FJ>cd9qsFJ6mSJ}z@E87cfj0?X~d{6WyrL&J*}iCP5& zYZhUgJ0ok})i70d9Q2nH|IG*)`1{(?LvM-Ujt_FHt}TJo+6Q)>1{AyV;Q|&0lGOsn z`)@_{Xo#}xi7d{8*(N%~#i*8pcXGN}kEC|n8;GoI?*Pef7yeY36sW?8-%aO|o;QM} znT{us7+xZ6!m6fJj1N@_Qq}&9aH4L2*~s;)4l^(z9ojT^AHIBj9?)ahbEdp;C0k*H zI7r=&k~Xi-&Qr0Fw>9U-tg#TuRf5tUM)oJf)M+phf;Sj<-%MV>mJJ&hR1W^*_n4o% zM3*M}o3mPZMrqN!b?!K6eqhA8g75A!p?0v@aKJ|kjS&d4GhA5d@i%hIL}E$YjUa6Z zd7n`lYs5zkk!|=P*>{69p>>^fn<JhZtT&6?U6VEXIb;&aVa81%J{@Ef?n@d;E)YC9 z9;1BDcTjr|OIU9%)kwJ#vHm8VG}Ao-Tw}%D7-C$K<c_b7*MmNOW=(7tIk?D%DJo1} z`lss(Ov8tuuuUTVgv6;Y+7t!5w3kdCz4ov$>GE%|EEa-N8#2Mwnx70D;RMcYq~Jqe ztIt1D>ZJ;ALrydWTQ>&%KDc|XZ6T;n5<a+k*+kTJpjEgZoA_N@|EG%Z#l^KPwRkD` zXqvC<#>z3pWZ&K-Qyi6OPbH<i5t>;hY!h*&3W?Q(pFG8OdbVh4Db}Ar%#=5%I@t&F zChFG2HXS;#N3<2FcSJum`9g<~>@UoTnEWgyi42+~IJ3foJ$Lpch}Oc8lM{wDUdnXp zLo5WWkrkwptc6<}RUf!=r{0O2>Sjzr7QJ>|tta3HP3Eo6tMhT*@Q!gW^q`i8a1RKw z`{xf~&LU)W7gu5ihBgcX05L$eU$()>3wRn#bP7(~TqGn=LkjA1d>v)t*8Ck#Ta^q- zI;;`sYcWMqdVk6<KCjcKai%s=6|D<@Py(uVo~DX{z?}^)to6||4HN{Y!{Lh4KT9$o zti$sZ0=nPyDN(<dBhI5Zf@}`7%StEMVR(WPy;ANm2NZ_JBvz@f)Ei0G!)Z~en3|#l zhX!wb+Lu46Mox9@{DXg9vIs1W^@(HZ<KP2dn~2&U82SoHTYhE9etHRWMq!$CLSw^_ z#o;1fO|n+<z^;3rb<LVwHyV{CN|I}w4*v3AFRl|8#X$}y<d$g{VIzZ7bW7+9UWMS< ze6Xx4-Wo6@sL@Bilr&H-3|mi*CS7PM)|jF9Y~<R|v`H2<i6!o+K}|K9z4p*$Z4t>u zFmYZie|<CAmrpji<|}F|cDJ5bvgY%2<8|!wT1AT><7Ovo)(z~?@z634`$j_CyHoYz zSAJ{~riZ#{Q&r+~q4qDTJV7oDTI1xFVu4kw*;MP~mXmee<cE!uiDHZydHp^P)9}#X zuP(RqAkQV0QWaFKLIyPUQeocjt>)KBZu>3mM)2OEWO4P^uG7z@=1*%w@O*#fECAUO zg)m^8TdbF*6i#hlP$iKE|60Gh9V-67c-zsx*rmn`_&}7Cm(Ug(G!0fu{OUEBSo#8{ zYQt<9w&fvWH=gKU^EDniswiIK9th}?2~P)El$P8pFd`1tY%6+693=6SqB=cLrN23r zH-A?{y^RFn{NhrQ;;!PGr80ReW2^8-<p4~>`!*LK31MM;(wQX26JvGa#w>xcc5PGg zHF(%yXnP9>cDGj#eavBed+_C@ViT`2jK4XxfO;MKA*KhcM5i25gDAQ=j`y8SP=Sb# zTl?CprOka9YxV~`iBorrjB)!X7$4QII6H~%fu)}g)vrwoIURon(^%yHIOd&ghT?uh z^;$JP=cKkw5Mpf&sb#-R9xclD3*ShMV#xV09wtba)KTNOSSq&%=E`1f7oj37Kh->- z_P%bjYAp4hZzRQOT&W!Vq*3YV^wB%*k(D~ls!ToA=()loSPs%(&z7}x6ZLYsxgLiw zOBkG<%NV21HHUwE6MA!gwRw6@jhvPA+LRQ_i0~>@)G#dnx$LQAOaR=#(*EY*La#m> zhrTnWozPWLKJPaCQ_OIh=ofg?(K>lxZ;*g0$*m(A(}{c3_YrBT=hDE>+GShyA{=!; zKDd+(&B!6HnTr*ct$FW<9qx1dXhzz%oN*l*Cd?}l-98i#j|tJ#EhE=b6-YnN_y717 zh_7k4lk5=F^yZ5{3AP7FxOQ{r9Rkoq08*}YL<Qe??I(Unat|y*azCUq9R7EX`BlrQ zQ6Z0uES`i&%;Jc<Q;7Rb(B9xMA%AQfC?-4wsdGQOwo@a5j3#z-m3Bf7J)FK2t!<ad zzDoA$6M3!4Nj|3W`qEi#<%f@~+LN;P)Jkrc?>&mPntiV%6A3;-bNVM0v?BImk)|Tq ztoF3vy|hsE0p5pu{%W}M+=P#vZpTF%^URMW$cc`rY|i-kQ(*f{LWQ(}>ePGSJz<sr z`1=F&LCvJOx19TAWfE8f0_uaW-1_Er_)xWGH}!Y4qv`w3?8t!@c1c6UfGDo;yRE1R zs>9`+XhVU{YeKTxf=Xf<u@S~WL`gh5=UvH#-&z1;eM%H@!lcH5@w4s2dC%p839Q7S zfaxTQ8h>m|UUqFgF(g^<eJ3Hr!o)M%&|t{KXU)4bhzJ`L@mV!Nxi{T;#aY*8y?D%o z6A=1hengWNv!v{(Lz@ZyY-L?b5?%JN8aiJx==ypq#@8y}e%RT76x;i`<||3P9fa42 zag0|X!q7@dP)@D1_D#w2dNeHvxj{oOa8^^<@sYAVN#-ftw6*$Z&vUEZK?C`Y_F)RY z{HRFH{*3Z?(<kBQp2Q*ROT-FeT6PGhc)^8$4q~htn8ZH#InfM6cG4fL4S9Z9W4N0% zsyx0k0ADEv&wzz~G#NbVREtaxEq@h2CO+PVo7$(eh|DZia+pOAih5lLv7;G_JtE); zm((EZZ67>k9~m}sl3_{41`w@w5uZWtpL!*!_XZSLoq@?`6<7oQ^<3l4w^yj^N!cYx z5dF37xj&a)nMQJ$hP)!2HfRVh_6}A%m(!Ka8f0<eFYV)r(}NLzJ#JX=sa<pP<WD!8 z@UHl+bLI4RhpVJRFOMIvviC8MPA%PFXm{I*-614&AxGX(%O}nW6dIRs_`JfqyxZO$ z-A`hCl~CUMMnsdM9u}y#P@hW?RBuyNO1Ks$;&_jyXtI+2xw{9yl5Ohw+z@7S*jBsf z7<99}nS<>?Wa}%P6*VSVX*S#<kW~#fZj@eqt@^UOE}_!*;^a`%xyzOD-lZHD9XSCj zntFa=-48WVu0i!L(&N}9NF$zT%93RfjHU;hNcqS@?qY=AcMIr+)bf+R<vt6|SVMtu z9a@Y6?OveK<;GF{NF%2W>nyjpU`?7tcYLkuX&Y-YB99Ci^%<{w=Kaf6Zk8acOOkDj z5wuKAER(3t%m^W`)Rezm=LEQ3*~bfP-_)UP@h2l*#wzz*Aflg!r~VpTK6jk4&l(cK zJH;RrANappPQ~e7KF*Oupd~Ykh*jT@ONM~@;;RC06hGI>o7*)|Zjn1AnAt--dMqxz zIOs=_|LPE}Yta37?`*R3?If2OfaCTiQMZ~~P%n?8ipGB}%`L~{jgacHFaFK+HNFBj z@+mJATjv?wyVd0WWt!2!-!C=*JQx@*(cXy5aw{Pk$0nKm)giGj17y_~3oo*Z#b3w| zDPER7Ou4TMZ?Opi@sAMXo+TX3rJ8Gq1Yfrp%CODy<lsN@@wLX*3y$HokfXGft(C)3 zHCHp$bq5F=&u^&?-AqvJe)PkH>F|ql=~U3c^pUJI&h7UOtcIr-=y*K)wV(eWR5^=V z#}(51J@c8+OXBeDEB}}bp(O{iCl0SI8k>xAn6`&5HpE=I*>(Qa^~>9~Z(n(Lk^0xy zZvCWHVB@GU+Eg1TaJ?0*T5{!|h%_~`WS%Zaco_9L(kZZMVKw^qrU9f}XXxTc!?y?+ z>b(VW%S7_DIWaQH?a5K2+XlN2D1>>!J!?UmRch*^tH5p0W%nO1v`z64lp(|4JPFFL z=+?~$Ag1zREDH>C11&Q6=Q?6exBp|2vIyJV6$R!EbCjIxefCD>ZO&`DKPoWFKah0{ zqSoa{ALrs>@~}JxI&$8)(#o~D{8+m=S%#CME)3(VWJSOCmwkD!a6jx7k>j6L@w(=) zxv~aJ9!Wv;v1V$p&9H)AsGHBNi#zKt?;DVfvyb24w1(z=S}20O%yLcWjtm;f!F>KI zs$l~N;5p=BxFl!O2uryY-OX1OJ?FqXv)XYZ9<oX7KF&sOjo7nqtW#mJdRqnmyy^O< z=&|6Ukg9vlqepeW%Hw0+y^y(-4}I{y2?zrZ%Gp<5zWC|VT-|38bOk>}%GxlF+4JrT z@E(6Pg3jxEZ*qNJGh96r-FvaUsm8Vs)O4#2eH6B8Tae_|!JBhjV^h5!uDtsE!6gXs z$xTY;L<1r1(OjDl1)P7{v_|Zg)3C6YDYWWYg7!hdayiKPZnNM1_9(_5_j|pPGOlbj z8WXPOa?|b!jF~~P*4nN2n!J~dcHd|YYr|GPb+Idd+Qg5WyQ|hH9nW21iH;CLx<1pZ z6ikP}Akp|_$w!NpR>Go4vgE@!Ejk6jTQ^q5zV5lDqR(HqS?B@A$pe@@vBm;L4z~IP z{h*@y7#Jnk8L4UVxVus5+glb+ckG>+XTIb%)B<k88+ANZH(q*V&?~5Ds64D6eIa}v zCCx3^S;tT9hO;Uz2#sycoR;exD>UHRiXl0R(7rLfL*XZxL=ES)LdQGmujVW2-?WVm zKGn@_j9EGe>M>yYyAc2~+7F^AVgYRAP}6v27I;6>vDAw01uMA>EpuN;MRq<Hv__X| z0}GH&x8ojo_#!{W-fJ9BDN34M&6iNb;;4ZN>|qz^6TY?5XTBp9QNINUOkv5A0Q5DE z86~ZcexVmCV*EuKbJazDc2p7r&X%r6kCZ8p(>d?e<=<XaF(`D<mckM|Y-i%OZoS~? zK>I7z3b*EPkWZU7O|%_9dcIjUjtN4&R+Rc^8Dur`!AGKzBE@C<$euE;r6l!p+ib1? z7?2)SKO4Zmu?y_72xv>qyPd0}HaB0Mr3TmIZd{rLDZiKuIN=%rN?5SJ1rcDNQ-f9y zy^DC`AVY5_a5YyqCH=nKP#OK)`CWx>(0<OvV2TTCfZ+(nD*%qO+zK%V#nj+pFPCc7 zB1&L&UN^-uXW<H|uB!aw=p!2`&xd|jPh6E4iSIzeHFOw~jf-L&Q9fsxsk-ry2(%~+ zFM?2Fg#K<+aW8%Q_lY|f&jnfFhIIxOTUht(D+xVP?E|!<;TZvpWMBUIPi#WTS;!)i ztTU=kS7;IW*iLvpmcyZqB3E(xAC?y%ohp&*8a_0{2{|(ox0QQcV=X83H6j2w=agau zVe%A=ie)&RWOzij+uRg`$p=;+cCHA#<Q}_XAKhL2ff<0_4tdP^ee#jP$6UPT56kc( z?9jD?Mq<t+SYnY&br848d%SVK{~81gS)FKbVs{J5gjtB*&m0ggV<h8$l94oB<xGy{ zWKp>GBkE#+Z7^I)G2o0G?`uViTSC@bY%x3E^)-dm*TZ-c^Jdahe^E_B>aE?p+?2?E zw2<j~3gV7koOw0!tprT{T$Gke<3QnV&+rd5B~;4;?ZEJYbt44=VKf}-mioBP!9~e5 z_W6{N4w?dh8A(ZvEc<Qd6O*ukyP>{R3`lPDfk?j7C9|=zdp4`@1Xe|K-415|qb28Y zik1%Q1=rs`=2M;j+}vrM<tL@L88p2!L~&b3bHe)NJDb$F{&Iz0F>1PN8I1Dr&p{h0 z)FqJM_iXuTg&=0~q5WIuUF-f@`hwzyV}a&ELG{AslQyY%4it&T@aOuu&1F*m<lxE} z8TnMm8p99HJS+CavNPJ#-QxT(zzh%&<{_(d5;6etlyMz9%;Ak_>5WpIo1E3j*g$^I zZVeC3W&(#Yp;<7WJa`p~v3EOE?v>ts)`lQNc@cuALR+nLKzq)T_jiR-Mz2eKkxf1I zOaYOBSmkMt8(v3D*7ii^8(z~s9$;*q?iSt_1ff_ojKYtviPQ@hR@$`o@=ulUlB&n< zoU^xIPH9VLfsU$u2$|TL{tQB%wtlmHoC9B5>nyJiRz7OHC~@M)!1sHh0v0O4&TtC1 zl54>6<S3)$eRUNZ>yEgCz7*XR;oKN_&xSgzo=IeYUlkAN_V~N16I8!LI?)Z~XOhi( zQJ+6P;ru29gW8rmau~mmed#Vw)W<WzpW=X_OVG0f?i*t-&!fGOfFtK*igrk#a7Ua) z!M&LhY_3IPUiXlCwom%EqlP2yX7CiGh+t_?HL9!odSSm0e|~Qf`Wg=zMu$Cp{QxO@ zPOu1HFu|2xuyV&7p)=IFVxe;|<u5SgG)xT@d7xO^eb~=J^|mMwUYPmh;)Pfu?}~J_ z$SU<V*vb>>!Xs5fKk1e^nksX4a>&07qn1@}5#qxTPXH#P#$YCXfil4<;?67b&8k0R zGdA}H^d{y=$>;4yQ4z`1S<s#$Gol~KYo-g}c<}0zlW1xMpE;HrFrOHZ_l|g@IH){S zB`i?WUNeLCT>sX?BL;}`$?9-m%msCD6etQJ4*pRtC0NGa6^{iz_={Q0a)rjqg%*{z zP=#y#QOngX=rB(j;#1ijpU<*$!ZOwxT!EH!yEODsauU8aAUs#%el%#d+c1q|;44qX zno`<nDV`d>XuEXuoBr@IVz>ZzN7l=bb2Z5E1V#`rhTZkIItq390Kf?7BPeqw*^6-# z!jxF)J~Z}IHnJk@j8H4^PF4hDZ~;l<MraYl5dz6-By)r_)_Q<154y}Byw4BTB4H5y zsitfYU$_&@yZiBm%ehK6zgLn3WPlB*1@c56vA$=_^MF@$;b6C1DuAxxC?fbwarfin z<ZK`sC`zl$Wvj!_ov}Au6OWQFHg|ltM`lXsiOxM$WI$amCT&!~t8`$3=`31uLBN*G z=VgUcJ*RC0kjGmu_7UCI_@s^|iQW^1=@vLgq(S&R+19VOuDzYmZQ_u8V|^Y_Llppf z&1jQxia8zqn5L@*koG|Q0wUxy3D<RBTwZuK_`>G5t&3%~;Hdx-qTL49FG$#U;s0V3 zCR^_p@XCym<*+2^LivHWL}RlJM+w4#0hbUA^lGz<Ee>#I+wVIyNIM~knFROw%xC)Q zoH5%GA;VBe;KJ<9Ix~N0m_O9VAIjkmCXoMfE%VMWc@oVfYZ~89_G@l%M29%}CAMH} zG2L6sXm&H2)GwG9ih-#HVe1eLxZevlyS#x9#HqbcoNk4j<RNcz9IW~GI59ZjSvnia zLFVEeke*f1AAO2u-Q)>dgNzY!?47vbQT$EFTX?XrgVQE9i(fRu&loHc3X|Q#<$(d% z)8?A>00|aFYRFuQD`^^=JFpta&7&oJ{M<~t1A3aVFnb!){zO=(MHf*o{X7D?dh;(C z54X-q;R1{Lm>=Q-%YgBcje*vu_(iL=#8tV0{<<h}tCeXm{@2rBafUN`Vad<4y>l9a zYUz-C7S)4_;^C)?zu2kW<&e%^m&D8J`!@!Rw@dA4$$X8H`OzWsXGaF4jpmF-!=pO} zB2^ID7~yElAs4ere$VYjj6$@ma;NO!Wf8ubtmjH+>XXj$1`+)yWG$lQZCqr_L;3Hr zG2<=rUY!cQ(HNQP*FT4TJ6uOEMo9@inevNPitkjaj*_tEkyCo1l-7yO>J;a+#pXmS zmv$<*<Vsa)t5nOOf&WsiECD{?4aEEZUbRY60M}yqlc!i&U>zSAZnx&YRI6fK(31+A zTlLTWrCL3{)$rmPJ_#Z9g#Ea!2<HL8ItSAFGeH9WFkE5d%NEaDq5oE`2GgbN?zVa{ z3007|YF&(2F`<Hx9I%>PYNT9*n2)@B^X)@22U7aqsuffW^zxGyMb(dlP#GId7mByw zYIkz)c=v)y%#c2M@Al?Yt;DaRJ5+za<g63dVpZCAko6pOE*8)3cYS)xN<zvw^tNw} z-!9fJloC{VyF7l~?wZ4cdtcwrB6U)2Om1=J%?)Pk%Q*J+{`kBxRc_DrdGPBydu8mJ z<HNo`2ddTkw=W((yjt<%{I|Dch)BpH1*W($#R*o~SWH4$VwY$_9wAG~V*jC9NnY4k zN=2s}s8;etA<Jpl`o`sSwYwY38MsF!3|{S-kd-XM^~RNK({CFq2db6wDuX0)pjufg zHm&B_>u;{+J6S5P6}WkvSu6BB)wEXR^KaE^y(GBk%z9}^ebahb_}$I*^2kTZ?<!(v z&b+IPTW@;zZ`F!RWrIl*3EilsD>iS`Wa|Gn)vCZFbhEDHRP$zi#eb?+DqD@UMWO$b zYSnssCiMM{?*CM+w%*@lajE{lQLVZbQ~sN3wNc;l@jq27_9N9#y<cX+{!_K;`~B_x zf2dY!Y!*Z`oZSyoYGn^_8*H-&QC4a@Lqf;GcZS7Ix9&WWytutHf=*T29hEN*-+hd2 zXx)9H*0sGmh8t1){8aZ<_~&Pa?^-`UH~qf-`9QT&|1wSzJ^N+CTIt4@Nqd72U#6U_ z)W1%<9XtE=rRV7zUuS$Se)#(8K(+cd8(jP^)#}E#*9WTAw>Ob77B=&-C*lz*pbD4o z3kl!%KYV{nhHC6B(nQbgEzyZ3Bck#08ZD}zggo2+nfaQumFBG*>DWpL&bFT&e)hS3 zNipwrqh$!-c(}f+Z`lx3vhs6Vp-K>Mbg;@d$$z{3(S&|?FzDB(1Jx>F^A=>>1`Ez5 zJlVN&REOtZs#WU~pSQ=9=Zj^>vDd=>m#Wn@rqI-zn-3#@ZvTgBB_v=7{+DVMvSr8w z3(MW-{C`xf9JYln=~N?pYYaS4kZ9G`6MB%m`_)XRh{~i)yea?S&#y}=wRnuee*Hl= zU_KCC6z9jc)=)&@exdZ7<E^s1Gtbr00Up8uu>%Iu6`toHng!E8L!#3y+^&oNETJBP zxMTp>iHt~H`sXJb*_wMS84weqJ|H^s<<5cNWJm<u{0p_#pP?2aiJ;oW93LlwaFtH5 z%t$dlilzY^l}!J<P9N11^3VO-&8gsGcyNOnh2fb_!yLJYAd(03uLa9%T6#UPp=tsN z<Y5W3Lv~l6<`vutKCur5?pMsapxYQ0LJ9p)zi*Rbx4GAUPU0Bn_vBN}QK_<(UVzLr zv0&ksv`n3{8J6WQ0K!AP?~!>u6L*ne_(A=HHpJ0dcFAh5pST}>e^eQ^D&^P;M?jZf z7|jmmhXDl8xh1|ZYd-NZ?7;=JQpc^_=jdf?rh^X_MNHt}@nWYcBJdn>tpPmoaWqAH z%=2^)N6EMC2k%Nz02W7(Si{!ic?OU~d!o!P17b>YI+#-s>&pDA>_)73s6*z`OZ3ND zIYv%)5P#lgEKTos2VFB<jxS?+M9#Epdgls<M79{+esGkx#ObS08#zG4b%!o163AaR z`$%a?YwTEo`{k>oQ3YRuvpc>siz7Z+Q5plc4XHuBVL&uD4n2FA?kEj~W9=+4=^o?D zs8rUF5?3@_GG+O820i&m{SK_q+auu<4kq;b5J27+@DRS?IgCLE!0p7$Gum*;%H8iw zZB1)X=MIV*#-OLKY@N~@x`!0dQFMDrNV0P+DJZPp_MM;Obx5^(fE9(X>2eGmPNpG~ z=!B0^cSV~0hw%@>%&?gl#kB{J5GXj!{dQn>!=m59`ent^&cKQ<Qo@q+h(71`8sYoN z7Um91uM8g92*LeCPRAg<J=>Sm!8XGbD}D<|`59p_KZjCY@sbN?Kic^y{IoL&F&+&b zV%R0Cu#N>9)M0q6bfYp1Uh+2O6${stXvjl$Q-H-~fg2$fhMSNKN!~fvj`KEYGU0yK zPC7tp$S}EBpJ&PU2X1}5)mD7l-^1EqU*J5BpxBNAynDgI4I4WZLz%UpDlgN;jNNla zJ2Z0$GYS;KS#{j|wkJwQw`+0u+DX%Nk9M#?cOyhd%{hfK&l6E4xLYf1h?w6J5r~43 zWoFSRkI2|*A=6VT8s>ECSPDPn%(-8)6CR$&Aqj2znwX)nz!N8M4@<c58j#L(A=}B> zTHX@{bz^XhKS7{U5oS?+rSF$ZaC2b_PF`|?Wa_glESIR?HKmlQrPe*l57JkKX}zXG zqTake_tswqyzPYo3xs;@zN1>B&cC~y5QwJOcxq)>bDIbz!^qcf>C7bE=Y9oZ;DK05 zPGsxg!GP6o_cxnMC$feoWnb(@qq<q&_+t#r4#wiC<u{>cc4UQiKq}Adgce=<B-J#% zhmU?0Mr)nyuViyzU^`r<tLmmTtVlrdT}+-r`$Z5cNpksUpbI%d<PLfWU8J_ta2op7 zozKg7oZ>~RO~Q<18q05?8R~fgAI>x^7!6SPl6>TVME!fO9!vQC5tju{&dMqqrho5s z{Uq_5JUA2dcMTx>U>MsU(Ccivb}d0j<U;Qcc6A0IX}$!8ClGP`WCKsx<r`c)nibip zmoomI-rTrMvdtveB`ovMVE7MpZSRKgKfd8rp@y&jGSpkZ0yO_588CC9P$orWRP(i1 z?;=XSB~YYD?83g4;6HKw2fZ3*d*U~KPVTd;l>({dNBG`F;3E`$9uE4ZT=YD}x?l+f z!UdX&T%uwSRm`yWBiLQ$DWw_*C?<lz=E}ie=wK#NCSu?ry5M$H_<E?F6)X>b1vGk! ztC;dA={&d}#6jUJJ{?i(@0p8(dFY{-r>I}1D1T4E8EAOydT8}2ihi7#bLy1{9CZ2) z7ijSqrxn@U(9Bp5<=h1?(S^1FmlI}aUpQ=-Y<Rdo4ZH(49SZT>FiR0OVx`7`s}c5w zDceDw*U<1V(uHu(BfQ_>N$4xlbaG6$*||L~M;6@f8?3lJ<Z_AG3y+k?iYTfzJ-Jb7 zdEZ@x{Y^gTc3kdfSi~Zf!8n`MXm*J!DG7hz_`~B+)N;Dg2ANtZYtcG>yu=^DSd4vF zpIWz}s6MLvJjTC8#ArYifEs2zTXy`3v&To<KhH<pLBSpI>3w4AvnXJ7kxUKX%@vbY zcyzc1g}gG(+0zaOx--X@c_WUAHO5`=9XTBJ66zGmUCs<@K&31+s_g=PgJNdSR}dYG zu-7m|4FmDQmHO%6hBq02@@HFu&FUhNX8>pyGspLP4hsx&c1G<g<$M+kJgCg}j2|5Q zL$=`&bvQEboT@|!s`<2h${lzQ04-!AetROyZ>L~NRi_tuxMA`sx>mLO?Tp#4dF4X+ zJ$ZnfGRmS@zC0FD9Z5F*k!KdK%E16Q&>)XRz6CtPDzCt!sQ}kgaEp4?I=axWw9xy9 z3Y*Qd%;I(Qls^$)c-S?=4SskUb$km|Y@b*3XHRF!(CkjPeC%e90Y}6~yxCQoT-(m# zBOH7qIM|=5qDxQ(+NKU<lUMIh(dmhNKV{u*RB7HB5rZ>@=L$+kZj}~1F0T4fT4_{P zA73V=4G`Im?9{SHK>%c;tj)%>-3YacD}R-5+YLWV?J0jaSlD-{V&IHsmr=!#PVOTc z)7tALk2j5X8_J)}853E?WYNlpgB3GrMv<kJ^K+F)LtuB_Rc7x`!Iwy|lPF{*KwF+O zxCvC<?W#%(s$!=ZB??!G8D6sr1fWbHV7k0gAi*W|nsanf^)9>^cM{wzFT~{AV`tWP zTEGzs7k?<9j3n_tk%!_@C27iWPF%f_@bB@}1Of;^$9`k;%=XAx6xCE!SIIt+gWyr? zxB}Bj-oK?{BH}>JVvXh{xpw7Pl1pBF?&-tE@?YD_4y2$~BGVY0W${`-M;`muiLcNf zbp@SS6&-h|k<Y$aX`9Jwd>+6*DU<kF>n>ZHsO<=Mt~m8Xe+pK9$Qb4Ox;~T$I%L&w zWr~vv58}X~rg7DA_fQ5ZdIw0`G#+$897q#y4Bx-b`_8Gc)W3lM4IF>m7#w8sZIQ3= zbW_9%Plc_)qDAF3<K|iw<@PxqEsy3iD?sz><~9Vj@MrU>!Gz9G{SNPzKsl2mw3gFJ zb-m*H@5gy}*e$1Ycn57;gJO8ce*k>s)}X1@=i)aey^Zq#q^a=@=RsfF<QrZ=oW1@h z=Mi#M_moS8m`hJ&$(P!E^8t9IGSlhgR+(I@t#XdoO-&a#7<Ur{9DL@yF$ip+<#{j# zS%c2_W-D8>1vDOf_3)r?i<!_C-Az_4A2VtO#ruwZGjY<FKSK_T2mgHCVINa2>W=zQ z<{+D)8-7XoSV^a*Hk?)~{lTC2eftHzeSw<46i<yY0XDn%uM^yejGAQ^XKF{mT-r^_ z1y&Y$LhezI9>?mH+%|Nn=f8*i%D%0##3j5M8*gA=iEnYqz}q)>1gL6}-lIM3bh8++ zyC~o@gU3YTj@97Zvl76r0g6rLjc;jdU~__(4w#a=COUj2!#qJv#%~wNN$KX)_cAjm zKsQu3MU{7h*;RPI3wl4odWyHO#bIr+r!&6IO;tzfGU^kvr)JmamG@l^?d;a~Is>S> zlgKs;Ilf(#@%1rm3FEqlQytj+{!J6iveT`sF)Tv}Sg=Hv;Sj70o#D&6A6PX7+OYdL zWU(B|=$;O|;I76m#I5n({`4_jLy5lC<9*+v5YSV7Tlf2}?ie-Uj9SL}a525R<vNzC zsOz(xUw`Q&qv4HA+OPXMSP`L{%v+#VT<asj@5fQX7g=CePUGr2jt;J5atLn%t`~I% z#6n&}pE2O4zII1-wX+P8?#UWQJ{imyBMKrj>B<TH8ai>Opo6*xha3_HPjz;43ZeeD z<GCETR}2&UiY1^7QDmXWtHb{to&I0MbK3%pn1e=gu%uSaf5da`gHV6x|015xF*R8b z&mF>2e(^z;haJMhxG`>$kL$vATmMh-T<IhJyQVHh(*w<ecyHs{0M{>QZSKDHKg4sG z#Qv4)*G&VD&br>?1<q?s9h6L*{)c!zA9;4-mMgAOJwIaS-G7hgsih;aSza+Gwio{^ zo~zm(ebM(n#q+C5P)fyDrNw{8^S{C7WVrtSPCQq<P0ZB&|Ks`pC*parttH?NVe8Mw z7?3RIdC!=mG~t!|%irH#g+|)Gp~>u76S}y+*aB(DFSaWgZ^0R>9V`Jm^DI76nj)t< z!3o0^|Gay#Ayb>N2?d$OEw$b{ovs98nLSws3wNgABUT9Gs*R?JW1l*HYy4&pKtEk( zKX|zOYvoB-jp<GrQU=g$7Mf1R)G(rvZ!=G5q^n%b*M5Sniql3YZy*a2-*1<vLf3oQ z(FbC%&;*e$fVN|!);yGFyAN`z0tzptgESoCYfu(qTZ|)I+U<!Jbbm4SD~@0Pe4>hF z`twJk%thMq)bp?<FtPi=adw-~irqh3uSW<Q)&%s4kbyTU&NO%mNZ?wxh1!KignPn( zV6&J7-#%yF0F`+TT?=FFSyK?M2?J?Wdk{sl+`+e3z@p98$-AEY=?<|3!5S6`2&ANY zl9vVBn6!h(^c1S3EO4#F4>%M@Hy#g+S~014>pf~UCFGn2-W)RD@Pzu!Q`4JZcqL0v zHzZva$bRZ4z(MY__3q4rbOf7Q=i=P~EueW%dJlXt-HkpFarn#93Tyz@%gN-)K*_HV z%#9VKopV*UuWRrp^(o}Z3f<O)$?=*$#IeDmzhXG~IBSTM?Z`|}?>s3)G~<}h$FiA( zdA;f%T?-bsuD+C@>vAd$okk4tgZtkgG0F_c&!d7<I4%XJfHB|KI=BbAQp$Mq{TC!I ze{N7*&|fqK`Ei&kz@bF~xSe6i;>-NZFdK{r=w6yfK@Hagguv16kVYn;Q|%hi%VL1X z)8(sq?I}mjnWy<Ie6BlfE_K+~obh`Hd|-EP5;z#CG+e)|#6MU<I~rBP#cCw|Idk-q z3S<B9fcOjps=4lkkX_LBJ%{Iz@VAwB*;CH~S#yXzkEG+~1Nl#~2BD=+G*i?vKjFNE z<VuO*f>gV3;!2I*_b105d~`;)n8<5JV;PRz`cWy|fJ(12!w$mgK=wm|Wzq)i#&v<V z#wsO}63PSO&%c3B;`^=j(&P7z?^KD(u`suxuRop%Rx{7YEaH=O_VI*jNI<e`^reH) zxh$M$SBoMx^%cW*a))?M8(QpG?HuZ$E4QxxIB0`Snn&jr2w5A#JL%_Is{t3Zy1SjT z`^A^Uu#fFrMa-~!t_9Tm8k{@^=A42nFh>V4ht`@$jyR5LV<{Zr4vKT#FgBHk6ZmAS z+|m8=M#P=rP^c-`DF=SDICt)kl%S_SmyV>nKovb%$xkcYwK*b>1y2@>2XTdVWBL(Q zTk78CB$!f$B*@yTFn#Z^_qZ(0ejJYkJ3&o7bE`h^kd>=ex*TpV^DpgbWDeS;5ny>2 z^fhJ-!DQZ8pAwN9=u?bT7HnjAAfnIbZBkkcf*42Kf8zShN{q_|uXg&7ui>c){=$oC zjzZ?>$i*R590l&;CY(Qm8CDh9IVCnI2HRy0UlIPE?#A4EzPzh#GQA^fBPM$lBt`%X zwK5<BA17zMVy_4MPS#_Z*FEW0u0O3VXl{uEoHmj)!T2=kD)E<TeqRjx?sK7q7DfKH zKhkXlrE5A3h=Euf&Sx&VdmlH!Y{*6Moxs2qX#u>1b}IhT6@-84NJNI%g*ZKDK%5oC z6E;ee0i(}R@XJ@mb;Wh3FMlY}j?Ob{<H+qmZylc|L~fgZ*Zl(Gvtbb-oMbLt>HZ!H z{TKfv3=lMY^C?>?Sm-k{KpYS!yTf=V!uGjx2L1%VbPwJSE#4TB<NkAk;)$uXO}abs zAlh5un-O(`8?P9ei}1KDdre6(=dHZfOH(zfz#D6vN&TgC^h^ahpKJB`jSmLi^EHW{ zxMo>?>1z(w)MfW?kL2Q(_~MuEG&h>W0bf#5wM_#nj-NPd_F!wpICP$$SOQTqUUK}A zNf4xN56Sv1<(yGl=C5Q+#B+x403{&g*~R3?pLv&dI%<TD@R1c3fMiPhK;4&W2<abx znC$_K|55!W-WHTTfLu*}xt<_1^3K3H0X!NYHK^#Xl`-4Td*nKkCXekHeU<<HLGj(T zk00V+?|e0U`el%yP>)Nohsl=|=w94UaOocDuTDfaMGkA|YhBsudey}s)81lC7*@OQ zeg|7wE4MBD70JFSe1qY7{)=TH8r9<;y%yyDqr+Gu`6?&o;-6Q>ruB%v^ROWrG#n3m zEgauad|62LGXJc8!?1;+n^oL6S2m6l+;8M3Ont@AnX^RY>mViRAkN1|L^yHPSjM8U zNmEgNW`;?bv4|@oS2?Pw;3zNiZrXakpYAD&p(od}N5TQ^s60X&UgGhLGj7bcy1r-% z_6*KH;MY=pkH@7f?_9lshwXf~1n0tUG2tJRQ+_R<Om`sxC9X8K<w>VgAY5GRsOE=7 zY}G5o!7vo8<WQuTNSURx_B+hr(})(l{dwjU&^WXQhdR7LuMm?=#*$OnW_1Ra%V*Q- zVUhsdHSuCv=^~=&LVEk2M0_lwwH>je6nWh<sG~chmJ$mZN8HAz1prXXA$o6IW=hA! zS`=ybqMIcebqi<sh@LqeB4#;~!d)x!nTzsrHmfohf18C6v4(m2L$Vo$zu#qTVa2Mx zBaDOz5Q<a2XySX%oWESQHvmMcA*u_9yb+mj_;d~!E^-ZfHEkAJ;e>2<O6QnkoNx{V ztnGJ1CDK<Zyz#lmmXb5p;5F#0xoA|yIDDR-D{qAQeJa%q<XeNv-F=q=LcuHBeHD!I zqnw1|<q<dcQJF&|mv#X0%_>JHKDS06RZ)}|KV%V5g3K5f(RD|B5h~Ex3|Jl)+!juo zRk~V=g6P@Af>;cvABB4Telto4Cpz-XIOqFf#9e67*N}htk4%2TQnF=nLB2nP_zsbK zIyXE%a~lQB;tD}z8h$BR4GwQ(z?}hT4-?+zACfRvJmOgZqvRQyCsxZ}ZSyY*>4AII z+T<N7(_Tt`;7*GOhMO<KI-HOx7i?<Ma(B_Ff-`~y`80ue`2BIt$aZ8|JH1#p>t<T! z5EgaSro1s9U#5(*L?g?YMGw<L@P{g18ba2^fcOi7*70x=*r6-!2TnEO%zD|xzH()+ zA*cB`2*efv`Sad7<73s6l3G%3gMv3ZA*<LGZSl#gXVRA<Q7e(WI=NQOEQ|0EuWTkb zi4Cu5r!T?Fe)e3;_T*hd6`$3DM4|bX{CPp?#trx)20OnKfJ?=hEfZ_T;nkzvVI2Li z<@S?WxsHkXuFtyR(fmM>hp}S14J)lCJB0TqE&@!Uy?a@u!GHalKSjFQm%Hpb^YQiG zZeHLLYWRo1kKou;7@U)zWUo@?V4L+b67|POP%*V`{xiHN(snPt#`j)^xHpP8&Iu0S zbrly(Wy7=4kgS&oEX{bYr#|rsN_qzZ-$LA;_Wtpsp|>&UKw{S4?}tU&!W7@x@%&`c z?_~r!Md+Bj^b8}OuGuYhT|W+Xs$L`)s;Hj932qRBAm$}E0R(7Har0maJrJazhw8+Y z)EC<oh$~j<mGrQkJIhpGc%qy``ENHjK(t`nLx|$LEkW8`k&#AB@z#c2UcKsOu=A<! z=Z$=HZ=9N}n6_0-PZ#tDYOB6B6FGQx7i*RflABJvxFzov4mgd~*y7(96L^|5(DuPr z#$vjK0|d<{LodOr61HyW<r^-d#M55hH05WM`a>A)?min$yzd*1#KVTf;Q3r+(Kl_L z2rhFaRNwh@HojKojiA%w6%cUBW35$rtVjfz2kt<I??+yIklv<cS5@!it}D!0ghr(@ za$xswwPU%2mon~nqmlu*^l?W^6Gjjk`q`sZkiWC+y63F;9eMao0xZjF&oeR>ejItn z=Y3W*8YGnKNQ_0j6fN!Tk2?KJN6ikrzsk3>$h)$I(mn*7IY~f-+>N=Mxq|}C8FxWw zt_lB2UM;iL^N|%~+DUW`<4Zo(q`PC3=T$reqE+~wiE7Yef^g8T^Cw>B<F`4byo9Vv z%5|<bC4<mV^GN=sTFTKogeIgE?#(^TAl?rE4NB>>jy+R_wv1TJgH_+^eM8?y^Ri4( zBPbyGS5%K^dZe36V?*!Q8~Os7?;fkCVm}PZq17OB@j)WFE{C(d=l+BHqkKbHC@&86 z8*wj5&`PfSFq490x^l&h^f`a#IbqEI!0j+=tE-D`qf;(+ZM^I6FWs$0o)@b84_;d$ zz8<s95c~O><tE1!y@+~0Xu%bAN~!+AX>*uSe1f>W${d4d8Qm+o%fk@`k!SUQ`~$cq zVp1c8&iY%OEEg*#BY^UO>r|fA%d(#@4`y4yzBII0{1QH_HsqNPpeB-1fm1JU-FLE2 zMVg>o)KEWx`^Y8O7o~e%+=YDWUWt)#%pG4*pGWeKxf0Q+vrf_XtOw3<XK0wB?h!kh zLq{&oGm6mzS0&3NESi(H8M%v|dHeXgslUq{=SFp!TEWg-DQx&#_~UOS_lhze7Y#H9 zYdx?Z@G}pFC*eCj4USfr=HLAVLsmS=sNtP?q745{OjLDiYsFgmDCen=^3@(A?mX_A zSC63Z{6)$4b^G3}xZ1z1-m%GZ)>!N<yJsWd^3U$4Yhd0<AF&tQ(l~G1I3+uU^x>Ip zHTEJeLH1_YV~3Rlb%F6=&fJm1lXoGY|AW2vifXFy*L7z?5>iN*R1pP3?-+U!Fm$Ab zA|e8YrU-}uq*);Jj-d#sl+dI@Kok&As)C|MKoCU?C}0BvHbj&Y|KD1Bt+Ce{d!KW) zFV4PBE;Evu_xHTd+xf9qnF|DvB#;n%#d^_U(c{VR;$s-(o<(ILAg20~iA|`Nems)Q zZKwjpGhMGq*ExH|ZZn4#0VoULNNG0uv9nFmXELA8EZ($HpO98j`Hbg;K)CIa39R>H z*!slnom6aM8g7X+On3xp_a=4sPU83;9()!1yMB_`2YzE<@(9&N0aKRE;3rX>{qL#L z=ysQj&)iC%x%WNuc=hZF1gILtI<G!6iUwe6PyMo!VT8$3kJ8V-oDQ&>r1T}p8qP#s zoY{BdQM6dnwEoojS8;P3i~aAJ$s<?@IFTe4?+RYay7t^gekP~+d@^P>*K@Y;;w*%X z+|HaWi83;Ih-jdojK^oifB0RqdvQAoDVX^p#?trN>CvWF(%fVq@Vr;RD+RZP`nE?h zGYX1DWTT!^866^agN!?aRqWq8ccgNrEP?xW^Bkx91A{y%%yUJfUox|$VFciW81Q9> z>2Fe5k)|U0y!6!}69^{-oD!2-Cd`+q*;k&PcS@KCNYaT|QI^7M2T9&C5BTxhBZf{h zTg?L72>H)=-dHOz9~`*G@A&N#FYJ-r2N2h`7vN{U;*yy5HDr17FT`%(AQ!;#M+?dw zkKQ%k;)1ZGV;v^47nJU}pCY`J7YAN}*Z1Gyzi+3-y@t`jzk)EPb?(@#&??sZkvbd= zvltM92gSwTCVwfy+lSfzags7xy6Dm*5whfdXQ|U?dWt#eF>mx^@3NoQa*fl%iFp&A zvgPE-x54(h)B310k4=J%RsySV9|&oY^ZG0F#q*D~86F^t0EzR`P4aq|wo~@5R~Ok1 zHfDHfUwVJ}(wf#O3I=ZQ-e_^9(4_c%)_WbNrLr7t92+RyK$q?QV9wc<ht}5Nq_b#1 zgDR+Tr|e^&+*h->;^YU-Wm4L<&~+scL5EIJp7(@kt<v7WSxal|^3*)DOCFz076BZ& zli8vr`U1;s`~iYzJ^Q0c$0_WdTh$*#YG#RlWZ<G>U&1zqw~dn*TLeC_i?;ev8dPwB z^f7j04#xlbbBMq)fD2ItH$Zmc;M(s$Qk#Dk?=xC7Lk}4L#B_R$L+Gf8Shj-(?y5Mj z`^>sz)e1K3wQ)H2EgBL6@B}<whda(2XlxAP!GJ$lPHsxxQC+K{BE0rqL!Hs+r+B?) z<GiN*y&Bi@ey(z<W3`$zKT|%f(&wY+C*%);S*4nH4&aWZtU$=$9QK3weHt%f!Pl(y zstqf}@^5@5vwr(E$H-q#9=~JB#rv7uJZGd(0bsb)5K=Zzf(}Zk@y-`7I()l@R=YB% zo&Uvba=ug&)y+ij2(4*<DLNMSJ>$}knAe)V2Y(jE{lrz)+GYJLdHu5&X8p|hXIZ&M z!ojTrU*`PjsB0&;4&`&JJiFV(tJy&iyovwWc7|}YQy}Y!W9Jh>M4|vr6^!ZU-kko$ zYl`Ux4HGX5AmK;gj&=u}*Nt&ev&pC*M+L6DvF!@l*5P;dslE4`weQd3!9N8Xo3BLv zb4(h@p_n@VmlV@e?{q-H+H66SP}R?~3!2nq^`E!-{@a*z;zE0)OqLMDx<JI6?L&o$ zK+S}#Z#MkT6q9frO%CG4LF(_-fY<H4MPj^9*k@EjbqZcR?EDXk$-7^wWXn*NGLmU! z?7#bH?xN}_Abee%v(5MKF{yrs&s_yCu(y$<_A%cUt{7W!7VlDD6aJC2&G#>gX~$4Z zKhmkD)mQ(SQg8Q{e~U@CUcV*y9=nB~xc%evzsIC8>8RrJ<Nq}#J(Jgc;tzn3|5r>( zx81cJ#Y*7$e;t#Kmf=+I$-nu(G3ozViYa?Tfv4j1_ZL!uCMf&B8!9>%J6+B`RB06~ zh%&DScZO|%m>-6;7u6*u)<CUv%Xj&z@m0<<H?l*=EFy`IxO8Ad-CC|PO+7=gLHhCL zLe{~Mb7zYM&vuzrMsGZjqjIy-P3lC9K-tQYb{*yV<6)pcbgvlk6~s;4LZo+&KU2N| z*8f00v|RP#+1wv*)8#6wp<4<~FwjORpPPu-4R0RA?C+j)x-Vgl-x>RnrBk-~^{d9F z_5AJE<p&k(kOdE34Pl5fEc~7L4o)m-#gf4DrASKe7p~UzSh3y(pr=14Y~`8(nxn?? z0W|z24tJ#aG#wDE#CL(C@~V89M~G1VRNY~ffc0)?&6Wh6VLDE2m^+@m7{lyIlHZyB zf%-Y1#Cv>n2)AQqu%nlYm-+fiz`5Au^@xd3tH?0%IaPa4UZqe`7mVjj8~UC3CC}-u zWZ6RbN)pm6BLLMe!9hS|VPs)R9^gxK*u4~b^Ep)d@i+R$=zA3^f~D`waB%)i0B0u9 z(Y2`L9*Q)Xs=zVm<|_tm`j|qD_%V(9+BBCGeTy~WCNlg5`sZFO*_*G4X{P+aBF)qz zET!~D1$x(*h3^&9y%4IUVHyl&I|q%dVfly8MPn?g<Kc&pT*A`EDEB#NN+)L=%=)R# z$!sZL8RXwjj?Zuqw8vkk<tT#n87JH!=u>2<zynfBAU~9UcFtEPKVl~bD5%<Nat^LE zq><rNFevoM)^rz(oo4ggF<U9otkH$FP7{LNNMibb1#LfBV90rPi24-H{m=YWrP zV_}@HbRoS2s}?`V8EhS@Hwh~ctN})L)FIqTZVP-9x=BO^qu&7;8rzdp@3g9M+oY^A zyy0DvlE;9vyqmE=T%#}GwV6IQOS)o%Z9FgeZsMA#Q$yz{%s5MJO23~i)YvsIZxBCK zG#xBD2?k}422Qr;v?M9;0D@2=%4@uhXMYlmWjk=_+J|p#OAA5Ha6M*1)<P1be`w3~ z1-fU=b~h~|*YA<&!FH2NLM?S8M9y|fWlpG2vrS;Y$&X@pb_%r;5ZSEnqATclGvl1o z&zpP>>m7OWig}~MPW8;FDDYB0DxwbH?6Uz5ETM1wb3qMZod-%+^gBa;H@+jfG(2~G zm)G+yIVVaibLd{KiBKCdm|t~e+O#7<xWcA2Hd$a`S$yp-`u!edD3G|npAA|xe_U}f zHh#PIV<6#u-3LL*1;Ah-S?vNmbT{{HM553j9x?tw(Zf6b>&$QhhRP=rI%Yk;>#Ug3 zTB@n-n+d85{)EV=j6^63TlHv23m0~Vm}+V2Cc>LyIIP6pbFlW1M5}cKArn`WVS$F> z_Vc_^+M4mJdH<&E#pztQL#};-LA(ILZ$v3L+DoD*W=AuBiNKl%sk$N+Jh@$FigdXp zdi<M5QtJD2R3Kc6qoG0&D_Q!k-`BK}X2=r42ah-70ek9wPoxIHC7}HXFA@adPm@sj z>b7WoU%o^`39dLOM>BZ?<!^E`_qVePdi<%mU>HdiDr0dUo*ESJZ@J0fHO;VhixGej zh6J*%>fm{Q&0dTbS4_wz9s(1<<4N=B6^~Bewc_J#>Pp@>4j^oLC53K%ymkBGVBgy1 zu*RY^E*^_gG_mE^JlVK`SRI-kYI;uS-Mxid>voieuSW#ySSNOGuu)bQOy;3&Q3G-z zlxqnN_%A$wifW95dvWI_L0&z31kNy9NjSc7hnl>b%pTmu>&KG3q-Uobt^4}&f^f@o z^L@6g)FU@4Z)g;DGf#yPEhbDvLy`SA4?~744tUCjmhHo9Rk(V+f%e$N-JU+Kej5;c zl~hy=-=A0J?M`l;IyU2~1%r~*9hr3Q3dOxiV0vMk;p+ScuB-DQq!9jLp$-B<=sJ7) z#L(W)(-~F70LAOqzk5ErfvF%S?SgY!4E*(<G#1PK14wsJ0t^gQk?kfpJ?%Yq5Vy5_ z<TGszPJQe!{Kfjm^_XeyMlm*fWH*$apnu5mQUl#wwG2!Zxd**_?{f2McEqXBXs`9) z7uw~VnL~%Ku8fGfnv18NFD=P6t|E<Z?v!ve*>1Lj$f5&g%7ol55vA9^=4;7uzkaM8 zoiq82P4(s+*HI^j;*K5{241_!iX-%2`G!N)Fo8lq320j0ADdZqZbwe}6aoB5mrW_q z<vxq%ARMz&o)8)$9gb=woxQ0Oe+LRD5Ks^*P9)m7G79}Wkvo`tv4w^4VIaFHhuSEp zn_pt(b(K%Cp?x}V=sGT|Q?>>SmYYJ23IkbG?+7C1>Qo%RNK&`DH9~^3MJOxxJ)(e> zcvJ@aewW2{;H+F)a=Rq%H5m?*b<3h-mk88gA8NL*AC2yQhXAJgA8%&H1zIUj5y8Jf z7E^YYzrT<RSj3`s??_o45lL&?z&>Xo8)ZQHFpe^D5ZY!Tb{Vth2sgGUCRaY4k#HWl z5c9NCznL1)T6?lV3-s}`vC($CE~30a0T0#5@_h}5K1C#fnOw5x>M0JW!idf~rO#xL zL{8%5f)o>U9obJ{>0G;R=1uv~vEoR<DfD6l=-ojqqo&k!Wj9PD!xpka!W?I!EFtWq zRubliphcx~&hn-riGVmW;UZ9tPNgF5)&})5(B|-<(dbLvCdBB3fN0J?h&n(2uh~ew zvpGl5^#ztNW0WTiRY1ioZXQ0Rn_JHhLxiSzJ$Gy%C0r}?@dSYuQkFrA=W&_5TNAj5 z#Ut4}Lue;K%xV{kLGj#Uk$<y2D{|tv?To?QT6YS7xWh(@EQd<Gmz*Rxo9KxxGcqFv z&+_SjE%M-z+PD+7*#;XY567tPMn<*bT@2slT_(dAWYm^rj?skG*>}4;X@~v0<;$hO zS_WF;EUJu!E@h-b+lY74Ok?UJmf@&qJnFd?+M(;PK?<ru;Bxxd=@!eA4V0*(DKXrq z6h6_@i{8uAO~DRI$V?Opn;L^Zb*XChbQ1IO9Wr-&6sig^EBtx2Ls%!8K&~g5<N&7( zBGJU!YweYnVw@0CE@vQw3*juZ+pZJ$P)cD01k5j=GKiM@krwTTaPG$x5=wh^Dl<ZS zvM;<h2qz<YrOqwtDftkg^Aa&Xyvvy3$1#Ey%Q9B0vx-@GkRJqYQ+XE{xLupF`wH@J zkZj2Ps27QmzfLLArMZn6FbIXqPd+wm5M32@8bU*@7GL9aSNM#N-O&R9nX8YU>N&XV zD`JP>N6<+i%9F`$FlL7rt;`EMB`O5?;JN2Rt5_0Vb^YW*5H&0Z#->))<>B7ZGLgBs zkV*$x3v`1Xw?jYXs&t{XqT&jO+a!ZCAmFDbryqlIZ3tDoT~oh--3GXgtSf}%LHL$z z5rtSp#e{<#Ztim6RmDv@210?c6+qvuUA;_NG<Z&|9j(8ELY07)(Ni81v$f@UxZ_*9 zBeo=(>G_w~b;@-nf8f;x4f0C>&i=vfDuiUcw8f<c^Ka9-mHG`i>YVR>kyIjv&bo?) z9=IlIkxTRCU@}+f=<79&?TUN*=~y-pD>jJbT7ct7jS#>#_NhL8MuLe#B@y6vh^Q8- zv-7#8B?(@)7)jNxUCUP_+ls3f0~Mhpxw&e?JyY<@boA=;mdf_3e;~;4Em?)-tonYt z)YR6FdoAZhfs1eGh?fl90ojOp*-xSgpLVzK9tbXbV+A3j@11M=HDXu#CW=hM)R3-< z9|)d#lLuku@tq{Kool~z7+p(i&p_T_?nD|o%Yd8#0C><1lWCp80MIb##s@dy=kGPI z;amSK-MCqZ=mgNAU)p&ya9g52eAP9!LEw&}ABhyJr`d7TM#Q3y7t*B>V2a`-_W6tx z{JU?J$73Nx+=`;eGNofV0euy~_L5K#y1CHDTa^nqlDo*^W2&`y)Fg`+T4C;n=}ML0 zeHX29F9Lmugnh>1Rc^G*IVSR#Syb!N(=e_jBbV850~T)w9aTp*yM_?~*@EzerraP6 zPk*Zv7B++gII(zp@u;6NH=ADyd=3PYGc?-RF5TfhK_uYz!=3`>(E%F~4!OA0pi%V^ z`|x3J&v{G%S(j%|pXW|4Fr);^Z)wb2>wEE$cdqdaOG)@Y;6>o}a%1oKwYxnJF|S_U zp&B<E4xzh~?*4q(YXtCqJm381rO-bhBi}WR(er&AnD96Q5x~IqzC@w3B#s5$m9W4* z<b*178cB3(uB<*d13@GKoh;sI>JcWxLM&J!5)*K&M+2L#+uea&rXqS8QE(#HDg(h0 z;$5Pn#2(_GzsF@R58uetC?_G3IQJr^UL6}bN#|Vv5Z~}nIDlo+hOLz)*%Y2cwm;t1 z_t|-k4EcU!?Z_X1+W^mdf!?zPnrK~+pnt@j?(HAj$nKU#ZGS{K1DIF+y{kL@cSjT? zKe6vq=ady+pz;_No&@AP8`;a^y~n(p+v}P76@7}yoyS1`Az&{tkTS5|@@-unZ7_#` zxkN&SFpvc#ljbH5{@s`YqMdZdaQ9vTE&|MQw8`#Ea|L>Q;1fTB2;Q61d~wg~p|ap3 z1Mn?T%U|n}TYSZfEHB5oM`Q4QXN@+N$76x$N6WpQ?bjZ^)Upm5e|%}FX^!WKj}~l5 z`uf)<kIyAfY_tZqx1Rv3T`9CWNV7{RD=LYEXro)fn_XH7%#0UI!eu6ZpG%A>^S%4i z6aRuQ2LyrFC34rMyF{~P`Nrie%pc2~mi-G~;yV-gX-bb|b#{8?baW<z!#EM*SolPI zFEvK@qO2eQ$OQ7fW;{9IlW!#^_+ampqX_`>#w|URS_LN#J~i9@amsIET*g{@q*3Vo z^=D)!-eFtNk6<fTDiy9YE#DTIuz~&7-wA)p?cXS8@qKKIHXSpF`#?<PW<DDkpA7yj zeSB3;v;=%-@I1)3^HI|zSH(<*oi+z$ql(R5{~z2XX|nJ%=&JH>+-1HPQ2To}h=W}c zUR)u}%DfO}Rlo3?bl_l@q1G>R-e7N^)_)iMq)%*a@S@_QIjpSSoZlN@v~O<QQ{l_p zoOgHwQ%w7b;VVx8`*SB>`8dzKc%=1lhr?YmUwLcb7F6cF!f|uk055so>&E=2-}CG~ zQx11&C-&OZ8B@iw`0lCY+K=h#eeE>(GO99K8p|?YoJHhlp=dxj6wP42MtR9Rz{;8L zSs?vIFBkqnFKK-;+yy=mDyG|a!5%t?Bh*1CfFPMSG-%O0A1C)4*g1t=py2kE$uwc! zxJm-j^aX=h&6%cT_y9{q<gID`^YE}Jt3T5D%=4>Hamx&xt)lpD6@1(Cw;m8)`%k== zX<W#7tbLZORuEpMWywvAvn2fd_k(5c!SsL}nS@u&9ujXz3x5df;(_22$aB<$*ow*I z40rAu>SKcM8a`^r{y)%50&c}>=v}rr@L2yZdU-|s^*`t(-Rzyd25<K$7Q5H>HKnD( zGpG`W=b)F)r!}vua#HvAH}AX$?8`Xl<;}H(CDz9$Jg>vWH7sH|=;g;)Xk&7YRC3QJ zJt>}$S8qWt%?&&+UGvjPAKONm83<wZvAxtHaj7|0Rw%iozDLhUW6fd`XM>eX1e=1S zLAwr(qQZBwf6zBrtFLo3kKFnE=g(*UJWt>t8`iofJ0E?~`8E8Y`sp4v!Ff4*>@BYR zFKyYVy{<cX`5@mVkxPVNrhq@rL~LjOVY)z+As9qLT5E1_<r~BeValmRS}GOBeIDS0 zA&t?Nr)$qv+b2<5Dgyo??FLUa6yCU<xBY5W{?+>K*Ua`0_PhRTf_VIY(Sv-tkOu6x zK+bA0%+T>D0t`IbR{g*0K{lgO@@*t`S!T)qO%OS`qnX%$lOSrp!w?{@y`;^zf8$0Y z1PC=n3RzN?@|6E`g19ggcVP54#*URKWRW;{uD#$?0#>S4@;@htUl;H0x7Rq_6@B`_ zGf2t3!}^3o_<v3ixe8T8BhfVs{|`cs|3`voNZBZERPmiZ*4Oht62xuOy5-5n|B@iq zzQvPn{Mq@p1W`91{%3dH|Az#zq0^MpgZ#e<;{UN8<en%=lJda_^$ht+nhE-O@R790 zmz1bO7DBRzjZ+Q<$yI-!5B;%YST2o?cVem>&R+bn@F7`}snEuDB8ft}Oi0Q##b2$J zTcxKSC?xH9t7}%8FZn<LdS&sDTqTT@Ay>vzptJbsmK3NTy==^s>K2h=%9tlPk`#;Y zN*cW9<>+TbB4DiZVs{=+Z4;{-E5FM(WSJNk2M)Cup1ByzPvrIfN_i*)ncEnX3pl=U zNU<_&@egtB{=o+ypSNCoFxxhqU^MHuub_K@|IpAbD1dT<^@n!oT784k`d0NwI+qDn z%5G{00dcd~&lmuqgCzc_SWT=XnJa>M`ti0;5+L&4=)>z7k0WyMLD5MH<M%Vi)mo8D z=i%$`eh`lfQ62Ka&6RiD`KW)swc?A0(CgO5=!x~kaL79@el7~?a4!YlN*-AxJs(mP zU*^9AT1oIYrU3<^e8h@jQ%+>pj~dQ~(350w6Wvo67t^3e%@wRH(Lc19nN$NFVQ}%D z$(?l?gz9Tu3{oWt6S>(Js->k49opMY=T`2QFx~*~9iz1fW=NG2U+e-V{0aY}4uhw$ zfx%M1eA@j|X^96eOtwJI!+m`4i43o;jiP?oiRF71xyR-f(<<@D6-SH40c8!qC;YlP z7du^Y+9b0&@r@|*2in=i9-oRg13E_gqd4w>z=ER({O;#OB-KZR3L=GIK1d6kQ+8g@ zutM6&o!+Tz`(%%=D207_1CG(qi)SYBT&<Qg&j}wP2q*tTp6tC?xOi=)A@va_`Ale% z5_@B1X+7tiErnI*3Cv1XbT_^=nY>(pNIzi<&(llCRqtx@rSFRo8TI27LLqhBq-1H7 z!*FH9$;8Lv*f56#;voLwr&ArHd_XRAthk(Lj@XSZ<wM}H&Y%_F3)<+>=Yr>c^&ThI zST}{j0I?1(C*|)7WwPRCVQJE%MmwX#vi6%EE+e1<VXIU?^l{^HY`+vejdt^okY|Ul zrKL*5(|DF-n=hEA3wKHlL=c58VNWO3)uLU;6Y#ESC(Y#KtZ!$0zsa>21lXUS1$Ky# zus6=5+gn}7N{y?k8B2~_dqzj5Ql8?Ex&)m`d^q=$rzn;ahN-YcsZ-*9MWSavJvuux zw`cuZ(!Fb^-y-sk*5df;U)g=W_%;fyQdWp}QXV4Wj5CkaNhZ+`x5j>UMyK(^c-)Xf z&dzSu3H@j9B3+-@+r*=fOlbqBcOxTtOIYYjD@j<*5gy-xG+?uz2R`c&s}Q`vU$nx1 zZ8X^*(|&7vP326xR$Er>BzkDf1n(^~s?3w>E%Gbk9ufCg!Or+q0<*KA?0G#ZZtq)J zjgx|TnOw$$>~zSG<~{qzVU(-S(`~F=kSVMtBG0+O8uJRZ@e%bb#hLW&g!~;Ugnd0S z{kr3~!WawS!iQIA6AZKA=tC+Z$8*0UcRL!!|I7gXy8XQ78JMVft;*0INnM&#@Y>Vj z9Q&OMj<g9y_pvLF9X-4e#PkPI_^~}-N=(J1X2+V+>qw)@0d0Y<FSj(Bsq%YX5XkXe zgF=YDn~aEXRJ1GwUkI!k85@2&u}}7Vt3VBLS;XY<fnP7KDR}P=$?exM@D{M#*0^=w zQy8<zQ77q|8VA~~MSfWlzKQJL10|shZvUG1i+QaO5bxRB(6eh37kx)1%~RQmiv?{P zh6yRMQ!@Q;6zSeV!P+O1@}4h<tc>j&)1$d;`hclrt4h<6>si<4<T`f16)9B+TBubU zcy8D|uJ!oX&6^2A6Opo(2u_35<J>aw^%&}?nyqPCg0Sj+ANfkrvtf{^DR0R&_x%I! z(^q=mzs+mEQf+jwm^W#un>s{H89m$-6@-Lc37!g?zyIBx2Hq7$3QMlL=p1|b=>@b+ zcfNYih3Yy&Q(8P}S=5>L<~LhtcBz|l3v>*0oJ+GT)MLkI$J|b_kM1{-vxi{Z-ge<i zO(ot+?Ng3~0ejB#5_4wHT03o*V2iBaJ`3X+u5&*gS068Y!3+JSS#Ouz`Oa+rUI^UY z>MMU`TEtqB1K(msLRwP4iHJ==GQ_m<(|CEI0j&Mk&Hb|%5AKuRG0tLqX*_w{-Dg+Y z`=@?x6E_DzH{djMftj2Vw!O_1P2k(hN9`}GAFm=BL*u#Ib^%wI@I*2(m34IUhq5yW z69c?CVArcu*;*#L7zBdB6YIBpG=+dNx(PN~`5!_pXv3(oAKgH9t|y>7@#dwLVB0-E zsdq|CBwXPxz!c=(0CCGq*?{oy6K{hMBEW_IldTl(q=>}9!Bc<nG?r_S<T0M-@rY1V z8{5NPM0uIc>y+dRt#A}7mhCeGo0xitDUzp^@<(a{cU!DNfbna;1JCkN@LYp$&r<GH z@^U*SG@UdYc1EPq(d)}$EhLPCx%R>Psdsnyli+HwZ@YkH&TvN<x|I@QDWl638k{ql zI%}#wqzS5jOTX`P7zTl#kvujbt6fL{RRS``BoWgivQ9HLmneY{Mhb@lT{JVQlFz)$ zA026;e>*MNfIIw$TvqN$x4xwlpJfoarbemMi{o`l7G#i8EL*Fo?_Y#CMaA5txXwIR z`b?C=e7EEJj&ehyud!X0kK}YFWQ1=RO(%xGHv=O<M_z4dCZ5+t{?b$~Ziyy0J;W(~ znzs|+6ryJxo@&=61yP{A+wl1u&heoGyNmTmc-^=1Xxk~NBraUV0Op8UZq@|ROwQ3$ z+ay{fEJXX9d`uW`3~D3Us9~o+^LUhDicY?qrNON??$D=~rgatAq!goWc|t^r7aWyK ziBP{%AZvNtUDG7r%1G^0qLW^DCly^uu*@fukEJV36w8fG8I?sJ{iI#ktd0o7o4*v1 zE2muIlE4&^jSa^No1JK(VSx`tfY!RAPDyTlrdYt&eGiKRTB<H5997(Z2nrz}{(!t| z#7iM2X!mOKBo=}>ReVFz#+X?A7e-^oU06Kq`2I@SAofob4AvI4Hnmq$8mtl7Cm8^C z($GQqR~xz&uCE0ArO%jRy?WyA)h1VV1Gx*feeV^QnYf5Z(CUzE6W%!~+z?-gxiwSL zJcwHaOSwXMAUk-Qa1(=A;NaYQ#lP$s>uO8)r4RRI_ZM7nckz4wQ*j#~8O8#*)N<qE zG5#)y?-mjRBH{1qjk}`CD>tyQo4d=&Q6hs>*g#xok>^M~J--q+50s_xW$pE$LueTF zhzgN&3Y>s2#TeO2#IU6$a~CiLEcC9CV3|PizuXz2RQMn6jCB=4aET2?@#;zH6=80$ z6Oua%we-cFlhfrF%Y7h~;+5KTA=DYrHP5ut?y3TcC^tEYqA`w+&(_qM<Z-RnKr49r zXJuU*(DsMUXpIJ(5T&?2KqvKM9GKj{hl(T4ou2VS<#LL$l)ShXiu(Gpfl}v-c0g1> zs98)*-C!ZQl!EM&t;gOEO#)Ev+-OvC{iZBBmF(QkKuLY|p=X?aE8W1KEL>I4P!U+a z-5Jgvs%BjEuLTpT+`($WdPYOWMdLE_{Km>Hmw<(OnYWFd4gO_RR1X@_O>U4GuF-11 zt<?E%6_|KMBIm=S9yWkZqJF;$Y-wy4A2RB?d*f?&(bF7Ajizx;3SCTUfvH{lcze&w z6)a6x<TZG0DGXgiK`nj2_$!?M@n8>&)tc1S`eqQ_L~PMcwzwI?sDkjW(KUVvGH4Ve z?7)c|mTjpLkU)1Z9j&nnZ@Yp=pmeXrqTBt{00<R;4^;J?)Y!eF#Ms-|&cK`W%(kmy zgr#i2(;02NnK$kLaFj0k_WK(Lj|p>lw)*=TIz4R)2auAtJ085~@RR_I_Y@t_Xt4<5 zR?572tKp{m!hf)B=*+fS5?U04y3B-M1u*;FjQxXd9Umw%%x|k?v|Yv{t^t@zMn~O) z&bW2lA{F<6bVJA47f@oH#Wa^G8U}Mq?y>=CAN`)=54<DcNar+C8R#aucK895C)nKn z!>8w`gvq&}g$#{GShzC=l|zO%Wp-sQOU&r^P+b$Mf;8Hw+%*r;I!cWsMo-Hg$-lT9 zF{MenS7(UYNVu6wLUCX!I=y4|Mkl8SN?RcIWqeeYEbi^<xqUsOI~^lwdGyZ9upSDd zuZ(PfLf@5@z1t&#KJe_urjl<bMz4j2)_4)IbHI1^v6h?<oKJOs4a<^yP6z;+=7@KU zG;Zb+;Q3Uvmw6T61tCr?*h@(hwYPTiy1w}Kz+q#c<h*8Qrf^m9pyCCgLOsq)s3ZV> z1w12gV95Pxx3R`ePQGl_fHHqS<g(DITGC(6MsSWIhZ?-CJbbDJ7;b28MOPCOy^$jW z40Gr6(1$3;{y3Pcb;i984-bJAWUrCNk<p+L2fD?lD*aPgLL9Cycv~YQ64k}xevQDC zvfCnTg`R=H85_;f%mDYD`#!x|qeO4`%ad0vO!aX=^#Ksfb>Q%okE2GA;aziHHyHJ& zE1X20`IdYVXn#8vml^&+%D$V0x_!m-==le@DH{mJ`wUQ}ZvC*A^VnrA=@yCVgQ1F8 z+$IcEAEis0`%dp(MZ^VUFdbdQE|Lr*2a)WWiI`L><^<?1<)?dNZoFm!eMea;i4u4N ze2@zQIl!3=)8<73MW(V8-5>cbJf5Q(Ak$FRd!F1jF@w632~OPG%ZykyA_+j>6L|b* zo1a4*Cf7SkmB=~BRH#Uz{Jx-@2@Q~*5v-lipB1^0d*dRKr*Xefd2B>19eo2#`0?xM zfl#g~Jn!-jY3O{|HMy`j+(Q)74!Nr?U>-e5To^f*z%A@48IWi)c>xpLk8n6-XksUX zphaGELRc8;D-Dtmez0&hDk^5!@uC0+T9nued;yM_@F%5u2$5AJ-AE>6s&Ekrqar$O zZ2XsBlsO=^%$PO~HJjv-dOH*sOGM)KOhuLoL}LN-y!$Q^R0R|5746-jY?R9wGrgIA z18CxMgvX{`H>?~E3PX02Ip-79@EqFRd_slGgSvs+V0y#VP<zkG`43Bm9RqchPZzJM z{~>f-sKhN$njv_Izac0TJfKizejg6cC(nwi3>k3Eall9HInYc@V|xWrXLnp{=iZAe z+59}2Gs$`&-A==2g?qTkVQTNZq1v<ir5Yp_a!(NB!-sjJTm-M@JcNm*T4|ghUq}Tp zjWoY7pGjw~mv<;!&SHSFvPK>K0(61f;i&oBsh6AC{3}4xKd@w$7*K+;(HwfZ)p1Ou zY(dWZ+_a~cuEv=vQH;te3f{D6l>17<7w$`p8vevk2zjH>mOb-Gogh<&h(^+9(1*Ui zA>y>WZbFm#-yH2Ao_+Dwg>P^Q?2$ID=i=jzAaQrGQN;=eT|<Nj7>#SUsqv5A`ajlW zFq;!Q+MIFor~mK|H>+P|U`T9)S1eNO)pW#Tft#M{(TC%Lsc#i`;P2vF1g1RIud>3j z`mL7q&4TZ|Qwq)TPUpPCZdBm>LyMKdHU31LdW#5<MRXk>I{oR(M8zF}y-R`8zU8(c zqLYQLk%?$l6<ndr@8fd668vH8%TgQj<oxJ|?iPV*_rFx9L_WqU2Q!$}`_=jV{m1;{ zYihnsZe5$>9aQakmp9LHv=V8k2z;z)v$>1?>Vm35A|7Mdi(d;rsQ(^)W8P*r?8(P9 zg%*MvChX+C^GI(hyyif3TIuJe_P&zmpIawU3_$lH5z_`DYzY|rA-ByCHeujnSo^sI zWqh2=v3wdTmC9{PPyKPz`9se7qL`Xmq;F3mhGu4*vD32Qx&ZLv<ysjiP#@oI2aXE> zuu|e=#y!n_f>1y%e-ocYXjqDMKl^Od{Iw8=FSXncZri1wzbMmI7~X;($N0eMc+5dw zR0p;9X5c4BUO^LU=(fVYa8vRq#Fybo&#+QGF6H<A)Q-?9c@j=tTB9UnhywgA_<kuc zm&8q@gwR-T*2CA&mkZ!n0PQHDg_`OB@MOe=JR3Gw*!NR~FX<Hp)Y%7As_eh+VRVBH zJ3&O2`X3nka<H6tYk&Nk(~A`!{dH?-=$j;zGZ_&}u|z_Cc9aWb0o5Pca3A{}1?+r* z1nmw6%Aa}EA>!rE<dG3x;ZNjqTRZ=dth8_LVN>ijo!Y;Z9_9x_jxmHxFZ-?Ijbkz2 zaY^ug<&|~W5>E-g4f(YM@Byw=AR5|>rf0BBQm|r1Ng|GmW*I^%Uc<$XZ!B`e3}a!t zo!(mI$=H>dU2$5nE>!Wnqgjtzw!Nx#dVctd^V>SdYO7K-HKU;6*oiWaEx}BB#j#rZ z^-qVaS6mtnH_sc$p7D67b)+vAzQ^^GTf6@wr|k&WRrgzvlB;M^<}L|kXLUZAXa%6& z)hOl`e6Jh(XdF!I*`5-&b)S3LVh2<99^Ei0J7}JM^;?E2k77@N-q{a2AN(e2>@IQr zAly7P-RyZcMeNx3PX$Ihr7iC8_uyp-$OT79w`EtVQ%L-TMOm-UfhFHg?No8k+lvQo z@xy`dAzR;z;<%z~wLXF^8nVK-CEesX^I=Ywd|$^r|6JITzch2d{CM1<kAuj-<L~xF zGviMl<dWIQkvr^i%K!2@(t9ui2nemoUxaR&)p6;(r42bT@mBj{ptO2Z0f%v3k>NWr z+@%21xOQ*CW8*f{I{Q;#o()c+veN@vETfy?>Ma8}2Abt5hv&JRx(cBE)U6dxawNTH zU!1ZOQ+cWoYW>?{K#gicsISV=L~cDD{RJg26*#GWRkzm@*b{1h;IqqkN#wm*Ya9Na zVGX^{Naz=JM+1e)9X^T2nj3vJc<(bzqFl{X!;0dFrgM>a+Pgi=nx$*|>Gs`O!tNh* z-{z|$Z^L&<a?z6L4uW}s6`RBnts|aMOA*Su&f7h%e`8g#blDW|cp2~I;h5H!jE||= z?<5Vs<sQ^JqJ1naFVyMSY?4qR6A0;+$s*uTQh+)U1@z%}-(J$N?5jC48S`<Z=t%VZ zQ~P@tgls4U58Y3VC?u4HWfpqi>ZP*uqhtIkJoMwO1b+lKe><M7v)tvohDdt)CYR>~ z$|JE<aqXU)S2vvBYEV9*2=GxG&9DyBs}VR{9j5JLQo*kmunh>^4zPZ7^!_{Aw1)x< zemp&SPBJ5)cxP8#Ot((a5qaT}+2jy!hs#dtuD3reKS!~gZp@rGb|mqD_m*_6SNzqw z<QN_)1uvtYu)1TKN9CuF>383(IKq>i@#5C5lf9w$_eH%Iw7#xp!T)`6&C12mN3AnW z+-SeX2M5(dOIEJCCu}a;3+nV;{((+4h@3rH+ZUN;pF1oX7gF)|axGy6IqpnKmkD&Y zcU)4BKfFGC_A4|%67ZP*wbpljm(R$7=ciZhod10H^Jam0Q=5gjm%Ku;97`il(_=); z#OkNxVs=Euo6oPrFZ}+oayQQQxLT6l9Trzy$^MJt@vj`ROmC$T8qbl>ndgeCtK|KB zlCW!-jQApT8Q#6LBhl)Xq%%hX6a;DfA16nzeU}u<7%@4KOf?l`C1(K9k}+je3<c@L z?F{jE|H+k&NY*uz6n?69{TCTILjw5M){>AV)ABBy1(%Ch!7^f*yaiw86L1($<`OWa z2AHWAKFvB={XkCC31QbHDG7YN$A87mgv+Z{l3{A4I;xFG>8%t#e<)3ux1E+Yk|5MT zV>Jt=Sy*UK<X%cTByL|Pn3Bf3H>{*e;8LPV8eUrRt<U5W<e)mr)k!FQ&m*)%x3%l7 ziOaj*`|!VxAG6&s5kUG@$h)Q*SZkXlcpgReAWgcQ&Qb~>bk3^9%)=wvlUJT3EsO4R zO0!XadKJC{45sNz+?afoa1B;}+_ZrKUg=AS9{J*_?mYr3%P)m-28j)p^c*zuAd-q~ z_`a6iR4uyqo<F0Bg2;pvc|QpZZow2l=W-`75)4yFPb8tVRD-Vgit^r($HJ(6h>6Ln zeen8KLG8U~ViR^%u!gh?yErvt{J(0(*9S69$P$1p8EL=U2`0<#K)Urq1qMMEgDHq^ z9&@2$%Swsx(=1mE`~D9oaJZpN&7V39Q#Ve_(JCMb!08Z!X-0~H)nGQGYlP_LZy#Pc zC~)T6u)L94i7U^FP~#@gz}gr6_UyKXICwDm;rD!V+bVH(^uM|3-tb+ee!3;E&jCY| zBz+@cFL+fZ91rz5Fv{Vl1LEO>r#6ScKYJ?#zpkf|(vtE?V#y|H;Sx_Wrf+qQG?!BD zV-5-W@D;ET0t=ycC^1R-VEXDc7q`AS?V0W;*?F?k>&U-yx_@>Ev*b*o$^yTHMEmQ^ z+IK|qwX*MP3a`7Z-<s+BJTiS%em%{kYXB@D$zAx?bNtWZDZ5fS%t`L$ap<n+{a#Ra zIBzc*p;K&xj-({XTzE<SPtKG;014cMo%k=Oye<lCC>4~lF0pE>9LW^X2%H;jtGa&) zZ<?|9(7%-ds=K^v9{yVyK-MZ%#tFte_3uhk>yEmoRaW_mo)0?eCu@acOiKToQ{Jtn z*&6|qIcL|6n_qTPvh}lUI$K`#M1K*74;ue11MunFE-;Ix`qKoIyvDoQ-rT1(Mj{y> zlZg*cK!+E;`h>jwm(ujnP4N9>oshVy1nnv@h%1|7eUTQC!S8qi)2l)lN(Szp`l~dJ zri$Im*AXAMP<t|Uf27z2ryuEOY5$V04t^m{bEK;~NP<^4M`^lq%l3)U8JV&>&?dH# zIV;1~Cz%viVJIPzYr>KSc`SO#_x9??cY2-ww=%$JF3A1Udp43AH87?Ip;YFF91WF! zjmiBgoyn(EP0v3AaU+!_{d3CWuT98!y`&4~6rqO2qL0*27D6zP7&nVD$WLe#SGuKF z_CHF~dm~~FMD?k;V~4!b^AZlHDEy-|HMh*soXHRdqW)cJYEsaj5b-}LP3>>aXD0un zG`&3qPt#X?U;V#Rn(AN2wcOiL{P_PXrRjZ@A9H7CPXBlnz0&;OC{5*BHW#yW);8bJ zELDHLEjSYLbE)`b%g^PKsI{Lf^i<WYchyB9Tkq>?Tedzlb*^oFWZYN%^{Hbf<kxD~ zO3Sac-XCkfKKFC)-)3`^rrYbIa;@7N<2s+Wzc4NL|K=!7_iZUnzbwhoV`Z66>VELs zZ*=P0I{`qGDbLj|FHp}9e18*u0b}y`Y!h06uWcVye(iqi2ABMLit*cpyHHU!mGvUg z?1PR#IG*MhvuPs!9g!es2-^o?aR&?g@Ip?Qp^1bv<o9Q&_yPhTcj1~=NJV;|p42|B zE2#%@{JhZ&E^(OmeZ3dPv~$!qd!>$Y8SkhvsoL;<?rd~2QB?x`0Aqn}9J>OPkO>fS z<Ltc4<=I6#d;i$&g?gvz^n24ni=Uo{5PXg21`OkY^}PXERtB(uoYR8C`@V^!i2`l+ zJ=}&gixd+DXQMD235OsAKO!%V)V{z1#k3qPH=*R5Fu|lO=#>;}CwW;b@}h7#lBgg& zW_823U4C68jf;zX$KX0&zQ_WAT^z=^(H8}(iGF~sqjg)KR1Oj1qo;g|w%V7N_Z}S8 zpXLLggH__oBHYSK6I39e9}bPT0F>8Za_FQ~zH`Zv=VP=fCNg5Ql4@d}UhWx^UlJF} zADH_|cckQ&jB!aCP~~?(A63q;gNPM!{Saw^{YC4A2vQ@Pk18*ogm|u8XJ+a97@$c3 zORRgU)V8M-r1Tzv>}Q&qW4h5GNqm89x%pfHJYD=m(#!0=f~oanC-TeQ6;ka%xXF|B zPYJtVyYH(9HOPNE{rEEb-6<0?IY9u%;(0FOt6zL*s$srHOryq66q|reCK=;(sVN4L zfzR6iz{MJ+)10yV>A|+Xi6^pye5|EGa!Efd>`{>KTkkt9=xX>mtTMS6btp7Vs^Z4L zlbd9YdY^90aQ~>N?WIpc3MPp?G%*K!jA^DU6a3ZW;3>vAw_rcts*KWUL-UtfcfD)` zZ3Rbn`3<-??lg0yzF-aSR*z2v@ObxHa`GS824eP5e0529^S(TFw3EKIAX^G4VA!Vr zAk1EDDS%t#%7lkgQ=ub8-b%^6;^7PXM;Gjq`z<>i9sMsZViS@EKVJXYeeusXnE0j= z&S^~9wTqV*LP?4lna)mBw<+VgQ=q^5S;97=UyO-94S*#qi<-lZYp~o7aBLPxs~dE5 z=03p%IK@j7-CN1Y!Nwk1?Fc%Y`ixsgHLJ-v&7|zho>3W6{OITQ;s90gGy_)XQ~17* zg1>*Y%~;Gexyb(<BjvOg#PN7j92Zb@BoI++(7{(uM&g#+i!0O*?Y$6j?5WrnCNqAZ z<tlLp0*U4*P1kW;jXxh7@0KON!w?0cyPr^1t!2MLF5!J2cE``}7NVZR6$WMsR}#-w z`bRn@6muRvUe%UXETQ9(1H7~@vphLZjUzZ1;^OGEqNWs0zZW`D7NA=1zx?<kj5Quo zJuPwKsYwFSN4UB8=A-FzAA#-JqsN4k^D!If&7W@1mA=UHkSWcY*T5ILL6(Y7h=|^h zAi)|WQI%n*5kWWIEB-B6r*S0Xyon@GD*IzRC7tFA5{`8gn*pN7Qr$cxpKsuzt=vM> z0Fgz3lD$?8b2X3n{7=Q)G4IQ+$;>6%R<sGsw+-3dIu&1STrv9~Ow`B-6gso*x3a^o zjcRyy7lk0tA{0K4owVosj@nq_s)r??3TY47TfJA{<g_FtWJEDVXIBU7=h&?S;9qSo zv9nO3(k(No*IlqI`qsn&VeW#+pgFcU@|Sd9#3if*aH=?Af3L1e{yx|zf1RVzT=>_N z>W<aWxY+}1VpNGyozK*hR{92t$A#P~j39O4w+cj}^Y}otD_GRL=d)S_+Y_I*GOeg> z97B7bk0*%?b+YDTXph7^)>ZpH2$`fmK@bNUTirmO#iwTm4898meeQH|{FVrc{oqa9 z?9$yGNU|Hc)6biwr;k%*^oYBBwTpeGyQA<J@mr}AX!!bbBxO}+eiaV6yYu6It7;_S z%Jw^lyIV6)V!bo({0=P|5*chfzj>f!^?OmLh!y^-<=eZCir-ZJ1BoWM?3^UzOaoXJ zFq2>!2EuGWKnIU?zez=y`pQMBEW1#-ybrAuiSWpQowf0CgU7iX?YJl^uc^kIgNuqh z_??NnFD%lYl8_K){hSFYgcBoVco)fu%sgCS6u6DQpuf3)P$v;4k(9Hnyh1wf!-8{F z*x4WnZ~Bje>|-zqu|+aY>bdf3Hg=oL9R>m%0Ge!e_$ZPf79I45bbfLJx4-T${k(k= z#w#n_3y`B3;b%4##DFA|?^rz<l?7kiCb;kOPO9*Zc3Q1EkRKm6>4bYn_Js0bHz~N+ zgcSGOvw2pEDbYvg6L@E$g#L2R#K<b7B0m5LB@1&{=j1{;FBag1M|j6asQ<{gUg<)X z;2l3HO9%juUKU#9&MM{K2de=1LGCSl)-#{L@vi*@;3NbOTt^Cxxyg&4&E8UvS!suP zvC|eeHCS(m(_oI-I<5eoQ6&MmiU5VhIqw%!z)B+nm$-_7IIaa;ecGiZNeCC1>SF9` z&zB6F)i$UGKFEL^>82tPOz#q8Q-hEdyy!y$BW&C%fZMVXwV~2p5VNrgs<)#6ZnoX= z&_pc=QhGV3K0Xz7Iq&n14{#$|i1UZ(9E*30&I{SxJx8`g^5HJ0<bQwyXc~%BKF|0e z$i+T}+zpsU3#!VATEu`G1e&#iDuS@*4S0EZ@v@<W1C4@a{J4B2FNVt-Fr{J_7^apL z=MAp_d_?Rw$|Y?zUW_BQhm2bT^3y}J1VEPr3rzhkU|`uZ_`QOPZsHb*OFAT&-<Ay@ zC^CmY?WtM0p;<NqF_rS*(Op2*_u`xc+>~x2f@%A@OK{FjNQm=Hn(Rn};I0-677(!a zsPGgD=5FfM%j$X1r&kX{5>Ozi&m2p3$x^FGSa~XJ<%qdN!2Y2ixo6O?M$B^*N*19& z(W$hh9Vy%il;Dj+qHCjZaTLKzWb8ElFIZhmLA$S%E=U5P6(~MJvuxv5W5LvD;4<q{ zyfJj;kYE9b$z)>#SX_VlF$L_*?|P~rGaqW4?;f9*)&}F&7p!NaGg;W+f05dqc+`vc z83GSf00J0t^om&<4|=MiDzsSZX(`MYbB$%hA-?As2sp7)R<xp)mZ*eQJv>%!|MW_w z8V}Sl!=wUTPeEhQ)yD3XpnkdHxoWu~B7|KIL5oI<0B{iSV!?0s^BN5x%gxa>Y_w5e z%@O@-^9MDH>X|x6g&xz16$|$E)}R+HMf3x|CyS%HtobZZYka%TZO0nb%BYD9RG9`M zAjA?I3EXEU4+JnBS+KvF&VM5}Fcl0e0xDPWwV5BdzELoIqV=y6E|A)AS_QRr5Lz6* z?z@#h9|^^|o)wWAG8x#qEqD+W@sdq1#aFbrt1LVFyQ<aE`MADym9<{sUoS*(+9G}W zUTrk)2P6cC4LACS4JSA;nI;czH$C$S$PSAM+7!6RIek!&jnC2LH11v|LZ;y_B)&mK zgm55nX3(eGDogc(gsURK+%>A+)zAfGZ$Rsx>*yPFG)Hn`DvMg>aN<;>6guiEjY8DO zv$l50>tNXOT`V`Q(tu!6Xozki^3K+o<{b*kzaR65gbW~KV~CYoY~(z=jc7{eJ})dy z&e6_AZ?+-n0E)(`I8e|FDTs15G8t@t30AMtYRrCVu--OVW(unjp@A%c?*7bjW@9VS ztC}5>f=3k*QOPXqB{I(+GEcL+=3iKyY$SK!mM>qc+5-CFcT~`M<QsqRDg&L#{!5x? zk{A|4PHU`^goi?5bcBT<@KFJL+mD4-wC{05*HbY$0KA>v{5g`-br7xSK-UmaZXXeu zL=<gHL%*OqARcCY>=M+mSwbRcbMjz0i~H_5bTc`OT8(~Wj>;pnm$Gm6e$?~d1Dv!G z;IMt9UyXH4^w!ReAPAvceu~r7L0u>IJ?qg+vH>@NW;sVx)mCHXL$eeRGjJVUL$&&N z`_7fbG$<bwmfHs*Htx?w<da*=DX1nexBw4MFW-Hn4xB8CUVESrN9+>W;(zt9zX?3{ zSp(En92oN{`R%6&%i^7-c1wnyCw)X~_xNYc-jxnkmJN0++i<cXSDko~t)_+&v&FDY zkwvr~tt@4+7=?xCK7}ma!E5~XIt>I{4DbWVV*q|QKRj%5I~(dffaeU}gNM5LW#mDW z#|@XgfIk~qNgQ&wRkr0;JT*E5&t*vDqK^s#M2{QI_zc%^-!lgK(LMrI+IO{k%!(;j z<9AAwea96dDT2Kjn6JM$H60+2G5SdIw#T@<z36p#1#jd9{vu*SGwnn*BdgdzIa08z zV6i%obR7}TyQhh>ScHn1Yb>IoT3tblk_Ww#w-0$JY*BdO@v!nnTh69J1&o`)9B8Kb zLgOFY*;X=TSt}nXY2nO4H}-v!LL~>bezn1*FcB3l=m~>I{eutk)vueYAt5XbYi~Mq z;oiGBrTZOYNs_p)c+ehz1~On)tZItCK+(3@1zS!V0nrAY`evZFc9wU5k#gt!t!?10 z>cV68_<iPu5v-UV3uxuy<Jn|6Y%25n&`@6<8dZ%Iiy7)|Q<46n_h8=rYC9FdPzan; z`l{wRxM5~}bZ#PX(i>WVfEa=@D*V60C%$B&AdHExJX6VuNXw^`suFZ@Kl*uiI7v(| zkZ{e4jx>J?N0g!!Rltg~kB^;JLJ)Gh&rMxSKnf+nB&a+bykLe$z+ZX#djopPd`zZj zdYJz~oD=VN68Mzk@mZaga7=*r&6F|wAyn=^%eSekN`K1=M4W@I`~@=j>l1EQ3BR7( zJx;r-i;)qsE3MB~R*Gl#vWlR^OZfpNkA1KJh{2rwVRjcm(UBX99Yi<&ej)!fk85C% z+WrKhPjV6iqC6)v&yJM<H*W%zXuQ=A0r>!xIR#@5t)K9HhmHNPEqAs1$$0g1yko-J z-d8<_-oS~gKQsqp!jS%iP6!K;wt{wOekEoMz$8)%p^2vN1%?jq3vTq`v{T}r-;?wx z_fa3bXaJUK!)5YbZ#DBZqc~H^$h*Kj2xEcyQ-H_v;zed-8$M%I49#wqtEONQV2>a~ zWGl&B$e#ZjX@JWZ5hMNlf+Y0pY3w@nu(2BJBC%~i)}fIapr9&Ogr9;}^wOQN^PGYO zH5B%gyL(Lj_+Eg%Td;&1kwaXp6zQx54jwd=gWG|Es(SQs6-6OSZt4Q3RJlZ+J6oAP zjt37K32t#=M&LJPR0H?NwxuV8s^at?d8*vsxe8|Y%5MU1iBCOhz>pFxcsmi<gnxsO zn=;)q7s_9vp~^4x?CP)zsNW)Y$xJXegae$wIc>I^tjHwl`y_tU=j)^8Ui_RM2SrsS zcg^og|A#_yn@tY)k88_k6aF9e-utP^fZw-$64FDG2Lebp^eTobAZmcn1p-n<F$gLG zB3(ey&^rXA3mTeq2q;BF3`i4EqbOiQssgrv1v@8inX~WgeP{N*Gxw)6=Pw8|$xOnt zzU#BFf^qNE_#Y4o#K9WZzC(3hhB#Y@X(dY?n?qisMIz6mQWU{s-YO1%HQ)R(`q$X@ z4O!sbN7bBQ5wTyGL>{c1h3@3+9g@ZNihLY*P+tqdzrBpUflt`Vi_Z}LkkpJ}vC)oX zWP>}R9`~_)_7e+A<?A7esXNL~AkG7KDnRUy{!c{5b(YS(Y$)N<9^#8<hl=r?>|}JM z->UkSrLB#_#?>l^sTI{_Z()snm=r4NGzC>1;#;Z}u7CRTwFB4&4*vyA`KNOkevX1U zUz#45y`rSvTR5z4i7K2xSFkXVY)_Ym8b4MwjnbaB<U~Jd;C|Kwt@eFuBOcoChxiKF z_oeJr$QAX0KF$03-nYlmWM)J%<pG59EM}iZ@wDcN3z+H&bm@BUu{poX=f5|1Y?`TH zI?0%pS$M;7i+=kbtqYWjoja=M&~YY>5H7rfgZS(2eVXvII&AsjV@y5wyMy0w>%On- zEwy*7Q&T!uZvR9Vnt+S_zgjwyrx%X2;1Rj6OGaL+zoqyR=GY^T55+lRY44D;e(xS` zy;gsc%m1^kkl!P7w=kvK0~KEXsS0mznYHiZyPII}8e#XPzaNT0^b-h{Y}NnywJ~6t z@kG_J(LqT4b4`AOOD#0ZS(NhMqP!%D1OFT4y>+;}C+;t-H-Aba$?@|0Dp86{gLAbd zJXz9p?H?%5d$`Q?om=bSTMxc`bA3P4T2F)bh_EbV(>op7`May{5A{ZVm>s_4{>i&P zuA%F*R7n+iK-Q+hHWH03QWHL0xUqDd=Qm!s<H$(4=jS)QXyK5Lu@=6)<5ekBXgUJ1 z!=r)nPm~w*ymRZ+WMqhxMlY~Nz8xUS5Ej#Q3~LFP`O*;l=6=OKKFW)ovxSD)!6@yo zdRDbg2^FEv&)z)4Gr;Z_#oCqVIR@X@v+NRl=I7TBulXqN_HZmwhFP)#VBVt{<$tW9 zZHSC7F)BbbcYTMh6O@kY)V*9{UEpM$=ie`|52j5OvQpG;is-p%od7hW-%5+vJwYW= zmF2IRMnBg^UU!-e%T70*NHZ@ySW-1+E}l!(u~91adn^yJ?$H9`ps2dLna2xs7-yo- zw(BSm6lx1~pcK`7w<0XZT4UPpn*FZV6BC?MTDB}E5S<u4zC$Sk)RT8a&*79&as^^N zMF)sm4i?*vU3apo*5Os5Wi8$gOuxA(DC!jKsVQtgiRZ&GYAMg@fTM-JtE+1n6`l^j zghnGD4-jiMhT_=|?TiXm3IQIc3QwL0@@L^<4(od!D?awkKKdn^bHzRkMS*?dF{ z+`pJ6bNB={cyL(jeUg}yys<F%`1G;vSFShSjqF2HQKa~nKd*I|a)Ru>OzTWUClZ$) zi&*P`SB?%JPTqF>`+aqR?>oC6svb?fi`@Qu${=!|#3q_{K+SdNyR!NnVLQpLu;N%w z!(Cj#ktqT+P`AGRwpO5Bs$L|o5S5!x%KBKC#{0gRZts$AP4fG^``D`7Z-$auN!<gT zEr!EVrSZF!zu38WC=?~n{|DjGj?scAre4NB6c-EybthO%7xCOxi@=hnH$1EQKD^m| z%~pKXj3Ln+M*<+tg=6Izr={vlciG1)GIZ9W7m05851SN|z3bFh{hN~pu0{KfYzvGV zYH+tm?{}-r{cG0tp_nS!P@hK)Lenn?<@i~M<g}9_3X>}2z2y@>G$jkC&ukP%ygjk| z-4EBNch@b1NhlxzhPk51h@CM~VZ_xgrc`AHzWUVSM)J91<*kLTT}{tvYb!bkr4?`6 z&n@V`FyZhcf%@C$@~t0jPScMcnhePif;o#)_@9W&I$hge^Bbs<X%;GU7)Ibt-4-LK z!x9ji9&nM619U+O0EpBQ1JH33CrRD1E)CmK>P7GCj!VhUW8B1(&QF>?P%E=CllM;X zvM_NSQ6wjR5amGB4WR~5O4(pmh(b1}BC0D1KU+|pxh(E9aG9TPXN|yIIB-R`^$cfK z`@MF)4(f9#X~n5WJLj)0R)5o1NuQttB6siK`PqT*F!Go0iG~#^>S%v3td9@Q7ep$_ z329R0wHcBU;O8D2hbSH8RbGk_eOF?}5+Ic@VF&rd%R`p6*c=rZQ`;Y!k>()}CmT{_ zf=#gp7am^ZGahoGpILeY14iq$misWc!^O4+A`BU%COKuNFQH^sw@T>wE2(<v<#zJQ zq#+glcuacvVEJX@apTfj)5xnB*`eQAYnZn~1NP>+8_d)gUYa^S1}Y{TV=9yZpsn9; zsMS)2jUEke``bBLNk~?;`li(7?sHmRo#nPLRE5{@P7=`XxudQE&5Cw;PpvaM0UXj6 zBAEE>@u?Ts>Fx7CPkXt1xA6&w$le2G3%UFUr|OQb!YPitqqQPv2XlqqC&lNO4RvdT zHEWJ_x`-C=goni`K2GuLOO#q99x-s#$2idz&YOD($cYgVB~t_9*L&c-=c9!do<_=t z_@R{#{LFJ48q^mqUHX05c&7OK@rWe*LZdKPcE$wB)+P<QwS8<O6Zk!ceAqmemF8o; z?$qolWMiQP1>ly{R`(kWHLsY^Os}D;e?&)vj_vk(KE+3Q6(?zt#`|i6{VKICj_nfw zF+*b0J&$!q1#-28gqdOTZnaneRWn%T%wp48{d_MCg0bJfgsmz(Bq1x5+21HH7WBb1 z_UTRUZyoNePsyjx&EIqTIVIQmZFr}bTxi<Ukp(f8bhuIOZaQ@HldjGjh8{g4loz%r zQ%|h)c&3k;4wB#I%TAzb`8>A*Y(*DDhLwy%(e})lA*Cs5hRw@#hv<Ypett>C<K}aT z>F;6-zo|#=Uh<Xw{C#BEqAY8lT;AL{*tRzQ@N(f+pI?d7I$uT~_pwOGvCh6T?kVu( zh|*vtps7bFP<7RqL6174zKXPi$wrS}-q4>EmVXloe=O37aXbe-X&v6K9;+ct(=51q z0r91`Cs99x2@J$mDvP&h&Zor4^PdugY*P)zPG`vriryIBA2Xa0t}{G&Ii>b7Yys`; zsH$_iC@uJy(Y^2QRiDPEL^fYZ1z@xA<_G4IROLaW1B^m!A|0^s2+f?o^`oxJva7l9 z*87NjUt8f&Q)u}+DB#J^?EWkL=g>Tc=b$KG9Sz@k+%(Uz@8}qWL#0M#y!V@oG;)x0 z?OQy>p3r_VyLo)dV4>4mn1&r7Ftqyj$y;tY(uRZ};)&F;2K2sS2q7Oet!9#qp-E-F zveYRtvN^`SfqA*O{q(l`s%B5K44=+k29wqHSDK_#ObvzS=_(#_`spI_?31ym0WGaH z{2rM7+M3~5^4^H5eLLmfm#2wtFfz9s6u0SAq{-P@JV<)%ETTCQJEcG75M?|h-}GTD zCDu6aV@Ku639GZ|Iuu(xjP9)BVx~Vo;D7FOhWjP{j7%dlIip#Q@TwLiDa*&h^j9NI z%Q`axz+#4pnQ-n*njU|oIGyS!&%9zSejI|W8BqFg1^FlZTZ5SlHxnVpO2g`mdvbRv z0S*4Wa!`7m%@-eeSI!tNn4YBPw>6K2{7w)_*iK3Rz4xP-1l8hr9=m>Lg2Li?3+La` zv1{%}3>>D$rlH(#85DB~^S9p*80cY~)J!;S{>E9voq1k|5`+t)f6EKDqkc}`22<!z zF@wP*dEOQDepKS{*liudq<c5hu3qbRFs_0f65SiCgQ!W{Z6_J~`9|H0u{~2tu1sw! z7CtkshyUFM)|e#g);ThF%|Jy)Zo=g-jF|+^wxogQEA{ED;;b1Ug9T}6jK@Xagt=_< zdv+u9vyn3@S#c6|gUi&*98mHzd+UD_JA(qhGXOAN{YhgMDm9wbPg=U6{AF<GbzylH zL>_>yRkdbv>)xvyYx(VpBuCuYWdbUtDQ8B*4$+%|wAAP^6><W_pm~?!A@yE?p#wge z0nn@{|J2x${An~Jl5E6XG?J4ZvZ<l2@`^%fsSz~I;f^#b>do4`AzP7QrwIJ}&t|ls zUCu7Uu6`C=nq<PsVUL1g&!x<LHN##*!%!^hKjNYR00y`P^Z73%-s8U~@rUkq{BIKf zpW~wcBJpxX*8e2&v})V`cM|W(IxzA5VBSJApTsYYSNxO2Q_tKIhxl%r&BkwH)-~AF z7XaVnrTy;y2Z>j(yS(4Csx6-E+>9a*?+|y8OE#3&K6=tTUP22-JA9+_-89?x-sSs~ zZFdsFz59TQukaE;!&~*7yzt1IJ7#oL<-$r2W#sz5;-ZnyyOFbdM`DIi3LU>cZXJ|7 zsjkN_r0_1I-`T9zq75{U$KCo@T=c@hLA`<Z$*-b3FfhxngFeYSl2{?qKZ*}yYH$Vd z@TLzZ{v8*U{qgp-*`LDY?Mbzj5#kZj|Bj1Rd2P@4lRURk`F-KvanXdrga0Ki`gkaw z@<sn&anWNDV$_)bSzL7dy7~W&i~fI)i~j#W;$=5>T+Nlvr7YEa?5%hwSo6T}_W6yU zgSj)8##OsFWsht2Bim{e3s5`Th^TD?RA5~9_PNj8eLLfTJ#20t#r!30jMB)=?~w9m zuSW<%&e20O8&QhmN|1=b{$C$%Km7Z1{m9YVe^vvb7}Fs3;|;w&)ytC`^I7pT=Gz-K zk|;21c)a-07!MR>{g4pDuKcKKjW}FQXY6Kr+90udg^GlSWqcWEmUX$9N?Cy5!^ehX zrdAHX?$AuWbV8#quOzt}`1b`rGf!UavDv*fH=tq@EiZ=Q@72em^qw#KNjp&QA`a1N z`06ULUfcq?b8M*h5ng7+BVCwFuJI^O$UH1^_#I5XUoNjo<fP(Z@n@CzD7IEk^hCAn z=9pD3MIj|lu!e;6)bs^6m}&cK<hR`&vozkwV`kM{H^{@rpEJ!bxo)QcW%EDyP+@3{ zg|gME*a7B7L8Js64o^UMur>;P<%ZQF3_){oEzDaR1;YI&XreHz;OZAC%-0^%9hcJu z;Xd#k=g{|#A72)Z^fw2x$cCp4uUWU0SODW7!}ieUONSw{hWABAuAg!y^@*P-dERc| z0^>hyudgwFt5)dNY({!qQ@8hu*;a;~DjB#=N>g$f*sb^RGi#4&@+LUWt%>NU1hea@ zDz;Ag6%fR&IX{bC<BxJilvuL32EJDNIKS*mjp_$q!zrf+1-)Nt$;o$#bdVwTTluPC zcG}K^G*G@uU6gQtwST;FP!6?p)y#g)bi$OXUTz9UsEsyww9{&zXUas0q`Gz+=N%Tj z*hIheR1T(-aUtdDq4z_sB05f~K+Qt)YR6&=<vIKXdZ|2QkGo;NHWN>QATFXPc8*`u z?Vc>?AVN=gPZp+Zqjc&*qDPHrowtU^1Er8csm5-@``r&39R5f4)L*j6RWeDe4VXVM zY?1v``K#1S2o+#~fW{U>jtI?bYNW0{566X)PIA0~m!Ua#!@9cHY?~-7y35k#FEVd9 zh!ZfKl=u?!?guzE%%w}O3Q`hDGAo0Ws+q$%N8L$B#RnCav~%7Sbytroq4eW^dgtfU zN$X@}%sV@$5HPPyxW1K=b?-G)Y9>!hFv#?|&})uq;w>cJ&bX#=Ffpho<X1M^eX7Us zN&Fp+K1N;2vJ^w%B?<V>NHsdT>u7q${1DtnyUD-@Ozi6MM2U<EDUuNJ9ECgeVM@}J zyEanWv9jCx+x6kXNxyP-xfQeDsr^2)c;c48_ITF;p#=V3G$&E&ZRAslCc&0ik{cAV zqFpLw?0K$6V(S(()C#B>SNB9EB}^RpeEmI(VAR$q;<}uyl+bwM*bOepcW!hy6nx_< z)XTk}FHqJ=DmKAVg;T~}QN$pt*XO&2_&?<KF3i7e?}JA6eb6g?VtT~AMGF-sPARJv z0`Rvjgdt2=>+6QK&d}&l2-_SO8o+f+Cu|#;+oA3;u=^lid_H~ZNZXw^xbuQTcU8|L znca_5bfgEPT#k=v)xA=L=rLU1h-;eigmO=vh6}ead|mI#C?iQ%UEgyXbC82F2auFZ zTfHXj)jzc`O~bp@e1M%pW*Q|}h*Vj>R<*6q&^`Ej!B_cv0Z3xtQ8206VA0~14aB2` zs*clJ$CO8qtrm_wzpoH)_o%A}ua{msmn1nV1l#-3+wHC#U^kX=0x67jD{o(};3cVE z|Blf$kP&T5`>8?GKF;tuoGFSl^bE~m(w0oj1sI$M0=#TQv8~LJ&NG1Wd~R^_jC$LQ zBF9w-t1+9ft(ZX-&)_EZ|GI_pL76D##BC0~UJyOBw7`*YHc`0n#~4xU+CDm$9KT|= z{T1VvdXZs<+qnfX3stD%S_t;wq4m!#)_>F~^FJJW{u0~MeySby`Dy%Q{$iWQu-bK5 zq0xPRjRj~7iN5^oApa=WVh(l4QRcfj_?M{Xesn_Hd$3l@<!628pSdHZnXh*4l{+N} zY)M}@y&aZxivZywsyh?1Es1KQ2sz|n>7e~VewjC^-dsG|$z$ck?-hwu@JaXC6Vx;9 zH00|jG#}%<wmQ!bI6*4`2#K(kqW*5~xa+*<DJJ$hEADj>|EL9Xc`i=o2}7vTqT$58 zu5DQ2=IKLLW>6vIP9EaMTqNFKMj8pg=g-#+y1Q#*k<n+jM_X#uS%7E4g+s%2r!j3j zo5X3%y`|{BivbY8<a1Qwg^QT0^hAMqetk6QipW`rq3}oqrX>XP{0utuL?lMYBR3^^ zaz41JDr)aQ*cnUk<rkY&O6)zD*-lmAgAtZY<{2hErIBl+><>Obq;^y$Lbv4bVfE^H zyFk+?#MG7O#1s3Rx+9fC!#h=yUh)SZO{M!N*wbTa9RrE%1wzSF;v;2m0iUxm+s>qp zr7N{Zi=Ei_U=v*xVw#?Yg^*w!qNnPkbqjZi99N}#pFt&BolQ+k(uhxJ<7B-!lX97c zneo6}rD0BsqRn_xog{G4J!_Xj(B2gyUn<GvB7A7bzUYVx(ZaU%m}jF|#azt1B{**# zv0#;R5fU#@354)8m@C9@({2xnV_|UO=P^t(IqmFNT&F)66^VVml-m*t2(<g%bS89N zC0?UpJEGCon7LY^;UF^fdI;l6M6PmaE??=Zpk#?Z6YsDD3%6K=S#J3C4S+xaMWgc% zO&@x9k=aZR9~Q|qlZfn%M%A<TCs~>Xya}rExOl?U3myvClR(o_Vw0}Q>qu~W4Dl8j z+oghL4KXAmlJy~>`_mX#0CW>4NFgH6?ME&jcNkm8HyX;2NFbbz?C?2d3V|0EU>ZS$ zM+o}XN+wi0SijPunTzT5Kng#zX`o!xHOe{jLu`%h51&utgPhm2bTMZ@AkX2BfyC=M zf_W&mlamDj5#Qd1*`Q1He3GibNR(k(8$JJ;D8O0S<NB<W4)K#rmvd)=KjwTP^r&1R z=-zm*c2A@S1=YmfZz`AV5RLkd3SBk#4cvO`7Id<l^_T#ihiOyx!sJQ{A7w!0D)wy( z->k9tWe$GRjSUJx3y+>Pc@%azBxOeo+7cPMdGhiRvs8gcxH<9#<9Pg2GI*9@0vost zTgU07D6&1UU^={jv3JC!TxUIQzcq>pVvA{*7Iwsf1kjLj3Du}5%-1@d2p_?8n^6C} zb;S$Z5M6Cl+?=hnaWtPMa^J?01Be1=Eb*mRQs<bI<;V~gIzzPDCE+-l2Ru;(Hz<cF zkBYBBp!@iTaCOz1>u#+z=<CcY)PQ}Kbrw<uHM@k;>gH;`TSo-b(ETTB4=FgjdUELs z*)3Tg6CqKzY*Z)X7x8WEO3{`Wru=T5>(R2{4P+Q6!(jegdn)o6ql)KWABhS{Fihj? zL3(cJCMG5o(_o`>P8zLpffUq&Ar>&th(%y$5ux3y4O{4tizllZIsD0~E1h$goW@3H zGu$lMlU}C0y{lPnep^V0L@HoX3}TNlklpO6DrQqdV@=XerpkDIl^^ome8R}MVgyws zj9cBZ*u32|>k{cwxgut^3lo5@OL^XM<423b8uRUQB?(EDeJ8G}n`X(6#PLZtKc5+q z-WDne{4}omU3SJXHt)7JwmzVB%T~v<n27p?ItHLGo{aqQlXx&GJE)Oa4Pcs>reVG9 zHoC!fOZHIhG{_bsx0r;E2GGr;Ej!<}C`Mo&)I}_)*gX&qOMqXS^f8M8fqt@^K&WFh z1yxMuBk4AQ&1;6*p);yEiz-zEj{|J&q+XwqDEwOUcQNu92`xs&Sl>16?d?=rxl%Eg zc{Wy)m0s=pPO=cl6cC~<?rN%=>w<L_(KXuFCNuwWL_$LMMfMCh6K;~ws!Oc1SW*62 z#T^p3=FV28`uZx_Mi1LGjJ8;WV)E(yQxa@JNcV`a#r#}rv6Kjr435qS*UVwATKH`a zC8f|1?-O%pR@i&u^My81Q#9NLNSQs6IiBEm%}&&Gx*BTARv0j^Bw-dr&{50GLrF-} zt=)Zr4V^}zm=ret$Uo0Ya+=y7z0iL0OIYCvGKmb@tAn|K3Erz?tOqqahk%pd@9faY z@A^Ld(k==Vj{nNvU)X0CfeQa|+C-$?Boy=aCISv}n(R36_x(uzwlW>hjS)UfLw}X( z`+H|EgkJ36(?81?kkI5nA{>~%2EIZ75A^Yv1$Y1%{LaK#dkKTPzz$I$s@4f-0_yh> z#RTzW={o{J;o*UI#PiDqMpR^WAF7Zds!w3lrGdX|1D21590iAUgE%gI+hIUK%;P&! z68!g5m~$}}4@0}mi1?Kc#2x}D0HJxenO*tFq+A0#VNd`PCt%vYck9s*&^-FDEx~t9 z=#098ghSg8d#aZ{t2z?x{yk=Nzt6zVLqH$^gNI=M(s7ey9G8VY5_q?Gzf6RI22BIp zR5aC+6!p{Ol+ge^fDkx`h~c4Hvqsv_>D{Womr2I`1PHkRL7oP10bC{vEgvx<dGuD4 zFz!1zY9^gaTCSuw53zp}#Y}L2>8LzGjx&qEAH|$$-ky22`*axLJBVMIyRX!~uatI= zbnJGa^msl<N#@T1vT+iEgo$^(>-%MfEguF8oB!M|e7X~Tl!Hp82tw%Sd4!|j9+3(X z`sx0E-h}WEPPjeQFSy@@Dj}IFugQ-T*D?HhOCrV;<03Y;yc;t$vHRagA(RPsuLqht zq}*sezA-8b<UuuU)JZ0mYRMnmFtI!_QHM<|;Gd+-ArSX>8^=9q%e!0G5m+H@3*jL2 zj6}CRK^IU=%IHsy%E&aCPlX8&?a)R=@lM(Vp`vLX873oJQTM|?=$Z#j`3Nz#AD+?H zji5&5!rN!EP8pt7a)bb#c1v|+RJ(}DGpj}Dg$827oM%6ae}Vk$NFuE2)HA9wCgZ6k zFYCF>HCP%61YZf;UAOW5>gF#p)p1LiFBto$n8Avam#)FIS*S6xAfN01v?L}{z|)1X zWnw`7pBFJ5PXdL_JI)FZZz(w1MPTgxhh98?Hgj0zU)__WX60$dQ5}2XMazpZyGo%0 z_SV0Z8aab+_Xt04R^Dn6z6lF$jziTyMW63&p&vc@=amqDdvU!*%}x(xt&i=CY_WKw zl=f;)))Ww6mVX8;8xsQmoI~{;Yk~ThE}c^<p0gdA$25R1q`ieiDBuTh{;)G)r#(^c zSGQ|@L$u1G#YS8+Gk}v;IH0#E?zC7X@d(0RG!R0<*U>NeP^XIjqkX72uFf`CXoFG6 zcaKqDd`>>jxb~9xSHYnUbm_l!oB`9|$5pcE;6<M6NnwHmj@S^w@{PoH|4w$l|I9YO zbM_kbK*d<()*_+3SDjy7VMzeO^kFFE_^UliN1JM3@mS^ls;-N-y`1Y{PD3osU754$ zpMVPpp*e410*^bZ4XG}tkIq}7u7$iZhn7RvA07@CI(~4`-vIOrRyLd!9vaJp`JgOR zlv_#DH~FI(TC4tH{32()0AxVpzEbqmd+9vHz@K+~QQ5~+`Hn2HnO^)O@SV-z+~tL} zMB-b%t4xpu0<+YSYmx7-v3puSgookzX)wO1tnwz!TO6qES2NcH&olG+CmdrrAAja3 zM@6hb->8@IuQGE#5nih_YAM^>i)4AWKp5{O9;(1n){a4!jkPgM8ls4?uh<@Iws(WE z^%?P4`EzPj-jk5ks(ef<(BI8KPXvEH9d@zV3>6K8d+hiUHHj%9fkP1Iz?Ls(Hdd}~ zFa?~}p_P==1z((BD@Qq~_sk-$Q0^YiRe^6;ucqY}(ZM3h2OB8-+@GLwKeJQb-=OXO z7&rCRNz5tNp}<RH(lrV_64*EZz94~6E&CL8Md*m5`ex0bUasO5FYuJoX69?5H5NWb zOMTfCj24|y8{{YNs;2Ba-o*VthvEnD>K?l>RXed2kpABD3fweIJ?l79D6}Q_=eG4y zcplJsQ|)`%kgq7(i5YkW{JJCIlCnsRr+2c9$?v{TLIXS1l~<9SjK;d#+rzeupYHds zf4uKcUqYMKnQI84FB(UmLD)g`9e?k3*zku4;O)QEJ50gi05;v7MXUXIL=(^sZ~+pk zpndX&N<=01Iw(_Ki8=S5q}m@s@}};Ms#9{-szA#Ds8zP$e<ksfE-SPui)>koGM827 ztM(O$W5bxo)MF6D;JGr_rl;{DYKPx1-JNvfOSP9RF8xEQJ@u;p4;ugRP;ZE*-1T~l zd_!;C9*myoTz(T^sV-agU8m~k?SD(Pd=ej5cCFk~*E$}A3oE0N>FNirnw)tx;dT_b zctd%iY9+l*C9z@a)a#K7ug&1u8!{#<GB4Xy`e61wmm|k3d0i~cu7f#cKO)wiwj3F~ ze3%mT(a}pN$>n&}=a0whgr#R1bzg6Mcy&8<`;os6mgp{G0p(G7?~gx$#=nzD8k{+$ zLTB6cHdR%6rFFgs6tw8Ng&I^h#qJy;o8x2>Psj^Pmy7|T^=Ntp&hdJE4}d_EL_|(D zk^wT=c=_hG(?i-;GG|^kR78-CNkG6$iMP_SJN;@!U7h99GJpUZc&~!?!EDk+b+dGm zl7-PJ+nu*zy8Cf5A&jK-H8jUs`<F&5-p;@$%s%@!MU$b^-|OtKXLISA;|ub;t5q=6 zK}8_!cTnz@=tUj}T5BqM=;J-{OC|)uj#E^<1NOU?zi3Wqb+9Hkyw?>e3F9+KMe&U= z-G@MkcBK4%i`q^%uhYxvc?u}#dOQqIGZl;*83?I}eBxwfFLJRt?cxC!quK(kJLT$p zCjG;&z&dof%j@)Qr8Jo+DA%e;0!otG7t(Ucx2k>6FS*KVK_tuU+tl!`BXP?^6PMBz z$=Bp>e0!xin`P@suuA=Iyp!Rjno(Q$9CfwlXy$2=R1yTh13j7gm%iS6Ohc0%sIas3 zfw$DWZ;R5od8sp%Qz19rU~L$b!x>9x#=fodrTL<%L)B@sM5J&NF+)Bkzp6gy>df{8 zJyYUVK-01YohEu6MUf2|xh1KUb})ur<!;smUe!2R>Awx3X0|fRzAbZt9{+Y^x1ob{ zJah=63=NgPc|+iYY$k>q+9~--9+fG&<3?EfQ;*@+@l(5mhZV;^e`}KoKKADKix4R9 zL<BNS%!l@a$5zVAV#K6cr5=?tW<(#h4`I1N8AF2N*789(JAv=PBCf43O(K@{Z=Q>B zdiEnUg765(V*HB!X0+E!Qcm?-dVf5!0)K?c{+52QqxdGK@D8fDjeHAcs^MCC$oTE2 z)MgPq)MMn?-=WFC189`o%<7`dCyEuojn4@Ksh(0{DCKd>yf;eq1joi<O?CP9)Ugj+ z7kEEJTCWN**5i0?+sg)CBUY}&4z<cGm=zgw^Y-A>a!86dtv7nYG5br#F+??sH)0lG zYEP23GF9F$x`^r(=@Sd0OaWmgfQAhm(OY`3`+2*?QMslQ9_5dT(LTEiOU*Q=)UwU1 zL>V3T<uD;6YZXC6_ZRI)IXRG5GDgcrf!5kcQtv}ds6e(AxQG{7pP@FcX9InSd1o{7 z(AI;J7D`tW8rHL_xMJyl@{&YYoWp=tgOzj9;{u8KhlVrlLjWJNCp^Jzq8<a;nzZ=9 zgSkSx2Ndo5=<)>TWL1ZG)BCDg&NX1N>5Ld~)!xs>PY@u&1op44@Cv54hTh23k@F<1 z>4*dGaSKp(V!EQQ<TK91F5w;yEMrv<bi&_t*4F0rnI-0}jmL9+_l;(0DtJmJ2CDky zMTe%BJfqe-eJ`as+)zM?{9ua26*8n@fTZgr&IE5gh<M&eTv}&XB&ks^QcqO!SM=0F zJo3&QR>bAZQTxo=ol|S&ZN}S`&G{sL+0+yzgd<sOOpXGA4|cqbp0j#0fQzZWR#Bes zrMA)uRTl~^2tVlwgcw>Th{QLE%nyB>=n+n^ULcwI!qvbi=gVE43iOC~ZwEsKv%$z+ z@B0d=A&u$i<BDQc^;f7_E5cWUn#`Vuc~}O=-~7Z}5IJKsw6*O)o%Hg4jn?81V?7&b zp21E}<<lbsg2hm|Q5=ERPDu-Oz4fki>x-mFlz?fLDbxK>p_<XKwWhR}knPffXtg2u zYlFf}tvn%Lv>X&xc&W|&q+*~1ih-$-%en9Trs2CfT-{knWykxf(DqxyJN61?7Og1? z?lC+aqz(1@mQs0Z<FU1PzocypJlss=2Fz42<;C*1>DxWy@h1dAv@(}ixeNZIC%1MJ zyJ~$<W&9TSgsoS?(wTsY9$1oo-aKmBj%Ztr+8L~E=}p%VyAloWLTx++>SyHJRoCzA z&8u-AstRfW;A+9WjR!=|2p#_Jqbc@o#>Zf%4fpxmgny8DulPILF3wOb{3$}nW;cyl zKuWC>J3oDWW-yt4e@BSA?Rb%d!e}B*ryIND+m2Dv7u&0*I#%HG@<HOAnz^u*;)x8C zh2cuZ*t+*RX5RtW{d6CVi=wwy$Su`Lu+VshKnTS0onJ|7S~2liG}FPbRlfJbxHolA zz*#2)h155w#=Ai`7jM*y4&Sm?mkwi1ygGV@xC&R#v3hO0`Fz^DSIgAJJ&*eLpmL7u zFzgj6Ge5iC0ir4*WiOQB*R@1>S1MB2TZM6JZq)c%okpPvRhU}MfWb4zfeB3JE1Ss6 zzVjV{56^Hjxi4lmN4hWQ(3Mw&mmtFrx-HceGqzmD_;%d9xwNO;k{8i^BH~+Dz3*T@ zKIi$ukl!hwk(mO3iR3avnp%Ae#)AkG3m1$Ycg?8^g$2lSYt`f3XY;-q)(|^O#t6h0 z>HWe<!q-9Fu1~vLnA;8?%xsUA@f^l(p#0_g>W8nX?#9FlD^hkC)!#bNAKB{uRyszy z3%j>!t}^LU4rm1WLwR@1ke0-I(jTeTDVV%elLu#z@4L<8c7F4FA-{UQka7azagn!d zYOi9g*=rw4J@aZkcc-I;ntZ}_y^zeS=h7`k7)bZDl5Hq{=SC8L<i)`ui%QBL4cm`o zZ-(J@qUY5Q&XogF&ke;$t-MBELd@*u)?Z_EgpsKZx&E|#K1t6SYB3Zk@=*Iau{F(N zq?RnSi&Y68X-`w^c`xMMV>xte$90P`TAo*d*VpEmze&rHn8c#l%}=TOf^9v3Z4;FD zVx<rQs!CAdn8b!*9co`VOsq6rbu2-ZnV`x-sg?9+jtP)=qmt6PECAiTV*-1{FK5uo zyh@UT59t5RxDAS!-kpQ|xtE3}rP0#&>0PQwOrsnO!JQ;&HEFbexRz#?X~1{yN7hlA z^aR0zB=kKtP|9*(^%@Fv3r$F6Ih#4Hm(Eq|jVqwkuA{cI(llua00~N>87VZTIis>1 zz&rR3jN?jDBe6r$JS{a||85^03`!TNMl(3kV31n!2^)h9nxukYH#Kl@AB=jNhKy2` zBkl)8f2VCnF+cz!<d?e~avM-hcAyh>W>sg;?8))S(Urfm__&t>8>X3H{n=>*9%>v5 z+19g99vo(UAHpQ0d;A`9s~J96jwQ{QCD4Zf6zot5;zIlIrIO*;7ubx?H|f+7Kh527 zK)PmqS|AC<lS`u?7zx;4zt&-SIzIK3-$=TDs_)6xAd%5f#nGF#$Z%eY6=pQdZ!{`m zbb_?o2>t({`<DFZ-U95{f1&$h?8^V}>=TusHL60%lbmd*?jaO;qw2q#%$6};zuQ{$ zPmBF%(m)p9Vn>k+>;H3fudCU!+3Yebx>8S0yx6SVEZJu%xztFl2=g+e>p!A<^LNsS z3eu3LpS0sOyr~%Vdt(_QF%}3m&9(jQKRtW<-s^nN9%=CH(gJ*-4<mJF@2U%Zaoc{R zZEacaKcjp9@a%i$o>m6#JZ8LG*`<HvUv&TLyP0d)VEnbH<5<Pc%&qN?{e67TezK{p z1o-)Llec*9isS8n(f!vCZ{Ob9(lecwV8F!u=i*Vy^>oK=f<1GIprz`3l8BrCzv;eo z)XID+DMfW5O|i&-Azk&~bbsNWli8-m6aI_;ru*Mk7XJ&~H&|V|_%F}i?c{Qy$MJ^$ z8QuR+p1oMWN@d!=Jo~kkYNqA?z_VXlYhwQ&?Acc@Chhn(<CpvA>$Af-3bbb{tZNU9 zkEOoCn}px-<$Lxo4tE;`bZ<>M82ck1_`URddmq1>_e3GrB;&<lg5gw<Z?^tZ+TI__ z#dg8juL7_iZ{$=o+4syuEA&S%^8EMyFqox;^9Qxd!!SF?Rl^;1H_71-_ulyY@z=-A zrSrLZ;~Zay-KQ_K_NA@W>vHE)+jc|&$6uc^UdwCqw%2T@<!9)Opl%aBZXWXetN+E? zobYpcMmKj4@Ajv^zj>33e@!0i5gm6gQTK(vSXLd~xcsE=P3MlFRWj0WBHl1sk1hL^ zF}h0&iTAHx5N)F&^kTR5eYQ!A`^<d(+sxWbcs5s7wPw`heVy6aXr{z{+7W=8mlHWQ zar(SD(g^UtM{#xp&7tHCw}zrPY&hqFKvv$f5l9X~-XU~@XSpnYCX;`^DEXLM@sYbZ z@by+(5?zo#z+FE`E_xI<ReuF}cUmx(s+ACuDe-Kgk`jhu%DlBMUs$Uo?6suHmg~yz zo)D{72ZxwY(;9OTPv%Z>Dh77L0`Qh&Ix)>iHDi9t*bbZHLJ!ijno{4WTc>->v`X|H zc#UlH86;=4Cw-&)X!@SS{px&p{z%dh&4*{Qk3U(E{eqfZx}Mi_hNB?+CfWm1e0Kth zNh(F6D`pbv4Mt7bvP(RKVV`!k`_O_|S#*-3Y$Y0}en)Z|rue1a%GzKLKY+7p4#>u5 z0!s<oz9+$VX0>lQp8q*1{<p7=vTnmYzi?5kgi8fPBpIQ$X2PG(QGunC*1N2~i1qcr z5l*2Q_EASgNHP{GdnF&+Urz8yz9zNUV`E{%TaX<_&8mAv-v&oE3jNBDVP9E~#IQHw zItpI@WUFRt;upmRf~uFg=J7X&6N6XNQg=VMv`W?wFNO3py1}7)qEOT{2qV?xrz#=b z!(5`92G@nPXLV^QZ2u8rdFV=B?ujwcR>n#y2`ZNsljJL9e(v&@tQ93k6jc<$T%wEt zsQ`~}V6%qIx0|M$^~ezd#}cKcIGzuJzhRH?f=*1cpWO>^1B2!Sq%f7~sm=?X?6?nx zN_Od1Tbu!$y?=sG6*JY0`B|imqPer@3^q$_v!|^Gu3;AY*t;-MddVNTTf95xuDv<Y z;??M0m%HOaMa;UkJ~dk4-2)X<j>TF_$NrWL2%dyFp7~J!ayKupr_MM;dQ}{0jJio~ z`MG)ffgtC_;2T`T_jVa>+OYf-nAJW0RN^69<FLa1dCWdvf>@NLS6;iIA51}Zb}nU? z<)IvSnJ;H@QdkKKN$GZ}1d9&e@!oordts($yWvQv_BZXc)SLt5x!{RYO7Cdn&d||c zW1;z>`xlj`dq%d#QnPD=7S%7t3;L4Gy&ytaJK1uCa~=Ycl+2U~M5*X-T(TOJ_SkMA zV@u{MZ^R(l3F}>>6KD2k0kgT^Y$JtTbPcwq8M$VvX^?np3G1!<UfUM+tvx=(ZuX1u z^bx@8VAINXgv{h4{K%?+Y|9P=Y01_H<sMDY223GthXIhmL9=t>o3WgDq#r+8JtL6v z;kl1rhzI!7@G$INlu|kZ5Onp2iuZDs&QBBxZ>t#&-M5}TKQbtCg~RIdtUM(ccJqaJ zA6%0L!G_+3ia{&=!iHrs4?clbf07Lb0v=^}eUX>^emq6tJ2wgN7{GXvb@P<km(H`| zahWSaJLqRH%>1ew9kE_UT~1HtOWUr-X)SJ>^uJAcC!D;d|2mfNVRr7+wCwCw+DpSP z17UIB@8k;YPc82>8j5l@_9=ewL+4>=&YcEdX~%M1r3@hyTI!DkyGy@W_kGeHk{m*M zjssWbthpsprr8b@Xh=)oP4z1A1k_E^)x2)i!_MvLCI;fnK7y`?S@rBWxVp96W4nl| z{0h?WE8-ykD%np2f*Q6)I)2YHi{i=cFtLU^Zn|VWA+F#Vny^6>waOIaSDLhf<@mcq z3gQN0(V<eaHtx5wr5D&p!AHgSaz?}A%tdd+W<JmIk?zeN5cKA)R2p|&d%2yHJF1s* zWH%$hG4al8OXGvHR;pnRm;5wJK1VpjMV9+YuK~!qVQpNj$ek5%HgSvS@rThmDcZV{ ztMhYyO%T<+9qkYeJoVfWD40q@NJLX6H(B$?^aQp~h6r-WxLFR>EFyf*LP#*eSs)$( z%|nEMg15PZUljB;24;Bq3~XSJBx<)ne3X!!jenhoq<+Gx7$8{^To94a!o#$1LmGMZ zP*ZeH2slDJRKyV+24iDLXnt3^tcFo9AG!oEdaVfEXU=xg_6-!Ay?tPBmK*NCkjp5H zFyd$O2H;az!W5HUlI)qxrXNc|_*thkxuTAMDZvax%3LCsB{<2(oqKXl2u4^0;y%>u zd}<Z9IA{2iPDtareL(uKy8<B0zzB-F({bNnj{mDI65$;i_lk?lpTRwkOh5h9Ep%Cs zw+Xmz1}vn)#8?*`D9GSppDC_Yqbgx_&iw9Yg=(I0D+zR?AkHTH=5w(tMQ-^@U<wTd zp`-eHP=nFJBg$YV4K-Mjl?eiO{ZY3)vIIqe0y6m2BO4Z){meSMjFAl&!a@g5L3n6m zalru|s)&cV21K(v@b<2$&#H|-fP{6np`)lNxMY~(n~D}8yhy_PcH+j_boy}=H-rgc zWlW5QL7fN?lF=l98zJMm*{DDdR3H!K&rNI#VTM_!G9ps-M~|#`q!uX~ERp#4qPQYT zNCbHPEGM8X1s0*?eveDo*y7<o0j48QT-QkW1sdL0KlL{k_k@jGr{lKRf_5i;&$0#O zSOLw5Ku@a-M;mlE1)a&v>H`RHLp&ylp&RC0LBn*@93f<wAIo=wl6}S<b&d({XJ<p@ z&`<q~agoKbrNy{mFx&{dkPhyr!64+4WSf$d(vq|rB@hmD4+om02JRxmVi?)-PZQpM zjp<~V#=Je=1TBhy9bTsInY!cfeVF<NpuFXp9Qzzj8MO*e$%_fWPR`*q&)9n#QMsL$ zOsV0x>xP+=VPCnpNxC4HgH2{2F4gAcf|!vTMw-ZS?*{v;YDI64=DUj;+`ooT55IJe zd;WK7fb*7G-~%=?GFk958~2os|H{BGFi&2%i2q?>uo8m*2;x6-aUZ!Z&Z78va{4@- z@OaKmrc2P8l=0;)j8_au0D%$oj0m#e-?@{TZ!@e!6lCC@;%V5E06c?^6#1SRO#%0l ztDd0H0_*6-G3*mDppJ!U27v`tAwI=??Q%#nqX_HnsIHEw0u!++U@<wTn1q3Zpc_JJ zY>aEH)NA;`CjN0i4}a>Gkx)+q@9SeqxafWn!C@Zi*~p=$FvHW~hFlA)%5?n0h`0&G zEAN>2i6QDiLwq;gGnpkg$F+hQ97Xo*hkU8KU~Bli#(uKXYDYJ2GQ^>e>3M0Z6Ol~0 zG|tQOTc$iIJ-U!k@mJsAEzPu=hPu@$=%I44)|#I&J^YzL_&~zDp$Kbp;eVHRy=Px} zN3mLDmrZTMrx6M7$>|r<2-9<JgbbK8<$^YFL5>HhErCw}ewjSf6bG+nl&?_5*t=FO zVT-9{9%^MGOj)QqycQ1{xPN?40W6eJhfyg^(9p*0lLRc+(CX^ol{xffdX0cnn_#rf z*-<bB-quLBfvtyJbOEoEz!Dz%J}+i~g1!P`D;b#Zx22tfWkplWpJZGC<={9EH!y;q zWrFU7uB{CfrN#y?o=~$C+%%{0C*ZiU5KpgkM6NMIWBT0Y790<oH+h-RaL~2hH<GYZ z;_|hrfE!nlp%%zZFeuJ1d6|9WX?om@jltR+#Z=AKv1fM#3lYJD45<f7^8yIANKXpk zN|gNvPy7SF3bDsFr4i2UC5PH+sKX>g6bl>AMtCsb`vY3vqeRN|Kw&##B@@J`faGI2 z`8+g#@EtS8=+KD+5coAtSRWJV&qBZAwjYrYGV!AL=^l-XHWro4i|j>srF#~zOkXgW z7eoLRI}Z=|j*53CRYZfg?EG%psWBF^w=1AkOu(HdxWy3UDB?cT_rIiA<xA1!Uzj|6 z()V<ifu0_If!=j4f{->BI4~C&FbCZ}m)@}@2HiZv8sH#Jqxv7(+FM@VzoB+TY#{_U zjSl#RisvCOkm1>#v?_MUv>QfXzGtBQIN}iktVLf5=^0@5v;oojKh+-;G}zY=7P;tP z8mf<DC2N<j*`BI=)BeCa|F|c~ToO9F3>m{hqwZSy=m&8}9sVv8C10vm*qvOQ+eJaA z#m))#d8PHgi1<*4{53}~j@cE^3vyw%+U?>XA_gA;yt75_mzkz%3X;J>ScA~dDuH5* zKx<|vgMpgno~!dsg%?mFL~dg9ZQ5r-ig@TN#qa<+)R2c7VwW~DT04jUbmDlNhIHa3 zFp+{qO|VrxFtx0axGZ(%R;H_QAoVAJuV8v|0aN`=V)5|~xT+heFMpDQ&151Uq#<&d z^$%k&$^9riYTj;ji1;*#!ce$#))2h>B9*^o@|=s?1W<juuWQo;BrW4r^>D^Na4xPx z;5ug_bLhc~{jER49|%VLk|6AHCwyid9-!YJW+5OPh)Z#R6bQ9uAp&^^+c}PXWZZj- z{Ut=5zo6V@Zg2t<euxBqb-|W#d(x$4ibXJgy+DpC7{o)N-_=&r(Jry0Y31sF_33k5 z{7){vjGOp^cT&4t^q{B#5{5ron~awLCYc^s%Y!+wSOFBl4r?84-LZ2*ICV1o<r0P2 zk$P;c?Df_h?kf$;U{3bFhiQ`w-8mQBDTGffg7Gu_8yenZG~D~CFu(F+bgzuogug(< zpBKSj7DKrTqO6$^7nMR1@W7LS@?^sAgF%ri6z^fY=&$X?UmkSQPz>@z{y_knKjX_h zvk}i{(1>63ockfzB3?D_kos1k>l_>ZlZnsMM9;DatIb_U*Ex@M!E_?<b&kNJ^rny= zv)<=*HyA$Km0x^Z81ltnhKDF(;U3khUVD*xPLZ&{!{25jcTWU}vyib|pXU~WqfNLW z&BG?6u6Ef(V~u+gPh24(_;~>Tkx>R67c{QlJ<LG8k}B-?YPKbz+VnAZPT=adObmdj z?bRT*mWkX?E_Ne>G42>#w`?nr01ZV!g%HD(h)>Fx_WCg|i#_POc%dC=;)h;loH(n= zO0)P`MNnS((?m&^YuVNP4HIKc(n8lV_}?Rla+2vtkgBqcfu;r~N&=MzpiDm8l;hk? z;Nf4ApJ;mHKXA>Vc~9Q5h!4(!_mW;tG~wR?gI{V1)8LdR0JA1R#W(@PIVgn*XBEP) z(YoH#@TZ@fv_9|ibX^{n*{&j5eT9SY3PJjk5c~;(&jy(05X_%u*=iQ1lUIX`N6!C@ zNg>%ViXUF-m}tL8&8S98Je$eAWl*EN=S2jbb2m(*K~OQM_tsV<_N`uOo#1TX2hdTA zzyZ-6l>G(~s?sL-(*gybNT{9`q&s)AY3kmM`#wXgiz{^eDuCB@0N+JW-!se&6^Z(- zpy7l54I8V!;)G9h{5KkQf-K0zMa2U!E%F5-2&JH0JVI_`TXUZLr+LxpUbbY?Rb ztv(J<;~+Db!L3}hw(Z-s$}_M>a5oCNk5QGtK)#t7Ib$+YF*xD3hVvE09-*TkvK|B4 z21)9@Kk2wvikHMnd;3pJtuY_xwt^qia0UI?*UXnKTB=XC0g!^^52O>XQc<yUFy|PE zHh_9wC}?(TVf2f{JBF1m{seg%|CNUF-2ta;Q3T{T0TOHh8xUTej9`b@e*g_mU);d% zlO+_}lmOUh4t#(txSAatqw;Cv(Zg%v06&BbbwWaDuhYnaR~YDhW!&<xN0Kds5!yh* z%-hGN)Mp~S;U&*fE+emKjw3y<r7PqM^}i-b0k6ptR~R_n96qTkd~yl*iG>brxmWoh zKr95#!lUk=*nj?jd9kb{48i}t#D5IIU8A7y@KATi$89MB+t>lyNdnFwJcx(T>cm~> zJ#yyAhowie`ALXVq}Nag_7{fpV;&Qz1^SYlJa~vrhF~%YSH(c9xW<;|R|o~+$Ozn( zlxvG}2JnymUqjrw8J^fK6mo0Tb>MhvRraRiDf}lEt{f0NPrBbZt8#87)mIdibwr>_ zR)ESvG8lrl*@U}v!Y7ab<l$v{Lm`5))DqhKzbCUF&G&?EtldpS?xdLbJM~-Jble$E zf};Esg%aQsQU+5xg9_H6<;MKUY+L?hHs7;1vdPnlUK3Gve2jsZiLA0T+$$WiCBG5_ z9RKOrH!@ur2T||H1L0~OWV<5gYz!#s@AeP6pDgA6@#STMzyvJowAW?*$u9!}?zH2k zy~#K$X+gYnU+mW}tJe@8#E$gm7Tge|J5}r|jS5r`vckXWK73O?-FNgOFW?`O*<EYT zKGUP7wzAUmsp;Y@No|ZseQ5H%zSx)VZ%w*?Ivf!7p}gC!82{}{s)#_Y0`l}Fb(^3K z_77nTG)_oRhf4WTGa+R&I_Gm}mxn>*PY=fi+ppuoI+Rm97)hYm#n`iHuK+<0)zXR| z6u=%ok6x0sBdfth>(A?;%wfBh*ye=D{A~HSz8Jr3FY(3q=AupcHrgZ7i4)>B-_5F- zUMwRO-I%Ext)!b`309Y^qvRB&pSu0Svv1FDxw`U1VpKYOeDzHQrIoXR0nclY5Sm}d zj>?uy#JrUX&ruAzyNd9#l8u2Ho{;vBMt@3I^b3&_fXS0h(^S~xJD|7NMHRBzv`^iZ zjegxtriiQYz|zH|;9dDrLnxrM%}H#zU<VB>gXRFd8DySS&7+}<2k?*C2i%V&i&j13 zw5t}G=!IHcG4x&5XNcX3aoQepHU7BJuI~$Q$!zl4x^mLOo#Wf~8LD-ZN5=9evuDbh zPnK`fjztnQyEREkyU+g^7CZj2^i9Q?k@Qtk#`QgdGHPl^k+MO4+SP)(Gwja}+vMjy zqs1@#SAw4230D2vR|^B5T3-@^<yjg+?yx*bZ#*hpg3&+*z^+f0peD=@=R0+&vwe$? zMBQ%<6`Qmw)!$gLbnl~obWwgVYxh9%m};mm&OEqXnK3ekem@^s-ZZK=xn`rXWq-MC zL{cue@;YADcgo+KX>h(F-cE>p{cZcwT+9hpGvT6|Lj*a%syyI#^defBZatV9zlU6z zta6#;2OjIX>(4GNk2_m;z+`o)$RgoKEiSQ{Q7h~!IT}@9Z;Iy#n0=IJDs|L!N*29- zaJlcR_q1t&Oh(wtyIOr;)Q51lXV4Ro`WNCJwvUNv9~3?|C)A}I2?m__7{Hi^NrpbZ zF?HtM+2yGhn?sMRUT(ks8wZo@>N$#~6ohUoU#ZFZ`18h$>FAB`U+<0(bU&V!%Mi=w zQ4kz2fQ}Vx&x|Es^%)O;ZSJC-;dt(-=F!Atp~oRiS0%1%*_eeAlm*q}Rc(n6u=CVi zA~6lD;RKc6G^6qPrU;J0-Z$3B@SGY@0>Mz$)gUSD|57|#Nwb-P6q)?h$@Y2~Bs8v0 zpTu|IBmB*!ZvrD)joN#*yE$1HR9YJ@xJdc)mDFz>^V8=KB<`G8l$>T+8NB?8Kk{Qd zz|HSo-<T;rbj)1(`S+ARuxTifw-dS*IPeFRmwC!i#Ys2*aDXsMw6Z)wl!&EjXZ$aQ z&ODy!KaS(y9k#iLVQko(BX^Er*x{HX<|^fAjwI(olBgZb2qBe9HKIl;N+nbqLPAI- zsYXcWPr7vac|5*<e;<$U<NNr0-k<mT^LjmB95_9E7S}w5#U8Pf3u&dQcOd|U()GX* zMw;4L1e;-Z%lF-Ir46XHpZKnB5E!fC4|7yUVmUA$cAQ6g{6bMnrqUtuA}a6JJ%^k` z`)mOO^Mo*B*T*SmZa!jvW{m=OnrkReWzE7PRwc@VVLa&!MK3vJ;6#ho@qIfoaZ5~$ z^&%67#VNpyg&cW6R=kV(8Z&A$fIYtVb`#n|y+$yjU(u#ah2m60&>qG~vn7m{OwUHT zr$yc@AJ@mpk}&(<Y9t0#-PwWtP%+@JO(IXXYprO_6e#R>EVDQ7(f*Yf=d)!}zkexC z+v5RmJGgb@9&vd&V;%~64)Q<ka6LQnoUE@+uyRJhwG<g7Nb^(cV;4gM?0<$uPBrf) zn;VRsmymE$pQJ3MR-yn(;V5{p0kKwrTmlg?7fDpZ{0g8&wDp;MuM;Go&MDwumuyG~ zlDnEMQaeo^T(kVnDfP7LMb!*49%y$xE3EyBX<LO_vD?aaEzcnzRSYPk5*e80gpCLH z^=UFBw9!vl34_Vr8^$V%PBl9KOM=aY`uLHozRT<Bc7uvL`^%HqiYbRXnh{AA3i%xd zx}R8&h|NWjH$)6Ofiv8BMn=KC7SE<G1K_3U^?T(E&9R&!V*Esh7e(esjTm~5yZf*$ zle2F9_5gGrL_z8nP-hcGDglM1u`@lYhAAkH<HeKXk<|9bqJBFzCx%KmgnfV^2r`Si zBRn{&rEgy_4NHY5?g#6(OkHwR2u4o5uu+}&yyUzk^0}njThNE=QBD%GUlrhL-Nm#$ zSJtjw)9Kogow!HMfw&ung^ocHOyF$5STuIZz~BQr=82p(s(mKbe1a$#OdOXDwL9T_ zF~jrZBbKtqWWAQh{SP%SQby1Rc$$yIEWS<4?5;>IrfIjv)333DJ4@%1_Wxrr->Cq; zbdKgPb`@o2Tq$K3uUfmxm%k~$t7@nc+utE$RZc0@L*4>y#d+Bts8k>gzm7u1oXw)2 zRzFek8nb5}X2J%E)oR3$tqzp^pS2HVU?=v}wD!4zRTOf=KLvMPRyL#VE(REQAbZTy zrlzh09(Sq%atm5_7M{rThm0NM7w^;vQQp+T(Uhru8a|?UN=!~rOv^d!l+;9B%kodw zo<^`Q|Iise(GAs!BukVTNG{k;2y;)QdCfFnlR9_LrtQ0MXWnK9w*3dxmI*}NoB?C| z40g*sJZX#-T&1=Q;I6YuOx;FLj@$+-?^uGMxIqe=CVL88iq0iT>q`9;w8uWdzJ6&2 z6;qoHf=X`mYih()?!%wHC&MW+d$JC=LoV)`LaT~qW6Fc}zsOI3!`o&?3T5nsfCmn& zd4pWwwFEi5Xno}Qi<R2!Y6ylp4|8nJ;{uT<*3X3djz74Z9^UrJWYu2IcJ+`<L887o z*Ii-5bSZq}FhwB_!GCMrMZUhI^)(zLxY@kBI0f1H;$yTUA0MQcRlUYD{&LI%DCLA0 z-@W6eKUawQqyKsj0;=03g<2tBmQRW&SGPh$PSQ%NNTK*Q0hgi37_&@c@-Qo_UISN@ zkB|S^sQW|;Rq{Om#)}-EnOH+i=Euu{@QWX(dMbET)l5O5Hxc0_F8mgu7-}o983Vf{ z@<WL-p=0JU!zW8tp*yBpFR0n=ebAcyS|(@g{BCxs)gYv?(nh}J@Q4VWMdn3}6`kIv zor<f9s(@z*N$QgtCE@U#Wq#@)-+S4uD-J0B&GE~DmnG_cdqgo&gMX3*Qo_4qpC7U4 zbx%RU_cHLg<H$cr{B4Ya{pb_^)`G~yo}NUJy#N|j0a<gdK>8urmx#2Qpw4F(Z!5>& zB=uSEkQR<J;Q2XFzuxxRlf6$FMfZRrD>g;zkP_w#Zx>RcZss94aXh=D;6KP+FcZ+n z@tqTS@c@7CvMaa7qXMIN69hAhyYkidh6WKb%<Kst-#C1zA=VmUAQT2?9ST9pg!X^~ zSWu@5o;QvkCT`)eT%)qovzH_aeXZI1ov9%=vtRSK4nZ8({rzJ3C&B%_9rzqZkyS_g z>D}=BV(3N@EQeK;_CY<psc82g-(mTV%$P?pjgzt}UnV&GkU7xIs5@w0lp}(-pSr8T zxb=PFE~mm{t6kmE;_7?^jGhQt|0{#BEo%q*N-iy30hSBb+xIA`Oj_J+)gF3)6Fg^- z9~ge~La(b*fma;6XxAz?Xt^j0fTx-Jbgtg6t^zZin)Wd2-az;)vf`_u`|3^F`&wb< z>y6v8+a?c?C3F4Z?v?T*Fz`3Tp^GBfomKD@5#J)2H0T1t*6=fH&PAIN0+$Q6iDW#O z{N9sX9#AMZJ#;2VCP*OjKo;0KR%j3o-9_v_D-w78smPn{r6l_#7W6C67gATj$s%|< z^5Pv^|64-Y^s%A{GVea`^o7bImNnvim%nloVxN@n_tj1Rw;O#7o<_Xz?~vJq`N#z` zc&b3pEaDa-{MN>bBJbW~YjuQ@Z7HPkhJw)MkuzhrfJ6wrqR^Mkwd*K6-}+!4bv}1c ztk_38UfP+m%C%bM=MvSB*8(~Q{SQ_^9hc$hLbs`1XIDN{961RiF+mp^ykV<u8Y2G1 zJd=J-U~Q{BzPV`Ql&u;YKu_5wS6H2ktUlXun6B07oyfaoCkQ4CuVo2FY@iMu&@F>d z0s_2UROp8;Jk&S#i=p^(R)#d(x~rfw`#0Bi5Ro}(cYriL#a0~|=7r}B0Bjw0_xR?M zn0y3pUwfAf8Kl96<_L=RhEuaz$8krGo+Q9C5{s^oAUtdO_au(Ln7@};R5*{S6JObn zEMQK-H?lcvr_`)X3k6{|<G@m3Vg=7#040VNh6q9&qskU}MNOFYnIrvs9`LDyyp&Z~ zMu)T84pl--(fYDXt*N^l7uw4{ost1(b;yv$08~ey{<51f0Lx<+Eq;FJn=d#?gr|(H z!>1>{uOsApKr9yAqxk4n>ua&Zf&zhDXsTc{T@c<;kjyB+4HkxVKsV#?!E~?fsq&8# zi&9q$j$uRhBwHTshUTpD{WCW=chu$9@JELwY4=JdSxS2e-f7E|{wPr3B?xob_6-A0 zXq3%3J@N7o+}vUeI%T`DRbs00NPQP-u#&&g0>+!A^VsJ57s3j}yuc-yT}X&kMd4bY zb!$7(nLkqEU04*sfZh8_P8xwZ<UrFH{J>RM*(G_*#IU`v03G`5rl3441D?*{+b)Od z(<Xi?+*?@pdG4>Nd8}=A57s{jJ;qy)ufV;^f=>sjdN~)0Pog3dA$V!Y<?!&jO^DG$ zGFxz)4Qin4-x<s}UHW+XOodL);3#>A&)zQqq%nRH(gGbjc5RcTx1#rP^p>uph^z$| zogA!)yDGQrMrR#2%2Jw=_;jh;s3!%d2)PzC06`yP2}caq3;UE6Paq=lS`r>lg%JxJ z1|eIf3ZlkjtOONT2Ol9`Kd;RR&0=}Ybltx207e&ZQ*v}8r(jtfGiy(8M{GCK&!38r zmYL>AVWjnG?budDCPzPKBsdK9I_gq=GiI~JEfYFBem~cL>h8-36@`5bpzZ?uW%k7| z`FA@i!bOFVOFZ{ho_EK_Fj?S9&~`psFGpN>EM;7|I>L19g~D%W8o6k$^Ho>=B~nhI zt}C-xpqwKu{M7>JXL1Zr!|ZcI(}K32V$>~@rqz}J5P59lSWz}2WO(FC!Wd~I@fA=b zBiph)!Tx#8H|XZX!YF%aXjP#P0$h<R<3HE{D>wa^**}wfzfzGs4S~5;!#QfPg~H+^ z)%W@PVg)R?s$s!GYBY)oPNUy_o60=NiVXO|tD*sLB52KQsxXrd{}-XM8DZ{>;U^$t zt6Bo0Yh-NOc}$VHzqL$N%N!5b`1dhcS>ahy4%9&kQ#|rKiB<kXVgB(-qxTrJrfj}2 zaa*()tSB4+lR=8?f)sW!2Z(!DW|ok0#-yd_Ts{}P#8z91-iN%$Zd6vB_4L<vhA9A> zI^ubR0zY<(50Y2MlbMvA^E(i_TPhPh7PV);qv@dQ4q^c<u0J~Z(!HNxpFPvj0c9CA ze7SJ8+^QlgfdjCMb50$Gd@r@$1m8`Z##?isY>wq)n8U9M?;hx`=QAo}==l#jD)2N< zG>lTg_X`h5_PSUdd0%;$Z<|x#(!y8pzq{6%KlkbpTt`1T*+I}Q0}J@42pa>8iO_t+ z^*w|IYmL_#iSX2ls}_DhV<R_>vCHu#()N0RvhVe@_l3Z60o`)EKn&f==EbC0Px`!~ z^G(P*B5wT!SLiTPA1CrU4&|<b6A3P5qngpez%3Ecbi%d}&-N^h*sdIEK5-kK0HD#} zjmt7Oo>8Hndu~=&I3l>B00fowfUV1q70Cn=`-fHMCI`y{1)a|y@a=I0WW^mh!iDHN z_<hzeM`U2yF`a!(F6*D73M-m9$j=76FLrf?c<%DpQ1sPh+LX->|M)U9H~AN_FqAHn zn9Q#`_gZra(&d1N3MllQl3BAs0Cr_i|8T7^WZ|!qF<qM!bLM*chpiKp*oyKNX;W@9 zm!r22LE@NFI&5P;lPjycQv-m#pI{E0pU5Dnr4S)zYz{P>V}hHlpILm1`vgb}>n_Ud z0w5c#VKcBN1xqD(^dT5V#-C-_4!n3ea(uG1Q{K41eh`*e5kW;SfX{zQuZ7*uj{W$L zA85_#eAFj5#twQ+&HbiOW}KXY9>a%&_MPYYlFQay6rQTf1c_uucEA9&6TGQMu(YGs ziRQJ>3)Us5ZbEFhxFD3c2yu_dCi?7{a-C5dNE(D4t4d=xe&P{5@;g3#NRx5|@Vuo& z$=@;=CWwmsyq1CcEG&!fVh6M6yFY$p<8#2<D;A!ll>z1<9*Hn#2QEcga9Jdx8{a?V zinzJ1o|o<QW79;$q;H$b(kqIN99;njkhB_S`l|g6Nbt-Jmco@-t0FkF0%ViUmJ@^X zk?@PpPv+i^SK7QQZ@EyThO1QZCL9)0l2Eo)U|6AY6c7~z5YlF%)zfH#O=zgiU_mSy z#>kO@Sd9m>v&jddjDPWW5uwqnC0LblO~=ao)wB<m(RJTea+eaJtz8NtKn=HRpZfdF z$IBKaup~x02nYIc!{Ac)m+Q<25v#)eh!sr{bQ`Ns=jl?|+yA`jPXIQA(7}%x`=X~& zvUXOGt#$t8IJ-D$kjrp$$41U<IQT*S><968jW}zNVrv&z#I`+NWVa=A@9{F+INU3T zt3rQ|7eG=Fz*3Epdjg-lN)14;-3FoOm$HkN3xP54cE<P3qQWp0xx~PV*KQHmIT@PR z?iuG+{lJR(-A@<Om<fISKoPL}NgqN4Nnu~eO5Ce<Tya|r6kP*ePqTGOf3L8&?84w< znYwg_sBn`c{L+=dKpR9Zflp?_;F*TIE=0d<DiS8uWD((e*zw~3zE-$1vlRC$lG!%i zY+LgF9LDccOF74_{=31M!3)1>)^PoCyOvWG?`HdXEdMCL6}~giZ6D;V)qGy_NAesi z%stTjh$U#?GFCn;qwKF&ayaDGImBl8pSr)<SMI*r)Vp3Y02pz-6hTuGA0GR$da~nX zngD_p?mcz$9P5hQ(;a@h1Puw&0@K#%hu88i-Gz?XAi}K?UWqWw8WapiYzDzp%@db# zJq2=_wkb=?_&$NENpOoO-~}=Niribs-k_*^75d&)=DSu5eGj2$H)V!Aj2x=5-8s=> zI&s>Ks%vIVVBok~IWy9H^W1Uci3Z=}wnpLAIxgwI(3Gu}KtFQh?CAAmZQzJ$g5>1m z=IS1X;g;y9S5x0>%$f2;h#onyg37ayGwUVe{SPZ?k*4Hr1Z308j<v%a&5db!8LZo+ z{&!`WDL=1n=}9odE#1dab@t7TX}OmCw0n0i@L4`@00BdRAm{z-VE;wk%J6r6Vb<?` zvW-(|S>~Jir(<Co<b}97Y{QtVUri|fO4@Dw;L+zRh5=Y${@e20&S>nwMB}ZY*H5>@ zO|Aq$VXi8n)&~D!-cCrLefjTh>ypcV%p?6MGX&BjbxwMt+T;vT)8A$t-ay8-Me0`^ z)Jj?!GjE+#2P{WWYQq-wP?nr&Luv2~-{R`g7sPMfRo+1HiADW#Ev55;x<!pg3@TDC zg&fxU{0+r{S1$D`x_ISl8deXeKMru36Fe$X0apMr2FrQZFs5rG3|kG8Ko1qNnTgk} z#oU_;&_hN)a9>UlYWnUOpD}GR2-CeXnOPpYPcC=szHjIwMQ-mDI}<(McU%a8D%vfp z;iuY<ZO<-En%*4rzJ)d#${1#lku(MUK;mNS5tMNa-GFX0lH$A};oPb!fWAsvm9O1! znZBVFQMOUZB{>Chxa_w~mwE8Q{YM6|!@d}{i<J4r3yQ!o0ElkrbbyPetCPho!=sCv zTuafFM$lMt%yX_o6SvqT_ObpZz&cWuZI*xZ_Z9zZ(B&B5_>9`1!AQ+jP4TsI17*A9 zNpxbb`bE@hi?poxw)3A_GE?)O>mwzYDfaXEprMTJtCTg*)0qM6$p#fb79P;1?r-<^ z*JBd{-HrFjNiXi(j;nBjD~ztssGl}!VrYs-J>Sr$3~n;K+9tPZW{o>7=fx;q-RAu^ z!1-6r_||pjHxq1Se3KX8WO`_%?Z6u$t(-I|R`CEwByb<PEM|Fz@UG9O(rs>f*%WPP zY9%_(Q`GF}0RQl6vB_j3de8hHMR{dyrpfbtPh65#2KyUsE-8`3!n%(TMI4jwHjP|p zc&EN|;5zZ!SCEXX4BCcoENJrW;Ej}q-AAR<RsBxhN=~JlgLQP+CdUb9OEMHPE&uLW z+{%Mpb>IeO?R(cUtLRd4#_FZ>Thbqo8?tn{$^11&@$Y|ky}pgokz59#PNpbKCJwla zQi#Fyb4W=?krrY_?w`uXbv0JsDFnB8KZ=H&7=s!Uh`OZ~^#+crcyYEzae$#*;nU(* zz1xr+sK6X-v0UUt3e(oKy-47GDeOwpfI{?<W`t+8W+YB=0)nf$DhJ@fttFdR4;9UC zE2I)X3lj+AC6Do?nChUze{xiqebfEgf-tYwLWqt{{VRyB@CGn8ig_=d*536^Me?{; zGmc0FX8<zWmtO0D!oz$V9Oc4V!D?rbhwN6ZE4*tFw0(axH6VaYfSrMcPPZrGci25Y z%f-^fDVWP3eP~A$L??JR@9|*U(AtC2*O*^I?hWl_07{aiz7t?{cb+gge(Rhr3&Dn{ z;`laS!8Y!`4JBT?OG21EM<mOII{K@!2aZx}+H-3u{QzA4*~R@Y&5in=REU^oLKq7% zKDs?m0`8I*u!}bRYDjBS?TG-)=c!pzQB!%AXh<gxK~|DuLD$g=dULD&&d6O=sF69= z@F0{jIZ?v4yr?mbL8zUOlmuCqo=e3K>$fD_(NMhDXsPpr{0RSu-OST@D;Tz`-!XBc zy%#$*XaY4Z1Q6B!*pK9AvU{}~>iY&YGX|@mTx(cfjR8kh@&2gXK;M3Uyb|P@D45fT zjg%pKa0R1TJ=4_>3)hsk`lufc8a7bQ5uek|y1jv}8rS!q=tEWETw#CrXaDQQMvfl^ z1A*5Tj?|q5VU~zyF0x&9hsX<<mr`#dFfdrSLc{uZn)#4aO17cSp@$KG0V3At{;03^ zVe|tNs*~@NA&<Q6<YC`u*IYio(AT)RYGHLFMlm^0Ru{DNww0b4u&3{#PBKy_H8plB z`wt2%8{Pu{!&b~`e_ftlcA0P4Gr%gPDCI{iI?UCPs~Qq<m#VyQS?j4^{s_$%&@1Ol z$?|bfu2x%x#ew9A!{Mwx%&Xf0*+TA3zjaA$zctK?t#XKlt(QnV8>41}%8ylDB@}4M z7zJxGPq5`NYYA)sJdfa*EYYy`N1qE!E|zCEK=fW9X#kZ0I0-;Xt88y2%7)7C2Ru>! zEd}U5$k&_pNR-Cdk2g>|=Bw$A$fEle2i?HxY0LUO&qT1Ai<M=&$UM!8b<AlRs4T7x zqMMebC+GL5LDbNeAL3Q)^iHMN5GU=F4R1@V+9P!_=s3EBfV-jbMI%EXrGHai6@K+{ zeqYVeN6-*MMA?PIN(EY+3NH(7JEVT{HvQh%B24q_ljQ?Y9nhGU{qXRiT?JZb=D!uY z&Ofrzp>Y_g@V(Q7N)Y~R`d-c1Bacb;AA&>T!@sdXB{B>)Z2dC2IJRi-@1d0U?1rnK zrE5i&Tqyv@N|gQ}<w6CUDqkuXD3YINpP3MLM@({2MumGlbk8g7iM{3SiHAFvMwCUV zQMHB;nf58E?^6g6^l`yG$%_w3R>9f*iwsYEG*~@w_BZ~sfw$`!_8jzs>N+ARYoM35 z^~sd2_DKt}(!6ysYcTkQ%6Rko(kkRCSS)B=ok!Iml7eQQzfq{uen+ZLU1L5^+dBfY zb^{gr0lnz<f3`iGy3&m|6Ld(CKVN(uKa`vZO6hUPrOj<o+Se}beCkPtkFw4D%j7>c zZN23*TzA-axg$NJf@ifn-Y+QWQ)?96GnmH!0aD2)OI1%}aYg2vipkFkm2%o^VBBF! z@={xBmbc5hwzAZe)0#zWqIFLG`vTe@(dL2@%)OUoo<fS==fM*Tg`Q}$j?;Xmm`|Dj zjWx!m9(-9);*{iH#;cNoNabGjV{K1M>_l3_tu*UJYb3oE+;VH(w>~kC@SNgkeY5=a z1FnCE%I-bmx6?VX$fzS*9Ov^~U~h=S?}2>*_w1SCUwjt%NqlCXfA7>Yj-60d+_;^B z!lAxy1^+pLWb%mfjQCshp(XgeNSsWRhetlmb$MN#O$O81!?TcNe?1T6R-UxSU`m3v zn<D!oA>{-5TdBYl<!7Pxug2}AWJo=_Mkw;eoal8NMw144ZsIkX1LC-23dAvm=QtLw zB_kzzK-`u&mNQ)U9Eg)hxPY&CrT{?u#?MLs2eE>X^)mkRQP{hp?M*zF4v1qn#9hGA zTz9tSaL^t!*DMIyxv!)_plaW1E#O#ss2JAJ70clUg%y@qiNzS#%v!%GU(fev@m_Pe z5ZBEwZ)rz0KF7lJ*CIVIuEREwG%ItieI)OAh5qz)o?{Ifsvy3B0HFRtZp-ZN`%{=> ze4%7(?R~sXMz4<LG{l^PwFbLObv+bfw};kCpj-_P2)>m92&fP3>-V%$PkZn*zJe{{ z4IGuAG4qsw)Ozw!ue1t?QwQoPFr*!(;j+92F%Re6`qpE|@KXF<O{$#&8b*LDK)oRb zyjytJ^}banipcII66ag}OX&@#0NX<shG!j@bnFKyfFT<)$gz~th@tb;^$2V_PhVkz zoN{E6F=4c+a)W?tMV8>^sU{6QMhDKW&V#%Van(x$tvNK+q25SOPrupGr!oM-m*%(* z-^!v{Ng>1~m`~bs7rG}_fo-9|2K;fc@tEpA_3&KZQ;&IDpY*DZh5<9tE2*_l_eecE zXrv{c<sb**FMbuq{g@9ix9qcv>M`=*>5C;cNGO4{$!T*DITCCX$wN<3EGyzn^A5j0 z0k=biTg?d$5DmAbLF@=?5W7i%+j=N<4rJ)|8D}wV!{WLwj%W9k>g^x-=`X`g7PwDg zgHw1``1xGHjzBLIsRLrw05(FI7|npK!XcfLv?GI|+p9*si4jqj9O_>k_q^VnVGE+l zp6$(4J1oTlF^tdI9=mP8ERuVXKm}I8MjcesTJVl(owJFt2{#54rq!93ICvpNcbS6k zkQfjkF6MPKrR}CecoMzWW{P9KOtT_Gc62u`_{gXO0CZ{*LMOwSG$QHP=Vx!I<-8Xx zhz6YlQ|JRH0&+q!(3*%rbDdaEod*{=(a=H9-ukzAy%mTvi}&8AZ+m}_p#WrV4yLq# zV=u3j60G$v+#1`EbB;jowT6PmI;aG)A~EdzqU+P<w);vupjLSxBmZ89CEkg5JbQAl zMGHk&_&QN{p@<vkx-eqD4AR&}v+C=8L3(rJ;~8kh>>g7#IG#ovMyG3RgMrUoYlEoe z0CMI)gI7`mObl)z$hUJCUWSorTZ!!FD&`zW4hOpoLFpbXI2Lbrlxo_+H6!+*^S}<# z)GF0YdG%w&XfEL^bt9Hy*WFW?a&BR(aeWT-3}6uT_k#T-kK|G4Xcw<q-)Nr&K2^mf zS?}cNF94V2h?5YzWsc!8%`vjq261NLx=LZR2<WQ>D}ZF=lrYV;>6blRyVp3V(Dka2 z6o>*~)@+23ywe(JxJ=Mwa<<BqBPfLqd616#98DA;`zOjZOZ0Wu8!~FtVhW@ezir=T zZ-Zj6#UxjM2~3bmTVNafNK{wk`;+MBzUwf>0yK$iNU@Ipd%xFiUZOceJ<;DHeEepn zgXg#e*6XA3%o1H2dZp;o7jk&+p#(*BGLS_!HkS?lIfr>U(wagupLu`#7xeD=rE|gW z&gFhAsVD2saCiS~_?p-2D20>{Q9#lK(G!}Je+sQZ;8W6LhUTIDd+<z(ITYBJW}Z>Q zH6<1)_4F7QY*$>lfAnX|-Fxa$r!Tn;KBRVp{@uhg?%<qSS!>~BkD5M#SR{g689Y}8 zEwt0%tm-!LRtQRg4H!NmC-kKDHKpCV=sZZXPh{V=WIx>uOkE|bOj1;=DTm4}ZvFw} z{;+MAco&;2-U@r2kURF>uM`FIq;-&48)#+WD`PPj1#H6Pa0$a2mxP04vVq;)rIQuG z-|Tt%1h9#M$B`t{X3EncTlJ`0AghL!Y}k&!*LzKuFW4{9et-SYrK%{N<!MAh+))-O zoxB(L3Q`{j3;>GwBa=grG;DMA>S8OKXIssIWu<~T*te6&Dge!a5aY_C>9k8qCIE>4 z(26Pr6Url{{P(k6rGC>+u%P+Yx21O)eN_`{J?5bXy49Rhz{P`KWnNqMAdv;1VU`q+ zM^%^U=G{FTYQdTZZ8QTz?8>MnrC?JLcu&n|!b1Ff4cNE?Y`Fw3mw*j^2}fXJ=Y@3P zAVfQn>(;9L)wqw=FCbO)XwFO8M7)WZ4fD(bH}js5W0!fK;&89Frq%HFhcB;RZ(91M zx?&CIU%tTPmiUMH0cfgBLq?zgSl&!liKjU-ggX{qxJ=T}EQ!Kzk3;{+8t5uwci<7^ zq31BMDoNa1ZkC<Bh4!J8&;T~4Q}vEX$kkTWA0p#pInYgu1Xf%6-zOHeU?UROP;iat z*Fy~98Yfa6_kXd-+O3soQrWiFHU<6EQ&DJ1pz6iP{dJCZT?QL9q!3<x@@Dhg=Rw|~ zwlswm)t6NKst;h-0P`C4_2+3wA@<dlXXbb>P@e_2Au-|BFn4x}5D(thN?40^s-Q*v zT<4u%4Qybktb(iyXh28YRUC4gL(fXR7;5;RGK+$j^3w)QU04t|1rOa%v!WX`2g8pq zs;H}Ni?{_z&gIPqJrpfb9(XAE^$RdTKs8@I=A_x9-2&1^aB+WV?jrk$D|_5q_E`Vn zVyeGsE?qDz?Mc5xj~vXLFX+KM<yt06#CF$y*6YNe`xoEZcy+*;I+uJ{#-whrHY2$V z#{xSJ_xks064zM3GS9W4o|K2bH+NiRh^9vn14K4m8Nf~|5#V+StBcqKh;}F$>LCYN zPFo)uE^BF)9f02ml6Ca&)iF<3Tv}271K2F}Zmv~!iSIqmnpgE_+w$jke33B~P)+DO z9kk?<RALcsU*2(_%%*NA`1W=lr2VJY9op-r(1Rm^jr@@=y*=sUV8Sl0lOH(mKbm#7 zy*Bf;MHba)hv_^tZC2W2Jw?%G^_WW=0(yEKYO8je-dLrBNK+?#+CyE#A)|Mw*H12D z5;h$X8S9n4fP_Fg-Yzp|pS!d}?7PKht7ZT?Ij#{x=vDu8W8%vFUbU%YnL(xhY$aMt zYY>N;UME&9WhpRe2x85mWOT6u4IMSjdmILN6P$+*P_|_b#m2qGvi4Nfxn`fF9vcA% zGc!bHRuZbIcBynL1rLl=YEj)|&>@L9rD43>lYX0<z6q(dmrAH^6JDf8vNFTho|uGl z4;qYGgo6z}dtOQyiGR|wL4jtS1=`>2`6;G=^x?T)?~U@~MT<UOt~s>S$7hQUf~-~{ zE|KrwTplL&5%kD3D-!E%bL`jMb~(2pq<Aiv4!|@403d6d`;;FpN~e0dEcH56Q=p0D zogVvT+5t!6m5>b{8*bA`1vFd3AIhs9ihsoFEQy=*d`)uME~W`3M*<CB6O)&DE~QE| z{}8h*u2rH$e@r;rc!jeQ;V{HCghC|$@r=T$-%<jA(rSHE=u0!zl8Q+aG4));uiKlP z$6LW029xZd-18gY9G90&sMvs^O7;Fke$O-PplD9?(Go0AX)O1Z5+4w*x}m5WbRq6p z4xwB{r-uDaKXZ+<$ZZc)0D>6H{7I2(hh@WE61lQ7**kN{vZp8xIcJ!xO~meAgA|D} z5`;jJ6`^8fL=P$42h*hV+%ly%fZV;^WP66yONUH50mvx6ij0Ey8w?o5@1azKtQ7LB zC#f5k!9Ojl%t+<G{&i6mVhIAS(H{*7rrgdxZ@#t1)O>B1)iOs1DmG_a8~m@>O(=;E zC-&um9!~cWg?@Ow497{H{@UEo6iM4I-O5e`dA-Y(&KmgHX(hY?jno8Y0GZsSJr}*Y zpQN7oDM>9Vg?X@LS0z>RULNh+_zxk~+a++pU-ds?jbX6ytDt$pl;dizy>-e=e^;pP zLu!klx!Kc*3^HdT4O@GpSBth~Q7BBXA(BK!b?v=hMF?y3l|e{N#Z4h{c&}<=C8|kq z4$NH1x`NhEXtOShZIpZMal|C(eCVyJ9e&5H)SXdBo1eAXfWjq{w~p)#JnPQ+7kVKL zOG+*Ti{v}2-`=ka9C-XY<KoMX^QHr3kG5P{t5)5#(p<jZ`TN_jYdiNhe>rc(wmtYX z_w%)cva{`RVNdHGcO6gPe&o$d3GW;Lu;H?Rg2ec8R9D@Bk*cF42OXFEN2DCV7{EzT z6SwZ(zeVXqXSccDVV55tqprJb5lj+*Ip5USfBlUSKRQfYUVXs9i{4^RJKoCp=U*fB z46r-+V)zo)Uasz9c)sw1_M|c371s0fJhw(ZwvBnO=Ec={pQF8ZE|9kVYFB<{z3aI3 z>8pe`R5Nf{EWd2NIY7nem?!^jY!%=ki^GHPr3`8@zr^<h>FZ~&CRzM`Ic&b+{ob>w zY<Z<xQOo_f=3MD#ua^5cuNnQ-lb{P{sOQ%t7tTaquJp5vnxnvVUL}}M44#?xF{xz{ z7)&-ummp<h=3|E23?hQ%yhLMoZ{6rKbbT&Dj>#N;DBTCwnP}m@HO-pby;GNzq=pBO z;0|zQM4v3sq1vW^GI}*k@zy&qUjZoq*E}*}r{CFCZ0MiSMpKA0G(G21Y^GX$Ap$C! zaF*_&vIF(^{PSez-~b8qNOY2{S4D)iWLH>luxFED;7<RAV=;UVofKVc@x-+LU0p%5 zL)o`oExYI27S{#ZD%KlvzCK%&H@z|L{lLO8WwTiOn<-R#-;m^jX0oWR=<Jrul||Uy zZ;#sCXZ78hWrI+@WRTedn>W6>k~O1bY<joExCB8W3)!RkiJ<oMX-d(v)BY~-(|cd; zGJL2FCWwotffL5;-9t{7q78~e;AeAGqbB98vS#7I`eD9C>VDZOG?i$u*Z>I4*tWGX zPQmnCIg>kEs2)Ue+EE?wt#glaSklkFs{LHbx(wL-XFy#fCKyo$#M?NN3zC`|YhpgI z38?FD7g?g~;2PK&*86B#v&1jb#%9C-2!19v?Wg`>V9K|dsa@RJk$!yeUXU(kw(5}O zuAUP!neCtMEy5tH>&Hh~^mx&!t9^fONOzlmDN<9$v4{}<U-9|Vdq;!l8AE52{A*bs z@Cov+iQ%aE4JG@$&$g_t{fi{d4RYXTYu0z@gahs43ICxtP3$`o+1CnLs%bbbQutC* z=~cb$!l_*M_7+`F^)Ql8qsFe`kQ+yeaMbHSWUP|aln3BkS@N?n-4r1!-oUj{AQGS` zg?8!IitA<eVuKBu4am@U<FX22$<(b)-mZ3^WrErFFy)ZrK73olY+*0YEJofArK*&_ zOt<_l=(n5y+@-CwTYu5I$jz({n2^N*5C++}@3T^yVIfmyV_DEj1ze3R1e7r$@=}To zxp9a28-lmXla)iHD7=0y;9)*oc{HnmC&;bSbz82J_uTPNzE`U2I3!V8-qa8Z5>;EW zBs$95>J?KFYyD3xRpfq}daw_i7&Q&&6#KEDD)$)5J`DToK^^rPa&Ng*6hiF$&JcgS z!_%gul5aQDgZdG%VDVQ&Jq{gPuqSUb(6B=tzfIoLY_8CK3RKSJT%q3k>~)VNt8xPv z*Llx^yCqUIJIBC!AHxUI`_Y@^@0^R+Wi19_#U2N2sJj2*ijI|B_kUH<k9}D&fWtAm z2rot<#!?TL!pUm%v3~3q9AEb<141(OP~IZ+cI{hl@k@@F?DeR|#xj79k4rJr%Of5J z!DiuObBJ+v0ek~UmW0zsj}VOZPa9m1qR>%QHOjUc;|d{@a{7(hn}Jd!5CUa#P+_vv zwe<|2FXjYIVe8qTx+JB2Xalt<p`1=JQ6qiTK)GQIE_)~xmESO^_++)&_IQ)hqiP=Z z+xj%F)5+@S<IjA#rXbfA70u)<n)aBe#6>I{2D`(<{IY(ddScaMAB$Eou2%j2Mre6P z?U-JmFiKMe0I9`O_5MQ^5fjl`jr1_xFCs<E=RPm;Bv^NGY$Q^~rB<uHH#Zjw()-BV z*e@4sq;Is#$dXeC<Wbc<Phrg+#!Jl+^Qvco!UHV(kipRT%}StCb~Sjj)+pOfWLp6> zF=l3}9@^w<;ROT~4}C5P(Y+;vp)Us=UQ*ai8|=IX+h5eklR$LOt#S?DeO~L<<UFu@ z+{L$Bia87nemiF2!Lyy8#pgsC0B-MOh%=St+0vBTM+`2woo4}s)<Iyeb;H)sZlwX; zw>A;K%A6Aj#ojeBGO~gRNa9XdN*+WPbWiB4&AYPi54g@=K*3Z}Y}&I|jrwfhZk8v< zjiADWS5qIu1A@)A4bLf$BLEHE-Njo(SJSHno)|DkUgW9R885H&*sQ1dH|L|S0Nrol zED5;^A^?M%Jb5*w%HUS6=3RuBk%CrYWDiffi^$g?l|0t|x5?}gx>k6#UO7j!q`s0k z&c0uzS>GOq8AgchPvW;v1>{;NA4`vmyl9!~)vLX7$)BihaXE8s{;8%JjtzoVtap1b z3^rt>q^x@Lo(2eZuEq=Q3~-=XZ2(dr-q{?lq_lm(RD1ux`n8R6yq#UV4GT<7u486M zou8`Vm7Fg(9dZw6A3pH4|L9ilsGnMfnpFs{Pa9cwuH<RrW(M6{ZX8CRFBs;m6c{Jj z93tn~y4xBh0d^{E)Am#P4K?>H4g@K93Gk^P25!J2r#v^MN3&~*>Jo75vD{ml+HJ!p z#r^O2_LH4FORW5^G5X<s!#v%&@NW(7^ZZO7XJCaj(7C#MJ^7kv_uT7NTlGr0KUNID z1gh&KK$-k_TFKy<%B%Uk+w)oA>B-9u>LO`TZUJvi$N!al<()d^NGPt(TSJRl8B_cq zwdMuZWYkeuS}U8Fwg1Pz#PtQM5-8BuJjC#@)0dp){3uhond6D?V3dUB^q_wA2mi7C zS?v7kmYPEGVBnR@$b!<I?xn)Q+_*KT#|7t9C#Ai(o;sUfn+FNoiR0FXLy0M$=j5x2 zb@x6vqaGO=>0U?vvhUui6!}u!8(T^bYMJ#;VvXv&x6J!=xcb%JRed08=Xy@b82p8g z&E3OM=htIr6?d$16(=mkF*q@#RigK97CWkJ@dVEV3$>SM%C%&Cf&uUyK<fHpM`Ij^ zEywbB*p+hKigSk&&JU4FbgV1VMP4Z9y5O}BVoh9~q9Fy3NZY}z(>lqKhvGGGG3v1l zhBZYk5vlSWq;bbD#bF1sQ>dCSJ2zd1ce{-A|M+d}VP;}7CijZ!FR}J~-9O7E(<l1M z;j{bR8JS6EHOAN|={hp9@3Q|nf>Mg^hdQkfp!W0WN2g*iV{DJ<cnAd0V+r(1>oDBD zclFkc{+K&}@csF+_qG(>aN4~O=_eNHSD9pxGZT<wPB$yAi%c<M%5yR8S9g<+og(rp z4v1xb9<>0D;elmj|5!RiMLFo75IFW)*<<;$_<}xCU){N`8CIvsU6hHaOOKsZJxM_# zIcV$ITiT!KX`bq_64ltc(X~i3RK1seA31GWF$pYvJ=Uv&>p2E%OB<u;vIN?qI@Q)? z?1z9{A-LuaPEgukFxag96@Q{WT}MjMzARBZ6{GtrUg`ZHL5_0IlCLA3#kP2B*W<P2 zSlHr10;*mXOzu;~fjTd%eg!!zSyQ)t*mIeHMUg>B-1;sB5~eD(;sFPLvVR;uM?vdY z9qR98pjM)FnW;BViPqlmJ?}MU5Ty5ER=Jz$&@EN|vxM<NJ`k97V&_yN@!DLb20JJ* z@^Ccsp=R}hCK#lw#L@7lbV3(4M|x`WCCTP^L+w$O*x7d^iQ2Rm(mz$s4y4his{g)G zmnqR4+pV_NNzrvhm^o}>RU8h#?5S5u**$}&6*PHD8A}a#rH6<`)-Dw=&{A&&d}zXS z`(uZdtstH{QmAeUxet))L)hRvO7t+O!Pw(jU;UY$7>wCxeT-CfM65}~WBNEy*9p57 zZk%9PwwC#M_@lAutoG0>X3`gz`O$>8qCHPmB)2|D;X7fH@13#LFrGzZa7arDX*lp) zQq0^k4u0r-6|}I^nW7fU(E?MnBV$l2@b9q?QPN;-s-+s3teU25_ZX)0bp`z^1Jj)@ zzq1@QBi7p{O8+2Rct?u5!Nn%ZYd6H`25i#i#@nVh=~l-m-g(EX24ju=?&Zjn*ADjy z=Iby7p}wa-pdf{bKvC@$5QxV!L9E3bS;kleWNGWGDuj%R^>Y2a_|%-QF?zl>KrQZ^ z98<YAM)?>;@2ljx$B0+ikYoESW|i`?L={?Ir6($PGNBpe&LV#qEB@<MKRHX1n^ke6 z94Ikkd`)$ZY}_P2t8v~78`xwK^vNR12RWK77u~7>D0<#29CzSogK;`MD`0v&(+s+8 zjGQhP66v3)tq`Lq>hVIREHNyA`g1mEvbuKmv|27S6O!AC3i=yM2%Xd<uz{0<Szs}& z6~CHm`|MLXwzE(U5c{Z-fwT|+CxqB?><43_<KrE{Wb9Im-r6q-NDmnpD>a5l)CckP zutle5F@8T|(EpgSolDB|;;0^k=2jDZ0E)f;`hx$Jtr{^%2hR5z<4VI>RbBn)r<v~O z4U*F8G{&xO4zA<EBr1Z|7cILFQUmZXkVe8RBkFoMIu$v#ThlIBUMq1i>C?sBw2YD- zJpxEPjn^&ZEPdeg%*ziFjtJ_xnzexfKJ{wD6==ks*q`;Szt}*cJ>dTaXqH~gE-M*T z^4{8~Hwb{aBWv112uciXt;4>Y4LYShNb=MB1giVaCTiZ3{Vvt2jlsNYva1anZ?DF5 zPRiHfe22sQH+V%wsp&gVNT05TD<Ra(>r!=_l-Bqc)6w->4YMRS&V^t8c-770Udoo~ zF>_!*PN7MSbz>_tP1AC-K`%boq-eFl^Mu=zOr-?sY>ck%7sZd9(AN(6Df22{z2XeO zUiw?S<|WeH8`kV<5!=_oJ%b2d-vbb3Gv=cTf~WI#>~vb+iukTF*!+I_RZ12T)P z6ii>LRxO9PX}5#;n9_HN9$QssanLEw&+j@u@-`bv2B0aGdUJT4c)D!>SZT67EscUF z#;Cn((O|2{M}tgGR&IF*S96n)awH6+@9&mP+%ZpfZ+{vt+@YDriOP#n(^aLo8!G$a zJ*)^D>g%<B*+@=Gw55`*>Dd`yV-(l^$Yl&=aqtD0o>>@}4WwNEi^gw~#uxksUp0nU zKe_TZ;M%m{<}{P6+f#R4*RS^_1><`Wb?HYy_Y<vS66B3K-EN5;OY?YpD0X#L`5z9Z zD+d3=q5DGVQU}PJo9Sj84X~7y#?hz%!+yiqCn(619QA+ZfZ5W!MNNk0k8Z4^=DW>> zhvL-`)!Kim1Qztn*W>$sC+N&H>xFFAmg05GEv>s4TJJ!GH=z|0o;H_^R{{W-6dCeH zXWKRUgzvpp8H_VfU1mR3q6y}+Rn)gqg^s}ar&=g(vb<F53?BFuqxp3flahTqkB4au zS2>1*8cQMb!i2dP?Ar8kbN@N_qPDaNoLW*HQjVf+H><YZ3H`nq?(C@^xu6T?sQNZh zlnCog823XQcfBn~+Mrv(Y%AFl+Vm6LZxY4W*$H&wFY$jiZ$OWyVyj#c*)u|IrBDw& z?=wGRY3MNhQQ5OT&s091XHHX^v+;800lDfY;TCNG3@3wP%Qf4bnQYeS!~6Uo<G(YN z$vD`sh29wu@)Jd`b@o(^YI8eEXFa7QmJK<E%m2)w4&>;6rR5SOwI}MTyMH3HSUU#! zwH9?+2RO<N9L=XELKf|AkT|GFQ)G=q(?Ll?;oD)IUuq92y5$`5I!}RnWygz3f;0vr z$I%J@k-2t05PylI^+Cb|*;Y8)=C=;�D5eI$rvrAL-$*A733ejK4A<6FFLUX1-3f z^OFw@0K>$FVH4T~&xA+HjNISr{)*8$Gdoz56_oQ+>sXA&_kKXfB=4@h&MN4H2>|7v z)a#2e4XNSuC8#kaByctxEJprmkDf_cX_!^feXD8-(r*uz&AfE_hnfPR4ztO#&BRcr zzE?Z<%DA~^=6n9?iV&mm>#Ul!*=ps|;;hEpGT754U+AedBW+N5{wDim*D2~%buQ3C z)@z>CnU>t;8C>e0)p<wB_PTn_NW511?JU}$y>Fqk)f0Ro6d#K_55eiJfY#3=m{z>* z8oQToA%I?w!PZk$h)i%SQx?U!ng2ZBRV3d~r%B>&R=R$&Y_UoTQHwM~!sfch{5Jgb zca1xw{xzKO$hb>Qbn#~wEfLX;xvu(2AG^3AUqIChn7w23g*(K#t@Bgdd4Fj!BKIA} z;~KW@hs)5F`hN*WcP?O+nydGgq9Wxg$BEMjIY<L-8^{o+nphnzLhH1A(EV4}c%r>= z$I0V7yiyyeRdB3c^yXxrI#d@2>&Epzi0N<q$vw|jVbvjZO)X4zHowh02;FlbAVwXx zrFu-ex#jn1oxN(S!y__%UFVFtH`HPHs};pm-7%nG=d;8oX21u@FV#}Lg$KYIJmN>y zy`MGe86r{1?tGJB$?1kfpJp+v+jWoj=h2uxu#>TxA?_M&E0}K&!Z8iEY@Cse!gt_- zPm<o74*EG-TFVsE{MW<DqKVIx$fI$hzak9j_K5pVHSCWA$+PN7rd>r|xn8sC%%;=; z3h9OUST)vi7o|nA`+)L~X*}(z<dk;aELxN%?>>*RZlJh|#Ot2P!pmA`?!S6rvu9Jk z*z=#-LzdvUht9<B`T^IH_5hGH{hCwPAyuYkLI|cuVwcylwY*)Y9fY~6p}*~U?+?&~ zPgv_OSDnkI=&Ex-tW-JIFzVWuM_K}9F%A%PX}M8IiXc@6zIMyvfwi<*4X-(i@jwGW z6QL6$mmTvaGpe~oqM|*bIY)U@#$V;TE<Ntbt@?ZAEvRZC_vj?o0#~}cv(F40#50Ln zis@suNVlIPRI7`#ELFF@kFjIEc?KyAy$;g*G^@2j!CyU~yDY&DN%|}h?`9SC>Sz6m zercb1gXy1|-jX1vLD8PiU~R2Star)B_PBUR^lhWZZDrNId$(ZrE<0@}dVIn5<JCkl zs?Iw{+z0M#J0oD8$$Djd$MWFOlGrym_dl}UyhDHaH{*2xeI3%lFa_-TOuR<|m4zxW zDr8@F0Uw5r%Cl|G^_O8?a{nM~8@%>_+GVERm~X$cbHkT=y=yx!&vfq5PoC~B-uTA* z(5DQ=h+rXG+jIQS9)p4M)18g}$KU12*_(O!-Uizo+VS>riyz1^U)#vOW$JJ@p~=kN z;nMVVEt`GKMi${VULjM{w+}g9nQnY7)j8FEF}fow*V8%b!Io%z^75$q0rL!Fr<|vk zN6tM}c-57;5x@Vk?89w!neY1Z-O8M=Cq3R2ad_kL^5cyd__{klD30NR9n-|iMnQ3J z9>*NHnyG1ty|Zua<l25s<<tHr`!2@$H-E(3jXB8HSpD)w+db=5)s2Lt{11dyP-J69 z{KDqP`;S|<`5tyZc;F^W#YTS2)AE-hT^jCp;*pa5EyKM^F&D4jSbIub$qIW&)X+%W z;{44nv&{9W-MK*LM=^rq1!MDdhaC+s55^t}Jbg3N<!xz5xgrdW1OSM6Uj<OPWS~r1 zYJD9WVAJ_JfaKfrTB*|0jsL>&7wb(Q6i3KVc3%;0YzVe?lby%~6;%0}=lky-(U;g6 zlo++NXV8IqC|kp{fo-Z9hi=L+In(r6bBhg#J-f3GV!5ZBv|_kL$LCGcj!n9+s}oMv zIh9?DDH=&pQ{HooYE);NycF{G!ud1X(53#3apm=n=z=kjDj*&MR9V~+;;Fjn@j_4o zB&Dgl<mja1wBk801TK6T?*2J%WBKuBB@AHNGz0bq2I%^0i2Uy(!E~UF(WRnIu82Sz z*V|?KS+B)F<vLeBHI6z-iQk3Ejg_cl&eEl82rKo`_d)f?d<+!bKDN`Ay&K;e$Qu1( zKVsd}fD7Momg7~SGO(#^avB7>gJHPRo!wS=CpsmhZF)&<M9&5#?a}*D>%Xo4j}k`C zi$xFdzj;jLl6Eh-wME0Y=If8`H!k25_iPd`%Hv69evh9zB#I$>f)@mFfg4ZUHV8O! zCi=q_w={ymVP4SP)TVRR8RwL>;4?YTL2$%ag<M$Zth~drHCF8JBPr|f`V^j7rmEK0 z3O%+eI9J||{FK*B$c&w*M;^9|lQRa1V%spqw8phGixH@rBKl}|M(&5V_MYPo%i*Z7 z>8ifqz{xkYy`xUgaWy&9$>b1a=c`tC^-CLWL(0_QAmPn&2+^*<?VrG)!Sm(oQPPBT zGV`Gx9fj;={E(`R{x}?bai7=eh&}Qf&V+Z<SBd*po>*}09u>OHP!B@$hJ(W!ExcFf zbQT4^+gm=%TsFFF(^InT$rEOmoCb?`Vb{oiFC}Fx=sH6MIPndNV?$;D%(PS${>tIb z3LXSiYlXP4+9+j&rfr+_m3a%cUVkq{r8)D#z0j}J!^_H+T!9w=t?46_ERbK04H)MI z6{iV$eVl)4o(`_=I4T+OAb^WtjRLRSHJb(Af8zd&3Tz}V^5JF_8tee0b=Wzi<n=P3 zh_MTTWP*a}G1|kJoNv7*(XTZR3q65P7raFlZCdvd`_a&)k~5weN0dT}ocj0Pi<;N> zOzZVYyu-2$P`YThLLBc4m3^Rj+I!0~jt5SIvbTbOLP)ED{aEEdc<}q}KN!7GIpnQ^ zrgK=A?#N#3?!)BCdW{xxp*3bvHfXZvU_keIN9C_pVn!TtmRYoNCKwT1F?4EoFUrc! z#yWfGh=H~K0P)W_l-NJyfJ^3*hIWtcJ78w|ngw@91p!C}&x-fV1pGLy)s6mIvsxr$ z;g4q|ZOTCR)_@IIL6=I;e_kWM5)Bw<Q_6hITRF~c{rVk*3H_fJb@}Z6f>CrxSPw#H zd5T{ad)=>S>5|+Edvkz%n3Dhh6rG7XRBs!{&+MC-Irg!SC0q9Fq_OXeeUfA;YcwQV z+hFWuEJ-SjeNCejN=5dfMoH2(mLjQ!QYyc^-hbd+=Q`JOo#%eO&wYPBjtheO(Rq?k zurT*TZuY>lfL<uzYV)H;?0R2>6qJwgd9&0M<X^L$B?!226htHBqlG@7I2XH_E_oL{ z9u)6MbQJ&_V<+5a*Mq$7{}e5ZH{+TucHo4dqM1OqrE*g>zMN2Q8~7Y)QBjRnQA!~F z;GtX^{_NU}`I_6hTR~};?kkm;GNMG>kdN16^9FOe@DzJk`A$EfKekSP6@9@o$eHcf z94c5asY%DtXzrD@viHe-BcPD?PLl5NA!20ioEiE0>4h74+d2JkjUD^vDQl^Zamsh> z@{8r&ZnlypZD=ETZy}l;Vgnp&Ib+>?@4*WxZ6(<Tf2gkyx+tDEnnbC&WDovl*rNSh z2Tl?-_iX4LklJWs9<RRp7y<@mCNt@0@@^drYm!Hj*=Y*P@<gj=gqo*Ev&gX?`MyDQ z0!^nYv)2Z$`Y&4vk_2rPj%^wGZgdLW+OXAHi6e|<*;qwXAk7Jw#iyKS=SA}MPzUzR zVHfn8x+JWW`+^Az{`<9u)KM18)ku&Lgz2Z~rpV=W<Rh+0bTG8-j+%!}?eHUFBZn1@ zO><mx(yyi1N!IW>@_RgCVp9>>CQp6}o@RVFpZQZ@d-r>Zr%u_|)xN1lD*wo`s+J|= z|IG}WL0cl9CSQ|&+hp(cTzrQk1e5woLw(W7GD%2-VlS!=YX?aK(erb{q+s_J`Gwqi z(T9YP(IMp@Cs*?{kDP*x+QwY_5>Z@%l#N!6?cAt2r{10x^FC0v@qv7i(;EjP1U**r zM{v}s^M7?utJzh#QXUHw77G1;d*QE(WiCdQ1X}WoIPRymeOAH?3eialjn+X<& zkcNsRp6tFqH6W;3KdhVB(d7A4UB9e}+OBIcbhZZ~DP;5eweef^L&<ISYHjI3hv(z( zMKqD#BGPbeX~d*Ojm~wa%rm<tGXqfzViSFX(Z{!AFZl5#gvZf#l7A>TXAS9<h8A&i zbGO1Cw;CxvIeXM-{knN?O_IveonozS{P8<ij>PZDHeIyDV?o9-f-XgLs~_+1^t8s; zz7dNp8lWTqllwScF@#Jj4k16}HIRSuUMOrhp9&!jEk9I>)or|XNY<sw1>6<ojJKyP z91eeq&ginMoP029Q`>T5RVtC4z&rTOvZD|($}T##v&D41%>9~Q{1M6xCaux46T;T- zXUXpceukMUQ`d6z3R<rXy+5=KPxIaXqxtU{y^)uwv_A*EcigBtC>MiuZO1nc7Z<z6 z${y3srf3dL&vEUAp?yZ^YUmW7(5QUucha`7m?!ZE-Ga<O4>5?7x-xE)iF@k~vFuNm z`r*zep^wtT(KO+PAnXJcCx}9A`e-ho(v?C8A3?$hJK}zjz#IrTO$$bVNz~ivcQe(> zf&}2VGkQxzwylsr1z;8rgO5^BB&KZtu4SDa<P)4BB7n8_!7GxfJluUG?iK@kEeJg@ z&6JbJR%hUfIHBjMnB2oEp$_DaLAE1|)J_D^a5;5@j#Hh-i*{!?%g2r?hQ&H4I18G8 z+qvi_LkPNn5lA2}o=G1S+#^p2`i{$C?{}gTe^H5Fc*&3pf(Socge7_wl`B1$P^N@T z<ft^$Rbps))4Ga(sN0zPLHOfG1V*UYvbq*2Izef)vt<us-u=wWd}udChoR%7EZNLN zbnc#Ne2}m}4&Q!1gSdm6duW@cQH$MQf$>3wHjqO@BEn;hwJH_y=^$LrR;7`wJP;wX zp+J01CPR?%bL8axrKq=z=<77e>JFsH;<+>H=5NSEI@_qLn2DgtLV5^049TBV0SXAy zWuPxk63RkN92Dure(2{)S`aEyqW^TdG4^8<I)sP2MaDLgQy~{6(LZc%?aJOiMUqZa zyUsxi?@`+#si!WNB;OE0s1ggPd#6e<hzNoUI@c*!@FyR)X_!(ePv9=89$Uc0_xm&g zS#l=Z=VBdj7g*RyI{YRV*Q}$WzFFEjM^deiIL}Fy{Gn}dLhsZ}c7+0_gcTXNU+E(w zR?i;jNdV3+;io^8EKvzd4B|_=MS@PsH{Pig{xMTyZHp<<P!M<k3iMKTNS`>Sjw$37 z_6QUOSwGqwbTqX`vZ6-wQ`eaVs*~A8)R653@^bbc7HTo8QtO6DfCAwU6#=1xQsvSd zL6*%kuj^DCi3%_{%9o7QicK!{h9n#m1pM|3YzPC__~^NKOdGv2v<ce+;5zAWwG>Rf zPDxL*r07T73yDPBLxPjC{Bs^sSojJWUGO%{U}a1p-iuK{S44pTl5^&Z(RRU}V8JyV z;trwCG7k5JPx!(hm@=bF_9sBdbX7I<I2&72THd@v9AzUCLHtU{(e}}+RdeKNJNz`u zbBdLpl#JWeRcijJ2)J0Y+p|EOuBfDs{L_cOR9$A7!~Vc#KcJwNzvF%a#Io<l;)eC? zE>utd#ta%#NO2fV31%}7TS|v>Shy>UK$BESjm$H7!x5TIf@f8UVzbP)IspsE22Cqg zBrm|Y2DlFrAH-i>^s8IrI4otrALtNW^9bBr{W1w4k%yC##MK<HA8^1xI2Z^UL8qi| z?P+XI+fjDlTYGS&tPASlUZ1#)i;Zzf7cX3Dk=uHvo`TxGZ0w0x<Ls`d)qM*hrcpxn zQ<_Sf2$yN+J@N!uN$1D;7}=E)77KTZjGCn4+9_DpU`x5-4!IB~^Q+3&OKtK7o}`qt zMT))sJL7qt{0fV3u9^so0^t<M6xZz9OQtwPW`beC0MVIFCjDhiH5|+(?$LDml?okf zv1!2tDkg*~FiFSMaAZ}T+EdmXH&_vR7gJm9FAMmhHvmFoUW*u%*h?!VI+K^cx~pQX zB0A_zDuL7AF=QnFpbvrI!N;irnR$5JLIXTBp`1)Fr3$2nU}~xQO3i{-`;J!fv9&x* z?$kMjXz>lJ44d*Z(?La~U<HW-we`u{XNey>|I8^3tFnz0Abo4Qt?#6N=8BIo1Q7uI zJC!JiZ8I^uNRr2e=wKf72{eG6`!N6KnvSy^E2!8yZs)<rVtw<6Z0z!bRWQQVB$D%4 z|GT#^VcpYfW(G~fixhw)&vxZ&xSM7vSrYCE0|uPSgKV8l5raQI%{$W1eJ9&Uf?8iy zk<uTEtAbQA5A@`u(ej=1`OW61A^3bwORRAWu;=Xk?z@@62Oq7SMfbPcmmiLQ-NB~_ zJR<=)9AbacL3%BgYlyxBa5~JiO6YNK{kpkgKnNFgeo?IF@0G``Vii!_ai4tc%KTC& z;ZJk#P*QI+H-9}}PM@}YB~=k(Bm^H51}?nbA@M70=n(P#upElOA0A;UTGzr5b1S;d zCPVPuE9SHaa2x~%*toCxZO~KVOZ*elV!$l~ZklyiN*52|KInQ`^jhbxQQO1lITAwk zc<P>=2?jL6fe`lkw3`Rv8&_bEZqX|V98fTu)>9E05x7piRs;h6*mN%tKR~rndovK7 zMqUs})M`2NnJM^(j~?6Ivv=%PXq)7JKM8+yFvcOfrLqomWifEVgn1p}11`GKN8lAV za?ToapNvcc@y+CGa=rDr-WaJCOa&vHuzSSQ(p<wS|2}}T3YV<*ym~vlx88$TM#l-4 zj18s{7Qk)71{Z#74tQdKmW)oaktD1K5ywC@1cW`H;v1C-<F%L`9gIJSzp2yU+H^ld z2h&d{vUXNM-QCtLkxzW>^L?0GA8J~X^n!;8uUR|d<1?1DOS@khPMeQFbOeW0A!Z7@ z?*nz0(e)cf!e`BigWyd+KF-o#@NuolJuc23#8=TVS3n>c1X?*6*T|vW04z{ipoofd zdd`Vxe&W97cn_DDV2l3>Xhhax3Y{MvGgbQtUedfUd39|d0fy)~yc@}df9K;H)Quds zTE#KM-);MoC{04Cf;SedFR^fnQS<=85_moXEdyxxVftAYZ}#mIzxOOSjxfjB#+OnL zC)~n_h9phS<D)4`=BtUh5PYrGv=3fXZV|uELdq%v1fFgXOW{`KSvha~Z9a|+!U`Dz zmXBN>*ER_yO<iSk1@>lT=%8uw82=<}MccGVTK6>hmR8i^bC1RUP%xX~cOr##hNNDl z#1S5qO8;I2pp3r0V1}mIv7C6qH*hqUl?<Ua2|bz}n9s|&guSJMfy_Hx;H6!?DEPuW z)tZHz1O?iuxFYp8)rAHdWZY5AKw(&t<S)b{VD@)XZ!enp<RIzjBF<>190=Ntq9Bh+ zX>Mqo?7HLNM+K6|_*D(Uzy)Le<B}tK7&`!Weg#XCKe4+TcaX7N@=p*bA6H>YJ$R=n z)E7?>EyqmrsxDD7@Pp$2NRK|gDJq^PEHDPKPsECpNmw!jZwV3MqE5)1ywP>`GnsH* zW>na*A7T7{a76FtX)I0(@85@dM#h%=oxSrJvV@+nzBw-2E_}!y_oj_JLMDpD-m3f( zwCmd2hAnI+CDQImugB#i6bm5IjcfuK0_Lf%9t6G){^bGS02e*jSGVWBxkfIgoKD=~ zX^&7a7eJK`M&RJy<gh*g$%t|i<N@uR@R3#YRsX{WUHe=tb+gF2p66PIg=x$uy?0*X zugA~o9z;+iiH3VWx_A)QSv%gdn--^udT#G?j!%lIZ10FW@dF^d6a;Ptp^wn(4Uw-d zgk$0%p+&BrsQv1H09^b`%?O9QL{&Sbs}@1W`Tfh6&{FH!_?)^n`;CRMXDbR+Tg~hx zoXa9K_)oV(h+}-5@I`^|R7RhO*_UqF8ZKtXv))Vs{0utLIjCe1{fn!des1zPK}hNz zuE=)vG{2lFf531HG2zx@JP}mHTm2U+{t+auvoM_=K;RkRQ3c@}Ip9K<on(nX5&-q1 z2rOHS|7lsN<<C^;r2p83D(}OP)-aX4&uYf0JzPW>Zz+d?n+U?N2A9D1f_`uDouY|T zEZdj`@{L`@cVxsgyTi-EBL3pEmE5+_vpM`X3Vz`Vkke!}O;*%Eo^UCa{zefPrz6OG z9Mj2g<&0@-JGPpKdGywPhv=J4MK+SLpVUrLgD@$apZ5SWOzei-WICUVxA|BT{40aU zGb{)sf}Qwv;8TX*+%yBJ<gt<YO|W#7GR1~AP8iAV=){2P{h#B{&5z9K5Fy;1X=hj= z{cB9oddGKt3o(3p5UP}SF>r14h7saC7rCD*@Jt6=Ucl>l@>|N|8WfdymxDQX_rRPO z(94FurV?@A)*8%fi4V3y;t2Cp#sTf!#2p8EEp!X4lRopBGAuHX{dA0jAk$HU6yma$ z(k*Q>Cs<r007hDDBghW)DOJxptk&Tf?woaw;4Zg1+T^@#0qK}v!4Kps?Z^q8lt;8@ zi;iV#KJABJJ=--D$8SQgeV<?Gpf7PXy<d7==>odyj<y<o{oqmOcs^{^#7(v`l3$=z z@Bd=Or)~e9Dzjf-4|eNf3FZzueQ8XWwReTW;(d+2-Eqx-j$Y7`HVqkzGX8Dr^4=_Y zIq}ghm&wvb|8^0)VuY$s@Mv-K{G7sa)h=g<ouG^AtMB35YMIJt`$8duLk2P)(cx|~ z?pNRau>4!&B1fI<IkD%c|1odb)4W8YN?<RCcYJ+C*K>|+nT|rKQsYriHx4Yky70&Q zW&6Qy`u7}+Gkkmg$@Rnk;5VPQZ_qU(2cWJOGgN@qpT9p0H^b2$HxJmEXvljKo_(Xh z3-^p%2Gl!pD_tLA`V8K^`O{n#Q^(uY4L7rCQA?Swu&Zh|*Iyg_`2?aOd*;-bC9sTS zQJ_1nk}uMUPb}l?v%5c!-KFy`s$4u2)ifs_{A~Bg-4oMu#k+jHdlpL~@^qo+451Mp z9JMt4>+=D!{KFg0NYDD4>D<+LSHnF{;nJt$tH&gx&b_jgos*m=NT)zI=gVKuigdEy z#TGLMEQNihb{*$Jv~wVE`V$D2z_G51Z~q)Q2|K;|)hsTnS24@1q+{ty;-mf9d);<9 zjrIXLg7p`-{Y5$y0jse7>n{xEMnB{m()$smUV*j_@`0tI`X<r7t&ta;R!qXZ-kr*G zykZXE*)~VaI)64dC9Ea}#KW3!y;4f7A8Am6F*`rCHznLZ>haqN`}TJi?MT5P#(EbY zOiN@RIEgncFY|&n?UJ;W6xro^7#DjTXIzJ=!#l+4ekhxOQoTZ0-}56cIYwE1Aqgqo zD3?j*s@lk%C{Qpy{5BP8f7Od|>0(%whYLz3?zZDg2*hCri=?_@nJtyn@MXWAdz#47 zmBY+e56ushq^QWMBq4v7dD=`aRt3j*ZwPrNp04b+IAy7X3#4NZ=e_bY`7^h^6Jjo> z#=oj}+m2H2Q2vnJou7Nf;65W;=HdqOnp)z_?+}~oGF_LukB_H}T##4FnTmiYk*uXp zKb!j+-)8QkB6D|GP?V|Jf;6rg-Hm!B?81A#3*~G$xB9in<HBc2%Wj7TVdoXGGby9b z(nc->gw+fe$JCXK&c<z34;CiQAF1LTd)r;#RH3=`@6=PVGSpRlZ<hYfSPzSgwx7QE zGV({!y0;GhoxHMO@Du>wKQJ;qTWw@;rAF)u&sHpu%>fdiq9{z@zjA0cu$4|o@5@wi z*@^hGK()GyvQbSPxM*gE3`*njfj4@DSEO3-Ii(EU^<4OsIn<a(nla{tT9Z9LNK=}# zw*{-LI{_uOXK8m~Lwb&odxw_vI;rFZg_~oCwwCJ*6@?c2u$@Ws=)_TkGL)rLl*Z51 zOoOcfYx!zdLd1ssLuGV5F93ZH#S_*Mnm+^yuLYTAH$1Y00^=@GW+xRoCQ;hmDn&z@ zTELP+or0!GaZ<9Pv>mw;=0Ig6sxfk3M~o1)oAq88s7pV0umiqQ8D>gq5*s-voJ?bb zCW1jUq1otb$z%1S8bTX29ABqH(3WpTL?BcI;+vgIMCD`Y(|=!Mc2^h0&a9^z7rc~= zohwSS6;>?hMM#Q;7evwqNU!;JUsiUxC5tH?|H!fj!^(gqmmolCIm2RnyT34wvtY2M zG!=bns**kxDqG00RlssGm9DguyWP0lv67ezm@D8cM{P8@zSwlPMO|D6N#TrTj&nk~ zC@RgzL3>OCRXt2vM`xSdN#5JVfXT}H!_0ZbDi?mLhTZ5H5{ClBBi^C1FDi!3lRXN> zXLBqq3&WHLCQ+i&j0h!=BIMJDJ~>q@WBl-t`Q8`Si3tOe5YSGMLeD&O7_W27{Jko* z9~;tXDQMq4r0iLYHMk?<s(8gpD=he#9tam9ekb|3n-KVm3I<aZHbyhLK6ydzG8?K) zlg|+E5&wvwKg)2*J`ZB(xT2KPgq>lzQ$bTFOy(2%i`oeV!gk!~fOyDq9h_pKD8CcP zzvn$N%l*`>95>V$vm=^6(|7&w_`vQ}_VO>9AU5EYB_@%N*cFh*!3rhR!N&%*)6-Dq z0Z`#cufQ15G1JD?d6IzyJX*)B*mZ*+X4Nqq9{t(+*bZ4Bg_2=DvqlKuOy9y)p>*o{ z3oqSyS@MydXYr1%FJ#OHFz6j40DU5^B9_fH|D670vM@?@K<xI+L+gb~+3RHk>6lBN zy6_J8!JK)aHqIsI1Ck7VTD3&prmZfNit^`LiB7D}6zw`{oiGX)+Y?8P7BdNvHuSXC zX{}SZ1Z|9IOB33lq9VI33zC{{_eVWJ>b3;mQ#r8x%<(PPUQ(LJI86Y`WWyAUZH~S% zXlXb5STWCnazY@(dePr`S?2evCq8r}>|q<*NF{VI9c^?(8)yw--j*&ZchiL-Bx||! zjv^}?9iWwZ;Iif`LdsDEgAsJLG15!u(vBf2HrZw`$tWalxWIj#Jt%qf=CxN36^C$V zP#Hb_`APbZUX+*NrIq?#NbKi9AS^&5-8wjRZ->eU)>;ePKMebqCG&d5ZnxAdL$b~I z&Z}gU5w!F{`IC8}5|Bwgr;~eN)wr;BGr`<zEpj)!R<1J{-j05#8}4@ZT;r`$15CKk zrTSXgELG0g3>o0c%7A3V4&I0PTv+B4ZeqI~fxML4kALO#=G=?>Kd)T>?=l>2+5N}Z zi2eO#>8NeHimMZ<Z7z*xZPbaxJHV}DCgb~nkJH7n4Pj7TE{)g!EHDSY2WLf3zEdLx zsdyNY^?!gZr1o0!kk!N8$A2^{n!KgqJ69&l%LWD9wyurbKG#a1H(ARC+rjjc2~$;U zm`)!VS$WUu*jnF$)Q23MH`d+kPZE~U&C6+3I2}MVqF?X@sr4KqrvK(o>h0GYJ3Ufm zj-0Vk{zI_H5BOf#oX-)x>kpSp_&Vv)=3T*+&fH}ok2HZV$TkL90|ZN47<3P(TwLDt zkvwrsc0lkCDZATkzVy<Xl{KVkdrNYp-}>vm5PW4*wt27oO(D$iZfs2NB`IP-QrXo% zznw=+;nD=-Q5_VTfl3A(ivdw%<S9zFr=IGRSGIEQ<pdf?tF77YK&)@3Np7ZTJnZ|i ziM#qI>m;s5wZBQPFGCm1@FVAX#W(Db>kh4FDpHsymow8}=M=@=`0pk;VOe<ZEHhO# zTWjF@rL=5=(TpLCx%R?+4{%R1n((?>>rE*tb`%-QFiCD|mw_uB-$b5fAt1dy&}0Dq z196IvJidAJTeaA<2dbZvUBSqXsX#`Mb8Hy*@CkQPq}q*6S)0w?vsQ&Ua-o{b?ccBs z<aE&;>$4jJ;RM3WwsVlhqZw8VrXQ{Oj^&^xyyjTWE!Xab_zKN(pm)NbX|N++;G6t_ zV84E58nBo#3<+)tx}SEL{d&+KD*Mtarr?aZQ1@+J4aq2eb~0DQC*g7xjivuXEhVDM zjx(US37LsA6@d2}X=L|}-cw1<bRIP|-$^-X2p84vIh;IgPTz|U_v_BIKtm7aWV!dL zrf<U27f1mCit)nPbUKT!n*BT!a~9ke%CiuEBp3S%={O3bE%wL<pp93nPYTo|GD@9T z3<-uHe37%{kZzHDGuK?^@vE}MO0lbYsAvu{Bzf5EO}Zo-k`tvG62W=Uw|8HGvM<`^ zAQ!5;ZJgx>W@b!UPNkjCFc$F0*<l$%6@!>S4r1TM5!KvLQw5`=WvDoE7t!QeaVcEy zd-d7Q%inQ~)TZo6o`7*MN*1fql+f0J&5mVc$m>YD&-P+A&4s9G`Z<Q}KZ+astK#?% zuFN7sHZyH#9X2_`lDzbOr6Q${y?qS*OG-JyHWq;#=B|@9st|-XE6aX!Cjib2AT^sZ z5Z(^XW;e>`_3F!c!ioaG2Xt@ysme5r`N4%uD|&`6L%46Z!!rTRM0yqHGE+b?O_1ET zv^hjxMkcA=301nlK5m`B!zME7k~mqR=<$Ayak<eaX5CK?bF5ASmf!e<bRITj+e(-s zzz8PWSZg3$MRs)U4616T_fAnuh3)2N?pMvp-k<rlO>toIaUB(PR<#9RUH3twLN?Xv z7#n^e4Vl74u|B)|N!2X%IJjehrJxJHbKU41HBnQpuLmkkAt!-W{mnS*a74yujd4v1 zM4{U{I6^g;VX9uBCnf5BVYbA%FGG(7Gvgs#`OHtkvN@MB-8sw<Hq0c58KI+yxu;|a zn=EC>cLZcmSt!r4XNOJpC88fkj>2?5U$?+CW}Wg3(aT;MgFuwhq)9u?xC{wObt(gu zL`PMhbhS;}SKB8DiO!BPc6@o)TI|0x&6y`zHxLmwjrv&T2ZRMAwrkaYp0Z3|hH26> z0+t=mHA{u2+>MJ<b~MXz-`pY5!A(f8LrqL?E_~0eI#-V?^~U=g;xoLqG^Ug;%y@GT z&|pSXgz;~+T42lvuc^P0DZyZvIq&c=ikDOwzb!KYXw^QG&$KRLYjdPcyt5AU)nxfQ zTAlU){B?uL$kYSgV>c&vE^6gkP1C#K0m&J9B&cyW!Vit`Y8vnDX!7bSQk3zrMI-H& zn>w7^f;RLlYxBV9x_y%<*!gLL+zG80*^xB3elk<A*j7%G=BHTg>X1QpU<h1-v_Aq) z&EM8yp`J^4WElufclah7w+Qd)wBt>eYj|76Fwd7hN!pIc-zj{IZ|-(CW&(^1H2_xS zlIa<dc?aSYAKC0hMR=fn!ggS>=qz2TlOO*MunG4dc@`9!`Q6HUUYVuMbxL*^DtlY} zJwNv~muU{l9gEnPBcf#fWj48{{p)0QD8pH(0<zTCBSC_lg=U`srn5ferA3w`@{!RD zWB?l;BQu2`hmsI}P3vmu6u+3V9*+v4Bp<l#Cexpk`*Zc8M<4S*L>7hG%|4&$M??J6 z$kBWyAXfJpwKdyftXVbN_N&#$u*c_glcy1zDY$m)rul){z4fEIs2w_CDD}C3F-{Z> zx$F!ma*+L@sD$MF9#_^O(d;Wx59s`>Hrq2#fW84qFil3)JAG6khKoGPLS2uTI$m%7 z*t&EgIn&peY09IScB7~isV&}YoTGo+U4#WC>of_L&SUO(KzvYxHM|jU+Z#BgMr+f- zo=ryJA&tFn0*Mk8!1rhN6qt2)row8qZ#_>X|8j0ycIYy2|8$_?2|}?eV+UVi#6dPY z%n`rJ%UL`y(a+kS%oI62907+2u+!vJ-;-jPEzMa+D_H)ADX$&{Onj;E(#iBE-35%H zCLl9x6YfH5z{rZ|n=E*BXWCM-&Md=p9boD7%$J%uw9#Fn1o;do7kB1BG}ni-DF1M8 z@r?KDSoTEjl`M|_<FrUDar=H~dc05yCrei+U7D|is(@g2a6sJ*RQF*aK4R?o!q1>N zj7#=$z8WOs{o$D>U*4oERxv>1aWf^fc~Iw-XDH;UQN0&${?c9=qZvb^VoV4B-bhh# zjZDAfOvNj+fjrpG;RFCOsX3Wh$Ia}A7tBAteJ!fvNXht@K0x^xNPB@wsX*>O2#;t& z9o!wbaPMP8P2KXKg*cyvqCQtLtpr9PQCx#$GD=qYoZQdgpZqLxB0}Ll%x}66smhQ9 z(lt2<jgZ#EWMn$4_t+*fE@J7w$L{;ca9v|4d{`hyDs%FKkU@`B$+^q}eQ?JL|FEC} zwgbWg%rq&7Cv78ZRAUw|kTe4~)4do<FQ>v5_y;@6;6|gcK;vM_lgF2`%t%gNLZbk> z=`jGlf+jFjX-paixjGS8_#{s#*zPnr%S`pN9VMbX;LZ+z<ieXLHW4s=VapQ)%Wrt# z(RYi2m|4xA87llYK|x5DO(rd9FeK}|9-;839;s^&YiH*>z=m7XGR`b#hXiE-9O!#p zbXJ5}{Lz)~W05_{2U1u*(F`jOEduz}Q(zLVPl35EYwN)dzus6?ks`%2vO`sUYXu=K zVy`5J7Y+K9&x%ELqnFd-s!s6aqbrc1I$1mPtxjY;5=@huanpzo38rRk+M?q7_8#rD z=-npxR!e7klMqh@0AUL9Fgh!Q1b6PvJS>}e(RX%!$NaacAL14^azE3J1UIahJu`!H z)nV$AGb|ZoX7!h6oxFKN6w~L$)e!omL(GYH$iRpLP7X^a0uQ6Mq7W(#s<lX+<#h5W z10+KX?}ZEUI1&KtEJNuPHk@Oax1_YMT#ysVy>nCRbHo+|3DiT`v05|fYnj)g_}CQ2 zp~`XR-3<rW`Wc24=2%#UB^y3+F4K>c>81lhKgDZr$LkP}>&hL62BRGpIz3fcUO9;K zXO24NtTz9beTEYcQ%2j5W_kh2>6``PNF*jZ|GCv=ZE{}4S{Ww0dU?^pe%l|G5Sx9X zJZApu_t{t!Bm;3@6w>?z0zI`8dh5uM;I7>WxsVl{;n#sr)S)ZLBjhakB`AI?jylVb zBSUZA|2llrE}o3)*GYKlo8!itmvYchMl;5${0);~j!lS>GnrlvVc};JBhDsj6eUI# z{dDO~Jo<Dn>MX)=Bz|O?X`i!du!%BxpKaL<59A>lG;$6GWv-PZY;PT>>_eSaRd)qe z2>-%+9KN6ss3U-v5fzEb&X%92OJx6wto3v*n!AVCe}luo@Mk2@>094d9Ikq1HBGaH zIZ3Ka!|sft2O07&DIgFJHbE3-pjxV;My*|U_nN-hlT3U+f!%(TIj)S>P=z_On5QdN z&ro27G`K5^Y0rY!s{FBcNUcAVTE8!~@oZ|-1-Mg1YRmQ1)}lW(?x~I>ra{j4GdihW zj7;~4)vV3LtssOiYovbApZRO{RXI+yxcv4t<X7BEz906?1N;%4p`*FBhhB?a9J!G{ z^WnC5HKG|s8-<9n(*#BtC~}%;MY!8phCsz;Q_yAlvrqlo!Sqq##L&GFqX=KQ^=0Hb zlAcy}eZ!6seKzOz2}*YUZ40ALRz~9&FM4Jxo}tCaOmE7tWn}^6R3|ilto-<bN>cn& z)S}<N#c!yEq%+HB&wRSNT6O)*eAmA!?SIQjXBLU{U)zB{eJMG&w9$S+-`!NVyyj1g zkt!Hl>AJ8}fiF*$jsA_JBCY8eRy@Q5?bm%*Qy6G6o!p;}Br3Qx(d7rS2y#{hs&NWK zd1Bfj<C~l}w<Ajfn4>I)4MB)#RdI@^U|*&^H*+Olf^u*uPWM%ZFwHG+Zwf#4kK)e{ z1o4`H+fxqyL6K<~g@~hb4|hpiKl<W!Oh)6kgLmT>rV9VIoclQ55jGa((weCG`gWu( zVg|mOA?gIt!Uw=ViyiX4z6t$j);g^jcs)$?e&)=~y8|bsVCSTH*BAUa5&fyQpT#sM zE+29|H!l8T$-QB3;fg*s!O{o9Q$IEINb}3=?PCkuPp%#KwZHSO@VW24#K0=;>!(tM zU*Aon(f4hnc$J5{$_Kt)d4XdE{9b?m?m-4o`;2)Ca{<2c*dWv{9h9?K3_2@6kbzQ~ z_S(~>)i#m6HBfat5cu3SKrnx;dOTmX@p4U`auV1vM07Oh^Y+pLI)-GRZ{zHx29F}1 z(mqy{p4<QCw{KP6?i&u&-R<2axt1m9vTRC6r$U}`OZ{-D%D$g77`1&^N32>cSt755 z&3sr_(vquyEomg@E*ASp=GIa6IlanNtx6Vp#KQE<gVCBb7aJ<0OOkvmgFl59N=4IZ ziRL_Zg@WCLiC>Y$>o<B=q^3W45zUf6?iah1zpXdhR9hq_B4&O!Lf(d;r9^&~`XiG? zfyj@uZG`-%)ZA$hv@!SW#5Gfb`D_a8$%&nM2O+r6g$9EO(<0JvRGAlc27Ynh@kab! zSdoctrfrDnQ!6RWy62vMS!!)l^Zu3{<hn;YC>qZr=b@4NS;ch%hd-QuUlsqM=UbK8 zF132@fjsqDg)wXw`g{+l+379C>4Vjph+TT}Y2dMV%2Y}??cOJh;MsQ^Mfd9Ih>~on z6w*!C>TC;vj!W>;fE!~fQX)@GHXQUaaMI>1OTYxK13^i+aNngC^*zjYht6RLHA^1` z-Q4+$2|;lI0_PFTo>&g#y0a_z@Vd-)hzvz>u&?x7+G^)>g86dJQJqKO?q+$G$Hqnb zG$EiKRUT1alBeECJ6uOuLb8+IFB1+c-GjWr3#vvaR&~$kOTpdT>)8FAD_gm%hiGGC zp}NM;9d6jkmQfZaMqZ!C>n=3bR;9))7u32xUd!xDLr8FSV5f;RG7G(DnLR+}!r3qA zdw+{uHhSk!l1+~2?BBZ9HBE-1#avu(p$%5~*4Hj{X5bA)9uH`oT{b^(=XY3h)tT7y zAiPpNTx`k-@C{q+vT`73v2LU1(jV`x1>8<UrOA+fm`XAyB=|YHkIod+`ys>J$K%@p zdf|<cZ$jKs$V2+c3dBU#c6)r-ZZgK%!Rk0$QTnw`mcgbDOp@0IK&vg$vN{HhKc1j0 zHh1i8kP36QJkDwyDj0h!qwW+NDa>JHR<1+Dr`S13eb!PX9z#~%8M{}44vxxJs0ycd z7}hNN*(`Q}5Bl?uoy|udvPxqe7_1QszN{$oS+!%je?hE>GO)X?zYjT_w+||j%?&{i zaVv@dmzOy_%|{<eZd1uveA3(<I^rBsa`-d9(w9;VljZjv@v0@F8kAZ1?jV#t8v-&Y za59&H?yyln>u?z>1|J{_n=gnt)ZJQ#(@6gurs=nz5jb0@kn(Y*Ju2x&dAvd=z$H}j zml!37-WszFS$;?f=+6g6pT<T-E1NuSzW<$vF}r-+T3)PLAbPWz%CBe~nwL<Cpo9vh zRJh5P=@wc^V135)uk_o|#4;-PRAVP5j2))%(aZ%gQ#622Ag2>u7=ABszzYlBB$2_k z5{;UNzq|QZ;g4Q@H@eU8j^(+;Qv=dl@*d{XaTaKWglf}5bl>RB+_do;VKW(Z5BF*5 zYke@uvEu`>J39MF8tiHbw{dB`ZzrFDN}hOTzXqOoep$?*EyNW!Nl?N#Mp)rQ5AL!( z2m<1LqU{P5(LX*)zNF0?)ZfP1Y||lykxGv#D?upnk#&mTIfD+C>2pn9<IISan9;S$ z?W6QRi^OD?h3jR>h+P65IreW9TDZm|l#j0pDeWs7*?XThD}0`PSs5<9NVQLd_T}3< zqzfHlL64p1KJrzcJ5NDtIeAnf8s0*LpYNz43X1Wo<HE9r81TdWS(%xTmu6Y41BrJ( zAI#*G-<Uk@Go<&jwAMCBYML`_*xP|$*gJmj-7?Z_IDT~e2qAL8^<&DYo?be)?&y0N z`ku&ix4BO+<~tpG1HMUNWRtk$_>f8_OsDV|+gf^_q-{QHsSsZ`eMeA{PFsq{MZQrG zk6jp2`5G^!98@g;i&M{y7I@_&;qYM4jGKCG?%ibXyl5jYlPTXU;0kvXc51Lu*-o5V z^wLNwZbZieR0y8_!+5uO?pLmW5bygd<ME)?Z{*A@mCK99cb0fMm*T7x9^Fz`RuWpv z8EWGyPAC8sn;t-~QoZNQ$C!>B+YIUGCF|1f`>y}VHSg_sC+c=l{1IvBoPIyfagWjS ze+m5BldGTH4=CQ;)X!=t?9W$D3K?xPM(9snGI^N3z+V2VUK72yucI!*MlWV3L0FsH zW*849e0_2@Cgy0C^e2O-=7u*vCs(CR!*+AYnYurWu?p_A))gP^rn~>~sMp0?=8;C; zcfUl&T4ziRvzbKeXnl^rN#%(uqj_x9Oz=|V%us{TgTG(CnN&4SzSa@Y_AlO!{F!Pt zwGe3B(=YQiYmfOnn3P<8@v*pfvh|&{e?}vShHpiF?F$NWCSwvyEpa48v92JkrU#m9 z*#np77aF=7A8US>wSV&vJCYLG4>|T-t!2?FTx2vqaH(2x?<c22#jUsFzPRt%`iQ@p z+7tejf5Gp+l{1|tFXad?VyO=$C6l~9mB;=RotRxd^zPTI*I$2jy$+LJ@3w8NjZLa} zy7fW$>gGelynV~b|Gq(J--@es6QB3*U7PRt<$C08@{qN~ddUTv=b_;5_rCAtdp<RN z7x(X1TgI8CjBg#x&^4^X{gvg?LwjRM+sV@d7C&#O<g~Kmu%Rr;ht#Jhm#okJLTtyM znbVTnT9&&P@bO=!c=g6G>VVnbCF^~Eo?W$w+5FxTLk+uWo2A}0@#XjB18@I+mND-t zdLIy2U?tS0W2fSOuW;+*B75rUzW+WS+x}at4v4m9*Ix6Wt9GR;Q>`>e*2R&PO@;5@ z#~t{!w<1F#sG(j;J0e}FDNAqb&~lsjcRcDDy6pShdsKQ5Ixpz8f&ICQ;%4N_1{DMP z?DS6<iQADcc7qsJ-LP6jx?Zw%neGML{q#?+)<y~M4a;8A7fEJqkI)LiLh5ru@d2%H z_jAny@`6v1vO?zMH@A;SoWu+!yUvx**(6BFAJLs7l>|#v24C~=ZLQls2`7@=N(@pG z*r=*G>1V+*vvZ+urv~b<U;Z1hLO+v%hLExI<PxuiG*Nkl5C!#lg%F_--FZc;KneiJ z|Ar&<00^KV0H6SIL^K3IZv!y2v;&9TpMe%u4;bZC4`hRiPL~}zYKHPjd!pWqcGQlf z$yww{JKm@pD^>Ms2^hOk@0=qKqw9<Ye|&t&`1s13vF}z^0$Mu!#r+{oV<L8?>K}T7 zo1ZsQYn`s#nff?&kyMF&!;t@+eUX;wDdT)w<7tJcb%pDG{h@ro_T{51&f>M1OwW~- zw~xE7zkdLk5)v`zhNA@;!n+Nd9b0W$3FnVU9~obp&$L|#)M_&6%b8$1JC!6G1*1Ev zy;=h&Bts(8>fkl^CGy!%r@N2uUah;^_3b^wKDw?S*S)qddi)t@O9$>>#VmF9`!c_H zE%NzU#fc|-8AXK(u}Rx<?)SI)WyWFVMCz&20|&HiFJ9IDC2GAXnIAp4-L;%gfUK@h zhdJOK<mk8d+q_8=Fr2wUY;xt0ZOlZt9;v9cC0>?xk3IDSglq?9nG`q8gx^1!?Je!D zWcUy}1?NLa(9^?nVNxy*9+8cfi3>#(btKcq30;S=)Hg3fS<BN!7fa1Op0Skw6i+#& zTzQpKNO`__!zw(Xo*`l|BfW<ketA_0Fwkz}KMU6`ATukW=Q#(VRujm2%lgcO#VQ6e z?{!iD61-%y_15=@CDX7@#mX16RLd?4)c-`;pWEftz_`XuI}2bJKPE!=>Oz|t)sjFV z^tTY>Qc(JK|CqhiDZ_{8pj2fl(jwCT6Gd5JXWaCGShR+_f>YTlB_}1BTPu1nb+vQq z%wkU3385c0(k&|+&@0_S%xhMfXW#=(Pz)pk^fpe91-QPuzxDq3YSU&t7)ZC|Z2bKE z&DBl>9;DRL64`PIePXBcLi<T7sPEh#5{0qd#T7yR`q#QPES<EvHqvsBTTa0Z9Jyh+ z%lb(8Z586CZ@Vf{zumU-6^VlFB9!$Xl*m~9{*;2!{J~ZI5Kucol)oo7eka5bd@@(n zd9c^UFJ|KfE&Q56hRaD2zajBsnm=a_Ux@kn3csHBbM|Q0m!GfcBbvY7B)p9I^|tNR z)Sh=cCiySF-ZTCl?SGdh9=kc0qtd=PUtsigbAe^A^?R|*FZTC`itzT|A1^0;{k_D_ z*820ttRVK!r>4gCKPzorU;ljOjA;E`?R**g_e=Lu``@p<zrOzc)`!yG;tz@++gck{ zxxTeNZuD*IJJ(+OzaLY6$Nt-x3BUf|&o@cm{`<wt*8aD-c;VQ;-^-2H|NU9*`u6WH ze?)tG>&MGu+y8AYUElt<_3PXAHXy(TP!4@iNj?MZ!iI{E_90FAX<z{xuHw*-_2;LP z#@R@t(SAZIKZ7h#jkb4qC{)R3s=8ET{YD>(-Qj2I6jTd@I}Aw9^0SP`s|iV?1G0bk z*%W~qa68*!P(gAn$HApW=)&lrvgukbwV+0%(P2p4e=UzTUL)2uI;54lmLDWgOB!() z)~j4Ah;XTud^tL7cxSDUUQjE&<S=47yLK*lyjJ$t=!nIiwIYT<9U0{~Y9+bO%5kYv z5FZ=0GhHuc71SxIIF32_ua{Je*C`u~jk%?+m$C)wRqY)gc~-8MHM!KQ`;9&Fy|aFv zQ&6uF?)cb$cD=lNyk0A5>~Y|q^$R<ltUB3_;~|pABNj;Zz;HDot*Q1R%(200Mi59Q z)yY8m!VEDrE>XxJna{=z#`dTQfMHEua&XwYBFH%5`&<gbu>)Fy@u{+hrPie#O#8;R z3CGTTzgiO-ZjQK7m_D;4+O%WVAuF>^t}e)qcaKmi;#konn9LIm6^c=m5k2gO^e3g9 zeS#(K$&!&G5LSUzd%tIDK&b3@l7kCOhj<d+*8sh!wihY%#LD9PMTIYo)W2g-i|3Dt z)RGZuEOo30TOYs-)tW$q2uHB+OY5W@M@$JhV^tq`NzU0DR>|rhEY`zzjru*k<9dR0 zzGz>Jvgx?)3!rJB1-dqD)NA=NVfE(q&p_0FW$Iv^kls~jvAgxJNrBv%&_>-WsJ$Uh zMI-N~>J4vY?Z<oKGWu#|W|ivnQO^j`%7dMsz|n}$zr5e+GX)NlF_MX+E`{5A@avfB z5x2M%pE0qzhEhcP-u5-xBV^Du{3|=(g$~!G<;mN~Vtd~WOP_Wm*|G>tQ6Z_b+NKpd ze=iJB<|!<7O?5>!m{SI29ZWM15fn5TvZSu~&jj!<lYXnaT+@9u_N=T;|DGC6?eY6e zrU6iR9%)q<?V7ApDziY&4q76;yer1M@`p|b3IrMM#!7OqYHQ0UbA{K^pK>5UEvjzv zSg)XYayptJN)iMD-YAHEJwF&R4FX2w!?$7kGl~!oL)U~-9HW!r$7Z8JwL&{%*u`|Q z84%bE{3P1Tumx6y0X%{&dOZSh%zSRDPHUqXwzy<E+)qfReczUPK9i+q6UWOQ{LwLV z1$9<%_x^w9UfeL<+fEU=%u1L#F0~e<V$t2>V)1hi@W~<E_@OQ<VICzhN*dh*<rRc4 zhCWBX8rbub42Hvlo{!S(T3UMwj~xx2XvG7jI+d(yN#c-dOq7@C4fLjI9jPoCzH8bU zl<E342LEIa{1jxI(fKR)ALDjsttRU%V^fX*(X&c$0ez(NG5{@yuoJlFz(UUr{kLtD zmGOdMWq1`IY@#$>bn!Ryy477DYBDPCnm8&Y{K^*IgwW$>4fbJRCWVL)D(i^!VC8<% z5u-=J-!f+IBzF@S>e%@#EfRC~jp3+f^4#2ksd=%sZFHYTl;WXudJ4IPg3z##&-a^I z66@4KYsALo&tASPehZx%p7Hf7Kn)S1H|@ZSbXZn!o;xaKu$cEf9-4l;9bK+!#r(T8 zDl7gJCh?WsZ|cF+H<U%}&FP(h5QK?!mnX)JGSB9*NX~W75x;>KP!M)Y=ahVY;ONll z?2!5v=mePdbQs26|5LtSH2><*JSsipk+|5JgAC%_t!S1TGo5^88Lq4|7xHdAUF^zR zj^%w8YBOyA<Huq-w-KHjK)E6?MCH5OwEzcAnG(%LIj<2`ZvkUJGU&B)vZ?lb)^bqx z-=Mba`ADC{H}}cOXLD{zDO}r2PLqFQkiGpHb<F(lDS4nnGe^lc7@L+HLN<Dt?00=P zi#D?@ih1ZB^KswVbpDdqb%4<UG6JUKQG&Qe5Z46a8W;=+Sx(jvETw?D!^hkBI|CA+ z=Q>t3Gx=|Z#|AYVE_f<Ek@$ms0`CJ(GiYlJ;`E@~I+?IcCPIDiSlyGbVpIeRRm4F? z^Ab9A@X}%j*MY#8!#+eYVE+bqGAIh(FQ6+*c*nty*yAIUz~4MNS{DMFgG=au1eFkR zyMuhd?GqT?|2+oUk51D8i*#^3bnw0}`o7rC<pny0k)2wReX2V<IS0(=24<1L`-VBt z;2h=*Mj{#XEJ+*P7K_K~GP=mPax!?)4vgyF_nAew`oayuaA$AkYF7BH4ZCgd!p3j8 zLdXPI|FPN=gmpvE+728_0{>8n0~az7lV@SUuJS&1T%{xo1S+Pt^Onq^UxZ^Q{}nRf z1DDW70=jaD`P2C62=MXF$p%mm>_7YwPI%U3UKxa;jv$>wKpF_R@X^^6@bkvG711I) z@uCvo#PTQ{R(x)=;vCKczPVfk0a(!AMVm7)4S<E7#B{{rp7GKB9AXLA2U)Rig+T~M z6VANIM+zoA)+c=C5t7am-r4w_|A@c+A+!U)&n||&no67_0gK?lD%E3uf;?w}!IEt* zM*V|(2Mv_|Z8y!vzxY8Q8Ti<ZdVyj<so}9zkobj*hwkV!$muQ0Adw;n%_Ka6AH3m} z0@X#pJ<vH#XQ<OhR@X4SfZR3ut{`MsXEtb<O~pnWS5N`F`(!)l7rI&H{50HEPKwO! z6xSD+3taC^HEgy7aJZaym5#Z<z_EB(<LQtL@US2$RiGy)D;|51w(q7g$kUG=)A#?+ zoAA=lo4kuA@#^45Z;+29e&j_Zh?ZWJ0LTW>ixk3p&ZYNMa5M7|{x%a=j9S{TO+JEl zTM|g6gQ+|LH&yTll{ht6Amd07MODguA}moNLBr^Gk(F#wU~QX+FH3YAtw%!Gq5(N{ zsJtd@?UMFyv)Yc7tGwXvOPE?t^xdC=d7^1GJj}Nx%oQ@$IO{4R4%^60W8PwSSkf|I zcssnnXo^cUa^eCLcR_+M=Z(RK^4NM-NZ7C?cjq(zxY#No7|{f3ID!qgK>2#&vlo>J z`2ve6_Xjk=h7H0Ovg<9|B(XHY3d{dp9YHe+Oklt#1%dY{Xg~xw>2Oe_%Pa;s4&h)6 zeleiB#k=JX1*Qn^bf7nrcXfbih@B3?bZ^2e<=IrJzNyG6^8|#E5hd>G)_EB|2Y28J zJmwueyg_)+Ym8|T{IFR386-Tr74gs!%prrq+tdQ+WRk02c0nQ-H)J~CE0w+EeKL(L zUR@7gJM;QyNO?p;F*{zisUcdIz^`-3RR>Gt58Dr(7wM?km0GJ3T=_V`t=5F_l~M>D z2FZL$SpPxLzA?!lxUm+)7sR<DQqYwR&(^#vbyAQWXihljjF7sbM&VITcaqNEa1vdo z<_im+<BGJ)GF#DtR|P!E&ddt^ryo4wUA)L5Q0`oTfXQ}I;LXYXw_ZlnruaD+S6=lx zgeXpNe^Ec&e-Xk@=`{v380mg`*tR|_MzRJ_q8&&HUaf42F#>g?P6_rC<f6eef6ILa zga;;q4IjcDY`UBgy{X$O^lpD#&GtoCzRtl`8n}G1Ze<eWWF1pWwQLN+R#6(hp11&u zBmPH5i<}RslBDc=mEXD|zC7EKxD56<2;D3vRG-IxVEM0EyKYe0@g4%Ow4H``!bdV~ zbcg3VTRau+^NT7Va*HTpphScaUhX%kx`VS9y0z~ir-g@w04QrR*h@jL<RHdDfpo^% zpJ>Y4C_jXyE3{RLb_wL#WT?yEhEH~Ve(vI|j2`Vn5ax(Cki=zjM&gHBXTh#&Dc}R^ z=Ad|f6bk{hG*;Nf8DqAe-h=fpL(+NbW#kl(4MjqWx6=u1o-s(}CqUPbI3+6ewol(( zN!vWo`QgE@-a-@GB83nJe$Hf{8vuo`oqmi#k8vXIerkL-cIW!ZcF~`=wdL;~Tk=)^ zOE|TGZ+;;#(I+rOO_0|Emp{Yy_n|zq-Hs;SNT}tg+k<y>z~&3o*LPG}=-9Bz)X=^_ zSQ=_6nH`bZU;EcZ{k0okzWHOvJ?Pw#sw0<BbA4Dr|DlT(UI_eLd6gUEj>!wRO+H~2 zxC8Yd+@2LrtM@pvoA`m#LzV{*F_7L3%yochYU;DfBYfpY9N+U$#u&>c<6s^Fxqst3 zApPm_ST%dlmx5s`gK3Q0k}8zxvU`2~E}P1=s5xX-)5FqA3WI}y_E+(R0KcHdZ<K?N zj33<Dj&oZo^N$HQ5<>$eC@@DV__mKQ;Z6ANZ{(C2ay1-0PX)QD8Xdt6S-W?h4*mrN z-X`wT=v9$<ESv2BCTxMc^Fy`;7R%1y0}k=g4B;!6V0Bdbr3!V87jOtfz~j!t1rZ+O zm3l`F15<G7<Cs=*wcLt!Gra|xhKQj*f)@90E`)B7iN2W+2q8YABZC8`_=hPE1tE>! z2Ivf(vPa8A>MY^-hHFK@<L0zOv|k*o{4VEB-^C=uPd*?;rPs*^ThASP6QIev3@Q~^ z%tgqpGY(A(C@Bv;8Ql5HM)&+0?pdLieH}m;4+T7;WwjW{{j<9}-#QK}RzhsA!I_kM zFiXGjPWQOu=yL$#d>^iohaGpu5>BW5i^uv#bvJ8(CqN*Nm#{84x$+$ILrmZNBl2an zN5@tba?SU{f~WTpf=X16)PGXy`G;0mJ`;XOc(H~R7Ygf8{Rq_695C$VkIy1npm9^= z7G2DVM>5igK@ezL4W7!g2*T@W@6UIhPk7eEbjShMFT08*T707nVRSn`1XteL{XdG% z#2w1-|HIGhgTY|NzRZk$&2B7dW(>x@FG;dzOSZD4ni+#3G}dG(dq}btk}N~0geaA= zR+6MeU-hZ{{QiS;UC(u$bDr~l-S;cfE)4DsK)n6IB+@g`4m3^^Eq!OfXXFKBW~jW4 zhxl^>vhpG{N(24(R68)`bQrzU9*BKn8hh?J8YHM>eAja=SC}Ew6tXxI@Bh{Lr4rwp zalBX8Juc-aS_$_IzW){e9GzR*Vn8=W3+SPjN?yyx|38WeW1x1hQo!V>yMyU6)NxYZ zV<hT<#OP9peByozx(S<m4?x|UE?gSn@7j8Lgz56)z$&hdfLDW%E{fP*r!CGS-1jct z`@GOHgAjZ4%xe_e8Ra?28)|Fz0hjZ?Tj-4~zcpvU=Q8@Qr+FN`&b=!dg@8~G{ii-v zjgDFr<cbP?o_6~iDDcNB6$*kh%K(dE=;gtJvnc&T&;33V(E~U|(VMrtMR@z$`Rq@k z54}Hi@~3HicL)q5IMScrX8P##8h>l9<Hx$E;C8-*Kmn^(vkhPz*Y*fGQ=WME5H?HT zo~ppBDt_MmXf)Cv9sS1fovHq3Sc#PvACHe=J%_iSi0THaXn$YyjASW=rU?cNe-G_A zC7&q5<M6lZ{myjxqcj9Z6MY1SE-J~!@#{Wi30%u{QGbOV^hbRi6lmSnX**nBe4sGh zNobAXed%l1(iWSBgp8npOOiloOwyPezabLE!AUUQ+P_tRU1WNlGB=u=cUm#tn%93f z<pu%gXCMEplV%>vD+EI1J4H+_lXWLwzDfx3hl2)@J<Gh6oMg17VMP;f&7fQi4*htC zw<hNEC<OJa>NBc-1&((rJZ|)BEMOb$xDit%=y>?S%`gAJ4y)Ruuo<wX{}-4Jq8|`= zx6k=-(DAr+3VqO7QOV(zy8C*>LBAHkgN*%r>BieTZeKwF3TOA`AEGwm6!BY$<EHF~ zku?72)Yg9v`YV`$V+6Ej4EW}$*o5ZSA<>`V0q_}9zE(7EBfSlA*}(h+Z;O8$SO-<) z-&4E%Vj%4Y=7>}H&6><w0T(~Prjrh`FtZ2u(8mU0N3`oFH#Q?%4RlN+S7R<MwY>p< z6}@!rz4##&8myT)IO(Q_jvbde;$$dZhQ2k(Yrb#NJB7yH{&D&S`fVR^7k8dwKX6;h zw6kd&3F80F;s0rWFDCwcm(nIA04#_o-(~VSB6dIrDDd=FynJ)6Ir`ZW@0_6N-+fFW z#O3Sq3I1nQKbD;yAzXU1^j?A-(I5RQ+n;rVfMQ<!kLGcsqw~8Emk9*<!<_49KnO?T zIDlMvsHM&;lnj0ubC$TvDm5Fc>BmK?k|gYSbYQqMylb=qMTcwDtFG^C(>I`=Hx2n0 zx+3&~o>z$ai&4(<o@)-0aNlsQv9xK8zv}#!SY=gdo-XO3#*GyegwdWiNZvjBZdS2U z(sRo@du_Zr@`V=3fT8T8uW#+Sy$C!OZr;?--u4@Cb*bh>t5=r-qcO>w<=$TdOEw2X zYkLiqUtbvnkN*)R-6EZTTc!(_Nol^Dewx1WN!4d}b9Bq~;Qbe{8%g}Kzy9&R3`e8L zxA!G#up7z&EF|wdbGNcTK*_7s1TS6h^($e_3nI-!x5KHs%-z3e<P-ndo}m{4Uru+% zCjHzBLOB1=qr$B6$D{Mn*H0W7KJ%%0_*f$&W7?RnGGX@Rp`j*D{J7+qu_oK0=^Z+y z%Eu&GK*3dEeY$Rg_Hw7l?s+7n=omBwTFq}7EM)cvS~Jlx9!I#W%NodPvy{1!atKJ8 z0|}4EfjQRF2{=}awW7o^1UczIrBwI|O1aU5yTXlAI6FOo8q73&RG=Y_j;k-ye(Jkn z;c8`^j`f79$<uv#nF0=`|J4ZMzY;nhH+*lzYz&zq9Bky`7kFIvjTG_~x@KzngW0e( z>H4|qc+m(DD1G+m4cA(K9uoGW+2O(`LVP@f#c7zp5KGq+1~$%z<Fip#ccSYxI!`}O z7V<m+GtmKF%t_pNapLkBc2g$1F=#UJS_0~*?Wj%IV-fUhgABa>e&c08g~#7L`j|p} zv5`==RaxwdV&n|#cTVgrAPStJX$H-{^v3H&vY@O2W6sE*)m7M4ow6zvMq|uCBh1ss zP&gTySS!sp`+uhO#hH(#-z{FMw?w=ck1p0}V444FsC10~lQf+I4eSjG?sidOu_7)# ztWXP?5+<gjlhlC|1IgCXK_T!fCk389v8Z<PKk5<g&9HsC-!NH4ZhQ;q>nZ_P{0dE? z+C}CD@d;BePesWH)qBb@8pG79PZc|k26n#;B24+zNGKuGwln6(3ZAYh(aowVGRk{F zC;MaP!<;v4v}I1}ETy->kG(gKlTa+?C)f2GO+&)cMJa76P%%4_2Myz8;WaA_Ox$}s z#;RLZx?$JBK#&)XVNiFLKIc5Ep2)N|f1vA$j4JW67gA0B;&)XM?|vltcnZ&2_Gsy` zed$B=L*lw0!afg0T3(lZdcu|UttTro_UEoT9@Go^m&9Q?y2M|Yrn<m1!>ZBFLJi_~ z+gNY@ytsC(6oLP$R?&|J3;xpNm~8bF!LCqmm4>(NA3lj@L-dQauQAjxvQUTpo;1#} zIi^U=@<FW@KG)HokfQR(Q6mXd_{}#|@+I=Xnp|8MRRvMSa;qam^SPpy6x`=QIg#Q{ zfpkUgg~e<~ifg+it4<lXN-MjnuP{2mrUrquxymFE-*Mc!$cigY!t#4=>(Td0-zOzQ z=mG4gM#cCz-zRdQiSoKIe-Q7)Sm#+o+7e1tmN$}&5N75AMYY+*V3!0(d_kT97XqSH zeG<Paewjx>)P|2PgMwsV&gn2(x`(pR0`W%=*1EL@=PH1g1!tFq_1_mt37?-3!;Q-8 zT^%GNZ+G)2^t_jr_%konS=$N>GDU0mCl5}94jWGt8ei!?uJXM0$@Dlh_1y#yg=OQ| zk-(|U`dEgCIMaC>pV_&jo(xR=U+xt}g|IS^Qkm6Vw8?pOfIjiTdsT(w4_y;_5*9-F zFR;6!Xhn!~^@So^!DZ}+NT_u2Bd+*xp5uy0UGT@JCa(f|@yK-^r0NNhU48bh|Eeq- zIe1vu^{~#h1g-LAuJ{;-V|3=>4cC0@6ndEHO&Cd{81vjkq)@rZyk7a+_gRyhlA<d} zY619{P%6@38i<M$9U6vd%}%FR&J8ynE53xy4ycwIHc;z2heI0_>bAe~&~WFcoBo{? z7Im)zcw?<kAWW~su+s3bET{e2@l75l=uHW*&hS6o-sw>vh4K*W_<iqcvC|hiJ1vF; z1;r?x&!%8)w={VbI&>7s!_QSo6Jn?a9QutCwL$auRyn$m^Tv~cJKTNCmbQ}RiMnE+ zLqa+ZU0p0_bjRNjL3Zm~9N%_*2*IM!lyydK@!3QTce*%b@vNMau@ml<O<ILvHSg1_ zUcG#=FbxF|>;$e3Tc@3_;)|#;$Yr+teB(ZV%tzCl#}biev&HbzLNAb98K7VYEbz&k z(Vr&$pmN7Hg99L(@d69<Ok>y0Mz)p$_6)y{O~oav*=jyKv$~07cy3vINkz&PjeL?| zs4(<%VcaS_Ti1JkXCi&QVcgm<>+Dl)=zE@E^xSmo4YbRpM{q#kUa6&;EyGvkaveYK z%UdMBuh}l8%!eTvg2qs$T2iB>XH008^-9!)lEFGZh%S6BEl}XF`nps%|1%;4t%2XF z5%!g?tx{+5niY|2`N-T59U&PP#r017wo|eYB~Rha(OHG$TXioPIAsD0w7a<7<Taa@ zh^(XV_10CIxxCV^{Pe8jEKMCq%QOqqkKh~P=5;2npMn}X4`vwJdB5hI#hJXqs9F;n zh3G;S0I&PBHSu}CXPE#B<_VfgDHzOh><P4ZFkonLP!VAyS(7d}p_4$2JaPG_?psBh zGglMcHulrQc9-~#AD;8)qyfQ(zyeL9+AsDQkdTZn5f{o4+~#;8saI}tVkprrwr2mG zTT{ME%ipc$535-u#EFhaD^_vh>E4tdRy3{cn(BYO75Gt+GK-&|<7@2tj;w8bKw<;G z*Bn~Ed3Ljxgbon1%kdX@g4gRmf8irAS5w6+5wBVky}o?w_D9u+dXI)LaT3M<Y#|w1 zS+D}ByPe9L-Q(fF>|&);q|Ccp8$^n&&|Z2N!M)?cx7RX(-()-GS3x8Ig09I=B)NPQ za^ahm%HyaKnf=+YZOREWomLkp3Z80Ma*Eb6l0Ej}36fQzUA-ZH5uSGCI&$dppY@)_ zec}HJ;(e6R1cv_2`gdnjD6@NFG9McUHWWVm2I(n;b?*OLexC8rwA3#FcT|8^kA&nd z#r_fC*G~d%jBdc>qZoA;Hk6I1M=gc2{b7K}6PjdC*opVtV;5^<ti)~A^3nm0@Ao4t z_T}b{j6IVUz@K&HXr0~)3rJ#;ryDt858j`9kn~CXl_~q5PffN6^5}9O<j-B{rp$k} zt&U9@tKoEbT|wWud$BPstb@lNmB!D{1Rd#MLps#mIsM7EE`DmSMQOStknUK};11#; zKO4F$FKV=qu}0QT<e^{Wr6bVDs3g$<ywNAU5?*p?9PWsKF+L+K-BTqU8~b4Y?jxoA zB&deAnK2JtXOE?~*eh##M5G95GtD>Fc^iSxOi5BrPf|VQk5F45VUbGFade*MI_1ZL zp8y!a>>hvbm2^(}-*%ScC!H|lP0Ji)jJ5&vKlsZ4WY4b*gve;Rza;~gld^!d`5{nw zPW5;P_fdT7<_t@<k>!IF_1j<>@U&;SkoQLf&lAU{)DQ{&{b2FI;r4#dRHROu+=G>F z?O&aC>WUvsP4kmrxit1(ja5zU<q+wXYsjA7n|I<Wkm|T<MIlx%FJOpceF(!Q&b3Qj zD!VOjc0OTvK?T~vqZ8j~kf9Bc;{lc+<LOCM;|=ibmsmv}csQH3&uF}s(a-jsqt$K{ z{iD_VuC=@l=FPB28Y1Z$pJ+XNbVW2BV2_7K=7*B7j7HY#uiM2`wg=iclxCFo<7PMs zlJ8Rx8i`D(lRiVtJY=s`hysw_CY3+(t?ZGJY&FrVtwc22Zkm|bU+uJ!=N-f1oiW}8 zCYw{z8=A~TUEqE@HNV|x0p!W)kI>^xJ!lmeSiv+Y6oiVTS-T%PJv|_hFHm_*n-L}= zbIi~MB|GAlZgdrF-UD}AwQCxOKT68FA&m4RK9F<C>^76D61U0gP+*5y-I#lrFfOJ` zW8<b_7xpqNUSE#NRyi%i&ZF7qn!$8z%l_UJfkM#xHy87fWysjA45SXCL0k1>vgPYd zJr*7KZ)O;1M8w{F3^aDz5W&LEhgdc(Gr_rguk%`=<7H-7^y!d$MBVAd%L&eWzo+vo zv@;R{k<6AOM*?lT8Hm&9tSM4kd`vk&1E67pczVgF#d-jTVujV}x^pg}=tqfS_&J;0 zSXe0vFsBs<P_^&53!hQBZRP^c-GhcqKhD(7JVTup{fI;O>(-JT5~0E;QFI$5U`%4` zu;IJ-%s&`@-s5ZoIxEN5MadT_VA<CCGQVp>P%9jfG+y{9p*GwZ{upB%#2F&g=PB`Y zE%i)w1|W@hU~_cA9R)svUoF<+@O{fR=wF@Tn3;(!)%3gH^v~-Z(mS5p6~q5#*)8D! zNb*M<#W-f{)I_&cEP=Ag{5tY<`p3E1n=H$%<te~<OrU9Ex{u`@Ry;aKduaB^S|+Q3 zR$%e9;K~X-av|dYOsVa^zaEPq{gB+;R78pc&R90@Bb4z@`6skn>Q09EZtj!c$nYv_ zRu9yZm~QmU`kF8MV%L1zbV+*BEMmy5UMN%0POH|JJ)=jm&EhnB7e(-k`#RJEJ50d8 z$56N6Zx3|DjRiD9bA1F)&yDNVJaan#yr8G(WJ*I3`1x4A+)vicL>l5e0AY|0Rz4Z6 zh>a<Il!+9MofpEz^6yvj02fHe?O=!EUwL!qL>ziDNZ!+|B$<%iBJ>ZrVLB{zS2Z!l z`9!k!wU^J*2N6C8pc<~^Ss$jBHL1=7#cE4hnu(k=L4>TJHmN>T2?R9u=@OX}JzfYc zo$^C!l$PhUiy+N+()IZ0Gp@+OQ==FgqyrINY6f@k#<t05FrE}NJI@RTz8+H@1=#S? zd~e?r8`cJ(5jkZGLXDJ<geM6e={pwgl8JF($1CPo)C(j*#5CwEqhI>n^;SN6-riKU zv$uug=aws@1+hDK4Pqef5^ox+p+UIGbqU1p(#Pp4i{xexh6(^f(oYR$Tzn!NL&BW0 zWWc8B`)`l4=W|P^o3u$Ih#Y=kkUR5u5GVKf(i6!}fTQHo_Q*$EGq!rss`?P4)cj$- zQjf;-pxmz1<2*f7_LZv{hoMC)?RBT=MbG(xL~q1cxBA7}c~&Dl8HZSWli%QcX*iAz zBQXGC9Z+>*^60#YnV0Zj9#D1ly8mT&=Ow-n_Lc+ZB?(DLNAkUw$gjG;&CWPVe4%LH zdiQW)ZB}k+av`O3gvEZD-Y#AAj^{<p+tg+cqzWBMpFDZ5@Pj_<pp-m?_YfZmDZobu z`602j($Nd>R5V+@l+N1m{j%Jb7f!*h_=@(jyl}?+Ca~HRmN#3r|DFR;ajDojbKi`^ zqNH)2ZYU-VO6n8kk^n^WnZUl$vd$g#H`<d|MF4A9*NYH-au&a^C>tIFVr?8(a4ea2 zkzV&erVb)viOchQ`pzUIMI|i_&C{{E3^j&%EYuw+&L(XM9|$?Vv?@K%tQX@?<HtqZ zDc86)uby{L#%vtxiD*(6KGaxHqK%|8f4!OB%1Q~7|JJl}f4pIPFqqMk?Tuba-wR%% zL9B3VW*D|-qq<wGzv*u1!`}DXVDYWK!ebk#hEG=z-|~CT9Jo4^ALRqDy00(HAJ#}l zhxtRiMc66LfT)W2-LD8BfSI|Ffe~4^0u`L4WpamSY#h*B+}fVoiT!(pd2JRjkR8%* zFzqE<5}>d@;L^R&IeGW+(vh%OA(-LE;Fe;ET`bR;8L+i~NVWG=wo1KpazOM)q0~0` zN*6qNJS3|*JcAfEs^SOnoUs^&Cszr^0+|aj<%T^FMhs);H%KAcx*JsR4?vtJy@h%+ z<0}Jprj2z@LCp4`B_1dP2|ahBMG~}_VW@b&$}MAB(T0|9-S)^a#&ZZjq56@!QdgWC zVV_IGOP1>kIN0CgX~(oz+Oskv>A@#EZ<3^ddJ%S&XMtxtGIjacAO#W6=DQoflmiAT zWW`QdB8O>+Xj*8W_j}aKTj#E(>jj1{Ig1=1X@h9?e%k#jduyw^+9$rYBMnJuYgWZw zmXEWw`!zC(T?W%12}2~_Yt1#}H6TUb9M3Y7NS`|+9m#=5CiOQr8=RlEJ=os;T8~e= z39}^RUOKQ>XO@=s;L)W8Y$9hm)_o!Pw4E$=gpYMho%Q|R=eOfZOBf_231%<5eX!{q zchz?`&Obn@yc(-nXeU+@<T746+xe4*4onXpr0t)#o$~qb9{BWhR1s1BVOGYq_Xtaa zOzg!QX;e164xG%sRO5+y$z`sx>0Tm85da=FopBnMSr-2$7Ww&AGlR7g-R<&47bbYZ z8G1+U+EH(FNPP4>-DvF<(j)1>1>Jh%7i&M?GhgGk^nLc*5k9lOKFG`O;~vCASU4x| ziEGD6ueUp*--YoS(F79>vqWA#ZEwnMXnGBBqL?|k)l)YP(lx+1z$i7=GAmN-RW$xd zUu^_d2d5CNRdpne-3hk3_NkjJk8Tj7gqHWTW|<6NEvDxLjJ?yvqi2)TU98d_X4_4# zyq^(HH|m2`QrM#9p}|KlZ%C-c{EG1kl*qIcu|*TwtJchqh(@#_F6=benydNcK`uI< zk_qqa-~sqm@=RzGm}6s(pv;s3Fh2WR2~T47`(5KAmfl>cmXiQ)!w9hKgArmI*?vSz zglLSh53p^AgQSEfY{(zxk}R_C0;=4~Pv5pIG5W>Q;-h<^J2%Y>6FPpfY26&<Vp9S7 zwT9R6W}4zv@MM2)o{yX9DgvTF^#MCoT!)-7UzY1(=04qO`{<hC|82c=?*R{Rbh_Ry zEH>qHuFsWRJEDCMKj5+h1-@~?ra%8mq&FXtU?7J>Zo+bBuD9|5L;tWIRj;)Cp(Bo3 zD8jGxou^G~*~=;C^pgddRAkQQ^n}&e&*6w$803G(bSdOrjrq$R;f%^XA<5Pil~pFN z%oJD2W-AswCi=yDAkW7jqOg_Nqs6dFeotaJaWbV34Ra3*Wzb>fgWyl&s>$<w=O40P z55RJ?&aK;yY@w0+*5j~C)}rnF#qNV6BMr!>>}<lh%YAZ~hz>+V6*SfP!oCh7wyG{& z92|v2M4uK!=UzG{cKdN-LB1J+_L3=huyq5hAO4xK&fiMfQ!PD^tK84&RV+PqnBWxY zt+>onFQf*53<tsCZAHx`%`9H)T*+|`j>{HS)K##|u2yz{UJ4+1Hy2S4^r{(UVc!%c zi`2Y2qQbugQLS(L&bEYqSDLCYN&L3;@w@VL6(v)6*TymMHe(}O_tfT(CN2arO1@>= zw&+^?YOYt^OY4TonJph?XT(p9fvn&CFz>{lH)MP-!&_7Me$1)3LlgPUs4)#HY{7J& z7MdDeZQuSn7{^E5nNwwpx_so{QK0KMS8l}(NNA8Gxgdc=ty91CBW~=tc1GX&UTzcf z!S`9~Dc$4G5Aw65$E+t6rz+Q`Z#nWDlI^>_nd<5Q-{38P;{r)72s7eY=Em%%q&Ki? z6umVTdL-*om8z%cqjHoqDaXbMggc^X)*J)4Fp`_<qyaB!3Q>3_W$Q5PrOI85oBctb zWgw2#m8*A*Wu6PkGcW5|d1|;`4R=jn;K7iLpv721wo|($2ZGkA5j2Xf4=XTPL%Y)e zq&_;|c%xLl)@gGOsX(0*`r#0*SEeL*Bo68y47`aIp=V;%bkVW}>nCR{<vnP2V*8Ne z;2FgdHf71*NutCVkQ9RQDYdW@<WxCXH3xmcP;EQST5MyT^KGaeN}4X|<6-gwMh^ni zWna0P7{2mctPSn$UQ{ZMP@4n6p`1Yg5<-|VdL$v~nG1>%p_f1u(L&lQ2_BBcCb#5+ zjN2@s!-?f3?*+`?Fi0F35X&eCU5NTIu3STJ43_If3+JoK{0e`5{d+Ejhnz}VlO@9_ z2jxkiq*Ys+pTAN>4ysT@>=i#v-YcxBfC6?v!IV^>!LRK{?xxn{U_t6uj~=IKUoCak z=%f2VW8&`(5dbRui<xWoThtOu9kFtE0<yJG7~?(tU%|KEJfS@z?a%Fq4JtO6@u}!R zj|SQV*JBsZN~P3iDBaOTVR}X8P(rribtHLIvops~*THxnY%s6pAWagRc7MVrxf>?! zd)UUa^4YCzx|!iCG(P}fK=#QI-fKm*Q@-&@r0G29(6gzewex>P9?G1nIP1L571@## zwb!23&TVahAHhj|n^4hv+Ot4veQZ<~5XwKsxzIww*yCq=n*4$V{e-PC<%6>}Y68hN zdqJIp!uC3lS-)NH-o2U#Q=X^gZ3abwnQ-<p@{8*&`6bDZ)E#2~e|@*Vy;qMJRi)E` zgA^HHxZNW^<>m0vmLmevh*r@1vTmoat5LjIC#_Q_?ecy9POk7v1?wG%y<rkQ%j>ZK z!8krw)t=13ql2|F8!gq{$z`t+>YUInf;2*HZ&tAS1?W{MW^Z-q{Krq?Cpd_7%vr;q zr4jrZ<jg^2TyBcJQ$QZmdU!6j;_}~9EZY<h0Pu%J^_)K7TnOZ;m<*soUgHA|@A7;m zFRuTILPDu6|M?!_RH%i(eZqJ%WiIQO8HMN19vJ;+h|g9UP1)lmDWwSUnFWKyy2tsd z9P!ytP+YM^unmGoY}_|&#w#l@umKDp;@fI7N76V)a5aL~*_y!D<<|@AWKP?Lt=P|H zYptD?af({FroHdmoU>oy%v7B~qQ(i2xtY9u0Ii|uB_CqDhtD4)LyK<(Ann0}Vmiz6 zf-nwK@+C1J+&9KszChK4GTB!w6&!A@$m@d9S&X(C{BH@i_?9I)a<!x4a)CPm;ZhSD z9P3x|Xo@J^ZCo^ML0BJO8lWer#{(ZEp{j3Ho=nI(#jYA<QV_|Q7~xagH0d^0w)Zrs zoFEV!gAPX!qZOwaMfKN|nh0mdB><!4AbuFJ;Yjq*m|+LP2_G9yJHg<wBT*TU8Nq>J z4BcH{fx{{kB&$`sl|*+@*0lW&iDg)%+HNT9l(P>{#X2?D+Y&l+5O^WaIo>me2p?|F zK{(=o-o}A7elYiVXfLJc;Qk}ixu_D8AR$zoPQ$eG0dhMl8HF|Obf|t+q+w6NQ=RYn zKdM#9CUK?r0{L}XlWri6T5;@k&fZiN4(R7Z9KF|{bD(YF^K`f5_`vDXn@O7wQjmEm z+@MaC2u0!m;}vgl7~$SBpW*Wv$D3WXG6Ykb>s%p$O!DJyF$1(Z)rf;b$xAD}Q`dd5 zz*_^qA<;>qK5^CO9YxoPF28EQfp_jPc4m5nzP&jDakdej3QOnk51PTh<-H60aiWZx z_CP^5Pm(;-zW^EpD3+X<wvj9Ee%<oM69i%(-%(ow<r#Vl-=UYd3GDhlNn!?-?)C=? zyKz|Yzfxv5TvxICa|Tb0cqmy5>0)j8S?=NC*C_i13<fm)%s$v_yeXuHFKy>bPRkJW zmRe3zM&FphmWvbLwL3%QYOEJZ1uKk}+8&Z4zX6h7a97O+3?Y-$A%pFMXOv{3kA9)9 zhrW-qA_9Km<E#Iw?DS7QtS>~iv-y_OQW}47TNvp|jS@ig6QoGDe@0N~q>^QHO-EhS zS5h44p8Cm?C4Cm<#p>M{2KVl@y)cBy=1pxQ7ZXchBZ7*G!l?oDb0CrdxpDTy6gvcW z%5NeI+MJ=tx;oX}j_gqp%Dew<moJhuVmP;OVC#)OyH`VP==gNSuEM4ltD6o(1acT$ z0+6?{f5$j^@wf}-&RkQICYjW*X?-i~jb2SQ?9;Ej=Y6jifBv&+G{aW6nI+-&J~MfR z0WN|bEA^^$H#{e5h9Rvevo`Sq8RQRA)Zt?Gm}v@q0kZ}`HE?$))1U#wAI9l3Sk9p7 zDIAlC^lDrLm4eBWH!XcwiT$9MU-zBjQ4z>a;or#2LN|;PJ11>ebuuuOXZT%uFCO@| zaB8YkM6GEqO$w3b9BmRqhoBb~R_VXP7vD_wLIG(vB}E<*X=i(3ts3uhfQr%W9WZqG zj(3{Ww;g1z_J5kEgSpALK;(&cNjNK@Up;u+BAk5=_jWXSZpk(4t0(h=-Q_<=_Y3?k z|8mXcFMTRt=<eJUQ>6d`@92_)gA=AW$+&Z+<NE9PyqlL}3@$p4v=Mg@#>)`7fmVKd z$PPPv&O){zEECDA{mnA0MuhXlzO+myf7D*va`x%jh6G7q^fKrD>fh8;hIoo_c*&cv z&WG%&?C>2a+LEns8`WfRW~(l!<gNhe_caBflyM8GXl$51bns*~&0=tvV4rpb1MZM0 z#B7ZC=5W8qTIoR{iZnTD3sX6V<rI*q%=Nw$03PT8;m^N7P9WB>7MJ<C8g-Q2_Up&D zhLdbW7kd5O79glf(fKY>{=SU=s@YzR)E6+oKzebrGUHg7E3lrXN8Bg>v!t4PgMYDn zriG@8ank3c$NtfVCEpDZoQDl7Fs3ao_v$kIVRQ{NRWFB!>~59)!(PwZpG>1J2~DZb z`HGFR)Y_H>%Eok1T;iYS)f(1#me70~%B-hyc%8Afg+Dt!QUugQ4o=TX0L`#!*Zwr@ z>{wjY$UE4etoNLr{U`}4xa(d}h^t{>*h*$h1!txbhG}F5KD3vnqw>tGGQ)p&h13rY zjD3~{*xs>WN;Z(ST9~z(et`Cf)Mxh{oxt$NRRx?3GnXe{!Y6sL)q3VIm_5`I_Ast1 zjRPaSu45S`1SRJnOct-({_wo-!OznOs`_K2tbYQ~*dJEk8`0MQe-A)N3sASZ7-?ot za=K;$yN1omD0~q!nox_gFBfz|*N%=uK9Yl-xoJP1Sj@smgZeJ>>ynn&MqLviPi>&b zssbaN*`ca~yJ#pZW>}$n1d~BCpB8?|Sw&(2;V|CwRJfuU1>eKKJA?ms-?Ge1L9>FX z%%<F=Gvk{0SoAzQ{@mW>QTW(pcLAuzpH=I!Q609klI!Ad5yb3q8cYbK5M8fVGfm<k zOi~piyjK7u=`G#Kkn=RI;!T5p+Wv~-++y}=OD=Rh7+4-LuCg$NKLoA76uWAaww_A+ zScZfQ&(SP2af%A!!+2kcYNItp5@}Jf&)nz-Lo0_ZeeH}_@|;6F^lB8{_J*}^D}AY; zm9CQf_V*vKl`h7|fyF_?8ZNiRf+3@HDs|)+Yt>$udbk>rCM0ko1wlqP1Vl{w=LDP_ zU+V}i?j>>Mp>TM8;4XG7pb_jRo<Yl<*2FPSmBEN?5rd)=DXUbgfg7nQwRQSKAeA{P z4cLUyy+{>|<#(}gl8P`D<svA|8w&gxGT2BnP4%cZ3q5Jic$PY*?9Zg3pm!UYDM`%p z?uro!VOKcHl^CoZahN!z>@t^j2sNx@KijZ?tVf=#_bsqdLmAenyxMwUGx&-W=6Z~f zlQWw^JTR;!6$#FJ`B3*+1ZtW&-Gae9!Kh=ZX%Ay)7B{*0s|sSl#1K|Y)|KC0wJTxH z2|=f7#(7npIPaCHw2>Pgwf#wTr77r(5`up$p@tifsGcT<*~}2<VMGF9WiZ3nhNbd( zC8da|-own2P1C{+AD(tsZ$pWiA=N8}ty8JV9afAa)f;hHq!g9U{$gQ+V3n58iuWwj z!I78T;OrdBGEbUl$O}xR+O2P%RDkZ@SV#SFy%f}3U6pptGuJT8qQDcwC<&iqP&K%q zP-lvE4m(MbNr+GiKM0NYS=~rcYi!6>rizdg$XW@Zx86fd+tjibXCG{Etlx}8^l#?0 zh~A~X>?zqVbVpO~fBVocJZiL)cBJVt62<DPKdILbcIM{>)_FISSl@};Bt@yuLB~Ac zB&~k0fruGneb;&J2)-|3^z4>XkDxpnN|yjm@2Fgh7H&?`aFoWXTS6Hw3TJsK2U?#; zGwEU6wPD?sa91b29QIwymPxgV2=<6^mxtpVq&oL;ob$NLo5tJ0_S2qE<RmRb*juEE zvdRk<F*Vs259(C3n@ri3FFNGJe~@!vB+a$}z}~KYz2(NX#;*S`99H#0&Bnv!6$|72 zDhb)~{BvzTB)=8fwAZ|}Nj*H8mfLglKI{O5w>W@EN8p*S&qj=7N6za*<Q7M=M5EJ- z_AM1R0*NYG)Irq`v#gDhRwLf0_iLagB>Bx&?kXCZrgpiv>{v+dcn&|e_|E6`=;n8M zx%x<oega6oXyudScv8NWL(BYE!$T_?na0<+i^M|?8;_QKAxD77r9eM9C>^IgqF%&w z5E@qW{e=CweVw}9KW=>oHaOvOIyo%sSOZm6`_P}aw}&-geQ!5O8)=tIU*4MA{wf+t zrN8nVuGluAg@_L;k~V(T913qd^snJV)*r|JMJRaN@7Pwf!mo@G=O%68bZF9KL@C6c zS9`PXHIb9nIODG-9i*wBmU}QhAI!-*%nSW5`cKzs#Ip>uD9DM8RR>gvpi_`w<o@Jl z9P`lNh-s2#ysQqDyG`2gH?&nH`$}r|gTtM{?{>7HURo>O<xgu)X(oY3DeXtOm$(8i zCu`cJq<EvsSlm(%ASULGNf;<~kTeL1s?x6a@RYN!QeST^Wm77bcf=y|zvg8?9<;lK zJ^5n=6{`ITm~=2UYy};m#yzcyf>h%!ZK@~b>>C1kZY!tiG(Lc$=RB;vFr>h0@-IED z{0VBpjooKLlr6Yo$g9r=w)OSjXmlc?SX(4%5>vuXD>CL2zj)fO_FlzVl5;3u**8_? z4nzQ0OFvJB2G%HIHo@cFa?&)@IvwnFjXN{U-I+J~56D!0k@+yerTu66epzO8h?!|^ zaCrUgst&<oE(v3&nEKrqVZ8<G>=)>YjDdXjS@l@#lox~?W{t$TuB*rJDen}JTKPu$ zG*yMxp1=pKV^k@Z6Hc~}w{~@H^wN!!6fTz>m$}hp{jxo|-aGA&wPp+RRkSVizX_}T z==mHQ9rlm{9jubWv}1(X9vBCQ5A`V;oNDWgMnga6>g)Abm{N7$*Oy9bJq~bg6+LRF zy<v0r!0%+*?N-(Gy{7vpA1uG$)=P(SILV?oze^I6W);}2H<^iF2JKGRd0p8Zm(GAO zLCR6^jg3rvB9H%VgP<2IAEUEQzOuqDgH&0|F!E2?zK7ca`&?Bn7(b^y^VsgUsOxpq zNbz2+Mv$RPDKDw%PUJq<+=c~Z%Mvd?ytRPDTCnskzMW=I$rla%H=v_NyDrnCtN-9< zxXNv*M``x*iFPEEW%{ITpP--V7ZD3+9B%Gspq~;IswNGV^3PK|X4mdajWGS6lfF?( zZKA0l^^Dsg!=lSUs66Ago#>_VLzt06Z8>ouBh}j2E!2omFh#R%S>m>l+t!O9`JVX1 zAY|s_b4FiG7MF&fDC;4a`Z>(FcJh|<4fxv7`#Oq#Fo>+Ll*VUCj0v`F{9ji28IuDA zjv!Sjs7(>_fe9Nt>0M-8l$L!%88qLLVez$VBi^-Vf4H<F@zQISkg{>16ZKY>{Xjm$ z{IS@jb1hcYBmZWF&Fry00+cZ5$e}^zGbsIp#u!8Hw7=P~W}Ebh9x#ugaYZ?;!W3p& zF+vsX{O<s(+I;Sf*()0uDX}L0cYnAP0YFYxIhmdgZnH;IAu3R-DUF{MPA2u8tV#sn z8h&*xD)D=(m(a@l)G@I03Rwc>P=mN-;Bo^h#MOB`yyj_QR~lo~KSP@(QpeM(7@gNf ze%o$H;Z1Z+sD}pL8l5hmn0RB27@1RU3;=!%>%NsPP)-&)9z#3`2s^NJr4zKjnB0z> zH(fNQ_IwcH`)&P?qQf?7S^{@ie1&H*WN7=4zP<Rn_gI{lk9_JzqF1Jk<Iml7y8Krl z^a4Xq3~KSZ{=;$XrJ#h@TP-HyBZu%n@a#5*c0Kv-z9RWgp1~Gnqt&4C>3@z3!Prvn z(LNnQmGT~XTee|XS9g6#m^&@)JY1uta3Fj&i!iV}cgdPJ%4g(@{jh$i!J+Tx?w%yb zmChQUyh7AC<B6F69~@AkKhhMB6HME?kAiA;F)!o{m!JDX{gVPL@XcAVW<K>z$KR*2 z{UVF+KfGWCpveGW(l&6?Q<IiHj4>Fwon%3kIJwL&JKy|kR!ij)74=r*(!Hf6?l))P zbXcEp<N1e%6eNmIZ!RruK-of=diVJLaFg{Z2EC!1#!`2Wps;_exQ$P}Ng=ZB@j3UU z>}*@*1{@Ozu&|?ru31t`Y4O4%?<a0_tMKVTm*lzNsTUD<v`xFYW?KkSzxN1D06Cec ztN-WRw-->P)HO5T<Hgt2Vw_=OP?DoknxezywR@f+hwp#=VE;k?cDE(yxWh%;Fnglx z|8o6Jdatw^pa=fj=UxzgBjg4nEvs2609OFSgbYgCF~A~I5N}mP%n!7@B&HMElGOB! zOz!i|at+&fu9B<l(%{}(5Mp;_6g;Q<u^`l;+$i?_TvlP3!HM$CN;mJ*Gmf>^`AQyr zMd5BYoT^Py|EC#9Or+F?&X;-YFAfE>F>$8ej`)#VCp)h(RXPGxyH2mXb>H2@D>;F@ zN9XTdx$Sxa`%*gi#g&+VqTR=mp8cgdw$<<3;GF5wxV2=^pe&|5Z)=EKOunID{0XP( zS{s_-S@~mjB(w?K=ySN-aPGL!GlL(Zq~oWS9xxDM<}Sy-q>%w)%l`z9udh7ym^@dS zdpCZg$PJ;bXzSJjuxMAzEB~e>XEw^J4bN}kBffvRe(|3a&I?FhOSzcw;K)0}v%i1w zIS;0^AOQd&O|c$?VTB*chDP{n_w3lmI}QK6ke`A1s?k4fG1(GMyAH(ZZI6gx!H7}p z#dFFP8Bl+rfw=KL`|1;t`|UR><4p=@ngrb16$m?+W{#O$B%cz1H=@qkblo{fN5ni1 zrwKp3minbcqgMkZ6EEJ;`e@nYW`ht3+{3(|IHeP7U$>}kS)?iWO5u*KERVm^oc*~% zZNAIybtS;|?6ap9iLW%}!_cSZW~}jVE?>)tF;=NKLzr*E+;weIp!@mr0Cxb-m*2<j zYd61FImUr3s?QTtG4n?az-@#xQT6lMXQw7SUYsxxZkA!AO4o7mNib0@BM4FfI0u#T zd|5(OP005%{~GPn<$fO7kmjC$>UFH9!E?z7LSUn8W~$<gH;H8RK_GqkDAMm%Om7fV zT_EM;!qE088~ajw-zCi44BYch_%8TuM2QO}yzzC0+%4B?G^CL#ckEJ4lDg$#fnS6~ zZLCDo8ATs!pTbe~Q$^1OOorV&kV9)CE>;tlLMpkiG){*7%VbYy)HNk{x||QhuKFrC z^Js(WfR)KvOsZr=(E|DRX3j#yINIgzKzO0^8j)s$ABmomDuV1ZRU1CbI~H9ABvs*0 zJU?vxxK~H_Bvt?Jo*|H=5nA^2E0Vv;HC<pPJ|N@Q^Kq;rmxxsIiuhW$3@GK9+2x$j z=&w$JELfR5jg1i7)q0fdQVk7EXk4GyoRxYNjEPVH&UYO({_LXt(hM-&8n5FR_Pbp= zdr99ojF<9u-}#%UkFc`)^LI{Lo46C&?_urt+i$2w?u=agUYQ{rGhPXdAKD*FyD*cJ zFz|htb$=3XydnH!F*9rq5Er7GqAc*uM2~$f_pBf&a9q+@28`cpov3rd&k^NL6U6BO z^LFBJ9+Ga<92RCNa4M!PO#?H_o1TDVhW+Ob&rgurhWRr<=;Iddb?EbSR0jVq@K_34 zg_njqFCach-ibx`;I(Bo(GQKZMADFoBXYd$KCgJkP^K#DLRXvv(D-jWg$J!^!f{Z@ zexSxB``R4BCJjhh7*nov1a!&<$q_<%7l*VZ?j+H?QXd-Kou0to9ADmtiUZ;LYa$@@ zK5WV=K*4z6q<7o0AEZg=L1v>sMpU`Nm4Sdf1&RXySAREXHzNO`Kj*ZPkfriLqoIll zm!lL=z35)w?6qDmnCs5wjPKd}Ti?O)n?1J~8?t%ja*(A=oz0V`FmYug(yPSd@}wQ~ zt-o3Y4!nTUu*IX8n(dPPa=`_&SmH_Eac_fu_VbP5N#ungbFS~nE3-xt?y^(~{+UYu zR-%y;R8th1%8>VE+&^Yjhke`sA?sD*O;n1-RlyKvw7?EpeWU$ilNk*pS#6qn@Vtn9 zb2Z;Sp2vljCIMO=DPd-j(tKAj0^MQso<zsuK?_SzZbj^}&`i13hRoY>Dr0}z2$N7+ z6h50>YZ2pNZeLX+v1QCuAmCe(qP6)xGHR)Fc)>(CDVI{rKK!8U`7$zH#;pu#!kw+{ z3CXQPw7YCecRU$C!^Xf-bc{fOvn#1JH3>IHwx2cb=2ey{b7z~C&?<0#;q5fAwHby0 zgu@3x-%XH2t8t?UE3W878^R3yaiG;;ou0ooLZ%M$R(d=)6E%hRodp%eu7@_(nH~=d zzeIo@UYF{$du^iap@_2`ZGU9yt3F-$06@u$$+WA^*{_LuX|&=Qbe0->toN&mVNbV& zkn+Olv0Q3Xs;!y8OR*ujw-??O1{O{;mo%eFFv7>H1L;=Xp93`?juaP*AV6>sS4 z7e*h&t%-dzoS@}eb^F|Lw|6B1_tn;=KWbZ>%spEEi}df|Pqx0l;8Jm`I8B<D*V;g# zqhdG2IeB&-yc-BH7*KM@6Fu3g_7ra+#0}#QJMNW@IvUG9T;jpZ{=BTX(MA2!13UEs zR711%75yvFkES)ElO0Rvu+}nZ6T0_Z`G&}cnSy5ix32lvwa>$=#HVJj`~2ZOskv`8 zx+@-eRKI35)?FuBDWa9~K0lZGbWMg!w^I3^?=>{S9}r$9{ifj<khzB~|Fdl%x+m~w zcLmKJe*BF5@9uPls-Yy}B|=k9B76g<4xFvIa$lFQ@ot|#^g{L&{0#kT9^ajyiH?7{ zDJy6|*v`L)mva>8bBVfqo;W#7gHorg9o7hKPS;4IV(&_v52E4{pd<^x2a@f{om+Uv zur}7%;&i7!k=of=C(i}w`1M=N4EiV3EHN(i-H|d0KUkJD&f(r@n8-i>+a^EmXzCUw zYsg0-%u3YrzbET6-}uA>t6t04yj9HB+vnW(%sGGBfgS-!$9v#y4t{<nL5+z1V@&;| zxzxyC(a74{X7T@|zv93ubc<K9?~gi2FPSg>vN+&U0?er7xOaCf<_TutF$Ws~9#~KM zzY6&;dA6G5hXp#)9V~rr;FYg;A4m}dV;hP4TLYj44eTm#?=WloKsjwtqraP`Uxk0x z6A4U%zB&dy6}gs_9yO_r%xohRn5Jdj0q<mcu%XVet^Wn4)J~ikl_IRs?oI!0y?R>T z1c-u;k(<dqPhVHcd|OVYw&XRpIG8n~zXk!~%TF)h{qVhqg3P39va2cy&(~Z%CZuZE z=LZ9o-Uh(F<5j=Egk=7R{lr#c4ReBD*~)CtGtD<g`NLFcuU>mSiKd)EBc<0tFyf#P z*!iqZB2Vw<##!PIc+Y|gaN$rnn6v|4PJPReqCMPOXJdzhK3#bHYwS`^nYB<ISyBZL z3@C{{fATkDBrvaKE2`!{Nz0EK6!QM#0PmFAKcs0RDyI{zMQDb?mY}`Q@kXz{;39Ao zfgSwviqtYlMtb_Hc{M8KaXR;sXIyw2!3wW5BxdN0r&h0ze}aXliR^?n*-qn=hUBIr zjxDeJP#T7|a}GTwTW(Rox;UUt_3XC@L@)Kv*zE@@;KYuV)MW-pop0;TL#)=yZy&g8 z*|fe1*>Kvwq%6R>ZFwS)@oOrE$RaexoKkMkMhU@4CZKQ?En!8fObV1Ylmz63VXzc% z++YT--bmjbPq4?go+4NU#|*4&Ma8y{H}by?abw=Vr-0rJWGKvm4a}a3sLNk1U48qO zt8tC@S5B;@Z;YtmFlgVs>XB@X*JIAl4lBX}L;CsDdv_PYoxum_FIyRHADMQ2Z$~jc z^5P}_C|!mqx8A^hTS8t@N)aleJ|pY2jy1N^brljoAo6zPcfksgck+)v2K#S@05YqH z3ncu7(+Tj0f10EBw<p#`t-MqYj>TnM9eEs;^}Xw|oP#T&t{vu7U>UlMDgKO)60}Ff z9YO1kdh<wpu1%0G0BqEO<!EX{Ao4ZCYTfykctb3lj4BFMiiqeJ-Exk@i|JR(Px{*# zuJd~7+U3-~-*F*o>#FBd!7Vz3jgNLa7NiK*Ye^$S@ppK_H-y;+LN#ue$@v>vFyxNR z_YCm~#hdN(;sGD>Ne!s_P={ULtWnBZlSzYiufjiR0_ca970w^U+!+A}OJfwS5*+cq z%JLm#skVUQQ`<PI3J|5;<A}fZ3MWuC$RE9ib7p7@hF~gO0_|&Uf(vzyaDRNWm4mJS zoWA`d#??q7xcrqi;7R{Syab&ELblK*F|McQ@TmPJd=ZY&$V`|EkXZork`6Qoh(qoH zQ|_NFHe<g@Qtk}bn`J%wyGRO$cN`XkJzH$UH_&r8L9zm!+TzR?QPE?I!cboT3C0Qi zYZB^VsKE==!l<Kt@iJqlk9@I7$F1<+q4EC&rDuPol&$9yYJ7M{uT&Hqe)r5qp-6YX zb>on63$>FgEz4$d^Z;2LR5FnNPtcK;A<3iwrBwuBdl@G=B+9}|{Na~fUP;A3WnH(_ zb5FJTG91^Jk^h7n99Lp!Ka4f%Fax)+u4JtLN+hmEUaK1QuLB!VXn7{x#w!g~YwIxc z!^ErwzvF}#(1Hjr=V1c99p{v0T?yk+(v<M!txdG>iU4mhLZS*}PQs%+@Ess2_y;cf z^w&F26-=1u$ICDbSj;v6!?Gv2r(;b5M3JiYd>I|mszBK{+oc5ihJc_dH+)q9|02oq z*seo%t<1Oh#e;FS3?1ShC%01Lqz;xi;ez$C5R+o=NDp5Yu+xBl+uF~bmW@<<C`}MX zrCVT`oRkE&Zp)KxI48$yd6!Mq)7^G^56yU2M0u_Mhz9<dGO$~0F&89&!n%OE33PDU zz~T=T_L*=2!V|(UAP3gpCCg$sdnR9f`9khQto<r!BTSR<{((q}BGxwmYrBiHjn;l* z;FrIyZ&B-K70i1kOeRT%k|`2=2+EzqJJzaNea2e7jP_2v{bS*wl)J(j&K0jT2qO%O zOV)@&NYYy!9v@opsS|?gYlf9^XdNfQ*r3qa0IYz{AxBNoW^F^nr2y~ZkiWrB)q%>t z1fs6j#c&6a;AJ9~0HF;=yT-<BR%hK|;-OEX4aV`?RVMp#Oe;BNE(Sx$b~Q(&x3EUS zPk(oJ<R?TGi};X5ct<(lWg&Asc5Ya+Pqf`|F6skEM>{sQe#FzWBtAb_^qDnOHvUv0 z4p701_6NM4s*&j*l3KWlzn~8wMIjnYHSm=LNR`{s7x)9&v*)mB%~{1MclnKB3B@7L zTkCi@Ud*pr#LzN`AH*lH8cM7yPkrGs1`0QHHu>GH+D{G>1WRH<Oy)bzbq4E2Y67dz z@v=D3&%6=t9lX{5^aS_`rPw_ICf}G2kb|EQ7=A0j{JY>4Z^ytSX#g#_my*N5s$dU@ zzfLEUIaE{)ri&?fOZwq4v=xj`HP##yun(rEG^fX#88Y-@jdCDC+jo@)#`u$}>8}rx z|ECqluB3~tNo$R2c;XPDxbwpP@VMnuFMe)-Nyt}ms;SR3F9J~JZ9Eb~pwCM8$9^VU z$_#MBw=DB*uHh!>!W&d!=Uutqpxpgx{I`HyNL8+2P3}A~_hVAt=N`G3RsK}f?<NG% zJFII0tD<u?>to;X@T-?jT3Y@fhpB$b+6~MUI!Y;NmTCz=`^0?-UdB;LP+=U1c0l<9 zuQuz6i!T)4pFF+^6WhwUC<P7^43sXemTZLhi0o_y_8cx}rHmbX7(1C*6vjCq==2IU zVnwv>ZfPz<G}~A#I>639AZTBnnX>v3+mPv4c2%_O*HsxxxfHX^p<4c}3Rd9@u78C7 zn}sPo`^M0ypqCpF?W8*HED0*9)O!b6G%SSBAw++0kvE=dC~q6eaFhoES8@ru1S%cb zgVV~N+85rD!b?QWuL>tj;(1qWp}is|_;!smwYzm9hRT5yJZ2G6F?6&JQYCLy?PEo* zl@G5AkYw2e)E@qk@BSN&SFMNe5&Wt#lpzsYMh-ZQx3J_|?(fE{l!PP_^cCmSGlchR zZJyR=**+9GNRrE$7bm5d$bUROhsH%8u%rvJ{+A@!1o5xC5yR`N2uSwe;iK4X3dVf} z6F60kEd2J3V79;cs=<nkRe4G`na%GIj6K=ch%XH?eZKBTRxl%D%;#J5bkyEIw7?(p zB1Pfnyb3=noqs<cE$ja!&R=L_oiP|dbU;His;)~hs~sN8B#nxWR!jG^b*Kj(z8@ii zY>IummG2zntA1Hg^7dCkjc<DSdP12aF9_9Fh0id?*asZ`NQrC5p;A^vLqA1^pR->k zkE`qwigfPX4UuMt`-yqr|J=C%8GMo*D0Sx>Zs0!!4Z0Oi5e|cp?ZN}&)qZ>3cq@^9 z0}3`e4V3}->NBwYK@}Sm&27q1!SL<>QtCyNhNZyF<9JakACDtgo*Or?9gur}P3<<x zvPBOi_ZI@F2SJVJ?-<uwk{8R5n@hVEWXZIwJjD#dd^+$y^APWMTPBQw<!AWjJ)8#M zq`4}#10-%lp0C~<{Xh2JtF5UhVAR~Hq>!*dK)RuW2!>un4IQKy6e$84iU@)jiU<mt zP(u$LDN2(n7z6|qF?3YW03xV}6a|!Gup$;F-}$~XbLKhc;yiOP7xT;y$j#1Pd+oi} zyWUs3LY`uho)SMGeO%Vt#QpMbmF=p`DEi$?Zn6=NzaE<xJz0*?Z6CS*$8oJrW#v7k z87W7z?)nw%^*q{+fS0-7E9A%KlYzSKspzUJ?B3%I-FhXvj{uN&bEM^DKAG(KCVN;q zP40$Y__EY~{<=m1xiqUh4Lh;sS$;)V>&cZ^CUdWn)@Kn$^T|ink>fc&Q!T~D(c|Tg z=0UyDR^~ZhU@x^5r7zzK$9wbnQ;-pan@3ICU^MQZh=zj<v3l9wC-ag!H)?CU=Os&! zvLO!@Y5H=Jvc>K30VjH^^xsD+dJDRCl{HSnv_FfwddQL?GYzF4qU~>gEzwmVtZyE2 z=74|Z+dRnyzNKR9%5PS1PqeN|AV*f(bX8+sS~2$VOSy%|goU^Ik+yeZ7A}-0!d}S| zWZp#4MOzb!G!M<YEtQ^ee81QwTZn%@^!|#7>D-=*SrO=%v>f&|0V}#JkxQ5K+l)T) zDc|wb32B@C+G5JN1gumAW`+P@dgeQaoxc(UX39P)dKYk^XD`c~;CGcVjlOn#;o)-U zCvD9n8I`s&$Y8yRc#&B5cCsYzCA+RkYL~$L!&${+aq5Y`A_KQJcGM05uF)8ESNRkg z`roO@>ws5N71ssv6=k>~fLK+GeJk>a6aSsSOm)j`l70!1-2A;J6nlHmBUNO>Eh{fk z%Qjgf`p5%AQR72$9d05U-fwaK!V;>YoW27Rb;2_HMSE|3wQrS+fc@&uyz6oZC^C>c z*B+tPYc`tuIr7xcIGBsVU(flxM<QC=*LS?!?;n(d_Fj{e4{h1LR(V*_RETy{sT$(* z<h0`W+uwT>5098$lsox%{#`}Ktjg{AKW^TVx66~CYybOo^9&?bxDJ40C5#!w^4<h~ zNh99*sfzw&VYQQ849&{HbSdr2@>>`Q^T3JQh(b}e!jU}Hqt*L%I>&E~q$wSE-Ic6e z^Q_eP%Jv_$PA#Y0JXPXgica15ExTf)7>w?xqY)6Kl7h`$#V2uYXutLC@zs|Fu1Bw` z2k2G5W+B^cVzBy6Go9h9uOFuB-<f?F{d@aw>TV_1=Aem}=EFj2uVYgLc1c|kTVEKU zskwKj8MZ8qmK?b9kKd?uC8@dT$kI7-h-qQMgph;!s}R#Oa368W^aJf1Z@aGi{)aQ} zpuVjYE0*~){r*+oUGY0ofhAsF=U+6qKgu}x;K%yRgQq8IG-zF~5w^$8Z<KuRJO6S9 z3A(Y4n?}yAzIl{+_|d<=e}3<rvEZm8O{~CZrXl>DiMyi^P3eoSc}$+k{4Xo71kqCr zuSAL9;Wq}js1A-^O`7R~3Ys3qQA50q#pvwOL<+<#+DAG7Dnf9%B%_UCpUgx5P`*sb zu_@4anKg9E78%ut&w@Wbe$-@9`h6AC`Bd_m{FA|t6|a3FPx=BUB5eG4EzD%UqH_@) zVC1eQ^x2Z#NcjI{q!r{5wL*w<kpDd+Z6?9&e>Bn_TS&|&`aCJIX;Cua*ZU76ZA;Db zo1{35^pV!uu}WA7rk^?wMdJ7Kogy7+tDj7l)wtU6<l-`;iPEzdZF}$bs}}#b6ziw= z&Od7e(>qJwd{OHW3jZ2Wr4Vw?R8aIAM#ip#<rG^Aw@i;(t)3rB&^5Wy)dD~Dq)_t9 zWJhJl((^Ji*k9)N#+8YHsqFU%T-)kYW<X@On5pX8n~tzO@5!u?07lozjB$IZm9_Xg zdNPj+yE?uuE7+htG@7-)txoTO&8xF$7a2OnuXmiMjUPni&%-)Yh7X?o{q;Z$0{mh= zhuQLfbi9N>?oSxlLa59+9<o+QAQcN%@tdrwt7KgR@G9lj$*Shb9`bqm^Nx`ZL7Ltr z1oLt1bQROoHu4tPRJeq{s)8hL_hBj#y1AR=j2^FD%y5BdGIb&R`dM-G0G&#+VvFI$ zY^16o2Pu}Ozbp5c7J3}@Q_<-r=>eRZ=LtJFcFT%5b5^_%=9v#ToEYCa#cOQ_d?*RO z`pw<^(#yK#8_^o^1<`!yc~Fdi-kdx`6x)my4=ahho)cra_hXgl<HyWfxqkH@kIH*E zJ1LyGyqBYC{Mfr6ql5%~08z^Qj}5HBoxQ8KTfZoLA}b@Qfk5Yt!UoeD|55}CZ*)^$ zkphu(=Nd=!R@YiMmVulmilaN&oR3x;uN;q9U2mUDR0}@x`lQoF9<;R3gkqJky77QJ zsCK7g`A05L^>wM?bN3&fk@gY5w~xz)_uadF)KS`l+sm)N#_j7jL~Qm8y98|xh@HLt zUq)I&(!MXl3I#ztNVn$pmnZw$*S<U@YFC+!=u8ED9W_|K{q>pg&;M?uHQ#;y+nBX- z<F|1;{q=7XWGnUWFP#3%Nc;Vz$EEe}Q<S9tZlv|EY5bpzw2{k=KmWUtmQQ1AF8+Vd zNV`&1@c(%uZR-t#3hRM-dS!}hmxT64vw%iumbm8(pBRjq>4%D!cC%Z2zU0NTuL9PH z5FeA*<%34E{MO%4Y~7`K=EdpFOwG!qgVV!ShDud3B2Ih~=-A-_v<+i~Id~8gYaPws zpDFf&xlWP2j)^cMq$>;?y`<yAfl&W?6iwM!5O5Us#o<ECfN3_L9>qLAwU!}RO+c9$ z%K<eg(!SuaLRWscC^wEzT79J~i;yh|AtsTYnJ`1rDlhyNi&uygN&tktuYM%+Av_Ji zvq4p!coROuVG})5L>b1Dx_o$h(>6ZZ+vpC_V&5svom3ZpA-OxQ1Ef<Ssn<mNMIhvX z!@oH3O0Fh^^K*T_`=jj9qH*$wj^X`ff=Ajc<bV%R3E}W;o`tApS1CBIBBPpxIl(Bw zh~rf)9aG5sRX2zE@qgzanQBM4;!6sQbh&JSINxss2UJfnd^{Cstq%0J9^OZiWje)% z7b4dgnuyrR*p0A;_nS4YB1V{FYrC%V^_U%mQP8#}+2PNr4BbQ5v*4(BJj69|YM6kE zeF1IM(~Q>-3t*TUSLC2yReSUG77WVhSs^r))b4Kc_G|z+JjBvb{1`sOE`+efu>xvk z!3(@-a_p#tA}C2So)%KFL&cE_3E;jRj-ISV$GZ7t7U;}^n&jQ`@ZhO=&qd1vPwj>c zYsG15v5PsI<RzmnStgZ}N7&&sn97j#hAZNC-|Vp1n;eDpSkV!!W7QM)%VHcoD)P`c zw({(O)AX(>LKCTWFS#63zqd-X4ICx}H&13E3#i2+!^T`lCZIDdyY8Q4BrFab$5*w8 z$e=tMy)pt6-q*tDPbd9C-qC9-MBsE)o7aKIL>siaD-0}%2(9D!7~fk;BGxMWcFemG zu|sGtgc6utD89$_{6ZJQ7!J+6MEohg5X~~!mkjE1WMPP8-qt70t*&%Iq|W0EK)Wq; zjA^J`$sAE;8<8n8;yaIb)2m6-QQ6_Gi!I;FLQM^bFKUx}2Ty2f+v=E<{y1NG{T=p` z*{mbJP)9=QkchSMj3Dj2#|7};#hdz~A0HlEkp(=Pj>KDi%!ufRU3nAz_4N;8mZgA& z6l1M+)3kh+9*M+Wn6@IudRd;hi95Z!Rn?@7g6Jm60j{V%Vu~Q+q|V?j+7I1Vb9DT< z2iq4cUrroxyMCH(9IhQnv{tS9tNZYiNY)Cox&%hfP%uk8Oya~66z1P1CYwHtL$RfQ zI5|7NfbNFUO(l@MNR#;D8Ol?6eNgpTsBu(pT-^`ST?)8Q9-dV=VxTmyxFWg7R}5M{ zaKlbhipDor9=L;J%Y&L}uC5hTDE*VPPJof9b2m4q{41$RmT5tglH;oI84qXSV;Wl* zMI?sB;Mv%h<H^-f9Cc*q2QDmky!X2JP~7$CPl;W0+yzP~`)X9u5tPENCQkfbyD{Yx zOgT-II!eaw->m=9m`hW3Ru+4N5bj5y67D-w;2b5*DZIDdPs2iWB+bWYbYa8Ib|c%4 z7Nq??`~II#unC0LMrDraW?K92jKTAuk`z>vS#tyHF-Hg3b7=KQ)9J5ysdR?1@PVd~ zh25tY?dKONcx>&;@kcEegk!A2R2cjyq2HoGVJ6uEQ*0Q31+K(?)A?uoS#rOs-mdpI z>L~*|+@lO!SKFfGXX?*Hj%;A8f0?XnQvSX_Mi?*cry{vb1SLdeUhx3+7p58ifs9`) z!}A21&v^rrX8=3{KKS9-!gVKp^Mwgt^BRW|S>O`r1#Q06nvI71h?<oX?<Ux0i704> zd!ThJUd@4iY+o)lx-C1RO-a3;cI-tnYLtR8vy2`&ex&IK9>R6xZ^m-C_ysVaMeFMG z-Xrm3o&ykF#5}J7m*We!Um@V>XF(hVoTOQ=vjd73!smtTW_JU*9R7nVanF5@>=ol( z89szp2rLBIPR6g5UCr-{D4<?O&N~O84u;3$KM({eK7hH^hT|sKmSq>s9Z|-!u!~DP zH(8Cq3@ccf2}j8a$oLyt>Y;piwLGdo@GXokD*5qO-*;^MIwuy{1BknVMrRFwP9l*e zm|Ch|ZHKYg4_UYul%H!jo)rKWOn}g09&8zp$A`hjpvrRz5KeNI*=0p%w4XlsqabZ; z!r%6#94ZTKpKl0N1c#KsG4RrB*MlFHQ%<QQUXk<pIv!aHV$TpjqdeOp_K}aMgA4Ka zj}-bH(}XY3%%Sk~->wH2oCK1@03`sDD`ZznU~;v5D!||Z8rg&b=d(FjEgY#10((@! z1-5^f7N&-To}lpOGNoqt_V>}f-@Agn?OD&hT-|GC|9XeTgbHT6R3#no&d#Rb{!y`N zQ9gFl>OzJfbO2*xlau`=@o$#a2hK&fm&>0BOeO{Qk|5AULifDL-h}2LWwF}Vb+}Xy zNf#3p5~xCkcd>EqTbiH9_zzRo22^moL$;EONhIR^=V1TX*lbSj7w^<2DlVc70ij%z zR@T8n1rDj2h|FDuFmc;l+=#1|>F|Zj{(^TbB!YmTf6V)LETf);ZF2$ZNrmz`1^jd@ z2hQBxnh%vNzTZ-iIEO0}FRFZ8w9xA_sIcc82n;YW-h)~Inty_fduk|+@+uasO5j9k zIdLEe**K%S1*rf&m<-IS7I}Uw=I&%i)YYLzK%lV9TgB(d%`$#A2*@abPu##sUJy=J z0M%h)0pi7x+RqsPgoIG0@-H*<g<^f~uu%6umcBF0t$MXzQ4f0^<m;jE4Un-nD46>y zT5BH(Puy;P7Y7n4wiBEZS>Z&@${Y+^0d*g>#46^;+z{B_Uq|%KDJxQg2^b-6ju_sA zJL1@7{58uNf~`P~4LCzSVxFS4>qjPpn^pnk-J4ZhdKpiR!2hI-L=b2vpc@G{J_}Jo zh~OwWMOD6-bP|+#d85$gmau{VPV~BJi(Lr`0i^>_34y5Eg1)S>IiM23Meu^6Z@@yq zfN+%Kl?e6;nVli6gAz9p5dQQ{H^Kfq2pifn4Om`AZBr76EqH$g{1+<HX-*bGgv03Z z!dp@{$;H=B0)YUJJIDT`;1n@9Uom0|D@g3M7U`3h>~<xDd~@PD>0c7q^jPbvLZGZT zV7(=!cJV?z_pJ84W9sMd{)D0;GN1zp1kNF&SSXAbF^_=trd94ejvG-0IUM^hhG2+< z$*%w~*ZH=_*E9j9B2NarMk(tUi>#z#Ys!wj#2m{c;<f>viy1FR1~>pNwG54OJ-lc8 zMkXb-?-Sv=s)-T{@D$V8E{j?cyxd5{BvDZXRJ7J$%pEH09}9Jwg^L1<wz;-eJLvsQ zPP}XEJ`CrBH76>z`2IxHA?c-J-{KoiYP;&g-FsU(Mwr_i43mn!Nanjk!fGV?)DX~~ zZm5JZ^qaZTHSh-IlLp)dyiU?yQ#svTi2t`u`n)?0HdgnEa%V3r1Sfh05puh;`3TP> zs9b#a4&f>s%Nw-lOxDQ+4la|8{a2QK=C?*onYW@Y%A0u)YT_niX2oWPa-&R~k^xWa zq<26)sn7E$70I)Che}AO4Pfe-cbQbw@Az2QSY!nU-T4Nc%EkO6;!>%u@Wmq%y%?i` zu)Xs3V^-&3WA{<<7xmo0h*d2v(ISmWcNXWHCgPX4_pW<2R_uUe<pXWaqz;M=*kg{) zB%^{^s9a(bBqvv*PHUBTXKk)pP#D4|7-JZRp9KWY&b7k0a54ydA!XM#AJbBLz@%dB z+#1J3?X+H^b4eF)Vx11J41Nj&q1Zd?a}RaD;_1o&bRHWmDIq<DX{Dl=oL<KRtX(1Z zKy9gRfQRxFiAxba{Jd&4dHEUU`oR{w%>npp$%3-xV-pe`1>E-Kr=XY=v6uvY&+nTq ze*_amexY4|=C1t-$ZOgSq(}CjvA{HPFsklt?X<Q}*R|yIK}oxT>GF8^W-J8gHCP;g zfdH9?^KTsp=)sDG9^Ll8(#Y;TexL)m(jvPfj~!(;P}iiS_ksETL&lX*q$b|RUDSRJ z_0!AlhqBMcMbt$Q8&u$vx$i*eQ)p;MibZ9V!amTn@V3`j<oH}?2~$jZcboc5uifq8 z8V{ox5una_$P9+BIKhSs;;-6?K2!otKp>v;6g`P);Pk3KxZ7>475L{Vx91V*xIh{e zv`iC~oCzdSk6K1x{G!n<lGs`zrh=9>Gh>7T9~b=UF>ARFAtGR7h!=CCEmG%;%Cd;N z?JCHF`%3OMlQH(j&+A}iz!9*zbwoD|zfu-^=m0p!cpfW=2%EzcurYp?n04I;H@OVl zI;X*B0BSO(Z)QKV4VVy-r8~Z@{&dt&GP?FMdVKS~-yih4$K9IR@x}>2FdYy4)n2Cd zE~j`vn2#xftQ(R*E$0Z|Lkv0wT}x!WvU_pk_;Z*E!fj;CqQ%aV1ifPnlHZC{QU&N` zXagz0=_00z@F0nbJ$>%UsZk>|B@aSD+AfV7<}mt@PXk9qXbkXv*VAr9-<5QuPvIWw z0L1kNAc&L8wbNOC?G$P!dch8CqF!ia^~Mw1y3eFo{+bTcdd9zK#pOD|${$U0DA%R? zk@S(+5cKh3Oho!HqTzLY<s-sNM(nz_!ak(^sA%QzbIv|6b@Zvqk2h>j<x-p`-q2~k z!9&w9ctqYz@J<$*XM=BHVXhTVP8+|y*!vpn8yA!Y{No>)ExyeYO%KvU6)j^N1E<Ds zPp$klgiYUky9t0?c!lCq^9h^}fe#h}>mv)yk?;En;>Z-V(UrFCQH<N0$-jRMKxHsi z4(#c=Gw@bBSLxjr`K@P2Wjq`C*#diqGQ8Ke!%Chm=^%DA5l{%qGy14=pA7O3it_Ot zQ!{Sci|x^MFj}|L-KH?1n&`{Uq8;|wRpSSDIGE{zaVr_4+@WB-7@Z{w{vT%%nx*Vt z?i?`lrgaW|t$N-q!|*8UzWl6q>B>~l7?R1tm|Y#!nq8`21dg}V3lJbMlW9K)x)Qf& zw-eA9^lZ6c*RsVT0yaNDalCYc{ftt*l6KXoXP-*$5nV!}z&vHn$`Se4YpRAocfIkk zI0s^NrY0jpXOsI$myR9>-D-$!U0usfnv?Z-ZQ#@L2K#2)x~TM3ov5ZskGHEeIYVz~ zI2(Jhp`n0W>gje0u5e1(#z8dO5t&5!ptSB+*R)nziJLEb+rOc$Wd{~8F;1uMrfP_3 zAj1}9v`Gt@OxaH`Iur{6tx@X=6CtRJmGI`L%sKb@e-A$&`Yh#B3LX2vYW}PVL*G-t zxSi*s?{JwdzT9=gnxCgyR?+p;7{1KS^sw_}00LzKQ0|jg|HQ|h=7Sfs(sxub#mu5d z?>AeqIr2xpq<+P}Bb)@NpfbOtsn{%p1c#6T92eI5iXL_s?%6yDKZ;$tvgxvUmY@jM zP!o-BYJJ@n-+FfZYyf_dga6LOd$AEPi1%SmSGXw@Q9gUPyfBiCeA(4s8~okHankdq zHoyeL6<1iY0$1Z{rPHWZH-+3UYbIGU1;o>J)K7Ki#T+dJdk(yaxu6-U1cA*hL*|yJ z3HC`bqVa#fz{>@m>`NE?fqTcs_1ssDX9!0SA4PJW*%=-?kSW@wAy|0xmp~j%%?RWf zi(GWJ0|X%=+-3+HUhjVO-CUQbWvg-+&YM;1N=1=MrwX&AC_CSMz)dubfqJo<v^8tA zZ3kjFh|*8K37Xfp-62Y40$<8-T<&+wCa%;$b&K%vz*r$ru1ca=bh2J_!jnZB=>MaU zwj>hc)9+Ygo&H4_$nSHN{4XPIzPe|3y!i1YyCU85mLrt{Gxj$Q#{7dzIIVDQ3P^qW zYUvbUAs_-BfhY;QbxJ$_G&ydWMeEap^dqd>oz|ukx7g+KSF(ib66=u1P7YK#)Z5nR zR1Zkz<kmVw{r!iKa^+Hb1>e@Gl@zix2hyd@jDLcpKFMiT+m+~+ShVS>M-_HS_^)iW z!=}t<B@*(FE?l=okU#hz(Xis%@$@_?Hn*rU$vfq^{la~Vx-gJle4E!~3N4Jv)l715 zG6fLs5dNN};P7whg3v->Nqngka7XIR-FSVv9as~}T##m;FmuR!KX|N7@8GEu6+d?P zh$IM~0*eIudW2FY2_61KN;wo*C)JAiHIEULxDU;myK6eq(>kMOCvpOLL>@RLgRaD% z@E067EHLmTzWu?es%A^c3;iJ~p`pg$fr#F_n|C9Of^15q8|EEVuFCcDHLgoMwaB7l zY_dd8ZcpsDQEz{L*LMG-_&Q0jN9P$00$7tFmhS`B2QM+w>UxsS5pooxq>9Q69Hflm z!9=IzJI@MY(F6q(0SlcSM~lsDWRXRB4k72jP&l`gM|gi6P0hU`EEnB+5}yrh`<@YX zv~<IEJ81U8<=dSTE*hF4U#mL1Ul`3QPJa15v2>U!U0V`Ldx$DU?(k5C1wAyO2q64= zpFPEBTM@REIH>^8Yd_p;_duSkaSu5g%4cpjv>s5La`~3yba@G>z|i$_Kt9t*1<lq- za+20R6i|q!6lPndwa@kR>Kb?@ASOiQ&}r=I(F7R7tKpzf{#LVF7h{P@6zxebPdF-Q z2$&~!S_mIqD+=*0h>7JJE;w85rV2quu1v))n=}I8IR`r-_2{}dw3)f5h1|Wt^LhF7 z!YD=IvYKk69qr5gCXr8lpwyakH}KS7+JkcAK7^?3C$Cq_MYAdwi87s4dD+U&13B4H z6-)iLpG#M2FZQ1IBlypToOM-ym7`SB^gBbfC-Fss_9+F)6fZdkalR)Rfhbj2@B`>Y z|BoS7Gx?mrqmKo`CSA^=8v~IGh5&lP;jZMR2;Z1nynxe*`HQckgx)q@-es}tbiWup z--y*=o_8!_m#0^(r1#Pj=dhtezjKxZYouOZ_~UdX4{uG`0^W-cl?;#RE=zAFzs?tO z#rG^`=apw3+K$u>K+XXU*G>arH5pHPG=Mj>A%kw0$_s_JWS2mSh0-oy2&WLErRHj6 zkf+I*Q`=Dk)8>w3FjG%SL9w~DPgUnyME@#|oRp0(2Nng5Wg7P<f`&8z&IKhl(xv=A zzQ`Vd^bhtc0iDzEzZ!!2A{8kK+7D)Nw>tC#I6gAGtiqhH{(!~2-4*j_;e$?L?LI-K z!u4AvyWFNtHSUe2pX%lJxgD7v)$b#nc%`xev!WH`)GrPTIV~gmrCvUELAb&?Phv{N z+EQ=a(rrvmbn=6>`T5Eu^n>^2Y)G$#I+a+~VUZjRNfA{HO?RvC-FxEKO=wC8VUxFZ z>T<pE(p+#p{FrEn_k4<O6F2wrgEPd0x}pQP7KiU-_qDWF%nOJ)kveka{@tB+=bR^s zrgr-MPX3q{Gt(Q(-FB0Z+#F9j0w;hYwHA7ls@5CxA*G+=YwRO;r5w{4OCFDwqo6*5 z0ae;JcGBk5fy;y#f@%)zVw!=(lGxRrp@J>`<<mbt-lkK$FQW$hEp^ZBatIdo#9gcn z=6-a{&i_XLz$&*%nvf{1YjvM{F{(OXSeSbMMK#9uiT(A;jNDHzl-CS)hnp);L~p;S zwX!&O4Dqeq1+QXTE0v~`YjmRCnK!}m)^g`$Clyit)pT_KL6wlkhWyFfXFoU^Kq&%e z&Y^2#o(}9odMB$?Og3E_SiL$}E*05f=8(FWr8i^KHf0DGiLwat7U9KfOUw)x*_53O z12F(=O!cM$eeLj&%)s@q=9`G~{%tjhAdLV&w(VrQIDlo0*tgzEI3E<Kq^<gAA8-u? zXzkX^ro(;2AV6tQ!U2zky=yXC<c6nJ|FND|*)&jk#>fcc`RQ0F^zg0<b!E%ilQWI? z8`9P;4Llw2|I>31*28z;iQuV(x28>t_GetbIX(l#<P9nD7p{iwK6JJElHXHlM&S42 zp%VNwd%=hAnzWEp+}ldoJHP<__(ul4Fs?^vkecW=&cD%Z+L!)qp#9m{gg`+DrQ@yS z&LLUdU5`Q(b_a)~bx!h|!zoZva(~UR$wG*unBZs!Ld|ubj|Pt(d7}`TP2W+x1toYj zZgG$Y@b_N>sE#v7uAV;lOw)7UrOx9CI6y!`YdZOFZ$KmWF7V+SC|2`o)HC*0O+Woz z0@}2`#$c_uSsxz*r|iCrY;BC~5ePSrda?j@oimp5e>s^lmMQw;kd&5yZ+*UBBZF8a zp5$wPNy2K0W~F(~nCZoqm+^HF6VsXpb*@N+Wm7NSz5vgBcj)~Kov#UIc7imk+;WA9 z?6%iRf&jHDZm7rd2h}%Xwyx1gtOG?-I~0P_<A49;@eNmv+N{7phS-~o7aF=_u>(o| zDRui>!n&aplreny&GDzY7v8B`2TK(dasBxYL|zUG{;<6}^t{DBgXOn7QIFCjUUI+w z!d&e``?bn^7Snt*l(%uK?ZFf5HMgdAJ@ALO@fCwgQmEj4dAGg$L~e0ecVJ`;<%+Qv zN`R!_JLXs5g43k)1Jl(xfvi6hGF&jp$X{mviLNQx+o<5typ4}(y2ilL%9iftW=2^< zqqgnyE!NG9izAKlp}VS(#=QsaMmj3?;{p;7jcDSND{adJ1P9tWHJZ|&AH33q1zK(! z{zxR1JUgR-+;=1JQn+pyLHLyR{6l0p08&anFut0Joo)#m^ya20J6knotzJl$`WmCn zUJRLSr)+)xidg(5s2aWf&|b87nem4N*UY^Ar_@iw`yi{@HXYd7SrFS`g>QI9WQ6~z zNB3HF|B#ZV`Eaj(e|+a;liAL5@9Dmn^GW|My;=nO&c6G-FUsJ@qnoEsvoHVA4$Of_ zU7&GbKZ>}dq^+UvsV8sVbS)MD4k=x@RwQjE)3bayiIYI5wtxIp4}23kJ$DceFZzh0 z5o(ia7a#pviKT_;BjfWT-^lToNC2&ecfdHm&3$;gT!cc;t{KS#<aj>-an#^|@a<i0 zG}Mh)lMt`{(7Cun4L$V2d}d_4E69?5pM41IO>l%D4Yh>g6CgnhTNP9DU)qt(N6JpQ zFcxHAHtDmxf+w@#{4bNeaI=BCahPJ$6}32`d7n<#-dHSc$Cb@P3`}(um>+Wb63Y9G zQ>4K;s5gohG5x3x9h*gxHLmS5-KQo8=VRC^^14rSc3Ol=XF|`x>8*GzHcU^aANmpb z@Tqxl6pi;0O2PmF?<?lfC1b0_zgElzqJ(CDw*cI(6Rjc_=I*NQRZ5!cqf?Ts;Szcb z#0>L*o1MTzGlO$;=3cELXE==~pfWEF;lBHrA1V{?#|=7Y?lBo}pUFn49+!6IWnAkl zA*#xMCiJ4QR_2ZnNNri7*nM6!BoQ!rbG-O$bi!`qp}#Z)LZ`=ZU*DD1EOHgnDXrXn zU;E*2R;~3(9$Z9WV08#{DDJ&rmn1{p9~Dj**pWP9Jn||Bh_hbV%G+4A)+$fbVOmF) zRMa-KM??-k3`xkx+N@B!3)Zr!W9od?OlV=Z)7|!m*Atu#NY|axG8Q_iD^_JQ0vD)< zF`=}?>Blo~L@VR*-K)~IYuUGgP(<sDAFRW+REc^!fx@p()L(Vei79jtCjI_Vz773| zSPyH2A7lGaL8tn_+TGv|2wyZRs@CFP3+&~#O}kXul39n%bYeZsP9k8>X|Y&36=(=Y zom!K;pGK%Vhq`7oGBnr8Yx)K<lPbDK=1FNGOg=;yN~9JZv6Yy&Ch5+saN@+fZ^ep; zq5QW;My7{eR|#IQt|Ln^E==3LPtDvhW!n$URk=v<PQE8q`43If?IyG0{i(eaV}~x{ zGv0iEODY~vVWCp^!lG|>8phgDvB#)3tKU*Pbe{W%qxh!FlL+nAB}IFvjH9mx06DQk zFJce#i2d5SZ^EhJK-QaY&mo3<acQXMPGT?LSCDCN*W*x41EhUnKSVn9Qxym1Hu&8b zKomZiv`G|?m(}?VpRXFm;`kf29r<J-CD#FT8Bp`8>O)o01^=XdBc-15ZNegHh7)5D zSqOyv6d=$&IOw-&1}{~U21DgdP&6A*#YyG4%tN$7n6)YbM7tgl5@TS_CGoFIdZQG| zOv!`d?1KTeYTwbPr{O!kcO7*^@bdl)Jc<_BFB5&GLBALFHAleST3UY{EiQ$MA?Y4g z#77R3)o+zu9C^}B=i7=)QW%w2=BH^^A*dzd<{e3=3dt^N%DHk*8^8+yb?l{J(o3;? z%@2}}%wjspQKm#Jx;f6DQ{fu8>tPP_=o$RXN7^17O`I#|sH?SQSC}{tTHS{m8}y}I z7WZT%V$*ad7j!&M;Bc2wgghF*7y}B%n$Sx85xbl|$i5PH(m$tL)|v1xt&LiHa5DGh zph~y*U8s;XAVg)~<qfpADyAjku4Ke~kV|d&?U`&oE0)dWJQS?4Jf;%Uf(GbL$sy+z z5+et%-J0Gpv%&0AfQT@sFx!~N@3X>D*aPPn!NAkvdOb~4j|0giTy-kt@5ubeM9VWS zy!RuzHN0RPB@h^Qhyy)9Osvrn`xx$ao$c~33<!!rU0E0Y+Mz0N+(N}4Wh+u(A$js9 z;PPPN!4D}E1Vx8igXk4#tg!HIV!bn|#TO9=FdJl7MavscUT0ash3_X)Aw%L2b$cef zkgmz$n>vsiG@N*eiSc?^{V(X1QHVQ(_@@2u2)r-@Zt_BfmFTLl%Zr0N4=Ch)dlQ`y z2b9HKVXz+g&UCB3-h3b>M0x=X)9IwwRy{Kj#H4pwW0A)Y*S<gvDaX#<%1VkA$QSqA zQA>!Oyj3PeqeaC4w-j>@1txjDYN$MisH4O8QW@^n33<(eR~_A*%U-{G$g#{z@+8pt zselkT+jViI=weP{&kRuLmU%4iBq)-^inm^YS1x8z$_{V*MSrt53-`wbf~WXsw8>E# z+~gFp-;u%1bRn021K$E%mn0VSp>2Y}i_`hQYa@lS+0_$6#=X#BPa$h}xUs@)nI&;P z-nn+J>H#I6>tglT+~H%aDhj~U81R+Xyb%3=_+tw_M^;l$EM^;18JF#5L=Png1)%E8 z`%c>o1FlbA+S8t3XcJ;6`nidT2~_9h0~)UoC#k9OmJ2zgJ#JM!bOvijyw;mxFn7~n z@#gf*w9w*iNP<Ho&WV&@8wu;UGN<`tNF7!#MTSWDzg7Q0yQq*dF3nJ{rAw3@PxVhX z(9m#Tz92H;m&@a=*agt!V~6#gv!)XR#O|3oye<=avA>XEm9Hr(gE|=Vz{R@g8`+}n zyYH@x0#TAEL2worrs-9qk0d{EEjw9Vdi-0NJAvTG7*1jF{;R5{Lm3HGJ|9NJ6i>dK zI{9+!zGBLH8p`OgViNPYx_?~Ma3bLPj^Xczn~2wrLDfVh*o$Pq%v)Ry@(vC9)k?u7 z2yYTO^hczVU&I)eR7UjIyN<Nw#E$z{oc#ypXjpElGz!oVW9-;&A%jp!!7A0XNga97 zWd45w*>3)ryj}YKsMAU*r`d77E0{p?<5akgW6Dwo?&Ec5jKd}$9n@wZF?aKhGB`=M z=T5u1+a;;UIIkQjviwvgmh|3;&$Wy$9{DL|2`x7V^_WhyIfn|4Ogc|l*wx=(WqHnU zbESxlke5Ws38mxu@3j>op27ncYLm*Y1~QmQXO@hP8mtsEV-;?!p4|9UNJx5k%-78q zy3e4`{+~-=VU^A0ggYCn--J~Je#2uoS^v5co<7@sA~HcR+0UbNX{eg)giat65Z4n? z$2hw=&g+whh66|jQ;FvT8SB${Kt5-EDt{g5SbsIUe($Z{`n#*9Q%&a!cWunepyo9; z76;ES`fV&YY-A%gR{TgadVz17HWG)|X9k1cSZ=)0+jtd$dLtA3I)CGf%%iD$!S6PL z-`@*nteju|v9Y1|`Pb6nS?7&!G8g{54E~_E`nUS?j-|=3#P!b^pVve;ekN`t79z!v zT;xvo_aDJ)iRe>v2@VlltV`Fw!B2Ej2ku((Wzd~}cgR3XVm8D5geEdrW>X}oXOG|J zZe^1_&#c967SaBvxcvV^l<$jN(tn|Re!W<Iiy+qj9p$smLB3U`!jSxuhq|N~CUuhy zt~OUY#N--W$`rd(q}9k69?CaS?`hkr_NJX`74h0A<dfMM@dKN8CEM@xvEWu)(ld_P z=2(oGlj2B6^WqRxP(VSE8ZzPv4>6q`>1;WBQ~p@A%qWLtDbZ#9A8~nq)P23T_ip@s zY4O;7!hdykJ(ABaO-|>lj6>HJX&QQ5{!(PaEtN%1dbjtqhtIk6$;!ZY_|RPTI}yh) zUR-{*S>WleezTeRtdG5G9~LviuW=#(LBz+Y7yI8SwE_ESvP{a~TeoB^vQ-CNcyW1u zVNgg_mZ^jkHv@4HR~1K;gW<}&O`>BhQ)w#s#ginL<a?&TG+Y!=egG$pV%6>{Ok?Fy zf|VpihA0Vo!Y#4F*FBlBkY#=KLm#QrQ7<d8*Gs|ItXjSBeIC}$W)kW641S`(HP)#Y zi$SX}_d{-@rb!g)mn<+go!DCh6D)){P%4JsnaaKwU%E-V8vo8b4tZ{+oN+{9Is=*Y zinEK*!>Y(MWfR~c8FnY#DoP?g1z26x68=<Em4DfZ?~vR8I-?E)A3e%4-qAekie8KF zsjXhBUv298@k!0GQ3B!00x;%ErKnq<{4E28#7LM>d@jVh<KMaUwrRhH^?O*u)ckf- zBYM3=>6d|G`$~1g#{IQ>#X@&Qd(@ON55NAj@o?+Ep?u?kFG~L+{{!XQ9mMTHDc|Oy ze3I=oj>k{D;r=JeH|R#t{Li@j{}SaJ+V}OpP`;-lr~ZGG@Bj6<yxiNl@&S$5QOQ&M zmD3x|nOBH$X}-Re;!nkB+8DUBcUtB6nr3DcoSlK_kvDlMJ9G#$nlXg}4&I&z4Yorr z)_~S>^ZEjToH3bL57cf$SNug`bD8U_aQkj%&&ioMnF4;2F>)aTj7^GcMOgrP<><ab zB_K7jAKos@JSJ)`y(Y$Ih)1`X7eRMHxOfxz7*iL{#zj&4OlK%|bd}@Rp|VPQra_t; zoFsHdf#Ibh2n35NV4_s|<)BnKCoWVJQs@9ghNQl*TNY`jSp4B?KE`*aD0uv_1h!Om zI=#sYg0B=%qz9_DZg}54kQH9?yPR|NPhUA0Q%m}?nF+k_ll4cDWQ6Zxw$l5U67VIG zM!n!;VSJH2V742+z@Z6M88vrUsKZ0$=)=2YYZwD+b7<^wHng;rHlQ9a0aR3nRj=Q+ zIB@Z@Q-ClWe}ZKq0l%AQY#l2!8_mdJ>t_J2$Kv{DhT$q_lL22o5ng*j$zrp_u~ts5 zs?1KsNVdX}Ss`4-T2hI(VLJMU5{mlGl}*dhf@7w2Xu*EMsjSqcTwO7z6E}@RJ5A0S z^FsE83~hd`mvIDHq&N{JT_H%DsZGy8xh1H=7m`2238IC`1MYkk4v{<Ev2}Os8AdSX z%g^i|ZLIY37b60huJ46Knu!S^M?)|t`ojqsgkj4-*>v~l1wx{s;{L<!Zn46!Y&d$z zlF6p?!6^d4KIR0JR;q_WKL{bl%VHq5>BinAkh1+ID-G}dV0^*w6DWN?4{*X`(i+~= zXXj`#Ll>(Sxv;(-A<q{(k`YeGxjjUh)?|jkfgD&J-ytXmM-Pu<3I(u9D;$3MTzgQF z$|`A^H5M<mASkEBB85kf%KVHhcGE?PvOpRUGz9DjTD!pBcsatW$M#q6=2l9b5&cF( zI4Gg^AitE*#aapOrPTM<60~!0k|d<?{Q>^F85e68cN*qbEDics@ewR}nRTM30smco zU-Kn`0`cP;k0VUyu7$=swW{_au^z~F)85YW`29_*$*$20qA$-s3qpq`+cFk}rXHFD z_wCL()Wq&)vJo2R98+DmCkR2)t)!~?QLAXvQl_Z(!hJRH@(VL5n2i;0rpXA4@5_gq zSQ$c@XX!LeV2;hF@)4w+LHYW4`B?15c+Yg>eeZyfOTZDwl!sacGu77Z$}<wQ_7qc* zRiy;?T_2M#e!VC>^01)`2D&H@<h{F~IG}n&^V9M8*iKl;hKWCqH{7i-T+7jYYaA`8 z+g{lq)U0h5Kk9Yo<?-N#$Zxd|b5@fHC7mieR$HeY+XvIvCTA9vwmRJAokKq7H5v?c zc6erdrgZ;Vs#u9vG0ytB>|y!<0t${R2J5G|_>Mw*I&5A`;RUhp7vbd*zzFu9W4NKb zs#WLnn15l>@AO3Z2U}lj;+_}2&hJc&Xxi(vnR0yX+s0_=gV_^f9;MyT&Y`yfMwf~% zO&6JpD4K?f^A=0P@m06mIs*RO4mtX*e7D>>P<Le3IOAE);@9Yzu-S-bZ&=rUe~3sr zdqA@kYfX~l_gXO#Na4VyryxH%9z9&YwCA_n)}bHlI}f>W@2<R(+}RpF+P!)0biAxp zgy7V}cLuCOhYptMBYjkF9k7(5d8z1#p+u~ApwIlm+CP=f96lPeFH|<&NXq-iO@nQR zQpp|n-*3mQlGfEeWnTLeck=s9F1ne3xyklGL}Cyt=$mtB!|xdWDKyB#Aj{C<y7cgi z=!A>(A}ac&$TbKBaa;uGAb=N$D7Yi$CfDW8V7Ol;->&&^(=7Z45Wmg!`a%$3JA+RJ z^}H@&u6*#Qzl8N7!<#Q*r8<toYB8oiLoZLoITVK8+8q)7Gu~-B?tMh?Em8u67k=iY z-k8#A36wJ=OFEk$CL6V{P;c2(bdDRuQ36LOiN87g10c$p1Upcui&_p#Oblq@yVB0N z)^yM1HY+Iwo?zAN@>hvk#l%eRcp-c!<TD`pA61}-g&gIg3prr{V)`opFXN0aS{C_E zj)OyvK$wVgB$x)rZGTIwR7hyDZ*V=|l_UU7-$K`us1ZNo!-hPn&WfZ&VjQ%100{yb zf}W({-f=HNI44=t$)^`%X&@l~1Gimu)I~q#lo$RpMc~~W?lb2^8?V+3CZQlu$Q+DU zYc^2QDw+0Skii0qJ-=*lBiDa)z`2x&X%j>8K%$oe&ZB28$25n9O`)6SFi=e-nT$IP zz_&T4HIzXwrF2gpE9W7v3wq!OAkHTQpXUp1lLfwW@Dk3V$gCunp&;m3h=elnKtbRD z0qpnzs_raHpISz@6L9xj`PQmZ`BfsAvcbOwG1>!Y&p9lW47jmzP?Ib%w5~7|<<0@C zr}3lr#3`+|6*^!aXbbk>dDNb~8!<#NxZWI;MPaW^g5H<H>Z#aH-k$YiY%3T2dGJz# zwM0tCg(?8kKtONs7`?gNe>6Uym9sF%(Bp2p>vQ;ZCjMBBgucp=ygD$5i+u6T3#aYC z0MXDMbOQ$sO9JOa3qD(7FGgK~Mq%q&1z`ojP{(j1WxJj&(SQJ#FM}RDDk_*-$fN(J z$;k6;CWP#K_ebGi%h{#5Jb_JKtjK-{@aBgheA(DGcJj4f1-E{Nwo<W4J7rhasxSp} zappFXJ9^@|&8S&QVefUsKN1Qm$REq$ADu58xvn!4sbC5MM@gs)+(gta&sE>7KS~$& zPZb6YxN9P=FbT9~A{H4SWf_3_tXh(!%KJImDv^IN9$i7r`t5d54ulAT057+Elmk5` zPE_=^FXfy>KM8A7#k7*JNyHmo<QsLwOI>FwIU(iZ_2q~%_zPlb6B+w;7^~%6Vfz*T z_Z8tP83eUJb%`=@Awar)zYhT{W@73<jLws=!;H#ykO@f+C?jLST`qJ6l=p^X#4tCL ze*Fi#w^=6OOfrA@O8+B;*FF!jI)=Z-<Ni3{={Akv9W5R!<AQVyt6^rgFJIowwcfUo z2`?)DFIbO^<B)JFe&F?O)AGVNktzsw4F8FS|H#6x0okv=T>S7exRHfvU%6~FaLGCp zlS;$~vdjOA)FYorBw&jv@T2T=&=61QJTuSxr0c36kyC+%;JHMb)FSn6wtY<0W$F~B z>|SNNXfb?u&0omv39<l}i{cWX2mr^S`4qj!T&F0(Lp-0_m>sVt`6KginxznGw)=JU zTryU1$hq^=)uw{Xwbz7=PXdWNQjy8m=O&Oz!c=fPhTXsf0<MT$P2PLZFTmQv=@vhP ze-IQ{D@%VR=XJOi)40RN!~^KXk2JHN%Go^Bl;Dud!X=>vy5{V2>W^?wfce}i1BDhG z-0B^r7SjVDy>K3If%s2q7Xq>{Pdv=qE6Wlu>{^v={DyM<Ui=?i9)&*}@Tz2EmfWO| zgR#m_4|?9JF9G-wUTyII>>0C<zKXrv%E2@(U(WdyM_+LHYk>Jr5U<%>R=J=A0-&q+ z9=mkqV00CpOTeoyfRjb)zor8Yyuk#WxatyH2irWFFo#Sfp?j+^I_=iD{O~4DTj_y= zAGr@!z!bjUIDaKjowbh_nr=O}SNk#MHpnc^_dg@4R7yg-OlG2GqrwPCACUjLwL{9z z%LfxJwJRL_CdCg)2b3t_(wy3rNlYuVqhlH~@up)dq8>I@1Ix<XQtKX-#}o8;C;}Ws zRX;q0S>iQMqp+=Im=5vu#Mno(W0-H^z}WJmcP+LjZ9ruX)I}0lFIK}hG$er!8(2x- z-S;{yq#?Iaql9yRQ+q~WRuY4E`FhY_n5@z--RLg%#rCqFp(toM@;+G_zpw92oXyIW zws%D;`;{?w${GwCQg!osAAGq`MMc+hkkI*45bhbxwEo9^UhlZck4zZ{_c5E4Ft-~t zp4oz@_6^Q1dMO%$>ST7ccgt;R>P-MWj_r3IQ43WC@ybK9Ew=R%0C5Kdl!@SLW>lgn z<2Ds-q{eLJl>IiXuyY?y{G+yysGSdIBbtXHgrN9TMUoZv4$yox2s2x^e?HLpS)?2| z^Z3TGE|{#O#_{ftZ&Yt{F|~n@54Ydo`^uLEV7(=Ddsa^nS^;<ubRWQf?1`2yI;h$j z!6(SVFI>cTG%)89?nn`{^-J4GCm|d@?Guc|LY+=J{?-GN+eV-Y2z=(^xm=vlZ7tcg z{*b4bpoFIAnzFx%#3pJ_%&o^7EziLa^egfc#cz+HS<ibHSyxIrnn_{%+ZnL0=SBtP zua%)P$=GKq+8A|k0{9QOxjHWr?l>;nk6YqC(+YzQ?^KL#W)(HpwcL-y+-4Q0GB|%j zF=aFd9#p0qfL^m4_e&Uuu-l=IIEPUM2yJ(ntEn9jG-af100MaSuoDaWfe_^Oc8|W= zBmGtO+sDQIGy9v3kH=8>dRVAYcBke<cQaL5b+o<uJ8BR<S)E|YC5&nDxQH=`id^u= zdndi04q~<o4nKVP`)+Ij2OScv{jN;*O#V386O6*0jy-Q8F*gFw!u<%EQ1i*(WCh6t zO~W_w$sRI?e`3m*Ek?!uzCWisq>0T^06&@!M#q+ccA8&bEB&21D$SD<;${GW8h+F5 zvZK|bT9v}Ub=IUu4AhB<>mQYVkQ`dML%3H!_5ZUp-Eoiu+x7G=_ZW2Z&i=4*<rr{+ z>iNROgiDbvmj)1I2o^w3gKyPy@cG|x-<fE2?o9{>N}=KAIe5RQiArW>YYZwGS=D7T zn;Apo-s*%4^5+t#bmPYT{AQp%?YM_Q5<2f-o3FHU&Q{hoDjU8WlchE$G%a6u{!sb` zZYDmb>Fxu@+Di_~=ipS&kNbtpK%0ZK)J-5yE$r8{r%M2NA{;U&Fh^+Eq_dN+p!oUy z^#4sDa;!VAr1cTNcJ>2}#o101)MzelivC=>A1XrevOX?wmH>((G4pfpTC$32xh_*@ zFoOCKo*4sZ`Ew95^3BdtWDE(cU_aj5XCcwuzh-M%6u3ZYsU;E-);t)Oo#1h3g&8vo zb3|4+W7F8$*-f2nKm6W9Cdu{QFj;|V4qhW&8+XXtiS*<RJ@HUMCA56r<3?FoH!)EI zlywKShP2iX;6#kU>~53cd%*P*DxXPs`$IZl*+*z|+x^WuIp=!x#H--VH~O9th5rmp zhGSEMpK0c#7qmVn;!Tbf)FL5mCi3`!H&AUdICDx$;1qbJqnOV`+~67UO@!|YX+TX8 zJiVgz2`CMC`DwQkgwN}<NhN*>@O~`=6ybxOK9!U^!+TDH@SAT)p2R!A=_V?gUm2te z13x*fYdhzkzL723@&wn*+AOt?1OTwQY;<*p<UXrlln1C|C0O1>d^YTSor8#G$%m$+ zZ#aBir2DC2RyS|w+01H3CE}n`t8YdnLO#3&GQaH(!wh7EU-Wl&+P_EmFz5#eJZ)Uo zm%j`XghMFEE|au)hPJ}FOeh5VlY9RB9cdp=KIrDANz3zL6vT{(c)_+vIVv_jH&D?T zP$&hM-nKq0Uu2^9HQ~8rq}1v=>bi9fkkM;#_Tz4w3+UJ$=HnY_5ZYEd@SYflWnPrN zw`cn%WL1VxH1S7AfolmN{q%0WF-klR7evc@9v|Dibg%^tq1;S={F?(=We0B`fg$2{ z2m%Y=#T;}&Um<i8umzLtm$-VIKBE;(z>d;>4{*^Afq%ywSFPd}m?o7^cHlGcZD2Fy z1kDivllou8<qI7bd+gE02sH)!3CsU8F8@EGe6x1LfQe}kcebwYzs2RnM>R`?fK#+k zi?i8s1FWf3pc!8wbdl-Y>rzv46(K2lYYK>b5{aSd0l6M!LZ>jy6Kfv#FRsrH6uW#r z)xBRHK3ql(nCMQx?LJX}_w0*YqRBY?^5xuesv6diLb!ch%5FR*tpj%n2HYU$r2oVx ze?9lI(eqIvFV)#wirU%ze6Un<z61CUDsc{Kx@tR+p(N7;?w1~Cm_;5&<}del2Hy!p z$L`we;TvxsUgO(yV<YYnWL90|=BfQ;19FCx4*pPXt0~s~mc;>XB=8rm-N47Jc0rlI zG*-Y~-v_{MUzQ2qo?LbMYiMNep7YZIe5SYyU(T!ZNg1d}MReJc!6Q{R{v!W2%&ZA< zdhuCRZeZ+to%m2kB5l?CeY4e`Yw+v}J{b}N69ctYwpO%B8IldN%-z_Pl<(7&x0Bz0 zOjdPQwgTYbXV@raOYGFL)qZZSJ=*ugWT+UZB~faiPk0%0{>lEFiZ>N4=gMuJ9tV|~ z&7B)~5^G7{yYpPEMJ})v81MK%Fegh{=vwR_(9w_5I)C0gD$UVfIi?#89B~-4J60~a z2C#B$UA-J-9V?7h298VnBAQI|!?3c>{ttCsy^<7vl$A=5hWX=Ps)|0f7YL=n<A>)5 zr9Z}IRj0<`Wf_MPTp#Zn^ArDeL}=fjg}!IkjMJq%k1!-gI?x}WZwnE<JaXWqYkbu# z&ZoyrR%IJCmqmfH%!jo8p6T#Pv%5I0fdY%R%5Hs0pY9o$KJgi6^`*ntvI&1#0|?Px z%E)u+(6wk=O<O^ft2<VA`W1gX##ehl;BpxNuXWu!Su8EQm<Zy9VECA>U#cBP`nhJO zJWN0C-=RHE{1=>O1?@1;b<&#nQFt1>hYxIdZh7TaC<;qReg}GMp9eO*%<&0ZvUvxr zpHPC;nglA21-~+;!!tE3UWLfE!Fh4{A@PNE0*WSow|%G&rcARD9<Q<azJ0!_ENB1n z+M(`UPY@Y8MS{Kuj$8j9?A_N}Q*8q-_?2F0p%*EkNfGHN-Oxi*x(K47N>k|qqHiDx z2|Xy%q=X_((4cft0Rd_9hK`6D5D~EjL<Jj@@7sI!TywDJU=HSJ{(&S1>sr^!v+nzM zQ_T|Y=M|VetO3)~-zg8WD5VL-bB7zLrh6B6mIOZNR(bFTgcSRP%Li}0sjsi_7vL8{ zyxH`hIro)By#AyJ=<W9FG{8PTS@jD8OSrrM%{V3c{$>5+tH=BMY%9z@o%<wBp-Efm z@2uo*uMD3CabC#R)@Jr?<>~dPrXS*8!=b$}j-vOm5sT3#50r8HKA=9t!)o`+lQdq< zSGuQu>3WN6wB-pSs;u=i+AXE#U9A4zUkMrHQ~=x#-gGoY)pno~zV4!-5?A1Lp;cS) z$W%sG>PetsphIQbhS$^zd2G-kcOy<gezHVVEz;Ab%84bPp%^GNmnZ@C(ByYI6?o>i zAn}lbwKxcA7pWi3H}nZX`I|AN@Y{gyp&=k2njNShY9!8Hc9h;(DoI`h>D*s|$O{|d zmB9f2r|uB(dUu+72<V26=DmZXj(C0V_AC;4px`d~t;<1MzG&omi@y8w7Wx($Bu;=- ziPb6atH93Q(cz2ryLsvu)QI;gR5&I31TeA4jq=@BezD&N=ZIO4wt=X*pvBiA4m!?c z+A5hSJe1||9P24Doi$`!uL;rSC8s<q{V}NG&?Lz1T)Uf=$BlqpFhrPiE%E&{ML^(Q z&RlP3Qm*$%VE|0&jX{LyZK9)A=~l(<w=*?zEl4<MsU}r7TMn^hDPlEP?k*x&tD4Fq z%PR<oO<7vVoLYB`@0n4|iK{=nm#!>6ke5s+Wp(e7RgYH<R34dYJfUp=C|#QfHROiy z4M*+=c(_qQiMKy(SDFq-VVo3diz%(1>NpUO4zA$hpL<f4>gc)bo%dKhQ+(Jp{K-eg zQ_^1+3!oCy^4P-^6r#!kka7V;eq-ekeDnJ<_AcEEj9^-@Jo)aLy6wRPgsZ0!{-my0 zqwb;s(8YLz?U_3{Z!TDjNz<@elh3nDgGjHl?97&;5M=BJ?CG~5b<?SN%Q8Wz*QWR= zzZthF9Z^%w_{DkC0LAIv`|S(ytH6>3(EJ@Km(}fTSi)We3Jm;`JZLX}KNpXdj5!P% zft>ChMh7K)H#y6~%PXzC@|CeXb18nvqK)D6Az-0TY~m&uU^_Q&lB&#ya^8VmDku|$ z(ksw+N4vIiFFC!bS2?7e6WTPfe&@bP!!mx38)pL&VeNT8r&EJZ_g|8>W+L+eQE-$9 z@`EizkN|KWV0j}$NtK3?BcF)-(JzgcSA|%xJWpfw;mkgTq*NrXmTaSZ)<vODPi#D* zzqt;-YRI>k`1JbV*CMo27wiiQZoHW4ucCI+PYg#hQCKL7=jR@>8<JBZg3o?dQc<i0 zid1WB-?I249Gj)|yyw{hxi&xDUYXL4Ni<c+AsGD6F$mL%)^oImK$&*{!XE;pk(({l z*wW&!3<F;l|8X7)Gp49$`f9iiI{99`zvIHT*j!X2r7t~*1_(I5Bo`f1K|;S|ag0Y+ z!xQPZzxqYZqcGb|JaU8c;}Vqzc|<zn+7qQHD&LcDdqke&y^%;cbXxKwL*r9oBr#o3 zlzZ7C*uYWl5dFr4%swBK0c$4P<*5x&0PU1H-UD5JOFWf+4Px?ZgYI{38r*N1$b2Pt z*Y9mQ@hRM<SK*yETJ{c;a$b&%B(iN9!Ned_*C+C?355e6!0$<9|3eF5cbMAIGTEf% z4RhVS?-y_{7L)A`Y(`P<>*=2R%5ZGBG^1@gKVIZVvk>g<vyzdz5_hl2OrFiy`_2y# zLCcQdl0Ms+hr)Taf!1VnMt|cSS>VRKgW?Z&^qv14Iq4*-2=wY-UiBB@6YzBbWgAY< zcL(MU;U6ijGkYyJ|0=c=iXUlS6;tAORb|}&;`QL_NROyo;m_Yu-|jB!Tj|Q@UR?X= zwy~H}F|uN0MBHb5x&5AE>D%iuiH;DV2>^1d+sRLU8v(}W9@#ABJ8lHF92eM2Km1TH z_rbqw=z*UQ<ixm?57a{ZPa4mPkxgM}WW7Xw&$p5zC#4j<j{VfnzG4Xgu<+CWoW>Fi zR7MJ3xzij-yaqU0Nq~;9yNDNFnvOx~?%nwHAS;1+46R=c1po?g^mrAOgy}<#nAj}k zW4&p+!eVXA{2xya@#-@p8W5iX=_w!j-aqe)md_UVMH=^2D7D__t%f=5LMR)masDu; zMWJN0j^386_$($4Kp*H%PYk8X@d{i<5>M}T{OlGdM_q4wAgW=F^ol@gH&;F80m2Q* zNAR-yVuuPR5><kbL_A9{D%!GsHAjFK&{<YEBq9(Yapb2O0Kp-<pA;CG9CF{TKI_h} z%2P-QOZU;H?2QWLK6t{{N{z)Lj+L4G1p%Nw{VN;k7unXPVN~msThE@~Y>Lv1YlVg} z>H(J=FWzehd#!<to8&&r%Zt@KvpF8uwZly+AcnL@5JcIb!i27JsaV<!LtJvADj(M$ z-B{oVB9Yj4edFkL+~`DGKWIaftU8onL6usjE34j?pU@uJ<vkz$h*WGFXJMvalBOw1 ziJTqgbfrfysRC_+XD6PLHU`>s?D$;m5?c>UM#0ir`EN6Zh-69`8vogwSEPixf3+8$ z5=vdZiKlXG19a|D6X7JVkQOeDqN?`@1G6<b`YpDfBv?t>AdhW~d|`+m*u#Z1+vjlL zp-P3(rpTJi{M&B;N)+!15jH2;MvAgW2aVo)KKhw?D+x!-${5RPD7-y*pVW`=CujS5 zS3ttXe0!f#d&d@B+V9UIm!c)i^sj&BA)cS1T-U`t!@^qi$A3Mb;0SOscit5`(MP5q zzeY0Iba>!|jFuc{5=r9dbO|?ZWDPir&phpI*+0v78Hcz#IMMe}DSkQodn(%JlvDMt zE~SeiomA~BanlKa_<o#V109QT+>oHKRa`$5Yh^>oq?_^%NjvY?O^jC?J_8yI$gU5i zlE+SB^_Sv~e`by5O7{a2meHJJPk`g>GQ5ZpQgM-dDP?jw6cMvKvKS}a_`v2ykD|wp zxLtEq0IRkG`R{U{^E+$m_UVW5i^g8p3k9tI-RtGCCctT67TAC_P+UtIxkbWSg|Vp7 zi-XA)Ppq${6NvvphPbEoS?%w8NiO8&RF`xVJOrO(&;zqZ0=6ucsF`+hKcX`Z^CymW zY-B_bgg4DkU+X55Pbu=)AYDR_i;24B86)<i5eal=fk)m&y!8!-@i-&+H&-R?5sGu) zQ~9CkA}PeO)wMKUf!EeF!AL~Zh^c=DNfQu_Oy$|n&{yDQ@$`uWN#oN-x7>@00dWb- z*IiTkNn>3;il0r9oaPw|Wsj^4+^c1ixDpo&?cT&T`Azj%{EgXb7zXTo(Pa!Yqyc87 zsCa_tq3w>)DxY=r%Mr*%R7#6$Tu&cY@^ota*Nfsg;?13d6_ZR>KFzTIXq=hckb9bi zh{DZzi_SB(wan8L|LLD4srDQk6HHT^{2+AS|Hk|P;E@iR^<sPIUQ2hPq&XSpU_Tv7 zZ|e(FUU-0<59mgSoKHV<s>Yia$j@jCB;1NJT!?8uS%ybUdKCFEC?_Q*MZ@9d66vAW z+_it1{O(;K=VTBJ8)F(y`pXv+qF|EAGW!N@&h+u4WY5K%^BE0#2Gop#zG#oXTOJ4A z3;pQ5bM}gNZt(MKZ096Sy4gb!3tav`?bs8c@b^n)Ye6mieuagwr6M|&C%X9TBHG(t z(TUZ6W)WHt-{dhqz_{U4tO`%=LqzV%q*v9KdMX(*^<B%Cm~+V6qWPt#D3LAI1U$r# z33VjQJeu}yz2QrZLL@~k00cNHuvn93-<MGnz!D2?*I&E&Vju_kY7y~B(aI#l*MF2u z#_?G7LDX7L{hYejr)=W92{+JNo_y96&?dQ6QXrNEvotKvZ?6mqg_{@_0~=88v|qh3 z{4CSxEFfC)ZCO9b6TO-f+J1e%?1`W09&Gne@pQO?dmrqHp2^MIxyznK`o6Wv3=<>B zm{Zc}(i;aoI9iUiRcE>tyn5WU@58r1qB~Kq2q-)6Y3f$NRJGX>N&8IwOWAHNnh#Lo zuDyPA&&bOd>0|a<|9Rg5rjd7b(WZg97ZZKNTQ+uFUc{{TG^|^7s3sQqYX3Z4Y3rEf za^KT-VVeO&toKdyr11J6?`(Xfmb>8HR<`KX46wu53)wZ7Xw(?a>x30C-JcIEGhcpK zf;n3Xi5(YCz?%dN)<glme<kyMXewceh=kpLlhp=DSXq@NvSXAL{ev%dSj2LoRwc75 z5jmGVI_u4_R@sIrA2iwLEK4iT1t?b;X&zLJqaBY<F)wIk`LbPgt0`wj&`}TXZ0x`y zki=u8@gugvV3(R$mT&VO>}^g>+@S}c??Q|EYZ}k}q|~WK{P4@6Xu(O5V;u}Fs~7k~ zdRwjOen`ZLJ8NHDsL^~xb?@MC_4H8hnHt6Rt+_I9uj@~hSFHomlf2Qn8mAo^D4p$X zzrPCk!I!>b)(6@lbI;x^yns1)g<!j7zzpCYt2OTUWHNTBRMOR;hvGBxT8C#1pd)sg zLJYP%U$+y!JQsWb4*roEv|f|0aps(Uw}m1d;n>c8+pQ21+MnVjuwHJI=2f7`@2eFc z>X+z6<`+mw-`LOiE~tYfhvH$eG1a<99-yAxAHEg(!XF8dAgcuX=jRJqb-@zb8J98o zyh<$kq)`8MP6&MIjNv3u{FFC_;=>MI|7DWo5?XQr0|^B;wS^TrOPk>Gh27puZIXkP zHycA}5&8o3iWkJH&6f3Wbh3k|DygO9-JSWY9;FC9$<3!zPrzM}*<?g~hh*_esRwZD zen*7LlJvF?;b{g)<F+wxqvZQNC{c}M{xISh5)p3xkx$ZE^Gs%2LfJiqbpGQv6MZ5l zRk0Si_9Krzei<42lr(+WTkOc4l2K<B;m?sh8=^OF!Y!OXA-ds}?Uk4Co5>}O3-j3y zPlA`PV)n;k<l;GU9U|F|Ari;gg{|x7TQ`v5m^B9^A_@C>t&k6eC#L>>zG)AioPtkx zl>DT@DsFu4X&_$~TYK5J$*IG29Y<c!KD(2yex-pNC_(rO^ZEhL3*sJ^(t(^c_{oGy zBijQ%Yt()XXN|0!1&ilJNsuDVX&^cvN+3(QzfIUu3#o`o><NJ0<=JwL<SWWy3gO8c z!G9Y+(flc%xC;VB8F(o|c<4pZ%AAXa4G5&&1<li5lr8PpYtrHZCZQe1M@~Bt!epQF zpbl=c=?Hr-nx=MGcgrFv5oDLRp{SDi%ys)~h3tJXC(Z42tVA>!iTJE}+8lXG9g($< z6RUJ!!mEzNE+!%lQ)LXPGIRRtM~YCWj&A!!cw%3SNj*;~3DW<QK|+G<To4z!qWta2 zn;?-hbZ`?ASo{`SP2aG;$k!%(fvgQc07~*kx=^K;PxpDpry1osF>ZN$&yUm28#*l7 z?<7dV$Mq#W?q-Nre_M3<0$-56m@bn@qe=}+>7&86xE56Jw-T4_z}LL7EOihdsL^Cx zVs-P274mfy_2fmddmG|5EU*vLE%;K#FH@QW;?hg@$2dXwPuJC!6_ClsJvFT#*A2fV zp3QN3s-s~3BU<tR#rss-R;J@(>6_|HC7hMib9^WuAM8R@Y#=8ux<&q5upa^W-nKGp zqMKMkq^dkhd?>N=TXQfP_-uYrEODgbr{sYEmFk?=$V-~kl#_dmVhMx*;G~yV(IZJ< zI7E#l{;g6mZvI+SNs~3dwgLZHrQJ^|PTg@v7Kw}TysOk@8qOr%5YhVCV1}gL{n@+W zf+-;)n4hbv&L{4smv>ekmOSK{7!&VGzCwgG<vq)lK-B&Fv!s}nsYXO3Mq$RvuBwQA zPd9L}yXi`R<#)dT@W1>eQ8x7SaKEV+TPso6pWSy+1gTU25JVL>tLn}J#k>BaH|v0u z;XSf0EBu~Ck^RO!jra~$QA&|ELdTKV=K{K@aLs;EMMth^i1~1z*YcBZ#-Ono)!7J< zbMa3VkQqf#RV@acQvs2m)}|_nK6<y<BU^O3i|nd(m9}23_#Pqz<V(_l*Zlc$#6&r@ zf7-h9iYEVld!5~-V$eCBdhYI+D8Gae;f5o9)5%rv``LG02pRxJpp~jD*<=JL22~)A zlj)}kskk+VZYd0BOC62*xUr=;LRYZ6rm@%RLG%KR@e18PxS)Dn_uO=WebfJKTt3WF zI($cUy4Im6Q~KzI05AeBjMU)nl+QH#bjExtbq`igwSsdcf3MoH`{4`s&VTrR{zP-s zyXlsQOV#cT&>C|L1{f$#08PI<9J$L}+CNzVZWG)%h&xq4`}b8@<eu*OM6p5G=Z||| zhkG}N+hdVAP@BfE%@W9`p9Ya>I*Ru)&&PbX^=d!=_4B7+M>*_)l}t@z9V!WsPuIIR z`8}r`2>(8cCcZHG{&A@@0{--m$!`A8Op>_alm2Z<J+MnoDBqdg-EFg;9%Yxwd`r+r z0Tr9@S=GNc(i{$jJ-dWWL#cORNoJB3EMB1~Hh>W9f8!jHWYFcG&|F|clZ39gjj3J( zy^}k2pYv2c>u}GmLiRxG%yF}CP_`vlN$KgCY_lVm#+;jW1znX2frgh_{n~F7uRDj- z<z06TIGTI()2=Qi9E9ie<M>ltkq-Nx7>ddzMU9qI0j-G*&(#h{DokOR$h9%`;H9K` zuL5?rO5~br0pzlz62paGsM$5|Xo~vgylNxu9xL@h^K^##gTu*cb-HimS^6c($==3k zsUVx8O;mwJp&n5XNU7{8^*jtZ-Ccea(q26paCfsO!X^*nA$zw!xt-r1gfnsh>oqW! zA?RSNMjNim!%O4!+ii!SsqkOwro-od9d>(HR+D?_rbvNB3=utB;Ue{Okgw~t=kUuz z+<6<eN}~1JX#CdCUs`=29+Bh5Z=@d#B!f)pw{W5gux49ceU@v)8Zz>*68MHi#+7S{ zk-j&@vrKhI|5gW19)0PpM~m72x3ovxrNu!6Kk77j$aNSzrGQawi1TWRH{dbTpL(Ec zZHeT+tBpYjJ88QdW#i%|ojzc8UaR2{oF_OwZ{;Z&5!C#WiJ17|vJA<WLb?{glHVQF zs_=uu&*NWQ>CD?SHpLV{l`UBAiWa8%NTE|$SA)4oMb=T_d||^^{jM<wZCiV;eejQT z-*Et%5)~Yl^0Um1-#_ja=J&cb;gV>L_LuDAeIy0Rn|MQnG<PZ;MnJ{E20|UUZ@r3i z<Fp%}%hdna#*J(}GucmhKQ0*5KO^Y;wF1{-Or8;|?5lA;`WEUUVB%$^RjFP&n=r1y zY_I;kw>5t3*y)s@ot@-;b9|7Tl<+4U3(DUqXo?Ax`ht0CJ)3XxlkX`S)Hie(-!BPw zW2TAq3Y+fuqhyd|I5dd}XjwwBE>H+x!z<kBlY;*+9b~@|^R_g1We^=L!uQ!_ys-^W zWG3IKdGO#2!3>Dh1OcIdOhqf}>L}X|s$Ur&DP{-r^R}l`dj_gR?>7t`?yxxlTI}Da zsS1kolH;4Xap|jlCJH;BQw789c;_sdVKIV+^%6EJr(K_#f$ij8yipWamZxhtL6O$T zK6#Y^idKp|z#^vWX6NU8L<L0=CnjYm)#TjS&1)6El~i>U?gJVZ6v|_2aoCKpi`iic z>xs8;SaFB_DF0N{PoXsp$u7PKq>?L$1`~@_bAlZw%fv|HO>9eW@nsso@n~_2X;%&Z zRr}-Lx5{u$w|c!ftHL1Fp+g?7hdo1cOK-*AG@2O|jB688iu0&1|2u;M`n42lFg9i@ zjsITRzF+zG_qoL8DYaCgon-joP#`gkMLweiAg+X3pwO%gx3+4rp=_L_Iz2nwqelAW z2F?mSou4pUC2pqX;NIj`M=mHTi&3+XT4JS+=+_|I-&>%nUD6feZkhj4b0KZ!ryA>5 z%lb7~`a8_fDz@tsMAbcN)IA$@<7@FPVf7(sx1#X)rZa!ky(yXQ6|$oB_RqpSRRZ{e z$&T$U7p@#Keb(brTDm4Sj8i%NwQ1p@kDwIzd9bxu{p__a`rULhjevKZIY++T7C!Hm zt}J}$`KX&$`mtt>5WU-{WbQ#^pDt^Jt_WfNFDh7qO9i9<-%`ObEB})U);pM9Y8ZP* zLtfh^L&W(1q=NC+)%_f{>u|i{n#(Ch9PrF-@B0^cqqj)&cL`52{hEUQLj}(?JyZ{9 zdC{r+&{7}Xd0|2jmbCQpL;f}E+bA1vwqqA_<p~nR^HGT&KH&?!_?eT{b?@zX@u@=A z&2BxbG097~?@m2!VKs7H>pS5aZ4u1#_S<RSdpgdK>)W2?UD@gQ^14qTMiqI=VA{3+ z`kUEu&YbPKc=@5q<K;?fsVwEpJChF|1Y@7T#P%2Y^M}c~4@Dh*OjaoIrD~$n|22Ai z#pNuBY%16_@YiQsq+Fbc6gOOdor*m3mSpXQg!%wmq9T>L!h)fMG>KAcl%HZt(Tb<( zf4pGmRso8#SPK+{fObV-Dv&)T7r2+&cYgpJ^NpQj`h8av134uO#0YKavIwQimQ^-K zj#xjZn14sU#T_8fUpaZ6kqpKw?i8`Ef<JLzJ0=S5kc(yeS+7Ha3sqgfN5hf=ukc;L zzAH>zSGyK1xTS_Ud3955gOR*Ver;iC2!-P<*|)@bZF>pB(zy2q%2mZ7O^tS!bZc+j zD8Hb-*`S-#SK^l6kQ5F)MJi_r9%|T^0CGUy81=@k|IshVoNdClAU|f}S{g9th682~ zp3{mvf++(nZ+>W-^@`y33v{6$y<dp6eGD1R3<~R5D~$Nuy-|0-y-Tc>$E^extnGb$ zb3Wn=w_lKT_kopiRO6%nK?VP>e!;T6qlhQJp2mNv;OKZazyC)n_<!{a6y6j6e=3;x z|8c({OBf;6*<cVAwUu=`aM<j-&ajRyDf^dUAn<vLH<by=j#64O{pg<uARDpq8hDe{ z5xWXhhAgOS*i`ynuDR57$PV+VG@|4wdG-luGf~k(cGOVeaK7Ypmz{-dMqa9jE?Krm zMinOrxO}83ET9NSp_cY(&4Dr-I0XFPEkjRepKt||sEWRqp57%7M6w|Vc&Epyym|r@ z7TIPOL$rgkMYy={;cO9})IM&!Tk_c<ANga6AGb)3QlpC9f<UbF1vwJk8kjA)t|bBG z``moicy_AakAG0|K-I~YVxs#*^|;i^{SB&~;5O=GZ#AQ#;h;4^kjD*<y(w^I=x|vq zPrB@ySbOo1)n!+VxqcPO3p=8y-#@uG6)P>R0k=aFyYNtg*<JiwoUKmg2kj7r5!6sX zs4;ptZlD6a@}BNCmEi#;h}|XHSaO(1ABo1B9L_4dGWFlI4R`F`?o*3xe@vn5AWEL$ z4ixsgE+z8u{Sg__N?TzZH=He8MA@q<Z<h5unw7sha{J6#|M3rrp+Z!pGe_5S_%B8V z9*~N*gmZ80DzqHl$5{N~P&b;5hyqa55-IQV6%$_=hb`b_g+dNJ027H=Pd=hKbUSwr z4#;jM-ZEy(^C#}}LgjAXO2={cacQOm>^Ot>+<md7o6}?z)Iw9N;DFG<S&Ld*-3yis z`=xQSKrHQ#E%0b7Cn049d(RAEH~`A^9DZ{111B9f&^ng(J5Un5*J2@recjA=RG}65 zHkKL7Ga~U#3<lHIj8n^ZM6L;q@e)&`{n_4K3L@NmV!SiAojn1O>o{+xG2Ty4XeP<z z>*I~uR2@^>7NpjThrJ;<MCyo5BwP%y5m1E|0Esq8soAI<*Fn3|EJYtcbx*?r#?y4k zqJ<)OwF^d>?zrnc6}zqKH0zg>LbYSUcMh0oDF~$Yy^(1vpc!{GW0IGS0IM5HOHTfQ z1@zVZXSIwli?Y*n`OAaCM`dg@WA|Jr5|WZ2!{EaAwjr5xckCL@-grr#KPk=#$U8!l zf+{c?GZaP-_3K(S{6afNK<moqZ|4grpzI||S_B5-esu^Q-?=p}|AnpXIOfV9wJ3FK zJ<1M<JO4mohk+DFL6``kbSoTK#DNcB92O*gXz;o6ioUk@ok0c4yfi40cBasK0v!pL zu>o^8<7)Lbb0v(#%=w82c{N_9e!M4KjKuZY_y?Kua0~yO_E_$_-&ERwP*ZWt{Wrfq zTI8J<5YBIR?LCxhH?JtocNEXye;1bHar&ul&bpdYD&5YhgVzRW1^kq!rPhM)T--0b z-#_#HE;Ac)3!J)V=8<e0f(0Wri+4ZSuAtMrQ-wOQWcf@NXoyJ7S~1J|#_Qgg?tX~O ziIa)mY{9V9(^lB<5wH-_<6h<uTAh=en}wwma2hv&aUxhsY_id3c090g7m}Z|d0yL9 zKPjW~<BZUsVxoGV99ZAAH3qY?LnI#NAdCbsZCIo|Qp*3B><AVdMNR9feu;2Ma<*$- z8|7bn7ouf#AhVxrf&mNlGAMcF%`x5o@X@)MXR~p^bs*d5aO<BnrEl^A4FXC$@KK^7 zgfqJO;nit>@dp+^WdI+f(whT~b*jA=O5EsaqU{?=2iXKlrDF~M$YI-kv1@|q+9|8T z&UKGI<QzGr2~^7$WGjaV9riqfAP7F8bFA2|{E75H&NpyE<Lm`)s=1p^kedqncTE!9 z5ZFLOa{<gdM4lH2m=_1xMTEsO1u|U{xLNp4W>9nI)ze@3)-jICAyVH6z8vOxzAZR6 zK7Qt)_GBF51{PDoMwc?s(mw<R@IeV)lIrz=5>J!L+2~H@6)$agJQ0?N;{|V_^0{YK z7#@7xRi#}M)f@cUKQOM^PI{`^Rsdoc=V4K-;$IX~?!wdAhl;|$t`HI7qR1aOWIY1a z)Q4_98FeaA|Fx*{K@8wcfd7csx<Vj26sm>cqiUFF;r$V0pf)T@8$;9P9p<ER{Y@?g zYC4~M1#hOw2Fqf!yR|Ws;%MVrw8q+`i|O3xB{`b_b0xy^`gp<eJe5&MDhI{o7+csG zmEQVk?-XNQxFK-uFoJVCmyKlxHSMNA5$EdJfzR#WR$MUB1w(g1PzjXs5vm56FLj3h zHHSZiD!;*UfLDR|^3xtF@LV%MH{#W!#B!n&(A+Fsw@W5mo{t(ueT2-`n&rm%<3;o{ zxo&gY5&lgU|N7ve;-l){4D)N*LG5(3Hdw8Tn5bz(!6l#{BXiX~F7qlm=G($TSYSSX z{#T;0J=ajzZP1g&heSp*b(7GI`z}0GOUyF>bqRTGMim3@wp>!SxL3f(?+-r%7XWC7 zj1$v$yswuoL<aou7#h6T$w}n~b=xr4`VGxmmH3sm`33$5?u_-URk(Ij;YQTKbG1NF z5k1F}@ehcNC~3%O1A^3#7N}V(2*mMAr}MYp`mgoO!GFS@FHR#qS}puWlNOZ(T3xcQ zeY;YB3CVRoCx;8qHky8xNP+!Ve8$!p(k0J9jw&@^&=6ZpelWU_k=5Hky}DO2U1P)V z|4(|XjIQT(h@DauD=P+%x$nX=T$u3!>fD)elbeZNZ4g){dP4+hyaWt+$WSB$bDM~U zyT-H<P|N#?s7eMJs!~w#zHCs@erb*$Z;#1vGy1lR3FIIq$YmbLv^G}YSbfEuUcffn zXKoabWn9aHTtR}I82}1IglpPhiWpg3h<16<{r&sOAuGp?KEHJ+FPQ5@6EH9O`2Fxk zj$Y_BZn9nhGeP9JghXL8DkL(^G)GYKnUD&_bM@S-R2y?Q2|C3<mmpC^Y?SGd8+s0A z+MPaM_Kb`jN`i^7+Z+#}@71^2H|)dBHaUDsZUqn!s6_8Z4H2!UhT<4v1ebFDjjK52 zW43`i;du^>Au!5n&}veEnK<Brfr1!W9ujo%rMeM!eoaG+x_$jBCZh03AZVXegP7-; zBG&bI2l_9Rr8TL24AldpAxLeEYJBdsny}U=6j20tgu7WpK+gs@7OAVAQOC5(>z(_q zAuk0yzzVG6BCbD);|j@N7gNA1uy^%Y7(BrlBCr&nB0~m4Q^7WUJj>d*)ob|O#H(vU z8Q-G#8B2!#KS*gb*n|%1O&9?$)?i{K&lI&3#bG`c{|AiT{-GO`gt4q{&aa7S*5;vd zyD%KIv}GdI1#wd%xH()``6s3ecf3l{azY)$^Fmi?y0(fGJlA%8_()X)y8&jR%fs`Z zG_~A;lZY)Q*27onke&<{fKC+@JaN~_tiy=|0YoH-QFeL%J!&1Tdv6Cd#;#I7h>`XE zj}RS~di$UUlsn?8@<Q*$reVvu6TJ-A-yw(-p{OFvr31I`gZl2{4&1Xk0HkX>&0y}S zw-vX9W2{Qh#Q;wa0ii$6LuMA;>N|JpgAUg;1#wzuFm3-sg8s$bduancIAE4Bj%kPV z-r=qx1Y2&Bf;)-CG!D5KK!a3jG`=#g`eM|F?{iAK<dg(D=Gu<x)hiBk70;k2&v8di zkfQ_?SO0wL)2RTtm*R`*10;JIEw%|t8d2qZxGpL~fcRdI=Rox=^TC7C=)26I$%33Z zDIgW-7$l&~Xx)e3bgF-Ezj6SudeA1cA4G>mGmq)PU{wNy?_D4kshZBkGkLfe@M9cr zZ7ntblsnQ#cMiA*2JyLSV`Pm<wLBIANthn^qoeM(&#c;)>Y;PPF<wLjml^INpruc` z-yYSKebAl9tpK?4ISSpC4g&K;6+6@jWOJZ0+L)VIevKDK-hJpMCJKasMPp7Ca!|>5 z%;-5?Ke51LmoZwrmd|ND<`Di411Lck)1l1IIAlbihDpI79W*^5Ul*lo{NFPzJ|>n! zEP6MIeR{E%JLbR(hQ<{gjs;wO#ZajnPo95Tr*Pk{Pum3|I4I-MfQ%|0P{F+B_~Rjv z?6(e;Z_4Y6c|r*A>3tVoZbhxLFA^^XNT@tj2t5AJu8*2wpFlxci4P_qMQ=nMbAkyz zW6(M*)!BwaQv2W&V!Y#qSE7q_Ke+UP`uI=uS_npAik$SP(IAK4KI@FpDs_xE2Oa(k z<-viLS|`$5Ys{9PoVzJ)yFTRf(ccatFpGn^ut21bMx!T#dlOOl9H_1;=1CM!IVQN8 zSUY7ZvpSM{hC=^BzhhHFhYLOiVfY6$jJU6?JDF%Q8{y7EOl!MLw$_-IJ^u9ZK(|xm zHgNY>wqC|%NZFeV^WmE3cvLGPl8S!<apm#uVs%s%!m0`e>-F!BdGAh$_x8!df-jm` zx$mK?iuUQKwU1K@pX6pWFw@;b`0MvB>J;R%<mPs68<OsV^XnV6iv%1J)#G_~Z_X^Q z3~8_tFXG27WBKiG*K@sA|Ed_6AEpeGZx)NLC5(Vrs1`zGE&+P4FLI>M$-0i^cK*P& zr<=K%{_9|9WzoNa&qQb{m=p)3ptruB8Ky@9aMa*S<?t{u7vn$4oO!8_!NQ^P@d5rp zGz0`DI<2cng!DV>6z0(hbC76(R2SY2>F52afXSab^QR52UlHxw<+(MoVB1c#u~JGW z!m6WC9uhzx2Q{&tl=pP0ZmO}|0dsF>!PIIT#CitKUkKp($@IKt+`=))q=)K3(mp*B zvV}5CU+$P<fmfEzo^-(gSO9y9WhQn*8+MTp-rb`A9lFfyJKoAdJ;U(YzJ0!yBgw~H z-q3zwXXTiUfu=ZMUZg)irGtJh2)rt}V5vwnuS2(Tkii_J$1Z9aAvx|uFgn0aSXttt z$^tSkj(>ILqRQ%rFz+}|19Z?0EvVnfht6O7uJqguU?K9^Nu6Yr;_=m}eBfmy+%Nsr zF}=Y;8Q}c^v56y?^$$)!uAaZ$Ii2|xxx<(=VyE>5$qgL;(i|9rO%Y%&D_OpDd6QzB zA_@~d1>S-~j=Zu^B<i<2He+RaBv5a~fIGjPwD~NjdvqvJfe-^s_kK2C$E|g{nl-1X zk)skoOs;;yq&xKwJW1_-<u|m|-?w4;<F`&vb{sX>3>9Cv`DWQ#vL~_bu=TVIr0zyt zLFKa1RNsOJ#Mw3^@|{Y?GzLgxPQ*=GkpAkdKU{84`FNXzxWjnkph)j?ret$m9^P@Q zxGK@JnG56m$6LN_^QcbvZ4u+FD`c6<<_X|9&Yh9$RKaXX0^gMRb90RhH9tGfprwyG zSvpj>PNuxSD$z~_)J;afJ;uMn34W3W%Ob$g^OZUM42bL7Kjvb$J{w0GU?@>Mp?^5X zAt!~^(HUmv1pkptZMbBmVNA5atiB4=OVV%E7?pi|7cymw*_Yc6+k$QbUz+uh!N6BU z-3vDePaAWSM0oy$Q_6Ds8ovUxk`Ry%wC9_KP#2dXHrm~gH=vIfo3m3W_@(s81#qjg z`x8ciQI&ay%;m;!Wcjlh)xAx^JdaB`u3!5SO6x!j<aOp!=tXf!wx@^oW*rIj@HnQD zx!v#o)Vw;(yfEW*`FzsZRS;w6GrcYQg7}By`j6QCryxK67S=6b;R)=EBNh*G9*c0r zb1u0IzaRmqo-e=za>?aQ8}(adq6OMK-q`Pd;Rd7iZ<^U#WXvwaHNX1UPsb|073~l4 z{olydJ2C91c2nCu(Ww5<2Sm=iMouTQf*gxPcYf`wBMUzfj17JdR*G1r@hhK@c$JG$ zWda};v-Pf;BT>YEAy(xdjO6}-)e|zv@W^RwI}oi->~pOF|8M#Qwz)E9SD}(_Yxw{6 z3zF_Z2IAEG9(i;DTq;=Ru}oVm$Krod!Epioq*^=-AI}jxY)QZ1DkSB(>Cxoba%QO1 z^TT}hHkkQF%Il*y?dYF;o10#rma1#5<+BYog$|ykipVS%6nr}K=*oYo;PXag7c3Hw z#r5?kr`d-SXqI(vn47b(DC*r-?;51d`7v0q8}UeibLDU-rmEhth$dq^f>H}#YTrNq zdbs?>=7Wnr!2n^y^XSt{Af~jE5Ccb&Qx(cRa3=O;7k6a<D<b^;{D3aK+EFB!GuQ9l z`sm!yS9_0$MbzsAbGfsBQ+|HiFTH;klWd*%=W)q_`tsygC=w4DjoUzwHOKENT@q2S z$ZhAi&~E&831c={E#lF_PW<u*RqPDy$FMcDF>M>slR>REIRGB8K%M5rRm6k)w1|H& z;e*|P1|z>t`l<1nFy35p#9UwBXHC#EZJ8!!rOL~=;e~SwEl`2r1Rb;<L-m|yx{UB? zAZbISb0iDJmVPN~iquWtLD`kd2!_{}UwpJuC#B<DimkdR@!P%0&UESCz6&)VOpEC0 zm3lrO=o=Xn{ZGHZ-T9UqRvwr@0%b=YXED;?n1EH@BqoZ$qAv0hN}Z!0SXb$SargSS zCQKTx*Qov+yhg&HfWlJ(;cxSGCn6}Kc&yq%u5vuJ*5Zav`{I4xrYF|-qMrxAd!;Su z>9Y-WBsL9D*S3&LYD+ygLVG0m?nM@E1pVj}f3-5vIQ-cOMz*aHrNGrx?TGvtgWv)_ zrLdB>7<?&;kWF@IJ^ChRn`P&bbFAZ{3VCPC)?9#94v|P=`6nq9jte3x$QbK}wq##$ z$suR{(%?eUH6d^JPUF1}Q7dpmyQq)S9c5x!DZlc$M&%glKC97DcRjpn!Ujo1B=lGu zh+N9g^RonF>R)9|TTnle?(E8wJL|<tZr3tKg7s@5OwOXa_UN}o?@4po4KGdCTSY(* z0b1mNoHyPkZ@%}6$=h}rj;RXq04#v?KDcaIjr#(W!18)fV**}WWw<LYJe7%Q&Q;$e z4bl%+oz3$MetjzEjH;OZKX9MeH+goCv;Z_7OFS?w>-T8(s5<qT<<%}rDEST!YF`re zxIm8D1#-M?#cWV4^zwi_7bc~_uTPPon(K_I0n)LgKR*^|(tlmSFO90j%UjzaDH5*K z{ohLMiH2(jKB-oEek5kuk>vr$t(W_{P*X}aVqd;7%0_Lw-a@EQTmB`Dfiegng8DYF z+4QGJk;0Xir0I&fzIeWlw~rsP6#%AA*=(91Ko$*;LUIqGcCOJIlpQE1epl)<Ktnmw z1YmFF*-5;cRfb1yrd)T{CBoOttEs%g!l$Y;4HM~Zk&Raq=rC26f)=eaYoS$5fwISJ z>i`KhfN}+RM=v$UOkjedEXNO~F)+MuKZ*<((`pmM9@{GCUqOyKN`0f{pO#*;y{S=P zGFCL;d;y~H_UCc=uvK#Qs61T%je}M$hHt>n*<hMr3#9wYs!VT)x{rwtn<mmvj|j^9 zfp6KEmpFw4Waf=t4hFt6)VyJA0o=X=k67=_QM(vn!6#i5Rnus6%=88=QUiAALO$J3 zm7M#GOxs`^owywR?9A6<Ul7OUL>^{UXt`iXa(pEF<f10NIgu={DW9nX)(6U+W=-~t zTxl#T>G6qwb+oNqpEVwi;GKG6vF56q9kYXFa!+FK_?MA1BEy?F(7T(RCgKkVOg4h> zXPkOwDBN@3?>MCXE7x{-ydp4-L?|RBW8BvxQxO@dR=r*BXA_^AJeyv+e$dF;zuZz( z-+8Jq(bJk-3ld{&ymd3m<WFkWmrtK?IT}<y-x(e$lT;mHJHVlxBzlHF41yo_h#uCy zF(pXAEh>K<b5EJHl76e&xSzsl^&Ty$F)YYID#t`4O+y39hG(qxVkC)o(!<J;shI&f z50<{BK;&ef2u2tb=Kfh8ly}K5=}kyJ(vZyw&-;DdP;fg72vPt@NL)2t&3AoiIQ^M{ ztWi_gwDa#grbVWW<a7<j0@^1oN7gjGWs#Qz+z0>>BNFGbZoJ>tZ~0*3XgK<l{&rx2 zn;HFLur4SNU%T*V-wbtIb~T%HI-%Ye#`H;yMv<mZwxi}NCnkAj>ns-sl%ii)YzqoT zZ4_42bw&B;ZqR?Gd&jz;XJmNt3W2C`?V5gDUO)o<^VLi8%DFn*LAGPkKZ+H0gYF!X z`WV>6`?cY*YI?NXzC#;{T|82H`SbN#z5LP+MygjDtO0O;cHQ&NY%eeWf_{zQ1Z3ib z_SBk1?NsotL(MRV4%I+!v-K99PhRt-8tbN<yI!j!h3p@^Tyls{=^ekA(|T;R=)+Lk z>vXY~!Gj_=*O!6Q-BU%wJ4FgN!}5_m-P3)JtzP|MZbim3AK6<LbjI}J7HgJo31P|l z8Sb-?JYjBz&lCVVrZAs$ya3131pBk`m!{{R+IHkkS@28WF_!<U-SiL~E#QEQd1zB$ ztDU(*Q&W2J;&twc_>Z79c-2x&H%Bt;Zp3R}-UHVg7q40On_W!)5-iP1rJ6J~&+dgP zKKwOX>?=4uvcDhhE3bIx(tzlr!q_s1@f!(t%GE1$)JHv8<riYoeJp#6Wh?J6{x65q z`gsjSf>%`Rj85!h=E!{sUcKHlD|hqQ(uLoShVJP?gfOi@86}A)>}kr){B&T@a^#3z z@^qy{Lz%rIrag4H=Tn4Qm&?Q1_Z;SQ`zt4mwoH&!Gc0@Vm)KFenirA!@q?X@zMH<X zGD7=5-FXzB6$dE}_)%;rcOiP`HiAnV@)LDb7tVBuzv5t{lUD$z1hOGm?dp*Ju)wiB zp>&empacH)r?=lpy<id41zR1WEV105*O&gd?M-w+_*m!Pa5uvdIXc%;%{b-y40w>g z@IcEvZokUyjs(S(HzdsVSM~LG%!eOtd}(>mTQ2vtk81W<bm;_dNq1>+x(*{P%O9y= z0*ZodI-b{<*LwZ?Re<eR3)V}L(qorgJ8QiQ{pb((#e@o&>BkbI8%PbZyCBS?mCFXF zN}9gv^__Ah0R-b@IyGALanYNb6wcwEWM~8vo<xWLJplD4P&`ysR$}kj-loQm^g#6c z9jg!@B&wsjRCD$ySHobtKIB9kM2>?9VUqkM$j&qiuVU^9f`!R#-7b@Ug+Y-~6B-T) zq+k#OGh!A%yF1o!!v`7_MFNk2|6##&7NJH5kZ$;Dlt)`MCnrI7K+jaHjt73#1+jmg zKsB2wJY6mE@`*-jKLqa$z35E>_gP*khB`A~ouOG4z4}E~PpryBlcEssXNtXcO~3g- zV;8N=3&8&*W}ZYoI-B3AV?B8Mw{Wb4rQg_5l`>HWdzu8VmL(o$1yJp4tsTkeAV;+m zwKh_&4@exX^R2BUKqpv7Ap6u|dm79u&c=Mg@(hFQg)z5GX`ce9aZ!(b3WirC;Fk&1 zPz{kcXt-QB<-{Upn{dY_iW;zHCD%Z$$5=Uy!@_qpBMcvf1!<n-(K=!=05l-}qJh)* z#Z{ez2-O4eU6$q=L@jTK{v!O(2Xfp*+m}tF#Gu0$h*rB};KC8T@!i7xFF#?GVU+$; zV(O7YU~dRkmFUZ%h8L%Y5#i3nGM^eaH(Z+_#7|vQV|OtFuwvff*sNKJtG{o2y4F1; z^wgli+F2ElB2o>!Nv4V9a(Q#7Uz$0_G~a^Jq#gyH0}6#!$bm)ui}n;ZiM(7Vg?USg z9TENy6MmG15L5+1iRm^hsPhIHJE&j8OT2)jBFe_Js>_f0AR|w!uWt7M*aPu><Ib*> z9xJ5W=@!r3TVaMg`bdPiDxk)q+96@p7J}Uq<Ii}7*lfpN+{Xnx^75{1OQZ7hOv=eb za`O~;Z3%8pMg%F*>elqnvTh2kIjN6v^=9fpruMxg*uFInF@%Kx@=Ir81SrdDJg3Nt zi%{ngQX(CChJ*NY)A=H4Y?-Wb`KQzFYSnW`<Tx5|n-x<c!5SkpzZ=1wRmmqg)UZ&Y z8@10I^*a9Y5M5>`O`G`1SmH4Sq9&4<9Mlp+qt=g&rA(9@&VucDXn8ll91_WvQ4lKz zxyys^S({!`Yx<YX+CLK~LP|BzE=a$?J2BeYQoi&u$!?wxP$ve|zQLv1h_ct)<~ISG z`^5_SnO<C0#xX_+@e$7!BYsavk|Q)9s#0n&5;4_N)-#90Id=lR2c^#+eC>fu8L`=2 za!?n|aOGIU1WX@{m^O*+4kWrszjbq28rm=XbvJ-X?RT0vo_&Pe@ULO}OsfRlgkpEL z*v9Nu^;tzC4+#;+adg_FO!>CPRCn_ES$2P&*%xHAn8L@BJn~o+(#Q>3(`?xmO!cLQ z>b-hNBN~=5dtwOb2x9porQOS=(yg_;u2g@vM%t1+sfk%1X>j`Oxr<w~e&0OX??G%r z;VvBL%I~?re99w@*}y+yjY0F7fGs(R?7cgBZm7VVIUfmA_U`f^7wep#D@;hE2E!K4 z>s$xub1{Ajew-5f()k$5!q<oj06Cj@h34D3kYZq(RP27mQ-VT+nHrXce_P<y8B8;) z&^vV)3jt|j;r(&5Whii96?xy0Aw(WpED01ocS{3<)$A9UIQ&iQwJYTWOS5%+QRF?` z!SQ*@Ey+wH*YVb#!r*)}lAGR+OX-|g45hw!StS5aKWr>}ghu(t?Ra?(ze6nd-`A<y z;Q2fXl~zz@8@&XNHVPk^Y%-XOXtN`;(}M8G?E)!p!_vKJpI;-owti0=%zWLiECQj> z)imlsrwSe2`HmX`-W#)L&I?xz`Ksy=0lfOv)u}_o7eFGlb?*h`_J7dt9{rAJ%!{Fi z1rQg|Rd)I%351XHL2q?_S%Zq@4BXfs{@6zM>2`611b`ZWmZ;&>Gi7Da#Ln{5qbT{= zTX}jzeis{W{#t9?kD>dlmB50RUoO+d58S@K`c2HRuWOUz`==H5w?yf!nE<y6NxF5$ z>3v$Rpii>Y!dfd?Yy8zNV|>fA;Hoo{3mUs8zY?HSiZnp|49<>4^%`99Yae(e%uD6E z->#m>q(0}6c1W@C<2^oJz4%dXW;r_aEM%B(OG6lh1(BI)h?T|t(X+zn4iZ5RQOA4W z*BythKKOUSQdhRLd=C^SOu<nvHoW|k@k+}9=G;Zm@=mRkoDs6+c{Jy*YTur83;G(# zKH-^Tx#2%1A*5#-pru1C<0HOm8BY>A^@q!TH{7W4TV=YeYVZrOZZ#wle1*UbiX-G& zz)JIb*1myFpeTr1=9f)LL?jlkuDN2!#Tp64f#c7wQRlemH~EzBn>IXkdu0XZB{-Er zlm9#GLL?Wsfpxr3C>pG_EUwyL5H!S;@Zx9?7hp&YVY4nLbiw+x&Z;7F?Gfvy`(&Pp zg|JYA!}zxc=YCfsdf02ARuay`GlZvSF8G(K5h4oMccx{1@OAxL7{gvx*}P-#t>OU; zpXoqrfvMu@>o1Dgq9HWXBeIFAh`{+$#~XZmE$fXOigReTkL<gdr~|5oTs)a5YI_|U z>LaY~Bs@SekB2$$HpSh^3^GGr8F9Nh%$Kw=hq_8!FCpZ|AYvQdHA;G1I3A)3F5WL= z!0wkz{fGOeuZ2zAyCAml1&?sudIxY`mqUVEs>Cgw54!d>0r=pyamfZIDb(<8Z`)yq z+ZB0#`IGY53Fb&4;&j<8_F{*0))2QE!^)nbgnG|47Chpe51VDQkVm-RntJp&QK@hK zbFi03TbVCMpUR6U2`g!s=PT1uKZH$P&nMn~mC=;l@+){Qt6Yk!d@COL(EHid&f6d5 z{egl(bWau&D^z%@d>-0Hw&a@&5dl#aicDKP7fb>$q>me9=DgV5;~$^#6Gb(N(u)+H z?870Vw5`zp>3P4Olh9a?EXI6HDQ8PY6G_K6@~_TsF^suCem~1x%sAx}0~_uYPbBjb zp~WY;ns*YGdi|=$Arz1TBLSR}pEDv0{1=M5eE$)3c1|El_pJl}p}eUXf%9$Ck>dTI z)$PB0w2gH3N=3~F{WC<mRzteH+Y3&(n3#D!>V~Nh7UX;|RXTAssr{tqhOQQ!^f`QU z!|<V;$LycNC>pkh><to%A~sDfc+sTrj5Kl=#bdYm>&CTH1Q@%5Bl6>A<s@<Skw1b> zOi|AC=~5&A*W@0o%_A6kh!&x(U->1fo)zDZ_~+qUN@CW@V%Mjvi!>(K!4a1BExLg4 zX)7N16#Wr{2l$!cWMa6N8HIx+HU|qH52fs@{=1^~1KC?qz4|gwvp5aA%XNsOz{f6h zqW}}?$!gbo@KF*OIr+`&Yo0^}iFszMU6>p?vS*9@;ss6=MOIo&!nyvoYK6tS47mR5 zSk;n>h~PI@1MUigyQ@QTSoTHQUy_95mI2D~K8gPd+$2&&jMLqaqdL@QT!9-;#EcLn z@iZu*2V0!ZKAiE_oF=tsl+l&pan|rSP|S6>hf-PIZ8_&U;^nA@QCx?+7%Ii$ko&$O zqEe-4;C`D&=_c`cBhy-j){Y-$W|AqcvAj)RKSg$alVlUiu^{e;-?c!7Ya`Czp@|4l zwk7K3pSLf#A|d|Bk}%YMY}AE|x8u89TJ-N``eNrPjEIz{I|xEtdSYBY#)U$ENk&eP zim8$8nqo6##%p6|%sKK#(aFV)R@N7ZYzn6#F;6@+!4Pq^26={#NCJKqAonPAM5hro zy`$T8absp@ukmS4Ep?R?8e44G5`_^>l9)ZtyA#kDGh+x-tN(eQnlarcJaELa`T?bD z@j_eCuZI9dk^@Qy_DZ9~UoTF`dn26*u&wf6{o*`#s^(Ctz@Ruv6AK<bfjoJcdVUuk zh5LTa=G4H`lw3|grr}<W#L4)P`&LD^HN_PE$&{G}1oqz)1ptgi0t<I(&;E5i(Y2RP ze3+@aGqZ4IKT9>KIqwGJ8tq!+@1bC@Mwe*B$=Ha{rn+Rx`0FcqBieylui~ZhPAp#A z!r%5~{Y`b@K384q;zVcv^H+0IEGG0qtoDA!u@`I}uFg&AS|~@#?eEq9^RNP5)Vu$? z6aHsm|1|;`G1Cl_Fg#4`Bf~}2dD$HK!T(LaAZ%M{tU&$by~y|5$`i%henE5C*MpN~ z#+SA~?nM(U(kx`aGCl>W77Uvrw3+&>%4~yMy<1E8H}(1d_6s(@9a>}tTs|ne%ZjwV zA1c%2S;`81LPd;gN=N+AeAS!$WBb#GA6o3bGz8>$X4HyBRi}f1W6;R#CzpY1D(-jw z+b<|R8v8j#G}=AwBA=|-6&KB=_KK7DFL3(>9~bYPo4J!Cs2esE=U8;dBw9-U#Q;@U z>%wot?X|J9AIvjZN?K=b6}sQO@W=Q+{eoDnkp$l*fbBYeec_Mk&z;SM`xn1Fs%!TK z8QVx3s1yGW^6vZ_>c{{4_-po!@gl~W#=bL(lD4sLEn^7@4I+D^5L(QP!B`uTEotma z(hyNmV@;w4X;-7{RA|%cn)m1PIp?~r?{%(ozQ0{RT>pUMhdF0nyl&6?!}$28@1H+? zTHiy5G~dsrBNXEPbzi_ey3B(~BuP5fQpx{Y6&wx7Ai^L3dL4kFmF#)kt|asZU2k?5 zA|)AAb1boMD(}mX+Y<VEpsC{id7@Ril0$RlgA3ZO_1+Jfs~#4R0tQPQZd4CnGCR5O z`oC7eMQYb&3|U^0xhv4IwO&*OzY#hy*n0KZKWcZQ)6IXYU7v?HMQWG!e(<tWTjRu? zxX%j{58JN4y+?=Pl=q6%Zuus>p6|b^;2brlMtdD{&4a=t+300|7RLwXR0$ReCwqo! zMej|AZ?`TEP|dQWo8v_v1>`o=08NGb=@~x>w`qSz`$~xsAMUwgIk_R1<PMkHNJfjP zxG6c*ocr1S{gbdKV|~-T7TDK%0sO9~$}7zVt+ptwxb(?wKYp!!UVQub?YkfKM!!=p zS<afyj?f`<TQ5hz0;!DSe{8fTS<>!v#mpd;LS_WIwD)o{F-7|wTRmUfB~?>gd(&CX zn{)3nNd4OHZ99g8-)EW4)V|N&`EBm~c`{N*76pBwHI-wpSvQqSJw#Q%K(W=C&U14Q znZD>5R5zXP9Xmf=Kuyt^DLk4VGE)>>T{lx4ezV2u60Kinwj}y#$n52~nY!81GvDTC zuh5aYb6ghTpDMU!{aktG)`htWj;-!|WuANJe3eM;&R2`7;PW-y6p`Ak%nx0ttF5kI zsBgHruyB>vzplI3(DF2N@!EgX?!w}AK2mRq*GmXnY8ueIy3{<hb#dv2z*g_Wf7I?j zRq)rbiyzvADS98<|D$&QRRv%CcxSm^?^DN@f2-ZApYHztw)pAZe^I+)+m@DlK)Zjd z-IYGMWB)z1Yc|{P|3K~Hb#<VAk+*J5*Sd0cu9Y|4>S-Esa?*x|tl9%tabE^hWiD_2 zxwJWbw?HBCwKA}&ZB~-6a81jtNF4$m5lA!TEGhGCU^Gr2-fH>l%P(h_B8%JxL(ED) z?#Th*7hG^)ZT*Yu-ybu$F9&u*eycf4L!>PQvNv(P*sp6z#~gv{Lz_8E=y=if0V5qa zV@bHqwE?Kc86I$MG?dY25b1o|>orrhb$|+NmdgmzuN3dNg9bKk%?9EO6E8USk!_=j z(lh;~p?-d1YNMDZl9efCB*cPOJNVXy7bo0c|7TrSQzAAG43z+7;Q?K}9%NoTn!&Z; z%F$<>R|t49K3b(b-Gk3d7wkYQ*T>=9J>L;8K2XJ8Zq171g-Kp>^#usdY#TXfY;2y| zqDj;)mZ)`|xTFlGeMj#jT7y*?eSfGc7zSJoNLjO9w=KJ6s+_TL$t=|j%5w<z`E&sa zsnX6kX3wHBFc7|_E{qR9s9A}wWd#C99UgkV+zjlZT1XU9SewPvCGvtxwW!Z6g5X@a zR!SdPH{^j&8BFCpd&cZ(7e4sG{)FGI19}umoEw^?(k?_8LBU5fygH$dqG@5RlJ3OY z0t|*%LSTYNw!X~LEA71+-d*blpt>hPIKxlRo{?s|Sv2q=$C563vDbUo7GTQWe#d^a zp$o@fx}I07yH%HSpu|!dy28?W^MmZH?HVfr#Wt;SbeEEM<wq)~a4@oiOW~K~yd`Um z@k1O4QkdDVZ?C(Tfz5c-Qg+=k)n%mBC5gJf(rhEbAwX_iw)Bhi;g(wWHtZPPQKnMw zce$gH`QE)~BY-P6poU;Rl2tg^V4tPucT*mB(B7GNJ-8I+q(w&EwTyl1rsn%gm+y+E zrAggdG<(1Wk48t+J$EhiH{>Ya($p1;S$2>}2aybtir8LyuZmz{0C2O7t<mnYJ+J$M zodr|Q|1;*}6!pk+ed=UsxH#Ey)4<a^_1zWq&kZbV?ZJJ~mKzGR1A&hrucy7LWts%X ztj|Gkdo!U|O|FH61w8a=_l(YvRI$;6KOD;fz&l>n*U7#=U0g{`#7@s?GPJ3ix3%@o z+6P>iaXr?(*8h%H{8h3e!yJvbAih@$0Cu)pxXk5M3x}_>zMgPfZ-&<B$E&zE4LYyi zvLsT_bWOG%$BTcmVMB^6TD0k<zg)(d+Fb7_v5NN1bO+A|!#CKz+UZzoc1P#0`*yMx zs3WItd@j_NHZkg!S^DnWCOnxf(~Y|kgy&m4%{PH>&J-fjE4~Lb&%FM5R2j*~!gYFf zDLL6V^C|26LvNmPFj5ky(1X&yDzrSGtv+pw%#)_<w$C$wV3;MAGA&uU2j7Pq(BOO} z$-rmlOoy;;yl$DMfj$eSN|xn~R+)Ozd}09B!}iioQ@fZDozYOvkZ!r$dwu)b&V&W8 zik}%(+z6+`W!(&Gh-@#J25eRY>@#IgdfsepHog$*(?ctqI?5uyp@5c3<@jC7Va-jp zQ-N3N>I$8bHIF)D9@QQ^*XKK1%4jf+W>;Kz<GVqJVvIYuR4!#px7fnm#Tof4@yO?D zP{*t2bV~HQo?91g1_X*9NQwPW2HSSw@STL$GgVYJ?3UKnR-Xm-=`)*2Qz~L9QJ_@n z2gOb61#$Zzg;+~_dC~SovaIX=lMndvm;P$9sWy_6#lO6bH>@w{)lQ5to-hbo?tOYZ zjW~bOK10UuoRv~PF$H+tBlTT+K!bbtOXD$HTx_kX1?QZ9>ghjA=NKxwwuh1NUK1(p z2=3^}UBfW`w?ma?2wiJPm!q2{z9B5-p2Q^i#qi~i3xn{TZ$=s}#^w-9-C>cFI_VzX z?eEzKJWSzt8-BfvCUQA_>Y&t2#4%-W$y)a}hnrUHf?pCN_w2eur5RjMC>NX0>->m1 z>68CcN@|2SAn!33^uhn!_owyu$zDV{0o^;Y$bQ<7Iw8(b>JdC#(p_zpIUi|sgm`zY ze|<-<h4azjXz7OKBZ{JJfi<L1;@sL>J(tj*TMb%&zuJZ~=QW*CA`<~EBDgBV+g0js zK*f}PBRgw?&j_dEH;Y5)_>zLeV`cc#06aQJc|)-Nwdo+lB$m6J0L`IS5WRhw41%a# z3Ig+FMnsdtOVCi=9re3E;j5j7w*7x%rJx+p6a;RcV@6saMEBxPPQ*cYqDdrl{7irk zlhMXcf&gMLXL0x1BnVdw0!V;%tVl^ZnriU<VvJiaO1;fHpXlz$PLhxg+ZCL=XAK=D zGP-L?R5{t7G^88(bbab};a9(6_ZS!?X7fQ;uT}AWTJkP-GGbjab#M$H|C}&Q#Sh8? zw)WujW&AYBz;7$KR~yWyVryt;+@Z(K*{LFe_7L$;WOQU(T4WanA_t&Ja5J9x2Oi_` zY8pZX$tHrLR>cCG=GC0EBMuxB*q_qMFshY+tpJ)t@HvQw2%{g4dd;I8;5i~*3@~`+ zh5XQ>fY^iGNe#8>P`_lo=V^}y2u<1`N)sdrajPWfG0VfNy$3E5aV$CDDiJJmKhtlo z@j{RUH5RwMnGPFC>sZUCl}QY18;ogzi(5g&7mWclgGEV&aKxLwiRYqoXd@^q9@N1E zR7*2}9R%4dY_+`xZ#txb4O-dfhOPUhebELF0I(-S{2g}UOe%X`0}Q7GQ(7d@2SG%L zhUs=@$(LZgv<o(CN>F121jwqlI{+`UOrl<7Q*c-lmvSM-%QVWF$rux!5FKr~>B!y% z_KlAo8FfVt!f<}-Ae$BgP1}ApDBF&CLfZ~p<s>22@<T@)ipZz!YYj#(#B8sLDXVnp zk-p$mj?d8qmq{1dKM30Q(dXI?1~kETEo{nBB!qI-{gmzc*CQ=Yi@KT<Atbn*i-C;0 zFH|y7#l&uuYM+R?)UBE}DYS)70-xo86?=nCrm+ZTF?g4=AEJb>ns?4#e8U5MM-OI= z0Gsmz69ob}6p=>Jx!jjq1R(-2`o-teW0v#!OHZ&6OnmbsvYCQA4~h*7?B#4q2g;!k z5DsOe3r5`lxJ4reyRr>zCxL%^uJpR#Yv)Ao`Qj4U&Wf_wBTrD!CJa34z_vMVOKu5F z(tnkPHwZSU(gsiD(TihoVWwvy(B&Pf5FbjJ^&xN6h*%c|-KkT-w=6?S;`gU!37Gj? zp0Y%dV0Qq=rTXKxVhib)b}vv6&H$Woej@keaUzo}SLOOsZ{izZK|)qVmyb02d_RgV zjonp4!+ZzP%J9M?<~7<3=PCh~!$Wdt2a>lUo5>h4P5(W%HLO7?k&4=mLSzHG#MZ0# zx_H$#`ybmHQhn^F&CpSFg^X>HKn$lFyZoh$v!JU&IFd~;Nc>@0MJh!~V`2f+DI3!_ zcBZNc28l&s*T5jGZFsgY_66Z`S+U;SviJ>MgSmsq@CTSAN(B<)!c{PNL)t1KZ&06J zdx=vZ-<EPW-DE`9G*?dIttI#MTx>QO9HQk6|GZiUMcf9=XGjghC*0m&q{EDnbvkH? zXiOD3bZ$ZF_iSU*YSs~Ud7&%v84OcPwJ#Eu{BqpzxGORJ9YR#geZx<C-W~Jj8=1#J zLTD7MdJQg2%77yAv``ztfzf60ljORShd|Bt9m-FdH)TkH0ti$R|94$MTO9-fz%xQ> zY3V>S(pXG0sK{7PN|gIu<u<cbQFrMQOCYaTcSmPF?zuE3pNo#=i?xzlY%b}pYlA;& zg)dx?g9ywyD$1|m?Ci_dE2=2K(QqLeU4dx&0*?sC>4k)WluHJKQzyIxxE7Afu2XHb z&@B2kFmoKg?W!7YOhL4v4WYyo&oEevx=k<7K__oKI^ibN@V-k$9ejqV6BZ~RzEwF| z_<HmfJ3)fG11zIpjYDsjsY-O6VnN7lr(dbn3&MhK%6-?^b$W&z9s)nex~{Exr)E`L zZ3h^ARlVu3TyXrJLv}c<n?D%lewW=*-7T*DJqtpuf~`m4{a?iue?D3n-}F*XZ;fiG zY#Lua&^rH6XS`D4HjO3R0nYK-$Do*AFt(Y0aV1Q5Nx1zttv#!#jr1-6{NmAe)3?eM z*+$3oJi7-WVRA?<%ZmJh&G?^u3HT%;^;I%ybNjWfTO1ZD%ftoheD5rPBPNG$tM4jp z7DqbAlpIn$!jViSVmfcil_=s;`RAa{ooA@13?Amr;q1*rx^u#8166zZoX(E#Hm~aJ zxb%H0Q@COw_V&$Q{~nKrd0n`pJHG^;ps)0#(z_vK-0K&05DunQh&3P2D{-m!RZ<&s zl%#7O%(C`o#`L@W#<rm>#uWi3C8kwaR<YiUlsbJMWnAcR0$a-UPGR(i3+b>N+>K>w z1ytg_o{IOJ=?1EXMqCcF>lSk-I10n8hRPe5>i%4AAao-yP7mm+JV<5q!@BxKBN5j( z#14MBeN##IDOuC^WnVmFFrhc0^UPj{1YAYN(BTVr?A~`F84?Dy_j=18LYuI!F_>>& zT@Y~C7lya4H<=Tjtyt1{^uq3R*-(8ZmP5xm>3|6J{(T$77ivuwcYxpTXyi43)kB2W zN<ag><_h>IgodlH+8_36)12nRp1p)Q+Nne;WN}ENLSWaiMQ{@G7}}Na`8Vz!DIvJ^ z%2p}c54Uudh;@3qMw-;X5urujx?rb^zHG2JvPy0AS_fv=?+&%qQPMS;VkeMuM&oZx zWM_y^1Lbyb*R5;dPSrmcb%O}+!AKIb%1T^cXS&i<{8s#m=ogK&e>U`W=c5<Jrt>Qg z4tGj6P$=Frg9#S6^HlW5JaVT#`l}drZOP;t2;8Degikz`mplQT^qhQg<g5>2H5ymI zABq%vel*}z(!S@i&Y{B;Ts3ebW(8BnAL1<I8Yz)ebEa=XUugPaMmZ@#(@&1C9R1ut z^@riV(q4keFI6B_XQOa|^zQS+*w5kD?@}sm@vX>zOlDu3_yTuR!|+c^G$3bX-SV)! zeUBjmWr%>=epV-X$6(?**P!FWt2Xn;h_VODaj#!RXovFP38xJ@#1rDuag#&b7X@!P z{=<-EBD@Lzcv!!Ujslf{LLye}Pe0W8_1B2E7d8)m4U^dayK&>QSE2(D*qb4Q-|NO} z!o(AotyNKruiid(F)yTHruKn6zU$nz$#c-wMDWa4%8MKbs##Kuep_wz<kb(ogSzK* z9Iv9UNv1=ia132Fy>a^#8txkRz;7q;0*PF4=RKzzvM3h!jxS!{#rpW&RoOuG)ikDm zu>U6uhZ_{T$W^+|nWPwM>uG|!eeuSgmBvayPvMk$X-p9*5T5fc<dK&Az7xIjO6p6h z54YReE6=opVnges#>&>&Jf_4f@NQ_djk^C`z;1B&L{H{N?eXt(mg4dr!)mPkxI8@O z{1lo3C=|WXUNQg^Y2rUc&w|$!*nct9EVU~XBnOyj$i$s~fr=|#=xK6TBTJksLyvGJ zvTt7FsEGHU#PrmtH3^XPVXWhR(Y>q0SwQrKgew<>Nr*3{MB(?(;+LqewkgSefAzQ_ z>g>o3wJUT)D!Ehr(LDxvCWK$9E&h>jjCT^9Y&{}`8G<w1rSp;~A0E3T_P}{vwUKNT zk36f<*mQ+9_ET9qw;&g~@+r&jL}I2|IR&}0f3{sT;6jrK0a0y~moi4$&$x(g6(&<y zBE7yx?UUgi5y$`RJ-?iX9qm|UtUl&PNieys@n_T)dU4whyg38b7JmH9K5?Pm;>f7r z&Q42Q=NU}uqrCl_w7X=Ni(hQ#kBGHCQmZGn751Y>1c*#J?!euza%x{-)pwwi*m7z_ zWTN&G_aih)d_Qjfd{dx`&li*Ps2uBe6&m7JNBm9tqE5Zl3gx*AIrpwbNpw9I(@j(> z5VSRjVGL(2dPs;85^m>}>rrpkPOeTsc>Z7b5-S}1ISG0H_!)D{!v(<J&fl2il(j2Y zCLr`<)z`I@r{D-0#P2))`X@OB1+hlrw|IgYfLy(lh|%otZp;`;`1{L07lA4p&Rrkb zDY^BtYO_nOa7SlHjl$G>6VuSQ*?)pnC4_?c3o7WtDKj!B+z1zA8qT2e>6qbVG+?~f zgAUX~GqL3KC$-L4%x;#P^E>Nw83W&5Q5F2ZsNEu$X~+My3ZC8jos^-<eEEC=u3+-s z$P41xDpl+@KkC}B8^O0kkCq+a(hQmdwD{F-DEY14|ES&Oz~Rz=)UMafh>5$VhlpgJ z-<M^-ur~Zh-^?DUz0-ilvS$ibHa)>jlmDdtJ2UWNtHVXz0~dEm9yRm)9Q5e&u0-TU zuP?!)Mjxj2uf@yMKe@KARF$p8FSE*D-))S`NA3qG<=UqQm%P?!@A|Sf*_C?V8jXWI zF_3uGCu{v&aBWWm%;8RrXAk_ve4wLrcyg7apKYAapM-B8ChnzfIx=<g$L1{-9pUK5 zt}b79q4rGYIRzz6U2qD`vE}&P7FKTXAYcv6)-@}6mN=tcQcq!emzHw0$=(oiYhZ^4 z!BTn)wztcdp-wl)-<l!^tqo*daCQk9P?0(H?<#n+*_oF=bOt!*ZfW%O`Ws7K6MDu6 z>+U6mR2Mer)~R1~6B}!C_?Ox>zOSFQd$Zo{10dhgVjA39YJRdoy@@)Mr`yL<lWn{? z)qKxv9d1IgKqVU%lKttm>l-b#RCW7+L2C1Dn-DJz;7`kj>0EeU;Z**9+wE1nzrRab z+*}XXm>w)k#{lqy8VboWnlI*b`5qqrwbuI0N!AzlS2|mZ9WjX~JyE*TVR|UA;GogQ zpkZwFLH3aI*Nb0>>0e*uN=r=>G`rc;xo&Q0nt)e=q)py#aW(Xzh_}hxeB&*w?KY*o zadx}zAyHIN>Fv-3wRLuJXwLA4+S~XTZcuGKlDa9yQ$O}mnrHQuP<hS^4|Qmxf0n0T zRUc`Aj3!W^%gMQJj@xa@y5+u^1r;5OoZndN`jZ4$Yb(r(t~%4En=k2{*uINXV_unk z$UI(KVQ+t!yydCX>f7s~SFZ<!D5nXd@Z;2Uk;7@&q-(y#J@~?uRCNr7$&G$C9<|Vv z+`OG`LAe<e*{R1$qIcT-oGvTb_a}M$o*$v=qC37zl@1A1nalUGhkW!blrYLr$TOb( zZ5}gJcJuRjW>bw);PvstDsGgzq_jTtYWHiF`L_!`Bgrn(<sHXo|CptpM(LaqLJZ8w z&bveYTyWFGPz!^^%xmY`6_s~amrC^CN%+uqAiF5OUAg4f9*g|?Ow#`Tp|OXf7Y?5( zoQm3W?uYB?)Wsk7hxDVon!{k{eO`k}hK0_!vWdr<yS7lFG6Mw(XDaM{1Nz@u$AB;M z7)JuA2Mv@(b7n6h*BM4d`+;o9?2~4TNm^p*=B(6i7vt+hxSv!|eZC&V2P!J`qc!)c z=nx)RpWFra2PK}#7{lrEg@uP{UR~vNCXKjrlI43JLGGpfHca>E_3taJmhov<O%roQ z{P2>dn}OEgFq*G}EwssB>sEO3+(u)m&({2@q_02P+C(bf_-fjMbh#N^9Sz9|>J|N= z*!<q%#7fVm+db)NtfT7Ara0!#KCq2DH7s``Pj19k)qgQv-RT`WRY?t~ln&HAC|~3I z1*%%if2nyGlIA1`!cqz|)S<+5pT^DVUx{o*H75B8VXSZm(-&9*3Nw9NE}$J=>q0SU z+bZdzf%jS)&GS0Bn<B?9z5S9C9*pGffu6{OPd=biw^-0z;2TAwc{`>>P*EMDTCd%s zhF9I<95tFUE0!WVzGj)=a&%*_ez2uX=ti}67jNz27aq1NSPFczRF)cAK&a0FBcD`k z(im3QBZ=FY*Hvna+aDMlkdkVRt0c_NI0c%!K3+C1Zwj@^RCP|3&C4OSQ2OG7&E3ig zF<X8~+T5IxDRZuLiel)iDfSZRUbWrs5;+{_*4qagv3;PnjZY?4oi)({aj!jHw=MeF z2taJPdOZ26qgj_x%b?!Xnt^$GImh{Tbj$__*Y=I>h<JP<sWH_?-vKL0_gt3pmpZGv zuFfY)YL90pY`F$EeO~POC^r8TBwcb<)AG*4M{b)EzlKYnCyR&XsI@W~N*0_|Qi?WS zs-4|~Q}shz!>trrYr~u;etNwlJX0+w{NQr0JKYQHmavSo7aB6G59Zyh<(WiE=uG07 zg*ta4{Q7j6R}K35*c%R@$?AY4U0o&ThVh?|qJw|BUH>Vay{E$yPMBgp>{P+G(+9L1 zyRe_7_gxhNnijFgjv!CTY<QU|XBFy<+q1Jvtc1@Dw~mr`De2xh_ac-Dc_sXitfnMA zZ@KG<*AXdHpEMZHQ0qV&Z8V*hx<Z0EZDLBh@gDS84u^W2pTxz*$({@iB$@ZFH)W-X zaoL*|Uce435q7Jmr9S+b?(A!!Xn95zJj74d+g;MXDM_wzf_0x(Gjt1L#)p8D#W~OP zrA>CL7qx9(#_cOh+XgaaA<w%@5P#Z^!+}kc&$9qz1mR#NQ`RL8Vxi2M{=!xzTm+I% z!T_`doLXP!Gg)rqfj>F09XP%l_>46Oy|gxe^|7V9p@|=Ji+Zr(6}bS;dxcQ<4EzHy z=b_b?t|?z!pxiBLag6i9jNN2E{5f<95kHwOyW{5bXVqRvWny?F^|a<GJX8%B!Uh_p z7u=tNUDL39u#)g<;!na2>m`VU?>$A0@sJ!<(F|E*$soT99ViQT0M~CIxh~_ar@Hkt z8B`Q-8+!`V|K$N}M`d{b^>;lR%$(Vmcd-KD$#Da3r&Hi&boh!U#M)E;L=JyO>ZiA5 zy*gZ|A}k-f$D`_{pE#EP-TUC<mHSpmTIiKFmML7GUEdN-(mVQ2_Fk=3mz8sLy`G-9 z6p>M`Hi}COSBpMq<RI*g$kTiO$*a=dM!%nwvUR7w?h!Oyhx;Uw_pH+m`aHJ0GW`4b zH4Q1^CO2)&D$akP+J@3inD}uw&UiZ&X(hoIw9*}2xBOKNY*(}(^<(=IG5ZsVJJpF; zw}%DFly8dG9h+QMQ=bGVeW>l2SA*6VOHcJNrGER<JdtMc>wyW)sB@g5rqHzTUw|E& zpLU1vJFQpu0_DuWhkGWb+u?kfmy)x3W>*4dPVKR86epwhUj}5%xWKD?z6q3D+j)8q zKM<^`>61RHE!HjTpoTUgjl_Tdo@fW90W$UgQyWl`gKK8&`efB%F%MNM%(6l!0iODt zm3!FVlDf@&4qclBDH;SwOaO7HHi<+|vMNNllh`{S@?{!8mgDveGh@?V7vM^Ym1bI- z8F%Zn&0hFx5x!WgQ&6rK=s;Xos<8OTXNwmc*tK?e+0R_Bb`^cn)huK5-(OvNE!o5d zwhWPtilfWRRg3MEsO0Z7_Du5TS&A23t;GTBzU}bR9!ug;3xg8&Hdh8<PlpfeFcG~# zKf1dTU8NF-{=F($+P>!{zt*!h`&(Mix8Qq!E3DGYwlf8{ZN=yw?U~GzB9W}1^*U!S zE!nHPtS_Nw$C#<pQHiByvcXYQjCO7SjRDDHi*W$bGD>}jf7^?!`~cy_74J_gF>$nV zQ@4Fb?XxqvHLiv>E<}!{^=uPhO`oF%<ZZtXz~vki)?QUTY_Ipvlb{v$%u-RY!Ks2A zx)R5Rjb^Z)r`Ubj<H6I~ZpQ30*ZEF5|HTuY&dnnHsP_m?j;XgjE^Ysgcr%sOArI1H z^Z_aG9uS8*Iag%Aw8x#QU@0(OXYxg!7IA=;O*yoUU7H-zt@5o~*IHrVf}2E)C+e5+ zfD(}{Mr5o0?#kCe?_sm;c`R3JyylM<Hos6&!GTF)KOjGtDy%5aL~l=`1MNM)03Gf* z(D|}(`mlwWI{P6Tk*<{0{0r?&OFk=Ib2vEJnUWlByrnW)+>z{*X;064-wj7IqSeu7 z*;<4SN#AbeA3W&h_DhE-$>syu7OD=LKd0lp9zGd>F)8<YOuAD^P<&xuS}m%_tIO+o z$xk}Ms}R9A0bg)gPV8h-sL6$+*8NY!&L*H~Ci|GdC`mOmdVnFz8iLz1&2~yur>T7B zu##Tv_1(_eOc7hRQD;NnbI0|wR7Eq4K<ZcmJEjCeQb*r9gO-oJcOohK@Lckr2iaD_ z<UUpOy{W+|=>wAhO4pGgKR~a^V?)spDZ1gu%^90SN}Wn4JWMv$g$2`*OP2e(<XCmZ z*Xq>JCUI;}Zt{&EeS4DFd((?oq6L$2c>fa&@cC9L4ulCZ=2(w(9n+D)q{W|bD+)5v z4AGir(6t6Hb2y*z$~eTbIKc$_NKJ9^j6eY)?#X^6fd(XL4+=`?DQfI1+(*SAL{-R4 zr$~p!qn1zWWuIX?)gr?NQmkmO4dMsd*oaRob{3|xax%G`j+P$EQEnO893igEw@O1p z);HSV41-yrwJE^d)^uX3%7m^XiEW4mc9T<$mLZ93vOYCQ+M%(Nm^9#w@LIOv{&r!{ zA;K7%TQ0giV^i*wL1Z~>41Fk_j`{^jjUsC9_=8qxhcVleZ29(aai}%1EAK*EQstNd zasM*(0|)~d$Nfw2Fg@Hsb++BIs+%X`$lhY}U^g~B*~9dKL*UaXx<eLM^_exsu$^_B zp8_l+8~svamaQIJvL6bQZMev7+H@!fnn>$8Ox|>tpX?!kd$l9@@FDMk%C%P-3K37w zAhP!5SxXkuJ1Wq>{c}wV(L_2LR|sTrvbNf%bc7sa0tcnSOb(D(>rtLbCrmw}ZH5z` zRK;%3sB%vBXip}gVT!jA8)8Zh5Zg?eFONQXR*;NK$Dk7F8YUBrRC`a{bGHlts>)?! z)<)PoAd{Y&P>VVXXbwuZx{BOC(Ia!0hws{6d%<16ekheAZ3$05+@Ab^o9qqj%{4{( z(k!2Rk!jvrZ|vh<82GBoJ~fK6o5^L!7rp`nBb)X;&jdz+WkF0PTFumjt(|K53mF-g z8bL&jcieO(!H>6lW)6F9i_RfYkiJ61K7OqTfS0qAU$fAV)|++j53=Ifb>TgSX`=v_ zwdW4Ptv%VBE1o-@tS+By)9$r*jn$}uriZ_Jv+L11yZw*?8n}I#EjCPH@}IER7^Mhr zCNYIgM@7roMUzuw<xt0>xAh}Z?<ac`Yf;-MP!ms>CY8CF4)^7%L&fQ)o^S{9p>O7L zaw0KJo!B#0b;cWJLf?_rjtG!Docn>HDolnxkiMkKcKmUl5_Rb9S<G2J8F>zaIOwDS zr0EAI>7(f(l$0<^O5|0PuFFeKfOk#uYomd;5z8n?ZC2kxk`|k_#SFr%W$K~<1x>Vt zQqms{wh;%~p0vY+oTSaC$~R5|b4el$Z|BJxA5K=)hH7dv0Z&$+<KEL*Y;_%ki|7*f z&|&nqcaP;#QKjgwSCN5i^cGF@dQXg&<_Gt1#mNkxf1fO%!ssFym?Bqx#7S6{GtVHc zy$3!rEHtMqf*3&TJ5{qOn~w}D!zl~o6iJ&&3NAs50Xu79`}l?%`dBS$?5vfhRv+rk ziIfS8W>3<D(e4cPFgl<0=4%q_q**Fk1GNx18uG(jaw{vEoOE)W1?58GJd;edSvGSl zieIto9Na*@?)9)wdO6&Y!%{!TQq+66cO*Of(M)hPYyTYF5j#xEy~qh{klTf|*=f!S zW*5wpF1rOX1usv16I-~PKMx;2oR4-s*zSFZ6(T^z#j#>R22}9aMlf~Y7J-EZpQAyy zWgdk-N2wKCuYED$G54DGtpa~|4p_Mm^Rgzb7Qf2(h}WFY^~F?QMkZ>*O`fOhBt1)r zgQwUR6qSZlFQ89prsZs%2YAS@i}P1Xkz8bG=_6t3%skg{f$JVx=DTn?=&7sd?t#Pd zuVzJPd&F{H?ztUQd^4mb7FV%#p~9Wl2Vd+{3TwhIwrGak*cx{I93^o7yI@0BWZXa3 z5&>KmCpPTSa!9575aKkt^4sFQ{R<U_VLi&><sTQz-YoVku_$p%`#t}4GvUdyW6$<~ z6T7m1;fifom3uh<?_!njVh=uSm~h}Zmu067-$r6Z+I|pF7j7UU9wR^Wep@Qf{!pWA zeJ*78+=R0DnC(Kd=ErW$4`bQrFmix!|9(3BqKRsnUf{<|#7F@?{KDMZq0-2f4&9XO z$oV%Pi|9zEc3`Y}XdVX@BL2w;`RQwRTEucN+iV7)Ap2rI{pvs7<az7&%<=QVpZ?-8 zv2@fa_%akVzrJ-D?m@dqUPhdv5wPh08PcQxXkZK;@_&%L0iH^aB>o?gmqW!eG+gp( z|8FGEHIn^5N!|wken2+<CQG}ecBJB;kmg`Z-B=B!!tt_WYv@6?#kK!C$?Lhj2L40x zg45pphvd~kCpozu!XCCnK=Pbk*t`28l2^J{K9Dh3xaGnJkopYAxH1f9_sl2z4*!ef z{nX0>1{DaQ`|fOYx~~YMYzU6vO76e8A@YeFqMe)t-Qtbr?QH)%D~NcTzKbJe6o5Kq z{r1tuN%kl5SIhM?O^d<{cMl9+Vl}Cf)1+#Qv3uz%<Ub$(A$fYLz(mTH4_e%l7va-R zfL_VgWU}7T@_cZ%Q{Zb!<*Ks|K)a~DxS*jZ=ST?tACh-2rVF8xU+W)XsWf%}*vF0P zaIO1r{sWu-<b!HVBWu+>ecJ|3x6L4e+I3d%ACk9s>%6*+uGn@;q%mGyBUr9e)*VYy zZUZl7pRJU=XcWBt$XWZ{{~~$wL9|Z@n`x_+F4LeAL&n<7e@LFHOpv3sWC-LW<3A*? zc0Z<aZSH?3c_HT@)j#I{P4Z6p5Ox21B=1|5)&JilFY?E9;jzXaGbN`!{+Q*a8vdNC zEQtI$Ut81obD^Q_<IhFjeZyZ%Ezcr<eQ2L;{PnTp`^R6O_$Z^_%e}J4f3FN^UH`p0 zwC&UH&jLH6KVP1B9RKt6`LXMNzP>Cbmzs?p!h<;>%|Z@dz78~(Ah<@9-rp^i=D z?H``qTigi|o?j<_L%U_{T9!*SU$P?~8tG9Gbtz5J&3wRK4OpStLA2!b5(H{0pK33g ztJ`xDC^To-Z$|^M(X6+fmH|8gi>&RuBc8}onxajZxl36l-ckWF=BxqbuI}bmE8+}@ zHd!}Z;TJrA&$L^z-zl8LFEc8XghaHtV8sG5!DPtlr|p^<*~8q)W2>F<-5vbSLX?zC z|CWHz_iak|gbQV^xA$RQ<dY3mb28#~`b+J3mlYbPrYtQl6pLv~Ek^q*K!VFV&C9G> z16PRR(F5p9Ih?Nu?l$O3Dj5h752nGDm)ZUw(XJaDRi!+;){@EU#<-GpXJQklLMdP+ z-Qxr+e}9Ggy6(H|Rhi0^0uy^>d^2)-*L%%}B!WSvKO2ztmsFWA8yTE^=oAUN07|n_ zm}YCTZu6NhigxC5xv4MYtS=zzQg@Gf*suf^1-F}7SVS&r>l6#)2ckE?nd`}CHK(Pu zwxn+Fx4>i4)c};n01>sBe^N|+<NKrb#>b7bh@q~^)3DTS9gu8B@q5KLWZ$iD%f3}a z)J7eZDzZOE>Ehq?)NPY}T9IYx!0UI_?IbaKLltaQRg%&)<-U1JLauxQZ=<3(f1CAo zPL%$a_<3%*gQ{aHpuPoAEaY2wJ6?4IEAxSCY1%Gj>CTy!(&dz7t(}rmE+P-+7jX$5 zAV+6-eX3hgK<IE>#@Y;Rr2dA@KC4EbPj~{`^tHB{+SV$*fPP#DVf%}9NuH04uE@x^ zoWISiy(6|aAZbl_$k==(%{C}M+$DzXe&FFt*NF-_XjxYxr9boO`rtL?Pvm13c$sF> zT?Vne-A2#a82hSpSZPHL6^L*-oE$8J_5xYzl{&_HnJPd#ofS2apDljEJ$-zLX|Y+T zvn^e<F|{k1+yDX|bJ2IA#^$ymNBK5lJ#H0%b^^>bok?a8k3Y8~2^HI-v<b>|B^h0c z3V85|iE)KsG6`4y1|X|Sr4o6sf(r2+w$@UmJLSk>Q8r0%EATt9mpoJJ*JZJ#67lM| z1!$b9dNYnjinGL(F273gW60;pEo()Fw{L6%cuhYh`3VZZW^^SUTeQ5&vpDK=OI7w3 zTGWhVW?F#OeZyg?=H3HFC$$d|<<$pJP)Wdl=>57vNYDi_Fn1a#DLPVZ7M3D<pX69S zDm8ji`<`k#NAEY8Xvj*nDRA4jMM%C+3NF+PZNiylY67sxkK}xv>G#8JL*gp6<ncTT zyRKY1j}}mXg{C>V$sdY{gIk1>K)F<_oCsaJP+8mbP9$B%G-Af01-C2W_o4t=q;hnk zGCO%t)R+zNOoLJ9J*@QPA@;V4xhwn=paNx1kYeVI7TY7&@C;&xNHVerXYlhMJl&nY zv){+o?hkL{G$(a8I_RnIB~ze&In*M(EG@AAu&4KPsHB1<5J9)9fB-?|Pb{LQrC5rv z?G{o{I*>Hb)AJ>P7u-wpVE_rfSJnxoT;tlT{0u9lx16<#M;3b+4QgF*V+%kIoM#GT zsI9@<?o>OA2Wr1pyfZU#dBeK}fUh=Rg0%w{7~%o4>QJq<XL{_jCm8JViCF{L5foJH zfcpmCoeSG7=_}bumOid3C8{z8Y2fX*i_-ff_?l3W<dY6~2?<8r?%xkSdYV+%mt;3I z{<rQ#OVW@Tn*3BUmIa{C`0$AxE9dx7LmpT1#ajQF;jTCrhl_)lOE!klBaNY%8|5Hi zEYPv?ZDO*!AhKp$y270Ix4E2nI#G59g1I&^?4I6^Ei)GndKBBW8>rcPa{hQKGghxO zee9Hs`OC8BiCOQyFRLbq9+60j5ocbV@?6unu2i3OR!jXCv-Ououk-1uD~TSaMsjNt zU)kZkwkr_2%RRNA9+#7^)JaP>4f|72?kKStS|X}Vb(*{<3Q4-0Z$K;nU-EW0{o~Z4 zJ6#iB+(>)@jVYQ<$cM)bpmwUtF|J$MT;YoGPB}t2@fa0}j2Y%>ON16pY?ereSNMur zeGi~XPokI*szVC(0J~-P_%g$MPP2#?0O10EUA)!h03I0>l^mI~Vf|2vPd3qG)Ffn? zSSnw98kXp6MwGsPS~L)U5-Ra}+2@zP6QYYcuo^qQd<G5?Gp>zW0$33P>c?ymFwyo} zZ^|dtIOMt?3Nhk1{4OCV80-KOl4~^=`4+1p#<vVb05B^m@-83|(RSi*E)ovGJ{nEk z7YvSbeI^Rh4xFGvn*xfs5)t=}uIFK)+mJp)kPBcp+v<-C6Ht)T&s8ik?KAXN0SHYQ z9hmw@mDck`Ukfc3s|9knVFq)V`*KBPzsv<@B%%x3hcGaF5^WL;g6M3g=CDyS_yG~g zTgLyWiFvZwC5{Z5+Oe10H4Vt%tVPhD+*6~gR(xU@q)z*eF<e3jjLJp*dB;Yt;KB(& zAw}P!B|4~=B7RGAnMTQ^f${@JS4p5%ivA+yjLHM8Ind=8`8<RK99TZ`eZBBJOl^;m z{I<JrgeWx#^*fJxuXgXC*Z|cv_xXj88+d%HA`}9FGQ@AJ8Reo8**q&40r0t>7kuFa zkRskbV?_OiVUfd6*M#`iZPjTbLRXGFsWm$EJo-2XCz2JS7vcF-Okit1A|?Gt^AWTT z2<yjPrevPmzSWirYSkG<UM!6Md_;u(vO)X;Ckg3_8wJsQ%UDHB(b0emh%g@tDg0xJ zZlr<V>FDzUu|j$wSAMGxS)BM>vWq76xy7)Jm(yBRkPjShx@C$-<inkJ1Mwt{o4I`X zl5<JuPg~&OG)yIpG2QJh3ZeNTE)BgfJ$vjJgjy`w#aUfnErOO=&9`3;uoACEm&)Y$ zHLwkPpQ0eN0=O~uNm}V)wW3e_QmH6qdQ9nTbM9K*)`=gIhvk8hqT(rktiC4L3}$w_ zUhIM)5MGi@iWpuBV2SFd4-E6cGsmN^z|u{jL<o`LAL)R;L5p8d#nAwyyw?>~g&l@J zcDzGN4H1hVyu6tcm~Th@^j@Ia=>^_8m)q6KUTs0I>VSvl4Au#85RTv9aa;@mC<VA` z>81fh6rKofBZ;Njm551-uOCE0{c>h<bCD{@Gk~~d3g%%^)wxN_spkeC$w--c+#01q zd?d0(z<tleRtZCcWdSY~V;(B!saq4dp2L9Y#C*uL7`KI9OqEDKRU)=>82Z!D1C9z2 zh%uMRQG>N{#&BT3@N?B+m@y_zT9OF@x$)>5K<#vMEkd#$LaMJEBy5le@InaGIdl;k z0LuXmCy1@l@NY!}t+GI~sIf@Hg{B+sO9!i4uSRs$s3VLxp<wz`Qe)b+2nZ`Dw!%fn z=nZ9`1hpJ$oG;#mOeRKu?{<GTNccn!gwYz|T~|K7L%>w3aS)7tvF$NL%GU(KjPRTY z?`|^(XTXBF+@t~(a1F#~g@7#zMlOyZ@-*)#!|gd0`9n9`M;A1|W%xN+f^rD_I0!b8 zuNSJ6s%<XhQLiemD-vMv02m3hOryN{VYmcJe6)jZP!#`4Yeq$h1%(=2O1Kdwd2FNX z#oHE%-z=dL!s};Ki%`zAKpHwh+h}aQC910t?kB!V5&hfLaE&j4P(eBNfh{C-1Q9GH zR<)2S5*hALW8M!xn*T4t4@d9?h|iWaddc7a_hpq#J=j4(=JLyfb>$EIY<vC=kXQ!X zJ&oRSc5^(zHFE3O^2>Rzbbo><C<EA#5oG_$5UU6X+L>quqI}0~8yHNA1MJEO{#tIY z@yuc)q6xxlaqPzaw7JvKeEgx8A(SmK{PQ-s1^g2y*ZbABiPAYEvd=W^uPTq3xK6Ae z{LDHJms#0aMY;P&2DlK`aRthQF)BlHcp2~TYoIuM@+J(@(XA+_1@~<Jc08BQDW<1B zabnHacD_6e2H1chRPhcnhI#BRH0SQZVcjWHV8^c;w8^_?Mz6vA?%`I@oMlWS;Z`gI z3E|}Y5yd$<Vh?C2q_YaF34NaDah-;}8_UNULwQ1pHnIp>Vy736Z{5*VxGKI%LIE_e zwTNIQ3n^eqSX=}tv2uB2Tnw!*hKB1TS+<dJZCnh!-zr5IC^>SxhKJQjLnP6~7X<uT zdXLoJ-kRq9w5ELud~LZ@a0zINprbm3$>T2xg+etR4ReLocLl`lTp!2O)3c{Tu#w45 z*S}!2w2l@~uXftr%@B$o5yJlRak&EQ-I-3t$tDk2S?pvl(jxJ}CG|2>u%ik*YzC?i z5po2Mb8(^{GEgA2MV`S1eXYFku(JZhLY6VZ<6>8qOQn|FQv~9X6u^bwlSl2@_-k7{ zSK?*;4oM#1xTN(~a9hl|4>}pjXduk!V4G;@7-IK}Ma<qH_i4p0;N|g3s(Zk=n65U+ ze?0(;!e;Qq!zjS$-r*aUwtb}3L@+lt=88TV3G|Uc2Pi%eKFe4Z@Zu#EK>io7lm zk#b*tNp{rU$4XZtuTujO%toO(4=(K#z;_Mr`rQv%Cl8)>m8c%liWhoTK~e5#K>U)u zQzk(S1o-CQOKQnkOZ;1*gx(#HLc}4W?nX>fTc~|8qO$cewgnhcj_RxzVC1syh9~>h zP|<IIG2=fE@__K;-lHeZ=)jhNIz>QAoFMRoxc-P{SmJ*#+he*8od=PAwDGuKGKKts zzL;?jF-$6doQ8OYSLuyR#uN(M+`YV`Vx9`QPs1ko^~+DKez)!UuG9UJAW3^t^G9or z=80{JzF~oG5@1t@Wg56vk>l6~LFm%!KD?&Xx8KKGc?E?jXcR;cvQIGR1MH?q?DEE` z?|P~HN}Ru_jRF7|=gv>AIQEas$#oL=dqHz%d2mA%`WpR3kY9gD-=iiDc1qDbcLMA> z>t0U2zSSKZ`0(Ng9~mYP|4S7s=8q;iKYXAju9B~Vq%<!S5J1W^nDfgte-1v!kHyE% zzLv?SVXElaHPp#e8rmlgOB8=Qx=YgX_t|_hW;q(Cb^isd6S<oLwDEh!Na6x6=11~f zjW-0@-MZa3hg(hpNUH3kJJ+);@#*R)A|I4@cXiuG0LH^^UmIT<8h@$yR=o^+opuev zwE`mW!KC403Sce}*Q281sp#2|u??=r3LQxw`4;0Jv|kIF19O0SZ}8NxW+DK++6wAN z3*1+V@JPz0bC`m4V6<x|cINb5&)t&iTe0C^$z41NdMx%lN&F`uabAE|r2tQt%MU-A zR{A`1=SJbu9fI^T?YgR|n0*Z}NKkN@JHrm=_2Kz-a;CZAW3b^paisHmxVx|><T4LE zCX`5~BVTb)2oB=8K-IVHJqVNdRJa35>pDK!duQ^{+jw31t=IgbENRKu;IETcgcwu( zq0Gp;QA3N<4;M8JBoCRP#Y<+2dE)SE5+O9J1jT1iXSLYfIw(-qO^A9fz@L7jbv5P) zPZ{{4h!j{04?`$HRj*RH<INM;`CpY;%AY>Inaei(5bldRPs9|HG08&l^L*T20PD)b z6?3qs*T2qnZje|$+MMWYIZ6vFl6oS3p756_f!U-z>;*pI_%-J@9f`t*O+TOY^)~q= zrFaMj3&M!bTQfl1Uy^vPAV8#p51iXM-m)h)Vj*@!{39@VAs2uhI5TmVFvGiD!9=7i z4FniZ%N@We7=6(7%ccclt{lQO{=nodqm%i_Br?X8go!lyeCF+rLWJB@mJUiNfUQJT z-Y1~<=)PVS|AEE?3LZXtEfcJPy-b@^-T2ke?@B2bGc53?Z^ah#t+=FzZTz;Lv2X-q z&nu7|^oj76SA##S<Iuswex-+v`0+-|{6?_XXp84Nzwa#jh)?;*u<1~PmupFX8(QBW zVHF`eF`<Pb0=M+Qx0?vFM|2X&E_J&J6{P7@`dl?V`}}pO`CqRJXqQun;$wO=U_^u5 z08~LasxstB%M|gA{~eN7thDSR3Tc`~l;^1#=ht7-J=}Ub8Z%nv(O|oA<M@S1=VZHs zRZ>+81PyD5zMtbo$H_|$*YnOH6#q@~BEwNp6NmmGc|K<NkKVUqoT_7L#~W?DTJRRw zgazrbwwhuKmJD~at}|=no)o1+t49Yf>K*S1J9M%qYU)WuY{<vYmK3f`y8q5E8x{c8 z+jN(;40oUuyI!U*7U=ao@=d48SXleh@3eQ?Z*%nit{qy<?Scxe?k_)$bhb#nxmkCR zJ3$@|?ZWdgj#VyoQk(6r`2P8sv8wbGM=Jhv<|jn>?D`$2E8f31OwYa3QvOTWEYWg! z{|~*|a_@@8Qb7BV2#)om`4|5h_L8h7Mn`y75_{mznm(mgjm^7tF+?yZGzu-nH|)x` zXx9&!k=+e#uiTKDi*2&olz1jYIcgBnY_E1+O!Nde;5XZ|M}O?9$|pj?QPVPteCGYz zJ0)$3?UV;uHU>HBH}-C++OcI{)0a9;`p^?=9VGi@)O{-(sJ7ju2jybK;$)Iv?FCO@ zN1t}(H}i(|dM9ax-t4{JP2he9t*RCmC)3TdqvyXle|Cs!U%4ixv<HJ#sqAMx+>q*N zY$NSV88>l1bb3pT(vP6Nn2O_2GcAvdmJvIZW9p+wMe|)sQ63X<UT!L~uz)4w1N;3n z0m9k7t%nCYMs6O?cyep}RZ5;)usk~*Lsbfxz{vK*n&PH&Ef<JKwJBaJNAp}Cg@xxI ziY)5Wi$ZC(Q<EebogSYmeqdKNtx*4U82{o&wZmX#n!R?p`-4+&@9%d;xU=juZymjG zK)G(C#_++~$=P=~&wC!3;HH!v_5JK~0l=z{!lEF}gUeDi&70%eBL<Y?%=En~y@Q<R zbW;}0)Yr9Ly~eh^tZtjR9d`X5Aw(&L+PH;&O1J^Pl+_qAkmn($^PW@h{JH2z>!<!5 z$2&8W?HVE98_{^u2@IKYnnuvbw_D~YzO2|QBTsvvRnu|eVbgTr!4%PQ)`kWdslELV z?X)_h#|}Ir87DL4t6Kr<AMgzG6y5r|mr7D%F%zd|J5Rk;xuD7MDuzgR+}nEd&#CEx zV|U|ckDq8HFhh6zz3861=Q8MxO}u;h(>>HCbvlf4(Cy`6<FDVw!a{sh?0Zs0B=0o5 zrd=rGA6RzJ`*&U4fR=2!C4K|IShf!PY$YOjp4(B*OhSVfJA>$a=W$UsDAB~pCbV1N zV>#=atxt&Za%JEtx1r6$=oC%pa@uP+(SpO@KY&&<=bP#Qa__BVH(R86{eGOZM?~^w zr8WwJ%L!{<(zE`P*nwd|YCJBzHAMx@;Gv~oN%|97+ii;HD!jx)QZWYa*#NOzzBMjc zi(q<(+oI~UzvVSTe)O()Lpj;IH$eHTnN(%nB#cO9%Wb=`-JJ`Sf^Ze;PIy=-xJOza zeIiuW*zVxyuZ~0jmdB57pu2NbfiU~2^40qyu+?~0Sa($SV9{WLy@g8XTo#ekUuZP0 zM@nI;P2(l$xCAL5f69bz^7f%!`-wmg8o6hvOgy$%fAbK!KbkUmacjFap<rE3Lua2X zI(g|`OfUSH*$sP%c(WUuMchKCk<eD}x5ew0iO;5BKg`#(vC{AGO}7ay1{p<~#cuw` zD4r{}%BCky%oSVjTDe6@F}xl_)aF~hgIEf<HwZOry#)%V(n>E6Cf;`Sv$8QCotQvz z?zg1w(7s(1EcN(g<_?zXjouwQv{msCx`IQ@?Xib1tW;Fw{D7w`je|oo(!Pwkz2XVm zeO{;497xuk&f_S#^om+jM3&3_7Prnnsz3-k)H7Kdvc?crer4aM?Voh$x3IkGq@y9q zJS77i&`bV(dMF(b56`#X*4F;?;6y^2pl|#{9Vy&bCgb+wjtUhNadF);q17`7&{xU$ zm9h6!o@ZxNe)E;il4d!7`VXDqEuAWTI)=eca>LTm+~kPx^CnMH0Pg9KC>!<TYxs-b zstHwQ$&aSKJq1W9SDS4jPt02xe)`d>@`-I{&NeHllzQ4a*cTbQ$Jz@<304$_NsZMm zT3VVty7AJ~vl=Q$1w4CX=l&=kad;@&W`3sHqzzL>OS	Kf9}W`nu`ghaJ&o1l2V; znhiB6b#pZSQi>x_@Z=5{Y8@AE-TL^g{%epqcZwJJnkQJ89R`#tx>bDNoRMXkNbi74 zJigtl_a^>Lxu2i8^K@87Ob2<9znoB@XSK0AeRAWc$h$~l#EbOx-x#aRg)_>Ry%nWZ zQ@*8r?Y+fMHPiH-8Z6oZtQLlU!qP^+EW@QP{}0~Y`>Ba2VA$O>l0XOx(wm_dK|=2u zdWX;vQ0YYkL&qLMLP9lw0wN$yjf#kZ3WyjwA}9zdVhae0fEucZg)eWr^WK>|bAP&b zCV#+Aa&~j}oaa2xSowyJU5AtU=A+<!2lvB(1KEu9-Z(5lO5TbIcU$Txndnyx{L)@k zSl@*?pi$`{abRBflR}*e)(T~n=g*!h_=gBuB85J<=9MM={e9nQQOhHnHQ^oox_#P# zo;qHFq7w(>^z{KTzXP2I*eeQp*VP<=eQ=lb{+K@NyTW8`wJ+f5;|hC7PT@7^Oa*$x zeY|G_2x;+u-QjIj{36oqq;eKYAa<9zh+Cx(%r0ElE9OH(Ey~{j7VVkp0kBp+)8@9P zGhk$xXc+AB^qZt{Qw$0Sy}y$l(`Hg)^fMLb+8)BK6VDJ|y7l9<8AQDgNFy?0G}8+Y z-P2$dZ1r1w&`tP&AwGwHUGc2#H2%WTdavY0x9BoYoS-R<bSS;BI8(&C*}KOxyo5ga z36p)B6|KtD`+GL7GQM5cj6f=1H(PW_{$Pqz#auL-PdG$2*P_mKpsm9U644ftVQP&r z{o{ELlRDpL+__k@J%1w7eUtJ@&iG?cxfKXYsL%#RU9ronOYN7HPrf;BBS95^ThR97 zI|NxnwwBFHAC8}qctWf=5$uUH>Z2rB`We0LewBZSd3)vB&(g<ovjt%ud+Ul1J5FcY zfNe7iYOhRf7b43a1ljKJZ#;G=*Rws{9s#JCZv5%n8>i3T+B@}fT(w-71p*f85uQY$ zxL5P1G1)}<ts^H-f9*Jfpfy~PJM`U6!B3J*%&6n)XinaAyXvv|e7i+G=@^h?C74mO z^E=2J0&xWBO#LS-nk~Aevu&j`Hp~Kd!Pl|FkJQ|=D(w=ZH%~zvHo3DSQ#Dl22fI`$ z4VcnE`mAHF2TMF(0MH^c|8!&D+0a~;r1ip3zkfHLz{z48D`6R^L9=_E3i>pY)>+3a zgP}?X9`EIOUtS+^WskJGBz$>wpWKMd5l5K3mYk_n*>2gwKop;O8(TS;k!jZPWvL=6 zB>!58wsb?!PUnHV-(wE|b>PJf8p$yaIw|A*spkV*pJ!WikwlylMzornaf%-o=^|uo z_vXae+*{#O@n-P$pA8)IH2z43)|_MNQD|-Q{-y}DY~#JGuA>)k=mslKDIyP-Jg}FQ z!?TcC-j|M(N<@5wT*?Krhpt-R!CIppdG?8GJcOtAG-br;_>IU6oa8y_=s)fncbXw? zaZAK_A?Zb3UlWU31uZQp{9zNm<7B&u@h;G2Ae#j2!QBT~B~hZ%t;LobZPb&jyFi;X zl_b_aBl2mrKRDB5tJoxw=n$?|p{w4VM!iL4Qv=zOho-5ok02gr2zzholg|$+>eG2r z)tyt0Sx4hgVl22t{;lX`s>c>Zw7Jx00sgZd5kyf?t8`S7>M5P8NakiI<Lt8;osV+p zXV(iFh>v-Xye#!5Z}y|hD5-Lb;#c~^O;*m?EaWk;;r95G*#L?alTS<}U;cNFjqC8O z$tHL?a5~Rg9414FIQM7e5iKO&mz$TCTXbq}_(4M>Bm%W#b8#(i_ydvU2GAN78fuRs z{C}ypiMr0;cmm)c?HC>}OFq`-!lJ;<iLlH7h9|3V1}bz*c4Xw#jT0GJ0M8l70cZ@H z9tiSf-mU7sqAW>-vrJP+gwrV1ZFtoXGWMXn96;BQgA9=8Y^9QME*qqR9fGK2_88nh zpvPrOXQ^BILH_7xWmS<3l*ka`G=Mx7Gm@ZT^`R4#n5lLu$9hT9V$C`vF|J<>o;T-e zEntAYqx2b=bRrq)(kJ8<LUSkF08F4gPxxDJmMyW%40}h`M2XIK%iVk!Scc8ICe4eD zT|9~ML*>pWvQ}ls_#a(6fkK)PJ({eL83bfv2=doDm|u@@1!+DpH2<MSmu7o`RL>%j zr%k%|mLksW79b0E+xY>Qc3xKDI?nL;0|_xNrP@)cwvL_Q-7>{lBbf!FZpx13G@8KJ zHn)L>r|jc&DZG5Kn-}96B16`w{%!q6^?OSG*uHD2Hul=JW6&l@W5HDMaKgJ6rZ1U- z_waXjU7(Q*{E41hd8G*29>L5?T3ZD$l*8mF>#%MftDCUDC4?l5&};fLf0^kWr}<7@ z$!>!?FFk)3j$j8rqlCFnuoeG?qC7bU4!*t{Bmg-@?9=KdH8fg9qKrV8E(+)iL->NU z0bzu<I>Lji&)?7V9MYhhz*UDPYJ*-zT@gYLW#*RH&=&YIxMLKHb3BT3CYW(!uE96? zX81{(#;tR)^<5rg{J!eG(UIqlHI88%ftU-g0NhQTA)001&C8(-&B!bu#+wj9Yn0sU zi*K5jc{$6f@Q8RVQ0v)N`TBC;b3*Q|K?T|li_>5c#0YlG^<D7(*KUvjE%pwc+8)!^ zR>>63cqt_bJ56pq7l9eTF`l?0Qu%Xjy<UIA`L7Ro%gDW{b~~3*5U`OCjT^d?GcUYX zSki(F>(8eGg!_N3%*Q8~Heslq)i?i0{%dpRusDdhFGEMJnaaKmprEE8m3941xijM2 zuko9yZ$ID3){U9i7=fTjWF6kXE6-ewJMiWR?PhIYb`33vH^Z)_*$uyWKjb6(<m!Xe z;0a=J#VKDpQABuj&*^RrdcaWYhQ$Ezvac%NIj$7HMG-K2HTY8SXK+AD%mE~sEK8oE z1;7U~oTjE7vNI3?>cMq22oL!4ovf-HpZ6#kkzjkfgYOBG)xPv&la9>=%{x-L<zBQ& zO|8?Bg#!l}<(41bFF3`Jf|BuS^3C|uZV0i(EQt(gHnXahO#2axn)xP}d9hG$ti_{w zpzQ6TCjszm(%#Fy#j?Q+rL7l^_ij@ibH7PZ&K$IIkIjk*fc<g8?g{D5CctQIw6~*& zN4fTch_Xb+IDLqWL<KR&i;P-~j33q1I2Q)D_0!uB38NfI`*TRtD5g9UM=EKVqDZqc zxo>eqMzMMb17BV>f(EL-7JLoyV~`I^rOiHJzGRRfbf7GL3B7x>#&ax}2H%51Bb-7g ziWzqRGA)4I5h9Ye^Hu#*+%GtVpi;>0QY-!Ro@d_M3dCjr;dMq`Q2KUkKoJRoo1!p? zB3NDem6U29@<SS%=7NVS8c{8?LOHytCz|XoiQvwm9t5Ezt3P@06^sQl;9CF|oCh4C z+t57in5^THMwXcjo5I~b0kpuj(!ES-kRz=|ouaq}wP3<;bLU#vAvr(@(LU;9IYc;s zAvN_D35N2p$e%-jrKHxhF?Vie<>m3RK2Ovh66^p_{+N|zaS*P2M$Y*kBS6yKxSSHf zJ15i5`|dKQZZWodUKcI!{bW2p;$A}?$_-}HG@GIOIEX`k1;QOaG&|<Ho7^bMK>R8A zvXhgRFXM@_RE0>RGA*J|a$}I}nA)$bkUMn&S50W{Bt!rSuHH;>Xrp<Msb(zLA$(Yi z$y*w+Ge5vT_w&~Qra<Bt9d{*@rcMU`-L`Ve^&%mHhj^|IO6dTiyeSLcMtj5Rx=TVF z!XsD<Uz^+ulQ}|N+Y7+fg7+DeWdegweW;!gdo>%T?wDoGI6@ByGq_&R&HGv76<o!0 ztTz@PA3CRV9VJ{od%_PDHSp@A-PfQY+P-Fr<`6|I10~i&=_L5LSEH&U85+!y9205) zaK4i7=p7dFrCfXk4yv+c^kzEBtNep+8|^xt`lgEwaADaoP<jjn2i)8#BXY7cK23-x zJViMih%ccLvuWH9VzBOJ&Dd*>W>z`z^et*o`67M+vOJJL56J`;G8MTfEmW2m2Bu0< z81I6Mb-+jD6LOlfFJ5Z*AN#QRA@7V?>%Tbqe$}h5{AmBGKYX-9aeXd$vkEr^$Yoa% zVkf9NGw#lgKh|F{s+h<8Io?vgbIRrNIaiP65WfhX&FKndbU_knU}8T%cbCJ8=og7@ zBCU!+gA7)jcDltJ_xCRUkp~<UdY$OtyCVNHk=A@D549?HHYXOuD>)>^Ij$-Tkz-?Y zl#V5-oJ~@>wyJVFN%5G)?$=48$W_&Wq-JuG`ne<;xQ36meXPHG%|ItPC%jKb?Vh#} z375Y1$RtVQnvvQul*WTK^UJI14r?mWD7D+ks+ZTqv(~IH=PO-KQr?}cDv@Fl&CtA- zq<1;Rz+v6f1ts=)eW*Ff`A4$-<#o%S$@@O8w|y!T)!BHmm8@aB=JzAnNg|nEo;~lL zYVvg5<mYN2J<sp*IxS|cu;y#ks||4Cwd?N9LH63uXKO%tdl8G?W3d_Y<3JpaQ5?x1 zz7-PtdNb$Q=lGwSkF$|!toO(KtI7XMGbjuo0TIN}{|BbAwwM0@rWy27q?i7eW>B?T zz$jT&tG4CZ^UH+)iGvdkE565*V0;+Y3;ccLR-R^1X@4*#^MdkoQ5`6EnLkmB7Y9c= zJN=ht@Mcnh%Yy`u>(~o#?4C?4AG(8Z_#^knv)ERE--f92pPE6Wu#mE0YE<JT$SKL} zkvECgp4FT!bQJC|=o^)a<?8V?gK?z><<6K|L$%k|x05GQJy%~Dychfn-HlBjjLcUg zi5z~`Y1%D!7yU}U?ZkF(khY!aNB4Cxn`LSLxE=V9(l2>fNE&Va*@s2-%)vc35<DKC ziQAnAb1fH2qz^9e7e#+0>#m5CQ3yyt2_+5vSs)g|6n6lkw(dfyM?H731wv5Dl9{P1 z4n+~UGl<z7^{WV~tuv}2$7%qywE=X+&m(OVOfJk8YCU2xRcCW1`IFC_W)u(}qv5@K zql@la0}fbaNi|omwVo0!^kxsr8m~b_gQ^7IGZx~?7yb5?@|ebxzwl$n&b#^4C!yQF zf)@qjqZBWlGHd-pAdWkE*BrYwmU(;uy&l2eC2N2PRB5CW=}^P%22u!VwFsmX;3*`? zsd9)rWm5{s;%Pi@TyMNTEkfDVy%Q*0-Sq0n9=F2A!MSU2ONB9kiaM3@GCrpc=I!0x z%`Ad78wVFF)RF;iJ@}6}_?}yf%==SmOYyGuvZ83}Zt)1Jmh1N(Z{>i*yDHgGt53VM zJWdUJLtR7J-yZz8X7K1s0hMxEXnUBH7Lgz0Zz$gR*dBAkN>ch{(SiA^oUa5a-2K~Z z99?U5NV!a_=vuf!C$U>lF9JWTYUOzAiNWimYojJ#PQC0CU0EIv`1$$f+L*0G{Q9_K z)?Bhjz3R9138I7c#-xvb{Km_GXiI||b{ZRZUWL%LH>V=}<GNo*Uc0q9ee}V%&9|gM z?Vs;bUdR7@pYi3^&kv`5?tJ_Ck&N8C#i2?hWaR#nYucL4H~zl$iRrNS*W7vk|IeAm zt+}#e|9&l8yZvu_`N5BWzqx}tJAc++AKUr6_2u@?zdt{J?Cb!T8UX3YhDvk)|BizP zjMRxg80z19VkIvGQ!hE_IG|Utk{{z*Fa3IGz^G%TfRtY^`^9n4Y<i_IW29dG=g{E3 z?Ui$6Oal(-G-NHk%4E1UC`vpTvNu~TV&*p}t2sS!4qPoRA8AlEe!}wtu9nnbuBbaW z4SQ9ro@d#rSctwT^yv^u{b0f{<kNfVKP{5_b867Cyy$7Lo=sVY7RoHaY2?|PaQQV! zh9$IlgvSM5gv8ieyyC4-imp|ZxO_H*5`^N$dga&2R|yRY%=r7^<x{R|bDu*C!i|zI zq23H=z7N2rirUJ5{*4hG9N#HDIhKWc%Z|3-n=LdQP@}X02-yb;Op3Uz+%hLx>6U4y zH=He6j$)rgDKfGf6@Y}HEE#+c9k8fV^d5uC@ZVton6F};WILc!350w*R{arV=-EO% zN=Cvjer!bTgW^4mhx3$gj(jy6=$`y8mL;P04J{2N)kFC-fEVBw`!hFQ0!Le<ppYfo zflPO!s1)2U6kA_UQHsv-mi?$c_`_bBtV*sGfPNj^PYegSeY3n}Q^cM_x_MdlbK<R% zL)wQzC#aJ>I1-B@_yWf?<k)8p!N2IWFFrfQx1qQ)HDIL7FMMXYq(IJcC{RT&GoMq> z>TR(FhO+qccKGM?>&Bj``_%Ghj?_I6eG{XZ@Ra#HM6o_v5YUFYD8bS$;O?cM0(R#y z164JE?U)$gYT|pwkWyWI%D@ryDw+C6=@wsNwpHLsP`M8W>-lXB43U_=<<_`rNk*uR zb#?z<Bk}wz*R8`6a|3D=#joPH8n(5$9tM6qThyqUdeQzx{<+H{IfF!+6Z44V++D;) zO@)^(V3e}H?1w3PtA|#C*-;Ihuv*x6NnsRaB<#LvcYy*%m~1T>CcN#6qR}nDUdaO@ z=N-KdM{jf1@7<M$y~#EVmL&`Jma<j?BKN>>g+M@wY=av^CgUh`xwKvWPNx!zpTIoD zEZ@Nqv1GI9acnB1UN%VF(K35lFf&D|L-YV24L0`TjfN?3ly$_VnGMejvBJ4#q*(Km zm$^P>3R3Yj@`N##)Sx7H6SH9>a2IPT)Nmam70YXxMQ2RbU-$qZO{3i6NL#{>AkEoE zBf{i#I3V{qCelo#=Q)Y01bh!cn$O;uPnhb!JtbrlLbO0Nlrn@{CC3m{M0bhLiQCNT z?9I4Sk$6tVqHU{>gsA)O5^QbWCdhs`f2#_ZdyQ)&+X7y~0-o=Fo>?Lw&B}8Z3;U8T zeBR=-8MP{;RDO~@drIGU$!gr}X4dsN^*F0{Glj|2`kGLCdhl9h6p8cc^3xp@IUmsz zwYmCz7xE3u-r)rYkvA(^&9zPV`8UV2ldfmHpEhRb%<q+7w*b}cus{8M4VZkm>sm~Q zo$XA{S&8Ng3x8T=70whL@2Z#kqqSw9?dF*pd=ZyI=n3YdPysS~{zi~p8#3%|<yNH_ zgyC(MaVh0dbi~+Viu~(6vvHZ!i^@v@4kmM%&jAB@g<T=ZOZJ{WM4c2x#O3P@3vcvV z+Rjztzor1FXC9|GO7fcvYy5Y>Y#TUdtW15@<e9sTWyU_f2q&c3<V>REzAcH?W?OaW zSqn?o2(EQ3(t;ZsMI+;~jNFb|dAa<V8(r4<9g<B5Zr(%>JQ3qdJiW7Vi;m5xv5}RI z&fB**erjah?elAAnkMIm;&F)v@lK+h+Mj*@-b?KUeZ_%~Om9;a@bgdc9~?on@zL>C z@c9?m0X7d=iaDaspBgR6AcAG2@FqQhCO|$s1OZ_S%)UO`SK@l|b7WFlAcTk=8WhjD zhShQe=eZeip5QA_Fi;f~y>gVOlnNoH!#y!jD{t#I;i+2wpP!{21~Z`$#HR?#-8DsW zGeR&lD#cHl!#x_H0``KwLfyPjHg?0n&`vG2*8w~)1~h{a^4;kfNLfb-fFl7Ys?&NV zu;0h9Ur8CYo>_2VA#6X$OOqePf#=c<wP~nj5ukFXnV;y-j|=7Bxu4vZnV!m^>qNw1 zB!oSPd=LV9kje0eAtKlU_d+uNCh^-?XF^v546o+gE;(~m5f0(Psa!q?o96uq1yzv$ zGpKW;nIAcGBA1BqSIN^?h6;la2oA2zg=;s*d+bs+euZ{X$2T%_pev{mX6D_ReAXJa zm8E)y2=37XUoi4U?K~ay`FNJP>rDPyW&!RKx`|!DZ*`Vxn>$*9{TzbD45^VBp!^u9 zAE4i@2sRP;iv#rgRz0DfG0@s$jFdA6)673{3P*fEL)_ulB*As2pi(^qC9J$i#(r(a zE^{f$-p38S`Ky`}>;c#)SpdR|<CX%+`F%yLpXhK;m_H8e+D!cmJ&(r~2tcr0ya!rJ zuZs}cNTM1j<uq{wl=@K+Tzr@zXd{wO_9?uhRNAvH2vx&RgTOluSR)DCE{#^QLEj@> zFiPgXoGGV)JIt4eX7Uzlhm13t<M-o1*n9@zt4;*Ny_F8KLoh3BEW$)D#YvyQlB1GA zm2$_T<K~8V@cw<8ioR>&d`4jghzS8-fk$9yd_smnQ*#3EadOtlr0+iosSKuTShW5e z4!hdyTnS(hi4|~NWG8@~Cm#7Rky1}O+{V2481D^FL?;_xN{0zeHJ^GEWpE`bZ5C7! zoGJOblbr2<Ou>JpwQ$N_9XAeQBleH+Ju)Jj-m5TOi|t51lkiJ0Rs+-y(S<>T_I}-$ z$jZAtg|YZ*77^<(djQ;K3cmS;om2Ps=%w%i@A6R~Dg?^c9k&6?_2VE;F^{vn1>f}x zaK}g|Y%iliiw=|<c3nKkkpi5^!0#;n+1HFMv6E1%sv4U*o<-Bu%P+*yfgTIKWDEB2 z8413wgC;_?$rTWGEq9H7V*uXH1TSrxzQk3+i=wxgQJE2?(WXYd@W?L=uo5Rk`nu1i zt{zs)*FmbeqA$oEJ9w4~4QBH`@E>f!UW2P~SsoI(6&`Q))z{R=*P!p>(W*O<W+~e; z@_b<*i47_1Xxf)JnzPZXh|;_R`x^)XHc5<aKlDwTVwl2}blXbAovX)SiA%<yHlcn~ z|11O)$YAp|;p*y=Yb657!xtTFiAdNAmdo@;R~QMF6*-FlYItxOIPoLgb1?@Lx4T)< za^)ovm4PF(q#d+KV1a#Bdbmf|0T7P^dpB>6JA+Bn>M%%f#l*qOT*1a+``@PEdtNJc z>{gn0tz^Z1cUCa3Kh9+DO=Skuhny>gq2GZ@(HE~DX$9cjP%Qv6Cs~uGlzlKN%7+9F z4)1%wl{$sv>mVZO;7JzKH0~l2VIp|O%t6%@R3D4$bH1Iq(|h};693Db5=7C(?5q}a zx8P%*5)}~AT)YM2UCzU5(eYA$X&|ln7L$y=jlV_iy?t)6UWow`1RUOlU|+Sio=JxG ztlU{%L)`%Qt?EuAfAfdDG44zgNR<YHrGcOd5E<j(Iu?0e+Qb9|u<S;kW`TK9>q?dk zk1p!QgQdW2<Di?fx`OGKl+STJ<u_&Ckg<!-4qW1G>aJ*Lk@{x1rw#P-Wq`jOkLI@B z%NRU&dQH$U>_PF#2Ye7rHdF9cYfW?mM8pMrLuib8XdEFal(f-MC!q2JSG$@_?Kpwv zH#8aM<;Wu&%7FjSq%Ps^A88O87&f6@M4#OeXj3B~-jcB$=KBdEKo}7$G&eaH_yDnj ze*M;-3o3QW00<&P06<THoo7n0o9lubOtf}L9)#Nf^^6|Q+fU+{q@HNMCv);2!@f!y zsE#uU@CS!Pu1w$Dm!t`X;VzYj+&fz$SbP$czbcWG+7)J7dULWnd*Tin*TDrmf5U>` zYJ$&~x>C&quR4R&F|5&&y%rHte9d%&#P=IUJtUR?ASCr{i?g^XOXi5f_I)<9mxAZ2 zLz?@6$q3q~(0C0{>Ueil3R92(u95}6joqW$WJ4SgU!1{j{`<egf=};JkGU9k@<wE= zLslDbRCUh}0v11Ff(8Mf9T55E>%cdgo={(mlq7I>!x*07;Whmr#5NEa3tlocon@9r z<KbI-z$}8`ESvssZ4kbaeA2>rkzAMI13|7lDXGVPCJN<q`awLr%d1h#Vt<0OyX$Z5 zf{Z@&(blpFEG<1AT7*um+<!;HH;*as`#;fa^Wc%D;?ig30}!w!MSLWG0vjL;5DAEF z($POzG8|pRX%OfohCg5izgyO9wE&|4q1Q`~bCa>1lE6$D-(RIO*NBwmB%z<dd*~XC z5b~W8rKeB@2n3IqY<33YC0=k_mtS<{_onwTz-FQVIr_Q4sM=jKaFr`amo**S14ah$ zM9*O94o;HulUeLt_4_5pRz2Vfc|vVem9q?4wl2I}e<4Q;d><!~JcUt|MyCgxULl;l zpapu$O<F*oiN_wP)W;IV_rkje@~uXMccGiW<|-wD5W^=IM*0G7sTKyC{$Qe!p#uqt z$0j%6qMyf0lTrR|Ao0&DwH`o2P=(9IYQHz};-~R|_9;Arq&op07YI$1)p%&izbELR z#+3PN{+rFq+C!#`V|1v(B?ud}5i(h@0?#6$uM_x7o|wjrzKQgj`uE4=54__)n%>Q5 zsPO9;VazBSO+=x~zL|zBC}q06HD3juO~r|wGF=2ZJXp7D<s@oxf|Cngn^&95c9g>4 z5P{N~v5mpkBj04v%oiRUp=mZYE#8!dMqt6VS!s!K9^6epN5}yR+Gb7Bh^%JxcFe6W zqw+$8_(fSD`=+U8M;ElMJ$|LTss0?|gX}yRd&d@mBGe<e@8W)asM-aG-h2{p=kRLO zhca*eL2a-o1bN1wJ2u>H6?_P_s(*KrQm0g%J|$Vjxq9sr3VA}HDQKqGs-EMj0E5ib z?P^OR`=<$GUU24`jOQ+W`c#QW9pp5@75IIg*@tW!J<I5$OFp{V0*8Wt`!mTGYGy7O zs4h8xgcCf+6&NK2AFQ^Yt26@f;K>AX@IkYiE-ohW62~~G<IR~bcdnZzFO+>32k1n! zJs{B6$aC7x+G3^kV!G#i0Tcmovz2qXMKFxRSrkAX&Ye2ui4Nl+=?sBb6En{%$F`05 z5=fY`E?JTm=!6HI-cuf&HnmYfBD#g{%Szm8{(M;}h1q=Tek2dR>o*a9`{0>0$Q;7k zzi0Kb$a}zTQ0N`-CcdawpSFCtWC6kni3O0;YGC@lZ<WHM_v!_Ns-|oq-)fG49|}y* zK6>-LNd|QaTt8&m>IhB3^NrUC-Q5(g{11`t55x@GVbJu&hvC29rThPxNhg8J+$9?Y zbU^dVFY-XCyjf4-VXJ_Z+HT5>b$pW&yVD(djZXr;BMr1vnNjf=OwMZKjNlst1jaOX zz=MaMiI)Lq_UT=?4ofbRT5sjPHhV7l7N|zyj)!_;e=x^uS}slw2rVEb5>QX-V3%_7 zXzPFLH7nS!H9{erH53=vzh9xTH;yM;O+77MG3L#l={Uzli8{sn?V0+$IUMC70e%TP z`C%ynE4|M|@B5fwK^cI5C9qAHwX@P{goK#*>E|-%&l6^{_Dg!5_{;}cEUc}}VxhAJ z1SY_-S1&SL$Ri}rbfq0hwGC8O>6Jf8g1N-A_1wkFA0_u620b5RasMQaWAW>5;`<MR z#XxQyy9_$cziYo_Y6zy2B<q<Tu6K=pY3EhN%e!5V4F5j%kl6Pzbd`X0ekMup1oYoN zWRI%ebb&hHmVX`*^)e3b+Cm@YqN;^>$2nBlY@pRZ*tQ%GXn67eZ>AAd^r8s3toOg- z;Qw1QIC2r>S0)pPa&FZ+p6hVwNyP`iRtj(Wml^UX*}7`qJo>utb$2TVtA5S9uLwj) zQ`G-3jXcd@TH}6A7{UU_`tjENUh20G1w(>z`>D=(v%8|PKYI1b_?~Oo9hp?m#t7{< zYIhRlF^$@X2PzM&MRh>3F(?iWvM{>$tmY)CBjsS)GPJqG|A%@oWou{b%|TbZn0i2% z>@EB2i|4}z3g~JU7lMB!eSWG`%@0_bk}fv04i8oz{GImw!sw$C2?C|}1Y|f>4Xp!| zWEwyX)XB3*>+Xfj`z~Mhk}Cma5nSgtyoab_-#&WH+KpNW5`!!Cm&eqcpBELV*(G2% z4ln6f*SgZ%Z?=qAP~Z$jih5dO05Kno))V0X)o@*Vspy6~_P^OVEDNdL5=Z&teZojt z(#ZI=YNPKs7KGxHJUURu9;e^VEagJY;SZ7{aelG_9C5mQ(VVcS#n*`QdLFU;Pl1e? zD^G)bPT`;VLz(*G=8qzj0Fw+SyMAw@&KFK}yl^YgM##=!hgZKMa3BzrvxB{y(p_yb z08?h<{DN{_Jj?ETI_3k4k1!&=t$ok1#hYJi8TLIf)Evctg-k!u6Kq5O;5^Pf2L8mB zVZh;D^*S1U5%p=xEF)CK%maC3{y^-tEB6EAKIPg#fPVsj!D+%bSK{s`-RE&BT{EAn z(yz9Qt4>2XUoJi6atiZ}&~+-chJ5@{IGd=iDz$;6M1(|^kiu2aVo|-m@J!LK=o+8z zohqdsTJFzgJxITli_Od!SrP?HtWUc<udXfLO!JRwk1RVp5NAPAuCeAFTYg_S2q=b- zal6Rf_LqR6SpK?ga^`Vm;%*A^OKXTSD$gvT9ljIENg9vGT|jDn-gPMH$%9dRhNsE} zU}Rtau6w>0BTEB<?@XN!Ahlm%1K@#)Vl7|c1hW~U?!1Wq>;k*sV3a4XS&lQMius8@ z)sB6lmX3B9);W8CV$ghiuu?U=G31N*hjG5D=NhZB$@%M6C~CK&vAIG&EXK(Egr%2y zpbyJhU7U6MNMkL`M&rt!1K+JsC7)2k@#lTaenl`PUbOX#dDxoHF<spMCC9ydjND&m z_-94+)SBgd8t!bV5fKK5j`2F{i$nIZ86#5H6jNWBA}gI>Bsr_iE7eJE2{K+iuD*OC z&EM8Tad&Ir)}3=Xo-B&k4dMjBXC-&;C~HR-HY0+{vB~vjS?{_x<($Q*S2aJUN@^<a z75Ko+^R2W_%&)iGgZpABZMO$#F*yu+K+pX_d#VoO>jFrsEdZM=y=wA2Uy)7GFQ>~w zNENn|p@rLU4$^;%O)wJcI<{q_e*;C9j8MqQjL;ymGi|N+CGxENeLi>EaC4Hg-Sp)< zCS#sKKPq2Z51eO;6)_LVCXDB}1cxQw9#asC_o<1}3d59S(Dqmt*}8k#?w((YaG3%M zh}kMwv?*I~UAPdM<lrQYA_$}jldnF?Rt`o1dm%Ah$1-5MQ4Ovdpq|TOUzp;%OZlm& zS)9`$W#cj3AU+r__X)})u6`%PZV&$}x`ZoKyzptYQqYRYkg3Mu;3exU+t5+3`x8|^ z4937_;ljOj*P>Si$QE<H#mOwBkpGmmB+?pAXnkU6=OS&!4K2utxN|<xv6nDR23-Qe z^zf@QgwDB#;2Aj4e}$?lX#%>|c$U8ocGa})&M}57?7Hq~r__RU+NE+t5<=>$G(vk+ zZyKoHT90)}0IN@=4Z^l2v(4TK_ZKyPGWy|IXU1J&dhmtFWqHDN#Ql(gBWV3Y7y1>O z@yx?18zNQ2{s_PEhyKCOl~2mL+l+h`j)3<l<juU*AX?=F)hO`a1rQw3*F)G+Z({#g z2vO|eR0$bYn;+@4quT80v%VFITLBgw`(~Jur*4xGY}ZSRArF>8{=|DSLkjyc2OM*W z%B1(73`Wy*Xv=uhg8W{A41EEaz3!TG`S0?HiJC*=uiK<@_#PH672iC9ggDm;nT?FU zJMUVic=7asYq<IwHk{1FTSMwmT1B8s%B<+*(f&XfY4Cjern0;!R@ET0Gm}jrYP=2A z^byWccg@_@!lEgm6HygjWA@_|Tir8O%qFdL6`CYUUCtsj{jSi3i{N1J{gQpug=m!p zb^>VSa`6yJxlsOiedMeO7;MlhQdZvY`|5<I&h;?Da>|p-iY81uI0t9mpz5mK&8Otk zv#V@jarXX>e}I~lJqT&e(o*jf;k^tGYlYM4w=5#-Z0BSek`mledWEA2rYim>mu187 zVMAkzs18PbD9>Bw65?$=Da&x^>|k=xx9gP?F&f{WVj?iT<)_wghWkU&3dBtDdolfc zP>>u`v%PHwt3#CA%Od*6rYDM9@YXdTdG8?0kO0YCs>HYN!OjVZkL``b3iH{(ah;dY zcIa`&G~Xk|q|=*gmHHy>{lqorpM*Yqg08CVx!L<=3>(pqJLs9<*<E=pDf)t<4t+OP zCe&gbu06I)c%lLTXpOqGB#J@$0{yyf?I6L=GLu&_SIs8(RU3Pod#gv>TZV65{w2%Z z2{{bkRc`X7!eBi2yVH<Z6SrUV#7J(rnTSXW?u%jk9N}d8JC)ZgWVwLdaLUPd3SXke zrJk`x6YG_8+cHpce2RsRRSA(w`<z)5)_HP5bHXW_1**Sqfza3AUw41@dVxMf%AFe+ z7*KYc22^t0*<s*8E<z<3;_iKg^2BhPhSL;|EGd&yUYK&?zb$+&ZK~6L6Ghm|^-OAc zXlK98x<cf*GXb-?J9{5qkDOwtj*jS>R!eT5&{3#tu35p268Q8Fg`&H3sTF>^hqS!z z@CRb<A9-ItKFjBolaf&P{n|Chf3tGrM|oMY2@i@48I0{rQ8oatJ(@N<zF2LtlY03} z-o40TrK3X`@OpS=pNx)M38xFX>ysd$-%wOL!%!4!Cfi9!X6Dfz_pDtTYRj*n30UBJ z*Y`A>-qr{^m)zM!Tp{id033P!YrV`zvSsRs!fJKvr=RwJ_~M85w{TS#+e|1#L_92S z&cq}Z)ybN;-R9DGw4ybj4eqy4J+IF^ywwhrQ(JQOZ|tE%Dds0hk4oQScQPMmavt3^ zCr{g;NLzf1!-c7w$Nz2$u_%mNQ;jkhD~bu6!nya<<hlY+T0`u(Nv_Uh^7${oJs9lB zIypb0p5u^_O)WftQMG%nhiBIlwLSOP+>(dBy}&UbT7uG@0x2~Qca9WgWq6<KC8~1D z^P}1of^0y+<($G{LDx2<l{z(w4d;_W;cIpo-`#gqV88Tny|C5Xy{?br+W1Z~9*9D1 z948AMF5We2EZq;N4ms*_+6)^Vdpx;tR~8})hZ?p~vU~$?>1Nw+Hw~H!Hw%zmaSV4y z#B6V$$3wwb6!~~fUmTmBhPrd;ys)mTVr>qCw}||%r8L|?fXKT363`iTRDjE(!js^v z-@APAI+nHriG78m&b1j6R!Lf-$GBDsW>t~pj6FvNqn(hk7MBl&NV>KWc$?{+Te%@I zyI2<~&Kb0W?{3E8`JB`h3QCH^1jrghhmu|G$8o5Qw!R%k12%!%oIYD*NkT;jNVS>p zpUf~;8oth8%LQd&tfq4PmUF)e0Nw<IQ#0RL4#IiJ1~G!AE29Dc#eCTZJCI@PP`S&2 zmO16wyK77LGhwG#qVBn@%nUu2rxS%hBev!peMfb3ymkwP@X3J3F&|wTVM{4wtF6&8 zhY$$q;rl61AB-?kVvyXNY+l{`sgt4!hng9aO?7M&>v8VH_3Z>QyaT9-TTooHQ>EzO zH&hSeDK&+HsG>fdzl%(X=^mbR{XDIeH>H(Aw6XD|x(^puPpV5y3}lj(4^c6PO;8tu z|1%WNr1byUC8aA#S%5l~kBqLjK3*T)sZ`*PnNv=cv|=ngq=uN=%?P<`j<$v4bWFt@ z8FG6fMmw5s%9T(Jh7fL!G%o_pZYtYQ9hhFH2eF@IE9(T-jBrw(|2&$L;-j@qxj3$c zj5?}jt&7RTp>8x_9#Tr($KXT)*t^cRs`Y%@_Bp$uaJn5{E`#DF$OA%Lwo;nYaMA*g z3Rg9p(kq^(NHI<^P>CSBz4bb<kexnUQyru;{VR9CK){o1Ha8~S3rE7;h;ON$CbQD_ zCdbf9&vuVuQiucTdgH)Y7JZ5ipekMwY?cG)WBK<K-4wlTyGBm-$yw(4ji`RUK0ehq zF01l%^BpFbObt=bc18g^8oOQ?rB1AuNStazMq>bBH&hBpAG1B@EkG{tVI&hCR`(dk z9GCTNa~~!d;kBRJX#+SW9WjsHO@RlqFB#vPbg{IIR~IrD1k4JMr-odmH0Vi8WTO?7 zMxyV0Ql9lf-K;INwItgAr5F;j;+vh;77M-6d{JA14t<k{5wF~KA&(Ln>Fh@7950Uv z{m%*$z0IDh!T;fW3*i2z^NpOH6*4wjKB+(da_<o02<BCy%IjG(dUDJI)lB3@hS&NQ zpRb#HwW2KrpC8|k>6N7$vfSMMuVj4ymEZ2%=`BG}^EK6Xss?(;(^T|N3WKP9#V;SV zllc(STbX@=Np~Rscdb72B{k|LCJaUGvVBbReRCo54RZ_TE}U82fpi%g%v5LM=JbW{ z2FwIeW4Ux|)=P^Tx6>I^BJRyd`Q$-b77v#zIr8QjZJOm~tb)4X5R>gy{(2*~lz;k7 zRe#=px!0@%;LcOos}ab%`9*{_dP>DOi}tqd!rQd4>>!Tz?wi^+mXpKy5{C@9TMgBE zA=`n2IO{m%Iax>%rgl^YY0dTx(B2(B{ca6S4QoSS`l`g<20nU;6}Zl{%Rrnh&$bJo zW;F|WC!(&Mp2iitd$lndN`!xVflOyVRo?Cm1Z}<9a+QK)UwqL{A3^AUQuS~OqVPOb z`h4UaZE9dQi@x@hhxO8rr@UX18%$Imo|~g*3#wp8YQ@@b)<4ScAA>v9P>b#fc{a-! zLbCQ{$h<r~J>CCdoA&gu^eENDOG)}308*pMY1eV6cd_F8X0bz_xRVD3t7Wq_$WI>m z9w-zr{(XgW2vepdi85R$10<12W8Q04MxxXDCvxgdA@Wxzu+iZ~Cb{)pM?>6ec-h;x z;pJCI%^&y&LZ_d8q=p=P>6B%Hnu*$?@(J`fn`>NI>Ivdx@yRm+@wC26L5;O9WUq#` zT)F`)Gzu-0nJg>YV8|g;{40WF#jA1@!tDAdryVM8WJ%?UM$@dZ{DY56T0bQjNn0V@ zC;KSOt5m`*{m(t2%~@6%w#!#O$Yg)A`Pb?bM9D<aE#@2e)((e=s=k1_^5CqEoABHV zK~+u+bNe}uYCViS>Nr5h8rI#FM(KWMoZt8~@$e0>kc-3sZrMRQMFir&{9Tzlp*3`S zcRz)SUH}CTu|R}Zuwu=mu0D*|sE@opIv@Srq|X|4ibT)rtPCNy`vC~ll9K4>9w+i# zdun)$YV=SN^3)Vv?)yZV<d+{1Sg<WTr1gzOj+y@EXHZm3z@Vosay)7C%WN?+)*h9X zaIF=S9R%9?+Uvq&=Rt$MKu5&t!2>&n-?ArveaTC^mLhW}j7<;MRtd%c!Q@t8tKE$B zG=#z8VT~xiH{o2w5fpG3&!^QBWBhGq@5p7b{LDY`^qXGDICp6)=9d5*{Di!-IZ^CM z^WpM+k1NDqJWKQ#(W^@9uWbE;z<Cup;AV0oW0UsqHDCe5TZiKupI-bNcI}nx7@_^= zB(i&J-b-YWhFb(A@jjl6NF!4#6y@8};5IGRVLhU?a47j9q&)liXx$>WDEr`1giQ@^ zxd_wutv_%`M5^#zc*tBbaHPBGp`*sVx4fv*ByseNnt^7Nb2h5e$P|}!=vmsgyEoPJ zC&&8s?dJYA)pNhobmm*lG-BtD(cF9Y{b@1$r&*LtF#bV`Aj1!pF+>!rLU<8r1_O7p ziSbFvEinLMr-9Q7Psqn0scnxQ^fjeP(w~UcA@pg#6;ak9FB2{JHm-0&{;~glOK?5a z$W3!eVR}$Z&attIz@yta(#_|Wt$CY$N>kKBL({J=cpMH<Us@R1_8T<70c{p^F>2#M zL4dD2E64hvMUQPGnymWnI=|5}z@ZAAC#8xG-`Ar5J+#+?bI^a@`XBz1$m2uX?k;gt zG}6?v*w40EzSWoNS;izsgi*U6723B*Ew1AfE5!-PCZ+cEf2v;XRnKl3XJH*szJ8DK z<hlFf@oj?l9(Atn=nqC(h46*H_`ZNQ%c*WQ;)!o0vk!oM9v={54#|5Pg`hQLz=X^{ z$hFiF5cWVB-E|hc@m(XUNYC+8U;tM(jeBZ4!Fu=L*DD_n!68O#*Y|DFLfLXHu?@Pf zif@j2o&40cZscQfmGArgln7f>B_?wJ>5XP!<9AP1pv^6#{g2d8z(Io6#=eNFSaMp^ z#yal>A#04voFY13iy;?5&^?bki@kSR_hZO`gw>_gjqsnFyuX;;*JSNtvhS}xjZYEJ zwzX7H<!TzGP)Nw|olUo=mM}@G_)d2O%f~A@p#Ml|78^F%G+b%;P`QQ`d*X9e)z7`M z=T@5?N-iOH!p5!uLws7rKb7y^*UO*=Y(4cS>TK93^pe+J^-CXj+@u+s!eXGgr?v{; zYWZpb$`_I0K3WI2o&Ysv=ln-wVx!LW_VY&kQ~O`FbTyqb^t_L)o`M6wSnJ^!_(|MC z|FC_G6(df0>+X`Sj>`6}FWcv1a*xEo2`KU&!hr_k-K;DGaf}*Z66LYrMI|1L+uzi+ zUaYzkfnM5P7V8E~hMAi^&Ofg^;VER{N(*!Fq>-tCAh~#YvornF%U^_J%?lGt`6rU` zp^xEJySMCqYAl326~o<*#v(1x{#kE%#PvH@@}mviMzP0br`H@CSR~ze6D?ePvcCr= ziHGf+iv6>FOD%gg;ib;sV-t?kaf#c(^r<h`{mbLDXYR#W6zLi_y&9P3%laCN`aE;{ zVH{^}t9~dw=D3356e)_4uV<8$2UlRlcAiW6cKcy^t!1j@cL4mYP0(U>?EW-O4NSg$ z1Ih4)K=Y*yxwsxGzl7e=h5w0zs~1Vt_(1RnmKRo(hM0;D#agjmvsZ!1Mg(sXS>0ap ze~W{gdRapu{I7p$9a&%KjzG#F#;yr!OtORy3i_OnDy!9l9Vj>=Mh30@U;@tCacN<- zS%;qAjbAE_S2@xZATOK#UHiY|;16mufth!IwNDuY_v{>YZtu2<-b%E)Q(h;hJjqvl z)%#kX;yVjxQLCXkH$_cx_Qb;EjrWT;Q}U<T2Vvb;g5rN0eSg>C;_S$(YwCF4WBE(~ zm(X^k5V;@0OmPz1<9nk=@pd6Nb~|YFe9({Y?`PVkJ`R@X9P5g1(-jq;HP^9dv%Uh6 z?oGceA#o)$i|^2he&_S**O+0K6Z+qU=cvFn1FCc&u6J=%VdsVS2Uju5Wa2Jad}!+6 zz24dbwQ%B7LWpc1zdvMb)j1mX&(}q}zUH%H!HLru;8D$PZ>4jV+v+ckbrsgx0J48g zsn|)iuLu{W>@yaqcGsF;BSPc2O6ix(2`2NviC-$^JHka|rrhfJU4+x2rIF7G(KljC z)XEJeFxEF)x1tW{&$dT94RU{})mSQ~5uwOb&vV9*cVg=G4=#i`t3fck2>g(kxg50$ z1P};RA_$T7wYeuIvrMtA3#<&43eB71@w@u6`Dw}FH%(_Iu($5ntBM~PfrlV<AT_fu zHT10&bE`WvA0Bl~HVnuyT%`_b-FsQRQD}TIAaSM~Z5kEtaFZfXoR5}Qc2W+P5{(2d z75x7G@XU=ljuE$pU#II=MT&&^2IdBD+qR~6^wGB7c}BOmAj_#4);^o72D_g$WTmBg zD)FXZSf}owSmrJdO96z@+Xr&ylUQ?ArM|C(op$N~|HG<6y{ciu!%jCljh2F2+Av>R z+yL8e76vw^S|Xz=usciFJ8aDb71cakZY33+hI0!hxw1~J_OM9nS*>fWVJifvp{3z8 ze?^7S+m1~wGK~L`K5<y}a3<062YA253Ighn2|qYm?5wG-ICt0zkvVPjskgR;HBjKP z_lAkNv%$AHi9A%PNE*)8`Nf}$VQHVQES0u=y}on(xwWz*7}u@&`qgI2EoKk@S4dx@ z*^leKFU+~eoWXPmzwF9M<AsJNiDgDQXQb6zF$P}=Rn4+&h15n9@PZ%Tj^$x)8+zX_ z3o{Pk0nDj6XaC!B{X(-ZeN8$RvsypaRd$NYjX*8<`$Fev_nAkl!k}i5m!m1(pN-hd zfZHv)0sJIpdh@f0LaC1v23hFOtyU6;9A6V+tOOioBkcT6$iuvcN)Gx^Qb)ZNFoQ5! z)(8#|!cG5WWM5B1)L@EHWML=)?N5b@z0PvCCQA0Il=el!uG66x)%)KM^;#oyE(y|- zz*8Y(As@lR*el|BnfVI94T9h(7K*-ezD_jylA^3#adD!pZef~_+YTQzv-U!LME<7{ zMUfY|e!&!~!a7x*56=4Yu83g0T@`X@YRKu|JXy))FrdubC&IQb{<W&~sZ&J2LMs}_ zDw0<y9xyO$U%?S2ZRgZYt9SNNyh`tn<e6d})kRo@JhY?r?i<2D+T^N3YNyfxquz_V z&2ltv<1T&YtK(NWb6vnn)={#V$T0kH*ZfQKm}$q<XkxXU+`OcyXcUeNNr{7I@P9H9 zs|C{pUCjKvDiuws&$C7rgdjk_)fh-VP+nBYXUV!dIU{*`GF(L2<l`}My~pS~^>xcQ zq$yTJ&m#?9U7#eO5vcG8Sb!=tNh(|OnYNskr&jFJqgi8~Tz;p}deunK*BA<#qUYEU zXxj`SZBic`*9AVaE`?kjciYo_6c=bZq+(*z;t>obzhAoKqIABFHVF}kCr-QdYWhV& z3<L3Bi^O(?2?SN|5Rbn2edOs8;g<jt6p0Id3S1C1ytb+s3zg<6VrIwL+YC6(nE~%! z&#EZY1&)<}*+@yx{mRk5y>B{7E5>=MSuwT6Y4}qpvKT;G5Y$1*todSFSkfUe=gQ1p z(P8mX@eMb(7f-H5_uj~P_m3ghs%XW>cbC%k9y}e(LOPuFDM&wcNB4X~af%iV^aXVf zT;5)y9@$eAeWdKchrfFZ#w5tPa%ub%l3H}>Zo$S;dV7E6?5w?l(OpC)_9wuq(p<|e zQv52C8gL-JJCAsfzuf*{g;k6{o(Z0cb@)L*QoYUHJsNt%b~btlq&r1a*J}aQG2t>F zO=KekS#dkrM3nF6_F-sCTmQUnk1*dXS*qcAmE+wp^R)H0<}RKDyoO?3^HmHuqS^;X zH^<M)NK@Bm6)qF)(zTanHM|cPeq$jmB4#LX3!iQXhXAyifC6$8mhZ~nzMK{f$eOgi ziupw)I9pvYI&^{X0Cmv1Px0fhV*4=XX3gb028Fi2C`gzBL`MiZ2}mjyWbS>g5n=}7 zcEiaRbm!^w!B_VEuxk-?60k8?{YZlkjh~CcDS1>ir1bT9fR2~Tq#BPvs}ze`W0I`h z^O>HUSC)5~-y46F(=*i#ryQq+B`ZbWWzKPM$^or+MoU_q8rc|3dq2U%5T{|2EeIap zLF7QWXh)_V;Hym|FUrPqEujkVL&oRU#~)kg-~iK%O&I^ZWgy=(hWnv_tY~*Z#^M6{ zFN)B9rTslX*ri<k%1P`Dt1jCy@WsyF-4<gf6QNIj<cwh1U1%B;*BM@?s&T`;EisW; zP#1TJ3{|p!@%`~ufI{1$!Y1>38s9aF-^%Qmj=6{wrsgX}?1@Q>K_>N{7Jx{L3_N)# zx0<z^OooW%IN2NTz5kvM;18TaRPQQYJo6`O8M%LG|Eeyt^|s~iXga@6Orn6_G6{E> z^W0B#byE0x-h|bTImd}on3&QloyDrPajbzWz-weS%`QAKUtQ0F*C`01PC4$x%-mI2 zE;UCczR`y<9mGQ){s-``?fP7R^sz1!cD!G^VX$tDz7LqX|98oz?c?j->a%tGhqS{! z=2kdpiiTHWrEh>ha3AHU@|>N#SQCHCFWI$MkN4S8KK0Sa$DujCPOiDq$8)!Sd#}bH z1;ovne5dvUia4l*^lEK+r_xgSeuSo1ZO#xvK;#=XtLGwxkpfK^wZ4$jqi*XARSf}B ztktMcxHX3?TT^M5yAdN}1#+$;0ES=<FU`5<AkK=EyJzm*Dq7$yg1nR{c{%j5Ko`!D zK^Tf8K!>KS)Vr;QvIZ<|Csq28aDY#%PaF;i8(15nN``gerssFweDuuO!>~K*`#cs0 zS79JVU6JDM6MXxeK8jLPPKBmaja`k+jv5(hDxefyq-bD7;C$s`>sBM}J(_c`35}e- zi=HXnHS*s>ZQ0LD9V=U;DhjmAA0fPe1~K=cz(0b0ayaS-Zf(cp8?viI?xXG>DS|zM zwhF`^crkQ_&}Vs?kDRYa&hUtklR{C-e-hEl@1eeAD+vr$IV4CEoV225>P{(g5BT1; zs?+(WXmg5;pjN)n?lWQ|74<^x0Elpuq(uzOh?zCd>cv{uY572<Fgzn`mbz^&{|O~= z?zt2yrLs26ma3>xJUc={oKHmL#^hdCv6VKl&ON@PWG&fiwOsY<o{tW+et%a;v<6iG zS6wFv7m^IL&L5XPZ!4qRtHbm%j0iSdoblBzw4dwAikQ;2&f0a)N{S?R{`9aoMbhbh zab#_{S*hY}DO+w1Dp=6=;k@;^nOAF&x^Lr9!1v?+@5-BE`9g5O>dZyANf}`+>V8>t z%}RsK^29fWU9L)>8r4e9;PO<?P{4Y)Z4GF+@nKUAuF?tBGT^BzC<Y_m*6*zMFbbl4 zl>ZNPZ~hMT|Nrs6W?zgkvagNoYm+R4p<yf&(ugFfMwXBmQ6%a$W-#_q-i4G&$R2G} zs$rx_NLf-zW0zE;RqFG0e6H{JoO7LD&UJo0*EN5@YhJIJ*L6J~kNfR@3oxnPci_GG z5+K_r#3#G{afYi9AY1%tK6aJ1sjyQIW?cu1mGYdsw(C0~fme|CA02~X>Tnnm<atLJ zbG28~rd=YTdwaTaMnV9}T6$Zl#-ru3P;5=qJ%Q48P1(PCZtZ~ExXU3V&{V|<^`42+ zhC4ron&F^oft@OJX8`T*nktz$hu>N5il1-^b#x(`hXIMsiWaW&aH{Iq$fwscR6?;a z&!zbHyQ9z?C*o9+rDqHhR0QU?3q|8Iy~(G!Kt9y8h1abFt-aJ8XYZ=hSFVL$cVB3_ zENo9K*13K(<dm|}oZCBwHP;f?osJYbu!`-dW2e-N+!9NGR=OGUZTPOkuHUIZ3z!w) zD$ngqj2NOSI+Oq1Qy>3M^<9@?H*}MdYt*jV^cdLwM(pmFwND#qzqfbW=T#KEas8*g z$V9MlGs&Zmveu<bP0xjj^+{Qo;WcWvy9_%PzTY-_grJ@txeOFRYa+{l?5a&so_rIY z<N2r$d=a-Y$~U<zD+-x(OwvbrZOGje`}&+!{5;%}yGfQ8de-<NvR;6%-yW&_L9ZYw zpgV7a2{(|l%g&_AhgRht4YY8poa(EP!fKzznpl&or%j})CcAKapY+9}<mhT;jry8J zs$jAHj!Dgp`o`wP2IY%&6DG}b(KM#X{>bR-+O9PbCM`kr4F^mbd`w&dqw9CoH`_Ga z+^~3cwf>rNL&IvlOQK1W`jJ*A)3y^0f@3C)o*!@IG_-V?>@RL;t7*7rxp>EAu{HWg zOQp%3H__29fizCD=|cnWeRHN2jD}XI>2~2<=~vUv0IvY0rHfP%bu7{a=)YdTrEqaw zK4v$UOdp?qYJ+x7I-X87qRAaF6K5{%gVu@9FAWDaK0StZ5YnhMjnC}+J0CXo4VbyT zZ0w&f^M}L#Z>7QxKn{2d5B-0~4>v$|74y2H1nz7#3pgRFwd(0PBft9Kr#GsfUHBjT zu%`baIbm`9>Hp$~{lCNZc&VB~i;cE)5qkg(3C_3wFMb$!^Z%(-*qg}=#zw6wW)`VL z%vCW=SfbbWlfNzguTlXfqpiv8_UjmG?zOzJ>G3!pV#d(-zI$W#S;^KT6Mc7Y&WTRW zJ5kJ5!~ED;2hFrpkJrz?Y6*RIdB^=bpWdEvKIqhx81<oK=cg%cpN{tBY4JJJga7`r z?HejI&kOT;aPP;*v71NU54;P5PQDZ6u5H};u;cf)g`tLn&mTVc^GiBCt?0D(;eY=8 zSE=y){d~sie-K6z5Uw04VWSOdCFwYu1qp}XZZyeN42Yb}P>raa%+x%wFquWn{I62M zpo+GRAJ$IgnB7^J$|dy}P3KvSMo#CG=W3@5C_fjb3#mxs8NRD>)Jzfmf0YU|=NRtB zv&H@aQM3O9M%2xo4?gi>_5w50c&;SueAHZNWX=C573MCodW`4G6Gx-wFD1{_&Ht}b z0co-z;3`KiT;ct%QeojL-`(WH|5K^(;hG@RWbuEL3bi%$i~rx03I+{J|36VGY^@sj zFMfD@#P@L8%rK<ZZ*XL~_T0c&SYg_a;rZHgKVKg{^65lDFp4xlP1xx;@L&8eX<}Zo z_U_mFdH6)q*ins+U+>~>emMRLr=tx}3PmD3<-jZ5!r78%3BTt`lOFzFcemmTXE@Wc zEfbO|{J>=WwbSj+35K8bMj<Ujx9wXs^iBd5g%*5k;l7*wHWS`gd(E%wo$)lgX7yjC zg5jE{*>&o4zfETxOm3k#Yk!<1@x82%-MO2(g-#0}MRxNa8n)e|T)jE8x_GQ`>(B9} z7C-#&rN*21x3|t|<+0id5?TG4(=C@4@Rl9>;NZy)u*d3iXI>hEwefrV6YGWee0++O zL;TAGT#{v@#;4O2Q;8;mR$11tE-=r!u=e#;f%=_L%?ZH6ezB95jEmFg5Yx2RR`@7q zxGtfSR7r&U@+gXxgu7s-;*}8Dgj+k)thpYtPp{l-`7Nilz{vX4Eye>DKH#PsW#d>h zo;_BOHKEGe;x8}5Cg}o6!xC$Ev2zMssQq*0s^h{I@k!N}+TYMZ3O0)Frfyl3pIW6S zkD+^>;A<NcyPFFkcRQ+&WZn@?k|k`X<nbwmeuAr0KxyG&^0Zn@-mK|CjMrgusM>F# zzJ<Jeo~>29eA`Nhb#TeU6jcU`sfV(cM!45sdEt`luy0IiWB)89P6Hxv#VjWm%H#F; zP{=%$_`xG(FjRZqdxogAm+s;D^^(-p(7xaJ`SxQiYSS!~s#elk^S}8=wW@}nSmAVd z)LS?HX-)0XzC6iwBttNCp0jHx0czMSxPskLYgSPtclfVJ?QU?7f=nlBcOyr0_0&cR zj(7il>GFvIJw>D55%2LGKH8(TnFdvzxQN6A&Z7S{D(=G*U}XzG|5m1Mle72;d{>=o zxQVY?>3}oxW&OOKo?~Mx{hG~fK1VatR#J5T^bK9DtG6_*&bQ<8?GvF25+TY7WUG!@ zBNc#7m^SbVx^f%vX)!|oi-qPzSY1Wm4hQ(`JSGvU*3jN#(_Qpv<#s{omT*n)=VRC0 z`do--`8;{JJm|rgQtGb%FdTs{j8(m=<}@qWgh}_QSyO&_hju&54>R?|@$$DMcde?U zw@pSSEsr<MnZ*ViZ`j><qDAdxi-!Z_UO_^?tk#5T^%kdAIeWeDO$fe`nfyJJUc0dQ zRA8;kFV+jFx8(X~b0KqbABYm#UjHBqy2PD)7H&1#+Sl%G{oPj%dXuL4XSzc5+WAKp zwDrK}F>=7SJ;G$_RaNzlMduUy-X1gA-Eg|x{Md`SeH+gFbJ^W-p7{La_<zkEOsz1? z$>=V(=vJ)}Hx&o>I=N);P_;XK9w}emF!(0J7-EaiWypao$FO?9&bUE)(BNxNUf0_Y zI+082fxo-<5EpjDow?A8bGD)>6c4&u_dp7S*|asy#dS=umt6pVYX_Y0AvqIM4g833 zWk@^1Y_XQGhft*qjdD?FB=T*f&Krsat^hK=p=|ZKrnJRl>%X<)_XDBr(2&-gi>Lf& z%7WU1K1pl)?;i5Irrt2{gBY_zj5`%5()dcw`m}l>G=VMB_)+4nozC{k46;Ig(2rwk zlpP=_j$)d;uNMzJdr>eqy>aZbhXu_uV&BUUISceJRKbpej}BNpcqV|AegJW<gCec2 zx9$!pF>M|DWpz?d_?cMw@_qBtiEDT_Bd8=B;B5jLs7HZh9fBpFO)MnvVByt4$Aj-_ zmOa$fQMoIggIYH{+G?niA3asm>o@#;&GnjJYxLVdudCcwk?vbFb@Fi&BJDBQ2}i)h zmOVUpX7<LF)yCFB$BwhlUY^!3E<O4}_-4cTz7q>B*DuM1E$M2$Tj-ffDL)>Q$kBc* z{Au|wJMZ}W4V4xIXI%OISfPEVTB1PYr1|lnlNC(;%h0%N=U89AcJFftBg4eoIfuG6 zm{>rhYj3hxPpwt%Ryy4B@53!}QE-9UgGeOGL3P|S<uX5DmfW~4Zucq4^fwK7H0FxT z{)EfYx#cl;>kfIjBq8mUl$7=PR6(<PjY#w8aL=Z62yc(Y{VP6T^(`&+z%Y$>YR?Ya zSR~vnOcCm8FYB647-aoP7Q;3!i|yB(nqL&A@!vgK46xm>z@NSS{MB`qdCd6G1Dult zrrst&Y`%5PEn$Xre3t4SUgci&6&)E6g!1)h6tFPy*vbtjLvA{LmD0Ws;;!#uw^+-x z=qC*7%WAK%iDJJ#63%j-UFVNOWT2zhsS71sXA8RjzrD7|lTyTy7IYy)W|ZhQ%D^LP z<O;9aIh>~zDA-Q9&^D0eK;ZZ@gNT<WQt{OcEu}OWMB0DWi>M{CKbi57$H}P)_`0h$ zOJEv2Q*Lt5`4<8ApFz2B6#AI}2?~&N`p_?^gBvp7-C1Z5#N`mt&=XDw<hEbu@Zn)` z<<*96Lb!!5tC1RsTJud7?26AjXHyB2`vJ<0qU2t4953>AZ2O)q8j@W<;&d?3kuAtt zF{+IzyIy}R9Fi?ZQ<~7SJtW!dAm>O+@?9P>mWml-;>^}3RNu%GRBo$+Z5G|UbqGJi zkVyw|13-p*TWa57-%|qA9lhgyH7MmU=kH)zc;YthkT>_+&d&gTk^oGy?AWUKdv4C1 zgRyzlvC&i%m4D(3;vf->VYR2T2QlmE_1u;-pO|S&RQxH9!&9<hD+^Oe#9m;s*eXB; zp-Aa>Tm_TR%)+#@Fqt*j5~@6Y!MMo7dP#ym@a@zWCjJA#PAb9AlkAtzZL_)?`dLWp zTpPvQT|nL>$-ZTHpXa5`Q}<rg#al*YpQkey{N&z}WP1g;_3qz}z@SJHe^7vXE9IQm zmHT>b|C4t9z|^+52syUI^JQeBZ<4RiVXwig)KgScgDdKnL~cwV_hk@2C)uW-owrUu z!sN+G=kN<G{A5c3LRsz$==hzq{&SE^sYNFOS#&DQf(iMKfD%RuL1B6-QMN}YJ9?P^ zER5%l*6$Z#8;Qw)Ef!@+XxhuFWU!j|viPb%l_c)pJ7v)2xZB&Y`~^&_@kQ7q5AG~; zT(Jo5j49${>m(Pi-{Ai{gy+&j{-xp3c6biW^9LY%mXA6@#0(1Y@HOPNdOvCs%&8-b zycULs@bQlV9L^`(K|rS+b+{n`#;P5i3nDXEGDAWauhQ%<r49#R=O0<x+(Ws4XmNZ) zl6yo76aPH1>l$jQ`uua1{MfswM@+d9(y1>XUT9lzYHt~C^71khfBP4CzU7~v4CnQr z`KOvJ79B?CuYX}*3LmjoieL*}Pf{^G!ZSZwLM2k!Aw4iWQSaZmi~rV?K?W)Hfa9)3 zN+aO76YE&ZudXFk59lTbn^ZRqVygzr5Jgzn6_%JvxXHq{*<lB^$J6UCM8oil4CW{i zQ(KD}Wq5v){BzeYAYXLqhl0ZlpEjo}2a$5-q!n#zEoiHDWNZtvSb#H2bSl&(ko9Wy zR!tGZ_;Nk0n31Yvf8~SQmFU-uv09XG4Jri)8)&%_SL3#uR)!BC6ijD?XW0I+!Uxab zmy)wDSmAgAG>?yXT#s}G!&euebUwn=2w@{e781PQa*7>({(}tCeR#L&p>g$fesz-o zdvy?VNr0J2X`Zde%+)u~y}?Z9G)sG%KVh$bFKeE;*Sr+eyc*P8Np*zq*HK?+GJi)D zG7>_-!MB|CUX5#pdcMdG{Rm`M!SQVj^pQc#spz!2o8DHPJ0FuhFL0b7EwX#EubmWB z?EX+ZO1!-I&4ql+{$RG!#W#isJ^Y(Bft=hTE;zHkIwjR-u%22||11-?%#gh?FKd>) z_tb|CyshNst@e|H?xQT(A*!60KQ5&<ok}hJG6E<NpjHC-E}+Smh+d7t^)O}MNnOk{ z$P-uhntZK+b~e2;ss5!Nbry&!CZQrg*y%rQphkQ8DP;P-_RK$RhOG7+nf5Ril(wGM z6T$--NX~j~jZRdx5F2~1if`0bwaeQ2!_H}z(<l|g&q;Db-mJN)P~ew0F^DhIy|E;$ z%?0Xe+gXEBa<%K_ql!1FzJlKYhT&TePqoPYTnCTZ>b+hizFNRFzTqn7;C?dXJ_+1H ztSVpkZum1~ov;=Ekz{ANhB>`VO7QYWr%Ms`SU8=Ur7#G{NuUk@d@m6ZDTVujNNx-E zt+e5*#QJo0U71pcM%Ueeq4h?0>}pO#@w$9Q(#8d_i}ly1axmv5C@uk0FrQo@S@(c+ zYG?wxgJjwy7>)8ygVZj=znIem%;~`{i@#l@C6w`BOa&?4j{sz>W6*D*5d`3|M3nKQ z<#yCXnx;u$sCANvHn`qnPsL6MoMMo*yC=zyYVha9G{*?p9s+Rt<2tB~Ub}k@9>K4i zxzEy2h#4|W;@~a(Wj@Sx{NdHtry%-OU@278fY%c?0{x5WZ1^4j1w4B!=q$9TN9&?( z>NWiQnlAqHp!hZk*GEA2*xzxY!Zt}E3WW6)5>%TH_mw`~$pjaBW!f_j&oUfF?G8g@ zbjnQ${ok64fhf=mUChE<U}7o=*kEjVH355Bf+>+c>!S2s7GA7oVBfx>$W3DE`Pd5r zY$YEnXV*XcmtRN1ip;Q`e=%XJ*8`{++!MGt0Z356T~r1ldhgz~GZ8v8B-YC<5nNBQ zWU9LHr`47J-m-tYwPJ7HncSA-3A;ML{&HA&UfWiMm$&XE-w2%oVjc<W9ZuzoUnTlb zQIDiDDSvOCBA~x8FP!*|Kf4t?TcULG>b)%WnCjY!Ob~gHh}bKD7iU9c2LbdN6-MR5 zU8Halh=?Ged-(g~_2gy=v}>9)&0THR$1$yc+YYlZWdiJF@Y(KY>?2L=NAEV|a&>}N z+hq-T-4BF=4=zFoSOFhv?@f3KU}8uEB5F{-6!Ung#_g~1z|25ZBHsQ3a!5#nP`90Q ze*F6QV?+&p&vs1FJtVYKrb(4C5<N&-=Q%`ayEF}dC!G6A#6OYAc-~MSeG>6pBQQ~b zie0HEHpvp-;Ws(HJg~(E>WqIcl^yx$AQj+xgjlu|;S0XqPJ~$zfYLqyO@L@Kq3a3Q z2<G@sDdr9H@rXL@ox^MFR5{(T*()EGKteSW`!4|4YYc47n(*$Eyo<+n$j9}LILcRF zA^?ZY3C*AkA4E<6MIHn=tTgQOj#n?O0#;jOYfLex>eB|BRKPTR**A_}1FlSR3AS9Z z?ez^r|EaC}Hu!UB-B;7P?h9H8=#=CbAIa-&r((7U5n}1<Js`Xrlmq)@-ve?BM7+%~ zo@=K3XZlp~O+1=g{8&Mzf`G}C!UGA2P*a!%_!I(+%QM&6a|Got@-*w8A;P&ke%pRd zVm~wy7R_FHt5>6fo6kzxUVXyeCMG{T+4r_yZF-do4M6}OCm<lIMip@we0Lkf#=jf+ zr^_bB-E)-0xg_nD^7p3)sWr*q4c~>XJ(bzNW=7~?R=kNy3lFw!Pw3g;>t5F0RleRV z>F2<_Wni6sVRlgVCx|Ab`C7N2QoNsRVN9u{)u*r!e*|(C15-?^vfDx8*D}g&DYmu< zJEt%lhw&&-Fyt$NSP?Z5AfPRQkk;!L2BAHlax9JU3j%Lq@8zW}uQ07mR|hFg63n{S zpja|{n6b`DV)}+^#s<`I`!En;q$HS-A!+L)RCk>;P9E3}-Oahq$5R(xwaPn85YFk` zf4?j2UQrq9tN>@~(9@>k5uqvn+Ydj*`XD4=Mv24ofcx*82LIl~x8~kd{4|-;QFyuk zwNFb{UIy;F6#pK?r|<PEW0Ns!>TkzMvQGfqdDeJ^CZfY!>-1y5V`8a)ppDxia~>u) zb9L}nXAS)m<`P3@vH*6N^m*2TfH?dfcSNI>kL}*RZhFG4o1P9ckrzPBRJ8H0(@ulT zoJN*YjJsydIs1&yp}m8b_+>kOKD{A5S9g4?{GAK3r$O1V7Mc43S*gIAecB*t2>(_e z`<M!kZ+v16h7pNx>g|79gJ^L41z0Yw|Dirj`gBO|9E9;Lf`N=+A_tt7tb~v=|3Ewn zX8L0>$_Mk#PH+FL^RDd!<udSNJveT8_}N2T^}x-6HfQYaSi(^f!BSIYW8I(GOP|@B zc1Q$2cNWXQ4Q6}g9UiSIp9@?Htt!cd4CZ1tU-o!^|7-z)YKtFZ;mSeT*8uLmz!8Es zcu|UvtKl}P|4vLr0P?y>p6Z^{kPQnnISSM-n#VZ5WVP&%E14hYuC)-l7ic;DU-)5q zIXO1?UgBI|_BlhjeRq;Z$d|S(&urfyw+Z{#jK3Z>Q#Q<TTK2oHMM*XpYHCQ{wdh~J zyXioaeRQ#*?=_#1`r|#gg01brck8Qr73zSP)`uAydp^4dR6~bzlq>_cZcFGZcm8M$ zUb|g&>+CUyJ<IF(;D410zr);*PYXMTQ09dip{tTo4a2?P7wSxCr(}Sg2OQH@8;#Eu zAMP)sw5<t_4(%y4CbO<s7X-Hzly}hYx9o+@p~^Z2J72fzYVBW5TpV#eZ>pj>N1^V4 zEBi0ZoRW2%kb%DB^aX57{v!G3BDv_sW5BoReOu1wi>}9KOCoZsa3+1Es~MLlXowMf z6LAr)IZ;9@jVg(LqMz_4YToXzO=_R%bsLwMVn2UhH-+siq4QZU|Lt!7_!4M&G_`q? z3`GXDUKen+v8OfK9jdD)i4J(jxa$_WT5fMNy6LT*R`Zl27rI!7vev)e(R&N%xEo{r zym3qB+1F43T>VJUkgWB4*DexB2d^MCm?v7@*G&x0C@;rfGeh<9lD*e19-W&^CuS&b zK(E2SHrF~6^#t)owkIFTXI1`Qm=-^DvcrAST$0ETFUH)OL~6L;Vmjgagc86AnQM|m zIC5{<yLyN1NWE^i&&lQD`+qmdGzG$Ch_Ch)&ekdw^o;S&0_hmZIj_~TGYY=JF-PcO zZL@dY)|GTDJ?*b)L|Mf>-;L3X`}g}XjmVn4-T5w9=h?oLnUKTpR;iZPG~>x^KaH3Z zzV78G2HeOYFVnvzT{auMpDs`*G(q5mW=U6vsm;Tl2P+mM!&muA+B+^K40I-JiZ6L- zu%T7lHHlF;!4&RR@DaYoZ8PA`mjf=kzv<m**hie^TnX&L-c-kG#p^Db`jPrOFvPXZ z1$|@aqEmm-lI#BIdN%HLPYnK;d-wN<Zves1bmflqze6wF_<d{lI<q=_?NU^1d}zK4 zl!3H;C&XlHB_jurJ~5kg^fZ%SvSVYP8h$a-n&`fJcsghEiAtoQnT6Paz()gwef+w) zOD7B#+cf#k>ZM<MDCUM>cFCbdt+Zl{0P#LUD&bV9ONl`FK60pfs^sZ6+t(hZ)$Y4; zY&Zlji|vT+`PL4-3;74AS9K4pZt5=F8))}fvG(!A!?ZZ(hrIf{b!6(3bxrXT&92!K zXP)2l3zenREa%*5np8f#$QvImDgYum3J)VCQ)X=0iXYF@+fsa3%47I6a@3mkwiWzU z_)AdrFO|C`lH*w4Dx11sKwA=vA6f)z<p^}GmP_dlVEj4lNnw%`Rk%}?d(*I-t@4#e z2l^)Q$$bRVLmFj<5zE*|eVuakB^k!Na5KZHYf4uc2zvT5#*1jKRKq)<GLqb|vcKD^ zm9zhi@CrUH<|^S}B!aRS(qR4bX~4&qSDnTo`EHG!vM8KT`;38YGMV5b6e11D5V`os z+QJLB3KGVa4UaHf+|pady6sgw-Q~kV53=b0_J!1`9y(^P{#3zhSiYcSL9}s9%K4%R zr{ENsJa;=-6=k=Y*S)iPq)m^1n}uXQl2j@O;lS_hk$nr?O?v5T?N2oC&1D7Mst$Cm zj38HU-8Q7!Z24DayL-x2ITq!R>=o9oxbE$3`N=dbANw)WhYa4n1$k|*4AtSK4xZJK zt^S%n1g|*PdAx7v%CQ#``yL&+LorKOM0?=XL*NSqpCx<}J=1YQ_t|esv6cFk*W^KG z{28rg^@J|xFF|}Zk|cyZ5p|k(%Y%t4eJ2h2M~!P#WFEDDNPXcoZOgV--@(#L)iBPq z>YhS*@zFVMLD2!T*9tNM+_mc2S+<Q3{5$Eg?#wXC!M+u_qnx%edT8<T%wD+@)aioj z!u)WP8wH%FE<O)cOEwPr-WNX}X(5If&2;+~=8Ose{qf*6STt#`8zNn`yClm=TBOsf zscb2eKYrl1IuPI3n0;7S>Kh;g;fiu4bKsN3F!FN|&e%Ns?=$o0Nz><N-IXq(g*s3o z*Nyr^;q;13AmhqIo!0AZ&)w?m)BWU6@<r;`OOTt1%a{X39OLQ0$eQtm{E~90Y@zr_ zoJ;8Fd@nk3p7qj7PadQ!v|4uBWx?dJPwC!L<4;F7JETwNAMNI-!b+E@>Vn#w9ZRUE z(kEZ1LJ9_;$yQ_RE3z-HsK>B48e1N#$znlp3ISpd8%ar8LHpuTrZ#Il)gCs(l`5xk z)gaU|rTwk9Vs<3-1T~2hUM?FZOI?CG0C(%+wLTeLQ%>^|>q)}6sztb<Q?~uJp8c7a zszL5EtwyTI*ng`>QcM;3SdgaSOsCNN$Vg_MewWf6ARX%6cL--Nt4wgtJ99QvtQ31Q ztRo1YZHBl|Ckskb4tD@d+Par_Y3F`5UDB>1LIQDp9XK^j6(N*L+TnT<Ns(7@<+=|z z{u(=`=(ttuuuz<N7DkfQH~hR|Fj*6~+0rBaZixEjqHFc%ikstyMd}w@-S6t%8=_m? zQ!gsdqzt}bgye4B|6?TsqvE}nKtJ&|pWdT82PsM_3DvrHKJm7j!m~Iy)j&wTjKU6r z7ZCueb+CslICjVD?37|-NrwJCWXW2PppsM<@N3_$qMX3uPTfkD+rh-2)<5*eue^At zM=5qjhj*8a4gpB<HRq4fsfSz^?&LW^rM%6F(6NuV$!ASqa%ZGdGHnby`;zt|5BFm# zzh!o833U=}`_Qwon`MTkj)6zLexj^d8HW$$UP)wzEmUT2td<mEG$lBs^~X!TEPlWV zf5&$!iW(sY<dwHtT~un6&W+4}&B-ruUauUP(|6K25BMKf{wS&+H%~6QzhioXXR|v1 zwiZS8*#n+FHyQ^acUh08WXcA0?U)uTYEj)9{$;Whn{30-Kb`71h21vYA$XgFhiS$f zl-1}U(wT5&K<TXwOz{V&aB9uv_$)I^c5-3$iGP(QbUO0|>%0K&Ds+CbfW%d7n!Oo! z{f?h&?C)L6Nk`=mS|p3RRc|q~A|x(Tr&r1t54MSJb&6Ckh%=|Q{ktpZS;dTZvxU~R zRwS())BN#5Q4U%*%?NHKXozQ_Si(#ID4FKL<5xBV#h2p8GE*YC>MIa?1-3d9M0^yg zOVYz4IZ3Q5^?uol=crF23zKr&P{{z=C<l<5;yx5kp1Qo>7vZf+-if|ST5PS|-g%BG zbMGy0r-YZbaJ{mNOFGs}EY>V`p(cwnAC+3K%Gd?n@8Z)sb`ByPU&4(g85a_|08LaJ z<E}N~K|CYtL~Yg@eTqvzn{iA{ba$`p86oG|IkP7(A5dH&7R>x(q52x-G+q!Yv9^jO zu`kaCQAX<@>^32?8hxYd2Jws^B7mw+uQk~qU*uec^>63q3)4L%=m^p_?~AbA=(ECa z-GWx$c~V#RzK)`EZb5(B`7osSAo55c$0tzsXY}Jmi3w{E<+*+c-JUgKj5;}n*v8}1 zd1#1?d*W|}17eOxI|svW#4p*neGs{eiz=2)oXg$YYk4PDkcJ=bDN8||5eO%(<I3;^ z0%`Hc##Wu8@YP%)DDPwH!4E{x$9N1JsLMm{5pLPaTj&4O1O7fa+R97dIi@$dtTt?0 zyL_Z0dZpci35!f_=szXivkP^o3T``y!up~9Q&JpL!sCxC4sNK;-jum<1)?ad-8e>j z>cVyq!VXEZQfdnWjy-)WRT<gdtsn)^wWSxMARf6WijK#P<+i=V`bBwi083s?!;?=$ z_!8WLB#8ZJaOx|}MHL>Kg81>aH+ItGgd|fmBo0cYn1^+k_94Uh=^la&aipx<RRz6L z<e5O&_GHrqe&H{)r{ec#f0(uNth1$6?6N6gStp>l!UiH?XI5~<!QM~AIwdQ};b=CV z2f#rO6EQqC8FhknsaCI4)feH#=W1hcoskw<<DTIdfP&7hbjcXt($|{LqQY0WD<9FT zAJO~zGQD`|>r>pg1uu!FVOm4h#Zbd|c-cykk6K9f=kJ*wkuWofP@T#ytK0f4h7(<a zI*RW86qcuX7Gok*L!&F9kq}J*bX&5|rz*`e4G0rU*p6HE9GKy+@6H8OdO`cGuXYvf z2|M+(>B%eH$A8dfiIml6NZJb2ys8_OkArZtj*4N!Qsc+p8H=m}K$2<G(ziVP0E!0G z7eobK`7(9)UfaKD6YH=$Gn+XOG(kI=!rnTF%D!P=mnhTJemUC@ar?W+ui^fJ6__0w z*rv+08+%yQ`(mI$PWmP@kZ*0SX!qm~IVconMZY0Zc(7*vA4YyH>Hv$A((Y^XpinZ# zJ5Q~QiG-Dhfe48Z$^@Q;rIT1Z&sIhI-MDzwES41U!WD2&1yqT<SWKf=OUm8kipm`L z9`OEWntvgwD;)>8kT_l~T)#+!@XzobETDSq_Jt|5Id`{Nd1lN?x@9Cv-_$26cy~`N z`cNu-#~{k|!^i>}f3`l;hM4{}3<Q{9S*y1)aX1OQHPSkCC?j{I6B#2cRY@L3f`AEC zJDHVrZT;vUmJ8nGYC~jpOFavcce&n%*{YFST6T<gkM<1maDR{!S4Ij?QHrkKUdKw} z7?x999=?Cit>5+5W0@6u$HaqGZZA>m^#gqfCb&%&P^7W}>4Rh*YN2JAr-YeXM!r}A z++!Xp2+~<bs5FN?8P0iYeGhjiUQBiyuDJm-FM-dz><(aL80hUyo2|dT*sOP-9&9!g z!{k`6Ao&eQJqOhctv5|3clMFE9~*<jM9WYKG(r|cg1!Z5+?e$y_sFaS2h<62R#8*X zCvsLY8Wlr#MYB5L3*c5E@+86NU&@6yU$N`6(d+Vg(59e0q>TL%bQD$nmO#B}{LNkT zjcvc-;b6y;1{Ze!;O1mXJ{(DxW?mEA5#P=^ID&%h(tDYan?0+SYyKPoun)frRAfR& z6iIEn-xU(Fo<HL%gX}e8%KE>B{jh|e@NHk*^7B1nr`RBM)$CwOOIbdHYulpj)vkP{ z|6K#x@;_pWs*K%RGH!c~F~kkX-6Z7P_P0w-IlcU>sFn2L-R~Qi+4CSOSTc4vZ4@~c zs7ypMlTrPmcPq2JW6$968SDxw0GDbBUG}MB)vu__SNY0p@I6T5O#o<a2$^Fyw&k`W z^HUR=)|a`HaiizixM^dikt8EV)h=k?<mD@G<a`W|lSC8&yy>5iy2$KfO`Pz@@A1Jv zfh_0NCKToAWPLI!kylkoWW(tIoUu+#A!C?XC&&{=opHNwz5MFy*2NfUvW8bb<pL#p z7H`A7B}!{cj)#g`&^cqs4VRzY{Y#D|js*_6xQroR2Zf#^sht=@S^-ZT-7%LEP>!=> zh}t?l&R@9}wkC^8Sjl{$6jl^i`-|$Tx$+Lhno=R*jTAhc>dc$OO8zUk;k};o{rj^L z5Z+)0K!7<D;Pr=cYuMx4l}qpZ&D?Z#&~ijP>k3mgxVw}5o?Z~LZ$jnJFxNvE5<17r z1~)SUM-jkqSqLCYW!p=$l1i@jG9%7KqS&u9bU=uE)z06Ia1)=mC7%?!f%Y5SR(_GY zQuW{MTR=N7VJ?w~fR(9O<;~5}n|yhXf`(m`d^CeDGA{7LPJc${GErGau^F)=z)I$t z2NR;mpZj|h&_QPEdp-pwrf=ozm6x*JT|s;#n=H&cMt?i{J#vwx+)c^|T#@muHQCp* zJ{zB=8X?y~8(%^O1L+bGu^x)b#2oD?e1>$1geeDD(n~Tq>_{7JR2oqbk`ZYzg*0nf zD07*C)&hz~Q0Gb~h20Cs$tX8RSUkQG2Lh@kFl@TjD)ESJr+)yk!hiTMbocc5kBluX zFt=J+U*h@N33Qjt!#EIrfJ!khPA_<7u_59)MQ7<|nVnTjX4dDqZKX)F+J%i4AYu?u zCUa9*sNa!M&atS}NPm+BumS|oBv>>dD+w$dx`W3$WmMLGco49E&AXjh0K#02GWXS* zwCl$7wqFF=;o&XgF(B8P7eoh;JU;KKkKrM`3`%lCYy>K3DuZ}BAn#Heg2|3v$+Wo< zTO_^kvX^U!u7rz06;;CP1J!RzkNj<S3TWYaIdFmk%eu&ira$vy)zd@JnUmTGEeeCz zgHGg&7kpy$$#A-=QW6Vg?)9asdFfe?RQJ3%$_OSa9CK<?8;oG5kiXn<tHV7iI0iON zTuO%<0rHU_by!w!?tD4!Q&Ycmf6w6IljlS3qd{Xjhq{6Y9CZFzU;*hqR|2B82XgRO za5QW=(d3TbU@W*{X5Prg0DUM=YdJasO6QrY+N-U-y&N{Oj4)A!Dy(GV7eK?Y(Ij$$ z)rCB>(YRfXu-*P%6Us~q`f)5443Th{%*^)z3%^Tv!S0-B9`7Gst;wU=>{TefVrG6N z^B6N7tGbM!f=>HEOOS`N^WTob9DRpSRZS;)N&qo8=<by6GTg6Z)1ycm!H;i_ClEfh za3d!7AR5X2-uAR6Pxc~`#<01v^+(3##icuo)|b&TD5O~+7##;je-Q#qw$ecO&3z~M zWZMxjcWW}cf(SvEz&xeR)LRKp#2yh}VS5-E>YaPlVl&>)@b<PNY%XNxM`i}nzfLPR zVP9mql@P4EU&OtV_Ocf6&nF_EWUWPAKatl2{2c*Xl(UYJQPwd@`(jb?LS%Gu`e?)v zC6G<#XR%243o2y7R-fCEIS)gNf>pv?q+h&2n7NpnM&%kG8?3#9?*BLaP{2x;L5~k3 z;!uCcB~F%h&xxH+#(-MTo{#c$v_)B@6bcC^1;}`Vc{NpN@t)zd`*APPMPs+Pw!B}- z?&ORf=x!FmOTyKOWS<hVj=w~0Z%4S9{JG!8vljSg?b*LTM4ezle6A(`Z32{m%vhdf zKyOMRSiow@)DfgBB|lMH0E(OSZhSfQbP&6C;6MwbBBf%+MY3adfUA=Xd#vRZ6=@<+ zp*Fj4j*eA{AALTQXt!3aBDs|@BU<~8s9ibS1lkIbV=mjzw}q=@p$?WnjX+Q>3ovRy z#srE2lcGr2H{%ltJDCVkesn-Pw}ZsJKgQH$!h_pe0ip|1MfkIylQMX0T%~l|dILD& zuQ>mw3x4?;3JsT0Hyfn#H0)1&7~X=D{Ga$?<npGTJayY+|AQaOzfBYMWMlK7a+-<s za}nw`CqAj?G^#O&jdoQ*TW+|D`_%T__9^O$`eyX9%JYKdZu=Z1*FC5IR;e8_25vHM zmxW+i^~Pf@hn}3hEoNwu(@w^YXzclEKHh$8-rj$H$I)wd5`TUDv`^sxIVMoqj4BkQ zPp*l~8bglQo~wB;K5O_~$*@`bwgn*|2iy{Np(CMi#BFr1*FP0@7tHE%YR_3Njoq-m zthRx;=cWh2qyO`#Q=ebQOYby=Bn^D}GShpZLBUCO$Aj6I*N(VmS!j2}1e%yJSz`_y zw0BFkgIAgT>i1LcZ(p@}OizbzRZPVnEzk<PXTST$t+1X##$~v)ECr!%w87}`$}+(M zWxvAQkIVNfG{{((mgTBNugC}eQ0&S*ppnzAVn5sMC#R#14lBvQ5gBaEs$d9z`geZv zG;b+n>tlk6A`uFAUaFL{n_G9Zo;>x*HdjA^Fy&!>lfcvcXCdmWXEcN=|I}c2irwqI zYf-b1e2O^j<Q%*IDQt(%(b8;#a-F^N_#AaJMrR20<TYol)zk!^{CKSWCA(?nbgmMK z#Q@;zV!mfKUx4V);6HViS!xx`${Z8>9d<^w3A6IxMlNZJVL^Dj!KA^aXjGFj)DGDR z#NA2x7$zC!AWQE|<$SdNI9NKBdoo1@#Jm<x57^KBXVolwz8EH_OY4wQp?dHw-NZ@m z);Ga_ekcmh)DKTRUEfa2oHy9f{HNJH1lc0iT?MC2JAPY?lsjEBJ9Pcwl^Y_w{hJcu zr4XKeIh^#h`zqeP7)fa@UnmjfQ{I5iE)WYk(@kYqs9V<^I+<9uF#;}BH(jgP_4ljm zK|AjDa|uGt7H(Hlh%9Ag;_prOX{!sU)6_FheSr5YkqbP<9XJ3t0ASBW@)hfeHkHzE z`Q-U3c~^)UodBqgwTBLj9LqnJV|cl5OO_FIt~hoSqA^Q|gD7qQbP~cWH=Era?vG|2 zx%1(hB>QT0p<XdizLH5l6Uqv)*fh5v&bOK?xXC{?;bT8v9*R)hsz`#tbv}M87}U>t zoMUpHZixct?=AiAKB~HF(cnB)UT9b>!5=PJH9M;^CDQn$nb=FK<&!%iStnc3a6+fy z*S^5eHv_N-J_``ip$r0)LUjSsG>7sXn(hzyn_p+%Q$GWn`23%nYe!InnbHW?sX;^O ze06ze=wU|%iA4F=6@m`me!azn;v~<;Qg(z`yrk;cpjv-flMc?2vYe)v@Qo+?u<lYf zNBVia8|7UatP?U!JSXe$505CzvAO4<#7rla3(IPl&mFy$`Q$&+!_kNQ63_1Gep)W8 zQNfVET(-W6bzKiFR{09fuiQ9MLem~*cB}eVLd~~q%6O;o%y_+r%b8NA%(!w<xk8Cb zSqUK&wR`GE$LEsOYm;-y2-t6OYy1LMb_jf82e;FBLT=5;j8dNqV#p-~&gbO>zY=yV z<5R0bkn?`d1XXrnQev#x&00jwzZZJ`?6>r}l8n|tcZ$}m;6kM)S2>7mZTG%A(ecGB zO>*+n?qudw+%8v8Q3C`GSDr>|D%J>)Kb?Kl+3?r)P~Gp4!WWcpx|L|5+3Gi&D<xfu zur7@0mA%!ru3b1Ti>G(*yUcbgks@@LVN7~$o(}SxJ5Fs(__C-Vt357bB~eTsgA`Z; z(HBtRz2$FoN<wXRl*;p~?8>Z3949OPeGOS!0s{A2KNXitMp6bNo>uj3Qo3Cms^Nfm zQc$@)IZNmdNC0G6Z%-kZ7@0EM`eH6GR0|)EvyXPeA44By%H7U&f(p-9eO0tr<}WB5 z_)cFRxTWl**PSE>?Ix!U=7zR(!LUR&5xxe&uMo#P-F9VL!kJ196903qt#z%~MTKx9 z*J!g&3=h2tXqq(Luji`1zksLnk3WjCI4OIC9H#M>?*T|4a#b%Bw@Im+$mHCymhMok zbY~#C$j%M!%2tpjHwJom>4TSbHCM%4)dIfxhP)8mFfWT5Dsz?$2juV{o}byZMW%9m z#~s_%93AkLE!}$)a7*k)f=YMHcez!>w)1&?e)z<W^C}%Ha6MoJ6DmEV{#NRqI6zYu zyd+&&3KZGk#rvx@F%Cl2&Mm%gcgwL{HWuf7JRRr1FL#-vz-TeR%t+q83Ni<}M(Fhu zYM|Gxo{ZU`X2U_dA-KbW(%OgPA@40;Ae`WWmR5q>1RbZGS@oE3wH9Ufx31uLi>^ki zB*StO6c_G2t&p|i3fP%i9lsH(xf<zq0BI6>@w<xlL#c3!4q+plFecpoX|7mS@7^&U zO?!nvBTVT+w(v2U105{)Rf2p#-=^>iX1=$mQO6(b(kX2Br`-3)M8K))koIer&z<$U z{6giz%xuP%8@~C`-nzh$AQ1rN!5IJ5j^0QVr3^NQcNtYbf)=K^UW_d8S5wsnf#~WI z5KR>b-CZ`6A2wAmyCKr@2wFrnB~%4rZrqtv<*3r7AfV}ttMva+Yrf&#^o_3Vr^oy+ z@A)JMaINy^@YfKU+As5HM>LFAXABFFHU(&CsQOT3lJ%Q+p8@6@9U;}yR^nXHVsh3> znUke6DQ|Y|yo0U>)Y{q`1kAm*0NNnLrp388_)L@pB1PJn_26Bjl@sU0?ZhWrbVxZm z5U7~V{l{01)lqNo=oI?c5nDm}RS&}?T{mMWdFz@P+EhdcHjX@?puW{YnH^(Bsh5}W z@q6>GxW=mE-O(>zQkR=DSK5E|>6Qaykdi<Z`}&XZ$RH0Qq~(q_94&wDNnrc#4}`lB z*17m+FVi$2wH}V6I$zxlW0~)hQQK1Fxw?uV+?G$%U;1Y;awlA_koUN~r}Sux*L-Y~ z<c`6bCNw9InWMl$!#DOg9_oD}^EtK_*;M~s7-t0AaG@Y&_{!-Ip0J&2*ZV7#Z(GP6 z38u+VWT-9lIQjkkkkOv`#jc8$6Fs@~nI(RfQ+;Qy2T2EGMr9+LuR{!&lgg5@M)7U> z_B2K)?igJND|5u0NemU#BcBpAH&hQ3rc5l4HcPK1jO}Zwj62QZZh{Njk3U|ReeVjF zx0-<@@6HZ=3foLg-_red=)v3Sy+Iuh4p^%~7uf^Uv`h2B`Sucy6$7>rC)&~&3=qm8 zPF%ZTj#@GhjiJ6S)q)!x^qf3UuD8Kn3?oaSI&^1eLM8#LgEa%N0-@o|z7_Me7k1+r zn|YlZ^gy`SS;dt@PUSGRymv(xoNMPBc~4+1P;GXuhJ4TWuIXCh3cCy)cRJmX-esz} z|6UP{!h-2hCHHr{`RFTI+Cj6Cu3uSU@$AIj!4TVE+GaDC%@UE_jH<>Bfm6BjRWr>- zed<^93T0*9ancA`z_F#$)W)(e5i*koL3DX#lIo;<C9qix+q7LqcDo-%3M*R|feOY| zNmHR2a6M*cU%RXh=rS=Doaa~>N6nzMLk%Lk&cHzxiYre|*KM#Q%bQkOzTG}BD<WK^ zHIZ%!h^jI|$?3Wzv;A1C;`_+~p+ICWp>3waaz8-x&D1ms)@b(a0u&n1KlTqG1Pqy# zC~dmoS<$x-Fsl|2si$WgAtc~+l501~usW^Ap8c78F6<E5N?|wT4{+C6;RTv)RT;gd zGxuc4#@a43K`w9m)x@fFnHN4lr1R#%u8`I$S7DBIyR(DYWNFNyuxc2Ip>@`nV+p8{ z0JY7*F4n0ud!ufm$xAL(WDOTu2Xm~0bv4qTb19I<4_D7OxnfC~Wbj#O9xO9ZWZvSu z!Fy*?J32&>3L$}nb#U2=3KP%DpN5dSVV#5gNHEB@<X~ztTk|`6TMUOj3XlFSd)W@Y zWidDQ*7_q}$MVkN9pQPe^<3LS%;;TE>{^caE{r1PP*^l;)z>;zb6Uqlw%j0tse!%U z%N*z;;zHNa;Bb4N(tuu?jQ12kU2g&xZj1GMdlK`q820@GXQOu^5=12phX?0S_l?dX zDPj99h4TLj4Le3Re8B38JLM@t#T>}C7?>^2TY8+k`Bo=wtW>|ei=-@w=v^<ON>}Ua zwB|Xh4;*$Sb?<LyTZ%<~>2qX0%^nQ$cRm<4BD#?$vJ1|~el02sq-`d1tz9{`R(n;W z!yOqAI1Ye<wKOUf1-jd{?Ei<bf!r=KZE;p4?KtGkPa2<1v;fimRKze9kqW?s`pKFh z%7Dm$%dtxw6tYBSZ`Pa%u9G-1L@jT_uVkWrA5@u|ZgQ*ZZFl}2La6=nwS%`HI(_MX zYrTnNu2iCVW=c=}yLW6fnp!7%d}}Upk><#cC>{6m+Z`s~r0XDonF~7owP_X-&T&_x z*?gLNeE3x>&(uU}cCRS#VNIgzc_$`q1A`xui0ewuq7t}Ne=5K{C~rXp%mAdKaQ)uN z{ROa+PKPR@Y^lg$fo3(Md`HaIq;ekU?Rt?2KlQTj3}3;3RhK%IV-&N;q`PPUK{fyD z3P{=V^xY<kx?cAtjg6Sw<O{gvG{*(b{l{IK=v`J+k<JTaN-{^hJ$kfJcl{k<U8Q3! zr2&7}Ca~#prJcg8%*Z{X>NbBd>2^FZn`Y-N(q%xEnR^Q-B4=6kNi2__O3qrt5E4L> zCqb|jS6FvAL?Dz~=Ux|RWHI+jN`aN#>n)Ocm?F^Z1Enk1(Hnie<sUznyq9~LM;l}G zj=OB8OzS7tWtbOeP-%<u1sQBuRDp|jyR-ISt{(BzrgmqYj&$o1)61i7@};Ot0_V+R z9Ba7tNb%Xh*9~ML2<0wxtp}>8Lc;eWzDkEPf#IG`&bAJSrS*<6#&c@BI0P;f9irLt z=WK6rY^vuTBY{L^s%)c)Hj8#t?H|B8s}1y3^tqxXh1r+SbC6-?5AtQ=*E}z*HXa;X z>Ob#kh~5b#Zr|}n&qo<$f6JI_<r+kVsW-9*7df9sjV}ezpp|Tm+OFYInEiO}oJoPh zV6?i=thFYs3AZ`vbpvI6O`N)rRbYfmepX=p9)$qNRF376iz0Pb<GXP9Sa_E|h=fxs zxEykxieDOm(&!U?j7<~H_B1a($${;*W>A7_%(a~XDTfjxVjSgWBB<vx$Hu`}uX}tw zLb{ew7gPUZs*Q)^czOntUR(Zne`MFdg6PszUCw|p#YnVC;H=%z^`}epz)YT21)~It zR3x-lNYEltG<f#%gG>>D{w1!)9Kf+{ibW5%#KnzWwH2?4h*S_IWJX^(pG%|$pI*mf z0n&=Oji!flwP-XiZyOiVPzj=i;Zy$tn?X^$72(KNnpIxs))O<7;wO(h;d-~6!;z*- zil)tZCD)d=Y*cwXKG=9<+!ZRyGZK{O8+D!bY*~!H9`xN4sc=b;kWUdDX)?RAkEfYQ zJqUETXbU<wc{hPCb!9RBj;U;mrOmswMf+wqF7QM)Mj(`a9ky^4%IH*T^T`xyaaK8M zgJsdx0m<G)v#zoVeUOvwG<#fp;1*Y{haB5>*p|d4C~vv`PUr5s7LU=p6Z4#bK(H4{ zwOXLDPjpWt@6&5f-*gIN;eF9uYg9%1<Bs69x;>4(ro%TKFLvz_`1zDWxBa@gZS9*W z*);{xsR0h{7~5%F4BfWV`?)*R;X}G+po`uLe-Zn{Ce_*Y`>Y_cWf@nLdB{~bajDHI z9dqvKH17rwB7WK1Kywvg@7%BvTC!}gZ)&IpVveVlxG1t!oXyb}bSh9fWdx(It4D_x zj>65Tc}y53mG;phArSG5+|Hr+!&Dkg<k!tz|AJO4+wIT<`#~M2u^Jk|U~d9fwcV;N ztk>ZE#@iG0=SZqCa10PYDF{%H-laS9<G_)0gK`(gCoYZ^F2=>p2a}+O4DTGubt!h` znl^^0*LA(27~Il?Y9yBI>^=w(*7lUyqwY8z3t~XkdFvq}xWS|A6o0XLv5w37EP<FG zM5k?*if}_Nz|7_`wcS05)bIZq098%!ur4JVFE(Mkh*ayu3P%x+gF5Fdubf9p0OfLs zONW~O=B@VYMJZu4jlWbNY)LMd{iK&h#?^jH<j__&yLQuT+BqH_{k^Q5(A8FfYXp$$ zoNL#;ZRyvx@0>HgXe2lccZ(`h4zN{LFcL6*Gnr#cRx(Nk7|y76XA4C$eM-6k8m*n> zX{wqYZ`W-?=py3MRpEeH%!S1XH=UM@BPwX?uU(A``{{(2+~kk7{B+7N$K`hNLt=gw zW7K-kX4_1cHFHfFf0agNz|0JV0DRr95@B=6Q2viw3pgNS%Gt8w5@78)6nJRJ{{^f& z2wu$o6n)-rpRGq}mNKl@feH=a{8IW$HCHXUoPxI<({erK46RK9ihsHfDt#JuF&7iq zsh=|i5LbE^k<mpehv3Qgtj5!;9(9>_cj>ox=~KFPc0jiNg@P9#N-NHK1Q)%=p5DMN z!?Clb5*Ne3^o@#%>f`CAD?ij~aj8A?*Spi#@3bj*MH45YmBik*uh1a9ac_8PMQ00_ z+kZa%LK}CnjU2*mb+|<?)nT|e`Y+H1(;W!7*b5p9Vv$AnSHS8n^luF`tm}Q9>3&?F z9k|A6Jj5XwQP=nEJQpf_LAPnr0m`+zPzoYTAT}(TgHU-awx+C2<j@V<;`&WFh6)Mp zRANCa0QVG==cpGZ%}#JznFY7*+ZviM0WJGe3wCR8M%Ae<eX_kpxx2XperUSei2l=9 zl3>=IUiH4zHT9gK=0~H{D<S>CoILRFcDMI^&gNBJ+C#_76O+{%vHn(=mL&FO^z(h! z1!YS^hkLdY(mKs!9_%2TrFqi~6<u1r9B$LR5Npq@U12GH;TE?t7$d)n<BQr&0bt?C zU7Apa!TH(U8pk@)c1R?X2(aA2$$gt1(WtP%O&1^>n@A41V>Eeh+g?{Rjki`1vHyqM zFcrf6rKC!8OyxW~kUFJ^bz;x}F$Ci+Tzr3tme=SycE@3FSD%J`L8FUlRk{f;U9aWu zGehaVotQHc*F9!O%o}s|cz4@ochwda(f$vL&i$XM|AFIYvzv`=?)TZ;a~-)xY;GYj zccF4i?oA|=+A#O~ElIVx)JUSMkmeE+HIeAk#r>9QiIOh9`~C;#yw4Bs^LSmJuNtrh z=ONz1_~yz!94}>elxzs;J>Oxi9^KB>d7)@G*!Iy5R}L02f~FUy3A)}w-uQc~*}q{m z-8}J@5yeK&Vgx%bPr4_ke)1w%5X>h!03>U8<l7H9S~qk_c6n0zVH52oA%g|$ns?;h zG;-_Av_unEit!)_28$&n6$79&1nyi<-u5kd^Mo}Tcq>VNr6Xbg^531f23WS1fA+ia ztXoGqSUzoGuRAJsquwN}^H%fJ1`np?27{UNnWrTs_hx8caktBzV7ndpw)FaJiO*A) zGy5a<*+AVjz3WyIg%?-dX}%I(hwmLUiL-Mrr+UdlqAInlPX3(;mY{7M9l!Cj+rV>4 zU&}8ZvDM_eho&*{Fm8GB@#RnLalA?2^uf#95zLvjZ`R5u1HJ(>1FzEuk%w?mJ2PYq z_g(UtuL^MfA?pR0OoO%^%`;t(be#S;J9zQ77vA`o0-#Y&45X!@yVsJ{X{VOPQ3?qk zB9<+o;v_^G8Xvd^jEG8Ms)?~VAkpY<Giog}V-DGWvVBbb(v8UM+1wkroWUk=Py$*b zaq1UL@%+MWae9U-xHw($e&%<C<U!51{iSY8nmYEszHCGht?|i=;=>MY&BM*k`V9}x zYVXw7_LbiYugHsxds^x`Vp><}cl}<}GZU@cMXYgGO@pLWFp8A#97!L4X|?RJY!ZcR zJRzS8Y`JjbrhZwQe#xz4n<ewhsQcFM9rPT(dH(Ws?n=ulR542Pts2hO<dE0vg17ny zt~rSVfdB%`AB^5*Cof+)g$Q_EyL3KX{c4H<ov4aHkw~f#2#KbKP%`bima_IM(;mAA z+@^K<ZA6yBnGX>Hc37})iFE2a{SyifsavP*&$LfxDjw<L`=WXa+4hPtqz+`BnQohH zh06Qg=%4r8B>le&aXo_;%ROShFO1|V^$nK<4F3`0<0~6WThfGI95TxDZ9HCRCMk2h z*3&w6`gk7X*0O}7Q0lbl>8@{s!iUxf%jT?so|ab!@7_H;o-lJMtR#g4x+xX4-L_QC z&*^H|*0ud;Q8>9kH?jgW!2lr9O6JuZ_1aIQ#g9Z}$r=XI<`^J(8jW1JkHQgvM+Wb? zj$m__6|S}lN9timlMh@w<}Ji&)B-NqcO>3%NwB}h?a7k8qlPCOIM*9jG*AfZnae-8 z???T{EnRYcxnJxh<<Y$Xj>m`JRre2-b>eZu5_@$V?^X^~Ly}LoET|+)wr{h;OXpd; z7sU8(H7)be%3ZMLzM~t=lJ{Q<QGQq5nmTpO1KYB`nuJ&4mTOWv#-Nez-^l8;vGJFR zdhwi|%rf6!HaGnbf#g0V4Vt}RHJ$EK2NpE4%(7MKozsUvSkp<T;9gO&do<+v)=bk8 zdSQ;droYc~6h$%#4G{^kGt!{pT1Z*uzRL0+$FJ2+kd+hi|6fTJfm<vqpR1YI`rDhW zw2lRAs$NLk*I*nub;c%d;<)7P)_(j8Dl9<gcJP3Wu$rc*kZp8>-jlvERU%zQ(=krt z77_9c3|tHn5)dj3npcS1%QlK0%seyk;iNpY$TH1Ufm_1gTCHr1VIhm8Wp;-Q!GRj5 z+XZm1vSCKsLHSWb>GIoA3+g(-g$W75G=X9gAWo(28S0aR3(1&wxCzG+YX!h7MNZn% zAebHVut;u>%pU?enNw%O*vmTF`Wk&kTQ^g;nU34!AyV(9lY}70V|BC8r#J$N9mO^X z5>3zfL7(4xYZyP<Tw+j80IrAIiCZ-yT`9pq7ai>S9OmsN7QRRZOxyC6M5NWotZ<3L zQ|;I@qxmXd58k8|;4?v4xio8*#AgReZG4{HicLv@kkgAvJ{&zM#PLEiykR(N&*t%$ z)Sq=FBGc`b)%s2u|5lzF)g~5Dv-@kWorAxbqXKQuA^|u>)ob?ys}Rx@Dc`ZdKx&Xc z3`#2*9f-~Fn>)yVQe<-iQ(q=Wmep({KbJJ9!2CrAo02ivftkkqylVUp@k?aZn8`bO z9bf?*vtGzFw}=qY7n&D6PE1$y)X(emT*?%%vD*{*4LJ?Pi?&dwDr)MG|AjNetl1&g zv_&k8+E#U+rmN%LCzTu?p*uWvu(7iy`%J?C+YijETd+NLpH)Ajc%}zpXG7eRi+kOd zKCut9K0WYp8&)*K9aIj7p+7$okawLwpqmkI95X6;Hhuhny!$gO3OoZuaO~%>?R$<^ z*x+_}gJ}R(40g!qBr<T)JK_~cD9##pC}hx#ld>xp(k+0Sb$|(lP-xO5G3-wc?1{$U zd%L5Ba__mH1imaPpAYTZFT-L;CVUgr4zL#Ys}>3y&k}UY4i3EAnxS%Ms-Kv=EFRvK ztAYQPiEoY;Z^QS?+Y*Rx#wu7KjZ2C!LUu3&5PDQhb=4m(j9Hkaa9)3m+ic7BpAe!j z#1)kaQ15zEp}1E;gT$Z|n`P^VVI+OH$?<sMRC?d}b<?G?wx#z>^nE2bg(SZ@D;!_{ z%XJyZvIwTbEPQ*?{svLfHNv$+$TNad%uLILF=Mh!nJH<t(zG`SV@tXViek)K{vi}y zok`Zh*NT|T(d$y^G{}V+xYa+|DPVVV4pGq#kyIfdU#CV7t!h2(1M^x9jWQ)5<~ng# zAD4W9a)eq}`nCP&3)~+qx?|n^dVnFy3hRii;7@k=-r`!V%}XTDuscGokMXVJ_v4PM zzl_032{ZxRXPUh>AHZ=`x-Q1MB_KgXzu*%{Rbi-YK=n2qbBY;4KjZT7`3JXJ!)#%~ zZ!;PQIOGnTY*NU*oCXr275lr9Kmu4!-Dh)}qYVK2w_SWv6BqcNS=@}Mh8vdf1GvQ~ zY;wDuId^O}Px(#DI-6MduN5NNPeO;ZXSN~~Xjc6qsB{P8h>lU;^@?>DE3~k+TaBhC zgm&E8_pqjAkl<uu@9wmuj)9i9IeeMi^X%YHjk*V{e2cEM=gf(#7T^dT82Yrhod1tE zHRi@*_h~G${dB6yMNuQ^xY1(!G%mRgdi~|2*w&-_a!YlSMxrEF*6OeHt^F*193r<f zW$MO=^dv=v#Izj~1wV8XjwX@WcY~9kLn$B8Rif5+*8rgx*h1>PwT9M@u{YAKU1C(A znNSK9_`!sqo#>O_|Ey#E$mfLQu_!^z45=`IUIdiiRT?iGkYWGL$z8?#ca_)AA@+!k z0D(-0b?*lK4$h}9;DYnfh8vAjq(%u90?=hE;T(oe3wqWcC>3e*V`@l#gp51I61~om z>sqY7cLTS(ujf6d=SVneU&i%)kwrIjgX#O8$-5K2uhVf$LAdoETs=!>=g{U-<mqUX zFrT<hw5DW7$h`w`T3!mAD3V(s2&3@;Hkj~7TdcQ7ep1biIWHfJZ_*$E&1>7f;H5AI z8Nz{N&Opx5E#8uswb7R~ikk5&%bS3pJRI_aBNG}yl4S4H7eA;jlxq(<+Jy(S@iiMz z#bNp}9$ZqAECQYpY6Wz=gj4?L-LXu^{$YkX2Mu_tN*I4q`Z5;^o^dGcuRRJ9MG}C2 zU%>**<POd=mo_YGaCD|e>Qs=_I`hQ2ubGKaa_>m^swgi~{kMIyBKv~mgrL5O&*gWk z$g-wI@H54@l^$GGkLM&PrgiYa21!OGM+3sJXA+U8^}Vnf^O>$}c@ogC1_*IvTj>fD zP|7P7?hjdUfV(KI(xkNDElz5ZkGUxhz&6SI-Vr#NB__Jd@_r4t9Z+=*9++H1*7V3A zdvG%>`SlYD<6q^XL$!%_fJzQ(eda)WPgx;L=^P7vm4+pfC9WU3;KFirvA^2fAKt+f zwGWZ>oZUMY8z@A)stp!fx0TROJ3gtO0%?c>bA-XPx;5ej$kRtEvyw}rftC8<FJ>hT zd!%RRb=7_JIRapO8-908w$)9R$@;jNW&VyS3lVe+h_Od5@9}9+*!@VxWdhOL=~iGG zxXGQ1Gq5~Yr=S87<^VJmd{Z$7T<Ge(p=R|b1kp;6=YY02n)>E3bfs?!O(2;~rc$OZ zPy-UNC_Q%dl*$vb_E7I{gM39^kemw<FeHd^!IB7;kjku>{jA#eLGZUwtaTsg?49HP zB95<zGF9jjsv}~B(O4u)COpLXN0HuLHH9v!TzI;`r=SIkT)|tchvHvdox<HdWGR$~ zh`)`JKbnC9GvTW}I@24n>$9@eWX0-`&Ds-`jTym+=kjI+=BbPF?XwCWO4yS8So<t) z6lB=hr?*HzAZWmLAAocRi82A{en99{x5khV&iTmhBq1w7*D@d`YBNZ2lZMtc0BQm; zl|eGTVha8AIi!g3w^`Y+vdKzP-yP6}8h0^cI`#t~`rxjq*X-0Q6^VZsaNCl87(bY^ z;t;T`ArYCZ&B9h{0~-8;7a`kRw+K8XwnmWGNRWyfP~4!2BVQgT^_xtPam@rw_l)>V zk79L?(mAZ$eG#i)Wp%?K5^K4{*r_A<>)!t+oag7|r^r6+S(vE{4vq(+Npe#O=nxgg zi&=%F9;q}E+q)2qwg!~Sz?H5`fCI?1N2-a8Q<;0>Y4|8OV|jQD2lUAN;O86f13&P< z3Jupi+x0dG`?9DruuPFQfg%M8?$*CXCD0YSXSEE#lA6KJIbvt?zYi|qC8tzAdoR1d z==Wi2EKMY4ct$evj)e6mCAC&(!fCIrR<k04)B-_1mp42YBfK!1M9lpN#=DLI-xFIc zzs6JU>&rE;&i8}diq!X&2ML2me@^c8U-R-1b?|BJK{y)${h5G9;IZd~-oSpnMl#5t z+-itxBSy11j3!JKr?rw5RnmOC4Sn{wDqvNV0?W~wU`Q}W(AWSw;40T)_l75AeEjaw zO4{V948<Y6&A=wJ>2Oo!gNaIXL;G~`V_~Af1POb(#9S=;4@V-bM{MYR39e2lx=uW> zPRW2j)2b<DVjLQv3hW-;kY<B$UDzUNSH%rLc1b*HZ340tBztE@B#}sY=tg-sCi{t? z@PZudqi!+KCr6a@`7TM>S4lp}VcRAWgzx~^c=fy<kf17Nsr$1wl4wpc_|=D(1cN>C zV%-F#$%AJtd{Q#Natn0JpEEuvKsn0`^CL)#4L*J`R^=H;aiA9!Oj@g)!8A!Ia(a>l zXaZR$%mxejXWc54Zdf}g5<pL~j*5+<$NVQ*H1+xjT<so&0Gwkf1+pZ0KjKrNDmyKr zY?eRYk14Ffxdg?xscR%^MAVbz1W1(kr-D*j<>qJi6MxQZl10PT2sR6vzkDn;(#QuZ z*r5zyHyW6D6+~OKIqt=QX>g9$tpV6xV4#&OFH8vJz`!$IN=hfrc&C7w3b<(8k6FbU zf?fAZ!HroNpa<6v>ivT@{!5Srb5QkOem5i)7s?{GZlELQMX!zv%@savp9t3s+O;J} z81{&FY*kx=Fd7tbmmcvs3FUpW>HaVryGNu(opvOLhSB@>Y7jQogEJ`7L3zs&&R7Xg zLoOOc70-)Y?|F!mDEgbBv`&}RU~U`SSBfU#M6=I6o^P<OARqfV?;r^*wBg<Ev!gFs zbwrXC?w1}e_kT;4+nmL1GLsm(u;4)7lM~YRO+M{aE%xq5um8-w?bGMr{-$~}X}5k> zxOGPV&O)eekkj+2Flmrf0O5gVn$$q~(FP64VF0tK2N3D^*WO4m@xaEJ3p!?QZ?DT~ z2aEkn^Z_0fZ_bLp)7kGo0GkcMMY43{D&eY0R+s62a57Pa6q$vd^!Z26eWm0)@c^1e zTx~;clFNf_<*SiW%>d1z6722*sEh;7Il{-jz|OIf749F=fXl6bWQ+}9G$UB}rcBjT zPq}ybrTeS*2*#&bxfQ=K3pCvMjDOuak^(cL#92}F^E-a}DVnnqm4!!=XRBR7x<n<Z zFQ&Dr4PO&Mk|}D`(@_s0hcDnAWSiq~xFq;{QL8h>a-V1A&xNsKu5a$niPrYWx?mgJ z3y{(L94eZLw0B}GD$oBR2*WND49eLmfkIC+$^G_A08MC<rFvpI(*3x7SCnGzo4Cng z!N^US4c68OU0&Ds!7Ep}F1n)UK(5CtRQ}FnwajhSGS<L89~#!gTE5?#yvo~iC1*h? zaQ4z~SxR`{`5<~7R!%DfCgIB)<`RyeA1N&n(w6<c|0t8G*=`w!^Cko3&M7_ezg{am zGY|U>5IcV^*&NTo0F**7g0J_`LfvAmC@(6-nMhNRTx-wX3#ML(IMWr5%+;QYWZFFe z&b^<3ihzZ}t2+_&eInB*{UXed{b9+K%bw-lQVM4&y#+A4u`CJCwud<}r<*&T?d#by zUVyb%23}8}zkvt3-gcQZ;56w1XXud~#A_G&gmH_*um+hKzaYga=KEK;FCbYSXw}<1 zYF|U@w(Q`?jQUmm$K#hpnpEwU`^=w^an&5azOwcBQ&51Z_n&nyqr1_T3ww{iR7P?w zb-=!kXMMGlaC1F$U!A}0vvS*HzHOLWr`uOYXv~{F9$=viRs--LG2-l?XkN_t3Ggo! zKqGRs|BdL(oD>)@#tC#jK^E_y9#&S>ESfzJ+Ga&ehn=%gjHQcKWlF=JcCLz@y4V#o z?MJ<8?)Irin#<8Vl<L*Xs?|>e+RvH${WU~G<ahrBjktYjgOh9>{h}SJpI`uPcaZh5 zx5wQLdv}7AFI0p_-Rt?@<H_DLtkrb?DQK;WBwVYjx{H^!Z|b`{@bs9wG8!b_GQ{jQ zzI-eUyN(w-znuCgY8*}wT{DsDpouoeO#My4yYC0oK=k$X<_jTm8uYHe(_wQ#a@8!j zqO_G6#>)I9&fULd$shtpkEm3bQ+}%CNdt(rf@}idcdBtA1fLj`@J!1lCMUFDnC+fp z70r3l#`@^6Lh`rw5#Zo*XJxc|FXovjf&rNaHln{JpluBMdqG?OnB1q9$4rMmjNfP% zpk0~s8Uj9qIkUtZj{FD<k}yjZJ0J9H_ieJ6q{0$e`t_~Z^UnkzFJ;X%=u&7C`fCvG z0gHaupYmU++->@wcOjoJEjYDS`Cm8}`!5Q;bde#NkThN7T#po+Fm7?$(!fP=23VZ* z_f{$c`eBRP^FS=X@rtRu8Q?L&l8+9>{UfjGDBZgjB(nnIRIJ|czpSv$%6(0Huy~|z zXwO(dm?9X&#M?`#@kCuR9UOWd?p3tMT8e_{GQ6L^gF+wLUy}qUS?gOy01xJm4V;+m zk&S+DdH<~3WwL2NMnTQZ6u|m}>1hyB)*_q8>SYMY?K_9iukFtf*K%?`qg!KnVQ2I8 zP4%zu%uYjesx7u(T(&fY31OMLd^Pc)0349#BL!)rgnz9iAqNcDlr*xd?0!G&<p;oX z<i5B&Ctlt?@q7i!nS61?u|A;FMSNIS+dQ6E3*~Jb7**7ZT;$HfG4J;!9{p6UU5Ul8 zfcT|$cdugcMz^|kS<8G={Wpg}+NrXetAV;t%eDNw<!KA1$&b#BA$?xRFO6M#O&`B_ z!}D=my?$A~6rX&S`~y5vcj9aH{*+fOvr$rk?>i<dy_V=|C$+vUj$GFBTpsm*n6_M# zcW&^|wF&`v08*M)8g>R)ka)+gb-nzEwSGlW;;2i&{*+(fiHFB7Oj|_z(mPL}B`GWY z=|xH)HcQe!{8>+t<u|6-?&O6484s@N4SAJks-?cQ$Up{^RF$Dr=qsgF>1&;>*fV1n zoTn?>@WON}+Q7k-C$u@|R^1aaDs^))Tio%>MEoJ3^YGrw`@aYDjToUH*hm$t3-`Ma zCf~7Z_%htD8p_C#pM@5bd$u%?fCC8t0Yjln0J4}+WIV_0J9;)i_a2(O)IR=lFLY5L z9QZlqQE0rreP%hxnq^aHz72_=6pd=z%F_Ka<KY5`sJ+E16$GVmRpY6MDl*|zZqwPD zRpB`*ZTM5JiXi98$Xj39;tP%1OGCA6AO-P$xaJiBm)qEibhPEDLr7@s8;AIp#@k(D z4Q)aNee<#=VPU&54?p0%6cRUt#zfBm(j*Y*ecX+4(4~p*=qsnu$8S+TX77Eu|Mz<Q z%V?j<flm)5+I(EhwrA?{qz<wx0vrCcdvLE0IPoiS@z_(rS#;qaEDlcjxP$h+8Vy0c ztKOnC?aTEWanH$x|Hp}@bcGawAD!c}K99U{-aGOxzQ}0no=qXu6yAEtAPReVam?im z>Ux!q3^n%BT*(QJFtY3S3(|Mkx{mpm{_k%4dA1hlC|4Vma_Yi44_Cv8MtWs^q}_Mo z5z(J1Le|$I6bHEzRo`+{Ys>w(jZu16DMPoIrVc7v-oa2kyg}h3>$Pl8@llmVPlTq` zzFX5_kNocL3S01!(qFutvc8*b`N8l?@@G=!^8yR+^0QwiB1+Xk$~#qi-@LhkszIC1 z)GH{zdT_?k-S=&H-%BF=I^(b61)f+T>-7)W15)DNLqXcmUv39fGL_N6gD(|tImv+D z^{(N&Abmpe-?KKlKdUs9p#?=6w2YqjJ(#>+*s4MVc&6}??lXomr_-cvvX1QPhF^*A znpc>W7UQoWT(6$Uuz+K6CKGPx`Ta3r(%KHR>pqY94xdiKIL->GY8>@Gm{6-RMA%6a zbk4UHuP0Xg_R}DG1+wt>c>)AJY}B^_l=JT{K5pf7DRXE=<Tm?2TcNQYfUZ}_KIPY1 zoUW|7+f-uOE_d-@r2F;LSMtC%L;Wz+^<JakLY2^o0h8^ZtVe%?g2Jb-nzj=pL&lo$ zlfNMvU@Yp_mYqaCVI)iZ#(^k1Q4FYxp*TX#@rTsOctA!N202cBQ_qyDg9eQy<2Vv6 zqVYEl3m9rv4F@QxMMh+YoVjj~0}RQy4UNHlJX5_R!v@+Px95r2`btLQqAc~-z=w{- zT)!@`cw@UQfEc^z$4(2mXi;k*ri#>-Pm{b_BcPg?^df03yi$BDcz@DZ&KRNC$2%Wy z@t_TMvQ@cYLz``9*e;wJs+6&0aPd$zP;|1mFX^u#`_{cFbdpd=>{v5vfA;Z12!8%q zx~SM*!`V%fy2FyZi)E<0FdXxoBFfCWeAQ<T7yGtbU$?MxFgR3em$WeJ6d58vW$;iY zyq%mV@j1fvWl-VCp?T>ipROE=K9%mA-6wzaceO{~0NTDlM>?XU9KXwxjLX>cf3^Ko zIeaV^VAlp`5c`}C6OaehUep{@aKm8Qa(y<R;zy+U*Y+&(-`4Be<UhG#n{l}f=i}P^ zo!-7eI88sT?vvkQ+IO^iw^Y{mD85S?Tv{tX9K~R`L6o%8TGbm<10r3jMSbyAA}H@a zpD)kc>(`ii_-3M1!=Ol`MrMhY7sl5u3K78b47ryBPAcqhyk-JjMcIi`i%Zz;_~P?l ziAb^`9nhb>0s<GqQlsY;hRR#c920-sT3UDiC^gM*g|`1on|=L*YHRX&f}melZ8ntN zFYmn*P_?o3xL*Gw!DT`!K-^a9NFdMb{qJICO_+Ex-rG$_n^4hCmf6AzXY1r@Q76(x z-u+UYjO9ySHFXN&F>5)O%Q&sIeF~FYhHTijpB*nm{%uv>V6}))<^5hUP<XlwLd4AH z-o4bG$KOujX8YY_GVJo(?%?#_VReS*QIlJD&PL|g%Uza9Z%-M_l}mZu{LE(H6Kka! zDlNX6ldhOcff%wPY!Z^b`X8Y}N{!r#DI{yXcq~-S-AxnvQD$!ve|}WmwR|*)$Lc+D z)ex4|+f^54YQME&n`O1WIu?jx{wK|@_BdkR5zUo)G9j1@CXP_q=>t{_qr&ea=$L!y zxZLeNoQhFjpf57(&#l+u0<`R~t~v3}$5T1ywWN;~T^BwlQ=zKT{8=(>pZ3wqx{kRO zSrLZBcU6vS$B&JExql=}ZWb?aX!xL*L3xtO<3f`Nu!@)Eu1xjMcJVtc5n2>l55Dqy zklYgBbg(A42J+)!a6nMZK?pM#I&FJHNB6mRtPNAlD}MCeBB@x*-hSA3ZQZkwEZkcl zJ0~*>%3S4~@9Q#%@y}|_c?{Y2=NG1rcJLGS=*>gY3sUzGB(0;naoJgyL86u6(5GjP zUc|vjp7B#V<Q<+v^Yc@CA5m?=i$;+v5Im-ydt>Tx=@Cb&)Q6M1lAb1a^Ac7U%-bj7 z6$wYrblU0xpM3{S-}Mv)o08qP3v?`d$JS#7(++p)q>H&iYNO%*RBkvx2Y;6$Jq+hX zK&>`<n%~}yp4C<eZG#QN^iMqa94>2VeSgihR@8qor1s&70P_(7=GZxJbpZqb?I2*N z3xf9_n~X$0p<^P7B?N7Jj00%t37(JV@I6xm%?BSdU5}>O)N#*!R}@upuixb83Ip|E zPR@6fw*5w{eZ1BzDv3KqkewVff3JH%oE`=yp8*Z+krvrSZ<Ao+BpetIM7Rsy@i;LU zLOT+q_mPQlu!obg@D5m^$-so^6FS+XWT?n_>3RP}pE!wa>`A73E%P)8fIkF~`a@~# z-jppL!3ivI87o@5<Y7Js`;TI8vW>m@0QMg14Gqt5H#qsPRRK0bdsia3%@h90IZ2wz zkkFT!n-Si|3g@;aUAT_eq+nL53Ak}+_sn_oek6#8sQhUwdn3(%2pdB}JYGBm!XpwX z*hUI6u}Z^iB?amxIF1FBXSJ%`A{CZ|(^jyKi>I6sIl8sv=@OXnHvk$aW=|59<B!Dp z=3qdI+(G^g0y)ftSxX6Z$5Bg8Xk7w!V_s2EH+X_sSm6AO%fgBChuF!@6l5_+>LgeC zd%Bc_aqbx~X$8P^ax%LCltd_*93=lR^z5^2!>vG}g97OC>;k0?v|t5H=bM7Dn>CMX zH1e~cd(QY-FeVo(z|DZ9Chl1R2(7+a(WX|TG{OHa=EYYfYlUar5cN3(i(9J;05K79 zT*t=Nz)vf<{3=wcjc__icw1VTM--02W3V|`gId8Z5)F4rQ%(hwTCAooBBttz`B04Z zwJn8%B0q7_PboqqQYxYr@i!Rrg<1gaO91gqvI3LCXoA;B(vPe1W#F+OqTnfsG96K6 zgR~3K5>zK`57&b~__K=y+6!M-$-6z<6QGKjXr*bI0VY0vM^tmMX5y#x(LFRo9vl%# zO6?Xw6ZgvNDCd<)0riyPix<<JlGB%dA~Ptk6GXUV8rDg@QrTK`nSyC;MOmz%I%m*( zE@G`gm?&<fm051{*rjn|Y0)#)St{cn09_~nFch`a8M}TPx|^dYPanTZOf_?a=W>Pm zPZb>yE0;>kn_KqxG0AP_AhR!Jv9Rf5t%4VMnb-G__zcyFRuq&hTtQX6C6-a2h$@w+ zm<kq_e`fKjQT4kw#;pnfV*wZwd`(*KkJ^=QPyN1Og%Yqu6Av$s(lG1Ad$!p&_bJ7@ zNinApyE$oNgyR$#{DB9YCD=$p-Uz)4)S^Sl!r23vomlz|mSm6|3*x|zK&n}LFi!KB z_cH}zxiYfiY7~wFU-~x|f$$u!#5^jrrfYwj!Hi=0f4Oj5Cai~>yWNV8NHR1vsu9VG z0Z(V#pdv3~Q99go=0?C{0Ck0TQFBdR0*R4$mJT8bmy?8fTo$ZN`M+W~R=M(WkkEgO z!+uUmv%Tc`DK)KUh)-MBgCA+g9!8zRf_DTV-6EJT#ptt-OzDEfFn%DV1li7qqcJUo zkvEj@9G)d<b(4fIQ&rWLtS=FiZ&MI=lq*jp>@BNSzU)<bC{O@B1L%Jfoxty6yNs{> z=ocDd!t`lnH>Xg2--Ua6OdF`kA{zXny=KNEhK5oDn<E``BkuZ|{N)DBWy+<=z$+rs zXkfwm+TFyPGZmjqX~}ENyFKXHnX-Sys3-$q-4O_;34fw7jQ8cP6O@0_5Dr)Y8YwlK zBeWfeUZAjDJ%n0m*bax&2Rqm_ne6D9H0LmEH%YKmwxwSmJ=RoIRgGHkQ<$zcUY~)z zrW(&aQ_keLifAbX_n`N*iHZUM(GN>zVtj_o_Gn(X?^yN(j^U#Z_jf=na}j+rXZT<~ z7rwsM<JiB)XCNj01~&iTrr?Kq6o{M9c;HTb8+w`N`iLYfet1`K$j7sqfZ<XPNA28y zhiLKmPkxq-NoC$4I^i@)u&E$4iFJeQMl`p<&;T%dh5ma+?uSMiPCyezZWTRIlW2-O z*)CN|!&WM@!t!LE_*@vRxIZz28lW^a5R@PC5Vf*be~OzIY1}RJm-<ShYX<?uwI*?@ zQ2$10{BNtz0Gdk`Hssbh0EkC{#uL+4X_v~KBWY=5=>{G$tT^v18w%p04r_K)wek7I zAy<0R51(zLK#5BB!S7_s>W5`nom~On&^4;(+*g245$DRNw@&}4>LsA(NSJII;{K<) z@<0rag1&Ipu&<*^-T=k<UHmwU*+dhpq(OCPyQmh5U@%c=j3mev40xX>9jc<-NxW4R zS;E81%EGeh&1&na&PEJ8Mn{WtSi#*Sm?i)S76YI6fOyZ$^d0Zc@fAWIDoG1$iA4N< zi@p@hKA?=SIg2e}y5FauDu$%b&%i+x_-IGmA4G3U9C~9WA4V3w@(s-)oVsd8!AA)v z)3g>R`$xynA1IiAScm|(ny>mGIT#<`I>oMJJ^8*ZzfKwr@sx9W;9j3;NLdNpv<fc> zuSDLT5$ryDe%cs$mx4;AL;I_+^xsd*+tepWsPcoi25Ftk07=G7Si$(P$|cY6nKQ9} zhSWqz+azH!0DxPsqDdfe;x6K7zmD5<*CHPCori*Q>x?*h9U@ZXvxXHs)MN;jK|Ei{ zm2yu+X1qJcIg7kXMY>7??cvxXlTYeKBqaACph3b_`vl)pmGvSH_uskB3ltLfd@$)O z15HQYa~3vfy@RFzP!b3RK<|_l*2*U_QqaRxVLAoSoq;&aAY<+Alk@j>aQl`7DxNZw z;(-W<&g801e|2}CjWX;F%IHe8xY?A<L~i3-vr<Qa;VbJU^~l?@e>t2t!Y0LHqO@KE zC*dWIa8CBi;2Yic8>nn56iUlAiN<`!qkrTb0@3n8*z^pJbh=lwd|z5K5miD&oDLk* zD3Ez3c59Hcn~qZ`m<L|GHGMVPxW|T}>Ul`ESqlAu^GY;u07^OP#VyrKer3<@o(sf0 z<8|Zl-~`H`m(V@fU;X_m{KN$|lZv{Uk@grhc2Zp$@zz%At}O^F{2pErnkp^rcA<v! zC@@8+6(2GaP+N$&b9uzD{JpG~vv7VfOaQ2BItSSBlEQx$+;2qBQPAHhLID66&jZnD zLjA-i_wJjXmj;5CZPqs(LGK88w?^m(q^|}drN&PqdRpsaq{4kK+_8Q%QG6w&12?w{ zGknmKR`n=v#?I)_d!e|5&rHk&w@H8pV5opN)?$Z;UMOyRHgsUMwfiec2n2xjDFP$J zT}*@O!}}h{D_oo7JVaaIR7n}~cjvp)S<L2OpZsX-hY8Mds`v`8YX@<?l_dPcq++WT zCM#byFotZepREF+H#i6ts+xv2Ac_S-nV4*qYv1;r9icwA7=@0sl23SK91uXc`V)Mc zq;3*X*d?jE+>wnpo#hL*$=eVj6$6?<w$mE4zDTT5?r+g9{O5e@5m9hXNP!*n;_3(~ zoY}K9x`+gsTw+d!X#+$}(9VEYTnx?L1O4YO%6vb_g@))SVtCjIU`@yUEFZw@uO95v z*qSO*czXC2@(`pkns4E|35}9aE;~z*&HirM{jpD|K_I!g<k7p8XR<l`Jx7rb*S<XF zaS)=UPdBds@7$I?5b1U7?zKQn%>8jZAKpq4I;S(?QYSUEDm@s`&T#%e=2t2Ndya-3 z6Z~}8ll8gy3TOs330yA=6mA$s&$Pmb^Ut=JkDO0`&W%IIxqSNi=M_+VRIZ#+!S0r| z6-xU3@(Et(XW)8v;okl&L9vTStdA*XR6j={_VGb!h1$4cKkOJ5VIz;!GjjP9E55`< z&oUDxW<Gn!e~FBjE$0f>e7dzmK}2MJ%V{HT5d}@~pk}}2r&16T(gzl6`QZ(_#Tnr@ zBq0**xe-?ga>!n~-yjP>))C{<1S8-g9{8-OwG*o~tyJ!VT}%lUDfVz<D)w~+mH!%J zrA*BGz^7}p>(GA%k>hP4kGHZ!Ld47wC%|<octA%40;V&}Vl&7kZ3Q%b`x?Lli0;2= z^5-{Sm67!3Jn6gju216sJV*AO?Z<I{y#CuiNxT2<MS3STq>qf<AtLhvuTM$8c<=iw zOJ7oR46aZ9*_=B-!J?NqM^i4O|NMu3&;|V#An=4D#IRJ)I%(cUHKhd!CK~l$nC=Xg zT5JY1uWf>bBCwsOck1PVH@Ds^S_!`UY+<kgeMrHm>j{3i@M8Re=n`}17IGd8%nM*4 z-Nop2qstQEzaMmsLjlACU}4igNg5(u1HpnIyM8-{S==VSs}3ciQ`}jbY!OwLdf%}* zyL=g=*ywiZ1e<ZyqAl1i+=WIsj*knSezkb8O8@wa`om%&9r4SizmTL+b?vCxS7sR} zKBFuWm!ox$zny3ti37j)OqU|P_h>$RKX&o${aUk=J39{egTXWbK@gDtP3lFB+3C33 zDGmN_Vri#8^;dM-ufNCu8`V#rg};2)(V3$vi{v@Z?D4+8RCBN1sbbJA*XZPf_Eyh5 zZdcXh9Ot>BYF;&7x5M7QZR&{I(p0ERY+i10+A2rN!&`8AhP=Q|wWD2grpermmG6?T zx8qmFE_b8My?X&cbSp+0SgbONTU~fjadh`+T<4kIXu=)}AkuaQ^x{_3iGO?4Esnci z@b-FMbjelopbm|(zL(noR@kQsIKGgcD*$rI{S|<P8P8gX<pEbnVmH>SA8Y=$D4pC( zZf3Qr9JaX@H}stM^af|_K&j7K#F(aZ{6xv!hoPObz~?*hcwk+F5+o(}CT>h^IkEhU zX6yM!b&s`VBbKh5=?_}ARS(KlrMbJTzQkCow5iZW5TWdY>Qa8$6~Gd&&d^%umnz^l zH4*=^dd}d6LS*2#J-}N{KHyXhx-oFgXoEL+S@l=Br_wS%4|i2g{dIyzWjVN9M44-# zr2|J3nNqf+LF&3L>IFAzPPGcn<nDrrt&38@>k$WPy8K2FV(z|eBccaKczt)kZ#KO; ziil#Wv|VtZ3e7w-N3G)c-7O=9_)WTM|5b~1*jUzp*@3HiD#?cKG1Io_YKfkpheuM> z6$TY9$UD-s;hDAv!N=A>2fVyLy%u?Js-K{C$v#+vhKPWq-MF$NRJc+C_?fBhbw*a# zNqV`sP0r0BLl;XAvfDwTHdsOXYQI-1$xA}xCHfbgV7GLn<g!kM%O@_7ZA2x-8h$-( z-OzYCkX)3wL;5IxiS_Z*NN-CXwd<Gtv$QCKoz?1%G@~nt6Ct-@0fOUq=58GM7CK+# zc}W{^wto~I+A87CmJFXyVzGA3^~m4vbfMH;uEcj<s#lL<e}jrkrv8&@wAi=jEmdHU zenQp|8zURfJzN&2z3$NN0u}}1$+!zMJ&rA0%*k&xiF1$cJ~odIf*sU(RBu)Yct<w$ z`ng~FPqb4k|M5+eSs@NND>h<jWbx(`)B|eoGlsgg08O<97};Y2Ft>j7j>UC9IBz7Q z_=vH(HUDN^u8pFu)%gjAClnY_`D<U21qaUOh{##&h|&}-MkITggBA+}bgsk~iDV>A z)19og7fL&c@A(f1DP=P9BhWSoKrb6#4CoA{YlS)m6p!yew%so>k(9NqRN9@gKrme& z5=V*EnMG*?$*uE(c17;K(y`~=)Sh~VPK+h?CuA?j+lL~}lYEW+odsh?_*Bep5pv%s z*rlfls-~?EKbT!BsZ=)yf3s;!uK~g0hHP!zgILB(ZK`YAVn!r#0X0?cTzPJ;6|N1I z%n^`J+04z~U<z*QyO-+d51O+<P>Ctbg)l)H<ZAYwJuY#jdeeteWkqP<1zj0XQkDg` z=RuwRJb~Z|ZOd=SJ=_{sF8eE+r0vj5ps)z-)Dhi+JtCIiNHGvX#3->1b;`}w{-Ljp z2^fDn!~kk$pA%~Q_*XHj28H|Ln*pqw01^le2tZi>m;^~prG8gUHj~naoZ|DC$on^E z-fLak&CCfODV2Df|MVT~hDGv=Qt<`^Ni(2FP`STHDtiX3r_1Wiz?J#$O!eymt0V8& zUkO3U4AG<>dAG1lr43&Jy=WEpiZ8F^+srbNVa$F2vReOGFwiMv2ixD)C;y-os)XdF zA5#gzeI*TQrFJy)^&i5N=rip<0?gqNFl!@Pa!-m`u1_==Nu}5W?Y!}mSD(u&=FaLn zlw0Nvh0D5|u2Q)jA~HG-ic{y-jvNl(dorRFvXsCH>|_?jaFo@-n^CqKV7a(#WqxeI zPKku24U2{}Zs4;PY925>#m5QC-!KH2h+ww};+EhkhL%APM0279oy7DHQ5TfkO-fKc zF|x^J4a^?S*|rY{v9pfEXpN>g&!fQUt8xD!DpR7Zp$xk#Y_=ps!WoSF=-~9GChy|u zdJOJAimS5jS@@Q=5#VP~^IokN>3@|aDY%OF3ku{<ClG)qoJq~@%Lk;^>O?ycq<J;{ zmZg0Vd56OSN{jT-T^BSiK_?biAloKv5_>HTv+_0FBn3&p1v80kNHfoU;QT{{CF}vy z5B&D}ByhKYs~z`-Y&-I}m(VxFP}A)}mPkNI>{W-<$2ll_2;l)(5TdUQ$~_U&o*n0S zAgfZQFCf82Lq`9iRjk`gN|Md+f>@!P%bIYMhK&rLA>d_b5%z0z_a1H#VV&rF#sj`U zx-cbUv)`a5_&<An^{?$PH-?)4cHxEO4<V8lHM$*Slp)eih1!I%kXDodLY0}Cb-X@8 zx|kpuLv>L1L@i6WKT??Wz3!UWmh%{VQE485(py=>wA)uH@Ypq$AA<5DAc3;|_<?GD zXt<}Ip86~^Q~4EXs%Imr)q{Irl6ngLb;l@muK0k#L<kBi&f$Xh<V(D{!LYIg56hT8 zy_8>(dsw6Y@(~FH159M>tswwC8tFEnmFu9Ukf%FITQO=q@`rtF+rz^RE&A63KDPFa zjO4fiO@y0(e6Vawo;v5|U?G)L_tuO;R&$)8C7>JCcmJ^m+sq3mA7<F#zB>$nNBz@{ zv0jh2IBr{bg5clWS?RmmaXMCUFkp4#hK;F!BBU*%NUBX?88PU0QUG;T{hbnz2A55n zf5%q&iFz35V*Y@hcV<Lc?mLkA_O^aOVyO8V^RANVLQjrNF&-{TA%l@Otw7CW(b9Ht zvtpf>ab1f6Unwv*fmTLcp}A$@gAY8}+DxEEP~ti_@Ve@^977qiqT$~g;>Iin;yw#~ zuj=WOWnHWOXXnlqD!Z8mHkQOCCEr>2ezWV(w_H7G<#U@kFQ2~AEshRNm-eJT{}gh< z?$m^`nEI{{dgM}vTM12MYujEUq`JGNN<el^WY=CPl1sBKzD5kVmU8SwW^U$G52_SF z($E}w7(Ch|A($))KO511>&`>{KuG9RmI((;r{b2sGuuh<WYbKU+RQ^tSYMLiJ26C* zv@G4X{#vkz$&kQFY*iO2e><@Ao`2_k8}kIt1E|oIle8@7_C2D+EAlHByXWg=0yEC6 zSb|DBE$%2ODP^6SDgGv!Y0uUkvbk)F0D=M=nzB13MCIvKhG0R);cUh(Uh+Am!`NEG zD;%oTnih!23`>GQq8W$7dpzfrPb1)zY!;cx>6^;7b*zUex8y5fX6iCh5PBaFz^T9n zAh0tT+aDaFdDP8jq_JLFy!3K42(-&5Xl3`GkAw8fViW@i_<nsngc;`xw{y=7Z7&-X zpvzJWgM6DlTW6i}tx)0%0vuK6y@FN_(4CzpZn<dy1!76eJTE4n?`}JF5MJGsL9HSX zBXd4b;1{sjSFF3h&(j<6ignXiZ};wC<p&WnnP;{YgA8jPa<cdWw*Gb}no5II>5e-B zrd;?Ba|=n?9x=yj34oom%oAnj3>`L|kA*#nqD5z8;%M-M_FU)uD-I|c9-CdeSGgWV zD{w1wti_pWWQ1jBH162L>h~pAv1;^%KF(&VxwZHdXGOhL?M&knR@1$y2N3buK5p=m zv+&q(c<j5L^a+Rb-Af%*cGiO=Q0aK5Lpcq?@5oev!ilgbY>`*;qa=B9igT9eDoWYb z8pZ}G;hQ!)pPj^J3C9hCL~j8}&==!ORJFifGX}IrdA}$lVCpH5EntNJ+z)axCZ4Uu zvCxf>ArSmlNKQ&I+{9O4F2!_zn(#+jmdAFQ9bT!gMrw*^F&hp~ND}VSmQUcpl4*>_ zOS%(g!}n;m-OuT?Y1!6*YZ`NvHQ7ondCd$*h(7}OzW1p%z6pBDI(fU+JD^#~opdBA zJ7`bk-YF}OZNzT;e#~2lK7!`h3bE$*O4~C!yPQ9j<n>R(HsYQf{#5B-3_i|<&sX2s zEXhjQ#dce?W`1KKq?{DnU%9L;lqcZfpv%?0O7vAHV84gLJ^Z1hBzUy>=$hb@OYT`m zE@%1^dp8bdD6;8wk&r3pCp7WwmU`!;{ND2@K%a_p!<K2^gSblLZqMO=O*i4IGMtEP zpgrTxxtCiqMUn)ipEcR-JYjy#<bXr{p1Oe)jh7hPmr=p41sq#Rs2pdfwXuZkph8y} z-Sa9TYYF=bWSw;+JxlZwJeYP!#llKt3jCiqEU5KH?@T5T-c*x+4U!Cf{`-*iD#VS# zaBFP{$$5xvs9mfP*vn1_vR?$szv@aD174{mQ?qcwcOiRg9wE#_sOi=S<18&t%U!!e z)x9m}FVR74GH9riFFl-R!BWG`ob$(y=OBON=L$!_quQaFaa}swbQlLv;=EFI&OF02 zN~QL;3vi7!(~W&yj){tC8w%)nLOqDkktxlQwkMg~G_fn``#4~mcBltdj82?9U^HP+ zkn?c^?my26Ti{HU<Q<=YC(bZ{Ap!ea-j2gL@yyJCstg%%{ZBTJcC=|4Oo$UZlb81D z(rQI!Ql8Y}z7|y0n{!+p5*@Y;L^d`<{Zx;YRY+-PMZH$`O~@X?mpx-c@gCXOhRLaK zjAtayUJz8lMr^^>X9V=R0D(&K6)>T}mylN;@nDI-OSkaWc%x~@-C+2+5=Pl4=eip5 zYdS5JK-XZyAF{d8&rn*TuRj2K)G63e3KVjrH&vU40l?Z4*?L!A`zd(P*(2EvN(#Rr z#^H$Bn|N;`)O@t7_>%V+>dGOafHi`4UI0oVF-m5AYesFTQ$}9fX;)5pro^$JHrf&; z88O@}xY)bL1&V$*vn;E~juV~d1px%*O4)OevO~pH<bV6=1?@vQZ00N56nMA;1b&+G zJ%l2%O*f|<QgeoFhfnFpG`-z=XL0JPBNuEQt|44)XBg@6@afaFM#x@M0mz>WR}#Z} zJAdGP>*g5zMM;M3#$+8`Sl+1x@J;tXknMusEf*-t?3TzPDDD%Ek7N^QjUs?faaKGr zYuDD#QRelJevS|Gp1nh+EqCzyUc2T)R)fl!(cCP*7}YfGtekIJ3T4(O5*RMnOCG-d z?fMLNjmd{sE<J4<f5a%x7d&R_0q;!D!qjBW4IAY-Dmug+;NzSv+MzN*a4K*Nb5t>& z4R2(1H$J1wXbj5=(G-?I$t#(=ImZGP%WA^mEqfi~!y#%Pj-~#gQ-1@pQ{dO5A0ya& zfG$jXx~FN|@7E~Xlm^afzvrwBv8vMZ;QFTY$@?Z{oQq1gp)fSGre$KAC4cFp0)-y! z#80D=-XgajuR$sqnF`P#w^ZTsTk|(c+>3YD(rRn?g<jgh*Pf33uF6Dk2(L!(1-2dh z3YaqD<4?mKoPsqVD$Q@<R8S=S{gilSULGc4I}=Fixvn{6YpG@zo{vnHbS4VyMbPd9 zgm4f0Yis=H70y6;hdu$%R*n-A@e{{EKFQN=;e0YK6B4yDVOJV-{OGkfQt$=ej9QCV z-QO<)?4CLmQ1d~>^#1o7(q39~9Sb{9i|{$~skEjTn$XJN-~Fo7i?A3z7MD}%)0BH% z6K*^CX1*!ikP99`K@YMSKD_k3N$GoWSeNIQ19<5sNg<h`?AU)ZQ9JuPM15kri?_7j z#qoKHj~Q{)!6igQ2pE+*lis-N_R8Y-^k&0LnIT4G`i(<{XxHoRE&pXkv}Q)kFl?xE z&=}eeD&5EKh`(uXr~@pPXXJC|ebZF2-@oVcN{nA=#mZPjqctn5UoyLS#;n4j)Dh}r zdbC3vVOSC2nO=Z>2dg|iT{S5tbtP=I0%E5+JGU0nF{!NOm(@xYs5$>eo;WN+vsL_I zPC;bF&ahky(DA=7@xM<J8|I_|2@cONr*ggaKluTG@Kb4T4rQ1-WJb1|#?0)~tz6Vs z=!H&5)3=Xj`7%&VD|s!&`IG*~B4G8(V&=JbdjHKBmu0yC0cBrGyCu!2?F?&@fD>g} z+H!Rv(-X88EP<s9?GAOytaK*eN)^xmb3I+6bA5RzZ!<a1z6`#RV0v;2c7}&a?LRRd zi;<-snXo$&<N!O)5lw4e9Nv6;@?QSos)OUw*;x>=b`UG{gSg3$bb~<fP99_b`!B+s zxl?R6OA<W%d`b8DrG?rIatl0e%lpg{Z|hl(cPRY8z^XiHSsnpEvZEEhq!G(5GF$St z>OZ<#dU;V92f{OqO&eY%uKfr<qMP)7a#A~%28XDvTn}FMFKl%<3(g`kT!#!p;urzo zh@b~Wg156nuu!L=ho^+E`bZy^x*dg$H9REUDY3l&H_u~qT5HW-;1B}!A~)zqVZ8lZ z<taAY1Pg-iV(Ic9W_d3fWe_w70wAt<TFGsWQdybt(<+i#XE@N;1Iu1eklJmD=8O#w zB+&3Gi*B3cl!kX6eD3DJAKqd-JeO^f4XOVv`fyaziJE;x8tTMM+e_53K1N!<1&<1x zjvb5b<c*8F6xy5;5S4sW^<h2aP2GgbKpY;Pypkp}M3Wiml$Z(<Ee4604g*Ovd1^Y# zG55vjspIQENDGbV%dq1!4FC2F>m<mN_H;#G?hn%#w)f{h74P2|!&~MvPqL54I~;m$ zc=!;4W|;)iJ(;b}JD&eX^g-ySLnY8|eF6D)$UzMOZLECI=nu9)kY)k&OM`oFn6TAn z|K#1k!V2vSA0XkXrql_aUsE!!CPQ>7JY9%NmstRbCIRa<w64pWG7f2?pf$xCg6>e? z<k&|*c!s*vX}aPzIGiS16|8a0+JYl`tZu{?XYGG=HoG5MuHjFg$^!U&8!W=f;a29% zY0Eb7fntU~8yc(*$?pfhO@T^)Bd*>4wDKMnF%l-`E$qBr&?|AbrykOiIXme3C)!DR z_zO%2`%?xBLJZM`k^n`QD>78N;{kz7VueW;a@D4z<EvmH?9`*o3=b;QVkV9D@he@5 zKCzURuJ<5f2-Xs<=_-y$e&gWFhG@~!gChmZbut6D;W2cXdaWM^nK~9TjKjN0lKpSa znSJ$-IdoCsebm$JKOd^57r^V*?Tph@M+>P7$!QXMDzY>XXH>o1We^~m1F?@GAhOp% zylTuY_j24kr!h}MKbV#)sTVxrJ4QH=wZ1@aR=<twO8MSSebjgSd8MooNjzKTZVz0_ z-}}R(yU>f>XL#p&qfWFa>`Pc3aGPK!>>0oAa?QFx^R(vcChxk$XV7Q0m-hNRNjskM zX;RCpR=2jtH_FAwx{cU`)H<X4z9aGL-000SdLLWYz)8xNmQi}C8=QhqHxp_*`ad|W zeYY1BmURMczDChZ+vZ+ewMs|pq!=EJUs;H_q(4uFNx|YnvC>TD8ki6U*^S7OQFxUj zQKq>V9ru18YX)2{XL9eo@&70~?|7*H2abPk-{JV!TX*JJb;uswS=oCfm6?&s%qVqt z4rg{ol8}{<$_f>AW=Mr1A)T37M@#GL=lB2TpU*$<$NTYqy`IlkK<Bys426293QP0L ze|<+ur$>MTA%EH91n~s_zSht`maPPX=x5aYoI_Xs^L%k#O-o}@iRE?s!K&`}bmibu zVUh|Y#xI3BdM^lxkNy@sb_H<psz?#_FT%TKXIEX-KGWfxZIYcdP-HfDsrt1}yU;?a z{F}F03#WTRy{fWx7m5P(2ErE@yyAfoqdbkmxSp$+jz({&jg{<>>KtX!{(P49gfnpE zw(C_Z+>q8Q!_M;7@mTGUcIh|>9gwlnM-a0ecUECn^`e^7UY*ikxbeyTwp-v0i;h`; z4Bn2|#E`$!xty*jzL)J1pj6r^Ou~!y$G%XDZj8003wLQ|mffOB)YpFdhu}5hH11f) zTn}v%4Unot-_afJXtI<Uju%uqTD3EM_rbH1F%H%oc?}rzAQNZGdslqP6e{2FgA!)M z62DW>rJ(2xczE=^s^bhshZ#2s<)LEZTPp<k4{8u0aT@k)C{{Q7=p4S!PLO5z1x|UT zyMXiLy~YyAT2vP97Y4+HCj`<J)Zr8hATNGh^<Yy>M%`t|Tg^I)R(YR&32MGkm^p91 zHJ3y+E5YZ)gP!7rhSayiwg#z9$y1gJUuRohU&@Yl(CvSP>w(G2-<^i>b+Ap5?I}zW z+KA(PUpsPdW!Bk$vGL9K_V3}amxqTr{v+xgmzw%xkGutwZ+t;gsGVWwBaZ?;oSiRL zf04MHQjv$KkFS$6b+}YfmSMT7;a$#0EiS>q=G4x&dHiaB5fP!D!EBcV!0s)XTm6BM zRma+$s?YUi-@OD`q7PVg;@PfU)46pTv?`vLDYJQJj5mF5KIZfao*L7iT!Pv*$p*4I z!z?pF${1d+ltMnt>E=E(!!RGW@=k1dsWZvA$0I@D@9r-;sLlTT1Yvaw28Mmi<vG~L zsT?^x5%DG`YNg217p5u$`PrNaxRJ@7yL}3;d{aFOWO)*4Fu4eRidWIT$xja^42?jB z?(PlA78-a#Y(shk{tJ@gaGU^-Hq-cyO=UNO8)l%Efba)dzB7crAH+8~>=S_(l%!<& z&kMEY4Vq!Bq2v2!s=P!X1tuFoe(S@bqGnH{49cmJ@!J{4_svo5@eU$ygDqvVtl_x$ znH!3@c8O{}g=0=b3Pdx3Tkvw}FOTxs#091-G*9^s!9q!8fuZcvC*Z~+YlS%HYO+^F z>i5S54&yN@B~<VhrC;vgf`$9xVc9Bl5Y9H#=H#_?&B;NS#7QB_2%PV<)cCYsHC#Nw zZl6Z3eXkSIcEc5_RU|Bn((i#}ka=XaW!aP`jRYF#gM;IDSx7w!gr_ePxn~0O=!{vx zapk$lgU*Y89t%=1PLA*+Bso#&C^9}iS@NTmqv2Bs%V2BU!G5iZm=>Sm+Ul>|+0iF^ zgKU~9m0|j*!ve5!=C+C8@aO?Ts+uk$L*KQkBql(Y!!4#~W*4|SH*Q-+A#=ndm#W*| z=K1Zq-q%)xO0YT4zg&Jac5}h)&@v%SuXX9FMMyqM(`yB$=;ZeE1aJ<q%R-g?63{7b zkrgD}IWzg_6~LYsjkg-WXJ}-Xv&^J78}rj!uf1tGS?w?4>;#Aq#yl?dh_y0(0Uo@* zn@?at6%UKRb!;#rrt(43J;H#PH-B$fHS=Nlk{qGQO3F@1wDip$+Hx%H{fi4Lfi>gL z^~;;k(sTY2@)H6bJ;HKHVy7iW85Z|unW&Rqa+W(@C{W|f%#5jm&2zz<8kZWArAK{H z_c2s-nYGWN$yeC8&%wysqQ;_d(&deMH2*XXz2W^+y4FJ0$gXPtT~DVoztL2<*(q1M zwH)D0?3FV@3}wW)2xc2_ADZ_5*tXFAG@yYYsxFs)w4)+Lc&*1mo}0^_B+{JQ(Wh`& z%(R29+ar*Zp_bI5p2iB5Dm!}?FCWRhlfEUAN$8Ux!Cjk%M9OqZiJ85}3(h8ONCi~T z<qI0^alm}L{+xzhw>WSfI{)0X%}S)<rn}L|qSBEyjP71}An(Qh`gKjiH5^>KN5KnG zpgYb?xY##2<1ilZ<Nb=w@<n{LsgMml*|PBzOi`;oHe!#~l0rHk)D@x$6zFwhyeTlU zm@JUsYX(elPG+*nf_G~NPu6XQys&)KGhK{U*O$F5dCu%gJF}00b!J#}`b!M#s)WIS zt7*8Jo~tKg9bQ+Iya}n3nZtcN9KX#tzG(37@#J@Hx0#wZl|Ll6_%n>(_-zJAN=i2j zge!aDGulZ?z=Pe_O4IA8bVae|O9PNwPqxmQv{MkE7Nig70T+P-{&oatMG=UM6I21x z2CY;K<}<hlDw|)-{Zv*^=T94Ll>7MG;~m%Ky&M8I^LDMp*#>KuwJ*@wp1)=B%C3ne z=iOB;RgKPO`B#5P-GIq`VW5DmV?t>{DS9Vd^$iI!b1wACiYg9WiB}}u(OeeDWzY}c zn!Z}?8hy%T_j^DA9@9-Ffupy2U#Ul8?0qW*Z|%a7cZ>@i{|1}ZhgcA-=VPxY|D!*6 zoR{uWZyFzeMt+`_racgx-Ja=qNwiH`ug#hN$ur|Glkq&)t)lAhC+Uv+9rz1Mn~r!F z_ey@*9as?lvKv<f+hIC(>N6H|s)~B2n&msIx*Rf+?OlW_t@;)GyGcHF{{(KaQr7LS zU~K77=buBfRbh@9raBoy)k{WSGFQ)2_wK^v)%i$MHUGGR2mwOZHtC84e(p~NXC>}& zvu0GG+0CI3eo!aqHO`UTZlvDNGw6}&VDaU-s%P=(<mdX+M}E%zRRjhcj{H-P;&OU5 zE12(wc<HEN<5EC-w|32kY5Gqb_u5=yL=WEaw?8AxS>YOXN7+p5A@5u^-}g}Zw`JRn z2==ZIj$vJ{*$J)A>Q5UwVBJxCOq$Kr?90vT2=VAUQVQjH?2G+fRvn2o3Y=EYGW|~s zcDPj<>0!R%mW*sm*Iweb6!WtX^Ak|4u!z8YKT)nh=v5EtQ6|3Ciy8X$-d8knUX<o1 zmVtloUc{BqE0&H$w!ISYrhk*h?@5~A1sy(ukMWY4ev*$XgpefRFzDfMe0;Vaj%xw8 z&(Thc@YcihN}z{F@j@%}E=KcmC;Q~Wa01?yQZ65nig*Fb1$9C)p5{-;SRmy2Z{sQr zI%ygazJjuTmJJo4zpwO3f7O$4^>KgoHb2SrQl&C)<=+d3paDd#fNVC-s0*r0=ilyL zkZ)U1e~K3}k=y@XZpBtRs&cMN`mk8CyjZdkut1~*=w&SG<psDq(V>a9Q?otF5g*|y za+aMZ6v7sy4Ezpy1l(-3R`3s)dH4!GM|&sUtMkoYUm%byu|(z#fEIpe@032qff|NE z4>2TmAoGU2c%jb$&x}r2qi8sbvL3k-nr4Y9$=j@>vG)Kz(58OLrn!2*p9?K4<b7JI zYuBsX*(0lxtVleiU=jH3Sg+FM1sMnSOsM0JF)xK|=#HPAT5D+t^+o%pjjheHn@f;8 z?Zec+<2DK0(+J9R_Zz7>>Fo&@OdjHxU9a^(>CEy6ooZ>Ta_MPlA2;u1pYfm*(?RsJ zCoSXQM!x3V7VztU;;9VxZmiVw_CW84Ab*t=e@(?|jErkIR=w-gZSB)Rk9|o1fd2(Y zXzpW0YBm5LFbDVF5Bv527+T7zvAjDOEvVu%*jUk<2Flr#ST$AlQ{|wYV)(#!ECFS> zA`7G}_2&~@>wSirZ@;)s3>Yr4ZmD^BQ!jdbcBtjf>szE`E@_)@crk~ADS=WNmGtf` zh^7yk_^@{3u2)OghvA2J-#zf{&5*WjYk1$}c(TWf9~TJViFBvPzR7z-E%9I1KfGvv z@bMW1#w}y#<%?=hs5p`Gy}IrVT++rv-R@EI@{1y^Gjk)4qJ#SqPm#>k3~swpon|zp zi@KriuNwnil-WON+nVV>-5I##9s8#ELNxaQht7`e#ld`4rP<>vYtM7P9K7Yw_4xb7 zRLhx<mt9nTeqr}!?j3M^+WG72>YKZ#UO(;n^OLNPF5!9h^xvP|uNxl^y@e+I2OtS- z3S1<FO+_o#vS~az`|~ZJC1IW}<PkETB6hlVK2_?%>U<h5m9W52+9EBa6KZM~GSu2u z7cz+hgvG4GlOc=QdMmYyIYvKL7q60#%1cahk<g`FE5*8{JUgAWrF<t#<>dl5kI?07 zUZ?Ap3w<uEEnoLdRbD9yEDT+_5mHmPQXJm4wsJFKU_a%KnGF3@8oyHasqE5^wNJMw zNR`!cx=7e+1w*lZwK7X*eYJ{dsj^mG;1RZVyXbWNT20A?^|d?YsVeKW)rDc}b+tA1 z>-7z7>+5$L2liAp8d@jAHtuz-)NkDH{IS0AfVHovZ0r*`v)MGLcz3gTL}z2OWz<r2 ztM#qNnXQLYr|)jH&0g5pYG<dae(qQ*JoEX{YR%oxk2l*kK0o0MsDA1EHhJbt*Y3*Q zFHise*!c1cK&f$9aM5s1H(IHI)5D{?$>{};s%`fPd4_NIiv>4q4@kvrZa>GRsqGBP zUk~3IBHU@%8CGlG+<8HKuJ(20@VoG@FZDh(e0^o~bMxzK5=#BssJZCbZ(~+U_r8tW z>27^{<8)L#)_hT{+5uP(ycau(b~kpIa83JHZE(sFegQaH^)L3lf4lnPd!eCdC*z&b zvvD8dKb~*|qFVL@0V9=DTW$H9LZ5Xf&v0L6E?hye9JDc|rlYD4NHI2QklHBFFh+3c z`*cLr89l>|2G~zMP9v<tA}hccoPi2I{mwSYOLi~}yWW*U>iF8FOJ<@t!vw^Kme<A* zpI!lDbeC)bFvk<aySjR=G}horvLK)j8#>`6lLD8uA}(^vj><xpyE93{aHniT#DuHE zIwg5ATOU%Lf5o8j&HXC<6&#BF3J-p9mrJY^L+@nZ!4=Gs1aAq7yn^qhx)A{(yL1>z zAam8v{>+5ntid>hH-ce?e}yKQfIC@22m8PTF$M}oc}8o5(cM+k_9Ey{CinxBP<7?T zdn<l?$wIj@0_K$nt)lMq5wmnyMVfXY0o;1|+2@$*&7V*w2DO8Udp%`FW`Zzk0e=?P zu>sAUrYu@VMFt0yVtdCadyjBOxE^NgC=MQ_dciWT@URYK?mkc8*^#giVi;FjU9}L2 z%uNtlBFTyaE7ttULOy}yRlWOaCU7|4E(y@X4O4}1Dv)><3<;$HC6V~oXp-79FVIj? zKIUqoxf0wIa~YDCn`|!2pF3z}#nqBq6fUo!B{rxm>zZyY9|-%&=w7l1WtOL;9|gvl zZDHUd&<X`JQwlt#Bo8krHVE^^<evTe`Mj=LiQ#OM;pVl)vfYt8Cb1oRy=eYi+(0Wz zHvN$m#=*IK<mLh*?bsmcH~$T)&yvESUruBLVlG@9xl_YWi7UPvvo(6^Xt$UxLkI_l zDc6zu!~ppQB7O&N1sT7=3}R?eyQI+n)<e6>ezZDVGqhUvjm$h=n^}aV2WqQ^TG3Qo zY3b&Q<bqo3OjF@ph?l&_wPRqGOyGf;+EktYkXK_mlFxkFsSy?IaY@tj<8vTbne;sZ z<r!?*ZQS78?(<rQ%{*KwI^|J;uDOlNDD#;6k~UBADBYi#3k?n1fqVDWh{RNyb>hfH zxnRQJB7GBgbj?3bFLI~_*OYYzaQicU?Y>C%Lbxiqk(_;Y54{vOGnJ|{Adz*sI#4_e zMB|ua1KvDKaZff*9Z`PE6Y3OQe=Td1KW%l;k5>bKa!Za}HsgN2uS$9)<f!4C2JcM8 zR&2+T$D}2i1@O@BDZ8nYmoh=`bva-+!pCry%%YVfOV1^rvY%+=F&Kql4w9@OuarRp zp?F*;QH4BMG5M{`Mx+o#Ywk~l@}MX})kW^cKMId730I51T(tngx{sw114Q8Sy{2LK zbf95A8@)Y{boF@uh0vC6p3sfsKiNEwMfwg*p-D!wWZuu}^hAU3qaQxcVCiZwFvbZc zjqZ6x9WCIclHk%z2!n(Ul=x!z0Xt^d#uwGR=UVD(0i45UpZshlP$W3`)koX-dH3QI z4j4fu?00-iKzz3<dWm)?>&L_bKh&?6G|5Vp_@gJiMoi;FRHE8z4&xQiJ=eE9&L3Od zEBW(G8XwG_c^RIJL-O7yiG^Dh2$+NV6LquGS+%zD3-YwmZ%Xt}?~cE%6nRh<U1r8} zH@0L^Dp2dW?g-u`k`)k}rZX7weV+sg@yA6e#z5xzb0+S+YT<jNLDnk<ABL$8b?+{y z!WvN;>)jX!y(;GX<1`0B`V0p+|DVeEvyDeE%H@qOAHxlqN$|yqFrbe#{Af6N6weKF zHs?v0$3Ci<={Y?<YfkdXeTFO-=Gse0@x94U!E&2N-zM}EEXg}wLHsd#qE-{Lr5pDX z?w@g&lhk{<V*fhvF#gPHc<9a8ei{ynk2s<Jl&|MJRo)PoMYD9D&M)0)$fhrHZW`VH zFqY70w1`bt1(7=`fST#RhmGm0cjWc;?=F0XcV9Gj=>BPZfc^zdPGLJ&1bcvd48*TC zWtKR_^WCoSz{?58*H6Cf4#{<$w;Y@ptnqnx&H(tFQ;{91HYoiydu^3<%GgB%ydrA; z@S8M4Y;m3EouK>!6|$=NQ%hD<xx)dLt}(fp^9=~BD3Ps=Cleh&qg(&|lD#LejodlQ z`mGII*4E#yImO((c?tjS`Q^Ru&m5VyRvkF)9}zELqc1#1Xn(YWuQ@){$r0zR7D7Vw z?eDj>|L6G&$2`pgo#&Hlvw-I&JQKKh|Mqz|6q>`~g)omV0i-Pjp><{iH1fzLIo|z3 zZFiMXH<1Tgfn@l~Lf8@r0D9XEJVB3#@+awPM#D9tHRHw2h~QZeDDnmGlyl|5{Iv;J zj#v4>oD<MRg3~bGYr){UPB3!Y@JF!fF*(PsXfTm@(O(F*a~t()zqUSqzD|z!Xop~x z94NY~N2`k1b?2L>@IqKT8hxnwDma`hfB;=%2%s|ue)bdoKF5zRkEsNs?~QVq)N)<> zn&cLNgf%5E?dkHz|KyTQ6O_>jhcHFpkx+yN*R4@Z3yz^Rm{ey<hfuCSHR6uX+ea+& zxii4eLUEr(RByjIwNH>FHu78~p8v68b9Xrf?PmlV+uuavC89+#zJ^0cq#YLT7RWc2 z@9IqiZP?I*6o_&WfOJMClQ18HDR43=%nC;=6kHF+)RcpFaM6{GIh#{Cn^s2EAYC(; z1kEK?axj%_%zeQ81QVHuqj-S;WQYvGWgHj?uZQZM8@2F&i9{rap}Nm~5(KJ6<L-Y| zVGHv@0BXy-#Ea}qh!YIa6a?SqmaOCZ5^;8m6czw6d~HbzuHuzb1O+_Ms{xl>_K0Av z2B--F&H&62L_nMZ+*i(ZUC%--#0lW9qAM_^q^m`^^qP<iES2fa?_UOTUC{#rIOq-# zh<5@XMsORVRWC>DS;w6UYSFpmtUa#>7FvR%q>xQ8(*ULNP7D0PB6Y5MKlQR~ibL>< z0Hvq-J~9Krsf?s<9r-}s?a?c6Y7}HNO|kJpn+~W*1cOKjM_=T13f5ig!f~OP-|u9i zkn!sCsOwJLWfaUak*meM1@RF2;W%b(BNyBc5fFhnC<cVEn292QjlRl-W26+S?O)Fj z=qlL%NZBX)^2O00Xe8pSLS%G4R&p&B${(V(CVE@Wa1p0xwkK*ZN({dRgeDORAdQeu zLJ;UST%7|i6~`D%=yAJ5Z;O`P0sW2RkOTdRM?$WZY+r*A5l_Scx-a<OjX16Ax61v| zXGrm7TB#H&uS04EWYpwzbgl@$3!(zM5W&03a*UNd4vR!I27_<)!D%p}ciZrNIZvt+ z@}eFSIxhjMfG9F=umpi+_Aw3zJ53_l56HBDTpFHSt#u%_KKKrJ8Ij9XM@)a%WP6{9 zLHbp}BEy^CE6>I2-F`2=cDq8y*+5QZpK;4NZB=nX_N1IU_;oT=gJbh_HAUbjUv>oF z_i}6xK}zA9_5%CZ2Pf>CM(%IQ{QLCC-8a19dyl1?%Q5v7E^8I=gn@o<om3TztAWjR zTpS1hN_aha+I^A1l;GC2^1_`2>3-gDed&UN7$^i=pGXm)W>{@wp%rG?zZE_m1+VDe zkx#GGX2U5?eCe&aSs7A+$ysG7yaC#%>mlHtAJ|O92D@g>=VBg~$6MD|Z-+3sB9X`I zFwc;TdiK4KT>k6B;kEVRa0$Qz2m0xQbRz0B&S=&%`I?0C_r`!H-jbnme1?kWf`250 zX{T<ugDlWm8?N-=ZKwk-FWBvpQsQyRP+r|{56W`259w#Ea<Cj6?*irSdw}QkC=>#~ zAfx$6YO{KII>}QzC`9^HT^zVau0NiLDQ1$`8B+Buu2NPVZ2KgpLjMja8mgi!@ZMRt z@IbW}xXf{w5(l1_$1YQNCH^S%41<Fl?sRM3nwpDm=2KUMs~0HP2@d8oh;+k&>dbt2 zHz31qgG4-lH}SGL;m!FETXVVZvl3xr<<^Eqa0sTD%~jc$WPDLdyZr&Q0*#nQU5V#P z&uq;xB$&_xqO@W@rN~5?)u6{p5KX)sq6eb;+&o5!|BNM)3?DDQPWW|#t&w#mns>4W zJJlFF3t%u~!2J&0(Kh;vNK7@zwXIvS=mowGcw}WLy>EJ>D@AQfAUa4q{Xa3I5<p?O z{+;4h8qGFh?@sKZc+Cv?DJ=5TtvH?ebY7*H+5-8`kV@3aT^kB6@7|q?j~w2YwMFb) z?c++|IlboC7Yr=5S>(*q9zUPu`p)YrU;~Bg6Z-1=?M~=CMkFgP%L(ir<+;U1K{XzI z{7pD7ulupwn0)=ft+@P@6@7QDxG8`Ks)6cCt_Y5@{4sM~J(xQet~Zn@vq;REtva$p z!GZ+7{c_Otp{m611~U+UkxQW4v`nKD2Dy#43~E>PU^1I^cYE9aIP2(Eo8<yLZ<&Em zNG0dE;yw8${4c~8U%pvDuj5YXW>bP^@?GdQFW3R1eOU<Vk*P4L-!{q5E%(V_?u(Q6 zm-ZsLKIwr(Uw8*A>X|R5_cXHCBRQi)>BhTQV5e0imDfYa5aK(4<Ue{|0H%%0J1qh% zYDeti^;U^t^~vD&Bao8+_=R(F1G5u0k6Bj%Z*<B;j>dPhcygIt5Z`!iJH_*<ECfX7 z%6EMpnr-DBK2O221_|H;MF^?kc*aKY=@W2$wDfP}LxBE#8sM1#c!-8)K8{uQ$btKV zHiWd+&GoJ=X9*~t2F)$+wyw*xRrnSM#$V!>5XX1G^%5w^JZrE;3JA0t=-f|i!WE-4 zzy*s}Kbo|E(nHtEOAX|Czq2rUqhS5O&_HBd3yW(X>dInp6GeJ{I7c_^k+^R8qLp8~ z{=@Eu5K#@m-L#939BHAwV%1Ic7479>kn%AEg!iZ?-_4&d1@cb*#<eWscu~e+3A3D| z)pBAyDCisPxiH_w23+r8LP&n#cc;n7yM3KzXNSh(V7XkJwAUL=)sP5Gp%>WB?!IuG zyIV~GSKYX!^-$EWN0er}8=Rqj2`r)1#Qas54+n>EeDl7%@9d1Zn|XT}caNsopvjdz z5dRitFa*FvwT<lJI}S_^rj542w=unz=%U7CtewKS+KA4ZA)qmMWi{JwGg>k)VUA>4 zWn?WV^8VC`Veg-0A%U|{{3UeLyFR}bRUPg>;%_0?1GhQV5B4}n{{*nURN;j<@P<^& zikN!?^uD2#4m<Jv<vu4Kl6t^2qaouWq>=ly-7QG)bKh~>i(h#=rZcKs*{M~yrE+ZL zzrd3`Vp^inTDs{nv&k2*xO)+GBOtfzCqHK+g`a(TYbUVGmbvw$(=65#&S>MWqaO*) z7Myb9BV4_(`EDWmUNcPtZeD&+tPCrI=Oea1SZwm&5YH1#pkACo<t0Nns7p?Rh<VH# zrMH&Nr;WMBK7E+kFamG+@+kjTqp~@2V8J-6`0U$qtoT5fwTpqATae8`P*(rFLg>_g z|75MUc|S83i^y-LH~flNIe_%kFS1cN>q&S-Ei4k_z2}fTQz{=*5b~*X&eLH5mWz#g zgK@_BIoHa<m-qyJFQDf6lfKF;>VpSHfrx{X)<3XyD3*?9rP)*Q-0S5HO5MCsS0OC; ztQ2r*ZU4A_G-a%C`ZtzwZm!#`c13-0ZOdf+5@y!-crn2D+i6xKiuZ@7js+J_>PcQ| ziG2P`06M>g&^QaDhAKm6q0ZxYOPvRE;sXl$4O_U@2#nv*6G%DoaRfKR1a%$cD)N~( zZ$3TTIHURM9R8IvGk-Hb^|bH1MQH)EIijijw}lxFmgl4FWd6xHUMO1zIKn~<k;)@J z$gNX8(aBNOPTXV!CfAAEB>pv*0R0Ye^XwkLm4ymL%yYTvD`;MReC*tEXA=5K?;~wl zy>mb)yD{O2-Lko6ip?!>TpWNJ$*JUk98O`8ALeJ6Tl#Tk{0H0}5;t)Gsb93=_}^!H zs9q<jcB8X(;2g-LMBX|px5hRbbKTa^Oeu2%b=5#~95}(6H0-G=@%?;*AJfar5blX% z987Ewg<JZ94Zq~wd%1_pU#)k2z5J{dRw1T*Zc%rq)wHMS6KnG66CmO#0(~fArcCa_ z0g=fqt|q5<!kS!IV{jaYx`G3LdUH2$`e2Y%1OJLuCbp0<hy3yr3gOw`dYbT^D!U@* zdf<1K)?EnuiE8aq$D7}>&`<b1gDH9>*Yg2Jy*T%0-oFBxn`97cBn{N!f^7v{+&g}J zZu!xzh21!NJf7&m0=Xwh{{Vgxn?yrkWz375=1o(v(k65<=Y_tsIl{@lBIiZR9BJc& zZlW$H%!H1tuX1w^0*?Xwk*9QV*OifMEEk+bPO+h!mka&xQf<aHk`^SQ%V0VE|Msgw zXo`gU`alKjA_DyS+>xRc?Sqk5Xk2q^4tiN;JauqC=7UfWMIQGgeA?eo-U|;7IL(AY z;t?Tf9vt5uiRZ$WC0<SDxhB%4HW)tX7yZ}NZw4tf&XD1Hi`mha-UmzoxnT&sAe(Pt zlc?heN=&G)3N3mM3UaYBCZ;C4l3*4`9i+O$F8t|HH}RY))`Vm{b05IYJ^nax&-Je) zn-lx_Lr~O36kkNZm*u-pq|TWvy3D}?9(o=)qOt}wK?gOxY_AcV?cZO`JH+}teo^&) z2mJAwgS1VR&*0GLkR1u*c{kXU`#5)~^g8Gd;A1Y0GfUBj<hRu>^!&0kqNx%1D~@^7 z$Ew~D@gdif-7u^pH9%I=^Om>Pha?x_#b>Mr;RYPRlS`q>hY#G!3Ns|!$x`m)4^pkA zAh@9Fru-Jwns!&Awu6>&3z3>n8;!&XA`^Y|eBAG;&f9H(Tix<Yy`M`~y%$FOFt(q5 zC)#$?<`Ql9aFOFnEzU;|+^#E$>e)_Dp&3XKWMYORH(&7M5$@$fBfnD1#d(X*^|)Hy zOlEqzDc>$|I{w$O-PRlfTs<B(Z;msWLIVZI(t@mdV@8~v2cHPUs8Yg_21LryYSmA! z{tx<fj$fbR^0h@0jR&QZ8%8FbbNk3~I26|)4iJNLDam~O@A!IwEBf(L{>2wv5e?2K zC0Fz9qsIC@ZU5FPIO_aT(2-Z>GtL<d`<&=;V}ANQbN-m}*se4G8|$M!GzqZ~h!9%h zQ%Rx0)3&!KVIk!ZI2;#Q_y(D%Kxy=P%6#heRCbVW+Q>QVXxV|6@#RlS1XsD`h24;4 zLSx4^_CoGHXd9Kz<r~jKsJZlfl8kOtY)hdE5C~e9kIWFh%}G99Spb}>@ccu`^sl=1 zJ5qPtYO1caJ$ejJjA-uq)p`hs;QiQQhK2g}9JmGr@*_>OTs80y-v%tNP<<bk7<M7T zEIg<=JUA?s=T~5PlG!a6>1RiVYFIUU#j1wegk<Sgp+%e0ma-yKJGi7N=Q~ov$p=Jk zo|~Tk@c8zw+<KNRQ6F)1rArR+?lo*Mh-U&Nv0QL_^+UoRjFy=)5U?4>jis90P?U@; z@VxaU(TP7~`!8%{7JAMfT=Uwv;x;@>a>E^PACVP+ZYQgTRS4}$F}3eR90v|U4ik8) z_e6fW^lzwz;G>uUm#@?bo?C(PMT(uHn?UEdUo7&nkE!5Q#K(FA<15bM1G!+%?_--k zJ=)mf7|cC!Ra!sYC({IzUQiZRpdk1XW*>Ol(VhP^u9hxPZE+popjBdrg+S0j1W}T4 zC{?a*BmN*zH|2OG-i@qTynF=d2U~}hbCW@NHG}%9Sb2B-VXpv%yy6it*dr_MoWAq$ zI$#Lye`JW*Y<^km_!IQPRiKEYTmR_2INDD_=2){qA<-1bpz?UkRtna9d*w&D!*`wm zFI3q1sO~8@G!6&$*TTvUF1Kh?NjOsJ@gkydzMYzpte35j74EYi#=hM0M#EmD*Fji$ zbL1+gcy@b5cWfaioLB*c_>#7{cCcCZ>`Nx=yn)MN6uyXHwL2PS@&~CI^}tRkt-@ZC zSA$!|qFeMXj|E_W@7XVzF|aAC6M>CjTrDi&a~9!DUyxPH36#mb#QqPTi=3MacCbN! z_lHy>^YkqAqP#oLb6<&D-u^K);uSgeFfa$8Y}UN%MruPF$3K=_4f)28R*g9P_?9KY zH=cmzL25AlI`S;-wYftYAG=?zgGn#?(hM*=9R+SVcN_ekFO?A;sVs`bJTXl_PqE1M zEi`@kEB!~rwXT-DWueND6G<V_sl15?Ba^aiR(jH>`Y(kwWn~ZU>0@^80VRTx)ElaS zqJl+sa2y(T3_>0>7jqs>#U09{pMDvYQG)4f{R-<h2FJ3zIfs(!|5>F(%-jt7th4_p z8ytj@oqR+ZY%j#{=&V>n;njJ9zk#Dh2v-|w2%pY`0$Td&MgDc+YC%sdpcaOA-8}bG zF5~d|#H5yo>ahbjyPjK#o?p$v8v~>bZV!bDWPlsPqKZGcHp#^rAZ>2)8LIGgz)Q(4 zbh#G3#FP`1c-ttN?Wy?hWj2{8<(HjB6F%2VjMwfUZbeP?O)WKA`LE8=O6H~2TRG{c zXh&4UAZMXe*c&K#s@cm_$g2OHlZ{$H>MB;a<_()vv&TuLb(;2>pJaGcs0kxp=$iFn zfn$gsXgHuK-CYt@%_|F~bp(V5HT5a{xOwwGsQQQmgh+nHIi0R%YN%1uV)-r5KemX8 zz>1*DVL(WH2W%vva7edA7Zix0)aKtD4i0MJqP^|Wfz%wVl+)zeN}^d_9^57sRfM{5 z*MMnt&F9}yc{6e5&5#I`q^-JObV>3Z=sbnwcC>V4T%N1#7gruC3X}RO5uX^)zv0$& z4WLl@n&Weu<~6d7M#ra|thLWgXz<2_TjJ1Ol=AZ}i)Zpv;J#>*@hhoo2Lxy$h|m+x z$h?s#IeHy5^c74R??^?5P2RX4XV<E~yvLh>1FmcPvUFt?B$a%T+-ffbIqc7#o8g3L z3jL|j<?yQacZJi?`+{@7o7-n+mt@Aa(x2FYk=zoA@h1A_R*fv2lUz9QIXeFoIaDgC zhsSirJ_nHbN@J#iu2>Q(h<wsswHFHs(H=8~@|Hx$N>{lvOr~XHvx|D^sZtC$4X0Zh zAgwsg)|IDR(3)|3$MVrdC&_B0{olJ4>)Ai**y-1C%SR@+7RcllD7*H(RCe9zn4yad zMGhUfeI%jRvt;3sqZjQ<YMiw4XGDYk)M*~ebj9iKISJ!;JYBX~iE!3;fX1*gyM4vV zYHoXw3ilIeeAQ+-%t`GP*z4!39Q?Ct?U*6=@Eq?WG(}D=l8;QR60uA8`ljk+W%SbJ z+&7+I)(|^%Po<^G#w&yRHYr!B`<rzTlEJb-89#Y8pp0H?@yX3Ez3oZDU}|tmsIzDq z5L1XNyrpT@(YcFG=XaLT3`GfYrAO<bqUz+%Hk%ComWY&NB$gX<o-i(i8qsPWr!tUo zgY*X#h!1)xRe$I;PAM0ASxMcnT3Lok2+|Wx2SV;qow~neus%m%E->&l+o|yNx|n!l z&FMDUD(hBM8Y>=}?AtXyns%P8!2`!!7t<>iM_=-4zb-~MA!c~0FxZmH$|FQ-JWgwu zo|KFTEh7IR+}@KE>aCs9nVUy2llL7XDVu1@S<dY=6(hAoSzd0QWHYoc8g+sBP#2ya zO+-bo((ITw6?rJ<Sg0uG!5jvX&<O92y!k30SBfzk`Fh8-@v4qhGr&PKbEg8F!$%Sg zfA!=_{mssuN}cTPedNS67!gXSEtZ?T$@D6zr&u&-J{jVo@S}l*kTin1IUSvT!3lMV z^%T%c<*GB!X@s5TrqI{ggUlHoVqCtz;HHh)RutOx`GIbtYLFP?6NB5ASU{zuHVv67 zCW;Z3gig}yguzb#42m5Eb&d6WCxqvof7*Jcs^)LzHzFe*hZ4=ev^{~_f={D)0JBE= z-eYC`3?puALgl9K(MJrCxR}haMl)lnwC^qD)w!rq(xF*zeVP>jr%*%yWWs2HF@Jg_ z<F1;Uczn@w>2WBeL!&3u%4Cxf(ks9|V=?tr>5K&0R*&((%O*Q3!?CESqbSoHvQI|j zJc=)TJD$eXTWKSO3Yt|<Aj0^V*4>#D@@U%enfzV=B?ISyx!jOxEstlVS>p^*%w$PM zs#PZ|+Y4sJXrpyp|D$CTD9NR!k;2+R5Le}><+}9+T(_9mptVfd8)DLCOapvX*k(F~ zUi*Uzbhq@JrR5KAV;beqA|wd55$|0)@VBn7Vx+hGtuZxTS8G)6g*kffNG*&CCi{sY zeXI!maEGga7Q$NSu@!h)98J=1-MWz#$-tX5rZ#FE+6yJ3ttfAJC`m$sbKA%OUv&PO z?%8<!`TS%l9K#2^KHY~F9l4>;%&u{I6>WFKBA#C-ba=T0^T41W?lAAGa1m;`gXVaO zC>iy^?NESh$y8+ed5%1F)r5ggTi+~w%?-@{wa&uPSIV)jIJhlK=3A4UO|-gg`4Q?A z>tE6Ew`L@6se;NxAws1)iRj}6*eq*#aoMyjlB4sQ*(}!>AcoU;uM;2N$zzN@slrG^ zTNZ9h8iHsmAx20ax*N}M8x({{x6zoo7UgiSBCGEUqkEY7rVBXhWMH3MLi+B~C+Cqd zUJtcD$Ot}8rRt>uMdrN8K!AL^vLDJgP&1oF3vC=56~{y~Q5D1Ek=qRCB12PB(We(8 zhAlXL=mWdea-UVY+iun2i3ZnldSZtY;h4KGP(>R|ZR?Ol_Q{q#?gB_p62YF6uIj}% z#HHK^1@yCGIn{|cI(n4C1>$&*0eQ-lL|L>thH`)e@oZ%I@svi6qE4YHQY?EaC>~zQ zXyc|F6JssMj717EPK?68ymuV*hJ}pg?EFnV^7h_7J(vLUxh;~$m&7f%+qNVCGzg%H zH5Cnq4s54hz+w5kJp4-<xFV<k39`o@;!%_?uKXQ&q1L64AEu9^o{Q~_XWq>Tx%W=M zl@7e54${3@d2vAv+Ea>GzUSmxrJbKL5a#E@g<Eq!=Ay2;s&pMH?ox=El7Nc=`{BlK z9_D(%_|Q7j^9^OHdMX+U`Qm!ZWeA~9M629B#wkWrDvP=k)ep6n-&*UWGLUv0)1s7y z{47EKW4a+72s7Wu7Ck6q9^f*1>YIQgihwqDzq*feCfMKmriPZ(%pgWEt}RWp`<b7U zPCk!FbMHqVVPVT6d(+|#+f(vy4&4~At$8`2mdSj7ZF6dODkqV}e?u4@EWj{A1OI8D zE7e7Z(R6FH7rU6J#lK;Xm*AypN8zPVBhaXtd&exGhmkmOvKeqlMP^_kZ4C<~?LOzU zd^oC~77z02>(Nl?W7OT$^IoWeEVP8i#B!&&&8oVe^{KNr-|4M!A1+GeO6Uw_h!tF` zh^b9G3BoS}h5_K!FpZBb23~*|^eh3@-Ic>6q=iV?MEnwokYikXle*o1Y#6*6=u17I zhbC&;4me{B^=Jx!PyBvt`yJi#Pn>FXL{?JI1cJ&0P<sht2@0j60{pRn%w;rihK;gj zrzJ|8&f3_c2`3}1K1?$9e+Mnd=!@vMHMDwSweDS<uYijYLp`KaVNz_Cjyg0T@Q<LA zO67YUgxDKj&i}6x8}3FwNtWHq5HsPwk;^GK)I=B^Rd3hN*~AL-uPN?qAP&ed5`nZ> z(#eLX2i3-Yi$UxSKn5K`-1$~XWntsv!DQdG3zW1dg0RRmK8E-NBZj`Rnks*mp~;}@ zvar$a&fLm$TKs!YffNU^6tDOc9}$L^o|-#}>xWZqpi4b{uw1mL-dR1xmE)t*4SPeg zS&)KzF#>*#n^j%P6Ek6)Gkxe*HQvivbec~NzwA?_S#sUZn<_SZp1|H<(Uq772r{j7 zpdD$8Gsa?~oXS4gq1{YM<iyIIdeJT=Fwy>e?R=(_Hrj9g5S1;qlSuD<ne7#yz1N4y z4AY#UuByM&WVnT-cy{yO0S&Y-3z!j-=Oh^>%#=(Izt+)}!V7EXB+wB+nFI5KcJE5> zqqSQW4MXTjniF6-niki%vL1p84u1=002plRCuua<F1;=xkQ$$sxVlC|FP`TW)@OUi zuv24o7<P>1L&hVRp+TSnA<~Z~m{3LZAX&s@k$4D|Nq?IMw`ml0yj0*N=KN<AOD%${ z>z)4fI8@I%kP%@oyuIKDL8<?KV<OEEQv3v1@zJmV1~^IO9Ig1AbIw4d#`!scSW_+Y z8elGM!$n`zpIoDCCa>cC^=<$i)Al>5k!=zO-Gx#JO*%w6z{%KS3ugY@!de0^%_xXg zUO+eEgs8(ke>RttUUF|G;$%F6c&$#Cn4BcWP-3<Nl;L65enWnSHw)n&Uw+5{Ylri6 z(tm%=gC{Zxeby4a*}Fc~#IT@*oZmnoO1?-NSW)$k+?GMdu!CPr`K4hfYMTJY_@!j@ zgYycE`W%LZ6k{I_4i!fGqthw|inom!H0s?L&WGf|5J`S1Jr#FM9h@4H?C6B`gA`JM z2aZf-8z$Br7`?p;f9aay1<n{`Ba*l%r$F>y7Tmc5E}(h<)MU&RCzC-5fAKTolHq>p z4CU91xx}L@5MLh)NAKnOhny5%CWR(F1?UCuMT&7=5W;>aqi+bI^R@v%7hOn^$=cP- z<f6oPBun6+Q};Q5)AL7a5mV_~0dSs+7oS*AQZ#E}GbGvE6<*)&tF%VAcYKPI9>T7i zUOKhRmXp|$NcoRgI!RTeHqt9PHa1-d-!jiofd+us8!ap-aU<m&KfF2M%P)#SF(>S< zb8ccS$~z+bay<VvOk|PDAeA{9?E!47yM3I}Q8r^Js-1;f0f*{`ycP@i#u%}B`_~7W zDjPbsZV}HEjopT3m(wKLyT!Y5lD={?bT$Aq!V!3?d!t1fWmXl+XsWHbso&uB>+HK+ z?0*+wOM>V~o-e~$`I9$Ncx+Vm{@EYGwo55SO7I%F6y9iyG5q<oYyIEliWuL#(+9i& zV$IhoBsv&dB!V^#Vn|*T4Rw}^WB$nTbxg6kF=rh|1FyzjR*%05=RdwO;Y(AxsCo8q zEIU*9Uy0oOo0~PPeX`b&8lU2-d!Rz@77&k3_;haW;8^8+{yW)s8dlqGVB1!6TZdhE zikH-eG2)jv<Kd_L)~l&cgVK6ZYsF}kYU5zn+0wb%$ETzn(T&-0Bn;B%LiTEfD#!OA zzg%;Zh~UAcOm>KXa`K3FtTs20dZkJzCN2$!Fj|A>J22e&3+yQ=p2b?VaFbHZs7yk3 z-obbDIKE%9Nh;KXb%VF}T$s0>GEp<H3bzPw?@FGqa@6HPL;wqQ?s<Jvf_T2t7NAGz zIJwos6e{GSC=qEzM;LIFBaIO)`UiQQc`>CnEztMR+}QZFtT1a|8W4f-E;{{dx0uR+ z+gR;zWElERh%E@ixe5xZg>Z1D$<@#jE^r;E=nk<_h>30Vpg2NajaX~H$XB9Pizupv z?#K@psCX9kRcWy90@0~W4WVE6{nrL@J4=|)?2a<iv^l!2gS7L_@6bk-^ux;gyQ|%G z`R(d}_C-i#x2n>2)u~2*$2Kjc*STa290FeY9kXd4yFOaMU4CDhjE3+|h3~7*_2Q1s zC$^+*l$Y(PGV0TlH+D6KAMe^^XgzNRyWLvN$(ManeTgUU9kvLxiO3PB-8V|Fw2Hxz z(+i<E?m!n`${3^!oRy+5Z#WjpUpQE%dHRMI{Ma$sJ|$8yP?zQU;M|9mnT?4Fg!bGC znYu&M&jl4kaV18yzmJ!>8V?)(+TA(x^lNGaWtz4!|04L)EomdqF0;{n6KgdIz^qPC zPa^Ro3t;E%Vvf&pymq0%hMF)Ssv#7E(1LjB97s2`_Z?+isEFYvUuKNE0Ug(B1!eJx z{utHUgCPUr9U;}j%8mT;RSu>|lGLGYI7>Vni>KQjfQ&Y$laqJnGt6tU%$KrGJvtl+ z?6nBHGL=shC!BWpTk+_${gE}-tNG}<p*$b>uji*7kDRcwy@)JLRw{p&RK-WWgb!hp zuRy1%fIy5B2!$t%cEd0euD41z8s3P@V))<K1IdW#AU#B>mw=&yawWGs;!zJ*q=tlk z7;s%IhD))kL?F<#DJSKw61om5N0vu`)<UjQef)(DCC$qOxv^rws9^*pmwaJRV6pW> z-p~AY>vWqk6V8Zte$9XP@^kdJimP}H*Qy0STQ9zq!;nAlFFBCM%tK_lAXoY)0f<l* z`$nu{0g22d#)z<qdZ|2V`0=j*O9Y-o0;Ru&1l(bro;x<KNQMK};suv_Z0z=`BlOkr z2yHp60>o<OEe?tJv*UH>nmkjb&Z{RCgp@Zg#Xv#?G#yWsSu*l+V)$8#)>=sqy#xbJ z<e9K@?!*E=?k#=vT@!9~IB`79n`tt~dcn)`LX5tc4x8x`JcXdzOY8gJ>f_jaYz>;N z+2OGQ(GDMs=brzq@pd_U&m?bH`5q%MoON#?ee}^p)8Mac$o|7qBfS5T{7PmOeM|}w zJ9cNi=>>1$Q#?w+(cn#Mr5!o`r3~dt-ig?3?Pro#K_Gnj-*(oQ-5e%VNUuE4WH#H( zVRmvXnwge(fbWKs=T;I^iChmo+dgR{8XjKnrHR5vcY24fzqO9WDDHi07s$Wo91hJ4 z_jcpHo5Y9rmt}~xxw8<OOb@cM=f4Xyz84`jeh|T%n(Mi;dw&BpThZ<r67lVSaaJ-k zGr>M6iF#Cc1P5CA0b&)|aRo5xsIh`_bQHo^9xiiL5bvm%4<_|h$v@5bpjs^qI4*tR zsnqkobdH+t3fdZoIC}sFk^H!HjzBAA>=0Z7LkL7N23*;O1I|yTZeSgMM`c?t(Rky1 zGI3vvj#}%)wrh*PeJ&ji=s*htfE^!z&;pc}G;-qlpR2M7*T~)s0W=RAp(NIGun~WC zJ9b6dTiFWY&*}xjdo@>BnT8Q)t7|1p9A6`eyt|#fC%E&8AN{_BMM%p~s)rtj*Y&F! zcuL>;V48`*r>M{iFqzCsVZ_ia;uYOYnoyNkKEdj+XK4HRzZw_n7OG>vA;`DCJ6oW~ zhK<_dz>8x2=SD-Sbgn2_!v?n!mYiKLL&3UK{RW%>g#|WN@P)I?q%t!2q&;PGc=}xx zMhu6@wmV3*82I&X3kZ4NZ)!^Yrb5v9_whgY)0bn;6)QnPH@zTo<hMQiz9FkWAE#?q zzfBhCtWC3f;`XH2dQj?Xa|QWr0@i4HTLOOL-F5@Yp(u}Fc!?}T=4s@nT{646Sg|M( zQ%MnI2S~|n6zVlUe@kZw<EJTn5Wn_^?@4<afS1ccR<U!YQ{#DqJ=d3i(c>!V<*(zV zlZrR|H9cw~mGEIwo0k-kIpB1z%nzqK24|eF#`~a~3MX<5=DM@#RxUCpf6ZSiPXyuE za&lf4Q+GNt=ZN}*-bFO&CzK6OX5W_H+EwxI@?a`7E+yZSV_0;>GWaq~g*NZH|2J~@ zW->fZUts8cE@kS)PvPD||DtS-Lz4FyD=+R$cLkGc_<_Sb=FB)A(l(TIb>W_8Y3vh; z!%uCeXkz&DXYgnpD6?&A6Px<a+$$Lk<&#vYe|WXdkNgcxc2YbD7*z)tOyM<PR~#GU ziD;9Un|Uh8aN&15*DQwV;~QDBkM^bx52?vVJr)geJ-hxj#LVF+vxML2X_bIHS!L{D ziRR024*OjDB;j2wlHC+9U;lv}y2$)MQAbvMV!w)^*fcGjSogYjqb$#<fDs_Q>4i#> zWYB>K0H5`J8Rh=T);8j_TaYZy+lOjrr<M)g(>n!2_@^)b_UGEQvB<ujRTGnCCeui; z((7^dn)qcu^bPvFkbB4LqL^@3j{2bXw{EYRdACsrH?&~L-~d-6Jq7*8OJ6>9SzruN zr*`Zp|MH(Sz^4Njg%dhqS;%$f;Zflx<{%^VHdlV$LE7nN`~T4B4Cja%<+dHO@?cNo z^@voVXWCW=4fxMGUd?z8k=#o&@%<)vezC6kf;>aJE$#X98bjb^W7-!rs|VOfL!a4l z%Y5v@5>OKG>>UPL$8Aah#DEBh6RDOv3MNKTo7l0;zsUcNO{ZLFe9VM}3z~{1Z$8Gk zFHSPOFV&d6t$&#qgf1VB0rgbx2pK>ne6GZ0zP^+rTtw6$`;s>kTh@vZ)HHpSSJ8_F za+4M{M-3j1e~zhfl~|B8c$>0tEzY-U=!Z0mwYK`<6}xd?e7j4Y$}>fC6s5>_Cip%a z2a=7Fah-x=aeKrwbUS8KyA@0d+L*C0OqdE@w~!uY-Ei3#u@g`QL;TQ`pwna41FUx% z*<BBhvnzNyJK({4==rqFAR6xd+=aJ8Euk~1`cCrVahq8_OJ|IJd=hFte#h*pQW$~t z6x|dSIg-SrDw!vsA-`KYv#@7pdvQ&-JA(dI2%dSwqjOnTP@Urh+N#+b_*^ncFW%0O zc-<p>8*CsS{P`sGimY(aZXfRc38r_v+mADOD8tQ14`(X6&;9i?AWJ=&qm7u!9O>?2 z1zwYV^s%;NvbYgZhi6Qc79I(KF%iQCt!4q`eOeq-0G#&4<Qx>Di%OY$mcq5ZmkySu z<9#t?pB|+wsA?8F>#d!2IdoUqd}PQ$HJtYozi&H)J-M2k&pciZPnojw?yI<-IPa|0 zXBM~0Mm*dT<ZZ@$;rFTiH4|Vo3z?E(JFy@<06<^~re@Vld0fVu^GF>y`=Ri{wuhQE z{?jG5!Tlaq!-3#}Zu|%|OYM5Y2(DNt8K;&`kSdlWyd<#7@f{N6KK5oS7nx!Dx5EKg z^${#iKSbxko5*@u`CTkEzg=ga=)92CF^vU%+$sj;FIZNm_ybF><iPo-{C%*TjI;dk zuG@48Zx0lba%9(jSO0+IaK;TUx^)O0zsqB$2LJK$s5&wEES&To>0Mq)kE$5-Ad(`F z_K1GuMds<T;x`wy>rrQzs#wV=Nj#VLN#S$gw%>+64fkf%&Vyw)$pv!dgS|5;0oR@O zU^WH931Tel)JdvXAJ0Sob}0v-voLL>kQ~yl2F(+?P%b)h;+;Glo#A^(gzo(kxm02L z(g)M{5P!1-Y6*vFfoby9-JhJ{hh^x9r>5HVFI9_#@Kb(xnw+u7Q3d&8f%=#BNFHhH z-XBiWMy<!m9ik?$<c)hq$@>L5C*TVNDA492o70T!*b_ztWV;eFNq|GVCR$4+zm+{Q z;%~mbP+R0BIWnc>+aq|wK_llmX%=cF09T2jDgKYWH~)t^jQ_nqvoK@E@-Z0O(2RBL z`%cY_ecww`&DcT|l7uuEj3tI7gvOFBgeXa}Zy`x&)6havO+{&S+>iU5^ZnlU<2>$j zpP$Yz=U@1I9@pc#uGjT`J)dzYPS_!br72t@)J}Imlnzx76nEc`FmUn)x&}=OmrB=Q zZ$c#=i$1zbcp32im9h-nKX%-8ZqkysHnz)ml?RZF*$M95Jx0Ely|<lV95)=8E_(pO z02`((VkR`~hLjgEa_RO>971V_cg|2Ip%9)evGSv@CfLI^9%rct2V~yX^!dP~hUDgB zZ1vt;y|(;F=|r9h@mOErOyr4o%(>LP#8(gdtG)cJDIl;Y20yg%{PdE5cP-<O25X>W zmK?*`!ySa5OP%4F90m?hs6#hrgqrKw(L?rS=JF247dH}xDeN?8#IYy^QFRV%|1OL* zFnFVN!L`vdCJZ#?>>pbziZfk1@CR<pt~hP(2gDE{i%VpxrI|wDnB6t<8_VYexJRk` z;TQGx97{9)pe{QYIdLFL=kgQ_exk+RP;!Up(29RNnXHH(*vq}<n@RNhW3T8$G1|Vm zVJtO2_DUw=;rH-0v$=8FVQ1!U>y>LeP+}EOxbm_m^@<eS6e$=xJzd^cPwpEersqWX zr9=+YU}QqOi0|#auC8yC@#w;Q*(!m5GS7Jh50JvxtU;ri+IYz!k200&6YFl&paIFg zQU^dDi3x4IkX8sceX&1D(~ZkYHRHk@hF}%3j+z@d3Tf%4{#AB7I#P-eHzg?hVnDUn zM>}U+bR*?tWY|0-s}?$;&+g9~&dtTZS-e0Q@5{?H_A?2~5Y_9FQG*`*eoIX%l*qvZ zsfVGZu<w(NU$!$$dHceo7&Qeuc1jiSqwm8G&pO=DoYBxvQ|w75$0VyKmffCpxe3ks z8k&-(nQKDwJ+nBfhHV<k8otUu25uZ7H@!EjSsxlf+(%BI`jad*d02y&WIk5c*9Vd4 z%T;76T45WuX;ZzLU<zhH89rcPWjh)?)l<P|2Gp!~SekYWn#S0cd{UoXhkHcAE<=H% zts%1$wra!2fk_#1cu_`dHjfgcSpt5n<7)n{%Y8B&;`|uzlX6Jca>+X4o{V~PQ?_4I zk!qX9%O$H}7h=E0Tk=f4@mR=9(~<JTN$p6*lMN6l%uv$S#%Y`{dC^0Sk)i|1*uxxR zeOiB2VO1&&pLTI}>f3qrcI2Yz(EHU-LrND~{_+4_N{n+)7mPY!S*4mj+Icd#p*^@0 zK*#D6ZOi+b3^dltlbZW>K$9#nps_tmPR!*h-PlM*-BtZuA2*oJkeZ9V{>@={%*lT| zTCwR!-b*+|XY;t_<_W+_<nRP%{>9r3D*2@UgIOXUxpmCaOAB_V`D?IPz{CxcEas^q zs|KRxzbg0v%n35b@<5l8<4??+&S`z??4SQmhJ!=XFQI#^EXB2<nu*o0^Fm#3$h_Bw z_Sgg<@=zv`Dil8+w>0hn+=-sAmW|D-_x=pX>%)j;PJ}r!8UDZy-nf{nDZ5!a2{P_m ziKC?R%$cL0{0_X!JZ109XJP5l?P6Ba&(Fen2Pq+`=mfMR58x;~#D5#2SIW!%#C`kA z>EAY)tUb7L5KcAx@<(Q=3-`sf6|&X-r4-Ph`02=8xB5Qxp=rwZFsJQyPq2pmpz<Ww zx``@rhU;iGfDbuBo`I8NQY2P&6w#9v`@bgs8LxHze8<1tdGQlDCc3MJj6>>b7<(@G zdv?6hrvE!xwut#NC%lIrCix`g$JrL;)#%WFWtwN~V;R2av{IQLUzacpsTl|vpFD=O z3ShS1?(qWPgZPIw5r$v*vp#DP7;5H2zL;-``cfiSKK+f?JBt&X+YhNMQ#HBFNDG0< z+|iQp+0h`6S$>;EsXI;mmU32`Q##c4r3DTsa*~_>U^S`eUWw192M{xdqbYmfd`6q6 z@xym#JrCHm!4}4wY8@;PS%l*{tWwHy6#Ts5mlkl;al3)s2T`wqQY>StWtA+i4oR)H zDa<(;-_>`0k!CVysUXWZcTLLWIZw}|HQ7yvJc)JYq*^~5)k<_*UMByU%Q=zWs*yjf z!hr^}a=}-$Z#<no#y9QF^-&2^K>XI}xm*Q{$^$%|waDpzQdVD<BgV8_-tAW-&mEPS z<h?l1f;otmi>Jiqzae*(9X!t?BXbPErScAMl6y`o?u5~fW|%pt5xYl?dj_==zLwK> z1_OzdU5CVzXVs=!F4{QW6n`>M3_0f130rvRhh=DXY~15L8Tf4|s(aApezm3^Ey6Q{ zw6`RIu5I-YlN-ffE1aLl%P$clD+j!PgoDcFcs=;kxocwu5_u`2yI9c_RVGxdGy3EY zxVv<b$BUS_3?q*~%SwRW|I^;B&Ou)l8X^rhD^z`K<*)sMqDO_QdUZ-JqE4f=+G=db z8w7nV#Kop)qpP=jjvSPhu}mmF?65ZPq1^1FXFM!5v}tN+@`}&$?v2Q!&d0DZYD8N} zJEJif9kmYVI1fn%r%XAXQbz0Yu^PWCH>3pBMJ)^(Kkmx2<b4wBpwF>1f3dUu1PNtT z41_xzZQeYE81;jSSm~J$Xfq*~{=|9sJtc=zG>0ne7j0!Z(Xu~`iw<O1M5g9`_{wBe zYNR;qUvgIXH=tiRpp1jY9{9RiGolP;NEH6`@qsCGQqPGqdS~*_9&IsTwp_Iw!Sl0= z?rzq`8ICq7?VUT5_7G9vYIXiYyU<blS!TZi>todd!zBEmt1a_(R3tOc^t!l}G#@G9 zrd;}GpHf7Qe$BuS8L0G->q5KXKh+G$A$~_`D~*tp8@Ib1=5j1%=k2?af5k;7PU*CZ zq|Lto6fUK{TIrAi$-rjneY(LsXsfo(bxh%t4j`ks1Im8TTay$m?Va(CRfdJN|5kE> z)=3RxTzroR!y>W)&g!SL2H7|CK-@P?2JHBg__0EYddK$pn>w`fP;6OpGhAxz<6V1x z4f1x1fx4LiXV`fJinwSpvSV!G6oSt8HDXxy6dN3vO_rh#85hC=o?p-l>TG78+<Jx@ z9EREiep<d{?l|_U{jM$0b;6$6J@b3pgnG@_DUa-S>wxWQ_CPjrm|tx!rC3d?qkc{? zF}+TFNT(@9LF=3|YtX|<Z1nel4)@TBE9b7?@Fy3;jO;8FAMiYtfD1?%oZATx4wyPt z_`6l0%|UEPF$VWUUHHX;gNM6J48p67#~dkdAbA(RUAyvkb8%;Z?w2$dHqkBd^U<-p zU+i8<avpHZT61Oy<Sw>)jv!0${mNDNnd0~_8<gj-PO7U@w5~YUy-(Oc096un1LEw{ zt>}4PK&Inf#Lv;IP0zMvhTfmys?_7KASL>&;ml6&M&6(a9j3e(pzsTtT|X|>BeJ^C z{CRY5)5TrriK)vd0OIw=)bGFA<NCJwAFNv2Np@r{P?*FtHBco19yKT>uPzqNGDC=9 zQ)ry;Z=Ef!6Fk@DUS)ck=agbiQR`tK7Uy2;b*CW6@v;_eq|oGIu=C}O5wSo8LSJgS zvg<QZ)54HPfSn&vUz}R*UMCd5(+3-W$Oamqaq-=kcGMoF@@P!ajIU$KY1Nal-gk?d zpOx`6|8$6RTAF2WQL)GGUOsvB{&@)EU6&wkZyKLy71~V`clT5Z!8UeGbL}1p^<K0C z;p%5PuCH<UmwD;ug#(ajyNI>-bA25(w9$9*(VjrqD0J+S(e&$q`1WLk_}(&O=Tol- zc)E1@D!U7YE5#2he>!6s&-1|AHFQL1fAh2c<B2jr!GLcI<*X^wFfri=rr{u(6LP3O zkMB{>!u_k~&sSyj^O2wsS&vnn9k7tuzQO)kg;#*~DOR#Ee#q-7dxaldLcRPwf%ovT zCmI;;P4+LKLHmX-elZRgzI8bKn{_X9<m>}$@q0UbeHTKx-H%3BX6-er&cywGGzO3& z`!mz#LnlUcQK&CX^3|T#u=}Ji3Ut@{jajX`n1bv0bKN=_11Vvf9#aNS{nSV>URGZn zqjYAq%h1Hhp>iWBC+&h|NJ9`o<x64CJs>RqD@a7E)=K(O`fFzFvr`_G<}1NPN*S{? zbB|rg-s4%3(|5GIR?7T{ylKx=>c*uFe%9pJ`qP34Sl6HrYTgcHMY;*nomnFKaKK<8 zK%>BY5~y$_=0&-*3m@d5_(;z}+nnF;KJuyd(bHO{4BJ;X?1>Bsg%0J4nCUleg^vFH zsjP#T(m@PmI4IkVGKpm8G1OI%&F<zqlM9@bBB_jv`Pu?~rLsb~J}cN)(VWVNXF8`> zdM5}Om1;~R_2$V%`%Y_jD?aMHFM37ulJDH}?FPGd#tL+mNk_?}B{w5fU!>sp@VJMl z=+xCmoaOIp*TkdgbpSjPpaYw`1^?mV@5i&#HdNkw%fBtZb}8ju@t~Nu%eZf?<#>`j z-N=KuCLS70mTcb2@xD8C;JW9UgoO0hV^?Cg-Z}KvpckY84AhR^$LKw4`+n$lSl~DS zKx)`$P`W=yE@fWBDGAxS^IR-Mf29)a(Q;`KkI>h0*4QVdRn}6>J(cTlv{i=+26W@_ zNxp7w#+l`8j57U$=(CJsM(<8+)I~>+{@0+JgRoa+;pbS3lW(L=iI>pgD5VH@1#2RG zq5tZfxD&0+50jR3;?=+32L6IOmACSh=qxfwU%dy@s(9@d0gcSmm5@^nEGfu9-MXL7 zR&@72h}82>&Mdc&bbdGXNP#1F`7k{amz6xv&>!i)Qt#%E4XAWpaThqG9Vp8U85Ow8 z$Vj155+E$bp0NI`&-UEYHB5(}9z)&YE#qF=1@0#(1A<LF^&%m@D`F-@h`9e3MHT)& zG4M-I3Wsak)o&#OrDuJ%L-};r*})I45%$;1Q5%FQ_o4U;R`=4+`RQY7Q@-Q0<{##z zSyfzAI%daX@J4*Rb!XIUs4X}64iSmR4a-kNTE%Au3tDW*W0QA*YIFiMYlA&Qk=yf= zE(dVAK9(F|bI)nr<GUd0e`~AOzJ`oLJV-j4sgsuiwovLlnNzd-vxq!&5Mm~ZyIkC^ zM_MM#ya-Aws|U|5+6CObqhwv^4o0qhy>jH4KQKL>YhQGcaBJIIfK_uRg&9z;xlT~$ zf5fZV>`%D%XGZzx7*aws(1*uf+U#(kI9wLy$t7aApo6f3RiTG34tR};hWW0+aKQz9 zCO5G{v@t#4K7J&)ctz1TQjSoiZEfjQiRuy4^?|fn5mJQdhvq03L{Gchy^-4ku1wcq zCH>@fvg74-mOTiFMY!!nDSDiGjqp?)Vl_v!>a!>u<FiYX@*QMdj@ZgVl*7a-*kEW* zN)vD)ENcCZdJou4a65Os^V2W+SkeYzJ5JF|<z_Qef@^o1O9Om#Z1-=Av{{B<J#=1} z9!#ZVo;~-_BS{34@peSwe(E(!VCD?x%j0(2Mk`ANZNLmp(!x7u9+!V7{L-Q(eR3Uh zP%H(tpV7&hpJY%ROtMmoZdtr{<2U%X)eCGulR*`R(pLw&6}h!gzP4icdZp0wq;K+D zX743Fyq6#3Wuvh%)gPdsoL*#T>i2->i+|2O1Im=F!@ZdXb?7n=9_zhx;6+jK*&XSc zBG2xh1_f9ckPdXE+_<?pW@7$(nDJ*t_CU}@9T5upms}%WB#7YaQ0bHy)qt<E*IMEp z=d27V0(kzD6els-Vq@{hP}?F<ygqYy;uc{X*=M%df5G*O=ea}OatTM)S&ls&3C(KJ z7cw6U{7ebd;Rzf25}X-Cyp24z=Ea2DvG*nH9x-lOAxtM}mjSFoai;sl8(zs(jQRnQ zE@x(W+5v6vL@1VDXE+oY3vOMDd+_&Bdy&9Xj-+_Eu?e58d80M7!gvZoa~Y%GsJ|Pf zFHsb9<go=dC2N2EKyffLOBJ`9>Ceew_@mN@y?T#@bWBa7`!CEWV0_hfq-JeiAJ%Wq z_$Hy<z{V?3%l=WK1yB8nKYt}yAr8g~H8@z60inLnz-+0B+`b(NDh#WbLeTqpsh)~h ziPj(Tdvq>^$!)P7YW%4@?uik3`HvQM<PEt*u{QP99dutnB!NF|5{y1Ja`A&{e>Sm+ zKFCv&R=9C#{o0+=1p6abhdv0D#1vcFMJBf&E-sJagcu<v^J4&)Y1V6oUyQ7Zt%;Ik zDzqb+v#)5>sOFxM2UQ~SeRC{XeW~}0AgXEem-2|Urld}UJT9>cS$n7c<^F+yTlR>D zU%aR~y92l+3Flpd{k<;?<SD`}ZWQn)IXCuAnRBl{ljwHg*drO$ohIpMq*9M~$aNuv z(=C-T!y$K0^lU<Lf>0hxkOk&MzhvFBXZE2z=r*E5=gU$@&B~4t59z$YG-;=)j$J-- z!qxnwuPTzTZ67t5r!+-VMXImo|IC)au73|mW%u-FpLMF1x{h#-=GV*AQ3&J}Xs|7T za<+fF*KP@xB>FEdDOvN7gnik=N*<M28EWnh>t}Tz2Fk?Wp)JS1{%*m77NVzk`&7TS zj7fEcEMD^pkbO#IvPSI|znxD%B<x}*C{-mhoy=vd;<%KYPgFuNLaXYATktXl-!B-~ zCzzOw@k_=p5((*!aT4SV(JE0NvMB4s&c7A;KUx4q4!83wSMG%?mz5!1k@2s+@?Y$Y zOHwR2VNjYw#`flrz#M`fD>S;wrcjxHA#<eIgqEzw=4riI1fU2Hc+`rzEHAqViM&G+ zyj=YjM^WbLz}QK#cXpeRt;Q|RD#*y96J(TOn$cusMZ9ZqJ3%Jw20zd1DkvV|g@*)F z0re4ta%Gs$rw|vpGEpe}mJOkGomVC3MGTFPR4>w+l8cd3bt0GaWX$BIMR+75{wmhR zAO|;C#&eY?q0|Xu%KCT2zxX%udsC$O^Lan!Da=NS!d@c~ctln0tQT8oeYtWjT^F9C zo3auYrU~S>UDEzMyw_R`PsTW%#PFjvc6^q_)QNx#nYo#J%!VN5QjNw``9kSf-(-C0 zBsQp8MX8c@g87!z7)GpH7_pK`S(P`p9Agrsjcto-m(M;+mf;naDTiulXTkC8P)v%j zrWP{a`qrmvdwv%gmjP+RYr^;&1jdF;Z?dFi&^HuCyvZ45P5br-$O|S!=)3zFLyql# za2_)tYUqX!s#e&9*w|D_FVc9ls@6A@g@S7cvz0QNkn5Nf2`*GN%w6fpip;?BJSJrk z&VHjF?6Q%13^%*id_|#9qbygOFrP!1JMmG0R|rcWu#aPpkVSO^1&cOBdsah!sRQsz zHi|N6<*q`LCk`!lgjFl-6wFRUU&n(VL-d!?YY(Jb(q2LPa7&dkjh6Dy`_t!_wZ6=% z%<j$v5Rh3~K-NP@Og_O__t2&WVE)>>k5HB?3@6dinwabQ9v>ZScKCzwv%!{=>_Qh^ zrM5H?u@$Mh8r@X+Rf$K1)DM$?3iy(5YAq&*gjvo?9OH%eeGpBN;?SP*kI27>e7d(v zcA9J#OcaK45TYw`=hXoQzw8Y8=U1M=cXfDunu7Fz#^(>eTdf75R1w~O%!^ucs~ZNl zv`ruZ(oK*)>Iyn;Im9Wdc*!4>#E|azi{LpX4;u(B+K0kwY!om9ye)W)4)BTnj{DI3 z(YIG|@AMm$2|N4A*5+g}e}X~P8wH~gB#t0H-DiE0jHf8f{CiBkbV?~{G-RDD`(k&M zi>kp2Y~=$)qJc@dj&8uyPqxuEvLD-bkx+31UyyvNL)1jMR?K`>-Aqet?=ohB*F9d< zKZkQ$6pD#GzRB`>ZRnzW2#O0Q3cX<eP*M`YuTx%Cc`oT2Lu*!ZF2I=rI_&f>YpY&y z(ZzFmK%=O=L?80Fi{l-L#iQl7bHU%ZboY1a_l8o2ay1nfhE|69jzatRi`n?_w1j`6 zt|R0<IW$@6!c0_^?|P*y?@jMYd7SAdy!#2E=IhF+DvKvW1Q{*mm^xfxhD?$zjw{z* z-+|vrqC>3kgsRi0J_*UroU&3m7A{qV9n!LLSjJggJ0LN@@8_l8<K=bwiS4gi)7(wl zMx<S4*#76<x+9e;n*@d2-SIQHse21PxDUx~bj*1|vMV$?u_hg_g-zU$kfy>=Q1fc< z;?_nF7)KiAZ){X6Hu4T*t_{SIMJVtf%!&x+0nXOV`5kbfmD(FZ!)Luc@^olt<;lMF z)yR<8eTBi<UUYbOuAWBiHkbT8=gnU2&Almw(zOst8E;>Cxv@`BS^arlftE8pTf3h_ zV(HXik-dLhrHEU>-ZQt{8V8RY4ixPpi#@s(o(ii51N6`XX$7x?UsW?|oF!WHfgPzn z9!ffa*?y_F-y=c6%=mjq*hK-+6^xae^}CJdg`vJP#AL7j152|JQ@02kSaYPZGKX+L z$H+8YpL))KimrN1Oh4H1&50R(@}f3OX+Pm>zVr-4t7}=t{6g3TY~qU+d>>UjcsV>N z_lTU4*Rz}aD4NsR2ji66J|Y8qpd55hr(+W0!5i|P$N^u&+h<{^H`GTCpmhN`ec%Wl z*+If$Iw&4NQn||{WjV>b0_ph{1*dDcbue~T3HzcJ?@ti3TQ*DdG_ptoCrBA#!_IeZ zJB|=+-}HwB-n7nnr}?WRLS$R7*qe|e0L>*)?fW3Xba<jYG+mP%5BJ|G&>_fj5dXfr z-|YW~=bdVm*H>H<6@&<J*!b@RjKVeS1aIE#agTH=CcXtf(brlW9;DV~9TOe%*U~jp ziS$Q5^JQuazX!qeCZ69w==H3%|0PQ^FT&mq;qXd>w}b+R6r5=Fq|{bg*f;Dtz8OWK zM5<Z+JMd}SQj9_-OhgklGy&{e*frw=UoF!+Un^j|#9$@+;`rl5s(cA@5RmEkcZC`? zsyE%QH>*Ciwod3RXv7TsD_otV78}hkvf713!<7IhHXgo=ZF+Mc(RdBR5HnqNB&<kz zFJo5q@|6|ICC0`B!(iM~+uT*29;d`pREqdYEU}nKEFtW0t7P<VNoQ#jh92+ka5>7Z zIk&E>-ad2QrxNR<L5L1>l*pbAG$E^I6Po0J0RTM|HOGo8K0hSzwNIwe!_4WL#TCP! z)SL=oE14INtE&un*5@cZ5G(mflUZ$hf=tn^`Z4XaCkduidWU6B7EL99S+t(%z6eZE ze2{=4d|Ph*27Zw(5MC>`9&QWic5Ea9f0jwTKUMUVY#Dc`)!Wy8TRuj~!D?>etpFg% zQX-WiYo7i16UqF5B0*u^{WDt_vuqi`J7$cKiPU`N)s$5O$rbSjx4&V>=J&CWZ=>Wk zpLxQC1_DI}uAS|+b_x>sB(BSUCxnwnX!+W_^L)?;9eYA11x`Jn-GYsa8I|hp%G=`) z-L*iq6Xan=H@r6v`#J@|2@th6EqmlNANKJhE1y6)!caVRBv^FOm-_DDjUR)q_ih>2 zir>%_ZFf)DcfxqL37&n51jpc2aQN1p6<@jV0`)5d6v-7^CE)ws2+y|~w&1(HN%7t= zIKk#m6uGwV%K2>n&de$lZ?edrRsMQB&{~68wX4;QY6`gPys_&}N<CBhyXP<L`kmzW zRcu1LF#%5H?O^9D$W1lQs~_wi!aTZ+^+#akB!8V1zA3LPT8$ID+(m-(7?JrUlJ`j} zN_?**Fgv>m{&_o9ozf{NBw4-jn&8fuPHo4G`r?y&=NYWOP^n%wm*2j_e_zXsTB0TV zc^jYbgk6ck-61;h_^(4`v-I0wbl#Rb#AGK~%^M01ltYkNZv5LPr~xv@KYAZwP;X^V zN6(&r$q(-JJm~-P;E-Hhv{ajeX-C4E=gH+D@2v}yher1CEbTp`pHfx3>}UK=x)n`v zjmOo?P-K1l<d(GE#c$gBZ;72q79%APOich39v&ZFf$>)felV?ZeD#waA?HMr4<0c8 zE#kC{r6%{Dpmn}P@}R4*In%8^hwEapo*cS|cX^Esq4k_do<I3_?lcN(WkEOsdE{t; z^{UL8vlR^>FvmuOoYV=mXU^_?{^J?#Z+HHu3K1gJk==sbdTR1U<5n@8d1YG=7Tdgn z-Gn-8`Vw-ZdG2sZVRn5oE7>s4{`^wNPRX6;&wse|i?JOE{sfHEh5)fr3dR<ZOT&kq z6%FpkEhrOAX;j?5<po=`8RWF+KRji5MXN$oGf9*}qe|_y=&Hkd*odxOpR`Qq6@@zD zyEX4U**AXZx$CfWlC9WRdE#`r{JK10LIbFkc_+dMnOz{n_uymLN*xO5B$Bzbg`7Y4 z-x0kF(l3616p;=DF6|!SMg23`Beqje4Yzk6`uA?gP-Z%~cwc!XcZir1`SRxiehwS+ zEBxCeRd5;*KT$ckldvqtaAdko6`kAbl@enfFRL_<7do-*tG)TTVaO(Hi4ek$N?$U1 zL%S%RvaSuSz^ydE=xF18gr(&(h34uzI>cwo$+p4~98JOtx=08_e43;#VU2^~m+d3w zB~~_~UTKUc{TP>(&oWXix`&sgS&}*lt$6<UW$eh44zWFlYF@tZrd(c<6WXSWNB90j zE8>0~Bv453f&m_Wv02Fs7}M2tRBi3xz{x>RdIdsUungC?EIs3M{Xr38oQgz2ProDm zK2qcfk)ziq*FnonncDP$G=6E*K;x|4T0KOeNL5h>7~XBD_r=$9vBWg5ND$?Ay@X;e z3uCD6@aWb~mgpaU)|07MH(hR?@aqqse*H|PRkoD(+6cjnwVrEw4rS0d*Wh*C_nyiP z8WWB+hDSc)4yFPG(b<{)*Mu8~1T$Z#bNdOGfrF9v9yD?f12Jo&xzfix4?n)nKuhnP zbi35(g;FNl-{b}Ye&Gi^P?2i$DjrB-hd+M~(nc!EDN%2(jW53iZiJooWx@^s-USj# znC-J(RvyfR-~R;6ySU5ven{G=wrkMJ<Q22?f--GUX^Fk+IB61tBKXWCa<O%p;*5WK z91ajX?^>FF={<{9&h?|8dHd{=NS#~c=HEZ%jxWq5?T)!cjjQu(U`T2=*d7y(;wm*e zSDb}4^_QIjhzj;WZ8iHH?IC44Pu0-&U&oc(dIlV<yD!Wi&DQKi%IBn7DEPbCTVUu$ zzu<JgoW1{$fvo)k?JPk-F|ZFVQiGrf*nQeW%ihNoOv(>!NC0Ll%*QUK?|KHsk5Y2& zmE3B2-c3-%yD{UGMtEO#GD=J?i_$i<!e?2&@v}6vM<=lKs(y3Z48GxIySwGk9Oi){ z<V_oRsHz_0ZhgKeGqkq!1gdav+;9xKhQLFAn^RVi71sFh0?fq}|A>@IArx+b&FlHY zGtK*ew&Or@$0OE0^m|WN^A_FB1MTM<Cc<mW=c-up5Fc9kX#w{X1Qu1<wgU!a`rj(D zTz=-o6NqYF0Tn{KJsczWD-W@(MA{d_?|olNC{98V&Ir0~!L?<2p+ZiPuD^I$VrD&a z62MtBqzyJCXa<K1ix?@`Nv9FLrtU-LQePOog7>YPLW<*~`&Dn-Wf9ABzB*_^@Y`b} zdfx77r4|NXZ1$ku=G%q|XvnQshZBbwl%N>hSydI)ThVhKt{Ng#Jp=1-U`9QV=_I>q z?BY40<aqjNa2;x~9nF&{qGOo4xn=gQBVhW-TV(o~rDLC+{mA7^i3b|DJ7$H09|#Xq zgfv9^DZ);o%dA_ChokK?!-rE)$9hi3x}_za7wpapdjNl!Lr)&u$u+;Ky1Dg)Uj`Sy z(Qb(-Zg4cP3ZLKVxoGgg2lIRS{=v5OsWI9inb@WHhtq#fRxnfSf!pUW;}N=F+ChZ~ z)45tjR-w-dvH13Yn|kA%kDGce^Q*mTRgQ<7HMoB3%IegsydCfTdpZT|xXAmg*|&(G zpK5H#)|u{=CmLF75+!3V^mI@5z;Nr@qsEiT<bsc%={WebicP-q`)ezhmewUo;OqL_ z7zXBSdxdh$>r9DW?xCKjSGVy6#3d(Yl62cq#ChaUF|Ns0>1Mjo#+zCoh9crvHm;8= zkaE^;6B(h4s2%CoPJfXbLEfkmKQk+Oy2jEeW%)rHRyQ|kCp0qkXt+F0$qV!@TM?<^ z!ew4<*8cDg%GmtyLf|FR4mMzUp{Zotu<6nLYA^Q?{(u1d9=>rqhv<F6zV0-0Bk<*R zR6$wJVX>nkK+rB*UZ^D9prRi1Y%D0e&flkU^yiT0e4x|>-9~-?<8i<B=*vAD*R;-u zUa|^nCbX&tt2^HTJ#sN64PHvR`Jqle-32ymc&)*W%&G9OQ&;i|gY@qIoCs_zAk0`@ zQ!6PE3F>Z-WW1?0d&T!KZsJr$ncOv_hm!QDT#>5}ChJV^zkhgaBAWd($KLFH<_tqM zrjkFR-nE;?@<<mcU;VR6L`zKvqx9L>x2qJZpU9xO!HfBV8V$Sc-`T=$&qBj|C6gfg zM^V9rN<7I#h<DcGvh|oc^Pr`V40{o)0!+QJ$s58Rs7P916v60YgXdM$lX?dOPd}>~ z3Y$=MO?OD5XDvik+MmBNGnk+(b?rc1)_h0f>E`g$)5e@Av$V0-NB_z<Ql^a?%i{P= zxDtmC?VuL>P_eD<nQG3ybr)+fv2Csb$p7F}9{_}aY50NvFHW`GAO_-5$Q%e|+aybB z!okqCn(_Y$r#k3o-~mSoHE1DGX8=C}@M*(YrX7t>{@<MH@Ppc#Y5M0-gJWpDQyxUI zuKuQ%cmFe|8f(0wvJ`qCNb+Dl<-{0(trx8L4^Fk@&E=lxJyL?_+8aoNT1A36rkyuG zEc{nabwuw~tt<Px3u7khPM`b_PW9>s>Dtgytj&MoR3FhHM}GPraH_d9-pjcE#;Lyg z?SG9^Eypm;3Hd*q>i<2Q>a97i0})$KbjMS-=J!_&Y%T0R5+Gzjz5MZw`L|+c6{2un zx#6>UINk7Rm|pjoI@ErEYY;86qyKO*s_vtq1^sdPDF}Y<oZ|B4q==D4UY^FxtA(1W zE{k(@&D-U*yS-uHb{{6YKlh?W7wH6oZt^C_OcwZH_~YBdebedzGqN#wLJAscqC;M} zTw7&NuFj!oFZ&~?0v0T_hly_zt50-Ial@;B8P2O&jgkoAn$_?4O8#||0`oM^0^4*~ z*SC)rCUZ?;cSHa)Zl4Irg3A#B3}9RGcS$imHb6cJAsqM6da9mBPpY7gN3dqsNVO}r z5(W(5)%dfKgHrLlxzX%u83;XNFBHsU0REC;07FW!xH_WiwFF|BM?Z(a3iG)kHD5nM zVnaGkHx1(8{iDd8x59!caG2y6X-L<L2rA6b)AqFQ`Qrr5i)Xarw>^<UC*N7dwpPpF zbM}yXgy|bw)e@psR;VWc17Ol&Zu<GsSY5&GJMuD~qD<3SGV64X4#Ruy+0a<m#kgWi znN@m*8Qg^B52x-C4HQwasTGPVlUH0Ht9d*I*{8O2gBkwS7k6kRH?m9~_tH4Sd{aC( zVkn}p)ydT~c-*$R>~#SI`I<B&T<cOJSJcN}t8Kl>1ma-0L8scRNiIA%DdqA+PHhH= zXJM(8Ji*k|J<vW&KZkEuM1Hvd<{XFw{acw-DPX!VJ{{Yw7j(AkmD!g9f#gC60@|Mf zLb*H1XTPTj^+=2v|2c>aOoB;s<3`O|mk}ahhn6pFl(feei%)tj4Iv>+;nBQV>uETV zt&oF;rS2&qud^mVm4lQ<kNeb)Yufi78jtkbM#bsY8lQV83**j~{hG7r{L|o;;V@Sv zwN-ED+~{$6Vy@P7tHJF;qgS27lSW@Lo5rrj{kJEcw8U>+rwUy68FiR%FWqVialY=m zFfo6td#gF}!gaq@hlTEETP<-@*N^;|Sm^!L>3x<#1tz{M3}`CkL8vt}@$0Npt%Fx` z#6Z>H?^(jUKzsh-4bf)WzQV%=xDs!cIh(LpcuBhh)vi9FpY;q;o_ekMg1T;i<MU@b z&k!O9J0-(C_a_6J^S6M~j}MX_sCYYJx-MstYNMrZKAO&fAn~6_cBU%38+n)R;HL*z z5P-Ys0a8o`>5a0A_ax=6-eA*2?;*$<>Wv7LhKT-~1qi_bX{yym;@id-$%$v~$8UWi zq1b+E>zKZ%k6JMJz^>@-jZC>U*DvAstK=L|hH<I&urwZY>9eesoNr~?;=IFgL;bR2 zR+LvUa3cE#j?{Erx8AG?cINhdnIc=W%_~ZLpu$MZ-y!8L;ax09Bcs<i%7mv~Q2w$C zQUTeA83KXOvFf^L9vcIE)P43Z6z*5CB?Xu4rq!Y%MczJcuvbSQ##nOaz*2pNq~O<A zMtSdRVfmJdpG*a)qKuKASzB8HXtGgSDhtk+BD1l6EH$p=z!rFu45un%)M-5%z*oOy z9aEZ0tby3>C5b;J=$5LbB;=ko00sp3i&258{Kvwxo|9K-a|L4<QkrFW-N~_q=Aug( zHsoyeFpqe=aM9yytG@)Abucpns+(<}6*AlrB>q_>-E8iPj60KpzwcMFw~1LC>~1=D z3X_V%xv@@=4iVO5T)t2ZZ7r=FA<*T{D=uiUEY8P9bH70>kH>gmn;B53xmjf+d=ldr z26W5P^V(>~_6o0Dzn@ezz|;N(2=R3hiX6k^avKEs*#oXSCV^!$UqYER16>Mvg;2aU z9k651z}D!b-Y;v#m$z!RZ2*8Pv&$c*;6H!=c@UxvRx5kGau7N`+?M>Re&M<_tbdfG zR#91V=-%N!5_X#F<c%AHVzPHHsh*nZ1=W00_sn;VEWTVm-S~?j*2#rCo72qQ--+$< zxs5Q`CZiMQEE)?0`-t1q-`~gIl#a?sHy_E55+HK`NGsHEDe7SK;Q_I7eA*YO^Q<F* zSEQb5MyD5RvPwnD@s~aqDGo%4IMvi(uMw>ek`D$Y*OXHLW8)7~K`+~>{+l(cxdUP| z89>=w-m(Xe8fy<$^X8=tzpE?=yuhO9P8If85MpOv{3CQtz#33Ek_c$u$h+7$iGlV1 ztv0RViP|i4l^%{aX1^j-$?JWWw>($W8hZiC`->y+V?mkAI){k{L^<fMc)wIA9rZOL zd&N0%*9l#u_gD$McubJ5OZh1&84(>-D3@%ampERB<3z^k>g|qhz<%CJ3GzM#Apv(c zb(1)#o18QHb}|5v`j|)0d^`1N+c~SvDEW)t!}6#GF5_Em+}tsSuNdkY3FT9q=C$qJ z#6s0XrX7?>KeXmu4W!c+BLjSJaCTC8hI+d;xJx%IT6R3<lMzy!-r1i%N=ZP_5;_ef zTHH`|+RRj+3`k@~+_r89!V*SHDBQt=;V_BA9CRTEbu=WyznHlXc0SP<QNFvzL&WQL z$+aBEMovUM5jC8ecAd#AMe6;=lRG)77mOu}nVC1@^l}wIPYIxio7oZ~emf-NPS>8> zf#7o^ndV@Ez9?{+lnv2F=J#cs*U3ru$$_V&juQmm_R&EKxrmy;6BX61EHNK<VNn7f zAA&0#BFu7`NF7A9F{*M=e6>EUzc^QZkcnt>_T#;f6qV;wpQkB;I6RXxZA^zn@iKt( zg#^}5JJz1+Fa#|brjvJ(z`~5{-XVd*c!5$nAJzx4OP6VKla#uXuVu;CIfDW+3x3oW zY*+dgVfgcA_}g}7Os?qI!!omV&+gGsR+;6Z^CHp82SKHhGbQAleFyhA7_0oiBPY2i zTS-9N2$|%DZepLg++XONsq5($bRW;BVGk-1LE$^%CB;QY`E=Rri%=Th^Oz%M<3$k- zI)^#PDUkoB8~TPDnCFvs=BY>MOd^DPu35X-jt3P&1~VIqZ94g2U(g*Okf#C)G{mt~ zyi!;ZmD*qul{b33;L3Z~^Cn<FDgS5SrE4Z$Ojd;HQ(kCte)Ch0ixNPCBv1#U^W1o0 z%dF0)9wi`f!z7z4R<`d_AoLMG_Y5+w)p<<CtCo)XZUffMWIy`pGAIdLk_4(#5l`*C zp6r-_3z8MG-u!XLP}QEiNvx7adilGjF88@6-3N|WHC#!_Bp7p0`4U(AJ@}R1^Ic3U z;Uca|`tx$%qW-C<SHmvD`!C7PLLnT!pLf`IzViJ&D;LhW0^w$2<JC{~1>Mv>r}Wii zkE!|(6}i!~Rf8#rAp8*}xr|-<D1>|Y?O4^f8n)NF9Ai_Fq@e`pGSySh9DG)-^C*m< zY`{U3**J)h*(tgH=TukHoK;11_FMIftHh_ufq`uAZj9@DVq7HhI`^dfik<bZYX&+1 zAFC#7g)fMUELW0qmju4n)$Vry_s*ZpjOJ_W<IR{Um!IXY%dFGM7yN)f`i~yDvGb1l zfk-UpMnsv`!Q3mwSFWX(VmQ=&3Lv97gP4?sU{GsIOce!{fW7;LXx++#dJWztVC=z0 zvw;(W_!_AYx%+r<M@OQ{6n$9|XrMQ=qZATML4d^@q%SuViQuIPjlUDW4Ax!6H;H{M zk(0bmo6T1Y(nqW&;0KKC=%A(#HqW@WJhFPQTY)G6yi}F@HiLw;QhC16k|9TN&-iYv z>*~V;Qu%i2&ZiUd(WM+d4&Twa(iYfYL{SvFk%SDN(IuIJ1@EJ*ETOQO7FlR(G3}(9 zsooa5)hr-YNsj*(*fJk0*&d06P!nJ%y-^POW8ZnQe3T%)4Y#u*aKEpq%-vUaa38F# z(bV(i@Gru57XOV$yz#Hu2;nrj!8~$<UY&I)Ryqh@b(6O(=X_gL+B4l=&P`iOsHIvI zTsTG4U#P53@-p|jx~0I47=1(HEhri4nxIVMtI&Df>HHeNaDcHa^eX2<=-14CDjW*o zyD@`WoX{Di-?sNW)zO&rMY~1NV_%bjWCxI>r`I+iX+S0kd<8ndDxp{O&ZK@+Cx}LG zLUY+{&6~$^r1h6Nkcef#sm_4@08dr86Za)^5CkM80LgV-8y!mEalM=Rpa~vCEVSGg zCw%65bUznQ#iOwex^L5OPd(Q|+`dhZM!9bD9o@l;qkfgB!W^y~*T2MuzI1>ZULmY- zn~K_EWlFll<c}H+@5`kM4D8p(kUH^{8%}T0^R4JIo^~@4_}=+msjs^*{(GuhCUMe& z>_d8&;SOWIAU3;I9b(l^t-8ZOjwtAFkd6pT1FGzPjbsPBI;iBU|8+(fzD$+O86fId zKQjea>9#MPHP<^p3-_N==tFL~h3QXH1ldrEDnzdj`B}T)IuZQZIbeJ0mf$k-SF6D7 z-$RZ8eTh;vzTv{$Y<-_&pxq=<@y@lQ8}e6A4SjqTl@-k!Ov(=}9Wm5}ZP-BFivW}p zap^&K<?zjN4?c$tKyT(gf|mM6iFj})h%Xo@cW@ll8_3(J9YQX|>*3p((DH1tWOj58 zlr~De0xK+n8P>aGP!cYL`#im(qBtkq5kGLt0aVcDIrTufnpDaPmsbEF?nR=!<j%6P z2M1o;Z>WJ7`~-w0N_m#dpwPS2Csq9q_BerQHc(|8pvNZuL`~^J58W#5Y4-~;p~7vb z{GF3iAKE55{P)RcOfeFtHoB!0v|*Pb>1%!lvFZ;Xocpl+sUJNCf6VXp|9<!hGS&kf zFd;!DwN=JQGx}A6AMt`;x$w3gD8d#x_vT@G6>^uAEpt52p?Z3F)`GWfCbIy2$_7ja zs@u4emY0SHbYbqi)6g9Pv<*jW0P<wH@co@FQ&lrh`61>cr~nuwahQ13*wm8S%G*Zf zuFa_X&nmP+37lGl`@k7pR43Q*BFA4<8fcdUh9k*t_vG9`KtTi4B|-NeCSGUrnM(2e zk>K5BU-xk5f+FO6NuWNJg#O`};=nh8N9B#dA?$Hj`GQom{hwk$j`L8Dvyc&uswZ7w zKdykaUDIq{#C{Ex1A|=QDurBB@q?$zDUK%WN17yPr3ENSg7$b4+c={<?z^;zr)+uf z$?<2RRY!8mAy3tzC)O7s)Y;_r=bU$}22LfE+|cuqAjt(DB~QWg=kua@b$`8(_7}A1 zL?(2}0I%}rU*4RFgiB^&_*f(!;~D<3=9iLkccE=C*ls_a3#@wqk6#kI`p}K<mvAf2 zkTkI19I-|U@MiJ+vykIPqW?OBW&m8sMK}VFi~}k{Z~B`XfWy}n8~Qj9Dl*RvdA^vl zb699KTv-2oRCmYn;T41GQ|LAjeaLY|#ot<3i4s=?E^!6TPAEUV{Zzk#5D2$&elhee z@{Q~<!M%sUM1`B=C9quET=Aly-jj5*CwK_te=*Dwh8)QO+mBN-MWG^8r1osp|18Xs zd4}OvzD&{1m2m&R!mQm0jOFk@3bURnYtfpJfG!=Bpwt`tKEGA-^#2iN$-bzJI1+Mz zW<h(V-_Kj%g>d{&Vb)JJ?Vc81O0c}Wp|39dvfw0@7Pk7|!mN+a&$$N}mY0T3b$6xy z_b}`CTaCvtuSa7qIsSL)+GUB;cmGGywGtfMCdu``hFJ@tw15A0{{KtYwmE`wMgJ$v z`rjm7`@h31C$3-f=}Xn&A5UM}oYZ@`5NH%CWD(@*fFAnhlX~m<cR1(!VyM<HJ7uW5 zTs}4&zSGK7YM#tCd<L7ch<)Mz_|$iE+6R6LMCjuer<c~#FSpI39%{@y-Q3k6KRt0? z7FaG^_=%#_4MsoEKtG|dmLOg<ODSlx`<Q&G9ftnt?QC_|S_J|h`{HCq^R_|M)pO2M zJDV3D>i(3l8kN<=>$vgbsn7V9;HNPTKOoc;`)vrvIr{@dLLS_eg>*1Ut%VQb*8DSa z&A$$0Xu7Q$f4I11_-tl`QuIjG3#ovuGfpEyxqS0{ff%?j{Idko>{z}aA;41lCG*U! zu5;6=kS<<}7P3+4o!2-R%@&xB5)_+&?fHZx8KK(w19vS{ods}3ePQ}8bN%#<NcPR0 zu>PE2eTL*@F%Nkg1jtA$0SF1Mi}GL^bR{2q?PhD@WelE0D#TU!Q-rCMtUex&@U!*w zUGEI*kXL}z(XvW|Mu<(&A19gD+z}F27}%S%F4C|&t87I;^=L%0AQEq&7BrS42a0L2 zvj(haS!s5#*u3qb_vwncK;$EZFI<0P6jVq{37%`{nW6e5KNsi-!0Bwv5it^U_ZVk< z4c;1v&U8#(oV{GVHl%W59Q4j{#rH41RQB(;2!2Z=d<c1KJd!++>~s;ojz=1ss|cN) z3-Euj$Y;Dl%RRmJUNqQ!7_u)4R5ZLU`&A;tp;qPL?78ur_<p$A$MKzqdoIz0*=x!T z`%9cXL#s;S2{wS!Op2a%z#gbcElK%Tm5yJE`0lSFeIkIttuCT#HT8Wl3m4+$CQ$p4 zbp0ZU90UD;t8y|vlJ#7;o*z^?)jy4tiviR)P;t19r4t$pNj9(Kajg$kfKo@BwlYQ8 z^=WFk1+%u?6_B?ib;;k|-e2&^k!HzV03S7la>-w;69@y?q`Nni)SEI)c~oN#g8Eo1 zsbj67iZ3S)pfAXYRnJ^g<JC=X60|B`-?;8CKZGh5WYnF*+u@B(LHpSCtY1DG)J6hJ z+l`FZU{L@Hb>3Uls@_M837Wj+-Qo+pQu-H-TCNlb-${He{eo_V7ER0QpEr=W-#4WA zhwABk?wfS$1r2JiFc8C*2e@m20Hc)X&8)(<;ZsTLAYFx*+Hi%^60PXz8V$nhJ|juC zm`mAya1sxU&xTN=gP=?jfR=CT)ss3)3pGaW&30))3sOKZKfGtX=J@&LwA@q0Hw!c6 z($xGA=?ris26cpccjAlRKe<Lx2seVfD;88GQ3ij+YhK$pp6*jGH%QFYp<4-~Q|GEA zk0D9tj8tCBe#j_RmPKX;MDfWST}jyM(w^k&&YL0{fbGOH3hK)C?B^QyY8l`!-FCXV z-_8r~+iIz2HThQeCgN(5#F&M4ez4x%pF8HhSR@w8VH!Ozv0#O?`yw!JT-3SK^rh*m zZLNmMJz6uqzrUqvCT9TPz&&Q}<{69{_<%w{7EE`<O3BcVz&S$E+btwsw7>HeQ<JuB zT{8FV`u<nJ#c-8P(mU4c!`;8;2OEaJMot}n-31k4ed=tD@Z5!1Xf6)Ad_N9V4&s$k z7+v$c)uG`To*W1*If<kzLQOxO@cf+s`la3;6}aNdD15P2;iRL!oDov@`z3wc^1`z7 z=Uyg6aBKR^(R9)ZjU&gdV|Vl-dd2oLp`smhXfLca(-mLH0Y@hk;d{Z@3bPf78(9h; z$}*3_tFiC)7T60ASSi7{qX%|0d2D!e`K^!&Q=&Wh_LT|INxSLMDb1t6GbwA<<zIFi z#-o$Rb1T&l<DgG#lR7F|$k9jc9jSZR2u6*rdj8?zLw!3PRvR*u>t?t0Vno@oXsXgx zQsmo_2%wal8K~=F$1S#*cgH$fr5XXX+L6GC%A>N*e*+sQJCvT`=zjWxFD+3$PlVIs z2=Al5K&2xADmiX!;R7c3(yT~JTuozLI0Q07s>#4d7mHo;Y+5rb9BPeu5Ks#(_V{~| zm%t(qJ+zIwED6O%#-|jfdUSG!o;P^$K@s-fRRT!6cZfeg9QA6znK>1Yqly$KmR+#z z)Az!3`n%NIGKW50*{S~Qxa!P$x|N(sa^LC~h_%``(yiW3_(M&28I&SvfF05>*Fn`+ z?@>pRz^P-w(PDtJA$S-BzI~5^L`LlxVTHBnLLj|lE6IL;#QZI@D>MAN3C9#WOlVuI zRUCjw00M3)TO8V<Sk&-*_+9$RUNGgXyBEwDd{q+{l<v*oAils5vs`4#OpGp5TnG>5 zvxQ!{308~-rM9Mm3dgey86HI8%+q{DTwafPp4dJc&owcf5OBf>T80<mEGS{{ybw1b z&WuA`JL<9<Z-KTS)Sb^$8*F+_FM<lF64hM{Kw-C(d0wH<+=TFGIGlDQ4s$HmCZV0h zi{82I;U1^L>O(&Vfv0t9oD5IiWB_bE1ObIqi<Erv0E7jrtmWs@nWr&6aEK?2fMj*4 z>}s64tA!HA)ZXER=1zmDY@y{DK}S2Ki}ZBHKm@EG(eD;8W~<T{iLRH(>VXRWA|>&V zv!L$Ip#=wd2)tk+5kHnwuMgg?SKDgMhC`UgqXqT6z-Sgd%^xutnN)<yh3n+rsS@hk z4}xyWd@L9=S!j1IHNl_P@hwkjM^2%KfW(^Gd0UW&df}7@gNK%PMi+4kFW@_~8wzDk zj-g|RT*?$#gI@uVEgikWvl<ohk(L9Yr?-;qkdi9P9oC~M04NE}?gS~na61zx=l+O_ z_(VKgsC$|V2ra~@|1JjLwB(4DyrgJkN2IB^3fN2HD_~@>JPJcYoJVv42)po1G#sOX zVCGwMDp5sSk#EV-(6;Pu5RLmu++rQ{t5=7t0cYe80YDK9BG|YH`eaJ?6w2<NXDgII zH6t+jJ#nSBU}_cu)p3ZN&A_M#>)0#peRDnwY8yhz<1*Bb{JaDKfNVL`;DQpv?d;)2 zF(?3OzLU4ix|q_=IuV_=`*3huS;c%@eT{h;MkqK5J%G-Sh{o`lNdUgud{^*=*G)uG z0Hjg{jQAqpl&SP)Cd11IZ8xvvECEF0`O5mrrgr#5W$=*SNJtGI1ce7b(=QYh`E+Z8 zQ6?1@WC2KP9t;m*oxQqni_-FaZ!C*1A0DtNDT>hsQ7pbSs$f4dq~rkGsz05NEU-e# zXV#YP9Tb8I3lY7_r3U=&6`@PDuNvIUg+%h(@Kt_JPPh4?w}G#G99x1IKsi`lfPFb- zJZL*d68ghJkI;qIX4sDn5shqA_Bf`P?PBaJvpyFd^G@%pTjm^9XdV>cl9+F9Wmn)) zj#>Cqk>^TH^w#kukUpW8EcAk#&>MV>h#cgD3C~yRk?>NDE-s&Sd=1=VcR&p}*m{a$ ziT)HMaQ9t>XfyyLXQlgsr+hW?ckp?7QKd?is3v;drDYeFjz~6GtE3M;!h`2S39!~Y zNNdGAOk&WNm<}4>eGqtAU*#=aiU1K1wr#er#$Q|Zk>#2WVg6yaV>Yi%u9gxqRY~fe z=#>)5&i@hz4EXaf2bSPOYlUn+0}uG13x#H(4gvsPd7z^j0P+B$C38y>Wu)aMWPL!4 zA+mH+@D7)lC-SsS?vSn(VgLdmPqnHs8HNcmDj9yzL<K>j8Da<Z@D1*oCqd^S24Dcx zfDL6hD1<5?4|-U#K?r<cL?L2QoR?fU6P*H~58m(%<`gK}Ft7g+WU?^_#Xt$05C8^r zuN4xoF@v$UrbL8L2qZQIps<`K|1u8LDl-6J05%{HzzH&^!wQY}8tPPey5ml+`V*uX z0PtFJCDR3!@CtxM5QNYQFV-2PK#iHu1+-TS{F<~jF#tO|5W)H}Z!ih5AV~sutd~&> z7z(yTK>#>;4nNB=@ly%tluM*wOMyjKgNYfY;B*DnpZN8)a4R)KI~(Npg@;Qvn_vV1 z5KyLI3Z+oFrS?mkVF}7w5Vwb`jr%mY={jl&8=^1>`AQJEFuI>>69xO5$ih>FOBoe* zP%2v)t{4Dym<wK8yQ_;5O?xbkT5$oumVhxqsW7>gd%3*p7wpuhU|_PE+Pmr^V#t<e zyrYPHF$e+bI@?(rOGRP<|DXx509eZ_z2`DM7&r**WVm3#3I+sNd)v2q>$jde8G`^` znE(Y0$F}C{F8APaw*Yl-yBGEQ8m{Q8tk%EtvZ?}shjZXMlxiWC;H1UptO`6BI5-e; zD;>LOAuGi|kh(jT5WyV+1+90%oAJBGfezH!A%T!c7<ymPYa#e_3%uF~b%?^8p~A)C zejJhuNNW(*7XaXDBDa7DdZ)wlvTFyCW9&4;7-9w|oCdG}3gxTB*#ZY(5Nwu!35w<i zb#Qkp(gnFtz*sCUiCGW}xj^iTA(FrgE;kU^d&cIHn`hJvtq=;_LkMQz2Ui>+S``4n z5DgV}3))G??&49b|6s-<Vg|l-4>^p;lF^Wq5(vd`3zO<1#5Gt>q`v`>3XCktWkJc3 zau0$4atRy&elQEvXCk;D4NjB>eGm(-(50fB7iAkM((nt9&<w`NUCQbSS6d?ORuC<E z%i^NHrd$hANf07iOC>^G%`gnZFa?YNRH2N_-tq}7dA|YB${=E2YgY@!zy}Gq3aMbr z+T1N^5C{Lu%n7_efBYb@Be6Mbs_QH+VBo7aHoz&eXO)%B`8+MK;Er<qB1Pspx}XS- zFusX9(Ai>)u!wgAF$X6`!W}XQn}C)OO)kH%HgRTOdIQB6@^fO~UJu>T)?&wj@WBFs z1_8ibDbfiN|78d3rPAXP3_xW@Ik!M0eIbh02ee?tIQ=bPaBYaNQmF6=hrns%QzG6> z5WR4_Ma?ZS7!0@Yfpfef#gKrKlzKm1)yzV;wGcRuPzGX5%xia>gOCY&GtXkZET`}Z zb~O<FCnDm53nV57X%@V3Z7pBuPV97mC=v?~deeVBE_LloVO=3cPzkb@*xdq)>3lkD zU|&Uc*CNt)a4p%zQVi;ZPHdT)wba=NVhI8!5No5lo^36^5I?0bZ_`y|7)>Gk+uGW~ zI<{Qf4`Kp@@Chl6+u8yP-xwm?C3(J33z}fs!ksLntqQXs&=4XDzC{Zg3C+zNE@yCk z8nQ`}{{VvBo88<}26%9~9Ws38eL(mu-rWXNp6m*jkjm`+72r2?mDx1=6x{Ru6&*_u ze5o|VNf6?*-+FNaF3Tvixgm4V2B|d=t`Ob?9u_LLO%iaEjI!7qB4uUJdc~mM5#ALr z3Mpkk2(!@G4MJVR(2d3Y;bkEK4*)re5({hql^~LH(GU!$!`v*+6aOU;p=sfSq6wc+ z29F@yB2r@}zT-mCU?`MX4&aqV$ismm3PpwoByJEvJRyD%-~^H6N<I|h;6+c4tw28I zLtf+`0s~WU<J|q_d_js1K$;pmn*m_uvyjTXeIQ2>47}jsZXOmS@Rc{otsv3}0+BtI z|3T!2O%Sf&<pQ!6v<Jft`{!n{v;!dl3HW#*LJv4p5buz%fRPG#a0sBF&K6=|+!n%Z zvR*8!GZ>4d9I{eGfDrxd7e!VEh7b!nPU%!)c7a|Z)nE$&fanC#4xsKA<HKo~;O7rQ zVm>q{?!^vu%i=Ij5VGkP$3O{~z+DF9=m*jaYoqGC4ksQu8Lu!3XB{HU9wrMLxt=;S z4)Ek5((agnRe3%#`q1h%<C`U73%^hU!=4$iKyvJ4S}@}aD5~!@BLPqT>mCvh!qDlP zLA)^oMwTcv`RVWv&%m951+={oe+x2<i=8~<R7%P4{N5pkeh{@j7(z7ZDMJkw|4%gW zP7o4+u^`(Z^FZ>J;R;)gGQMD+M}w_5f9a%*CkaT{E;I8=!|)_fVXgoV^!_FbBnZR^ zmFK?njGHug>6Q5@5Gk4=><5gL(F_tBGsPDGLJu`JU=QIi?GN$}@&NaIfeM|V3VoUa zm2lf5bFy0>G$vID2SEZ}IZ9J6A@C5Sl`%dBW(NZC^C@!-Tbc7OV-6|^Ujgvz7<>2* zV(d<<8Q{tHAQL<m&-ps@>xBO&d)o=T5Cv=DI^r%e>$vtsvk5s6oerS!8nUgM5rrMG z>kE@j+86*aI0@Sj4zLb1Dv<IWf)2-SYScgtxv&l5pzt)K0*0#l8zP9w|1W8N?|UJx zGo$23g;fv?Kki_$P3<KRyFhyu+cW1NnWjV#PKo|sArID&_JwCO@NmKa5g>qo01_Ms zM3_+FLWT_;K7<%i;zWuSEndW!QR7CA9X);o8B*j(k|j-^M43`0$#ViZDGX<h-AbA@ zZQjJ0Q|C^eJrfQffiS_00S5_6n555}Po_<sK7|@p>Qt&#tzN~NRqIx+UA;0Lkb__V z5-R%C8~0W1TDEQ7zJ(iC?YaPy<le=bS1(?36&b;Mmv--9!i5bVMx0pjV#bXfGgSw1 ztiT74Enmi*S@UL^;y8Z>9lEPFhGIpZhU>?SCDg55zlI%K_Uw<F|Hw)RickV=-c-$; zaV3ycZ{o#`A4i_tD}<mk4mwDnT>45+s$xyYo?ZLnJlnnV+>`@1^W6&%25|RXJ;hW3 zF3p)E5Y>A6_3husk9Zftpk)I@AE<-L@*_~7_zFZYK?OmoXQ>4rlqj5V5Mquw6{1t& zyviV4uNH*h<1j=KIZS6n6BSA?7qS8fYaoVZFruClrxQh#8E?cfM;*O$fCLBvP=TTI z@F{0UBacKfNhOzzN*{rk6R51{W(eTC^O&4%6opj5vP&<&1hXm`$+~hy2y%!r%-Fb8 zvrRYOgtH`c6uNQ+g`j*P2rXn8GfqGM1oXSe0zFZl02YbT|HmWvL#TimB)A1FLMNrP zQcEwz%g2PMEK?vfF$FbLQAZ`!ClMe@z_wCXWwlkW3~@ETN&<L6gid2kEErsO<+WGN z&QZr5ce>cn)3G4PAOJgkl`EJ)in(R4Q<$X|t3j((FxiDp#TG7Uo=|8INCdiNxNgtQ zZYFdUB!S9hqttd?u0**+pcl%JH(%`>)EB=Q5^#a697F)P%6R*|N=sY<xB=gV*a+Ye zgeRuB;*oMYGXnq{^2}nUNKvJe05%aLfN=wGIGBArX1QgT9nvCzgJ&T4WvWnd#YQN; zP*I>d0yyInNo*#%XoRCk$c2E7mWmV`RSjSkUM?A$|Ahb|LC6%Qx8^$5w2VP00}__b z;oz=!D&>^m6pAI1dIh3HAg#})yKYeXjPg_}?S4v<SlHw{aKQ-`Yz7_p6Jc+m5+9r< z>l%8);Q->kE&#wA$2@Z!CsZhd5JU*rg^eEwiUZ9{YHuNW1yW^}gkCv4cG+`Gzyi|) zpdq0TX2%JKg?R@)_yWlR2O&Pb5a{**xLrN~(>D-k0^v!T`V1;AaeaF2w^wfvgbt7X zfe8u-U;^p6C&`saK0&{I_meA8Ag~(>;eC!oPRI)6?dQLL+SuU*>=*)s9S|@hf@nh_ zei49b1mGR;5Xd_aA{fn$;uR`dgdrYL2>*4^UxT3;hdl5mk`cC}F9Nxi>{t;1*u~-& zw`j!&WjMpuIH^zdsE3mx0uFC{;~V`W1u05FLn0Q@GR6DhH{PK{bSN<ZKIE4}(vm_W ZRuNO0z@HU&q>gmVX;A2xQ<4G#06S&@>K6b2 literal 0 HcmV?d00001 diff --git a/include/gfx.h b/include/gfx.h deleted file mode 100644 index fa52295..0000000 --- a/include/gfx.h +++ /dev/null @@ -1,178 +0,0 @@ -// Minimalist OpenGL utilities -// adapted from https://github.com/colormotor/colormotor - -#pragma once - -#include <stdio.h> -#include <stdarg.h> -#include <math.h> -#include <time.h> -#include <stdlib.h> -#include <string.h> -#include <assert.h> - -#include <iostream> -#include <vector> -#include <map> -#include <string> -#include <sstream> //for ostringsream -#include <iomanip> //for setprecision -#include <errno.h> -#include <functional> -#include <fstream> -#include <thread> -#include <complex> - -#include "armadillo" - -// Detect platform -#ifdef _WIN32 - #define GFX_WINDOWS - #include <windows.h> -#elif __APPLE__ - #define GFX_OSX -#elif __linux__ - #define GFX_LINUX -#elif __unix__ - #define GFX_LINUX -#elif defined(_POSIX_VERSION) - #define GFX_LINUX -#else - #error "Unknown platform" -#endif - -// GL includes -#ifdef GFX_WINDOWS - // NOT TESTED HERE - #include <windows.h> - #include <GL/glu.h> - #ifndef GL_CLAMP_TO_EDGE - #define GL_CLAMP_TO_EDGE 0x812F - #endif -#elif defined GFX_LINUX - #ifndef __glew_h__ - #define GL_GLEXT_PROTOTYPES - #include <GL/glew.h> - #include <GL/glu.h> - #include <GL/gl.h> - #include <GL/glx.h> - #endif -#elif defined GFX_OSX - #ifndef __glew_h__ - #define GL_GLEXT_PROTOTYPES - #include <GL/glew.h> - #endif - #include <OpenGL/glu.h> - #include <OpenGL/OpenGL.h> - #include <OpenGL/gl.h> - #include <OpenGL/glext.h> -#endif - -namespace gfx -{ - -void init(); - -int checkGlExtension(char const *name); - -////////////////////////////////////////////////// -/// Projections/view/transformations -//@{ -/// Returns a perspective projection matrix -arma::fmat perspective(float fovy, float aspect, float zNear, float zFar); -/// Sets perspective projection (as in MESA standard) -void setPerspectiveProjection(float fovy, float aspect, float zNear, float zFar); -/// Set orthographic projection with origin at (0,0) top-left -void setOrtho( float w, float h ); -/// Wrapper around glMultMatrix with armadillo matrices -/// handles 2d and 3d affine matrices (3x3 and 4x4) -void multMatrix( const arma::mat& mat ); -/// Returns a view (or camera) matrix -arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, const arma::fvec& up); -/// Returns a rotation matrix for the provided axis and angle -arma::fmat rotate(const arma::fvec& axis, float angle); -//@} - -////////////////////////////////////////////////// -/// Drawing -//@{ -/// Draw a 2d quad providing texture coordinates (u,v) -void drawUVQuad( float x , float y , float w , float h, float maxU=0.0f, float maxV=1.0f, bool flip=true ); -/// Draw a 2d quad -void drawQuad( float x, float y, float w, float h ); -/// Draw a line between a and b -void drawLine( const arma::vec& a, const arma::vec& b ); -/// draw a set of points (columns of the matrix) with a given GL primitive defined with @prim, -/// e.g. GL_LINE_STRIP, GL_LINE_LOOP, GL_POINTS -void draw( const arma::mat & P, int prim=GL_LINE_STRIP ); -/// Draw 3d axes defined by a 4x4 matrix (have to test here) -void drawAxis( const arma::mat& mat, float scale ); -//@} - -////////////////////////////////////// -/// Shader interface (needs further testing) -//@{ -/// Convert to string (handy to create a shader, but messes up line numbers, which makes it tricky with errors) -#define STRINGIFY( expr ) #expr - -void removeShader( int id ); -void deleteShaderProgram( int id ); -void deleteAllShaders(); - -void setShaderVersion( const std::string& version ); - -int loadShader( const std::string& vs, const std::string& ps ); -int reloadShader( int id, const std::string& vs, const std::string& ps ); -std::string shaderString( const std::string& path ); -bool setTexture( const std::string& handle, int sampler ); -void bindShader( int id ); -void unbindShader(); - -bool setInt( const std::string& handle, int v ); -bool setBool( const std::string& handle, bool v ); -bool setVector( const std::string& handle, const arma::vec& v ); -bool setMatrix( const std::string& handle, const arma::mat& v ); -//@} - -////////////////////////////////////// -/// Texture interface -/// Example combinations of parameters: -/// { GL_RGB8, GL_BGR, GL_UNSIGNED_BYTE,3 }, //R8G8B8, -/// { GL_RGBA8, GL_BGRA, GL_UNSIGNED_BYTE,4 }, //A8R8G8B8 -/// { GL_LUMINANCE, GL_LUMINANCE, GL_UNSIGNED_BYTE,1 }, //L8, -//@{ -int createTexture(int w, int h, int glFormat=GL_RGB8, int dataFormat=GL_BGRA, int dataType=GL_UNSIGNED_BYTE ); -int createTexture(void* data, int w, int h, int glFormat=GL_RGB8, int dataFormat=GL_BGRA, int dataType=GL_UNSIGNED_BYTE ); -void bindTexture( int id, int sampler=0 ); -void unbindTexture( int sampler=0 ); -void grabFrameBuffer( int texId, int w, int h ); -//@} - -} // end gfx - - -////////////////////////////////////// -// OpenGL transformation matrix utils - -/// 3d transformations, when @affine is set to true a 4x4 matrix is created to handle homogeneous coords -//@{ -arma::mat rotX3d( double theta, bool affine=true ); -arma::mat rotY3d( double theta, bool affine=true ); -arma::mat rotZ3d( double theta, bool affine=true ); -arma::mat trans3d( const arma::vec& xyz ); -arma::mat trans3d( double x, double y, double z ); -arma::mat scaling3d( const arma::vec& xyz, bool affine=true ); -arma::mat scaling3d( double s, bool affine=true ); -arma::mat scaling3d( double x, double y, double z, bool affine=true ); -//@} - -////////////////////////////////////// -/// 2d transformations, when @affine is set to true a 3x3 matrix is created to handle homogeneous coords -//@{ -arma::mat rot2d( double theta, bool affine=true ); -arma::mat trans2d( const arma::vec& xy, bool affine=true ); -arma::mat trans2d( double x, double y, bool affine=true ); -arma::mat scaling2d( const arma::vec& xy, bool affine=true ); -arma::mat scaling2d( double s, bool affine=true ); -arma::mat scaling2d( double x, double y, bool affine=true ); -//@} diff --git a/include/gfx2.h b/include/gfx2.h new file mode 100644 index 0000000..8f72291 --- /dev/null +++ b/include/gfx2.h @@ -0,0 +1,417 @@ +/* + * gfx2.h + * + * Rendering utility structures and functions based on OpenGL 2 (no shader) + * + * Authors: Philip Abbet + */ + +#pragma once + +#define ARMA_DONT_PRINT_ERRORS +#include <armadillo> +#include <map> + +// Detect the platform +#ifdef _WIN32 + #define GFX_WINDOWS + #include <windows.h> +#elif __APPLE__ + #define GFX_OSX +#elif __linux__ || __unix__ || defined(_POSIX_VERSION) + #define GFX_LINUX +#else + #error "Unknown platform" +#endif + +// OpenGL includes +#ifdef GFX_WINDOWS + // NOT TESTED HERE + #include <windows.h> + #include <GL/glu.h> + #ifndef GL_CLAMP_TO_EDGE + #define GL_CLAMP_TO_EDGE 0x812F + #endif +#elif defined GFX_LINUX + #ifndef __glew_h__ + #define GL_GLEXT_PROTOTYPES + #include <GL/glew.h> + #include <GL/glu.h> + #include <GL/gl.h> + #include <GL/glx.h> + #endif +#elif defined GFX_OSX + #ifndef __glew_h__ + #define GL_GLEXT_PROTOTYPES + #include <GL/glew.h> + #endif + #include <OpenGL/glu.h> + #include <OpenGL/OpenGL.h> + #include <OpenGL/gl.h> + #include <OpenGL/glext.h> +#endif + + + +namespace gfx2 +{ + /**************************** UTILITY FUNCTIONS **************************/ + + //------------------------------------------------------------------------- + // Holds the sizes of the window and of the OpenGL front-buffer (they might + // be different, for instance on a 4K screen) + //------------------------------------------------------------------------- + struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } + }; + + //------------------------------------------------------------------------- + // Initialisations + //------------------------------------------------------------------------- + void init(); + + //------------------------------------------------------------------------- + // Convert radian to degrees + //------------------------------------------------------------------------- + double deg2rad(double deg); + + //------------------------------------------------------------------------- + // Returns the sinus of an angle in degrees + //------------------------------------------------------------------------- + double sin_deg(double deg); + + //------------------------------------------------------------------------- + // Returns the cosinus of an angle in degrees + //------------------------------------------------------------------------- + double cos_deg(double deg); + + //------------------------------------------------------------------------- + // Indicates if two values are close enough + //------------------------------------------------------------------------- + bool is_close(float a, float b, float epsilon = 1e-6f); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to OpenGL-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + //------------------------------------------------------------------------- + arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to OpenGL-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + //------------------------------------------------------------------------- + arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size); + + //------------------------------------------------------------------------- + // Converts some coordinates from OpenGL-space to UI-space + // + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + // UI coordinates range from (0, 0) to (win_width, win_height) + //------------------------------------------------------------------------- + arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height); + + //------------------------------------------------------------------------- + // Converts some coordinates from OpenGL-space to UI-space + // + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + // UI coordinates range from (0, 0) to (win_width, win_height) + //------------------------------------------------------------------------- + arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size); + + + /*********************** PROJECTION & VIEW MATRICES **********************/ + + //------------------------------------------------------------------------- + // Returns a perspective projection matrix + //------------------------------------------------------------------------- + arma::fmat perspective(float fovy, float aspect, float zNear, float zFar); + + // //------------------------------------------------------------------------- + // // Returns a orthographic projection matrix + // //------------------------------------------------------------------------- + // arma::fmat orthographic(float width, float height, float zNear, float zFar); + + //------------------------------------------------------------------------- + // Returns a view matrix + //------------------------------------------------------------------------- + arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, + const arma::fvec& up); + + + /**************************** TRANSFORMATIONS ****************************/ + + //------------------------------------------------------------------------- + // Holds all the transformations needed for a 3D entity + // + // Can be organised in a hierarchy, where the parent transforms affect the + // children ones + //------------------------------------------------------------------------- + struct transforms_t { + + // Constructor + transforms_t() + : parent(0) + { + position.zeros(3); + rotation.eye(4, 4); + } + + transforms_t* parent; + + arma::fvec position; + arma::fmat rotation; + }; + + //------------------------------------------------------------------------- + // Returns a rotation matrix given an axis and an angle (in radian) + //------------------------------------------------------------------------- + arma::fmat rotate(const arma::fvec& axis, float angle); + + //------------------------------------------------------------------------- + // Returns the rotation matrix to go from one direction to another one + //------------------------------------------------------------------------- + arma::fmat rotation(const arma::fvec& from, const arma::fvec& to); + + //------------------------------------------------------------------------- + // Compute the translation and rotation to apply to a list of 3D points A to + // obtain the list of 3D points B. + // + // Points are organised in columns: + // [ x0 x1 x2 ... + // y0 y1 y2 + // z0 z1 z2 ] + //------------------------------------------------------------------------- + void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, + arma::fmat &rotation, arma::fvec &translation); + + //------------------------------------------------------------------------- + // Returns the full world transformation matrix corresponding to the given + // transforms structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fmat worldTransforms(const transforms_t* transforms); + + //------------------------------------------------------------------------- + // Returns the full world position corresponding to the given transforms + // structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fvec worldPosition(const transforms_t* transforms); + + //------------------------------------------------------------------------- + // Returns the full world rotation matrix corresponding to the given + // transforms structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fmat worldRotation(const transforms_t* transforms); + + + /******************************* LIGHTNING *******************************/ + + //------------------------------------------------------------------------- + // Holds all the needed informations about a point light + //------------------------------------------------------------------------- + struct point_light_t { + transforms_t transforms; + arma::fvec color; + }; + + //------------------------------------------------------------------------- + // A list of lights + //------------------------------------------------------------------------- + typedef std::vector<point_light_t> light_list_t; + + + /********************************* MESHES ********************************/ + + //------------------------------------------------------------------------- + // Holds all the needed informations about a mesh + //------------------------------------------------------------------------- + struct model_t { + GLenum mode; + + // Vertex data + GLuint nb_vertices; + GLfloat* vertex_buffer; + GLfloat* normal_buffer; + GLfloat* uv_buffer; + + // Transforms + transforms_t transforms; + + // Material + arma::fvec ambiant_color; + arma::fvec diffuse_color; + arma::fvec specular_color; + float specular_power; + + // Other + bool lightning_enabled; + }; + + //------------------------------------------------------------------------- + // Create a rectangular mesh, colored (no lightning) + //------------------------------------------------------------------------- + model_t create_rectangle(const arma::fvec& color, float width, float height, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a square mesh, colored (no lightning) + //------------------------------------------------------------------------- + model_t create_square(const arma::fvec& color, float size, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a sphere mesh, lighted + //------------------------------------------------------------------------- + model_t create_sphere(float radius = 1.0f, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a line mesh, colored (no lightning), from a matrix containing the + // point coordinates + //------------------------------------------------------------------------- + model_t create_line(const arma::fvec& color, const arma::mat& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a line mesh, colored (no lightning), from an array containing the + // point coordinates + //------------------------------------------------------------------------- + model_t create_line(const arma::fvec& color, const std::vector<arma::vec>& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a mesh, colored (no lightning), from a matrix containing the + // vertex coordinates + //------------------------------------------------------------------------- + model_t create_mesh(const arma::fvec& color, const arma::mat& vertices, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Release the OpenGL resources used by the model + //------------------------------------------------------------------------- + void destroy(const model_t& model); + + + /******************************* RENDERING *******************************/ + + //------------------------------------------------------------------------- + // Render a mesh + //------------------------------------------------------------------------- + bool draw(const model_t& model, const light_list_t& lights); + + //------------------------------------------------------------------------- + // Render a mesh (shortcut when lights aren't used) + //------------------------------------------------------------------------- + inline bool draw(const model_t& model) + { + light_list_t lights; + return draw(model, lights); + } + + //------------------------------------------------------------------------- + // Render a rectangular mesh, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_rectangle(const arma::fvec& color, float width, float height, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a line, colored (no lightning), from a matrix containing the + // point coordinates + //------------------------------------------------------------------------- + bool draw_line(const arma::fvec& color, const arma::mat& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a line, colored (no lightning), from an array containing the + // point coordinates + //------------------------------------------------------------------------- + bool draw_line(const arma::fvec& color, const std::vector<arma::vec>& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a mesh, colored (no lightning), from a matrix containing the + // vertex coordinates + //------------------------------------------------------------------------- + bool draw_mesh(const arma::fvec& color, const arma::mat& vertices, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_gaussian(const arma::fvec& color, const arma::vec& mu, + const arma::mat& sigma, bool background = true, + bool border = true); + + //------------------------------------------------------------------------- + // Render the border of a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + inline bool draw_gaussian_border(const arma::fvec& color, const arma::vec& mu, + const arma::mat& sigma) { + + return draw_gaussian(color, mu, sigma, false, true); + } + + //------------------------------------------------------------------------- + // Render the background of a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + inline bool draw_gaussian_background(const arma::fvec& color, const arma::vec& mu, + const arma::mat& sigma) { + + return draw_gaussian(color, mu, sigma, true, false); + } + + + /****************************** RAY CASTING ******************************/ + + //------------------------------------------------------------------------- + // Represents a 3D ray (in world coordinates) + //------------------------------------------------------------------------- + struct ray_t { + arma::fvec origin; + arma::fvec direction; + }; + + ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, + const arma::fmat& view, const arma::fmat& projection, + int window_width, int window_height); + + bool intersects(const ray_t& ray, const arma::fvec& center, float radius, + arma::fvec &result); + +}; diff --git a/include/gfx3.h b/include/gfx3.h index f37d304..93ce949 100644 --- a/include/gfx3.h +++ b/include/gfx3.h @@ -14,462 +14,599 @@ // Detect the platform #ifdef _WIN32 - #define GFX_WINDOWS - #include <windows.h> + #define GFX_WINDOWS + #include <windows.h> #elif __APPLE__ - #define GFX_OSX + #define GFX_OSX #elif __linux__ || __unix__ || defined(_POSIX_VERSION) - #define GFX_LINUX + #define GFX_LINUX #else - #error "Unknown platform" + #error "Unknown platform" #endif // OpenGL includes #ifdef GFX_WINDOWS - // NOT TESTED HERE - #include <windows.h> - #include <GL/glu.h> - #ifndef GL_CLAMP_TO_EDGE - #define GL_CLAMP_TO_EDGE 0x812F - #endif + // NOT TESTED HERE + #include <windows.h> + #include <GL/glu.h> + #ifndef GL_CLAMP_TO_EDGE + #define GL_CLAMP_TO_EDGE 0x812F + #endif #elif defined GFX_LINUX - #ifndef __glew_h__ - #define GL_GLEXT_PROTOTYPES - #include <GL/glew.h> - #include <GL/glu.h> - #include <GL/gl.h> - #include <GL/glx.h> - #endif + #ifndef __glew_h__ + #define GL_GLEXT_PROTOTYPES + #include <GL/glew.h> + #include <GL/glu.h> + #include <GL/gl.h> + #include <GL/glx.h> + #endif #elif defined GFX_OSX - #ifndef __glew_h__ - #define GL_GLEXT_PROTOTYPES - #include <GL/glew.h> - #endif - #include <OpenGL/glu.h> - #include <OpenGL/OpenGL.h> - #include <OpenGL/gl.h> - #include <OpenGL/glext.h> + #ifndef __glew_h__ + #define GL_GLEXT_PROTOTYPES + #include <GL/glew.h> + #endif + #include <OpenGL/glu.h> + #include <OpenGL/OpenGL.h> + #include <OpenGL/gl.h> + #include <OpenGL/glext.h> #endif namespace gfx3 { - /**************************** UTILITY FUNCTIONS **************************/ - - //------------------------------------------------------------------------- - // Initialisations - //------------------------------------------------------------------------- - void init(); - - //------------------------------------------------------------------------- - // Convert radian to degrees - //------------------------------------------------------------------------- - double deg2rad(double deg); - - //------------------------------------------------------------------------- - // Returns the sinus of an angle in degrees - //------------------------------------------------------------------------- - double sin_deg(double deg); - - //------------------------------------------------------------------------- - // Returns the cosinus of an angle in degrees - //------------------------------------------------------------------------- - double cos_deg(double deg); - - //------------------------------------------------------------------------- - // Indicates if two values are close enough - //------------------------------------------------------------------------- - bool is_close(float a, float b, float epsilon = 1e-6f); - - //------------------------------------------------------------------------- - // Converts some coordinates from UI-space to OpenGL-space - // - // UI coordinates range from (0, 0) to (win_width, win_height) - // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to - // (fb_width / 2, -fb_height / 2) - //------------------------------------------------------------------------- - arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height); - - //------------------------------------------------------------------------- - // Converts some coordinates from OpenGL-space to UI-space - // - // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to - // (fb_width / 2, -fb_height / 2) - // UI coordinates range from (0, 0) to (win_width, win_height) - //------------------------------------------------------------------------- - arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height); - - //------------------------------------------------------------------------- - // Converts some coordinates from UI-space to shader-space - // - // UI coordinates range from (0, 0) to (win_width, win_height) - // Shader coordinates range from (sh_left, sh_top) to (sh_right, sh_bottom) - // by default: (-1, 1) to (1, -1) - //------------------------------------------------------------------------- - arma::vec ui2shader(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height, float sh_left = -1.0f, - float sh_top = 1.0f, float sh_right = 1.0f, - float sh_bottom = -1.0f); - - - /*********************** PROJECTION & VIEW MATRICES **********************/ - - //------------------------------------------------------------------------- - // Returns a perspective projection matrix - //------------------------------------------------------------------------- - arma::fmat perspective(float fovy, float aspect, float zNear, float zFar); - - //------------------------------------------------------------------------- - // Returns a orthographic projection matrix - //------------------------------------------------------------------------- - arma::fmat orthographic(float width, float height, float zNear, float zFar); - - //------------------------------------------------------------------------- - // Returns a view matrix - //------------------------------------------------------------------------- - arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, - const arma::fvec& up); - - - /**************************** TRANSFORMATIONS ****************************/ - - //------------------------------------------------------------------------- - // Holds all the transformations needed for a 3D entity - // - // Can be organised in a hierarchy, where the parent transforms affect the - // children ones - //------------------------------------------------------------------------- - struct transforms_t { - - // Constructor - transforms_t() : parent(0) {} - - transforms_t* parent; - - arma::fvec position; - arma::fmat rotation; - }; - - //------------------------------------------------------------------------- - // Returns a rotation matrix given an axis and an angle (in radian) - //------------------------------------------------------------------------- - arma::fmat rotate(const arma::fvec& axis, float angle); - - //------------------------------------------------------------------------- - // Returns the rotation matrix to go from one direction to another one - //------------------------------------------------------------------------- - arma::fmat rotation(const arma::fvec& from, const arma::fvec& to); - - //------------------------------------------------------------------------- - // Compute the translation and rotation to apply to a list of 3D points A to - // obtain the list of 3D points B. - // - // Points are organised in columns: - // [ x0 x1 x2 ... - // y0 y1 y2 - // z0 z1 z2 ] - //------------------------------------------------------------------------- - void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, - arma::fmat &rotation, arma::fvec &translation); - - //------------------------------------------------------------------------- - // Returns the full world transformation matrix corresponding to the given - // transforms structure, taking all its parent hierarchy into account - //------------------------------------------------------------------------- - arma::fmat worldTransforms(const transforms_t* transforms); - - //------------------------------------------------------------------------- - // Returns the full world position corresponding to the given transforms - // structure, taking all its parent hierarchy into account - //------------------------------------------------------------------------- - arma::fvec worldPosition(const transforms_t* transforms); - - //------------------------------------------------------------------------- - // Returns the full world rotation matrix corresponding to the given - // transforms structure, taking all its parent hierarchy into account - //------------------------------------------------------------------------- - arma::fmat worldRotation(const transforms_t* transforms); - - - /******************************** SHADERS ********************************/ - - struct shader_fmat_uniform_t { - GLint handle; - arma::fmat value; - }; - - - struct shader_fvec_uniform_t { - GLint handle; - arma::fvec value; - }; - - - struct shader_float_uniform_t { - GLint handle; - float value; - }; - - - struct shader_bool_uniform_t { - GLint handle; - bool value; - }; - - - //------------------------------------------------------------------------- - // Holds all the needed informations about a GLSL program - //------------------------------------------------------------------------- - struct shader_t { - GLuint id; - - bool use_lightning; - - // Matrices - GLint model_matrix_handle; - GLint view_matrix_handle; - GLint projection_matrix_handle; - - // Material - GLint ambiant_color_handle; // valid if lightning is used - GLint diffuse_color_handle; - GLint specular_color_handle; // valid if lightning is used - GLint specular_power_handle; // valid if lightning is used - - // Textures - GLint diffuse_texture_handle; // valid if textures are used - - // Light - GLint light_position_handle; // valid if lightning is used - GLint light_color_handle; // valid if lightning is used - GLint light_power_handle; // valid if lightning is used - - // RTT-specific - GLint backbuffer_handle; - - // Application-dependant uniforms - std::map<std::string, shader_fmat_uniform_t> fmat_uniforms; - std::map<std::string, shader_fvec_uniform_t> fvec_uniforms; - std::map<std::string, shader_float_uniform_t> float_uniforms; - std::map<std::string, shader_bool_uniform_t> bool_uniforms; - - void setUniform(const std::string& name, const arma::fmat& value); - void setUniform(const std::string& name, const arma::mat& value); - void setUniform(const std::string& name, const arma::fvec& value); - void setUniform(const std::string& name, const arma::vec& value); - void setUniform(const std::string& name, float value); - void setUniform(const std::string& name, bool value); - }; - - - //------------------------------------------------------------------------- - // Convert to string (handy to create a shader, but messes up line numbers, - // which makes it tricky with errors) - //------------------------------------------------------------------------- - #define STRINGIFY( expr ) #expr - - //------------------------------------------------------------------------- - // Load and compile a vertex and a fragment shaders into a GLSL program - //------------------------------------------------------------------------- - shader_t loadShader(const std::string& vertex_shader, - const std::string& fragment_shader, - const std::string& version = "330 core"); - - //------------------------------------------------------------------------- - // Vertex and fragment shaders for a mesh with normals and one point light - // source - //------------------------------------------------------------------------- - extern const char* VERTEX_SHADER_ONE_LIGHT; - extern const char* FRAGMENT_SHADER_ONE_LIGHT; - - //------------------------------------------------------------------------- - // Vertex and fragment shaders without any lightning - //------------------------------------------------------------------------- - extern const char* VERTEX_SHADER_COLORED; - extern const char* FRAGMENT_SHADER_COLORED; - - //------------------------------------------------------------------------- - // Vertex and fragment shaders with a texture, without any lightning - //------------------------------------------------------------------------- - extern const char* VERTEX_SHADER_TEXTURED; - extern const char* FRAGMENT_SHADER_ONE_TEXTURE; - - //------------------------------------------------------------------------- - // Vertex and fragment shaders to do render-to-texture - //------------------------------------------------------------------------- - extern const char* RTT_VERTEX_SHADER; - extern const char* RTT_FRAGMENT_SHADER_GAUSSIAN; - extern const char* RTT_FRAGMENT_SHADER_LIC; - - - /******************************* LIGHTNING *******************************/ - - //------------------------------------------------------------------------- - // Holds all the needed informations about a point light - //------------------------------------------------------------------------- - struct point_light_t { - transforms_t transforms; - arma::fvec color; - float power; - }; - - //------------------------------------------------------------------------- - // A list of lights - //------------------------------------------------------------------------- - typedef std::vector<point_light_t> light_list_t; - - - /*************************** RENDER-TO-TEXTURE ***************************/ - - struct render_to_texture_buffer_t { - GLuint framebuffer; - GLuint texture; - }; - - struct render_to_texture_t { - - // Textures - render_to_texture_buffer_t buffers[2]; - unsigned int nb_buffers; - unsigned int current_buffer; - unsigned int width; - unsigned int height; - - // Rectangular mesh - GLuint nb_vertices; - GLuint vertex_buffer; - - // Shader - shader_t const* shader; - - inline GLuint texture() const { - return buffers[current_buffer].texture; - }; - - inline GLuint previous_texture() const { - unsigned int previous_buffer = current_buffer + 1; - if (previous_buffer >= nb_buffers) - previous_buffer = 0; - - return buffers[previous_buffer].texture; - }; - }; - - //------------------------------------------------------------------------- - // Create a render-to-texture object - //------------------------------------------------------------------------- - render_to_texture_t createRTT(const shader_t& shader, unsigned int width, - unsigned int height, const arma::fvec& color); - - //------------------------------------------------------------------------- - // Render a render-to-texture object - //------------------------------------------------------------------------- - bool draw(render_to_texture_t &rtt); - - - /********************************* MESHES ********************************/ - - //------------------------------------------------------------------------- - // Holds all the needed informations about a mesh - //------------------------------------------------------------------------- - struct model_t { - GLenum mode; - - // Vertex data - GLuint nb_vertices; - GLuint vertex_buffer; - GLuint normal_buffer; - GLuint uv_buffer; - - // Transforms - transforms_t transforms; - - // Shader - shader_t const* shader; - - // Material - arma::fvec ambiant_color; - arma::fvec diffuse_color; - arma::fvec specular_color; - float specular_power; - - // Textures - GLuint diffuse_texture; - }; - - //------------------------------------------------------------------------- - // Render a mesh - //------------------------------------------------------------------------- - bool draw(const model_t& model, const arma::fmat& view, - const arma::fmat& projection, - const light_list_t& lights); - - //------------------------------------------------------------------------- - // Render a mesh (shortcut when lights aren't used by the shaders) - //------------------------------------------------------------------------- - inline bool draw(const model_t& model, const arma::fmat& view, - const arma::fmat& projection) - { - light_list_t lights; - return draw(model, view, projection, lights); - } - - //------------------------------------------------------------------------- - // Create a rectangular mesh, colored (no lightning) - //------------------------------------------------------------------------- - model_t create_rectangle(const shader_t& shader, const arma::fvec& color, - float width, float height); - - //------------------------------------------------------------------------- - // Create a square mesh, colored (no lightning) - //------------------------------------------------------------------------- - model_t create_square(const shader_t& shader, const arma::fvec& color, - float size); - - //------------------------------------------------------------------------- - // Create a sphere mesh, either colored or that can be lighted (it depends - // on the shader) - //------------------------------------------------------------------------- - model_t create_sphere(const shader_t& shader, float radius = 1.0f); - - //------------------------------------------------------------------------- - // Create a line mesh, colored (no lightning), from a matrix containing the - // point coordinates - //------------------------------------------------------------------------- - model_t create_line(const shader_t& shader, const arma::fvec& color, - const arma::mat& points); - - //------------------------------------------------------------------------- - // Create a line mesh, colored (no lightning), from an array containing the - // point coordinates - //------------------------------------------------------------------------- - model_t create_line(const shader_t& shader, const arma::fvec& color, - const std::vector<arma::vec>& points); - - //------------------------------------------------------------------------- - // Release the OpenGL resources used by the model - //------------------------------------------------------------------------- - void destroy(const model_t& model); - - - /****************************** RAY CASTING ******************************/ - - //------------------------------------------------------------------------- - // Represents a 3D ray (in world coordinates) - //------------------------------------------------------------------------- - struct ray_t { - arma::fvec origin; - arma::fvec direction; - }; - - ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, - const arma::fmat& view, const arma::fmat& projection, - int window_width, int window_height); - - bool intersects(const ray_t& ray, const arma::fvec& center, float radius, - arma::fvec &result); + /**************************** UTILITY FUNCTIONS **************************/ + + //------------------------------------------------------------------------- + // Holds the sizes of the window and of the OpenGL front-buffer (they might + // be different, for instance on a 4K screen) + //------------------------------------------------------------------------- + struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } + }; + + //------------------------------------------------------------------------- + // Initialisations + //------------------------------------------------------------------------- + void init(); + + //------------------------------------------------------------------------- + // Convert radian to degrees + //------------------------------------------------------------------------- + double deg2rad(double deg); + + //------------------------------------------------------------------------- + // Returns the sinus of an angle in degrees + //------------------------------------------------------------------------- + double sin_deg(double deg); + + //------------------------------------------------------------------------- + // Returns the cosinus of an angle in degrees + //------------------------------------------------------------------------- + double cos_deg(double deg); + + //------------------------------------------------------------------------- + // Indicates if two values are close enough + //------------------------------------------------------------------------- + bool is_close(float a, float b, float epsilon = 1e-6f); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to OpenGL-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + //------------------------------------------------------------------------- + arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to OpenGL-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + //------------------------------------------------------------------------- + arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size); + + //------------------------------------------------------------------------- + // Converts some coordinates from OpenGL-space to UI-space + // + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + // UI coordinates range from (0, 0) to (win_width, win_height) + //------------------------------------------------------------------------- + arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height); + + //------------------------------------------------------------------------- + // Converts some coordinates from OpenGL-space to UI-space + // + // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to + // (fb_width / 2, -fb_height / 2) + // UI coordinates range from (0, 0) to (win_width, win_height) + //------------------------------------------------------------------------- + arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to shader-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // Shader coordinates range from (sh_left, sh_top) to (sh_right, sh_bottom) + // by default: (-1, 1) to (1, -1) + //------------------------------------------------------------------------- + arma::vec ui2shader(const arma::vec& coords, int win_width, int win_height, + int fb_width, int fb_height, float sh_left = -1.0f, + float sh_top = 1.0f, float sh_right = 1.0f, + float sh_bottom = -1.0f); + + //------------------------------------------------------------------------- + // Converts some coordinates from UI-space to shader-space + // + // UI coordinates range from (0, 0) to (win_width, win_height) + // Shader coordinates range from (sh_left, sh_top) to (sh_right, sh_bottom) + // by default: (-1, 1) to (1, -1) + //------------------------------------------------------------------------- + arma::vec ui2shader(const arma::vec& coords, const window_size_t& window_size, + float sh_left = -1.0f, float sh_top = 1.0f, + float sh_right = 1.0f, float sh_bottom = -1.0f); + + + /*********************** PROJECTION & VIEW MATRICES **********************/ + + //------------------------------------------------------------------------- + // Returns a perspective projection matrix + //------------------------------------------------------------------------- + arma::fmat perspective(float fovy, float aspect, float zNear, float zFar); + + //------------------------------------------------------------------------- + // Returns a orthographic projection matrix + //------------------------------------------------------------------------- + arma::fmat orthographic(float width, float height, float zNear, float zFar); + + //------------------------------------------------------------------------- + // Returns a view matrix + //------------------------------------------------------------------------- + arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, + const arma::fvec& up); + + + /**************************** TRANSFORMATIONS ****************************/ + + //------------------------------------------------------------------------- + // Holds all the transformations needed for a 3D entity + // + // Can be organised in a hierarchy, where the parent transforms affect the + // children ones + //------------------------------------------------------------------------- + struct transforms_t { + + // Constructor + transforms_t() + : parent(0) + { + position.zeros(3); + rotation.eye(4, 4); + } + + transforms_t* parent; + + arma::fvec position; + arma::fmat rotation; + }; + + //------------------------------------------------------------------------- + // Returns a rotation matrix given an axis and an angle (in radian) + //------------------------------------------------------------------------- + arma::fmat rotate(const arma::fvec& axis, float angle); + + //------------------------------------------------------------------------- + // Returns the rotation matrix to go from one direction to another one + //------------------------------------------------------------------------- + arma::fmat rotation(const arma::fvec& from, const arma::fvec& to); + + //------------------------------------------------------------------------- + // Compute the translation and rotation to apply to a list of 3D points A to + // obtain the list of 3D points B. + // + // Points are organised in columns: + // [ x0 x1 x2 ... + // y0 y1 y2 + // z0 z1 z2 ] + //------------------------------------------------------------------------- + void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, + arma::fmat &rotation, arma::fvec &translation); + + //------------------------------------------------------------------------- + // Returns the full world transformation matrix corresponding to the given + // transforms structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fmat worldTransforms(const transforms_t* transforms); + + //------------------------------------------------------------------------- + // Returns the full world position corresponding to the given transforms + // structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fvec worldPosition(const transforms_t* transforms); + + //------------------------------------------------------------------------- + // Returns the full world rotation matrix corresponding to the given + // transforms structure, taking all its parent hierarchy into account + //------------------------------------------------------------------------- + arma::fmat worldRotation(const transforms_t* transforms); + + + /******************************** SHADERS ********************************/ + + struct shader_fmat_uniform_t { + GLint handle; + arma::fmat value; + }; + + + struct shader_fvec_uniform_t { + GLint handle; + arma::fvec value; + }; + + + struct shader_float_uniform_t { + GLint handle; + float value; + }; + + + struct shader_bool_uniform_t { + GLint handle; + bool value; + }; + + + //------------------------------------------------------------------------- + // Holds all the needed informations about a GLSL program + //------------------------------------------------------------------------- + struct shader_t { + GLuint id; + + bool use_lightning; + + // Matrices + GLint model_matrix_handle; + GLint view_matrix_handle; + GLint projection_matrix_handle; + + // Material + GLint ambiant_color_handle; // valid if lightning is used + GLint diffuse_color_handle; + GLint specular_color_handle; // valid if lightning is used + GLint specular_power_handle; // valid if lightning is used + + // Textures + GLint diffuse_texture_handle; // valid if textures are used + + // Light + GLint light_position_handle; // valid if lightning is used + GLint light_color_handle; // valid if lightning is used + GLint light_power_handle; // valid if lightning is used + + // RTT-specific + GLint backbuffer_handle; + + // Application-dependant uniforms + std::map<std::string, shader_fmat_uniform_t> fmat_uniforms; + std::map<std::string, shader_fvec_uniform_t> fvec_uniforms; + std::map<std::string, shader_float_uniform_t> float_uniforms; + std::map<std::string, shader_bool_uniform_t> bool_uniforms; + + void setUniform(const std::string& name, const arma::fmat& value); + void setUniform(const std::string& name, const arma::mat& value); + void setUniform(const std::string& name, const arma::fvec& value); + void setUniform(const std::string& name, const arma::vec& value); + void setUniform(const std::string& name, float value); + void setUniform(const std::string& name, bool value); + }; + + + //------------------------------------------------------------------------- + // Convert to string (handy to create a shader, but messes up line numbers, + // which makes it tricky with errors) + //------------------------------------------------------------------------- + #define STRINGIFY( expr ) #expr + + //------------------------------------------------------------------------- + // Load and compile a vertex and a fragment shaders into a GLSL program + //------------------------------------------------------------------------- + shader_t loadShader(const std::string& vertex_shader, + const std::string& fragment_shader, + const std::string& version = "330 core"); + + //------------------------------------------------------------------------- + // Vertex and fragment shaders for a mesh with normals and one point light + // source + //------------------------------------------------------------------------- + extern const char* VERTEX_SHADER_ONE_LIGHT; + extern const char* FRAGMENT_SHADER_ONE_LIGHT; + + //------------------------------------------------------------------------- + // Vertex and fragment shaders without any lightning + //------------------------------------------------------------------------- + extern const char* VERTEX_SHADER_COLORED; + extern const char* FRAGMENT_SHADER_COLORED; + + //------------------------------------------------------------------------- + // Vertex and fragment shaders with a texture, without any lightning + //------------------------------------------------------------------------- + extern const char* VERTEX_SHADER_TEXTURED; + extern const char* FRAGMENT_SHADER_ONE_TEXTURE; + extern const char* FRAGMENT_SHADER_GAUSSIAN; + + //------------------------------------------------------------------------- + // Vertex and fragment shaders to do render-to-texture + //------------------------------------------------------------------------- + extern const char* RTT_VERTEX_SHADER; + extern const char* RTT_FRAGMENT_SHADER_GAUSSIAN; + extern const char* RTT_FRAGMENT_SHADER_LIC; + + + /******************************* LIGHTNING *******************************/ + + //------------------------------------------------------------------------- + // Holds all the needed informations about a point light + //------------------------------------------------------------------------- + struct point_light_t { + transforms_t transforms; + arma::fvec color; + float power; + }; + + //------------------------------------------------------------------------- + // A list of lights + //------------------------------------------------------------------------- + typedef std::vector<point_light_t> light_list_t; + + + /*************************** RENDER-TO-TEXTURE ***************************/ + + struct render_to_texture_buffer_t { + GLuint framebuffer; + GLuint texture; + }; + + struct render_to_texture_t { + + // Textures + render_to_texture_buffer_t buffers[2]; + unsigned int nb_buffers; + unsigned int current_buffer; + unsigned int width; + unsigned int height; + + // Rectangular mesh + GLuint nb_vertices; + GLuint vertex_buffer; + + // Shader + shader_t const* shader; + + inline GLuint texture() const { + return buffers[current_buffer].texture; + }; + + inline GLuint previous_texture() const { + unsigned int previous_buffer = current_buffer + 1; + if (previous_buffer >= nb_buffers) + previous_buffer = 0; + + return buffers[previous_buffer].texture; + }; + }; + + //------------------------------------------------------------------------- + // Create a render-to-texture object + //------------------------------------------------------------------------- + render_to_texture_t createRTT(const shader_t& shader, unsigned int width, + unsigned int height, const arma::fvec& color); + + //------------------------------------------------------------------------- + // Render a render-to-texture object + //------------------------------------------------------------------------- + bool draw(render_to_texture_t &rtt); + + + /********************************* MESHES ********************************/ + + //------------------------------------------------------------------------- + // Holds all the needed informations about a mesh + //------------------------------------------------------------------------- + struct model_t { + GLenum mode; + + // Vertex data + GLuint nb_vertices; + GLuint vertex_buffer; + GLuint normal_buffer; + GLuint uv_buffer; + + // Transforms + transforms_t transforms; + + // Shader + shader_t const* shader; + + // Material + arma::fvec ambiant_color; + arma::fvec diffuse_color; + arma::fvec specular_color; + float specular_power; + + // Textures + GLuint diffuse_texture; + }; + + //------------------------------------------------------------------------- + // Create a rectangular mesh, colored (no lightning) + //------------------------------------------------------------------------- + model_t create_rectangle(const shader_t& shader, const arma::fvec& color, + float width, float height, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a square mesh, colored (no lightning) + //------------------------------------------------------------------------- + model_t create_square(const shader_t& shader, const arma::fvec& color, float size, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a sphere mesh, either colored or that can be lighted (it depends + // on the shader) + //------------------------------------------------------------------------- + model_t create_sphere(const shader_t& shader, float radius = 1.0f, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a line mesh, colored (no lightning), from a matrix containing the + // point coordinates + //------------------------------------------------------------------------- + model_t create_line(const shader_t& shader, const arma::fvec& color, + const arma::mat& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a line mesh, colored (no lightning), from an array containing the + // point coordinates + //------------------------------------------------------------------------- + model_t create_line(const shader_t& shader, const arma::fvec& color, + const std::vector<arma::vec>& points, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Create a mesh, colored (no lightning), from a matrix containing the + // vertex coordinates + //------------------------------------------------------------------------- + model_t create_mesh(const shader_t& shader, const arma::fvec& color, + const arma::mat& vertices, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4), + transforms_t* parent_transforms = 0); + + //------------------------------------------------------------------------- + // Release the OpenGL resources used by the model + //------------------------------------------------------------------------- + void destroy(const model_t& model); + + + /******************************* RENDERING *******************************/ + + //------------------------------------------------------------------------- + // Render a mesh + //------------------------------------------------------------------------- + bool draw(const model_t& model, const arma::fmat& view, + const arma::fmat& projection, + const light_list_t& lights); + + //------------------------------------------------------------------------- + // Render a mesh (shortcut when lights aren't used by the shaders) + //------------------------------------------------------------------------- + inline bool draw(const model_t& model, const arma::fmat& view, + const arma::fmat& projection) + { + light_list_t lights; + return draw(model, view, projection, lights); + } + + //------------------------------------------------------------------------- + // Render a rectangular mesh, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_rectangle(const shader_t& shader, const arma::fvec& color, + float width, float height, const arma::fmat& view, + const arma::fmat& projection, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a line, colored (no lightning), from a matrix containing the + // point coordinates + //------------------------------------------------------------------------- + bool draw_line(const shader_t& shader, const arma::fvec& color, + const arma::mat& points, const arma::fmat& view, + const arma::fmat& projection, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a line, colored (no lightning), from an array containing the + // point coordinates + //------------------------------------------------------------------------- + bool draw_line(const shader_t& shader, const arma::fvec& color, + const std::vector<arma::vec>& points, const arma::fmat& view, + const arma::fmat& projection, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a mesh, colored (no lightning), from a matrix containing the + // vertex coordinates + //------------------------------------------------------------------------- + bool draw_mesh(const shader_t& shader, const arma::fvec& color, + const arma::mat& vertices,const arma::fmat& view, + const arma::fmat& projection, + const arma::fvec& position = arma::zeros<arma::fvec>(3), + const arma::fmat& rotation = arma::eye<arma::fmat>(4, 4)); + + //------------------------------------------------------------------------- + // Render a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_gaussian(shader_t* shader, const arma::fvec& color, + const arma::vec& mu, const arma::mat& sigma, + const arma::fmat& view, const arma::fmat& projection, + float viewport_width, float viewport_height); + + //------------------------------------------------------------------------- + // Render the border of a gaussian, colored (no lightning) + //------------------------------------------------------------------------- + bool draw_gaussian_border(shader_t* shader, const arma::fvec& color, + const arma::vec& mu, const arma::mat& sigma, + const arma::fmat& view, + const arma::fmat& projection, + float viewport_width, float viewport_height); + + + /****************************** RAY CASTING ******************************/ + + //------------------------------------------------------------------------- + // Represents a 3D ray (in world coordinates) + //------------------------------------------------------------------------- + struct ray_t { + arma::fvec origin; + arma::fvec direction; + }; + + ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, + const arma::fmat& view, const arma::fmat& projection, + int window_width, int window_height); + + bool intersects(const ray_t& ray, const arma::fvec& center, float radius, + arma::fvec &result); }; diff --git a/include/gfx_ui.h b/include/gfx_ui.h index 470b0a5..2ca400e 100644 --- a/include/gfx_ui.h +++ b/include/gfx_ui.h @@ -9,9 +9,9 @@ -- `. : : / gfx_ui -- `. :.,' A immediate mode 2d graphics manipulation UI -- `-.________,-' Built on top of IMGUI - -- © Daniel Berio + -- © Daniel Berio -- http://www.enist.org - -- drand48@gmail.com + -- drand48@gmail.com -- -------------------------------------------------------------------- ********************************************************************/ @@ -76,6 +76,7 @@ namespace ui hoverColor = 0xff0000ff; selectedColor = 0xff0044ff; color=0xff666666; + textColor=0xff333333; } float rounding; @@ -84,6 +85,7 @@ namespace ui ImU32 hoverColor; ImU32 selectedColor; ImU32 color; + ImU32 textColor; }; extern Config config; @@ -104,13 +106,12 @@ namespace ui void begin( const std::string& name="gfx_ui" ); void end(); - void textColor( ImVec4 clr ); - void text( ImVec2 pos, const std::string& str ); - void textf( ImVec2 pos, const char * format, ... ); - /// Will return true if the previous widget call has caught an interaction bool modified(); + bool modifierShift(); + bool modifierAlt(); + /// Dragger widget ImVec2 dragger( int index, ImVec2 pos, bool selected=false, float size=-1. ); @@ -118,7 +119,10 @@ namespace ui void highlightDragger( const ImVec2& pos, float size=-1. ); /// Draw a line from a to b - void line( const ImVec2& a, const ImVec2& b ); + void line( const ImVec2& a, const ImVec2& b, ImColor clr=ImColor(ImVec4(-1,-1,-1,1)) ); + + // Draw text string + void text( ImVec2 pos, const std::string& str, ImColor clr=ImColor(ImVec4(-1,-1,-1,1)) ); /// Angle and length handle widget ImVec2 lengthHandle( int index, ImVec2 thetaLen, float startTheta, const ImVec2& pos, const ImVec2& minThetaLen, const ImVec2& maxThetaLen, bool selected=false ); @@ -127,7 +131,7 @@ namespace ui float handle( int index, float ang, const ImVec2& pos, float length, float startTheta=0.0f, float minTheta=0.0f, float maxTheta=0.0f, bool selected=false ); /// Simple affine transform widget (two axes, centered) - Trans2d affineSimple( int index, Trans2d m, bool selected=false ); + Trans2d affineSimple( int index, Trans2d m, bool selected=false, float scale=1. ); /// Creates a draggable rect for selection, see demo() for example usage Rect selector(); diff --git a/include/imconfig.h b/include/imconfig.h index 9ef94f7..ad8b248 100644 --- a/include/imconfig.h +++ b/include/imconfig.h @@ -1,7 +1,12 @@ //----------------------------------------------------------------------------- -// USER IMPLEMENTATION -// This file contains compile-time options for ImGui. -// Other options (memory allocation overrides, callbacks, etc.) can be set at runtime via the ImGuiIO structure - ImGui::GetIO(). +// COMPILE-TIME OPTIONS FOR DEAR IMGUI +// Runtime options (clipboard callbacks, enabling various features, etc.) can generally be set via the ImGuiIO structure. +// You can use ImGui::SetAllocatorFunctions() before calling ImGui::CreateContext() to rewire memory allocation functions. +//----------------------------------------------------------------------------- +// A) You may edit imconfig.h (and not overwrite it when updating imgui, or maintain a patch/branch with your modifications to imconfig.h) +// B) or add configuration directives in your own file and compile with #define IMGUI_USER_CONFIG "myfilename.h" +// C) Many compile-time options have an effect on data structures. They need defined consistently _everywhere_ imgui.h is included, +// not only for the imgui*.cpp compilation units. Defining those options in imconfig.h will ensure they correctly get used everywhere. //----------------------------------------------------------------------------- #pragma once @@ -14,27 +19,35 @@ //#define IMGUI_API __declspec( dllexport ) //#define IMGUI_API __declspec( dllimport ) -//---- Include imgui_user.h at the end of imgui.h -//#define IMGUI_INCLUDE_IMGUI_USER_H +//---- Don't define obsolete functions/enums names. Consider enabling from time to time after updating to avoid using soon-to-be obsolete function/names +//#define IMGUI_DISABLE_OBSOLETE_FUNCTIONS -//---- Don't implement default handlers for Windows (so as not to link with OpenClipboard() and others Win32 functions) -//#define IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCS -//#define IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCS +//---- Don't implement default handlers for Windows (so as not to link with certain functions) +//#define IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCTIONS // Don't use and link with OpenClipboard/GetClipboardData/CloseClipboard etc. +//#define IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCTIONS // Don't use and link with ImmGetContext/ImmSetCompositionWindow. -//---- Don't implement help and test window functionality (ShowUserGuide()/ShowStyleEditor()/ShowTestWindow() methods will be empty) -//#define IMGUI_DISABLE_TEST_WINDOWS +//---- Don't implement demo windows functionality (ShowDemoWindow()/ShowStyleEditor()/ShowUserGuide() methods will be empty) +//---- It is very strongly recommended to NOT disable the demo windows during development. Please read the comments in imgui_demo.cpp. +//#define IMGUI_DISABLE_DEMO_WINDOWS -//---- Don't define obsolete functions names -//#define IMGUI_DISABLE_OBSOLETE_FUNCTIONS +//---- Don't implement ImFormatString(), ImFormatStringV() so you can reimplement them yourself. +//#define IMGUI_DISABLE_FORMAT_STRING_FUNCTIONS -//---- Pack colors to BGRA instead of RGBA (remove need to post process vertex buffer in back ends) +//---- Include imgui_user.h at the end of imgui.h as a convenience +//#define IMGUI_INCLUDE_IMGUI_USER_H + +//---- Pack colors to BGRA8 instead of RGBA8 (if you needed to convert from one to another anyway) //#define IMGUI_USE_BGRA_PACKED_COLOR -//---- Implement STB libraries in a namespace to avoid conflicts -//#define IMGUI_STB_NAMESPACE ImGuiStb +//---- Avoid multiple STB libraries implementations, or redefine path/filenames to prioritize another version +// By default the embedded implementations are declared static and not available outside of imgui cpp files. +//#define IMGUI_STB_TRUETYPE_FILENAME "my_folder/stb_truetype.h" +//#define IMGUI_STB_RECT_PACK_FILENAME "my_folder/stb_rect_pack.h" +//#define IMGUI_DISABLE_STB_TRUETYPE_IMPLEMENTATION +//#define IMGUI_DISABLE_STB_RECT_PACK_IMPLEMENTATION //---- Define constructor and implicit cast operators to convert back<>forth from your math types and ImVec2/ImVec4. -// Does not work with columns yet... +// This will be inlined as part of ImVec2 and ImVec4 class declarations. #define IM_VEC2_CLASS_EXTRA \ ImVec2(const arma::vec& f) { x = f[0]; y = f[1]; } \ ImVec2(const arma::subview_col<double>& f) { x = f[0]; y = f[1]; }\ @@ -47,12 +60,13 @@ operator arma::vec() const { return arma::vec({x,y,z,w}); } \ ImVec4& operator = (const arma::vec& v) { x = v.at(0); y = v.at(1); z = v.at(2); w = v.at(3); return *this; } +//---- Use 32-bit vertex indices (default is 16-bit) to allow meshes with more than 64K vertices. Render function needs to support it. +//#define ImDrawIdx unsigned int + //---- Tip: You can add extra functions within the ImGui:: namespace, here or in your own headers files. -//---- e.g. create variants of the ImGui::Value() helper for your low-level math types, or your own widgets/helpers. /* namespace ImGui { - void Value(const char* prefix, const MyMatrix44& v, const char* float_format = NULL); + void MyFunction(const char* name, const MyMatrix44& v); } */ - diff --git a/include/imgui.h b/include/imgui.h index 7ef8bd2..d1174bd 100644 --- a/include/imgui.h +++ b/include/imgui.h @@ -1,22 +1,27 @@ -// dear imgui, v1.50 WIP +// dear imgui, v1.60 // (headers) // See imgui.cpp file for documentation. -// See ImGui::ShowTestWindow() in imgui_demo.cpp for demo code. +// Call and read ImGui::ShowDemoWindow() in imgui_demo.cpp for demo code. // Read 'Programmer guide' in imgui.cpp for notes on how to setup ImGui in your codebase. // Get latest version at https://github.com/ocornut/imgui #pragma once +// Configuration file (edit imconfig.h or define IMGUI_USER_CONFIG to set your own filename) +#ifdef IMGUI_USER_CONFIG +#include IMGUI_USER_CONFIG +#endif #if !defined(IMGUI_DISABLE_INCLUDE_IMCONFIG_H) || defined(IMGUI_INCLUDE_IMCONFIG_H) -#include "imconfig.h" // User-editable configuration file +#include "imconfig.h" #endif + #include <float.h> // FLT_MAX #include <stdarg.h> // va_list #include <stddef.h> // ptrdiff_t, NULL #include <string.h> // memset, memmove, memcpy, strlen, strchr, strcpy, strcmp -#define IMGUI_VERSION "1.50 WIP" +#define IMGUI_VERSION "1.60" // Define attributes of all API symbols declarations, e.g. for DLL under Windows. #ifndef IMGUI_API @@ -29,12 +34,16 @@ #define IM_ASSERT(_EXPR) assert(_EXPR) #endif -// Some compilers support applying printf-style warnings to user functions. +// Helpers #if defined(__clang__) || defined(__GNUC__) -#define IM_PRINTFARGS(FMT) __attribute__((format(printf, FMT, (FMT+1)))) +#define IM_FMTARGS(FMT) __attribute__((format(printf, FMT, FMT+1))) // Apply printf-style warnings to user functions. +#define IM_FMTLIST(FMT) __attribute__((format(printf, FMT, 0))) #else -#define IM_PRINTFARGS(FMT) +#define IM_FMTARGS(FMT) +#define IM_FMTLIST(FMT) #endif +#define IM_ARRAYSIZE(_ARR) ((int)(sizeof(_ARR)/sizeof(*_ARR))) // Size of a static C-style array. Don't use on pointers! +#define IM_OFFSETOF(_TYPE,_MEMBER) ((size_t)&(((_TYPE*)0)->_MEMBER)) // Offset of _MEMBER within _TYPE. Standardized as offsetof() in modern C++. #if defined(__clang__) #pragma clang diagnostic push @@ -46,9 +55,10 @@ struct ImDrawChannel; // Temporary storage for outputting drawing struct ImDrawCmd; // A single draw command within a parent ImDrawList (generally maps to 1 GPU draw call) struct ImDrawData; // All draw command lists required to render the frame struct ImDrawList; // A single draw command list (generally one per window) +struct ImDrawListSharedData; // Data shared among multiple draw lists (typically owned by parent ImGui context, but you may create one yourself) struct ImDrawVert; // A single vertex (20 bytes by default, override layout with IMGUI_OVERRIDE_DRAWVERT_STRUCT_LAYOUT) struct ImFont; // Runtime data for a single font within a parent ImFontAtlas -struct ImFontAtlas; // Runtime data for multiple fonts, bake multiple fonts into a single texture, TTF font loader +struct ImFontAtlas; // Runtime data for multiple fonts, bake multiple fonts into a single texture, TTF/OTF font loader struct ImFontConfig; // Configuration data when adding a font or merging fonts struct ImColor; // Helper functions to create a color that can be converted to either u32 or float4 struct ImGuiIO; // Main configuration and I/O between your application and ImGui @@ -58,37 +68,55 @@ struct ImGuiStyle; // Runtime data for styling/colors struct ImGuiTextFilter; // Parse and apply text filters. In format "aaaaa[,bbbb][,ccccc]" struct ImGuiTextBuffer; // Text buffer for logging/accumulating text struct ImGuiTextEditCallbackData; // Shared state of ImGui::InputText() when using custom ImGuiTextEditCallback (rare/advanced use) -struct ImGuiSizeConstraintCallbackData;// Structure used to constraint window size in custom ways when using custom ImGuiSizeConstraintCallback (rare/advanced use) +struct ImGuiSizeCallbackData; // Structure used to constraint window size in custom ways when using custom ImGuiSizeCallback (rare/advanced use) struct ImGuiListClipper; // Helper to manually clip large list of items +struct ImGuiPayload; // User data payload for drag and drop operations struct ImGuiContext; // ImGui context (opaque) -// Typedefs and Enumerations (declared as int for compatibility and to not pollute the top of this file) +#ifndef ImTextureID +typedef void* ImTextureID; // User data to identify a texture (this is whatever to you want it to be! read the FAQ about ImTextureID in imgui.cpp) +#endif + +// Typedefs and Enumerations (declared as int for compatibility with old C++ and to not pollute the top of this file) typedef unsigned int ImU32; // 32-bit unsigned integer (typically used to store packed colors) -typedef unsigned int ImGuiID; // unique ID used by widgets (typically hashed from a stack of string) -typedef unsigned short ImWchar; // character for keyboard input/display -typedef void* ImTextureID; // user data to identify a texture (this is whatever to you want it to be! read the FAQ about ImTextureID in imgui.cpp) -typedef int ImGuiCol; // a color identifier for styling // enum ImGuiCol_ -typedef int ImGuiStyleVar; // a variable identifier for styling // enum ImGuiStyleVar_ -typedef int ImGuiKey; // a key identifier (ImGui-side enum) // enum ImGuiKey_ -typedef int ImGuiColorEditMode; // color edit mode for ColorEdit*() // enum ImGuiColorEditMode_ -typedef int ImGuiMouseCursor; // a mouse cursor identifier // enum ImGuiMouseCursor_ -typedef int ImGuiWindowFlags; // window flags for Begin*() // enum ImGuiWindowFlags_ -typedef int ImGuiSetCond; // condition flags for Set*() // enum ImGuiSetCond_ -typedef int ImGuiInputTextFlags; // flags for InputText*() // enum ImGuiInputTextFlags_ -typedef int ImGuiSelectableFlags; // flags for Selectable() // enum ImGuiSelectableFlags_ -typedef int ImGuiTreeNodeFlags; // flags for TreeNode*(), Collapsing*() // enum ImGuiTreeNodeFlags_ +typedef unsigned int ImGuiID; // Unique ID used by widgets (typically hashed from a stack of string) +typedef unsigned short ImWchar; // Character for keyboard input/display +typedef int ImGuiCol; // enum: a color identifier for styling // enum ImGuiCol_ +typedef int ImGuiDir; // enum: a cardinal direction // enum ImGuiDir_ +typedef int ImGuiCond; // enum: a condition for Set*() // enum ImGuiCond_ +typedef int ImGuiKey; // enum: a key identifier (ImGui-side enum) // enum ImGuiKey_ +typedef int ImGuiNavInput; // enum: an input identifier for navigation // enum ImGuiNavInput_ +typedef int ImGuiMouseCursor; // enum: a mouse cursor identifier // enum ImGuiMouseCursor_ +typedef int ImGuiStyleVar; // enum: a variable identifier for styling // enum ImGuiStyleVar_ +typedef int ImDrawCornerFlags; // flags: for ImDrawList::AddRect*() etc. // enum ImDrawCornerFlags_ +typedef int ImDrawListFlags; // flags: for ImDrawList // enum ImDrawListFlags_ +typedef int ImFontAtlasFlags; // flags: for ImFontAtlas // enum ImFontAtlasFlags_ +typedef int ImGuiBackendFlags; // flags: for io.BackendFlags // enum ImGuiBackendFlags_ +typedef int ImGuiColorEditFlags; // flags: for ColorEdit*(), ColorPicker*() // enum ImGuiColorEditFlags_ +typedef int ImGuiColumnsFlags; // flags: for *Columns*() // enum ImGuiColumnsFlags_ +typedef int ImGuiConfigFlags; // flags: for io.ConfigFlags // enum ImGuiConfigFlags_ +typedef int ImGuiDragDropFlags; // flags: for *DragDrop*() // enum ImGuiDragDropFlags_ +typedef int ImGuiComboFlags; // flags: for BeginCombo() // enum ImGuiComboFlags_ +typedef int ImGuiFocusedFlags; // flags: for IsWindowFocused() // enum ImGuiFocusedFlags_ +typedef int ImGuiHoveredFlags; // flags: for IsItemHovered() etc. // enum ImGuiHoveredFlags_ +typedef int ImGuiInputTextFlags; // flags: for InputText*() // enum ImGuiInputTextFlags_ +typedef int ImGuiSelectableFlags; // flags: for Selectable() // enum ImGuiSelectableFlags_ +typedef int ImGuiTreeNodeFlags; // flags: for TreeNode*(),CollapsingHeader()// enum ImGuiTreeNodeFlags_ +typedef int ImGuiWindowFlags; // flags: for Begin*() // enum ImGuiWindowFlags_ typedef int (*ImGuiTextEditCallback)(ImGuiTextEditCallbackData *data); -typedef void (*ImGuiSizeConstraintCallback)(ImGuiSizeConstraintCallbackData* data); - -// Others helpers at bottom of the file: -// class ImVector<> // Lightweight std::vector like class. -// IMGUI_ONCE_UPON_A_FRAME // Execute a block of code once per frame only (convenient for creating UI within deep-nested code that runs multiple times) +typedef void (*ImGuiSizeCallback)(ImGuiSizeCallbackData* data); +#if defined(_MSC_VER) && !defined(__clang__) +typedef unsigned __int64 ImU64; // 64-bit unsigned integer +#else +typedef unsigned long long ImU64; // 64-bit unsigned integer +#endif struct ImVec2 { float x, y; ImVec2() { x = y = 0.0f; } ImVec2(float _x, float _y) { x = _x; y = _y; } + float operator[] (size_t idx) const { IM_ASSERT(idx <= 1); return (&x)[idx]; } // We very rarely use this [] operator, the assert overhead is fine. #ifdef IM_VEC2_CLASS_EXTRA // Define constructor and implicit cast operators in imconfig.h to convert back<>forth from your math types and ImVec2. IM_VEC2_CLASS_EXTRA #endif @@ -108,178 +136,205 @@ struct ImVec4 // In a namespace so that user can add extra functions in a separate file (e.g. Value() helpers for your vector or common types) namespace ImGui { + // Context creation and access + // All contexts share a same ImFontAtlas by default. If you want different font atlas, you can new() them and overwrite the GetIO().Fonts variable of an ImGui context. + // All those functions are not reliant on the current context. + IMGUI_API ImGuiContext* CreateContext(ImFontAtlas* shared_font_atlas = NULL); + IMGUI_API void DestroyContext(ImGuiContext* ctx = NULL); // NULL = destroy current context + IMGUI_API ImGuiContext* GetCurrentContext(); + IMGUI_API void SetCurrentContext(ImGuiContext* ctx); + // Main IMGUI_API ImGuiIO& GetIO(); IMGUI_API ImGuiStyle& GetStyle(); - IMGUI_API ImDrawData* GetDrawData(); // same value as passed to your io.RenderDrawListsFn() function. valid after Render() and until the next call to NewFrame() - IMGUI_API void NewFrame(); // start a new ImGui frame, you can submit any command from this point until NewFrame()/Render(). - IMGUI_API void Render(); // ends the ImGui frame, finalize rendering data, then call your io.RenderDrawListsFn() function if set. - IMGUI_API void Shutdown(); - IMGUI_API void ShowUserGuide(); // help block - IMGUI_API void ShowStyleEditor(ImGuiStyle* ref = NULL); // style editor block. you can pass in a reference ImGuiStyle structure to compare to, revert to and save to (else it uses the default style) - IMGUI_API void ShowTestWindow(bool* p_open = NULL); // test window demonstrating ImGui features - IMGUI_API void ShowMetricsWindow(bool* p_open = NULL); // metrics window for debugging ImGui - - // Window - IMGUI_API bool Begin(const char* name, bool* p_open = NULL, ImGuiWindowFlags flags = 0); // push window to the stack and start appending to it. see .cpp for details. return false when window is collapsed, so you can early out in your code. 'bool* p_open' creates a widget on the upper-right to close the window (which sets your bool to false). - IMGUI_API bool Begin(const char* name, bool* p_open, const ImVec2& size_on_first_use, float bg_alpha = -1.0f, ImGuiWindowFlags flags = 0); // OBSOLETE. this is the older/longer API. the extra parameters aren't very relevant. call SetNextWindowSize() instead if you want to set a window size. For regular windows, 'size_on_first_use' only applies to the first time EVER the window is created and probably not what you want! might obsolete this API eventually. - IMGUI_API void End(); // finish appending to current window, pop it off the window stack. - IMGUI_API bool BeginChild(const char* str_id, const ImVec2& size = ImVec2(0,0), bool border = false, ImGuiWindowFlags extra_flags = 0); // begin a scrolling region. size==0.0f: use remaining window size, size<0.0f: use remaining window size minus abs(size). size>0.0f: fixed size. each axis can use a different mode, e.g. ImVec2(0,400). - IMGUI_API bool BeginChild(ImGuiID id, const ImVec2& size = ImVec2(0,0), bool border = false, ImGuiWindowFlags extra_flags = 0); // " + IMGUI_API void NewFrame(); // start a new ImGui frame, you can submit any command from this point until Render()/EndFrame(). + IMGUI_API void Render(); // ends the ImGui frame, finalize the draw data. (Obsolete: optionally call io.RenderDrawListsFn if set. Nowadays, prefer calling your render function yourself.) + IMGUI_API ImDrawData* GetDrawData(); // valid after Render() and until the next call to NewFrame(). this is what you have to render. (Obsolete: this used to be passed to your io.RenderDrawListsFn() function.) + IMGUI_API void EndFrame(); // ends the ImGui frame. automatically called by Render(), so most likely don't need to ever call that yourself directly. If you don't need to render you may call EndFrame() but you'll have wasted CPU already. If you don't need to render, better to not create any imgui windows instead! + + // Demo, Debug, Information + IMGUI_API void ShowDemoWindow(bool* p_open = NULL); // create demo/test window (previously called ShowTestWindow). demonstrate most ImGui features. call this to learn about the library! try to make it always available in your application! + IMGUI_API void ShowMetricsWindow(bool* p_open = NULL); // create metrics window. display ImGui internals: draw commands (with individual draw calls and vertices), window list, basic internal state, etc. + IMGUI_API void ShowStyleEditor(ImGuiStyle* ref = NULL); // add style editor block (not a window). you can pass in a reference ImGuiStyle structure to compare to, revert to and save to (else it uses the default style) + IMGUI_API bool ShowStyleSelector(const char* label); // add style selector block (not a window), essentially a combo listing the default styles. + IMGUI_API void ShowFontSelector(const char* label); // add font selector block (not a window), essentially a combo listing the loaded fonts. + IMGUI_API void ShowUserGuide(); // add basic help/info block (not a window): how to manipulate ImGui as a end-user (mouse/keyboard controls). + IMGUI_API const char* GetVersion(); // get a version string e.g. "1.23" + + // Styles + IMGUI_API void StyleColorsDark(ImGuiStyle* dst = NULL); // new, recommended style (default) + IMGUI_API void StyleColorsClassic(ImGuiStyle* dst = NULL); // classic imgui style + IMGUI_API void StyleColorsLight(ImGuiStyle* dst = NULL); // best used with borders and a custom, thicker font + + // Windows + // (Begin = push window to the stack and start appending to it. End = pop window from the stack. You may append multiple times to the same window during the same frame) + // Begin()/BeginChild() return false to indicate the window being collapsed or fully clipped, so you may early out and omit submitting anything to the window. + // However you need to always call a matching End()/EndChild() for a Begin()/BeginChild() call, regardless of its return value (this is due to legacy reason and is inconsistent with BeginMenu/EndMenu, BeginPopup/EndPopup and other functions where the End call should only be called if the corresponding Begin function returned true.) + // Passing 'bool* p_open != NULL' shows a close widget in the upper-right corner of the window, which when clicking will set the boolean to false. + // Use child windows to introduce independent scrolling/clipping regions within a host window. Child windows can embed their own child. + IMGUI_API bool Begin(const char* name, bool* p_open = NULL, ImGuiWindowFlags flags = 0); + IMGUI_API void End(); + IMGUI_API bool BeginChild(const char* str_id, const ImVec2& size = ImVec2(0,0), bool border = false, ImGuiWindowFlags flags = 0); // Begin a scrolling region. size==0.0f: use remaining window size, size<0.0f: use remaining window size minus abs(size). size>0.0f: fixed size. each axis can use a different mode, e.g. ImVec2(0,400). + IMGUI_API bool BeginChild(ImGuiID id, const ImVec2& size = ImVec2(0,0), bool border = false, ImGuiWindowFlags flags = 0); IMGUI_API void EndChild(); - IMGUI_API ImVec2 GetContentRegionMax(); // current content boundaries (typically window boundaries including scrolling, or current column boundaries), in windows coordinates - IMGUI_API ImVec2 GetContentRegionAvail(); // == GetContentRegionMax() - GetCursorPos() - IMGUI_API float GetContentRegionAvailWidth(); // - IMGUI_API ImVec2 GetWindowContentRegionMin(); // content boundaries min (roughly (0,0)-Scroll), in window coordinates - IMGUI_API ImVec2 GetWindowContentRegionMax(); // content boundaries max (roughly (0,0)+Size-Scroll) where Size can be override with SetNextWindowContentSize(), in window coordinates - IMGUI_API float GetWindowContentRegionWidth(); // - IMGUI_API ImDrawList* GetWindowDrawList(); // get rendering command-list if you want to append your own draw primitives - IMGUI_API ImVec2 GetWindowPos(); // get current window position in screen space (useful if you want to do your own drawing via the DrawList api) - IMGUI_API ImVec2 GetWindowSize(); // get current window size - IMGUI_API float GetWindowWidth(); - IMGUI_API float GetWindowHeight(); + + // Windows Utilities + IMGUI_API bool IsWindowAppearing(); IMGUI_API bool IsWindowCollapsed(); - IMGUI_API void SetWindowFontScale(float scale); // per-window font scale. Adjust IO.FontGlobalScale if you want to scale all windows - - IMGUI_API void SetNextWindowPos(const ImVec2& pos, ImGuiSetCond cond = 0); // set next window position. call before Begin() - IMGUI_API void SetNextWindowPosCenter(ImGuiSetCond cond = 0); // set next window position to be centered on screen. call before Begin() - IMGUI_API void SetNextWindowSize(const ImVec2& size, ImGuiSetCond cond = 0); // set next window size. set axis to 0.0f to force an auto-fit on this axis. call before Begin() - IMGUI_API void SetNextWindowSizeConstraints(const ImVec2& size_min, const ImVec2& size_max, ImGuiSizeConstraintCallback custom_callback = NULL, void* custom_callback_data = NULL); // set next window size limits. use -1,-1 on either X/Y axis to preserve the current size. Use callback to apply non-trivial programmatic constraints. - IMGUI_API void SetNextWindowContentSize(const ImVec2& size); // set next window content size (enforce the range of scrollbars). set axis to 0.0f to leave it automatic. call before Begin() - IMGUI_API void SetNextWindowContentWidth(float width); // set next window content width (enforce the range of horizontal scrollbar). call before Begin() - IMGUI_API void SetNextWindowCollapsed(bool collapsed, ImGuiSetCond cond = 0); // set next window collapsed state. call before Begin() - IMGUI_API void SetNextWindowFocus(); // set next window to be focused / front-most. call before Begin() - IMGUI_API void SetWindowPos(const ImVec2& pos, ImGuiSetCond cond = 0); // (not recommended) set current window position - call within Begin()/End(). prefer using SetNextWindowPos(), as this may incur tearing and side-effects. - IMGUI_API void SetWindowSize(const ImVec2& size, ImGuiSetCond cond = 0); // (not recommended) set current window size - call within Begin()/End(). set to ImVec2(0,0) to force an auto-fit. prefer using SetNextWindowSize(), as this may incur tearing and minor side-effects. - IMGUI_API void SetWindowCollapsed(bool collapsed, ImGuiSetCond cond = 0); // (not recommended) set current window collapsed state. prefer using SetNextWindowCollapsed(). - IMGUI_API void SetWindowFocus(); // (not recommended) set current window to be focused / front-most. prefer using SetNextWindowFocus(). - IMGUI_API void SetWindowPos(const char* name, const ImVec2& pos, ImGuiSetCond cond = 0); // set named window position. - IMGUI_API void SetWindowSize(const char* name, const ImVec2& size, ImGuiSetCond cond = 0); // set named window size. set axis to 0.0f to force an auto-fit on this axis. - IMGUI_API void SetWindowCollapsed(const char* name, bool collapsed, ImGuiSetCond cond = 0); // set named window collapsed state - IMGUI_API void SetWindowFocus(const char* name); // set named window to be focused / front-most. use NULL to remove focus. - - IMGUI_API float GetScrollX(); // get scrolling amount [0..GetScrollMaxX()] - IMGUI_API float GetScrollY(); // get scrolling amount [0..GetScrollMaxY()] - IMGUI_API float GetScrollMaxX(); // get maximum scrolling amount ~~ ContentSize.X - WindowSize.X - IMGUI_API float GetScrollMaxY(); // get maximum scrolling amount ~~ ContentSize.Y - WindowSize.Y - IMGUI_API void SetScrollX(float scroll_x); // set scrolling amount [0..GetScrollMaxX()] - IMGUI_API void SetScrollY(float scroll_y); // set scrolling amount [0..GetScrollMaxY()] - IMGUI_API void SetScrollHere(float center_y_ratio = 0.5f); // adjust scrolling amount to make current cursor position visible. center_y_ratio=0.0: top, 0.5: center, 1.0: bottom. - IMGUI_API void SetScrollFromPosY(float pos_y, float center_y_ratio = 0.5f); // adjust scrolling amount to make given position valid. use GetCursorPos() or GetCursorStartPos()+offset to get valid positions. - IMGUI_API void SetKeyboardFocusHere(int offset = 0); // focus keyboard on the next widget. Use positive 'offset' to access sub components of a multiple component widget. Use negative 'offset' to access previous widgets. - IMGUI_API void SetStateStorage(ImGuiStorage* tree); // replace tree state storage with our own (if you want to manipulate it yourself, typically clear subsection of it) - IMGUI_API ImGuiStorage* GetStateStorage(); + IMGUI_API bool IsWindowFocused(ImGuiFocusedFlags flags=0); // is current window focused? or its root/child, depending on flags. see flags for options. + IMGUI_API bool IsWindowHovered(ImGuiHoveredFlags flags=0); // is current window hovered (and typically: not blocked by a popup/modal)? see flags for options. NB: If you are trying to check whether your mouse should be dispatched to imgui or to your app, you should use the 'io.WantCaptureMouse' boolean for that! Please read the FAQ! + IMGUI_API ImDrawList* GetWindowDrawList(); // get draw list associated to the window, to append your own drawing primitives + IMGUI_API ImVec2 GetWindowPos(); // get current window position in screen space (useful if you want to do your own drawing via the DrawList API) + IMGUI_API ImVec2 GetWindowSize(); // get current window size + IMGUI_API float GetWindowWidth(); // get current window width (shortcut for GetWindowSize().x) + IMGUI_API float GetWindowHeight(); // get current window height (shortcut for GetWindowSize().y) + IMGUI_API ImVec2 GetContentRegionMax(); // current content boundaries (typically window boundaries including scrolling, or current column boundaries), in windows coordinates + IMGUI_API ImVec2 GetContentRegionAvail(); // == GetContentRegionMax() - GetCursorPos() + IMGUI_API float GetContentRegionAvailWidth(); // + IMGUI_API ImVec2 GetWindowContentRegionMin(); // content boundaries min (roughly (0,0)-Scroll), in window coordinates + IMGUI_API ImVec2 GetWindowContentRegionMax(); // content boundaries max (roughly (0,0)+Size-Scroll) where Size can be override with SetNextWindowContentSize(), in window coordinates + IMGUI_API float GetWindowContentRegionWidth(); // + + IMGUI_API void SetNextWindowPos(const ImVec2& pos, ImGuiCond cond = 0, const ImVec2& pivot = ImVec2(0,0)); // set next window position. call before Begin(). use pivot=(0.5f,0.5f) to center on given point, etc. + IMGUI_API void SetNextWindowSize(const ImVec2& size, ImGuiCond cond = 0); // set next window size. set axis to 0.0f to force an auto-fit on this axis. call before Begin() + IMGUI_API void SetNextWindowSizeConstraints(const ImVec2& size_min, const ImVec2& size_max, ImGuiSizeCallback custom_callback = NULL, void* custom_callback_data = NULL); // set next window size limits. use -1,-1 on either X/Y axis to preserve the current size. Use callback to apply non-trivial programmatic constraints. + IMGUI_API void SetNextWindowContentSize(const ImVec2& size); // set next window content size (~ enforce the range of scrollbars). not including window decorations (title bar, menu bar, etc.). set an axis to 0.0f to leave it automatic. call before Begin() + IMGUI_API void SetNextWindowCollapsed(bool collapsed, ImGuiCond cond = 0); // set next window collapsed state. call before Begin() + IMGUI_API void SetNextWindowFocus(); // set next window to be focused / front-most. call before Begin() + IMGUI_API void SetNextWindowBgAlpha(float alpha); // set next window background color alpha. helper to easily modify ImGuiCol_WindowBg/ChildBg/PopupBg. + IMGUI_API void SetWindowPos(const ImVec2& pos, ImGuiCond cond = 0); // (not recommended) set current window position - call within Begin()/End(). prefer using SetNextWindowPos(), as this may incur tearing and side-effects. + IMGUI_API void SetWindowSize(const ImVec2& size, ImGuiCond cond = 0); // (not recommended) set current window size - call within Begin()/End(). set to ImVec2(0,0) to force an auto-fit. prefer using SetNextWindowSize(), as this may incur tearing and minor side-effects. + IMGUI_API void SetWindowCollapsed(bool collapsed, ImGuiCond cond = 0); // (not recommended) set current window collapsed state. prefer using SetNextWindowCollapsed(). + IMGUI_API void SetWindowFocus(); // (not recommended) set current window to be focused / front-most. prefer using SetNextWindowFocus(). + IMGUI_API void SetWindowFontScale(float scale); // set font scale. Adjust IO.FontGlobalScale if you want to scale all windows + IMGUI_API void SetWindowPos(const char* name, const ImVec2& pos, ImGuiCond cond = 0); // set named window position. + IMGUI_API void SetWindowSize(const char* name, const ImVec2& size, ImGuiCond cond = 0); // set named window size. set axis to 0.0f to force an auto-fit on this axis. + IMGUI_API void SetWindowCollapsed(const char* name, bool collapsed, ImGuiCond cond = 0); // set named window collapsed state + IMGUI_API void SetWindowFocus(const char* name); // set named window to be focused / front-most. use NULL to remove focus. + + // Windows Scrolling + IMGUI_API float GetScrollX(); // get scrolling amount [0..GetScrollMaxX()] + IMGUI_API float GetScrollY(); // get scrolling amount [0..GetScrollMaxY()] + IMGUI_API float GetScrollMaxX(); // get maximum scrolling amount ~~ ContentSize.X - WindowSize.X + IMGUI_API float GetScrollMaxY(); // get maximum scrolling amount ~~ ContentSize.Y - WindowSize.Y + IMGUI_API void SetScrollX(float scroll_x); // set scrolling amount [0..GetScrollMaxX()] + IMGUI_API void SetScrollY(float scroll_y); // set scrolling amount [0..GetScrollMaxY()] + IMGUI_API void SetScrollHere(float center_y_ratio = 0.5f); // adjust scrolling amount to make current cursor position visible. center_y_ratio=0.0: top, 0.5: center, 1.0: bottom. When using to make a "default/current item" visible, consider using SetItemDefaultFocus() instead. + IMGUI_API void SetScrollFromPosY(float pos_y, float center_y_ratio = 0.5f); // adjust scrolling amount to make given position valid. use GetCursorPos() or GetCursorStartPos()+offset to get valid positions. // Parameters stacks (shared) - IMGUI_API void PushFont(ImFont* font); // use NULL as a shortcut to push default font + IMGUI_API void PushFont(ImFont* font); // use NULL as a shortcut to push default font IMGUI_API void PopFont(); + IMGUI_API void PushStyleColor(ImGuiCol idx, ImU32 col); IMGUI_API void PushStyleColor(ImGuiCol idx, const ImVec4& col); IMGUI_API void PopStyleColor(int count = 1); IMGUI_API void PushStyleVar(ImGuiStyleVar idx, float val); IMGUI_API void PushStyleVar(ImGuiStyleVar idx, const ImVec2& val); IMGUI_API void PopStyleVar(int count = 1); - IMGUI_API ImFont* GetFont(); // get current font - IMGUI_API float GetFontSize(); // get current font size (= height in pixels) of current font with current scale applied - IMGUI_API ImVec2 GetFontTexUvWhitePixel(); // get UV coordinate for a while pixel, useful to draw custom shapes via the ImDrawList API - IMGUI_API ImU32 GetColorU32(ImGuiCol idx, float alpha_mul = 1.0f); // retrieve given style color with style alpha applied and optional extra alpha multiplier - IMGUI_API ImU32 GetColorU32(const ImVec4& col); // retrieve given color with style alpha applied + IMGUI_API const ImVec4& GetStyleColorVec4(ImGuiCol idx); // retrieve style color as stored in ImGuiStyle structure. use to feed back into PushStyleColor(), otherwhise use GetColorU32() to get style color with style alpha baked in. + IMGUI_API ImFont* GetFont(); // get current font + IMGUI_API float GetFontSize(); // get current font size (= height in pixels) of current font with current scale applied + IMGUI_API ImVec2 GetFontTexUvWhitePixel(); // get UV coordinate for a while pixel, useful to draw custom shapes via the ImDrawList API + IMGUI_API ImU32 GetColorU32(ImGuiCol idx, float alpha_mul = 1.0f); // retrieve given style color with style alpha applied and optional extra alpha multiplier + IMGUI_API ImU32 GetColorU32(const ImVec4& col); // retrieve given color with style alpha applied + IMGUI_API ImU32 GetColorU32(ImU32 col); // retrieve given color with style alpha applied // Parameters stacks (current window) - IMGUI_API void PushItemWidth(float item_width); // width of items for the common item+label case, pixels. 0.0f = default to ~2/3 of windows width, >0.0f: width in pixels, <0.0f align xx pixels to the right of window (so -1.0f always align width to the right side) + IMGUI_API void PushItemWidth(float item_width); // width of items for the common item+label case, pixels. 0.0f = default to ~2/3 of windows width, >0.0f: width in pixels, <0.0f align xx pixels to the right of window (so -1.0f always align width to the right side) IMGUI_API void PopItemWidth(); - IMGUI_API float CalcItemWidth(); // width of item given pushed settings and current cursor position - IMGUI_API void PushTextWrapPos(float wrap_pos_x = 0.0f); // word-wrapping for Text*() commands. < 0.0f: no wrapping; 0.0f: wrap to end of window (or column); > 0.0f: wrap at 'wrap_pos_x' position in window local space + IMGUI_API float CalcItemWidth(); // width of item given pushed settings and current cursor position + IMGUI_API void PushTextWrapPos(float wrap_pos_x = 0.0f); // word-wrapping for Text*() commands. < 0.0f: no wrapping; 0.0f: wrap to end of window (or column); > 0.0f: wrap at 'wrap_pos_x' position in window local space IMGUI_API void PopTextWrapPos(); - IMGUI_API void PushAllowKeyboardFocus(bool v); // allow focusing using TAB/Shift-TAB, enabled by default but you can disable it for certain widgets + IMGUI_API void PushAllowKeyboardFocus(bool allow_keyboard_focus); // allow focusing using TAB/Shift-TAB, enabled by default but you can disable it for certain widgets IMGUI_API void PopAllowKeyboardFocus(); - IMGUI_API void PushButtonRepeat(bool repeat); // in 'repeat' mode, Button*() functions return repeated true in a typematic manner (uses io.KeyRepeatDelay/io.KeyRepeatRate for now). Note that you can call IsItemActive() after any Button() to tell if the button is held in the current frame. + IMGUI_API void PushButtonRepeat(bool repeat); // in 'repeat' mode, Button*() functions return repeated true in a typematic manner (using io.KeyRepeatDelay/io.KeyRepeatRate setting). Note that you can call IsItemActive() after any Button() to tell if the button is held in the current frame. IMGUI_API void PopButtonRepeat(); // Cursor / Layout - IMGUI_API void Separator(); // horizontal line - IMGUI_API void SameLine(float pos_x = 0.0f, float spacing_w = -1.0f); // call between widgets or groups to layout them horizontally - IMGUI_API void NewLine(); // undo a SameLine() - IMGUI_API void Spacing(); // add vertical spacing - IMGUI_API void Dummy(const ImVec2& size); // add a dummy item of given size - IMGUI_API void Indent(float indent_w = 0.0f); // move content position toward the right, by style.IndentSpacing or indent_w if >0 - IMGUI_API void Unindent(float indent_w = 0.0f); // move content position back to the left, by style.IndentSpacing or indent_w if >0 - IMGUI_API void BeginGroup(); // lock horizontal starting position + capture group bounding box into one "item" (so you can use IsItemHovered() or layout primitives such as SameLine() on whole group, etc.) + IMGUI_API void Separator(); // separator, generally horizontal. inside a menu bar or in horizontal layout mode, this becomes a vertical separator. + IMGUI_API void SameLine(float pos_x = 0.0f, float spacing_w = -1.0f); // call between widgets or groups to layout them horizontally + IMGUI_API void NewLine(); // undo a SameLine() + IMGUI_API void Spacing(); // add vertical spacing + IMGUI_API void Dummy(const ImVec2& size); // add a dummy item of given size + IMGUI_API void Indent(float indent_w = 0.0f); // move content position toward the right, by style.IndentSpacing or indent_w if != 0 + IMGUI_API void Unindent(float indent_w = 0.0f); // move content position back to the left, by style.IndentSpacing or indent_w if != 0 + IMGUI_API void BeginGroup(); // lock horizontal starting position + capture group bounding box into one "item" (so you can use IsItemHovered() or layout primitives such as SameLine() on whole group, etc.) IMGUI_API void EndGroup(); - IMGUI_API ImVec2 GetCursorPos(); // cursor position is relative to window position - IMGUI_API float GetCursorPosX(); // " - IMGUI_API float GetCursorPosY(); // " - IMGUI_API void SetCursorPos(const ImVec2& local_pos); // " - IMGUI_API void SetCursorPosX(float x); // " - IMGUI_API void SetCursorPosY(float y); // " - IMGUI_API ImVec2 GetCursorStartPos(); // initial cursor position - IMGUI_API ImVec2 GetCursorScreenPos(); // cursor position in absolute screen coordinates [0..io.DisplaySize] (useful to work with ImDrawList API) - IMGUI_API void SetCursorScreenPos(const ImVec2& pos); // cursor position in absolute screen coordinates [0..io.DisplaySize] - IMGUI_API void AlignFirstTextHeightToWidgets(); // call once if the first item on the line is a Text() item and you want to vertically lower it to match subsequent (bigger) widgets - IMGUI_API float GetTextLineHeight(); // height of font == GetWindowFontSize() - IMGUI_API float GetTextLineHeightWithSpacing(); // distance (in pixels) between 2 consecutive lines of text == GetWindowFontSize() + GetStyle().ItemSpacing.y - IMGUI_API float GetItemsLineHeightWithSpacing(); // distance (in pixels) between 2 consecutive lines of standard height widgets == GetWindowFontSize() + GetStyle().FramePadding.y*2 + GetStyle().ItemSpacing.y - - // Columns - // You can also use SameLine(pos_x) for simplified columning. The columns API is still work-in-progress and rather lacking. - IMGUI_API void Columns(int count = 1, const char* id = NULL, bool border = true); // setup number of columns. use an identifier to distinguish multiple column sets. close with Columns(1). - IMGUI_API void NextColumn(); // next column - IMGUI_API int GetColumnIndex(); // get current column index - IMGUI_API float GetColumnOffset(int column_index = -1); // get position of column line (in pixels, from the left side of the contents region). pass -1 to use current column, otherwise 0..GetcolumnsCount() inclusive. column 0 is usually 0.0f and not resizable unless you call this - IMGUI_API void SetColumnOffset(int column_index, float offset_x); // set position of column line (in pixels, from the left side of the contents region). pass -1 to use current column - IMGUI_API float GetColumnWidth(int column_index = -1); // column width (== GetColumnOffset(GetColumnIndex()+1) - GetColumnOffset(GetColumnOffset()) - IMGUI_API int GetColumnsCount(); // number of columns (what was passed to Columns()) - - // ID scopes - // If you are creating widgets in a loop you most likely want to push a unique identifier so ImGui can differentiate them. - // You can also use the "##foobar" syntax within widget label to distinguish them from each others. Read "A primer on the use of labels/IDs" in the FAQ for more details. - IMGUI_API void PushID(const char* str_id); // push identifier into the ID stack. IDs are hash of the *entire* stack! + IMGUI_API ImVec2 GetCursorPos(); // cursor position is relative to window position + IMGUI_API float GetCursorPosX(); // " + IMGUI_API float GetCursorPosY(); // " + IMGUI_API void SetCursorPos(const ImVec2& local_pos); // " + IMGUI_API void SetCursorPosX(float x); // " + IMGUI_API void SetCursorPosY(float y); // " + IMGUI_API ImVec2 GetCursorStartPos(); // initial cursor position + IMGUI_API ImVec2 GetCursorScreenPos(); // cursor position in absolute screen coordinates [0..io.DisplaySize] (useful to work with ImDrawList API) + IMGUI_API void SetCursorScreenPos(const ImVec2& screen_pos); // cursor position in absolute screen coordinates [0..io.DisplaySize] + IMGUI_API void AlignTextToFramePadding(); // vertically align upcoming text baseline to FramePadding.y so that it will align properly to regularly framed items (call if you have text on a line before a framed item) + IMGUI_API float GetTextLineHeight(); // ~ FontSize + IMGUI_API float GetTextLineHeightWithSpacing(); // ~ FontSize + style.ItemSpacing.y (distance in pixels between 2 consecutive lines of text) + IMGUI_API float GetFrameHeight(); // ~ FontSize + style.FramePadding.y * 2 + IMGUI_API float GetFrameHeightWithSpacing(); // ~ FontSize + style.FramePadding.y * 2 + style.ItemSpacing.y (distance in pixels between 2 consecutive lines of framed widgets) + + // ID stack/scopes + // Read the FAQ for more details about how ID are handled in dear imgui. If you are creating widgets in a loop you most + // likely want to push a unique identifier (e.g. object pointer, loop index) to uniquely differentiate them. + // You can also use the "##foobar" syntax within widget label to distinguish them from each others. + // In this header file we use the "label"/"name" terminology to denote a string that will be displayed and used as an ID, + // whereas "str_id" denote a string that is only used as an ID and not aimed to be displayed. + IMGUI_API void PushID(const char* str_id); // push identifier into the ID stack. IDs are hash of the entire stack! IMGUI_API void PushID(const char* str_id_begin, const char* str_id_end); IMGUI_API void PushID(const void* ptr_id); IMGUI_API void PushID(int int_id); IMGUI_API void PopID(); - IMGUI_API ImGuiID GetID(const char* str_id); // calculate unique ID (hash of whole ID stack + given parameter). useful if you want to query into ImGuiStorage yourself. otherwise rarely needed + IMGUI_API ImGuiID GetID(const char* str_id); // calculate unique ID (hash of whole ID stack + given parameter). e.g. if you want to query into ImGuiStorage yourself IMGUI_API ImGuiID GetID(const char* str_id_begin, const char* str_id_end); IMGUI_API ImGuiID GetID(const void* ptr_id); - // Widgets - IMGUI_API void Text(const char* fmt, ...) IM_PRINTFARGS(1); - IMGUI_API void TextV(const char* fmt, va_list args); - IMGUI_API void TextColored(const ImVec4& col, const char* fmt, ...) IM_PRINTFARGS(2); // shortcut for PushStyleColor(ImGuiCol_Text, col); Text(fmt, ...); PopStyleColor(); - IMGUI_API void TextColoredV(const ImVec4& col, const char* fmt, va_list args); - IMGUI_API void TextDisabled(const char* fmt, ...) IM_PRINTFARGS(1); // shortcut for PushStyleColor(ImGuiCol_Text, style.Colors[ImGuiCol_TextDisabled]); Text(fmt, ...); PopStyleColor(); - IMGUI_API void TextDisabledV(const char* fmt, va_list args); - IMGUI_API void TextWrapped(const char* fmt, ...) IM_PRINTFARGS(1); // shortcut for PushTextWrapPos(0.0f); Text(fmt, ...); PopTextWrapPos();. Note that this won't work on an auto-resizing window if there's no other widgets to extend the window width, yoy may need to set a size using SetNextWindowSize(). - IMGUI_API void TextWrappedV(const char* fmt, va_list args); - IMGUI_API void TextUnformatted(const char* text, const char* text_end = NULL); // doesn't require null terminated string if 'text_end' is specified. no copy done to any bounded stack buffer, recommended for long chunks of text - IMGUI_API void LabelText(const char* label, const char* fmt, ...) IM_PRINTFARGS(2); // display text+label aligned the same way as value+label widgets - IMGUI_API void LabelTextV(const char* label, const char* fmt, va_list args); - IMGUI_API void Bullet(); // draw a small circle and keep the cursor on the same line. advance cursor x position by GetTreeNodeToLabelSpacing(), same distance that TreeNode() uses - IMGUI_API void BulletText(const char* fmt, ...) IM_PRINTFARGS(1); // shortcut for Bullet()+Text() - IMGUI_API void BulletTextV(const char* fmt, va_list args); - IMGUI_API bool Button(const char* label, const ImVec2& size = ImVec2(0,0)); // button - IMGUI_API bool SmallButton(const char* label); // button with FramePadding=(0,0) - IMGUI_API bool InvisibleButton(const char* str_id, const ImVec2& size); + // Widgets: Text + IMGUI_API void TextUnformatted(const char* text, const char* text_end = NULL); // raw text without formatting. Roughly equivalent to Text("%s", text) but: A) doesn't require null terminated string if 'text_end' is specified, B) it's faster, no memory copy is done, no buffer size limits, recommended for long chunks of text. + IMGUI_API void Text(const char* fmt, ...) IM_FMTARGS(1); // simple formatted text + IMGUI_API void TextV(const char* fmt, va_list args) IM_FMTLIST(1); + IMGUI_API void TextColored(const ImVec4& col, const char* fmt, ...) IM_FMTARGS(2); // shortcut for PushStyleColor(ImGuiCol_Text, col); Text(fmt, ...); PopStyleColor(); + IMGUI_API void TextColoredV(const ImVec4& col, const char* fmt, va_list args) IM_FMTLIST(2); + IMGUI_API void TextDisabled(const char* fmt, ...) IM_FMTARGS(1); // shortcut for PushStyleColor(ImGuiCol_Text, style.Colors[ImGuiCol_TextDisabled]); Text(fmt, ...); PopStyleColor(); + IMGUI_API void TextDisabledV(const char* fmt, va_list args) IM_FMTLIST(1); + IMGUI_API void TextWrapped(const char* fmt, ...) IM_FMTARGS(1); // shortcut for PushTextWrapPos(0.0f); Text(fmt, ...); PopTextWrapPos();. Note that this won't work on an auto-resizing window if there's no other widgets to extend the window width, yoy may need to set a size using SetNextWindowSize(). + IMGUI_API void TextWrappedV(const char* fmt, va_list args) IM_FMTLIST(1); + IMGUI_API void LabelText(const char* label, const char* fmt, ...) IM_FMTARGS(2); // display text+label aligned the same way as value+label widgets + IMGUI_API void LabelTextV(const char* label, const char* fmt, va_list args) IM_FMTLIST(2); + IMGUI_API void BulletText(const char* fmt, ...) IM_FMTARGS(1); // shortcut for Bullet()+Text() + IMGUI_API void BulletTextV(const char* fmt, va_list args) IM_FMTLIST(1); + + // Widgets: Main + IMGUI_API bool Button(const char* label, const ImVec2& size = ImVec2(0,0)); // button + IMGUI_API bool SmallButton(const char* label); // button with FramePadding=(0,0) to easily embed within text + IMGUI_API bool ArrowButton(const char* str_id, ImGuiDir dir); + IMGUI_API bool InvisibleButton(const char* str_id, const ImVec2& size); // button behavior without the visuals, useful to build custom behaviors using the public api (along with IsItemActive, IsItemHovered, etc.) IMGUI_API void Image(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0 = ImVec2(0,0), const ImVec2& uv1 = ImVec2(1,1), const ImVec4& tint_col = ImVec4(1,1,1,1), const ImVec4& border_col = ImVec4(0,0,0,0)); IMGUI_API bool ImageButton(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0 = ImVec2(0,0), const ImVec2& uv1 = ImVec2(1,1), int frame_padding = -1, const ImVec4& bg_col = ImVec4(0,0,0,0), const ImVec4& tint_col = ImVec4(1,1,1,1)); // <0 frame_padding uses default frame padding settings. 0 for no padding IMGUI_API bool Checkbox(const char* label, bool* v); IMGUI_API bool CheckboxFlags(const char* label, unsigned int* flags, unsigned int flags_value); IMGUI_API bool RadioButton(const char* label, bool active); IMGUI_API bool RadioButton(const char* label, int* v, int v_button); - IMGUI_API bool Combo(const char* label, int* current_item, const char** items, int items_count, int height_in_items = -1); - IMGUI_API bool Combo(const char* label, int* current_item, const char* items_separated_by_zeros, int height_in_items = -1); // separate items with \0, end item-list with \0\0 - IMGUI_API bool Combo(const char* label, int* current_item, bool (*items_getter)(void* data, int idx, const char** out_text), void* data, int items_count, int height_in_items = -1); - IMGUI_API bool ColorButton(const ImVec4& col, bool small_height = false, bool outline_border = true); - IMGUI_API bool ColorEdit3(const char* label, float col[3]); // Hint: 'float col[3]' function argument is same as 'float* col'. You can pass address of first element out of a contiguous set, e.g. &myvector.x - IMGUI_API bool ColorEdit4(const char* label, float col[4], bool show_alpha = true); // " - IMGUI_API void ColorEditMode(ImGuiColorEditMode mode); // FIXME-OBSOLETE: This is inconsistent with most of the API and will be obsoleted/replaced. IMGUI_API void PlotLines(const char* label, const float* values, int values_count, int values_offset = 0, const char* overlay_text = NULL, float scale_min = FLT_MAX, float scale_max = FLT_MAX, ImVec2 graph_size = ImVec2(0,0), int stride = sizeof(float)); IMGUI_API void PlotLines(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset = 0, const char* overlay_text = NULL, float scale_min = FLT_MAX, float scale_max = FLT_MAX, ImVec2 graph_size = ImVec2(0,0)); IMGUI_API void PlotHistogram(const char* label, const float* values, int values_count, int values_offset = 0, const char* overlay_text = NULL, float scale_min = FLT_MAX, float scale_max = FLT_MAX, ImVec2 graph_size = ImVec2(0,0), int stride = sizeof(float)); IMGUI_API void PlotHistogram(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset = 0, const char* overlay_text = NULL, float scale_min = FLT_MAX, float scale_max = FLT_MAX, ImVec2 graph_size = ImVec2(0,0)); IMGUI_API void ProgressBar(float fraction, const ImVec2& size_arg = ImVec2(-1,0), const char* overlay = NULL); + IMGUI_API void Bullet(); // draw a small circle and keep the cursor on the same line. advance cursor x position by GetTreeNodeToLabelSpacing(), same distance that TreeNode() uses + + // Widgets: Combo Box + // The new BeginCombo()/EndCombo() api allows you to manage your contents and selection state however you want it. + // The old Combo() api are helpers over BeginCombo()/EndCombo() which are kept available for convenience purpose. + IMGUI_API bool BeginCombo(const char* label, const char* preview_value, ImGuiComboFlags flags = 0); + IMGUI_API void EndCombo(); // only call EndCombo() if BeginCombo() returns true! + IMGUI_API bool Combo(const char* label, int* current_item, const char* const items[], int items_count, int popup_max_height_in_items = -1); + IMGUI_API bool Combo(const char* label, int* current_item, const char* items_separated_by_zeros, int popup_max_height_in_items = -1); // Separate items with \0 within a string, end item-list with \0\0. e.g. "One\0Two\0Three\0" + IMGUI_API bool Combo(const char* label, int* current_item, bool(*items_getter)(void* data, int idx, const char** out_text), void* data, int items_count, int popup_max_height_in_items = -1); // Widgets: Drags (tip: ctrl+click on a drag box to input with keyboard. manually input values aren't clamped, can go off-bounds) - // For all the Float2/Float3/Float4/Int2/Int3/Int4 versions of every functions, remember than a 'float v[3]' function argument is the same as 'float* v'. You can pass address of your first element out of a contiguous set, e.g. &myvector.x + // For all the Float2/Float3/Float4/Int2/Int3/Int4 versions of every functions, note that a 'float v[X]' function argument is the same as 'float* v', the array syntax is just a way to document the number of elements that are expected to be accessible. You can pass address of your first element out of a contiguous set, e.g. &myvector.x + // Speed are per-pixel of mouse movement (v_speed=0.2f: mouse needs to move by 5 pixels to increase value by 1). For gamepad/keyboard navigation, minimum speed is Max(v_speed, minimum_step_at_given_precision). IMGUI_API bool DragFloat(const char* label, float* v, float v_speed = 1.0f, float v_min = 0.0f, float v_max = 0.0f, const char* display_format = "%.3f", float power = 1.0f); // If v_min >= v_max we have no bound IMGUI_API bool DragFloat2(const char* label, float v[2], float v_speed = 1.0f, float v_min = 0.0f, float v_max = 0.0f, const char* display_format = "%.3f", float power = 1.0f); IMGUI_API bool DragFloat3(const char* label, float v[3], float v_speed = 1.0f, float v_min = 0.0f, float v_max = 0.0f, const char* display_format = "%.3f", float power = 1.0f); @@ -302,9 +357,10 @@ namespace ImGui IMGUI_API bool InputInt2(const char* label, int v[2], ImGuiInputTextFlags extra_flags = 0); IMGUI_API bool InputInt3(const char* label, int v[3], ImGuiInputTextFlags extra_flags = 0); IMGUI_API bool InputInt4(const char* label, int v[4], ImGuiInputTextFlags extra_flags = 0); + IMGUI_API bool InputDouble(const char* label, double* v, double step = 0.0f, double step_fast = 0.0f, const char* display_format = "%.6f", ImGuiInputTextFlags extra_flags = 0); // Widgets: Sliders (tip: ctrl+click on a slider to input with keyboard. manually input values aren't clamped, can go off-bounds) - IMGUI_API bool SliderFloat(const char* label, float* v, float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); // adjust display_format to decorate the value with a prefix or a suffix. Use power!=1.0 for logarithmic sliders + IMGUI_API bool SliderFloat(const char* label, float* v, float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); // adjust display_format to decorate the value with a prefix or a suffix for in-slider labels or unit display. Use power!=1.0 for logarithmic sliders IMGUI_API bool SliderFloat2(const char* label, float v[2], float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); IMGUI_API bool SliderFloat3(const char* label, float v[3], float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); IMGUI_API bool SliderFloat4(const char* label, float v[4], float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); @@ -316,30 +372,39 @@ namespace ImGui IMGUI_API bool VSliderFloat(const char* label, const ImVec2& size, float* v, float v_min, float v_max, const char* display_format = "%.3f", float power = 1.0f); IMGUI_API bool VSliderInt(const char* label, const ImVec2& size, int* v, int v_min, int v_max, const char* display_format = "%.0f"); + // Widgets: Color Editor/Picker (tip: the ColorEdit* functions have a little colored preview square that can be left-clicked to open a picker, and right-clicked to open an option menu.) + // Note that a 'float v[X]' function argument is the same as 'float* v', the array syntax is just a way to document the number of elements that are expected to be accessible. You can the pass the address of a first float element out of a contiguous structure, e.g. &myvector.x + IMGUI_API bool ColorEdit3(const char* label, float col[3], ImGuiColorEditFlags flags = 0); + IMGUI_API bool ColorEdit4(const char* label, float col[4], ImGuiColorEditFlags flags = 0); + IMGUI_API bool ColorPicker3(const char* label, float col[3], ImGuiColorEditFlags flags = 0); + IMGUI_API bool ColorPicker4(const char* label, float col[4], ImGuiColorEditFlags flags = 0, const float* ref_col = NULL); + IMGUI_API bool ColorButton(const char* desc_id, const ImVec4& col, ImGuiColorEditFlags flags = 0, ImVec2 size = ImVec2(0,0)); // display a colored square/button, hover for details, return true when pressed. + IMGUI_API void SetColorEditOptions(ImGuiColorEditFlags flags); // initialize current options (generally on application startup) if you want to select a default format, picker type, etc. User will be able to change many settings, unless you pass the _NoOptions flag to your calls. + // Widgets: Trees - IMGUI_API bool TreeNode(const char* label); // if returning 'true' the node is open and the tree id is pushed into the id stack. user is responsible for calling TreePop(). - IMGUI_API bool TreeNode(const char* str_id, const char* fmt, ...) IM_PRINTFARGS(2); // read the FAQ about why and how to use ID. to align arbitrary text at the same level as a TreeNode() you can use Bullet(). - IMGUI_API bool TreeNode(const void* ptr_id, const char* fmt, ...) IM_PRINTFARGS(2); // " - IMGUI_API bool TreeNodeV(const char* str_id, const char* fmt, va_list args); // " - IMGUI_API bool TreeNodeV(const void* ptr_id, const char* fmt, va_list args); // " + IMGUI_API bool TreeNode(const char* label); // if returning 'true' the node is open and the tree id is pushed into the id stack. user is responsible for calling TreePop(). + IMGUI_API bool TreeNode(const char* str_id, const char* fmt, ...) IM_FMTARGS(2); // read the FAQ about why and how to use ID. to align arbitrary text at the same level as a TreeNode() you can use Bullet(). + IMGUI_API bool TreeNode(const void* ptr_id, const char* fmt, ...) IM_FMTARGS(2); // " + IMGUI_API bool TreeNodeV(const char* str_id, const char* fmt, va_list args) IM_FMTLIST(2); + IMGUI_API bool TreeNodeV(const void* ptr_id, const char* fmt, va_list args) IM_FMTLIST(2); IMGUI_API bool TreeNodeEx(const char* label, ImGuiTreeNodeFlags flags = 0); - IMGUI_API bool TreeNodeEx(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) IM_PRINTFARGS(3); - IMGUI_API bool TreeNodeEx(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) IM_PRINTFARGS(3); - IMGUI_API bool TreeNodeExV(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args); - IMGUI_API bool TreeNodeExV(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args); - IMGUI_API void TreePush(const char* str_id = NULL); // ~ Indent()+PushId(). Already called by TreeNode() when returning true, but you can call Push/Pop yourself for layout purpose - IMGUI_API void TreePush(const void* ptr_id = NULL); // " - IMGUI_API void TreePop(); // ~ Unindent()+PopId() - IMGUI_API void TreeAdvanceToLabelPos(); // advance cursor x position by GetTreeNodeToLabelSpacing() - IMGUI_API float GetTreeNodeToLabelSpacing(); // horizontal distance preceding label when using TreeNode*() or Bullet() == (g.FontSize + style.FramePadding.x*2) for a regular unframed TreeNode - IMGUI_API void SetNextTreeNodeOpen(bool is_open, ImGuiSetCond cond = 0); // set next TreeNode/CollapsingHeader open state. - IMGUI_API bool CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags = 0); // if returning 'true' the header is open. doesn't indent nor push on ID stack. user doesn't have to call TreePop(). + IMGUI_API bool TreeNodeEx(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) IM_FMTARGS(3); + IMGUI_API bool TreeNodeEx(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) IM_FMTARGS(3); + IMGUI_API bool TreeNodeExV(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) IM_FMTLIST(3); + IMGUI_API bool TreeNodeExV(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) IM_FMTLIST(3); + IMGUI_API void TreePush(const char* str_id); // ~ Indent()+PushId(). Already called by TreeNode() when returning true, but you can call Push/Pop yourself for layout purpose + IMGUI_API void TreePush(const void* ptr_id = NULL); // " + IMGUI_API void TreePop(); // ~ Unindent()+PopId() + IMGUI_API void TreeAdvanceToLabelPos(); // advance cursor x position by GetTreeNodeToLabelSpacing() + IMGUI_API float GetTreeNodeToLabelSpacing(); // horizontal distance preceding label when using TreeNode*() or Bullet() == (g.FontSize + style.FramePadding.x*2) for a regular unframed TreeNode + IMGUI_API void SetNextTreeNodeOpen(bool is_open, ImGuiCond cond = 0); // set next TreeNode/CollapsingHeader open state. + IMGUI_API bool CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags = 0); // if returning 'true' the header is open. doesn't indent nor push on ID stack. user doesn't have to call TreePop(). IMGUI_API bool CollapsingHeader(const char* label, bool* p_open, ImGuiTreeNodeFlags flags = 0); // when 'p_open' isn't NULL, display an additional small close button on upper right of the header // Widgets: Selectable / Lists - IMGUI_API bool Selectable(const char* label, bool selected = false, ImGuiSelectableFlags flags = 0, const ImVec2& size = ImVec2(0,0)); // size.x==0.0: use remaining width, size.x>0.0: specify width. size.y==0.0: use label height, size.y>0.0: specify height - IMGUI_API bool Selectable(const char* label, bool* p_selected, ImGuiSelectableFlags flags = 0, const ImVec2& size = ImVec2(0,0)); - IMGUI_API bool ListBox(const char* label, int* current_item, const char** items, int items_count, int height_in_items = -1); + IMGUI_API bool Selectable(const char* label, bool selected = false, ImGuiSelectableFlags flags = 0, const ImVec2& size = ImVec2(0,0)); // "bool selected" carry the selection state (read-only). Selectable() is clicked is returns true so you can modify your selection state. size.x==0.0: use remaining width, size.x>0.0: specify width. size.y==0.0: use label height, size.y>0.0: specify height + IMGUI_API bool Selectable(const char* label, bool* p_selected, ImGuiSelectableFlags flags = 0, const ImVec2& size = ImVec2(0,0)); // "bool* p_selected" point to the selection state (read-write), as a convenient helper. + IMGUI_API bool ListBox(const char* label, int* current_item, const char* const items[], int items_count, int height_in_items = -1); IMGUI_API bool ListBox(const char* label, int* current_item, bool (*items_getter)(void* data, int idx, const char** out_text), void* data, int items_count, int height_in_items = -1); IMGUI_API bool ListBoxHeader(const char* label, const ImVec2& size = ImVec2(0,0)); // use if you want to reimplement ListBox() will custom data or interactions. make sure to call ListBoxFooter() afterwards. IMGUI_API bool ListBoxHeader(const char* label, int items_count, int height_in_items = -1); // " @@ -350,76 +415,99 @@ namespace ImGui IMGUI_API void Value(const char* prefix, int v); IMGUI_API void Value(const char* prefix, unsigned int v); IMGUI_API void Value(const char* prefix, float v, const char* float_format = NULL); - IMGUI_API void ValueColor(const char* prefix, const ImVec4& v); - IMGUI_API void ValueColor(const char* prefix, ImU32 v); // Tooltips - IMGUI_API void SetTooltip(const char* fmt, ...) IM_PRINTFARGS(1); // set tooltip under mouse-cursor, typically use with ImGui::IsHovered(). last call wins - IMGUI_API void SetTooltipV(const char* fmt, va_list args); - IMGUI_API void BeginTooltip(); // use to create full-featured tooltip windows that aren't just text + IMGUI_API void SetTooltip(const char* fmt, ...) IM_FMTARGS(1); // set text tooltip under mouse-cursor, typically use with ImGui::IsItemHovered(). overidde any previous call to SetTooltip(). + IMGUI_API void SetTooltipV(const char* fmt, va_list args) IM_FMTLIST(1); + IMGUI_API void BeginTooltip(); // begin/append a tooltip window. to create full-featured tooltip (with any kind of contents). IMGUI_API void EndTooltip(); // Menus - IMGUI_API bool BeginMainMenuBar(); // create and append to a full screen menu-bar. only call EndMainMenuBar() if this returns true! - IMGUI_API void EndMainMenuBar(); - IMGUI_API bool BeginMenuBar(); // append to menu-bar of current window (requires ImGuiWindowFlags_MenuBar flag set). only call EndMenuBar() if this returns true! - IMGUI_API void EndMenuBar(); + IMGUI_API bool BeginMainMenuBar(); // create and append to a full screen menu-bar. + IMGUI_API void EndMainMenuBar(); // only call EndMainMenuBar() if BeginMainMenuBar() returns true! + IMGUI_API bool BeginMenuBar(); // append to menu-bar of current window (requires ImGuiWindowFlags_MenuBar flag set on parent window). + IMGUI_API void EndMenuBar(); // only call EndMenuBar() if BeginMenuBar() returns true! IMGUI_API bool BeginMenu(const char* label, bool enabled = true); // create a sub-menu entry. only call EndMenu() if this returns true! - IMGUI_API void EndMenu(); + IMGUI_API void EndMenu(); // only call EndMenu() if BeginMenu() returns true! IMGUI_API bool MenuItem(const char* label, const char* shortcut = NULL, bool selected = false, bool enabled = true); // return true when activated. shortcuts are displayed for convenience but not processed by ImGui at the moment IMGUI_API bool MenuItem(const char* label, const char* shortcut, bool* p_selected, bool enabled = true); // return true when activated + toggle (*p_selected) if p_selected != NULL // Popups - IMGUI_API void OpenPopup(const char* str_id); // mark popup as open. popups are closed when user click outside, or activate a pressable item, or CloseCurrentPopup() is called within a BeginPopup()/EndPopup() block. popup identifiers are relative to the current ID-stack (so OpenPopup and BeginPopup needs to be at the same level). - IMGUI_API bool BeginPopup(const char* str_id); // return true if the popup is open, and you can start outputting to it. only call EndPopup() if BeginPopup() returned true! - IMGUI_API bool BeginPopupModal(const char* name, bool* p_open = NULL, ImGuiWindowFlags extra_flags = 0); // modal dialog (can't close them by clicking outside) - IMGUI_API bool BeginPopupContextItem(const char* str_id, int mouse_button = 1); // helper to open and begin popup when clicked on last item. read comments in .cpp! - IMGUI_API bool BeginPopupContextWindow(bool also_over_items = true, const char* str_id = NULL, int mouse_button = 1); // helper to open and begin popup when clicked on current window. - IMGUI_API bool BeginPopupContextVoid(const char* str_id = NULL, int mouse_button = 1); // helper to open and begin popup when clicked in void (no window). - IMGUI_API void EndPopup(); + IMGUI_API void OpenPopup(const char* str_id); // call to mark popup as open (don't call every frame!). popups are closed when user click outside, or if CloseCurrentPopup() is called within a BeginPopup()/EndPopup() block. By default, Selectable()/MenuItem() are calling CloseCurrentPopup(). Popup identifiers are relative to the current ID-stack (so OpenPopup and BeginPopup needs to be at the same level). + IMGUI_API bool BeginPopup(const char* str_id, ImGuiWindowFlags flags = 0); // return true if the popup is open, and you can start outputting to it. only call EndPopup() if BeginPopup() returns true! + IMGUI_API bool BeginPopupContextItem(const char* str_id = NULL, int mouse_button = 1); // helper to open and begin popup when clicked on last item. if you can pass a NULL str_id only if the previous item had an id. If you want to use that on a non-interactive item such as Text() you need to pass in an explicit ID here. read comments in .cpp! + IMGUI_API bool BeginPopupContextWindow(const char* str_id = NULL, int mouse_button = 1, bool also_over_items = true); // helper to open and begin popup when clicked on current window. + IMGUI_API bool BeginPopupContextVoid(const char* str_id = NULL, int mouse_button = 1); // helper to open and begin popup when clicked in void (where there are no imgui windows). + IMGUI_API bool BeginPopupModal(const char* name, bool* p_open = NULL, ImGuiWindowFlags flags = 0); // modal dialog (regular window with title bar, block interactions behind the modal window, can't close the modal window by clicking outside) + IMGUI_API void EndPopup(); // only call EndPopup() if BeginPopupXXX() returns true! + IMGUI_API bool OpenPopupOnItemClick(const char* str_id = NULL, int mouse_button = 1); // helper to open popup when clicked on last item. return true when just opened. + IMGUI_API bool IsPopupOpen(const char* str_id); // return true if the popup is open IMGUI_API void CloseCurrentPopup(); // close the popup we have begin-ed into. clicking on a MenuItem or Selectable automatically close the current popup. - // Logging: all text output from interface is redirected to tty/file/clipboard. By default, tree nodes are automatically opened during logging. + // Columns + // You can also use SameLine(pos_x) for simplified columns. The columns API is still work-in-progress and rather lacking. + IMGUI_API void Columns(int count = 1, const char* id = NULL, bool border = true); + IMGUI_API void NextColumn(); // next column, defaults to current row or next row if the current row is finished + IMGUI_API int GetColumnIndex(); // get current column index + IMGUI_API float GetColumnWidth(int column_index = -1); // get column width (in pixels). pass -1 to use current column + IMGUI_API void SetColumnWidth(int column_index, float width); // set column width (in pixels). pass -1 to use current column + IMGUI_API float GetColumnOffset(int column_index = -1); // get position of column line (in pixels, from the left side of the contents region). pass -1 to use current column, otherwise 0..GetColumnsCount() inclusive. column 0 is typically 0.0f + IMGUI_API void SetColumnOffset(int column_index, float offset_x); // set position of column line (in pixels, from the left side of the contents region). pass -1 to use current column + IMGUI_API int GetColumnsCount(); + + // Logging/Capture: all text output from interface is captured to tty/file/clipboard. By default, tree nodes are automatically opened during logging. IMGUI_API void LogToTTY(int max_depth = -1); // start logging to tty IMGUI_API void LogToFile(int max_depth = -1, const char* filename = NULL); // start logging to file IMGUI_API void LogToClipboard(int max_depth = -1); // start logging to OS clipboard IMGUI_API void LogFinish(); // stop logging (close file, etc.) IMGUI_API void LogButtons(); // helper to display buttons for logging to tty/file/clipboard - IMGUI_API void LogText(const char* fmt, ...) IM_PRINTFARGS(1); // pass text data straight to log (without being displayed) + IMGUI_API void LogText(const char* fmt, ...) IM_FMTARGS(1); // pass text data straight to log (without being displayed) + + // Drag and Drop + // [BETA API] Missing Demo code. API may evolve. + IMGUI_API bool BeginDragDropSource(ImGuiDragDropFlags flags = 0); // call when the current item is active. If this return true, you can call SetDragDropPayload() + EndDragDropSource() + IMGUI_API bool SetDragDropPayload(const char* type, const void* data, size_t size, ImGuiCond cond = 0);// type is a user defined string of maximum 32 characters. Strings starting with '_' are reserved for dear imgui internal types. Data is copied and held by imgui. + IMGUI_API void EndDragDropSource(); // only call EndDragDropSource() if BeginDragDropSource() returns true! + IMGUI_API bool BeginDragDropTarget(); // call after submitting an item that may receive an item. If this returns true, you can call AcceptDragDropPayload() + EndDragDropTarget() + IMGUI_API const ImGuiPayload* AcceptDragDropPayload(const char* type, ImGuiDragDropFlags flags = 0); // accept contents of a given type. If ImGuiDragDropFlags_AcceptBeforeDelivery is set you can peek into the payload before the mouse button is released. + IMGUI_API void EndDragDropTarget(); // only call EndDragDropTarget() if BeginDragDropTarget() returns true! // Clipping IMGUI_API void PushClipRect(const ImVec2& clip_rect_min, const ImVec2& clip_rect_max, bool intersect_with_current_clip_rect); IMGUI_API void PopClipRect(); + // Focus, Activation + // (Prefer using "SetItemDefaultFocus()" over "if (IsWindowAppearing()) SetScrollHere()" when applicable, to make your code more forward compatible when navigation branch is merged) + IMGUI_API void SetItemDefaultFocus(); // make last item the default focused item of a window. Please use instead of "if (IsWindowAppearing()) SetScrollHere()" to signify "default item". + IMGUI_API void SetKeyboardFocusHere(int offset = 0); // focus keyboard on the next widget. Use positive 'offset' to access sub components of a multiple component widget. Use -1 to access previous widget. + // Utilities - IMGUI_API bool IsItemHovered(); // was the last item hovered by mouse? - IMGUI_API bool IsItemHoveredRect(); // was the last item hovered by mouse? even if another item is active or window is blocked by popup while we are hovering this - IMGUI_API bool IsItemActive(); // was the last item active? (e.g. button being held, text field being edited- items that don't interact will always return false) - IMGUI_API bool IsItemClicked(int mouse_button = 0); // was the last item clicked? (e.g. button/node just clicked on) - IMGUI_API bool IsItemVisible(); // was the last item visible? (aka not out of sight due to clipping/scrolling.) + IMGUI_API bool IsItemHovered(ImGuiHoveredFlags flags = 0); // is the last item hovered? (and usable, aka not blocked by a popup, etc.). See ImGuiHoveredFlags for more options. + IMGUI_API bool IsItemActive(); // is the last item active? (e.g. button being held, text field being edited- items that don't interact will always return false) + IMGUI_API bool IsItemFocused(); // is the last item focused for keyboard/gamepad navigation? + IMGUI_API bool IsItemClicked(int mouse_button = 0); // is the last item clicked? (e.g. button/node just clicked on) + IMGUI_API bool IsItemVisible(); // is the last item visible? (aka not out of sight due to clipping/scrolling.) IMGUI_API bool IsAnyItemHovered(); IMGUI_API bool IsAnyItemActive(); - IMGUI_API ImVec2 GetItemRectMin(); // get bounding rect of last item in screen space + IMGUI_API bool IsAnyItemFocused(); + IMGUI_API ImVec2 GetItemRectMin(); // get bounding rectangle of last item, in screen space IMGUI_API ImVec2 GetItemRectMax(); // " - IMGUI_API ImVec2 GetItemRectSize(); // " + IMGUI_API ImVec2 GetItemRectSize(); // get size of last item, in screen space IMGUI_API void SetItemAllowOverlap(); // allow last item to be overlapped by a subsequent item. sometimes useful with invisible buttons, selectables, etc. to catch unused area. - IMGUI_API bool IsWindowHovered(); // is current window hovered and hoverable (not blocked by a popup) (differentiate child windows from each others) - IMGUI_API bool IsWindowFocused(); // is current window focused - IMGUI_API bool IsRootWindowFocused(); // is current root window focused (root = top-most parent of a child, otherwise self) - IMGUI_API bool IsRootWindowOrAnyChildFocused(); // is current root window or any of its child (including current window) focused - IMGUI_API bool IsRootWindowOrAnyChildHovered(); // is current root window or any of its child (including current window) hovered and hoverable (not blocked by a popup) IMGUI_API bool IsRectVisible(const ImVec2& size); // test if rectangle (of given size, starting from cursor position) is visible / not clipped. IMGUI_API bool IsRectVisible(const ImVec2& rect_min, const ImVec2& rect_max); // test if rectangle (in screen space) is visible / not clipped. to perform coarse clipping on user's side. - IMGUI_API bool IsPosHoveringAnyWindow(const ImVec2& pos); // is given position hovering any active imgui window IMGUI_API float GetTime(); IMGUI_API int GetFrameCount(); - IMGUI_API const char* GetStyleColName(ImGuiCol idx); - IMGUI_API ImVec2 CalcItemRectClosestPoint(const ImVec2& pos, bool on_edge = false, float outward = +0.0f); // utility to find the closest point the last item bounding rectangle edge. useful to visually link items + IMGUI_API ImDrawList* GetOverlayDrawList(); // this draw list will be the last rendered one, useful to quickly draw overlays shapes/text + IMGUI_API ImDrawListSharedData* GetDrawListSharedData(); // you may use this when creating your own ImDrawList instances + IMGUI_API const char* GetStyleColorName(ImGuiCol idx); + IMGUI_API void SetStateStorage(ImGuiStorage* storage); // replace current window storage with our own (if you want to manipulate it yourself, typically clear subsection of it) + IMGUI_API ImGuiStorage* GetStateStorage(); IMGUI_API ImVec2 CalcTextSize(const char* text, const char* text_end = NULL, bool hide_text_after_double_hash = false, float wrap_width = -1.0f); IMGUI_API void CalcListClipping(int items_count, float items_height, int* out_items_display_start, int* out_items_display_end); // calculate coarse clipping for large list of evenly sized items. Prefer using the ImGuiListClipper higher-level helper if you can. - IMGUI_API bool BeginChildFrame(ImGuiID id, const ImVec2& size, ImGuiWindowFlags extra_flags = 0); // helper to create a child window / scrolling region that looks like a normal widget frame - IMGUI_API void EndChildFrame(); + IMGUI_API bool BeginChildFrame(ImGuiID id, const ImVec2& size, ImGuiWindowFlags flags = 0); // helper to create a child window / scrolling region that looks like a normal widget frame + IMGUI_API void EndChildFrame(); // always call EndChildFrame() regardless of BeginChildFrame() return values (which indicates a collapsed/clipped window) IMGUI_API ImVec4 ColorConvertU32ToFloat4(ImU32 in); IMGUI_API ImU32 ColorConvertFloat4ToU32(const ImVec4& in); @@ -427,67 +515,54 @@ namespace ImGui IMGUI_API void ColorConvertHSVtoRGB(float h, float s, float v, float& out_r, float& out_g, float& out_b); // Inputs - IMGUI_API int GetKeyIndex(ImGuiKey key); // map ImGuiKey_* values into user's key index. == io.KeyMap[key] - IMGUI_API bool IsKeyDown(int key_index); // key_index into the keys_down[] array, imgui doesn't know the semantic of each entry, uses your own indices! - IMGUI_API bool IsKeyPressed(int key_index, bool repeat = true); // uses user's key indices as stored in the keys_down[] array. if repeat=true. uses io.KeyRepeatDelay / KeyRepeatRate - IMGUI_API bool IsKeyReleased(int key_index); // " + IMGUI_API int GetKeyIndex(ImGuiKey imgui_key); // map ImGuiKey_* values into user's key index. == io.KeyMap[key] + IMGUI_API bool IsKeyDown(int user_key_index); // is key being held. == io.KeysDown[user_key_index]. note that imgui doesn't know the semantic of each entry of io.KeyDown[]. Use your own indices/enums according to how your backend/engine stored them into KeyDown[]! + IMGUI_API bool IsKeyPressed(int user_key_index, bool repeat = true); // was key pressed (went from !Down to Down). if repeat=true, uses io.KeyRepeatDelay / KeyRepeatRate + IMGUI_API bool IsKeyReleased(int user_key_index); // was key released (went from Down to !Down).. + IMGUI_API int GetKeyPressedAmount(int key_index, float repeat_delay, float rate); // uses provided repeat rate/delay. return a count, most often 0 or 1 but might be >1 if RepeatRate is small enough that DeltaTime > RepeatRate IMGUI_API bool IsMouseDown(int button); // is mouse button held + IMGUI_API bool IsAnyMouseDown(); // is any mouse button held IMGUI_API bool IsMouseClicked(int button, bool repeat = false); // did mouse button clicked (went from !Down to Down) IMGUI_API bool IsMouseDoubleClicked(int button); // did mouse button double-clicked. a double-click returns false in IsMouseClicked(). uses io.MouseDoubleClickTime. IMGUI_API bool IsMouseReleased(int button); // did mouse button released (went from Down to !Down) - IMGUI_API bool IsMouseHoveringWindow(); // is mouse hovering current window ("window" in API names always refer to current window). disregarding of any consideration of being blocked by a popup. (unlike IsWindowHovered() this will return true even if the window is blocked because of a popup) - IMGUI_API bool IsMouseHoveringAnyWindow(); // is mouse hovering any visible window - IMGUI_API bool IsMouseHoveringRect(const ImVec2& r_min, const ImVec2& r_max, bool clip = true); // is mouse hovering given bounding rect (in screen space). clipped by current clipping settings. disregarding of consideration of focus/window ordering/blocked by a popup. IMGUI_API bool IsMouseDragging(int button = 0, float lock_threshold = -1.0f); // is mouse dragging. if lock_threshold < -1.0f uses io.MouseDraggingThreshold + IMGUI_API bool IsMouseHoveringRect(const ImVec2& r_min, const ImVec2& r_max, bool clip = true); // is mouse hovering given bounding rect (in screen space). clipped by current clipping settings. disregarding of consideration of focus/window ordering/blocked by a popup. + IMGUI_API bool IsMousePosValid(const ImVec2* mouse_pos = NULL); // IMGUI_API ImVec2 GetMousePos(); // shortcut to ImGui::GetIO().MousePos provided by user, to be consistent with other calls - IMGUI_API ImVec2 GetMousePosOnOpeningCurrentPopup(); // retrieve backup of mouse positioning at the time of opening popup we have BeginPopup() into + IMGUI_API ImVec2 GetMousePosOnOpeningCurrentPopup(); // retrieve backup of mouse position at the time of opening popup we have BeginPopup() into IMGUI_API ImVec2 GetMouseDragDelta(int button = 0, float lock_threshold = -1.0f); // dragging amount since clicking. if lock_threshold < -1.0f uses io.MouseDraggingThreshold IMGUI_API void ResetMouseDragDelta(int button = 0); // - IMGUI_API ImGuiMouseCursor GetMouseCursor(); // get desired cursor type, reset in ImGui::NewFrame(), this updated during the frame. valid before Render(). If you use software rendering by setting io.MouseDrawCursor ImGui will render those for you + IMGUI_API ImGuiMouseCursor GetMouseCursor(); // get desired cursor type, reset in ImGui::NewFrame(), this is updated during the frame. valid before Render(). If you use software rendering by setting io.MouseDrawCursor ImGui will render those for you IMGUI_API void SetMouseCursor(ImGuiMouseCursor type); // set desired cursor type - IMGUI_API void CaptureKeyboardFromApp(bool capture = true); // manually override io.WantCaptureKeyboard flag next frame (said flag is entirely left for your application handle). e.g. force capture keyboard when your widget is being hovered. - IMGUI_API void CaptureMouseFromApp(bool capture = true); // manually override io.WantCaptureMouse flag next frame (said flag is entirely left for your application handle). + IMGUI_API void CaptureKeyboardFromApp(bool capture = true); // manually override io.WantCaptureKeyboard flag next frame (said flag is entirely left for your application to handle). e.g. force capture keyboard when your widget is being hovered. + IMGUI_API void CaptureMouseFromApp(bool capture = true); // manually override io.WantCaptureMouse flag next frame (said flag is entirely left for your application to handle). - // Helpers functions to access functions pointers in ImGui::GetIO() - IMGUI_API void* MemAlloc(size_t sz); - IMGUI_API void MemFree(void* ptr); + // Clipboard Utilities (also see the LogToClipboard() function to capture or output text data to the clipboard) IMGUI_API const char* GetClipboardText(); IMGUI_API void SetClipboardText(const char* text); - // Internal context access - if you want to use multiple context, share context between modules (e.g. DLL). There is a default context created and active by default. - // All contexts share a same ImFontAtlas by default. If you want different font atlas, you can new() them and overwrite the GetIO().Fonts variable of an ImGui context. - IMGUI_API const char* GetVersion(); - IMGUI_API ImGuiContext* CreateContext(void* (*malloc_fn)(size_t) = NULL, void (*free_fn)(void*) = NULL); - IMGUI_API void DestroyContext(ImGuiContext* ctx); - IMGUI_API ImGuiContext* GetCurrentContext(); - IMGUI_API void SetCurrentContext(ImGuiContext* ctx); - - // Obsolete (will be removed) -#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS - static inline bool CollapsingHeader(const char* label, const char* str_id, bool framed = true, bool default_open = false) { (void)str_id; (void)framed; ImGuiTreeNodeFlags default_open_flags = 1<<5; return CollapsingHeader(label, (default_open ? default_open_flags : 0)); } // OBSOLETE 1.49+ - static inline ImFont* GetWindowFont() { return GetFont(); } // OBSOLETE 1.48+ - static inline float GetWindowFontSize() { return GetFontSize(); } // OBSOLETE 1.48+ - static inline void SetScrollPosHere() { SetScrollHere(); } // OBSOLETE 1.42+ - static inline bool GetWindowCollapsed() { return ImGui::IsWindowCollapsed(); } // OBSOLETE 1.39+ - static inline bool IsRectClipped(const ImVec2& size) { return !IsRectVisible(size); } // OBSOLETE 1.39+ -#endif + // Memory Utilities + // All those functions are not reliant on the current context. + // If you reload the contents of imgui.cpp at runtime, you may need to call SetCurrentContext() + SetAllocatorFunctions() again. + IMGUI_API void SetAllocatorFunctions(void* (*alloc_func)(size_t sz, void* user_data), void(*free_func)(void* ptr, void* user_data), void* user_data = NULL); + IMGUI_API void* MemAlloc(size_t size); + IMGUI_API void MemFree(void* ptr); } // namespace ImGui // Flags for ImGui::Begin() enum ImGuiWindowFlags_ { - // Default: 0 ImGuiWindowFlags_NoTitleBar = 1 << 0, // Disable title-bar ImGuiWindowFlags_NoResize = 1 << 1, // Disable user resizing with the lower-right grip ImGuiWindowFlags_NoMove = 1 << 2, // Disable user moving the window ImGuiWindowFlags_NoScrollbar = 1 << 3, // Disable scrollbars (window can still scroll with mouse or programatically) - ImGuiWindowFlags_NoScrollWithMouse = 1 << 4, // Disable user vertically scrolling with mouse wheel + ImGuiWindowFlags_NoScrollWithMouse = 1 << 4, // Disable user vertically scrolling with mouse wheel. On child window, mouse wheel will be forwarded to the parent unless NoScrollbar is also set. ImGuiWindowFlags_NoCollapse = 1 << 5, // Disable user collapsing window by double-clicking on it ImGuiWindowFlags_AlwaysAutoResize = 1 << 6, // Resize every window to its content every frame - ImGuiWindowFlags_ShowBorders = 1 << 7, // Show borders around windows and items + //ImGuiWindowFlags_ShowBorders = 1 << 7, // Show borders around windows and items (OBSOLETE! Use e.g. style.FrameBorderSize=1.0f to enable borders). ImGuiWindowFlags_NoSavedSettings = 1 << 8, // Never load/save settings in .ini file - ImGuiWindowFlags_NoInputs = 1 << 9, // Disable catching mouse or keyboard inputs + ImGuiWindowFlags_NoInputs = 1 << 9, // Disable catching mouse or keyboard inputs, hovering test with pass through. ImGuiWindowFlags_MenuBar = 1 << 10, // Has a menu-bar ImGuiWindowFlags_HorizontalScrollbar = 1 << 11, // Allow horizontal scrollbar to appear (off by default). You may use SetNextWindowContentSize(ImVec2(width,0.0f)); prior to calling Begin() to specify width. Read code in imgui_demo in the "Horizontal Scrolling" section. ImGuiWindowFlags_NoFocusOnAppearing = 1 << 12, // Disable taking focus when transitioning from hidden to visible state @@ -495,21 +570,23 @@ enum ImGuiWindowFlags_ ImGuiWindowFlags_AlwaysVerticalScrollbar= 1 << 14, // Always show vertical scrollbar (even if ContentSize.y < Size.y) ImGuiWindowFlags_AlwaysHorizontalScrollbar=1<< 15, // Always show horizontal scrollbar (even if ContentSize.x < Size.x) ImGuiWindowFlags_AlwaysUseWindowPadding = 1 << 16, // Ensure child windows without border uses style.WindowPadding (ignored by default for non-bordered child windows, because more convenient) + ImGuiWindowFlags_ResizeFromAnySide = 1 << 17, // [BETA] Enable resize from any corners and borders. Your back-end needs to honor the different values of io.MouseCursor set by imgui. + ImGuiWindowFlags_NoNavInputs = 1 << 18, // No gamepad/keyboard navigation within the window + ImGuiWindowFlags_NoNavFocus = 1 << 19, // No focusing toward this window with gamepad/keyboard navigation (e.g. skipped by CTRL+TAB) + ImGuiWindowFlags_NoNav = ImGuiWindowFlags_NoNavInputs | ImGuiWindowFlags_NoNavFocus, + // [Internal] - ImGuiWindowFlags_ChildWindow = 1 << 20, // Don't use! For internal use by BeginChild() - ImGuiWindowFlags_ChildWindowAutoFitX = 1 << 21, // Don't use! For internal use by BeginChild() - ImGuiWindowFlags_ChildWindowAutoFitY = 1 << 22, // Don't use! For internal use by BeginChild() - ImGuiWindowFlags_ComboBox = 1 << 23, // Don't use! For internal use by ComboBox() - ImGuiWindowFlags_Tooltip = 1 << 24, // Don't use! For internal use by BeginTooltip() - ImGuiWindowFlags_Popup = 1 << 25, // Don't use! For internal use by BeginPopup() - ImGuiWindowFlags_Modal = 1 << 26, // Don't use! For internal use by BeginPopupModal() - ImGuiWindowFlags_ChildMenu = 1 << 27 // Don't use! For internal use by BeginMenu() + ImGuiWindowFlags_NavFlattened = 1 << 23, // [BETA] Allow gamepad/keyboard navigation to cross over parent border to this child (only use on child that have no scrolling!) + ImGuiWindowFlags_ChildWindow = 1 << 24, // Don't use! For internal use by BeginChild() + ImGuiWindowFlags_Tooltip = 1 << 25, // Don't use! For internal use by BeginTooltip() + ImGuiWindowFlags_Popup = 1 << 26, // Don't use! For internal use by BeginPopup() + ImGuiWindowFlags_Modal = 1 << 27, // Don't use! For internal use by BeginPopupModal() + ImGuiWindowFlags_ChildMenu = 1 << 28 // Don't use! For internal use by BeginMenu() }; // Flags for ImGui::InputText() enum ImGuiInputTextFlags_ { - // Default: 0 ImGuiInputTextFlags_CharsDecimal = 1 << 0, // Allow 0123456789.+-*/ ImGuiInputTextFlags_CharsHexadecimal = 1 << 1, // Allow 0123456789ABCDEFabcdef ImGuiInputTextFlags_CharsUppercase = 1 << 2, // Turn a..z into A..Z @@ -521,11 +598,13 @@ enum ImGuiInputTextFlags_ ImGuiInputTextFlags_CallbackAlways = 1 << 8, // Call user function every time. User code may query cursor position, modify text buffer. ImGuiInputTextFlags_CallbackCharFilter = 1 << 9, // Call user function to filter character. Modify data->EventChar to replace/filter input, or return 1 to discard character. ImGuiInputTextFlags_AllowTabInput = 1 << 10, // Pressing TAB input a '\t' character into the text field - ImGuiInputTextFlags_CtrlEnterForNewLine = 1 << 11, // In multi-line mode, allow exiting edition by pressing Enter. Ctrl+Enter to add new line (by default adds new lines with Enter). + ImGuiInputTextFlags_CtrlEnterForNewLine = 1 << 11, // In multi-line mode, unfocus with Enter, add new line with Ctrl+Enter (default is opposite: unfocus with Ctrl+Enter, add line with Enter). ImGuiInputTextFlags_NoHorizontalScroll = 1 << 12, // Disable following the cursor horizontally ImGuiInputTextFlags_AlwaysInsertMode = 1 << 13, // Insert mode ImGuiInputTextFlags_ReadOnly = 1 << 14, // Read-only mode ImGuiInputTextFlags_Password = 1 << 15, // Password mode, display all characters as '*' + ImGuiInputTextFlags_NoUndoRedo = 1 << 16, // Disable undo/redo. Note that input text owns the text data while active, if you want to provide your own undo/redo stack you need e.g. to call ClearActiveID(). + ImGuiInputTextFlags_CharsScientific = 1 << 17, // Allow 0123456789.+-*/eE (Scientific notation input) // [Internal] ImGuiInputTextFlags_Multiline = 1 << 20 // For internal use by InputTextMultiline() }; @@ -535,7 +614,7 @@ enum ImGuiTreeNodeFlags_ { ImGuiTreeNodeFlags_Selected = 1 << 0, // Draw as selected ImGuiTreeNodeFlags_Framed = 1 << 1, // Full colored frame (e.g. for CollapsingHeader) - ImGuiTreeNodeFlags_AllowOverlapMode = 1 << 2, // Hit testing to allow subsequent widgets to overlap this one + ImGuiTreeNodeFlags_AllowItemOverlap = 1 << 2, // Hit testing to allow subsequent widgets to overlap this one ImGuiTreeNodeFlags_NoTreePushOnOpen = 1 << 3, // Don't do a TreePush() when open (e.g. for CollapsingHeader) = no extra indent nor pushing on ID stack ImGuiTreeNodeFlags_NoAutoOpenOnLog = 1 << 4, // Don't automatically and temporarily open node when Logging is active (by default logging will automatically open tree nodes) ImGuiTreeNodeFlags_DefaultOpen = 1 << 5, // Default node to be open @@ -543,36 +622,112 @@ enum ImGuiTreeNodeFlags_ ImGuiTreeNodeFlags_OpenOnArrow = 1 << 7, // Only open when clicking on the arrow part. If ImGuiTreeNodeFlags_OpenOnDoubleClick is also set, single-click arrow or double-click all box to open. ImGuiTreeNodeFlags_Leaf = 1 << 8, // No collapsing, no arrow (use as a convenience for leaf nodes). ImGuiTreeNodeFlags_Bullet = 1 << 9, // Display a bullet instead of arrow - //ImGuITreeNodeFlags_SpanAllAvailWidth = 1 << 10, // FIXME: TODO: Extend hit box horizontally even if not framed - //ImGuiTreeNodeFlags_NoScrollOnOpen = 1 << 11, // FIXME: TODO: Disable automatic scroll on TreePop() if node got just open and contents is not visible + ImGuiTreeNodeFlags_FramePadding = 1 << 10, // Use FramePadding (even for an unframed text node) to vertically align text baseline to regular widget height. Equivalent to calling AlignTextToFramePadding(). + //ImGuITreeNodeFlags_SpanAllAvailWidth = 1 << 11, // FIXME: TODO: Extend hit box horizontally even if not framed + //ImGuiTreeNodeFlags_NoScrollOnOpen = 1 << 12, // FIXME: TODO: Disable automatic scroll on TreePop() if node got just open and contents is not visible + ImGuiTreeNodeFlags_NavLeftJumpsBackHere = 1 << 13, // (WIP) Nav: left direction may move to this TreeNode() from any of its child (items submitted between TreeNode and TreePop) ImGuiTreeNodeFlags_CollapsingHeader = ImGuiTreeNodeFlags_Framed | ImGuiTreeNodeFlags_NoAutoOpenOnLog + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiTreeNodeFlags_AllowOverlapMode = ImGuiTreeNodeFlags_AllowItemOverlap +#endif }; // Flags for ImGui::Selectable() enum ImGuiSelectableFlags_ { - // Default: 0 ImGuiSelectableFlags_DontClosePopups = 1 << 0, // Clicking this don't close parent popup window ImGuiSelectableFlags_SpanAllColumns = 1 << 1, // Selectable frame can span all columns (text will still fit in current column) ImGuiSelectableFlags_AllowDoubleClick = 1 << 2 // Generate press events on double clicks too }; +// Flags for ImGui::BeginCombo() +enum ImGuiComboFlags_ +{ + ImGuiComboFlags_PopupAlignLeft = 1 << 0, // Align the popup toward the left by default + ImGuiComboFlags_HeightSmall = 1 << 1, // Max ~4 items visible. Tip: If you want your combo popup to be a specific size you can use SetNextWindowSizeConstraints() prior to calling BeginCombo() + ImGuiComboFlags_HeightRegular = 1 << 2, // Max ~8 items visible (default) + ImGuiComboFlags_HeightLarge = 1 << 3, // Max ~20 items visible + ImGuiComboFlags_HeightLargest = 1 << 4, // As many fitting items as possible + ImGuiComboFlags_NoArrowButton = 1 << 5, // Display on the preview box without the square arrow button + ImGuiComboFlags_NoPreview = 1 << 6, // Display only a square arrow button + ImGuiComboFlags_HeightMask_ = ImGuiComboFlags_HeightSmall | ImGuiComboFlags_HeightRegular | ImGuiComboFlags_HeightLarge | ImGuiComboFlags_HeightLargest +}; + +// Flags for ImGui::IsWindowFocused() +enum ImGuiFocusedFlags_ +{ + ImGuiFocusedFlags_ChildWindows = 1 << 0, // IsWindowFocused(): Return true if any children of the window is focused + ImGuiFocusedFlags_RootWindow = 1 << 1, // IsWindowFocused(): Test from root window (top most parent of the current hierarchy) + ImGuiFocusedFlags_AnyWindow = 1 << 2, // IsWindowFocused(): Return true if any window is focused + ImGuiFocusedFlags_RootAndChildWindows = ImGuiFocusedFlags_RootWindow | ImGuiFocusedFlags_ChildWindows +}; + +// Flags for ImGui::IsItemHovered(), ImGui::IsWindowHovered() +// Note: If you are trying to check whether your mouse should be dispatched to imgui or to your app, you should use the 'io.WantCaptureMouse' boolean for that. Please read the FAQ! +enum ImGuiHoveredFlags_ +{ + ImGuiHoveredFlags_Default = 0, // Return true if directly over the item/window, not obstructed by another window, not obstructed by an active popup or modal blocking inputs under them. + ImGuiHoveredFlags_ChildWindows = 1 << 0, // IsWindowHovered() only: Return true if any children of the window is hovered + ImGuiHoveredFlags_RootWindow = 1 << 1, // IsWindowHovered() only: Test from root window (top most parent of the current hierarchy) + ImGuiHoveredFlags_AnyWindow = 1 << 2, // IsWindowHovered() only: Return true if any window is hovered + ImGuiHoveredFlags_AllowWhenBlockedByPopup = 1 << 3, // Return true even if a popup window is normally blocking access to this item/window + //ImGuiHoveredFlags_AllowWhenBlockedByModal = 1 << 4, // Return true even if a modal popup window is normally blocking access to this item/window. FIXME-TODO: Unavailable yet. + ImGuiHoveredFlags_AllowWhenBlockedByActiveItem = 1 << 5, // Return true even if an active item is blocking access to this item/window. Useful for Drag and Drop patterns. + ImGuiHoveredFlags_AllowWhenOverlapped = 1 << 6, // Return true even if the position is overlapped by another window + ImGuiHoveredFlags_RectOnly = ImGuiHoveredFlags_AllowWhenBlockedByPopup | ImGuiHoveredFlags_AllowWhenBlockedByActiveItem | ImGuiHoveredFlags_AllowWhenOverlapped, + ImGuiHoveredFlags_RootAndChildWindows = ImGuiHoveredFlags_RootWindow | ImGuiHoveredFlags_ChildWindows +}; + +// Flags for ImGui::BeginDragDropSource(), ImGui::AcceptDragDropPayload() +enum ImGuiDragDropFlags_ +{ + // BeginDragDropSource() flags + ImGuiDragDropFlags_SourceNoPreviewTooltip = 1 << 0, // By default, a successful call to BeginDragDropSource opens a tooltip so you can display a preview or description of the source contents. This flag disable this behavior. + ImGuiDragDropFlags_SourceNoDisableHover = 1 << 1, // By default, when dragging we clear data so that IsItemHovered() will return true, to avoid subsequent user code submitting tooltips. This flag disable this behavior so you can still call IsItemHovered() on the source item. + ImGuiDragDropFlags_SourceNoHoldToOpenOthers = 1 << 2, // Disable the behavior that allows to open tree nodes and collapsing header by holding over them while dragging a source item. + ImGuiDragDropFlags_SourceAllowNullID = 1 << 3, // Allow items such as Text(), Image() that have no unique identifier to be used as drag source, by manufacturing a temporary identifier based on their window-relative position. This is extremely unusual within the dear imgui ecosystem and so we made it explicit. + ImGuiDragDropFlags_SourceExtern = 1 << 4, // External source (from outside of imgui), won't attempt to read current item/window info. Will always return true. Only one Extern source can be active simultaneously. + // AcceptDragDropPayload() flags + ImGuiDragDropFlags_AcceptBeforeDelivery = 1 << 10, // AcceptDragDropPayload() will returns true even before the mouse button is released. You can then call IsDelivery() to test if the payload needs to be delivered. + ImGuiDragDropFlags_AcceptNoDrawDefaultRect = 1 << 11, // Do not draw the default highlight rectangle when hovering over target. + ImGuiDragDropFlags_AcceptPeekOnly = ImGuiDragDropFlags_AcceptBeforeDelivery | ImGuiDragDropFlags_AcceptNoDrawDefaultRect // For peeking ahead and inspecting the payload before delivery. +}; + +// Standard Drag and Drop payload types. You can define you own payload types using 12-characters long strings. Types starting with '_' are defined by Dear ImGui. +#define IMGUI_PAYLOAD_TYPE_COLOR_3F "_COL3F" // float[3]: Standard type for colors, without alpha. User code may use this type. +#define IMGUI_PAYLOAD_TYPE_COLOR_4F "_COL4F" // float[4]: Standard type for colors. User code may use this type. + +// A cardinal direction +enum ImGuiDir_ +{ + ImGuiDir_None = -1, + ImGuiDir_Left = 0, + ImGuiDir_Right = 1, + ImGuiDir_Up = 2, + ImGuiDir_Down = 3, + ImGuiDir_COUNT +}; + // User fill ImGuiIO.KeyMap[] array with indices into the ImGuiIO.KeysDown[512] array enum ImGuiKey_ { - ImGuiKey_Tab, // for tabbing through fields - ImGuiKey_LeftArrow, // for text edit - ImGuiKey_RightArrow,// for text edit - ImGuiKey_UpArrow, // for text edit - ImGuiKey_DownArrow, // for text edit + ImGuiKey_Tab, + ImGuiKey_LeftArrow, + ImGuiKey_RightArrow, + ImGuiKey_UpArrow, + ImGuiKey_DownArrow, ImGuiKey_PageUp, ImGuiKey_PageDown, - ImGuiKey_Home, // for text edit - ImGuiKey_End, // for text edit - ImGuiKey_Delete, // for text edit - ImGuiKey_Backspace, // for text edit - ImGuiKey_Enter, // for text edit - ImGuiKey_Escape, // for text edit + ImGuiKey_Home, + ImGuiKey_End, + ImGuiKey_Insert, + ImGuiKey_Delete, + ImGuiKey_Backspace, + ImGuiKey_Space, + ImGuiKey_Enter, + ImGuiKey_Escape, ImGuiKey_A, // for text edit CTRL+A: select all ImGuiKey_C, // for text edit CTRL+C: copy ImGuiKey_V, // for text edit CTRL+V: paste @@ -582,13 +737,71 @@ enum ImGuiKey_ ImGuiKey_COUNT }; +// [BETA] Gamepad/Keyboard directional navigation +// Keyboard: Set io.ConfigFlags |= ImGuiConfigFlags_NavEnableKeyboard to enable. NewFrame() will automatically fill io.NavInputs[] based on your io.KeyDown[] + io.KeyMap[] arrays. +// Gamepad: Set io.ConfigFlags |= ImGuiConfigFlags_NavEnableGamepad to enable. Back-end: set ImGuiBackendFlags_HasGamepad and fill the io.NavInputs[] fields before calling NewFrame(). Note that io.NavInputs[] is cleared by EndFrame(). +// Read instructions in imgui.cpp for more details. Download PNG/PSD at goo.gl/9LgVZW. +enum ImGuiNavInput_ +{ + // Gamepad Mapping + ImGuiNavInput_Activate, // activate / open / toggle / tweak value // e.g. Cross (PS4), A (Xbox), A (Switch), Space (Keyboard) + ImGuiNavInput_Cancel, // cancel / close / exit // e.g. Circle (PS4), B (Xbox), B (Switch), Escape (Keyboard) + ImGuiNavInput_Input, // text input / on-screen keyboard // e.g. Triang.(PS4), Y (Xbox), X (Switch), Return (Keyboard) + ImGuiNavInput_Menu, // tap: toggle menu / hold: focus, move, resize // e.g. Square (PS4), X (Xbox), Y (Switch), Alt (Keyboard) + ImGuiNavInput_DpadLeft, // move / tweak / resize window (w/ PadMenu) // e.g. D-pad Left/Right/Up/Down (Gamepads), Arrow keys (Keyboard) + ImGuiNavInput_DpadRight, // + ImGuiNavInput_DpadUp, // + ImGuiNavInput_DpadDown, // + ImGuiNavInput_LStickLeft, // scroll / move window (w/ PadMenu) // e.g. Left Analog Stick Left/Right/Up/Down + ImGuiNavInput_LStickRight, // + ImGuiNavInput_LStickUp, // + ImGuiNavInput_LStickDown, // + ImGuiNavInput_FocusPrev, // next window (w/ PadMenu) // e.g. L1 or L2 (PS4), LB or LT (Xbox), L or ZL (Switch) + ImGuiNavInput_FocusNext, // prev window (w/ PadMenu) // e.g. R1 or R2 (PS4), RB or RT (Xbox), R or ZL (Switch) + ImGuiNavInput_TweakSlow, // slower tweaks // e.g. L1 or L2 (PS4), LB or LT (Xbox), L or ZL (Switch) + ImGuiNavInput_TweakFast, // faster tweaks // e.g. R1 or R2 (PS4), RB or RT (Xbox), R or ZL (Switch) + + // [Internal] Don't use directly! This is used internally to differentiate keyboard from gamepad inputs for behaviors that require to differentiate them. + // Keyboard behavior that have no corresponding gamepad mapping (e.g. CTRL+TAB) will be directly reading from io.KeyDown[] instead of io.NavInputs[]. + ImGuiNavInput_KeyMenu_, // toggle menu // = io.KeyAlt + ImGuiNavInput_KeyLeft_, // move left // = Arrow keys + ImGuiNavInput_KeyRight_, // move right + ImGuiNavInput_KeyUp_, // move up + ImGuiNavInput_KeyDown_, // move down + ImGuiNavInput_COUNT, + ImGuiNavInput_InternalStart_ = ImGuiNavInput_KeyMenu_ +}; + +// Configuration flags stored in io.ConfigFlags. Set by user/application. +enum ImGuiConfigFlags_ +{ + ImGuiConfigFlags_NavEnableKeyboard = 1 << 0, // Master keyboard navigation enable flag. NewFrame() will automatically fill io.NavInputs[] based on io.KeyDown[]. + ImGuiConfigFlags_NavEnableGamepad = 1 << 1, // Master gamepad navigation enable flag. This is mostly to instruct your imgui back-end to fill io.NavInputs[]. Back-end also needs to set ImGuiBackendFlags_HasGamepad. + ImGuiConfigFlags_NavEnableSetMousePos = 1 << 2, // Instruct navigation to move the mouse cursor. May be useful on TV/console systems where moving a virtual mouse is awkward. Will update io.MousePos and set io.WantSetMousePos=true. If enabled you MUST honor io.WantSetMousePos requests in your binding, otherwise ImGui will react as if the mouse is jumping around back and forth. + ImGuiConfigFlags_NavNoCaptureKeyboard = 1 << 3, // Instruct navigation to not set the io.WantCaptureKeyboard flag with io.NavActive is set. + ImGuiConfigFlags_NoMouse = 1 << 4, // Instruct imgui to clear mouse position/buttons in NewFrame(). This allows ignoring the mouse information back-end + ImGuiConfigFlags_NoMouseCursorChange = 1 << 5, // Instruct back-end to not alter mouse cursor shape and visibility. + + // User storage (to allow your back-end/engine to communicate to code that may be shared between multiple projects. Those flags are not used by core ImGui) + ImGuiConfigFlags_IsSRGB = 1 << 20, // Application is SRGB-aware. + ImGuiConfigFlags_IsTouchScreen = 1 << 21 // Application is using a touch screen instead of a mouse. +}; + +// Back-end capabilities flags stored in io.BackendFlags. Set by imgui_impl_xxx or custom back-end. +enum ImGuiBackendFlags_ +{ + ImGuiBackendFlags_HasGamepad = 1 << 0, // Back-end has a connected gamepad. + ImGuiBackendFlags_HasMouseCursors = 1 << 1, // Back-end can honor GetMouseCursor() values and change the OS cursor shape. + ImGuiBackendFlags_HasSetMousePos = 1 << 2 // Back-end can honor io.WantSetMousePos and reposition the mouse (only used if ImGuiConfigFlags_NavEnableSetMousePos is set). +}; + // Enumeration for PushStyleColor() / PopStyleColor() enum ImGuiCol_ { ImGuiCol_Text, ImGuiCol_TextDisabled, ImGuiCol_WindowBg, // Background of normal windows - ImGuiCol_ChildWindowBg, // Background of child windows + ImGuiCol_ChildBg, // Background of child windows ImGuiCol_PopupBg, // Background of popups, menus, tooltips windows ImGuiCol_Border, ImGuiCol_BorderShadow, @@ -596,14 +809,13 @@ enum ImGuiCol_ ImGuiCol_FrameBgHovered, ImGuiCol_FrameBgActive, ImGuiCol_TitleBg, - ImGuiCol_TitleBgCollapsed, ImGuiCol_TitleBgActive, + ImGuiCol_TitleBgCollapsed, ImGuiCol_MenuBarBg, ImGuiCol_ScrollbarBg, ImGuiCol_ScrollbarGrab, ImGuiCol_ScrollbarGrabHovered, ImGuiCol_ScrollbarGrabActive, - ImGuiCol_ComboBg, ImGuiCol_CheckMark, ImGuiCol_SliderGrab, ImGuiCol_SliderGrabActive, @@ -613,105 +825,170 @@ enum ImGuiCol_ ImGuiCol_Header, ImGuiCol_HeaderHovered, ImGuiCol_HeaderActive, - ImGuiCol_Column, - ImGuiCol_ColumnHovered, - ImGuiCol_ColumnActive, + ImGuiCol_Separator, + ImGuiCol_SeparatorHovered, + ImGuiCol_SeparatorActive, ImGuiCol_ResizeGrip, ImGuiCol_ResizeGripHovered, ImGuiCol_ResizeGripActive, - ImGuiCol_CloseButton, - ImGuiCol_CloseButtonHovered, - ImGuiCol_CloseButtonActive, ImGuiCol_PlotLines, ImGuiCol_PlotLinesHovered, ImGuiCol_PlotHistogram, ImGuiCol_PlotHistogramHovered, ImGuiCol_TextSelectedBg, - ImGuiCol_ModalWindowDarkening, // darken entire screen when a modal window is active + ImGuiCol_ModalWindowDarkening, // darken/colorize entire screen behind a modal window, when one is active + ImGuiCol_DragDropTarget, + ImGuiCol_NavHighlight, // gamepad/keyboard: current highlighted item + ImGuiCol_NavWindowingHighlight, // gamepad/keyboard: when holding NavMenu to focus/move/resize windows ImGuiCol_COUNT + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiCol_ChildWindowBg = ImGuiCol_ChildBg, ImGuiCol_Column = ImGuiCol_Separator, ImGuiCol_ColumnHovered = ImGuiCol_SeparatorHovered, ImGuiCol_ColumnActive = ImGuiCol_SeparatorActive + //ImGuiCol_CloseButton, ImGuiCol_CloseButtonActive, ImGuiCol_CloseButtonHovered, // [unused since 1.60+] the close button now uses regular button colors. + //ImGuiCol_ComboBg, // [unused since 1.53+] ComboBg has been merged with PopupBg, so a redirect isn't accurate. +#endif }; -// Enumeration for PushStyleVar() / PopStyleVar() -// NB: the enum only refers to fields of ImGuiStyle() which makes sense to be pushed/poped in UI code. Feel free to add others. +// Enumeration for PushStyleVar() / PopStyleVar() to temporarily modify the ImGuiStyle structure. +// NB: the enum only refers to fields of ImGuiStyle which makes sense to be pushed/popped inside UI code. During initialization, feel free to just poke into ImGuiStyle directly. +// NB: if changing this enum, you need to update the associated internal table GStyleVarInfo[] accordingly. This is where we link enum values to members offset/type. enum ImGuiStyleVar_ { - ImGuiStyleVar_Alpha, // float - ImGuiStyleVar_WindowPadding, // ImVec2 - ImGuiStyleVar_WindowRounding, // float - ImGuiStyleVar_WindowMinSize, // ImVec2 - ImGuiStyleVar_ChildWindowRounding, // float - ImGuiStyleVar_FramePadding, // ImVec2 - ImGuiStyleVar_FrameRounding, // float - ImGuiStyleVar_ItemSpacing, // ImVec2 - ImGuiStyleVar_ItemInnerSpacing, // ImVec2 - ImGuiStyleVar_IndentSpacing, // float - ImGuiStyleVar_GrabMinSize, // float - ImGuiStyleVar_ButtonTextAlign, // flags ImGuiAlign_* - ImGuiStyleVar_Count_ + // Enum name ......................// Member in ImGuiStyle structure (see ImGuiStyle for descriptions) + ImGuiStyleVar_Alpha, // float Alpha + ImGuiStyleVar_WindowPadding, // ImVec2 WindowPadding + ImGuiStyleVar_WindowRounding, // float WindowRounding + ImGuiStyleVar_WindowBorderSize, // float WindowBorderSize + ImGuiStyleVar_WindowMinSize, // ImVec2 WindowMinSize + ImGuiStyleVar_WindowTitleAlign, // ImVec2 WindowTitleAlign + ImGuiStyleVar_ChildRounding, // float ChildRounding + ImGuiStyleVar_ChildBorderSize, // float ChildBorderSize + ImGuiStyleVar_PopupRounding, // float PopupRounding + ImGuiStyleVar_PopupBorderSize, // float PopupBorderSize + ImGuiStyleVar_FramePadding, // ImVec2 FramePadding + ImGuiStyleVar_FrameRounding, // float FrameRounding + ImGuiStyleVar_FrameBorderSize, // float FrameBorderSize + ImGuiStyleVar_ItemSpacing, // ImVec2 ItemSpacing + ImGuiStyleVar_ItemInnerSpacing, // ImVec2 ItemInnerSpacing + ImGuiStyleVar_IndentSpacing, // float IndentSpacing + ImGuiStyleVar_ScrollbarSize, // float ScrollbarSize + ImGuiStyleVar_ScrollbarRounding, // float ScrollbarRounding + ImGuiStyleVar_GrabMinSize, // float GrabMinSize + ImGuiStyleVar_GrabRounding, // float GrabRounding + ImGuiStyleVar_ButtonTextAlign, // ImVec2 ButtonTextAlign + ImGuiStyleVar_COUNT + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiStyleVar_Count_ = ImGuiStyleVar_COUNT, ImGuiStyleVar_ChildWindowRounding = ImGuiStyleVar_ChildRounding +#endif }; -// Enumeration for ColorEditMode() -// FIXME-OBSOLETE: Will be replaced by future color/picker api -enum ImGuiColorEditMode_ +// Enumeration for ColorEdit3() / ColorEdit4() / ColorPicker3() / ColorPicker4() / ColorButton() +enum ImGuiColorEditFlags_ { - ImGuiColorEditMode_UserSelect = -2, - ImGuiColorEditMode_UserSelectShowButton = -1, - ImGuiColorEditMode_RGB = 0, - ImGuiColorEditMode_HSV = 1, - ImGuiColorEditMode_HEX = 2 + ImGuiColorEditFlags_NoAlpha = 1 << 1, // // ColorEdit, ColorPicker, ColorButton: ignore Alpha component (read 3 components from the input pointer). + ImGuiColorEditFlags_NoPicker = 1 << 2, // // ColorEdit: disable picker when clicking on colored square. + ImGuiColorEditFlags_NoOptions = 1 << 3, // // ColorEdit: disable toggling options menu when right-clicking on inputs/small preview. + ImGuiColorEditFlags_NoSmallPreview = 1 << 4, // // ColorEdit, ColorPicker: disable colored square preview next to the inputs. (e.g. to show only the inputs) + ImGuiColorEditFlags_NoInputs = 1 << 5, // // ColorEdit, ColorPicker: disable inputs sliders/text widgets (e.g. to show only the small preview colored square). + ImGuiColorEditFlags_NoTooltip = 1 << 6, // // ColorEdit, ColorPicker, ColorButton: disable tooltip when hovering the preview. + ImGuiColorEditFlags_NoLabel = 1 << 7, // // ColorEdit, ColorPicker: disable display of inline text label (the label is still forwarded to the tooltip and picker). + ImGuiColorEditFlags_NoSidePreview = 1 << 8, // // ColorPicker: disable bigger color preview on right side of the picker, use small colored square preview instead. + + // User Options (right-click on widget to change some of them). You can set application defaults using SetColorEditOptions(). The idea is that you probably don't want to override them in most of your calls, let the user choose and/or call SetColorEditOptions() during startup. + ImGuiColorEditFlags_AlphaBar = 1 << 9, // // ColorEdit, ColorPicker: show vertical alpha bar/gradient in picker. + ImGuiColorEditFlags_AlphaPreview = 1 << 10, // // ColorEdit, ColorPicker, ColorButton: display preview as a transparent color over a checkerboard, instead of opaque. + ImGuiColorEditFlags_AlphaPreviewHalf= 1 << 11, // // ColorEdit, ColorPicker, ColorButton: display half opaque / half checkerboard, instead of opaque. + ImGuiColorEditFlags_HDR = 1 << 12, // // (WIP) ColorEdit: Currently only disable 0.0f..1.0f limits in RGBA edition (note: you probably want to use ImGuiColorEditFlags_Float flag as well). + ImGuiColorEditFlags_RGB = 1 << 13, // [Inputs] // ColorEdit: choose one among RGB/HSV/HEX. ColorPicker: choose any combination using RGB/HSV/HEX. + ImGuiColorEditFlags_HSV = 1 << 14, // [Inputs] // " + ImGuiColorEditFlags_HEX = 1 << 15, // [Inputs] // " + ImGuiColorEditFlags_Uint8 = 1 << 16, // [DataType] // ColorEdit, ColorPicker, ColorButton: _display_ values formatted as 0..255. + ImGuiColorEditFlags_Float = 1 << 17, // [DataType] // ColorEdit, ColorPicker, ColorButton: _display_ values formatted as 0.0f..1.0f floats instead of 0..255 integers. No round-trip of value via integers. + ImGuiColorEditFlags_PickerHueBar = 1 << 18, // [PickerMode] // ColorPicker: bar for Hue, rectangle for Sat/Value. + ImGuiColorEditFlags_PickerHueWheel = 1 << 19, // [PickerMode] // ColorPicker: wheel for Hue, triangle for Sat/Value. + + // [Internal] Masks + ImGuiColorEditFlags__InputsMask = ImGuiColorEditFlags_RGB|ImGuiColorEditFlags_HSV|ImGuiColorEditFlags_HEX, + ImGuiColorEditFlags__DataTypeMask = ImGuiColorEditFlags_Uint8|ImGuiColorEditFlags_Float, + ImGuiColorEditFlags__PickerMask = ImGuiColorEditFlags_PickerHueWheel|ImGuiColorEditFlags_PickerHueBar, + ImGuiColorEditFlags__OptionsDefault = ImGuiColorEditFlags_Uint8|ImGuiColorEditFlags_RGB|ImGuiColorEditFlags_PickerHueBar // Change application default using SetColorEditOptions() }; // Enumeration for GetMouseCursor() +// User code may request binding to display given cursor by calling SetMouseCursor(), which is why we have some cursors that are marked unused here enum ImGuiMouseCursor_ { + ImGuiMouseCursor_None = -1, ImGuiMouseCursor_Arrow = 0, ImGuiMouseCursor_TextInput, // When hovering over InputText, etc. - ImGuiMouseCursor_Move, // Unused - ImGuiMouseCursor_ResizeNS, // Unused - ImGuiMouseCursor_ResizeEW, // When hovering over a column - ImGuiMouseCursor_ResizeNESW, // Unused + ImGuiMouseCursor_ResizeAll, // Unused by imgui functions + ImGuiMouseCursor_ResizeNS, // When hovering over an horizontal border + ImGuiMouseCursor_ResizeEW, // When hovering over a vertical border or a column + ImGuiMouseCursor_ResizeNESW, // When hovering over the bottom-left corner of a window ImGuiMouseCursor_ResizeNWSE, // When hovering over the bottom-right corner of a window - ImGuiMouseCursor_Count_ + ImGuiMouseCursor_COUNT + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiMouseCursor_Count_ = ImGuiMouseCursor_COUNT +#endif }; -// Condition flags for ImGui::SetWindow***(), SetNextWindow***(), SetNextTreeNode***() functions -// All those functions treat 0 as a shortcut to ImGuiSetCond_Always -enum ImGuiSetCond_ +// Condition for ImGui::SetWindow***(), SetNextWindow***(), SetNextTreeNode***() functions +// Important: Treat as a regular enum! Do NOT combine multiple values using binary operators! All the functions above treat 0 as a shortcut to ImGuiCond_Always. +enum ImGuiCond_ { - ImGuiSetCond_Always = 1 << 0, // Set the variable - ImGuiSetCond_Once = 1 << 1, // Set the variable once per runtime session (only the first call with succeed) - ImGuiSetCond_FirstUseEver = 1 << 2, // Set the variable if the window has no saved data (if doesn't exist in the .ini file) - ImGuiSetCond_Appearing = 1 << 3 // Set the variable if the window is appearing after being hidden/inactive (or the first time) + ImGuiCond_Always = 1 << 0, // Set the variable + ImGuiCond_Once = 1 << 1, // Set the variable once per runtime session (only the first call with succeed) + ImGuiCond_FirstUseEver = 1 << 2, // Set the variable if the object/window has no persistently saved data (no entry in .ini file) + ImGuiCond_Appearing = 1 << 3 // Set the variable if the object/window is appearing after being hidden/inactive (or the first time) + + // Obsolete names (will be removed) +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + , ImGuiSetCond_Always = ImGuiCond_Always, ImGuiSetCond_Once = ImGuiCond_Once, ImGuiSetCond_FirstUseEver = ImGuiCond_FirstUseEver, ImGuiSetCond_Appearing = ImGuiCond_Appearing +#endif }; +// You may modify the ImGui::GetStyle() main instance during initialization and before NewFrame(). +// During the frame, use ImGui::PushStyleVar(ImGuiStyleVar_XXXX)/PopStyleVar() to alter the main style values, and ImGui::PushStyleColor(ImGuiCol_XXX)/PopStyleColor() for colors. struct ImGuiStyle { - float Alpha; // Global alpha applies to everything in ImGui - ImVec2 WindowPadding; // Padding within a window - ImVec2 WindowMinSize; // Minimum window size - float WindowRounding; // Radius of window corners rounding. Set to 0.0f to have rectangular windows + float Alpha; // Global alpha applies to everything in ImGui. + ImVec2 WindowPadding; // Padding within a window. + float WindowRounding; // Radius of window corners rounding. Set to 0.0f to have rectangular windows. + float WindowBorderSize; // Thickness of border around windows. Generally set to 0.0f or 1.0f. (Other values are not well tested and more CPU/GPU costly). + ImVec2 WindowMinSize; // Minimum window size. This is a global setting. If you want to constraint individual windows, use SetNextWindowSizeConstraints(). ImVec2 WindowTitleAlign; // Alignment for title bar text. Defaults to (0.0f,0.5f) for left-aligned,vertically centered. - float ChildWindowRounding; // Radius of child window corners rounding. Set to 0.0f to have rectangular windows - ImVec2 FramePadding; // Padding within a framed rectangle (used by most widgets) + float ChildRounding; // Radius of child window corners rounding. Set to 0.0f to have rectangular windows. + float ChildBorderSize; // Thickness of border around child windows. Generally set to 0.0f or 1.0f. (Other values are not well tested and more CPU/GPU costly). + float PopupRounding; // Radius of popup window corners rounding. (Note that tooltip windows use WindowRounding) + float PopupBorderSize; // Thickness of border around popup/tooltip windows. Generally set to 0.0f or 1.0f. (Other values are not well tested and more CPU/GPU costly). + ImVec2 FramePadding; // Padding within a framed rectangle (used by most widgets). float FrameRounding; // Radius of frame corners rounding. Set to 0.0f to have rectangular frame (used by most widgets). - ImVec2 ItemSpacing; // Horizontal and vertical spacing between widgets/lines - ImVec2 ItemInnerSpacing; // Horizontal and vertical spacing between within elements of a composed widget (e.g. a slider and its label) + float FrameBorderSize; // Thickness of border around frames. Generally set to 0.0f or 1.0f. (Other values are not well tested and more CPU/GPU costly). + ImVec2 ItemSpacing; // Horizontal and vertical spacing between widgets/lines. + ImVec2 ItemInnerSpacing; // Horizontal and vertical spacing between within elements of a composed widget (e.g. a slider and its label). ImVec2 TouchExtraPadding; // Expand reactive bounding box for touch-based system where touch position is not accurate enough. Unfortunately we don't sort widgets so priority on overlap will always be given to the first widget. So don't grow this too much! float IndentSpacing; // Horizontal indentation when e.g. entering a tree node. Generally == (FontSize + FramePadding.x*2). - float ColumnsMinSpacing; // Minimum horizontal spacing between two columns - float ScrollbarSize; // Width of the vertical scrollbar, Height of the horizontal scrollbar - float ScrollbarRounding; // Radius of grab corners for scrollbar + float ColumnsMinSpacing; // Minimum horizontal spacing between two columns. + float ScrollbarSize; // Width of the vertical scrollbar, Height of the horizontal scrollbar. + float ScrollbarRounding; // Radius of grab corners for scrollbar. float GrabMinSize; // Minimum width/height of a grab box for slider/scrollbar. float GrabRounding; // Radius of grabs corners rounding. Set to 0.0f to have rectangular slider grabs. ImVec2 ButtonTextAlign; // Alignment of button text when button is larger than text. Defaults to (0.5f,0.5f) for horizontally+vertically centered. ImVec2 DisplayWindowPadding; // Window positions are clamped to be visible within the display area by at least this amount. Only covers regular windows. ImVec2 DisplaySafeAreaPadding; // If you cannot see the edge of your screen (e.g. on a TV) increase the safe area padding. Covers popups/tooltips as well regular windows. + float MouseCursorScale; // Scale software rendered mouse cursor (when io.MouseDrawCursor is enabled). May be removed later. bool AntiAliasedLines; // Enable anti-aliasing on lines/borders. Disable if you are really tight on CPU/GPU. - bool AntiAliasedShapes; // Enable anti-aliasing on filled shapes (rounded rectangles, circles, etc.) - float CurveTessellationTol; // Tessellation tolerance. Decrease for highly tessellated curves (higher quality, more polygons), increase to reduce quality. + bool AntiAliasedFill; // Enable anti-aliasing on filled shapes (rounded rectangles, circles, etc.) + float CurveTessellationTol; // Tessellation tolerance when using PathBezierCurveTo() without a specific number of segments. Decrease for highly tessellated curves (higher quality, more polygons), increase to reduce quality. ImVec4 Colors[ImGuiCol_COUNT]; IMGUI_API ImGuiStyle(); + IMGUI_API void ScaleAllSizes(float scale_factor); }; // This is where your app communicate with ImGui. Access via ImGui::GetIO(). @@ -722,6 +999,8 @@ struct ImGuiIO // Settings (fill once) // Default value: //------------------------------------------------------------------ + ImGuiConfigFlags ConfigFlags; // = 0 // See ImGuiConfigFlags_ enum. Set by user/application. Gamepad/keyboard navigation options, etc. + ImGuiBackendFlags BackendFlags; // = 0 // Set ImGuiBackendFlags_ enum. Set by imgui_impl_xxx files or custom back-end. ImVec2 DisplaySize; // <unset> // Display size, in pixels. For clamping windows positions. float DeltaTime; // = 1.0f/60.0f // Time elapsed since last frame, in seconds. float IniSavingRate; // = 5.0f // Maximum time between saving positions/sizes to .ini file, in seconds. @@ -729,106 +1008,144 @@ struct ImGuiIO const char* LogFilename; // = "imgui_log.txt" // Path to .log file (default parameter to ImGui::LogToFile when no file is specified). float MouseDoubleClickTime; // = 0.30f // Time for a double-click, in seconds. float MouseDoubleClickMaxDist; // = 6.0f // Distance threshold to stay in to validate a double-click, in pixels. - float MouseDragThreshold; // = 6.0f // Distance threshold before considering we are dragging - int KeyMap[ImGuiKey_COUNT]; // <unset> // Map of indices into the KeysDown[512] entries array + float MouseDragThreshold; // = 6.0f // Distance threshold before considering we are dragging. + int KeyMap[ImGuiKey_COUNT]; // <unset> // Map of indices into the KeysDown[512] entries array which represent your "native" keyboard state. float KeyRepeatDelay; // = 0.250f // When holding a key/button, time before it starts repeating, in seconds (for buttons in Repeat mode, etc.). - float KeyRepeatRate; // = 0.020f // When holding a key/button, rate at which it repeats, in seconds. + float KeyRepeatRate; // = 0.050f // When holding a key/button, rate at which it repeats, in seconds. void* UserData; // = NULL // Store your own data for retrieval by callbacks. ImFontAtlas* Fonts; // <auto> // Load and assemble one or more fonts into a single tightly packed texture. Output to Fonts array. float FontGlobalScale; // = 1.0f // Global scale all fonts bool FontAllowUserScaling; // = false // Allow user scaling text of individual window with CTRL+Wheel. + ImFont* FontDefault; // = NULL // Font to use on NewFrame(). Use NULL to uses Fonts->Fonts[0]. ImVec2 DisplayFramebufferScale; // = (1.0f,1.0f) // For retina display or other situations where window coordinates are different from framebuffer coordinates. User storage only, presently not used by ImGui. ImVec2 DisplayVisibleMin; // <unset> (0.0f,0.0f) // If you use DisplaySize as a virtual space larger than your screen, set DisplayVisibleMin/Max to the visible area. ImVec2 DisplayVisibleMax; // <unset> (0.0f,0.0f) // If the values are the same, we defaults to Min=(0.0f) and Max=DisplaySize // Advanced/subtle behaviors - bool OSXBehaviors; // = defined(__APPLE__) // OS X style: Text editing cursor movement using Alt instead of Ctrl, Shortcuts using Cmd/Super instead of Ctrl, Line/Text Start and End using Cmd+Arrows instead of Home/End, Double click selects by word instead of selecting whole text, Multi-selection in lists uses Cmd/Super instead of Ctrl + bool OptMacOSXBehaviors; // = defined(__APPLE__) // OS X style: Text editing cursor movement using Alt instead of Ctrl, Shortcuts using Cmd/Super instead of Ctrl, Line/Text Start and End using Cmd+Arrows instead of Home/End, Double click selects by word instead of selecting whole text, Multi-selection in lists uses Cmd/Super instead of Ctrl + bool OptCursorBlink; // = true // Enable blinking cursor, for users who consider it annoying. //------------------------------------------------------------------ - // User Functions + // Settings (User Functions) //------------------------------------------------------------------ - // Rendering function, will be called in Render(). - // Alternatively you can keep this to NULL and call GetDrawData() after Render() to get the same pointer. - // See example applications if you are unsure of how to implement this. - void (*RenderDrawListsFn)(ImDrawData* data); - // Optional: access OS clipboard // (default to use native Win32 clipboard on Windows, otherwise uses a private clipboard. Override to access OS clipboard on other architectures) - const char* (*GetClipboardTextFn)(); - void (*SetClipboardTextFn)(const char* text); - - // Optional: override memory allocations. MemFreeFn() may be called with a NULL pointer. - // (default to posix malloc/free) - void* (*MemAllocFn)(size_t sz); - void (*MemFreeFn)(void* ptr); + const char* (*GetClipboardTextFn)(void* user_data); + void (*SetClipboardTextFn)(void* user_data, const char* text); + void* ClipboardUserData; // Optional: notify OS Input Method Editor of the screen position of your cursor for text input position (e.g. when using Japanese/Chinese IME in Windows) // (default to use native imm32 api on Windows) void (*ImeSetInputScreenPosFn)(int x, int y); void* ImeWindowHandle; // (Windows) Set this to your HWND to get automatic IME cursor positioning. +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + // [OBSOLETE] Rendering function, will be automatically called in Render(). Please call your rendering function yourself now! You can obtain the ImDrawData* by calling ImGui::GetDrawData() after Render(). + // See example applications if you are unsure of how to implement this. + void (*RenderDrawListsFn)(ImDrawData* data); +#endif + //------------------------------------------------------------------ // Input - Fill before calling NewFrame() //------------------------------------------------------------------ - ImVec2 MousePos; // Mouse position, in pixels (set to -1,-1 if no mouse / on another screen, etc.) - bool MouseDown[5]; // Mouse buttons: left, right, middle + extras. ImGui itself mostly only uses left button (BeginPopupContext** are using right button). Others buttons allows us to track if the mouse is being used by your application + available to user as a convenience via IsMouse** API. - float MouseWheel; // Mouse wheel: 1 unit scrolls about 5 lines text. - bool MouseDrawCursor; // Request ImGui to draw a mouse cursor for you (if you are on a platform without a mouse cursor). - bool KeyCtrl; // Keyboard modifier pressed: Control - bool KeyShift; // Keyboard modifier pressed: Shift - bool KeyAlt; // Keyboard modifier pressed: Alt - bool KeySuper; // Keyboard modifier pressed: Cmd/Super/Windows - bool KeysDown[512]; // Keyboard keys that are pressed (in whatever storage order you naturally have access to keyboard data) - ImWchar InputCharacters[16+1]; // List of characters input (translated by user from keypress+keyboard state). Fill using AddInputCharacter() helper. + ImVec2 MousePos; // Mouse position, in pixels. Set to ImVec2(-FLT_MAX,-FLT_MAX) if mouse is unavailable (on another screen, etc.) + bool MouseDown[5]; // Mouse buttons: left, right, middle + extras. ImGui itself mostly only uses left button (BeginPopupContext** are using right button). Others buttons allows us to track if the mouse is being used by your application + available to user as a convenience via IsMouse** API. + float MouseWheel; // Mouse wheel: 1 unit scrolls about 5 lines text. + float MouseWheelH; // Mouse wheel (Horizontal). Most users don't have a mouse with an horizontal wheel, may not be filled by all back-ends. + bool MouseDrawCursor; // Request ImGui to draw a mouse cursor for you (if you are on a platform without a mouse cursor). + bool KeyCtrl; // Keyboard modifier pressed: Control + bool KeyShift; // Keyboard modifier pressed: Shift + bool KeyAlt; // Keyboard modifier pressed: Alt + bool KeySuper; // Keyboard modifier pressed: Cmd/Super/Windows + bool KeysDown[512]; // Keyboard keys that are pressed (ideally left in the "native" order your engine has access to keyboard keys, so you can use your own defines/enums for keys). + ImWchar InputCharacters[16+1]; // List of characters input (translated by user from keypress+keyboard state). Fill using AddInputCharacter() helper. + float NavInputs[ImGuiNavInput_COUNT]; // Gamepad inputs (keyboard keys will be auto-mapped and be written here by ImGui::NewFrame, all values will be cleared back to zero in ImGui::EndFrame) // Functions - IMGUI_API void AddInputCharacter(ImWchar c); // Helper to add a new character into InputCharacters[] - IMGUI_API void AddInputCharactersUTF8(const char* utf8_chars); // Helper to add new characters into InputCharacters[] from an UTF-8 string - inline void ClearInputCharacters() { InputCharacters[0] = 0; } // Helper to clear the text input buffer + IMGUI_API void AddInputCharacter(ImWchar c); // Add new character into InputCharacters[] + IMGUI_API void AddInputCharactersUTF8(const char* utf8_chars); // Add new characters into InputCharacters[] from an UTF-8 string + inline void ClearInputCharacters() { InputCharacters[0] = 0; } // Clear the text input buffer manually //------------------------------------------------------------------ - // Output - Retrieve after calling NewFrame(), you can use them to discard inputs or hide them from the rest of your application + // Output - Retrieve after calling NewFrame() //------------------------------------------------------------------ - bool WantCaptureMouse; // Mouse is hovering a window or widget is active (= ImGui will use your mouse input) - bool WantCaptureKeyboard; // Widget is active (= ImGui will use your keyboard input) - bool WantTextInput; // Some text input widget is active, which will read input characters from the InputCharacters array. - float Framerate; // Framerate estimation, in frame per second. Rolling average estimation based on IO.DeltaTime over 120 frames - int MetricsAllocs; // Number of active memory allocations + bool WantCaptureMouse; // When io.WantCaptureMouse is true, imgui will use the mouse inputs, do not dispatch them to your main game/application (in both cases, always pass on mouse inputs to imgui). (e.g. unclicked mouse is hovering over an imgui window, widget is active, mouse was clicked over an imgui window, etc.). + bool WantCaptureKeyboard; // When io.WantCaptureKeyboard is true, imgui will use the keyboard inputs, do not dispatch them to your main game/application (in both cases, always pass keyboard inputs to imgui). (e.g. InputText active, or an imgui window is focused and navigation is enabled, etc.). + bool WantTextInput; // Mobile/console: when io.WantTextInput is true, you may display an on-screen keyboard. This is set by ImGui when it wants textual keyboard input to happen (e.g. when a InputText widget is active). + bool WantSetMousePos; // MousePos has been altered, back-end should reposition mouse on next frame. Set only when ImGuiConfigFlags_NavEnableSetMousePos flag is enabled. + bool NavActive; // Directional navigation is currently allowed (will handle ImGuiKey_NavXXX events) = a window is focused and it doesn't use the ImGuiWindowFlags_NoNavInputs flag. + bool NavVisible; // Directional navigation is visible and allowed (will handle ImGuiKey_NavXXX events). + float Framerate; // Application framerate estimation, in frame per second. Solely for convenience. Rolling average estimation based on IO.DeltaTime over 120 frames int MetricsRenderVertices; // Vertices output during last call to Render() int MetricsRenderIndices; // Indices output during last call to Render() = number of triangles * 3 - int MetricsActiveWindows; // Number of visible windows (exclude child windows) + int MetricsActiveWindows; // Number of visible root windows (exclude child windows) + ImVec2 MouseDelta; // Mouse delta. Note that this is zero if either current or previous position are invalid (-FLT_MAX,-FLT_MAX), so a disappearing/reappearing mouse won't have a huge delta. //------------------------------------------------------------------ - // [Internal] ImGui will maintain those fields for you + // [Internal] ImGui will maintain those fields. Forward compatibility not guaranteed! //------------------------------------------------------------------ - ImVec2 MousePosPrev; // Previous mouse position - ImVec2 MouseDelta; // Mouse delta. Note that this is zero if either current or previous position are negative to allow mouse enabling/disabling. - bool MouseClicked[5]; // Mouse button went from !Down to Down + ImVec2 MousePosPrev; // Previous mouse position temporary storage (nb: not for public use, set to MousePos in NewFrame()) ImVec2 MouseClickedPos[5]; // Position at time of clicking float MouseClickedTime[5]; // Time of last click (used to figure out double-click) + bool MouseClicked[5]; // Mouse button went from !Down to Down bool MouseDoubleClicked[5]; // Has mouse button been double-clicked? bool MouseReleased[5]; // Mouse button went from Down to !Down bool MouseDownOwned[5]; // Track if button was clicked inside a window. We don't request mouse capture from the application if click started outside ImGui bounds. float MouseDownDuration[5]; // Duration the mouse button has been down (0.0f == just clicked) float MouseDownDurationPrev[5]; // Previous time the mouse button has been down - float MouseDragMaxDistanceSqr[5]; // Squared maximum distance of how much mouse has traveled from the click point + ImVec2 MouseDragMaxDistanceAbs[5]; // Maximum distance, absolute, on each axis, of how much mouse has traveled from the clicking point + float MouseDragMaxDistanceSqr[5]; // Squared maximum distance of how much mouse has traveled from the clicking point float KeysDownDuration[512]; // Duration the keyboard key has been down (0.0f == just pressed) float KeysDownDurationPrev[512]; // Previous duration the key has been down + float NavInputsDownDuration[ImGuiNavInput_COUNT]; + float NavInputsDownDurationPrev[ImGuiNavInput_COUNT]; IMGUI_API ImGuiIO(); }; +//----------------------------------------------------------------------------- +// Obsolete functions (Will be removed! Read 'API BREAKING CHANGES' section in imgui.cpp for details) +//----------------------------------------------------------------------------- + +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS +namespace ImGui +{ + // OBSOLETED in 1.60 (from Dec 2017) + static inline bool IsAnyWindowFocused() { return IsWindowFocused(ImGuiFocusedFlags_AnyWindow); } + static inline bool IsAnyWindowHovered() { return IsWindowHovered(ImGuiHoveredFlags_AnyWindow); } + static inline ImVec2 CalcItemRectClosestPoint(const ImVec2& pos, bool on_edge = false, float outward = 0.f) { (void)on_edge; (void)outward; IM_ASSERT(0); return pos; } + // OBSOLETED in 1.53 (between Oct 2017 and Dec 2017) + static inline void ShowTestWindow() { return ShowDemoWindow(); } + static inline bool IsRootWindowFocused() { return IsWindowFocused(ImGuiFocusedFlags_RootWindow); } + static inline bool IsRootWindowOrAnyChildFocused() { return IsWindowFocused(ImGuiFocusedFlags_RootAndChildWindows); } + static inline void SetNextWindowContentWidth(float w) { SetNextWindowContentSize(ImVec2(w, 0.0f)); } + static inline float GetItemsLineHeightWithSpacing() { return GetFrameHeightWithSpacing(); } + // OBSOLETED in 1.52 (between Aug 2017 and Oct 2017) + bool Begin(const char* name, bool* p_open, const ImVec2& size_on_first_use, float bg_alpha_override = -1.0f, ImGuiWindowFlags flags = 0); // Use SetNextWindowSize(size, ImGuiCond_FirstUseEver) + SetNextWindowBgAlpha() instead. + static inline bool IsRootWindowOrAnyChildHovered() { return IsWindowHovered(ImGuiHoveredFlags_RootAndChildWindows); } + static inline void AlignFirstTextHeightToWidgets() { AlignTextToFramePadding(); } + static inline void SetNextWindowPosCenter(ImGuiCond c=0) { ImGuiIO& io = GetIO(); SetNextWindowPos(ImVec2(io.DisplaySize.x * 0.5f, io.DisplaySize.y * 0.5f), c, ImVec2(0.5f, 0.5f)); } + // OBSOLETED in 1.51 (between Jun 2017 and Aug 2017) + static inline bool IsItemHoveredRect() { return IsItemHovered(ImGuiHoveredFlags_RectOnly); } + static inline bool IsPosHoveringAnyWindow(const ImVec2&) { IM_ASSERT(0); return false; } // This was misleading and partly broken. You probably want to use the ImGui::GetIO().WantCaptureMouse flag instead. + static inline bool IsMouseHoveringAnyWindow() { return IsWindowHovered(ImGuiHoveredFlags_AnyWindow); } + static inline bool IsMouseHoveringWindow() { return IsWindowHovered(ImGuiHoveredFlags_AllowWhenBlockedByPopup | ImGuiHoveredFlags_AllowWhenBlockedByActiveItem); } + // OBSOLETED IN 1.49 (between Apr 2016 and May 2016) + static inline bool CollapsingHeader(const char* label, const char* str_id, bool framed = true, bool default_open = false) { (void)str_id; (void)framed; ImGuiTreeNodeFlags default_open_flags = 1 << 5; return CollapsingHeader(label, (default_open ? default_open_flags : 0)); } +} +#endif + //----------------------------------------------------------------------------- // Helpers //----------------------------------------------------------------------------- -// Lightweight std::vector<> like class to avoid dragging dependencies (also: windows implementation of STL with debug enabled is absurdly slow, so let's bypass it so our code runs fast in debug). -// Our implementation does NOT call c++ constructors because we don't use them in ImGui. Don't use this class as a straight std::vector replacement in your code! +// Helper: Lightweight std::vector<> like class to avoid dragging dependencies (also: Windows implementation of STL with debug enabled is absurdly slow, so let's bypass it so our code runs fast in debug). +// *Important* Our implementation does NOT call C++ constructors/destructors. This is intentional, we do not require it but you have to be mindful of that. Do not use this class as a straight std::vector replacement in your code! template<typename T> class ImVector { @@ -841,13 +1158,14 @@ public: typedef value_type* iterator; typedef const value_type* const_iterator; - ImVector() { Size = Capacity = 0; Data = NULL; } - ~ImVector() { if (Data) ImGui::MemFree(Data); } + inline ImVector() { Size = Capacity = 0; Data = NULL; } + inline ~ImVector() { if (Data) ImGui::MemFree(Data); } + inline ImVector(const ImVector<T>& src) { Size = Capacity = 0; Data = NULL; operator=(src); } + inline ImVector& operator=(const ImVector<T>& src) { clear(); resize(src.Size); memcpy(Data, src.Data, (size_t)Size * sizeof(value_type)); return *this; } inline bool empty() const { return Size == 0; } inline int size() const { return Size; } inline int capacity() const { return Capacity; } - inline value_type& operator[](int i) { IM_ASSERT(i < Size); return Data[i]; } inline const value_type& operator[](int i) const { IM_ASSERT(i < Size); return Data[i]; } @@ -858,17 +1176,18 @@ public: inline const_iterator end() const { return Data + Size; } inline value_type& front() { IM_ASSERT(Size > 0); return Data[0]; } inline const value_type& front() const { IM_ASSERT(Size > 0); return Data[0]; } - inline value_type& back() { IM_ASSERT(Size > 0); return Data[Size-1]; } - inline const value_type& back() const { IM_ASSERT(Size > 0); return Data[Size-1]; } - inline void swap(ImVector<T>& rhs) { int rhs_size = rhs.Size; rhs.Size = Size; Size = rhs_size; int rhs_cap = rhs.Capacity; rhs.Capacity = Capacity; Capacity = rhs_cap; value_type* rhs_data = rhs.Data; rhs.Data = Data; Data = rhs_data; } - - inline int _grow_capacity(int new_size) { int new_capacity = Capacity ? (Capacity + Capacity/2) : 8; return new_capacity > new_size ? new_capacity : new_size; } - - inline void resize(int new_size) { if (new_size > Capacity) reserve(_grow_capacity(new_size)); Size = new_size; } - inline void reserve(int new_capacity) + inline value_type& back() { IM_ASSERT(Size > 0); return Data[Size - 1]; } + inline const value_type& back() const { IM_ASSERT(Size > 0); return Data[Size - 1]; } + inline void swap(ImVector<value_type>& rhs) { int rhs_size = rhs.Size; rhs.Size = Size; Size = rhs_size; int rhs_cap = rhs.Capacity; rhs.Capacity = Capacity; Capacity = rhs_cap; value_type* rhs_data = rhs.Data; rhs.Data = Data; Data = rhs_data; } + + inline int _grow_capacity(int sz) const { int new_capacity = Capacity ? (Capacity + Capacity/2) : 8; return new_capacity > sz ? new_capacity : sz; } + inline void resize(int new_size) { if (new_size > Capacity) reserve(_grow_capacity(new_size)); Size = new_size; } + inline void resize(int new_size,const value_type& v){ if (new_size > Capacity) reserve(_grow_capacity(new_size)); if (new_size > Size) for (int n = Size; n < new_size; n++) memcpy(&Data[n], &v, sizeof(v)); Size = new_size; } + inline void reserve(int new_capacity) { - if (new_capacity <= Capacity) return; - T* new_data = (value_type*)ImGui::MemAlloc((size_t)new_capacity * sizeof(value_type)); + if (new_capacity <= Capacity) + return; + value_type* new_data = (value_type*)ImGui::MemAlloc((size_t)new_capacity * sizeof(value_type)); if (Data) memcpy(new_data, Data, (size_t)Size * sizeof(value_type)); ImGui::MemFree(Data); @@ -876,22 +1195,27 @@ public: Capacity = new_capacity; } - inline void push_back(const value_type& v) { if (Size == Capacity) reserve(_grow_capacity(Size+1)); Data[Size++] = v; } - inline void pop_back() { IM_ASSERT(Size > 0); Size--; } - - inline iterator erase(const_iterator it) { IM_ASSERT(it >= Data && it < Data+Size); const ptrdiff_t off = it - Data; memmove(Data + off, Data + off + 1, ((size_t)Size - (size_t)off - 1) * sizeof(value_type)); Size--; return Data + off; } - inline iterator insert(const_iterator it, const value_type& v) { IM_ASSERT(it >= Data && it <= Data+Size); const ptrdiff_t off = it - Data; if (Size == Capacity) reserve(Capacity ? Capacity * 2 : 4); if (off < (int)Size) memmove(Data + off + 1, Data + off, ((size_t)Size - (size_t)off) * sizeof(value_type)); Data[off] = v; Size++; return Data + off; } + // NB: &v cannot be pointing inside the ImVector Data itself! e.g. v.push_back(v[10]) is forbidden. + inline void push_back(const value_type& v) { if (Size == Capacity) reserve(_grow_capacity(Size + 1)); memcpy(&Data[Size], &v, sizeof(v)); Size++; } + inline void pop_back() { IM_ASSERT(Size > 0); Size--; } + inline void push_front(const value_type& v) { if (Size == 0) push_back(v); else insert(Data, v); } + inline iterator erase(const_iterator it) { IM_ASSERT(it >= Data && it < Data+Size); const ptrdiff_t off = it - Data; memmove(Data + off, Data + off + 1, ((size_t)Size - (size_t)off - 1) * sizeof(value_type)); Size--; return Data + off; } + inline iterator insert(const_iterator it, const value_type& v) { IM_ASSERT(it >= Data && it <= Data+Size); const ptrdiff_t off = it - Data; if (Size == Capacity) reserve(_grow_capacity(Size + 1)); if (off < (int)Size) memmove(Data + off + 1, Data + off, ((size_t)Size - (size_t)off) * sizeof(value_type)); memcpy(&Data[off], &v, sizeof(v)); Size++; return Data + off; } + inline bool contains(const value_type& v) const { const T* data = Data; const T* data_end = Data + Size; while (data < data_end) if (*data++ == v) return true; return false; } }; -// Helper: execute a block of code at maximum once a frame -// Convenient if you want to quickly create an UI within deep-nested code that runs multiple times every frame. -// Usage: -// IMGUI_ONCE_UPON_A_FRAME -// { -// // code block will be executed one per frame -// } -// Attention! the macro expands into 2 statement so make sure you don't use it within e.g. an if() statement without curly braces. -#define IMGUI_ONCE_UPON_A_FRAME static ImGuiOnceUponAFrame imgui_oaf##__LINE__; if (imgui_oaf##__LINE__) +// Helper: IM_NEW(), IM_PLACEMENT_NEW(), IM_DELETE() macros to call MemAlloc + Placement New, Placement Delete + MemFree +// We call C++ constructor on own allocated memory via the placement "new(ptr) Type()" syntax. +// Defining a custom placement new() with a dummy parameter allows us to bypass including <new> which on some platforms complains when user has disabled exceptions. +struct ImNewDummy {}; +inline void* operator new(size_t, ImNewDummy, void* ptr) { return ptr; } +inline void operator delete(void*, ImNewDummy, void*) {} // This is only required so we can use the symetrical new() +#define IM_PLACEMENT_NEW(_PTR) new(ImNewDummy(), _PTR) +#define IM_NEW(_TYPE) new(ImNewDummy(), ImGui::MemAlloc(sizeof(_TYPE))) _TYPE +template<typename T> void IM_DELETE(T*& p) { if (p) { p->~T(); ImGui::MemFree(p); p = NULL; } } + +// Helper: Execute a block of code at maximum once a frame. Convenient if you want to quickly create an UI within deep-nested code that runs multiple times every frame. +// Usage: static ImGuiOnceUponAFrame oaf; if (oaf) ImGui::Text("This will be called only once per frame"); struct ImGuiOnceUponAFrame { ImGuiOnceUponAFrame() { RefFrame = -1; } @@ -899,6 +1223,11 @@ struct ImGuiOnceUponAFrame operator bool() const { int current_frame = ImGui::GetFrameCount(); if (RefFrame == current_frame) return false; RefFrame = current_frame; return true; } }; +// Helper: Macro for ImGuiOnceUponAFrame. Attention: The macro expands into 2 statement so make sure you don't use it within e.g. an if() statement without curly braces. +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS // Will obsolete +#define IMGUI_ONCE_UPON_A_FRAME static ImGuiOnceUponAFrame imgui_oaf; if (imgui_oaf) +#endif + // Helper: Parse and apply text filters. In format "aaaaa[,bbbb][,ccccc]" struct ImGuiTextFilter { @@ -922,13 +1251,12 @@ struct ImGuiTextFilter ImVector<TextRange> Filters; int CountGrep; - ImGuiTextFilter(const char* default_filter = ""); - ~ImGuiTextFilter() {} + IMGUI_API ImGuiTextFilter(const char* default_filter = ""); + IMGUI_API bool Draw(const char* label = "Filter (inc,-exc)", float width = 0.0f); // Helper calling InputText+Build + IMGUI_API bool PassFilter(const char* text, const char* text_end = NULL) const; + IMGUI_API void Build(); void Clear() { InputBuf[0] = 0; Build(); } - bool Draw(const char* label = "Filter (inc,-exc)", float width = 0.0f); // Helper calling InputText+Build - bool PassFilter(const char* text, const char* text_end = NULL) const; bool IsActive() const { return !Filters.empty(); } - IMGUI_API void Build(); }; // Helper: Text buffer for logging/accumulating text @@ -943,19 +1271,19 @@ struct ImGuiTextBuffer int size() const { return Buf.Size - 1; } bool empty() { return Buf.Size <= 1; } void clear() { Buf.clear(); Buf.push_back(0); } + void reserve(int capacity) { Buf.reserve(capacity); } const char* c_str() const { return Buf.Data; } - IMGUI_API void append(const char* fmt, ...) IM_PRINTFARGS(2); - IMGUI_API void appendv(const char* fmt, va_list args); + IMGUI_API void appendf(const char* fmt, ...) IM_FMTARGS(2); + IMGUI_API void appendfv(const char* fmt, va_list args) IM_FMTLIST(2); }; // Helper: Simple Key->value storage -// - Store collapse state for a tree (Int 0/1) -// - Store color edit options (Int using values in ImGuiColorEditMode enum). -// - Custom user storage for temporary values. // Typically you don't have to worry about this since a storage is held within each Window. -// Declare your own storage if: +// We use it to e.g. store collapse state for a tree (Int 0/1) +// This is optimized for efficient lookup (dichotomy into a contiguous buffer) and rare insertion (typically tied to user interactions aka max once a frame) +// You can use it as custom user storage for temporary values. Declare your own storage if, for example: // - You want to manipulate the open/close state of a particular sub-tree in your interface (tree node uses Int 0/1 to store their state). -// - You want to store custom debug data easily without adding or editing structures in your code. +// - You want to store custom debug data easily without adding or editing structures in your code (probably not efficient, but convenient) // Types are NOT stored, so it is up to you to make sure your Key don't collide with different types. struct ImGuiStorage { @@ -963,7 +1291,7 @@ struct ImGuiStorage { ImGuiID key; union { int val_i; float val_f; void* val_p; }; - Pair(ImGuiID _key, int _val_i) { key = _key; val_i = _val_i; } + Pair(ImGuiID _key, int _val_i) { key = _key; val_i = _val_i; } Pair(ImGuiID _key, float _val_f) { key = _key; val_f = _val_f; } Pair(ImGuiID _key, void* _val_p) { key = _key; val_p = _val_p; } }; @@ -972,7 +1300,7 @@ struct ImGuiStorage // - Get***() functions find pair, never add/allocate. Pairs are sorted so a query is O(log N) // - Set***() functions find pair, insertion on demand if missing. // - Sorted insertion is costly, paid once. A typical frame shouldn't need to insert any new pair. - IMGUI_API void Clear(); + void Clear() { Data.clear(); } IMGUI_API int GetInt(ImGuiID key, int default_val = 0) const; IMGUI_API void SetInt(ImGuiID key, int val); IMGUI_API bool GetBool(ImGuiID key, bool default_val = false) const; @@ -984,9 +1312,8 @@ struct ImGuiStorage // - Get***Ref() functions finds pair, insert on demand if missing, return pointer. Useful if you intend to do Get+Set. // - References are only valid until a new value is added to the storage. Calling a Set***() function or a Get***Ref() function invalidates the pointer. - // - A typical use case where this is convenient: + // - A typical use case where this is convenient for quick hacking (e.g. add storage during a live Edit&Continue session if you can't modify existing struct) // float* pvar = ImGui::GetFloatRef(key); ImGui::SliderFloat("var", pvar, 0, 100.0f); some_var += *pvar; - // - You can also use this to quickly create temporary editable values during a session of using Edit&Continue, without restarting your application. IMGUI_API int* GetIntRef(ImGuiID key, int default_val = 0); IMGUI_API bool* GetBoolRef(ImGuiID key, bool default_val = false); IMGUI_API float* GetFloatRef(ImGuiID key, float default_val = 0.0f); @@ -994,6 +1321,9 @@ struct ImGuiStorage // Use on your own storage if you know only integer are being stored (open/close all tree nodes) IMGUI_API void SetAllInt(int val); + + // For quicker full rebuild of a storage (instead of an incremental one), you may add all your contents and then sort once. + IMGUI_API void BuildSortByKey(); }; // Shared state of InputText(), passed to callback when a ImGuiInputTextFlags_Callback* flag is used and the corresponding callback is triggered. @@ -1019,42 +1349,66 @@ struct ImGuiTextEditCallbackData int SelectionEnd; // // Read-write // NB: Helper functions for text manipulation. Calling those function loses selection. - void DeleteChars(int pos, int bytes_count); - void InsertChars(int pos, const char* text, const char* text_end = NULL); - bool HasSelection() const { return SelectionStart != SelectionEnd; } + IMGUI_API void DeleteChars(int pos, int bytes_count); + IMGUI_API void InsertChars(int pos, const char* text, const char* text_end = NULL); + bool HasSelection() const { return SelectionStart != SelectionEnd; } }; // Resizing callback data to apply custom constraint. As enabled by SetNextWindowSizeConstraints(). Callback is called during the next Begin(). // NB: For basic min/max size constraint on each axis you don't need to use the callback! The SetNextWindowSizeConstraints() parameters are enough. -struct ImGuiSizeConstraintCallbackData +struct ImGuiSizeCallbackData { void* UserData; // Read-only. What user passed to SetNextWindowSizeConstraints() - ImVec2 Pos; // Read-only. Window position, for reference. - ImVec2 CurrentSize; // Read-only. Current window size. + ImVec2 Pos; // Read-only. Window position, for reference. + ImVec2 CurrentSize; // Read-only. Current window size. ImVec2 DesiredSize; // Read-write. Desired size, based on user's mouse position. Write to this field to restrain resizing. }; +// Data payload for Drag and Drop operations +struct ImGuiPayload +{ + // Members + const void* Data; // Data (copied and owned by dear imgui) + int DataSize; // Data size + + // [Internal] + ImGuiID SourceId; // Source item id + ImGuiID SourceParentId; // Source parent id (if available) + int DataFrameCount; // Data timestamp + char DataType[32+1]; // Data type tag (short user-supplied string, 32 characters max) + bool Preview; // Set when AcceptDragDropPayload() was called and mouse has been hovering the target item (nb: handle overlapping drag targets) + bool Delivery; // Set when AcceptDragDropPayload() was called and mouse button is released over the target item. + + ImGuiPayload() { Clear(); } + void Clear() { SourceId = SourceParentId = 0; Data = NULL; DataSize = 0; memset(DataType, 0, sizeof(DataType)); DataFrameCount = -1; Preview = Delivery = false; } + bool IsDataType(const char* type) const { return DataFrameCount != -1 && strcmp(type, DataType) == 0; } + bool IsPreview() const { return Preview; } + bool IsDelivery() const { return Delivery; } +}; + // Helpers macros to generate 32-bits encoded colors #ifdef IMGUI_USE_BGRA_PACKED_COLOR #define IM_COL32_R_SHIFT 16 #define IM_COL32_G_SHIFT 8 #define IM_COL32_B_SHIFT 0 #define IM_COL32_A_SHIFT 24 +#define IM_COL32_A_MASK 0xFF000000 #else #define IM_COL32_R_SHIFT 0 #define IM_COL32_G_SHIFT 8 #define IM_COL32_B_SHIFT 16 #define IM_COL32_A_SHIFT 24 +#define IM_COL32_A_MASK 0xFF000000 #endif #define IM_COL32(R,G,B,A) (((ImU32)(A)<<IM_COL32_A_SHIFT) | ((ImU32)(B)<<IM_COL32_B_SHIFT) | ((ImU32)(G)<<IM_COL32_G_SHIFT) | ((ImU32)(R)<<IM_COL32_R_SHIFT)) -#define IM_COL32_WHITE IM_COL32(255,255,255,255) // Opaque white +#define IM_COL32_WHITE IM_COL32(255,255,255,255) // Opaque white = 0xFFFFFFFF #define IM_COL32_BLACK IM_COL32(0,0,0,255) // Opaque black -#define IM_COL32_BLACK_TRANS IM_COL32(0,0,0,0) // Transparent black +#define IM_COL32_BLACK_TRANS IM_COL32(0,0,0,0) // Transparent black = 0x00000000 -// ImColor() helper to implicity converts colors to either ImU32 (packed 4x1 byte) or ImVec4 (4x1 float) +// Helper: ImColor() implicity converts colors to either ImU32 (packed 4x1 byte) or ImVec4 (4x1 float) // Prefer using IM_COL32() macros if you want a guaranteed compile-time ImU32 for usage with ImDrawList API. -// Avoid storing ImColor! Store either u32 of ImVec4. This is not a full-featured color class. -// None of the ImGui API are using ImColor directly but you can use it as a convenience to pass colors in either ImU32 or ImVec4 formats. +// **Avoid storing ImColor! Store either u32 of ImVec4. This is not a full-featured color class. MAY OBSOLETE. +// **None of the ImGui API are using ImColor directly but you can use it as a convenience to pass colors in either ImU32 or ImVec4 formats. Explicitly cast to ImU32 or ImVec4 if needed. struct ImColor { ImVec4 Value; @@ -1067,8 +1421,8 @@ struct ImColor inline operator ImU32() const { return ImGui::ColorConvertFloat4ToU32(Value); } inline operator ImVec4() const { return Value; } + // FIXME-OBSOLETE: May need to obsolete/cleanup those helpers. inline void SetHSV(float h, float s, float v, float a = 1.0f){ ImGui::ColorConvertHSVtoRGB(h, s, v, Value.x, Value.y, Value.z); Value.w = a; } - static ImColor HSV(float h, float s, float v, float a = 1.0f) { float r,g,b; ImGui::ColorConvertHSVtoRGB(h, s, v, r, g, b); return ImColor(r,g,b,a); } }; @@ -1092,7 +1446,7 @@ struct ImGuiListClipper int ItemsCount, StepNo, DisplayStart, DisplayEnd; // items_count: Use -1 to ignore (you can call Begin later). Use INT_MAX if you don't know how many items you have (in which case the cursor won't be advanced in the final step). - // items_height: Use -1.0f to be calculated automatically on first step. Otherwise pass in the distance between your items, typically GetTextLineHeightWithSpacing() or GetItemsLineHeightWithSpacing(). + // items_height: Use -1.0f to be calculated automatically on first step. Otherwise pass in the distance between your items, typically GetTextLineHeightWithSpacing() or GetFrameHeightWithSpacing(). // If you don't specify an items_height, you NEED to call Step(). If you specify items_height you may call the old Begin()/End() api directly, but prefer calling Step(). ImGuiListClipper(int items_count = -1, float items_height = -1.0f) { Begin(items_count, items_height); } // NB: Begin() initialize every fields (as we allow user to call Begin/End multiple times on a same instance if they want). ~ImGuiListClipper() { IM_ASSERT(ItemsCount == -1); } // Assert if user forgot to call End() or Step() until false. @@ -1113,7 +1467,7 @@ struct ImGuiListClipper // The expected behavior from your rendering function is 'if (cmd.UserCallback != NULL) cmd.UserCallback(parent_list, cmd); else RenderTriangles()' typedef void (*ImDrawCallback)(const ImDrawList* parent_list, const ImDrawCmd* cmd); -// Typically, 1 command = 1 gpu draw call (unless command is a callback) +// Typically, 1 command = 1 GPU draw call (unless command is a callback) struct ImDrawCmd { unsigned int ElemCount; // Number of indices (multiple of 3) to be rendered as triangles. Vertices are stored in the callee ImDrawList's vtx_buffer[] array, indices in idx_buffer[]. @@ -1122,7 +1476,7 @@ struct ImDrawCmd ImDrawCallback UserCallback; // If != NULL, call the function instead of rendering the vertices. clip_rect and texture_id will be set normally. void* UserCallbackData; // The draw callback code can access this. - ImDrawCmd() { ElemCount = 0; ClipRect.x = ClipRect.y = -8192.0f; ClipRect.z = ClipRect.w = +8192.0f; TextureId = NULL; UserCallback = NULL; UserCallbackData = NULL; } + ImDrawCmd() { ElemCount = 0; ClipRect.x = ClipRect.y = ClipRect.z = ClipRect.w = 0.0f; TextureId = NULL; UserCallback = NULL; UserCallbackData = NULL; } }; // Vertex index (override with '#define ImDrawIdx unsigned int' inside in imconfig.h) @@ -1142,6 +1496,7 @@ struct ImDrawVert // You can override the vertex format layout by defining IMGUI_OVERRIDE_DRAWVERT_STRUCT_LAYOUT in imconfig.h // The code expect ImVec2 pos (8 bytes), ImVec2 uv (8 bytes), ImU32 col (4 bytes), but you can re-order them or add other fields as needed to simplify integration in your engine. // The type has to be described within the macro (you can either declare the struct or use a typedef) +// NOTE: IMGUI DOESN'T CLEAR THE STRUCTURE AND DOESN'T CALL A CONSTRUCTOR SO ANY CUSTOM FIELD WILL BE UNINITIALIZED. IF YOU ADD EXTRA FIELDS (SUCH AS A 'Z' COORDINATES) YOU WILL NEED TO CLEAR THEM DURING RENDER OR TO IGNORE THEM. IMGUI_OVERRIDE_DRAWVERT_STRUCT_LAYOUT; #endif @@ -1153,21 +1508,42 @@ struct ImDrawChannel ImVector<ImDrawIdx> IdxBuffer; }; +enum ImDrawCornerFlags_ +{ + ImDrawCornerFlags_TopLeft = 1 << 0, // 0x1 + ImDrawCornerFlags_TopRight = 1 << 1, // 0x2 + ImDrawCornerFlags_BotLeft = 1 << 2, // 0x4 + ImDrawCornerFlags_BotRight = 1 << 3, // 0x8 + ImDrawCornerFlags_Top = ImDrawCornerFlags_TopLeft | ImDrawCornerFlags_TopRight, // 0x3 + ImDrawCornerFlags_Bot = ImDrawCornerFlags_BotLeft | ImDrawCornerFlags_BotRight, // 0xC + ImDrawCornerFlags_Left = ImDrawCornerFlags_TopLeft | ImDrawCornerFlags_BotLeft, // 0x5 + ImDrawCornerFlags_Right = ImDrawCornerFlags_TopRight | ImDrawCornerFlags_BotRight, // 0xA + ImDrawCornerFlags_All = 0xF // In your function calls you may use ~0 (= all bits sets) instead of ImDrawCornerFlags_All, as a convenience +}; + +enum ImDrawListFlags_ +{ + ImDrawListFlags_AntiAliasedLines = 1 << 0, + ImDrawListFlags_AntiAliasedFill = 1 << 1 +}; + // Draw command list // This is the low-level list of polygons that ImGui functions are filling. At the end of the frame, all command lists are passed to your ImGuiIO::RenderDrawListFn function for rendering. -// At the moment, each ImGui window contains its own ImDrawList but they could potentially be merged in the future. -// If you want to add custom rendering within a window, you can use ImGui::GetWindowDrawList() to access the current draw list and add your own primitives. +// Each ImGui window contains its own ImDrawList. You can use ImGui::GetWindowDrawList() to access the current window draw list and draw custom primitives. // You can interleave normal ImGui:: calls and adding primitives to the current draw list. -// All positions are in screen coordinates (0,0=top-left, 1 pixel per unit). Primitives are always added to the list and not culled (culling is done at render time and at a higher-level by ImGui:: functions). +// All positions are generally in pixel coordinates (top-left at (0,0), bottom-right at io.DisplaySize), however you are totally free to apply whatever transformation matrix to want to the data (if you apply such transformation you'll want to apply it to ClipRect as well) +// Important: Primitives are always added to the list and not culled (culling is done at higher-level by ImGui:: functions), if you use this API a lot consider coarse culling your drawn objects. struct ImDrawList { // This is what you have to render - ImVector<ImDrawCmd> CmdBuffer; // Commands. Typically 1 command = 1 gpu draw call. + ImVector<ImDrawCmd> CmdBuffer; // Draw commands. Typically 1 command = 1 GPU draw call, unless the command is a callback. ImVector<ImDrawIdx> IdxBuffer; // Index buffer. Each command consume ImDrawCmd::ElemCount of those ImVector<ImDrawVert> VtxBuffer; // Vertex buffer. + ImDrawListFlags Flags; // Flags, you may poke into these to adjust anti-aliasing settings per-primitive. // [Internal, used while building lists] - const char* _OwnerName; // Pointer to owner window's name (if any) for debugging + const ImDrawListSharedData* _Data; // Pointer to shared draw data (you can use ImGui::GetDrawListSharedData() to get the one from current ImGui context) + const char* _OwnerName; // Pointer to owner window's name for debugging unsigned int _VtxCurrentIdx; // [Internal] == VtxBuffer.Size ImDrawVert* _VtxWritePtr; // [Internal] point within VtxBuffer.Data after each add command (to avoid using the ImVector<> operators too much) ImDrawIdx* _IdxWritePtr; // [Internal] point within IdxBuffer.Data after each add command (to avoid using the ImVector<> operators too much) @@ -1178,18 +1554,21 @@ struct ImDrawList int _ChannelsCount; // [Internal] number of active channels (1+) ImVector<ImDrawChannel> _Channels; // [Internal] draw channels for columns API (not resized down so _ChannelsCount may be smaller than _Channels.Size) - ImDrawList() { _OwnerName = NULL; Clear(); } + // If you want to create ImDrawList instances, pass them ImGui::GetDrawListSharedData() or create and use your own ImDrawListSharedData (so you can use ImDrawList without ImGui) + ImDrawList(const ImDrawListSharedData* shared_data) { _Data = shared_data; _OwnerName = NULL; Clear(); } ~ImDrawList() { ClearFreeMemory(); } IMGUI_API void PushClipRect(ImVec2 clip_rect_min, ImVec2 clip_rect_max, bool intersect_with_current_clip_rect = false); // Render-level scissoring. This is passed down to your render function but not used for CPU-side coarse clipping. Prefer using higher-level ImGui::PushClipRect() to affect logic (hit-testing and widget culling) IMGUI_API void PushClipRectFullScreen(); IMGUI_API void PopClipRect(); - IMGUI_API void PushTextureID(const ImTextureID& texture_id); + IMGUI_API void PushTextureID(ImTextureID texture_id); IMGUI_API void PopTextureID(); + inline ImVec2 GetClipRectMin() const { const ImVec4& cr = _ClipRectStack.back(); return ImVec2(cr.x, cr.y); } + inline ImVec2 GetClipRectMax() const { const ImVec4& cr = _ClipRectStack.back(); return ImVec2(cr.z, cr.w); } // Primitives IMGUI_API void AddLine(const ImVec2& a, const ImVec2& b, ImU32 col, float thickness = 1.0f); - IMGUI_API void AddRect(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding = 0.0f, int rounding_corners = 0x0F, float thickness = 1.0f); // a: upper-left, b: lower-right - IMGUI_API void AddRectFilled(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding = 0.0f, int rounding_corners = 0x0F); // a: upper-left, b: lower-right + IMGUI_API void AddRect(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding = 0.0f, int rounding_corners_flags = ImDrawCornerFlags_All, float thickness = 1.0f); // a: upper-left, b: lower-right, rounding_corners_flags: 4-bits corresponding to which corner to round + IMGUI_API void AddRectFilled(const ImVec2& a, const ImVec2& b, ImU32 col, float rounding = 0.0f, int rounding_corners_flags = ImDrawCornerFlags_All); // a: upper-left, b: lower-right IMGUI_API void AddRectFilledMultiColor(const ImVec2& a, const ImVec2& b, ImU32 col_upr_left, ImU32 col_upr_right, ImU32 col_bot_right, ImU32 col_bot_left); IMGUI_API void AddQuad(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& d, ImU32 col, float thickness = 1.0f); IMGUI_API void AddQuadFilled(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& d, ImU32 col); @@ -1199,21 +1578,23 @@ struct ImDrawList IMGUI_API void AddCircleFilled(const ImVec2& centre, float radius, ImU32 col, int num_segments = 12); IMGUI_API void AddText(const ImVec2& pos, ImU32 col, const char* text_begin, const char* text_end = NULL); IMGUI_API void AddText(const ImFont* font, float font_size, const ImVec2& pos, ImU32 col, const char* text_begin, const char* text_end = NULL, float wrap_width = 0.0f, const ImVec4* cpu_fine_clip_rect = NULL); - IMGUI_API void AddImage(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& uv0 = ImVec2(0,0), const ImVec2& uv1 = ImVec2(1,1), ImU32 col = 0xFFFFFFFF); - IMGUI_API void AddPolyline(const ImVec2* points, const int num_points, ImU32 col, bool closed, float thickness, bool anti_aliased); - IMGUI_API void AddConvexPolyFilled(const ImVec2* points, const int num_points, ImU32 col, bool anti_aliased); + IMGUI_API void AddImage(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& uv_a = ImVec2(0,0), const ImVec2& uv_b = ImVec2(1,1), ImU32 col = 0xFFFFFFFF); + IMGUI_API void AddImageQuad(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& d, const ImVec2& uv_a = ImVec2(0,0), const ImVec2& uv_b = ImVec2(1,0), const ImVec2& uv_c = ImVec2(1,1), const ImVec2& uv_d = ImVec2(0,1), ImU32 col = 0xFFFFFFFF); + IMGUI_API void AddImageRounded(ImTextureID user_texture_id, const ImVec2& a, const ImVec2& b, const ImVec2& uv_a, const ImVec2& uv_b, ImU32 col, float rounding, int rounding_corners = ImDrawCornerFlags_All); + IMGUI_API void AddPolyline(const ImVec2* points, const int num_points, ImU32 col, bool closed, float thickness); + IMGUI_API void AddConvexPolyFilled(const ImVec2* points, const int num_points, ImU32 col); IMGUI_API void AddBezierCurve(const ImVec2& pos0, const ImVec2& cp0, const ImVec2& cp1, const ImVec2& pos1, ImU32 col, float thickness, int num_segments = 0); // Stateful path API, add points then finish with PathFill() or PathStroke() inline void PathClear() { _Path.resize(0); } inline void PathLineTo(const ImVec2& pos) { _Path.push_back(pos); } inline void PathLineToMergeDuplicate(const ImVec2& pos) { if (_Path.Size == 0 || memcmp(&_Path[_Path.Size-1], &pos, 8) != 0) _Path.push_back(pos); } - inline void PathFill(ImU32 col) { AddConvexPolyFilled(_Path.Data, _Path.Size, col, true); PathClear(); } - inline void PathStroke(ImU32 col, bool closed, float thickness = 1.0f) { AddPolyline(_Path.Data, _Path.Size, col, closed, thickness, true); PathClear(); } + inline void PathFillConvex(ImU32 col) { AddConvexPolyFilled(_Path.Data, _Path.Size, col); PathClear(); } + inline void PathStroke(ImU32 col, bool closed, float thickness = 1.0f) { AddPolyline(_Path.Data, _Path.Size, col, closed, thickness); PathClear(); } IMGUI_API void PathArcTo(const ImVec2& centre, float radius, float a_min, float a_max, int num_segments = 10); - IMGUI_API void PathArcToFast(const ImVec2& centre, float radius, int a_min_of_12, int a_max_of_12); // Use precomputed angles for a 12 steps circle + IMGUI_API void PathArcToFast(const ImVec2& centre, float radius, int a_min_of_12, int a_max_of_12); // Use precomputed angles for a 12 steps circle IMGUI_API void PathBezierCurveTo(const ImVec2& p1, const ImVec2& p2, const ImVec2& p3, int num_segments = 0); - IMGUI_API void PathRect(const ImVec2& rect_min, const ImVec2& rect_max, float rounding = 0.0f, int rounding_corners = 0x0F); + IMGUI_API void PathRect(const ImVec2& rect_min, const ImVec2& rect_max, float rounding = 0.0f, int rounding_corners_flags = ImDrawCornerFlags_All); // Channels // - Use to simulate layers. By switching channels to can render out-of-order (e.g. submit foreground primitives before background primitives) @@ -1225,6 +1606,7 @@ struct ImDrawList // Advanced IMGUI_API void AddCallback(ImDrawCallback callback, void* callback_data); // Your rendering function must check for 'UserCallback' in ImDrawCmd and call the function instead of rendering triangles. IMGUI_API void AddDrawCmd(); // This is useful if you need to forcefully create a new draw call (to allow for dependent rendering / blending). Otherwise primitives are merged into the same draw-call as much as possible + IMGUI_API ImDrawList* CloneOutput() const; // Create a clone of the CmdBuffer/IdxBuffer/VtxBuffer. // Internal helpers // NB: all primitives needs to be reserved via PrimReserve() beforehand! @@ -1242,50 +1624,69 @@ struct ImDrawList }; // All draw data to render an ImGui frame +// (NB: the style and the naming convention here is a little inconsistent but we preserve them for backward compatibility purpose) struct ImDrawData { bool Valid; // Only valid after Render() is called and before the next NewFrame() is called. - ImDrawList** CmdLists; - int CmdListsCount; - int TotalVtxCount; // For convenience, sum of all cmd_lists vtx_buffer.Size - int TotalIdxCount; // For convenience, sum of all cmd_lists idx_buffer.Size + ImDrawList** CmdLists; // Array of ImDrawList* to render. The ImDrawList are owned by ImGuiContext and only pointed to from here. + int CmdListsCount; // Number of ImDrawList* to render + int TotalIdxCount; // For convenience, sum of all ImDrawList's IdxBuffer.Size + int TotalVtxCount; // For convenience, sum of all ImDrawList's VtxBuffer.Size // Functions - ImDrawData() { Valid = false; CmdLists = NULL; CmdListsCount = TotalVtxCount = TotalIdxCount = 0; } - IMGUI_API void DeIndexAllBuffers(); // For backward compatibility: convert all buffers from indexed to de-indexed, in case you cannot render indexed. Note: this is slow and most likely a waste of resources. Always prefer indexed rendering! - IMGUI_API void ScaleClipRects(const ImVec2& sc); // Helper to scale the ClipRect field of each ImDrawCmd. Use if your final output buffer is at a different scale than ImGui expects, or if there is a difference between your window resolution and framebuffer resolution. + ImDrawData() { Valid = false; Clear(); } + ~ImDrawData() { Clear(); } + void Clear() { Valid = false; CmdLists = NULL; CmdListsCount = TotalVtxCount = TotalIdxCount = 0; } // The ImDrawList are owned by ImGuiContext! + IMGUI_API void DeIndexAllBuffers(); // Helper to convert all buffers from indexed to non-indexed, in case you cannot render indexed. Note: this is slow and most likely a waste of resources. Always prefer indexed rendering! + IMGUI_API void ScaleClipRects(const ImVec2& sc); // Helper to scale the ClipRect field of each ImDrawCmd. Use if your final output buffer is at a different scale than ImGui expects, or if there is a difference between your window resolution and framebuffer resolution. }; struct ImFontConfig { - void* FontData; // // TTF data - int FontDataSize; // // TTF data size - bool FontDataOwnedByAtlas; // true // TTF data ownership taken by the container ImFontAtlas (will delete memory itself). Set to true - int FontNo; // 0 // Index of font within TTF file - float SizePixels; // // Size in pixels for rasterizer - int OversampleH, OversampleV; // 3, 1 // Rasterize at higher quality for sub-pixel positioning. We don't use sub-pixel positions on the Y axis. - bool PixelSnapH; // false // Align every glyph to pixel boundary. Useful e.g. if you are merging a non-pixel aligned font with the default font. If enabled, you can set OversampleH/V to 1. - ImVec2 GlyphExtraSpacing; // 0, 0 // Extra spacing (in pixels) between glyphs - const ImWchar* GlyphRanges; // // Pointer to a user-provided list of Unicode range (2 value per range, values are inclusive, zero-terminated list). THE ARRAY DATA NEEDS TO PERSIST AS LONG AS THE FONT IS ALIVE. - bool MergeMode; // false // Merge into previous ImFont, so you can combine multiple inputs font into one ImFont (e.g. ASCII font + icons + Japanese glyphs). - bool MergeGlyphCenterV; // false // When merging (multiple ImFontInput for one ImFont), vertically center new glyphs instead of aligning their baseline + void* FontData; // // TTF/OTF data + int FontDataSize; // // TTF/OTF data size + bool FontDataOwnedByAtlas; // true // TTF/OTF data ownership taken by the container ImFontAtlas (will delete memory itself). + int FontNo; // 0 // Index of font within TTF/OTF file + float SizePixels; // // Size in pixels for rasterizer. + int OversampleH; // 3 // Rasterize at higher quality for sub-pixel positioning. We don't use sub-pixel positions on the Y axis. + int OversampleV; // 1 // Rasterize at higher quality for sub-pixel positioning. We don't use sub-pixel positions on the Y axis. + bool PixelSnapH; // false // Align every glyph to pixel boundary. Useful e.g. if you are merging a non-pixel aligned font with the default font. If enabled, you can set OversampleH/V to 1. + ImVec2 GlyphExtraSpacing; // 0, 0 // Extra spacing (in pixels) between glyphs. Only X axis is supported for now. + ImVec2 GlyphOffset; // 0, 0 // Offset all glyphs from this font input. + const ImWchar* GlyphRanges; // NULL // Pointer to a user-provided list of Unicode range (2 value per range, values are inclusive, zero-terminated list). THE ARRAY DATA NEEDS TO PERSIST AS LONG AS THE FONT IS ALIVE. + bool MergeMode; // false // Merge into previous ImFont, so you can combine multiple inputs font into one ImFont (e.g. ASCII font + icons + Japanese glyphs). You may want to use GlyphOffset.y when merge font of different heights. + unsigned int RasterizerFlags; // 0x00 // Settings for custom font rasterizer (e.g. ImGuiFreeType). Leave as zero if you aren't using one. + float RasterizerMultiply; // 1.0f // Brighten (>1.0f) or darken (<1.0f) font output. Brightening small fonts may be a good workaround to make them more readable. // [Internal] - char Name[32]; // Name (strictly for debugging) + char Name[40]; // Name (strictly to ease debugging) ImFont* DstFont; IMGUI_API ImFontConfig(); }; -// Load and rasterize multiple TTF fonts into a same texture. +struct ImFontGlyph +{ + ImWchar Codepoint; // 0x0000..0xFFFF + float AdvanceX; // Distance to next character (= data from font + ImFontConfig::GlyphExtraSpacing.x baked in) + float X0, Y0, X1, Y1; // Glyph corners + float U0, V0, U1, V1; // Texture coordinates +}; + +enum ImFontAtlasFlags_ +{ + ImFontAtlasFlags_NoPowerOfTwoHeight = 1 << 0, // Don't round the height to next power of two + ImFontAtlasFlags_NoMouseCursors = 1 << 1 // Don't build software mouse cursors into the atlas +}; + +// Load and rasterize multiple TTF/OTF fonts into a same texture. // Sharing a texture for multiple fonts allows us to reduce the number of draw calls during rendering. // We also add custom graphic data into the texture that serves for ImGui. // 1. (Optional) Call AddFont*** functions. If you don't call any, the default font will be loaded for you. // 2. Call GetTexDataAsAlpha8() or GetTexDataAsRGBA32() to build and retrieve pixels data. // 3. Upload the pixels data into a texture within your graphics system. // 4. Call SetTexID(my_tex_id); and pass the pointer/identifier to your texture. This value will be passed back to you during rendering to identify the texture. -// 5. Call ClearTexData() to free textures memory on the heap. -// NB: If you use a 'glyph_ranges' array you need to make sure that your array persist up until the ImFont is cleared. We only copy the pointer, not the data. +// IMPORTANT: If you pass a 'glyph_ranges' array to AddFont*** functions, you need to make sure that your array persist up until the ImFont is build (when calling GetTextData*** or Build()). We only copy the pointer, not the data. struct ImFontAtlas { IMGUI_API ImFontAtlas(); @@ -1293,70 +1694,111 @@ struct ImFontAtlas IMGUI_API ImFont* AddFont(const ImFontConfig* font_cfg); IMGUI_API ImFont* AddFontDefault(const ImFontConfig* font_cfg = NULL); IMGUI_API ImFont* AddFontFromFileTTF(const char* filename, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); - IMGUI_API ImFont* AddFontFromMemoryTTF(void* ttf_data, int ttf_size, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // Transfer ownership of 'ttf_data' to ImFontAtlas, will be deleted after Build() - IMGUI_API ImFont* AddFontFromMemoryCompressedTTF(const void* compressed_ttf_data, int compressed_ttf_size, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // 'compressed_ttf_data' still owned by caller. Compress with binary_to_compressed_c.cpp - IMGUI_API ImFont* AddFontFromMemoryCompressedBase85TTF(const char* compressed_ttf_data_base85, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // 'compressed_ttf_data_base85' still owned by caller. Compress with binary_to_compressed_c.cpp with -base85 paramaeter - IMGUI_API void ClearTexData(); // Clear the CPU-side texture data. Saves RAM once the texture has been copied to graphics memory. - IMGUI_API void ClearInputData(); // Clear the input TTF data (inc sizes, glyph ranges) - IMGUI_API void ClearFonts(); // Clear the ImGui-side font data (glyphs storage, UV coordinates) - IMGUI_API void Clear(); // Clear all - - // Retrieve texture data - // User is in charge of copying the pixels into graphics memory, then call SetTextureUserID() - // After loading the texture into your graphic system, store your texture handle in 'TexID' (ignore if you aren't using multiple fonts nor images) - // RGBA32 format is provided for convenience and high compatibility, but note that all RGB pixels are white, so 75% of the memory is wasted. + IMGUI_API ImFont* AddFontFromMemoryTTF(void* font_data, int font_size, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // Note: Transfer ownership of 'ttf_data' to ImFontAtlas! Will be deleted after Build(). Set font_cfg->FontDataOwnedByAtlas to false to keep ownership. + IMGUI_API ImFont* AddFontFromMemoryCompressedTTF(const void* compressed_font_data, int compressed_font_size, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // 'compressed_font_data' still owned by caller. Compress with binary_to_compressed_c.cpp. + IMGUI_API ImFont* AddFontFromMemoryCompressedBase85TTF(const char* compressed_font_data_base85, float size_pixels, const ImFontConfig* font_cfg = NULL, const ImWchar* glyph_ranges = NULL); // 'compressed_font_data_base85' still owned by caller. Compress with binary_to_compressed_c.cpp with -base85 parameter. + IMGUI_API void ClearInputData(); // Clear input data (all ImFontConfig structures including sizes, TTF data, glyph ranges, etc.) = all the data used to build the texture and fonts. + IMGUI_API void ClearTexData(); // Clear output texture data (CPU side). Saves RAM once the texture has been copied to graphics memory. + IMGUI_API void ClearFonts(); // Clear output font data (glyphs storage, UV coordinates). + IMGUI_API void Clear(); // Clear all input and output. + + // Build atlas, retrieve pixel data. + // User is in charge of copying the pixels into graphics memory (e.g. create a texture with your engine). Then store your texture handle with SetTexID(). + // RGBA32 format is provided for convenience and compatibility, but note that unless you use CustomRect to draw color data, the RGB pixels emitted from Fonts will all be white (~75% of waste). // Pitch = Width * BytesPerPixels + IMGUI_API bool Build(); // Build pixels data. This is called automatically for you by the GetTexData*** functions. IMGUI_API void GetTexDataAsAlpha8(unsigned char** out_pixels, int* out_width, int* out_height, int* out_bytes_per_pixel = NULL); // 1 byte per-pixel IMGUI_API void GetTexDataAsRGBA32(unsigned char** out_pixels, int* out_width, int* out_height, int* out_bytes_per_pixel = NULL); // 4 bytes-per-pixel - void SetTexID(void* id) { TexID = id; } + void SetTexID(ImTextureID id) { TexID = id; } + + //------------------------------------------- + // Glyph Ranges + //------------------------------------------- // Helpers to retrieve list of common Unicode ranges (2 value per range, values are inclusive, zero-terminated list) - // NB: Make sure that your string are UTF-8 and NOT in your local code page. See FAQ for details. + // NB: Make sure that your string are UTF-8 and NOT in your local code page. In C++11, you can create UTF-8 string literal using the u8"Hello world" syntax. See FAQ for details. IMGUI_API const ImWchar* GetGlyphRangesDefault(); // Basic Latin, Extended Latin IMGUI_API const ImWchar* GetGlyphRangesKorean(); // Default + Korean characters IMGUI_API const ImWchar* GetGlyphRangesJapanese(); // Default + Hiragana, Katakana, Half-Width, Selection of 1946 Ideographs - IMGUI_API const ImWchar* GetGlyphRangesChinese(); // Japanese + full set of about 21000 CJK Unified Ideographs + IMGUI_API const ImWchar* GetGlyphRangesChinese(); // Default + Japanese + full set of about 21000 CJK Unified Ideographs IMGUI_API const ImWchar* GetGlyphRangesCyrillic(); // Default + about 400 Cyrillic characters IMGUI_API const ImWchar* GetGlyphRangesThai(); // Default + Thai characters + // Helpers to build glyph ranges from text data. Feed your application strings/characters to it then call BuildRanges(). + struct GlyphRangesBuilder + { + ImVector<unsigned char> UsedChars; // Store 1-bit per Unicode code point (0=unused, 1=used) + GlyphRangesBuilder() { UsedChars.resize(0x10000 / 8); memset(UsedChars.Data, 0, 0x10000 / 8); } + bool GetBit(int n) { return (UsedChars[n >> 3] & (1 << (n & 7))) != 0; } + void SetBit(int n) { UsedChars[n >> 3] |= 1 << (n & 7); } // Set bit 'c' in the array + void AddChar(ImWchar c) { SetBit(c); } // Add character + IMGUI_API void AddText(const char* text, const char* text_end = NULL); // Add string (each character of the UTF-8 string are added) + IMGUI_API void AddRanges(const ImWchar* ranges); // Add ranges, e.g. builder.AddRanges(ImFontAtlas::GetGlyphRangesDefault) to force add all of ASCII/Latin+Ext + IMGUI_API void BuildRanges(ImVector<ImWchar>* out_ranges); // Output new ranges + }; + + //------------------------------------------- + // Custom Rectangles/Glyphs API + //------------------------------------------- + + // You can request arbitrary rectangles to be packed into the atlas, for your own purposes. After calling Build(), you can query the rectangle position and render your pixels. + // You can also request your rectangles to be mapped as font glyph (given a font + Unicode point), so you can render e.g. custom colorful icons and use them as regular glyphs. + struct CustomRect + { + unsigned int ID; // Input // User ID. Use <0x10000 to map into a font glyph, >=0x10000 for other/internal/custom texture data. + unsigned short Width, Height; // Input // Desired rectangle dimension + unsigned short X, Y; // Output // Packed position in Atlas + float GlyphAdvanceX; // Input // For custom font glyphs only (ID<0x10000): glyph xadvance + ImVec2 GlyphOffset; // Input // For custom font glyphs only (ID<0x10000): glyph display offset + ImFont* Font; // Input // For custom font glyphs only (ID<0x10000): target font + CustomRect() { ID = 0xFFFFFFFF; Width = Height = 0; X = Y = 0xFFFF; GlyphAdvanceX = 0.0f; GlyphOffset = ImVec2(0,0); Font = NULL; } + bool IsPacked() const { return X != 0xFFFF; } + }; + + IMGUI_API int AddCustomRectRegular(unsigned int id, int width, int height); // Id needs to be >= 0x10000. Id >= 0x80000000 are reserved for ImGui and ImDrawList + IMGUI_API int AddCustomRectFontGlyph(ImFont* font, ImWchar id, int width, int height, float advance_x, const ImVec2& offset = ImVec2(0,0)); // Id needs to be < 0x10000 to register a rectangle to map into a specific font. + const CustomRect* GetCustomRectByIndex(int index) const { if (index < 0) return NULL; return &CustomRects[index]; } + + // [Internal] + IMGUI_API void CalcCustomRectUV(const CustomRect* rect, ImVec2* out_uv_min, ImVec2* out_uv_max); + IMGUI_API bool GetMouseCursorTexData(ImGuiMouseCursor cursor, ImVec2* out_offset, ImVec2* out_size, ImVec2 out_uv_border[2], ImVec2 out_uv_fill[2]); + + //------------------------------------------- // Members - // (Access texture data via GetTexData*() calls which will setup a default font for you.) - void* TexID; // User data to refer to the texture once it has been uploaded to user's graphic systems. It ia passed back to you during rendering. + //------------------------------------------- + + ImFontAtlasFlags Flags; // Build flags (see ImFontAtlasFlags_) + ImTextureID TexID; // User data to refer to the texture once it has been uploaded to user's graphic systems. It is passed back to you during rendering via the ImDrawCmd structure. + int TexDesiredWidth; // Texture width desired by user before Build(). Must be a power-of-two. If have many glyphs your graphics API have texture size restrictions you may want to increase texture width to decrease height. + int TexGlyphPadding; // Padding between glyphs within texture in pixels. Defaults to 1. + + // [Internal] + // NB: Access texture data via GetTexData*() calls! Which will setup a default font for you. unsigned char* TexPixelsAlpha8; // 1 component per pixel, each component is unsigned 8-bit. Total size = TexWidth * TexHeight unsigned int* TexPixelsRGBA32; // 4 component per pixel, each component is unsigned 8-bit. Total size = TexWidth * TexHeight * 4 int TexWidth; // Texture width calculated during Build(). int TexHeight; // Texture height calculated during Build(). - int TexDesiredWidth; // Texture width desired by user before Build(). Must be a power-of-two. If have many glyphs your graphics API have texture size restrictions you may want to increase texture width to decrease height. + ImVec2 TexUvScale; // = (1.0f/TexWidth, 1.0f/TexHeight) ImVec2 TexUvWhitePixel; // Texture coordinates to a white pixel ImVector<ImFont*> Fonts; // Hold all the fonts returned by AddFont*. Fonts[0] is the default font upon calling ImGui::NewFrame(), use ImGui::PushFont()/PopFont() to change the current font. - - // Private + ImVector<CustomRect> CustomRects; // Rectangles for packing custom texture data into the atlas. ImVector<ImFontConfig> ConfigData; // Internal data - IMGUI_API bool Build(); // Build pixels data. This is automatically for you by the GetTexData*** functions. - IMGUI_API void RenderCustomTexData(int pass, void* rects); + int CustomRectIds[1]; // Identifiers of custom texture rectangle used by ImFontAtlas/ImDrawList }; // Font runtime data and rendering // ImFontAtlas automatically loads a default embedded font for you when you call GetTexDataAsAlpha8() or GetTexDataAsRGBA32(). struct ImFont { - struct Glyph - { - ImWchar Codepoint; - float XAdvance; - float X0, Y0, X1, Y1; - float U0, V0, U1, V1; // Texture coordinates - }; - // Members: Hot ~62/78 bytes float FontSize; // <user set> // Height of characters, set during loading (don't change after loading) float Scale; // = 1.f // Base font scale, multiplied by the per-window font scale which you can adjust with SetFontScale() - ImVec2 DisplayOffset; // = (0.f,1.f) // Offset font rendering by xx pixels - ImVector<Glyph> Glyphs; // // All glyphs. - ImVector<float> IndexXAdvance; // // Sparse. Glyphs->XAdvance in a directly indexable way (more cache-friendly, for CalcTextSize functions which are often bottleneck in large UI). + ImVec2 DisplayOffset; // = (0.f,0.f) // Offset font rendering by xx pixels + ImVector<ImFontGlyph> Glyphs; // // All glyphs. + ImVector<float> IndexAdvanceX; // // Sparse. Glyphs->AdvanceX in a directly indexable way (more cache-friendly, for CalcTextSize functions which are often bottleneck in large UI). ImVector<unsigned short> IndexLookup; // // Sparse. Index glyphs by Unicode code-point. - const Glyph* FallbackGlyph; // == FindGlyph(FontFallbackChar) - float FallbackXAdvance; // == FallbackGlyph->XAdvance + const ImFontGlyph* FallbackGlyph; // == FindGlyph(FontFallbackChar) + float FallbackAdvanceX; // == FallbackGlyph->AdvanceX ImWchar FallbackChar; // = '?' // Replacement glyph if one isn't found. Only set via SetFallbackChar() // Members: Cold ~18/26 bytes @@ -1364,16 +1806,20 @@ struct ImFont ImFontConfig* ConfigData; // // Pointer within ContainerAtlas->ConfigData ImFontAtlas* ContainerAtlas; // // What we has been loaded into float Ascent, Descent; // // Ascent: distance from top to bottom of e.g. 'A' [0..FontSize] + bool DirtyLookupTables; + int MetricsTotalSurface;// // Total surface in pixels to get an idea of the font rasterization/texture cost (not exact, we approximate the cost of padding between glyphs) // Methods IMGUI_API ImFont(); IMGUI_API ~ImFont(); - IMGUI_API void Clear(); + IMGUI_API void ClearOutputData(); IMGUI_API void BuildLookupTable(); - IMGUI_API const Glyph* FindGlyph(ImWchar c) const; + IMGUI_API const ImFontGlyph*FindGlyph(ImWchar c) const; + IMGUI_API const ImFontGlyph*FindGlyphNoFallback(ImWchar c) const; IMGUI_API void SetFallbackChar(ImWchar c); - float GetCharAdvance(ImWchar c) const { return ((int)c < IndexXAdvance.Size) ? IndexXAdvance[(int)c] : FallbackXAdvance; } + float GetCharAdvance(ImWchar c) const { return ((int)c < IndexAdvanceX.Size) ? IndexAdvanceX[(int)c] : FallbackAdvanceX; } bool IsLoaded() const { return ContainerAtlas != NULL; } + const char* GetDebugName() const { return ConfigData ? ConfigData->Name : "<unknown>"; } // 'max_width' stops rendering after a certain width (could be turned into a 2d size). FLT_MAX to disable. // 'wrap_width' enable automatic word-wrapping across multiple lines to fit into given width. 0.0f to disable. @@ -1382,18 +1828,21 @@ struct ImFont IMGUI_API void RenderChar(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col, unsigned short c) const; IMGUI_API void RenderText(ImDrawList* draw_list, float size, ImVec2 pos, ImU32 col, const ImVec4& clip_rect, const char* text_begin, const char* text_end, float wrap_width = 0.0f, bool cpu_fine_clip = false) const; - // Private + // [Internal] IMGUI_API void GrowIndex(int new_size); + IMGUI_API void AddGlyph(ImWchar c, float x0, float y0, float x1, float y1, float u0, float v0, float u1, float v1, float advance_x); IMGUI_API void AddRemapChar(ImWchar dst, ImWchar src, bool overwrite_dst = true); // Makes 'dst' character/glyph points to 'src' character/glyph. Currently needs to be called AFTER fonts have been built. + +#ifndef IMGUI_DISABLE_OBSOLETE_FUNCTIONS + typedef ImFontGlyph Glyph; // OBSOLETE 1.52+ +#endif }; #if defined(__clang__) #pragma clang diagnostic pop #endif -//---- Include imgui_user.h at the end of imgui.h -//---- So you can include code that extends ImGui using any of the types declared above. -//---- (also convenient for user to only explicitly include vanilla imgui.h) +// Include imgui_user.h at the end of imgui.h (convenient for user to only explicitly include vanilla imgui.h) #ifdef IMGUI_INCLUDE_IMGUI_USER_H #include "imgui_user.h" #endif diff --git a/include/imgui_impl_glfw.h b/include/imgui_impl_glfw.h deleted file mode 100644 index 07dd96f..0000000 --- a/include/imgui_impl_glfw.h +++ /dev/null @@ -1,29 +0,0 @@ -// ImGui GLFW binding with OpenGL -// In this binding, ImTextureID is used to store an OpenGL 'GLuint' texture identifier. Read the FAQ about ImTextureID in imgui.cpp. - -// If your context is GL3/GL3 then prefer using the code in opengl3_example. -// You *might* use this code with a GL3/GL4 context but make sure you disable the programmable pipeline by calling "glUseProgram(0)" before ImGui::Render(). -// We cannot do that from GL2 code because the function doesn't exist. - -// You can copy and use unmodified imgui_impl_* files in your project. See main.cpp for an example of using this. -// If you use this binding you'll need to call 4 functions: ImGui_ImplXXXX_Init(), ImGui_ImplXXXX_NewFrame(), ImGui::Render() and ImGui_ImplXXXX_Shutdown(). -// If you are new to ImGui, see examples/README.txt and documentation at the top of imgui.cpp. -// https://github.com/ocornut/imgui - -struct GLFWwindow; - -IMGUI_API bool ImGui_ImplGlfw_Init(GLFWwindow* window, bool install_callbacks); -IMGUI_API void ImGui_ImplGlfw_Shutdown(); -IMGUI_API void ImGui_ImplGlfw_NewFrame(); - -// Use if you want to reset your rendering device without losing ImGui state. -IMGUI_API void ImGui_ImplGlfw_InvalidateDeviceObjects(); -IMGUI_API bool ImGui_ImplGlfw_CreateDeviceObjects(); - -// GLFW callbacks (installed by default if you enable 'install_callbacks' during initialization) -// Provided here if you want to chain callbacks. -// You can also handle inputs yourself and use those as a reference. -IMGUI_API void ImGui_ImplGlfw_MouseButtonCallback(GLFWwindow* window, int button, int action, int mods); -IMGUI_API void ImGui_ImplGlfw_ScrollCallback(GLFWwindow* window, double xoffset, double yoffset); -IMGUI_API void ImGui_ImplGlFw_KeyCallback(GLFWwindow* window, int key, int scancode, int action, int mods); -IMGUI_API void ImGui_ImplGlfw_CharCallback(GLFWwindow* window, unsigned int c); diff --git a/include/imgui_impl_glfw_gl2.h b/include/imgui_impl_glfw_gl2.h new file mode 100644 index 0000000..4e0f393 --- /dev/null +++ b/include/imgui_impl_glfw_gl2.h @@ -0,0 +1,32 @@ +// ImGui GLFW binding with OpenGL (legacy, fixed pipeline) +// (GLFW is a cross-platform general purpose library for handling windows, inputs, OpenGL/Vulkan graphics context creation, etc.) + +// Implemented features: +// [X] User texture binding. Cast 'GLuint' OpenGL texture identifier as void*/ImTextureID. Read the FAQ about ImTextureID in imgui.cpp. + +// **DO NOT USE THIS CODE IF YOUR CODE/ENGINE IS USING MODERN OPENGL (SHADERS, VBO, VAO, etc.)** +// **Prefer using the code in the opengl3_example/ folder** +// See imgui_impl_glfw.cpp for details. + +// You can copy and use unmodified imgui_impl_* files in your project. See main.cpp for an example of using this. +// If you use this binding you'll need to call 4 functions: ImGui_ImplXXXX_Init(), ImGui_ImplXXXX_NewFrame(), ImGui::Render() and ImGui_ImplXXXX_Shutdown(). +// If you are new to ImGui, see examples/README.txt and documentation at the top of imgui.cpp. +// https://github.com/ocornut/imgui + +struct GLFWwindow; + +IMGUI_API bool ImGui_ImplGlfwGL2_Init(GLFWwindow* window, bool install_callbacks); +IMGUI_API void ImGui_ImplGlfwGL2_Shutdown(); +IMGUI_API void ImGui_ImplGlfwGL2_NewFrame(); +IMGUI_API void ImGui_ImplGlfwGL2_RenderDrawData(ImDrawData* draw_data); + +// Use if you want to reset your rendering device without losing ImGui state. +IMGUI_API void ImGui_ImplGlfwGL2_InvalidateDeviceObjects(); +IMGUI_API bool ImGui_ImplGlfwGL2_CreateDeviceObjects(); + +// GLFW callbacks (registered by default to GLFW if you enable 'install_callbacks' during initialization) +// Provided here if you want to chain callbacks yourself. You may also handle inputs yourself and use those as a reference. +IMGUI_API void ImGui_ImplGlfw_MouseButtonCallback(GLFWwindow* window, int button, int action, int mods); +IMGUI_API void ImGui_ImplGlfw_ScrollCallback(GLFWwindow* window, double xoffset, double yoffset); +IMGUI_API void ImGui_ImplGlfw_KeyCallback(GLFWwindow* window, int key, int scancode, int action, int mods); +IMGUI_API void ImGui_ImplGlfw_CharCallback(GLFWwindow* window, unsigned int c); diff --git a/include/imgui_impl_glfw_gl3.h b/include/imgui_impl_glfw_gl3.h index 83c69aa..33b5329 100644 --- a/include/imgui_impl_glfw_gl3.h +++ b/include/imgui_impl_glfw_gl3.h @@ -1,5 +1,10 @@ // ImGui GLFW binding with OpenGL3 + shaders -// In this binding, ImTextureID is used to store an OpenGL 'GLuint' texture identifier. Read the FAQ about ImTextureID in imgui.cpp. +// (GLFW is a cross-platform general purpose library for handling windows, inputs, OpenGL/Vulkan graphics context creation, etc.) +// (GL3W is a helper library to access OpenGL functions since there is no standard header to access modern OpenGL functions easily. Alternatives are GLEW, Glad, etc.) + +// Implemented features: +// [X] User texture binding. Cast 'GLuint' OpenGL texture identifier as void*/ImTextureID. Read the FAQ about ImTextureID in imgui.cpp. +// [X] Gamepad navigation mapping. Enable with 'io.ConfigFlags |= ImGuiConfigFlags_NavEnableGamepad'. // You can copy and use unmodified imgui_impl_* files in your project. See main.cpp for an example of using this. // If you use this binding you'll need to call 4 functions: ImGui_ImplXXXX_Init(), ImGui_ImplXXXX_NewFrame(), ImGui::Render() and ImGui_ImplXXXX_Shutdown(). @@ -8,9 +13,10 @@ struct GLFWwindow; -IMGUI_API bool ImGui_ImplGlfwGL3_Init(GLFWwindow* window, bool install_callbacks); +IMGUI_API bool ImGui_ImplGlfwGL3_Init(GLFWwindow* window, bool install_callbacks, const char* glsl_version = NULL); IMGUI_API void ImGui_ImplGlfwGL3_Shutdown(); IMGUI_API void ImGui_ImplGlfwGL3_NewFrame(); +IMGUI_API void ImGui_ImplGlfwGL3_RenderDrawData(ImDrawData* draw_data); // Use if you want to reset your rendering device without losing ImGui state. IMGUI_API void ImGui_ImplGlfwGL3_InvalidateDeviceObjects(); @@ -19,7 +25,7 @@ IMGUI_API bool ImGui_ImplGlfwGL3_CreateDeviceObjects(); // GLFW callbacks (installed by default if you enable 'install_callbacks' during initialization) // Provided here if you want to chain callbacks. // You can also handle inputs yourself and use those as a reference. -IMGUI_API void ImGui_ImplGlfwGL3_MouseButtonCallback(GLFWwindow* window, int button, int action, int mods); -IMGUI_API void ImGui_ImplGlfwGL3_ScrollCallback(GLFWwindow* window, double xoffset, double yoffset); -IMGUI_API void ImGui_ImplGlfwGL3_KeyCallback(GLFWwindow* window, int key, int scancode, int action, int mods); -IMGUI_API void ImGui_ImplGlfwGL3_CharCallback(GLFWwindow* window, unsigned int c); +IMGUI_API void ImGui_ImplGlfw_MouseButtonCallback(GLFWwindow* window, int button, int action, int mods); +IMGUI_API void ImGui_ImplGlfw_ScrollCallback(GLFWwindow* window, double xoffset, double yoffset); +IMGUI_API void ImGui_ImplGlfw_KeyCallback(GLFWwindow* window, int key, int scancode, int action, int mods); +IMGUI_API void ImGui_ImplGlfw_CharCallback(GLFWwindow* window, unsigned int c); diff --git a/include/imgui_internal.h b/include/imgui_internal.h index 4bfec9d..0af5302 100644 --- a/include/imgui_internal.h +++ b/include/imgui_internal.h @@ -1,9 +1,10 @@ -// dear imgui, v1.50 WIP +// dear imgui, v1.60 // (internals) // You may use this file to debug, understand or extend ImGui features but we don't provide any guarantee of forward compatibility! -// Implement maths operators for ImVec2 (disabled by default to not collide with using IM_VEC2_CLASS_EXTRA along with your own math types+operators) +// Set: // #define IMGUI_DEFINE_MATH_OPERATORS +// To implement maths operators for ImVec2 (disabled by default to not collide with using IM_VEC2_CLASS_EXTRA along with your own math types+operators) #pragma once @@ -13,6 +14,7 @@ #include <stdio.h> // FILE* #include <math.h> // sqrtf, fabsf, fmodf, powf, floorf, ceilf, cosf, sinf +#include <limits.h> // INT_MIN, INT_MAX #ifdef _MSC_VER #pragma warning (push) @@ -34,18 +36,21 @@ struct ImRect; struct ImGuiColMod; struct ImGuiStyleMod; struct ImGuiGroupData; -struct ImGuiSimpleColumns; +struct ImGuiMenuColumns; struct ImGuiDrawContext; struct ImGuiTextEditState; -struct ImGuiIniData; -struct ImGuiMouseCursorData; struct ImGuiPopupRef; struct ImGuiWindow; +struct ImGuiWindowSettings; -typedef int ImGuiLayoutType; // enum ImGuiLayoutType_ -typedef int ImGuiButtonFlags; // enum ImGuiButtonFlags_ -typedef int ImGuiTreeNodeFlags; // enum ImGuiTreeNodeFlags_ -typedef int ImGuiSliderFlags; // enum ImGuiSliderFlags_ +typedef int ImGuiLayoutType; // enum: horizontal or vertical // enum ImGuiLayoutType_ +typedef int ImGuiButtonFlags; // flags: for ButtonEx(), ButtonBehavior() // enum ImGuiButtonFlags_ +typedef int ImGuiItemFlags; // flags: for PushItemFlag() // enum ImGuiItemFlags_ +typedef int ImGuiItemStatusFlags; // flags: storage for DC.LastItemXXX // enum ImGuiItemStatusFlags_ +typedef int ImGuiNavHighlightFlags; // flags: for RenderNavHighlight() // enum ImGuiNavHighlightFlags_ +typedef int ImGuiNavDirSourceFlags; // flags: for GetNavInputAmount2d() // enum ImGuiNavDirSourceFlags_ +typedef int ImGuiSeparatorFlags; // flags: for Separator() - internal // enum ImGuiSeparatorFlags_ +typedef int ImGuiSliderFlags; // flags: for SliderBehavior() // enum ImGuiSliderFlags_ //------------------------------------------------------------------------- // STB libraries @@ -67,15 +72,20 @@ namespace ImGuiStb // Context //----------------------------------------------------------------------------- -extern IMGUI_API ImGuiContext* GImGui; // current implicit ImGui context pointer +#ifndef GImGui +extern IMGUI_API ImGuiContext* GImGui; // Current implicit ImGui context pointer +#endif //----------------------------------------------------------------------------- // Helpers //----------------------------------------------------------------------------- -#define IM_ARRAYSIZE(_ARR) ((int)(sizeof(_ARR)/sizeof(*_ARR))) -#define IM_PI 3.14159265358979323846f -#define IM_OFFSETOF(_TYPE,_ELM) ((size_t)&(((_TYPE*)0)->_ELM)) +#define IM_PI 3.14159265358979323846f +#ifdef _WIN32 +#define IM_NEWLINE "\r\n" // Play it nice with Windows users (2018: Notepad _still_ doesn't display files properly when they use Unix-style carriage returns) +#else +#define IM_NEWLINE "\n" +#endif // Helpers: UTF-8 <> wchar IMGUI_API int ImTextStrToUtf8(char* buf, int buf_size, const ImWchar* in_text, const ImWchar* in_text_end); // return output UTF-8 bytes count @@ -86,20 +96,29 @@ IMGUI_API int ImTextCountUtf8BytesFromStr(const ImWchar* in_text, cons // Helpers: Misc IMGUI_API ImU32 ImHash(const void* data, int data_size, ImU32 seed = 0); // Pass data_size==0 for zero-terminated strings -IMGUI_API void* ImLoadFileToMemory(const char* filename, const char* file_open_mode, int* out_file_size = NULL, int padding_bytes = 0); -IMGUI_API bool ImIsPointInTriangle(const ImVec2& p, const ImVec2& a, const ImVec2& b, const ImVec2& c); -static inline bool ImCharIsSpace(int c) { return c == ' ' || c == '\t' || c == 0x3000; } +IMGUI_API void* ImFileLoadToMemory(const char* filename, const char* file_open_mode, int* out_file_size = NULL, int padding_bytes = 0); +IMGUI_API FILE* ImFileOpen(const char* filename, const char* file_open_mode); +static inline bool ImCharIsSpace(unsigned int c) { return c == ' ' || c == '\t' || c == 0x3000; } +static inline bool ImIsPowerOfTwo(int v) { return v != 0 && (v & (v - 1)) == 0; } static inline int ImUpperPowerOfTwo(int v) { v--; v |= v >> 1; v |= v >> 2; v |= v >> 4; v |= v >> 8; v |= v >> 16; v++; return v; } +// Helpers: Geometry +IMGUI_API ImVec2 ImLineClosestPoint(const ImVec2& a, const ImVec2& b, const ImVec2& p); +IMGUI_API bool ImTriangleContainsPoint(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& p); +IMGUI_API ImVec2 ImTriangleClosestPoint(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& p); +IMGUI_API void ImTriangleBarycentricCoords(const ImVec2& a, const ImVec2& b, const ImVec2& c, const ImVec2& p, float& out_u, float& out_v, float& out_w); + // Helpers: String IMGUI_API int ImStricmp(const char* str1, const char* str2); -IMGUI_API int ImStrnicmp(const char* str1, const char* str2, int count); +IMGUI_API int ImStrnicmp(const char* str1, const char* str2, size_t count); +IMGUI_API void ImStrncpy(char* dst, const char* src, size_t count); IMGUI_API char* ImStrdup(const char* str); +IMGUI_API const char* ImStrchrRange(const char* str_begin, const char* str_end, char c); IMGUI_API int ImStrlenW(const ImWchar* str); IMGUI_API const ImWchar*ImStrbolW(const ImWchar* buf_mid_line, const ImWchar* buf_begin); // Find beginning-of-line IMGUI_API const char* ImStristr(const char* haystack, const char* haystack_end, const char* needle, const char* needle_end); -IMGUI_API int ImFormatString(char* buf, int buf_size, const char* fmt, ...) IM_PRINTFARGS(3); -IMGUI_API int ImFormatStringV(char* buf, int buf_size, const char* fmt, va_list args); +IMGUI_API int ImFormatString(char* buf, size_t buf_size, const char* fmt, ...) IM_FMTARGS(3); +IMGUI_API int ImFormatStringV(char* buf, size_t buf_size, const char* fmt, va_list args) IM_FMTLIST(3); // Helpers: Math // We are keeping those not leaking to the user by default, in the case the user has implicit cast operators between ImVec2 and its own types (when IM_VEC2_CLASS_EXTRA is defined) @@ -114,35 +133,37 @@ static inline ImVec2& operator+=(ImVec2& lhs, const ImVec2& rhs) static inline ImVec2& operator-=(ImVec2& lhs, const ImVec2& rhs) { lhs.x -= rhs.x; lhs.y -= rhs.y; return lhs; } static inline ImVec2& operator*=(ImVec2& lhs, const float rhs) { lhs.x *= rhs; lhs.y *= rhs; return lhs; } static inline ImVec2& operator/=(ImVec2& lhs, const float rhs) { lhs.x /= rhs; lhs.y /= rhs; return lhs; } +static inline ImVec4 operator+(const ImVec4& lhs, const ImVec4& rhs) { return ImVec4(lhs.x+rhs.x, lhs.y+rhs.y, lhs.z+rhs.z, lhs.w+rhs.w); } static inline ImVec4 operator-(const ImVec4& lhs, const ImVec4& rhs) { return ImVec4(lhs.x-rhs.x, lhs.y-rhs.y, lhs.z-rhs.z, lhs.w-rhs.w); } +static inline ImVec4 operator*(const ImVec4& lhs, const ImVec4& rhs) { return ImVec4(lhs.x*rhs.x, lhs.y*rhs.y, lhs.z*rhs.z, lhs.w*rhs.w); } #endif static inline int ImMin(int lhs, int rhs) { return lhs < rhs ? lhs : rhs; } static inline int ImMax(int lhs, int rhs) { return lhs >= rhs ? lhs : rhs; } static inline float ImMin(float lhs, float rhs) { return lhs < rhs ? lhs : rhs; } static inline float ImMax(float lhs, float rhs) { return lhs >= rhs ? lhs : rhs; } -static inline ImVec2 ImMin(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(ImMin(lhs.x,rhs.x), ImMin(lhs.y,rhs.y)); } -static inline ImVec2 ImMax(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(ImMax(lhs.x,rhs.x), ImMax(lhs.y,rhs.y)); } +static inline ImVec2 ImMin(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(lhs.x < rhs.x ? lhs.x : rhs.x, lhs.y < rhs.y ? lhs.y : rhs.y); } +static inline ImVec2 ImMax(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(lhs.x >= rhs.x ? lhs.x : rhs.x, lhs.y >= rhs.y ? lhs.y : rhs.y); } static inline int ImClamp(int v, int mn, int mx) { return (v < mn) ? mn : (v > mx) ? mx : v; } static inline float ImClamp(float v, float mn, float mx) { return (v < mn) ? mn : (v > mx) ? mx : v; } static inline ImVec2 ImClamp(const ImVec2& f, const ImVec2& mn, ImVec2 mx) { return ImVec2(ImClamp(f.x,mn.x,mx.x), ImClamp(f.y,mn.y,mx.y)); } static inline float ImSaturate(float f) { return (f < 0.0f) ? 0.0f : (f > 1.0f) ? 1.0f : f; } +static inline void ImSwap(int& a, int& b) { int tmp = a; a = b; b = tmp; } +static inline void ImSwap(float& a, float& b) { float tmp = a; a = b; b = tmp; } +static inline int ImLerp(int a, int b, float t) { return (int)(a + (b - a) * t); } static inline float ImLerp(float a, float b, float t) { return a + (b - a) * t; } +static inline ImVec2 ImLerp(const ImVec2& a, const ImVec2& b, float t) { return ImVec2(a.x + (b.x - a.x) * t, a.y + (b.y - a.y) * t); } static inline ImVec2 ImLerp(const ImVec2& a, const ImVec2& b, const ImVec2& t) { return ImVec2(a.x + (b.x - a.x) * t.x, a.y + (b.y - a.y) * t.y); } +static inline ImVec4 ImLerp(const ImVec4& a, const ImVec4& b, float t) { return ImVec4(a.x + (b.x - a.x) * t, a.y + (b.y - a.y) * t, a.z + (b.z - a.z) * t, a.w + (b.w - a.w) * t); } static inline float ImLengthSqr(const ImVec2& lhs) { return lhs.x*lhs.x + lhs.y*lhs.y; } static inline float ImLengthSqr(const ImVec4& lhs) { return lhs.x*lhs.x + lhs.y*lhs.y + lhs.z*lhs.z + lhs.w*lhs.w; } static inline float ImInvLength(const ImVec2& lhs, float fail_value) { float d = lhs.x*lhs.x + lhs.y*lhs.y; if (d > 0.0f) return 1.0f / sqrtf(d); return fail_value; } static inline float ImFloor(float f) { return (float)(int)f; } -static inline ImVec2 ImFloor(ImVec2 v) { return ImVec2((float)(int)v.x, (float)(int)v.y); } - -// We call C++ constructor on own allocated memory via the placement "new(ptr) Type()" syntax. -// Defining a custom placement new() with a dummy parameter allows us to bypass including <new> which on some platforms complains when user has disabled exceptions. -#ifdef IMGUI_DEFINE_PLACEMENT_NEW -struct ImPlacementNewDummy {}; -inline void* operator new(size_t, ImPlacementNewDummy, void* ptr) { return ptr; } -inline void operator delete(void*, ImPlacementNewDummy, void*) {} -#define IM_PLACEMENT_NEW(_PTR) new(ImPlacementNewDummy(), _PTR) -#endif +static inline ImVec2 ImFloor(const ImVec2& v) { return ImVec2((float)(int)v.x, (float)(int)v.y); } +static inline float ImDot(const ImVec2& a, const ImVec2& b) { return a.x * b.x + a.y * b.y; } +static inline ImVec2 ImRotate(const ImVec2& v, float cos_a, float sin_a) { return ImVec2(v.x * cos_a - v.y * sin_a, v.x * sin_a + v.y * cos_a); } +static inline float ImLinearSweep(float current, float target, float speed) { if (current < target) return ImMin(current + speed, target); if (current > target) return ImMax(current - speed, target); return current; } +static inline ImVec2 ImMul(const ImVec2& lhs, const ImVec2& rhs) { return ImVec2(lhs.x * rhs.x, lhs.y * rhs.y); } //----------------------------------------------------------------------------- // Types @@ -151,16 +172,19 @@ inline void operator delete(void*, ImPlacementNewDummy, void*) {} enum ImGuiButtonFlags_ { ImGuiButtonFlags_Repeat = 1 << 0, // hold to repeat - ImGuiButtonFlags_PressedOnClickRelease = 1 << 1, // (default) return pressed on click+release on same item (default if no PressedOn** flag is set) - ImGuiButtonFlags_PressedOnClick = 1 << 2, // return pressed on click (default requires click+release) - ImGuiButtonFlags_PressedOnRelease = 1 << 3, // return pressed on release (default requires click+release) - ImGuiButtonFlags_PressedOnDoubleClick = 1 << 4, // return pressed on double-click (default requires click+release) - ImGuiButtonFlags_FlattenChilds = 1 << 5, // allow interaction even if a child window is overlapping - ImGuiButtonFlags_DontClosePopups = 1 << 6, // disable automatically closing parent popup on press - ImGuiButtonFlags_Disabled = 1 << 7, // disable interaction - ImGuiButtonFlags_AlignTextBaseLine = 1 << 8, // vertically align button to match text baseline - ButtonEx() only - ImGuiButtonFlags_NoKeyModifiers = 1 << 9, // disable interaction if a key modifier is held - ImGuiButtonFlags_AllowOverlapMode = 1 << 10 // require previous frame HoveredId to either match id or be null before being usable + ImGuiButtonFlags_PressedOnClickRelease = 1 << 1, // return true on click + release on same item [DEFAULT if no PressedOn* flag is set] + ImGuiButtonFlags_PressedOnClick = 1 << 2, // return true on click (default requires click+release) + ImGuiButtonFlags_PressedOnRelease = 1 << 3, // return true on release (default requires click+release) + ImGuiButtonFlags_PressedOnDoubleClick = 1 << 4, // return true on double-click (default requires click+release) + ImGuiButtonFlags_FlattenChildren = 1 << 5, // allow interactions even if a child window is overlapping + ImGuiButtonFlags_AllowItemOverlap = 1 << 6, // require previous frame HoveredId to either match id or be null before being usable, use along with SetItemAllowOverlap() + ImGuiButtonFlags_DontClosePopups = 1 << 7, // disable automatically closing parent popup on press // [UNUSED] + ImGuiButtonFlags_Disabled = 1 << 8, // disable interactions + ImGuiButtonFlags_AlignTextBaseLine = 1 << 9, // vertically align button to match text baseline - ButtonEx() only // FIXME: Should be removed and handled by SmallButton(), not possible currently because of DC.CursorPosPrevLine + ImGuiButtonFlags_NoKeyModifiers = 1 << 10, // disable interaction if a key modifier is held + ImGuiButtonFlags_NoHoldingActiveID = 1 << 11, // don't set ActiveId while holding the mouse (ImGuiButtonFlags_PressedOnClick only) + ImGuiButtonFlags_PressedOnDragDropHold = 1 << 12, // press when held into while we are drag and dropping another item (used by e.g. tree nodes, collapsing headers) + ImGuiButtonFlags_NoNavFocus = 1 << 13 // don't override navigation focus when activated }; enum ImGuiSliderFlags_ @@ -168,15 +192,38 @@ enum ImGuiSliderFlags_ ImGuiSliderFlags_Vertical = 1 << 0 }; +enum ImGuiColumnsFlags_ +{ + // Default: 0 + ImGuiColumnsFlags_NoBorder = 1 << 0, // Disable column dividers + ImGuiColumnsFlags_NoResize = 1 << 1, // Disable resizing columns when clicking on the dividers + ImGuiColumnsFlags_NoPreserveWidths = 1 << 2, // Disable column width preservation when adjusting columns + ImGuiColumnsFlags_NoForceWithinWindow = 1 << 3, // Disable forcing columns to fit within window + ImGuiColumnsFlags_GrowParentContentsSize= 1 << 4 // (WIP) Restore pre-1.51 behavior of extending the parent window contents size but _without affecting the columns width at all_. Will eventually remove. +}; + enum ImGuiSelectableFlagsPrivate_ { // NB: need to be in sync with last value of ImGuiSelectableFlags_ - ImGuiSelectableFlags_Menu = 1 << 3, - ImGuiSelectableFlags_MenuItem = 1 << 4, + ImGuiSelectableFlags_Menu = 1 << 3, // -> PressedOnClick + ImGuiSelectableFlags_MenuItem = 1 << 4, // -> PressedOnRelease ImGuiSelectableFlags_Disabled = 1 << 5, ImGuiSelectableFlags_DrawFillAvailWidth = 1 << 6 }; +enum ImGuiSeparatorFlags_ +{ + ImGuiSeparatorFlags_Horizontal = 1 << 0, // Axis default to current layout type, so generally Horizontal unless e.g. in a menu bar + ImGuiSeparatorFlags_Vertical = 1 << 1 +}; + +// Storage for LastItem data +enum ImGuiItemStatusFlags_ +{ + ImGuiItemStatusFlags_HoveredRect = 1 << 0, + ImGuiItemStatusFlags_HasDisplayRect = 1 << 1 +}; + // FIXME: this is in development, not exposed/functional as a generic feature yet. enum ImGuiLayoutType_ { @@ -184,6 +231,13 @@ enum ImGuiLayoutType_ ImGuiLayoutType_Horizontal }; +enum ImGuiAxis +{ + ImGuiAxis_None = -1, + ImGuiAxis_X = 0, + ImGuiAxis_Y = 1 +}; + enum ImGuiPlotType { ImGuiPlotType_Lines, @@ -194,7 +248,51 @@ enum ImGuiDataType { ImGuiDataType_Int, ImGuiDataType_Float, - ImGuiDataType_Float2, + ImGuiDataType_Double, + ImGuiDataType_COUNT +}; + +enum ImGuiInputSource +{ + ImGuiInputSource_None = 0, + ImGuiInputSource_Mouse, + ImGuiInputSource_Nav, + ImGuiInputSource_NavKeyboard, // Only used occasionally for storage, not tested/handled by most code + ImGuiInputSource_NavGamepad, // " + ImGuiInputSource_COUNT +}; + +// FIXME-NAV: Clarify/expose various repeat delay/rate +enum ImGuiInputReadMode +{ + ImGuiInputReadMode_Down, + ImGuiInputReadMode_Pressed, + ImGuiInputReadMode_Released, + ImGuiInputReadMode_Repeat, + ImGuiInputReadMode_RepeatSlow, + ImGuiInputReadMode_RepeatFast +}; + +enum ImGuiNavHighlightFlags_ +{ + ImGuiNavHighlightFlags_TypeDefault = 1 << 0, + ImGuiNavHighlightFlags_TypeThin = 1 << 1, + ImGuiNavHighlightFlags_AlwaysDraw = 1 << 2, + ImGuiNavHighlightFlags_NoRounding = 1 << 3 +}; + +enum ImGuiNavDirSourceFlags_ +{ + ImGuiNavDirSourceFlags_Keyboard = 1 << 0, + ImGuiNavDirSourceFlags_PadDPad = 1 << 1, + ImGuiNavDirSourceFlags_PadLStick = 1 << 2 +}; + +enum ImGuiNavForward +{ + ImGuiNavForward_None, + ImGuiNavForward_ForwardQueued, + ImGuiNavForward_ForwardActive }; // 2D axis aligned bounding-box @@ -209,34 +307,27 @@ struct IMGUI_API ImRect ImRect(const ImVec4& v) : Min(v.x, v.y), Max(v.z, v.w) {} ImRect(float x1, float y1, float x2, float y2) : Min(x1, y1), Max(x2, y2) {} - ImVec2 GetCenter() const { return ImVec2((Min.x+Max.x)*0.5f, (Min.y+Max.y)*0.5f); } - ImVec2 GetSize() const { return ImVec2(Max.x-Min.x, Max.y-Min.y); } - float GetWidth() const { return Max.x-Min.x; } - float GetHeight() const { return Max.y-Min.y; } - ImVec2 GetTL() const { return Min; } // Top-left - ImVec2 GetTR() const { return ImVec2(Max.x, Min.y); } // Top-right - ImVec2 GetBL() const { return ImVec2(Min.x, Max.y); } // Bottom-left - ImVec2 GetBR() const { return Max; } // Bottom-right - bool Contains(const ImVec2& p) const { return p.x >= Min.x && p.y >= Min.y && p.x < Max.x && p.y < Max.y; } - bool Contains(const ImRect& r) const { return r.Min.x >= Min.x && r.Min.y >= Min.y && r.Max.x < Max.x && r.Max.y < Max.y; } - bool Overlaps(const ImRect& r) const { return r.Min.y < Max.y && r.Max.y > Min.y && r.Min.x < Max.x && r.Max.x > Min.x; } - void Add(const ImVec2& rhs) { if (Min.x > rhs.x) Min.x = rhs.x; if (Min.y > rhs.y) Min.y = rhs.y; if (Max.x < rhs.x) Max.x = rhs.x; if (Max.y < rhs.y) Max.y = rhs.y; } - void Add(const ImRect& rhs) { if (Min.x > rhs.Min.x) Min.x = rhs.Min.x; if (Min.y > rhs.Min.y) Min.y = rhs.Min.y; if (Max.x < rhs.Max.x) Max.x = rhs.Max.x; if (Max.y < rhs.Max.y) Max.y = rhs.Max.y; } - void Expand(const float amount) { Min.x -= amount; Min.y -= amount; Max.x += amount; Max.y += amount; } - void Expand(const ImVec2& amount) { Min.x -= amount.x; Min.y -= amount.y; Max.x += amount.x; Max.y += amount.y; } - void Reduce(const ImVec2& amount) { Min.x += amount.x; Min.y += amount.y; Max.x -= amount.x; Max.y -= amount.y; } - void Clip(const ImRect& clip) { if (Min.x < clip.Min.x) Min.x = clip.Min.x; if (Min.y < clip.Min.y) Min.y = clip.Min.y; if (Max.x > clip.Max.x) Max.x = clip.Max.x; if (Max.y > clip.Max.y) Max.y = clip.Max.y; } - void Floor() { Min.x = (float)(int)Min.x; Min.y = (float)(int)Min.y; Max.x = (float)(int)Max.x; Max.y = (float)(int)Max.y; } - ImVec2 GetClosestPoint(ImVec2 p, bool on_edge) const - { - if (!on_edge && Contains(p)) - return p; - if (p.x > Max.x) p.x = Max.x; - else if (p.x < Min.x) p.x = Min.x; - if (p.y > Max.y) p.y = Max.y; - else if (p.y < Min.y) p.y = Min.y; - return p; - } + ImVec2 GetCenter() const { return ImVec2((Min.x + Max.x) * 0.5f, (Min.y + Max.y) * 0.5f); } + ImVec2 GetSize() const { return ImVec2(Max.x - Min.x, Max.y - Min.y); } + float GetWidth() const { return Max.x - Min.x; } + float GetHeight() const { return Max.y - Min.y; } + ImVec2 GetTL() const { return Min; } // Top-left + ImVec2 GetTR() const { return ImVec2(Max.x, Min.y); } // Top-right + ImVec2 GetBL() const { return ImVec2(Min.x, Max.y); } // Bottom-left + ImVec2 GetBR() const { return Max; } // Bottom-right + bool Contains(const ImVec2& p) const { return p.x >= Min.x && p.y >= Min.y && p.x < Max.x && p.y < Max.y; } + bool Contains(const ImRect& r) const { return r.Min.x >= Min.x && r.Min.y >= Min.y && r.Max.x <= Max.x && r.Max.y <= Max.y; } + bool Overlaps(const ImRect& r) const { return r.Min.y < Max.y && r.Max.y > Min.y && r.Min.x < Max.x && r.Max.x > Min.x; } + void Add(const ImVec2& p) { if (Min.x > p.x) Min.x = p.x; if (Min.y > p.y) Min.y = p.y; if (Max.x < p.x) Max.x = p.x; if (Max.y < p.y) Max.y = p.y; } + void Add(const ImRect& r) { if (Min.x > r.Min.x) Min.x = r.Min.x; if (Min.y > r.Min.y) Min.y = r.Min.y; if (Max.x < r.Max.x) Max.x = r.Max.x; if (Max.y < r.Max.y) Max.y = r.Max.y; } + void Expand(const float amount) { Min.x -= amount; Min.y -= amount; Max.x += amount; Max.y += amount; } + void Expand(const ImVec2& amount) { Min.x -= amount.x; Min.y -= amount.y; Max.x += amount.x; Max.y += amount.y; } + void Translate(const ImVec2& v) { Min.x += v.x; Min.y += v.y; Max.x += v.x; Max.y += v.y; } + void ClipWith(const ImRect& r) { Min = ImMax(Min, r.Min); Max = ImMin(Max, r.Max); } // Simple version, may lead to an inverted rectangle, which is fine for Contains/Overlaps test but not for display. + void ClipWithFull(const ImRect& r) { Min = ImClamp(Min, r.Min, r.Max); Max = ImClamp(Max, r.Min, r.Max); } // Full version, ensure both points are fully clipped. + void Floor() { Min.x = (float)(int)Min.x; Min.y = (float)(int)Min.y; Max.x = (float)(int)Max.x; Max.y = (float)(int)Max.y; } + void FixInverted() { if (Min.x > Max.x) ImSwap(Min.x, Max.x); if (Min.y > Max.y) ImSwap(Min.y, Max.y); } + bool IsInverted() const { return Min.x > Max.x || Min.y > Max.y; } }; // Stacked color modifier, backup of modified data so we can restore it @@ -270,22 +361,15 @@ struct ImGuiGroupData bool AdvanceCursor; }; -// Per column data for Columns() -struct ImGuiColumnData -{ - float OffsetNorm; // Column start offset, normalized 0.0 (far left) -> 1.0 (far right) - //float IndentX; -}; - // Simple column measurement currently used for MenuItem() only. This is very short-sighted/throw-away code and NOT a generic helper. -struct IMGUI_API ImGuiSimpleColumns +struct IMGUI_API ImGuiMenuColumns { int Count; float Spacing; float Width, NextWidth; - float Pos[8], NextWidths[8]; + float Pos[4], NextWidths[4]; - ImGuiSimpleColumns(); + ImGuiMenuColumns(); void Update(int count, float spacing, bool clear); float DeclColumns(float w0, float w1, float w2); float CalcExtraSpace(float avail_w); @@ -311,52 +395,174 @@ struct IMGUI_API ImGuiTextEditState void CursorClamp() { StbState.cursor = ImMin(StbState.cursor, CurLenW); StbState.select_start = ImMin(StbState.select_start, CurLenW); StbState.select_end = ImMin(StbState.select_end, CurLenW); } bool HasSelection() const { return StbState.select_start != StbState.select_end; } void ClearSelection() { StbState.select_start = StbState.select_end = StbState.cursor; } - void SelectAll() { StbState.select_start = 0; StbState.select_end = CurLenW; StbState.cursor = StbState.select_end; StbState.has_preferred_x = false; } + void SelectAll() { StbState.select_start = 0; StbState.cursor = StbState.select_end = CurLenW; StbState.has_preferred_x = false; } void OnKeyPressed(int key); }; // Data saved in imgui.ini file -struct ImGuiIniData +struct ImGuiWindowSettings { char* Name; ImGuiID Id; ImVec2 Pos; ImVec2 Size; bool Collapsed; + + ImGuiWindowSettings() { Name = NULL; Id = 0; Pos = Size = ImVec2(0,0); Collapsed = false; } }; -// Mouse cursor data (used when io.MouseDrawCursor is set) -struct ImGuiMouseCursorData +struct ImGuiSettingsHandler { - ImGuiMouseCursor Type; - ImVec2 HotOffset; - ImVec2 Size; - ImVec2 TexUvMin[2]; - ImVec2 TexUvMax[2]; + const char* TypeName; // Short description stored in .ini file. Disallowed characters: '[' ']' + ImGuiID TypeHash; // == ImHash(TypeName, 0, 0) + void* (*ReadOpenFn)(ImGuiContext* ctx, ImGuiSettingsHandler* handler, const char* name); + void (*ReadLineFn)(ImGuiContext* ctx, ImGuiSettingsHandler* handler, void* entry, const char* line); + void (*WriteAllFn)(ImGuiContext* ctx, ImGuiSettingsHandler* handler, ImGuiTextBuffer* out_buf); + void* UserData; + + ImGuiSettingsHandler() { memset(this, 0, sizeof(*this)); } }; // Storage for current popup stack struct ImGuiPopupRef { - ImGuiID PopupId; // Set on OpenPopup() - ImGuiWindow* Window; // Resolved on BeginPopup() - may stay unresolved if user never calls OpenPopup() - ImGuiWindow* ParentWindow; // Set on OpenPopup() - ImGuiID ParentMenuSet; // Set on OpenPopup() - ImVec2 MousePosOnOpen; // Copy of mouse position at the time of opening popup + ImGuiID PopupId; // Set on OpenPopup() + ImGuiWindow* Window; // Resolved on BeginPopup() - may stay unresolved if user never calls OpenPopup() + ImGuiWindow* ParentWindow; // Set on OpenPopup() + int OpenFrameCount; // Set on OpenPopup() + ImGuiID OpenParentId; // Set on OpenPopup(), we need this to differenciate multiple menu sets from each others (e.g. inside menu bar vs loose menu items) + ImVec2 OpenPopupPos; // Set on OpenPopup(), preferred popup position (typically == OpenMousePos when using mouse) + ImVec2 OpenMousePos; // Set on OpenPopup(), copy of mouse position at the time of opening popup +}; + +struct ImGuiColumnData +{ + float OffsetNorm; // Column start offset, normalized 0.0 (far left) -> 1.0 (far right) + float OffsetNormBeforeResize; + ImGuiColumnsFlags Flags; // Not exposed + ImRect ClipRect; + + ImGuiColumnData() { OffsetNorm = OffsetNormBeforeResize = 0.0f; Flags = 0; } +}; - ImGuiPopupRef(ImGuiID id, ImGuiWindow* parent_window, ImGuiID parent_menu_set, const ImVec2& mouse_pos) { PopupId = id; Window = NULL; ParentWindow = parent_window; ParentMenuSet = parent_menu_set; MousePosOnOpen = mouse_pos; } +struct ImGuiColumnsSet +{ + ImGuiID ID; + ImGuiColumnsFlags Flags; + bool IsFirstFrame; + bool IsBeingResized; + int Current; + int Count; + float MinX, MaxX; + float LineMinY, LineMaxY; + float StartPosY; // Copy of CursorPos + float StartMaxPosX; // Copy of CursorMaxPos + ImVector<ImGuiColumnData> Columns; + + ImGuiColumnsSet() { Clear(); } + void Clear() + { + ID = 0; + Flags = 0; + IsFirstFrame = false; + IsBeingResized = false; + Current = 0; + Count = 1; + MinX = MaxX = 0.0f; + LineMinY = LineMaxY = 0.0f; + StartPosY = 0.0f; + StartMaxPosX = 0.0f; + Columns.clear(); + } +}; + +struct IMGUI_API ImDrawListSharedData +{ + ImVec2 TexUvWhitePixel; // UV of white pixel in the atlas + ImFont* Font; // Current/default font (optional, for simplified AddText overload) + float FontSize; // Current/default font size (optional, for simplified AddText overload) + float CurveTessellationTol; + ImVec4 ClipRectFullscreen; // Value for PushClipRectFullscreen() + + // Const data + // FIXME: Bake rounded corners fill/borders in atlas + ImVec2 CircleVtx12[12]; + + ImDrawListSharedData(); +}; + +struct ImDrawDataBuilder +{ + ImVector<ImDrawList*> Layers[2]; // Global layers for: regular, tooltip + + void Clear() { for (int n = 0; n < IM_ARRAYSIZE(Layers); n++) Layers[n].resize(0); } + void ClearFreeMemory() { for (int n = 0; n < IM_ARRAYSIZE(Layers); n++) Layers[n].clear(); } + IMGUI_API void FlattenIntoSingleLayer(); +}; + +struct ImGuiNavMoveResult +{ + ImGuiID ID; // Best candidate + ImGuiID ParentID; // Best candidate window->IDStack.back() - to compare context + ImGuiWindow* Window; // Best candidate window + float DistBox; // Best candidate box distance to current NavId + float DistCenter; // Best candidate center distance to current NavId + float DistAxial; + ImRect RectRel; // Best candidate bounding box in window relative space + + ImGuiNavMoveResult() { Clear(); } + void Clear() { ID = ParentID = 0; Window = NULL; DistBox = DistCenter = DistAxial = FLT_MAX; RectRel = ImRect(); } +}; + +// Storage for SetNexWindow** functions +struct ImGuiNextWindowData +{ + ImGuiCond PosCond; + ImGuiCond SizeCond; + ImGuiCond ContentSizeCond; + ImGuiCond CollapsedCond; + ImGuiCond SizeConstraintCond; + ImGuiCond FocusCond; + ImGuiCond BgAlphaCond; + ImVec2 PosVal; + ImVec2 PosPivotVal; + ImVec2 SizeVal; + ImVec2 ContentSizeVal; + bool CollapsedVal; + ImRect SizeConstraintRect; // Valid if 'SetNextWindowSizeConstraint' is true + ImGuiSizeCallback SizeCallback; + void* SizeCallbackUserData; + float BgAlphaVal; + + ImGuiNextWindowData() + { + PosCond = SizeCond = ContentSizeCond = CollapsedCond = SizeConstraintCond = FocusCond = BgAlphaCond = 0; + PosVal = PosPivotVal = SizeVal = ImVec2(0.0f, 0.0f); + ContentSizeVal = ImVec2(0.0f, 0.0f); + CollapsedVal = false; + SizeConstraintRect = ImRect(); + SizeCallback = NULL; + SizeCallbackUserData = NULL; + BgAlphaVal = FLT_MAX; + } + + void Clear() + { + PosCond = SizeCond = ContentSizeCond = CollapsedCond = SizeConstraintCond = FocusCond = BgAlphaCond = 0; + } }; // Main state for ImGui struct ImGuiContext { bool Initialized; + bool FontAtlasOwnedByContext; // Io.Fonts-> is owned by the ImGuiContext and will be destructed along with it. ImGuiIO IO; ImGuiStyle Style; ImFont* Font; // (Shortcut) == FontStack.empty() ? IO.Font : FontStack.back() - float FontSize; // (Shortcut) == FontBaseSize * g.CurrentWindow->FontWindowScale == window->FontSize() - float FontBaseSize; // (Shortcut) == IO.FontGlobalScale * Font->Scale * Font->FontSize. Size of characters. - ImVec2 FontTexUvWhitePixel; // (Shortcut) == Font->TexUvWhitePixel + float FontSize; // (Shortcut) == FontBaseSize * g.CurrentWindow->FontWindowScale == window->FontSize(). Text height for current window. + float FontBaseSize; // (Shortcut) == IO.FontGlobalScale * Font->Scale * Font->FontSize. Base text height. + ImDrawListSharedData DrawListSharedData; float Time; int FrameCount; @@ -364,71 +570,114 @@ struct ImGuiContext int FrameCountRendered; ImVector<ImGuiWindow*> Windows; ImVector<ImGuiWindow*> WindowsSortBuffer; - ImGuiWindow* CurrentWindow; // Being drawn into ImVector<ImGuiWindow*> CurrentWindowStack; - ImGuiWindow* FocusedWindow; // Will catch keyboard inputs + ImGuiStorage WindowsById; + int WindowsActiveCount; + ImGuiWindow* CurrentWindow; // Being drawn into ImGuiWindow* HoveredWindow; // Will catch mouse inputs ImGuiWindow* HoveredRootWindow; // Will catch mouse inputs (for focus/move only) ImGuiID HoveredId; // Hovered widget bool HoveredIdAllowOverlap; ImGuiID HoveredIdPreviousFrame; + float HoveredIdTimer; ImGuiID ActiveId; // Active widget ImGuiID ActiveIdPreviousFrame; - bool ActiveIdIsAlive; + float ActiveIdTimer; + bool ActiveIdIsAlive; // Active widget has been seen this frame bool ActiveIdIsJustActivated; // Set at the time of activation for one frame - bool ActiveIdAllowOverlap; // Set only by active widget + bool ActiveIdAllowOverlap; // Active widget allows another widget to steal active id (generally for overlapping widgets, but not always) + int ActiveIdAllowNavDirFlags; // Active widget allows using directional navigation (e.g. can activate a button and move away from it) ImVec2 ActiveIdClickOffset; // Clicked offset from upper-left corner, if applicable (currently only set by ButtonBehavior) ImGuiWindow* ActiveIdWindow; - ImGuiWindow* MovedWindow; // Track the child window we clicked on to move a window. - ImGuiID MovedWindowMoveId; // == MovedWindow->RootWindow->MoveId - ImVector<ImGuiIniData> Settings; // .ini Settings - float SettingsDirtyTimer; // Save .ini Settings on disk when time reaches zero + ImGuiInputSource ActiveIdSource; // Activating with mouse or nav (gamepad/keyboard) + ImGuiWindow* MovingWindow; // Track the window we clicked on (in order to preserve focus). The actually window that is moved is generally MovingWindow->RootWindow. ImVector<ImGuiColMod> ColorModifiers; // Stack for PushStyleColor()/PopStyleColor() ImVector<ImGuiStyleMod> StyleModifiers; // Stack for PushStyleVar()/PopStyleVar() ImVector<ImFont*> FontStack; // Stack for PushFont()/PopFont() ImVector<ImGuiPopupRef> OpenPopupStack; // Which popups are open (persistent) ImVector<ImGuiPopupRef> CurrentPopupStack; // Which level of BeginPopup() we are in (reset every frame) - - // Storage for SetNexWindow** and SetNextTreeNode*** functions - ImVec2 SetNextWindowPosVal; - ImVec2 SetNextWindowSizeVal; - ImVec2 SetNextWindowContentSizeVal; - bool SetNextWindowCollapsedVal; - ImGuiSetCond SetNextWindowPosCond; - ImGuiSetCond SetNextWindowSizeCond; - ImGuiSetCond SetNextWindowContentSizeCond; - ImGuiSetCond SetNextWindowCollapsedCond; - ImRect SetNextWindowSizeConstraintRect; // Valid if 'SetNextWindowSizeConstraint' is true - ImGuiSizeConstraintCallback SetNextWindowSizeConstraintCallback; - void* SetNextWindowSizeConstraintCallbackUserData; - bool SetNextWindowSizeConstraint; - bool SetNextWindowFocus; - bool SetNextTreeNodeOpenVal; - ImGuiSetCond SetNextTreeNodeOpenCond; + ImGuiNextWindowData NextWindowData; // Storage for SetNextWindow** functions + bool NextTreeNodeOpenVal; // Storage for SetNextTreeNode** functions + ImGuiCond NextTreeNodeOpenCond; + + // Navigation data (for gamepad/keyboard) + ImGuiWindow* NavWindow; // Focused window for navigation. Could be called 'FocusWindow' + ImGuiID NavId; // Focused item for navigation + ImGuiID NavActivateId; // ~~ (g.ActiveId == 0) && IsNavInputPressed(ImGuiNavInput_Activate) ? NavId : 0, also set when calling ActivateItem() + ImGuiID NavActivateDownId; // ~~ IsNavInputDown(ImGuiNavInput_Activate) ? NavId : 0 + ImGuiID NavActivatePressedId; // ~~ IsNavInputPressed(ImGuiNavInput_Activate) ? NavId : 0 + ImGuiID NavInputId; // ~~ IsNavInputPressed(ImGuiNavInput_Input) ? NavId : 0 + ImGuiID NavJustTabbedId; // Just tabbed to this id. + ImGuiID NavJustMovedToId; // Just navigated to this id (result of a successfully MoveRequest) + ImGuiID NavNextActivateId; // Set by ActivateItem(), queued until next frame + ImGuiInputSource NavInputSource; // Keyboard or Gamepad mode? + ImRect NavScoringRectScreen; // Rectangle used for scoring, in screen space. Based of window->DC.NavRefRectRel[], modified for directional navigation scoring. + int NavScoringCount; // Metrics for debugging + ImGuiWindow* NavWindowingTarget; // When selecting a window (holding Menu+FocusPrev/Next, or equivalent of CTRL-TAB) this window is temporarily displayed front-most. + float NavWindowingHighlightTimer; + float NavWindowingHighlightAlpha; + bool NavWindowingToggleLayer; + int NavLayer; // Layer we are navigating on. For now the system is hard-coded for 0=main contents and 1=menu/title bar, may expose layers later. + int NavIdTabCounter; // == NavWindow->DC.FocusIdxTabCounter at time of NavId processing + bool NavIdIsAlive; // Nav widget has been seen this frame ~~ NavRefRectRel is valid + bool NavMousePosDirty; // When set we will update mouse position if (io.ConfigFlags & ImGuiConfigFlags_NavEnableSetMousePos) if set (NB: this not enabled by default) + bool NavDisableHighlight; // When user starts using mouse, we hide gamepad/keyboard highlight (NB: but they are still available, which is why NavDisableHighlight isn't always != NavDisableMouseHover) + bool NavDisableMouseHover; // When user starts using gamepad/keyboard, we hide mouse hovering highlight until mouse is touched again. + bool NavAnyRequest; // ~~ NavMoveRequest || NavInitRequest + bool NavInitRequest; // Init request for appearing window to select first item + bool NavInitRequestFromMove; + ImGuiID NavInitResultId; + ImRect NavInitResultRectRel; + bool NavMoveFromClampedRefRect; // Set by manual scrolling, if we scroll to a point where NavId isn't visible we reset navigation from visible items + bool NavMoveRequest; // Move request for this frame + ImGuiNavForward NavMoveRequestForward; // None / ForwardQueued / ForwardActive (this is used to navigate sibling parent menus from a child menu) + ImGuiDir NavMoveDir, NavMoveDirLast; // Direction of the move request (left/right/up/down), direction of the previous move request + ImGuiNavMoveResult NavMoveResultLocal; // Best move request candidate within NavWindow + ImGuiNavMoveResult NavMoveResultOther; // Best move request candidate within NavWindow's flattened hierarchy (when using the NavFlattened flag) // Render - ImDrawData RenderDrawData; // Main ImDrawData instance to pass render information to the user - ImVector<ImDrawList*> RenderDrawLists[3]; + ImDrawData DrawData; // Main ImDrawData instance to pass render information to the user + ImDrawDataBuilder DrawDataBuilder; float ModalWindowDarkeningRatio; ImDrawList OverlayDrawList; // Optional software render of mouse cursors, if io.MouseDrawCursor is set + a few debug overlays ImGuiMouseCursor MouseCursor; - ImGuiMouseCursorData MouseCursorData[ImGuiMouseCursor_Count_]; + + // Drag and Drop + bool DragDropActive; + ImGuiDragDropFlags DragDropSourceFlags; + int DragDropMouseButton; + ImGuiPayload DragDropPayload; + ImRect DragDropTargetRect; + ImGuiID DragDropTargetId; + float DragDropAcceptIdCurrRectSurface; + ImGuiID DragDropAcceptIdCurr; // Target item id (set at the time of accepting the payload) + ImGuiID DragDropAcceptIdPrev; // Target item id from previous frame (we need to store this to allow for overlapping drag and drop targets) + int DragDropAcceptFrameCount; // Last time a target expressed a desire to accept the source + ImVector<unsigned char> DragDropPayloadBufHeap; // We don't expose the ImVector<> directly + unsigned char DragDropPayloadBufLocal[8]; // Local buffer for small payloads // Widget state ImGuiTextEditState InputTextState; ImFont InputTextPasswordFont; ImGuiID ScalarAsInputTextId; // Temporary text input when CTRL+clicking on a slider, etc. - ImGuiStorage ColorEditModeStorage; // Store user selection of color edit mode + ImGuiColorEditFlags ColorEditOptions; // Store user options for color edit widgets + ImVec4 ColorPickerRef; float DragCurrentValue; // Currently dragged value, always float, not rounded by end-user precision settings ImVec2 DragLastMouseDelta; float DragSpeedDefaultRatio; // If speed == 0.0f, uses (max-min) * DragSpeedDefaultRatio float DragSpeedScaleSlow; float DragSpeedScaleFast; ImVec2 ScrollbarClickDeltaToGrabCenter; // Distance between mouse and center of grab box, normalized in parent space. Use storage? - char Tooltip[1024]; - char* PrivateClipboard; // If no custom clipboard handler is defined + int TooltipOverrideCount; + ImVector<char> PrivateClipboard; // If no custom clipboard handler is defined ImVec2 OsImePosRequest, OsImePosSet; // Cursor position request & last passed to the OS Input Method Editor + // Settings + bool SettingsLoaded; + float SettingsDirtyTimer; // Save .ini Settings on disk when time reaches zero + ImVector<ImGuiWindowSettings> SettingsWindows; // .ini settings for ImGuiWindow + ImVector<ImGuiSettingsHandler> SettingsHandlers; // List of .ini settings handlers + // Logging bool LogEnabled; FILE* LogFile; // If != NULL log to stdout/ file @@ -440,66 +689,95 @@ struct ImGuiContext float FramerateSecPerFrame[120]; // calculate estimate of framerate for user int FramerateSecPerFrameIdx; float FramerateSecPerFrameAccum; - int CaptureMouseNextFrame; // explicit capture via CaptureInputs() sets those flags - int CaptureKeyboardNextFrame; + int WantCaptureMouseNextFrame; // explicit capture via CaptureInputs() sets those flags + int WantCaptureKeyboardNextFrame; + int WantTextInputNextFrame; char TempBuffer[1024*3+1]; // temporary text buffer - ImGuiContext() + ImGuiContext(ImFontAtlas* shared_font_atlas) : OverlayDrawList(NULL) { Initialized = false; Font = NULL; FontSize = FontBaseSize = 0.0f; - FontTexUvWhitePixel = ImVec2(0.0f, 0.0f); + FontAtlasOwnedByContext = shared_font_atlas ? false : true; + IO.Fonts = shared_font_atlas ? shared_font_atlas : IM_NEW(ImFontAtlas)(); Time = 0.0f; FrameCount = 0; FrameCountEnded = FrameCountRendered = -1; + WindowsActiveCount = 0; CurrentWindow = NULL; - FocusedWindow = NULL; HoveredWindow = NULL; HoveredRootWindow = NULL; HoveredId = 0; HoveredIdAllowOverlap = false; HoveredIdPreviousFrame = 0; + HoveredIdTimer = 0.0f; ActiveId = 0; ActiveIdPreviousFrame = 0; + ActiveIdTimer = 0.0f; ActiveIdIsAlive = false; ActiveIdIsJustActivated = false; ActiveIdAllowOverlap = false; + ActiveIdAllowNavDirFlags = 0; ActiveIdClickOffset = ImVec2(-1,-1); ActiveIdWindow = NULL; - MovedWindow = NULL; - MovedWindowMoveId = 0; - SettingsDirtyTimer = 0.0f; + ActiveIdSource = ImGuiInputSource_None; + MovingWindow = NULL; + NextTreeNodeOpenVal = false; + NextTreeNodeOpenCond = 0; + + NavWindow = NULL; + NavId = NavActivateId = NavActivateDownId = NavActivatePressedId = NavInputId = 0; + NavJustTabbedId = NavJustMovedToId = NavNextActivateId = 0; + NavInputSource = ImGuiInputSource_None; + NavScoringRectScreen = ImRect(); + NavScoringCount = 0; + NavWindowingTarget = NULL; + NavWindowingHighlightTimer = NavWindowingHighlightAlpha = 0.0f; + NavWindowingToggleLayer = false; + NavLayer = 0; + NavIdTabCounter = INT_MAX; + NavIdIsAlive = false; + NavMousePosDirty = false; + NavDisableHighlight = true; + NavDisableMouseHover = false; + NavAnyRequest = false; + NavInitRequest = false; + NavInitRequestFromMove = false; + NavInitResultId = 0; + NavMoveFromClampedRefRect = false; + NavMoveRequest = false; + NavMoveRequestForward = ImGuiNavForward_None; + NavMoveDir = NavMoveDirLast = ImGuiDir_None; - SetNextWindowPosVal = ImVec2(0.0f, 0.0f); - SetNextWindowSizeVal = ImVec2(0.0f, 0.0f); - SetNextWindowCollapsedVal = false; - SetNextWindowPosCond = 0; - SetNextWindowSizeCond = 0; - SetNextWindowContentSizeCond = 0; - SetNextWindowCollapsedCond = 0; - SetNextWindowFocus = false; - SetNextWindowSizeConstraintCallback = NULL; - SetNextWindowSizeConstraintCallbackUserData = NULL; - SetNextTreeNodeOpenVal = false; - SetNextTreeNodeOpenCond = 0; + ModalWindowDarkeningRatio = 0.0f; + OverlayDrawList._Data = &DrawListSharedData; + OverlayDrawList._OwnerName = "##Overlay"; // Give it a name for debugging + MouseCursor = ImGuiMouseCursor_Arrow; + + DragDropActive = false; + DragDropSourceFlags = 0; + DragDropMouseButton = -1; + DragDropTargetId = 0; + DragDropAcceptIdCurrRectSurface = 0.0f; + DragDropAcceptIdPrev = DragDropAcceptIdCurr = 0; + DragDropAcceptFrameCount = -1; + memset(DragDropPayloadBufLocal, 0, sizeof(DragDropPayloadBufLocal)); ScalarAsInputTextId = 0; + ColorEditOptions = ImGuiColorEditFlags__OptionsDefault; DragCurrentValue = 0.0f; DragLastMouseDelta = ImVec2(0.0f, 0.0f); DragSpeedDefaultRatio = 1.0f / 100.0f; - DragSpeedScaleSlow = 0.01f; + DragSpeedScaleSlow = 1.0f / 100.0f; DragSpeedScaleFast = 10.0f; ScrollbarClickDeltaToGrabCenter = ImVec2(0.0f, 0.0f); - memset(Tooltip, 0, sizeof(Tooltip)); - PrivateClipboard = NULL; + TooltipOverrideCount = 0; OsImePosRequest = OsImePosSet = ImVec2(-1.0f, -1.0f); - ModalWindowDarkeningRatio = 0.0f; - OverlayDrawList._OwnerName = "##Overlay"; // Give it a name for debugging - MouseCursor = ImGuiMouseCursor_Arrow; - memset(MouseCursorData, 0, sizeof(MouseCursorData)); + SettingsLoaded = false; + SettingsDirtyTimer = 0.0f; LogEnabled = false; LogFile = NULL; @@ -510,11 +788,24 @@ struct ImGuiContext memset(FramerateSecPerFrame, 0, sizeof(FramerateSecPerFrame)); FramerateSecPerFrameIdx = 0; FramerateSecPerFrameAccum = 0.0f; - CaptureMouseNextFrame = CaptureKeyboardNextFrame = -1; + WantCaptureMouseNextFrame = WantCaptureKeyboardNextFrame = WantTextInputNextFrame = -1; memset(TempBuffer, 0, sizeof(TempBuffer)); } }; +// Transient per-window flags, reset at the beginning of the frame. For child window, inherited from parent on first Begin(). +// This is going to be exposed in imgui.h when stabilized enough. +enum ImGuiItemFlags_ +{ + ImGuiItemFlags_AllowKeyboardFocus = 1 << 0, // true + ImGuiItemFlags_ButtonRepeat = 1 << 1, // false // Button() will return true multiple times based on io.KeyRepeatDelay and io.KeyRepeatRate settings. + ImGuiItemFlags_Disabled = 1 << 2, // false // FIXME-WIP: Disable interactions but doesn't affect visuals. Should be: grey out and disable interactions with widgets that affect data + view widgets (WIP) + ImGuiItemFlags_NoNav = 1 << 3, // false + ImGuiItemFlags_NoNavDefaultFocus = 1 << 4, // false + ImGuiItemFlags_SelectableDontClosePopup = 1 << 5, // false // MenuItem/Selectable() automatically closes current Popup window + ImGuiItemFlags_Default_ = ImGuiItemFlags_AllowKeyboardFocus +}; + // Transient per-window data, reset at the beginning of the frame // FIXME: That's theory, in practice the delimitation between ImGuiWindow and ImGuiDrawContext is quite tenuous and could be reconsidered. struct IMGUI_API ImGuiDrawContext @@ -522,49 +813,45 @@ struct IMGUI_API ImGuiDrawContext ImVec2 CursorPos; ImVec2 CursorPosPrevLine; ImVec2 CursorStartPos; - ImVec2 CursorMaxPos; // Implicitly calculate the size of our contents, always extending. Saved into window->SizeContents at the end of the frame + ImVec2 CursorMaxPos; // Used to implicitly calculate the size of our contents, always growing during the frame. Turned into window->SizeContents at the beginning of next frame float CurrentLineHeight; float CurrentLineTextBaseOffset; float PrevLineHeight; float PrevLineTextBaseOffset; float LogLinePosY; int TreeDepth; + ImU32 TreeDepthMayJumpToParentOnPop; // Store a copy of !g.NavIdIsAlive for TreeDepth 0..31 ImGuiID LastItemId; - ImRect LastItemRect; - bool LastItemHoveredAndUsable; // Item rectangle is hovered, and its window is currently interactable with (not blocked by a popup preventing access to the window) - bool LastItemHoveredRect; // Item rectangle is hovered, but its window may or not be currently interactable with (might be blocked by a popup preventing access to the window) - bool MenuBarAppending; + ImGuiItemStatusFlags LastItemStatusFlags; + ImRect LastItemRect; // Interaction rect + ImRect LastItemDisplayRect; // End-user display rect (only valid if LastItemStatusFlags & ImGuiItemStatusFlags_HasDisplayRect) + bool NavHideHighlightOneFrame; + bool NavHasScroll; // Set when scrolling can be used (ScrollMax > 0.0f) + int NavLayerCurrent; // Current layer, 0..31 (we currently only use 0..1) + int NavLayerCurrentMask; // = (1 << NavLayerCurrent) used by ItemAdd prior to clipping. + int NavLayerActiveMask; // Which layer have been written to (result from previous frame) + int NavLayerActiveMaskNext; // Which layer have been written to (buffer for current frame) + bool MenuBarAppending; // FIXME: Remove this float MenuBarOffsetX; ImVector<ImGuiWindow*> ChildWindows; ImGuiStorage* StateStorage; ImGuiLayoutType LayoutType; + ImGuiLayoutType ParentLayoutType; // Layout type of parent window at the time of Begin() // We store the current settings outside of the vectors to increase memory locality (reduce cache misses). The vectors are rarely modified. Also it allows us to not heap allocate for short-lived windows which are not using those settings. + ImGuiItemFlags ItemFlags; // == ItemFlagsStack.back() [empty == ImGuiItemFlags_Default] float ItemWidth; // == ItemWidthStack.back(). 0.0: default, >0.0: width in pixels, <0.0: align xx pixels to the right of window float TextWrapPos; // == TextWrapPosStack.back() [empty == -1.0f] - bool AllowKeyboardFocus; // == AllowKeyboardFocusStack.back() [empty == true] - bool ButtonRepeat; // == ButtonRepeatStack.back() [empty == false] + ImVector<ImGuiItemFlags>ItemFlagsStack; ImVector<float> ItemWidthStack; ImVector<float> TextWrapPosStack; - ImVector<bool> AllowKeyboardFocusStack; - ImVector<bool> ButtonRepeatStack; ImVector<ImGuiGroupData>GroupStack; - ImGuiColorEditMode ColorEditMode; int StackSizesBackup[6]; // Store size of various stacks for asserting float IndentX; // Indentation / start position from left of window (increased by TreePush/TreePop, etc.) float GroupOffsetX; float ColumnsOffsetX; // Offset to the current column (if ColumnsCurrent > 0). FIXME: This and the above should be a stack to allow use cases like Tree->Column->Tree. Need revamp columns API. - int ColumnsCurrent; - int ColumnsCount; - float ColumnsMinX; - float ColumnsMaxX; - float ColumnsStartPosY; - float ColumnsCellMinY; - float ColumnsCellMaxY; - bool ColumnsShowBorders; - ImGuiID ColumnsSetId; - ImVector<ImGuiColumnData> ColumnsData; + ImGuiColumnsSet* ColumnsSet; // Current columns set ImGuiDrawContext() { @@ -573,29 +860,28 @@ struct IMGUI_API ImGuiDrawContext CurrentLineTextBaseOffset = PrevLineTextBaseOffset = 0.0f; LogLinePosY = -1.0f; TreeDepth = 0; + TreeDepthMayJumpToParentOnPop = 0x00; LastItemId = 0; - LastItemRect = ImRect(0.0f,0.0f,0.0f,0.0f); - LastItemHoveredAndUsable = LastItemHoveredRect = false; + LastItemStatusFlags = 0; + LastItemRect = LastItemDisplayRect = ImRect(); + NavHideHighlightOneFrame = false; + NavHasScroll = false; + NavLayerActiveMask = NavLayerActiveMaskNext = 0x00; + NavLayerCurrent = 0; + NavLayerCurrentMask = 1 << 0; MenuBarAppending = false; MenuBarOffsetX = 0.0f; StateStorage = NULL; - LayoutType = ImGuiLayoutType_Vertical; + LayoutType = ParentLayoutType = ImGuiLayoutType_Vertical; ItemWidth = 0.0f; - ButtonRepeat = false; - AllowKeyboardFocus = true; + ItemFlags = ImGuiItemFlags_Default_; TextWrapPos = -1.0f; - ColorEditMode = ImGuiColorEditMode_RGB; memset(StackSizesBackup, 0, sizeof(StackSizesBackup)); IndentX = 0.0f; + GroupOffsetX = 0.0f; ColumnsOffsetX = 0.0f; - ColumnsCurrent = 0; - ColumnsCount = 1; - ColumnsMinX = ColumnsMaxX = 0.0f; - ColumnsStartPosY = 0.0f; - ColumnsCellMinY = ColumnsCellMaxY = 0.0f; - ColumnsShowBorders = true; - ColumnsSetId = 0; + ColumnsSet = NULL; } }; @@ -605,53 +891,71 @@ struct IMGUI_API ImGuiWindow char* Name; ImGuiID ID; // == ImHash(Name) ImGuiWindowFlags Flags; // See enum ImGuiWindowFlags_ - int IndexWithinParent; // Order within immediate parent window, if we are a child window. Otherwise 0. ImVec2 PosFloat; ImVec2 Pos; // Position rounded-up to nearest pixel ImVec2 Size; // Current size (==SizeFull or collapsed title bar size) ImVec2 SizeFull; // Size when non collapsed - ImVec2 SizeContents; // Size of contents (== extents reach of the drawing cursor) from previous frame + ImVec2 SizeFullAtLastBegin; // Copy of SizeFull at the end of Begin. This is the reference value we'll use on the next frame to decide if we need scrollbars. + ImVec2 SizeContents; // Size of contents (== extents reach of the drawing cursor) from previous frame. Include decoration, window title, border, menu, etc. ImVec2 SizeContentsExplicit; // Size of contents explicitly set by the user via SetNextWindowContentSize() ImRect ContentsRegionRect; // Maximum visible content position in window coordinates. ~~ (SizeContentsExplicit ? SizeContentsExplicit : Size - ScrollbarSizes) - CursorStartPos, per axis - ImVec2 WindowPadding; // Window padding at the time of begin. We need to lock it, in particular manipulation of the ShowBorder would have an effect + ImVec2 WindowPadding; // Window padding at the time of begin. + float WindowRounding; // Window rounding at the time of begin. + float WindowBorderSize; // Window border size at the time of begin. ImGuiID MoveId; // == window->GetID("#MOVE") + ImGuiID ChildId; // Id of corresponding item in parent window (for child windows) ImVec2 Scroll; ImVec2 ScrollTarget; // target scroll position. stored as cursor position with scrolling canceled out, so the highest point is always 0.0f. (FLT_MAX for no change) ImVec2 ScrollTargetCenterRatio; // 0.0f = scroll so that target position is at top, 0.5f = scroll so that target position is centered bool ScrollbarX, ScrollbarY; ImVec2 ScrollbarSizes; - float BorderSize; - bool Active; // Set to true on Begin() + bool Active; // Set to true on Begin(), unless Collapsed bool WasActive; - bool Accessed; // Set to true when any widget access the current window + bool WriteAccessed; // Set to true when any widget access the current window bool Collapsed; // Set when collapsing window to become only title-bar - bool SkipItems; // == Visible && !Collapsed + bool CollapseToggleWanted; + bool SkipItems; // Set when items can safely be all clipped (e.g. window not visible or collapsed) + bool Appearing; // Set during the frame where the window is appearing (or re-appearing) + bool CloseButton; // Set when the window has a close button (p_open != NULL) + int BeginOrderWithinParent; // Order within immediate parent window, if we are a child window. Otherwise 0. + int BeginOrderWithinContext; // Order within entire imgui context. This is mostly used for debugging submission order related issues. int BeginCount; // Number of Begin() during the current frame (generally 0 or 1, 1+ if appending via multiple Begin/End pairs) ImGuiID PopupId; // ID in the popup stack when this window is used as a popup/menu (because we use generic Name/ID for recycling) int AutoFitFramesX, AutoFitFramesY; bool AutoFitOnlyGrows; - int AutoPosLastDirection; + int AutoFitChildAxises; + ImGuiDir AutoPosLastDirection; int HiddenFrames; - int SetWindowPosAllowFlags; // bit ImGuiSetCond_*** specify if SetWindowPos() call will succeed with this particular flag. - int SetWindowSizeAllowFlags; // bit ImGuiSetCond_*** specify if SetWindowSize() call will succeed with this particular flag. - int SetWindowCollapsedAllowFlags; // bit ImGuiSetCond_*** specify if SetWindowCollapsed() call will succeed with this particular flag. - bool SetWindowPosCenterWanted; + ImGuiCond SetWindowPosAllowFlags; // store condition flags for next SetWindowPos() call. + ImGuiCond SetWindowSizeAllowFlags; // store condition flags for next SetWindowSize() call. + ImGuiCond SetWindowCollapsedAllowFlags; // store condition flags for next SetWindowCollapsed() call. + ImVec2 SetWindowPosVal; // store window position when using a non-zero Pivot (position set needs to be processed when we know the window size) + ImVec2 SetWindowPosPivot; // store window pivot for positioning. ImVec2(0,0) when positioning from top-left corner; ImVec2(0.5f,0.5f) for centering; ImVec2(1,1) for bottom right. ImGuiDrawContext DC; // Temporary per-window data, reset at the beginning of the frame ImVector<ImGuiID> IDStack; // ID stack. ID are hashes seeded with the value at the top of the stack ImRect ClipRect; // = DrawList->clip_rect_stack.back(). Scissoring / clipping rectangle. x1, y1, x2, y2. ImRect WindowRectClipped; // = WindowRect just after setup in Begin(). == window->Rect() for root window. + ImRect InnerRect, InnerClipRect; int LastFrameActive; float ItemWidthDefault; - ImGuiSimpleColumns MenuColumns; // Simplified columns storage for menu items + ImGuiMenuColumns MenuColumns; // Simplified columns storage for menu items ImGuiStorage StateStorage; + ImVector<ImGuiColumnsSet> ColumnsStorage; float FontWindowScale; // Scale multiplier per-window ImDrawList* DrawList; - ImGuiWindow* RootWindow; // If we are a child window, this is pointing to the first non-child parent window. Else point to ourself. - ImGuiWindow* RootNonPopupWindow; // If we are a child window, this is pointing to the first non-child non-popup parent window. Else point to ourself. - ImGuiWindow* ParentWindow; // If we are a child window, this is pointing to our parent window. Else point to NULL. + ImGuiWindow* ParentWindow; // If we are a child _or_ popup window, this is pointing to our parent. Otherwise NULL. + ImGuiWindow* RootWindow; // Point to ourself or first ancestor that is not a child window. + ImGuiWindow* RootWindowForTitleBarHighlight; // Point to ourself or first ancestor which will display TitleBgActive color when this window is active. + ImGuiWindow* RootWindowForTabbing; // Point to ourself or first ancestor which can be CTRL-Tabbed into. + ImGuiWindow* RootWindowForNav; // Point to ourself or first ancestor which doesn't have the NavFlattened flag. + + ImGuiWindow* NavLastChildNavWindow; // When going to the menu bar, we remember the child window we came from. (This could probably be made implicit if we kept g.Windows sorted by last focused including child window.) + ImGuiID NavLastIds[2]; // Last known NavId for this window, per layer (0/1) + ImRect NavRectRel[2]; // Reference rectangle, in window relative space // Navigation / Focus + // FIXME-NAV: Merge all this with the new Nav system, at least the request variables should be moved to ImGuiContext int FocusIdxAllCounter; // Start at -1 and increase as assigned via FocusItemRegister() int FocusIdxTabCounter; // (same, but only count widgets which you can Tab through) int FocusIdxAllRequestCurrent; // Item being requested for focus @@ -660,13 +964,15 @@ struct IMGUI_API ImGuiWindow int FocusIdxTabRequestNext; // " public: - ImGuiWindow(const char* name); + ImGuiWindow(ImGuiContext* context, const char* name); ~ImGuiWindow(); ImGuiID GetID(const char* str, const char* str_end = NULL); ImGuiID GetID(const void* ptr); ImGuiID GetIDNoKeepAlive(const char* str, const char* str_end = NULL); + ImGuiID GetIDFromRectangle(const ImRect& r_abs); + // We don't use g.FontSize because the window may be != g.CurrentWidow. ImRect Rect() const { return ImRect(Pos.x, Pos.y, Pos.x+Size.x, Pos.y+Size.y); } float CalcFontSize() const { return GImGui->FontBaseSize * FontWindowScale; } float TitleBarHeight() const { return (Flags & ImGuiWindowFlags_NoTitleBar) ? 0.0f : CalcFontSize() + GImGui->Style.FramePadding.y * 2.0f; } @@ -675,6 +981,19 @@ public: ImRect MenuBarRect() const { float y1 = Pos.y + TitleBarHeight(); return ImRect(Pos.x, y1, Pos.x + SizeFull.x, y1 + MenuBarHeight()); } }; +// Backup and restore just enough data to be able to use IsItemHovered() on item A after another B in the same window has overwritten the data. +struct ImGuiItemHoveredDataBackup +{ + ImGuiID LastItemId; + ImGuiItemStatusFlags LastItemStatusFlags; + ImRect LastItemRect; + ImRect LastItemDisplayRect; + + ImGuiItemHoveredDataBackup() { Backup(); } + void Backup() { ImGuiWindow* window = GImGui->CurrentWindow; LastItemId = window->DC.LastItemId; LastItemStatusFlags = window->DC.LastItemStatusFlags; LastItemRect = window->DC.LastItemRect; LastItemDisplayRect = window->DC.LastItemDisplayRect; } + void Restore() const { ImGuiWindow* window = GImGui->CurrentWindow; window->DC.LastItemId = LastItemId; window->DC.LastItemStatusFlags = LastItemStatusFlags; window->DC.LastItemRect = LastItemRect; window->DC.LastItemDisplayRect = LastItemDisplayRect; } +}; + //----------------------------------------------------------------------------- // Internal API // No guarantee of forward compatibility here. @@ -687,39 +1006,87 @@ namespace ImGui // - ImGui::NewFrame() has never been called, which is illegal. // - You are calling ImGui functions after ImGui::Render() and before the next ImGui::NewFrame(), which is also illegal. inline ImGuiWindow* GetCurrentWindowRead() { ImGuiContext& g = *GImGui; return g.CurrentWindow; } - inline ImGuiWindow* GetCurrentWindow() { ImGuiContext& g = *GImGui; g.CurrentWindow->Accessed = true; return g.CurrentWindow; } - IMGUI_API ImGuiWindow* GetParentWindow(); + inline ImGuiWindow* GetCurrentWindow() { ImGuiContext& g = *GImGui; g.CurrentWindow->WriteAccessed = true; return g.CurrentWindow; } IMGUI_API ImGuiWindow* FindWindowByName(const char* name); IMGUI_API void FocusWindow(ImGuiWindow* window); + IMGUI_API void BringWindowToFront(ImGuiWindow* window); + IMGUI_API void BringWindowToBack(ImGuiWindow* window); + IMGUI_API bool IsWindowChildOf(ImGuiWindow* window, ImGuiWindow* potential_parent); + IMGUI_API bool IsWindowNavFocusable(ImGuiWindow* window); + + IMGUI_API void Initialize(ImGuiContext* context); + IMGUI_API void Shutdown(ImGuiContext* context); // Since 1.60 this is a _private_ function. You can call DestroyContext() to destroy the context created by CreateContext(). - IMGUI_API void EndFrame(); // Ends the ImGui frame. Automatically called by Render()! you most likely don't need to ever call that yourself directly. If you don't need to render you can call EndFrame() but you'll have wasted CPU already. If you don't need to render, don't create any windows instead! + IMGUI_API void NewFrameUpdateHoveredWindowAndCaptureFlags(); + + IMGUI_API void MarkIniSettingsDirty(); + IMGUI_API ImGuiSettingsHandler* FindSettingsHandler(const char* type_name); + IMGUI_API ImGuiWindowSettings* FindWindowSettings(ImGuiID id); IMGUI_API void SetActiveID(ImGuiID id, ImGuiWindow* window); + IMGUI_API ImGuiID GetActiveID(); + IMGUI_API void SetFocusID(ImGuiID id, ImGuiWindow* window); + IMGUI_API void ClearActiveID(); IMGUI_API void SetHoveredID(ImGuiID id); + IMGUI_API ImGuiID GetHoveredID(); IMGUI_API void KeepAliveID(ImGuiID id); IMGUI_API void ItemSize(const ImVec2& size, float text_offset_y = 0.0f); IMGUI_API void ItemSize(const ImRect& bb, float text_offset_y = 0.0f); - IMGUI_API bool ItemAdd(const ImRect& bb, const ImGuiID* id); - IMGUI_API bool IsClippedEx(const ImRect& bb, const ImGuiID* id, bool clip_even_when_logged); - IMGUI_API bool IsHovered(const ImRect& bb, ImGuiID id, bool flatten_childs = false); - IMGUI_API bool FocusableItemRegister(ImGuiWindow* window, bool is_active, bool tab_stop = true); // Return true if focus is requested + IMGUI_API bool ItemAdd(const ImRect& bb, ImGuiID id, const ImRect* nav_bb = NULL); + IMGUI_API bool ItemHoverable(const ImRect& bb, ImGuiID id); + IMGUI_API bool IsClippedEx(const ImRect& bb, ImGuiID id, bool clip_even_when_logged); + IMGUI_API bool FocusableItemRegister(ImGuiWindow* window, ImGuiID id, bool tab_stop = true); // Return true if focus is requested IMGUI_API void FocusableItemUnregister(ImGuiWindow* window); IMGUI_API ImVec2 CalcItemSize(ImVec2 size, float default_x, float default_y); IMGUI_API float CalcWrapWidthForPos(const ImVec2& pos, float wrap_pos_x); - - IMGUI_API void OpenPopupEx(const char* str_id, bool reopen_existing); - - // NB: All position are in absolute pixels coordinates (not window coordinates) - // FIXME: All those functions are a mess and needs to be refactored into something decent. AVOID USING OUTSIDE OF IMGUI.CPP! NOT FOR PUBLIC CONSUMPTION. - // We need: a sort of symbol library, preferably baked into font atlas when possible + decent text rendering helpers. + IMGUI_API void PushMultiItemsWidths(int components, float width_full = 0.0f); + IMGUI_API void PushItemFlag(ImGuiItemFlags option, bool enabled); + IMGUI_API void PopItemFlag(); + + IMGUI_API void SetCurrentFont(ImFont* font); + + IMGUI_API void OpenPopupEx(ImGuiID id); + IMGUI_API void ClosePopup(ImGuiID id); + IMGUI_API void ClosePopupsOverWindow(ImGuiWindow* ref_window); + IMGUI_API bool IsPopupOpen(ImGuiID id); + IMGUI_API bool BeginPopupEx(ImGuiID id, ImGuiWindowFlags extra_flags); + IMGUI_API void BeginTooltipEx(ImGuiWindowFlags extra_flags, bool override_previous_tooltip = true); + + IMGUI_API void NavInitWindow(ImGuiWindow* window, bool force_reinit); + IMGUI_API void NavMoveRequestCancel(); + IMGUI_API void ActivateItem(ImGuiID id); // Remotely activate a button, checkbox, tree node etc. given its unique ID. activation is queued and processed on the next frame when the item is encountered again. + + IMGUI_API float GetNavInputAmount(ImGuiNavInput n, ImGuiInputReadMode mode); + IMGUI_API ImVec2 GetNavInputAmount2d(ImGuiNavDirSourceFlags dir_sources, ImGuiInputReadMode mode, float slow_factor = 0.0f, float fast_factor = 0.0f); + IMGUI_API int CalcTypematicPressedRepeatAmount(float t, float t_prev, float repeat_delay, float repeat_rate); + + IMGUI_API void Scrollbar(ImGuiLayoutType direction); + IMGUI_API void VerticalSeparator(); // Vertical separator, for menu bars (use current line height). not exposed because it is misleading what it doesn't have an effect on regular layout. + IMGUI_API bool SplitterBehavior(ImGuiID id, const ImRect& bb, ImGuiAxis axis, float* size1, float* size2, float min_size1, float min_size2, float hover_extend = 0.0f); + + IMGUI_API bool BeginDragDropTargetCustom(const ImRect& bb, ImGuiID id); + IMGUI_API void ClearDragDrop(); + IMGUI_API bool IsDragDropPayloadBeingAccepted(); + + // FIXME-WIP: New Columns API + IMGUI_API void BeginColumns(const char* str_id, int count, ImGuiColumnsFlags flags = 0); // setup number of columns. use an identifier to distinguish multiple column sets. close with EndColumns(). + IMGUI_API void EndColumns(); // close columns + IMGUI_API void PushColumnClipRect(int column_index = -1); + + // NB: All position are in absolute pixels coordinates (never using window coordinates internally) + // AVOID USING OUTSIDE OF IMGUI.CPP! NOT FOR PUBLIC CONSUMPTION. THOSE FUNCTIONS ARE A MESS. THEIR SIGNATURE AND BEHAVIOR WILL CHANGE, THEY NEED TO BE REFACTORED INTO SOMETHING DECENT. IMGUI_API void RenderText(ImVec2 pos, const char* text, const char* text_end = NULL, bool hide_text_after_hash = true); IMGUI_API void RenderTextWrapped(ImVec2 pos, const char* text, const char* text_end, float wrap_width); IMGUI_API void RenderTextClipped(const ImVec2& pos_min, const ImVec2& pos_max, const char* text, const char* text_end, const ImVec2* text_size_if_known, const ImVec2& align = ImVec2(0,0), const ImRect* clip_rect = NULL); IMGUI_API void RenderFrame(ImVec2 p_min, ImVec2 p_max, ImU32 fill_col, bool border = true, float rounding = 0.0f); - IMGUI_API void RenderCollapseTriangle(ImVec2 pos, bool is_open, float scale = 1.0f, bool shadow = false); + IMGUI_API void RenderFrameBorder(ImVec2 p_min, ImVec2 p_max, float rounding = 0.0f); + IMGUI_API void RenderColorRectWithAlphaCheckerboard(ImVec2 p_min, ImVec2 p_max, ImU32 fill_col, float grid_step, ImVec2 grid_off, float rounding = 0.0f, int rounding_corners_flags = ~0); + IMGUI_API void RenderArrow(ImVec2 pos, ImGuiDir dir, float scale = 1.0f); IMGUI_API void RenderBullet(ImVec2 pos); - IMGUI_API void RenderCheckMark(ImVec2 pos, ImU32 col); + IMGUI_API void RenderCheckMark(ImVec2 pos, ImU32 col, float sz); + IMGUI_API void RenderNavHighlight(const ImRect& bb, ImGuiID id, ImGuiNavHighlightFlags flags = ImGuiNavHighlightFlags_TypeDefault); // Navigation highlight + IMGUI_API void RenderRectFilledRangeH(ImDrawList* draw_list, const ImRect& rect, ImU32 col, float x_start_norm, float x_end_norm, float rounding); IMGUI_API const char* FindRenderedTextEnd(const char* text, const char* text_end = NULL); // Find the optional ## from which we stop displaying text. IMGUI_API bool ButtonBehavior(const ImRect& bb, ImGuiID id, bool* out_hovered, bool* out_held, ImGuiButtonFlags flags = 0); @@ -740,6 +1107,9 @@ namespace ImGui IMGUI_API bool InputScalarEx(const char* label, ImGuiDataType data_type, void* data_ptr, void* step_ptr, void* step_fast_ptr, const char* scalar_format, ImGuiInputTextFlags extra_flags); IMGUI_API bool InputScalarAsWidgetReplacement(const ImRect& aabb, const char* label, ImGuiDataType data_type, void* data_ptr, ImGuiID id, int decimal_precision); + IMGUI_API void ColorTooltip(const char* text, const float* col, ImGuiColorEditFlags flags); + IMGUI_API void ColorEditOptionsPopup(const float* col, ImGuiColorEditFlags flags); + IMGUI_API bool TreeNodeBehavior(ImGuiID id, ImGuiTreeNodeFlags flags, const char* label, const char* label_end = NULL); IMGUI_API bool TreeNodeBehaviorIsOpen(ImGuiID id, ImGuiTreeNodeFlags flags = 0); // Consume previous SetNextTreeNodeOpened() data, if any. May return true when logging IMGUI_API void TreePushRawID(ImGuiID id); @@ -749,8 +1119,22 @@ namespace ImGui IMGUI_API int ParseFormatPrecision(const char* fmt, int default_value); IMGUI_API float RoundScalar(float value, int decimal_precision); + // Shade functions (write over already created vertices) + IMGUI_API void ShadeVertsLinearColorGradientKeepAlpha(ImDrawVert* vert_start, ImDrawVert* vert_end, ImVec2 gradient_p0, ImVec2 gradient_p1, ImU32 col0, ImU32 col1); + IMGUI_API void ShadeVertsLinearAlphaGradientForLeftToRightText(ImDrawVert* vert_start, ImDrawVert* vert_end, float gradient_p0_x, float gradient_p1_x); + IMGUI_API void ShadeVertsLinearUV(ImDrawVert* vert_start, ImDrawVert* vert_end, const ImVec2& a, const ImVec2& b, const ImVec2& uv_a, const ImVec2& uv_b, bool clamp); + } // namespace ImGui +// ImFontAtlas internals +IMGUI_API bool ImFontAtlasBuildWithStbTruetype(ImFontAtlas* atlas); +IMGUI_API void ImFontAtlasBuildRegisterDefaultCustomRects(ImFontAtlas* atlas); +IMGUI_API void ImFontAtlasBuildSetupFont(ImFontAtlas* atlas, ImFont* font, ImFontConfig* font_config, float ascent, float descent); +IMGUI_API void ImFontAtlasBuildPackCustomRects(ImFontAtlas* atlas, void* spc); +IMGUI_API void ImFontAtlasBuildFinish(ImFontAtlas* atlas); +IMGUI_API void ImFontAtlasBuildMultiplyCalcLookupTable(unsigned char out_table[256], float in_multiply_factor); +IMGUI_API void ImFontAtlasBuildMultiplyRectAlpha8(const unsigned char table[256], unsigned char* pixels, int x, int y, int w, int h, int stride); + #ifdef __clang__ #pragma clang diagnostic pop #endif diff --git a/include/lqr.h b/include/lqr.h new file mode 100644 index 0000000..41a1505 --- /dev/null +++ b/include/lqr.h @@ -0,0 +1,120 @@ +/* + * lqr.h + * + * Linear quadratic regulation related functions + * + * Original implementation in pbdlib, by Danilo Bruno and Sylvain Calinon + * + * Authors: Danilo Bruno, Sylvain Calinon, Philip Abbet + */ + +#pragma once + +#include <armadillo> + + +namespace lqr { + + arma::mat solve_algebraic_Riccati(const arma::mat& A, const arma::mat& B, + const arma::mat& Q, const arma::mat& R) + { + const int n = A.n_rows; + + arma::mat G = B * R.i() * B.t(); + + arma::mat Z(2 * n, 2 * n); + Z(arma::span(0, n - 1), arma::span(0, n - 1)) = A; + Z(arma::span(n, 2 * n - 1), arma::span(0, n - 1)) = -Q; + Z(arma::span(0, n - 1), arma::span(n, 2 * n - 1)) = -G; + Z(arma::span(n, 2 * n - 1), arma::span(n, 2 * n - 1)) = -A.t(); + + //Using diagonalization + arma::cx_mat U(2 * n, n); + arma::cx_vec dd(2 * n); + arma::cx_mat V(2 * n, 2 * n); + + arma::eig_gen(dd, V, Z); + int i = 0; + for (int j = 0; j < 2 * n; ++j) { + if (real(dd(j)) < 0) { + U.col(i) = V.col(j); + ++i; + } + } + + arma::mat S1 = arma::zeros(n, n); + arma::cx_mat Sc = U(arma::span(0, n - 1), arma::span(0, n - 1)).t().i() * + U(arma::span(n, 2 * n - 1), arma::span(0, n - 1)).t(); + + return arma::real(Sc); + }; + + + //----------------------------------------------------- + + + arma::mat solve_algebraic_Riccati_discrete(const arma::mat& A, const arma::mat& B, + const arma::mat& Qx, const arma::mat& R) + { + // Ajay Tanwani, 2016 + + int n = A.n_rows; + + arma::mat Q = (Qx + Qx.t()) / 2; // mat Q here corresponds to (Q+Q')/2 specified + // in set_problem + arma::mat G = B * R.i() * B.t(); + arma::mat Z(2 * n , 2 * n); + Z(arma::span(0, n - 1), arma::span(0, n - 1)) = A + G * arma::inv(A.t()) * Q; + Z(arma::span(0, n - 1), arma::span(n, 2 * n - 1)) = -G * arma::inv(A.t()); + Z(arma::span(n, 2 * n - 1), arma::span(0, n - 1)) = -arma::inv(A.t()) * Q; + Z(arma::span(n, 2 * n - 1), arma::span(n, 2 * n - 1)) = arma::inv(A.t()); + + // Using diagonalization + arma::cx_mat V(2 * n, 2 * n), U(2 * n, n); + arma::cx_vec dd(2 * n); + + arma::eig_gen(dd, V, Z); + + int i = 0; + for (int j = 0; j < 2 * n; j++) { + if (norm(dd(j)) < 1) { + U.col(i) = V.col(j); + i++; + } + } + + return arma::real(U(arma::span(n, 2 * n - 1), arma::span(0, n - 1)) * + U(arma::span(0, n - 1), arma::span(0, n - 1)).i()); + }; + + + //----------------------------------------------------- + + + std::vector<arma::mat> evaluate_gains_infinite_horizon(const arma::mat& A, + const arma::mat& B, + const arma::mat& R, + const std::vector<arma::mat>& Q, + const arma::mat& Target) + { + const int nb_data = Q.size(); + const int nb_var = A.n_rows; + const int nb_ctrl = B.n_cols; + + std::vector<arma::mat> S; // Riccati solution + std::vector<arma::mat> L; // LQR Gains + + for (int i = 0; i < nb_data; ++i) { + S.push_back(arma::zeros(nb_var, nb_var)); + L.push_back(arma::zeros(nb_ctrl, nb_var)); + } + + arma::mat invR = R.i(); + for (int t = 0; t < nb_data; ++t) { + S[t] = solve_algebraic_Riccati(A, B, Q[t], R); + L[t] = invR * B.t() * S[t]; + } + + return L; + }; +} diff --git a/include/mvn.h b/include/mvn.h new file mode 100644 index 0000000..ab67254 --- /dev/null +++ b/include/mvn.h @@ -0,0 +1,38 @@ +/* + * mvn.h + * + * Multivariate gaussian distribution related functions + * + * Original implementation in pbdlib, by Davide De Tommaso and Milad Malekzadeh + * + * Authors: Davide De Tommaso, Milad Malekzadeh, Philip Abbet + */ + +#pragma once + +#include <armadillo> + + +namespace mvn { + + arma::colvec getPDFValue(const arma::colvec& mu, const arma::mat& sigma, + const arma::mat& samples) + { + arma::colvec probs(samples.n_cols); + + arma::mat lambda = sigma.i(); + + // Calculate difference (x - mu) + arma::mat diff = arma::trans(samples) - arma::repmat(arma::trans(mu), samples.n_cols, 1); + + // Calculate exponential (x - mu)^T * inv(sigma) * (x - mu) + probs = arma::sum((diff * lambda) % diff, 1); + + // Calculate exponential + probs = sqrt(fabs(arma::det(lambda)) / pow(2 * arma::datum::pi, lambda.n_cols)) * + exp(-0.5 * arma::abs(probs)); + + return probs; + } + +} diff --git a/include/stb_rect_pack.h b/include/stb_rect_pack.h index fafd889..2b07dcc 100644 --- a/include/stb_rect_pack.h +++ b/include/stb_rect_pack.h @@ -1,4 +1,4 @@ -// stb_rect_pack.h - v0.08 - public domain - rectangle packing +// stb_rect_pack.h - v0.11 - public domain - rectangle packing // Sean Barrett 2014 // // Useful for e.g. packing rectangular textures into an atlas. @@ -27,11 +27,16 @@ // Sean Barrett // Minor features // Martins Mozeiko +// github:IntellectualKitty +// // Bugfixes / warning fixes // Jeremy Jaussaud // // Version history: // +// 0.11 (2017-03-03) return packing success/fail result +// 0.10 (2016-10-25) remove cast-away-const to avoid warnings +// 0.09 (2016-08-27) fix compiler warnings // 0.08 (2015-09-13) really fix bug with empty rects (w=0 or h=0) // 0.07 (2015-09-13) fix bug with empty rects (w=0 or h=0) // 0.06 (2015-04-15) added STBRP_SORT to allow replacing qsort @@ -41,9 +46,7 @@ // // LICENSE // -// This software is in the public domain. Where that dedication is not -// recognized, you are granted a perpetual, irrevocable license to copy, -// distribute, and modify this file as you see fit. +// See end of file for license information. ////////////////////////////////////////////////////////////////////////////// // @@ -75,7 +78,7 @@ typedef int stbrp_coord; typedef unsigned short stbrp_coord; #endif -STBRP_DEF void stbrp_pack_rects (stbrp_context *context, stbrp_rect *rects, int num_rects); +STBRP_DEF int stbrp_pack_rects (stbrp_context *context, stbrp_rect *rects, int num_rects); // Assign packed locations to rectangles. The rectangles are of type // 'stbrp_rect' defined below, stored in the array 'rects', and there // are 'num_rects' many of them. @@ -96,6 +99,9 @@ STBRP_DEF void stbrp_pack_rects (stbrp_context *context, stbrp_rect *rects, int // arrays will probably produce worse packing results than calling it // a single time with the full rectangle array, but the option is // available. +// +// The function returns 1 if all of the rectangles were successfully +// packed and 0 otherwise. struct stbrp_rect { @@ -198,6 +204,14 @@ struct stbrp_context #define STBRP_ASSERT assert #endif +#ifdef _MSC_VER +#define STBRP__NOTUSED(v) (void)(v) +#define STBRP__CDECL __cdecl +#else +#define STBRP__NOTUSED(v) (void)sizeof(v) +#define STBRP__CDECL +#endif + enum { STBRP__INIT_skyline = 1 @@ -268,12 +282,14 @@ STBRP_DEF void stbrp_init_target(stbrp_context *context, int width, int height, } // find minimum y position if it starts at x1 -static int stbrp__skyline_find_min_y(stbrp_context *, stbrp_node *first, int x0, int width, int *pwaste) +static int stbrp__skyline_find_min_y(stbrp_context *c, stbrp_node *first, int x0, int width, int *pwaste) { - //(void)c; stbrp_node *node = first; int x1 = x0 + width; int min_y, visited_width, waste_area; + + STBRP__NOTUSED(c); + STBRP_ASSERT(first->x <= x0); #if 0 @@ -478,17 +494,14 @@ static stbrp__findresult stbrp__skyline_pack_rectangle(stbrp_context *context, i STBRP_ASSERT(cur->next == NULL); { - stbrp_node *L1 = NULL, *L2 = NULL; int count=0; cur = context->active_head; while (cur) { - L1 = cur; cur = cur->next; ++count; } cur = context->free_head; while (cur) { - L2 = cur; cur = cur->next; ++count; } @@ -499,10 +512,10 @@ static stbrp__findresult stbrp__skyline_pack_rectangle(stbrp_context *context, i return res; } -static int rect_height_compare(const void *a, const void *b) +static int STBRP__CDECL rect_height_compare(const void *a, const void *b) { - stbrp_rect *p = (stbrp_rect *) a; - stbrp_rect *q = (stbrp_rect *) b; + const stbrp_rect *p = (const stbrp_rect *) a; + const stbrp_rect *q = (const stbrp_rect *) b; if (p->h > q->h) return -1; if (p->h < q->h) @@ -510,21 +523,10 @@ static int rect_height_compare(const void *a, const void *b) return (p->w > q->w) ? -1 : (p->w < q->w); } -static int rect_width_compare(const void *a, const void *b) -{ - stbrp_rect *p = (stbrp_rect *) a; - stbrp_rect *q = (stbrp_rect *) b; - if (p->w > q->w) - return -1; - if (p->w < q->w) - return 1; - return (p->h > q->h) ? -1 : (p->h < q->h); -} - -static int rect_original_order(const void *a, const void *b) +static int STBRP__CDECL rect_original_order(const void *a, const void *b) { - stbrp_rect *p = (stbrp_rect *) a; - stbrp_rect *q = (stbrp_rect *) b; + const stbrp_rect *p = (const stbrp_rect *) a; + const stbrp_rect *q = (const stbrp_rect *) b; return (p->was_packed < q->was_packed) ? -1 : (p->was_packed > q->was_packed); } @@ -534,9 +536,9 @@ static int rect_original_order(const void *a, const void *b) #define STBRP__MAXVAL 0xffff #endif -STBRP_DEF void stbrp_pack_rects(stbrp_context *context, stbrp_rect *rects, int num_rects) +STBRP_DEF int stbrp_pack_rects(stbrp_context *context, stbrp_rect *rects, int num_rects) { - int i; + int i, all_rects_packed = 1; // we use the 'was_packed' field internally to allow sorting/unsorting for (i=0; i < num_rects; ++i) { @@ -566,8 +568,56 @@ STBRP_DEF void stbrp_pack_rects(stbrp_context *context, stbrp_rect *rects, int n // unsort STBRP_SORT(rects, num_rects, sizeof(rects[0]), rect_original_order); - // set was_packed flags - for (i=0; i < num_rects; ++i) + // set was_packed flags and all_rects_packed status + for (i=0; i < num_rects; ++i) { rects[i].was_packed = !(rects[i].x == STBRP__MAXVAL && rects[i].y == STBRP__MAXVAL); + if (!rects[i].was_packed) + all_rects_packed = 0; + } + + // return the all_rects_packed status + return all_rects_packed; } #endif + +/* +------------------------------------------------------------------------------ +This software is available under 2 licenses -- choose whichever you prefer. +------------------------------------------------------------------------------ +ALTERNATIVE A - MIT License +Copyright (c) 2017 Sean Barrett +Permission is hereby granted, free of charge, to any person obtaining a copy of +this software and associated documentation files (the "Software"), to deal in +the Software without restriction, including without limitation the rights to +use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies +of the Software, and to permit persons to whom the Software is furnished to do +so, subject to the following conditions: +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +------------------------------------------------------------------------------ +ALTERNATIVE B - Public Domain (www.unlicense.org) +This is free and unencumbered software released into the public domain. +Anyone is free to copy, modify, publish, use, compile, sell, or distribute this +software, either in source code form or as a compiled binary, for any purpose, +commercial or non-commercial, and by any means. +In jurisdictions that recognize copyright laws, the author or authors of this +software dedicate any and all copyright interest in the software to the public +domain. We make this dedication for the benefit of the public at large and to +the detriment of our heirs and successors. We intend this dedication to be an +overt act of relinquishment in perpetuity of all present and future rights to +this software under copyright law. +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN +ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION +WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +------------------------------------------------------------------------------ +*/ diff --git a/include/stb_textedit.h b/include/stb_textedit.h index 2dddefe..7324fb6 100644 --- a/include/stb_textedit.h +++ b/include/stb_textedit.h @@ -1,10 +1,10 @@ -// [ImGui] this is a slightly modified version of stb_truetype.h 1.8 +// [ImGui] this is a slightly modified version of stb_truetype.h 1.9. Those changes would need to be pushed into nothings/sb +// [ImGui] - fixed linestart handler when over last character of multi-line buffer + simplified existing code (#588, #815) // [ImGui] - fixed a state corruption/crash bug in stb_text_redo and stb_textedit_discard_redo (#715) // [ImGui] - fixed a crash bug in stb_textedit_discard_redo (#681) // [ImGui] - fixed some minor warnings -// [ImGui] - added STB_TEXTEDIT_MOVEWORDLEFT/STB_TEXTEDIT_MOVEWORDRIGHT custom handler (#473) -// stb_textedit.h - v1.8 - public domain - Sean Barrett +// stb_textedit.h - v1.9 - public domain - Sean Barrett // Development of this library was sponsored by RAD Game Tools // // This C header file implements the guts of a multi-line text-editing @@ -37,6 +37,7 @@ // // VERSION HISTORY // +// 1.9 (2016-08-27) customizable move-by-word // 1.8 (2016-04-02) better keyboard handling when mouse button is down // 1.7 (2015-09-13) change y range handling in case baseline is non-0 // 1.6 (2015-04-15) allow STB_TEXTEDIT_memmove @@ -425,10 +426,9 @@ static int stb_text_locate_coord(STB_TEXTEDIT_STRING *str, float x, float y) // check if it's before the end of the line if (x < r.x1) { // search characters in row for one that straddles 'x' - k = i; prev_x = r.x0; - for (i=0; i < r.num_chars; ++i) { - float w = STB_TEXTEDIT_GETWIDTH(str, k, i); + for (k=0; k < r.num_chars; ++k) { + float w = STB_TEXTEDIT_GETWIDTH(str, i, k); if (x < prev_x+w) { if (x < prev_x+w/2) return k+i; @@ -618,15 +618,16 @@ static void stb_textedit_move_to_last(STB_TEXTEDIT_STRING *str, STB_TexteditStat } #ifdef STB_TEXTEDIT_IS_SPACE -static int is_word_boundary( STB_TEXTEDIT_STRING *_str, int _idx ) +static int is_word_boundary( STB_TEXTEDIT_STRING *str, int idx ) { - return _idx > 0 ? (STB_TEXTEDIT_IS_SPACE( STB_TEXTEDIT_GETCHAR(_str,_idx-1) ) && !STB_TEXTEDIT_IS_SPACE( STB_TEXTEDIT_GETCHAR(_str, _idx) ) ) : 1; + return idx > 0 ? (STB_TEXTEDIT_IS_SPACE( STB_TEXTEDIT_GETCHAR(str,idx-1) ) && !STB_TEXTEDIT_IS_SPACE( STB_TEXTEDIT_GETCHAR(str, idx) ) ) : 1; } #ifndef STB_TEXTEDIT_MOVEWORDLEFT -static int stb_textedit_move_to_word_previous( STB_TEXTEDIT_STRING *_str, int c ) +static int stb_textedit_move_to_word_previous( STB_TEXTEDIT_STRING *str, int c ) { - while( c >= 0 && !is_word_boundary( _str, c ) ) + --c; // always move at least one character + while( c >= 0 && !is_word_boundary( str, c ) ) --c; if( c < 0 ) @@ -638,10 +639,11 @@ static int stb_textedit_move_to_word_previous( STB_TEXTEDIT_STRING *_str, int c #endif #ifndef STB_TEXTEDIT_MOVEWORDRIGHT -static int stb_textedit_move_to_word_next( STB_TEXTEDIT_STRING *_str, int c ) +static int stb_textedit_move_to_word_next( STB_TEXTEDIT_STRING *str, int c ) { - const int len = STB_TEXTEDIT_STRINGLEN(_str); - while( c < len && !is_word_boundary( _str, c ) ) + const int len = STB_TEXTEDIT_STRINGLEN(str); + ++c; // always move at least one character + while( c < len && !is_word_boundary( str, c ) ) ++c; if( c > len ) @@ -675,9 +677,8 @@ static int stb_textedit_cut(STB_TEXTEDIT_STRING *str, STB_TexteditState *state) } // API paste: replace existing selection with passed-in text -static int stb_textedit_paste(STB_TEXTEDIT_STRING *str, STB_TexteditState *state, STB_TEXTEDIT_CHARTYPE const *ctext, int len) +static int stb_textedit_paste(STB_TEXTEDIT_STRING *str, STB_TexteditState *state, STB_TEXTEDIT_CHARTYPE const *text, int len) { - STB_TEXTEDIT_CHARTYPE *text = (STB_TEXTEDIT_CHARTYPE *) ctext; // if there's a selection, the paste should delete it stb_textedit_clamp(str, state); stb_textedit_delete_selection(str,state); @@ -778,7 +779,7 @@ retry: if (STB_TEXT_HAS_SELECTION(state)) stb_textedit_move_to_first(state); else { - state->cursor = STB_TEXTEDIT_MOVEWORDLEFT(str, state->cursor-1); + state->cursor = STB_TEXTEDIT_MOVEWORDLEFT(str, state->cursor); stb_textedit_clamp( str, state ); } break; @@ -787,7 +788,7 @@ retry: if( !STB_TEXT_HAS_SELECTION( state ) ) stb_textedit_prep_selection_at_cursor(state); - state->cursor = STB_TEXTEDIT_MOVEWORDLEFT(str, state->cursor-1); + state->cursor = STB_TEXTEDIT_MOVEWORDLEFT(str, state->cursor); state->select_end = state->cursor; stb_textedit_clamp( str, state ); @@ -799,7 +800,7 @@ retry: if (STB_TEXT_HAS_SELECTION(state)) stb_textedit_move_to_last(str, state); else { - state->cursor = STB_TEXTEDIT_MOVEWORDRIGHT(str, state->cursor+1); + state->cursor = STB_TEXTEDIT_MOVEWORDRIGHT(str, state->cursor); stb_textedit_clamp( str, state ); } break; @@ -808,7 +809,7 @@ retry: if( !STB_TEXT_HAS_SELECTION( state ) ) stb_textedit_prep_selection_at_cursor(state); - state->cursor = STB_TEXTEDIT_MOVEWORDRIGHT(str, state->cursor+1); + state->cursor = STB_TEXTEDIT_MOVEWORDRIGHT(str, state->cursor); state->select_end = state->cursor; stb_textedit_clamp( str, state ); @@ -991,58 +992,58 @@ retry: #ifdef STB_TEXTEDIT_K_LINESTART2 case STB_TEXTEDIT_K_LINESTART2: #endif - case STB_TEXTEDIT_K_LINESTART: { - StbFindState find; + case STB_TEXTEDIT_K_LINESTART: stb_textedit_clamp(str, state); stb_textedit_move_to_first(state); - stb_textedit_find_charpos(&find, str, state->cursor, state->single_line); - state->cursor = find.first_char; + if (state->single_line) + state->cursor = 0; + else while (state->cursor > 0 && STB_TEXTEDIT_GETCHAR(str, state->cursor-1) != STB_TEXTEDIT_NEWLINE) + --state->cursor; state->has_preferred_x = 0; break; - } #ifdef STB_TEXTEDIT_K_LINEEND2 case STB_TEXTEDIT_K_LINEEND2: #endif case STB_TEXTEDIT_K_LINEEND: { - StbFindState find; + int n = STB_TEXTEDIT_STRINGLEN(str); stb_textedit_clamp(str, state); stb_textedit_move_to_first(state); - stb_textedit_find_charpos(&find, str, state->cursor, state->single_line); - + if (state->single_line) + state->cursor = n; + else while (state->cursor < n && STB_TEXTEDIT_GETCHAR(str, state->cursor) != STB_TEXTEDIT_NEWLINE) + ++state->cursor; state->has_preferred_x = 0; - state->cursor = find.first_char + find.length; - if (find.length > 0 && STB_TEXTEDIT_GETCHAR(str, state->cursor-1) == STB_TEXTEDIT_NEWLINE) - --state->cursor; break; } #ifdef STB_TEXTEDIT_K_LINESTART2 case STB_TEXTEDIT_K_LINESTART2 | STB_TEXTEDIT_K_SHIFT: #endif - case STB_TEXTEDIT_K_LINESTART | STB_TEXTEDIT_K_SHIFT: { - StbFindState find; + case STB_TEXTEDIT_K_LINESTART | STB_TEXTEDIT_K_SHIFT: stb_textedit_clamp(str, state); stb_textedit_prep_selection_at_cursor(state); - stb_textedit_find_charpos(&find, str, state->cursor, state->single_line); - state->cursor = state->select_end = find.first_char; + if (state->single_line) + state->cursor = 0; + else while (state->cursor > 0 && STB_TEXTEDIT_GETCHAR(str, state->cursor-1) != STB_TEXTEDIT_NEWLINE) + --state->cursor; + state->select_end = state->cursor; state->has_preferred_x = 0; break; - } #ifdef STB_TEXTEDIT_K_LINEEND2 case STB_TEXTEDIT_K_LINEEND2 | STB_TEXTEDIT_K_SHIFT: #endif case STB_TEXTEDIT_K_LINEEND | STB_TEXTEDIT_K_SHIFT: { - StbFindState find; + int n = STB_TEXTEDIT_STRINGLEN(str); stb_textedit_clamp(str, state); stb_textedit_prep_selection_at_cursor(state); - stb_textedit_find_charpos(&find, str, state->cursor, state->single_line); - state->has_preferred_x = 0; - state->cursor = find.first_char + find.length; - if (find.length > 0 && STB_TEXTEDIT_GETCHAR(str, state->cursor-1) == STB_TEXTEDIT_NEWLINE) - --state->cursor; + if (state->single_line) + state->cursor = n; + else while (state->cursor < n && STB_TEXTEDIT_GETCHAR(str, state->cursor) != STB_TEXTEDIT_NEWLINE) + ++state->cursor; state->select_end = state->cursor; + state->has_preferred_x = 0; break; } diff --git a/include/stb_truetype.h b/include/stb_truetype.h index e6dae97..f65deb5 100644 --- a/include/stb_truetype.h +++ b/include/stb_truetype.h @@ -1,11 +1,12 @@ -// stb_truetype.h - v1.10 - public domain -// authored from 2009-2015 by Sean Barrett / RAD Game Tools +// stb_truetype.h - v1.19 - public domain +// authored from 2009-2016 by Sean Barrett / RAD Game Tools // // This library processes TrueType files: // parse files // extract glyph metrics // extract glyph shapes // render glyphs to one-channel bitmaps with antialiasing (box filter) +// render glyphs to one-channel SDF bitmaps (signed-distance field/function) // // Todo: // non-MS cmaps @@ -20,37 +21,43 @@ // // Mikko Mononen: compound shape support, more cmap formats // Tor Andersson: kerning, subpixel rendering +// Dougall Johnson: OpenType / Type 2 font handling +// Daniel Ribeiro Maciel: basic GPOS-based kerning // // Misc other: // Ryan Gordon // Simon Glass +// github:IntellectualKitty +// Imanol Celaya +// Daniel Ribeiro Maciel // // Bug/warning reports/fixes: -// "Zer" on mollyrocket (with fix) -// Cass Everitt -// stoiko (Haemimont Games) -// Brian Hook -// Walter van Niftrik -// David Gow -// David Given -// Ivan-Assen Ivanov -// Anthony Pesch -// Johan Duparc -// Hou Qiming -// Fabian "ryg" Giesen -// Martins Mozeiko -// Cap Petschulat -// Omar Cornut -// github:aloucks -// Peter LaValle -// Sergey Popov -// Giumo X. Clanjor -// Higor Euripedes -// Thomas Fields -// Derek Vinyard -// +// "Zer" on mollyrocket Fabian "ryg" Giesen +// Cass Everitt Martins Mozeiko +// stoiko (Haemimont Games) Cap Petschulat +// Brian Hook Omar Cornut +// Walter van Niftrik github:aloucks +// David Gow Peter LaValle +// David Given Sergey Popov +// Ivan-Assen Ivanov Giumo X. Clanjor +// Anthony Pesch Higor Euripedes +// Johan Duparc Thomas Fields +// Hou Qiming Derek Vinyard +// Rob Loach Cort Stratton +// Kenney Phillis Jr. github:oyvindjam +// Brian Costabile github:vassvik +// // VERSION HISTORY // +// 1.19 (2018-02-11) GPOS kerning, STBTT_fmod +// 1.18 (2018-01-29) add missing function +// 1.17 (2017-07-23) make more arguments const; doc fix +// 1.16 (2017-07-12) SDF support +// 1.15 (2017-03-03) make more arguments const +// 1.14 (2017-01-16) num-fonts-in-TTC function +// 1.13 (2017-01-02) support OpenType fonts, certain Apple fonts +// 1.12 (2016-10-25) suppress warnings about casting away const with -Wcast-qual +// 1.11 (2016-04-02) fix unused-variable warning // 1.10 (2016-04-02) user-defined fabs(); rare memory leak; remove duplicate typedef // 1.09 (2016-01-16) warning fix; avoid crash on outofmem; use allocation userdata properly // 1.08 (2015-09-13) document stbtt_Rasterize(); fixes for vertical & horizontal edges @@ -59,20 +66,12 @@ // fix stbtt_GetFontOFfsetForIndex (never worked for non-0 input?); // fixed an assert() bug in the new rasterizer // replace assert() with STBTT_assert() in new rasterizer -// 1.06 (2015-07-14) performance improvements (~35% faster on x86 and x64 on test machine) -// also more precise AA rasterizer, except if shapes overlap -// remove need for STBTT_sort -// 1.05 (2015-04-15) fix misplaced definitions for STBTT_STATIC -// 1.04 (2015-04-15) typo in example -// 1.03 (2015-04-12) STBTT_STATIC, fix memory leak in new packing, various fixes // // Full history can be found at the end of this file. // // LICENSE // -// This software is dual-licensed to the public domain and under the following -// license: you are granted a perpetual, irrevocable license to copy, modify, -// publish, and distribute this file as you see fit. +// See end of file for license information. // // USAGE // @@ -92,14 +91,15 @@ // Improved 3D API (more shippable): // #include "stb_rect_pack.h" -- optional, but you really want it // stbtt_PackBegin() -// stbtt_PackSetOversample() -- for improved quality on small fonts +// stbtt_PackSetOversampling() -- for improved quality on small fonts // stbtt_PackFontRanges() -- pack and renders // stbtt_PackEnd() // stbtt_GetPackedQuad() // // "Load" a font file from a memory buffer (you have to keep the buffer loaded) // stbtt_InitFont() -// stbtt_GetFontOffsetForIndex() -- use for TTC font collections +// stbtt_GetFontOffsetForIndex() -- indexing for TTC font collections +// stbtt_GetNumberOfFonts() -- number of fonts for TTC font collections // // Render a unicode codepoint to a bitmap // stbtt_GetCodepointBitmap() -- allocates and returns a bitmap @@ -109,6 +109,7 @@ // Character advance/positioning // stbtt_GetCodepointHMetrics() // stbtt_GetFontVMetrics() +// stbtt_GetFontVMetricsOS2() // stbtt_GetCodepointKernAdvance() // // Starting with version 1.06, the rasterizer was replaced with a new, @@ -164,7 +165,7 @@ // measurement for describing font size, defined as 72 points per inch. // stb_truetype provides a point API for compatibility. However, true // "per inch" conventions don't make much sense on computer displays -// since they different monitors have different number of pixels per +// since different monitors have different number of pixels per // inch. For example, Windows traditionally uses a convention that // there are 96 pixels per inch, thus making 'inch' measurements have // nothing to do with inches, and thus effectively defining a point to @@ -174,6 +175,39 @@ // for non-commercial fonts, thus making fonts scaled in points // according to the TrueType spec incoherently sized in practice. // +// DETAILED USAGE: +// +// Scale: +// Select how high you want the font to be, in points or pixels. +// Call ScaleForPixelHeight or ScaleForMappingEmToPixels to compute +// a scale factor SF that will be used by all other functions. +// +// Baseline: +// You need to select a y-coordinate that is the baseline of where +// your text will appear. Call GetFontBoundingBox to get the baseline-relative +// bounding box for all characters. SF*-y0 will be the distance in pixels +// that the worst-case character could extend above the baseline, so if +// you want the top edge of characters to appear at the top of the +// screen where y=0, then you would set the baseline to SF*-y0. +// +// Current point: +// Set the current point where the first character will appear. The +// first character could extend left of the current point; this is font +// dependent. You can either choose a current point that is the leftmost +// point and hope, or add some padding, or check the bounding box or +// left-side-bearing of the first character to be displayed and set +// the current point based on that. +// +// Displaying a character: +// Compute the bounding box of the character. It will contain signed values +// relative to <current_point, baseline>. I.e. if it returns x0,y0,x1,y1, +// then the character should be displayed in the rectangle from +// <current_point+SF*x0, baseline+SF*y0> to <current_point+SF*x1,baseline+SF*y1). +// +// Advancing for the next character: +// Call GlyphHMetrics, and compute 'current_point += SF * advance'. +// +// // ADVANCED USAGE // // Quality: @@ -380,7 +414,8 @@ int main(int arg, char **argv) //// INTEGRATION WITH YOUR CODEBASE //// //// The following sections allow you to supply alternate definitions -//// of C library functions used by stb_truetype. +//// of C library functions used by stb_truetype, e.g. if you don't +//// link with the C runtime library. #ifdef STB_TRUETYPE_IMPLEMENTATION // #define your own (u)stbtt_int8/16/32 before including to override this @@ -396,7 +431,7 @@ int main(int arg, char **argv) typedef char stbtt__check_size32[sizeof(stbtt_int32)==4 ? 1 : -1]; typedef char stbtt__check_size16[sizeof(stbtt_int16)==2 ? 1 : -1]; - // #define your own STBTT_ifloor/STBTT_iceil() to avoid math.h + // e.g. #define your own STBTT_ifloor/STBTT_iceil() to avoid math.h #ifndef STBTT_ifloor #include <math.h> #define STBTT_ifloor(x) ((int) floor(x)) @@ -406,6 +441,18 @@ int main(int arg, char **argv) #ifndef STBTT_sqrt #include <math.h> #define STBTT_sqrt(x) sqrt(x) + #define STBTT_pow(x,y) pow(x,y) + #endif + + #ifndef STBTT_fmod + #include <math.h> + #define STBTT_fmod(x,y) fmod(x,y) + #endif + + #ifndef STBTT_cos + #include <math.h> + #define STBTT_cos(x) cos(x) + #define STBTT_acos(x) acos(x) #endif #ifndef STBTT_fabs @@ -431,7 +478,7 @@ int main(int arg, char **argv) #endif #ifndef STBTT_memcpy - #include <memory.h> + #include <string.h> #define STBTT_memcpy memcpy #define STBTT_memset memset #endif @@ -457,6 +504,14 @@ int main(int arg, char **argv) extern "C" { #endif +// private structure +typedef struct +{ + unsigned char *data; + int cursor; + int size; +} stbtt__buf; + ////////////////////////////////////////////////////////////////////////////// // // TEXTURE BAKING API @@ -486,7 +541,7 @@ typedef struct float x1,y1,s1,t1; // bottom-right } stbtt_aligned_quad; -STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, // same data as above +STBTT_DEF void stbtt_GetBakedQuad(const stbtt_bakedchar *chardata, int pw, int ph, // same data as above int char_index, // character to display float *xpos, float *ypos, // pointers to current position in screen pixel space stbtt_aligned_quad *q, // output: quad to draw @@ -526,7 +581,7 @@ typedef struct stbrp_rect stbrp_rect; STBTT_DEF int stbtt_PackBegin(stbtt_pack_context *spc, unsigned char *pixels, int width, int height, int stride_in_bytes, int padding, void *alloc_context); // Initializes a packing context stored in the passed-in stbtt_pack_context. // Future calls using this context will pack characters into the bitmap passed -// in here: a 1-channel bitmap that is weight x height. stride_in_bytes is +// in here: a 1-channel bitmap that is width * height. stride_in_bytes is // the distance from one row to the next (or 0 to mean they are packed tightly // together). "padding" is the amount of padding to leave between each // character (normally you want '1' for bitmaps you'll use as textures with @@ -539,7 +594,7 @@ STBTT_DEF void stbtt_PackEnd (stbtt_pack_context *spc); #define STBTT_POINT_SIZE(x) (-(x)) -STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, float font_size, +STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, const unsigned char *fontdata, int font_index, float font_size, int first_unicode_char_in_range, int num_chars_in_range, stbtt_packedchar *chardata_for_range); // Creates character bitmaps from the font_index'th font found in fontdata (use // font_index=0 if you don't know what that is). It creates num_chars_in_range @@ -564,7 +619,7 @@ typedef struct unsigned char h_oversample, v_oversample; // don't set these, they're used internally } stbtt_pack_range; -STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges); +STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, const unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges); // Creates character bitmaps from multiple ranges of characters stored in // ranges. This will usually create a better-packed bitmap than multiple // calls to stbtt_PackFontRange. Note that you can call this multiple @@ -586,15 +641,15 @@ STBTT_DEF void stbtt_PackSetOversampling(stbtt_pack_context *spc, unsigned int h // To use with PackFontRangesGather etc., you must set it before calls // call to PackFontRangesGatherRects. -STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, // same data as above +STBTT_DEF void stbtt_GetPackedQuad(const stbtt_packedchar *chardata, int pw, int ph, // same data as above int char_index, // character to display float *xpos, float *ypos, // pointers to current position in screen pixel space stbtt_aligned_quad *q, // output: quad to draw int align_to_integer); -STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); +STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, const stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); STBTT_DEF void stbtt_PackFontRangesPackRects(stbtt_pack_context *spc, stbrp_rect *rects, int num_rects); -STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); +STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, const stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); // Calling these functions in sequence is roughly equivalent to calling // stbtt_PackFontRanges(). If you more control over the packing of multiple // fonts, or if you want to pack custom data into a font texture, take a look @@ -625,14 +680,19 @@ struct stbtt_pack_context { // // +STBTT_DEF int stbtt_GetNumberOfFonts(const unsigned char *data); +// This function will determine the number of fonts in a font file. TrueType +// collection (.ttc) files may contain multiple fonts, while TrueType font +// (.ttf) files only contain one font. The number of fonts can be used for +// indexing with the previous function where the index is between zero and one +// less than the total fonts. If an error occurs, -1 is returned. + STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *data, int index); // Each .ttf/.ttc file may have more than one font. Each font has a sequential // index number starting from 0. Call this function to get the font offset for // a given index; it returns -1 if the index is out of range. A regular .ttf // file will only define one font and it always be at offset 0, so it will -// return '0' for index 0, and -1 for all other indices. You can just skip -// this step if you know it's that kind of font. - +// return '0' for index 0, and -1 for all other indices. // The following structure is defined publically so you can declare one on // the stack or as a global or etc, but you should treat it as opaque. @@ -644,9 +704,16 @@ struct stbtt_fontinfo int numGlyphs; // number of glyphs, needed for range checking - int loca,head,glyf,hhea,hmtx,kern; // table locations as offset from start of .ttf + int loca,head,glyf,hhea,hmtx,kern,gpos; // table locations as offset from start of .ttf int index_map; // a cmap mapping for our chosen character encoding int indexToLocFormat; // format needed to map from glyph index to glyph + + stbtt__buf cff; // cff font data + stbtt__buf charstrings; // the charstring index + stbtt__buf gsubrs; // global charstring subroutines index + stbtt__buf subrs; // private charstring subroutines index + stbtt__buf fontdicts; // array of font dicts + stbtt__buf fdselect; // map from glyph to fontdict }; STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data, int offset); @@ -694,6 +761,12 @@ STBTT_DEF void stbtt_GetFontVMetrics(const stbtt_fontinfo *info, int *ascent, in // these are expressed in unscaled coordinates, so you must multiply by // the scale factor for a given size +STBTT_DEF int stbtt_GetFontVMetricsOS2(const stbtt_fontinfo *info, int *typoAscent, int *typoDescent, int *typoLineGap); +// analogous to GetFontVMetrics, but returns the "typographic" values from the OS/2 +// table (specific to MS/Windows TTF files). +// +// Returns 1 on success (table present), 0 on failure. + STBTT_DEF void stbtt_GetFontBoundingBox(const stbtt_fontinfo *info, int *x0, int *y0, int *x1, int *y1); // the bounding box around all possible characters @@ -724,7 +797,8 @@ STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, in enum { STBTT_vmove=1, STBTT_vline, - STBTT_vcurve + STBTT_vcurve, + STBTT_vcubic }; #endif @@ -733,7 +807,7 @@ STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, in #define stbtt_vertex_type short // can't use stbtt_int16 because that's not visible in the header file typedef struct { - stbtt_vertex_type x,y,cx,cy; + stbtt_vertex_type x,y,cx,cy,cx1,cy1; unsigned char type,padding; } stbtt_vertex; #endif @@ -787,6 +861,10 @@ STBTT_DEF void stbtt_MakeCodepointBitmapSubpixel(const stbtt_fontinfo *info, uns // same as stbtt_MakeCodepointBitmap, but you can specify a subpixel // shift for the character +STBTT_DEF void stbtt_MakeCodepointBitmapSubpixelPrefilter(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int oversample_x, int oversample_y, float *sub_x, float *sub_y, int codepoint); +// same as stbtt_MakeCodepointBitmapSubpixel, but prefiltering +// is performed (see stbtt_PackSetOversampling) + STBTT_DEF void stbtt_GetCodepointBitmapBox(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1); // get the bbox of the bitmap centered around the glyph origin; so the // bitmap width is ix1-ix0, height is iy1-iy0, and location to place @@ -804,6 +882,7 @@ STBTT_DEF unsigned char *stbtt_GetGlyphBitmap(const stbtt_fontinfo *info, float STBTT_DEF unsigned char *stbtt_GetGlyphBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int glyph, int *width, int *height, int *xoff, int *yoff); STBTT_DEF void stbtt_MakeGlyphBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int glyph); STBTT_DEF void stbtt_MakeGlyphBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int glyph); +STBTT_DEF void stbtt_MakeGlyphBitmapSubpixelPrefilter(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int oversample_x, int oversample_y, float *sub_x, float *sub_y, int glyph); STBTT_DEF void stbtt_GetGlyphBitmapBox(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1); STBTT_DEF void stbtt_GetGlyphBitmapBoxSubpixel(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y,float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1); @@ -826,6 +905,64 @@ STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, // 1-channel bitmap int invert, // if non-zero, vertically flip shape void *userdata); // context for to STBTT_MALLOC +////////////////////////////////////////////////////////////////////////////// +// +// Signed Distance Function (or Field) rendering + +STBTT_DEF void stbtt_FreeSDF(unsigned char *bitmap, void *userdata); +// frees the SDF bitmap allocated below + +STBTT_DEF unsigned char * stbtt_GetGlyphSDF(const stbtt_fontinfo *info, float scale, int glyph, int padding, unsigned char onedge_value, float pixel_dist_scale, int *width, int *height, int *xoff, int *yoff); +STBTT_DEF unsigned char * stbtt_GetCodepointSDF(const stbtt_fontinfo *info, float scale, int codepoint, int padding, unsigned char onedge_value, float pixel_dist_scale, int *width, int *height, int *xoff, int *yoff); +// These functions compute a discretized SDF field for a single character, suitable for storing +// in a single-channel texture, sampling with bilinear filtering, and testing against +// larger than some threshhold to produce scalable fonts. +// info -- the font +// scale -- controls the size of the resulting SDF bitmap, same as it would be creating a regular bitmap +// glyph/codepoint -- the character to generate the SDF for +// padding -- extra "pixels" around the character which are filled with the distance to the character (not 0), +// which allows effects like bit outlines +// onedge_value -- value 0-255 to test the SDF against to reconstruct the character (i.e. the isocontour of the character) +// pixel_dist_scale -- what value the SDF should increase by when moving one SDF "pixel" away from the edge (on the 0..255 scale) +// if positive, > onedge_value is inside; if negative, < onedge_value is inside +// width,height -- output height & width of the SDF bitmap (including padding) +// xoff,yoff -- output origin of the character +// return value -- a 2D array of bytes 0..255, width*height in size +// +// pixel_dist_scale & onedge_value are a scale & bias that allows you to make +// optimal use of the limited 0..255 for your application, trading off precision +// and special effects. SDF values outside the range 0..255 are clamped to 0..255. +// +// Example: +// scale = stbtt_ScaleForPixelHeight(22) +// padding = 5 +// onedge_value = 180 +// pixel_dist_scale = 180/5.0 = 36.0 +// +// This will create an SDF bitmap in which the character is about 22 pixels +// high but the whole bitmap is about 22+5+5=32 pixels high. To produce a filled +// shape, sample the SDF at each pixel and fill the pixel if the SDF value +// is greater than or equal to 180/255. (You'll actually want to antialias, +// which is beyond the scope of this example.) Additionally, you can compute +// offset outlines (e.g. to stroke the character border inside & outside, +// or only outside). For example, to fill outside the character up to 3 SDF +// pixels, you would compare against (180-36.0*3)/255 = 72/255. The above +// choice of variables maps a range from 5 pixels outside the shape to +// 2 pixels inside the shape to 0..255; this is intended primarily for apply +// outside effects only (the interior range is needed to allow proper +// antialiasing of the font at *smaller* sizes) +// +// The function computes the SDF analytically at each SDF pixel, not by e.g. +// building a higher-res bitmap and approximating it. In theory the quality +// should be as high as possible for an SDF of this size & representation, but +// unclear if this is true in practice (perhaps building a higher-res bitmap +// and computing from that can allow drop-out prevention). +// +// The algorithm has not been optimized at all, so expect it to be slow +// if computing lots of characters or very large sizes. + + + ////////////////////////////////////////////////////////////////////////////// // // Finding the right font... @@ -949,6 +1086,158 @@ typedef int stbtt__test_oversample_pow2[(STBTT_MAX_OVERSAMPLE & (STBTT_MAX_OVERS #define STBTT_RASTERIZER_VERSION 2 #endif +#ifdef _MSC_VER +#define STBTT__NOTUSED(v) (void)(v) +#else +#define STBTT__NOTUSED(v) (void)sizeof(v) +#endif + +////////////////////////////////////////////////////////////////////////// +// +// stbtt__buf helpers to parse data from file +// + +static stbtt_uint8 stbtt__buf_get8(stbtt__buf *b) +{ + if (b->cursor >= b->size) + return 0; + return b->data[b->cursor++]; +} + +static stbtt_uint8 stbtt__buf_peek8(stbtt__buf *b) +{ + if (b->cursor >= b->size) + return 0; + return b->data[b->cursor]; +} + +static void stbtt__buf_seek(stbtt__buf *b, int o) +{ + STBTT_assert(!(o > b->size || o < 0)); + b->cursor = (o > b->size || o < 0) ? b->size : o; +} + +static void stbtt__buf_skip(stbtt__buf *b, int o) +{ + stbtt__buf_seek(b, b->cursor + o); +} + +static stbtt_uint32 stbtt__buf_get(stbtt__buf *b, int n) +{ + stbtt_uint32 v = 0; + int i; + STBTT_assert(n >= 1 && n <= 4); + for (i = 0; i < n; i++) + v = (v << 8) | stbtt__buf_get8(b); + return v; +} + +static stbtt__buf stbtt__new_buf(const void *p, size_t size) +{ + stbtt__buf r; + STBTT_assert(size < 0x40000000); + r.data = (stbtt_uint8*) p; + r.size = (int) size; + r.cursor = 0; + return r; +} + +#define stbtt__buf_get16(b) stbtt__buf_get((b), 2) +#define stbtt__buf_get32(b) stbtt__buf_get((b), 4) + +static stbtt__buf stbtt__buf_range(const stbtt__buf *b, int o, int s) +{ + stbtt__buf r = stbtt__new_buf(NULL, 0); + if (o < 0 || s < 0 || o > b->size || s > b->size - o) return r; + r.data = b->data + o; + r.size = s; + return r; +} + +static stbtt__buf stbtt__cff_get_index(stbtt__buf *b) +{ + int count, start, offsize; + start = b->cursor; + count = stbtt__buf_get16(b); + if (count) { + offsize = stbtt__buf_get8(b); + STBTT_assert(offsize >= 1 && offsize <= 4); + stbtt__buf_skip(b, offsize * count); + stbtt__buf_skip(b, stbtt__buf_get(b, offsize) - 1); + } + return stbtt__buf_range(b, start, b->cursor - start); +} + +static stbtt_uint32 stbtt__cff_int(stbtt__buf *b) +{ + int b0 = stbtt__buf_get8(b); + if (b0 >= 32 && b0 <= 246) return b0 - 139; + else if (b0 >= 247 && b0 <= 250) return (b0 - 247)*256 + stbtt__buf_get8(b) + 108; + else if (b0 >= 251 && b0 <= 254) return -(b0 - 251)*256 - stbtt__buf_get8(b) - 108; + else if (b0 == 28) return stbtt__buf_get16(b); + else if (b0 == 29) return stbtt__buf_get32(b); + STBTT_assert(0); + return 0; +} + +static void stbtt__cff_skip_operand(stbtt__buf *b) { + int v, b0 = stbtt__buf_peek8(b); + STBTT_assert(b0 >= 28); + if (b0 == 30) { + stbtt__buf_skip(b, 1); + while (b->cursor < b->size) { + v = stbtt__buf_get8(b); + if ((v & 0xF) == 0xF || (v >> 4) == 0xF) + break; + } + } else { + stbtt__cff_int(b); + } +} + +static stbtt__buf stbtt__dict_get(stbtt__buf *b, int key) +{ + stbtt__buf_seek(b, 0); + while (b->cursor < b->size) { + int start = b->cursor, end, op; + while (stbtt__buf_peek8(b) >= 28) + stbtt__cff_skip_operand(b); + end = b->cursor; + op = stbtt__buf_get8(b); + if (op == 12) op = stbtt__buf_get8(b) | 0x100; + if (op == key) return stbtt__buf_range(b, start, end-start); + } + return stbtt__buf_range(b, 0, 0); +} + +static void stbtt__dict_get_ints(stbtt__buf *b, int key, int outcount, stbtt_uint32 *out) +{ + int i; + stbtt__buf operands = stbtt__dict_get(b, key); + for (i = 0; i < outcount && operands.cursor < operands.size; i++) + out[i] = stbtt__cff_int(&operands); +} + +static int stbtt__cff_index_count(stbtt__buf *b) +{ + stbtt__buf_seek(b, 0); + return stbtt__buf_get16(b); +} + +static stbtt__buf stbtt__cff_index_get(stbtt__buf b, int i) +{ + int count, offsize, start, end; + stbtt__buf_seek(&b, 0); + count = stbtt__buf_get16(&b); + offsize = stbtt__buf_get8(&b); + STBTT_assert(i >= 0 && i < count); + STBTT_assert(offsize >= 1 && offsize <= 4); + stbtt__buf_skip(&b, i*offsize); + start = stbtt__buf_get(&b, offsize); + end = stbtt__buf_get(&b, offsize); + return stbtt__buf_range(&b, 2+(count+1)*offsize+start, end - start); +} + ////////////////////////////////////////////////////////////////////////// // // accessors to parse data from file @@ -961,32 +1250,22 @@ typedef int stbtt__test_oversample_pow2[(STBTT_MAX_OVERSAMPLE & (STBTT_MAX_OVERS #define ttCHAR(p) (* (stbtt_int8 *) (p)) #define ttFixed(p) ttLONG(p) -#if defined(STB_TRUETYPE_BIGENDIAN) && !defined(ALLOW_UNALIGNED_TRUETYPE) - - #define ttUSHORT(p) (* (stbtt_uint16 *) (p)) - #define ttSHORT(p) (* (stbtt_int16 *) (p)) - #define ttULONG(p) (* (stbtt_uint32 *) (p)) - #define ttLONG(p) (* (stbtt_int32 *) (p)) - -#else - - static stbtt_uint16 ttUSHORT(const stbtt_uint8 *p) { return p[0]*256 + p[1]; } - static stbtt_int16 ttSHORT(const stbtt_uint8 *p) { return p[0]*256 + p[1]; } - static stbtt_uint32 ttULONG(const stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } - static stbtt_int32 ttLONG(const stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } - -#endif +static stbtt_uint16 ttUSHORT(stbtt_uint8 *p) { return p[0]*256 + p[1]; } +static stbtt_int16 ttSHORT(stbtt_uint8 *p) { return p[0]*256 + p[1]; } +static stbtt_uint32 ttULONG(stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } +static stbtt_int32 ttLONG(stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } #define stbtt_tag4(p,c0,c1,c2,c3) ((p)[0] == (c0) && (p)[1] == (c1) && (p)[2] == (c2) && (p)[3] == (c3)) #define stbtt_tag(p,str) stbtt_tag4(p,str[0],str[1],str[2],str[3]) -static int stbtt__isfont(const stbtt_uint8 *font) +static int stbtt__isfont(stbtt_uint8 *font) { // check the version number if (stbtt_tag4(font, '1',0,0,0)) return 1; // TrueType 1 if (stbtt_tag(font, "typ1")) return 1; // TrueType with type 1 font -- we don't support this! if (stbtt_tag(font, "OTTO")) return 1; // OpenType with CFF if (stbtt_tag4(font, 0,1,0,0)) return 1; // OpenType 1.0 + if (stbtt_tag(font, "true")) return 1; // Apple specification for TrueType fonts return 0; } @@ -1004,7 +1283,7 @@ static stbtt_uint32 stbtt__find_table(stbtt_uint8 *data, stbtt_uint32 fontstart, return 0; } -STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *font_collection, int index) +static int stbtt_GetFontOffsetForIndex_internal(unsigned char *font_collection, int index) { // if it's just a font, there's only one valid index if (stbtt__isfont(font_collection)) @@ -1023,14 +1302,43 @@ STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *font_collection, return -1; } -STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data2, int fontstart) +static int stbtt_GetNumberOfFonts_internal(unsigned char *font_collection) +{ + // if it's just a font, there's only one valid font + if (stbtt__isfont(font_collection)) + return 1; + + // check if it's a TTC + if (stbtt_tag(font_collection, "ttcf")) { + // version 1? + if (ttULONG(font_collection+4) == 0x00010000 || ttULONG(font_collection+4) == 0x00020000) { + return ttLONG(font_collection+8); + } + } + return 0; +} + +static stbtt__buf stbtt__get_subrs(stbtt__buf cff, stbtt__buf fontdict) +{ + stbtt_uint32 subrsoff = 0, private_loc[2] = { 0, 0 }; + stbtt__buf pdict; + stbtt__dict_get_ints(&fontdict, 18, 2, private_loc); + if (!private_loc[1] || !private_loc[0]) return stbtt__new_buf(NULL, 0); + pdict = stbtt__buf_range(&cff, private_loc[1], private_loc[0]); + stbtt__dict_get_ints(&pdict, 19, 1, &subrsoff); + if (!subrsoff) return stbtt__new_buf(NULL, 0); + stbtt__buf_seek(&cff, private_loc[1]+subrsoff); + return stbtt__cff_get_index(&cff); +} + +static int stbtt_InitFont_internal(stbtt_fontinfo *info, unsigned char *data, int fontstart) { - stbtt_uint8 *data = (stbtt_uint8 *) data2; stbtt_uint32 cmap, t; stbtt_int32 i,numTables; info->data = data; info->fontstart = fontstart; + info->cff = stbtt__new_buf(NULL, 0); cmap = stbtt__find_table(data, fontstart, "cmap"); // required info->loca = stbtt__find_table(data, fontstart, "loca"); // required @@ -1039,8 +1347,62 @@ STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data2, i info->hhea = stbtt__find_table(data, fontstart, "hhea"); // required info->hmtx = stbtt__find_table(data, fontstart, "hmtx"); // required info->kern = stbtt__find_table(data, fontstart, "kern"); // not required - if (!cmap || !info->loca || !info->head || !info->glyf || !info->hhea || !info->hmtx) + info->gpos = stbtt__find_table(data, fontstart, "GPOS"); // not required + + if (!cmap || !info->head || !info->hhea || !info->hmtx) return 0; + if (info->glyf) { + // required for truetype + if (!info->loca) return 0; + } else { + // initialization for CFF / Type2 fonts (OTF) + stbtt__buf b, topdict, topdictidx; + stbtt_uint32 cstype = 2, charstrings = 0, fdarrayoff = 0, fdselectoff = 0; + stbtt_uint32 cff; + + cff = stbtt__find_table(data, fontstart, "CFF "); + if (!cff) return 0; + + info->fontdicts = stbtt__new_buf(NULL, 0); + info->fdselect = stbtt__new_buf(NULL, 0); + + // @TODO this should use size from table (not 512MB) + info->cff = stbtt__new_buf(data+cff, 512*1024*1024); + b = info->cff; + + // read the header + stbtt__buf_skip(&b, 2); + stbtt__buf_seek(&b, stbtt__buf_get8(&b)); // hdrsize + + // @TODO the name INDEX could list multiple fonts, + // but we just use the first one. + stbtt__cff_get_index(&b); // name INDEX + topdictidx = stbtt__cff_get_index(&b); + topdict = stbtt__cff_index_get(topdictidx, 0); + stbtt__cff_get_index(&b); // string INDEX + info->gsubrs = stbtt__cff_get_index(&b); + + stbtt__dict_get_ints(&topdict, 17, 1, &charstrings); + stbtt__dict_get_ints(&topdict, 0x100 | 6, 1, &cstype); + stbtt__dict_get_ints(&topdict, 0x100 | 36, 1, &fdarrayoff); + stbtt__dict_get_ints(&topdict, 0x100 | 37, 1, &fdselectoff); + info->subrs = stbtt__get_subrs(b, topdict); + + // we only support Type 2 charstrings + if (cstype != 2) return 0; + if (charstrings == 0) return 0; + + if (fdarrayoff) { + // looks like a CID font + if (!fdselectoff) return 0; + stbtt__buf_seek(&b, fdarrayoff); + info->fontdicts = stbtt__cff_get_index(&b); + info->fdselect = stbtt__buf_range(&b, fdselectoff, b.size-fdselectoff); + } + + stbtt__buf_seek(&b, charstrings); + info->charstrings = stbtt__cff_get_index(&b); + } t = stbtt__find_table(data, fontstart, "maxp"); if (t) @@ -1191,6 +1553,8 @@ static int stbtt__GetGlyfOffset(const stbtt_fontinfo *info, int glyph_index) { int g1,g2; + STBTT_assert(!info->cff.size); + if (glyph_index >= info->numGlyphs) return -1; // glyph index out of range if (info->indexToLocFormat >= 2) return -1; // unknown index->glyph map format @@ -1205,15 +1569,21 @@ static int stbtt__GetGlyfOffset(const stbtt_fontinfo *info, int glyph_index) return g1==g2 ? -1 : g1; // if length is 0, return -1 } +static int stbtt__GetGlyphInfoT2(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1); + STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1) { - int g = stbtt__GetGlyfOffset(info, glyph_index); - if (g < 0) return 0; + if (info->cff.size) { + stbtt__GetGlyphInfoT2(info, glyph_index, x0, y0, x1, y1); + } else { + int g = stbtt__GetGlyfOffset(info, glyph_index); + if (g < 0) return 0; - if (x0) *x0 = ttSHORT(info->data + g + 2); - if (y0) *y0 = ttSHORT(info->data + g + 4); - if (x1) *x1 = ttSHORT(info->data + g + 6); - if (y1) *y1 = ttSHORT(info->data + g + 8); + if (x0) *x0 = ttSHORT(info->data + g + 2); + if (y0) *y0 = ttSHORT(info->data + g + 4); + if (x1) *x1 = ttSHORT(info->data + g + 6); + if (y1) *y1 = ttSHORT(info->data + g + 8); + } return 1; } @@ -1225,7 +1595,10 @@ STBTT_DEF int stbtt_GetCodepointBox(const stbtt_fontinfo *info, int codepoint, i STBTT_DEF int stbtt_IsGlyphEmpty(const stbtt_fontinfo *info, int glyph_index) { stbtt_int16 numberOfContours; - int g = stbtt__GetGlyfOffset(info, glyph_index); + int g; + if (info->cff.size) + return stbtt__GetGlyphInfoT2(info, glyph_index, NULL, NULL, NULL, NULL) == 0; + g = stbtt__GetGlyfOffset(info, glyph_index); if (g < 0) return 1; numberOfContours = ttSHORT(info->data + g); return numberOfContours == 0; @@ -1247,7 +1620,7 @@ static int stbtt__close_shape(stbtt_vertex *vertices, int num_vertices, int was_ return num_vertices; } -STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) +static int stbtt__GetGlyphShapeTT(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) { stbtt_int16 numberOfContours; stbtt_uint8 *endPtsOfContours; @@ -1473,6 +1846,414 @@ STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, s return num_vertices; } +typedef struct +{ + int bounds; + int started; + float first_x, first_y; + float x, y; + stbtt_int32 min_x, max_x, min_y, max_y; + + stbtt_vertex *pvertices; + int num_vertices; +} stbtt__csctx; + +#define STBTT__CSCTX_INIT(bounds) {bounds,0, 0,0, 0,0, 0,0,0,0, NULL, 0} + +static void stbtt__track_vertex(stbtt__csctx *c, stbtt_int32 x, stbtt_int32 y) +{ + if (x > c->max_x || !c->started) c->max_x = x; + if (y > c->max_y || !c->started) c->max_y = y; + if (x < c->min_x || !c->started) c->min_x = x; + if (y < c->min_y || !c->started) c->min_y = y; + c->started = 1; +} + +static void stbtt__csctx_v(stbtt__csctx *c, stbtt_uint8 type, stbtt_int32 x, stbtt_int32 y, stbtt_int32 cx, stbtt_int32 cy, stbtt_int32 cx1, stbtt_int32 cy1) +{ + if (c->bounds) { + stbtt__track_vertex(c, x, y); + if (type == STBTT_vcubic) { + stbtt__track_vertex(c, cx, cy); + stbtt__track_vertex(c, cx1, cy1); + } + } else { + stbtt_setvertex(&c->pvertices[c->num_vertices], type, x, y, cx, cy); + c->pvertices[c->num_vertices].cx1 = (stbtt_int16) cx1; + c->pvertices[c->num_vertices].cy1 = (stbtt_int16) cy1; + } + c->num_vertices++; +} + +static void stbtt__csctx_close_shape(stbtt__csctx *ctx) +{ + if (ctx->first_x != ctx->x || ctx->first_y != ctx->y) + stbtt__csctx_v(ctx, STBTT_vline, (int)ctx->first_x, (int)ctx->first_y, 0, 0, 0, 0); +} + +static void stbtt__csctx_rmove_to(stbtt__csctx *ctx, float dx, float dy) +{ + stbtt__csctx_close_shape(ctx); + ctx->first_x = ctx->x = ctx->x + dx; + ctx->first_y = ctx->y = ctx->y + dy; + stbtt__csctx_v(ctx, STBTT_vmove, (int)ctx->x, (int)ctx->y, 0, 0, 0, 0); +} + +static void stbtt__csctx_rline_to(stbtt__csctx *ctx, float dx, float dy) +{ + ctx->x += dx; + ctx->y += dy; + stbtt__csctx_v(ctx, STBTT_vline, (int)ctx->x, (int)ctx->y, 0, 0, 0, 0); +} + +static void stbtt__csctx_rccurve_to(stbtt__csctx *ctx, float dx1, float dy1, float dx2, float dy2, float dx3, float dy3) +{ + float cx1 = ctx->x + dx1; + float cy1 = ctx->y + dy1; + float cx2 = cx1 + dx2; + float cy2 = cy1 + dy2; + ctx->x = cx2 + dx3; + ctx->y = cy2 + dy3; + stbtt__csctx_v(ctx, STBTT_vcubic, (int)ctx->x, (int)ctx->y, (int)cx1, (int)cy1, (int)cx2, (int)cy2); +} + +static stbtt__buf stbtt__get_subr(stbtt__buf idx, int n) +{ + int count = stbtt__cff_index_count(&idx); + int bias = 107; + if (count >= 33900) + bias = 32768; + else if (count >= 1240) + bias = 1131; + n += bias; + if (n < 0 || n >= count) + return stbtt__new_buf(NULL, 0); + return stbtt__cff_index_get(idx, n); +} + +static stbtt__buf stbtt__cid_get_glyph_subrs(const stbtt_fontinfo *info, int glyph_index) +{ + stbtt__buf fdselect = info->fdselect; + int nranges, start, end, v, fmt, fdselector = -1, i; + + stbtt__buf_seek(&fdselect, 0); + fmt = stbtt__buf_get8(&fdselect); + if (fmt == 0) { + // untested + stbtt__buf_skip(&fdselect, glyph_index); + fdselector = stbtt__buf_get8(&fdselect); + } else if (fmt == 3) { + nranges = stbtt__buf_get16(&fdselect); + start = stbtt__buf_get16(&fdselect); + for (i = 0; i < nranges; i++) { + v = stbtt__buf_get8(&fdselect); + end = stbtt__buf_get16(&fdselect); + if (glyph_index >= start && glyph_index < end) { + fdselector = v; + break; + } + start = end; + } + } + if (fdselector == -1) stbtt__new_buf(NULL, 0); + return stbtt__get_subrs(info->cff, stbtt__cff_index_get(info->fontdicts, fdselector)); +} + +static int stbtt__run_charstring(const stbtt_fontinfo *info, int glyph_index, stbtt__csctx *c) +{ + int in_header = 1, maskbits = 0, subr_stack_height = 0, sp = 0, v, i, b0; + int has_subrs = 0, clear_stack; + float s[48]; + stbtt__buf subr_stack[10], subrs = info->subrs, b; + float f; + +#define STBTT__CSERR(s) (0) + + // this currently ignores the initial width value, which isn't needed if we have hmtx + b = stbtt__cff_index_get(info->charstrings, glyph_index); + while (b.cursor < b.size) { + i = 0; + clear_stack = 1; + b0 = stbtt__buf_get8(&b); + switch (b0) { + // @TODO implement hinting + case 0x13: // hintmask + case 0x14: // cntrmask + if (in_header) + maskbits += (sp / 2); // implicit "vstem" + in_header = 0; + stbtt__buf_skip(&b, (maskbits + 7) / 8); + break; + + case 0x01: // hstem + case 0x03: // vstem + case 0x12: // hstemhm + case 0x17: // vstemhm + maskbits += (sp / 2); + break; + + case 0x15: // rmoveto + in_header = 0; + if (sp < 2) return STBTT__CSERR("rmoveto stack"); + stbtt__csctx_rmove_to(c, s[sp-2], s[sp-1]); + break; + case 0x04: // vmoveto + in_header = 0; + if (sp < 1) return STBTT__CSERR("vmoveto stack"); + stbtt__csctx_rmove_to(c, 0, s[sp-1]); + break; + case 0x16: // hmoveto + in_header = 0; + if (sp < 1) return STBTT__CSERR("hmoveto stack"); + stbtt__csctx_rmove_to(c, s[sp-1], 0); + break; + + case 0x05: // rlineto + if (sp < 2) return STBTT__CSERR("rlineto stack"); + for (; i + 1 < sp; i += 2) + stbtt__csctx_rline_to(c, s[i], s[i+1]); + break; + + // hlineto/vlineto and vhcurveto/hvcurveto alternate horizontal and vertical + // starting from a different place. + + case 0x07: // vlineto + if (sp < 1) return STBTT__CSERR("vlineto stack"); + goto vlineto; + case 0x06: // hlineto + if (sp < 1) return STBTT__CSERR("hlineto stack"); + for (;;) { + if (i >= sp) break; + stbtt__csctx_rline_to(c, s[i], 0); + i++; + vlineto: + if (i >= sp) break; + stbtt__csctx_rline_to(c, 0, s[i]); + i++; + } + break; + + case 0x1F: // hvcurveto + if (sp < 4) return STBTT__CSERR("hvcurveto stack"); + goto hvcurveto; + case 0x1E: // vhcurveto + if (sp < 4) return STBTT__CSERR("vhcurveto stack"); + for (;;) { + if (i + 3 >= sp) break; + stbtt__csctx_rccurve_to(c, 0, s[i], s[i+1], s[i+2], s[i+3], (sp - i == 5) ? s[i + 4] : 0.0f); + i += 4; + hvcurveto: + if (i + 3 >= sp) break; + stbtt__csctx_rccurve_to(c, s[i], 0, s[i+1], s[i+2], (sp - i == 5) ? s[i+4] : 0.0f, s[i+3]); + i += 4; + } + break; + + case 0x08: // rrcurveto + if (sp < 6) return STBTT__CSERR("rcurveline stack"); + for (; i + 5 < sp; i += 6) + stbtt__csctx_rccurve_to(c, s[i], s[i+1], s[i+2], s[i+3], s[i+4], s[i+5]); + break; + + case 0x18: // rcurveline + if (sp < 8) return STBTT__CSERR("rcurveline stack"); + for (; i + 5 < sp - 2; i += 6) + stbtt__csctx_rccurve_to(c, s[i], s[i+1], s[i+2], s[i+3], s[i+4], s[i+5]); + if (i + 1 >= sp) return STBTT__CSERR("rcurveline stack"); + stbtt__csctx_rline_to(c, s[i], s[i+1]); + break; + + case 0x19: // rlinecurve + if (sp < 8) return STBTT__CSERR("rlinecurve stack"); + for (; i + 1 < sp - 6; i += 2) + stbtt__csctx_rline_to(c, s[i], s[i+1]); + if (i + 5 >= sp) return STBTT__CSERR("rlinecurve stack"); + stbtt__csctx_rccurve_to(c, s[i], s[i+1], s[i+2], s[i+3], s[i+4], s[i+5]); + break; + + case 0x1A: // vvcurveto + case 0x1B: // hhcurveto + if (sp < 4) return STBTT__CSERR("(vv|hh)curveto stack"); + f = 0.0; + if (sp & 1) { f = s[i]; i++; } + for (; i + 3 < sp; i += 4) { + if (b0 == 0x1B) + stbtt__csctx_rccurve_to(c, s[i], f, s[i+1], s[i+2], s[i+3], 0.0); + else + stbtt__csctx_rccurve_to(c, f, s[i], s[i+1], s[i+2], 0.0, s[i+3]); + f = 0.0; + } + break; + + case 0x0A: // callsubr + if (!has_subrs) { + if (info->fdselect.size) + subrs = stbtt__cid_get_glyph_subrs(info, glyph_index); + has_subrs = 1; + } + // fallthrough + case 0x1D: // callgsubr + if (sp < 1) return STBTT__CSERR("call(g|)subr stack"); + v = (int) s[--sp]; + if (subr_stack_height >= 10) return STBTT__CSERR("recursion limit"); + subr_stack[subr_stack_height++] = b; + b = stbtt__get_subr(b0 == 0x0A ? subrs : info->gsubrs, v); + if (b.size == 0) return STBTT__CSERR("subr not found"); + b.cursor = 0; + clear_stack = 0; + break; + + case 0x0B: // return + if (subr_stack_height <= 0) return STBTT__CSERR("return outside subr"); + b = subr_stack[--subr_stack_height]; + clear_stack = 0; + break; + + case 0x0E: // endchar + stbtt__csctx_close_shape(c); + return 1; + + case 0x0C: { // two-byte escape + float dx1, dx2, dx3, dx4, dx5, dx6, dy1, dy2, dy3, dy4, dy5, dy6; + float dx, dy; + int b1 = stbtt__buf_get8(&b); + switch (b1) { + // @TODO These "flex" implementations ignore the flex-depth and resolution, + // and always draw beziers. + case 0x22: // hflex + if (sp < 7) return STBTT__CSERR("hflex stack"); + dx1 = s[0]; + dx2 = s[1]; + dy2 = s[2]; + dx3 = s[3]; + dx4 = s[4]; + dx5 = s[5]; + dx6 = s[6]; + stbtt__csctx_rccurve_to(c, dx1, 0, dx2, dy2, dx3, 0); + stbtt__csctx_rccurve_to(c, dx4, 0, dx5, -dy2, dx6, 0); + break; + + case 0x23: // flex + if (sp < 13) return STBTT__CSERR("flex stack"); + dx1 = s[0]; + dy1 = s[1]; + dx2 = s[2]; + dy2 = s[3]; + dx3 = s[4]; + dy3 = s[5]; + dx4 = s[6]; + dy4 = s[7]; + dx5 = s[8]; + dy5 = s[9]; + dx6 = s[10]; + dy6 = s[11]; + //fd is s[12] + stbtt__csctx_rccurve_to(c, dx1, dy1, dx2, dy2, dx3, dy3); + stbtt__csctx_rccurve_to(c, dx4, dy4, dx5, dy5, dx6, dy6); + break; + + case 0x24: // hflex1 + if (sp < 9) return STBTT__CSERR("hflex1 stack"); + dx1 = s[0]; + dy1 = s[1]; + dx2 = s[2]; + dy2 = s[3]; + dx3 = s[4]; + dx4 = s[5]; + dx5 = s[6]; + dy5 = s[7]; + dx6 = s[8]; + stbtt__csctx_rccurve_to(c, dx1, dy1, dx2, dy2, dx3, 0); + stbtt__csctx_rccurve_to(c, dx4, 0, dx5, dy5, dx6, -(dy1+dy2+dy5)); + break; + + case 0x25: // flex1 + if (sp < 11) return STBTT__CSERR("flex1 stack"); + dx1 = s[0]; + dy1 = s[1]; + dx2 = s[2]; + dy2 = s[3]; + dx3 = s[4]; + dy3 = s[5]; + dx4 = s[6]; + dy4 = s[7]; + dx5 = s[8]; + dy5 = s[9]; + dx6 = dy6 = s[10]; + dx = dx1+dx2+dx3+dx4+dx5; + dy = dy1+dy2+dy3+dy4+dy5; + if (STBTT_fabs(dx) > STBTT_fabs(dy)) + dy6 = -dy; + else + dx6 = -dx; + stbtt__csctx_rccurve_to(c, dx1, dy1, dx2, dy2, dx3, dy3); + stbtt__csctx_rccurve_to(c, dx4, dy4, dx5, dy5, dx6, dy6); + break; + + default: + return STBTT__CSERR("unimplemented"); + } + } break; + + default: + if (b0 != 255 && b0 != 28 && (b0 < 32 || b0 > 254)) + return STBTT__CSERR("reserved operator"); + + // push immediate + if (b0 == 255) { + f = (float)(stbtt_int32)stbtt__buf_get32(&b) / 0x10000; + } else { + stbtt__buf_skip(&b, -1); + f = (float)(stbtt_int16)stbtt__cff_int(&b); + } + if (sp >= 48) return STBTT__CSERR("push stack overflow"); + s[sp++] = f; + clear_stack = 0; + break; + } + if (clear_stack) sp = 0; + } + return STBTT__CSERR("no endchar"); + +#undef STBTT__CSERR +} + +static int stbtt__GetGlyphShapeT2(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) +{ + // runs the charstring twice, once to count and once to output (to avoid realloc) + stbtt__csctx count_ctx = STBTT__CSCTX_INIT(1); + stbtt__csctx output_ctx = STBTT__CSCTX_INIT(0); + if (stbtt__run_charstring(info, glyph_index, &count_ctx)) { + *pvertices = (stbtt_vertex*)STBTT_malloc(count_ctx.num_vertices*sizeof(stbtt_vertex), info->userdata); + output_ctx.pvertices = *pvertices; + if (stbtt__run_charstring(info, glyph_index, &output_ctx)) { + STBTT_assert(output_ctx.num_vertices == count_ctx.num_vertices); + return output_ctx.num_vertices; + } + } + *pvertices = NULL; + return 0; +} + +static int stbtt__GetGlyphInfoT2(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1) +{ + stbtt__csctx c = STBTT__CSCTX_INIT(1); + int r = stbtt__run_charstring(info, glyph_index, &c); + if (x0) *x0 = r ? c.min_x : 0; + if (y0) *y0 = r ? c.min_y : 0; + if (x1) *x1 = r ? c.max_x : 0; + if (y1) *y1 = r ? c.max_y : 0; + return r ? c.num_vertices : 0; +} + +STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) +{ + if (!info->cff.size) + return stbtt__GetGlyphShapeTT(info, glyph_index, pvertices); + else + return stbtt__GetGlyphShapeT2(info, glyph_index, pvertices); +} + STBTT_DEF void stbtt_GetGlyphHMetrics(const stbtt_fontinfo *info, int glyph_index, int *advanceWidth, int *leftSideBearing) { stbtt_uint16 numOfLongHorMetrics = ttUSHORT(info->data+info->hhea + 34); @@ -1485,7 +2266,7 @@ STBTT_DEF void stbtt_GetGlyphHMetrics(const stbtt_fontinfo *info, int glyph_inde } } -STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2) +static int stbtt__GetGlyphKernInfoAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2) { stbtt_uint8 *data = info->data + info->kern; stbtt_uint32 needle, straw; @@ -1515,9 +2296,261 @@ STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int glyph1, return 0; } +static stbtt_int32 stbtt__GetCoverageIndex(stbtt_uint8 *coverageTable, int glyph) +{ + stbtt_uint16 coverageFormat = ttUSHORT(coverageTable); + switch(coverageFormat) { + case 1: { + stbtt_uint16 glyphCount = ttUSHORT(coverageTable + 2); + + // Binary search. + stbtt_int32 l=0, r=glyphCount-1, m; + int straw, needle=glyph; + while (l <= r) { + stbtt_uint8 *glyphArray = coverageTable + 4; + stbtt_uint16 glyphID; + m = (l + r) >> 1; + glyphID = ttUSHORT(glyphArray + 2 * m); + straw = glyphID; + if (needle < straw) + r = m - 1; + else if (needle > straw) + l = m + 1; + else { + return m; + } + } + } break; + + case 2: { + stbtt_uint16 rangeCount = ttUSHORT(coverageTable + 2); + stbtt_uint8 *rangeArray = coverageTable + 4; + + // Binary search. + stbtt_int32 l=0, r=rangeCount-1, m; + int strawStart, strawEnd, needle=glyph; + while (l <= r) { + stbtt_uint8 *rangeRecord; + m = (l + r) >> 1; + rangeRecord = rangeArray + 6 * m; + strawStart = ttUSHORT(rangeRecord); + strawEnd = ttUSHORT(rangeRecord + 2); + if (needle < strawStart) + r = m - 1; + else if (needle > strawEnd) + l = m + 1; + else { + stbtt_uint16 startCoverageIndex = ttUSHORT(rangeRecord + 4); + return startCoverageIndex + glyph - strawStart; + } + } + } break; + + default: { + // There are no other cases. + STBTT_assert(0); + } break; + } + + return -1; +} + +static stbtt_int32 stbtt__GetGlyphClass(stbtt_uint8 *classDefTable, int glyph) +{ + stbtt_uint16 classDefFormat = ttUSHORT(classDefTable); + switch(classDefFormat) + { + case 1: { + stbtt_uint16 startGlyphID = ttUSHORT(classDefTable + 2); + stbtt_uint16 glyphCount = ttUSHORT(classDefTable + 4); + stbtt_uint8 *classDef1ValueArray = classDefTable + 6; + + if (glyph >= startGlyphID && glyph < startGlyphID + glyphCount) + return (stbtt_int32)ttUSHORT(classDef1ValueArray + 2 * (glyph - startGlyphID)); + + classDefTable = classDef1ValueArray + 2 * glyphCount; + } break; + + case 2: { + stbtt_uint16 classRangeCount = ttUSHORT(classDefTable + 2); + stbtt_uint8 *classRangeRecords = classDefTable + 4; + + // Binary search. + stbtt_int32 l=0, r=classRangeCount-1, m; + int strawStart, strawEnd, needle=glyph; + while (l <= r) { + stbtt_uint8 *classRangeRecord; + m = (l + r) >> 1; + classRangeRecord = classRangeRecords + 6 * m; + strawStart = ttUSHORT(classRangeRecord); + strawEnd = ttUSHORT(classRangeRecord + 2); + if (needle < strawStart) + r = m - 1; + else if (needle > strawEnd) + l = m + 1; + else + return (stbtt_int32)ttUSHORT(classRangeRecord + 4); + } + + classDefTable = classRangeRecords + 6 * classRangeCount; + } break; + + default: { + // There are no other cases. + STBTT_assert(0); + } break; + } + + return -1; +} + +// Define to STBTT_assert(x) if you want to break on unimplemented formats. +#define STBTT_GPOS_TODO_assert(x) + +static stbtt_int32 stbtt__GetGlyphGPOSInfoAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2) +{ + stbtt_uint16 lookupListOffset; + stbtt_uint8 *lookupList; + stbtt_uint16 lookupCount; + stbtt_uint8 *data; + stbtt_int32 i; + + if (!info->gpos) return 0; + + data = info->data + info->gpos; + + if (ttUSHORT(data+0) != 1) return 0; // Major version 1 + if (ttUSHORT(data+2) != 0) return 0; // Minor version 0 + + lookupListOffset = ttUSHORT(data+8); + lookupList = data + lookupListOffset; + lookupCount = ttUSHORT(lookupList); + + for (i=0; i<lookupCount; ++i) { + stbtt_uint16 lookupOffset = ttUSHORT(lookupList + 2 + 2 * i); + stbtt_uint8 *lookupTable = lookupList + lookupOffset; + + stbtt_uint16 lookupType = ttUSHORT(lookupTable); + stbtt_uint16 subTableCount = ttUSHORT(lookupTable + 4); + stbtt_uint8 *subTableOffsets = lookupTable + 6; + switch(lookupType) { + case 2: { // Pair Adjustment Positioning Subtable + stbtt_int32 sti; + for (sti=0; sti<subTableCount; sti++) { + stbtt_uint16 subtableOffset = ttUSHORT(subTableOffsets + 2 * sti); + stbtt_uint8 *table = lookupTable + subtableOffset; + stbtt_uint16 posFormat = ttUSHORT(table); + stbtt_uint16 coverageOffset = ttUSHORT(table + 2); + stbtt_int32 coverageIndex = stbtt__GetCoverageIndex(table + coverageOffset, glyph1); + if (coverageIndex == -1) continue; + + switch (posFormat) { + case 1: { + stbtt_int32 l, r, m; + int straw, needle; + stbtt_uint16 valueFormat1 = ttUSHORT(table + 4); + stbtt_uint16 valueFormat2 = ttUSHORT(table + 6); + stbtt_int32 valueRecordPairSizeInBytes = 2; + stbtt_uint16 pairSetCount = ttUSHORT(table + 8); + stbtt_uint16 pairPosOffset = ttUSHORT(table + 10 + 2 * coverageIndex); + stbtt_uint8 *pairValueTable = table + pairPosOffset; + stbtt_uint16 pairValueCount = ttUSHORT(pairValueTable); + stbtt_uint8 *pairValueArray = pairValueTable + 2; + // TODO: Support more formats. + STBTT_GPOS_TODO_assert(valueFormat1 == 4); + if (valueFormat1 != 4) return 0; + STBTT_GPOS_TODO_assert(valueFormat2 == 0); + if (valueFormat2 != 0) return 0; + + STBTT_assert(coverageIndex < pairSetCount); + STBTT__NOTUSED(pairSetCount); + + needle=glyph2; + r=pairValueCount-1; + l=0; + + // Binary search. + while (l <= r) { + stbtt_uint16 secondGlyph; + stbtt_uint8 *pairValue; + m = (l + r) >> 1; + pairValue = pairValueArray + (2 + valueRecordPairSizeInBytes) * m; + secondGlyph = ttUSHORT(pairValue); + straw = secondGlyph; + if (needle < straw) + r = m - 1; + else if (needle > straw) + l = m + 1; + else { + stbtt_int16 xAdvance = ttSHORT(pairValue + 2); + return xAdvance; + } + } + } break; + + case 2: { + stbtt_uint16 valueFormat1 = ttUSHORT(table + 4); + stbtt_uint16 valueFormat2 = ttUSHORT(table + 6); + + stbtt_uint16 classDef1Offset = ttUSHORT(table + 8); + stbtt_uint16 classDef2Offset = ttUSHORT(table + 10); + int glyph1class = stbtt__GetGlyphClass(table + classDef1Offset, glyph1); + int glyph2class = stbtt__GetGlyphClass(table + classDef2Offset, glyph2); + + stbtt_uint16 class1Count = ttUSHORT(table + 12); + stbtt_uint16 class2Count = ttUSHORT(table + 14); + STBTT_assert(glyph1class < class1Count); + STBTT_assert(glyph2class < class2Count); + + // TODO: Support more formats. + STBTT_GPOS_TODO_assert(valueFormat1 == 4); + if (valueFormat1 != 4) return 0; + STBTT_GPOS_TODO_assert(valueFormat2 == 0); + if (valueFormat2 != 0) return 0; + + if (glyph1class >= 0 && glyph1class < class1Count && glyph2class >= 0 && glyph2class < class2Count) { + stbtt_uint8 *class1Records = table + 16; + stbtt_uint8 *class2Records = class1Records + 2 * (glyph1class * class2Count); + stbtt_int16 xAdvance = ttSHORT(class2Records + 2 * glyph2class); + return xAdvance; + } + } break; + + default: { + // There are no other cases. + STBTT_assert(0); + break; + }; + } + } + break; + }; + + default: + // TODO: Implement other stuff. + break; + } + } + + return 0; +} + +STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int g1, int g2) +{ + int xAdvance = 0; + + if (info->gpos) + xAdvance += stbtt__GetGlyphGPOSInfoAdvance(info, g1, g2); + + if (info->kern) + xAdvance += stbtt__GetGlyphKernInfoAdvance(info, g1, g2); + + return xAdvance; +} + STBTT_DEF int stbtt_GetCodepointKernAdvance(const stbtt_fontinfo *info, int ch1, int ch2) { - if (!info->kern) // if no kerning table, don't waste time looking up both codepoint->glyphs + if (!info->kern && !info->gpos) // if no kerning table, don't waste time looking up both codepoint->glyphs return 0; return stbtt_GetGlyphKernAdvance(info, stbtt_FindGlyphIndex(info,ch1), stbtt_FindGlyphIndex(info,ch2)); } @@ -1534,6 +2567,17 @@ STBTT_DEF void stbtt_GetFontVMetrics(const stbtt_fontinfo *info, int *ascent, in if (lineGap) *lineGap = ttSHORT(info->data+info->hhea + 8); } +STBTT_DEF int stbtt_GetFontVMetricsOS2(const stbtt_fontinfo *info, int *typoAscent, int *typoDescent, int *typoLineGap) +{ + int tab = stbtt__find_table(info->data, info->fontstart, "OS/2"); + if (!tab) + return 0; + if (typoAscent ) *typoAscent = ttSHORT(info->data+tab + 68); + if (typoDescent) *typoDescent = ttSHORT(info->data+tab + 70); + if (typoLineGap) *typoLineGap = ttSHORT(info->data+tab + 72); + return 1; +} + STBTT_DEF void stbtt_GetFontBoundingBox(const stbtt_fontinfo *info, int *x0, int *y0, int *x1, int *y1) { *x0 = ttSHORT(info->data + info->head + 36); @@ -1630,7 +2674,7 @@ static void *stbtt__hheap_alloc(stbtt__hheap *hh, size_t size, void *userdata) hh->num_remaining_in_head_chunk = count; } --hh->num_remaining_in_head_chunk; - return (char *) (hh->head) + size * hh->num_remaining_in_head_chunk; + return (char *) (hh->head) + sizeof(stbtt__hheap_chunk) + size * hh->num_remaining_in_head_chunk; } } @@ -2026,19 +3070,18 @@ static void stbtt__fill_active_edges_new(float *scanline, float *scanline_fill, // from the other y segment, and it might ignored as an empty segment. to avoid // that, we need to explicitly produce segments based on x positions. - // rename variables to clear pairs + // rename variables to clearly-defined pairs float y0 = y_top; float x1 = (float) (x); float x2 = (float) (x+1); float x3 = xb; float y3 = y_bottom; - float y1,y2; // x = e->x + e->dx * (y-y_top) // (y-y_top) = (x - e->x) / e->dx // y = (x - e->x) / e->dx + y_top - y1 = (x - x0) / dx + y_top; - y2 = (x+1 - x0) / dx + y_top; + float y1 = (x - x0) / dx + y_top; + float y2 = (x+1 - x0) / dx + y_top; if (x0 < x1 && x3 > x2) { // three segments descending down-right stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x1,y1); @@ -2073,12 +3116,13 @@ static void stbtt__fill_active_edges_new(float *scanline, float *scanline_fill, // directly AA rasterize edges w/o supersampling static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int n, int vsubsample, int off_x, int off_y, void *userdata) { - (void)vsubsample; stbtt__hheap hh = { 0, 0, 0 }; stbtt__active_edge *active = NULL; int y,j=0, i; float scanline_data[129], *scanline, *scanline2; + STBTT__NOTUSED(vsubsample); + if (result->w > 64) scanline = (float *) STBTT_malloc((result->w*2+1) * sizeof(float), userdata); else @@ -2342,6 +3386,48 @@ static int stbtt__tesselate_curve(stbtt__point *points, int *num_points, float x return 1; } +static void stbtt__tesselate_cubic(stbtt__point *points, int *num_points, float x0, float y0, float x1, float y1, float x2, float y2, float x3, float y3, float objspace_flatness_squared, int n) +{ + // @TODO this "flatness" calculation is just made-up nonsense that seems to work well enough + float dx0 = x1-x0; + float dy0 = y1-y0; + float dx1 = x2-x1; + float dy1 = y2-y1; + float dx2 = x3-x2; + float dy2 = y3-y2; + float dx = x3-x0; + float dy = y3-y0; + float longlen = (float) (STBTT_sqrt(dx0*dx0+dy0*dy0)+STBTT_sqrt(dx1*dx1+dy1*dy1)+STBTT_sqrt(dx2*dx2+dy2*dy2)); + float shortlen = (float) STBTT_sqrt(dx*dx+dy*dy); + float flatness_squared = longlen*longlen-shortlen*shortlen; + + if (n > 16) // 65536 segments on one curve better be enough! + return; + + if (flatness_squared > objspace_flatness_squared) { + float x01 = (x0+x1)/2; + float y01 = (y0+y1)/2; + float x12 = (x1+x2)/2; + float y12 = (y1+y2)/2; + float x23 = (x2+x3)/2; + float y23 = (y2+y3)/2; + + float xa = (x01+x12)/2; + float ya = (y01+y12)/2; + float xb = (x12+x23)/2; + float yb = (y12+y23)/2; + + float mx = (xa+xb)/2; + float my = (ya+yb)/2; + + stbtt__tesselate_cubic(points, num_points, x0,y0, x01,y01, xa,ya, mx,my, objspace_flatness_squared,n+1); + stbtt__tesselate_cubic(points, num_points, mx,my, xb,yb, x23,y23, x3,y3, objspace_flatness_squared,n+1); + } else { + stbtt__add_point(points, *num_points,x3,y3); + *num_points = *num_points+1; + } +} + // returns number of contours static stbtt__point *stbtt_FlattenCurves(stbtt_vertex *vertices, int num_verts, float objspace_flatness, int **contour_lengths, int *num_contours, void *userdata) { @@ -2398,6 +3484,14 @@ static stbtt__point *stbtt_FlattenCurves(stbtt_vertex *vertices, int num_verts, objspace_flatness_squared, 0); x = vertices[i].x, y = vertices[i].y; break; + case STBTT_vcubic: + stbtt__tesselate_cubic(points, &num_points, x,y, + vertices[i].cx, vertices[i].cy, + vertices[i].cx1, vertices[i].cy1, + vertices[i].x, vertices[i].y, + objspace_flatness_squared, 0); + x = vertices[i].x, y = vertices[i].y; + break; } } (*contour_lengths)[n] = num_points - start; @@ -2414,8 +3508,9 @@ error: STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, float flatness_in_pixels, stbtt_vertex *vertices, int num_verts, float scale_x, float scale_y, float shift_x, float shift_y, int x_off, int y_off, int invert, void *userdata) { - float scale = scale_x > scale_y ? scale_y : scale_x; - int winding_count, *winding_lengths; + float scale = scale_x > scale_y ? scale_y : scale_x; + int winding_count = 0; + int *winding_lengths = NULL; stbtt__point *windings = stbtt_FlattenCurves(vertices, num_verts, flatness_in_pixels / scale, &winding_lengths, &winding_count, userdata); if (windings) { stbtt__rasterize(result, windings, winding_lengths, winding_count, scale_x, scale_y, shift_x, shift_y, x_off, y_off, invert, userdata); @@ -2503,6 +3598,11 @@ STBTT_DEF unsigned char *stbtt_GetCodepointBitmapSubpixel(const stbtt_fontinfo * return stbtt_GetGlyphBitmapSubpixel(info, scale_x, scale_y,shift_x,shift_y, stbtt_FindGlyphIndex(info,codepoint), width,height,xoff,yoff); } +STBTT_DEF void stbtt_MakeCodepointBitmapSubpixelPrefilter(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int oversample_x, int oversample_y, float *sub_x, float *sub_y, int codepoint) +{ + stbtt_MakeGlyphBitmapSubpixelPrefilter(info, output, out_w, out_h, out_stride, scale_x, scale_y, shift_x, shift_y, oversample_x, oversample_y, sub_x, sub_y, stbtt_FindGlyphIndex(info,codepoint)); +} + STBTT_DEF void stbtt_MakeCodepointBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint) { stbtt_MakeGlyphBitmapSubpixel(info, output, out_w, out_h, out_stride, scale_x, scale_y, shift_x, shift_y, stbtt_FindGlyphIndex(info,codepoint)); @@ -2524,7 +3624,7 @@ STBTT_DEF void stbtt_MakeCodepointBitmap(const stbtt_fontinfo *info, unsigned ch // // This is SUPER-CRAPPY packing to keep source code small -STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, // font location (use offset=0 for plain .ttf) +static int stbtt_BakeFontBitmap_internal(unsigned char *data, int offset, // font location (use offset=0 for plain .ttf) float pixel_height, // height of font in pixels unsigned char *pixels, int pw, int ph, // bitmap to be filled in int first_char, int num_chars, // characters to bake @@ -2570,11 +3670,11 @@ STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, // fo return bottom_y; } -STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int opengl_fillrule) +STBTT_DEF void stbtt_GetBakedQuad(const stbtt_bakedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int opengl_fillrule) { float d3d_bias = opengl_fillrule ? 0 : -0.5f; float ipw = 1.0f / pw, iph = 1.0f / ph; - stbtt_bakedchar *b = chardata + char_index; + const stbtt_bakedchar *b = chardata + char_index; int round_x = STBTT_ifloor((*xpos + b->xoff) + 0.5f); int round_y = STBTT_ifloor((*ypos + b->yoff) + 0.5f); @@ -2597,11 +3697,6 @@ STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, int // #ifndef STB_RECT_PACK_VERSION -#ifdef _MSC_VER -#define STBTT__NOTUSED(v) (void)(v) -#else -#define STBTT__NOTUSED(v) (void)sizeof(v) -#endif typedef int stbrp_coord; @@ -2859,7 +3954,7 @@ static float stbtt__oversample_shift(int oversample) } // rects array must be big enough to accommodate all characters in the given ranges -STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) +STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, const stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) { int i,j,k; @@ -2887,8 +3982,31 @@ STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fon return k; } +STBTT_DEF void stbtt_MakeGlyphBitmapSubpixelPrefilter(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int prefilter_x, int prefilter_y, float *sub_x, float *sub_y, int glyph) +{ + stbtt_MakeGlyphBitmapSubpixel(info, + output, + out_w - (prefilter_x - 1), + out_h - (prefilter_y - 1), + out_stride, + scale_x, + scale_y, + shift_x, + shift_y, + glyph); + + if (prefilter_x > 1) + stbtt__h_prefilter(output, out_w, out_h, out_stride, prefilter_x); + + if (prefilter_y > 1) + stbtt__v_prefilter(output, out_w, out_h, out_stride, prefilter_y); + + *sub_x = stbtt__oversample_shift(prefilter_x); + *sub_y = stbtt__oversample_shift(prefilter_y); +} + // rects array must be big enough to accommodate all characters in the given ranges -STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) +STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, const stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) { int i,j,k, return_value = 1; @@ -2975,7 +4093,7 @@ STBTT_DEF void stbtt_PackFontRangesPackRects(stbtt_pack_context *spc, stbrp_rect stbrp_pack_rects((stbrp_context *) spc->pack_info, rects, num_rects); } -STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges) +STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, const unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges) { stbtt_fontinfo info; int i,j,n, return_value = 1; @@ -3011,7 +4129,7 @@ STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontd return return_value; } -STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, float font_size, +STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, const unsigned char *fontdata, int font_index, float font_size, int first_unicode_codepoint_in_range, int num_chars_in_range, stbtt_packedchar *chardata_for_range) { stbtt_pack_range range; @@ -3023,10 +4141,10 @@ STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontda return stbtt_PackFontRanges(spc, fontdata, font_index, &range, 1); } -STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int align_to_integer) +STBTT_DEF void stbtt_GetPackedQuad(const stbtt_packedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int align_to_integer) { float ipw = 1.0f / pw, iph = 1.0f / ph; - stbtt_packedchar *b = chardata + char_index; + const stbtt_packedchar *b = chardata + char_index; if (align_to_integer) { float x = (float) STBTT_ifloor((*xpos + b->xoff) + 0.5f); @@ -3050,6 +4168,387 @@ STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, i *xpos += b->xadvance; } +////////////////////////////////////////////////////////////////////////////// +// +// sdf computation +// + +#define STBTT_min(a,b) ((a) < (b) ? (a) : (b)) +#define STBTT_max(a,b) ((a) < (b) ? (b) : (a)) + +static int stbtt__ray_intersect_bezier(float orig[2], float ray[2], float q0[2], float q1[2], float q2[2], float hits[2][2]) +{ + float q0perp = q0[1]*ray[0] - q0[0]*ray[1]; + float q1perp = q1[1]*ray[0] - q1[0]*ray[1]; + float q2perp = q2[1]*ray[0] - q2[0]*ray[1]; + float roperp = orig[1]*ray[0] - orig[0]*ray[1]; + + float a = q0perp - 2*q1perp + q2perp; + float b = q1perp - q0perp; + float c = q0perp - roperp; + + float s0 = 0., s1 = 0.; + int num_s = 0; + + if (a != 0.0) { + float discr = b*b - a*c; + if (discr > 0.0) { + float rcpna = -1 / a; + float d = (float) STBTT_sqrt(discr); + s0 = (b+d) * rcpna; + s1 = (b-d) * rcpna; + if (s0 >= 0.0 && s0 <= 1.0) + num_s = 1; + if (d > 0.0 && s1 >= 0.0 && s1 <= 1.0) { + if (num_s == 0) s0 = s1; + ++num_s; + } + } + } else { + // 2*b*s + c = 0 + // s = -c / (2*b) + s0 = c / (-2 * b); + if (s0 >= 0.0 && s0 <= 1.0) + num_s = 1; + } + + if (num_s == 0) + return 0; + else { + float rcp_len2 = 1 / (ray[0]*ray[0] + ray[1]*ray[1]); + float rayn_x = ray[0] * rcp_len2, rayn_y = ray[1] * rcp_len2; + + float q0d = q0[0]*rayn_x + q0[1]*rayn_y; + float q1d = q1[0]*rayn_x + q1[1]*rayn_y; + float q2d = q2[0]*rayn_x + q2[1]*rayn_y; + float rod = orig[0]*rayn_x + orig[1]*rayn_y; + + float q10d = q1d - q0d; + float q20d = q2d - q0d; + float q0rd = q0d - rod; + + hits[0][0] = q0rd + s0*(2.0f - 2.0f*s0)*q10d + s0*s0*q20d; + hits[0][1] = a*s0+b; + + if (num_s > 1) { + hits[1][0] = q0rd + s1*(2.0f - 2.0f*s1)*q10d + s1*s1*q20d; + hits[1][1] = a*s1+b; + return 2; + } else { + return 1; + } + } +} + +static int equal(float *a, float *b) +{ + return (a[0] == b[0] && a[1] == b[1]); +} + +static int stbtt__compute_crossings_x(float x, float y, int nverts, stbtt_vertex *verts) +{ + int i; + float orig[2], ray[2] = { 1, 0 }; + float y_frac; + int winding = 0; + + orig[0] = x; + orig[1] = y; + + // make sure y never passes through a vertex of the shape + y_frac = (float) STBTT_fmod(y, 1.0f); + if (y_frac < 0.01f) + y += 0.01f; + else if (y_frac > 0.99f) + y -= 0.01f; + orig[1] = y; + + // test a ray from (-infinity,y) to (x,y) + for (i=0; i < nverts; ++i) { + if (verts[i].type == STBTT_vline) { + int x0 = (int) verts[i-1].x, y0 = (int) verts[i-1].y; + int x1 = (int) verts[i ].x, y1 = (int) verts[i ].y; + if (y > STBTT_min(y0,y1) && y < STBTT_max(y0,y1) && x > STBTT_min(x0,x1)) { + float x_inter = (y - y0) / (y1 - y0) * (x1-x0) + x0; + if (x_inter < x) + winding += (y0 < y1) ? 1 : -1; + } + } + if (verts[i].type == STBTT_vcurve) { + int x0 = (int) verts[i-1].x , y0 = (int) verts[i-1].y ; + int x1 = (int) verts[i ].cx, y1 = (int) verts[i ].cy; + int x2 = (int) verts[i ].x , y2 = (int) verts[i ].y ; + int ax = STBTT_min(x0,STBTT_min(x1,x2)), ay = STBTT_min(y0,STBTT_min(y1,y2)); + int by = STBTT_max(y0,STBTT_max(y1,y2)); + if (y > ay && y < by && x > ax) { + float q0[2],q1[2],q2[2]; + float hits[2][2]; + q0[0] = (float)x0; + q0[1] = (float)y0; + q1[0] = (float)x1; + q1[1] = (float)y1; + q2[0] = (float)x2; + q2[1] = (float)y2; + if (equal(q0,q1) || equal(q1,q2)) { + x0 = (int)verts[i-1].x; + y0 = (int)verts[i-1].y; + x1 = (int)verts[i ].x; + y1 = (int)verts[i ].y; + if (y > STBTT_min(y0,y1) && y < STBTT_max(y0,y1) && x > STBTT_min(x0,x1)) { + float x_inter = (y - y0) / (y1 - y0) * (x1-x0) + x0; + if (x_inter < x) + winding += (y0 < y1) ? 1 : -1; + } + } else { + int num_hits = stbtt__ray_intersect_bezier(orig, ray, q0, q1, q2, hits); + if (num_hits >= 1) + if (hits[0][0] < 0) + winding += (hits[0][1] < 0 ? -1 : 1); + if (num_hits >= 2) + if (hits[1][0] < 0) + winding += (hits[1][1] < 0 ? -1 : 1); + } + } + } + } + return winding; +} + +static float stbtt__cuberoot( float x ) +{ + if (x<0) + return -(float) STBTT_pow(-x,1.0f/3.0f); + else + return (float) STBTT_pow( x,1.0f/3.0f); +} + +// x^3 + c*x^2 + b*x + a = 0 +static int stbtt__solve_cubic(float a, float b, float c, float* r) +{ + float s = -a / 3; + float p = b - a*a / 3; + float q = a * (2*a*a - 9*b) / 27 + c; + float p3 = p*p*p; + float d = q*q + 4*p3 / 27; + if (d >= 0) { + float z = (float) STBTT_sqrt(d); + float u = (-q + z) / 2; + float v = (-q - z) / 2; + u = stbtt__cuberoot(u); + v = stbtt__cuberoot(v); + r[0] = s + u + v; + return 1; + } else { + float u = (float) STBTT_sqrt(-p/3); + float v = (float) STBTT_acos(-STBTT_sqrt(-27/p3) * q / 2) / 3; // p3 must be negative, since d is negative + float m = (float) STBTT_cos(v); + float n = (float) STBTT_cos(v-3.141592/2)*1.732050808f; + r[0] = s + u * 2 * m; + r[1] = s - u * (m + n); + r[2] = s - u * (m - n); + + //STBTT_assert( STBTT_fabs(((r[0]+a)*r[0]+b)*r[0]+c) < 0.05f); // these asserts may not be safe at all scales, though they're in bezier t parameter units so maybe? + //STBTT_assert( STBTT_fabs(((r[1]+a)*r[1]+b)*r[1]+c) < 0.05f); + //STBTT_assert( STBTT_fabs(((r[2]+a)*r[2]+b)*r[2]+c) < 0.05f); + return 3; + } +} + +STBTT_DEF unsigned char * stbtt_GetGlyphSDF(const stbtt_fontinfo *info, float scale, int glyph, int padding, unsigned char onedge_value, float pixel_dist_scale, int *width, int *height, int *xoff, int *yoff) +{ + float scale_x = scale, scale_y = scale; + int ix0,iy0,ix1,iy1; + int w,h; + unsigned char *data; + + // if one scale is 0, use same scale for both + if (scale_x == 0) scale_x = scale_y; + if (scale_y == 0) { + if (scale_x == 0) return NULL; // if both scales are 0, return NULL + scale_y = scale_x; + } + + stbtt_GetGlyphBitmapBoxSubpixel(info, glyph, scale, scale, 0.0f,0.0f, &ix0,&iy0,&ix1,&iy1); + + // if empty, return NULL + if (ix0 == ix1 || iy0 == iy1) + return NULL; + + ix0 -= padding; + iy0 -= padding; + ix1 += padding; + iy1 += padding; + + w = (ix1 - ix0); + h = (iy1 - iy0); + + if (width ) *width = w; + if (height) *height = h; + if (xoff ) *xoff = ix0; + if (yoff ) *yoff = iy0; + + // invert for y-downwards bitmaps + scale_y = -scale_y; + + { + int x,y,i,j; + float *precompute; + stbtt_vertex *verts; + int num_verts = stbtt_GetGlyphShape(info, glyph, &verts); + data = (unsigned char *) STBTT_malloc(w * h, info->userdata); + precompute = (float *) STBTT_malloc(num_verts * sizeof(float), info->userdata); + + for (i=0,j=num_verts-1; i < num_verts; j=i++) { + if (verts[i].type == STBTT_vline) { + float x0 = verts[i].x*scale_x, y0 = verts[i].y*scale_y; + float x1 = verts[j].x*scale_x, y1 = verts[j].y*scale_y; + float dist = (float) STBTT_sqrt((x1-x0)*(x1-x0) + (y1-y0)*(y1-y0)); + precompute[i] = (dist == 0) ? 0.0f : 1.0f / dist; + } else if (verts[i].type == STBTT_vcurve) { + float x2 = verts[j].x *scale_x, y2 = verts[j].y *scale_y; + float x1 = verts[i].cx*scale_x, y1 = verts[i].cy*scale_y; + float x0 = verts[i].x *scale_x, y0 = verts[i].y *scale_y; + float bx = x0 - 2*x1 + x2, by = y0 - 2*y1 + y2; + float len2 = bx*bx + by*by; + if (len2 != 0.0f) + precompute[i] = 1.0f / (bx*bx + by*by); + else + precompute[i] = 0.0f; + } else + precompute[i] = 0.0f; + } + + for (y=iy0; y < iy1; ++y) { + for (x=ix0; x < ix1; ++x) { + float val; + float min_dist = 999999.0f; + float sx = (float) x + 0.5f; + float sy = (float) y + 0.5f; + float x_gspace = (sx / scale_x); + float y_gspace = (sy / scale_y); + + int winding = stbtt__compute_crossings_x(x_gspace, y_gspace, num_verts, verts); // @OPTIMIZE: this could just be a rasterization, but needs to be line vs. non-tesselated curves so a new path + + for (i=0; i < num_verts; ++i) { + float x0 = verts[i].x*scale_x, y0 = verts[i].y*scale_y; + + // check against every point here rather than inside line/curve primitives -- @TODO: wrong if multiple 'moves' in a row produce a garbage point, and given culling, probably more efficient to do within line/curve + float dist2 = (x0-sx)*(x0-sx) + (y0-sy)*(y0-sy); + if (dist2 < min_dist*min_dist) + min_dist = (float) STBTT_sqrt(dist2); + + if (verts[i].type == STBTT_vline) { + float x1 = verts[i-1].x*scale_x, y1 = verts[i-1].y*scale_y; + + // coarse culling against bbox + //if (sx > STBTT_min(x0,x1)-min_dist && sx < STBTT_max(x0,x1)+min_dist && + // sy > STBTT_min(y0,y1)-min_dist && sy < STBTT_max(y0,y1)+min_dist) + float dist = (float) STBTT_fabs((x1-x0)*(y0-sy) - (y1-y0)*(x0-sx)) * precompute[i]; + STBTT_assert(i != 0); + if (dist < min_dist) { + // check position along line + // x' = x0 + t*(x1-x0), y' = y0 + t*(y1-y0) + // minimize (x'-sx)*(x'-sx)+(y'-sy)*(y'-sy) + float dx = x1-x0, dy = y1-y0; + float px = x0-sx, py = y0-sy; + // minimize (px+t*dx)^2 + (py+t*dy)^2 = px*px + 2*px*dx*t + t^2*dx*dx + py*py + 2*py*dy*t + t^2*dy*dy + // derivative: 2*px*dx + 2*py*dy + (2*dx*dx+2*dy*dy)*t, set to 0 and solve + float t = -(px*dx + py*dy) / (dx*dx + dy*dy); + if (t >= 0.0f && t <= 1.0f) + min_dist = dist; + } + } else if (verts[i].type == STBTT_vcurve) { + float x2 = verts[i-1].x *scale_x, y2 = verts[i-1].y *scale_y; + float x1 = verts[i ].cx*scale_x, y1 = verts[i ].cy*scale_y; + float box_x0 = STBTT_min(STBTT_min(x0,x1),x2); + float box_y0 = STBTT_min(STBTT_min(y0,y1),y2); + float box_x1 = STBTT_max(STBTT_max(x0,x1),x2); + float box_y1 = STBTT_max(STBTT_max(y0,y1),y2); + // coarse culling against bbox to avoid computing cubic unnecessarily + if (sx > box_x0-min_dist && sx < box_x1+min_dist && sy > box_y0-min_dist && sy < box_y1+min_dist) { + int num=0; + float ax = x1-x0, ay = y1-y0; + float bx = x0 - 2*x1 + x2, by = y0 - 2*y1 + y2; + float mx = x0 - sx, my = y0 - sy; + float res[3],px,py,t,it; + float a_inv = precompute[i]; + if (a_inv == 0.0) { // if a_inv is 0, it's 2nd degree so use quadratic formula + float a = 3*(ax*bx + ay*by); + float b = 2*(ax*ax + ay*ay) + (mx*bx+my*by); + float c = mx*ax+my*ay; + if (a == 0.0) { // if a is 0, it's linear + if (b != 0.0) { + res[num++] = -c/b; + } + } else { + float discriminant = b*b - 4*a*c; + if (discriminant < 0) + num = 0; + else { + float root = (float) STBTT_sqrt(discriminant); + res[0] = (-b - root)/(2*a); + res[1] = (-b + root)/(2*a); + num = 2; // don't bother distinguishing 1-solution case, as code below will still work + } + } + } else { + float b = 3*(ax*bx + ay*by) * a_inv; // could precompute this as it doesn't depend on sample point + float c = (2*(ax*ax + ay*ay) + (mx*bx+my*by)) * a_inv; + float d = (mx*ax+my*ay) * a_inv; + num = stbtt__solve_cubic(b, c, d, res); + } + if (num >= 1 && res[0] >= 0.0f && res[0] <= 1.0f) { + t = res[0], it = 1.0f - t; + px = it*it*x0 + 2*t*it*x1 + t*t*x2; + py = it*it*y0 + 2*t*it*y1 + t*t*y2; + dist2 = (px-sx)*(px-sx) + (py-sy)*(py-sy); + if (dist2 < min_dist * min_dist) + min_dist = (float) STBTT_sqrt(dist2); + } + if (num >= 2 && res[1] >= 0.0f && res[1] <= 1.0f) { + t = res[1], it = 1.0f - t; + px = it*it*x0 + 2*t*it*x1 + t*t*x2; + py = it*it*y0 + 2*t*it*y1 + t*t*y2; + dist2 = (px-sx)*(px-sx) + (py-sy)*(py-sy); + if (dist2 < min_dist * min_dist) + min_dist = (float) STBTT_sqrt(dist2); + } + if (num >= 3 && res[2] >= 0.0f && res[2] <= 1.0f) { + t = res[2], it = 1.0f - t; + px = it*it*x0 + 2*t*it*x1 + t*t*x2; + py = it*it*y0 + 2*t*it*y1 + t*t*y2; + dist2 = (px-sx)*(px-sx) + (py-sy)*(py-sy); + if (dist2 < min_dist * min_dist) + min_dist = (float) STBTT_sqrt(dist2); + } + } + } + } + if (winding == 0) + min_dist = -min_dist; // if outside the shape, value is negative + val = onedge_value + pixel_dist_scale * min_dist; + if (val < 0) + val = 0; + else if (val > 255) + val = 255; + data[(y-iy0)*w+(x-ix0)] = (unsigned char) val; + } + } + STBTT_free(precompute, info->userdata); + STBTT_free(verts, info->userdata); + } + return data; +} + +STBTT_DEF unsigned char * stbtt_GetCodepointSDF(const stbtt_fontinfo *info, float scale, int codepoint, int padding, unsigned char onedge_value, float pixel_dist_scale, int *width, int *height, int *xoff, int *yoff) +{ + return stbtt_GetGlyphSDF(info, scale, stbtt_FindGlyphIndex(info, codepoint), padding, onedge_value, pixel_dist_scale, width, height, xoff, yoff); +} + +STBTT_DEF void stbtt_FreeSDF(unsigned char *bitmap, void *userdata) +{ + STBTT_free(bitmap, userdata); +} ////////////////////////////////////////////////////////////////////////////// // @@ -3057,7 +4556,7 @@ STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, i // // check if a utf8 string contains a prefix which is the utf16 string; if so return length of matching utf8 string -static stbtt_int32 stbtt__CompareUTF8toUTF16_bigendian_prefix(const stbtt_uint8 *s1, stbtt_int32 len1, const stbtt_uint8 *s2, stbtt_int32 len2) +static stbtt_int32 stbtt__CompareUTF8toUTF16_bigendian_prefix(stbtt_uint8 *s1, stbtt_int32 len1, stbtt_uint8 *s2, stbtt_int32 len2) { stbtt_int32 i=0; @@ -3096,9 +4595,9 @@ static stbtt_int32 stbtt__CompareUTF8toUTF16_bigendian_prefix(const stbtt_uint8 return i; } -STBTT_DEF int stbtt_CompareUTF8toUTF16_bigendian(const char *s1, int len1, const char *s2, int len2) +static int stbtt_CompareUTF8toUTF16_bigendian_internal(char *s1, int len1, char *s2, int len2) { - return len1 == stbtt__CompareUTF8toUTF16_bigendian_prefix((const stbtt_uint8*) s1, len1, (const stbtt_uint8*) s2, len2); + return len1 == stbtt__CompareUTF8toUTF16_bigendian_prefix((stbtt_uint8*) s1, len1, (stbtt_uint8*) s2, len2); } // returns results in whatever encoding you request... but note that 2-byte encodings @@ -3154,7 +4653,7 @@ static int stbtt__matchpair(stbtt_uint8 *fc, stbtt_uint32 nm, stbtt_uint8 *name, return 1; } else if (matchlen < nlen && name[matchlen] == ' ') { ++matchlen; - if (stbtt_CompareUTF8toUTF16_bigendian((char*) (name+matchlen), nlen-matchlen, (char*)(fc+stringOffset+off),slen)) + if (stbtt_CompareUTF8toUTF16_bigendian_internal((char*) (name+matchlen), nlen-matchlen, (char*)(fc+stringOffset+off),slen)) return 1; } } else { @@ -3200,7 +4699,7 @@ static int stbtt__matches(stbtt_uint8 *fc, stbtt_uint32 offset, stbtt_uint8 *nam return 0; } -STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *font_collection, const char *name_utf8, stbtt_int32 flags) +static int stbtt_FindMatchingFont_internal(unsigned char *font_collection, char *name_utf8, stbtt_int32 flags) { stbtt_int32 i; for (i=0;;++i) { @@ -3211,11 +4710,61 @@ STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *font_collection, const } } +#if defined(__GNUC__) || defined(__clang__) +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wcast-qual" +#endif + +STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, + float pixel_height, unsigned char *pixels, int pw, int ph, + int first_char, int num_chars, stbtt_bakedchar *chardata) +{ + return stbtt_BakeFontBitmap_internal((unsigned char *) data, offset, pixel_height, pixels, pw, ph, first_char, num_chars, chardata); +} + +STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *data, int index) +{ + return stbtt_GetFontOffsetForIndex_internal((unsigned char *) data, index); +} + +STBTT_DEF int stbtt_GetNumberOfFonts(const unsigned char *data) +{ + return stbtt_GetNumberOfFonts_internal((unsigned char *) data); +} + +STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data, int offset) +{ + return stbtt_InitFont_internal(info, (unsigned char *) data, offset); +} + +STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *fontdata, const char *name, int flags) +{ + return stbtt_FindMatchingFont_internal((unsigned char *) fontdata, (char *) name, flags); +} + +STBTT_DEF int stbtt_CompareUTF8toUTF16_bigendian(const char *s1, int len1, const char *s2, int len2) +{ + return stbtt_CompareUTF8toUTF16_bigendian_internal((char *) s1, len1, (char *) s2, len2); +} + +#if defined(__GNUC__) || defined(__clang__) +#pragma GCC diagnostic pop +#endif + #endif // STB_TRUETYPE_IMPLEMENTATION // FULL VERSION HISTORY // +// 1.19 (2018-02-11) OpenType GPOS kerning (horizontal only), STBTT_fmod +// 1.18 (2018-01-29) add missing function +// 1.17 (2017-07-23) make more arguments const; doc fix +// 1.16 (2017-07-12) SDF support +// 1.15 (2017-03-03) make more arguments const +// 1.14 (2017-01-16) num-fonts-in-TTC function +// 1.13 (2017-01-02) support OpenType fonts, certain Apple fonts +// 1.12 (2016-10-25) suppress warnings about casting away const with -Wcast-qual +// 1.11 (2016-04-02) fix unused-variable warning // 1.10 (2016-04-02) allow user-defined fabs() replacement // fix memory leak if fontsize=0.0 // fix warning from duplicate typedef @@ -3261,3 +4810,45 @@ STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *font_collection, const // 0.2 (2009-03-11) Fix unsigned/signed char warnings // 0.1 (2009-03-09) First public release // + +/* +------------------------------------------------------------------------------ +This software is available under 2 licenses -- choose whichever you prefer. +------------------------------------------------------------------------------ +ALTERNATIVE A - MIT License +Copyright (c) 2017 Sean Barrett +Permission is hereby granted, free of charge, to any person obtaining a copy of +this software and associated documentation files (the "Software"), to deal in +the Software without restriction, including without limitation the rights to +use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies +of the Software, and to permit persons to whom the Software is furnished to do +so, subject to the following conditions: +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +------------------------------------------------------------------------------ +ALTERNATIVE B - Public Domain (www.unlicense.org) +This is free and unencumbered software released into the public domain. +Anyone is free to copy, modify, publish, use, compile, sell, or distribute this +software, either in source code form or as a compiled binary, for any purpose, +commercial or non-commercial, and by any means. +In jurisdictions that recognize copyright laws, the author or authors of this +software dedicate any and all copyright interest in the software to the public +domain. We make this dedication for the benefit of the public at large and to +the detriment of our heirs and successors. We intend this dedication to be an +overt act of relinquishment in perpetuity of all present and future rights to +this software under copyright law. +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN +ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION +WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +------------------------------------------------------------------------------ +*/ diff --git a/include/tensor.h b/include/tensor.h new file mode 100644 index 0000000..53364aa --- /dev/null +++ b/include/tensor.h @@ -0,0 +1,328 @@ +/* + * tensor.h + * + * N-dimensional tensor class, built around a flattened 1-D vector + * + * This class only contains enough functionalities to implement the demos, since + * armadillo doesn't provide tensors with more than 3 dimensions + * + * Authors: Philip Abbet + */ + +#pragma once + + +#include <stdio.h> +#include <assert.h> +#include <armadillo> + + +template <typename T, size_t N> +class Tensor { + +public: + + //------------------------------------------------------------------------- + // Creates an empty tensor + //------------------------------------------------------------------------- + Tensor() + : size(0) + { + } + + + //------------------------------------------------------------------------- + // Creates the tensor with the provided dimensions + //------------------------------------------------------------------------- + template<typename... Ints> + Tensor(Ints... dims) + : Tensor(arma::ivec({((int) dims)...})) + { + } + + + //------------------------------------------------------------------------- + // Creates the tensor with the provided dimensions + //------------------------------------------------------------------------- + Tensor(const arma::ivec& dims) + : size(1) + { + assert(dims.n_elem == N); + + this->dims = dims; + + for (int i = 0; i < dims.n_elem; ++i) + size *= this->dims(i); + + _indices = arma::ivec(dims.n_elem); + + _indices(0) = 1; + for (int i = 1; i < dims.n_elem; ++i) + _indices(i) = dims(i - 1) * _indices(i - 1); + + data = arma::Col<T>(size, arma::fill::zeros); + } + + + //------------------------------------------------------------------------- + // Returns the element index (in the flattened vector) corresponding to the + // provided N indices + //------------------------------------------------------------------------- + int indice(const arma::ivec& subscripts) const { + assert(subscripts.n_elem == N); + + int indice = 0; + + for (int i = 0; i < dims.n_elem; ++i) + indice += subscripts(i) * _indices(i); + + return indice; + } + + + //------------------------------------------------------------------------- + // Returns the element index (in the flattened vector) corresponding to the + // provided N indices + //------------------------------------------------------------------------- + template<typename... Ints> + int indice(Ints... subscripts) const { + static_assert(sizeof...(Ints) == N, "Wrong number of arguments"); + + return indice(arma::ivec({subscripts...})); + } + + + //------------------------------------------------------------------------- + // Returns the list of element indices (in the flattened vector) + // corresponding to the provided N indices + //------------------------------------------------------------------------- + template<typename... Spans> + arma::uvec indices(Spans... spans) const { + static_assert(sizeof...(Spans) == N, "Wrong number of arguments"); + + arma::uvec result(size); + size_t nb_indices = 0; + + _compute_indices(result, nb_indices, 0, 0, spans...); + + return result.subvec(0, nb_indices - 1); + } + + + //------------------------------------------------------------------------- + // Returns A COPY of the elements located at the provided indices + //------------------------------------------------------------------------- + inline const arma::Col<T> operator()(const arma::uvec& indices) const { + return data(indices); + } + + + //------------------------------------------------------------------------- + // Returns A COPY of the elements located at the provided N indices/spans + //------------------------------------------------------------------------- + template<typename... Spans> + inline Tensor<T, N> operator()(Spans... spans) const { + static_assert(sizeof...(Spans) == N, "Wrong number of arguments"); + + arma::ivec dims(this->dims.n_elem); + + _compute_dims(dims, 0, spans...); + + Tensor<T, N> result(dims); + result.data = data(indices(spans...)); + return result; + } + + + //------------------------------------------------------------------------- + // Returns the value of the n-th element under the assumption of a flat + // layout, with column-major ordering of data (ie. column by column) + //------------------------------------------------------------------------- + inline T operator[](int index) const { + return data(index); + } + + + //------------------------------------------------------------------------- + // Assignement operator + //------------------------------------------------------------------------- + inline void operator=(const arma::Col<T>& v) { + assert(size == v.n_elem); + data = v; + } + + + //------------------------------------------------------------------------- + // Assignement operator + //------------------------------------------------------------------------- + inline void operator=(const Tensor<T, N>& t) { + assert(size == t.size); + assert(arma::all(dims == t.dims)); + data = t.data; + } + + + //------------------------------------------------------------------------- + // Set the value at the locations given by provided N indices + //------------------------------------------------------------------------- + inline void set(const arma::uvec& indices, T value) { + data(indices) = arma::Col<T>({ value }); + } + + + //------------------------------------------------------------------------- + // Set the values at the locations given by provided N indices + //------------------------------------------------------------------------- + inline void set(const arma::uvec& indices, const arma::Col<T>& values) { + data(indices) = values; + } + + + //------------------------------------------------------------------------- + // Set the value at the locations given by provided N indices + //------------------------------------------------------------------------- + template<typename... Spans> + inline void set(Spans... spans, T value) { + static_assert(sizeof...(Spans) == N, "Wrong number of arguments"); + + data(indices(spans...)) = arma::Col<T>({ value }); + } + + + //------------------------------------------------------------------------- + // Set the values at the locations given by provided N indices + //------------------------------------------------------------------------- + template<typename... Spans> + inline void set(Spans... spans, const arma::Col<T>& values) { + static_assert(sizeof...(Spans) == N, "Wrong number of arguments"); + + data(indices(spans...)) = values; + } + + + //------------------------------------------------------------------------- + // Multiplication by a scalar + //------------------------------------------------------------------------- + Tensor<T, N> operator*(T scalar) const { + Tensor<T, N> result(dims); + result.data = data * scalar; + return result; + } + + + //------------------------------------------------------------------------- + // Division by a scalar + //------------------------------------------------------------------------- + Tensor<T, N> operator/(T scalar) const { + Tensor<T, N> result(dims); + result.data = data / scalar; + return result; + } + + + //------------------------------------------------------------------------- + // Addition of a scalar + //------------------------------------------------------------------------- + Tensor<T, N> operator+(T scalar) const { + Tensor<T, N> result(dims); + result.data = data + scalar; + return result; + } + + + //------------------------------------------------------------------------- + // Addition of a tensor of same dimensions + //------------------------------------------------------------------------- + Tensor<T, N> operator+(const Tensor<T, N>& m) const { + Tensor<T, N> result(dims); + result.data = data + m.data; + return result; + } + + + //------------------------------------------------------------------------- + // Substraction of a tensor of same dimensions + //------------------------------------------------------------------------- + Tensor<T, N> operator-(const Tensor<T, N>& m) const { + Tensor<T, N> result(dims); + result.data = data - m.data; + return result; + } + + +protected: + + inline void _process_span(arma::span &s, unsigned int size) const { + if (s.whole) { + s.a = 0; + s.b = size - 1; + } + } + + + template<typename... Spans> + void _compute_indices(arma::uvec &result, size_t &nb_indices, unsigned int dim, + unsigned int base_index, int index, Spans... spans) const { + unsigned int next_index = base_index + index * _indices(dim); + _compute_indices(result, nb_indices, dim + 1, next_index, spans...); + } + + + template<typename... Spans> + void _compute_indices(arma::uvec &result, size_t &nb_indices, unsigned int dim, + unsigned int base_index, arma::span indices, Spans... spans) const { + _process_span(indices, dims(dim)); + + for (int i = indices.a; i <= indices.b; ++i) { + unsigned int next_index = base_index + i * _indices(dim); + _compute_indices(result, nb_indices, dim + 1, next_index, spans...); + } + } + + + void _compute_indices(arma::uvec &result, size_t &nb_indices, unsigned int dim, + unsigned int base_index, int index) const { + unsigned int next_index = base_index + index * _indices(dim); + result(nb_indices) = next_index; + ++nb_indices; + } + + + void _compute_indices(arma::uvec &result, size_t &nb_indices, unsigned int dim, + unsigned int base_index, arma::span indices) const { + _process_span(indices, dims(dim)); + + for (int i = indices.a; i <= indices.b; ++i) { + unsigned int next_index = base_index + i * _indices(dim); + result(nb_indices) = next_index; + ++nb_indices; + } + } + + + template<typename... Spans> + void _compute_dims(arma::ivec &result, unsigned int dim, arma::span indices, + Spans... spans) const { + _process_span(indices, dims(dim)); + + result[dim] = indices.b - indices.a + 1; + + _compute_dims(result, dim + 1, spans...); + } + + + void _compute_dims(arma::ivec &result, unsigned int dim, arma::span indices) const { + _process_span(indices, dims(dim)); + + result[dim] = indices.b - indices.a + 1; + } + + +public: + arma::ivec dims; // The N dimensions of the tensor + int size; // Total number of elements + arma::Col<T> data; // The flattened 1-D vector + +protected: + arma::ivec _indices; // Used to compute 1-D indices from N-D ones +}; diff --git a/include/window_utils.h b/include/window_utils.h new file mode 100644 index 0000000..af47019 --- /dev/null +++ b/include/window_utils.h @@ -0,0 +1,106 @@ +/* + * window_utils.h + * + * Helper functions to manage windows taking multiple monitors + * into account. + * + * Authors: Philip Abbet + */ + +#pragma once + +#include <GLFW/glfw3.h> +#include <algorithm> + + +//----------------------------------------------------------------------------- +// Returns the monitor on which the provided window is located. +// +// This functionality doesn't exists in GLFW. +//----------------------------------------------------------------------------- +GLFWmonitor* get_current_monitor(GLFWwindow* window) +{ + int win_x, win_y, win_width, win_height; + glfwGetWindowPos(window, &win_x, &win_y); + glfwGetWindowSize(window, &win_width, &win_height); + + int nb_monitors; + GLFWmonitor** monitors; + monitors = glfwGetMonitors(&nb_monitors); + + int best_overlap = 0; + GLFWmonitor* best_monitor = 0; + + for (int i = 0; i < nb_monitors; ++i) { + const GLFWvidmode* mode = glfwGetVideoMode(monitors[i]); + + int monitor_x, monitor_y; + glfwGetMonitorPos(monitors[i], &monitor_x, &monitor_y); + + int monitor_width = mode->width; + int monitor_height = mode->height; + + int overlap = + std::max(0, std::min(win_x + win_width, monitor_x + monitor_width) - std::max(win_x, monitor_x)) * + std::max(0, std::min(win_y + win_height, monitor_y + monitor_height) - std::max(win_y, monitor_y) + ); + + if (best_overlap < overlap) { + best_overlap = overlap; + best_monitor = monitors[i]; + } + } + + return best_monitor; +} + + +//----------------------------------------------------------------------------- +// Create a window as large as possiblem but adapted to the current monitor. +// On input, the provided dimensions are used as an hint for the desired aspect +// ratio. On output, the real dimensions of the window is returned. +//----------------------------------------------------------------------------- +GLFWwindow* create_window_at_optimal_size(const char* title, + int &width, int &height) { + + // First create a window of the desired size + GLFWwindow* window = glfwCreateWindow( + width, height, title, NULL, NULL + ); + + // Next determine on which monitor the window is located + GLFWmonitor* monitor = get_current_monitor(window); + + // Then compute the "optimal" size of the window on that monitor + const GLFWvidmode* mode = glfwGetVideoMode(monitor); + + int original_width = width; + int original_height = height; + + if (mode->height >= 2000) + height = 1800; + else if (mode->height >= 1440) + height = 1200; + else if (mode->height >= 1200) + height = 1000; + else if (mode->height >= 1000) + height = 900; + else if (mode->height >= 900) + height = 800; + else + height = 600; + + width = original_width * height / original_height; + + if (width >= mode->width) + { + width = mode->width - 100; + height = original_height * width / original_width; + } + + // Finally, resize the window and center it + glfwSetWindowSize(window, width, height); + glfwSetWindowPos(window, (mode->width - width) / 2, (mode->height - height) / 2); + + return window; +} diff --git a/src/demo_MPC_batch01.cpp b/src/demo_MPC_batch01.cpp new file mode 100644 index 0000000..1b2487f --- /dev/null +++ b/src/demo_MPC_batch01.cpp @@ -0,0 +1,471 @@ +/* + * demo_MPC_batch01.cpp + * + * Interactive MPC demo, with batch LQT and repulsive field test + * + * Fabien Crépon, Sylvain Calinon, 2017 + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +#include <mpc_utils.h> +#include <gl2ps.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + +//------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space +// +// UI coordinates range from (0, 0) to (win_width, win_height) +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +//------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width; + result(1) = coords(1) * (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space +// +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +// UI coordinates range from (0, 0) to (win_width, win_height) +//------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width; + result(1) = coords(1) * (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + +//----------------------------------------------- + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +void setOrtho( float w, float h ) +{ + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, 0+w, 0+h, 0, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); +} + +//----------------------------------------------- + +void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d, + const window_size_t& window_size) +{ + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + *Sigma = basis * basis.t(); + *mu = ui2fb(arma::vec({t2d.pos.x, t2d.pos.y}), window_size); +} + +//----------------------------------------------- + +void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma, + const window_size_t& window_size) +{ + arma::vec ui_mu = fb2ui(mu, window_size); + + t2d->pos.x = ui_mu(0); + t2d->pos.y = ui_mu(1); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, Sigma); + arma::mat VD = V*diagmat(sqrt(d)); + + arma::vec t_x = fb2ui(arma::vec({VD.col(0)(0), VD.col(1)(0)}), window_size); + arma::vec t_y = fb2ui(arma::vec({VD.col(0)(1), VD.col(1)(1)}), window_size); + + t2d->x.x = t_x(0); + t2d->x.y = t_x(1); + t2d->y.x = t_y(0); + t2d->y.y = t_y(1); +} + +//----------------------------------------------- + +void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) +{ + glBegin(primitive); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat gradient_2d( arma::mat X, int order=1 ) +{ + mat df = diff(X, 1, 1); + mat db = fliplr( -diff(fliplr(X), 1, 1) ); + mat d = (df+db)/2; + d = join_horiz(zeros(2,1), d); + d.col(0) = df.col(0); + d.col(d.n_cols-1) = db.col(db.n_cols-1); + if(order>1) + return gradient_2d(d, order-1); + return d; +} + +//----------------------------------------------- + +void plot( float x, float y, float w, float h, const vec& v ) +{ + float v_min = v.min(); + float v_max = v.max(); + float inc = w / v.n_rows; + glBegin(GL_LINE_STRIP); + for (int i=0; i < v.n_rows; i++) + { + glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); + } + glEnd(); +} + +//----------------------------------------------- + +void drawGauss(ui::Trans2d& t2d, const window_size_t& window_size) +{ + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + + vec mu = ui2fb(vec({t2d.pos.x, t2d.pos.y}), window_size); + + arma::mat pts = basis * circ + arma::repmat(mu, 1, 35); + + glBegin(GL_TRIANGLE_FAN); + glVertex2f(mu(0), mu(1)); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +int main(int argc, char **argv){ + + arma_rng::set_seed_random(); + + //--------------- Setup parameters --------------- + + double dt = 0.01; + int order = 4; + + int m = 5; // Number of targets + double globScale = 0.0001; // global scale, avoids numerical issues in batch method + double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) + + float d=10.1; // maximum displacement, used to compute R diagonal + float stroke_duration=0.3; // duration of a stroke + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + // Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Batch MPC", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + FILE* eps_file = NULL; + bool saving_eps = false; + + // Covariances + mat Mu; + cube Sigma; + + // Gaussian widgets + std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // At the very first frame: random initialisation of the gaussians (taking 4K + // screens into account) + if (first && (window_size.fb_width > 0)) { + + Mu = arma::randu(2, m); + Mu.row(0) = Mu.row(0) * (window_size.fb_width - 200) + 100; + Mu.row(1) = Mu.row(1) * (window_size.fb_height - 200) + 100; + + randomCovariances( + &Sigma, Mu, + arma::vec({ 50 * (float) window_size.fb_width / window_size.win_width, + 50 * (float) window_size.fb_height / window_size.win_height + }), + false, 0.0, 0.8 + ); + + for( int i = 0; i < m; i++ ) + gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i), window_size); + } + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + if (saving_eps) + { + eps_file = fopen("out.eps", "wb"); + gl2psBeginPage("grab", "gl2psTestSimple", NULL, GL2PS_EPS, GL2PS_SIMPLE_SORT, + GL2PS_DRAW_BACKGROUND | GL2PS_USE_CURRENT_VIEWPORT, + GL_RGBA, 0, NULL, 0, 0, 0, 0, eps_file, "out.eps"); + } + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + + setOrtho(window_size.fb_width, window_size.fb_height); + + //Model rendering + glPushMatrix(); + + // Gauss UI + ui::begin("Gaussian"); + arma::vec mu; + arma::mat Sigm; + + for( int i = 0; i < m; i++ ) + { + t2ds[i] = ui::affineSimple(i, t2ds[i]); + trans2d_to_gauss(&mu, &Sigm, t2ds[i], window_size); + Mu.col(i) = mu; + Sigma.slice(i) = Sigm; + } + ui::end(); + + // Parameters window + int winw = 400; + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - winw, 2)); + ImGui::Begin("Params", NULL, ImVec2(winw, 86), 0.5f, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + + if(ImGui::Button("Save EPS")) + saving_eps = true; + + ImGui::SliderInt("Order", &order, 2, 7); + ImGui::SliderFloat("Max Displacement", &d, 0.1, 100.); + ImGui::End(); + + // Recompute LQR + int dim = 2; + double duration = stroke_duration * m; + int n = (int)(duration/dt); + int cDim = dim * order; + + // system matrices + mat A, B; + makeIntegratorChain(&A, &B, order); + discretizeSystem(&A, &B, A, B, dt); + // make bi-variate + A = kron(A, eye(dim, dim)); + B = kron( B, eye(dim, dim) ); + + // reference + mat Q, MuQ; + stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + MuQ *= globScale; + Q /= globScale*globScale; + + // r based on oscillatory movement displacement + double r = SHM_r(d*globScale, stroke_duration, order); + mat R = kron( eye(n-1, n-1), + eye(dim, dim) * r + ); + + //////////////////////////////////// + // Batch LQR + + // Sx and Su matrices for batch LQR + mat Su = zeros(cDim*n, dim*(n-1)); + mat Sx = kron( ones(n,1), + eye(dim*order, dim*order) + ); + mat M = B; + for( int i = 1; i < n; i++ ) + { + Sx.rows( i*cDim, n*cDim-1 ) = + Sx.rows( i*cDim, n*cDim-1 ) * A; + Su.submat( i*cDim, 0, + (i+1)*cDim-1, i*dim-1 ) = M; + M = join_horiz( A*M.cols(0, dim-1), M ); + } + + arma::vec x0 = MuQ.col(0); + + // Flatten Mu's + mat Xi_hat = reshape(MuQ, cDim*n, 1); + + mat SuInvSigmaQ = Su.t()*Q; + + mat Rq, rq; + + Rq = SuInvSigmaQ*Su + R; + rq = SuInvSigmaQ*(Xi_hat - Sx*x0); + + // least squares solution + vec u = solve(Rq,rq); + mat Y = reshape( Sx*x0 + Su*u, cDim, n ); + mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; + + ////////////////////////////////////// + + glEnable( GL_BLEND ); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // draw gaussians + glColor4f(0.0, 0.5f, 1.0f, 0.2f); + for (int i = 0; i < m; i++) + drawGauss(t2ds[i], window_size); + + // draw motor plan + glColor3f(0.5,0.5,0.5); + draw(Mu); + + // draw trajectory + glColor3f(0, 0, 1); + draw(Xi); + + // plot derivatives magnitude + int plot_width = 200 * window_size.fb_width / window_size.win_width; + int plot_height = 100 * window_size.fb_height / window_size.win_height; + int plot_y = window_size.fb_height - 25 * window_size.fb_height / window_size.win_height; + + glColor3f(1,0,0); + mat dx = gradient_2d(Xi, 1); + vec speed = sqrt(sum(dx%dx, 0)).t(); + plot(0, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(10, window_size.win_height - 25), "velocity magnitude", + ImVec4(1,0,0,1)); + ui::end(); + + glColor3f(0,0,1); + dx = gradient_2d(Xi, 2); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(200 + 10, window_size.win_height - 25), "acceleration magnitude", + ImVec4(0,0,1,1)); + ui::end(); + + glColor3f(0,0.5,0); + dx = gradient_2d(Xi, 3); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(2 * plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(400 + 10, window_size.win_height - 25), "jerk magnitude", + ImVec4(0,0.5,0,1)); + ui::end(); + + glPopMatrix(); + + // Render UI + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // save eps + if(eps_file) + { + glFlush(); + gl2psEndPage(); + fclose(eps_file); + eps_file=NULL; + saving_eps=false; + } + + glfwSwapBuffers(window); + + //Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_MPC_batch_01.cpp b/src/demo_MPC_batch_01.cpp deleted file mode 100644 index 7c110b8..0000000 --- a/src/demo_MPC_batch_01.cpp +++ /dev/null @@ -1,344 +0,0 @@ -/* - * demo_MPC_batch_01.cpp - * - * Interactive MPC demo, with batch LQT and repulsive field test - * - * Fabien Crépon, Sylvain Calinon, 2017 - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <stdio.h> -#include <GLFW/glfw3.h> -#include "mpc_utils.h" - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -#include "gl2ps.h" - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int factorial(int n){ - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d) -{ - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - *Sigma = basis * basis.t(); - *mu = arma::vec({t2d.pos.x, t2d.pos.y}); -} - -void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma) -{ - t2d->pos.x = mu(0); - t2d->pos.y = mu(1); - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, Sigma); - arma::mat VD = V*diagmat(sqrt(d)); - t2d->x.x = VD.col(0)(0); - t2d->x.y = VD.col(0)(1); - t2d->y.x = VD.col(1)(0); - t2d->y.y = VD.col(1)(1); -} - -void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) -{ - glBegin(primitive); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat gradient_2d( arma::mat X, int order=1 ) -{ - mat df = diff(X, 1, 1); - mat db = fliplr( -diff(fliplr(X), 1, 1) ); - mat d = (df+db)/2; - d = join_horiz(zeros(2,1), d); - d.col(0) = df.col(0); - d.col(d.n_cols-1) = db.col(db.n_cols-1); - if(order>1) - return gradient_2d(d, order-1); - return d; -} - -void plot( float x, float y, float w, float h, const vec& v ) -{ - float v_min = v.min(); - float v_max = v.max(); - float inc = w / v.n_rows; - glBegin(GL_LINE_STRIP); - for (int i=0; i < v.n_rows; i++) - { - glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); - } - glEnd(); -} - -void drawGauss( ui::Trans2d& t2d ) -{ - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - arma::mat pts = basis*circ + arma::repmat(vec({t2d.pos.x, t2d.pos.y}), 1, 35); - - glBegin(GL_TRIANGLE_FAN); - glVertex2f(t2d.pos.x, t2d.pos.y); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -int main(int argc, char **argv){ - - arma_rng::set_seed_random(); - - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- - int w = 800; - int h = 600; - - double dt = 0.01; - int order = 4; - - int m = 5; // Number of targets - double globScale = 0.0001; // global scale, avoids numerical issues in batch method - double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) - - float d=10.1; // maximum displacement, used to compute R diagonal - float stroke_duration=0.3; // duration of a stroke - - // Gui settings - int plot_deriv = 1; - - // targets - arma::mat V = arma::randu(2, m); - V.row(0) *= w; - V.row(1) *= h; - - // Covariances - mat Mu = V; - cube Sigma; - randomCovariances(&Sigma, Mu, arma::vec({50.,50.}), false, 0.0, 0.8); - - // Gaussians - std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); - for( int i = 0; i < m; i++ ) - gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i)); - - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(w, h, "Demo Batch MPC", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - FILE * eps_file = NULL; - bool saving_eps = false; - - while (!glfwWindowShouldClose(window)) { - w = ImGui::GetIO().DisplaySize.x; - h = ImGui::GetIO().DisplaySize.y; - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - if(saving_eps) - { - eps_file = fopen("out.eps", "wb"); - gl2psBeginPage("grab", "gl2psTestSimple", NULL, GL2PS_EPS, GL2PS_SIMPLE_SORT, - GL2PS_DRAW_BACKGROUND | GL2PS_USE_CURRENT_VIEWPORT, - GL_RGBA, 0, NULL, 0, 0, 0, 0, eps_file, "out.eps"); - } - - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //Model rendering - glPushMatrix(); - - // Gauss UI - ui::begin("Gaussian"); - arma::vec mu; - arma::mat Sigm; - - for( int i = 0; i < m; i++ ) - { - t2ds[i] = ui::affineSimple(i, t2ds[i]); - trans2d_to_gauss(&mu, &Sigm, t2ds[i]); - Mu.col(i) = mu; - Sigma.slice(i) = Sigm; - } - ui::end(); - - // Slider window - int winw = 250; - ImGui::SetNextWindowPos(ImVec2(w-winw,2)); - ImGui::Begin("Params", NULL, ImVec2(winw,300), 0.5f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - if(ImGui::Button("Save EPS")) - { - saving_eps = true; - } - ImGui::SliderInt("Order", &order, 2, 7); - ImGui::SliderFloat("Max Displacement", &d, 0.1, 100.); - ImGui::SliderInt("Plot deriv", &plot_deriv, 1, 3); - ImGui::End(); - - // Recompute LQR - int dim = 2; - double duration = stroke_duration * m; - int n = (int)(duration/dt); - int cDim = dim * order; - - // system matrices - mat A, B; - makeIntegratorChain(&A, &B, order); - discretizeSystem(&A, &B, A, B, dt); - // make bi-variate - A = kron(A, eye(dim, dim)); - B = kron( B, eye(dim, dim) ); - - // reference - mat Q, MuQ; - stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - MuQ *= globScale; - Q /= globScale*globScale; - - // r based on oscillatory movement displacement - double r = SHM_r(d*globScale, stroke_duration, order); - mat R = kron( eye(n-1, n-1), - eye(dim, dim) * r ); - - //////////////////////////////////// - // Batch LQR - - // Sx and Su matrices for batch LQR - mat Su = zeros(cDim*n, dim*(n-1)); - mat Sx = kron( ones(n,1), - eye(dim*order, dim*order)); - mat M = B; - for( int i = 1; i < n; i++ ) - { - Sx.rows( i*cDim, n*cDim-1 ) = - Sx.rows( i*cDim, n*cDim-1 ) * A; - Su.submat( i*cDim, 0, - (i+1)*cDim-1, i*dim-1 ) = M; - M = join_horiz( A*M.cols(0, dim-1), M ); - } - - arma::vec x0 = MuQ.col(0); - - // Flatten Mu's - mat Xi_hat = reshape(MuQ, cDim*n, 1); - - mat SuInvSigmaQ = Su.t()*Q; - - mat Rq, rq; - - Rq = SuInvSigmaQ*Su + R; - rq = SuInvSigmaQ*(Xi_hat - Sx*x0); - - // least squares solution - vec u = solve(Rq,rq); - mat Y = reshape( Sx*x0 + Su*u, cDim, n ); - mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; - - ////////////////////////////////////// - - glEnable( GL_BLEND ); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // draw gaussians - glColor4f(0.0, 0.5f, 1.0f, 0.2f); - for( int i = 0; i < m; i++ ) - { - drawGauss(t2ds[i]); - } - - // draw motor plan - glColor3f(0.5,0.5,0.5); - draw(Mu); - - // draw trajectory - glColor3f(0, 0, 0); - draw(Xi); - - // plot derivatives magnitude - glColor3f(1,0,0); - mat dx = gradient_2d(Xi, plot_deriv); //, 1, 1); - vec speed = sqrt(sum(dx%dx, 0)).t(); - plot(10, h, 200, 100, speed); - - ui::begin("Text"); - const char* sderiv[] = - { - "velocity", - "acceleration", - "jerk" - }; - ui::textf(ImVec2(200+10, h-20), "%s magnitude", sderiv[plot_deriv-1]); //sderiv[plot_deriv-1]); - ui::end(); - - glPopMatrix(); - - // Render UI - ImGui::Render(); - - // save eps - if(eps_file) - { - glFlush(); - gl2psEndPage(); - fclose(eps_file); - eps_file=NULL; - saving_eps=false; - } - - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_MPC_iterative01.cpp b/src/demo_MPC_iterative01.cpp new file mode 100644 index 0000000..51b841a --- /dev/null +++ b/src/demo_MPC_iterative01.cpp @@ -0,0 +1,449 @@ +/* + * demo_MPC_iterative01.cpp + * + * Interactive MPC demo, with iterative LQT + * + * Fabien Crépon, Sylvain Calinon, 2017 + */ + + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +#include <mpc_utils.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + +//------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space +// +// UI coordinates range from (0, 0) to (win_width, win_height) +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +//------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width; + result(1) = coords(1) * (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space +// +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +// UI coordinates range from (0, 0) to (win_width, win_height) +//------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width; + result(1) = coords(1) * (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + +//----------------------------------------------- + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +void setOrtho( float w, float h ) +{ + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, 0+w, 0+h, 0, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); +} + +//----------------------------------------------- + +void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d, + const window_size_t& window_size) +{ + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + *Sigma = basis * basis.t(); + *mu = ui2fb(arma::vec({t2d.pos.x, t2d.pos.y}), window_size); +} + +//----------------------------------------------- + +void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma, + const window_size_t& window_size) +{ + arma::vec ui_mu = fb2ui(mu, window_size); + + t2d->pos.x = ui_mu(0); + t2d->pos.y = ui_mu(1); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, Sigma); + arma::mat VD = V*diagmat(sqrt(d)); + + arma::vec t_x = fb2ui(arma::vec({VD.col(0)(0), VD.col(1)(0)}), window_size); + arma::vec t_y = fb2ui(arma::vec({VD.col(0)(1), VD.col(1)(1)}), window_size); + + t2d->x.x = t_x(0); + t2d->x.y = t_x(1); + t2d->y.x = t_y(0); + t2d->y.y = t_y(1); +} + +//----------------------------------------------- + +void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) +{ + glBegin(primitive); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat gradient_2d( arma::mat X, int order=1 ) +{ + mat df = diff(X, 1, 1); + mat db = fliplr( -diff(fliplr(X), 1, 1) ); + mat d = (df+db)/2; + d = join_horiz(zeros(2,1), d); + d.col(0) = df.col(0); + d.col(d.n_cols-1) = db.col(db.n_cols-1); + if(order>1) + return gradient_2d(d, order-1); + return d; +} + +//----------------------------------------------- + +void plot( float x, float y, float w, float h, const vec& v ) +{ + float v_min = v.min(); + float v_max = v.max(); + float inc = w / v.n_rows; + glBegin(GL_LINE_STRIP); + for (int i=0; i < v.n_rows; i++) + { + glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); + } + glEnd(); +} + +//----------------------------------------------- + +void drawGauss(ui::Trans2d& t2d, const window_size_t& window_size) +{ + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + + vec mu = ui2fb(vec({t2d.pos.x, t2d.pos.y}), window_size); + + arma::mat pts = basis * circ + arma::repmat(mu, 1, 35); + + glBegin(GL_TRIANGLE_FAN); + glVertex2f(mu(0), mu(1)); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +int main(int argc, char **argv){ + + arma_rng::set_seed_random(); + + //--------------- Setup parameters --------------- + + double dt = 0.01; + int order = 5; + + int m = 3; // Number of targets + double globScale = 0.001; // global scale, avoids numerical issues in batch method + double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) + + float d=0.1; // maximum displacement, used to compute R diagonal + float stroke_duration=0.3; // duration of a stroke + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Iterative MPC", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + //Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + // Covariances + mat Mu; + cube Sigma; + + // Gaussian widgets + std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // At the very first frame: random initialisation of the gaussians (taking 4K + // screens into account) + if (first && (window_size.fb_width > 0)) { + + Mu = arma::randu(2, m); + Mu.row(0) = Mu.row(0) * (window_size.fb_width - 200) + 100; + Mu.row(1) = Mu.row(1) * (window_size.fb_height - 200) + 100; + + randomCovariances( + &Sigma, Mu, + arma::vec({ 50 * (float) window_size.fb_width / window_size.win_width, + 50 * (float) window_size.fb_height / window_size.win_height + }), + false, 0.0, 0.8 + ); + + for( int i = 0; i < m; i++ ) + gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i), window_size); + } + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + + setOrtho(window_size.fb_width, window_size.fb_height); + + //Model rendering + glPushMatrix(); + + // Gauss UI + ui::begin("Gaussian"); + arma::vec mu; + arma::mat Sigm; + + for( int i = 0; i < m; i++ ) + { + t2ds[i] = ui::affineSimple(i, t2ds[i]); + trans2d_to_gauss(&mu, &Sigm, t2ds[i], window_size); + Mu.col(i) = mu; + Sigma.slice(i) = Sigm; + } + + ui::end(); + + // Parameters window + int winw = 400; + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - winw, 2)); + ImGui::Begin("Params", NULL, ImVec2(winw,60), 0.5f, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + ImGui::SliderInt("Order", &order, 2, 7); + ImGui::SliderFloat("Max Displacement", &d, 0.05, 5.); + ImGui::End(); + + // Recompute LQR + int dim = 2; + double duration = stroke_duration * m; + int n = (int)(duration/dt); + int cDim = dim * order; + + // system matrices + mat A, B; + makeIntegratorChain(&A, &B, order); + discretizeSystem(&A, &B, A, B, dt); + // make bi-variate + A = kron(A, eye(dim, dim)); + B = kron( B, eye(dim, dim) ); + + // reference + mat Q, MuQ, Q0, MuQ0; + stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + MuQ *= globScale; + Q /= globScale*globScale; + + // r based on oscillatory movement displacement + double r = SHM_r(d, stroke_duration, order); + + //////////////////////////////////// + // Iterative LQR + mat R = eye(dim, dim) * r; + + cube P = zeros(cDim, cDim, n); + int i = n-1; + P.slice(i) = Q.submat(span(i*cDim,i*cDim+cDim-1),span(i*cDim,i*cDim+cDim-1)); + + mat D = zeros(cDim, n); + // Riccati recursion + for( int i = n-2; i >=0; i-- ) + { + mat Qi = Q.submat(span(i*cDim,i*cDim+cDim-1),span(i*cDim,i*cDim+cDim-1)); + mat P2 = P.slice(i+1); + P.slice(i) = Qi - (A.t() * (P2 * B * inv(B.t() * P2 * B + R) * B.t() * P2 - P2 ) * A); + D.col(i) = (A.t() - A.t() * P2 * B * inv(B.t() * P2 * B + R) * B.t()) + * (P2 * (A * MuQ.col(i) - MuQ.col(i+1)) + D.col(i+1)); + } + + // compute trajectory + arma::vec x0 = MuQ.col(0); + mat Y = zeros(cDim, n); + vec x = x0; + + for( int i = 0; i < n; i++ ) + { + Y.col(i) = x; + mat p = P.slice(i); + vec mu = MuQ.col(i); + + mat G = inv( B.t() * p * B + R ) * B.t(); + + // feedback gain + mat K = G * p * A; + // Feedforward term + mat M = -G * (p * (A * mu - mu) + D.col(i)); + // Control command (highest order derivative of system) + vec u = K * (mu - x) + M; + // New state + x = A*x + B*u; + } + + mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; + + ////////////////////////////////////// + + glEnable( GL_BLEND ); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // draw gaussians + glColor4f(0.0, 0.5f, 1.0f, 0.2f); + for( int i = 0; i < m; i++ ) + drawGauss(t2ds[i], window_size); + + // draw trajectory + glColor3f(0, 0, 1); + draw(Xi); + + // plot derivatives magnitude + int plot_width = 200 * window_size.fb_width / window_size.win_width; + int plot_height = 100 * window_size.fb_height / window_size.win_height; + int plot_y = window_size.fb_height - 25 * window_size.fb_height / window_size.win_height; + + glColor3f(1,0,0); + mat dx = gradient_2d(Xi, 1); + vec speed = sqrt(sum(dx%dx, 0)).t(); + plot(0, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(10, window_size.win_height - 25), "velocity magnitude", + ImVec4(1,0,0,1)); + ui::end(); + + glColor3f(0,0,1); + dx = gradient_2d(Xi, 2); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(200 + 10, window_size.win_height - 25), "acceleration magnitude", + ImVec4(0,0,1,1)); + ui::end(); + + glColor3f(0,0.5,0); + dx = gradient_2d(Xi, 3); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(2 * plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(400 + 10, window_size.win_height - 25), "jerk magnitude", + ImVec4(0,0.5,0,1)); + ui::end(); + + glPopMatrix(); + + // Render UI + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + glfwSwapBuffers(window); + + //Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_MPC_iterative_01.cpp b/src/demo_MPC_iterative_01.cpp deleted file mode 100644 index 277d004..0000000 --- a/src/demo_MPC_iterative_01.cpp +++ /dev/null @@ -1,322 +0,0 @@ -/* - * demo_MPC_iterative_01.cpp - * - * Interactive MPC demo, with iterative LQT - * - * Fabien Crépon, Sylvain Calinon, 2017 - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <stdio.h> -#include <GLFW/glfw3.h> -#include "mpc_utils.h" - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int factorial(int n){ - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d) -{ - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - *Sigma = basis * basis.t(); - *mu = arma::vec({t2d.pos.x, t2d.pos.y}); -} - -void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma) -{ - t2d->pos.x = mu(0); - t2d->pos.y = mu(1); - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, Sigma); - arma::mat VD = V*diagmat(sqrt(d)); - t2d->x.x = VD.col(0)(0); - t2d->x.y = VD.col(0)(1); - t2d->y.x = VD.col(1)(0); - t2d->y.y = VD.col(1)(1); -} - -void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) -{ - glBegin(primitive); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat gradient_2d( arma::mat X, int order=1 ) -{ - mat df = diff(X, 1, 1); - mat db = fliplr( -diff(fliplr(X), 1, 1) ); - mat d = (df+db)/2; - d = join_horiz(zeros(2,1), d); - d.col(0) = df.col(0); - d.col(d.n_cols-1) = db.col(db.n_cols-1); - if(order>1) - return gradient_2d(d, order-1); - return d; -} - -void plot( float x, float y, float w, float h, const vec& v ) -{ - float v_min = v.min(); - float v_max = v.max(); - float inc = w / v.n_rows; - glBegin(GL_LINE_STRIP); - for (int i=0; i < v.n_rows; i++) - { - glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); - } - glEnd(); -} - -void drawGauss( ui::Trans2d& t2d ) -{ - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - arma::mat pts = basis*circ + arma::repmat(vec({t2d.pos.x, t2d.pos.y}), 1, 35); - - glBegin(GL_TRIANGLE_FAN); - glVertex2f(t2d.pos.x, t2d.pos.y); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -int main(int argc, char **argv){ - - arma_rng::set_seed_random(); - - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- - int w = 800; - int h = 600; - - double dt = 0.01; - int order = 5; - - int m = 3; // Number of targets - double globScale = 0.001; // global scale, avoids numerical issues in batch method - double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) - - float d=0.1; // maximum displacement, used to compute R diagonal - float stroke_duration=0.3; // duration of a stroke - - // Gui settings - int plot_deriv = 1; - - // targets - arma::mat V = arma::randu(2, m); - V.row(0) *= w; - V.row(1) *= h; - - // Covariances - mat Mu = V; - cube Sigma; - randomCovariances(&Sigma, Mu, arma::vec({120.,50.}), false, 0.0, 0.8); - - // Gaussians - std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); - for( int i = 0; i < m; i++ ) - gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i)); - - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(w, h, "Demo Iterative MPC", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - while (!glfwWindowShouldClose(window)) { - w = ImGui::GetIO().DisplaySize.x; - h = ImGui::GetIO().DisplaySize.y; - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //Model rendering - glPushMatrix(); - - // Gauss UI - ui::begin("Gaussian"); - arma::vec mu; - arma::mat Sigm; - - for( int i = 0; i < m; i++ ) - { - t2ds[i] = ui::affineSimple(i, t2ds[i]); - trans2d_to_gauss(&mu, &Sigm, t2ds[i]); - Mu.col(i) = mu; - Sigma.slice(i) = Sigm; - } - - ui::end(); - - // Slider window - int winw = 250; - ImGui::SetNextWindowPos(ImVec2(w-winw,2)); - ImGui::Begin("Params", NULL, ImVec2(winw,300), 0.5f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - ImGui::SliderInt("Order", &order, 2, 7); - ImGui::SliderFloat("Max Displacement", &d, 0.05, 5.); - ImGui::SliderInt("Plot deriv", &plot_deriv, 1, 3); - ImGui::End(); - - // Recompute LQR - int dim = 2; - double duration = stroke_duration * m; - int n = (int)(duration/dt); - int cDim = dim * order; - - // system matrices - mat A, B; - makeIntegratorChain(&A, &B, order); - discretizeSystem(&A, &B, A, B, dt); - // make bi-variate - A = kron(A, eye(dim, dim)); - B = kron( B, eye(dim, dim) ); - - // reference - mat Q, MuQ, Q0, MuQ0; - stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - MuQ *= globScale; - Q /= globScale*globScale; - - // r based on oscillatory movement displacement - double r = SHM_r(d, stroke_duration, order); - - //////////////////////////////////// - // Iterative LQR - mat R = eye(dim, dim) * r; - - cube P = zeros(cDim, cDim, n); - int i = n-1; - P.slice(i) = Q.submat(span(i*cDim,i*cDim+cDim-1),span(i*cDim,i*cDim+cDim-1)); - - mat D = zeros(cDim, n); - // Riccati recursion - for( int i = n-2; i >=0; i-- ) - { - mat Qi = Q.submat(span(i*cDim,i*cDim+cDim-1),span(i*cDim,i*cDim+cDim-1)); - mat P2 = P.slice(i+1); - P.slice(i) = Qi - (A.t() * (P2 * B * inv(B.t() * P2 * B + R) * B.t() * P2 - P2 ) * A); - D.col(i) = (A.t() - A.t() * P2 * B * inv(B.t() * P2 * B + R) * B.t()) - * (P2 * (A * MuQ.col(i) - MuQ.col(i+1)) + D.col(i+1)); - } - - // compute trajectory - arma::vec x0 = MuQ.col(0); - mat Y = zeros(cDim, n); - vec x = x0; - - for( int i = 0; i < n; i++ ) - { - Y.col(i) = x; - mat p = P.slice(i); - vec mu = MuQ.col(i); - - mat G = inv( B.t() * p * B + R ) * B.t(); - - // feedback gain - mat K = G * p * A; - // Feedforward term - mat M = -G * (p * (A * mu - mu) + D.col(i)); - // Control command (highest order derivative of system) - vec u = K * (mu - x) + M; - // New state - x = A*x + B*u; - } - - mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; - - ////////////////////////////////////// - - glEnable( GL_BLEND ); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // draw gaussians - glColor4f(0.0, 0.5f, 1.0f, 0.2f); - for( int i = 0; i < m; i++ ) - { - drawGauss(t2ds[i]); - } - - // draw trajectory - glColor3f(0, 0, 0); - draw(Xi); - - // plot derivatives magnitude - glColor3f(1,0,0); - mat dx = gradient_2d(Xi, plot_deriv); //, 1, 1); - vec speed = sqrt(sum(dx%dx, 0)).t(); - plot(10, h, 200, 100, speed); - - ui::begin("Text"); - const char* sderiv[] = - { - "velocity", - "acceleration", - "jerk" - }; - ui::textf(ImVec2(200+10, h-20), "%s magnitude", sderiv[plot_deriv-1]); //sderiv[plot_deriv-1]); - ui::end(); - - glPopMatrix(); - - // Render UI - ImGui::Render(); - - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_MPC_semitied01.cpp b/src/demo_MPC_semitied01.cpp new file mode 100644 index 0000000..610f538 --- /dev/null +++ b/src/demo_MPC_semitied01.cpp @@ -0,0 +1,522 @@ +/* + * demo_MPC_semitied01.cpp + * + * Interactive MPC demo, demonstrates a GUI to edit semi-tied covariances (2d) + * + * Fabien Crépon, Sylvain Calinon, 2017 + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +#include <mpc_utils.h> +#include <gl2ps.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + +//------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space +// +// UI coordinates range from (0, 0) to (win_width, win_height) +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +//------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width; + result(1) = coords(1) * (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space +// +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +// UI coordinates range from (0, 0) to (win_width, win_height) +//------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width; + result(1) = coords(1) * (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + +//----------------------------------------------- + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +void setOrtho( float w, float h ) +{ + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, 0+w, 0+h, 0, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); +} + +//----------------------------------------------- + +void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma, + const window_size_t& window_size) +{ + arma::vec ui_mu = fb2ui(mu, window_size); + + t2d->pos.x = ui_mu(0); + t2d->pos.y = ui_mu(1); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, Sigma); + arma::mat VD = V*diagmat(sqrt(d)); + + arma::vec t_x = fb2ui(arma::vec({VD.col(0)(0), VD.col(1)(0)}), window_size); + arma::vec t_y = fb2ui(arma::vec({VD.col(0)(1), VD.col(1)(1)}), window_size); + + t2d->x.x = t_x(0); + t2d->x.y = t_x(1); + t2d->y.x = t_y(0); + t2d->y.y = t_y(1); +} + +//----------------------------------------------- + +void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) +{ + glBegin(primitive); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat gradient_2d( arma::mat X, int order=1 ) +{ + mat df = diff(X, 1, 1); + mat db = fliplr( -diff(fliplr(X), 1, 1) ); + mat d = (df+db)/2; + d = join_horiz(zeros(2,1), d); + d.col(0) = df.col(0); + d.col(d.n_cols-1) = db.col(db.n_cols-1); + if(order>1) + return gradient_2d(d, order-1); + return d; +} + +//----------------------------------------------- + +void plot( float x, float y, float w, float h, const vec& v ) +{ + float v_min = v.min(); + float v_max = v.max(); + float inc = w / v.n_rows; + glBegin(GL_LINE_STRIP); + for (int i=0; i < v.n_rows; i++) + { + glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); + } + glEnd(); +} + +//----------------------------------------------- + +void drawGauss(ui::Trans2d& t2d, const window_size_t& window_size) +{ + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + + vec mu = ui2fb(vec({t2d.pos.x, t2d.pos.y}), window_size); + + arma::mat pts = basis * circ + arma::repmat(mu, 1, 35); + + glBegin(GL_TRIANGLE_FAN); + glVertex2f(mu(0), mu(1)); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat semitiedBasis( const arma::vec& params ) +{ + float t1 = params[0]; + float t2 = params[1]; + return {{cos(t1), cos(t2)}, {sin(t1), sin(t2)}}; +} + +//----------------------------------------------- + +arma::mat semitiedSigma( const arma::vec& params ) +{ + float h = params[2]; + arma::mat H = semitiedBasis(params); + return H*H.t()*h*h; +} + +//----------------------------------------------- + +arma::cube semitiedCovariances( const arma::mat& Mu, const arma::vec& params ) +{ + int m = Mu.n_cols; + arma::cube Sigma = arma::zeros(2,2,m); + arma::mat sigm = semitiedSigma(params); + for( int i = 0; i < m; i++ ) + { + Sigma.slice(i) = sigm; + } + return Sigma; +} + +//----------------------------------------------- + +arma::vec semitiedWidget(int id, arma::vec params, const arma::vec& pos, + const window_size_t& window_size, float minLength=2.0, + float maxLength=500.0) +{ + float h = params[2] * (float) window_size.win_height / window_size.fb_height; + arma::vec theta = params.subvec(0,1); + for( int i = 0; i < 2; i++ ) + { + ImVec2 theta_length = ui::lengthHandle(id+i, ImVec2(theta[i], h), 0.0, pos, + ImVec2(-1000.0, minLength), + ImVec2(1000.0, maxLength) + ); + params[i] = theta_length.x; + h = theta_length.y; + } + + h = h * (float) window_size.fb_height / window_size.win_height; + + params[2] = h; + + // draw ellipse + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + arma::mat basis = semitiedBasis(params); + arma::mat pts = basis*circ*h + arma::repmat(ui2fb(pos, window_size), 1, 35); + glColor4f(1.0,0.0,0.0,1.0); + draw(pts); + return params; +} + +//----------------------------------------------- + +int main(int argc, char **argv){ + + arma_rng::set_seed_random(); + + //--------------- Setup parameters --------------- + + double dt = 0.01; + int order = 4; + + int m = 4; // Number of targets + double globScale = 0.001; // global scale, avoids numerical issues in batch method + double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) + + float d=0.05; // maximum displacement, used to compute R diagonal + float stroke_duration=0.3; // duration of a stroke + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Semitied MPC", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + //Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + // Targets + mat Mu; + + // semi tied parameters (theta1, theta2, h) + arma::vec semitied_params; + + FILE* eps_file = NULL; + bool saving_eps = false; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // At the very first frame: random initialisation of the gaussians (taking 4K + // screens into account) + if (first && (window_size.fb_width > 0)) { + + Mu = arma::randu(2, m); + Mu.row(0) = Mu.row(0) * (window_size.fb_width - 200) + 100; + Mu.row(1) = Mu.row(1) * (window_size.fb_height - 200) + 100; + + semitied_params = { + 0.0, + datum::pi/2, + 100.0 * (float) window_size.fb_height / window_size.win_height + }; + } + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + if(saving_eps) + { + eps_file = fopen("out.eps", "wb"); + gl2psBeginPage("grab", "gl2psTestSimple", NULL, GL2PS_EPS, GL2PS_SIMPLE_SORT, + GL2PS_DRAW_BACKGROUND | GL2PS_USE_CURRENT_VIEWPORT, + GL_RGBA, 0, NULL, 0, 0, 0, 0, eps_file, "out.eps"); + } + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + + setOrtho(window_size.fb_width, window_size.fb_height); + + //Model rendering + glPushMatrix(); + + // Gauss UI + ui::begin("Gaussian"); + arma::vec mu; + arma::mat Sigm; + + // Drag only target means + for( int i = 0; i < m; i++ ) + Mu.col(i) = ui2fb((arma::vec) ui::dragger(i, fb2ui(Mu.col(i), window_size)), window_size); + + // manipulate semitied covariance + semitied_params = semitiedWidget(m, semitied_params, {100, 100}, window_size); + // Setup cov states + cube Sigma = semitiedCovariances(Mu, semitied_params); + + std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); + for( int i = 0; i < m; i++ ) + gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i), window_size); + + ui::end(); + + + // Parameters window + int winw = 360; + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - winw, 2)); + ImGui::Begin("Params", NULL, ImVec2(winw,84), 0.5f, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + + if(ImGui::Button("Save EPS")) + saving_eps = true; + + ImGui::SliderInt("Order", &order, 2, 7); + ImGui::SliderFloat("Max Displacement", &d, 0.01, 5.); + ImGui::End(); + + + // Recompute LQR + int dim = 2; + double duration = stroke_duration * m; + int n = (int)(duration/dt); + int cDim = dim * order; + + // system matrices + mat A, B; + makeIntegratorChain(&A, &B, order); + discretizeSystem(&A, &B, A, B, dt); + // make bi-variate + A = kron(A, eye(dim, dim)); + B = kron( B, eye(dim, dim) ); + + // reference + mat Q, MuQ; + stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + MuQ *= globScale; + Q /= globScale*globScale; + + // r based on oscillatory movement displacement + double r = SHM_r(d, stroke_duration, order); + mat R = kron( eye(n-1, n-1), + eye(dim, dim) * r ); + + //////////////////////////////////// + // Batch LQR + + // Sx and Su matrices for batch LQR + mat Su = zeros(cDim*n, dim*(n-1)); + mat Sx = kron( ones(n,1), + eye(dim*order, dim*order)); + mat M = B; + for( int i = 1; i < n; i++ ) + { + Sx.rows( i*cDim, n*cDim-1 ) = + Sx.rows( i*cDim, n*cDim-1 ) * A; + Su.submat( i*cDim, 0, + (i+1)*cDim-1, i*dim-1 ) = M; + M = join_horiz( A*M.cols(0, dim-1), M ); + } + + arma::vec x0 = MuQ.col(0); + + // Flatten Mu's + mat Xi_hat = reshape(MuQ, cDim*n, 1); + mat SuInvSigmaQ = Su.t()*Q; + + mat Rq, rq; + + Rq = SuInvSigmaQ*Su + R; + rq = SuInvSigmaQ*(Xi_hat - Sx*x0); + + // least squares solution + vec u = solve(Rq,rq); + mat Y = reshape( Sx*x0 + Su*u, cDim, n ); + mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; + + ////////////////////////////////////// + + glEnable( GL_BLEND ); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // draw gaussians + glColor4f(0.0, 0.5f, 1.0f, 0.2f); + for( int i = 0; i < m; i++ ) + drawGauss(t2ds[i], window_size); + + // draw trajectory + glColor3f(0, 0, 1); + draw(Xi); + + // plot derivatives magnitude + int plot_width = 200 * window_size.fb_width / window_size.win_width; + int plot_height = 100 * window_size.fb_height / window_size.win_height; + int plot_y = window_size.fb_height - 25 * window_size.fb_height / window_size.win_height; + + glColor3f(1,0,0); + mat dx = gradient_2d(Xi, 1); + vec speed = sqrt(sum(dx%dx, 0)).t(); + plot(0, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(10, window_size.win_height - 25), "velocity magnitude", + ImVec4(1,0,0,1)); + ui::end(); + + glColor3f(0,0,1); + dx = gradient_2d(Xi, 2); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(200 + 10, window_size.win_height - 25), "acceleration magnitude", + ImVec4(0,0,1,1)); + ui::end(); + + glColor3f(0,0.5,0); + dx = gradient_2d(Xi, 3); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(2 * plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(400 + 10, window_size.win_height - 25), "jerk magnitude", + ImVec4(0,0.5,0,1)); + ui::end(); + + glPopMatrix(); + + // Render UI + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + if(eps_file) + { + glFlush(); + gl2psEndPage(); + fclose(eps_file); + eps_file=NULL; + saving_eps=false; + } + + glfwSwapBuffers(window); + + //Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_MPC_semitied_01.cpp b/src/demo_MPC_semitied_01.cpp deleted file mode 100644 index 0625825..0000000 --- a/src/demo_MPC_semitied_01.cpp +++ /dev/null @@ -1,402 +0,0 @@ -/* - * demo_MPC_batch_01.cpp - * - * Interactive MPC demo, demonstrates a GUI to edit semi-tied covariances (2d) - * - * Fabien Crépon, Sylvain Calinon, 2017 - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <stdio.h> -#include <GLFW/glfw3.h> -#include "mpc_utils.h" - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -#include "gl2ps.h" - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int factorial(int n){ - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d) -{ - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - *Sigma = basis * basis.t(); - *mu = arma::vec({t2d.pos.x, t2d.pos.y}); -} - -void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma) -{ - t2d->pos.x = mu(0); - t2d->pos.y = mu(1); - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, Sigma); - arma::mat VD = V*diagmat(sqrt(d)); - t2d->x.x = VD.col(0)(0); - t2d->x.y = VD.col(0)(1); - t2d->y.x = VD.col(1)(0); - t2d->y.y = VD.col(1)(1); -} - -void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) -{ - glBegin(primitive); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat gradient_2d( arma::mat X, int order=1 ) -{ - mat df = diff(X, 1, 1); - mat db = fliplr( -diff(fliplr(X), 1, 1) ); - mat d = (df+db)/2; - d = join_horiz(zeros(2,1), d); - d.col(0) = df.col(0); - d.col(d.n_cols-1) = db.col(db.n_cols-1); - if(order>1) - return gradient_2d(d, order-1); - return d; -} - -void plot( float x, float y, float w, float h, const vec& v ) -{ - float v_min = v.min(); - float v_max = v.max(); - float inc = w / v.n_rows; - glBegin(GL_LINE_STRIP); - for (int i=0; i < v.n_rows; i++) - { - glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); - } - glEnd(); -} - -void drawGauss( ui::Trans2d& t2d ) -{ - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - arma::mat pts = basis*circ + arma::repmat(vec({t2d.pos.x, t2d.pos.y}), 1, 35); - - glBegin(GL_TRIANGLE_FAN); - glVertex2f(t2d.pos.x, t2d.pos.y); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat semitiedBasis( const arma::vec& params ) -{ - float t1 = params[0]; - float t2 = params[1]; - return {{cos(t1), cos(t2)}, {sin(t1), sin(t2)}}; -} - -arma::mat semitiedSigma( const arma::vec& params ) -{ - float h = params[2]; - arma::mat H = semitiedBasis(params); - return H*H.t()*h*h; -} - -arma::cube semitiedCovariances( const arma::mat& Mu, const arma::vec& params ) -{ - int m = Mu.n_cols; - arma::cube Sigma = arma::zeros(2,2,m); - arma::mat sigm = semitiedSigma(params); - for( int i = 0; i < m; i++ ) - { - Sigma.slice(i) = sigm; - } - return Sigma; -} - -arma::vec semitiedWidget(int id, arma::vec params, const arma::vec& pos, float minLength=2.0, float maxLength=500.0) -{ - float h = params[2]; - arma::vec theta = params.subvec(0,1); - for( int i = 0; i < 2; i++ ) - { - ImVec2 theta_length = ui::lengthHandle(id+i, ImVec2(theta[i], h), 0.0, pos, ImVec2(-1000.0, minLength), ImVec2(1000.0, maxLength)); - params[i] = theta_length.x; - h = theta_length.y; - } - params[2] = h; - - // draw ellipse - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = semitiedBasis(params); - arma::mat pts = basis*circ*h + arma::repmat(pos, 1, 35); - glColor4f(1.0,0.0,0.0,1.0); - draw(pts); - return params; -} - - - -int main(int argc, char **argv){ - - arma_rng::set_seed_random(); - - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- - int w = 800; - int h = 600; - - double dt = 0.01; - int order = 4; - - int m = 4; // Number of targets - double globScale = 0.001; // global scale, avoids numerical issues in batch method - double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) - - float d=0.05; // maximum displacement, used to compute R diagonal - float stroke_duration=0.3; // duration of a stroke - float covscale = 1.0; // hack, field covariance scaling factor - int fieldDeriv=1; // derivative used for additional field - // Gui settings - int plot_deriv = 1; - bool useField = true; - - // targets - arma::mat Mu = arma::randu(2, m); - Mu.row(0) *= w; - Mu.row(1) *= h; - // semi tied parameters (theta1, theta2, h) - arma::vec semitied_params = {0.0, PI/2, 100.0}; - - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(w, h, "Demo Batch MPC", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - float theta = 0.0; - float vv = 1.0; - - FILE * eps_file = NULL; - bool saving_eps = false; - - while (!glfwWindowShouldClose(window)) { - w = ImGui::GetIO().DisplaySize.x; - h = ImGui::GetIO().DisplaySize.y; - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - if(saving_eps) - { - eps_file = fopen("out.eps", "wb"); - gl2psBeginPage("grab", "gl2psTestSimple", NULL, GL2PS_EPS, GL2PS_SIMPLE_SORT, - GL2PS_DRAW_BACKGROUND | GL2PS_USE_CURRENT_VIEWPORT, - GL_RGBA, 0, NULL, 0, 0, 0, 0, eps_file, "out.eps"); - } - - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //Model rendering - glPushMatrix(); - - // Gauss UI - ui::begin("Gaussian"); - arma::vec mu; - arma::mat Sigm; - - // Drag only target means - for( int i = 0; i < m; i++ ) - { - Mu.col(i) = (arma::vec)ui::dragger(i, Mu.col(i)); - } - - // manipulate semitied covariance - semitied_params = semitiedWidget(m, semitied_params, {200, 300}); - // Setup cov states - cube Sigma = semitiedCovariances(Mu, semitied_params); - - std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); - for( int i = 0; i < m; i++ ) - gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i)); - - ui::end(); - - - - // Slider window - int winw = 250; - ImGui::SetNextWindowPos(ImVec2(w-winw,2)); - ImGui::Begin("Params", NULL, ImVec2(winw,300), 0.5f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - if(ImGui::Button("Save EPS")) - { - saving_eps = true; - } - - ImGui::SliderInt("Order", &order, 2, 7); - ImGui::SliderFloat("Max Displacement", &d, 0.01, 5.); - ImGui::SliderFloat("Theta", &theta, -PI, PI); - ImGui::SliderInt("Plot deriv", &plot_deriv, 1, 3); - ImGui::End(); - - // Recompute LQR - int dim = 2; - double duration = stroke_duration * m; - int n = (int)(duration/dt); - int cDim = dim * order; - - // system matrices - mat A, B; - makeIntegratorChain(&A, &B, order); - discretizeSystem(&A, &B, A, B, dt); - // make bi-variate - A = kron(A, eye(dim, dim)); - B = kron( B, eye(dim, dim) ); - - // reference - mat Q, MuQ; - stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - MuQ *= globScale; - Q /= globScale*globScale; - - // r based on oscillatory movement displacement - double r = SHM_r(d, stroke_duration, order); - mat R = kron( eye(n-1, n-1), - eye(dim, dim) * r ); - - //////////////////////////////////// - // Batch LQR - - // Sx and Su matrices for batch LQR - mat Su = zeros(cDim*n, dim*(n-1)); - mat Sx = kron( ones(n,1), - eye(dim*order, dim*order)); - mat M = B; - for( int i = 1; i < n; i++ ) - { - Sx.rows( i*cDim, n*cDim-1 ) = - Sx.rows( i*cDim, n*cDim-1 ) * A; - Su.submat( i*cDim, 0, - (i+1)*cDim-1, i*dim-1 ) = M; - M = join_horiz( A*M.cols(0, dim-1), M ); - } - - arma::vec x0 = MuQ.col(0); - - // Flatten Mu's - mat Xi_hat = reshape(MuQ, cDim*n, 1); - mat SuInvSigmaQ = Su.t()*Q; - - mat Rq, rq; - - Rq = SuInvSigmaQ*Su + R; - rq = SuInvSigmaQ*(Xi_hat - Sx*x0); - - // least squares solution - vec u = solve(Rq,rq); - mat Y = reshape( Sx*x0 + Su*u, cDim, n ); - mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; - - ////////////////////////////////////// - - glEnable( GL_BLEND ); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // draw gaussians - glColor4f(0.0, 0.5f, 1.0f, 0.2f); - for( int i = 0; i < m; i++ ) - { - drawGauss(t2ds[i]); - } - - // draw trajectory - glColor3f(0, 0, 0); - draw(Xi); - - // plot derivatives magnitude - glColor3f(1,0,0); - mat dx = gradient_2d(Xi, plot_deriv); //, 1, 1); - vec speed = sqrt(sum(dx%dx, 0)).t(); - plot(10, h, 200, 100, speed); - - ui::begin("Text"); - const char* sderiv[] = - { - "velocity", - "acceleration", - "jerk" - }; - ui::textf(ImVec2(200+10, h-20), "%s magnitude", sderiv[plot_deriv-1]); //sderiv[plot_deriv-1]); - ui::end(); - - glPopMatrix(); - - // Render UI - ImGui::Render(); - - if(eps_file) - { - glFlush(); - gl2psEndPage(); - fclose(eps_file); - eps_file=NULL; - saving_eps=false; - } - - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_MPC_velocity01.cpp b/src/demo_MPC_velocity01.cpp new file mode 100644 index 0000000..f4eb36c --- /dev/null +++ b/src/demo_MPC_velocity01.cpp @@ -0,0 +1,513 @@ +/* + * demo_MPC_velocity01.cpp + * + * Interactive MPC demo, with batch LQT and repulsive field test + * + * Fabien Crépon, Sylvain Calinon, 2017 + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +#include <mpc_utils.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + +//------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space +// +// UI coordinates range from (0, 0) to (win_width, win_height) +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +//------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width; + result(1) = coords(1) * (float) window_size.fb_height / (float) window_size.win_height; + + return result; +} + +//------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space +// +// OpenGL coordinates range from (0, 0) to (fb_width, fb_height) +// UI coordinates range from (0, 0) to (win_width, win_height) +//------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const window_size_t& window_size) { + arma::vec result = coords; + + result(0) = coords(0) * (float) window_size.win_width / (float) window_size.fb_width; + result(1) = coords(1) * (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + +//----------------------------------------------- + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +void setOrtho( float w, float h ) +{ + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, 0+w, 0+h, 0, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); +} + +//----------------------------------------------- + +void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d, + const window_size_t& window_size) +{ + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + *Sigma = basis * basis.t(); + *mu = ui2fb(arma::vec({t2d.pos.x, t2d.pos.y}), window_size); +} + +//----------------------------------------------- + +void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma, + const window_size_t& window_size) +{ + arma::vec ui_mu = fb2ui(mu, window_size); + + t2d->pos.x = ui_mu(0); + t2d->pos.y = ui_mu(1); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, Sigma); + arma::mat VD = V*diagmat(sqrt(d)); + + arma::vec t_x = fb2ui(arma::vec({VD.col(0)(0), VD.col(1)(0)}), window_size); + arma::vec t_y = fb2ui(arma::vec({VD.col(0)(1), VD.col(1)(1)}), window_size); + + t2d->x.x = t_x(0); + t2d->x.y = t_x(1); + t2d->y.x = t_y(0); + t2d->y.y = t_y(1); +} + +//----------------------------------------------- + +void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) +{ + glBegin(primitive); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +arma::mat gradient_2d( arma::mat X, int order=1 ) +{ + mat df = diff(X, 1, 1); + mat db = fliplr( -diff(fliplr(X), 1, 1) ); + mat d = (df+db)/2; + d = join_horiz(zeros(2,1), d); + d.col(0) = df.col(0); + d.col(d.n_cols-1) = db.col(db.n_cols-1); + if(order>1) + return gradient_2d(d, order-1); + return d; +} + +//----------------------------------------------- + +void plot( float x, float y, float w, float h, const vec& v ) +{ + float v_min = v.min(); + float v_max = v.max(); + float inc = w / v.n_rows; + glBegin(GL_LINE_STRIP); + for (int i=0; i < v.n_rows; i++) + { + glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); + } + glEnd(); +} + +//----------------------------------------------- + +void drawGauss(ui::Trans2d& t2d, const window_size_t& window_size) +{ + static arma::mat circ(2,35); + static bool circ_init = true; + if(circ_init) + { + circ = join_cols(cos(linspace<rowvec>(0,2*datum::pi,35)), + sin(linspace<rowvec>(0,2*datum::pi,35))); + circ_init = false; + } + + arma::vec t_x = ui2fb(arma::vec({t2d.x.x, t2d.x.y}), window_size); + arma::vec t_y = ui2fb(arma::vec({t2d.y.x, t2d.y.y}), window_size); + + arma::mat basis = arma::mat{{t_x(0), t_y(0)}, {t_x(1), t_y(1)}}; + + vec mu = ui2fb(vec({t2d.pos.x, t2d.pos.y}), window_size); + + arma::mat pts = basis * circ + arma::repmat(mu, 1, 35); + + glBegin(GL_TRIANGLE_FAN); + glVertex2f(mu(0), mu(1)); + for (uint t=0; t<pts.n_cols; t++){ + glVertex2f(pts(0,t), pts(1,t)); + } + glEnd(); +} + +//----------------------------------------------- + +int main(int argc, char **argv){ + + arma_rng::set_seed_random(); + + //--------------- Setup parameters --------------- + + double dt = 0.01; + int order = 3; + + int m = 4; // Number of targets + double globScale = 0.001; // global scale, avoids numerical issues in batch method + double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) + + float d=0.1; // maximum displacement, used to compute R diagonal + float stroke_duration=0.3; // duration of a stroke + float covscale = 1.0; // hack, field covariance scaling factor + int fieldDeriv=1; // derivative used for additional field + + // Gui settings + bool useField = true; + bool stepwise = false; + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Velocity MPC", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + //Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + // Covariances + mat Mu; + cube Sigma; + + mat Mu0; + cube Sigma0; + + // Gaussian widgets + std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); + std::vector<ui::Trans2d> t2ds0(1, ui::Trans2d()); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // At the very first frame: initialise the UI widgets of the gaussians + if (first && (window_size.fb_width > 0)) { + + Mu = arma::randu(2, m); + Mu.row(0) = Mu.row(0) * (window_size.fb_width - 200) + 100; + Mu.row(1) = Mu.row(1) * (window_size.fb_height - 200) + 100; + + randomCovariances( + &Sigma, Mu, + arma::vec({ 50 * (float) window_size.fb_width / window_size.win_width, + 50 * (float) window_size.fb_height / window_size.win_height + }), + false, 0.0, 0.8 + ); + + Mu0 = arma::randu(2, 1); + Mu0.row(0) = Mu0.row(0) * (window_size.fb_width - 200) + 100; + Mu0.row(1) = Mu0.row(1) * (window_size.fb_height - 200) + 100; + + randomCovariances( + &Sigma0, Mu0, + arma::vec({ 120 * (float) window_size.fb_width / window_size.win_width, + 120 * (float) window_size.fb_height / window_size.win_height + }), + false, 0.0, 0.8 + ); + + for( int i = 0; i < t2ds.size(); i++ ) + gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i), window_size); + + for( int i = 0; i < t2ds0.size(); i++ ) + gauss_to_trans2d(&t2ds0[i], Mu0.col(i), Sigma0.slice(i), window_size); + } + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + + setOrtho(window_size.fb_width, window_size.fb_height); + + //Model rendering + glPushMatrix(); + + // Gauss UI + ui::begin("Gaussian"); + arma::vec mu; + arma::mat Sigm; + + for( int i = 0; i < t2ds.size(); i++ ) + { + t2ds[i] = ui::affineSimple(i, t2ds[i]); + trans2d_to_gauss(&mu, &Sigm, t2ds[i], window_size); + Mu.col(i) = mu; + Sigma.slice(i) = Sigm; + } + + // Velocity field Gaussians + for( int i = 0; i < t2ds0.size(); i++ ) + { + t2ds0[i] = ui::affineSimple(i+m, t2ds0[i]); + trans2d_to_gauss(&mu, &Sigm, t2ds0[i], window_size); + Mu0.col(i) = mu; + Sigma0.slice(i) = Sigm; + } + + ui::end(); + + + // Parameters window + int winw = 400; + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - winw, 2)); + ImGui::Begin("Params", NULL, ImVec2(winw,154), 0.5f, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + ImGui::SliderInt("Order", &order, 2, 7); + ImGui::SliderInt("Field deriv", &fieldDeriv, 0, 4); + ImGui::SliderFloat("covscale", &covscale, 0.1, 1.0); + ImGui::SliderFloat("Max Displacement", &d, 0.01, 2.); + ImGui::Checkbox("Use Field", &useField); + ImGui::Checkbox("Stepwise", &stepwise); + ImGui::End(); + + // Recompute LQR + int dim = 2; + double duration = stroke_duration * m; + int n = (int)(duration/dt); + int cDim = dim * order; + + // system matrices + mat A, B; + makeIntegratorChain(&A, &B, order); + discretizeSystem(&A, &B, A, B, dt); + // make bi-variate + A = kron(A, eye(dim, dim)); + B = kron( B, eye(dim, dim) ); + + // reference + mat Q, MuQ, Q0, MuQ0; + if(stepwise) + stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + else + viaPointReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); + MuQ *= globScale; + Q /= globScale*globScale; + + // velocity field + int deriv=std::min(fieldDeriv, order-2); + // Mu0 = zeros(cDim,1); + MuQ0 = repmat(Mu0.col(0), 1, n);// * globScale; + mat invSigma0 = zeros(cDim, cDim); + invSigma0(span(dim*deriv, dim*deriv+1), span(dim*deriv, dim*deriv+1)) = inv(Sigma0.slice(0)*covscale*covscale); + Q0 = kron(eye(n,n), invSigma0);// / (globScale*globScale); + + /* + Q0 = zeros(cDim, cDim); + Q0(span(0, dim-1), span(0, dim-1)) = inv(Sigma0.slice(0)); + Q0 = kron(eye(n,n), Q0) / (globScale*globScale); + Q0 = (kron(ones(nbData,1), eye(model.nbVar)) * reshape(model0.invSigma(:,:,qList0), model.nbVar, model.nbVar*nbData)) .* kron(eye(nbData), ones(model.nbVar)); + */ + // Q0 = (kron(ones(n,1), eye(cDim, cDim)) * kron(ones(1,n), invSigma0)) % kron(eye(n,n), ones(cDim,cDim)); + + + // r based on oscillatory movement displacement + double r = SHM_r(d, stroke_duration, order); + mat R = kron( eye(n-1, n-1), + eye(dim, dim) * r ); + + //////////////////////////////////// + // Batch LQR + + // Sx and Su matrices for batch LQR + mat Su = zeros(cDim*n, dim*(n-1)); + mat Sx = kron( ones(n,1), + eye(dim*order, dim*order)); + mat M = B; + for( int i = 1; i < n; i++ ) + { + Sx.rows( i*cDim, n*cDim-1 ) = + Sx.rows( i*cDim, n*cDim-1 ) * A; + Su.submat( i*cDim, 0, + (i+1)*cDim-1, i*dim-1 ) = M; + M = join_horiz( A*M.cols(0, dim-1), M ); + } + + arma::vec x0 = MuQ.col(0); + + // Flatten Mu's + mat Xi_hat = reshape(MuQ, cDim*n, 1); + mat Xi_hat0 = reshape(MuQ0, cDim*n, 1); + + mat SuInvSigmaQ = Su.t()*Q; + mat SuInvSigmaQ0 = Su.t()*Q0; + + mat Rq, rq; + + if(useField) + { + Rq = SuInvSigmaQ*Su + SuInvSigmaQ0*Su + R; + rq = SuInvSigmaQ*(Xi_hat - Sx*x0) + SuInvSigmaQ0*(Xi_hat0 - Sx*x0); + } + else + { + Rq = SuInvSigmaQ*Su + R; + rq = SuInvSigmaQ*(Xi_hat - Sx*x0); + } + + // least squares solution + vec u = solve(Rq,rq); + mat Y = reshape( Sx*x0 + Su*u, cDim, n ); + mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; + + ////////////////////////////////////// + + glEnable( GL_BLEND ); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // draw gaussians + glColor4f(0.0, 0.5f, 1.0f, 0.2f); + for( int i = 0; i < t2ds.size(); i++ ) + drawGauss(t2ds[i], window_size); + + // repulsive gaussians + glColor4f(1.0, 0.5f, 0.0f, 0.2f); + for( int i = 0; i < t2ds0.size(); i++ ) + drawGauss(t2ds0[i], window_size); + + // draw trajectory + glColor3f(0, 0, 1); + draw(Xi); + + // plot derivatives magnitude + int plot_width = 200 * window_size.fb_width / window_size.win_width; + int plot_height = 100 * window_size.fb_height / window_size.win_height; + int plot_y = window_size.fb_height - 25 * window_size.fb_height / window_size.win_height; + + glColor3f(1,0,0); + mat dx = gradient_2d(Xi, 1); + vec speed = sqrt(sum(dx%dx, 0)).t(); + plot(0, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(10, window_size.win_height - 25), "velocity magnitude", + ImVec4(1,0,0,1)); + ui::end(); + + glColor3f(0,0,1); + dx = gradient_2d(Xi, 2); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(200 + 10, window_size.win_height - 25), "acceleration magnitude", + ImVec4(0,0,1,1)); + ui::end(); + + glColor3f(0,0.5,0); + dx = gradient_2d(Xi, 3); + speed = sqrt(sum(dx%dx, 0)).t(); + plot(2 * plot_width, plot_y, plot_width, plot_height, speed); + + ui::begin("Text"); + ui::text(ImVec2(400 + 10, window_size.win_height - 25), "jerk magnitude", + ImVec4(0,0.5,0,1)); + ui::end(); + + glPopMatrix(); + + // Render UI + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + glfwSwapBuffers(window); + + //Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_MPC_velocity_01.cpp b/src/demo_MPC_velocity_01.cpp deleted file mode 100644 index 5885d47..0000000 --- a/src/demo_MPC_velocity_01.cpp +++ /dev/null @@ -1,379 +0,0 @@ -/* - * demo_MPC_batch_01.cpp - * - * Interactive MPC demo, with batch LQT and repulsive field test - * - * Fabien Crépon, Sylvain Calinon, 2017 - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <stdio.h> -#include <GLFW/glfw3.h> -#include "mpc_utils.h" - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int factorial(int n){ - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void trans2d_to_gauss(arma::vec* mu, arma::mat* Sigma, const ui::Trans2d& t2d) -{ - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - *Sigma = basis * basis.t(); - *mu = arma::vec({t2d.pos.x, t2d.pos.y}); -} - -void gauss_to_trans2d(ui::Trans2d *t2d, const arma::vec& mu, const arma::mat& Sigma) -{ - t2d->pos.x = mu(0); - t2d->pos.y = mu(1); - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, Sigma); - arma::mat VD = V*diagmat(sqrt(d)); - t2d->x.x = VD.col(0)(0); - t2d->x.y = VD.col(0)(1); - t2d->y.x = VD.col(1)(0); - t2d->y.y = VD.col(1)(1); -} - -void draw(const arma::mat& pts, int primitive=GL_LINE_STRIP) -{ - glBegin(primitive); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -arma::mat gradient_2d( arma::mat X, int order=1 ) -{ - mat df = diff(X, 1, 1); - mat db = fliplr( -diff(fliplr(X), 1, 1) ); - mat d = (df+db)/2; - d = join_horiz(zeros(2,1), d); - d.col(0) = df.col(0); - d.col(d.n_cols-1) = db.col(db.n_cols-1); - if(order>1) - return gradient_2d(d, order-1); - return d; -} - -void plot( float x, float y, float w, float h, const vec& v ) -{ - float v_min = v.min(); - float v_max = v.max(); - float inc = w / v.n_rows; - glBegin(GL_LINE_STRIP); - for (int i=0; i < v.n_rows; i++) - { - glVertex2f(x + inc*i, y - h * ((v[i] - v_min) / (v_max - v_min))); - } - glEnd(); -} - -void drawGauss( ui::Trans2d& t2d ) -{ - static arma::mat circ(2,35); - static bool circ_init = true; - if(circ_init) - { - circ = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - circ_init = false; - } - arma::mat basis = arma::mat{{t2d.x.x, t2d.y.x}, {t2d.x.y, t2d.y.y}}; - arma::mat pts = basis*circ + arma::repmat(vec({t2d.pos.x, t2d.pos.y}), 1, 35); - - glBegin(GL_TRIANGLE_FAN); - glVertex2f(t2d.pos.x, t2d.pos.y); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(pts(0,t), pts(1,t)); - } - glEnd(); -} - -int main(int argc, char **argv){ - - arma_rng::set_seed_random(); - - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- - int w = 800; - int h = 600; - - double dt = 0.01; - int order = 3; - - int m = 4; // Number of targets - double globScale = 0.001; // global scale, avoids numerical issues in batch method - double endWeight = 1.; //1e-10; // forces movement to a stop (see stepwiseReference function) - - float d=0.1; // maximum displacement, used to compute R diagonal - float stroke_duration=0.3; // duration of a stroke - float covscale = 1.0; // hack, field covariance scaling factor - int fieldDeriv=1; // derivative used for additional field - // Gui settings - int plot_deriv = 1; - bool useField = true; - bool stepwise = false; - - // targets - arma::mat V = arma::randu(2, m); - V.row(0) *= w; - V.row(1) *= h; - - // Covariances - mat Mu = V; - cube Sigma; - randomCovariances(&Sigma, Mu, arma::vec({50.,50.}), false, 0.0, 0.8); - - mat Mu0 = arma::randu(2,1); - Mu0.row(0) *= w; - Mu0.row(1) *= h; - cube Sigma0; - randomCovariances(&Sigma0, Mu0, arma::vec({120.,120.}), false, 0.0, 0.8); - - // Gaussians - std::vector<ui::Trans2d> t2ds(m, ui::Trans2d()); - for( int i = 0; i < m; i++ ) - gauss_to_trans2d(&t2ds[i], Mu.col(i), Sigma.slice(i)); - - std::vector<ui::Trans2d> t2ds0(m, ui::Trans2d()); - for( int i = 0; i < 1; i++ ) - gauss_to_trans2d(&t2ds0[i], Mu0.col(i), Sigma0.slice(i)); - - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(w, h, "Demo Batch MPC", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - while (!glfwWindowShouldClose(window)) { - w = ImGui::GetIO().DisplaySize.x; - h = ImGui::GetIO().DisplaySize.y; - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //Model rendering - glPushMatrix(); - - // Gauss UI - ui::begin("Gaussian"); - arma::vec mu; - arma::mat Sigm; - - for( int i = 0; i < m; i++ ) - { - t2ds[i] = ui::affineSimple(i, t2ds[i]); - trans2d_to_gauss(&mu, &Sigm, t2ds[i]); - Mu.col(i) = mu; - Sigma.slice(i) = Sigm; - } - - - // Velocity field Gaussians (actually one) - for( int i = 0; i < 1; i++ ) - { - t2ds0[i] = ui::affineSimple(i+m, t2ds0[i]); - trans2d_to_gauss(&mu, &Sigm, t2ds0[i]); - //Mu0.col(i) = mu; - Sigma0.slice(i) = Sigm; - } - - - ui::end(); - - - // Slider window - int winw = 250; - ImGui::SetNextWindowPos(ImVec2(w-winw,2)); - ImGui::Begin("Params", NULL, ImVec2(winw,300), 0.5f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - ImGui::SliderInt("Order", &order, 2, 7); - ImGui::SliderInt("Field deriv", &fieldDeriv, 0, 4); - ImGui::SliderFloat("covscale", &covscale, 0.1, 1.0); - ImGui::SliderFloat("Max Displacement", &d, 0.01, 2.); - ImGui::Checkbox("Use Field", &useField); - ImGui::Checkbox("Stepwise", &stepwise); - ImGui::SliderInt("Plot deriv", &plot_deriv, 1, 3); - ImGui::End(); - - // Recompute LQR - int dim = 2; - double duration = stroke_duration * m; - int n = (int)(duration/dt); - int cDim = dim * order; - - // system matrices - mat A, B; - makeIntegratorChain(&A, &B, order); - discretizeSystem(&A, &B, A, B, dt); - // make bi-variate - A = kron(A, eye(dim, dim)); - B = kron( B, eye(dim, dim) ); - - // reference - mat Q, MuQ, Q0, MuQ0; - if(stepwise) - stepwiseReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - else - viaPointReference( &MuQ, &Q, Mu, Sigma, n, order, dim, endWeight ); - MuQ *= globScale; - Q /= globScale*globScale; - - // velocity field - int deriv=std::min(fieldDeriv, order-2); - Mu0 = zeros(cDim,1); - MuQ0 = repmat(Mu0.col(0), 1, n);// * globScale; - mat invSigma0 = zeros(cDim, cDim); - invSigma0(span(dim*deriv, dim*deriv+1), span(dim*deriv, dim*deriv+1)) = inv(Sigma0.slice(0)*covscale*covscale); - Q0 = kron(eye(n,n), invSigma0);// / (globScale*globScale); - - /* - Q0 = zeros(cDim, cDim); - Q0(span(0, dim-1), span(0, dim-1)) = inv(Sigma0.slice(0)); - Q0 = kron(eye(n,n), Q0) / (globScale*globScale); - Q0 = (kron(ones(nbData,1), eye(model.nbVar)) * reshape(model0.invSigma(:,:,qList0), model.nbVar, model.nbVar*nbData)) .* kron(eye(nbData), ones(model.nbVar)); - */ - // Q0 = (kron(ones(n,1), eye(cDim, cDim)) * kron(ones(1,n), invSigma0)) % kron(eye(n,n), ones(cDim,cDim)); - - - // r based on oscillatory movement displacement - double r = SHM_r(d, stroke_duration, order); - mat R = kron( eye(n-1, n-1), - eye(dim, dim) * r ); - - //////////////////////////////////// - // Batch LQR - - // Sx and Su matrices for batch LQR - mat Su = zeros(cDim*n, dim*(n-1)); - mat Sx = kron( ones(n,1), - eye(dim*order, dim*order)); - mat M = B; - for( int i = 1; i < n; i++ ) - { - Sx.rows( i*cDim, n*cDim-1 ) = - Sx.rows( i*cDim, n*cDim-1 ) * A; - Su.submat( i*cDim, 0, - (i+1)*cDim-1, i*dim-1 ) = M; - M = join_horiz( A*M.cols(0, dim-1), M ); - } - - arma::vec x0 = MuQ.col(0); - - // Flatten Mu's - mat Xi_hat = reshape(MuQ, cDim*n, 1); - mat Xi_hat0 = reshape(MuQ0, cDim*n, 1); - - mat SuInvSigmaQ = Su.t()*Q; - mat SuInvSigmaQ0 = Su.t()*Q0; - - mat Rq, rq; - - if(useField) - { - Rq = SuInvSigmaQ*Su + SuInvSigmaQ0*Su + R; - rq = SuInvSigmaQ*(Xi_hat - Sx*x0) + SuInvSigmaQ0*(Xi_hat0 - Sx*x0); - } - else - { - Rq = SuInvSigmaQ*Su + R; - rq = SuInvSigmaQ*(Xi_hat - Sx*x0); - } - - // least squares solution - vec u = solve(Rq,rq); - mat Y = reshape( Sx*x0 + Su*u, cDim, n ); - mat Xi = Y.submat(0,0, dim-1, n-1) / globScale; - - ////////////////////////////////////// - - glEnable( GL_BLEND ); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // draw gaussians - glColor4f(0.0, 0.5f, 1.0f, 0.2f); - for( int i = 0; i < m; i++ ) - { - drawGauss(t2ds[i]); - } - // repulsive gaussians - glColor4f(1.0, 0.5f, 0.0f, 0.2f); - for( int i = 0; i < 1; i++ ) - { - drawGauss(t2ds0[i]); - } - - // draw trajectory - glColor3f(0, 0, 0); - draw(Xi); - - // plot derivatives magnitude - glColor3f(1,0,0); - mat dx = gradient_2d(Xi, plot_deriv); //, 1, 1); - vec speed = sqrt(sum(dx%dx, 0)).t(); - plot(10, h, 200, 100, speed); - - ui::begin("Text"); - const char* sderiv[] = - { - "velocity", - "acceleration", - "jerk" - }; - ui::textf(ImVec2(200+10, h-20), "%s magnitude", sderiv[plot_deriv-1]); //sderiv[plot_deriv-1]); - ui::end(); - - glPopMatrix(); - - // Render UI - ImGui::Render(); - - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_Riemannian_cov_GMR01.cpp b/src/demo_Riemannian_cov_GMR01.cpp new file mode 100644 index 0000000..c7644eb --- /dev/null +++ b/src/demo_Riemannian_cov_GMR01.cpp @@ -0,0 +1,912 @@ +/* + * demo_Riemannian_cov_GMR01.cpp + * + * GMR with time as input and covariance data as output by relying on Riemannian manifold + * + * @article{Jaquier17IROS, + * author="Jaquier, N. and Calinon, S.", + * title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: + * Application to Wrist Motion Estimation with s{EMG}", + * year="2017, submitted for publication", + * booktitle = "{IEEE/RSJ} Intl. Conf. on Intelligent Robots and Systems ({IROS})", + * address = "Vancouver, Canada" + * } + * + * Authors: Sylvain Calinon, Philip Abbet + */ + + +#include <stdio.h> +#include <armadillo> + +#include <tensor.h> +#include <mvn.h> +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/******************************** CONSTANTS **********************************/ + +const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, + { 0.25f, 0.25f, 0.25f, 1.0f }, + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, + { 0.25f, 0.25f, 0.25f, 1.0f }, + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, +}); + + +/*********************************** TYPES ***********************************/ + +// 4-dimensional tensor of doubles +typedef Tensor<double, 4> Tensor4D; + +//----------------------------------------------- + +struct parameters_t { + int nb_states; // Number of components in the GMM + int nb_var; // Dimension of the manifold and tangent space (here: + // 1D input + 2^2 output) + int nb_data; // Number of datapoints + float dt; // Time step duration + int nb_iter_EM; // Number of iterations for the EM algorithm + int nb_iter; // Number of iterations for the Gauss Newton algorithm + float diag_reg_fact; // Regularization term to avoid numerical instability +}; + +//----------------------------------------------- + +struct model_t { + // These lists contain one element per GMM state + vec priors; + std::vector<mat> mu_man; + std::vector<mat> mu; + std::vector<Tensor4D> sigma; + std::vector<mat> xhat; + std::vector<vec> H; +}; + + +//----------------------------------------------------------------------------- +// Computation of the outer product between two complex matrices +//----------------------------------------------------------------------------- +template <typename type> +Tensor4D outerprod(const Mat<type>& U, const Mat<type>& V) { + Tensor4D T(U.n_rows, U.n_cols, V.n_rows, V.n_cols); + + T.data = real(vectorise(vectorise(U) * strans(vectorise(V)))); + + return T; +} + + +//----------------------------------------------------------------------------- +// Set the factors necessary to simplify a 4th-order covariance of symmetric +// matrix to a 2nd-order covariance. The dimension ofthe 4th-order +// covariance is dim x dim x dim x dim. +//----------------------------------------------------------------------------- +class CovOrder { + +public: + CovOrder(int dim) + : dim(dim) + { + new_dim = dim + dim * (dim - 1) / 2; + + // Computation of the indices and coefficients to transform 4th-order + // covariances to 2nd-order covariances + Tensor4D sizeS(dim, dim, dim, dim); + SizeMat sizeSred = size(new_dim, new_dim); + + //---- left-up part + + id.insert_rows(0, dim * dim); + id_red.insert_rows(0, dim * dim); + coeffs.insert_rows(0, dim * dim); + + int offset = 0; + for (int k = 0; k < dim; ++k) { + for (int m = 0; m < dim; ++m) { + id(offset) = sizeS.indice(k, k, m, m); + id_red(offset) = sub2ind(sizeSred, k, m); + coeffs(offset) = 1.0; + ++offset; + } + } + + //---- right-down part + + int row = dim; + int col = dim; + + for (int k = 0; k < dim - 1; ++k) { + for (int m = k + 1; m < dim; ++m) { + for (int p = 0; p < dim - 1; ++p) { + id.insert_rows(offset, dim - (p + 1)); + id_red.insert_rows(offset, dim - (p + 1)); + coeffs.insert_rows(offset, dim - (p + 1)); + + for (int q = p + 1; q < dim; ++q) { + id(offset) = sizeS.indice({k, m, p, q}); + id_red(offset) = sub2ind(sizeSred, row, col); + coeffs(offset) = 2.0; + ++offset; + ++col; + } + } + + ++row; + col = dim; + } + } + + //---- side-parts + + for (int k = 0; k < dim; ++k) { + col = dim; + + for (int p = 0; p < dim - 1; ++p) { + id.insert_rows(offset, 2 * (dim - (p + 1))); + id_red.insert_rows(offset, 2 * (dim - (p + 1))); + coeffs.insert_rows(offset, 2 * (dim - (p + 1))); + + for (int q = p + 1; q < dim; ++q) { + id(offset) = sizeS.indice({k, k, p, q}); + id(offset + 1) = sizeS.indice({k, k, p, q}); + + id_red(offset) = sub2ind(sizeSred, k, col); + id_red(offset + 1) = sub2ind(sizeSred, col, k); + + coeffs(offset) = sqrt(2.0); + coeffs(offset+1) = sqrt(2.0); + + offset += 2; + ++col; + } + } + } + + // Computation of the indices and coefficients to transform eigenvectors + // to eigentensors + SizeCube sizeV = size(dim, dim, new_dim); + SizeMat sizeVred = size(new_dim, new_dim); + + offset = 0; + for (int n = 0; n < new_dim; ++n) { + + id_eigen.insert_rows(offset, dim); + id_red_eigen.insert_rows(offset, dim); + coeffs_eigen.insert_rows(offset, dim); + + // diagonal part + for (int j = 0; j < dim; ++j) { + id_eigen(offset) = sub2ind(sizeV, j, j, n); + id_red_eigen(offset) = sub2ind(sizeVred, j, n); + coeffs_eigen(offset) = 1.0; + ++offset; + } + + // side part + int j = dim; + for (int k = 0; k < dim - 1; ++k) { + id_eigen.insert_rows(offset, 2 * (dim - (k + 1))); + id_red_eigen.insert_rows(offset, 2 * (dim - (k + 1))); + coeffs_eigen.insert_rows(offset, 2 * (dim - (k + 1))); + + for (int m = k + 1; m < dim; ++m) { + id_eigen(offset) = sub2ind(sizeV, k, m, n); + id_eigen(offset + 1) = sub2ind(sizeV, m, k, n); + + id_red_eigen(offset) = sub2ind(sizeVred, j, n); + id_red_eigen(offset + 1) = sub2ind(sizeVred, j, n); + + coeffs_eigen(offset) = 1.0 / sqrt(2.0); + coeffs_eigen(offset + 1) = 1.0 / sqrt(2.0); + + ++j; + offset += 2; + } + } + } + } + + + void conv4to2(const Tensor4D& S, mat &Sred, cx_cube &V, cx_vec &D) const { + Sred = zeros(new_dim, new_dim); + Sred(id_red) = S(id) % coeffs; + + cx_mat v; + eig_gen(D, v, Sred); + + V.set_size(dim, dim, new_dim); + V.zeros(); + V(id_eigen) = v(id_red_eigen) % coeffs_eigen; + } + + + void conv2to4(const mat& Sred, Tensor4D &S, cx_cube &V, cx_vec &D) const { + cx_mat v; + eig_gen(D, v, Sred); + + V.set_size(dim, dim, new_dim); + V(id_eigen) = v(id_red_eigen) % coeffs_eigen; + + S = Tensor4D(dim, dim, dim, dim); + + cx_vec S_complex(S.size, fill::zeros); + for (int i = 0; i < new_dim; ++i) + S_complex = S_complex + D(i) * outerprod(V.slice(i), V.slice(i)).data; + + S = vec(real(S_complex)); + } + +private: + int dim; + int new_dim; + uvec id; + uvec id_red; + vec coeffs; + uvec id_eigen; + uvec id_red_eigen; + vec coeffs_eigen; +}; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//----------------------------------------------------------------------------- +// Creates a MxNx1 cube from a MxN matrix +//----------------------------------------------------------------------------- +template <typename T> +Cube<T> mat2cube(const Mat<T>& m) { + return Cube<T>(m.memptr(), m.n_rows, m.n_cols, 1); +} + + +//----------------------------------------------------------------------------- +// Creates a MxN matrix from a MxNx1 cube +//----------------------------------------------------------------------------- +template <typename T> +Mat<T> cube2mat(const Cube<T>& c) { + assert(c.n_slices == 1); + return Mat<T>(c.memptr(), c.n_rows, c.n_cols); +} + + +//----------------------------------------------------------------------------- +// Reduced vectorisation of a symmetric matrix +//----------------------------------------------------------------------------- +template <typename T> +Col<T> sym_mat_to_vec(const Mat<T>& S) { + + Col<T> v = zeros<Col<T> >(S.n_rows + S.n_rows * (S.n_rows - 1) / 2); + + v.subvec(0, S.n_rows - 1) = S.diag(); + + int row = S.n_rows; + for (int i = 0; i < S.n_rows - 1; ++i) { + v.subvec(row, row + S.n_rows - 2 - i) = sqrtf(2.0f) * + S.submat(i+1, i, S.n_rows - 1, i); + row = row + S.n_rows - 1 - i; + } + + return v; +} + + +//----------------------------------------------------------------------------- +// Return locations of non-zero elements in a block diagonal matrix +//----------------------------------------------------------------------------- +uvec find_non_zero_indices(const span& in, const span& out) { + int in_size = in.b - in.a + 1; + int out_size = out.b - out.a + 1; + + fmat number_mat = zeros<fmat>(out_size + 1, out_size + 1); + + number_mat.submat(in, in) = ones<fmat>(in_size, in_size); + number_mat.submat(out, out) = ones<fmat>(out_size, out_size); + + fvec sym_number_vec = sym_mat_to_vec(number_mat); + + uvec number_vec = zeros<uvec>(sym_number_vec.n_elem); + number_vec(find(sym_number_vec)).ones(); + + number_vec = number_vec % linspace<uvec>(1, number_vec.n_elem, number_vec.n_elem); + + return find(number_vec); +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) +//----------------------------------------------------------------------------- +arma::cube logmap(const arma::cube& X, const arma::mat& S) { + arma::cube U(size(X)); + + for (int n = 0; n < X.n_slices; ++n) { + U(span::all, span::all, span(n)) = + real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * mat(X(span::all, span::all, span(n))) * + inv(sqrtmat(S)) + ) * sqrtmat(S) + ); + } + + return U; +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) +//----------------------------------------------------------------------------- +arma::mat logmap(const arma::mat& X, const arma::mat& S) { + return real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * X * inv(sqrtmat(S))) * sqrtmat(S)); +} + + +//----------------------------------------------------------------------------- +// Exponential map (SPD manifold) +//----------------------------------------------------------------------------- +arma::mat expmap(const arma::mat& U, const arma::mat& S) { + return real(sqrtmat(S) * expmat(inv(sqrtmat(S)) * U * inv(sqrtmat(S))) * sqrtmat(S)); +} + + +//----------------------------------------------------------------------------- +// Parallel transport (SPD manifold) +// +// Transportation operator Ac to move V from S1 to S2: VT = Ac * V * Ac' +//----------------------------------------------------------------------------- +mat transp(const mat& S1, const mat& S2) { + mat U = cube2mat(logmap(mat2cube(S2), S1)); + return real(sqrtmat(S1) * expmat(0.5 * inv(sqrtmat(S1)) * U * inv(sqrtmat(S1))) * inv(sqrtmat(S1))); +} + + +//----------------------------------------------------------------------------- +// Mean of SPD matrices on the manifold +//----------------------------------------------------------------------------- +mat spdMean(const cube& setS, unsigned int nb_iterations = 10) { + mat M = setS(span::all, span::all, span(0)); + + for (unsigned int i = 0; i < nb_iterations; ++i) { + mat L = zeros<mat>(setS.n_rows, setS.n_cols); + + mat sqrt_M = real(sqrtmat(M)); + mat inv_sqrt_M = inv(M) * sqrt_M; + + for (unsigned int n = 0; n < setS.n_slices; ++n) { + L = L + real(logmat(inv_sqrt_M * mat(setS(span::all, span::all, span(n))) * + inv_sqrt_M)); + } + + M = sqrt_M * expmat(L / setS.n_slices) * sqrt_M; + } + + return M; +} + + +//----------------------------------------------------------------------------- +// Compute the 4th-order covariance of matrix data +//----------------------------------------------------------------------------- +Tensor4D compute_cov(const cube& data) { + const int d = data.n_rows; + const int N = data.n_slices; + + cube data_mean = mean(data, 2); + + cube data2(size(data)); + + for (int n = 0; n < N; ++n) { + data2(span::all, span::all, span(n)) = data(span::all, span::all, span(n)) - data_mean; + } + + Tensor4D S(d, d, d, d); + for (int n = 0; n < N; ++n) { + mat m = mat(data2(span::all, span::all, span(n))); + S.data = S.data + outerprod(m, m).data; + } + + S.data /= (N - 1); + + return S; +} + + +//------------------------------------------------------------------------- +// Matricisation of a tensor +// +// The rows, respectively columns of the matrix are 'rows', respectively +// 'cols' of the tensor +//------------------------------------------------------------------------- +mat tensor2mat(const Tensor4D& T) { + + const uvec rows = { 0, 1 }; + const uvec cols = { 2, 3 }; + + return mat(T.data.memptr(), prod(T.dims(rows)), prod(T.dims(cols))); +} + + +//----------------------------------------------------------------------------- +// K-Bins initialisation by relying on SPD manifold +//----------------------------------------------------------------------------- +void spd_init_GMM_kbins(const cube& data, const span& spd_data_id, + const parameters_t& parameters, model_t &model) { + // Parameters + int nb_data = data.n_slices; + + model.priors = vec(parameters.nb_states); + model.mu_man.clear(); + model.sigma.clear(); + + Tensor4D e0tensor(parameters.nb_var, parameters.nb_var, parameters.nb_var, parameters.nb_var); + for (int i = 0; i < parameters.nb_var; ++i) + e0tensor.set(e0tensor.indices(i, i, i, i), 1.0); + + // Delimit the cluster bins + uvec t_sep = conv_to<uvec>::from(round(linspace<vec>(0, parameters.nb_data, parameters.nb_states + 1))); + + // Compute statistics for each bin + for (int i = 0; i < parameters.nb_states; ++i) { + span id(t_sep(i), t_sep(i + 1) - 1); + + model.priors(i) = id.b - id.a + 1; + + // Mean computed on SPD manifold for parts of the data belonging to the + // manifold + mat mu_man = mean(data(span::all, span::all, id), 2); + + mu_man(spd_data_id, spd_data_id) = spdMean(data(spd_data_id, spd_data_id, id), 3); + + // Parts of data belonging to SPD manifold projected to tangent space at + // the mean to compute the covariance tensor in the tangent space + cube data_tgt = data(span::all, span::all, id); + + data_tgt(spd_data_id, spd_data_id, span::all) = + logmap(cube(data(spd_data_id, spd_data_id, id)), + mat(mu_man(spd_data_id, spd_data_id)) + ); + + Tensor4D sigma = compute_cov(data_tgt) + e0tensor * parameters.diag_reg_fact; + + model.mu_man.push_back(mu_man); + model.sigma.push_back(sigma); + } + + model.priors /= sum(model.priors); +} + + +/********************************* FUNCTIONS *********************************/ + +void process(const parameters_t& parameters, cube &X, model_t &model) { + + CovOrder cov_order(parameters.nb_var); + + //_____ Generate covariance data from rotating covariance __________ + + mat v_data = eye(parameters.nb_var - 1, parameters.nb_var - 1); + mat d_data = eye(parameters.nb_var - 1, parameters.nb_var - 1); + + X = zeros(parameters.nb_var, parameters.nb_var, parameters.nb_data); + X.tube(0, 0) = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + for (int t = 1; t <= parameters.nb_data; ++t) { + d_data(0, 0) = parameters.dt * t; + + mat R(2, 2); + double a = datum::pi / 2.0 * t * parameters.dt; + R(0, 0) = cos(a); + R(0, 1) = -sin(a); + R(1, 0) = sin(a); + R(1, 1) = cos(a); + + mat V = R * v_data; + X.subcube(1, 1, t-1, 2, 2, t-1) = V * d_data * V.t(); + } + + + //_____ GMM parameters estimation __________ + + // Initialisation on the manifold + span in(0); + span out(1, parameters.nb_var - 1); + uvec id = find_non_zero_indices(in, out); + + spd_init_GMM_kbins(X, out, parameters, model); + + for (size_t i = 0; i < model.mu_man.size(); ++i) + model.mu.push_back(zeros(size(model.mu_man[i]))); + + mat L = zeros(parameters.nb_states, parameters.nb_data); + + for (int nb = 0; nb < parameters.nb_iter_EM; ++nb) { + // E-step + for (int i = 0; i < parameters.nb_states; ++i) { + cube Xts = zeros(parameters.nb_var, parameters.nb_var, parameters.nb_data); + + cube mu_man = mat2cube(mat(model.mu_man[i](in, in))); + for (int j = 0; j < parameters.nb_data; ++j) + Xts(in, in, span(j)) = X(in, in, span(j)) - mu_man; + + Xts(out, out, span::all) = logmap(cube(X(out, out, span::all)), model.mu_man[i](out, out)); + + // Compute probabilities using the reduced form (computationally less + // expensive than complete form) + mat sym_xts; + + for (int j = 0; j < parameters.nb_data; ++j) { + vec v = sym_mat_to_vec(cube2mat(cube(Xts(span::all, span::all, span(j))))); + + if (sym_xts.n_rows == 0) + sym_xts.set_size(v.n_rows, parameters.nb_data); + + sym_xts(span::all, span(j)) = v; + } + + vec mu_vec = sym_mat_to_vec(model.mu[i]); + + mat sigma_vec; + cx_cube V; + cx_vec D; + + cov_order.conv4to2(model.sigma[i], sigma_vec, V, D); + + L(i, span::all) = trans(model.priors(i) * + mvn::getPDFValue(vec(mu_vec(id)), sigma_vec(id, id), sym_xts.rows(id))); + } + + mat GAMMA = L / repmat(sum(L, 0) + DBL_MIN, parameters.nb_states, 1); + mat H = GAMMA / repmat(sum(GAMMA, 1) + DBL_MIN, 1, parameters.nb_data); + + // M-step + for (int i = 0; i < parameters.nb_states; ++i) { + // Update priors + model.priors(i) = mat(sum(GAMMA(span(i), span::all), 1))(0, 0) / parameters.nb_data; + + // Update mu_man + cube uTmp = zeros(parameters.nb_var, parameters.nb_var, parameters.nb_data); + for (int n = 0; n < parameters.nb_iter; ++n) { + cube mu_man = mat2cube(mat(model.mu_man[i](in, in))); + for (int j = 0; j < parameters.nb_data; ++j) + uTmp(in, in, span(j)) = X(in, in, span(j)) - mu_man; + + uTmp(out, out, span::all) = logmap(cube(X(out, out, span::all)), model.mu_man[i](out, out)); + + mat uTmpTot = zeros(parameters.nb_var, parameters.nb_var); + + for (int k = 0; k < parameters.nb_data; ++k) + uTmpTot = uTmpTot + cube2mat(cube(uTmp(span::all, span::all, span(k)))) * H(i, k); + + model.mu_man[i](in, in) = uTmpTot(in, in) + model.mu_man[i](in, in); + model.mu_man[i](out, out) = expmap(uTmpTot(out, out), model.mu_man[i](out, out)); + } + + // Update Sigma + Tensor4D sigma(parameters.nb_var, parameters.nb_var, parameters.nb_var, parameters.nb_var); + for (int k = 0; k < parameters.nb_data; ++k) { + sigma = sigma + outerprod(mat(uTmp(span::all, span::all, span(k))), + mat(uTmp(span::all, span::all, span(k))) + ) * H(i, k); + } + + model.sigma[i] = sigma + parameters.diag_reg_fact * parameters.diag_reg_fact; + } + } + + // Eigendecomposition of sigma + std::vector<cube> V; + std::vector<vec> D; + + for (int i = 0; i < parameters.nb_states; ++i) { + mat Sred; + cx_cube V_; + cx_vec D_; + + cov_order.conv4to2(model.sigma[i], Sred, V_, D_); + V.push_back(real(V_)); + D.push_back(real(D_)); + } + + + //_____ GMR (version with single optimization loop) __________ + + vec xIn = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + int nb_var_out = out.b - out.a + 1; + int nb_var_cov_out = parameters.nb_var + parameters.nb_var * (parameters.nb_var - 1) / 2; + + model.xhat.clear(); + model.H.clear(); + + for (unsigned int t = 0; t < parameters.nb_data; ++t) { + // Compute activation weight + vec H_(parameters.nb_states); + + for (unsigned int i = 0; i < parameters.nb_states; ++i) { + H_(i) = model.priors(i) * mvn::getPDFValue(model.mu[i](in, in), + model.sigma[i](in, in, in, in).data, + xIn(t) - model.mu_man[i](in, in))(0); + } + H_ = H_ / sum(H_ + DBL_MIN); + + model.H.push_back(H_); + + + // Compute conditional mean (with covariance transportation) + mat xhat; + + if (t == 0) { + uword id = index_max(H_); + xhat = model.mu_man[id](out, out); // Initial point + } + else { + xhat = model.xhat[t - 1]; + } + + std::vector<Tensor4D> pSigma; + + for (int n = 0; n < parameters.nb_iter; ++n) { + mat uhat = zeros(nb_var_out, nb_var_out); + + for (int i = 0; i < parameters.nb_states; ++i) { + // Transportation of covariance from model.mu_man to xhat + mat Ac = zeros(parameters.nb_var, parameters.nb_var); + Ac(0, 0) = 1.0; + Ac(out, out) = transp(model.mu_man[i](out, out), xhat); + + // Parallel transport of eigenvectors + cube pV(V[i].n_rows, V[i].n_cols, V[i].n_slices); + + for (int j = 0; j < V[i].n_slices; ++j) { + double sqrt_d = sqrt(D[i](j)); + if (std::isnan(sqrt_d)) + sqrt_d = 0.0; + + pV(span::all, span::all, span(j)) = + real(Ac * sqrt_d * mat(V[i](span::all, span::all, span(j))) * Ac.t()); + } + + // Parallel transported sigma (reconstruction from eigenvectors) + Tensor4D pSigma(model.sigma[i].dims); + for (int j = 0; j < pV.n_slices; ++j) { + mat pV2 = pV(span::all, span::all, span(j)); + pSigma = pSigma + outerprod(pV2, pV2); + } + + // Gaussian conditioning on the tangent space + int dim = out.b - out.a + 1; + + mat uOut = logmap(model.mu_man[i](out, out), xhat(span::all, span::all)) + + mat(reshape(tensor2mat(pSigma(out, out, in, in) / pSigma(in, in, in, in)[0]) * + (xIn(t) - model.mu_man[i](in, in))[0], dim, dim)); + + uhat = uhat + uOut * H_(i); + } + + xhat = expmap(uhat, xhat); + } + + model.xhat.push_back(xhat); + } +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + // Parameters + parameters_t parameters; + parameters.nb_states = 10; + parameters.nb_data = 50; + parameters.nb_var = 3; + parameters.dt = 0.1; + parameters.nb_iter_EM = 5; + parameters.nb_iter = 5; + parameters.diag_reg_fact = 1e-4f; + + + // Initial computation + cube X; + model_t model; + process(parameters, X, model); + + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 400; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + // Initialise GLFW + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Gaussian Mixture Regression", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + float workspace_size = (parameters.nb_data + 1) * parameters.dt; + + // Setup GLSL + gfx2::init(); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + + // Main loop + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + + // Detect if the parameters have changed + if ((parameters.nb_data != X.n_slices) || (parameters.nb_states != model.mu_man.size())) { + parameters.nb_states = std::min(parameters.nb_states, parameters.nb_data / 2); + + process(parameters, X, model); + + workspace_size = (parameters.nb_data + 1) * parameters.dt; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + glEnable(GL_BLEND); + + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho(-window_size.fb_width / 2, window_size.fb_width / 2, + -window_size.fb_height / 2, window_size.fb_height / 2, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + + // Draw the datapoints + for (int i = 0; i < parameters.nb_data; ++i) { + gfx2::draw_gaussian( + fvec({ 0.5f, 0.5f, 0.5f, 0.25f }), + vec({ X(0, 0, i) * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 140.0) * window_size.scale_y() + }), + X.subcube(1, 1, i, 2, 2, i) * window_size.fb_width / workspace_size + ); + } + + // Draw the GMM states + for (int i = 0; i < parameters.nb_states; ++i) { + fvec color = COLORS.row(i).t(); + + gfx2::draw_gaussian( + fvec({ color(0), color(1), color(2), 0.5f }), + vec({ model.mu_man[i](0, 0) * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 140.0) * window_size.scale_y() + }), + model.mu_man[i].submat(1, 1, 2, 2) * window_size.fb_width / workspace_size + ); + } + + // Draw the GMR results + vec xIn = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + for (int t = 0; t < parameters.nb_data; ++t) { + gfx2::draw_gaussian( + fvec({ 0.0f, 1.0f, 0.0f, 0.5f }), + vec({ xIn[t] * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 240.0) * window_size.scale_y() + }), + model.xhat[t] * window_size.fb_width / workspace_size + ); + } + + glDisable(GL_BLEND); + + // Draw the lines + double plot_height = ((double) window_size.win_height - 290.0 - 100) * window_size.scale_y(); + + for (int i = 0; i < parameters.nb_states; ++i) { + mat points(2, parameters.nb_data); + + points(span(0), span::all) = xIn.t() * window_size.fb_width / workspace_size - window_size.fb_width / 2; + + for (int t = 0; t < parameters.nb_data; ++t) { + points(1, t) = model.H[t](i) * plot_height + (50 - window_size.win_height / 2) * window_size.scale_y(); + } + + gfx2::draw_line(fvec(COLORS.row(i).t()), points); + } + + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 80)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove + ); + ImGui::SliderInt("Nb datapoints", ¶meters.nb_data, 10, 100); + ImGui::SliderInt("Nb GMM states", ¶meters.nb_states, 3, std::min(20, parameters.nb_data / 2)); + ImGui::End(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_cov_GMR_Mandel01.cpp b/src/demo_Riemannian_cov_GMR_Mandel01.cpp new file mode 100644 index 0000000..3aa49a4 --- /dev/null +++ b/src/demo_Riemannian_cov_GMR_Mandel01.cpp @@ -0,0 +1,706 @@ +/* + * demo_Riemannian_cov_GMR_Mandel01.cpp + * + * GMR with time as input and covariance data as output by relying on Riemannian manifold + * + * @article{Jaquier17IROS, + * author="Jaquier, N. and Calinon, S.", + * title="Gaussian Mixture Regression on Symmetric Positive Definite Matrices Manifolds: + * Application to Wrist Motion Estimation with s{EMG}", + * year="2017, submitted for publication", + * booktitle = "{IEEE/RSJ} Intl. Conf. on Intelligent Robots and Systems ({IROS})", + * address = "Vancouver, Canada" + * } + * + * Authors: Sylvain Calinon, Philip Abbet, Noemie Jaquier + */ + + +#include <stdio.h> +#include <armadillo> +#include <iomanip> + +#include <mvn.h> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/******************************** CONSTANTS **********************************/ + +const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, + { 0.25f, 0.25f, 0.25f, 1.0f }, + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, + { 0.25f, 0.25f, 0.25f, 1.0f }, + { 0.00f, 0.00f, 1.00f, 1.0f }, + { 0.00f, 0.50f, 0.00f, 1.0f }, + { 1.00f, 0.00f, 0.00f, 1.0f }, + { 0.00f, 0.75f, 0.75f, 1.0f }, + { 0.75f, 0.00f, 0.75f, 1.0f }, + { 0.75f, 0.75f, 0.00f, 1.0f }, +}); + + +/*********************************** TYPES ***********************************/ + +struct parameters_t { + int nb_states; // Number of components in the GMM + int nb_var; // Dimension of the manifold and tangent space (here: + // 1D input + 2^2 output) + int nb_var_vec; // Dimension of the manifold and tangent space in vector form + int nb_data; // Number of datapoints + float dt; // Time step duration + int nb_iter_EM; // Number of iterations for the EM algorithm + int nb_iter; // Number of iterations for the Gauss Newton algorithm + float diag_reg_fact; // Regularization term to avoid numerical instability +}; + +//----------------------------------------------- + +struct model_t { + // These lists contain one element per GMM state + vec priors; + std::vector<vec> mu_man; + std::vector<vec> mu; + std::vector<mat> sigma; + std::vector<vec> xhat; + std::vector<vec> H; +}; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//----------------------------------------------------------------------------- +// Creates a MxNx1 cube from a MxN matrix +//----------------------------------------------------------------------------- +template <typename T> +Cube<T> mat2cube(const Mat<T>& m) { + return Cube<T>(m.memptr(), m.n_rows, m.n_cols, 1); +} + + +//------------------------------------------------------------------------- +// Vectorization of a tensor of symmetric matrices +//------------------------------------------------------------------------- +arma::vec symMat2vec(const arma::mat& data) { + const int D = data.n_rows; + int ind = D; + + arma::vec v = arma::zeros<vec>(D*D/2 + D/2); + for (int d = 0; d < D; ++d){ + v(d) = data(d,d); + } + + for (int d = 1; d < D; ++d){ + for (int i = 0; i < D-d; ++i){ + v(ind) = sqrtf(2.0f) * data(i, d); + ind++; + } + } + return v; +} + + +//------------------------------------------------------------------------- +// Vectorization of a tensor of symmetric matrices +//------------------------------------------------------------------------- +arma::mat symMat2vec(const arma::cube& data) { + const int D = data.n_rows; + const int N = data.n_slices; + arma::mat V = arma::zeros<mat>(D*D/2 + D/2, N); + + for (int n = 0; n < N; ++n) { + arma::mat M = mat(data.slice(n)); + V(span::all, n) = symMat2vec(M); + } + return V; +} + + +//------------------------------------------------------------------------- +// Transforms a matrix of vector to a tensor of symmetric matrices +//------------------------------------------------------------------------- +arma::mat vec2symMat(const arma::vec& data) { + const int D = data.n_rows; + const int newD = (-1 + sqrtf(1 + 8*D))/2; + + arma::mat M = arma::zeros<mat>(newD, newD); + for (int d = 0; d < newD; ++d){ + M(d,d) = data(d); + } + + int ind = newD; + for (int d = 1; d < newD; ++d){ + for (int i = 0; i < newD-d; ++i){ + M(i, d) = data(ind)/sqrtf(2.0f); + M(d, i) = M(i, d); + ind++; + } + } + return M; +} + + +//------------------------------------------------------------------------- +// Transforms a matrix of vector to a tensor of symmetric matrices +//------------------------------------------------------------------------- +arma::cube vec2symMat(const arma::mat& data) { + const int D = data.n_rows; + const int N = data.n_cols; + const int newD = (-1 + sqrtf(1 + 8*D))/2; + + arma::cube S = arma::zeros<cube>(newD, newD, N); + + for (int n = 0; n < N; ++n) { + S.slice(n) = mat2cube(vec2symMat(vec(data(span::all,n)))); + } + return S; +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) +//----------------------------------------------------------------------------- +arma::cube logmap(const arma::cube& X, const arma::mat& S) { + arma::cube U(size(X)); + + for (int n = 0; n < X.n_slices; ++n) { + U(span::all, span::all, span(n)) = + real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * mat(X(span::all, span::all, span(n))) * + inv(sqrtmat(S)) + ) * sqrtmat(S) + ); + } + + return U; +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) +//----------------------------------------------------------------------------- +arma::mat logmap(const arma::mat& X, const arma::mat& S) { + return real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * X * inv(sqrtmat(S))) * sqrtmat(S)); +} + + +//----------------------------------------------------------------------------- +// Exponential map (SPD manifold) +//----------------------------------------------------------------------------- +arma::mat expmap(const arma::mat& U, const arma::mat& S) { + return real(sqrtmat(S) * expmat(inv(sqrtmat(S)) * U * inv(sqrtmat(S))) * sqrtmat(S)); +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) for data in vector form +//----------------------------------------------------------------------------- +arma::vec logmap_vec(const arma::vec& x, const arma::vec& s) { + arma::mat X = vec2symMat(x); + arma::mat S = vec2symMat(s); + arma::mat U = logmap(X, S); + return symMat2vec(U); +} + + +//----------------------------------------------------------------------------- +// Logarithm map (SPD manifold) for data in matrix form +//----------------------------------------------------------------------------- +arma::mat logmap_vec(const arma::mat& x, const arma::vec& s) { + arma::cube X = vec2symMat(x); + arma::mat S = vec2symMat(s); + arma::cube U = logmap(X, S); + return symMat2vec(U); +} + + +//----------------------------------------------------------------------------- +// Exponential map (SPD manifold) for data in vector form +//----------------------------------------------------------------------------- +arma::vec expmap_vec(const arma::vec& u, const arma::vec& s) { + arma::mat U = vec2symMat(u); + arma::mat S = vec2symMat(s); + arma::mat X = expmap(U, S); + return symMat2vec(X); +} + + +//----------------------------------------------------------------------------- +// Parallel transport (SPD manifold) +// +// Transportation operator Ac to move V from S1 to S2: VT = Ac * V * Ac' +//----------------------------------------------------------------------------- +mat transp(const mat& S1, const mat& S2) { + mat U = logmap(S2, S1); + return real(sqrtmat(S1) * expmat(0.5 * inv(sqrtmat(S1)) * U * inv(sqrtmat(S1))) * inv(sqrtmat(S1))); +} + + +//----------------------------------------------------------------------------- +// Mean of SPD matrices on the manifold +//----------------------------------------------------------------------------- +mat spdMean(const cube& setS, unsigned int nb_iterations = 10) { + mat M = setS(span::all, span::all, span(0)); + + for (unsigned int i = 0; i < nb_iterations; ++i) { + mat L = zeros<mat>(setS.n_rows, setS.n_cols); + + mat sqrt_M = real(sqrtmat(M)); + mat inv_sqrt_M = inv(M) * sqrt_M; + + for (unsigned int n = 0; n < setS.n_slices; ++n) { + L = L + real(logmat(inv_sqrt_M * mat(setS(span::all, span::all, span(n))) * + inv_sqrt_M)); + } + + M = sqrt_M * expmat(L / setS.n_slices) * sqrt_M; + } + + return M; +} + + +//----------------------------------------------------------------------------- +// K-Bins initialisation by relying on SPD manifold +//----------------------------------------------------------------------------- +void spd_init_GMM_kbins(const mat& data, const span& spd_data_id, + const parameters_t& parameters, model_t &model) { + // Parameters + int nb_var = data.n_rows; + int nb_data = data.n_cols; + + model.priors = vec(parameters.nb_states); + model.mu_man.clear(); + model.sigma.clear(); + + // Delimit the cluster bins + uvec t_sep = conv_to<uvec>::from(round(linspace<vec>(0, parameters.nb_data, parameters.nb_states + 1))); + + // Compute statistics for each bin + for (int i = 0; i < parameters.nb_states; ++i) { + span id(t_sep(i), t_sep(i + 1) - 1); + + model.priors(i) = id.b - id.a + 1; + + // Mean computed on SPD manifold for parts of the data belonging to the + // manifold + vec mu_man = mean(data(span::all, id), 1); + mu_man(spd_data_id) = symMat2vec(spdMean(vec2symMat(mat(data(spd_data_id, id))), 3)); + + // Parts of data belonging to SPD manifold projected to tangent space at + // the mean to compute the covariance tensor in the tangent space + mat data_tgt = data(span::all, id); + data_tgt(spd_data_id, span::all) = logmap_vec(mat(data(spd_data_id, id)), mu_man(spd_data_id)); + + mat sigma = cov(data_tgt.t()) + arma::eye(nb_var,nb_var) * parameters.diag_reg_fact; + + model.mu_man.push_back(mu_man); + model.sigma.push_back(sigma); + } + + model.priors /= sum(model.priors); +} + + +/********************************* FUNCTIONS *********************************/ + +void process(const parameters_t& parameters, cube &X, model_t &model) { + //_____ Generate covariance data from rotating covariance __________ + + mat v_data = eye(parameters.nb_var - 1, parameters.nb_var - 1); + mat d_data = eye(parameters.nb_var - 1, parameters.nb_var - 1); + + mat x = zeros(parameters.nb_var_vec, parameters.nb_data); + + X = zeros(parameters.nb_var, parameters.nb_var, parameters.nb_data); + X.tube(0, 0) = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + for (int t = 1; t <= parameters.nb_data; ++t) { + d_data(0, 0) = parameters.dt * t; + + mat R(2, 2); + double a = datum::pi / 2.0 * t * parameters.dt; + R(0, 0) = cos(a); + R(0, 1) = -sin(a); + R(1, 0) = sin(a); + R(1, 1) = cos(a); + + mat V = R * v_data; + X.subcube(1, 1, t-1, 2, 2, t-1) = V * d_data * V.t(); + + x.submat(0, t-1, 0, t-1) = mat(X.subcube(0,0,t-1,0,0,t-1)); + x.submat(1, t-1, x.n_rows-1, t-1) = symMat2vec(mat(X.subcube(1, 1, t-1, 2, 2, t-1))); + } + + //_____ GMM parameters estimation __________ + + // Initialisation on the manifold + span in(0); + span out(1, parameters.nb_var_vec - 1); + span out_mat(1, parameters.nb_var - 1); + + spd_init_GMM_kbins(x, out, parameters, model); + + for (size_t i = 0; i < model.mu_man.size(); ++i) + model.mu.push_back(zeros(size(model.mu_man[i]))); + + mat L = zeros(parameters.nb_states, parameters.nb_data); + for (int nb = 0; nb < parameters.nb_iter_EM; ++nb) { + // E-step + for (int i = 0; i < parameters.nb_states; ++i) { + mat xts = zeros(parameters.nb_var_vec, parameters.nb_data); + mat mu_man = vec(model.mu_man[i](in)); + for (int j = 0; j < parameters.nb_data; ++j) + xts(in, span(j)) = x(in, span(j)) - mu_man; + + xts(out, span::all) = logmap_vec(mat(x(out, span::all)), model.mu_man[i](out)); + + L(i, span::all) = trans(model.priors(i) * mvn::getPDFValue(model.mu[i], + model.sigma[i], xts)); + } + + mat GAMMA = L / repmat(sum(L, 0) + DBL_MIN, parameters.nb_states, 1); + mat H = GAMMA / repmat(sum(GAMMA, 1) + DBL_MIN, 1, parameters.nb_data); + + // M-step + for (int i = 0; i < parameters.nb_states; ++i) { + // Update priors + model.priors(i) = mat(sum(GAMMA(span(i), span::all), 1))(0, 0) / parameters.nb_data; + + // Update mu_man + mat uTmp = zeros(parameters.nb_var_vec, parameters.nb_data); + for (int n = 0; n < parameters.nb_iter; ++n) { + vec mu_man = vec(model.mu_man[i](in)); + for (int j = 0; j < parameters.nb_data; ++j) + uTmp(in, span(j)) = x(in, span(j)) - mu_man; + + uTmp(out, span::all) = logmap_vec(mat(x(out, span::all)), model.mu_man[i](out)); + + vec uTmpTot = zeros(parameters.nb_var_vec); + + for (int k = 0; k < parameters.nb_data; ++k) + uTmpTot = uTmpTot + mat(uTmp(span::all, span(k))) * H(i, k); + + model.mu_man[i](in) = uTmpTot(in) + model.mu_man[i](in); + model.mu_man[i](out) = expmap_vec(uTmpTot(out), model.mu_man[i](out)); + } + + // Update Sigma + mat sigma(parameters.nb_var_vec, parameters.nb_var_vec); + sigma = uTmp * diagmat(H(i,span::all)) * uTmp.t(); + model.sigma[i] = sigma + eye(parameters.nb_var_vec,parameters.nb_var_vec) * parameters.diag_reg_fact; + } + } + // Eigendecomposition of sigma + std::vector<mat> V; + std::vector<vec> D; + + for (int i = 0; i < parameters.nb_states; ++i) { + cx_mat V_; + cx_vec D_; + + eig_gen(D_, V_, model.sigma[i]); + + V.push_back(real(V_)); + D.push_back(real(D_)); + } + + //_____ GMR (version with single optimization loop) __________ + + vec xIn = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + int nb_var_out = out.b - out.a + 1; + //int nb_var_out_vec = parameters.nb_var + parameters.nb_var * (parameters.nb_var - 1) / 2; + + model.xhat.clear(); + model.H.clear(); + for (unsigned int t = 0; t < parameters.nb_data; ++t) { + // Compute activation weight + vec H_(parameters.nb_states); + + for (unsigned int i = 0; i < parameters.nb_states; ++i) { + H_(i) = model.priors(i) * mvn::getPDFValue(model.mu[i](in), + model.sigma[i](in, in), + xIn(t) - model.mu_man[i](in))(0); + } + H_ = H_ / sum(H_ + DBL_MIN); + + model.H.push_back(H_); + + + // Compute conditional mean (with covariance transportation) + mat xhat; + + if (t == 0) { + uword id = index_max(H_); + xhat = model.mu_man[id](out); // Initial point + } + else { + xhat = model.xhat[t - 1]; + } + + std::vector<mat> pSigma; + + for (int n = 0; n < parameters.nb_iter; ++n) { + vec uhat = zeros(nb_var_out); + + for (int i = 0; i < parameters.nb_states; ++i) { + // Transportation of covariance from model.mu_man to xhat + mat Ac = zeros(parameters.nb_var, parameters.nb_var); + Ac(0, 0) = 1.0; + Ac(out_mat, out_mat) = transp(vec2symMat(vec(model.mu_man[i](out))), vec2symMat(xhat)); + + // Parallel transport of eigenvectors + mat pV(V[i].n_rows, V[i].n_cols); + + for (int j = 0; j < V[i].n_cols; ++j) { + double sqrt_d = sqrt(D[i](j)); + if (std::isnan(sqrt_d)) + sqrt_d = 0.0; + mat M_tmp = zeros(parameters.nb_var, parameters.nb_var); + M_tmp.submat(0,0,0,0) = V[i](in, span(j)); + M_tmp.submat(1, 1, parameters.nb_var-1, parameters.nb_var-1) = vec2symMat(vec(V[i](out, span(j)))); + + mat pM_tmp = real(Ac * sqrt_d * M_tmp * Ac.t()); + + pV(in, span(j)) = pM_tmp(0, 0); + pV(out, span(j)) = symMat2vec(pM_tmp.submat(1, 1, parameters.nb_var-1, parameters.nb_var -1)); + } + + // Parallel transported sigma (reconstruction from eigenvectors) + mat pSigma(model.sigma[i].n_rows, model.sigma[i].n_cols); + pSigma = pV * pV.t(); + + // Gaussian conditioning on the tangent space + int dim = out.b - out.a + 1; + + mat uOut = logmap_vec(vec(model.mu_man[i](out)), xhat) + + pSigma(out, in) * inv(pSigma(in, in)) * (xIn(t) - model.mu_man[i](in)); + + uhat = uhat + uOut * H_(i); + } + + xhat = expmap_vec(uhat, xhat); + } + + model.xhat.push_back(xhat); + } +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + arma::arma_version ver; + + arma_rng::set_seed_random(); + + + // Parameters + parameters_t parameters; + parameters.nb_states = 10; + parameters.nb_data = 50; + parameters.nb_var = 3; + parameters.nb_var_vec = 4; + parameters.dt = 0.1; + parameters.nb_iter_EM = 5; + parameters.nb_iter = 5; + parameters.diag_reg_fact = 1e-4f; + + + // Initial computation + cube X; + model_t model; + process(parameters, X, model); + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 400; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + // Initialise GLFW + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Gaussian Mixture Regression", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + float workspace_size = (parameters.nb_data + 1) * parameters.dt; + + // Setup GLSL + gfx2::init(); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + + // Main loop + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + + // Detect if the parameters have changed + if ((parameters.nb_data != X.n_slices) || (parameters.nb_states != model.mu_man.size())) { + parameters.nb_states = std::min(parameters.nb_states, parameters.nb_data / 2); + + process(parameters, X, model); + + workspace_size = (parameters.nb_data + 1) * parameters.dt; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + glEnable(GL_BLEND); + + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho(-window_size.fb_width / 2, window_size.fb_width / 2, + -window_size.fb_height / 2, window_size.fb_height / 2, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + + // Draw the datapoints + for (int i = 0; i < parameters.nb_data; ++i) { + gfx2::draw_gaussian( + fvec({ 0.5f, 0.5f, 0.5f, 0.25f }), + vec({ X(0, 0, i) * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 140.0) * window_size.scale_y() + }), + X.subcube(1, 1, i, 2, 2, i) * window_size.fb_width / workspace_size + ); + } + + // Draw the GMM states + for (int i = 0; i < parameters.nb_states; ++i) { + fvec color = COLORS.row(i).t(); + + gfx2::draw_gaussian( + fvec({ color(0), color(1), color(2), 0.5f }), + vec({ model.mu_man[i](0) * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 140.0) * window_size.scale_y() + }), + vec2symMat(vec(model.mu_man[i].subvec(1, 3))) * window_size.fb_width / workspace_size + ); + } + + // Draw the GMR results + vec xIn = linspace<vec>( + 1, parameters.nb_data, parameters.nb_data + ) * parameters.dt; + + for (int t = 0; t < parameters.nb_data; ++t) { + gfx2::draw_gaussian( + fvec({ 0.0f, 1.0f, 0.0f, 0.5f }), + vec({ xIn[t] * window_size.fb_width / workspace_size - window_size.fb_width / 2, + ((double) window_size.win_height / 2 - 240.0) * window_size.scale_y() + }), + vec2symMat(model.xhat[t]) * window_size.fb_width / workspace_size + ); + } + + glDisable(GL_BLEND); + + // Draw the lines + double plot_height = ((double) window_size.win_height - 290.0 - 100) * window_size.scale_y(); + + for (int i = 0; i < parameters.nb_states; ++i) { + mat points(2, parameters.nb_data); + + points(span(0), span::all) = xIn.t() * window_size.fb_width / workspace_size - window_size.fb_width / 2; + + for (int t = 0; t < parameters.nb_data; ++t) { + points(1, t) = model.H[t](i) * plot_height + (50 - window_size.win_height / 2) * window_size.scale_y(); + } + + gfx2::draw_line(fvec(COLORS.row(i).t()), points); + } + + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 80)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove + ); + ImGui::SliderInt("Nb datapoints", ¶meters.nb_data, 10, 100); + ImGui::SliderInt("Nb GMM states", ¶meters.nb_states, 3, std::min(20, parameters.nb_data / 2)); + ImGui::End(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_cov_interp02.cpp b/src/demo_Riemannian_cov_interp02.cpp index 2e7b682..aaa1773 100644 --- a/src/demo_Riemannian_cov_interp02.cpp +++ b/src/demo_Riemannian_cov_interp02.cpp @@ -13,329 +13,292 @@ #include <armadillo> #include <imgui.h> -#include <imgui_impl_glfw.h> -#include <gfx.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx2.h> #include <gfx_ui.h> #include <GLFW/glfw3.h> +#include <window_utils.h> -#include <pbdlib/gmm.h> +using namespace arma; -/********************************** SHADERS **********************************/ +/***************************** ALGORITHM SECTION *****************************/ -static char const *vert_shader_str = STRINGIFY( - void main(){ - gl_TexCoord[0] = gl_MultiTexCoord0; - gl_Position = gl_ProjectionMatrix * gl_ModelViewMatrix * gl_Vertex; - } -); +void trans2d_to_gauss(const ui::Trans2d& gaussian_transforms, + const gfx2::window_size_t& window_size, + arma::vec &mu, arma::mat &sigma) { + mu = gfx2::ui2fb(vec({ gaussian_transforms.pos.x, gaussian_transforms.pos.y }), + window_size); -static char const *frag_shader_str = STRINGIFY( - uniform vec2 Mu; - uniform mat2 Sigma; - uniform vec4 Color; - void main(){ - vec2 e = gl_FragCoord.xy - Mu; - float p = clamp(exp(-(Sigma[0][0] * e.x * e.x - 2 * Sigma[0][1] * e.x * e.y + - Sigma[1][1] * e.y * e.y)), 0, 0.5f); - gl_FragColor = vec4(Color.x, Color.y, Color.z, clamp(Color.a * 2 * p, 0.0, 1.0)); - } -); + vec t_x({ + gaussian_transforms.x.x * window_size.scale_x(), + gaussian_transforms.x.y * window_size.scale_y() + }); + vec t_y({ + gaussian_transforms.y.x * window_size.scale_x(), + gaussian_transforms.y.y * window_size.scale_y() + }); -/********************************* RENDERING *********************************/ + mat RG = { + { t_x(0), t_y(0) }, + { -t_x(1), -t_y(1) } + }; -//----------------------------------------------------------------------------- -// Render a 2d gaussian from its parameters (mu and sigma) -//----------------------------------------------------------------------------- -void render_gaussian(const arma::vec& mu, const arma::mat& sigma, int shader, - const arma::vec& color, float devicePixelRatio) { - - // Compute the gaussian parameters in the fragment shader system coordinates - // (y is 0 at bottom) - arma::vec mu_shad = { - mu(0), - ImGui::GetIO().DisplaySize.y * devicePixelRatio - mu(1) - }; - - // Rendering of the Gaussian "background" with GLSL - gfx::bindShader(shader); - gfx::setVector("Mu", mu_shad); - gfx::setMatrix("Sigma", inv(sigma)); - gfx::setVector("Color", color); - gfx::drawUVQuad(0, 0, ImGui::GetIO().DisplaySize.x * devicePixelRatio, - ImGui::GetIO().DisplaySize.y * devicePixelRatio); - gfx::unbindShader(); - - // Rendering of the Gaussian "border" with standard GL - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, sigma); - arma::mat R = V * diagmat(sqrt(d)); - - arma::mat pts = R * join_cols(cos(linspace<rowvec>(-PI, PI, 60)), - sin(linspace<rowvec>(-PI, PI, 60))); - - glColor3f(0.5 * color(0), 0.5 * color(1), 0.5 * color(2)); - glLineWidth(2.0f); - - glBegin(GL_LINE_STRIP); - for (uint t = 0; t < pts.n_cols; t++) - glVertex2f(mu(0) + pts(0, t), mu(1) + pts(1, t)); - glEnd(); - - // Rendering of the Gaussian position with standard GL - glPointSize(4.); - - glBegin(GL_POINTS); - glVertex2f(mu(0), mu(1)); - glEnd(); + sigma = RG * RG.t(); } +//--------------------------------------------------------- -//----------------------------------------------------------------------------- -// Render a 2d gaussian defined by a transform widget -//----------------------------------------------------------------------------- -void render_gaussian(const ui::Trans2d& gaussian_transforms, int shader, - const arma::vec& color, float devicePixelRatio) { +arma::mat expmap(const arma::mat& U, const arma::mat& S) { + return real(sqrtmat(S) * expmat(inv(sqrtmat(S)) * U * inv(sqrtmat(S))) * sqrtmat(S)); +} - // Compute the gaussian parameters - arma::vec mu = { - gaussian_transforms.pos.x, - gaussian_transforms.pos.y - }; +//--------------------------------------------------------- - arma::mat RG = { - { gaussian_transforms.x.x, gaussian_transforms.y.x }, - { gaussian_transforms.x.y, gaussian_transforms.y.y } - }; +arma::mat logmap(const arma::mat& X, const arma::mat& S) { + return real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * X * inv(sqrtmat(S))) * sqrtmat(S)); +} - mu *= devicePixelRatio; - RG *= devicePixelRatio; +//--------------------------------------------------------- - render_gaussian(mu, RG * RG.t(), shader, color, devicePixelRatio); -} +void interpolate(const std::vector<ui::Trans2d>& gaussian_transforms, + int nb_data, + std::vector<arma::vec> &interpolated_mu, + std::vector<arma::mat> &interpolated_sigma, + const gfx2::window_size_t& window_size) { + + const int nb_var = 2; // Number of variables (fixed, since we use a + // ui::Trans2d to define a gaussian) + const int nb_var2 = nb_var + 1; + + // Transformation to Gaussians with augmented covariances centered on zero + std::vector<arma::mat> augmented_sigma; + + for (size_t i = 0; i < gaussian_transforms.size(); ++i) { + + arma::vec current_mu; + arma::mat sigma; + trans2d_to_gauss(gaussian_transforms[i], window_size, current_mu, sigma); -//----------------------------------------------------------------------------- -// Render a line passing through the provided points -//----------------------------------------------------------------------------- -void render_line(const std::vector<arma::vec>& points, const arma::vec& color) { + arma::mat current_sigma(nb_var2, nb_var2); - glColor3f(color(0), color(1), color(2)); - glLineWidth(2.0f); + current_sigma(0, 0, arma::size(nb_var, nb_var)) = sigma + current_mu * current_mu.t(); + current_sigma(0, nb_var, arma::size(nb_var, 1)) = current_mu; + current_sigma(nb_var, 0, arma::size(1, nb_var)) = current_mu.t(); + current_sigma(nb_var, nb_var) = 1; - glBegin(GL_LINE_STRIP); - for (size_t i = 0; i < points.size(); ++i) - glVertex2f(points[i](0), points[i](1)); - glEnd(); + augmented_sigma.push_back(current_sigma); + } + + // Geodesic interpolation + arma::vec w = arma::linspace(0, 1, nb_data); + + for (size_t i = 1; i < augmented_sigma.size(); ++i) { + for (size_t t = 0; t < nb_data; ++t) { + // Interpolation between two covariances can be computed in closed form + arma::mat sigma = expmap(w(t) * logmap(augmented_sigma[i], augmented_sigma[i-1]), + augmented_sigma[i-1]); + + double beta = sigma(sigma.n_elem - 1); + arma::vec mu = sigma(sigma.n_rows - 1, 0, arma::size(1, sigma.n_cols-1)).t() / beta; + + interpolated_mu.push_back(mu); + interpolated_sigma.push_back(sigma(0, 0, arma::size(sigma.n_rows-1, sigma.n_cols-1)) - beta * mu * mu.t()); + } + } } -/****************************** HELPER FUNCTIONS *****************************/ +/*************************** DEMONSTRATION SECTION ***************************/ static void error_callback(int error, const char* description) { - fprintf(stderr, "Error %d: %s\n", error, description); + fprintf(stderr, "Error %d: %s\n", error, description); } +// ----------------------------------------------------------------------------- +// Render a 2d gaussian from its parameters (mu and sigma) +// ----------------------------------------------------------------------------- +void render_gaussian(const arma::vec& mu, const arma::mat& sigma, + const arma::vec& color, + const gfx2::window_size_t& window_size) { -arma::mat expmap(const arma::mat& U, const arma::mat& S) { - return real(sqrtmat(S) * expmat(inv(sqrtmat(S)) * U * inv(sqrtmat(S))) * sqrtmat(S)); -} + // Rendering of the Gaussian + gfx2::draw_gaussian(conv_to<fvec>::from(color), mu, sigma); + glClear(GL_DEPTH_BUFFER_BIT); -arma::mat logmap(const arma::mat& X, const arma::mat& S) { - return real(sqrtmat(S) * logmat(inv(sqrtmat(S)) * X * inv(sqrtmat(S))) * sqrtmat(S)); -} + // Rendering of the Gaussian position + fvec position({ (float) mu(0), (float) mu(1), 0.0f }); + fvec darker_color = conv_to<fvec>::from(color(span(0, 2))) * 0.5f; -/********************************* FUNCTIONS *********************************/ + gfx2::draw_rectangle(darker_color, 4.0f * window_size.scale_x(), + 4.0f * window_size.scale_y(), position); -void interpolate(const std::vector<ui::Trans2d>& gaussian_transforms, - int nb_data, - std::vector<arma::vec> &interpolated_mu, - std::vector<arma::mat> &interpolated_sigma, - float devicePixelRatio) { - - const int nb_var = 2; // Number of variables (fixed, since we use a - // ui::Trans2d to define a gaussian) - const int nb_var2 = nb_var + 1; - - // Transformation to Gaussians with augmented covariances centered on zero - std::vector<arma::mat> augmented_sigma; - - for (size_t i = 0; i < gaussian_transforms.size(); ++i) { - arma::vec current_mu = { - gaussian_transforms[i].pos.x, - gaussian_transforms[i].pos.y - }; - - arma::mat RG = { - { gaussian_transforms[i].x.x, gaussian_transforms[i].y.x }, - { gaussian_transforms[i].x.y, gaussian_transforms[i].y.y } - }; - - current_mu *= devicePixelRatio; - RG *= devicePixelRatio; - - arma::mat current_sigma(nb_var2, nb_var2); - - current_sigma(0, 0, arma::size(nb_var, nb_var)) = RG * RG.t() + current_mu * current_mu.t(); - current_sigma(0, nb_var, arma::size(nb_var, 1)) = current_mu; - current_sigma(nb_var, 0, arma::size(1, nb_var)) = current_mu.t(); - current_sigma(nb_var, nb_var) = 1; - - augmented_sigma.push_back(current_sigma); - } - - // Geodesic interpolation - arma::vec w = arma::linspace(0, 1, nb_data); - - for (size_t i = 1; i < augmented_sigma.size(); ++i) { - for (size_t t = 0; t < nb_data; ++t) { - // Interpolation between two covariances can be computed in closed form - arma::mat sigma = expmap(w(t) * logmap(augmented_sigma[i], augmented_sigma[i-1]), - augmented_sigma[i-1]); - - double beta = sigma(sigma.n_elem - 1); - arma::vec mu = sigma(sigma.n_rows - 1, 0, arma::size(1, sigma.n_cols-1)).t() / beta; - - interpolated_mu.push_back(mu); - interpolated_sigma.push_back(sigma(0, 0, arma::size(sigma.n_rows-1, sigma.n_cols-1)) - beta * mu * mu.t()); - } - } + glClear(GL_DEPTH_BUFFER_BIT); } +/******************************* MAIN FUNCTION *******************************/ + int main(int argc, char **argv) { - arma_rng::set_seed_random(); - - // Parameters - int nb_states = 2; // Number of states in the GMM - int nb_data = 20; // Length of each trajectory - - // Generate random transform widgets to represent some Gaussians - std::vector<ui::Trans2d> gaussian_transforms; - for (int i = 0; i < nb_states; ++i) { - arma::ivec mu = arma::randi(2, arma::distr_param(100, 500)); - arma::ivec xy = arma::randi(2, arma::distr_param(20, 100)); - gaussian_transforms.push_back(ui::Trans2d(ImVec2(xy(0), 0), ImVec2(0, xy(1)), - ImVec2(mu(0), mu(1)))); - } - - // Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(600, 600, "Covariance interpolation", NULL, NULL); - glfwMakeContextCurrent(window); - - // Setup GLSL - gfx::init(); - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - int shader = gfx::loadShader(vert_shader_str, frag_shader_str); - - // Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - // Take 4k screens into account (framebuffer size != window size) - int win_width = ImGui::GetIO().DisplaySize.x; - int win_height = ImGui::GetIO().DisplaySize.y; - - int fb_width, fb_height; - glfwGetFramebufferSize(window, &fb_width, &fb_height); - - float devicePixelRatio = float(fb_width) / win_width; - - // Main loop - while (!glfwWindowShouldClose(window)) { - glfwPollEvents(); - - // Detect when the window was resized - if ((ImGui::GetIO().DisplaySize.x != win_width) || (ImGui::GetIO().DisplaySize.y != win_height)) { - win_width = ImGui::GetIO().DisplaySize.x; - win_height = ImGui::GetIO().DisplaySize.y; - - glfwGetFramebufferSize(window, &fb_width, &fb_height); - - devicePixelRatio = float(fb_width) / win_width; - } - - // Start of rendering - ImGui_ImplGlfw_NewFrame(); - glViewport(0, 0, fb_width, fb_height); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - gfx::setOrtho(fb_width, fb_height); - - glPushMatrix(); - - // Ensure that the number of desired states hasn't changed - if (nb_states > gaussian_transforms.size()) { - for (int i = gaussian_transforms.size(); i < nb_states; ++i) { - arma::ivec mu = arma::randi(2, arma::distr_param(100, 500)); - arma::ivec xy = arma::randi(2, arma::distr_param(20, 100)); - gaussian_transforms.push_back(ui::Trans2d(ImVec2(xy(0), 0), - ImVec2(0, xy(1)), - ImVec2(mu(0), mu(1)))); - } - } - else if (nb_states < gaussian_transforms.size()) { - gaussian_transforms.resize(nb_states); - } - - // Interpolation between the gaussians - std::vector<arma::vec> interpolated_mu; - std::vector<arma::mat> interpolated_sigma; - - interpolate(gaussian_transforms, nb_data, interpolated_mu, interpolated_sigma, - devicePixelRatio); - - // Rendering of the gaussians - for (size_t i = 0; i < gaussian_transforms.size(); ++i) { - render_gaussian(gaussian_transforms[i], shader, - arma::vec({ 0.5, 0.5, 0.5, 0.5 }), devicePixelRatio); - } - - for (size_t i = 0; i < interpolated_sigma.size(); ++i) { - render_gaussian(interpolated_mu[i], interpolated_sigma[i], shader, - arma::vec({ 0.8, 0.0, 0.0, 0.02 }), devicePixelRatio); - } - - render_line(interpolated_mu, arma::vec({ 0.8, 0.0, 0.0 })); - - // Gaussian UI widgets - ui::begin("Gaussians"); - for (size_t i = 0; i < gaussian_transforms.size(); ++i) - gaussian_transforms[i] = ui::affineSimple(i, gaussian_transforms[i]); - ui::end(); - - // Parameter window - ImGui::Begin("Parameters", NULL, ImVec2(250, 80), 0.5f, - ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings); - ImGui::SliderInt("Nb states", &nb_states, 2, 5); - ImGui::SliderInt("Nb data", &nb_data, 5, 30); - ImGui::End(); - - // GUI rendering - ImGui::Render(); - - // End of rendering - glPopMatrix(); - glfwSwapBuffers(window); - - // Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - // Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; + arma_rng::set_seed_random(); + + // Parameters + int nb_states = 2; // Number of states in the GMM + int nb_data = 20; // Length of each trajectory + + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 600; + window_size.win_height = 600; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + // Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Covariance interpolation", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + // glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + // Main loop + std::vector<ui::Trans2d> gaussian_transforms; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(-window_size.fb_width / 2, window_size.fb_width / 2, + -window_size.fb_height / 2, window_size.fb_height / 2, + -1.0f, 10.0f); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + glPushMatrix(); + + // Ensure that the number of desired states hasn't changed (only once everything + // is initialised) + if (window_size.fb_width > 0) { + if (nb_states > gaussian_transforms.size()) { + for (int i = gaussian_transforms.size(); i < nb_states; ++i) { + arma::vec mu = arma::randu(2); + mu(0) = mu(0) * (window_size.win_width - 200) + 100; + mu(1) = mu(1) * (window_size.win_height - 200) + 100; + + arma::vec xy = arma::randu(2); + xy(0) = (xy(0) * window_size.win_width / 6 + 20); + xy(1) = (xy(1) * window_size.win_height / 6 + 20); + + gaussian_transforms.push_back(ui::Trans2d(ImVec2((int) xy(0), 0), + ImVec2(0, (int) xy(1)), + ImVec2((int) mu(0), (int) mu(1)))); + } + } + else if (nb_states < gaussian_transforms.size()) { + gaussian_transforms.resize(nb_states); + } + } + + // Interpolation between the gaussians + std::vector<arma::vec> interpolated_mu; + std::vector<arma::mat> interpolated_sigma; + + interpolate(gaussian_transforms, nb_data, interpolated_mu, interpolated_sigma, + window_size); + + // Rendering of the gaussians + for (size_t i = 0; i < interpolated_sigma.size(); ++i) { + render_gaussian(interpolated_mu[i], interpolated_sigma[i], + arma::vec({ 0.8, 0.0, 0.0, 0.02 }), window_size); + } + + for (size_t i = 0; i < gaussian_transforms.size(); ++i) { + arma::vec mu; + arma::mat sigma; + + trans2d_to_gauss(gaussian_transforms[i], window_size, mu, sigma); + + render_gaussian(mu, sigma, arma::vec({ 0.5, 0.5, 0.5, 0.5 }), window_size); + } + + gfx2::draw_line(arma::fvec({ 0.8f, 0.0f, 0.0f }), interpolated_mu); + + // Gaussian UI widgets + ui::begin("Gaussians"); + for (size_t i = 0; i < gaussian_transforms.size(); ++i) + gaussian_transforms[i] = ui::affineSimple(i, gaussian_transforms[i]); + ui::end(); + + // Parameter window + ImGui::Begin("Parameters", NULL, ImVec2(250, 80), 0.5f, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings); + ImGui::SliderInt("Nb states", &nb_states, 2, 5); + ImGui::SliderInt("Nb data", &nb_data, 5, 30); + ImGui::End(); + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // End of rendering + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; } diff --git a/src/demo_Riemannian_pose_batchLQR01.cpp b/src/demo_Riemannian_pose_batchLQR01.cpp new file mode 100644 index 0000000..d8ee330 --- /dev/null +++ b/src/demo_Riemannian_pose_batchLQR01.cpp @@ -0,0 +1,625 @@ +/* + * demo_Riemannian_pose_batchLQR.cpp + * + * Batch LQR for R3 x S3 pose data. + * + * Created on: Nov 3, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> +#include <vector> +#include <ctime> + +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_internal.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <window_utils.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } +}; + +//----------------------------------------------- + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +int factorial(int n) { + return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { { q(0),-q(1),-q(2),-q(3)}, + { q(1), q(0),-q(3), q(2)}, + { q(2), q(3), q(0),-q(1)}, + { q(3),-q(2), q(1), q(0)}}; + + return Q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z + << 2 * y * z - 2 * x * w << endr << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat Qexpfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat Qlogfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + if (scale.has_nan()) { + scale = 1.0; + } + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat Qexpmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * Qexpfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat Qlogmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) + Q = { { 1,0,0,0}, + { 0,1,0,0}, + { 0,0,1,0}, + { 0,0,0,1}}; + else + Q = QuatMatrix(mu); + + arma::mat u; + u = Qlogfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat Qtransp(vec g, vec h) { + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = Qlogmap(h, g); + + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + + colvec uv = vm / mn; + + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + + return Ac; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat Ac = eye(6, 6); + + if (norm(g - h, 2) == 0) { + Ac = eye(6, 6); + } else { + Ac.submat(3, 3, 5, 5) = Qtransp(g.subvec(3, 6), h.subvec(3, 6)); + } + + return Ac; +} + +//----------------------------------------------- + +arma::vec logmap(vec x, vec mu) { + vec u = join_vert(x.subvec(0, 2), Qlogmap(x.subvec(3, 6), mu.subvec(3, 6))); + return u; +} + +//----------------------------------------------- + +arma::vec expmap(vec u, vec mu) { + vec x = join_vert(u.subvec(0, 2), Qexpmap(u.subvec(3, 5), mu.subvec(3, 6))); + return x; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, + { 0.00f, 0.75f, 0.75f }, + { 0.75f, 0.00f, 0.75f }, + { 0.75f, 0.75f, 0.00f }, + { 0.25f, 0.25f, 0.25f }, + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, +}); + +//----------------------------------------------- + +int main(int argc, char **argv) { + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 780; + window_size.win_height = 540; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Riemannian Pose batchLQR", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + glEnable (GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui binding + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + // white background + ImVec4 clear_color = ImColor(255, 255, 255); + ImVector<ImVec2> points, velocities; + float filterAlphaPos = 0.5; + + // Load Fonts + ImGuiIO& io = ImGui::GetIO(); + io.Fonts->AddFontDefault(); + ui::init(20.); + + arma_rng::set_seed_random(); + + int nbData = 100; //Number of datapoints + + int nbVarTan = 3 + 3; //Dimension of tangent space data (here: TE3 + TS3) + int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) + int nbVar = nbVarTan * nbDeriv; //Dimension of tangent state space + int nbVarMan = nbVarTan + 1; //Dimension of the manifold (here: E3 + S3) + double params_diagRegFact = 1E-4; //Regularization of covariance + double dt = 1E-3; //Time step duration + double rfactor = 1E-7; //Control cost in LQR + double rfactor_pos = 1E-7; + int nbRepros = 5; + int nbRepros_prev = 5; + int nbD = 20; // time horizon for LQR + + //Control cost matrix + mat R = eye(nbVarTan, nbVarTan) * rfactor; + R.submat(0, 0, 2, 2) = eye(3, 3) * rfactor_pos; + R = kron(eye(nbD - 1, nbD - 1), R); + + //Target and desired covariance + colvec xTar; + xTar = (randn(4)) * 3; + xTar = xTar / norm(xTar, 2); + xTar = join_vert(randn(3), xTar); + + mat uCov = eye(2 * nbVarTan, 2 * nbVarTan) * 1E10; // also include velocity + uCov.submat(0, 0, nbVarTan - 1, nbVarTan - 1) = eye(nbVarTan, nbVarTan) * 1E-2; //position and orientation + uCov.submat(0, 0, 2, 2) = eye(3, 3) * 1E-2; // position + mat tmpMatRandn = randn(nbVarTan, nbVarTan ) * .09; //random variance on position + uCov.submat(0, 0, nbVarTan - 1, nbVarTan - 1) = tmpMatRandn * tmpMatRandn.t(); + + //Eigendecomposition + vec tmpEigenValues; + mat tmpEigenVectors; + eig_sym(tmpEigenValues, tmpEigenVectors, uCov); + mat U0 = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + mat A = eye(nbVarTan * 2, nbVarTan * 2); + A.submat(0, nbVarTan, nbVarTan - 1, (nbVarTan * 2) - 1) = eye(nbVarTan, nbVarTan) * dt; + + mat B = join_vert(eye(nbVarTan, nbVarTan) * pow(dt, 2) / factorial(2), eye(nbVarTan, nbVarTan) * dt); + mat Su = zeros(nbVar * nbD, nbVarTan * (nbD - 1)); + mat Sx = kron(ones(nbD, 1), eye(nbVar, nbVar)); + mat M = B; + + for (int n = 2; n < nbD + 1; n++) { + Sx.rows(span((n - 1) * nbVar, nbD * nbVar - 1)) = Sx.rows(span((n - 1) * nbVar, nbD * nbVar - 1)) * A; + Su.submat(span((n - 1) * nbVar, n * nbVar - 1), span(0, (n - 1) * nbVarTan - 1)) = M; + M = join_horiz(A * M.cols(span(0, nbVarTan - 1)), M); + } + colvec duTar = zeros(nbVarTan * (nbDeriv - 1), 1); + + bool recompute = true; + bool init = true; + cube Xsave(7, nbData, nbRepros); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + ImGui_ImplGlfwGL2_NewFrame(); + + if (init) + ImGui::SetNextWindowPos(ImVec2(450, 430)); + + ui::begin("demo"); + ImGuiWindow *win = ImGui::GetCurrentWindow(); + ui::end(); + + if (init) { // Init the control panel + ImGui::SetNextWindowPos(ImVec2(2, 2)); + ImGui::SetNextWindowCollapsed(false); //true); + } + + nbRepros_prev = nbRepros; + ImGui::SetNextWindowSize(ImVec2(400, 54)); + ImGui::Begin("Parameters", NULL, ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings | ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb repros", &nbRepros, 1, 10); + + ImVec4 clip_rect2(0, 0, window_size.win_width, window_size.win_height); + + // time + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 4 - 20, window_size.win_height - 40), + ImColor(0, 0, 0, 255), "time", + NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(3 * window_size.win_width / 4 - 20, window_size.win_height - 40), + ImColor(0, 0, 0, 255), "time", + NULL, 0.0f, &clip_rect2); + + // xyz + int plot_height_px = (window_size.win_height - 50) / 4 - 50; + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, 3 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "z", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, 2 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "y", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "x", NULL, 0.0f, &clip_rect2); + + // qw qx qy qz + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 3 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qz", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 2 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qy", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qx", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qw", NULL, 0.0f, &clip_rect2); + + ImGui::End(); + + // Recompute if needed + if (init || (nbRepros_prev != nbRepros)) { + xTar = (randn(4)) * 3; + xTar = xTar / norm(xTar, 2); + xTar = join_vert(randn(3), xTar); + xTar = join_vert(xTar, zeros(6, 1)); //add 0 velocity + Xsave.clear(); + Xsave = zeros(7, nbData, nbRepros); + // cout << "Recomputing..." << endl; + for (int r = 0; r < nbRepros; r++) { + + vec x; + x << 0 << 0 << 0 << -1 << -1 << 1 << 0; + x = x + randn(nbVarMan) * 1.5; + + vec tmpVec = { 0, 0, 0 }; + x.subvec(3, 6) = x.subvec(3, 6) / norm(x.subvec(3, 6), 2); + + vec x_old = x; + vec U = zeros(nbVar, 1); + + mat Ac; + mat U1; + mat uCovTmp; + mat Q = zeros(nbVar, nbVar); + mat P, L; + vec ddu; + colvec MuQ; + mat SigmaQ; + mat Acblkdiag = zeros(2 * nbVarTan, 2 * nbVarTan); + colvec duTmp; + mat SuInvSigmaQ; + mat Rq; + vec rq; + vec tmpEigenValues; + mat tmpEigenVectors; + + for (int t = 0; t < nbData; t++) { + Xsave.slice(r).col(t) = x; //Log data + U.subvec(0, nbVarTan - 1) = zeros(nbVarTan, 1); //Set tangent space at x + Ac = transp(x_old, x); + U.subvec(nbVarTan, nbVarTan + 5) = Ac * U.subvec(nbVarTan, nbVarTan + 5); + U.subvec(0, 2) = x.subvec(0, 2); // transport of position + + //Create single Gaussian N(MuQ,SigmaQ) based on optimal state sequence q + MuQ = zeros(nbVar * nbD, 1); + SigmaQ = zeros(nbVar * nbD, nbVar * nbD); + + for (int s = 0; s < nbD; s++) { + //Transportation of Sigma and duCov from model.MuMan to x + Ac = transp(xTar.subvec(0, nbVarMan - 1), x); + Acblkdiag.submat(0, 0, nbVarTan - 1, nbVarTan - 1) = Ac; + Acblkdiag.submat(nbVarTan, nbVarTan, 2 * nbVarTan - 1, 2 * nbVarTan - 1) = Ac; + + SigmaQ(span(s * nbVar, (s + 1) * nbVar - 1), span(s * nbVar, (s + 1) * nbVar - 1)) = Acblkdiag * uCov * Acblkdiag.t(); + + //Transportation of du from model.MuMan to x + duTmp = Ac * xTar.subvec(nbVarMan, nbVarMan + 5); + MuQ.subvec(s * nbVar, (s + 1) * nbVar - 1) = join_vert(logmap(xTar.subvec(0, nbVarMan), x), duTmp); + } + + //Compute acceleration commands + SuInvSigmaQ = Su.t() * inv(SigmaQ); + Rq = SuInvSigmaQ * Su + R; + rq = SuInvSigmaQ * (MuQ - Sx * U); + ddu = inv(Rq) * rq; + + tmpVec = (MuQ - Sx * U); + + eig_sym(tmpEigenValues, tmpEigenVectors, uCov); + + U = A * U + B * ddu.subvec(0, nbVarTan - 1); // Update U with first control command + x_old = x; //Keep x for next iteration + x = expmap(U.subvec(0, nbVarTan -1), x); //%Update x + + } + + if (Xsave.slice(r).has_nan()) { + cout << "Reproduction #" << r << " has NaN!" << endl; + } + + if (all((Xsave.slice(r).col(nbData - 1).subvec(3, 6) % xTar.subvec(3, 6)) < 0)) { + Xsave.slice(r).rows(3, 6) = Xsave.slice(r).rows(3, 6) * -1.0; + } + + } + recompute = false; + } + + //======================== GUI rendering ======================== + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear (GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + //======================== PbDlib rendering ======================== + glPushMatrix(); + glTranslatef(-1.0f, -1.0f, 0); + glScalef(2.0f / (float) window_size.fb_width, + 2.0f / (float) window_size.fb_height, 1.0f); + glLineWidth(2.0f); + + //======================== PLOTTING ======================== + float lineWidth = 1.5; + float biasX = 0.0; + float biasY = 0.0; + float scalerX = 1.0; + float scalerY = 1.0; + float min_value = 0.0; + + float max_xyz = std::max(Xsave(span(0, 2), span::all, span::all).max(), xTar(span(0, 2)).max()); + float min_xyz = std::min(Xsave(span(0, 2), span::all, span::all).min(), xTar(span(0, 2)).min()); + float max_q = std::max(Xsave(span(3, 6), span::all, span::all).max(), xTar(span(3, 6)).max()); + float min_q = std::min(Xsave(span(3, 6), span::all, span::all).min(), xTar(span(3, 6)).min()); + + float plot_width = (window_size.fb_width / 2 - 100 * window_size.scale_x()); + float plot_height = (window_size.fb_height - 50 * window_size.scale_y()) / 4 - + 50 * window_size.scale_y(); + + for (int r = 0; r < nbRepros; r++) { + + for (int i = 0; i < 7; i++) { + + scalerX = plot_width / nbData; + + if (i < 3) { + biasX = 50.0 * window_size.scale_x(); + biasY = (2 - i) * (plot_height + 50 * window_size.scale_y()) + + 50 * window_size.scale_y(); + + scalerY = plot_height / (max_xyz - min_xyz); + min_value = min_xyz; + + } else { + biasX = window_size.fb_width / 2 + 50.0 * window_size.scale_x(); + + biasY = (6 - i) * (plot_height + 50 * window_size.scale_y()) + + 50 * window_size.scale_y(); + + scalerY = plot_height / (max_q - min_q); + min_value = min_q; + } + + if (r == 0) { //plot the background + glColor3f(0.9f, 0.9f, 0.9f); + + glBegin (GL_QUADS); + glVertex2f(biasX, biasY); + glVertex2f(biasX + plot_width, biasY); + glVertex2f(biasX + plot_width, biasY + plot_height); + glVertex2f(biasX, biasY + plot_height); + glEnd(); + } + + glLineWidth(lineWidth); + glColor3f(COLORS(r, 0), COLORS(r, 1), COLORS(r, 2)); + + glBegin (GL_LINE_STRIP); + float dummyx; + float dummyy; + for (int t = 0; t < Xsave.n_cols - 1; t++) { + dummyx = t * scalerX + biasX; + dummyy = (float) (Xsave.slice(r)(i, t) - min_value) * scalerY + biasY; + glVertex2f(dummyx, dummyy); + } + glEnd(); + + if (r == 0) { //plot the reference + glLineWidth(lineWidth); + glColor3f(0.0f, 0.0f, 0.0f); + glBegin(GL_LINE_STRIP); + float dummyx; + float dummyy; + for (int t = 0; t < Xsave.n_cols - 1; t++) { + dummyx = t * scalerX + biasX; + dummyy = (xTar(i) - min_value) * scalerY + biasY; + glVertex2f(dummyx, dummyy); + } + glEnd(); + } + } + } + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + init = false; + } + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_pose_gmm01.cpp b/src/demo_Riemannian_pose_gmm01.cpp new file mode 100644 index 0000000..c7ac8af --- /dev/null +++ b/src/demo_Riemannian_pose_gmm01.cpp @@ -0,0 +1,363 @@ +/* + * demo_Riemannian_pose_gmm.cpp + * + * GMM on R3 x S3. + * + * Created on: Nov 24, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +using namespace arma; + + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { { q(0),-q(1),-q(2),-q(3)}, + { q(1), q(0),-q(3), q(2)}, + { q(2), q(3), q(0),-q(1)}, + { q(3),-q(2), q(1), q(0)}}; + + return Q; +} + +//----------------------------------------------- + +arma::colvec QuatVector(arma::mat Q) { + arma::colvec q; + q = Q.col(0); + return q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z + << 2 * y * z - 2 * x * w << endr << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat Qexpfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat Qlogfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + if (scale.has_nan()) { + for (int i = 0; i < x.n_cols; i++) { + if (scale.row(0).has_nan()) { + scale(0, i) = 1.0; + } + } + } + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat Qexpmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * Qexpfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat Qlogmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) + Q = { { 1,0,0,0}, + { 0,1,0,0}, + { 0,0,1,0}, + { 0,0,0,1}}; + else + Q = QuatMatrix(mu); + + arma::mat u; + u = Qlogfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat Qtransp(vec g, vec h) { + + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = Qlogmap(h, g); + + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + + colvec uv = vm / mn; + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + + return Ac; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat Ac = eye(6, 6); + + if (norm(g - h, 2) == 0) { + Ac = eye(6, 6); + } else { + Ac.submat(3, 3, 5, 5) = Qtransp(g.subvec(3, 6), h.subvec(3, 6)); + } + + return Ac; +} + +//----------------------------------------------- + +arma::mat logmap(mat x, vec mu) { + mat u = join_vert(x.rows(0, 2), Qlogmap(x.rows(3, 6), mu.subvec(3, 6))); + return u; +} + +//----------------------------------------------- + +arma::mat expmap(mat u, vec mu) { + mat x = join_vert(u.rows(0, 2), Qexpmap(u.rows(3, 5), mu.subvec(3, 6))); + return x; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + + arma_rng::set_seed_random(); + + bool init = true; + int nbStates = 5; + int nbStates_prev = 5; + int nbVar = 6; + int nbSamples = 250; + int nbVarMan = 7; + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + int nbDemo = 5; + + vec e0 = { 0, 0, 0, 1.0, 0.0, 0, 0.0 }; // center on manifold + + mat demo(nbVarMan, nbSamples); + demo.load("./data/data_pose_gmm_XU.txt"); + + mat demoX = demo; // data = [X, [U; 0]] + mat demoU = demoX.submat(0, nbSamples, nbVar - 1, 2 * nbSamples - 1); + demoX = demoX.submat(0, 0, nbVarMan - 1, nbSamples - 1); + + cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + // ================== Recomputing tpgmm model with the latest task parameters ====================== + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + vec Priors(nbStates); + cube Sigma(nbVar, nbVar, nbStates); + mat Mu(nbVar, nbStates); + + // ++++++++++++++++++++++ RANDOM INIT ++++++++++++++++++ + /* arma_rng::set_seed_random(); // set the seed to a random value + + Priors = ones(nbStates); + Priors /= nbStates; + + // Random init the means and covariances + //cout << "init menas and covs" << endl; + // 5 x nbStates + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < (1 + 2 * (nbVar - 1)); j++) { + Mu(j, i) = randn(); + } + } + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1)) * 0.5; //%Covariance in the tangent plane at point MuMan + } + */ + // +++++++++++++++++++++++ KBINS INIT +++++++++++++++++++++++ + vec nbSamplesCumSum = {1, 50, 100, 150, 200, 250 }; + + if (init || (nbStates != nbStates_prev)) { + cout << "Recomputing the model... " << endl; + for (int i = 0; i < nbStates; i++) { + rowvec id; + + for (int n = 0; n < nbDemo; n++) { + vec indices = round(nbSamplesCumSum(n)-1 + linspace(0, nbSamples/nbDemo - 1, nbStates + 1)); + vec vecDummy = round(linspace(indices(i), indices(i + 1), indices(i + 1) - indices(i))); + id = join_horiz(id, vecDummy.t()); + } + + Priors(i) = id.n_elem; + + mat demoUColID = zeros(nbVar, id.n_cols); + + for (int j = 0; j < id.n_elem; j++) { + demoUColID.col(j) = demoU.col((uint) id(j)); + } + + Mu.col(i) = mean(demoUColID, 1); + Sigma.slice(i) = cov(demoUColID.t()) + eye(nbVar, nbVar) * 1E-4; + } + Priors = Priors / sum(Priors); + + int totalSamples = nbSamplesCumSum(nbSamplesCumSum.n_elem - 1); + + // +++++++++++++++++++++++++ INIT END +++++++++++++++++++++++++++++++++ + cout << " starting EM " << endl; + + mat MuMan = expmap(Mu, e0); + Mu.rows(3, 5) = zeros(3, nbStates); + + mat utmp2; + + cube u(nbVar , nbSamples, nbStates); //uTmp in matlab code + + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + mat xcTmp; + float multiplier = 1E-5; + + for (int i = 0; i < nbStates; i++) { + + xcTmp = logmap(demoX, MuMan.col(i)); + + while (true) { // sometimes the starting Mu is far from our data => add bigger regularization + L.row(i) = Priors(i) * (gaussPDF(xcTmp, Mu.col(i), Sigma.slice(i) + eye(nbVar, nbVar) * multiplier).t()); + if (norm(L.row(i), 2) == 0) { + multiplier *= 10.0; + // cout << "EM step #" << i << ", multiplier: " << multiplier << endl; + } else { + break; + } + } + } + + rowvec Lsum = sum(L, 0) + 1E-308; + + mat GAMMA = L / repmat(Lsum, nbStates, 1); + + colvec GammaSum = sum(GAMMA, 1); + + mat GAMMA2 = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + + //Update MuMan + for (int n = 0; n < nbIter; n++) { + u.slice(i) = logmap(demoX, MuMan.col(i)); + MuMan.col(i) = expmap(u.slice(i) * GAMMA2.row(i).t(), MuMan.col(i)); + } + + Mu.submat(0, i, 2, i) = MuMan.col(i).subvec(0, 2); + + utmp2 = u.slice(i); + utmp2.each_col() -= Mu.col(i); + + //Update Sigma + Sigma.slice(i) = utmp2 * diagmat(GAMMA2.row(i)) * utmp2.t() + eye( nbVar, nbVar) * params_diagRegFact; + } + } + + for (int i = 0; i < nbStates; i++) { + cout << "============= Component #" << i << " ===========" << endl; + cout << "Prior: " << Priors(i) << endl; + cout << "MuMan:" << endl; + cout << MuMan.col(i).t() << endl; + cout << "Sigma: " << endl; + cout << Sigma.slice(i) << endl << endl; + } + } + + return 0; +} diff --git a/src/demo_Riemannian_pose_infHorLQR01.cpp b/src/demo_Riemannian_pose_infHorLQR01.cpp new file mode 100644 index 0000000..fb83376 --- /dev/null +++ b/src/demo_Riemannian_pose_infHorLQR01.cpp @@ -0,0 +1,614 @@ +/* + * demo_Riemannian_pose_infHorLQR.cpp + * + * Infinite horizon LQR for R3 x S3 pose. + * + * Created on: Nov 2, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <vector> + +#include <armadillo> + +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_internal.h> +#include <imgui_impl_glfw_gl2.h> +#include <gfx_ui.h> +#include <window_utils.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } +}; + +//----------------------------------------------- + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { { q(0),-q(1),-q(2),-q(3)}, + { q(1), q(0),-q(3), q(2)}, + { q(2), q(3), q(0),-q(1)}, + { q(3),-q(2), q(1), q(0)}}; + + return Q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z + << 2 * y * z - 2 * x * w << endr << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat Qexpfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat Qlogfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + if (scale.has_nan()) { + scale = 1.0; + } + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat Qexpmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * Qexpfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat Qlogmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) + Q = { { 1,0,0,0}, + { 0,1,0,0}, + { 0,0,1,0}, + { 0,0,0,1}}; + else + Q = QuatMatrix(mu); + + arma::mat u; + u = Qlogfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat Qtransp(vec g, vec h) { + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = Qlogmap(h, g); + + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + + colvec uv = vm / mn; + + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + + return Ac; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat Ac = eye(6, 6); + Ac.submat(3, 3, 5, 5) = Qtransp(g.subvec(3, 6), h.subvec(3, 6)); + return Ac; +} + +//----------------------------------------------- + +arma::vec logmap(vec x, vec mu) { + vec u = join_vert(x.subvec(0, 2), Qlogmap(x.subvec(3, 6), mu.subvec(3, 6))); + return u; +} + +//----------------------------------------------- + +arma::vec expmap(vec u, vec mu) { + vec x = join_vert(u.subvec(0, 2), Qexpmap(u.subvec(3, 5), mu.subvec(3, 6))); + return x; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +arma::mat solveAlgebraicRiccati_eig_discrete(mat A, mat B, mat Qx, mat R) { + // Ajay Tanwani, 2016 + + int n = A.n_rows; + mat Q = (Qx + Qx.t()) / 2; // mat Q here corresponds to (Q+Q')/2 specified in set_problem + mat G = B * R.i() * B.t(); + mat Z(2 * n, 2 * n); + Z(span(0, n - 1), span(0, n - 1)) = A + G * inv(A.t()) * Q; + Z(span(0, n - 1), span(n, 2 * n - 1)) = -G * inv(A.t()); + Z(span(n, 2 * n - 1), span(0, n - 1)) = -inv(A.t()) * Q; + Z(span(n, 2 * n - 1), span(n, 2 * n - 1)) = inv(A.t()); + + //Using diagonalization + cx_mat V(2 * n, 2 * n), U(2 * n, n); + cx_vec dd(2 * n); + + arma::eig_gen(dd, V, Z); + + int i = 0; + for (int j = 0; j < 2 * n; j++) { + if (norm(dd(j)) < 1) { + U.col(i) = V.col(j); + i++; + } + } + + mat X = real(U(span(n, 2 * n - 1), span(0, n - 1)) * U(span(0, n - 1), span(0, n - 1)).i()); + + return X; +} + +//----------------------------------------------- + +const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, + { 0.00f, 0.75f, 0.75f }, + { 0.75f, 0.00f, 0.75f }, + { 0.75f, 0.75f, 0.00f }, + { 0.25f, 0.25f, 0.25f }, + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, +}); + +//----------------------------------------------- + +int main(int argc, char **argv) { + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 780; + window_size.win_height = 540; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Riemannian Pose InfHorLQR", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + glEnable (GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui binding + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + // white background + ImVec4 clear_color = ImColor(255, 255, 255); + ImVector<ImVec2> points, velocities; + float filterAlphaPos = 0.5; + + // Load Fonts + ImGuiIO& io = ImGui::GetIO(); + io.Fonts->AddFontDefault(); + ui::init(20.); + + arma_rng::set_seed_random(); + + int nbData = 100; //Number of datapoints + + int nbVarTan = 3 + 3; //Dimension of tangent space data (here: TE3 + TS3) + int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) + int nbVar = nbVarTan * nbDeriv; //Dimension of tangent state space + int nbVarMan = nbVarTan + 1; //Dimension of the manifold (here: E3 + S3) + double params_diagRegFact = 1E-4; //Regularization of covariance + double dt = 1E-2; //Time step duration + double rfactor = 1E-1; //Control cost in LQR + int nbRepros = 5; + int nbRepros_prev = 5; + + //Control cost matrix + mat R = eye(nbVarTan, nbVarTan) * rfactor; + //R.submat(0, 0, 2, 2)=diagmat(ones(3,1)*1E-1); % Set different position control cost + + //Target and desired covariance + colvec xTar; + xTar = (randn(4)) * 3; + xTar = xTar / norm(xTar, 2); + xTar = join_vert(randn(3), xTar); + + mat uCov = eye(nbVarTan, nbVarTan) * 1E-3; + + //Eigendecomposition + vec tmpEigenValues; + mat tmpEigenVectors; + eig_sym(tmpEigenValues, tmpEigenVectors, uCov); + mat U0 = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + mat A = eye(nbVarTan * 2, nbVarTan * 2); + A.submat(0, nbVarTan, nbVarTan - 1, (nbVarTan * 2) - 1) = eye(nbVarTan, nbVarTan) * dt; + mat B = join_vert(eye(nbVarTan, nbVarTan) * pow(dt, 2), eye(nbVarTan, nbVarTan) * dt); + + colvec duTar = zeros(nbVarTan * (nbDeriv - 1), 1); + + bool recompute = true; + bool init = true; + cube Xsave(7, nbData, nbRepros); + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + ImGui_ImplGlfwGL2_NewFrame(); + + if (init) + ImGui::SetNextWindowPos(ImVec2(450, 430)); + + ui::begin("demo"); + ImGuiWindow *win = ImGui::GetCurrentWindow(); + ui::end(); + + if (init) { // Init the control panel + ImGui::SetNextWindowPos(ImVec2(2, 2)); + ImGui::SetNextWindowCollapsed(false); //true); + } + + nbRepros_prev = nbRepros; + ImGui::SetNextWindowSize(ImVec2(400, 54)); + ImGui::Begin("Parameters", NULL, ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings | ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb repros", &nbRepros, 1, 10); + + ImVec4 clip_rect2(0, 0, window_size.win_width, window_size.win_height); + + // time + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 4 - 20, window_size.win_height - 40), + ImColor(0, 0, 0, 255), "time", + NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(3 * window_size.win_width / 4 - 20, window_size.win_height - 40), + ImColor(0, 0, 0, 255), "time", + NULL, 0.0f, &clip_rect2); + + // xyz + int plot_height_px = (window_size.win_height - 50) / 4 - 50; + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, 3 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "z", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, 2 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "y", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(20, (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "x", NULL, 0.0f, &clip_rect2); + + // qw qx qy qz + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 3 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qz", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 2 * (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qy", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + (plot_height_px + 50) + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qx", NULL, 0.0f, &clip_rect2); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(window_size.win_width / 2 + 10, + 50 + plot_height_px / 2 - 10), + ImColor(0, 0, 0, 255), "qw", NULL, 0.0f, &clip_rect2); + + ImGui::End(); + + // Recompute if needed + if (init || (nbRepros_prev != nbRepros)) { + + xTar = (randn(4)) * 3; + xTar = xTar / norm(xTar, 2); + xTar = join_vert(randn(3), xTar); + Xsave.clear(); + Xsave = zeros(7, nbData, nbRepros); + for (int r = 0; r < nbRepros; r++) { + + vec x; + x << 0 << 0 << 0 << -1 << -1 << 1 << 0; + + x = x + randn(nbVarMan) * 1.5; + + vec tmpVec = { 0, 0, 0 }; + //x.subvec(0, 2) = tmpVec; // Start position + x.subvec(3, 6) = x.subvec(3, 6) / norm(x.subvec(3, 6), 2); + vec x_old = x; + vec U = zeros(nbVar, 1); + + mat Ac; + mat U1; + mat uCovTmp; + mat Q = zeros(nbVar, nbVar); + mat P, L; + vec ddu; + + + for (int t = 0; t < nbData; t++) { + Xsave.slice(r).col(t) = x; + U.subvec(0, nbVarTan - 1) = zeros(nbVarTan, 1); //Set tangent space at x + + //Transportation of velocity vector from x_old to x + if (norm(x_old - x, 2) != 0) { // haven't reached target + Ac = transp(x_old, x); + } else { + Ac = eye(nbVarTan, nbVarTan); + } + + U.subvec(nbVarTan, (2 * nbVarTan) - 1) = Ac * U.subvec(nbVarTan, (2 * nbVarTan) - 1); //Transport of velocity + U.subvec(0, 2) = x.subvec(0, 2); // Transport of position (action part) + + //Transportation of uCov from xTar to x + Ac = transp(xTar, x); + if (norm(xTar - x, 2) != 0) { // haven't reached target + Ac = transp(xTar, x); + } else { + Ac = eye(nbVarTan, nbVarTan); + } + U1 = Ac * U0; + uCovTmp = U1 * U1.t(); + + Q = zeros(nbVar, nbVar); + Q.submat(0, 0, nbVarTan - 1, nbVarTan - 1) = inv(uCovTmp); //Precision matrix + P = solveAlgebraicRiccati_eig_discrete(A, B, Q, R); // * (inv(R) * B.t()), (Q + Q.t()) / 2); + + + L = inv(B.t() * P * B + R) * B.t() * P * A; //Feedback gain (discrete version) + ddu = L * (join_vert(logmap(xTar, x), duTar) - U); //Compute acceleration + U = A * U + B * ddu; //Update U + x_old = x; + + x = expmap(U.subvec(0, nbVarTan - 1), x); + } + + if (all((Xsave.slice(r).col(nbData - 1).subvec(3, 6) % xTar.subvec(3, 6)) < 0)) { + Xsave.slice(r).rows(3, 6) = Xsave.slice(r).rows(3, 6) * -1.0; + } + + } + recompute = false; + } + + //======================== GUI rendering ======================== + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear (GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + //======================== PbDlib rendering ======================== + glPushMatrix(); + glTranslatef(-1.0f, -1.0f, 0); + glScalef(2.0f / (float) window_size.fb_width, + 2.0f / (float) window_size.fb_height, 1.0f); + glLineWidth(2.0f); + + //======================== PLOTTING ======================== + float lineWidth = 1.5; + float biasX = 0.0; + float biasY = 0.0; + float scalerX = 1.0; + float scalerY = 1.0; + float min_value = 0.0; + + float max_xyz = std::max(Xsave(span(0, 2), span::all, span::all).max(), xTar(span(0, 2)).max()); + float min_xyz = std::min(Xsave(span(0, 2), span::all, span::all).min(), xTar(span(0, 2)).min()); + float max_q = std::max(Xsave(span(3, 6), span::all, span::all).max(), xTar(span(3, 6)).max()); + float min_q = std::min(Xsave(span(3, 6), span::all, span::all).min(), xTar(span(3, 6)).min()); + + float plot_width = (window_size.fb_width / 2 - 100 * window_size.scale_x()); + float plot_height = (window_size.fb_height - 50 * window_size.scale_y()) / 4 - + 50 * window_size.scale_y(); + + for (int r = 0; r < nbRepros; r++) { + + for (int i = 0; i < 7; i++) { + scalerX = plot_width / nbData; + + if (i < 3) { + biasX = 50.0 * window_size.scale_x(); + biasY = (2 - i) * (plot_height + 50 * window_size.scale_y()) + + 50 * window_size.scale_y(); + + scalerY = plot_height / (max_xyz - min_xyz); + min_value = min_xyz; + + } else { + biasX = window_size.fb_width / 2 + 50.0 * window_size.scale_x(); + + biasY = (6 - i) * (plot_height + 50 * window_size.scale_y()) + + 50 * window_size.scale_y(); + + scalerY = plot_height / (max_q - min_q); + min_value = min_q; + } + + if (r == 0) { //plot the background + glColor3f(0.9f, 0.9f, 0.9f); + + glBegin (GL_QUADS); + glVertex2f(biasX, biasY); + glVertex2f(biasX + plot_width, biasY); + glVertex2f(biasX + plot_width, biasY + plot_height); + glVertex2f(biasX, biasY + plot_height); + glEnd(); + } + + glLineWidth(lineWidth); + glColor3f(COLORS(r, 0), COLORS(r, 1), COLORS(r, 2)); + + glBegin (GL_LINE_STRIP); + float dummyx; + float dummyy; + for (int t = 0; t < Xsave.n_cols - 1; t++) { + dummyx = t * scalerX + biasX; + dummyy = (float) (Xsave.slice(r)(i, t) - min_value) * scalerY + biasY; + glVertex2f(dummyx, dummyy); + } + glEnd(); + + if (r == 0) { //plot the reference + glLineWidth(lineWidth); + glColor3f(0.0f, 0.0f, 0.0f); + glBegin(GL_LINE_STRIP); + float dummyx; + float dummyy; + for (int t = 0; t < Xsave.n_cols - 1; t++) { + dummyx = t * scalerX + biasX; + dummyy = (xTar(i) - min_value) * scalerY + biasY; + glVertex2f(dummyx, dummyy); + } + glEnd(); + } + } + } + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + init = false; + } + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_pose_tpgmm01.cpp b/src/demo_Riemannian_pose_tpgmm01.cpp new file mode 100644 index 0000000..8af6774 --- /dev/null +++ b/src/demo_Riemannian_pose_tpgmm01.cpp @@ -0,0 +1,522 @@ +/* + * demo_Riemannian_pose_tpgmm.cpp + * + * TP-GMM on R3 x S3 with two frames. + * + * Created on: Nov 7, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +using namespace arma; + + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { { q(0),-q(1),-q(2),-q(3)}, + { q(1), q(0),-q(3), q(2)}, + { q(2), q(3), q(0),-q(1)}, + { q(3),-q(2), q(1), q(0)}}; + + return Q; +} + +//----------------------------------------------- + +arma::colvec QuatVector(arma::mat Q) { + arma::colvec q; + q = Q.col(0); + return q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z + << 2 * y * z - 2 * x * w << endr << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat Qexpfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat Qlogfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + if (scale.has_nan()) { + for (int i = 0; i < x.n_cols; i++) { + if (scale.row(0).has_nan()) { + scale(0, i) = 1.0; + } + } + } + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat Qexpmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * Qexpfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat Qlogmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) + Q = { { 1,0,0,0}, + { 0,1,0,0}, + { 0,0,1,0}, + { 0,0,0,1}}; + else + Q = QuatMatrix(mu); + + arma::mat u; + u = Qlogfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat Qtransp(vec g, vec h) { + + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = Qlogmap(h, g); + + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + + colvec uv = vm / mn; + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + + return Ac; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat Ac = eye(6, 6); + + if (norm(g - h, 2) == 0) { + Ac = eye(6, 6); + } else { + Ac.submat(3, 3, 5, 5) = Qtransp(g.subvec(3, 6), h.subvec(3, 6)); + } + + return Ac; +} + +//----------------------------------------------- + +arma::mat logmap(mat x, vec mu) { + mat u = join_vert(x.rows(0, 2), Qlogmap(x.rows(3, 6), mu.subvec(3, 6))); + return u; +} + +//----------------------------------------------- + +arma::mat expmap(mat u, vec mu) { + mat x = join_vert(u.rows(0, 2), Qexpmap(u.rows(3, 5), mu.subvec(3, 6))); + return x; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma)); // + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + + arma_rng::set_seed_random(); + + int nbStates = 3; + int nbStates_prev = 3; + int nbVar = 6; + int nbSamples = 531; + int nbVarMan = 7; + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + int nbFrames = 2; + vec e0 = { 0, 0, 0, 1.0, 0.0, 0, 0.0 }; // center on manifold + int nbDemo = 8; + + // Load manifold data, first row is time, 2:4 is data in fame 1, 5:7 is data in frame 2 + mat demo(2 * nbVarMan, 2 * nbSamples); + demo.load("./data/data_pose_tpgmm_XU2.txt"); + + mat demoX = demo; // data = [X, [U; 0]] + mat demoU = demoX.submat(0, nbSamples, 11, 2 * nbSamples - 1); + demoX = demoX.submat(0, 0, 13, nbSamples - 1); + + cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + mat A1; + A1 = eye(6, 6); + mat A2 = eye(6, 6); + vec tmpq = { -0.034, 0.0684, 0.0097, -0.997 }; + A2.submat(0, 0, 2, 2) = QuatToRotMat(tmpq); + A2.submat(3, 3, 5, 5) = QuatToRotMat(tmpq); + colvec b1; + b1 << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0; + colvec b2; + b2 << 0.7 << endr << -0.15 << endr << 1.0 << endr << 0.0 << endr << 0.0 << endr << 0.0 << endr << 0.0; + + mat MuManProduct; + cube MuMan2; + + bool init = true; + + bool recompute = true; + + // ================== Recomputing tpgmm model with the latest task parameters ====================== + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + vec Priors(nbStates); + cube Sigma(nbVar * 2, nbVar * 2, nbStates); + mat Mu(nbVar * 2, nbStates); + + // ++++++++++++++++++++++ RANDOM INIT ++++++++++++++++++ + /* arma_rng::set_seed_random(); // set the seed to a random value + + Priors = ones(nbStates); + Priors /= nbStates; + + // Random init the means and covariances + //cout << "init menas and covs" << endl; + // 5 x nbStates + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < (1 + 2 * (nbVar - 1)); j++) { + Mu(j, i) = randn(); + } + } + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1)) * 0.5; //%Covariance in the tangent plane at point MuMan + } + */ + // +++++++++++++++++++++++ KBINS INIT +++++++++++++++++++++++ + if (init || (nbStates != nbStates_prev)) { + cout << "Recomputing the model... " << endl; + + vec nbSamplesCumSum = { 0, 67, 143, 213, 284, 347, 417, 478, 531 }; + field<mat> tmpField(nbStates); + + + for (int i = 0; i < nbSamplesCumSum.n_elem-1; i++) { + vec id = linspace(nbSamplesCumSum(i), nbSamplesCumSum(i + 1), nbSamplesCumSum(i + 1) - nbSamplesCumSum(i)); + vec idloc = round(linspace(0, id.n_elem, nbStates + 1)); + + for (int j = 0; j < nbStates; j++) { + vec idLoc = nbSamplesCumSum(i) + round(linspace(idloc(j), idloc(j+1)-1, idloc(j+1)-1-idloc(j))); + for (int k = 0; k < idLoc.n_elem; k++) { + tmpField(j) = join_horiz(tmpField(j), demoU.col((uint) idLoc(k))); + } + } + } + + for (int i = 0; i < nbStates; i++ ) { + Mu.col(i) = mean(tmpField(i), 1); + Sigma.slice(i) = cov(tmpField(i).t()) + eye(2*nbVar, 2*nbVar) * 1E-4; + Priors(i) = tmpField(i).n_cols; + } + Priors = Priors / sum(Priors); + + nbSamples = nbSamplesCumSum(nbSamplesCumSum.n_elem - 1); + + mat MuMan = join_vert(expmap(Mu.rows(0, nbVar - 1), e0), expmap(Mu.rows(nbVar, 2 * nbVar - 1), e0)); + Mu.rows(3, 5) = zeros(3, nbStates); + Mu.rows(9, 11) = zeros(3, nbStates); // center on manifold + mat utmp2; + + cube u(nbVar * 2, nbSamples, nbStates); //uTmp in matlab code + + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + mat xcTmp; + float multiplier = 1E-5; + + for (int i = 0; i < nbStates; i++) { + + xcTmp = join_vert(logmap(demoX.rows(0, 6), MuMan.submat(0, i, 6, i)), logmap(demoX.rows(7, 13), MuMan.submat(7, i, 13, i))); + + while (true) { // sometimes the starting Mu is far from our data => add bigger regularization + L.row(i) = Priors(i) * (gaussPDF(xcTmp, Mu.col(i), Sigma.slice(i) + eye(12, 12) * multiplier).t()); + + if (norm(L.row(i), 2) == 0) { + multiplier *= 10.0; + } else { + break; + } + } + } + + rowvec Lsum = sum(L, 0); // + 1E-308; + + mat GAMMA = L / repmat(Lsum, nbStates, 1); + + colvec GammaSum = sum(GAMMA, 1); + cout << GammaSum << endl; + + mat GAMMA2 = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + + //Update MuMan + for (int n = 0; n < nbIter; n++) { + + u.slice(i) = join_vert(logmap(demoX.rows(0, 6), MuMan.submat(0, i, 6, i)), logmap(demoX.rows(7, 13), MuMan.submat(7, i, 13, i))); + + MuMan.col(i) = join_vert(expmap(u.slice(i).rows(0, 5) * GAMMA2.row(i).t(), MuMan.submat(0, i, 6, i)), + expmap(u.slice(i).rows(6, 11) * GAMMA2.row(i).t(), MuMan.submat(7, i, 13, i))); + } + + Mu.submat(0, i, 2, i) = MuMan.col(i).subvec(0, 2); + Mu.submat(6, i, 8, i) = MuMan.col(i).subvec(7, 9); + utmp2 = u.slice(i); + utmp2.each_col() -= Mu.col(i); + + //Update Sigma + Sigma.slice(i) = utmp2 * diagmat(GAMMA2.row(i)) * utmp2.t() + eye(2 * nbVar, 2 * nbVar) * params_diagRegFact; + } + } + + for (int i = 0; i < nbStates; i++) { + + cout << "============= Component #" << i << " ===========" << endl; + cout << "Prior: " << Priors(i) << endl; + cout << "MuMan:" << endl; + cout << MuMan.col(i).t() << endl; + cout << "Sigma: " << endl; + cout << Sigma.slice(i) << endl << endl; + + } + + //Reformatting as a tensor GMM + mat MuManOld = MuMan; + cube SigmaOld = Sigma; + MuMan2 = zeros(nbVarMan, nbFrames, nbStates); + field<cube> Sigma2(nbStates); + for (int i = 0; i < nbStates; i++) { + cube dummyCube(nbVar, nbVar, nbFrames); + Sigma2.at(i) = dummyCube; + } + + for (int i = 0; i < nbStates; i++) { + for (int m = 0; m < nbFrames; m++) { + + // dummy way to construct id and idMan, works for 2 frames + uvec id; + uvec idMan; + if (m == 0) { + id = {0, 1, 2, 3, 4, 5}; + } else { + id = {6, 7, 8, 9, 10, 11}; + } + + if (m == 0) { + idMan = {0, 1, 2, 3, 4, 5, 6}; + } else { + idMan = {7, 8, 9, 10, 11, 12, 13}; + } + + for (int ii = 0; ii < idMan.size(); ii++) { + + MuMan2.slice(i).col(m)(ii) = MuManOld.col(i)(idMan(ii)); + + } + + Sigma2.at(i).slice(m) = SigmaOld.slice(i).submat(id, id); + + } + } + + // Transforming gaussians with respective frames + for (int i = 0; i < nbStates; i++) { + + // ============ Important ================ + // If you have real task parameters add the following #Frame lines: + // b{#frame}.subvec(3, 6) = QuatVector(A.submat(3, 3, 6, 6)); + // this is important for proper expmap/logmap + // ======================================= + + vec uTmp = A1 * logmap(MuMan2.slice(i).col(0).rows(0, 6), e0); + colvec norotq = { 1, 0, 0, 0 }; + b1.subvec(3, 6) = norotq; // manual + MuMan2.slice(i).col(0).rows(0, 6) = expmap(uTmp, b1); + MuMan2.slice(i).col(0).rows(0, 2) = MuMan2.slice(i).col(0).rows(0, 2) + b1.subvec(0, 2); + + mat Ac1 = transp(b1, MuMan2.slice(i).col(0).rows(0, 6)); + + Sigma2.at(i).slice(0).submat(0, 0, 5, 5) = Ac1 * A1 * Sigma2.at(i).slice(0).submat(0, 0, 5, 5) * A1.t() * Ac1.t(); + + uTmp = A2 * logmap(MuMan2.slice(i).col(1).rows(0, 6), e0); + b2.subvec(3, 6) = tmpq; //manual + MuMan2.slice(i).col(1).rows(0, 6) = expmap(uTmp, b2); + MuMan2.slice(i).col(1).rows(0, 2) = MuMan2.slice(i).col(1).rows(0, 2) + b2.subvec(0, 2); + mat Ac2 = transp(b2, MuMan2.slice(i).col(1).rows(0, 6)); + Sigma2.at(i).slice(1).submat(0, 0, 5, 5) = Ac2 * A2 * Sigma2.at(i).slice(1).submat(0, 0, 5, 5) * A2.t() * Ac2.t(); + + } + + cout << MuMan2 << endl; + cout << Sigma2 << endl; + + //Gaussian product + MuManProduct = zeros(nbVarMan, nbStates); + cube SigmaProduct(nbVar, nbVar, nbStates); + + for (int i = 0; i < nbStates; i++) { + mat componentsMu = zeros(nbVarMan, nbVar); // current means of the components + cube U0 = zeros(nbVar, nbVar, nbStates); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + componentsMu.col(0) = MuMan2.slice(i).col(0).rows(0, 6); + tmpCov = Sigma2.at(i).slice(0).submat(0, 0, 5, 5); + + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + + U0.slice(0) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + componentsMu.col(1) = MuMan2.slice(i).col(1).rows(0, 6); + + tmpCov = Sigma2.at(i).slice(1).submat(0, 0, 5, 5); + + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + + U0.slice(1) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + vec MuMan; // starting point on the manifold + MuMan << 0.0 << endr << 0.0 << endr << 0.0 << endr << 1.0 << endr << 0.0 << endr << 0.0 << endr << 0.0; + MuMan /= norm(MuMan, 2); + mat Sigma = zeros(nbVar, nbVar); + + mat MuTmp = zeros(nbVar, nbVar); //nbVar (on tangent space) x components + cube SigmaTmp = zeros(nbVar, nbVar, nbStates); // nbVar (on tangent space) x nbVar (on tangent space) x components + + for (int n = 0; n < 10; n++) { // compute the Gaussian product + // nbVar = 3 for S3 sphere tangent space + colvec Mu = zeros(nbVar, 1); + mat SigmaSum = zeros(nbVar, nbVar); + + for (int j = 0; j < 2; j++) { // we have two frames + mat Ac = transp(componentsMu.col(j), MuMan); + mat U1 = Ac * U0.slice(j); + SigmaTmp.slice(j) = U1 * U1.t(); + + //Tracking component for Gaussian i + SigmaSum += inv(SigmaTmp.slice(j)); + MuTmp.col(j) = logmap(componentsMu.col(j), MuMan); + Mu += inv(SigmaTmp.slice(j)) * MuTmp.col(j); + } + + Sigma = inv(SigmaSum); + + //Gradient computation + Mu = Sigma * Mu; + + MuMan = expmap(Mu, MuMan); + } + + MuManProduct.col(i) = MuMan; + SigmaProduct.slice(i) = Sigma; + + cout << "================ Gaussian Product component #" << i << " ========================" << endl; + cout << "MuMan: " << MuMan.t() << endl; + cout << "Sigma: " << endl << Sigma << endl; + } + } + + return 0; +} diff --git a/src/demo_Riemannian_quat_infHorLQR.cpp b/src/demo_Riemannian_quat_infHorLQR01.cpp similarity index 64% rename from src/demo_Riemannian_quat_infHorLQR.cpp rename to src/demo_Riemannian_quat_infHorLQR01.cpp index 200d64d..fd93161 100644 --- a/src/demo_Riemannian_quat_infHorLQR.cpp +++ b/src/demo_Riemannian_quat_infHorLQR01.cpp @@ -14,53 +14,92 @@ #include <math.h> #include <GLFW/glfw3.h> +#include <window_utils.h> namespace linmath{ #include <linmath.h> } -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> +#include <armadillo> +#include <lqr.h> + +using namespace arma; + #define REFERENTIALS 0 //Change REFERENTIALS to 1 (referentials in sphere) or 0 (LQR for quaternions) -#define RADIUS 1.f -#define STEP_LONGITUDE 10.5f -#define STEP_LATITUDE 10.5f +#define RADIUS 1.f +#define STEP_LONGITUDE 10.5f +#define STEP_LATITUDE 10.5f #define DIST_BALL (RADIUS * 2.f + RADIUS * 0.1f) #define VIEW_SCENE_DIST (DIST_BALL * 3.f + 200.f) -/* Draw ball */ -typedef enum { DRAW_BALL } DRAW_BALL_ENUM; + /* Vertex type */ typedef struct {float x; float y; float z;} vertex_t; + void DrawSphereBand( GLfloat long_lo, GLfloat long_hi ); void DrawSphere( void ); + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } +}; + +//----------------------------------------------- + static void error_callback(int error, const char* description) { fprintf(stderr, "Error %d: %s\n", error, description); } + +//----------------------------------------------- + int factorial(int n) { return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; } + +//----------------------------------------------- + double deg2rad( double deg ) { return deg / 360 * (2 * M_PI); } + +//----------------------------------------------- + double sin_deg( double deg ) { return sin( deg2rad( deg ) ); } + +//----------------------------------------------- + double cos_deg( double deg ) { return cos(deg2rad ( deg ) ); } + +//----------------------------------------------- + void CrossProduct( vertex_t a, vertex_t b, vertex_t c, vertex_t *n ) { GLfloat u1, u2, u3; @@ -78,20 +117,26 @@ void CrossProduct( vertex_t a, vertex_t b, vertex_t c, vertex_t *n ) n->y = u3 * v1 - v3 * u1; n->z = u1 * v2 - v1 * u2; } + +//----------------------------------------------- + arma::mat QuatMatrix(arma::mat q) { arma::mat Q; - Q = {{q(0),-q(1),-q(2),-q(3)}, - {q(1), q(0),-q(3), q(2)}, - {q(2), q(3), q(0),-q(1)}, - {q(3),-q(2), q(1), q(0)}}; + Q = {{q(0),-q(1),-q(2),-q(3)}, + {q(1), q(0),-q(3), q(2)}, + {q(2), q(3), q(0),-q(1)}, + {q(3),-q(2), q(1), q(0)}}; return Q; } + +//----------------------------------------------- + arma::mat acoslog(arma::mat x) { arma::mat acosx(1,x.size()); - + for (int n=0; n <= x.size()-1; n++) { if (x(0,n) >= 1.0) @@ -108,6 +153,9 @@ arma::mat acoslog(arma::mat x) return acosx; } + +//----------------------------------------------- + arma::mat expfct(arma::mat u) { arma::mat normv = sqrt(pow(u.row(0),2)+pow(u.row(1),2)+pow(u.row(2),2)); @@ -120,6 +168,9 @@ arma::mat expfct(arma::mat u) return Exp; } + +//----------------------------------------------- + arma::mat logfct(arma::mat x) { arma::mat fullone; @@ -134,11 +185,17 @@ arma::mat logfct(arma::mat x) return Log; } + +//----------------------------------------------- + arma::mat expmap(arma::mat u, arma::vec mu) { arma::mat x = QuatMatrix(mu)*expfct(u); return x; } + +//----------------------------------------------- + arma::mat logmap(arma::mat x, arma::vec mu) { arma::mat pole; @@ -159,6 +216,9 @@ arma::mat logmap(arma::mat x, arma::vec mu) return u; } + +//----------------------------------------------- + void DrawTarget(int nbData) { glColor3f(0.98, 0.349, 0.329); @@ -184,50 +244,74 @@ void DrawTarget(int nbData) } glEnd(); } + +//----------------------------------------------- + void DrawResults(int nbData, int nbRepros, arma::mat x_y) { - glColor3f(0.f, 0.f, 0.f); + const arma::fmat COLORS({ + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, + { 0.00f, 0.75f, 0.75f }, + { 0.75f, 0.00f, 0.75f }, + { 0.75f, 0.75f, 0.00f }, + { 0.25f, 0.25f, 0.25f }, + { 0.00f, 0.00f, 1.00f }, + { 0.00f, 0.50f, 0.00f }, + { 1.00f, 0.00f, 0.00f }, + }); + + glLineWidth(1.3); for (int n = 0; n < nbRepros; n++) { + glColor3f(COLORS(n, 0), COLORS(n, 1), COLORS(n, 2)); + glBegin(GL_LINE_STRIP); for (int t = 0; t < nbData; t++) { - glBegin(GL_LINE_STRIP); glVertex2f(t, x_y(0, n * nbData + t)); } glEnd(); } for (int n = 0; n < nbRepros; n++) { + glColor3f(COLORS(n, 0), COLORS(n, 1), COLORS(n, 2)); + glBegin(GL_LINE_STRIP); for (int t = 0; t < nbData; t++) { - glBegin(GL_LINE_STRIP); glVertex2f(nbData + 0.05 + t, x_y(1, n * nbData + t)); } glEnd(); } + for (int n = 0; n < nbRepros; n++) { + glColor3f(COLORS(n, 0), COLORS(n, 1), COLORS(n, 2)); + glBegin(GL_LINE_STRIP); for (int t = 0; t < nbData; t++) { - glBegin(GL_LINE_STRIP); glVertex2f(t, x_y(2, n * nbData + t) - 2.10); } glEnd(); } + for (int n = 0; n < nbRepros; n++) { + glColor3f(COLORS(n, 0), COLORS(n, 1), COLORS(n, 2)); + glBegin(GL_LINE_STRIP); for (int t = 0; t < nbData; t++) { - glBegin(GL_LINE_STRIP); glVertex2f(nbData + 0.05 + t, x_y(3, n * nbData + t) - 2.10); } glEnd(); } - } + +//----------------------------------------------- + void printQuat(arma::mat q,int black) { arma::mat referential = {{1,0,0},{0,1,0},{0,0,1}}; arma::mat rotation; - rotation << 2*(pow(q(0),2)+pow(q(1),2))-1 << 2*(q(1)*q(2)-q(0)*q(3)) << 2*(q(1)*q(3)+q(0)*q(2)) << endr + rotation << 2*(pow(q(0),2)+pow(q(1),2))-1 << 2*(q(1)*q(2)-q(0)*q(3)) << 2*(q(1)*q(3)+q(0)*q(2)) << endr << 2*(q(1)*q(2)+q(0)*q(3)) << 2*(pow(q(0),2)+pow(q(2),2))-1 << 2*(q(2)*q(3)-q(0)*q(1)) << endr << 2*(q(1)*q(3)-q(0)*q(2)) << 2*(q(2)*q(3)+q(0)*q(1)) << 2*(pow(q(0),2)+pow(q(3),2))-1 << endr; arma::mat orientation; @@ -266,6 +350,9 @@ void printQuat(arma::mat q,int black) return; } + +//----------------------------------------------- + void reshape( GLFWwindow* window, int w, int h ) { linmath::mat4x4 projection, view; @@ -286,22 +373,24 @@ void reshape( GLFWwindow* window, int w, int h ) } glLoadMatrixf((const GLfloat*) view); } + +//----------------------------------------------- + int main(int argc, char **argv){ arma_rng::set_seed_random(); - //---------------------------------------Setup parameters---------------------------------------------------- - //----------------------------------------------------------------------------------------------------------- + //------------------------ Setup parameters ------------------------ - int nbData = 100; //Number of datapoints - int nbRepros = 5; //Number of reproductions + int nbData = 100; //Number of datapoints + int nbRepros = 5; //Number of reproductions - int nbVarPos = 3; //Dimension of position data (here: x1,x2) - int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) - int nbVar = nbVarPos * nbDeriv; //Dimension of state vector in the tangent space - int nbVarMan = nbVarPos + 1; //Dimension of the manifold - double dt = 1E-3; //Time step duration - float rfactor = 1E-6; //Control cost in LQR + int nbVarPos = 3; //Dimension of position data (here: x1,x2) + int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) + int nbVar = nbVarPos * nbDeriv; //Dimension of state vector in the tangent space + int nbVarMan = nbVarPos + 1; //Dimension of the manifold + double dt = 1E-3; //Time step duration + float rfactor = 1E-6; //Control cost in LQR //Control Cost matrix arma::mat R = eye(nbVarPos,nbVarPos) * rfactor; @@ -315,8 +404,7 @@ int main(int argc, char **argv){ arma::mat uCov = diagmat(vecCov); - //--------------------------Discrete dynamical system settings (in tangent space)---------------------------- - //----------------------------------------------------------------------------------------------------------- + //------------ Discrete dynamical system settings (in tangent space) ------------ arma::mat A, B; @@ -332,15 +420,13 @@ int main(int argc, char **argv){ A = kron(A1d, eye(nbVarPos,nbVarPos)); B = kron(B1d, eye(nbVarPos,nbVarPos)); - //------------------------------Iterative discrete LQR with infinite horizon--------------------------------- - //----------------------------------------------------------------------------------------------------------- + //---------------- Iterative discrete LQR with infinite horizon ---------------- - pbdlib::LQR lqr(A,B,dt); arma:: mat duTar = zeros(nbVarPos*(nbDeriv-1),1); arma::mat Q = inv(uCov); Q.resize(6,6); - arma::mat P = lqr.solveAlgebraicRiccati_Discrete(A,B,Q,R); + arma::mat P = lqr::solve_algebraic_Riccati_discrete(A, B, Q, R); arma::mat L = (trans(B)*P*B + R).i() * trans(B)*P*A; arma::mat x(nbVarMan,1); @@ -371,29 +457,63 @@ int main(int argc, char **argv){ } } - //------------------------------------------------Plots----------------------------------------------------- - //---------------------------------------------------------------------------------------------------------- + //------------------------ Plots ------------------------ + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 500; + window_size.win_height = 500; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; //Setup GUI glfwSetErrorCallback(error_callback); if (!glfwInit()) exit(1); - GLFWwindow* window = glfwCreateWindow(500, 500, "Quaternions", NULL, NULL); + GLFWwindow* window = create_window_at_optimal_size( + "Quaternions", window_size.win_width, window_size.win_height + ); + glfwMakeContextCurrent(window); - if(!REFERENTIALS) - glOrtho(0,2*nbData+0.1,-3.15,1.05,0,1); + glfwSetInputMode(window, GLFW_STICKY_KEYS, 1); while (!glfwWindowShouldClose(window)) { glfwPollEvents(); + // Detect when the window was resized + int current_win_width; + int current_win_height; + glfwGetWindowSize(window, ¤t_win_width, ¤t_win_height); + + if ((current_win_width != window_size.win_width) || + (current_win_height != window_size.win_height)) { + + // Retrieve the new window size + window_size.win_width = current_win_width; + window_size.win_height = current_win_height; + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); glClearColor(1.f, 1.f, 1.f, 1.f); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + if (!REFERENTIALS) + glOrtho(0, 2 * nbData + 0.1, -3.15, 1.05, 0, 1); + + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + glPushMatrix(); - //------------Draw referentials in sphere--------------- + //------------ Draw referentials in sphere --------------- if (REFERENTIALS) { printQuat(x_y.col(1), 0); @@ -402,7 +522,7 @@ int main(int argc, char **argv){ DrawSphere(); } - //------------ Draw Q1,Q2,Q3,Q4-------------------------- + //--------------- Draw Q1,Q2,Q3,Q4 --------------- else { DrawTarget(nbData); @@ -412,46 +532,49 @@ int main(int argc, char **argv){ glPopMatrix(); glfwSwapBuffers(window); - + // Keyboard input + int state = glfwGetKey(window, GLFW_KEY_ESCAPE); + if (state == GLFW_PRESS) + break; } //Cleanup glfwTerminate(); return 0; } + +//----------------------------------------------- + void DrawSphere( void ) { - GLfloat lon_deg; //degree of longitude + GLfloat lon_deg; //degree of longitude double dt_total, dt2; glPushMatrix(); - glMatrixMode( GL_MODELVIEW ); + glMatrixMode(GL_MODELVIEW); - glCullFace( GL_FRONT ); - glEnable( GL_CULL_FACE ); - glEnable( GL_NORMALIZE ); + glCullFace( GL_FRONT); + glEnable(GL_CULL_FACE); + glEnable(GL_NORMALIZE); //Build a faceted latitude slice of the sphere, //stepping same-sized vertical bands of the sphere. - - for ( lon_deg = 0; - lon_deg < 180; - lon_deg += STEP_LONGITUDE ) + for (lon_deg = 0; lon_deg < 180; lon_deg += STEP_LONGITUDE ) { - //Draw a latitude circle at this longitude. - - DrawSphereBand( lon_deg, - lon_deg + STEP_LONGITUDE ); + DrawSphereBand(lon_deg, lon_deg + STEP_LONGITUDE); } glPopMatrix(); return; } + +//----------------------------------------------- + void DrawSphereBand( GLfloat long_lo, GLfloat long_hi ) { - vertex_t vert_ne; //"ne" means south-east, so on + vertex_t vert_ne; //"ne" means south-east, so on vertex_t vert_nw; vertex_t vert_sw; vertex_t vert_se; @@ -461,13 +584,9 @@ void DrawSphereBand( GLfloat long_lo, GLfloat long_hi ) { // Iterate thru the points of a latitude circle. // A latitude circle is a 2D set of X,Z points. - for (lat_deg = 0; - lat_deg <= (360 - STEP_LATITUDE); + for (lat_deg = 0; lat_deg <= (360 - STEP_LATITUDE); lat_deg += STEP_LATITUDE) { -#if 0 - -#endif glColor3f(0.55f, 0.55f, 0.55f); //Assign each Y. @@ -505,13 +624,12 @@ void DrawSphereBand( GLfloat long_lo, GLfloat long_hi ) { #if SPHERE_DEBUG printf( "----------------------------------------------------------- \n" ); - printf( "lat = %f long_lo = %f long_hi = %f \n", lat_deg, long_lo, long_hi ); - printf( "vert_ne x = %.8f y = %.8f z = %.8f \n", vert_ne.x, vert_ne.y, vert_ne.z ); - printf( "vert_nw x = %.8f y = %.8f z = %.8f \n", vert_nw.x, vert_nw.y, vert_nw.z ); - printf( "vert_se x = %.8f y = %.8f z = %.8f \n", vert_se.x, vert_se.y, vert_se.z ); - printf( "vert_sw x = %.8f y = %.8f z = %.8f \n", vert_sw.x, vert_sw.y, vert_sw.z ); + printf( "lat = %f long_lo = %f long_hi = %f \n", lat_deg, long_lo, long_hi ); + printf( "vert_ne x = %.8f y = %.8f z = %.8f \n", vert_ne.x, vert_ne.y, vert_ne.z ); + printf( "vert_nw x = %.8f y = %.8f z = %.8f \n", vert_nw.x, vert_nw.y, vert_nw.z ); + printf( "vert_se x = %.8f y = %.8f z = %.8f \n", vert_se.x, vert_se.y, vert_se.z ); + printf( "vert_sw x = %.8f y = %.8f z = %.8f \n", vert_sw.x, vert_sw.y, vert_sw.z ); #endif - } return; diff --git a/src/demo_Riemannian_quat_tpgmm01.cpp b/src/demo_Riemannian_quat_tpgmm01.cpp new file mode 100644 index 0000000..e35f527 --- /dev/null +++ b/src/demo_Riemannian_quat_tpgmm01.cpp @@ -0,0 +1,631 @@ +/* + * demo_Riemannian_quat_tpgmm.cpp + * + * TPGMM on S3 (unit quaternion) with two frames. + * + * Created on: Oct 31, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_internal.h> +#include <imgui_impl_glfw_gl2.h> +#include <GLFW/glfw3.h> +#include <gfx_ui.h> +#include <window_utils.h> + +#include <vector> +#include <armadillo> +#include <lqr.h> + +using namespace arma; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; + + inline float scale_x() const { + return (float) fb_width / (float) win_width; + } + + inline float scale_y() const { + return (float) fb_height / (float) win_height; + } +}; + +//----------------------------------------------- + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat QuatMatrix(arma::mat q) { + arma::mat Q; + Q = { + { q(0),-q(1),-q(2),-q(3) }, + { q(1), q(0),-q(3), q(2) }, + { q(2), q(3), q(0),-q(1) }, + { q(3),-q(2), q(1), q(0) } + }; + + return Q; +} + +//----------------------------------------------- + +mat QuatToRotMat(vec4 q) { + float w = q(0); + float x = q(1); + float y = q(2); + float z = q(3); + mat RotMat(3, 3); + RotMat << 1 - 2 * y * y - 2 * z * z << 2 * x * y - 2 * z * w << 2 * x * z + 2 * y * w << endr + << 2 * x * y + 2 * z * w << 1 - 2 * x * x - 2 * z * z << 2 * y * z - 2 * x * w << endr + << 2 * x * z - 2 * y * w << 2 * y * z + 2 * x * w << 1 - 2 * x * x - 2 * y * y << endr; + return RotMat; +} + +//----------------------------------------------- + +arma::mat acoslog(arma::mat x) { + arma::mat acosx(1, x.size()); + + for (int n = 0; n <= x.size() - 1; n++) { + if (x(0, n) >= 1.0) + x(0, n) = 1.0; + if (x(0, n) <= -1.0) + x(0, n) = -1.0; + if (x(0, n) < 0) { + acosx(0, n) = acos(x(0, n)) - M_PI; + } else + acosx(0, n) = acos(x(0, n)); + } + + return acosx; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2) + pow(u.row(2), 2)); + arma::mat Exp(4, u.n_cols); + + Exp.row(0) = cos(normv); + Exp.row(1) = u.row(0) % sin(normv) / normv; + Exp.row(2) = u.row(1) % sin(normv) / normv; + Exp.row(3) = u.row(2) % sin(normv) / normv; + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(0))); + arma::mat scale(1, x.size() / 4); + scale = acoslog(x.row(0)) / sqrt(fullone - pow(x.row(0), 2)); + + arma::mat Log(3, x.size() / 4); + Log.row(0) = x.row(1) % scale; + Log.row(1) = x.row(2) % scale; + Log.row(2) = x.row(3) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + arma::mat x = QuatMatrix(mu) * expfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + arma::mat Q(4, 4, fill::ones); + + pole = {1,0,0,0}; + + if (norm(mu - trans(pole)) < 1E-6) { + Q = { + { 1,0,0,0 }, + { 0,1,0,0 }, + { 0,0,1,0 }, + { 0,0,0,1 } + }; + } else { + Q = QuatMatrix(mu); + } + + arma::mat u; + u = logfct(trans(Q) * x); + + return u; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat E; + E << 0.0 << 0.0 << 0.0 << endr << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec tmpVec = zeros(4, 1); + tmpVec.subvec(0, 2) = logmap(h, g); + vec vm = QuatMatrix(g) * tmpVec; + double mn = norm(vm, 2); + mat Ac; + if (mn < 1E-10) { + Ac = eye(3, 3); + } + colvec uv = vm / mn; + mat Rpar = eye(4, 4) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + Ac = E.t() * QuatMatrix(h).t() * Rpar * QuatMatrix(g) * E; + return Ac; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + +//----------------------------------------------- + +void DrawFrame(ImGuiWindow& win, float lineWidth, mat A, vec center) { + win.DrawList->PathClear(); + + vec3 coordinatePos = zeros(3); + ImVec2 cent, pt; + + cent.x = center(0); + cent.y = center(1); + + for (int j = 0; j < 3; j++) { + + coordinatePos = A.col(j); + + pt.x = cent.x + coordinatePos(0); + pt.y = cent.y - coordinatePos(1); + + if (j == 0) + win.DrawList->AddLine(cent, pt, 0xffff0000, lineWidth); + + if (j == 1) + win.DrawList->AddLine(cent, pt, 0xff00ff00, lineWidth); + + if (j == 2) + win.DrawList->AddLine(cent, pt, 0xff0000ff, lineWidth); + } +} + + +//----------------------------------------------- + +int main(int argc, char **argv) { + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 780; + window_size.win_height = 540; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Riemannian quaternion TP-GMM", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + glEnable (GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui binding + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + // white background + ImVec4 clear_color = ImColor(255, 255, 255); + ImVector<ImVec2> points, velocities; + //vector<vec> pointsV, velocitiesV; + float filterAlphaPos = 0.5; + + // Load Fonts + ImGuiIO& io = ImGui::GetIO(); + io.Fonts->AddFontDefault(); + ui::init(20.); + + arma_rng::set_seed_random(); + + int nbStates = 5; + int nbStates_prev = 5; + int nbVar = 3; + int nbSamples = 80; + int nbVarMan = 4; + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + int nbFrames = 2; + vec e0 = { 0, 1.0, 0, 0.0 }; // center on manifold + + // Load manifold data, first row is time, 2:4 is data in fame 1, 5:7 is data in frame 2 + mat demo(2 * nbVarMan, 2 * nbSamples); + demo.load("./data/data_quat_tpgmm_XU.txt", raw_ascii); + + mat demoX = demo; // data = [X, [U; 0]] + mat demoU = demoX.submat(0, nbSamples, 5, 2 * nbSamples - 1); + demoX = demoX.submat(0, 0, 7, nbSamples - 1); + + // cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + // cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + mat A1; + A1 = eye(3, 3); + mat A2; + A2 << 1.0 << 0.0 << 0.0 << endr << 0.0 << 1.0 << 0.0 << endr << 0.0 << 0.0 << 1.0; + colvec b1; + b1 << 0.6399 << endr << 0.4254 << endr << 0.0 << endr << -0.6399; + colvec b2; + b2 << 0.3816 << endr << 0.8636 << endr << 0.0 << endr << 0.3295; + + mat MuManProduct; + cube MuMan2; + + // Drawing + bool init = true; + vec x_centers = { 150, 300, 450, 600 }; + vec y_centers = { 375, 250, 125 }; + bool recompute = true; + + while (!glfwWindowShouldClose(window)) { + + //========== Recomputing tpgmm model with the latest task parameters ========== + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + vec Priors(nbStates); + cube Sigma(nbVar * 2, nbVar * 2, nbStates); + mat Mu(nbVar * 2, nbStates); + + // ++++++++++++++++++++++ RANDOM INIT ++++++++++++++++++ + /* arma_rng::set_seed_random(); // set the seed to a random value + + Priors = ones(nbStates); + Priors /= nbStates; + + // Random init the means and covariances + //cout << "init menas and covs" << endl; + // 5 x nbStates + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < (1 + 2 * (nbVar - 1)); j++) { + Mu(j, i) = randn(); + } + } + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1)) * 0.5; //%Covariance in the tangent plane at point MuMan + } + */ + + // +++++++++++++++++++++++ KBINS INIT +++++++++++++++++++++++ + if (init || (nbStates != nbStates_prev)) { + // cout << "Recomputing the model... " << endl; + int nbData = 20; + + vec tSep = round(linspace<vec>(0, nbData, nbStates + 1)); + + for (int i = 0; i < nbStates; i++) { + rowvec id; + + for (int n = 0; n < 4; n++) { // data was made out of 4 demos + vec vecDummy = round(n * nbData + linspace<vec>(tSep(i), tSep(i + 1) - 1, tSep(i + 1) - tSep(i))); + + id = join_horiz(id, vecDummy.t()); + } + + Priors(i) = id.n_elem; + + mat demoUColID = zeros(2 * nbVar, id.n_cols); + + for (int j = 0; j < id.n_elem; j++) { + + demoUColID.col(j) = demoU.col((uint) id(j)); + } + + Mu.col(i) = mean(demoUColID, 1); + Sigma.slice(i) = cov(demoUColID.t()) + eye(2 * nbVar, 2 * nbVar) * 1E-4; + } + Priors = Priors / sum(Priors); + + // +++++++++++++++++++++++++ INIT END +++++++++++++++++++++++++++++++++ + + mat MuMan = join_vert(expmap(Mu.rows(0, 2), e0), expmap(Mu.rows(3, 5), e0)); + Mu = zeros(nbVar * 2, nbStates); + + cube u(nbVar * 2, nbSamples, nbStates); //uTmp in matlab code + + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + mat xcTmp; + + for (int i = 0; i < nbStates; i++) { + + xcTmp = join_vert(logmap(demoX.rows(0, 3), MuMan.submat(0, i, 3, i)), + logmap(demoX.rows(4, 7), MuMan.submat(4, i, 7, i))); + + L.row(i) = Priors(i) * (gaussPDF(xcTmp, Mu.col(i), Sigma.slice(i)).t()); + + } + + rowvec Lsum = sum(L, 0) + 1E-308; + + mat GAMMA = L / repmat(Lsum, nbStates, 1); + + colvec GammaSum = sum(GAMMA, 1); + mat GAMMA2 = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + + //Update MuMan + for (int n = 0; n < nbIter; n++) { + u.slice(i) = join_vert(logmap(demoX.rows(0, 3), MuMan.submat(0, i, 3, i)), + logmap(demoX.rows(4, 7), MuMan.submat(4, i, 7, i))); + + MuMan.col(i) = join_vert(expmap(u.slice(i).rows(0, 2) * GAMMA2.row(i).t(), MuMan.submat(0, i, 3, i)), + expmap(u.slice(i).rows(3, 5) * GAMMA2.row(i).t(), MuMan.submat(4, i, 7, i))); + } + //Update Sigma + Sigma.slice(i) = u.slice(i) * diagmat(GAMMA2.row(i)) * u.slice(i).t() + + eye(2 * nbVar, 2 * nbVar) * params_diagRegFact; + } + + } + + // for (int i = 0; i < nbStates; i++) { + // cout << "============= Component #" << i << " ===========" << endl; + // cout << "Prior: " << Priors(i) << endl; + // cout << "MuMan:" << endl; + // cout << MuMan.col(i).t() << endl; + // cout << "Sigma: " << endl; + // cout << Sigma.slice(i) << endl << endl; + // } + + //Reformatting as a tensor GMM + mat MuManOld = MuMan; + cube SigmaOld = Sigma; + MuMan2 = zeros(nbVarMan, nbFrames, nbStates); + field<cube> Sigma2(nbStates); + for (int i = 0; i < nbStates; i++) { + cube dummyCube(nbVar, nbVar, nbFrames); + Sigma2.at(i) = dummyCube; + } + + for (int i = 0; i < nbStates; i++) { + for (int m = 0; m < nbFrames; m++) { + + // dummy way to construct id and idMan, works for 2 frames + uvec id; + uvec idMan; + if (m == 0) { + id = {0, 1, 2}; + } else { + id = {3, 4, 5}; + } + + if (m == 0) { + idMan = {0, 1, 2, 3}; + } else { + idMan = {4, 5, 6, 7}; + } + + for (int ii = 0; ii < idMan.size(); ii++) { + MuMan2.slice(i).col(m)(ii) = MuManOld.col(i)(idMan(ii)); + } + + Sigma2.at(i).slice(m) = SigmaOld.slice(i).submat(id, id); + + } + } + + // Transforming gaussians with respective frames + for (int i = 0; i < nbStates; i++) { + + vec uTmp = A1 * logmap(MuMan2.slice(i).col(0).rows(0, 3), e0); + MuMan2.slice(i).col(0).rows(0, 3) = expmap(uTmp, b1); + mat Ac1 = transp(b1, MuMan2.slice(i).col(0).rows(0, 3)); + Sigma2.at(i).slice(0).submat(0, 0, 2, 2) = Ac1 * A1 * Sigma2.at(i).slice(0).submat(0, 0, 2, 2) * A1.t() * Ac1.t(); + + uTmp = A2 * logmap(MuMan2.slice(i).col(1).rows(0, 3), e0); + MuMan2.slice(i).col(1).rows(0, 3) = expmap(uTmp, b2); + mat Ac2 = transp(b2, MuMan2.slice(i).col(1).rows(0, 3)); + Sigma2.at(i).slice(1).submat(0, 0, 2, 2) = Ac2 * A2 * Sigma2.at(i).slice(1).submat(0, 0, 2, 2) * A2.t() * Ac2.t(); + + } + + //Gaussian product + MuManProduct = zeros(nbVarMan, nbStates); + cube SigmaProduct(nbVar, nbVar, nbStates); + + for (int i = 0; i < nbStates; i++) { + mat componentsMu = zeros(nbVarMan, nbVar); // current means of the components + cube U0 = zeros(nbVar, nbVar, nbStates); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + componentsMu.col(0) = MuMan2.slice(i).col(0).rows(0, 3); + tmpCov = Sigma2.at(i).slice(0).submat(0, 0, 2, 2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(0) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + componentsMu.col(1) = MuMan2.slice(i).col(1).rows(0, 3); + tmpCov = Sigma2.at(i).slice(1).submat(0, 0, 2, 2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(1) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + vec MuMan; // starting point on the manifold + MuMan << 0.0 << endr << 0.0 << endr << 1.0 << endr << 0.0; + MuMan /= norm(MuMan, 2); + mat Sigma = zeros(nbVar, nbVar); + + mat MuTmp = zeros(nbVar, nbVar); //nbVar (on tangent space) x components + cube SigmaTmp = zeros(nbVar, nbVar, nbStates); // nbVar (on tangent space) x nbVar (on tangent space) x components + + for (int n = 0; n < 10; n++) { // compute the Gaussian product + // nbVar = 3 for S3 sphere tangent space + colvec Mu = zeros(nbVar, 1); + mat SigmaSum = zeros(nbVar, nbVar); + + for (int j = 0; j < 2; j++) { // we have two frames + mat Ac = transp(componentsMu.col(j), MuMan); + mat U1 = Ac * U0.slice(j); + SigmaTmp.slice(j) = U1 * U1.t(); + //Tracking component for Gaussian i + SigmaSum += inv(SigmaTmp.slice(j)); + MuTmp.col(j) = logmap(componentsMu.col(j), MuMan); + Mu += inv(SigmaTmp.slice(j)) * MuTmp.col(j); + } + + Sigma = inv(SigmaSum); + //Gradient computation + Mu = Sigma * Mu; + + MuMan = expmap(Mu, MuMan); + } + + MuManProduct.col(i) = MuMan; + SigmaProduct.slice(i) = Sigma; + + // cout << "================ Gaussian Product component #" << i << " ========================" << endl; + // cout << "MuMan: " << MuMan.t() << endl; + // cout << "Sigma: " << endl << Sigma << endl; + } + } + + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + ImGui_ImplGlfwGL2_NewFrame(); + + if (init) + ImGui::SetNextWindowPos(ImVec2(450, 430)); + + ui::begin("demo"); + ImGuiWindow *win = ImGui::GetCurrentWindow(); + ui::end(); + + if (init) { // Init the control panel + ImGui::SetNextWindowPos(ImVec2(2, 2)); + ImGui::SetNextWindowCollapsed(false); //true); + } + + nbStates_prev = nbStates; + ImGui::SetNextWindowSize(ImVec2(400, 54)); + ImGui::Begin("Parameters", NULL, ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings | ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb states", &nbStates, 2, 7); + + ImGui::End(); + ImVec4 clip_rect2(0, 0, window_size.win_width, window_size.win_height); + + //=================== Plotting component frames =================== + float plot_width = (window_size.win_width - 100) / 4; + float plot_height = (window_size.win_height - 100) / 2; + + for (int i = 0; i < nbStates_prev; i++) { // nbStates_prev because we first want to recompute the model + + vec center({ + 50 + plot_width * (i % 4) + plot_width / 2, + 80 + plot_height * (i / 4) + plot_height / 2, + }); + + mat Rot; + for (int j = 0; j < 3; j++) { + float linewidth; + + if (j == 2) { + // frame product + Rot = QuatToRotMat(MuManProduct.col(i)); + linewidth = 2.5; + } else { + // frame 1 or 2 + Rot = QuatToRotMat(MuMan2.slice(i).col(j).rows(0, 3)); + linewidth = 1.0; + } + + DrawFrame(*win, linewidth, Rot * std::min(plot_width, plot_height) / 2, center); + + } + std::string s = std::to_string(i); + + win->DrawList->AddText(ImGui::GetFont(), ImGui::GetFontSize() * 1.5f, + ImVec2(center(0), center(1) - std::min(plot_width, plot_height) / 2), + ImColor(0, 0, 0, 255), s.c_str(), + NULL, 0.0f, &clip_rect2); + } + + ////=================== GUI rendering =================== + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear (GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + init = false; + } + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_sphere_gmm01.cpp b/src/demo_Riemannian_sphere_gmm01.cpp new file mode 100644 index 0000000..f63f869 --- /dev/null +++ b/src/demo_Riemannian_sphere_gmm01.cpp @@ -0,0 +1,547 @@ +/* + * demo_Riemannian_sphere_gmm.cpp + * + * GMM on sphere. + * + * Created on: Oct 13, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +#include <sstream> + +using namespace arma; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat trans2cov(const ui::Trans2d& trans) { + arma::mat RG = { + { trans.x.x / 200.0, trans.y.x / 200.0 }, + { -trans.x.y / 200.0, -trans.y.y / 200.0 } + }; + + return RG * RG.t(); +} + +//----------------------------------------------- + +arma::mat rotM(arma::vec v) { + arma::vec st = v / norm(v); + float acangle = st(2); + float cosa = acangle; + float sina = sqrt(1 - pow(acangle, 2)); + + if ((1 - acangle) > 1E-16) { + v << st(1) << endr << -st(0) << endr << 0 << endr; + v = v / sina; + } else { + v = zeros(3); + } + + float vera = 1 - cosa; + float x = v(0); + float y = v(1); + float z = v(2); + + arma::mat rot; + rot = { + { cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina }, + { x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina }, + { x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera } + }; + + return rot; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); + arma::mat Exp(3, u.n_cols); + + Exp.row(0) = u.row(0) % sin(normv) / normv; + Exp.row(1) = u.row(1) % sin(normv) / normv; + Exp.row(2) = cos(normv); + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(2))); + arma::mat scale(1, x.n_cols); + scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); + + arma::mat Log(2, x.n_cols); + Log.row(0) = x.row(0) % scale; + Log.row(1) = x.row(1) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + return trans(rotM(mu)) * expfct(u); +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + pole = {0, 0, 1}; + arma::mat R(3, 3, fill::ones); + + if (norm(mu - trans(pole)) < 1E-6) { + R = { + { 1, 0, 0 }, + { 0, -1, 0 }, + { 0, 0, -1 } + }; + } + else { + R = rotM(mu); + } + + arma::mat u; + u = logfct(R * x); + + return u; +} + +//----------------------------------------------- + +arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat sample_points( { { 0.0f, 0.0f }, { 1.0f, 0.0f }, { 0.0f, 1.0f }, { -1.0f, 0.0f }, { 0.0f, -1.0f }, }); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); + + points.col(0) = target; + + return points; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma)); + + return prob; +} + + +/********************************* RENDERING *********************************/ + +//----------------------------------------------------------------------------- +// Create a gaussian mesh, colored (no lightning) +//----------------------------------------------------------------------------- +gfx2::model_t create_gaussian(const arma::fvec& color, const ui::Trans2d& gaussian, + const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); + + return gfx2::create_line(color, points); +} + + +/********************************* FUNCTIONS *********************************/ + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + arma::vec target( { 0.0, 0.2, 0.6 }); + target = target / norm(target); + + arma::vec target2( { 0.2, 0.2, 0.2 }); + target2 = target2 / norm(target2); + + arma::vec target_product( { -1.0, -1.0, 0.0 }); + target_product = target_product / norm(target_product); + + ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 680)); + + + // Initialise GLFW + gfx2::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Riemannian sphere gmm", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glDepthFunc(GL_LESS); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + ui::config.color = 0x770000ff; + ui::config.lineColor = 0x770000ff; + + // Creation of the models + // + // The following hierarchy is used: + // - transforms node ("node") + // |__ sphere ("sphere") + // + // This allows to rotate everything by just changing the rotation of the + // root transforms node. + + //-- The root transforms node + gfx2::transforms_t node; + node.position.zeros(3); + node.rotation.eye(4, 4); + + //-- The sphere + gfx2::model_t sphere = gfx2::create_sphere(0.99f); + sphere.transforms.parent = &node; + + arma::mat points1 = sample_gaussian_points(gaussian, arma::vec( { 1.0f, 0.0f, 0.0f })); + arma::mat points2 = sample_gaussian_points(gaussian, target); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + // Creation of the light + gfx2::point_light_t light; + light.transforms.position = arma::fvec( { 0.0f, 0.0f, 5.0f, 1.0f }); + light.color = arma::fvec( { 1.0f, 1.0f, 1.0f }); + + gfx2::light_list_t lights; + lights.push_back(light); + + // Mouse control + double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; + bool rotating = false; + GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); + GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + + glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); + + // Main loop + ui::Trans2d previous_gaussian = gaussian; + bool must_recompute = true; + int display_mode = 0; + int nbStates = 5; + int previous_nbStates = 5; + int nbVar = 2; + int nbSamples = 250; + int nbVarMan = 3; + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + + // Load S shape on manifold + mat demo(nbVarMan, nbSamples * 2); + demo.load("./data/data_sphere_gmm_letter_S.txt"); + mat demoX = demo.submat(0, 0, 2, nbSamples - 1); + mat demoU = demo.submat(0, nbSamples, 1, nbSamples * 2 - 1); + + // cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + // cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + std::vector<gfx2::model_t> gaussian_models; + std::vector<gfx2::model_t> sample_points; + + for (int i = 0; i < nbSamples; i++) { + vec tmpEigenValues; + mat tmpEigenVectors; + mat tmpSigma; + tmpSigma << 1.0 << 0.0 << endr << 0.0 << 1.0; + eig_sym(tmpEigenValues, tmpEigenVectors, tmpSigma); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 1.0); + + ui::Trans2d gaussian_gmm; + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 1.0f }), gaussian_gmm, demoX.col(i) + ); + + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + } + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + previous_nbStates = nbStates; + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + if (must_recompute) { + for (int i = 0; i < gaussian_models.size(); i++) { + gfx2::destroy(gaussian_models.at(i)); + } + + mat componentsMu = zeros(3, 2); // current means of the components + cube U0 = zeros(2, 2, 2); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + arma_rng::set_seed_random(); // set the seed to a random value + + vec Priors = ones(nbStates); + Priors /= nbStates; + + arma::mat randTmp(nbVar, nbStates); + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < nbVar; j++) { + randTmp(j, i) = randn(); + } + } + + mat MuMan = expmap(randTmp, randn(nbVarMan)); //Center on the manifold + + mat Mu = zeros(nbVar, nbStates); //Center in the tangent plane at point MuMan of the manifold + cube Sigma(nbVar, nbVar, nbStates); + cube u(nbVar, nbSamples, nbStates); + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(nbVar, nbVar) * 0.5; //%Covariance in the tangent plane at point MuMan + } + + // cout << "Starting EM iteration" << endl; + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + for (int i = 0; i < nbStates; i++) { + L.row(i) = Priors(i) * gaussPDF(logmap(demoX, MuMan.col(i)), + Mu.col(i), Sigma.slice(i)).t(); + } + + rowvec Lsum = sum(L, 0); + mat GAMMA = L / repmat(Lsum, nbStates, 1); + colvec GammaSum = sum(GAMMA, 1); + mat H = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + //Update MuMan + for (int n = 0; n < nbIter; n++) { + u.slice(i) = logmap(demoX, MuMan.col(i)); + MuMan.col(i) = expmap(u.slice(i) * H.row(i).t(), MuMan.col(i)); + } + //Update Sigma + Sigma.slice(i) = u.slice(i) * diagmat(H.row(i)) * u.slice(i).t() + + eye(nbVar, nbVar) * params_diagRegFact; + } + } + + gaussian_models.clear(); + for (int i = 0; i < nbStates; i++) { + // cout << "========= Component " << i << " =============" << endl; + // cout << "MuMan: " << endl << MuMan.col(i).t() << endl; + // cout << "Sigma: " << endl << Sigma.slice(i) << endl; + + eig_sym(tmpEigenValues, tmpEigenVectors, Sigma.slice(i)); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 200.0); + + ui::Trans2d gaussian_gmm; + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model = create_gaussian( + arma::fvec( { 1.0f, 0.0f, 0.0f }), gaussian_gmm, MuMan.col(i) + ); + gaussian_gmm_model.transforms.parent = &node; + + gaussian_models.push_back(gaussian_gmm_model); + } + + // cout << "Priors: " << Priors.t() << endl; + } + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + + arma::fmat projection = gfx2::perspective( + gfx2::deg2rad(45.0f), (float) window_size.fb_width / (float) window_size.fb_height, + 0.1f, 10.0f + ); + glMultMatrixf(projection.memptr()); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + glTranslatef(0.0f, 0.0f, -3.0f); + + // Drawing + gfx2::draw(sphere, lights); + + for (int i = 0; i < nbStates; i++) { + gfx2::draw(gaussian_models.at(i), lights); + } + + for (int i = 0; i < sample_points.size(); i++) { + gfx2::draw(sample_points.at(i), lights); + } + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 74)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb states", &nbStates, 1, 10); + ImGui::Text("Hold the right mouse button to rotate the sphere"); + ImGui::End(); + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + if (previous_nbStates != nbStates) { + must_recompute = true; + // cout << "Recomputing GMM with " << nbStates << " states..." << endl; + } else { + must_recompute = false; + } + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + // Mouse input + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + //-- Right mouse button: rotation of the meshes while held down + if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { + if (!rotating) { + rotating = true; + glfwSetCursor(window, crosshair_cursor); + } + + arma::fmat rotation = gfx2::rotate( + arma::fvec( { 0.0f, 1.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_x - previous_mouse_x)) * + gfx2::rotate(arma::fvec( { 1.0f, 0.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_y - previous_mouse_y) + ); + + node.rotation = rotation * node.rotation; + } else if (rotating) { + rotating = false; + glfwSetCursor(window, arrow_cursor); + } + + previous_mouse_x = mouse_x; + previous_mouse_y = mouse_y; + } + + // Cleanup + glfwDestroyCursor(crosshair_cursor); + glfwDestroyCursor(arrow_cursor); + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_sphere_infHorLQR.cpp b/src/demo_Riemannian_sphere_infHorLQR.cpp deleted file mode 100644 index a2fccf7..0000000 --- a/src/demo_Riemannian_sphere_infHorLQR.cpp +++ /dev/null @@ -1,823 +0,0 @@ -/* - * demo_sphere.cpp - * - * Linear quadratic regulation on a sphere by relying on Riemannian manifold and - * infinite-horizon LQR - * - * Authors: Sylvain Calinon, Fabien Crépon, Philip Abbet - */ - -#include <stdio.h> -#include <armadillo> -#include <pbdlib/lqr.h> - -#include <gfx3.h> -#include <gfx_ui.h> -#include <GLFW/glfw3.h> -#include <imgui.h> -#include <imgui_impl_glfw_gl3.h> - -using namespace arma; - - -/********************************* SHADERS *********************************/ - -const char* VERTEX_SHADER_SPHERE = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - layout(location = 1) in vec3 normal; - - // Values that stay constant for the whole mesh - uniform mat4 ModelMatrix; - uniform mat4 ViewMatrix; - uniform mat4 ProjectionMatrix; - uniform vec3 LightPosition; - - // Output data ; will be interpolated for each fragment - out vec3 position_modelspace; - out vec3 position_worldspace; - out vec3 eye_direction_cameraspace; - out vec3 light_direction_cameraspace; - out vec3 normal_cameraspace; - - void main() { - position_modelspace = vertex_position; - - // Position of the vertex, in clip space - gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); - - // Position of the vertex, in worldspace - position_worldspace = (ModelMatrix * vec4(vertex_position, 1)).xyz; - - // Vector that goes from the vertex to the camera, in camera space. - // In camera space, the camera is at the origin (0,0,0). - vec3 vertex_position_cameraspace = (ViewMatrix * vec4(position_worldspace, 1)).xyz; - eye_direction_cameraspace = vec3(0,0,0) - vertex_position_cameraspace; - - // Vector that goes from the vertex to the light, in camera space - vec3 light_position_cameraspace = (ViewMatrix * vec4(LightPosition, 1)).xyz; - light_direction_cameraspace = light_position_cameraspace + eye_direction_cameraspace; - - // Normal of the the vertex, in camera space (Only correct if ModelMatrix does - // not scale the model) - normal_cameraspace = (ViewMatrix * ModelMatrix * vec4(normal, 0)).xyz; - } -); - -//----------------------------------------------- - -const char* FRAGMENT_SHADER_SPHERE = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec3 AmbiantColor; - uniform vec3 DiffuseColor; - uniform vec3 SpecularColor; - uniform float SpecularPower; - uniform vec3 LightPosition; - uniform vec3 LightColor; - uniform float LightPower; - uniform bool Attenuation; - uniform sampler2D DiffuseTexture; - - // Interpolated values from the vertex shaders - in vec3 position_modelspace; - in vec3 position_worldspace; - in vec3 eye_direction_cameraspace; - in vec3 light_direction_cameraspace; - in vec3 normal_cameraspace; - - // Output data - out vec3 color; - - void main() { - // Normal of the computed fragment, in camera space - vec3 n = normalize(normal_cameraspace); - - // Direction of the light (from the fragment to the light) - vec3 l = normalize(light_direction_cameraspace); - - // Eye vector (towards the camera) - vec3 E = normalize(eye_direction_cameraspace); - - // Direction in which the triangle reflects the light - vec3 R = reflect(-l, n); - - // Cosine of the angle between the normal and the light direction, - // clamped above 0 - // - light is at the vertical of the triangle -> 1 - // - light is perpendicular to the triangle -> 0 - // - light is behind the triangle -> 0 - float cos_theta = clamp(dot(n, l), 0, 1); - - // Cosine of the angle between the Eye vector and the Reflect vector, - // clamped to 0 - // - Looking into the reflection -> 1 - // - Looking elsewhere -> < 1 - float cos_alpha = clamp(dot(E, R), 0, 1); - - // Distance to the light - float distance = length(LightPosition - position_worldspace); - - // Apply the gaussian texture around the target point - vec3 pos = position_modelspace; - - vec2 longitudeLatitude = vec2((atan(pos.z, pos.x) / 3.1415926 + 1.0) * 0.5, - (asin(-pos.y) / 3.1415926 + 1.0) * 0.5); - - vec3 diffuse_color = texture(DiffuseTexture, longitudeLatitude).rgb; - - if (Attenuation) { - float d = clamp(2.0 * length(2.0 * (longitudeLatitude - vec2(0.5, 0.5))), 0.0, 1.0); - diffuse_color = d * DiffuseColor + (1.0 - d) * diffuse_color; - } - - // Computation of the color of the fragment - color = AmbiantColor + - diffuse_color * LightColor * LightPower * cos_theta / (distance * distance) + - SpecularColor * LightColor * LightPower * pow(cos_alpha, SpecularPower) / (distance * distance); - } -); - - -/****************************** HELPER FUNCTIONS *****************************/ - -static void error_callback(int error, const char* description) { - fprintf(stderr, "Error %d: %s\n", error, description); -} - -//----------------------------------------------- - -int factorial(int n) { - return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; -} - -//----------------------------------------------- - -arma::mat trans2cov(const ui::Trans2d& trans) { - arma::mat RG = { - { trans.x.x / 200.0, trans.y.x / 200.0 }, - { -trans.x.y / 200.0, -trans.y.y / 200.0 } - }; - - return RG * RG.t(); -} - -//----------------------------------------------- - -arma::mat rotM(arma::vec v) { - arma::vec st = v / norm(v); - float acangle = st(2); - float cosa = acangle; - float sina = sqrt(1 - pow(acangle, 2)); - - - if ((1 - acangle) > 1E-16) { - v << st(1) << endr << -st(0) << endr << 0 << endr; - v = v / sina; - } - else { - v = zeros(3); - } - - float vera = 1 - cosa; - float x = v(0); - float y = v(1); - float z = v(2); - - arma::mat rot; - rot = {{cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina}, - {x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina}, - {x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera}}; - - return rot; -} - -//----------------------------------------------- - -arma::mat expfct(arma::mat u) { - arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); - arma::mat Exp(3, u.n_cols); - - Exp.row(0) = u.row(0) % sin(normv) / normv; - Exp.row(1) = u.row(1) % sin(normv) / normv; - Exp.row(2) = cos(normv); - - return Exp; -} - -//----------------------------------------------- - -arma::mat logfct(arma::mat x) { - arma::mat fullone; - fullone.ones(size(x.row(2))); - arma::mat scale(1, x.n_cols); - scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); - - arma::mat Log(2, x.n_cols); - Log.row(0) = x.row(0) % scale; - Log.row(1) = x.row(1) % scale; - - return Log; -} - -//----------------------------------------------- - -arma::mat expmap(arma::mat u, arma::vec mu) { - arma::mat x = trans(rotM(mu)) * expfct(u); - return x; -} - -//----------------------------------------------- - -arma::mat logmap(arma::mat x, arma::vec mu) { - arma::mat pole; - pole = {0, 0, 1}; - arma::mat R(3, 3, fill::ones); - - if (norm(mu - trans(pole)) < 1E-6) { - R = {{1, 0, 0}, - {0, -1, 0}, - {0, 0, -1}}; - } - else { - R = rotM(mu); - } - - arma::mat u; - u = logfct(R * x); - - return u; -} - -//----------------------------------------------- - -arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { - - arma::mat uCov = trans2cov(gaussian); - - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, uCov); - - arma::mat sample_points({ - { 0.0f, 0.0f }, - { 1.0f, 0.0f }, - { 0.0f, 1.0f }, - { -1.0f, 0.0f }, - { 0.0f, -1.0f }, - }); - - arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); - - points.col(0) = target; - - return points; -} - - -/********************************* RENDERING *********************************/ - -//----------------------------------------------------------------------------- -// Create a gaussian mesh, colored (no lightning) -//----------------------------------------------------------------------------- -gfx3::model_t create_gaussian(const gfx3::shader_t& shader, const arma::fvec& color, - const ui::Trans2d& gaussian, const arma::vec& target) { - - arma::mat uCov = trans2cov(gaussian); - - arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); - - arma::mat V; - arma::vec d; - arma::eig_sym(d, V, uCov); - - arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); - - return gfx3::create_line(shader, color, points); -} - - -/********************************* FUNCTIONS *********************************/ - -void compute(const ui::Trans2d& gaussian, const arma::vec& target, - const std::vector<arma::vec>& start_points, - std::vector<arma::mat> &reproductions) { - - //_____ Setup __________ - - // Parameters - const int nbData = 200; // Number of datapoints - const int nbVarPos = 2; // Dimension of position data (here: x1,x2) - const int nbDeriv = 2; // Number of static & dynamic features (D=2 for [x,dx]) - const int nbVar = nbVarPos * nbDeriv; // Dimension of state vector in the tangent space - const int nbVarMan = nbVarPos + 1; // Dimension of the manifold - const double dt = 1E-3; // Time step duration - const float rfactor = 1E-8; // Control cost in LQR - - // Control Cost matrix - arma::mat R = eye(nbVarPos, nbVarPos) * rfactor; - - // Desired covariance - arma::mat uCov = trans2cov(gaussian); - - - //_____ Discrete dynamical system settings (in tangent space) __________ - - arma::mat A, B; - - arma::mat A1d(zeros(nbDeriv, nbDeriv)); - for (int i = 0; i <= nbDeriv - 1; i++) { - A1d = A1d + diagmat(ones(nbDeriv - i), i) * pow(dt, i) * 1.0 / factorial(i); - } - - arma::mat B1d(zeros(nbDeriv, 1)); - for (int i = 1; i <= nbDeriv; i++) { - B1d(nbDeriv - i, 0) = pow(dt, i) * 1.0 / factorial(i); - } - - A = kron(A1d, eye(nbVarPos, nbVarPos)); - B = kron(B1d, eye(nbVarPos, nbVarPos)); - - - //_____ Iterative discrete LQR with infinite horizon __________ - - pbdlib::LQR lqr(A, B, dt); - arma::vec duTar = zeros(nbVarPos * (nbDeriv - 1)); - - arma::mat Q = inv(uCov); - Q.resize(nbVar, nbVar); - arma::mat P = lqr.solveAlgebraicRiccati_Discrete(A, B, Q, R); - arma::mat L = (trans(B) * P * B + R).i() * trans(B) * P * A; - - arma::vec x(nbVarMan); - arma::mat U; - arma::mat x_y(zeros(3, nbData)); - arma::vec ddu(nbVarPos); - - for (int n = 0; n < start_points.size(); n++) { - x = start_points[n]; - - U = -logmap(x, target); - U.resize(4, U.n_cols); - - for (int t = 0; t < nbData; t++) { - x_y.col(t) = x.col(0); - - ddu.rows(0, 1) = logmap(x, target); - ddu.resize(4); - ddu.rows(2, 3) = duTar - U.rows(2, 3); - - ddu = L * ddu; - U = A * U + B * ddu; - x = expmap(-U.rows(0, nbVarPos - 1), target); - } - - reproductions.push_back(x_y); - } -} - -//----------------------------------------------- - -int main(int argc, char **argv) { - arma_rng::set_seed_random(); - - // Parameters - int nb_repros = 5; // Initial number of reproductions - - // Initial LQR computation - std::vector<arma::vec> start_points; - std::vector<arma::mat> reproductions; - - arma::vec target({ 0.0, 0.2, 0.6 }); - target = target / norm(target); - - ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 680)); - - for (int i = 0; i < nb_repros; ++i) { - arma::vec x(3); - x(0) = -1.0 + randn() * 0.9; - x(1) = -1.0 + randn() * 0.9; - x(2) = randn() * 0.9; - start_points.push_back(x / norm(x)); - } - - compute(gaussian, target, start_points, reproductions); - - - // Initialise GLFW - glfwSetErrorCallback(error_callback); - - if (!glfwInit()) - return -1; - - glfwWindowHint(GLFW_SAMPLES, 4); - glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3); - glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 3); - glfwWindowHint(GLFW_OPENGL_FORWARD_COMPAT, GL_TRUE); - glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE); - - // Open a window and create its OpenGL context - GLFWwindow* window = glfwCreateWindow(800, 800, "Demo Riemannian sphere", NULL, NULL); - - glfwMakeContextCurrent(window); - - // Take 4k screens into account (framebuffer size != window size) - int win_width = ImGui::GetIO().DisplaySize.x; - int win_height = ImGui::GetIO().DisplaySize.y; - - int fb_width, fb_height; - glfwGetFramebufferSize(window, &fb_width, &fb_height); - - // Setup GLSL - gfx3::init(); - glEnable(GL_DEPTH_TEST); - glEnable(GL_CULL_FACE); - glEnable(GL_LINE_SMOOTH); - glDepthFunc(GL_LESS); - - // Setup ImGui - ImGui_ImplGlfwGL3_Init(window, true); - - ui::config.color = 0x770000ff; - ui::config.lineColor = 0x770000ff; - - // Creation of the Vertex Array Object (VAO) - GLuint vertexArrayID; - glGenVertexArrays(1, &vertexArrayID); - glBindVertexArray(vertexArrayID); - - - // Projection matrix - arma::fmat projection = gfx3::perspective( - gfx3::deg2rad(45.0f), (float) fb_width / (float) fb_height, 0.1f, 10.0f); - - // Camera matrix - arma::fmat view = gfx3::lookAt( - arma::fvec({0, 0, 3}), // Position of the camera - arma::fvec({0, 0, 0}), // Look at the origin - arma::fvec({0, 1, 0}) // Head is up - ); - - - // Loading of the shaders - gfx3::shader_t gaussian_rtt_shader = gfx3::loadShader(gfx3::RTT_VERTEX_SHADER, - gfx3::RTT_FRAGMENT_SHADER_GAUSSIAN); - - gaussian_rtt_shader.setUniform("Scale", conv_to<fvec>::from(arma::vec({arma::datum::pi, arma::datum::pi}))); - gaussian_rtt_shader.setUniform("Mu", conv_to<fvec>::from(target)); - gaussian_rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(trans2cov(gaussian)))); - gaussian_rtt_shader.setUniform("GaussianColor", arma::fvec({0.8f, 0.0f, 0.0f})); - gaussian_rtt_shader.setUniform("BackgroundColor", arma::fvec({0.5f, 0.5f, 0.5f})); - - gfx3::shader_t lic_rtt_shader = gfx3::loadShader(gfx3::RTT_VERTEX_SHADER, - gfx3::RTT_FRAGMENT_SHADER_LIC); - - lic_rtt_shader.setUniform("Time", 0.0f); - lic_rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(trans2cov(gaussian)))); - lic_rtt_shader.setUniform("Resolution", arma::fvec({1024, 1024})); - lic_rtt_shader.setUniform("Target", arma::vec({0.0, 0.0})); - - gfx3::shader_t lighted_shader = gfx3::loadShader(VERTEX_SHADER_SPHERE, - FRAGMENT_SHADER_SPHERE); - - gfx3::shader_t colored_shader = gfx3::loadShader(gfx3::VERTEX_SHADER_COLORED, - gfx3::FRAGMENT_SHADER_COLORED); - - lighted_shader.setUniform("AmbiantColor", arma::fvec({0.2f, 0.2f, 0.2f})); - lighted_shader.setUniform("DiffuseColor", arma::fvec({0.5f, 0.5f, 0.5f})); - lighted_shader.setUniform("SpecularColor", arma::fvec({0.0f, 0.0f, 0.0f})); - lighted_shader.setUniform("Attenuation", false); - - // Creation of the RTTs - gfx3::render_to_texture_t gaussian_rtt = gfx3::createRTT(gaussian_rtt_shader, 512, 512, - arma::fvec({ 0.0f, 0.0f, 0.0f })); - - gfx3::render_to_texture_t lic_rtt = gfx3::createRTT(lic_rtt_shader, 1024, 1024, - arma::fvec({ 0.5f, 0.5f, 0.5f })); - - // Creation of the models - // - // The following hierarchy is used: - // - transforms node ("node") - // |__ sphere ("sphere") - // |__ reproduction lines ("reproductions_models") - // |__ gaussian ("gaussian_model") - // |__ transforms node ("target_model_node") - // |__ target point ("target_model") - // - // This allows to rotate everything by just changing the rotation of the - // root transforms node. The "target_model_node" transforms is necessary - // correctly place the target point, always tangent to the sphere. - - //-- The root transforms node - gfx3::transforms_t node; - node.position.zeros(3); - node.rotation.eye(4, 4); - - //-- The sphere - gfx3::model_t sphere = gfx3::create_sphere(lighted_shader, 0.99f); - sphere.transforms.parent = &node; - sphere.diffuse_texture = gaussian_rtt.texture(); - - arma::mat points1 = sample_gaussian_points(gaussian, arma::vec({1.0f, 0.0f, 0.0f})); - arma::mat points2 = sample_gaussian_points(gaussian, target); - - arma::fmat rotation; - arma::fvec translation; - gfx3::rigid_transform_3D(conv_to<fmat>::from(points1), - conv_to<fmat>::from(points2), - rotation, translation); - - sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; - - //-- The reproduction lines - std::vector<gfx3::model_t> reproductions_models; - for (size_t i = 0; i < reproductions.size(); ++i) { - gfx3::model_t line = gfx3::create_line( - colored_shader, arma::fvec({0.0f, 0.5f, 0.0f}), reproductions[i]); - - line.transforms.parent = &node; - - reproductions_models.push_back(line); - } - - //-- The gaussian - gfx3::model_t gaussian_model = create_gaussian( - colored_shader, arma::fvec({0.8f, 0.0f, 0.0f}), gaussian, target); - - gaussian_model.transforms.parent = &node; - - //-- The intermediate transforms node of the target - gfx3::transforms_t target_model_node; - target_model_node.position.zeros(3); - target_model_node.rotation = gfx3::rotation(arma::fvec({1.0f, 0.0f, 0.0f}), - conv_to<fvec>::from(target)); - target_model_node.parent = &node; - - //-- The target point - gfx3::model_t target_model = gfx3::create_square( - colored_shader, arma::fvec({0.8f, 0.0f, 0.0f}), 0.01f); - - target_model.transforms.position = arma::fvec({1.0f, 0.0f, 0.0f}); - target_model.transforms.rotation = gfx3::rotate(arma::fvec({0.0f, 1.0f, 0.0f}), - gfx3::deg2rad(90.0f)); - target_model.transforms.parent = &target_model_node; - - - // Creation of the light - gfx3::point_light_t light; - light.transforms.position = arma::fvec({-3.0f, 3.0f, 5.0f}); - light.color = arma::fvec({1.0f, 1.0f, 1.0f}); - light.power = 30.0f; - - gfx3::light_list_t lights; - lights.push_back(light); - - - // Mouse control - double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; - bool rotating = false; - GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); - GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); - - glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); - - - // RTT initial rendering - gfx3::draw(gaussian_rtt); - - - // Main loop - ui::Trans2d previous_gaussian = gaussian; - bool must_recompute = false; - int display_mode = 0; - - while (!glfwWindowShouldClose(window)) { - glfwPollEvents(); - - // Detect when the window was resized - if ((ImGui::GetIO().DisplaySize.x != win_width) || (ImGui::GetIO().DisplaySize.y != win_height)) { - win_width = ImGui::GetIO().DisplaySize.x; - win_height = ImGui::GetIO().DisplaySize.y; - - glfwGetFramebufferSize(window, &fb_width, &fb_height); - - // Update the projection matrix - projection = gfx3::perspective( - gfx3::deg2rad(45.0f), (float) fb_width / (float) fb_height, 0.1f, 10.0f); - - // Ensure that the gaussian widgets are still visible - gaussian.pos.x = 50; - gaussian.pos.y = win_height - 120; - } - - - // Ensure that the number of desired reproductions hasn't changed - // -> trigger a recomputation or the recreation of the meshes - bool must_recreate_lines = false; - - if (nb_repros > reproductions.size()) { - for (int i = reproductions.size(); i < nb_repros; ++i) { - arma::vec x(3); - x(0) = -1.0 + randn() * 0.9; - x(1) = -1.0 + randn() * 0.9; - x(2) = randn() * 0.9; - start_points.push_back(x / norm(x)); - } - - must_recompute = true; - } - else if (nb_repros < reproductions.size()) { - start_points.resize(nb_repros); - reproductions.resize(nb_repros); - - must_recreate_lines = true; - } - - - // Ensure that the gaussian parameters have not changed - // -> trigger a recomputation - if (!gfx3::is_close(previous_gaussian.x.x, gaussian.x.x) || - !gfx3::is_close(previous_gaussian.x.y, gaussian.x.y) || - !gfx3::is_close(previous_gaussian.y.x, gaussian.y.x) || - !gfx3::is_close(previous_gaussian.y.y, gaussian.y.y)) { - - gaussian_rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(trans2cov(gaussian)))); - gfx3::draw(gaussian_rtt); - - lic_rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(trans2cov(gaussian)))); - - must_recompute = true; - previous_gaussian = gaussian; - } - - - // If needed, recompute the LQR - if (must_recompute) { - reproductions.clear(); - compute(gaussian, target, start_points, reproductions); - - must_recreate_lines = true; - must_recompute = false; - } - - - // If needed, recreate the models - if (must_recreate_lines) { - for (size_t i = 0; i < reproductions_models.size(); ++i) { - gfx3::destroy(reproductions_models[i]); - } - - reproductions_models.clear(); - - for (size_t i = 0; i < reproductions.size(); ++i) { - gfx3::model_t line = gfx3::create_line(colored_shader, - arma::fvec({0.0f, 0.5f, 0.0f}), - reproductions[i]); - - line.transforms.parent = &node; - - reproductions_models.push_back(line); - } - - gfx3::destroy(gaussian_model); - - gaussian_model = create_gaussian( - colored_shader, arma::fvec({0.8f, 0.0f, 0.0f}), gaussian, target); - - gaussian_model.transforms.parent = &node; - } - - - // RTT rendering - lic_rtt_shader.setUniform("Time", (float) glfwGetTime()); - gfx3::draw(lic_rtt); - - if (display_mode == 1) { - sphere.diffuse_texture = lic_rtt.texture(); - lighted_shader.setUniform("Attenuation", true); - } - else { - sphere.diffuse_texture = gaussian_rtt.texture(); - lighted_shader.setUniform("Attenuation", false); - } - - // Start the rendering - ImGui_ImplGlfwGL3_NewFrame(); - glViewport(0, 0, fb_width, fb_height); - glClearColor(0.6f, 0.6f, 0.6f, 0.0f); - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - - - // Drawing - gfx3::draw(sphere, view, projection, lights); - - for (size_t i = 0; i < reproductions_models.size(); ++i) - gfx3::draw(reproductions_models[i], view, projection, lights); - - gfx3::draw(gaussian_model, view, projection, lights); - gfx3::draw(target_model, view, projection, lights); - - - // Gaussian UI widget - ui::begin("Gaussian"); - gaussian = ui::affineSimple(0, gaussian); - ui::end(); - - - // Parameter window - ImGui::SetNextWindowSize(ImVec2(400, 110)); - ImGui::Begin("Parameters", NULL, - ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | - ImGuiWindowFlags_NoMove - ); - ImGui::SliderInt("Nb reproductions", &nb_repros, 1, 10); - ImGui::Combo("Display", &display_mode, "Gaussian\0Line integral convolution\0\0"); - ImGui::Text("Hold the right mouse button to rotate the sphere"); - ImGui::Text("Left-click on the sphere to change the target point"); - ImGui::End(); - - - // GUI rendering - ImGui::Render(); - - // Swap buffers - glfwSwapBuffers(window); - - // Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - - - // Mouse input - glfwGetCursorPos(window, &mouse_x, &mouse_y); - - //-- Left click - if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { - - // Determine if the click was on the sphere, and where exactly - gfx3::ray_t ray = gfx3::create_ray( - arma::fvec({0, 0, 3}), (int) mouse_x, (int) mouse_y, - view, projection, win_width, win_height - ); - - arma::fvec intersection; - if (gfx3::intersects(ray, node.position, 1.0f, intersection)) { - // Change the target position - arma::fvec p(4); - p.rows(0, 2) = intersection; - p(3) = 1.0f; - - p = arma::inv(gfx3::worldRotation(&node)) * p; - - target = arma::conv_to<arma::vec>::from(p.rows(0, 2)); - - target_model_node.rotation = gfx3::rotation(arma::fvec({1.0f, 0.0f, 0.0f}), - conv_to<fvec>::from(target)); - - arma::mat points1 = sample_gaussian_points(gaussian, arma::vec({1.0f, 0.0f, 0.0f})); - arma::mat points2 = sample_gaussian_points(gaussian, target); - - arma::fmat rotation; - arma::fvec translation; - gfx3::rigid_transform_3D(conv_to<fmat>::from(points1), - conv_to<fmat>::from(points2), - rotation, translation); - - sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; - - must_recompute = true; - } - } - - //-- Right mouse button: rotation of the meshes while held down - if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { - if (!rotating) { - rotating = true; - glfwSetCursor(window, crosshair_cursor); - } - - arma::fmat rotation = - gfx3::rotate(arma::fvec({ 0.0f, 1.0f, 0.0f }), 0.2f * gfx3::deg2rad(mouse_x - previous_mouse_x)) * - gfx3::rotate(arma::fvec({ 1.0f, 0.0f, 0.0f }), 0.2f * gfx3::deg2rad(mouse_y - previous_mouse_y)); - - node.rotation = rotation * node.rotation; - } - else if (rotating) { - rotating = false; - glfwSetCursor(window, arrow_cursor); - } - - previous_mouse_x = mouse_x; - previous_mouse_y = mouse_y; - } - - - // Cleanup - glfwDestroyCursor(crosshair_cursor); - glfwDestroyCursor(arrow_cursor); - - ImGui_ImplGlfwGL3_Shutdown(); - glfwTerminate(); - - return 0; -} diff --git a/src/demo_Riemannian_sphere_infHorLQR01.cpp b/src/demo_Riemannian_sphere_infHorLQR01.cpp new file mode 100644 index 0000000..cceeed2 --- /dev/null +++ b/src/demo_Riemannian_sphere_infHorLQR01.cpp @@ -0,0 +1,655 @@ +/* + * demo_Riemannian_sphere_infHorLQR.cpp + * + * Linear quadratic regulation on a sphere by relying on Riemannian manifold and + * infinite-horizon LQR + * + * Authors: Sylvain Calinon, Fabien Crépon, Philip Abbet + */ + +#include <stdio.h> +#include <armadillo> + +#include <lqr.h> +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +int factorial(int n) { + return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; +} + +//----------------------------------------------- + +arma::mat trans2cov(const ui::Trans2d& trans) { + arma::mat RG = { + { trans.x.x / 200.0, trans.y.x / 200.0 }, + { -trans.x.y / 200.0, -trans.y.y / 200.0 } + }; + + return RG * RG.t(); +} + +//----------------------------------------------- + +arma::mat rotM(arma::vec v) { + arma::vec st = v / norm(v); + float acangle = st(2); + float cosa = acangle; + float sina = sqrt(1 - pow(acangle, 2)); + + + if ((1 - acangle) > 1E-16) { + v << st(1) << endr << -st(0) << endr << 0 << endr; + v = v / sina; + } + else { + v = zeros(3); + } + + float vera = 1 - cosa; + float x = v(0); + float y = v(1); + float z = v(2); + + arma::mat rot; + rot = {{cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina}, + {x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina}, + {x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera}}; + + return rot; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); + arma::mat Exp(3, u.n_cols); + + Exp.row(0) = u.row(0) % sin(normv) / normv; + Exp.row(1) = u.row(1) % sin(normv) / normv; + Exp.row(2) = cos(normv); + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(2))); + arma::mat scale(1, x.n_cols); + scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); + + arma::mat Log(2, x.n_cols); + Log.row(0) = x.row(0) % scale; + Log.row(1) = x.row(1) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + arma::mat x = trans(rotM(mu)) * expfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + pole = {0, 0, 1}; + arma::mat R(3, 3, fill::ones); + + if (norm(mu - trans(pole)) < 1E-6) { + R = {{1, 0, 0}, + {0, -1, 0}, + {0, 0, -1}}; + } + else { + R = rotM(mu); + } + + arma::mat u; + u = logfct(R * x); + + return u; +} + +//----------------------------------------------- + +arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat sample_points({ + { 0.0f, 0.0f }, + { 1.0f, 0.0f }, + { 0.0f, 1.0f }, + { -1.0f, 0.0f }, + { 0.0f, -1.0f }, + }); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); + + points.col(0) = target; + + return points; +} + + +/********************************* RENDERING *********************************/ + +//----------------------------------------------------------------------------- +// Create a gaussian mesh, colored (no lightning) +//----------------------------------------------------------------------------- +gfx2::model_t create_gaussian(const arma::fvec& color, const ui::Trans2d& gaussian, + const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); + + return gfx2::create_line(color, points); +} + + +/********************************* FUNCTIONS *********************************/ + +void compute(const ui::Trans2d& gaussian, const arma::vec& target, + const std::vector<arma::vec>& start_points, + std::vector<arma::mat> &reproductions) { + + //_____ Setup __________ + + // Parameters + const int nbData = 200; // Number of datapoints + const int nbVarPos = 2; // Dimension of position data (here: x1,x2) + const int nbDeriv = 2; // Number of static & dynamic features (D=2 for [x,dx]) + const int nbVar = nbVarPos * nbDeriv; // Dimension of state vector in the tangent space + const int nbVarMan = nbVarPos + 1; // Dimension of the manifold + const double dt = 1E-3; // Time step duration + const float rfactor = 1E-8; // Control cost in LQR + + // Control Cost matrix + arma::mat R = eye(nbVarPos, nbVarPos) * rfactor; + + // Desired covariance + arma::mat uCov = trans2cov(gaussian); + + + //_____ Discrete dynamical system settings (in tangent space) __________ + + arma::mat A, B; + + arma::mat A1d(zeros(nbDeriv, nbDeriv)); + for (int i = 0; i <= nbDeriv - 1; i++) { + A1d = A1d + diagmat(ones(nbDeriv - i), i) * pow(dt, i) * 1.0 / factorial(i); + } + + arma::mat B1d(zeros(nbDeriv, 1)); + for (int i = 1; i <= nbDeriv; i++) { + B1d(nbDeriv - i, 0) = pow(dt, i) * 1.0 / factorial(i); + } + + A = kron(A1d, eye(nbVarPos, nbVarPos)); + B = kron(B1d, eye(nbVarPos, nbVarPos)); + + + //_____ Iterative discrete LQR with infinite horizon __________ + + arma::vec duTar = zeros(nbVarPos * (nbDeriv - 1)); + + arma::mat Q = inv(uCov); + Q.resize(nbVar, nbVar); + arma::mat P = lqr::solve_algebraic_Riccati_discrete(A, B, Q, R); + arma::mat L = (trans(B) * P * B + R).i() * trans(B) * P * A; + + arma::vec x(nbVarMan); + arma::mat U; + arma::mat x_y(zeros(3, nbData)); + arma::vec ddu(nbVarPos); + + for (int n = 0; n < start_points.size(); n++) { + x = start_points[n]; + + U = -logmap(x, target); + U.resize(4, U.n_cols); + + for (int t = 0; t < nbData; t++) { + x_y.col(t) = x.col(0); + + ddu.rows(0, 1) = logmap(x, target); + ddu.resize(4); + ddu.rows(2, 3) = duTar - U.rows(2, 3); + + ddu = L * ddu; + U = A * U + B * ddu; + x = expmap(-U.rows(0, nbVarPos - 1), target); + } + + reproductions.push_back(x_y); + } +} + +//----------------------------------------------- + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + // Parameters + int nb_repros = 5; // Initial number of reproductions + + // Initial LQR computation + std::vector<arma::vec> start_points; + std::vector<arma::mat> reproductions; + + arma::vec target({ 0.0, 0.2, 0.6 }); + target = target / norm(target); + + ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 680)); + + for (int i = 0; i < nb_repros; ++i) { + arma::vec x(3); + x(0) = -1.0 + randn() * 0.9; + x(1) = -1.0 + randn() * 0.9; + x(2) = randn() * 0.9; + start_points.push_back(x / norm(x)); + } + + compute(gaussian, target, start_points, reproductions); + + + // Initialise GLFW + gfx2::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Riemannian sphere", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glDepthFunc(GL_LESS); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + ui::config.color = 0x770000ff; + ui::config.lineColor = 0x770000ff; + + + // Projection matrix + arma::fmat projection; + + // Camera matrix + arma::fmat view = gfx2::lookAt( + arma::fvec({0, 0, 3}), // Position of the camera + arma::fvec({0, 0, 0}), // Look at the origin + arma::fvec({0, 1, 0}) // Head is up + ); + + + // Creation of the models + // + // The following hierarchy is used: + // - transforms node ("node") + // |__ sphere ("sphere") + // |__ reproduction lines ("reproductions_models") + // |__ gaussian ("gaussian_model") + // |__ transforms node ("target_model_node") + // |__ target point ("target_model") + // + // This allows to rotate everything by just changing the rotation of the + // root transforms node. The "target_model_node" transforms is necessary + // correctly place the target point, always tangent to the sphere. + + //-- The root transforms node + gfx2::transforms_t node; + node.position.zeros(3); + node.rotation.eye(4, 4); + + //-- The sphere + gfx2::model_t sphere = gfx2::create_sphere(0.99f); + sphere.transforms.parent = &node; + + arma::mat points1 = sample_gaussian_points(gaussian, arma::vec({1.0f, 0.0f, 0.0f})); + arma::mat points2 = sample_gaussian_points(gaussian, target); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), + conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + //-- The reproduction lines + std::vector<gfx2::model_t> reproductions_models; + for (size_t i = 0; i < reproductions.size(); ++i) { + gfx2::model_t line = gfx2::create_line( + arma::fvec({0.0f, 0.5f, 0.0f}), reproductions[i] + ); + + line.transforms.parent = &node; + + reproductions_models.push_back(line); + } + + //-- The gaussian + gfx2::model_t gaussian_model = create_gaussian( + arma::fvec({0.8f, 0.0f, 0.0f}), gaussian, target + ); + + gaussian_model.transforms.parent = &node; + + //-- The intermediate transforms node of the target + gfx2::transforms_t target_model_node; + target_model_node.position.zeros(3); + target_model_node.rotation = gfx2::rotation(arma::fvec({1.0f, 0.0f, 0.0f}), + conv_to<fvec>::from(target)); + target_model_node.parent = &node; + + //-- The target point + gfx2::model_t target_model = gfx2::create_square( + arma::fvec({0.8f, 0.0f, 0.0f}), 0.01f + ); + + target_model.transforms.position = arma::fvec({1.0f, 0.0f, 0.0f}); + target_model.transforms.rotation = gfx2::rotate(arma::fvec({0.0f, 1.0f, 0.0f}), + gfx2::deg2rad(90.0f)); + target_model.transforms.parent = &target_model_node; + + + // Creation of the light + gfx2::point_light_t light; + light.transforms.position = arma::fvec({0.0f, 0.0f, 5.0f, 1.0f}); + light.color = arma::fvec({1.0f, 1.0f, 1.0f}); + + gfx2::light_list_t lights; + lights.push_back(light); + + + // Mouse control + double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; + bool rotating = false; + GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); + GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + + glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); + + + // Main loop + ui::Trans2d previous_gaussian = gaussian; + bool must_recompute = false; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // Update the projection matrix + projection = gfx2::perspective( + gfx2::deg2rad(45.0f), + (float) window_size.fb_width / (float) window_size.fb_height, + 0.1f, 10.0f + ); + + // Ensure that the gaussian widgets are still visible + gaussian.pos.x = 50; + gaussian.pos.y = window_size.win_height - 120; + } + + + // Ensure that the number of desired reproductions hasn't changed + // -> trigger a recomputation or the recreation of the meshes + bool must_recreate_lines = false; + + if (nb_repros > reproductions.size()) { + for (int i = reproductions.size(); i < nb_repros; ++i) { + arma::vec x(3); + x(0) = -1.0 + randn() * 0.9; + x(1) = -1.0 + randn() * 0.9; + x(2) = randn() * 0.9; + start_points.push_back(x / norm(x)); + } + + must_recompute = true; + } + else if (nb_repros < reproductions.size()) { + start_points.resize(nb_repros); + reproductions.resize(nb_repros); + + must_recreate_lines = true; + } + + + // Ensure that the gaussian parameters have not changed + // -> trigger a recomputation + if (!gfx2::is_close(previous_gaussian.x.x, gaussian.x.x) || + !gfx2::is_close(previous_gaussian.x.y, gaussian.x.y) || + !gfx2::is_close(previous_gaussian.y.x, gaussian.y.x) || + !gfx2::is_close(previous_gaussian.y.y, gaussian.y.y)) { + + must_recompute = true; + previous_gaussian = gaussian; + } + + + // If needed, recompute the LQR + if (must_recompute) { + reproductions.clear(); + compute(gaussian, target, start_points, reproductions); + + must_recreate_lines = true; + must_recompute = false; + } + + + // If needed, recreate the models + if (must_recreate_lines) { + for (size_t i = 0; i < reproductions_models.size(); ++i) { + gfx2::destroy(reproductions_models[i]); + } + + reproductions_models.clear(); + + for (size_t i = 0; i < reproductions.size(); ++i) { + gfx2::model_t line = gfx2::create_line( + arma::fvec({0.0f, 0.5f, 0.0f}), reproductions[i] + ); + + line.transforms.parent = &node; + + reproductions_models.push_back(line); + } + + gfx2::destroy(gaussian_model); + + gaussian_model = create_gaussian( + arma::fvec({0.8f, 0.0f, 0.0f}), gaussian, target + ); + + gaussian_model.transforms.parent = &node; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glMultMatrixf(projection.memptr()); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glMultMatrixf(view.memptr()); + + + // Drawing + gfx2::draw(sphere, lights); + + for (size_t i = 0; i < reproductions_models.size(); ++i) + gfx2::draw(reproductions_models[i], lights); + + gfx2::draw(gaussian_model, lights); + gfx2::draw(target_model, lights); + + + // Gaussian UI widget + ui::begin("Gaussian"); + gaussian = ui::affineSimple(0, gaussian); + ui::end(); + + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 90)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove + ); + ImGui::SliderInt("Nb reproductions", &nb_repros, 1, 10); + ImGui::Text("Hold the right mouse button to rotate the sphere"); + ImGui::Text("Left-click on the sphere to change the target point"); + ImGui::End(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + + // Mouse input + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + //-- Left click + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { + + // Determine if the click was on the sphere, and where exactly + gfx2::ray_t ray = gfx2::create_ray( + arma::fvec({0, 0, 3}), (int) mouse_x, (int) mouse_y, + view, projection, window_size.win_width, window_size.win_height + ); + + arma::fvec intersection; + if (gfx2::intersects(ray, node.position, 1.0f, intersection)) { + // Change the target position + arma::fvec p(4); + p.rows(0, 2) = intersection; + p(3) = 1.0f; + + p = arma::inv(gfx2::worldRotation(&node)) * p; + + target = arma::conv_to<arma::vec>::from(p.rows(0, 2)); + + target_model_node.rotation = gfx2::rotation(arma::fvec({1.0f, 0.0f, 0.0f}), + conv_to<fvec>::from(target)); + + arma::mat points1 = sample_gaussian_points(gaussian, arma::vec({1.0f, 0.0f, 0.0f})); + arma::mat points2 = sample_gaussian_points(gaussian, target); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), + conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + must_recompute = true; + } + } + + //-- Right mouse button: rotation of the meshes while held down + if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { + if (!rotating) { + rotating = true; + glfwSetCursor(window, crosshair_cursor); + } + + arma::fmat rotation = + gfx2::rotate(arma::fvec({ 0.0f, 1.0f, 0.0f }), 0.2f * gfx2::deg2rad(mouse_x - previous_mouse_x)) * + gfx2::rotate(arma::fvec({ 1.0f, 0.0f, 0.0f }), 0.2f * gfx2::deg2rad(mouse_y - previous_mouse_y)); + + node.rotation = rotation * node.rotation; + } + else if (rotating) { + rotating = false; + glfwSetCursor(window, arrow_cursor); + } + + previous_mouse_x = mouse_x; + previous_mouse_y = mouse_y; + } + + + // Cleanup + glfwDestroyCursor(crosshair_cursor); + glfwDestroyCursor(arrow_cursor); + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_sphere_product01.cpp b/src/demo_Riemannian_sphere_product01.cpp new file mode 100644 index 0000000..cb932bc --- /dev/null +++ b/src/demo_Riemannian_sphere_product01.cpp @@ -0,0 +1,571 @@ +/* + * demo_Riemannian_sphere_product.cpp + * + * Gaussian product on sphere. + * 3 Gaussians are displayed: + * - Red is a Gaussian whose position and variance can be altered by the user by left clicking on the sphere and by changing the eigenvalues/vectors of the covariance in the bottom left of the window. + * - Blue is a constant Gaussian. + * - Black is the product of Red and Blue + * By right clicking on the sphere the user can rotate it. + * + * Created on: Oct 13, 2017 + * Author: Andras Kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat trans2cov(const ui::Trans2d& trans) { + arma::mat RG = { + { trans.x.x / 200.0, trans.y.x / 200.0 }, + { -trans.x.y / 200.0, -trans.y.y / 200.0 } + }; + + return RG * RG.t(); +} + +//----------------------------------------------- + +arma::mat rotM(arma::vec v) { + arma::vec st = v / norm(v); + float acangle = st(2); + float cosa = acangle; + float sina = sqrt(1 - pow(acangle, 2)); + + if ((1 - acangle) > 1E-16) { + v << st(1) << endr << -st(0) << endr << 0 << endr; + v = v / sina; + } else { + v = zeros(3); + } + + float vera = 1 - cosa; + float x = v(0); + float y = v(1); + float z = v(2); + + arma::mat rot; + rot = { + { cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina }, + { x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina }, + { x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera } + }; + + return rot; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); + arma::mat Exp(3, u.n_cols); + + Exp.row(0) = u.row(0) % sin(normv) / normv; + Exp.row(1) = u.row(1) % sin(normv) / normv; + Exp.row(2) = cos(normv); + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + arma::mat fullone; + fullone.ones(size(x.row(2))); + arma::mat scale(1, x.n_cols); + scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); + + arma::mat Log(2, x.n_cols); + Log.row(0) = x.row(0) % scale; + Log.row(1) = x.row(1) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + arma::mat x = trans(rotM(mu)) * expfct(u); + return x; +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + pole = {0, 0, 1}; + arma::mat R(3, 3, fill::ones); + + if (norm(mu - trans(pole)) < 1E-6) { + R = { { 1, 0, 0}, + { 0, -1, 0}, + { 0, 0, -1}}; + } + else { + R = rotM(mu); + } + + arma::mat u; + u = logfct(R * x); + + return u; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat E; + E << 1.0 << 0.0 << endr << 0.0 << 1.0 << endr << 0.0 << 0.0; + vec logmapTmp = logmap(h, g); + vec logmapTmp_bottom = zeros(1, 1); + + vec vm = rotM(g).t() * arma::join_vert(logmapTmp, logmapTmp_bottom); + double mn = norm(vm, 2); + vec uv = vm / (mn); + mat Rpar = arma::eye(3, 3) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + mat Ac = E.t() * rotM(h) * Rpar * rotM(g).t() * E; //Transportation operator from g to h + return Ac; + +} + +//----------------------------------------------- + +arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat sample_points( { + { 0.0f, 0.0f }, + { 1.0f, 0.0f }, + { 0.0f, 1.0f }, + { -1.0f, 0.0f }, + { 0.0f, -1.0f }, + }); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); + + points.col(0) = target; + + return points; +} + + +/********************************* RENDERING *********************************/ + +//----------------------------------------------------------------------------- +// Create a gaussian mesh, colored (no lightning) +//----------------------------------------------------------------------------- +gfx2::model_t create_gaussian(const arma::fvec& color, const ui::Trans2d& gaussian, + const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); + + return gfx2::create_line(color, points); +} + + +/********************************* FUNCTIONS *********************************/ + +int main(int argc, char **argv) { + cout << "Gaussian product on S2 Riemannian manifold." << endl; + cout << "3 Gaussians are displayed:" << endl; + cout + << " - Red is a Gaussian whose position and variance can be altered by the user by left clicking on the sphere and by changing the eigenvalues/vectors of the covariance in the bottom left of the window." + << endl; + cout << " - Blue is a constant Gaussian." << endl; + cout << " - Black is the product of Red and Blue." << endl; + cout << "By right clicking on the sphere the user can rotate it." << endl; + arma_rng::set_seed_random(); + + arma::vec target( { 0.0, 0.2, 0.6 }); + target = target / norm(target); + + arma::vec target2( { 0.2, 0.2, 0.2 }); + target2 = target2 / norm(target2); + + arma::vec target_product( { -1.0, -1.0, 0.0 }); + target_product = target_product / norm(target_product); + + ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 680)); + ui::Trans2d gaussian2(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 300)); + ui::Trans2d gaussian_product(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 300)); + + // Initialise GLFW + gfx2::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Riemannian sphere product", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glDepthFunc(GL_LESS); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + ui::config.color = 0x770000ff; + ui::config.lineColor = 0x770000ff; + + + // Projection matrix + arma::fmat projection; + + // Camera matrix + arma::fmat view = gfx2::lookAt( + arma::fvec( { 0, 0, 3 }), // Position of the camera + arma::fvec( { 0, 0, 0 }), // Look at the origin + arma::fvec( { 0, 1, 0 }) // Head is up + ); + + + // Creation of the models + // + // The following hierarchy is used: + // - transforms node ("node") + // |__ sphere ("sphere") + // |__ user-modifiable gaussian ("gaussian_model") + // |__ constant gaussian ("gaussian_model2") + // |__ gaussians product ("gaussian_product_model") + // |__ transforms node ("target_model_node") + // |__ target point ("target_model") + // + // This allows to rotate everything by just changing the rotation of the + // root transforms node. The "target_model_node" transforms is necessary + // correctly place the target point, always tangent to the sphere. + + //-- The root transforms node + gfx2::transforms_t node; + node.position.zeros(3); + node.rotation.eye(4, 4); + + //-- The sphere + gfx2::model_t sphere = gfx2::create_sphere(0.99f); + sphere.transforms.parent = &node; + + arma::mat points1 = sample_gaussian_points(gaussian_product, + arma::vec( { 1.0f, 0.0f, 0.0f })); + arma::mat points2 = sample_gaussian_points(gaussian_product, target_product); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + //-- The gaussian + gfx2::model_t gaussian_model = create_gaussian( + arma::fvec( { 0.8f, 0.0f, 0.0f }), gaussian, target + ); + + gfx2::model_t gaussian_model2 = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.8f }), gaussian2, target2 + ); + + gfx2::model_t gaussian_product_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.8f }), gaussian_product, target_product + ); + + gaussian_model.transforms.parent = &node; + gaussian_model2.transforms.parent = &node; + gaussian_product_model.transforms.parent = &node; + + //-- The intermediate transforms node of the target + + gfx2::transforms_t target_model_node; + target_model_node.position.zeros(3); + target_model_node.rotation = gfx2::rotation(arma::fvec( { 1.0f, 0.0f, 0.0f }), + conv_to<fvec>::from(target_product)); + target_model_node.parent = &node; + + //-- The target point + gfx2::model_t target_model = gfx2::create_square( + arma::fvec( { 0.0f, 0.0f, 0.0f }), 0.01f + ); + + target_model.transforms.position = arma::fvec( { 1.0f, 0.0f, 0.0f }); + target_model.transforms.rotation = gfx2::rotate(arma::fvec( { 0.0f, 1.0f, 0.0f }), + gfx2::deg2rad(90.0f)); + target_model.transforms.parent = &target_model_node; + + // Creation of the light + gfx2::point_light_t light; + light.transforms.position = arma::fvec( { 0.0f, 0.0f, 5.0f, 1.0f }); + light.color = arma::fvec( { 1.0f, 1.0f, 1.0f }); + + gfx2::light_list_t lights; + lights.push_back(light); + + // Mouse control + double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; + bool rotating = false; + GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); + GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + + glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); + + // Main loop + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // Update the projection matrix + projection = gfx2::perspective( + gfx2::deg2rad(45.0f), + (float) window_size.fb_width / (float) window_size.fb_height, + 0.1f, 10.0f + ); + + // Ensure that the gaussian widgets are still visible + gaussian.pos.x = 50; + gaussian.pos.y = window_size.win_height - 120; + } + + mat componentsMu = zeros(3, 2); // current means of the components + cube U0 = zeros(2, 2, 2); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + componentsMu.col(0) = target; + tmpCov = trans2cov(gaussian); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(0) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + componentsMu.col(1) = target2; + tmpCov = trans2cov(gaussian2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(1) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + vec MuMan; // starting point on the manifold + MuMan << -1.0 << endr << -1.0 << endr << 0.0; + MuMan /= norm(MuMan, 2); + mat Sigma = zeros(2, 2); + + mat MuTmp = zeros(2, 2); //nbVar (on tangent space) x components + cube SigmaTmp = zeros(2, 2, 2); // nbVar (on tangent space) x nbVar (on tangent space) x components + + for (int n = 0; n < 10; n++) { // compute the Gaussian product + // nbVar = 2 for S2 sphere tangent space + colvec Mu = zeros(2, 1); + mat SigmaSum = zeros(2, 2); + + for (int i = 0; i < 2; i++) { // we have two states + mat Ac = transp(componentsMu.col(i), MuMan); + mat U1 = Ac * U0.slice(i); + SigmaTmp.slice(i) = U1 * U1.t(); + //Tracking component for Gaussian i + SigmaSum += inv(SigmaTmp.slice(i)); + MuTmp.col(i) = logmap(componentsMu.col(i), MuMan); + Mu += inv(SigmaTmp.slice(i)) * MuTmp.col(i); + } + + Sigma = inv(SigmaSum); + //Gradient computation + Mu = Sigma * Mu; + + MuMan = expmap(Mu, MuMan); + } + + eig_sym(tmpEigenValues, tmpEigenVectors, Sigma); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 200.0); + + if (tmpMat(0, 1) >= 0) { + gaussian_product.x.x = -tmpMat(0, 0); + gaussian_product.x.y = tmpMat(1, 0); + gaussian_product.y.x = -tmpMat(0, 1); + gaussian_product.y.y = tmpMat(1, 1); + } else { + gaussian_product.x.x = tmpMat(0, 0); + gaussian_product.x.y = -tmpMat(1, 0); + gaussian_product.y.x = tmpMat(0, 1); + gaussian_product.y.y = -tmpMat(1, 1); + } + + target_product = MuMan; + + // Recreate the gaussian 3D models + gfx2::destroy(gaussian_model); + gaussian_model = create_gaussian( + arma::fvec( { 0.8f, 0.0f, 0.0f }), gaussian, target + ); + gaussian_model.transforms.parent = &node; + + gfx2::destroy(gaussian_product_model); + gaussian_product_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.0f }), gaussian_product, MuMan + ); + gaussian_product_model.transforms.parent = &node; + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glMultMatrixf(projection.memptr()); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glMultMatrixf(view.memptr()); + + // Drawing + gfx2::draw(sphere, lights); + + gfx2::draw(gaussian_model, lights); + gfx2::draw(gaussian_model2, lights); + gfx2::draw(gaussian_product_model, lights); + gfx2::draw(target_model, lights); + + // Gaussian UI widget + ui::begin("Gaussian"); + gaussian = ui::affineSimple(0, gaussian); + ui::end(); + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + // Mouse input + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + //-- Left click + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { + + // Determine if the click was on the sphere, and where exactly + gfx2::ray_t ray = gfx2::create_ray( + arma::fvec( { 0, 0, 3 }), (int) mouse_x, (int) mouse_y, view, + projection, window_size.win_width, window_size.win_height + ); + + arma::fvec intersection; + if (gfx2::intersects(ray, node.position, 1.0f, intersection)) { + // Change the target position + arma::fvec p(4); + p.rows(0, 2) = intersection; + p(3) = 1.0f; + + p = arma::inv(gfx2::worldRotation(&node)) * p; + + target = arma::conv_to<arma::vec>::from(p.rows(0, 2)); + } + } + + target_model_node.rotation = gfx2::rotation( + arma::fvec( { 1.0f, 0.0f, 0.0f }), conv_to<fvec>::from(target_product) + ); + + arma::mat points1 = sample_gaussian_points(gaussian_product, + arma::vec( { 1.0f, 0.0f, 0.0f })); + arma::mat points2 = sample_gaussian_points(gaussian_product, target_product); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + //-- Right mouse button: rotation of the meshes while held down + if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { + if (!rotating) { + rotating = true; + glfwSetCursor(window, crosshair_cursor); + } + + arma::fmat rotation = gfx2::rotate( + arma::fvec( { 0.0f, 1.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_x - previous_mouse_x)) * + gfx2::rotate(arma::fvec( { 1.0f, 0.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_y - previous_mouse_y) + ); + + node.rotation = rotation * node.rotation; + } else if (rotating) { + rotating = false; + glfwSetCursor(window, arrow_cursor); + } + + previous_mouse_x = mouse_x; + previous_mouse_y = mouse_y; + } + + // Cleanup + glfwDestroyCursor(crosshair_cursor); + glfwDestroyCursor(arrow_cursor); + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_Riemannian_sphere_tpgmm01.cpp b/src/demo_Riemannian_sphere_tpgmm01.cpp new file mode 100644 index 0000000..a261a49 --- /dev/null +++ b/src/demo_Riemannian_sphere_tpgmm01.cpp @@ -0,0 +1,922 @@ +/* + * demo_Riemannian_sphere_tpgmm.cpp + * + * TPGMM on sphere with two frames. + * + * Created on: Oct 25, 2017 + * Author: kupcsik + */ + +#include <stdio.h> +#include <armadillo> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + +//----------------------------------------------- + +arma::mat trans2cov(const ui::Trans2d& trans) { + arma::mat RG = { + { trans.x.x / 200.0, trans.y.x / 200.0 }, + { -trans.x.y / 200.0, -trans.y.y / 200.0 } + }; + + return RG * RG.t(); +} + +//----------------------------------------------- + +arma::mat rotM(arma::vec v) { + arma::vec st = v / norm(v); + float acangle = st(2); + float cosa = acangle; + float sina = sqrt(1 - pow(acangle, 2)); + + if ((1 - acangle) > 1E-16) { + v << st(1) << endr << -st(0) << endr << 0 << endr; + v = v / sina; + } else { + v = zeros(3); + } + + float vera = 1 - cosa; + float x = v(0); + float y = v(1); + float z = v(2); + + arma::mat rot; + rot = { + { cosa + pow(x, 2) * vera, x * y * vera - z * sina, x * z * vera + y * sina }, + { x * y * vera + z * sina, cosa + pow(y, 2) * vera, y * z * vera - x * sina }, + { x * z * vera - y * sina, y * z * vera + x * sina, cosa + pow(z, 2) * vera } + }; + + return rot; +} + +//----------------------------------------------- + +arma::mat expfct(arma::mat u) { + arma::mat normv = sqrt(pow(u.row(0), 2) + pow(u.row(1), 2)); + arma::mat Exp(3, u.n_cols); + + Exp.row(0) = u.row(0) % sin(normv) / normv; + Exp.row(1) = u.row(1) % sin(normv) / normv; + Exp.row(2) = cos(normv); + + return Exp; +} + +//----------------------------------------------- + +arma::mat logfct(arma::mat x) { + + arma::mat fullone; + fullone.ones(size(x.row(2))); + arma::mat scale(1, x.n_cols); + scale = acos(x.row(2)) / sqrt(fullone - pow(x.row(2), 2)); + mat ac = acos(x.row(2)); + mat sq = sqrt(fullone - pow(x.row(2), 2)); + + arma::mat Log(2, x.n_cols); + Log.row(0) = x.row(0) % scale; + Log.row(1) = x.row(1) % scale; + + return Log; +} + +//----------------------------------------------- + +arma::mat expmap(arma::mat u, arma::vec mu) { + arma::mat x = trans(rotM(mu)) * expfct(u); + + return x; +} + +//----------------------------------------------- + +arma::mat logmap(arma::mat x, arma::vec mu) { + arma::mat pole; + pole = {0, 0, 1}; + arma::mat R(3, 3, fill::ones); + + if (norm(mu - trans(pole)) < 1E-6) { + R = { { 1, 0, 0}, + { 0, -1, 0}, + { 0, 0, -1}}; + } + else { + R = rotM(mu); + } + + arma::mat u; + u = logfct(R * x); + + return u; +} + +//----------------------------------------------- + +arma::mat transp(vec g, vec h) { + mat E; + E << 1.0 << 0.0 << endr << 0.0 << 1.0 << endr << 0.0 << 0.0; + vec logmapTmp = logmap(h, g); + vec logmapTmp_bottom = zeros(1, 1); + + vec vm = rotM(g).t() * arma::join_vert(logmapTmp, logmapTmp_bottom); + double mn = norm(vm, 2); + vec uv = vm / (mn); + mat Rpar = arma::eye(3, 3) - sin(mn) * (g * uv.t()) - (1 - cos(mn)) * (uv * uv.t()); + mat Ac = E.t() * rotM(h) * Rpar * rotM(g).t() * E; //Transportation operator from g to h + return Ac; + +} + +//----------------------------------------------- + +arma::mat sample_gaussian_points(const ui::Trans2d& gaussian, const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat sample_points({ + { 0.0f, 0.0f }, + { 1.0f, 0.0f }, + { 0.0f, 1.0f }, + { -1.0f, 0.0f }, + { 0.0f, -1.0f }, + }); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * sample_points.t(), target); + + points.col(0) = target; + + return points; +} + +//----------------------------------------------- + +arma::vec gaussPDF(mat Data, colvec Mu, mat Sigma) { + + int nbVar = Data.n_rows; + int nbData = Data.n_cols; + Data = Data.t() - repmat(Mu.t(), nbData, 1); + + vec prob = sum((Data * inv(Sigma)) % Data, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nbVar) * det(Sigma) + 2.2251E-308); + + return prob; +} + + +/********************************* RENDERING *********************************/ + +//----------------------------------------------------------------------------- +// Create a gaussian mesh, colored (no lightning) +//----------------------------------------------------------------------------- +gfx2::model_t create_gaussian(const arma::fvec& color, const ui::Trans2d& gaussian, + const arma::vec& target) { + + arma::mat uCov = trans2cov(gaussian); + + arma::rowvec tl = arma::linspace<arma::rowvec>(-arma::datum::pi, arma::datum::pi, 100); + + arma::mat V; + arma::vec d; + arma::eig_sym(d, V, uCov); + + arma::mat points = expmap(V * diagmat(sqrt(d)) * join_cols(cos(tl), sin(tl)), target); + + return gfx2::create_line(color, points); +} + + +/********************************* FUNCTIONS *********************************/ + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + arma::vec target( { 0.0, 0.2, 0.6 }); + target = target / norm(target); + + arma::vec target2( { 0.2, 0.2, 0.2 }); + target2 = target2 / norm(target2); + + arma::vec target_product( { -1.0, -1.0, 0.0 }); + target_product = target_product / norm(target_product); + + ui::Trans2d gaussian(ImVec2(50, 0), ImVec2(0, 50), ImVec2(50, 680)); + ui::Trans2d gaussian_gmm(ImVec2(50, 0), ImVec2(0, 100), ImVec2(50, 500)); + + // Initialise GLFW + gfx2::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Riemannian sphere tpgmm", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glDepthFunc(GL_LESS); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + ui::config.color = 0x770000ff; + ui::config.lineColor = 0x770000ff; + + + // Projection matrix + arma::fmat projection; + + // Camera matrix + arma::fmat view = gfx2::lookAt( + arma::fvec( { 0, 0, 3 }), // Position of the camera + arma::fvec( { 0, 0, 0 }), // Look at the origin + arma::fvec( { 0, 1, 0 }) // Head is up + ); + + + // Creation of the models + // + // The following hierarchy is used: + // - transforms node ("node") + // |__ sphere ("sphere") + // + // This allows to rotate everything by just changing the rotation of the + // root transforms node. + + //-- The root transforms node + gfx2::transforms_t node; + node.position.zeros(3); + node.rotation.eye(4, 4); + + //-- The sphere + gfx2::model_t sphere = gfx2::create_sphere(0.99f); + sphere.transforms.parent = &node; + + arma::mat points1 = sample_gaussian_points(gaussian, arma::vec( { 1.0f, 0.0f, 0.0f })); + arma::mat points2 = sample_gaussian_points(gaussian, target); + + arma::fmat rotation; + arma::fvec translation; + gfx2::rigid_transform_3D(conv_to<fmat>::from(points1), conv_to<fmat>::from(points2), + rotation, translation); + + sphere.transforms.rotation.submat(0, 0, 2, 2) = rotation; + + // Creation of the light + gfx2::point_light_t light; + light.transforms.position = arma::fvec( { -3.0f, 3.0f, 5.0f, 1.0f }); + light.color = arma::fvec( { 1.0f, 1.0f, 1.0f }); + + gfx2::light_list_t lights; + lights.push_back(light); + + // Mouse control + double mouse_x, mouse_y, previous_mouse_x, previous_mouse_y; + bool rotating = false; + GLFWcursor* crosshair_cursor = glfwCreateStandardCursor(GLFW_HAND_CURSOR); + GLFWcursor* arrow_cursor = glfwCreateStandardCursor(GLFW_ARROW_CURSOR); + + glfwGetCursorPos(window, &previous_mouse_x, &previous_mouse_y); + + // Main loop + bool must_recompute = true; + int nbStates = 5; + int previous_nbStates = nbStates; + int nbVar = 3; //including time + int nbSamples = 80; + int nbVarMan = 4; //including time + int nbIterEM = 30; + int nbIter = 10; //Number of iteration for the Gauss Newton algorithm + double params_diagRegFact = 1E-4; + int nbFrames = 2; + vec e0 = { 0, 0, 1 }; // center on manifold + + // Load manifold data: + // - first row is time + // - 2:4 is data in frame 1 + // - 5:7 is data in frame 2 + mat demo(1 + 2 * nbVarMan, nbSamples); + demo.load("./data/data_sphere_tpgmm_transformedXU.txt"); + + mat demoX = demo; // data = [X, [U; 0]] + mat demoU = demoX.submat(0, nbSamples, 4, 2 * nbSamples - 1); + demoX = demoX.submat(0, 0, 6, nbSamples - 1); + + // cout << "demoX ncols/nrows: " << demoX.n_cols << ", " << demoX.n_rows << endl; + // cout << "demoU ncols/nrows: " << demoU.n_cols << ", " << demoU.n_rows << endl; + + rowvec xIn = demoX.row(0); + mat xOut = demoX.rows(1, 6); + + std::vector<gfx2::model_t> gaussian_models; + std::vector<gfx2::model_t> sample_points; + + for (int i = 0; i < nbSamples; i++) { + vec tmpEigenValues; + mat tmpEigenVectors; + mat tmpSigma; + tmpSigma << 1.0 << 0.0 << endr << 0.0 << 1.0; + eig_sym(tmpEigenValues, tmpEigenVectors, tmpSigma); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 1.0); + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.5f }), gaussian_gmm, demoX.col(i).rows(1, 3) + ); + + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + + gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.5f, 0.0f, 0.0f }), gaussian_gmm, demoX.col(i).rows(4, 6) + ); + + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + } + + mat A1; + mat A1_prev; + mat A2; + colvec b1; + colvec b2; + + // Task parameters + A1 << 0.4122 << -0.9111 << endr << -0.9111 << -0.4122; + gaussian.x.x = -34.9728; + gaussian.x.y = -30.6904; + gaussian.y.x = 43.0625; + gaussian.y.y = -49.4486; + + A2 << -0.9252 << -0.3796 << endr << -0.3796 << 0.9252; + + b1 << 0.7046 << endr << 0.1091 << endr << -0.7012; + b2 << -0.4133 << endr << 0.5748 << endr << -0.7062; + + bool tasp_params_changed = true; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + previous_nbStates = nbStates; + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + // Update the projection matrix + projection = gfx2::perspective( + gfx2::deg2rad(45.0f), + (float) window_size.fb_width / (float) window_size.fb_height, + 0.1f, 10.0f + ); + + // Ensure that the gaussian widgets are still visible + gaussian.pos.x = 50; + gaussian.pos.y = window_size.win_height - 120; + } + + if (must_recompute) { + + for (int i = 0; i < gaussian_models.size(); i++) { + gfx2::destroy(gaussian_models.at(i)); + } + + //======== Recomputing tpgmm model with the latest task parameters ======== + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + vec Priors(nbStates); + cube Sigma(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1), nbStates); + mat Mu(1 + 2 * (nbVar - 1), nbStates); + + // ++++++++++++++++++++++ RANDOM INIT ++++++++++++++++++ + /* arma_rng::set_seed_random(); // set the seed to a random value + + Priors = ones(nbStates); + Priors /= nbStates; + + // Random init the means and covariances + //cout << "init menas and covs" << endl; + // 5 x nbStates + + for (int i = 0; i < nbStates; i++) { //for some reason the matrix randn doesn't work => doing it with vectors + for (int j = 0; j < (1 + 2 * (nbVar - 1)); j++) { + Mu(j, i) = randn(); + } + } + for (int i = 0; i < nbStates; i++) { + Sigma.slice(i) = eye(1 + 2 * (nbVar - 1), 1 + 2 * (nbVar - 1)) * 0.5; //%Covariance in the tangent plane at point MuMan + } + */ + // +++++++++++++++++++++++ KBINS INIT +++++++++++++++++++++++ + int nbData = 20; + + vec tSep = round(linspace<vec>(0, nbData, nbStates + 1)); + + for (int i = 0; i < nbStates; i++) { + rowvec id; + + for (int n = 0; n < 4; n++) { + vec vecDummy = round(n * nbData + linspace<vec>( + tSep(i), tSep(i + 1) - 1, tSep(i + 1) - tSep(i)) + ); + + id = join_horiz(id, vecDummy.t()); + } + + Priors(i) = id.n_elem; + + mat demoUColID = zeros(5, id.n_cols); + + for (int j = 0; j < id.n_elem; j++) { + + demoUColID.col(j) = demoU.col((uint) id(j)); + } + + Mu.col(i) = mean(demoUColID, 1); + Sigma.slice(i) = cov(demoUColID.t()) + eye(5, 5) * 1E-4; + } + Priors = Priors / sum(Priors); + + // +++++++++++++++++++++++++ INIT END +++++++++++++++++++++++++++++++++ + + mat MuMan = join_vert(Mu.row(0), expmap(Mu.rows(1, 2), e0)); //Center on the manifold + MuMan = join_vert(MuMan, expmap(Mu.rows(3, 4), e0)); + Mu = zeros(1 + (nbVar - 1) * 2, nbStates); + + cube u(1 + 2 * (nbVar - 1), nbSamples, nbStates); //uTmp in matlab code + + for (int nb = 0; nb < nbIterEM; nb++) { + + //E-step + mat L = zeros(nbStates, nbSamples); + mat xcTmp; + + for (int i = 0; i < nbStates; i++) { + xcTmp = join_vert(xIn - MuMan(0, i), logmap(xOut.rows(0, 2), MuMan.submat(1, i, 3, i))); + xcTmp = join_vert(xcTmp, logmap(xOut.rows(3, 5), MuMan.submat(4, i, 6, i))); + + L.row(i) = Priors(i) * (gaussPDF(xcTmp, Mu.col(i), Sigma.slice(i)).t()); + } + + rowvec Lsum = sum(L, 0) + 1E-308; + + mat GAMMA = L / repmat(Lsum, nbStates, 1); + + colvec GammaSum = sum(GAMMA, 1); + mat GAMMA2 = GAMMA / repmat(GammaSum, 1, nbSamples); + + //M-step + for (int i = 0; i < nbStates; i++) { + //Update Priors + Priors(i) = sum(GAMMA.row(i)) / (nbSamples); + + //Update MuMan + for (int n = 0; n < nbIter; n++) { + u.slice(i) = join_vert(join_vert(xIn - MuMan(0, i), logmap(xOut.rows(0, 2), MuMan.submat(1, i, 3, i))), + logmap(xOut.rows(3, 5), MuMan.submat(4, i, 6, i))); + MuMan.col(i) = join_vert( + join_vert((MuMan(0, i) + u.slice(i).row(0)) * GAMMA2.row(i).t(), + expmap(u.slice(i).rows(1, 2) * GAMMA2.row(i).t(), MuMan.submat(1, i, 3, i))), + expmap(u.slice(i).rows(3, 4) * GAMMA2.row(i).t(), MuMan.submat(4, i, 6, i))); + } + //Update Sigma + Sigma.slice(i) = u.slice(i) * diagmat(GAMMA2.row(i)) * u.slice(i).t() + + eye(1 + 2 * (nbVar - 1), + 1 + 2 * (nbVar - 1) + ) * params_diagRegFact; + } + + } + + // for (int i = 0; i < nbStates; i++) { + // cout << "============= Component #" << i << " ===========" << endl; + // cout << "Prior: " << Priors(i) << endl; + // cout << "MuMan:" << endl; + // cout << MuMan.col(i).t() << endl; + // cout << "Sigma: " << endl; + // cout << Sigma.slice(i) << endl << endl; + // } + + //Reformatting as a tensor GMM + mat MuManOld = MuMan; + cube SigmaOld = Sigma; + cube MuMan2 = zeros(1 + nbVar, nbFrames, nbStates); + field<cube> Sigma2(nbStates); + for (int i = 0; i < nbStates; i++) { + cube dummyCube(nbVar, nbVar, nbFrames); + Sigma2.at(i) = dummyCube; + } + + for (int i = 0; i < nbStates; i++) { + for (int m = 0; m < nbFrames; m++) { + + // dummy way to construct id and idMan, works for 2 frames + uvec id; + uvec idMan; + if (m == 0) { + id = {0, 1, 2}; + } else { + id = {0, 3, 4}; + } + + if (m == 0) { + idMan = {0, 1, 2, 3}; + } else { + idMan = {0, 4, 5, 6}; + } + + for (int ii = 0; ii < idMan.size(); ii++) { + MuMan2.slice(i).col(m)(ii) = MuManOld.col(i)(idMan(ii)); + } + + Sigma2.at(i).slice(m) = SigmaOld.slice(i).submat(id, id); + } + } + + // Transforming gaussians with respective frames + for (int i = 0; i < nbStates; i++) { + + vec uTmp = A1 * logmap(MuMan2.slice(i).col(0).rows(1, 3), e0); + MuMan2.slice(i).col(0).rows(1, 3) = expmap(uTmp, b1); + mat Ac1 = transp(b1, MuMan2.slice(i).col(0).rows(1, 3)); + + Sigma2.at(i).slice(0).submat(1, 1, 2, 2) = + Ac1 * A1 * Sigma2.at(i).slice(0).submat(1, 1, 2, 2) * A1.t() * Ac1.t(); + + uTmp = A2 * logmap(MuMan2.slice(i).col(1).rows(1, 3), e0); + MuMan2.slice(i).col(1).rows(1, 3) = expmap(uTmp, b2); + mat Ac2 = transp(b2, MuMan2.slice(i).col(1).rows(1, 3)); + + Sigma2.at(i).slice(1).submat(1, 1, 2, 2) = + Ac2 * A2 * Sigma2.at(i).slice(1).submat(1, 1, 2, 2) * A2.t() * Ac2.t(); + } + + // Transforming sample points with respective frames + for (int i = 0; i < sample_points.size(); i++) { + gfx2::destroy(sample_points.at(i)); + } + sample_points.clear(); + for (int i = 0; i < nbSamples; i++) { + vec tmpEigenValues; + mat tmpEigenVectors; + mat tmpSigma; + vec uTmp; + tmpSigma << 1.0 << 0.0 << endr << 0.0 << 1.0; + eig_sym(tmpEigenValues, tmpEigenVectors, tmpSigma); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 1.0); + + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + + uTmp = A1 * logmap(demoX.col(i).rows(1, 3), e0); + uTmp = expmap(uTmp, b1); + + gfx2::model_t gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 1.0f }), gaussian_gmm, uTmp + ); + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + + uTmp = A2 * logmap(demoX.col(i).rows(4, 6), e0); + uTmp = expmap(uTmp, b2); + + gaussian_gmm_model = create_gaussian( + arma::fvec( { 1.0f, 0.0f, 0.0f }), gaussian_gmm, uTmp + ); + gaussian_gmm_model.transforms.parent = &node; + + sample_points.push_back(gaussian_gmm_model); + } + + //Gaussian product + mat MuManProduct(3, nbStates); + cube SigmaProduct(2, 2, nbStates); + + for (int i = 0; i < nbStates; i++) { + mat componentsMu = zeros(3, 2); // current means of the components + cube U0 = zeros(2, 2, 2); //current covariances of the components + + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + componentsMu.col(0) = MuMan2.slice(i).col(0).rows(1, 3); + tmpCov = Sigma2.at(i).slice(0).submat(1, 1, 2, 2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(0) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + componentsMu.col(1) = MuMan2.slice(i).col(1).rows(1, 3); + tmpCov = Sigma2.at(i).slice(1).submat(1, 1, 2, 2); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + U0.slice(1) = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5)); + + vec MuMan; // starting point on the manifold + MuMan << 0.0 << endr << 0.0 << endr << 1.0; + MuMan /= norm(MuMan, 2); + mat Sigma = zeros(2, 2); + + mat MuTmp = zeros(2, 2); //nbVar (on tangent space) x components + cube SigmaTmp = zeros(2, 2, 2); // nbVar (on tangent space) x nbVar (on tangent space) x components + + for (int n = 0; n < 10; n++) { // compute the Gaussian product + colvec Mu = zeros(2, 1); + mat SigmaSum = zeros(2, 2); + + for (int i = 0; i < 2; i++) { // we have two states + mat Ac = transp(componentsMu.col(i), MuMan); + mat U1 = Ac * U0.slice(i); + SigmaTmp.slice(i) = U1 * U1.t(); + + //Tracking component for Gaussian i + SigmaSum += inv(SigmaTmp.slice(i)); + MuTmp.col(i) = logmap(componentsMu.col(i), MuMan); + Mu += inv(SigmaTmp.slice(i)) * MuTmp.col(i); + } + + Sigma = inv(SigmaSum); + //Gradient computation + Mu = Sigma * Mu; + + MuMan = expmap(Mu, MuMan); + } + + MuManProduct.col(i) = MuMan; + SigmaProduct.slice(i) = Sigma; + + // cout << "================ Gaussian Product component #" << i << " ========================" << endl; + // cout << "MuMan: " << MuMan.t() << endl; + // cout << "Sigma: " << endl << Sigma << endl; + } + + // Data for plotting + gaussian_models.clear(); + for (int f = 0; f < nbFrames; f++) { + uvec id = { 1, 2 }; + uvec idMan = { 1, 3 }; + + for (int i = 0; i < nbStates; i++) { + eig_sym(tmpEigenValues, tmpEigenVectors, Sigma2.at(i).slice(f).submat(id, id)); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 200.0); + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model; + if (f == 0) { + gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 1.0f }), + gaussian_gmm, MuMan2.slice(i).col(f).rows(idMan(0), idMan(1)) + ); + } else { + gaussian_gmm_model = create_gaussian( + arma::fvec( { 1.0f, 0.0f, 0.0f }), + gaussian_gmm, MuMan2.slice(i).col(f).rows(idMan(0), idMan(1)) + ); + } + gaussian_gmm_model.transforms.parent = &node; + + gaussian_models.push_back(gaussian_gmm_model); + + } + + } + //product + for (int i = 0; i < nbStates; i++) { + vec tmpVec; + mat tmpCov; + vec tmpEigenValues; + mat tmpEigenVectors; + + eig_sym(tmpEigenValues, tmpEigenVectors, SigmaProduct.slice(i)); + mat tmpMat = tmpEigenVectors * diagmat(pow(tmpEigenValues, 0.5) * 200.0); + + if (tmpMat(0, 1) >= 0) { + gaussian_gmm.x.x = -tmpMat(0, 0); + gaussian_gmm.x.y = tmpMat(1, 0); + gaussian_gmm.y.x = -tmpMat(0, 1); + gaussian_gmm.y.y = tmpMat(1, 1); + } else { + gaussian_gmm.x.x = tmpMat(0, 0); + gaussian_gmm.x.y = -tmpMat(1, 0); + gaussian_gmm.y.x = tmpMat(0, 1); + gaussian_gmm.y.y = -tmpMat(1, 1); + } + + gfx2::model_t gaussian_gmm_model; + + gaussian_gmm_model = create_gaussian( + arma::fvec( { 0.0f, 0.0f, 0.0f }), gaussian_gmm, MuManProduct.col(i) + ); + + gaussian_gmm_model.transforms.parent = &node; + + gaussian_models.push_back(gaussian_gmm_model); + } + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(1.0f, 1.0f, 1.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glMultMatrixf(projection.memptr()); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glMultMatrixf(view.memptr()); + + // Drawing + gfx2::draw(sphere, lights); + + for (int i = 0; i < gaussian_models.size(); i++) { + gfx2::draw(gaussian_models.at(i), lights); + } + + for (int i = 0; i < sample_points.size(); i++) { + gfx2::draw(sample_points.at(i), lights); + } + + // Gaussian UI widget + ui::begin("Gaussian"); + gaussian = ui::affineSimple(0, gaussian); + ui::end(); + + mat tmpEigenVectors; + vec tmpEigenValues; + mat tmpCov = trans2cov(gaussian); + eig_sym(tmpEigenValues, tmpEigenVectors, tmpCov); + + A1_prev = A1; + A1 = tmpEigenVectors; + + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 74)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove); + ImGui::SliderInt("Nb states", &nbStates, 1, 10); + ImGui::Text("Hold the right mouse button to rotate the sphere"); + ImGui::End(); + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + if (previous_nbStates != nbStates) { + must_recompute = true; + // cout << "Recomputing GMM with " << nbStates << " states..." << endl; + } else { + must_recompute = false; + } + + if (norm(A1 - A1_prev, 2) != 0) { + tasp_params_changed = true; + must_recompute = true; + } + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + // Mouse input + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + //-- Left click + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { + + // Determine if the click was on the sphere, and where exactly + gfx2::ray_t ray = gfx2::create_ray( + arma::fvec( { 0, 0, 3 }), (int) mouse_x, (int) mouse_y, view, + projection, window_size.win_width, window_size.win_height + ); + + arma::fvec intersection; + if (gfx2::intersects(ray, node.position, 1.0f, intersection)) { + // Change the target position + arma::fvec p(4); + p.rows(0, 2) = intersection; + p(3) = 1.0f; + + p = arma::inv(gfx2::worldRotation(&node)) * p; + + target = arma::conv_to<arma::vec>::from(p.rows(0, 2)); + b1 = -target; + tasp_params_changed = true; + + must_recompute = true; + } + } + + //-- Right mouse button: rotation of the meshes while held down + if (ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_2)) { + if (!rotating) { + rotating = true; + glfwSetCursor(window, crosshair_cursor); + } + + arma::fmat rotation = gfx2::rotate( + arma::fvec( { 0.0f, 1.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_x - previous_mouse_x)) * + gfx2::rotate(arma::fvec( { 1.0f, 0.0f, 0.0f }), + 0.2f * gfx2::deg2rad(mouse_y - previous_mouse_y) + ); + + node.rotation = rotation * node.rotation; + } else if (rotating) { + rotating = false; + glfwSetCursor(window, arrow_cursor); + } + + previous_mouse_x = mouse_x; + previous_mouse_y = mouse_y; + } + + // Cleanup + glfwDestroyCursor(crosshair_cursor); + glfwDestroyCursor(arrow_cursor); + + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_TPbatchLQR01.cpp b/src/demo_TPbatchLQR01.cpp new file mode 100644 index 0000000..a15a5c1 --- /dev/null +++ b/src/demo_TPbatchLQR01.cpp @@ -0,0 +1,2031 @@ +/* + * demo_TPbatchLQR01.cpp + * + * Linear quadratic control (unconstrained linear MPC) acting in multiple frames, + * which is equivalent to a product of Gaussian controllers through a TP-GMM + * representation. + * + * @article{Calinon16JIST, + * author="Calinon, S.", + * title="A Tutorial on Task-Parameterized Movement Learning and Retrieval", + * journal="Intelligent Service Robotics", + * publisher="Springer Berlin Heidelberg", + * doi="10.1007/s11370-015-0187-9", + * year="2016", + * volume="9", + * number="1", + * pages="1--29" + * } + * + * Authors: Sylvain Calinon, Philip Abbet + */ + + +#include <stdio.h> +#include <float.h> +#include <armadillo> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +#define IMGUI_DEFINE_MATH_OPERATORS +#include <imgui_internal.h> + +using namespace arma; + + +/***************************** ALGORITHM SECTION *****************************/ + +typedef std::vector<vec> vector_list_t; +typedef std::vector<mat> matrix_list_t; + + +//----------------------------------------------------------------------------- +// Contains all the parameters used by the algorithm. Some of them are +// modifiable through the UI, others are hard-coded. +//----------------------------------------------------------------------------- +struct parameters_t { + int nb_states; // Number of components in the GMM + int nb_frames; // Number of candidate frames of reference + int nb_deriv; // Number of static and dynamic features + int nb_data; // Number of datapoints in a trajectory + double rfactor; // Control cost in LQR + float dt; // Time step duration + int nb_stoch_repros; // Number of reproductions with stochastic sampling +}; + + +//----------------------------------------------------------------------------- +// Contains values precomputed from the parameters and model, to speed up +// further computations +//----------------------------------------------------------------------------- +struct precomputed_t { + // Control cost matrix + mat R; + + // Transfer matrices in batch LQR, see Eq. (35) + mat Su; + mat Sx; + + // Eigen decompositions (indexing: V[state][frame]) + std::vector<matrix_list_t> V; + std::vector<matrix_list_t> D; + + // Inverses (indexing: inv_sigma[state][frame]) + std::vector<matrix_list_t> inv_sigma; +}; + + +//----------------------------------------------------------------------------- +// Model trained using the algorithm +//----------------------------------------------------------------------------- +struct model_t { + parameters_t parameters; // Parameters used to train the model + precomputed_t precomputed; // Precomputed values + + // These lists contain one element per GMM state and per frame (access them + // by doing: mu[state][frame]) + std::vector<vector_list_t> mu; + std::vector<matrix_list_t> sigma; + + int nb_var; + mat pix; + vec priors; +}; + + +//----------------------------------------------------------------------------- +// Represents a coordinate system, aka a reference frame +//----------------------------------------------------------------------------- +struct coordinate_system_t { + + coordinate_system_t(const arma::vec& position, const arma::mat& orientation, + const parameters_t& parameters) { + + this->position = zeros(2 + (parameters.nb_deriv - 1) * 2); + this->position(span(0, 1)) = position(span(0, 1)); + + this->orientation = kron(eye(parameters.nb_deriv, parameters.nb_deriv), + orientation(span(0, 1), span(0, 1))); + } + + vec position; + mat orientation; +}; + + +//----------------------------------------------------------------------------- +// Represents a list of coordinate systems +//----------------------------------------------------------------------------- +typedef std::vector<coordinate_system_t> coordinate_system_list_t; + + +//----------------------------------------------------------------------------- +// Contains all the needed informations about a demonstration, like: +// - its reference frames +// - the trajectory originally drawn by the user +// - the resampled trajectory +// - the trajectory expressed in each reference frame +//----------------------------------------------------------------------------- +class Demonstration +{ +public: + Demonstration(coordinate_system_list_t coordinate_systems, + const std::vector<arma::vec>& points, + const parameters_t& parameters) + : coordinate_systems(coordinate_systems) + { + points_original = mat(2, points.size()); + + for (size_t i = 0; i < points.size(); ++i) { + points_original(0, i) = points[i](0); + points_original(1, i) = points[i](1); + } + + update(parameters); + } + + + //------------------------------------------------------------------------- + // Resample the trajectory and recompute it in each reference frame + // according to the provided parameters + //------------------------------------------------------------------------- + void update(const parameters_t& parameters) + { + // Resampling of the trajectory + arma::vec x = points_original.row(0).t(); + arma::vec y = points_original.row(1).t(); + arma::vec x2(parameters.nb_data); + arma::vec y2(parameters.nb_data); + + arma::vec from_indices = arma::linspace<arma::vec>(0, points_original.n_cols - 1, points_original.n_cols); + arma::vec to_indices = arma::linspace<arma::vec>(0, points_original.n_cols - 1, parameters.nb_data); + + interp1(from_indices, x, to_indices, x2, "*linear"); + interp1(from_indices, y, to_indices, y2, "*linear"); + + points = mat(2 * parameters.nb_deriv, parameters.nb_data); + points(span(0), span::all) = x2.t(); + points(span(1), span::all) = y2.t(); + + // Compute the derivatives + mat D = (diagmat(ones(1, parameters.nb_data - 1), -1) - + eye(parameters.nb_data, parameters.nb_data)) / parameters.dt; + + D(parameters.nb_data - 1, parameters.nb_data - 1) = 0.0; + + points(span(2, 3), span::all) = points(span(0, 1), span::all) * pow(D, 1); + + // Compute the points in each coordinate system + points_in_coordinate_systems.clear(); + + for (int m = 0; m < coordinate_systems.size(); ++m) { + points_in_coordinate_systems.push_back( + solve(coordinate_systems[m].orientation, + points - repmat(coordinate_systems[m].position, 1, parameters.nb_data)) + ); + } + } + + + //------------------------------------------------------------------------- + // Returns the coordinates of a point in a specific reference frame of + // the demonstration + //------------------------------------------------------------------------- + arma::vec convert_to_coordinate_system(const arma::vec& point, int frame) const { + vec original_point = zeros(points.n_rows); + original_point(span(0, 1)) = point(span(0, 1)); + + vec result = solve(coordinate_systems[frame].orientation, + original_point - coordinate_systems[frame].position); + + return result(span(0, 1)); + } + + +public: + coordinate_system_list_t coordinate_systems; + arma::mat points_original; + arma::mat points; + matrix_list_t points_in_coordinate_systems; +}; + + +//----------------------------------------------------------------------------- +// Represents a list of demonstrations +//----------------------------------------------------------------------------- +typedef std::vector<Demonstration> demonstration_list_t; + + +//----------------------------------------------------------------------------- +// Computes the factorial of a number +//----------------------------------------------------------------------------- +int factorial(int n) { + return (n == 1 || n == 0) ? 1 : factorial(n - 1) * n; +} + + +//----------------------------------------------------------------------------- +// Return the likelihood of datapoint(s) to be generated by a Gaussian +// parameterized by center and covariance +//----------------------------------------------------------------------------- +arma::vec gaussPDF(const mat& data, colvec mu, mat sigma) { + + int nb_var = data.n_rows; + int nb_data = data.n_cols; + + mat data2 = data.t() - repmat(mu.t(), nb_data, 1); + + vec prob = sum((data2 * inv(sigma)) % data2, 1); + + prob = exp(-0.5 * prob) / sqrt(pow((2 * datum::pi), nb_var) * det(sigma) + DBL_MIN); + + return prob; +} + + +//----------------------------------------------------------------------------- +// Initialization of Gaussian Mixture Model (GMM) parameters by clustering an +// ordered dataset into equal bins +//----------------------------------------------------------------------------- +void init_tensorGMM_kbins(const demonstration_list_t& demos, + model_t &model) { + + model.priors.resize(model.parameters.nb_states); + model.mu.clear(); + model.sigma.clear(); + + model.nb_var = demos[0].points_in_coordinate_systems[0].n_rows; + + + // Initialize bins + uvec t_sep = linspace<uvec>(0, model.parameters.nb_data - 1, + model.parameters.nb_states + 1); + + struct bin_t { + mat data; + vec mu; + mat sigma; + }; + + std::vector<bin_t> bins; + for (int i = 0; i < model.parameters.nb_states; ++i) { + bin_t bin; + bin.data = zeros(model.nb_var * model.parameters.nb_frames, + demos.size() * (t_sep(i + 1) - t_sep(i) + 1)); + + bins.push_back(bin); + } + + + // Split each demonstration in K equal bins + for (int n = 0; n < demos.size(); ++n) { + + for (int i = 0; i < model.parameters.nb_states; ++i) { + int bin_size = t_sep(i + 1) - t_sep(i) + 1; + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + bins[i].data(span(m * model.nb_var, (m + 1) * model.nb_var - 1), + span(n * bin_size, (n + 1) * bin_size - 1)) = + demos[n].points_in_coordinate_systems[m](span::all, span(t_sep(i), t_sep(i + 1))); + } + } + } + + + // Calculate statistics on bin data + for (int i = 0; i < model.parameters.nb_states; ++i) { + bins[i].mu = mean(bins[i].data, 1); + bins[i].sigma = cov(bins[i].data.t()); + model.priors(i) = bins[i].data.n_elem; + } + + + // Reshape GMM into a tensor + for (int i = 0; i < model.parameters.nb_states; ++i) { + model.mu.push_back(vector_list_t()); + model.sigma.push_back(matrix_list_t()); + } + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + for (int i = 0; i < model.parameters.nb_states; ++i) { + model.mu[i].push_back(bins[i].mu(span(m * model.nb_var, (m + 1) * model.nb_var - 1))); + + model.sigma[i].push_back(bins[i].sigma(span(m * model.nb_var, (m + 1) * model.nb_var - 1), + span(m * model.nb_var, (m + 1) * model.nb_var - 1))); + } + } + + model.priors /= sum(model.priors); +} + + +//----------------------------------------------------------------------------- +// Training of a task-parameterized Gaussian mixture model (GMM) with an +// expectation-maximization (EM) algorithm. +// +// The approach allows the modulation of the centers and covariance matrices of +// the Gaussians with respect to external parameters represented in the form of +// candidate coordinate systems. +//----------------------------------------------------------------------------- +void train_EM_tensorGMM(const demonstration_list_t& demos, + model_t &model) { + + const int nb_max_steps = 100; // Maximum number of iterations allowed + const int nb_min_steps = 5; // Minimum number of iterations allowed + const double max_diff_log_likelihood = 1e-5; // Likelihood increase threshold + // to stop the algorithm + const double diag_reg_fact = 1e-2; // Regularization term is optional + + + cube data(model.nb_var, model.parameters.nb_frames, + demos.size() * model.parameters.nb_data); + + for (int n = 0; n < demos.size(); ++n) { + for (int m = 0; m < model.parameters.nb_frames; ++m) { + data(span::all, span(m), span(n * model.parameters.nb_data, + (n + 1) * model.parameters.nb_data - 1)) = + demos[n].points_in_coordinate_systems[m]; + } + } + + + std::vector<double> log_likelihoods; + + for (int iter = 0; iter < nb_max_steps; ++iter) { + + // E-step + mat L = ones(model.parameters.nb_states, data.n_slices); + + for (int i = 0; i < model.parameters.nb_states; ++i) { + for (int m = 0; m < model.parameters.nb_frames; ++m) { + + // Matricization/flattening of tensor + mat data_mat(data(span::all, span(m), span::all)); + + vec gamma0 = gaussPDF(data_mat, model.mu[i][m], model.sigma[i][m]); + + L(i, span::all) = L(i, span::all) % gamma0.t(); + } + + L(i, span::all) = L(i, span::all) * model.priors(i); + } + + mat gamma = L / repmat(sum(L, 0) + DBL_MIN, L.n_rows, 1); + mat gamma2 = gamma / repmat(sum(gamma, 1), 1, data.n_slices); + + model.pix = gamma2; + + + // M-step + for (int i = 0; i < model.parameters.nb_states; ++i) { + + // Update priors + model.priors(i) = sum(gamma(i, span::all)) / data.n_slices; + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + + // Matricization/flattening of tensor + mat data_mat(data(span::all, span(m), span::all)); + + // Update mu + model.mu[i][m] = data_mat * gamma2(i, span::all).t(); + + // Update sigma + mat data_tmp = data_mat - repmat(model.mu[i][m], 1, data.n_slices); + model.sigma[i][m] = data_tmp * diagmat(gamma2(i, span::all)) * data_tmp.t() + + eye(data_tmp.n_rows, data_tmp.n_rows) * diag_reg_fact; + } + } + + // Compute average log-likelihood + log_likelihoods.push_back(vec(sum(log(sum(L, 0)), 1))[0] / data.n_slices); + + // Stop the algorithm if EM converged (small change of log-likelihood) + if (iter >= nb_min_steps) { + if (log_likelihoods[iter] - log_likelihoods[iter - 1] < max_diff_log_likelihood) + break; + } + } +} + + +//----------------------------------------------------------------------------- +// Perform the precomputations needed to speed-up further processing +//----------------------------------------------------------------------------- +void precompute(model_t &model) { + + model.precomputed.inv_sigma.clear(); + model.precomputed.V.clear(); + model.precomputed.D.clear(); + + // Precomputation of eigendecompositions and inverses + for (int i = 0; i < model.parameters.nb_states; ++i) { + model.precomputed.inv_sigma.push_back(matrix_list_t()); + model.precomputed.V.push_back(matrix_list_t()); + model.precomputed.D.push_back(matrix_list_t()); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + vec eigval; + mat eigvec; + + eig_sym(eigval, eigvec, model.sigma[i][m](span(0, 1), span(0, 1))); + + uvec id = sort_index(eigval, "descend"); + + model.precomputed.V[i].push_back(eigvec.cols(id)); + model.precomputed.D[i].push_back(diagmat(eigval(id))); + model.precomputed.inv_sigma[i].push_back(inv(model.sigma[i][m])); + } + } + + // Control cost matrix + model.precomputed.R = eye(2, 2) * model.parameters.rfactor; + model.precomputed.R = kron(eye(model.parameters.nb_data - 1, model.parameters.nb_data - 1), + model.precomputed.R); + + // Integration with higher order Taylor series expansion + mat A1d = zeros(model.parameters.nb_deriv, model.parameters.nb_deriv); + mat B1d = zeros(model.parameters.nb_deriv, 1); + + for (int i = 0; i < model.parameters.nb_deriv; ++i) { + // Discrete 1D + A1d = A1d + diagmat(ones(model.parameters.nb_deriv - i, 1), i) * + pow(model.parameters.dt, i) * 1.0 / factorial(i); + + B1d(model.parameters.nb_deriv - i - 1) = pow(model.parameters.dt, i + 1) * + 1.0 / factorial(i + 1); + } + + mat A = kron(A1d, eye(2, 2)); // Discrete nD + mat B = kron(B1d, eye(2, 2)); // Discrete nD + + // Build Sx and Su matrices (transfer matrices in batch LQR), see Eq. (35) + model.precomputed.Su = zeros(model.nb_var * model.parameters.nb_data, + 2 * (model.parameters.nb_data - 1)); + + model.precomputed.Sx = kron(ones(model.parameters.nb_data, 1), + eye(model.nb_var, model.nb_var)); + + mat M = zeros(B.n_rows, 2 * model.parameters.nb_data); + + int n = 2 * model.parameters.nb_data - 2; + M(span::all, span(n, n + 1)) = B; + + for (int n = 1; n < model.parameters.nb_data; ++n) { + span id1(n * model.nb_var, model.parameters.nb_data * model.nb_var - 1); + model.precomputed.Sx(id1, span::all) = model.precomputed.Sx(id1, span::all) * A; + + id1 = span(n * model.nb_var, (n + 1) * model.nb_var - 1); + span id2(0, n * 2 - 1); + + int n2 = 2 * model.parameters.nb_data - n * 2; + model.precomputed.Su(id1, id2) = M(span::all, span(n2, n2 + n * 2 - 1)); + + M(span::all, span(n2 - 2, n2 - 1)) = A * M(span::all, span(n2, n2 + 1)); + } +} + + +//----------------------------------------------------------------------------- +// Training of the model +//----------------------------------------------------------------------------- +void learn(const demonstration_list_t& demos, model_t &model) { + + init_tensorGMM_kbins(demos, model); + train_EM_tensorGMM(demos, model); + precompute(model); +} + + +//----------------------------------------------------------------------------- +// Compute a reproduction +//----------------------------------------------------------------------------- +mat batch_lqr_reproduction(const model_t& model, + const coordinate_system_list_t& coordinate_systems, + const vec& start_coordinates, + int reference_demonstration_index = 0) { + + std::vector< vector_list_t > mu; // Indexing: mu[state][frame] + std::vector< matrix_list_t > inv_sigma; // Indexing: inv_sigma[state][frame] + + // GMM projection, see Eq. (5) + for (int i = 0; i < model.parameters.nb_states; ++i) { + mu.push_back(vector_list_t()); + inv_sigma.push_back(matrix_list_t()); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + mu[i].push_back(coordinate_systems[m].orientation * model.mu[i][m] + + coordinate_systems[m].position); + + inv_sigma[i].push_back(coordinate_systems[m].orientation * + model.precomputed.inv_sigma[i][m] * + coordinate_systems[m].orientation.t()); + } + } + + // Compute best path + uvec q = index_max(model.pix(span::all, + span(reference_demonstration_index * model.parameters.nb_data, + (reference_demonstration_index + 1) * model.parameters.nb_data - 1)), + 0).t(); + + // Build a reference trajectory for each frame + vector_list_t muQ; + matrix_list_t frames_Q; + + mat Q = zeros(model.nb_var * model.parameters.nb_data, + model.nb_var * model.parameters.nb_data); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + vec frame_muQ = zeros(model.nb_var * model.parameters.nb_data); + mat frame_Q = zeros(model.nb_var, model.nb_var * model.parameters.nb_data); + + for (int i = 0; i < model.parameters.nb_data; ++i) { + span id(i * model.nb_var, (i + 1) * model.nb_var - 1); + frame_muQ(id) = mu[q(i)][m]; + frame_Q(span::all, id) = inv_sigma[q(i)][m]; + } + + frame_Q = kron(ones(model.parameters.nb_data, 1), + eye(model.nb_var, model.nb_var)) * frame_Q % + kron(eye(model.parameters.nb_data, model.parameters.nb_data), + ones(model.nb_var, model.nb_var)); + + muQ.push_back(frame_muQ); + frames_Q.push_back(frame_Q); + + Q = Q + frame_Q; + } + + // Batch LQR (unconstrained linear MPC in multiple frames), corresponding to a + // product of Gaussian controllers + mat Rq = model.precomputed.Su.t() * Q * model.precomputed.Su + model.precomputed.R; + + vec X = zeros(model.nb_var); + X(span(0, 1)) = start_coordinates(span(0, 1)); + + mat rq = zeros(model.nb_var * model.parameters.nb_data); + for (int m = 0; m < model.parameters.nb_frames; ++m) { + rq = rq + frames_Q[m] * (muQ[m] - model.precomputed.Sx * X); + } + + rq = model.precomputed.Su.t() * rq; + + mat u = solve(Rq, rq); + + return reshape(model.precomputed.Sx * X + model.precomputed.Su * u, model.nb_var, + model.parameters.nb_data); +} + + +//----------------------------------------------------------------------------- +// Compute stochastic reproductions +//----------------------------------------------------------------------------- +void batch_lqr_stochastic_reproduction(const model_t& model, + const coordinate_system_list_t& coordinate_systems, + const vec& start_coordinates, + matrix_list_t &reproductions, + std::vector< std::vector< vector_list_t > > &stochastic_mu) { + + const int nb_eigs = 2; // Number of principal eigencomponents to keep + + reproductions.clear(); + stochastic_mu.clear(); + + + // Compute best path + uvec q = index_max(model.pix(span::all, span(0, model.parameters.nb_data - 1)), 0).t(); + + + for (int n = 0; n < model.parameters.nb_stoch_repros; ++n) { + std::vector< vector_list_t > mu; // Indexing: mu[state][frame] + std::vector< matrix_list_t > inv_sigma; // Indexing: inv_sigma[state][frame] + + // GMM projection by moving centers randomly + std::vector<vector_list_t> stoch_mu = model.mu; + + cube N(nb_eigs, model.parameters.nb_frames, model.parameters.nb_states, fill::randn); + // Noise on all components in all frames + + for (int i = 0; i < model.parameters.nb_states; ++i) { + mu.push_back(vector_list_t()); + inv_sigma.push_back(matrix_list_t()); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + stoch_mu[i][m](span(0, nb_eigs - 1)) = + model.mu[i][m](span(0, nb_eigs - 1)) + + model.precomputed.V[i][m](span::all, span(0, nb_eigs - 1)) * + pow(model.precomputed.D[i][m](span(0, nb_eigs - 1), span(0, nb_eigs - 1)), 0.5) * + vec(N(span::all, span(m), span(i))); + + mu[i].push_back(coordinate_systems[m].orientation * stoch_mu[i][m] + + coordinate_systems[m].position); + + inv_sigma[i].push_back(coordinate_systems[m].orientation * + model.precomputed.inv_sigma[i][m] * + coordinate_systems[m].orientation.t()); + } + } + + // Build a reference trajectory for each frame + vector_list_t muQ; + matrix_list_t frames_Q; + + mat Q = zeros(model.nb_var * model.parameters.nb_data, + model.nb_var * model.parameters.nb_data); + + for (int m = 0; m < model.parameters.nb_frames; ++m) { + vec frame_muQ = zeros(model.nb_var * model.parameters.nb_data); + mat frame_Q = zeros(model.nb_var, model.nb_var * model.parameters.nb_data); + + for (int i = 0; i < model.parameters.nb_data; ++i) { + span id(i * model.nb_var, (i + 1) * model.nb_var - 1); + frame_muQ(id) = mu[q(i)][m]; + frame_Q(span::all, id) = inv_sigma[q(i)][m]; + } + + frame_Q = kron(ones(model.parameters.nb_data, 1), + eye(model.nb_var, model.nb_var)) * frame_Q % + kron(eye(model.parameters.nb_data, model.parameters.nb_data), + ones(model.nb_var, model.nb_var)); + + muQ.push_back(frame_muQ); + frames_Q.push_back(frame_Q); + + Q = Q + frame_Q; + } + + // Batch LQR (unconstrained linear MPC in multiple frames), corresponding to a + // product of Gaussian controllers + mat Rq = model.precomputed.Su.t() * Q * model.precomputed.Su + model.precomputed.R; + + vec X = zeros(model.nb_var); + X(span(0, 1)) = start_coordinates(span(0, 1)); + + mat rq = zeros(model.nb_var * model.parameters.nb_data); + for (int m = 0; m < model.parameters.nb_frames; ++m) { + rq = rq + frames_Q[m] * (muQ[m] - model.precomputed.Sx * X); + } + + rq = model.precomputed.Su.t() * rq; + + mat u = solve(Rq, rq); + + mat reproduction = reshape(model.precomputed.Sx * X + model.precomputed.Su * u, + model.nb_var, model.parameters.nb_data); + + reproductions.push_back(reproduction(span(0, 1), span::all)); + + stochastic_mu.push_back(stoch_mu); + } +} + + +/*************************** DEMONSTRATION SECTION ***************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//----------------------------------------------------------------------------- +// Contains all the informations about a viewport +//----------------------------------------------------------------------------- +struct viewport_t { + int x; + int y; + int width; + int height; + + // Projection matrix parameters + arma::vec projection_top_left; + arma::vec projection_bottom_right; + double projection_near; + double projection_far; + + // View matrix parameters + arma::fvec view; +}; + + +//----------------------------------------------------------------------------- +// Helper function to setup a viewport +//----------------------------------------------------------------------------- +void setup_viewport(viewport_t* viewport, int x, int y, int width, int height, + double near = -1.0, double far = 1.0, + const fvec& view_transforms = zeros<fvec>(3)) { + + viewport->x = x; + viewport->y = y; + viewport->width = width; + viewport->height = height; + viewport->projection_top_left = vec({ (double) -width / 2, + (double) height / 2 }); + viewport->projection_bottom_right = vec({ (double) width / 2, + (double) -height / 2 }); + viewport->projection_near = near; + viewport->projection_far = far; + viewport->view = view_transforms; +} + + +//----------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space, taking the +// coordinates of a viewport into account +//----------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const gfx2::window_size_t& window_size, + const viewport_t& viewport) { + arma::vec result = coords; + + // ui -> viewport + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width - viewport.x; + result(1) = (window_size.win_height - coords(1)) * + (float) window_size.fb_height / (float) window_size.win_height - viewport.y; + + // viewport -> fb + result(0) = result(0) - (float) viewport.width * 0.5f; + result(1) = result(1) - (float) viewport.height * 0.5f; + + return result; +} + + +//----------------------------------------------------------------------------- +// Converts some coordinates from OpenGL-space to UI-space, taking the +// coordinates of a viewport into account +//----------------------------------------------------------------------------- +arma::vec fb2ui(const arma::vec& coords, const gfx2::window_size_t& window_size, + const viewport_t& viewport) { + arma::vec result = coords; + + // fb -> viewport + result(0) = result(0) + (float) viewport.width * 0.5f; + result(1) = result(1) + (float) viewport.height * 0.5f; + + // viewport -> ui + result(0) = (result(0) + viewport.x) * (float) window_size.win_width / + (float) window_size.fb_width; + + result(1) = window_size.win_height - (result(1) + viewport.y) * + (float) window_size.win_height / (float) window_size.fb_height; + + return result; +} + + +//----------------------------------------------------------------------------- +// Colors used by the movable handlers +//----------------------------------------------------------------------------- +const arma::fmat HANDLER_COLORS({ + { 0.0, 0.0, 0.0 }, + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, + { 0.0, 0.75, 0.75 }, +}); + + +//----------------------------------------------------------------------------- +// Colors used by the fixed handlers +//----------------------------------------------------------------------------- +const arma::fmat HANDLER_FIXED_COLORS({ + { 0.4, 0.4, 0.4 }, + { 0.4, 0.4, 1.0 }, + { 0.2, 0.5, 0.2 }, + { 1.0, 0.4, 0.4 }, + { 0.3, 0.75, 0.75 }, +}); + + +//----------------------------------------------------------------------------- +// Colors of the displayed lines and gaussians +//----------------------------------------------------------------------------- +const arma::mat COLORS({ + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, + { 0.0, 0.75, 0.75 }, + { 0.75, 0.0, 0.75 }, + { 0.75, 0.75, 0.0 }, + { 0.25, 0.25, 0.25 }, + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, +}); + + +//----------------------------------------------------------------------------- +// An user-movable UI widget representing a coordinate system +// +// Can be "fixed", so the user can't move it anymore +//----------------------------------------------------------------------------- +class Handler +{ +public: + Handler(const viewport_t* viewport, const ImVec2& position, const ImVec2& y, + int index) + : viewport(viewport), hovered(false), fixed(false), moved(false), index(index) + { + ui_position = position; + ui_y = y; + + fvec color = HANDLER_COLORS.row(index).t(); + + models[0] = gfx2::create_rectangle(color, 25.0f, 5.0f); + models[0].transforms.parent = &transforms; + models[0].transforms.rotation = gfx2::rotate(arma::fvec({0.0f, 0.0f, 1.0f}), + gfx2::deg2rad(90.0f)); + + models[1] = gfx2::create_rectangle(color, 60.0f, 5.0f); + models[1].transforms.parent = &transforms; + models[1].transforms.position(0) = 30.0f; + models[1].transforms.position(1) = -10.0f; + + models[2] = gfx2::create_rectangle(color, 60.0f, 5.0f); + models[2].transforms.parent = &transforms; + models[2].transforms.position(0) = 30.0f; + models[2].transforms.position(1) = 10.0f; + } + + + void update(const gfx2::window_size_t& window_size) + { + transforms.position.rows(0, 1) = arma::conv_to<arma::fvec>::from( + ui2fb(ui_position, window_size, *viewport) + ); + + arma::vec delta = ui_y / arma::norm(arma::vec(ui_y)); + + transforms.rotation(0, 0) = -delta(0); + transforms.rotation(1, 0) = delta(1); + transforms.rotation(0, 1) = -delta(1); + transforms.rotation(1, 1) = -delta(0); + } + + + void update() + { + transforms.position(0) = ui_position.x; + transforms.position(1) = ui_position.y; + + arma::vec delta = ui_y / arma::norm(arma::vec(ui_y)); + + transforms.rotation(0, 0) = -delta(0); + transforms.rotation(1, 0) = delta(1); + transforms.rotation(0, 1) = -delta(1); + transforms.rotation(1, 1) = -delta(0); + } + + + void viewport_resized(const gfx2::window_size_t& window_size) + { + ui_position = fb2ui(arma::conv_to<arma::vec>::from(transforms.position.rows(0, 1)), + window_size, *viewport); + } + + + void fix() + { + fixed = true; + + for (int i = 0; i < 3; ++i) + models[i].diffuse_color = HANDLER_FIXED_COLORS.row(index).t(); + } + + + bool draw(const gfx2::window_size_t& window_size) + { + if (!fixed) + { + std::stringstream id; + id << "handler" << (uint64_t) this; + + ImGuiWindow* window = ImGui::GetCurrentWindow(); + if (window->SkipItems) + return false; + + ImGui::PushID(id.str().c_str()); + + // Position + ImVec2 current_position = ui_position; + + ui_position = ui::dragger(0, ui_position, false, ui::config.draggerSize ); + + moved = moved || (ui_position.x != current_position.x) || (ui_position.y != current_position.y); + + hovered = ImGui::IsItemHovered(); + + // y-axis + ImVec2 py = ui_position + ui_y; + current_position = ui_y; + + py = ui::dragger(1, py, false, ui::config.draggerSize * 0.7); + ui_y = py - ui_position; + + moved = moved || ((ui_y.x != current_position.x) || (ui_y.y != current_position.y)); + + hovered = ImGui::IsItemHovered() || hovered; + + window->DrawList->AddLine(ui_position, py, ui::config.lineColor); + + ImGui::PopID(); + + update(window_size); + } + + return hovered; + } + + + void draw_anchor() const + { + for (int i = 0; i < 3; ++i) + gfx2::draw(models[i]); + } + + +public: + const viewport_t* viewport; + int index; + + ImVec2 ui_position; + ImVec2 ui_y; + + gfx2::transforms_t transforms; + gfx2::model_t models[3]; + + bool hovered; + bool fixed; + bool moved; +}; + + +//----------------------------------------------------------------------------- +// Represents a list of handlers +//----------------------------------------------------------------------------- +typedef std::vector<Handler*> handler_list_t; + + +//----------------------------------------------------------------------------- +// Contains all the needed infos about the state of the application (values of +// the parameters modifiable via the UI, which action the user is currently +// doing, ...) +//----------------------------------------------------------------------------- +struct gui_state_t { + // Indicates if the user can draw a new demonstration + bool can_draw_demonstration; + + // Indicates if the user is currently drawing a new demonstration + bool is_drawing_demonstration; + + // Indicates if the parameters dialog is displayed + bool is_parameters_dialog_displayed; + + // Indicates if the parameters were modified through the UI + bool are_parameters_modified; + + // Indicates if the reproductions must be recomputed + bool must_recompute_reproductions; + + // Parameters modifiable via the UI (they correspond to the ones declared + //in parameters_t) + int parameter_nb_states; + int parameter_nb_frames; + int parameter_nb_data; + int parameter_nb_stoch_repros; + + // The reference frame currently displayed for the models + int displayed_frame; +}; + + +//----------------------------------------------------------------------------- +// Create a handler at a random position (within the given boundaries) +//----------------------------------------------------------------------------- +Handler* create_random_handler(const viewport_t* viewport, int index, + int min_x, int min_y, int max_x, int max_y) { + return new Handler(viewport, + ImVec2((randu() * 0.8f + 0.1f) * (max_x - min_x) + min_x, + (randu() * 0.5f + 0.1f) * (max_y - min_y) + min_y), + ImVec2((randu() - 0.5) * 10, randu() * -10 - 10), + index); +} + + +//----------------------------------------------------------------------------- +// Create handlers to be used for a new demonstration at random positions +//----------------------------------------------------------------------------- +void create_new_demonstration_handlers(const viewport_t& viewport, + const gfx2::window_size_t& window_size, + int nb_frames, + handler_list_t &handlers) { + + for (size_t i = 0; i < handlers.size(); ++i) + delete handlers[i]; + + handlers.clear(); + + handlers.push_back( + new Handler(&viewport, ImVec2(window_size.win_width / 6, + window_size.win_height / 2 - 50), + ImVec2(0, 30), 0) + ); + + for (int n = 1; n < nb_frames; ++n) { + handlers.push_back( + create_random_handler(&viewport, n, 10, 20, + window_size.win_width / 3 - 10, + window_size.win_height / 2 - 20) + ); + }; +} + + +//----------------------------------------------------------------------------- +// Create handlers to be used for a new reproduction at random positions +//----------------------------------------------------------------------------- +void create_reproduction_handlers(const viewport_t& viewport, + const gfx2::window_size_t& window_size, + int nb_frames, + handler_list_t &handlers) { + + for (size_t i = 0; i < handlers.size(); ++i) + delete handlers[i]; + + handlers.clear(); + + handlers.push_back( + new Handler(&viewport, ImVec2(window_size.win_width / 2, + window_size.win_height - 50), + ImVec2(0, 30), 0) + ); + + for (int n = 1; n < nb_frames; ++n) { + handlers.push_back( + create_random_handler(&viewport, n, + window_size.win_width / 3 + 20, + window_size.win_height / 2 + 20, + window_size.win_width * 2 / 3 - 20, + window_size.win_height - 20) + ); + }; +} + + +//----------------------------------------------------------------------------- +// Extract a list of coordinate systems from a list of handlers +//----------------------------------------------------------------------------- +void convert(const handler_list_t& from, coordinate_system_list_t &to, + const parameters_t& parameters) { + + to.clear(); + + for (int n = 0; n < from.size(); ++n) { + to.push_back( + coordinate_system_t(arma::conv_to<arma::vec>::from(from[n]->transforms.position), + arma::conv_to<arma::mat>::from(from[n]->transforms.rotation), + parameters) + ); + } +} + + +//----------------------------------------------------------------------------- +// Extract a list of coordinate systems from a list of demonstrations +//----------------------------------------------------------------------------- +void convert(const demonstration_list_t& from, std::vector<coordinate_system_list_t> &to) { + + to.clear(); + + for (int n = 0; n < from.size(); ++n) { + to.push_back(from[n].coordinate_systems); + } +} + + +//----------------------------------------------------------------------------- +// Compute a view matrix centered on the given reference frame across all the +// demonstrations +//----------------------------------------------------------------------------- +arma::fvec compute_centered_view_matrix(const demonstration_list_t& demonstrations, + int frame) { + vec top_left({-30, 0}); + vec bottom_right({0, 0}); + + for (auto iter = demonstrations.begin(); iter != demonstrations.end(); ++iter) { + top_left(0) = fmin(top_left(0), iter->points_in_coordinate_systems[frame](0, span::all).min()); + top_left(1) = fmax(top_left(1), iter->points_in_coordinate_systems[frame](1, span::all).max()); + + bottom_right(0) = fmax(bottom_right(0), iter->points_in_coordinate_systems[frame](0, span::all).max()); + bottom_right(1) = fmin(bottom_right(1), iter->points_in_coordinate_systems[frame](1, span::all).min()); + } + + vec center = (bottom_right - top_left) / 2 + top_left; + + return fvec({ (float) -center(0), (float) -center(1), 0.0f }); +} + + +//----------------------------------------------------------------------------- +// Render the "demonstrations" viewport +//----------------------------------------------------------------------------- +void draw_demos_viewport(const viewport_t& viewport, + const std::vector<arma::vec>& current_trajectory, + const demonstration_list_t& demonstrations, + const std::vector<handler_list_t> fixed_demonstration_handlers, + const handler_list_t current_demonstration_handlers) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.7f, 0.7f, 0.7f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glTranslatef(viewport.view(0), viewport.view(1), viewport.view(2)); + + // Draw the currently created demonstration (if any) + if (current_trajectory.size() > 1) + gfx2::draw_line(arma::fvec({0.33f, 0.97f, 0.33f}), current_trajectory); + + // Draw the demonstrations + int color_index = 0; + for (auto iter = demonstrations.begin(); iter != demonstrations.end(); ++iter) { + arma::mat datapoints = iter->points(span(0, 1), span::all); + + arma::fvec color = arma::conv_to<arma::fvec>::from(COLORS.row(color_index)); + + gfx2::draw_line(color, datapoints); + + ++color_index; + if (color_index >= demonstrations.size()) + color_index = 0; + } + + // Draw the handlers + for (size_t n = 0; n < fixed_demonstration_handlers.size(); ++n) { + for (size_t i = 0; i < fixed_demonstration_handlers[n].size(); ++i) + fixed_demonstration_handlers[n][i]->draw_anchor(); + } + + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + current_demonstration_handlers[i]->draw_anchor(); +} + + +//----------------------------------------------------------------------------- +// Render a "model" viewport +//----------------------------------------------------------------------------- +void draw_model_viewport(const viewport_t& viewport, + const demonstration_list_t& demonstrations, + int perspective, + const model_t& model, + std::vector< std::vector< vector_list_t > >* stochastic_mu = 0) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.9f, 0.9f, 0.9f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glTranslatef(viewport.view(0), viewport.view(1), viewport.view(2)); + + // Draw the GMM states + if (!demonstrations.empty()) { + if (!stochastic_mu) { + for (int i = 0; i < model.parameters.nb_states; ++i) { + glClear(GL_DEPTH_BUFFER_BIT); + gfx2::draw_gaussian(conv_to<fvec>::from(COLORS.row(i).t()), + model.mu[i][perspective], + model.sigma[i][perspective]); + } + } else { + for (int n = 0; n < stochastic_mu->size(); ++n) { + for (int i = 0; i < model.parameters.nb_states; ++i) { + glClear(GL_DEPTH_BUFFER_BIT); + gfx2::draw_gaussian(conv_to<fvec>::from(COLORS.row(i).t()), + (*stochastic_mu)[n][i][perspective], + model.sigma[i][perspective]); + } + } + } + } + + glClear(GL_DEPTH_BUFFER_BIT); + + // Draw the demonstrations + int color_index = 0; + for (auto iter = demonstrations.begin(); iter != demonstrations.end(); ++iter) { + arma::mat datapoints = iter->points_in_coordinate_systems[perspective](span(0, 1), span::all); + + arma::fvec color = arma::conv_to<arma::fvec>::from(COLORS.row(color_index)); + + gfx2::draw_line(color, datapoints); + + ++color_index; + if (color_index >= demonstrations.size()) + color_index = 0; + } + + // Draw the handler + Handler handler(&viewport, ImVec2(0, 0), ImVec2(-30, 0), perspective); + handler.update(); + handler.draw_anchor(); + + for (auto iter = demonstrations.begin(); iter != demonstrations.end(); ++iter) { + for (int n = 0; n < model.parameters.nb_frames; ++n) { + if (n == perspective) + continue; + + fvec color = HANDLER_COLORS.row(n).t(); + + vec pos = iter->convert_to_coordinate_system(iter->coordinate_systems[n].position, + perspective); + + gfx2::draw_rectangle(color, 10, 10, fvec({ (float) pos(0), (float) pos(1), 0.0f })); + } + } + + + // Draw the axes + arma::mat x_axis({{(float) -viewport.width, (float) viewport.width, 0.0f}, + {0.0f, 0.0f, 0.0f}}); + + gfx2::draw_line(fvec({0.0f, 0.0f, 0.0f}), x_axis); + + arma::mat y_axis({{0.0f, 0.0f, 0.0f}, + {(float) -viewport.height, (float) viewport.height, 0.0f}}); + + gfx2::draw_line(fvec({0.0f, 0.0f, 0.0f}), y_axis); +} + + +//----------------------------------------------------------------------------- +// Render a "reproduction" viewport +//----------------------------------------------------------------------------- +void draw_reproductions_viewport(const viewport_t& viewport, + const std::vector<handler_list_t>& handlers, + const matrix_list_t& reproductions) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.9f, 0.9f, 0.9f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glTranslatef(viewport.view(0), viewport.view(1), viewport.view(2)); + + // Draw the reproductions (if any) + int color_index = 0; + for (auto iter = reproductions.begin(); iter != reproductions.end(); ++iter) { + arma::fvec color = arma::conv_to<arma::fvec>::from(COLORS.row(color_index)); + + gfx2::draw_line(color, *iter); + + ++color_index; + if (color_index >= reproductions.size()) + color_index = 0; + } + + // Draw the handlers + for (size_t n = 0; n < handlers.size(); ++n) { + for (size_t i = 0; i < handlers[n].size(); ++i) + handlers[n][i]->draw_anchor(); + } +} + + +//----------------------------------------------------------------------------- +// Render a "reproduction" viewport +//----------------------------------------------------------------------------- +void draw_reproductions_viewport(const viewport_t& viewport, + const handler_list_t& handlers, + const matrix_list_t& reproductions) { + + std::vector<handler_list_t> handler_list; + handler_list.push_back(handlers); + + draw_reproductions_viewport(viewport, handler_list, reproductions); +} + + +/******************************* MAIN FUNCTION *******************************/ + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + // Model + model_t model; + + // Parameters + model.parameters.nb_states = 6; + model.parameters.nb_frames = 2; + model.parameters.nb_deriv = 2; + model.parameters.nb_data = 200; + model.parameters.rfactor = 0.01; + model.parameters.dt = 0.1f; + model.parameters.nb_stoch_repros = 10; + + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + int viewport_width = 0; + int viewport_height = 0; + + + // Initialise GLFW + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo - Linear quadratic optimal control", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup GLSL + gfx2::init(); + glEnable(GL_SCISSOR_TEST); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + + // Viewports + viewport_t viewport_demos; + viewport_t viewport_repros; + viewport_t viewport_model; + viewport_t viewport_new_repros; + viewport_t viewport_stochastic_model; + viewport_t viewport_stochastic_repros; + + + // GUI state + gui_state_t gui_state; + gui_state.can_draw_demonstration = true; + gui_state.is_drawing_demonstration = false; + gui_state.is_parameters_dialog_displayed = false; + gui_state.are_parameters_modified = false; + gui_state.must_recompute_reproductions = false; + gui_state.parameter_nb_states = model.parameters.nb_states; + gui_state.parameter_nb_frames = model.parameters.nb_frames; + gui_state.parameter_nb_data = model.parameters.nb_data; + gui_state.parameter_nb_stoch_repros = model.parameters.nb_stoch_repros; + gui_state.displayed_frame = 2; + + + // Demonstration and reproduction handlers + std::vector<handler_list_t> fixed_demonstration_handlers; + handler_list_t current_demonstration_handlers; + handler_list_t reproduction_handlers; + + // List of demonstrations and reproductions + demonstration_list_t demos; + matrix_list_t reproductions; + matrix_list_t new_reproductions; + matrix_list_t stochastic_reproductions; + std::vector< std::vector< vector_list_t > > stochastic_mu; + + + // Main loop + vector_list_t current_trajectory; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + viewport_width = window_size.fb_width / 3 - 1; + viewport_height = window_size.fb_height / 2 - 1; + + // Update all the viewports + setup_viewport(&viewport_demos, 0, window_size.fb_height - viewport_height, + viewport_width, viewport_height); + + setup_viewport(&viewport_repros, 0, 0, + viewport_width, viewport_height); + + setup_viewport(&viewport_model, viewport_width + 2, + window_size.fb_height - viewport_height, + viewport_width, viewport_height, -1.0f, 1.0f, + compute_centered_view_matrix(demos, gui_state.displayed_frame - 1)); + + setup_viewport(&viewport_new_repros, viewport_width + 2, 0, + viewport_width, viewport_height); + + setup_viewport(&viewport_stochastic_model, window_size.fb_width - viewport_width, + window_size.fb_height - viewport_height, + viewport_width, viewport_height, -1.0f, 1.0f, + viewport_model.view); + + setup_viewport(&viewport_stochastic_repros, window_size.fb_width - viewport_width, 0, + viewport_width, viewport_height); + + // Update all the handlers + if (!first) { + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + current_demonstration_handlers[i]->viewport_resized(window_size); + + for (size_t i = 0; i < reproduction_handlers.size(); ++i) + reproduction_handlers[i]->viewport_resized(window_size); + } + + // At the very first frame: load initial data from files (can't be done + // outside the loop because we need to know the size of the OpenGL front + // buffer) + else if ((window_size.win_width != -1) && (window_size.fb_width != -1)) { + cube loaded_trajectories; + mat loaded_frames; + loaded_trajectories.load("data/data_tpbatch_lqr_trajectories.txt"); + loaded_frames.load("data/data_tpbatch_lqr_frames.txt"); + + for (int n = 0; n < loaded_frames.n_cols / 2; ++n) { + Handler* handler1 = new Handler( + &viewport_demos, + ImVec2(loaded_frames(0, n * 2) * window_size.win_width, + loaded_frames(1, n * 2) * window_size.win_height), + ImVec2(loaded_frames(2, n * 2) * window_size.win_width, + loaded_frames(3, n * 2) * window_size.win_height), + 0 + ); + handler1->update(window_size); + handler1->fix(); + + Handler* handler2 = new Handler( + &viewport_demos, + ImVec2(loaded_frames(0, n * 2 + 1) * window_size.win_width, + loaded_frames(1, n * 2 + 1) * window_size.win_height), + ImVec2(loaded_frames(2, n * 2 + 1) * window_size.win_width, + loaded_frames(3, n * 2 + 1) * window_size.win_height), + 1 + ); + handler2->update(window_size); + handler2->fix(); + + handler_list_t handlers; + handlers.push_back(handler1); + handlers.push_back(handler2); + + fixed_demonstration_handlers.push_back(handlers); + } + + Handler* handler_reproduction_1 = new Handler( + &viewport_new_repros, + fixed_demonstration_handlers[0][0]->ui_position + + ImVec2(window_size.win_width / 3, window_size.win_height / 2), + fixed_demonstration_handlers[0][0]->ui_y, + 0 + ); + handler_reproduction_1->update(window_size); + reproduction_handlers.push_back(handler_reproduction_1); + + Handler* handler_reproduction_2 = new Handler( + &viewport_new_repros, + fixed_demonstration_handlers[0][1]->ui_position + + ImVec2(window_size.win_width / 3, window_size.win_height / 2), + fixed_demonstration_handlers[0][1]->ui_y, + 1 + ); + handler_reproduction_2->update(window_size); + reproduction_handlers.push_back(handler_reproduction_2); + + for (int n = 0; n < loaded_trajectories.n_slices; ++n) { + vector_list_t trajectory; + for (int i = 0; i < loaded_trajectories.n_cols; ++i) { + mat t = loaded_trajectories(span::all, span(i), span(n)); + t(0, span::all) *= window_size.fb_width; + t(1, span::all) *= window_size.fb_height; + trajectory.push_back(t); + } + + coordinate_system_list_t coordinate_systems; + convert(fixed_demonstration_handlers[n], coordinate_systems, model.parameters); + + Demonstration demonstration(coordinate_systems, trajectory, model.parameters); + demos.push_back(demonstration); + } + + // Initial learning from the loaded data + learn(demos, model); + + std::vector<coordinate_system_list_t> coordinate_systems_list; + convert(demos, coordinate_systems_list); + + for (int n = 0; n < demos.size(); ++n) { + mat reproduction = batch_lqr_reproduction( + model, coordinate_systems_list[n], + demos[n].points_original(span::all, 0), n); + + reproductions.push_back(reproduction); + } + + gui_state.must_recompute_reproductions = true; + } + } + + + // If the parameters changed, recompute + if (gui_state.are_parameters_modified) { + + // If the number of frames changed, clear everything + if (model.parameters.nb_frames != gui_state.parameter_nb_frames) { + demos.clear(); + + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + delete current_demonstration_handlers[i]; + + for (size_t n = 0; n < fixed_demonstration_handlers.size(); ++n) { + for (size_t i = 0; i < fixed_demonstration_handlers[n].size(); ++i) + delete fixed_demonstration_handlers[n][i]; + } + + for (size_t i = 0; i < reproduction_handlers.size(); ++i) + delete reproduction_handlers[i]; + + current_demonstration_handlers.clear(); + fixed_demonstration_handlers.clear(); + reproduction_handlers.clear(); + + reproductions.clear(); + new_reproductions.clear(); + stochastic_reproductions.clear(); + + create_new_demonstration_handlers(viewport_demos, window_size, + gui_state.parameter_nb_frames, + current_demonstration_handlers + ); + + create_reproduction_handlers(viewport_new_repros, window_size, + gui_state.parameter_nb_frames, + reproduction_handlers); + + model.parameters.nb_frames = gui_state.parameter_nb_frames; + gui_state.displayed_frame = 2; + gui_state.can_draw_demonstration = true; + + viewport_model.view = compute_centered_view_matrix( + demos, gui_state.displayed_frame - 1 + ); + + viewport_stochastic_model.view = viewport_model.view; + } + + // If the number of states or datapoints changed, recompute the model + if ((model.parameters.nb_data != gui_state.parameter_nb_data) || + (model.parameters.nb_states != gui_state.parameter_nb_states)) { + + model.parameters.nb_data = gui_state.parameter_nb_data; + model.parameters.nb_states = gui_state.parameter_nb_states; + + for (auto iter = demos.begin(); iter != demos.end(); ++iter) + iter->update(model.parameters); + + if (!demos.empty()) { + learn(demos, model); + + std::vector<coordinate_system_list_t> coordinate_systems; + convert(demos, coordinate_systems); + + reproductions.clear(); + for (int n = 0; n < demos.size(); ++n) { + reproductions.push_back( + batch_lqr_reproduction(model, coordinate_systems[n], + demos[n].points_original(span::all, 0), + n) + ); + } + + gui_state.must_recompute_reproductions = true; + + viewport_model.view = compute_centered_view_matrix( + demos, gui_state.displayed_frame - 1 + ); + + viewport_stochastic_model.view = viewport_model.view; + } + } + + // If the number of stochastic reproductions changed, recompute them + if (model.parameters.nb_stoch_repros != gui_state.parameter_nb_stoch_repros) { + model.parameters.nb_stoch_repros = gui_state.parameter_nb_stoch_repros; + gui_state.must_recompute_reproductions = true; + } + + gui_state.are_parameters_modified = false; + } + + // Recompute the new reproductions (if necessary) + if (!demos.empty() && gui_state.must_recompute_reproductions) { + + coordinate_system_list_t coordinate_systems; + convert(reproduction_handlers, coordinate_systems, model.parameters); + + new_reproductions.clear(); + + new_reproductions.push_back( + batch_lqr_reproduction( + model, coordinate_systems, + conv_to<vec>::from(reproduction_handlers[0]->transforms.position) + ) + ); + + batch_lqr_stochastic_reproduction( + model, coordinate_systems, + conv_to<vec>::from(reproduction_handlers[0]->transforms.position), + stochastic_reproductions, + stochastic_mu + ); + + gui_state.must_recompute_reproductions = false; + + for (size_t i = 0; i < reproduction_handlers.size(); ++i) + reproduction_handlers[i]->moved = false; + + viewport_model.view = compute_centered_view_matrix( + demos, gui_state.displayed_frame - 1 + ); + + viewport_stochastic_model.view = viewport_model.view; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glScissor(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(0.0f, 0.0f, 0.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT); + + draw_demos_viewport(viewport_demos, current_trajectory, demos, + fixed_demonstration_handlers, + current_demonstration_handlers); + + draw_reproductions_viewport(viewport_repros, fixed_demonstration_handlers, + reproductions); + + draw_model_viewport(viewport_model, demos, gui_state.displayed_frame - 1, model); + + draw_reproductions_viewport(viewport_new_repros, reproduction_handlers, + new_reproductions); + + draw_model_viewport(viewport_stochastic_model, demos, gui_state.displayed_frame - 1, + model, &stochastic_mu); + + draw_reproductions_viewport(viewport_stochastic_repros, reproduction_handlers, + stochastic_reproductions); + + + // Draw the UI controls of the handlers + ui::begin("handlers"); + + bool hovering_ui = false; + + for (size_t i = 0; i < reproduction_handlers.size(); ++i) { + hovering_ui = reproduction_handlers[i]->draw(window_size) || hovering_ui; + + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)) { + gui_state.must_recompute_reproductions = gui_state.must_recompute_reproductions || + reproduction_handlers[i]->moved; + } + } + + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + hovering_ui = current_demonstration_handlers[i]->draw(window_size) || hovering_ui; + + ui::end(); + + + // Window: Demonstrations + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(0, 0)); + ImGui::Begin("Demonstrations", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Demonstrations "); + ImGui::SameLine(); + + if (!gui_state.can_draw_demonstration) { + if (ImGui::Button("Add")) { + create_new_demonstration_handlers(viewport_demos, window_size, + gui_state.parameter_nb_frames, + current_demonstration_handlers + ); + + gui_state.can_draw_demonstration = true; + } + } + + ImGui::SameLine(); + + if (ImGui::Button("Clear")) { + demos.clear(); + + for (size_t i = 0; i < current_demonstration_handlers.size(); ++i) + delete current_demonstration_handlers[i]; + + for (size_t n = 0; n < fixed_demonstration_handlers.size(); ++n) { + for (size_t i = 0; i < fixed_demonstration_handlers[n].size(); ++i) + delete fixed_demonstration_handlers[n][i]; + } + + current_demonstration_handlers.clear(); + fixed_demonstration_handlers.clear(); + + reproductions.clear(); + new_reproductions.clear(); + stochastic_reproductions.clear(); + + create_new_demonstration_handlers(viewport_demos, window_size, + model.parameters.nb_frames, + current_demonstration_handlers + ); + + gui_state.can_draw_demonstration = true; + } + + ImGui::SameLine(); + ImGui::Text(" "); + ImGui::SameLine(); + + if (ImGui::Button("Parameters")) + gui_state.is_parameters_dialog_displayed = true; + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Reproductions + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(0, window_size.win_height / 2)); + ImGui::Begin("Reproductions", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Reproductions"); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Model + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width / 3, 0)); + ImGui::Begin("Model", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Model"); + ImGui::SameLine(); + ImGui::Text("Frame:"); + ImGui::SameLine(); + + int previous_displayed_frame = gui_state.displayed_frame; + + ImGui::SliderInt("", &gui_state.displayed_frame, 1, model.parameters.nb_frames); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + if (previous_displayed_frame != gui_state.displayed_frame) { + viewport_model.view = compute_centered_view_matrix( + demos, gui_state.displayed_frame - 1 + ); + + viewport_stochastic_model.view = viewport_model.view; + } + + + // Window: New reproductions + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width / 3, window_size.win_height / 2)); + ImGui::Begin("New reproductions", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("New reproductions"); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Stochastic model + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - window_size.win_width / 3, 0)); + ImGui::Begin("Stochastic model", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Stochastic model"); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Stochastic reproductions + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - window_size.win_width / 3, window_size.win_height / 2)); + ImGui::Begin("Stochastic reproductions", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Stochastic reproductions"); + + hovering_ui = ImGui::IsWindowHovered() || hovering_ui; + + ImGui::End(); + + + // Window: Parameters + ImGui::SetNextWindowSize(ImVec2(600, 146)); + ImGui::SetNextWindowPos(ImVec2((window_size.win_width - 600) / 2, (window_size.win_height - 146) / 2)); + ImGui::PushStyleColor(ImGuiCol_WindowBg, ImVec4(0, 0, 0, 255)); + + if (gui_state.is_parameters_dialog_displayed) + ImGui::OpenPopup("Parameters"); + + if (ImGui::BeginPopupModal("Parameters", NULL, + ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings)) { + + ImGui::SliderInt("Nb states", &gui_state.parameter_nb_states, 1, 10); + ImGui::SliderInt("Nb frames", &gui_state.parameter_nb_frames, 2, 5); + ImGui::SliderInt("Nb data", &gui_state.parameter_nb_data, 100, 300); + ImGui::SliderInt("Nb stochastic reproductions", &gui_state.parameter_nb_stoch_repros, 2, 10); + + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + gui_state.is_parameters_dialog_displayed = false; + gui_state.are_parameters_modified = true; + } + + ImGui::EndPopup(); + + hovering_ui = true; + } + + ImGui::PopStyleColor(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + + // Left click: start a new demonstration (only if not on the UI and in the + // demonstrations viewport) + if (!gui_state.is_drawing_demonstration) { + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1) && gui_state.can_draw_demonstration) { + double mouse_x, mouse_y; + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + if (!hovering_ui && (mouse_x <= window_size.win_width / 3) && + (mouse_y <= window_size.win_height / 2)) + { + gui_state.is_drawing_demonstration = true; + + vec coords = ui2fb({ mouse_x, mouse_y }, window_size, viewport_demos); + current_trajectory.push_back(coords); + } + } + } else { + double mouse_x, mouse_y; + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + vec coords = ui2fb({ mouse_x, mouse_y }, window_size, viewport_demos); + + vec last_point = current_trajectory[current_trajectory.size() - 1]; + vec diff = abs(coords - last_point); + + if ((diff(0) > 1e-6) && (diff(1) > 1e-6)) + current_trajectory.push_back(coords); + + // Left mouse button release: end the demonstration creation + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)) { + gui_state.is_drawing_demonstration = false; + + if (current_trajectory.size() > 1) { + + coordinate_system_list_t coordinate_systems; + convert(current_demonstration_handlers, coordinate_systems, model.parameters); + + Demonstration demonstration(coordinate_systems, current_trajectory, + model.parameters); + + demos.push_back(demonstration); + + for (int i = 0; i < current_demonstration_handlers.size(); ++i) + current_demonstration_handlers[i]->fix(); + + fixed_demonstration_handlers.push_back(current_demonstration_handlers); + current_demonstration_handlers.clear(); + + learn(demos, model); + + std::vector<coordinate_system_list_t> coordinate_systems_list; + convert(demos, coordinate_systems_list); + + reproductions.clear(); + + for (int n = 0; n < demos.size(); ++n) { + mat reproduction = batch_lqr_reproduction( + model, coordinate_systems_list[n], + demos[n].points_original(span::all, 0), n); + + reproductions.push_back(reproduction); + } + + gui_state.must_recompute_reproductions = true; + gui_state.can_draw_demonstration = false; + } + + current_trajectory.clear(); + } + } + + ImGui::CaptureMouseFromApp(); + } + + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_dptpgmm.cpp b/src/demo_dptpgmm.cpp deleted file mode 100644 index de0710f..0000000 --- a/src/demo_dptpgmm.cpp +++ /dev/null @@ -1,566 +0,0 @@ -/* - * demo_dptpgmm.cpp - * - * Online tp-gmm learning and lqr-based trajectory generation. - * - * Authors: Sylvain Calinon, Emmanuel Pignat - */ - -#define N_TPS 3 -#define N_TPTRS 4 -#define N_REC_POINTS 200 - - -#include <stdio.h> - - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/tpdpgmm.h> - -#include <GLFW/glfw3.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include <pbdlib/taskparameters.h> - - -using namespace std; -using namespace pbdlib; -using namespace arma; - - - -class Ref -{ -public: - vec p1; - vec p2; - - mat A; - vec b; - - void updateRef() - { - - b = p1; - A = mat(2,2); - - vec delta = p2-p1; - delta = delta/arma::norm(delta); - A(0,0) = delta(0); - A(1,0) = delta(1); - A(0,1) = -delta(1); - A(1,1) = delta(0); - } - void updateRef_rel() - { - - b = p1; - A = mat(2,2); - - vec delta = (p2-p1)/500.0; - - A(0,0) = delta(0); - A(1,0) = delta(1); - A(0,1) = -delta(1); - A(1,1) = delta(0); - } -}; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -mat solveReconstruction(TPDPGMM& tpgmm,vec startPoint,int iFactor,int nSUB) -{ - mat A(4,4), B(4,2); - float dt = 0.01f*sqrt((double)nSUB); - - - mat R = eye(2,2) * pow(10.0f,iFactor); - - mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - LQR lqr(A,B,dt); - - std::vector<mat> Q; - - mat pred; - pred = tpgmm.predictForwardVariable(N_REC_POINTS,0); - - //cout << "Alpha Predictions" << endl << pred.t() << endl; - - uword imax[N_REC_POINTS/ nSUB]; - - for (int t=0; t<N_REC_POINTS/ nSUB; t++){ - vec vTmp = pred.col(t* nSUB); - vTmp.max(imax[t]); - //cout<<imax[t]<<"-"; - } - //cout<<endl<<endl; - - //LQR - vec vTmp(4,fill::zeros); - mat QTmp(4,4,fill::zeros); - mat Target(4,N_REC_POINTS/ nSUB,fill::zeros); - for (int t=0; t<N_REC_POINTS/ nSUB; t++){ - QTmp.submat(0,0,1,1) = inv(tpgmm.getProdGMM()->getSIGMA(imax[t])); - Q.push_back(QTmp); - vTmp.subvec(0,1) = tpgmm.getProdGMM()->getMU(imax[t]); - Target.col(t) = vTmp; - } - lqr.setProblem(R,Q,Target); - mat S(4,4,fill::zeros); - vec d(4,fill::zeros); - //lqr.evaluate_gains_finiteHorizon(S,d); - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - - mat rData(2,N_REC_POINTS/ nSUB); - //vec x = demo.getDatapoints().getData().col(0); - //vec dx(2,fill::zeros), ddx(2); - //for (int t=0; t<points.size(); t++){ - //rData.col(t) = x; - //ddx = 100.0f * (Target.submat(0,t,1,t)-x) - sqrtf(2*100.0f) * dx; - //ddx = lqr.getGains().at(t).cols(0,1) * (Target.submat(0,t,1,t)-x) - lqr.getGains().at(t).cols(2,3) * dx; - //ddx += lqr.getFF().at(t); - //dx += ddx * dt; - //x += dx * dt; - //} - - vec u(2); - vec X = join_cols(startPoint, zeros<vec>(2)); - for (int t=0; t<N_REC_POINTS/ nSUB; t++){ - rData.col(t) = X.rows(0,1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - - //Clean up - - Q.clear(); - return rData; -} - -int main(int argc, char **argv){ - - //reference drawings - - mat refShape = {{1, 1, -1, -1, -0.5, -0.5, 0.5, 0.5,1}, - {1.5, -0.5, -0.5, 1.5, 1.5, 0, 0, 1.5, 1.5}}; - refShape = 50*refShape; - //Setup TPDPGMM - - GMM_Model gmm(1,2); - float minSigma = 20.0f; - float lambda = 70.0f; - TPDPGMM tpgmm(2,1,N_TPS,N_TPTRS,lambda); - - TaskParameters tp(2,N_TPS); - - - - mat minSIGMA = eye(2,2) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros; - - //Setup LQR - int iFactor = -6; - - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 820, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(154, 154, 154); - - ImVector<ImVec2> points; - bool adding_line = false; - bool modelExist = false; - bool dispRef = true; - bool dispDemo = false; - bool dispGMM = true; - bool useFramePRIORS = true; - bool movingRef = false; - bool hoveringRef = false; - int nbPts = 0; - bool init = true; - bool startFlag = false; - bool endFlag = false; - float alphaHandles = 0.2f; - Ref refFrame[3]; - refFrame[0].p1 = zeros(2); - refFrame[0].p2 = zeros(2); - refFrame[1].p1 = vec(2); - refFrame[1].p2 = vec(2); - refFrame[2].p1 = vec(2); - refFrame[2].p2 = vec(2); - - //plotting color - float color[5][3] = {{0.f,0.6211f,0.8164f}, - {0.9883f,0.4531f,0.f}, - {0.7422f,0.8555f,0.2227f}, - {0.1211f,0.5391f,0.4375f}, - {0.9961f,0.8789f,0.1016f}}; - - while (!glfwWindowShouldClose(window)){ - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - hoveringRef = false; - //Control panel GUI - if(init)ImGui::SetNextWindowPos(ImVec2(500,200)); - - ImGui::Begin("r1p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - vec tmpPos = refFrame[0].p1; - refFrame[0].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[0].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(500,300)); - ImGui::Begin("r1p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[0].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(1000,200)); - ImGui::Begin("r2p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - tmpPos = refFrame[1].p1; - refFrame[1].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[1].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(1000,100)); - ImGui::Begin("r2p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[1].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - refFrame[0].updateRef(); - refFrame[1].updateRef(); - refFrame[2].p1 = refFrame[0].p1; - refFrame[2].p2 = refFrame[1].p1; - refFrame[2].updateRef_rel(); - - - //cout<< refFrame[0].A<<endl; - init = false; - - ImGui::SetNextWindowPos(ImVec2(2,2)); - - //ImGui::Begin("Control Panel"); - - ImGui::Begin("Control Panel", NULL, ImVec2(350,250), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - - - - //cout<<ImGui::IsItemHovered()<<endl; - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - gmm.clear(); - tpgmm = TPDPGMM(2,1,N_TPS,N_TPTRS,lambda); - modelExist = false; - //cout<<gmm.getNumSTATES()<<endl; - } - //ImGui::SameLine(); - //if (ImGui::Button("Train")) { - // cout << "\n Number of EM iterations: " << gmm.EM_learn(); - // dispGMM = true; - //} - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), (int)points.size(), (int)gmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 100.0f); - ImGui::Checkbox("Display Demo",&dispDemo); - ImGui::Checkbox("Plot Gaussian",&dispGMM); - ImGui::Checkbox("Use Frame Priors",&useFramePRIORS); - ImGui::SliderInt("rFactor", &iFactor, -9, -5); - - tpgmm.useFramePRIORS(useFramePRIORS); - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - //ImGui::GetCursorScreenPos() - - //ImGuiWindow* hw = FindHoveredWindow(ImGui::GetIO().MousePos, false); - - if(hoveringRef&&ImGui::GetIO().MouseClicked[0]) - movingRef = true; - if(movingRef&&!ImGui::GetIO().MouseDown[0]) - movingRef = false; - - if(movingRef&&modelExist&& !ImGui::GetIO().MouseClicked[0]) - { - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { - tpTmp.A = refFrame[i].A; - tpTmp.b = refFrame[i].b; - tp.setTaskParameters(i,tpTmp); - } - tpgmm.getTransformedGMM(tp,INVERTIBLE); - - colvec trParam = ones(N_TPTRS); - trParam.rows(0,1) = refFrame[1].b-refFrame[0].b; - mat test = (refFrame[1].A*refFrame[0].A); - trParam.rows(2,3) = lambda*test.col(0); - cout << trParam<<endl; - tpgmm.updateTransition(trParam); - - repros.clear(); - // variable resolution for fast preview when moving references - int nSub; - if (!ImGui::GetIO().MouseDown[0]) nSub= 1; - else nSub = 4; - - mat rData = solveReconstruction(tpgmm,tpgmm.getProdGMM()->getMU(0),iFactor,nSub); - repros.push_back(rData); - } - - - if ((ImGui::GetIO().MousePos.x<352 && ImGui::GetIO().MousePos.y<252)==0&&!movingRef){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; - startFlag = true; - endFlag = false; - if (!modelExist){ - colvec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - cout<<p<<endl; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - gmm.setCOMPONENTS(comps); - comps.clear(); - } - } - if (!ImGui::GetIO().MouseDown[0]) endFlag = true; - - if (adding_line){ //Trajectory recording - usleep(1e4); - points.push_back(mouse_pos_in_canvas); - nbPts++; - vec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - mat p_frame(2,N_TPS+1); - - TaskParameter tpTmp; - - - for(int i=0;i<N_TPS;i++) - { - p_frame.col(i) = refFrame[i].A.t()/det(refFrame[i].A)*(p-refFrame[i].b); - tpTmp.A = refFrame[i].A; - tpTmp.b = refFrame[i].b; - tp.setTaskParameters(i,tpTmp); - } - // also add the position in absolute space - p_frame.col(N_TPS) = p; - - colvec trParam = ones(N_TPTRS); - trParam.rows(0,1) = refFrame[1].b-refFrame[0].b; - mat test = (refFrame[1].A*refFrame[0].A); - trParam.rows(2,3) = lambda*test.col(0); - - tpgmm.addDatapoints(p_frame,trParam,startFlag,endFlag,lambda,minSigma); - tpgmm.getTransformedGMM(tp,INVERTIBLE); - - startFlag = false; - modelExist = true; - //gmm.onlineEMDP(nbPts, p, lambda, minSigma); - - if (!ImGui::GetIO().MouseDown[0]) - { //Button released - adding_line = false; - - bool merged = true; - while (merged) - { - merged = tpgmm.reduceStates(); - tpgmm.getTransformedGMM(tp, INVERTIBLE); - tpgmm.updateTransition(trParam); - } - //Add demonstration - Demonstration demo = Demonstration(2,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; - } - demos.push_back(demo); - - - //Reconstruction - repros.clear(); - - mat rData = solveReconstruction(tpgmm,demo.getDatapoints().getData().col(0),iFactor,1); - repros.push_back(rData); - - points.clear(); - - } - - } - } - ImGui::End(); - - - //GUI rendering - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - glColor3f(0.0f, 0.0f, 0.0f); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); - - //Draw demos - glColor3f(0.3f, 0.3f, 0.3f); - if(dispDemo) - { - for (int n=0; n<(int)demos.size(); n++){ - glBegin(GL_LINE_STRIP); - - for (int t=0; t<(int)demos[n].getDatapoints().getNumPOINTS(); t++){ - glVertex2f(demos[n].getDatapoints().getData()(0,t), demos[n].getDatapoints().getData()(1,t)); - } - glEnd(); - } - } - - - //Draw references - if(dispRef) - { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpgmm.getNumFRAMES()-1; k++) { - - glColor3f(color[0][0], color[0][1], color[0][2]); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians - if (modelExist&&dispGMM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glLineWidth(2.0f); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++) { - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - eig_sym(d, V, tpgmm.getGMMS(k).getSIGMA(i)); - R = refFrame[k].A*(V * sqrt(diagmat(d))); - pts = R * pts0; - - glColor3f(color[k+1][0], color[k+1][1], color[k+1][2]); - glBegin(GL_LINE_STRIP); - - vec refMU = refFrame[k].b + refFrame[k].A*tpgmm.getGMMS(k).getMU(i); - - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f((pts(0, t) + refMU(0)), (pts(1, t) +refMU(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f(tpgmm.getGMMS(k).getMU(i)(0), tpgmm.getGMMS(k).getMU(i)(1)); - } - glEnd(); - } - } - } - if (modelExist){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(0.8f, 0.0f, 0.0f); - glColor3f(color[4][0], color[4][1], color[4][2]); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++){ - eig_sym(d, V, tpgmm.getProdGMM()->getSIGMA(i)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+tpgmm.getProdGMM()->getMU(i)(0)), - (pts(1,t)+tpgmm.getProdGMM()->getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(tpgmm.getProdGMM()->getMU(i)(0), - tpgmm.getProdGMM()->getMU(i)(1)); - } - glEnd(); - } - } - glLineWidth(5.0f); - //Draw repros - glColor3f(color[3][0], color[3][1], color[3][2]); - for (int n=0; n<(int)repros.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)repros[n].n_cols; t++){ - glVertex2f(repros[n](0,t), repros[n](1,t)); - } - glEnd(); - } - glLineWidth(2.0f); - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; -} - diff --git a/src/demo_glsl.cpp b/src/demo_glsl.cpp deleted file mode 100644 index 8a68455..0000000 --- a/src/demo_glsl.cpp +++ /dev/null @@ -1,172 +0,0 @@ -//Sylvain Calinon, 2017 - -#include <stdio.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <epoxy/gl.h> -#include <GLFW/glfw3.h> -#include "armadillo" -#include <pbdlib/gmm.h> - -static char const *vert_shader_str = - "#version 120\n" - "void main(){\n" - "\tgl_TexCoord[0] = gl_MultiTexCoord0;\n" - "\tgl_Position = gl_ProjectionMatrix * gl_ModelViewMatrix * gl_Vertex;\n" - "}\n"; - -static char const *frag_shader_str = - "#version 120\n" - "uniform vec2 Mu;\n" - "uniform mat2 Gamma;\n" - "void main(){\n" - "\tvec2 e = gl_FragCoord.xy - Mu;\n" - //"\tfloat p = exp(-0.5f * dot(e,Gamma*e));\n" - "\tfloat p = clamp(exp(-0.5f * dot(e,Gamma*e)), 0, 0.5f);\n" - "\tgl_FragColor = vec4(p, p, p, p);\n" - "}\n"; - -GLint prog, vert_shader, frag_shader, Mu_loc, Gamma_loc; - -void shader_status(int shader_id){ - int status; - glGetShaderiv(shader_id, GL_COMPILE_STATUS, &status); - if (!status){ - int infologLength, charsWritten; - GLchar *infoLog; - glGetShaderiv(shader_id, GL_INFO_LOG_LENGTH, &infologLength); - infoLog = (GLchar *)malloc(sizeof(GLchar) * infologLength); - glGetShaderInfoLog(shader_id, infologLength, &charsWritten, infoLog); - std::cout << infoLog << std::endl; - free(infoLog); - } -} - -int check_gl_extension(char const *name){ - const char *glExtensions = (const char *)glGetString(GL_EXTENSIONS); - return (strstr(glExtensions, name) != NULL); -} - -void glsl_init(void){ - if(!check_gl_extension("GL_ARB_fragment_shader")) - fprintf(stderr, "Warning: GL_ARB_fragment_shader extension not present\n"); - else if(!check_gl_extension("GL_ARB_vertex_shader")) - fprintf(stderr, "Warning: GL_ARB_vertex_shader extension not present\n"); - else{ - vert_shader = glCreateShader(GL_VERTEX_SHADER); - frag_shader = glCreateShader(GL_FRAGMENT_SHADER); - glShaderSource(vert_shader, 1, &vert_shader_str, NULL); - glShaderSource(frag_shader, 1, &frag_shader_str, NULL); - glCompileShader(vert_shader); - glCompileShader(frag_shader); - prog = glCreateProgram(); - glAttachShader(prog, vert_shader); - glAttachShader(prog, frag_shader); - glLinkProgram(prog); - glValidateProgram(prog); - shader_status(vert_shader); - shader_status(frag_shader); - glUseProgram(prog); - Mu_loc = glGetUniformLocation(prog, "Mu"); - Gamma_loc = glGetUniformLocation(prog, "Gamma"); - } - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); -} - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int main(int argc, char **argv){ - arma_rng::set_seed_random(); - - //Gaussian - arma::vec Utar = {500.0, 500.0}; - arma::mat RG(2,2,fill::eye); - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(600, 600, "Demo GLSL", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup GLSL - glsl_init(); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(0, 0, 40); - - //Setup ui - //ui::init(20.); - ui::Trans2d trans(ImVec2(200,0), ImVec2(0,100), ImVec2(Utar(0),Utar(1))); - - while (!glfwWindowShouldClose(window)) { - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - glPushMatrix(); - glTranslatef(-1.0f, -1.0f, 0); - glScalef(2.0f / (float) ImGui::GetIO().DisplaySize.x, 2.0f / (float) ImGui::GetIO().DisplaySize.y, 1.0f); - - //GUI rendering - ui::begin("Gaussian"); - trans = ui::affineSimple(0, trans); - Utar = {trans.pos.x, ImGui::GetIO().DisplaySize.y - trans.pos.y, 0, 0}; - RG = {{trans.x.x, trans.y.x}, {-trans.x.y, -trans.y.y}}; - ui::end(); - ImGui::Render(); - - - //Gaussian rendering with GLSL - glUseProgram(prog); - - glUniform2f(Mu_loc, Utar(0), Utar(1)); - - fmat S = conv_to<fmat>::from(inv(RG * RG.t())); - glUniformMatrix2fv(Gamma_loc, 1, GL_FALSE, (GLfloat*)S.memptr()); - - glBegin(GL_QUADS); - glTexCoord2f(0.0, 1.0); glVertex2f(0, 0); - glTexCoord2f(0.0, 0.0); glVertex2f(ImGui::GetIO().DisplaySize.x, 0); - glTexCoord2f(1.0, 0.0); glVertex2f(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - glTexCoord2f(1.0, 1.0); glVertex2f(0, ImGui::GetIO().DisplaySize.y); - glEnd(); - - glUseProgram(0); - - - //Gaussian rendering with standard GL - arma::mat pts0(2,35), pts(2,35); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - pts = RG * pts0; - glColor3f(0.79f, 0.33f, 0.33f); - glBegin(GL_LINE_STRIP); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(Utar(0)+pts(0,t), Utar(1)+pts(1,t)); - } - glEnd(); - glPointSize(2.); - glBegin(GL_POINTS); - glVertex2f(Utar(0), Utar(1)); - glEnd(); - - - glPopMatrix(); - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_glsl_gfx.cpp b/src/demo_glsl_gfx.cpp deleted file mode 100644 index 746bc43..0000000 --- a/src/demo_glsl_gfx.cpp +++ /dev/null @@ -1,165 +0,0 @@ -//Sylvain Calinon, 2017 - -#include <stdio.h> -#include <imgui.h> -#include "gfx.h" -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" -#include <GLFW/glfw3.h> - -#include "armadillo" -#include <pbdlib/gmm.h> - - -static char const *vert_shader_str = STRINGIFY( - void main(){ - gl_TexCoord[0] = gl_MultiTexCoord0; - gl_Position = gl_ProjectionMatrix * gl_ModelViewMatrix * gl_Vertex; - } -); - -static char const *frag_shader_str = STRINGIFY( - uniform vec2 Mu; - uniform mat2 Gamma; - void main(){ - vec2 e = gl_FragCoord.xy - Mu; - //float p = exp(-0.5f * dot(e,Gamma*e)); - float p = clamp(exp(-0.5f * dot(e,Gamma*e)), 0, 0.5f); - gl_FragColor = vec4(p, p, p, p); - } -); - -/* -static char const *vert_shader_str = - "#version 130\n" - "void main(){\n" - "\tgl_TexCoord[0] = gl_MultiTexCoord0;\n" - "\tgl_Position = gl_ProjectionMatrix * gl_ModelViewMatrix * gl_Vertex;\n" - "}\n"; - -static char const *frag_shader_str = - "#version 130\n" - "uniform vec2 Mu;\n" - "uniform mat2 Gamma;\n" - "void main(){\n" - "\tvec2 e = gl_FragCoord.xy - Mu;\n" - //"\tfloat p = exp(-0.5f * dot(e,Gamma*e));\n" - "\tfloat p = clamp(exp(-0.5f * dot(e,Gamma*e)), 0, 0.5f);\n" - "\tgl_FragColor = vec4(p, p, p, p);\n" - "}\n"; - */ -GLint prog, vert_shader, frag_shader, Mu_loc, Gamma_loc; - -void shader_status(int shader_id){ - int status; - glGetShaderiv(shader_id, GL_COMPILE_STATUS, &status); - if (!status){ - int infologLength, charsWritten; - GLchar *infoLog; - glGetShaderiv(shader_id, GL_INFO_LOG_LENGTH, &infologLength); - infoLog = (GLchar *)malloc(sizeof(GLchar) * infologLength); - glGetShaderInfoLog(shader_id, infologLength, &charsWritten, infoLog); - std::cout << infoLog << std::endl; - free(infoLog); - } -} - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int main(int argc, char **argv){ - arma_rng::set_seed_random(); - - //Gaussian - arma::vec Utar = {500.0, 500.0}; - arma::mat RG(2,2,fill::eye); - arma::vec Utar_shad = {500.0, 500.0}; - arma::mat RG_shad(2,2,fill::eye); - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(600, 600, "Demo GLSL", NULL, NULL); - glfwMakeContextCurrent(window); - - //Setup GLSL - gfx::init(); - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - int shader = gfx::loadShader(vert_shader_str, frag_shader_str); - - //Setup ImGui - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(0, 0, 40); - - //Setup ui - //ui::init(20.); - ui::Trans2d trans(ImVec2(200,0), ImVec2(0,100), ImVec2(Utar(0),Utar(1))); - - while (!glfwWindowShouldClose(window)) { - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - - gfx::setOrtho(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - - //GUI rendering - ui::begin("Gaussian"); - trans = ui::affineSimple(0, trans); - Utar = {trans.pos.x, trans.pos.y, 0, 0}; - RG = {{trans.x.x, trans.y.x}, {trans.x.y, trans.y.y}}; - // Need to find a better solution to this, since frag y coords have zero at bottom... - Utar_shad = {trans.pos.x, ImGui::GetIO().DisplaySize.y - trans.pos.y, 0, 0}; - RG_shad = {{trans.x.x, trans.y.x}, {-trans.x.y, -trans.y.y}}; - ui::end(); - ImGui::Render(); - - //Gaussian rendering with GLSL - gfx::bindShader(shader); - gfx::setVector("Mu", arma::vec({Utar_shad[0], Utar_shad[1]})); - gfx::setMatrix("Gamma", inv(RG_shad * RG_shad.t())); - - gfx::drawUVQuad(0, 0, ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - // glBegin(GL_QUADS); - // glTexCoord2f(0.0, 1.0); glVertex2f(0, 0); - // glTexCoord2f(0.0, 0.0); glVertex2f(ImGui::GetIO().DisplaySize.x, 0); - // glTexCoord2f(1.0, 0.0); glVertex2f(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y); - // glTexCoord2f(1.0, 1.0); glVertex2f(0, ImGui::GetIO().DisplaySize.y); - // glEnd(); - - gfx::unbindShader(); - - - //Gaussian rendering with standard GL - arma::mat pts0(2,35), pts(2,35); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,35)), sin(linspace<rowvec>(0,2*PI,35))); - pts = RG * pts0; - glColor3f(0.79f, 0.33f, 0.33f); - glBegin(GL_LINE_STRIP); - for (uint t=0; t<pts.n_cols; t++){ - glVertex2f(Utar(0)+pts(0,t), Utar(1)+pts(1,t)); - } - glEnd(); - glPointSize(2.); - glBegin(GL_POINTS); - glVertex2f(Utar(0), Utar(1)); - glEnd(); - - - glPopMatrix(); - glfwSwapBuffers(window); - - //Keyboard input - if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) - break; - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_LQR_infHor.cpp b/src/demo_infHorLQR01_glsl.cpp similarity index 59% rename from src/demo_LQR_infHor.cpp rename to src/demo_infHorLQR01_glsl.cpp index ac523ba..7a4774a 100644 --- a/src/demo_LQR_infHor.cpp +++ b/src/demo_infHorLQR01_glsl.cpp @@ -1,5 +1,5 @@ /* - * demo_LQR_infHor.cpp + * demo_infHorLQR01_glsl.cpp * * Discrete infinite horizon linear quadratic regulation * @@ -12,11 +12,11 @@ #include <gfx3.h> #include <gfx_ui.h> #include <GLFW/glfw3.h> - +#include <lqr.h> +#include <window_utils.h> #include <armadillo> -#include <pbdlib/gmm.h> -#include <pbdlib/lqr.h> +using namespace arma; /****************************** HELPER FUNCTIONS *****************************/ @@ -38,10 +38,10 @@ int factorial(int n) { // OpenGL coordinates range from (-fb_width / 2, fb_height / 2) to // (fb_width / 2, -fb_height / 2) //----------------------------------------------------------------------------- -arma::mat trans2RG(const ui::Trans2d& trans, int win_width, int win_height, - int fb_width, int fb_height) { - float scale_x = (float) fb_width / (float) win_width; - float scale_y = (float) fb_height / (float) win_height; +arma::mat trans2RG(const ui::Trans2d& trans, const gfx3::window_size_t& window_size) { + + float scale_x = (float) window_size.fb_width / (float) window_size.win_width; + float scale_y = (float) window_size.fb_height / (float) window_size.win_height; arma::mat RG = { { trans.x.x * scale_x, trans.y.x * scale_x }, @@ -59,12 +59,12 @@ int main(int argc, char **argv){ //--------------- Setup parameters --------------- - int nbData = 100; //Number of datapoints - int nbRepros = 10; //Number of reproductions - int nbVarPos = 2; //Dimension of position data (here: x1,x2) - int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) - int nbVar = nbVarPos * nbDeriv; //Dimension of state vector in the tangent space - double dt = 1E-2; //Time step duration + int nbData = 100; //Number of datapoints + int nbRepros = 10; //Number of reproductions + int nbVarPos = 2; //Dimension of position data (here: x1,x2) + int nbDeriv = 2; //Number of static & dynamic features (D=2 for [x,dx]) + int nbVar = nbVarPos * nbDeriv; //Dimension of state vector in the tangent space + double dt = 1E-2; //Time step duration double rfactor = 1E-8; //Control cost in LQR // Control cost @@ -76,7 +76,7 @@ int main(int argc, char **argv){ // Initial positions arma:mat U0(nbVarPos, 0); arma::mat pts0(2, 35), pts(3, 35, fill::zeros); - pts0 = join_cols(cos(linspace<rowvec>(0, 2 * PI, 35)), sin(linspace<rowvec>(0, 2 * PI, 35))); + pts0 = join_cols(cos(linspace<rowvec>(0, 2 * datum::pi, 35)), sin(linspace<rowvec>(0, 2 * datum::pi, 35))); arma::mat RG(2, 2, fill::eye); @@ -94,12 +94,16 @@ int main(int argc, char **argv){ A = kron(A1d, eye(nbVarPos, nbVarPos)); B = kron(B1d, eye(nbVarPos, nbVarPos)); - // Initialize discrete LQR with infinite horizon - pbdlib::LQR lqr(A, B, dt); - //--------------- Setup of the rendering --------------- + // Take 4k screens into account (framebuffer size != window size) + gfx3::window_size_t window_size; + window_size.win_width = 800; + window_size.win_height = 800; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + // Setup GUI glfwSetErrorCallback(error_callback); if (!glfwInit()) @@ -111,15 +115,11 @@ int main(int argc, char **argv){ glfwWindowHint(GLFW_OPENGL_FORWARD_COMPAT, GL_TRUE); glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE); - GLFWwindow* window = glfwCreateWindow(600, 600, "Demo LQR", NULL, NULL); - glfwMakeContextCurrent(window); - - // Take 4k screens into account (framebuffer size != window size) - int win_width = ImGui::GetIO().DisplaySize.x; - int win_height = ImGui::GetIO().DisplaySize.y; + GLFWwindow* window = create_window_at_optimal_size( + "Demo LQR", window_size.win_width, window_size.win_height + ); - int fb_width, fb_height; - glfwGetFramebufferSize(window, &fb_width, &fb_height); + glfwMakeContextCurrent(window); // Setup GLSL gfx3::init(); @@ -134,6 +134,7 @@ int main(int argc, char **argv){ glBindVertexArray(vertexArrayID); // Setup ImGui + ImGui::CreateContext(); ImGui_ImplGlfwGL3_Init(window, true); ImVec4 clear_color = ImColor(0, 0, 40); @@ -146,29 +147,21 @@ int main(int argc, char **argv){ // Projection matrix - arma::fmat projection = gfx3::orthographic( - (float) fb_width, (float) fb_height, 0.1f, 10.0f); + arma::fmat projection; // Camera matrix arma::fmat view = gfx3::lookAt( - arma::fvec({0, 0, 3}), // Position of the camera - arma::fvec({0, 0, 0}), // Look at the origin - arma::fvec({0, 1, 0}) // Head is up + arma::fvec({0, 0, 3}), // Position of the camera + arma::fvec({0, 0, 0}), // Look at the origin + arma::fvec({0, 1, 0}) // Head is up ); - gfx3::light_list_t lights; // Not used, but required by gfx3 - // Loading of the shaders gfx3::shader_t rtt_shader = gfx3::loadShader(gfx3::RTT_VERTEX_SHADER, gfx3::RTT_FRAGMENT_SHADER_LIC); - rtt_shader.setUniform("Time", 0.0f); - rtt_shader.setUniform("Sigma", arma::fmat(nbVarPos, nbVarPos)); rtt_shader.setUniform("Resolution", arma::fvec({512, 512})); - rtt_shader.setUniform("Target", arma::vec(gfx3::ui2shader({trans.pos.x, trans.pos.y}, - win_width, win_height, - fb_width, fb_height))); gfx3::shader_t background_shader = gfx3::loadShader(gfx3::VERTEX_SHADER_TEXTURED, gfx3::FRAGMENT_SHADER_ONE_TEXTURE); @@ -180,11 +173,8 @@ int main(int argc, char **argv){ gfx3::render_to_texture_t background_rtt = gfx3::createRTT(rtt_shader, 512, 512, arma::fvec({ 0.5f, 0.5f, 0.5f })); - // Creation of the background model - gfx3::model_t background = gfx3::create_rectangle(background_shader, - arma::fvec({ 0.5f, 0.0f, 0.0f }), - (float) fb_width, (float) fb_height); - background.diffuse_texture = background_rtt.texture(); + // Background model + gfx3::model_t background; //--------------- Main loop --------------- @@ -193,39 +183,49 @@ int main(int argc, char **argv){ glfwPollEvents(); // Detect when the window was resized - if ((ImGui::GetIO().DisplaySize.x != win_width) || (ImGui::GetIO().DisplaySize.y != win_height)) { - int previous_win_width = win_width; - int previous_win_height = win_height; - int previous_fb_width = fb_width; - int previous_fb_height = fb_height; + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + bool first = (window_size.win_width == -1) || (window_size.fb_width == -1); + + int previous_win_width = window_size.win_width; + int previous_win_height = window_size.win_height; + int previous_fb_width = window_size.fb_width; + int previous_fb_height = window_size.fb_height; // Retrieve the new window size - win_width = ImGui::GetIO().DisplaySize.x; - win_height = ImGui::GetIO().DisplaySize.y; + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; // Retrieve the new framebuffer size - glfwGetFramebufferSize(window, &fb_width, &fb_height); + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); // Update the projection matrix - projection = gfx3::orthographic((float) fb_width, (float) fb_height, 0.1f, 10.0f); + projection = gfx3::orthographic( + (float) window_size.fb_width, (float) window_size.fb_height, 0.1f, 10.0f); // Recreate the background model gfx3::destroy(background); - background = gfx3::create_rectangle(background_shader, arma::fvec({ 0.5f, 0.0f, 0.0f }), - (float) fb_width, (float) fb_height); + background = gfx3::create_rectangle(background_shader, + arma::fvec({ 0.5f, 0.0f, 0.0f }), + (float) window_size.fb_width, + (float) window_size.fb_height); + background.diffuse_texture = background_rtt.texture(); // Move and rescale the various objects so they stay in the window - if (previous_win_width > 0) { - float scale = std::min((float) fb_width / previous_fb_width, (float) fb_height / previous_fb_height); + if (!first) { + float scale = std::min((float) window_size.fb_width / previous_fb_width, + (float) window_size.fb_height / previous_fb_height); U0 *= scale; - + arma::vec target = gfx3::fb2ui(gfx3::ui2fb({trans.pos.x, trans.pos.y}, previous_win_width, previous_win_height, - previous_fb_width, previous_fb_height) * scale, - win_width, win_height, fb_width, fb_height); + previous_fb_width, previous_fb_height) * scale, + window_size.win_width, window_size.win_height, + window_size.fb_width, window_size.fb_height); trans.pos.x = target(0); trans.pos.y = target(1); @@ -237,44 +237,36 @@ int main(int argc, char **argv){ } // Detect if the number of reproductions has changed - if (nbRepros > U0.n_cols) { + if (nbRepros > U0.n_cols) { unsigned int nb = U0.n_cols; U0.reshape(nbVarPos, nbRepros); - for (int i = nb; i < nbRepros; ++i) { - U0.col(i) = arma::vec({(randu() - 0.5) * fb_width, (randu() - 0.5) * fb_height}); + for (int i = nb; i < nbRepros; ++i) { + U0.col(i) = arma::vec({ (randu() - 0.5) * window_size.fb_width, + (randu() - 0.5) * window_size.fb_height }); } - } - else if (nbRepros < U0.n_cols) { + } + else if (nbRepros < U0.n_cols) { U0.reshape(nbVarPos, nbRepros); - } + } // Start of rendering ImGui_ImplGlfwGL3_NewFrame(); - glViewport(0, 0, fb_width, fb_height); + glViewport(0, 0, window_size.fb_width, window_size.fb_height); glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - glMatrixMode(GL_PROJECTION); - glLoadIdentity(); - glOrtho(0, fb_width, fb_height, 0, -1., 1.); - glMatrixMode(GL_MODELVIEW); - glLoadIdentity(); - - glPushMatrix(); - // Gaussian UI widget ui::begin("Gaussian"); trans = ui::affineSimple(0, trans); - Utar = gfx3::ui2fb({trans.pos.x, trans.pos.y, 0, 0}, win_width, win_height, - fb_width, fb_height); - RG = trans2RG(trans, win_width, win_height, fb_width, fb_height); + Utar = gfx3::ui2fb({ trans.pos.x, trans.pos.y, 0, 0 }, window_size); + RG = trans2RG(trans, window_size); ui::end(); // Recompute LQR arma::mat Q = inv(RG * RG.t()); Q.resize(nbVar, nbVar); - arma::mat P = lqr.solveAlgebraicRiccati_Discrete(A, B, Q, R); + arma::mat P = lqr::solve_algebraic_Riccati_discrete(A, B, Q, R); arma::mat L = inv(B.t() * P * B + R) * B.t() * P * A; arma::vec U(nbVar, fill::zeros); arma::vec ddu(nbVarPos); @@ -298,9 +290,8 @@ int main(int argc, char **argv){ // RTT rendering rtt_shader.setUniform("Time", (float) glfwGetTime()); rtt_shader.setUniform("Sigma", conv_to<fmat>::from(inv(RG * RG.t()))); - rtt_shader.setUniform("Target", arma::vec(gfx3::ui2shader({trans.pos.x, trans.pos.y}, - win_width, win_height, - fb_width, fb_height))); + rtt_shader.setUniform("Target", arma::vec(gfx3::ui2shader({ trans.pos.x, trans.pos.y }, + window_size))); gfx3::draw(background_rtt); @@ -308,41 +299,33 @@ int main(int argc, char **argv){ // Draw repros for (size_t i = 0; i < reproductions.size(); ++i) { - gfx3::model_t line = gfx3::create_line( - colored_shader, arma::fvec({0.33f, 0.97f, 0.33f}), reproductions[i]); - - gfx3::draw(line, view, projection, lights); - - gfx3::destroy(line); + gfx3::draw_line(colored_shader, arma::fvec({0.33f, 0.97f, 0.33f}), + reproductions[i], view, projection); } // Draw the gaussian pts.rows(0, 1) = arma::mat(RG * pts0).each_col() + Utar.subvec(0, 1); - gfx3::model_t line = gfx3::create_line( - colored_shader, arma::fvec({1.0f, 0.33f, 0.33f}), pts); - - gfx3::draw(line, view, projection, lights); - - gfx3::destroy(line); + gfx3::draw_line(colored_shader, arma::fvec({1.0f, 0.33f, 0.33f}), pts, view, + projection); // Draw the background - gfx3::draw(background, view, projection, lights); + gfx3::draw(background, view, projection); - // Parameter window - ImGui::SetNextWindowSize(ImVec2(400, 50)); - ImGui::Begin("Parameters", NULL, - ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | - ImGuiWindowFlags_NoMove - ); - ImGui::SliderInt("Nb reproductions", &nbRepros, 1, 10); - ImGui::End(); + // Parameter window + ImGui::SetNextWindowSize(ImVec2(400, 56)); + ImGui::Begin("Parameters", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove + ); + ImGui::SliderInt("Nb reproductions", &nbRepros, 1, 10); + ImGui::End(); // UI rendering ImGui::Render(); + ImGui_ImplGlfwGL3_RenderDrawData(ImGui::GetDrawData()); // End of rendering - glPopMatrix(); glfwSwapBuffers(window); // Keyboard input diff --git a/src/demo_online_gmm.cpp b/src/demo_online_gmm.cpp deleted file mode 100644 index 0776922..0000000 --- a/src/demo_online_gmm.cpp +++ /dev/null @@ -1,275 +0,0 @@ -/* - * demo_online_gmm.cpp - * - * Online gmm learning and lqr-based trajectory generation. - * - * Author: Sylvain Calinon - */ - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <stdio.h> -#include <GLFW/glfw3.h> - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> - -using namespace std; -using namespace pbdlib; -using namespace arma; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -int main(int argc, char **argv){ - - //Setup GMM - GMM_Model gmm(1,2); - float minSigma = 2E2; - float lambda = 50.0f; - mat minSIGMA = eye(2,2) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros; - - //Setup LQR - mat A(4,4), B(4,2); - float dt = 0.01f; - - int iFactor = -8; - mat R = eye(2,2) * pow(10.0f,iFactor); - std::vector<mat> Q; - mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - LQR lqr(A,B,dt); - - - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 520, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(114, 144, 154); - - ImVector<ImVec2> points; - bool adding_line = false; - bool dispGMM = false; - int nbPts = 0; - - while (!glfwWindowShouldClose(window)){ - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - //Control panel GUI - ImGui::SetNextWindowPos(ImVec2(2,2)); - //ImGui::SetNextWindowSize(ImVec2(250,200)); - //ImGui::Begin("Control Panel"); - - ImGui::Begin("Control Panel", NULL, ImVec2(350,160), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - - //cout<<ImGui::IsItemHovered()<<endl; - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - gmm.clear(); - dispGMM = false; - //cout<<gmm.getNumSTATES()<<endl; - } - //ImGui::SameLine(); - //if (ImGui::Button("Train")) { - // cout << "\n Number of EM iterations: " << gmm.EM_learn(); - // dispGMM = true; - //} - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("nbDemos: %d, nbPoints: %d, nbStates: %d", (int)demos.size(), (int)points.size(), (int)gmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 100.0f); - if (ImGui::SliderInt("rFactor", &iFactor, -9, -6)){ - R = eye(2,2) * pow(10.0f,iFactor); - } - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - //ImGui::GetCursorScreenPos() - - //ImGuiWindow* hw = FindHoveredWindow(ImGui::GetIO().MousePos, false); - - if ((ImGui::GetIO().MousePos.x<352 && ImGui::GetIO().MousePos.y<162)==0){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; - if (!dispGMM){ - colvec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - gmm.setCOMPONENTS(comps); - comps.clear(); - dispGMM = true; - } - } - if (adding_line){ //Trajectory recording - points.push_back(mouse_pos_in_canvas); - nbPts++; - vec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - gmm.onlineEMDP(nbPts, p, lambda, minSigma); - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - //Add demonstration - Demonstration demo = Demonstration(2,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; - } - demos.push_back(demo); - //gmm.addDemo(demo); - - //Compute sequence of states - mat h(gmm.getNumSTATES(), points.size()); - for (int i=0; i<(int)gmm.getNumSTATES(); i++){ - h.row(i) = trans(gmm.getCOMPONENTS(i).getPDFValue(demo.getDatapoints().getData())); - } - uword imax[points.size()]; - for (int t=0; t<points.size(); t++){ - vec vTmp = h.col(t); - vTmp.max(imax[t]); - //cout<<imax[t]<<"-"; - } - //cout<<endl<<endl; - - //LQR - vec vTmp(4,fill::zeros); - mat QTmp(4,4,fill::zeros); - mat Target(4,points.size(),fill::zeros); - for (int t=0; t<points.size(); t++){ - QTmp.submat(0,0,1,1) = inv(gmm.getSIGMA(imax[t])); - Q.push_back(QTmp); - vTmp.subvec(0,1) = gmm.getMU(imax[t]); - Target.col(t) = vTmp; - } - lqr.setProblem(R,Q,Target); - mat S(4,4,fill::zeros); - vec d(4,fill::zeros); - //lqr.evaluate_gains_finiteHorizon(S,d); - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - mat rData(2,points.size()); - //vec x = demo.getDatapoints().getData().col(0); - //vec dx(2,fill::zeros), ddx(2); - //for (int t=0; t<points.size(); t++){ - //rData.col(t) = x; - //ddx = 100.0f * (Target.submat(0,t,1,t)-x) - sqrtf(2*100.0f) * dx; - //ddx = lqr.getGains().at(t).cols(0,1) * (Target.submat(0,t,1,t)-x) - lqr.getGains().at(t).cols(2,3) * dx; - //ddx += lqr.getFF().at(t); - //dx += ddx * dt; - //x += dx * dt; - //} - vec u(2); - vec X = join_cols(demo.getDatapoints().getData().col(0), zeros<vec>(2)); - for (int t=0; t<points.size(); t++){ - rData.col(t) = X.rows(0,1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - repros.push_back(rData); - - //Clean up - points.clear(); - Q.clear(); - } - } - } - ImGui::End(); - - - //GUI rendering - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - glColor3f(0.0f, 0.0f, 0.0f); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); - - //Draw demos - glColor3f(0.3f, 0.3f, 0.3f); - for (int n=0; n<(int)demos.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)demos[n].getDatapoints().getNumPOINTS(); t++){ - glVertex2f(demos[n].getDatapoints().getData()(0,t), demos[n].getDatapoints().getData()(1,t)); - } - glEnd(); - } - - //Draw repros - glColor3f(0.0f, 0.8f, 0.0f); - for (int n=0; n<(int)repros.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)repros[n].n_cols; t++){ - glVertex2f(repros[n](0,t), repros[n](1,t)); - } - glEnd(); - } - - //Draw Gaussians - if (dispGMM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(0.8f, 0.0f, 0.0f); - for (int i=0; i<(int)gmm.getNumSTATES(); i++){ - eig_sym(d, V, gmm.getSIGMA(i)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+gmm.getMU(i)(0)), (pts(1,t)+gmm.getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(gmm.getMU(i)(0), gmm.getMU(i)(1)); - } - glEnd(); - } - } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} diff --git a/src/demo_online_gmm01.cpp b/src/demo_online_gmm01.cpp new file mode 100644 index 0000000..10e7c81 --- /dev/null +++ b/src/demo_online_gmm01.cpp @@ -0,0 +1,452 @@ +/* + * demo_online_gmm01.cpp + * + * Online gmm learning. + * + * Author: Sylvain Calinon + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +// #include <lqr.h> +#include <mvn.h> + +using namespace arma; + + +//----------------------------------------------------------------------------- +// Contains the parameters of a gaussian +//----------------------------------------------------------------------------- +struct gaussian_t { + + gaussian_t() {} + + gaussian_t(const vec& mu, const mat& sigma) + : mu(mu), sigma(sigma) {} + + vec mu; + mat sigma; +}; + + +//--------------------------------------------------------- + + +typedef std::vector<mat> matrix_list_t; +typedef std::vector<gaussian_t> gaussian_list_t; + + +//--------------------------------------------------------- + + +class GMM_Model +{ +public: + // Constructor + GMM_Model(uint _nSTATES, uint _nVARS) { + nVARS = _nVARS; + nSTATES = _nSTATES; + PRIORS = rowvec(_nSTATES); + + // Initialize Components + COMPONENTS.resize(nSTATES); + } + + + inline uint getNumSTATES() const { + return nSTATES; + } + + inline gaussian_t& getCOMPONENTS(int id) { + return COMPONENTS[id]; + } + + inline const colvec& getMU(int id) const { + return COMPONENTS[id].mu; + } + + inline const mat& getSIGMA(int id) const { + return COMPONENTS[id].sigma; + } + + inline void setCOMPONENTS(gaussian_list_t& components) { + COMPONENTS = components; + } + + + //---------------------------------------------------------------------------- + // Performs online GMM clustering by using an updated DP-Means algorithms + // Ref: + // Kulis, B. and Jordan, M. I. (2012). Revisiting k-means: New algorithms + // via bayesian nonparametrics. In Proc. Intl Conf. on Machine Learning + // (ICML) + // + // Input: + // N: Number of points processed + // P: current point being added to GMM + // lambda: splitting distance + // nimSigma: minimum covariance for regularization + //---------------------------------------------------------------------------- + void online_EMDP(int N, const colvec& P, double lambda, double minSigma) { + // Initialized distance of P from first cluster + double d = arma::norm(this->getMU(0)-P,2); + + int minIndex = 0; //Index corresponding to current cluster + + // Find cluster corresponding to minimum distance + for(int k=1;k<nSTATES;k++){ + double Dist = arma::norm(this->getMU(k) - P,2); + if (Dist < d){ + d = Dist; + minIndex = k; // Index corresponding to minimum distance + } + } + + // Allocate new cluster if distance of each component higher than lambda + if (lambda < d){ + minIndex = nSTATES; + mat SigmaTmp = minSigma*eye(nVARS,nVARS); // Sigma of new component is the minimum cov + + COMPONENTS.push_back(gaussian_t(P, SigmaTmp)); // Mean of new component is P + + rowvec priorsTmp = zeros(1, nSTATES + 1); + priorsTmp.cols(0, nSTATES - 1) = PRIORS; + priorsTmp(nSTATES) = 1. / N; //prior for new component inversely proportional to #P + priorsTmp = priorsTmp / arma::norm(priorsTmp, 1); //evaluate new priors + nSTATES = nSTATES +1; //update number of states + PRIORS = priorsTmp; + } + else{ + /* + *Update components belonging to P by using MAP estimate + Ref: + Gauvain, J.-L. and Lee, C.-H. (1994). Maximum a pos- teriori estimation for + multivariate gaussian mixture observations of markov chians. IEE Transactions + on Speech and Audio Processing, 2(2). */ + double PriorsTmp = 1. / N + PRIORS[minIndex]; + + vec MuTmp = 1. / PriorsTmp * (PRIORS[minIndex] * getMU(minIndex) + P / N); + + COMPONENTS[minIndex].sigma = PRIORS[minIndex] / PriorsTmp * + (getSIGMA(minIndex) + (getMU(minIndex) - MuTmp) * (getMU(minIndex) - MuTmp).t()) + + 1. / (N * PriorsTmp) * (minSigma * eye(nVARS, nVARS) + (P - MuTmp) * (P - MuTmp).t()); + + COMPONENTS[minIndex].mu = MuTmp; + + rowvec priors = PRIORS; + priors[minIndex] = PriorsTmp; + priors = priors / arma::norm(priors, 1); + PRIORS = priors; + } + } + + + void clear() { + nSTATES = 1; + PRIORS = ones<vec>(1); + + COMPONENTS.clear(); + COMPONENTS.resize(nSTATES); + } + + +private: + uint nVARS; + uint nSTATES; + gaussian_list_t COMPONENTS; + rowvec PRIORS; +}; + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + + +//--------------------------------------------------------- + + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//--------------------------------------------------------- + + +int main(int argc, char **argv){ + + //Setup GMM + GMM_Model gmm(1,2); + float minSigma = 2E2; + float lambda = 250.0f; + mat minSIGMA = eye(2,2) * minSigma; + gaussian_list_t comps; + matrix_list_t demos; + // matrix_list_t repros; + + //Setup LQR + // mat A(4,4), B(4,2); + // float dt = 0.01f; + // int iFactor = -8; + // mat R = eye(2,2) * pow(10.0f,iFactor); + // std::vector<mat> Q; + // mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; + // mat B1d; B1d << 0 << endr << 1 << endr; + // A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf + // B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 600; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Online GMM", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup ImGui binding + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + ImVector<ImVec2> points; + bool adding_line = false; + bool dispGMM = false; + int nbPts = 0; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + //Control panel GUI + ImGui::SetNextWindowPos(ImVec2(2,2)); + // ImGui::SetNextWindowSize(ImVec2(350,140)); + ImGui::SetNextWindowSize(ImVec2(300,116)); + + ImGui::Begin("Control Panel", NULL, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + + if (ImGui::Button("Clear")){ + demos.clear(); + // repros.clear(); + gmm.clear(); + dispGMM = false; + } + + ImGui::Text("Left-click to collect demonstrations"); + ImGui::Text("nbDemos: %d, nbPoints: %d, nbStates: %d", (int)demos.size(), (int)points.size(), (int)gmm.getNumSTATES()); + ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E3); + ImGui::SliderFloat("lambda", &lambda, 10.0f, 500.0f); + // if (ImGui::SliderInt("rFactor", &iFactor, -9, -6)){ + // R = eye(2,2) * pow(10.0f,iFactor); + // } + + ImGui::End(); + + + //Get data + ImVec2 mouse_pos_in_canvas( + ImGui::GetIO().MousePos.x * + (float) window_size.fb_width / (float) window_size.win_width, + (window_size.win_height - ImGui::GetIO().MousePos.y) * + (float) window_size.fb_height / (float) window_size.win_height + ); + + if (!ImGui::GetIO().WantCaptureMouse) { //Is outside gui? + if (!adding_line && ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { //Button pushed + adding_line = true; + if (!dispGMM){ + colvec p(2); + p(0) = mouse_pos_in_canvas.x; + p(1) = mouse_pos_in_canvas.y; + comps.push_back(gaussian_t(p, minSIGMA)); + gmm.setCOMPONENTS(comps); + comps.clear(); + dispGMM = true; + } + } + + if (adding_line){ //Trajectory recording + points.push_back(mouse_pos_in_canvas); + nbPts++; + vec p(2); + p(0) = mouse_pos_in_canvas.x; + p(1) = mouse_pos_in_canvas.y; + gmm.online_EMDP(nbPts, p, lambda, minSigma); + + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)) { //Button released + adding_line = false; + //Add demonstration + mat demo(2, points.size()); + for (int t = 0; t < (int) points.size(); t++) { + demo(0, t) = points[t].x; + demo(1, t) = points[t].y; + } + demos.push_back(demo); + + //Compute sequence of states + mat h(gmm.getNumSTATES(), points.size()); + for (int i = 0; i < (int) gmm.getNumSTATES(); i++) { + h.row(i) = trans(mvn::getPDFValue(gmm.getCOMPONENTS(i).mu, gmm.getCOMPONENTS(i).sigma, demo)); + } + uword imax[points.size()]; + for (int t=0; t<points.size(); t++){ + vec vTmp = h.col(t); + vTmp.max(imax[t]); + } + + // //LQR + // vec vTmp(4,fill::zeros); + // mat QTmp(4,4,fill::zeros); + // mat Target(4,points.size(),fill::zeros); + // for (int t=0; t<points.size(); t++){ + // QTmp.submat(0,0,1,1) = inv(gmm.getSIGMA(imax[t])); + // Q.push_back(QTmp); + // vTmp.subvec(0,1) = gmm.getMU(imax[t]); + // Target.col(t) = vTmp; + // } + // + // matrix_list_t gains = lqr::evaluate_gains_infinite_horizon(A, B, R, Q, Target); + // + // //Retrieve data + // mat rData(2,points.size()); + // vec u(2); + // vec X = join_cols(demo.col(0), zeros<vec>(2)); + // for (int t=0; t<points.size(); t++){ + // rData.col(t) = X.rows(0,1); + // u = gains[t] * (Target.col(t) - X); + // X += (A * X + B * u) * dt; + // } + // repros.push_back(rData); + + //Clean up + points.clear(); + // Q.clear(); + } + } + } + + //GUI rendering + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + //Rendering + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, window_size.fb_width, 0, window_size.fb_height, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + glPushMatrix(); + + //Draw current demo + glColor3f(0.0f, 0.0f, 0.0f); + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)points.size(); t++){ + glVertex2f(points[t].x, points[t].y); + } + glEnd(); + + //Draw demos + glColor3f(0.3f, 0.3f, 0.3f); + for (int n=0; n<(int)demos.size(); n++){ + glBegin(GL_LINE_STRIP); + for (int t = 0; t < (int) demos[n].n_cols; t++){ + glVertex2f(demos[n](0, t), demos[n](1, t)); + } + glEnd(); + } + + //Draw repros + // glColor3f(0.0f, 0.8f, 0.0f); + // for (int n=0; n<(int)repros.size(); n++){ + // glBegin(GL_LINE_STRIP); + // for (int t = 0; t < (int) repros[n].n_cols; t++){ + // glVertex2f(repros[n](0, t), repros[n](1, t)); + // } + // glEnd(); + // } + + //Draw Gaussians + if (dispGMM){ + vec d(2); + mat V(2,2), R(2,2), pts(2,30); + mat pts0(2,30); + pts0 = join_cols(cos(linspace<rowvec>(0, 2 * datum::pi, 30)), + sin(linspace<rowvec>(0, 2 * datum::pi, 30))); + + glColor3f(0.8f, 0.0f, 0.0f); + for (int i=0; i<(int)gmm.getNumSTATES(); i++){ + eig_sym(d, V, gmm.getSIGMA(i)); + R = V * sqrt(diagmat(d)); + pts = R * pts0; + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)pts.n_cols; t++){ + glVertex2f((pts(0,t)+gmm.getMU(i)(0)), (pts(1,t)+gmm.getMU(i)(1))); + } + glEnd(); + glBegin(GL_POINTS); + for (int t=0; t<(int)pts.n_cols; t++){ + glVertex2f(gmm.getMU(i)(0), gmm.getMU(i)(1)); + } + glEnd(); + } + } + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_online_hsmm.cpp b/src/demo_online_hsmm.cpp deleted file mode 100644 index 223dd75..0000000 --- a/src/demo_online_hsmm.cpp +++ /dev/null @@ -1,386 +0,0 @@ -/* - * demo_online_hsmm.cpp - * - * Online hsmm learning and sampling with lqr-based trajectory generation. - * - * Authors: Sylvain Calinon, Ioannis Havoutis - */ - -#define prt(x) std::cout << #x " = '" << x << "'" << std::endl; - -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <stdio.h> -#include <GLFW/glfw3.h> - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include "pbdlib/hsmm.h" - -using namespace std; -using namespace pbdlib; -using namespace arma; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -mat run_lqr(mat A, mat B, float dt, - mat R, - int traj_length, colvec start_state, uword state_seq[], - GMM_Model model); - -void get_state_seq(uword state_seq[], mat pred); - -int main(int argc, char **argv){ - - //int nVars = 4; - int nVars = 2; //position only - HSMM hsmm(1,nVars); - float minSigma = 2E2; - float lambda = 50.0f; - mat minSIGMA = eye(nVars,nVars) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros; - vector<mat> repros_hsmm; - vector<mat> repros_sampling; - - //Setup hsmm - int init_nStates = 1; // we need to initialize the states to something - - //Setup LQR - mat A(4,4), B(4,2); - float dt = 0.01f; - - float iFactor = -8; - mat R = eye(2,2) * pow(10.0f,iFactor); - mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 520, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(255, 255, 255); - - ImVector<ImVec2> points; - ImVector<ImVec2> pointsVel; - bool adding_line = false; - bool dispGMM = false; - int nbPts = 0; - - ImVec2 mouse_pos_in_canvas; - - running_stat<float> xi; - float counter = 2; - while (!glfwWindowShouldClose(window)){ - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - - //Control panel GUI - ImGui::SetNextWindowPos(ImVec2(2,2)); - //ImGui::SetNextWindowSize(ImVec2(250,200)); - - ImGui::Begin("Control Panel", NULL, ImVec2(350,300), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - repros_sampling.clear(); - repros_hsmm.clear(); - hsmm.clear(); - dispGMM = false; - } - - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), (int)points.size(), (int)hsmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E3); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 500.0f); - if (ImGui::SliderFloat("rFactor", &iFactor, -9.0f, -1.0f, "%.1f" )){ - R = eye(2,2) * pow(10.0f,iFactor); - } - - static bool hsmm_stochastic_sampling = true; - ImGui::Checkbox("Stochastic sampling", &hsmm_stochastic_sampling); - - static bool hsmm_sampling = false; - static int hsmm_sampling_start_state = 0; - static int hsmm_sampling_traj_length = 10; - ImGui::Checkbox("Run hsmm sampling", &hsmm_sampling); - - if (hsmm_sampling) { - ImGui::SliderInt("Start state", &hsmm_sampling_start_state, 0, hsmm.getNumSTATES() - 1); - ImGui::SliderInt("Trajectory length", &hsmm_sampling_traj_length, 2, 1000); - if (ImGui::Button("Sample") && (hsmm.getNumSTATES()!=1)) { - mat pred(hsmm.getNumSTATES(), hsmm_sampling_traj_length, fill::zeros); - if (!hsmm_stochastic_sampling) { - hsmm.predictForwardVariableDeterministic(pred, hsmm_sampling_start_state); - }else{ - hsmm.predictForwardVariableStochastic(pred); - } - uword state_seq[pred.n_cols]; - get_state_seq(state_seq, pred); - mat hsmm_rData = run_lqr(A, B, dt, - R, hsmm_sampling_traj_length, hsmm.getMU(state_seq[0]), state_seq, - hsmm); - repros_sampling.push_back(hsmm_rData); - } - ImGui::SameLine(); - if (ImGui::Button("Clear Samples")) { - repros_sampling.clear(); - } - } - - //Get data - ImVec2 mouse_pos_in_canvas_curr = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - - double alpha = 0.2; - mouse_pos_in_canvas.x = mouse_pos_in_canvas.x + - alpha*(mouse_pos_in_canvas_curr.x - mouse_pos_in_canvas.x); - mouse_pos_in_canvas.y = mouse_pos_in_canvas.y + - alpha*(mouse_pos_in_canvas_curr.y - mouse_pos_in_canvas.y); - - if ((ImGui::GetIO().MousePos.x<352 && ImGui::GetIO().MousePos.y<300)==0){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; - if (!dispGMM){ - colvec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; -// p(2) = 0.0; -// p(3) = 0.0; -// colvec pd(2); -// pd(0) = 0.0; // initial velocity is always set to 0 -// pd(1) = 0.0; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - hsmm.setCOMPONENTS(comps); - comps.clear(); - dispGMM = true; - } - } - if (adding_line){ //Trajectory recording - points.push_back(mouse_pos_in_canvas); -// if (points.size()>2){ -// ImVec2 currVel ( ((float)points.back().x - (float)points[points.size()-2].x ) / (float) dt, -// ((float)points.back().y - (float)points[points.size()-2].y ) / (float) dt ); -// pointsVel.push_back(currVel); -// }else{ -// ImVec2 zero(0.0,0.0); // always start with zeros -// pointsVel.push_back(zero); -// } - - nbPts++; - vec p(2); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; -// p(2) = pointsVel.back().x; -// p(3) = pointsVel.back().y; - - hsmm.onlineEMDP(nbPts, p, lambda, minSigma); - - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - //Add demonstration - Demonstration demo = Demonstration(nVars,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; -// demo.getDatapoints().getData()(2,t) = pointsVel[t].x; -// demo.getDatapoints().getData()(3,t) = pointsVel[t].y; - } - demos.push_back(demo); - - //Compute sequence of states - mat h(hsmm.getNumSTATES(), points.size()); - for (int i=0; i<(int)hsmm.getNumSTATES(); i++){ - h.row(i) = trans(hsmm.getCOMPONENTS(i).getPDFValue(demo.getDatapoints().getData())); - } - uword imax[points.size()]; - get_state_seq(imax, h); - - //LQR - mat rData = run_lqr(A, B, dt, - R, /*Q,*/ points.size(), demo.getDatapoints().getData().col(0), imax, - hsmm); - repros.push_back(rData); - - //.HSMM testing part - hsmm.integrateDemonstration(demo); - mat pred(hsmm.getNumSTATES(), points.size(), fill::zeros); - - hsmm.predictForwardVariableDeterministic(pred, imax[0]); - - uword state_seq[pred.n_cols]; - get_state_seq(state_seq, pred); - - //LQR - mat hsmm_rData = run_lqr(A, B, dt, - R, /*Q,*/ points.size(), hsmm.getMU(state_seq[0]), state_seq, - hsmm); - repros_hsmm.push_back(hsmm_rData); - //.End of HSMM section// - - //Clean up - points.clear(); - pointsVel.clear(); - } - } - } - ImGui::End(); - - //GUI rendering - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - glColor3f(0.0f, 0.0f, 0.0f); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); - - //Draw demos - glColor3f(0.3f, 0.3f, 0.3f); - for (int n=0; n<(int)demos.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)demos[n].getDatapoints().getNumPOINTS(); t++){ - glVertex2f(demos[n].getDatapoints().getData()(0,t), demos[n].getDatapoints().getData()(1,t)); - } - glEnd(); - } - -// //Draw repros -// glColor3f(0.0f, 0.8f, 0.0f); -// for (int n=0; n<(int)repros.size(); n++){ -// glBegin(GL_LINE_STRIP); -// for (int t=0; t<(int)repros[n].n_cols; t++){ -// glVertex2f(repros[n](0,t), repros[n](1,t)); -// } -// glEnd(); -// } - -// //Draw repros hsmm -// glColor3f(0.0f, 0.0f, 0.8f); -// for (int n=0; n<(int)repros_hsmm.size(); n++){ -// glBegin(GL_LINE_STRIP); -// for (int t=0; t<(int)repros_hsmm[n].n_cols; t++){ -// glVertex2f(repros_hsmm[n](0,t), repros_hsmm[n](1,t)); -// } -// glEnd(); -// } - - //Draw repros sampling - glLineWidth(3.0f); - glColor3f(0.0f, 0.0f, 0.9f); - for (int n=0; n<(int)repros_sampling.size(); n++){ - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)repros_sampling[n].n_cols; t++){ - glVertex2f(repros_sampling[n](0,t), repros_sampling[n](1,t)); - } - glEnd(); - } - glLineWidth(2.0f); - - //Draw Gaussians - if (dispGMM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(0.8f, 0.0f, 0.0f); - for (int i=0; i<(int)hsmm.getNumSTATES(); i++){ -// eig_sym(d, V, gmm.getSIGMA(i)); - eig_sym(d, V, hsmm.getSIGMA(i).submat(0,0,1,1)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+hsmm.getMU(i)(0)), (pts(1,t)+hsmm.getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(hsmm.getMU(i)(0), hsmm.getMU(i)(1)); - } - glEnd(); - } - } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - return 0; -} - -mat run_lqr(mat A, mat B, float dt, - mat R, //std::vector<mat> Q, - int traj_length, colvec start_state, uword state_seq[], - GMM_Model model){ - - LQR lqr(A, B, dt); - - std::vector<mat> Q; - vec vTmp(4, fill::zeros); - mat QTmp(4, 4, fill::zeros); - mat Target(4, traj_length, fill::zeros); - for (int t=0; t<traj_length; t++){ - QTmp.submat(0, 0, 1, 1) = inv(model.getSIGMA(state_seq[t])); - // QTmp = inv(model.getSIGMA(state_seq[t])); // for vel - Q.push_back(QTmp); - vTmp.subvec(0, 1) = model.getMU(state_seq[t]); - // vTmp = model.getMU(state_seq[t]); // for vel - Target.col(t) = vTmp; - } - lqr.setProblem(R, Q, Target); - - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - mat rData(2, traj_length); - vec u(2); - vec X = join_cols(start_state, zeros<vec>(2)); // second part sets the velocities to zero - // vec X = start_state; // for vel - for (int t=0; t<traj_length; t++){ - rData.col(t) = X.rows(0, 1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - return rData; -} - -void get_state_seq(uword state_seq[], mat pred){ - for (int t=0; t<pred.n_cols; t++){ - vec vTmp = pred.col(t); - vTmp.max(state_seq[t]); - } -} - - diff --git a/src/demo_online_hsmm01.cpp b/src/demo_online_hsmm01.cpp new file mode 100644 index 0000000..298d0ec --- /dev/null +++ b/src/demo_online_hsmm01.cpp @@ -0,0 +1,768 @@ +/* + * demo_online_hsmm01.cpp + * + * Online hsmm learning. + * + * Authors: Sylvain Calinon, Ioannis Havoutis + */ + +#include <stdio.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <GLFW/glfw3.h> +#include <window_utils.h> + +#include <armadillo> +// #include <lqr.h> +#include <mvn.h> + +using namespace arma; + + +//----------------------------------------------------------------------------- +// Contains the parameters of a gaussian +//----------------------------------------------------------------------------- +struct gaussian_t { + + gaussian_t() {} + + gaussian_t(const vec& mu, const mat& sigma) + : mu(mu), sigma(sigma) {} + + vec mu; + mat sigma; +}; + + +//--------------------------------------------------------- + + +typedef std::vector<mat> matrix_list_t; +typedef std::vector<gaussian_t> gaussian_list_t; + + +//--------------------------------------------------------- + + +void get_state_seq(uword state_seq[], mat pred) { + for (int t=0; t<pred.n_cols; t++){ + vec vTmp = pred.col(t); + vTmp.max(state_seq[t]); + } +} + + +//--------------------------------------------------------- + + +class HSMM +{ +public: + // Constructor + HSMM(uint _nSTATES, uint _nVARS) { + nVARS = _nVARS; + nSTATES = _nSTATES; + PRIORS = rowvec(_nSTATES); + + // Initialize Components + COMPONENTS.resize(nSTATES); + } + + + inline uint getNumSTATES() const { + return nSTATES; + } + + inline gaussian_t& getCOMPONENTS(int id) { + return COMPONENTS[id]; + } + + inline const colvec& getMU(int id) const { + return COMPONENTS[id].mu; + } + + inline const mat& getSIGMA(int id) const { + return COMPONENTS[id].sigma; + } + + inline void setCOMPONENTS(gaussian_list_t& components) { + COMPONENTS = components; + } + + + //---------------------------------------------------------------------------- + // Performs online GMM clustering by using an updated DP-Means algorithms + // Ref: + // Kulis, B. and Jordan, M. I. (2012). Revisiting k-means: New algorithms + // via bayesian nonparametrics. In Proc. Intl Conf. on Machine Learning + // (ICML) + // + // Input: + // N: Number of points processed + // P: current point being added to GMM + // lambda: splitting distance + // nimSigma: minimum covariance for regularization + //---------------------------------------------------------------------------- + void online_EMDP(int N, const colvec& P, double lambda, double minSigma) { + // Initialized distance of P from first cluster + double d = arma::norm(this->getMU(0)-P,2); + + int minIndex = 0; //Index corresponding to current cluster + + // Find cluster corresponding to minimum distance + for(int k=1;k<nSTATES;k++){ + double Dist = arma::norm(this->getMU(k) - P,2); + if (Dist < d){ + d = Dist; + minIndex = k; // Index corresponding to minimum distance + } + } + + // Allocate new cluster if distance of each component higher than lambda + if (lambda < d){ + minIndex = nSTATES; + mat SigmaTmp = minSigma*eye(nVARS,nVARS); // Sigma of new component is the minimum cov + + COMPONENTS.push_back(gaussian_t(P, SigmaTmp)); // Mean of new component is P + + rowvec priorsTmp = zeros(1, nSTATES + 1); + priorsTmp.cols(0, nSTATES - 1) = PRIORS; + priorsTmp(nSTATES) = 1. / N; //prior for new component inversely proportional to #P + priorsTmp = priorsTmp / arma::norm(priorsTmp, 1); //evaluate new priors + nSTATES = nSTATES +1; //update number of states + PRIORS = priorsTmp; + } + else{ + /* + *Update components belonging to P by using MAP estimate + Ref: + Gauvain, J.-L. and Lee, C.-H. (1994). Maximum a pos- teriori estimation for + multivariate gaussian mixture observations of markov chians. IEE Transactions + on Speech and Audio Processing, 2(2). */ + double PriorsTmp = 1. / N + PRIORS[minIndex]; + + vec MuTmp = 1. / PriorsTmp * (PRIORS[minIndex] * getMU(minIndex) + P / N); + + COMPONENTS[minIndex].sigma = PRIORS[minIndex] / PriorsTmp * + (getSIGMA(minIndex) + (getMU(minIndex) - MuTmp) * (getMU(minIndex) - MuTmp).t()) + + 1. / (N * PriorsTmp) * (minSigma * eye(nVARS, nVARS) + (P - MuTmp) * (P - MuTmp).t()); + + COMPONENTS[minIndex].mu = MuTmp; + + rowvec priors = PRIORS; + priors[minIndex] = PriorsTmp; + priors = priors / arma::norm(priors, 1); + PRIORS = priors; + } + } + + + //---------------------------------------------------------------------------- + // Predict forward variable without predicted observations (implementation + // for real-time, no checks on sizes done) + //---------------------------------------------------------------------------- + void predict_forward_variable(mat& _AlphaPred) { + mat ALPHA = Pd; + ALPHA.each_col() %= PRIORS.t(); // % is the element wise product + + vec S = zeros<vec>(nSTATES); + + for (uint i = 0; i < _AlphaPred.n_cols; i++) + { + // Alpha variable + if (i > 0) + updateALPHA(ALPHA, S); + + // Update S + updateS(S, ALPHA); + + // Update alpha + _AlphaPred.col(i) = sum(ALPHA, 1); + } + } + + + void clear() { + hsmm_transition.zeros(); + hsmm_transition_ticks.zeros(); + hsmm_priors.clear(); + hsmm_priors_ticks.clear(); + + nSTATES = 1; + PRIORS = ones<vec>(1); + + COMPONENTS.clear(); + COMPONENTS.resize(nSTATES); + } + + + void predict_forward_variable_deterministic(mat& _AlphaPred, int startState) { + rowvec tempPriors = PRIORS; + + rowvec fixed_priors(nSTATES, fill::zeros); + fixed_priors(startState) = 1.0; + + PRIORS = fixed_priors; + + initialize_forward_calculation(); + predict_forward_variable(_AlphaPred); + + PRIORS = tempPriors; + } + + + void predict_forward_variable_stochastic(mat& _AlphaPred) { + rowvec tempPriors = PRIORS; + PRIORS = hsmm_priors; + + initialize_forward_calculation(); + + int nbSt = 0; + int currTime = 0; + rowvec iList(1, fill::zeros); + int nbData = _AlphaPred.n_cols; + int nStates = nSTATES; + mat h = zeros(nStates, nbData); + rowvec h1, h2; + + int nbD = this->Pd.n_cols; + + uword Iminmax; + while (currTime < nbData) { + if (nbSt==0){ + vec tmp = PRIORS.t() % randu(nStates); + tmp.max(Iminmax); + iList(0) = Iminmax; + h1 = ones<rowvec>(nbData); + }else{ + h1 = join_rows( join_rows( + zeros<rowvec>(currTime), cumsum(this->Pd.row(iList(iList.n_elem-2))) ), + ones<rowvec>( std::max( (nbData-currTime-nbD),0) )); + currTime = currTime + round( DurationCOMPONENTS[(uint)iList(iList.n_elem-2)].mu(0,0) ); + } + h2 = join_rows( join_rows( + ones<rowvec>(currTime), + ones<rowvec>( this->Pd.row(iList(iList.n_elem-1)).n_elem ) + - cumsum(this->Pd.row(iList(iList.n_elem-1))) ), + zeros<rowvec>( std::max( (nbData-currTime-nbD),0) )); + + h.row(iList(iList.n_elem-1)) = h.row(iList(iList.n_elem-1)) + + min( join_cols(h1.cols(0,nbData-1),h2.cols(0,nbData-1)) ); + vec tmp= TransitionMatrix.row(iList(iList.n_elem-1)).t() % randu(nStates); + tmp.max(Iminmax); + iList.resize(iList.n_elem+1); + iList(iList.n_elem-1) = Iminmax; + + nbSt = nbSt+1; + } + h = h / repmat(sum(h,0) ,nStates,1); + _AlphaPred = h; + PRIORS = tempPriors; + } + + + void integrate_demonstration(mat demo) { + //Compute sequence of states + const int nPoints = demo.n_cols; + mat h(nSTATES, nPoints); + for (int i=0; i<(int)nSTATES; i++){ + h.row(i) = trans(mvn::getPDFValue(getCOMPONENTS(i).mu, getCOMPONENTS(i).sigma, demo)); + } + uword imax[nPoints]; + get_state_seq(imax, h); + + hsmm_transition.resize(nSTATES, nSTATES); + hsmm_transition_ticks.resize(nSTATES, nSTATES); + hsmm_priors.resize(nSTATES); + hsmm_priors_ticks.resize(nSTATES); + + //update hsmm priors for stochastic sampling + hsmm_priors_ticks(imax[0]) += 1; + hsmm_priors = hsmm_priors_ticks / accu(hsmm_priors_ticks); + + //update duration statistics + hsmm_duration_stats.resize(nSTATES); + + uint s0 = imax[0], currStateDuration = 1; + for (int t = 0; t < nPoints; t++) { + if ( (imax[t] != s0) || (t+1 == nPoints) ) { + if (t + 1 == nPoints) + currStateDuration += 1; + + hsmm_duration_stats[s0](currStateDuration); + currStateDuration = 0.0; + hsmm_transition(s0, imax[t]) += 1.0; + hsmm_transition_ticks(s0, imax[t]) += 1.0; + s0 = imax[t]; + } + currStateDuration += 1; + } + + // normalize the transition matrix + for (int i = 0; i < hsmm_transition.n_rows ; i++){ + double row_sum = accu(hsmm_transition.row(i)); + if (row_sum > 1){ + double row_sum_ticks = accu(hsmm_transition_ticks.row(i)); + hsmm_transition.row(i) = hsmm_transition_ticks.row(i) / row_sum_ticks; + } + } + + TransitionMatrix = hsmm_transition; + + // Set hsmmd durations: + mat _SIGMA = zeros(1,1); + colvec _MU = zeros(1,1); + gaussian_list_t hsmm_components; + + for (uint i=0; i<nSTATES; i++) { + _MU(0,0) = hsmm_duration_stats[i].mean();//state_duration_means(i); + _SIGMA(0,0) = std::max( hsmm_duration_stats[i].var(), 1.0); + hsmm_components.push_back(gaussian_t(_MU, _SIGMA)); + } + + DurationCOMPONENTS = hsmm_components; + } + + +private: + void initialize_forward_calculation() { + // Calculate PD size: + PdSize = 0; + for (uint i = 0;i<nSTATES;i++) + { + if (PdSize < accu(DurationCOMPONENTS[i].mu)) + PdSize = accu(DurationCOMPONENTS[i].mu); + } + + PdSize *= 1.2; // Enlarge the Size of Pd for 'accuracy' + + Pd.zeros(nSTATES, PdSize); + + + // Duration input vector + mat dur = linspace(1,PdSize, PdSize); + // Pre-Calculate Pd + for (uint i = 0;i<nSTATES;i++) + { + // Note that we need to transpose twice.... + // getPDFValue accepts a rowvec of values, but returns a colvec.... + Pd.row(i) = mvn::getPDFValue(DurationCOMPONENTS[i].mu, + DurationCOMPONENTS[i].sigma, + dur.t() + ).t(); + } + } + + + // Equation (12): ALPHA MATRIX without observation + void updateALPHA(mat &ALPHA, const colvec& S) const { + mat Atmp1 = Pd.cols(0, PdSize - 2); + Atmp1.each_col() %= S; + + mat Atmp2 = ALPHA.cols(1, PdSize - 1); + + ALPHA.cols(0, PdSize - 2) = Atmp2 + Atmp1; + ALPHA.col(PdSize - 1) = S % Pd.col(PdSize - 1); + } + + + // Equation (6): Update S + void updateS(colvec &S, const mat& ALPHA) const { + S = TransitionMatrix.t() * ALPHA.col(0); + } + + +private: + uint nVARS; + uint nSTATES; + + gaussian_list_t COMPONENTS; + gaussian_list_t DurationCOMPONENTS; + rowvec PRIORS; + + mat TransitionMatrix; + + // Variables for state duration + mat Pd; // Matrix with precomputed probability values for the duration; + uint PdSize; // Maximum maximum duration step + + // For demonstration integration + mat hsmm_transition; + mat hsmm_transition_ticks; + rowvec hsmm_priors; + rowvec hsmm_priors_ticks; + + std::vector <running_stat<double> > hsmm_duration_stats; +}; + + +//--------------------------------------------------------- + + +static void error_callback(int error, const char* description){ + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//--------------------------------------------------------- + + +// mat run_lqr(const mat& A, const mat& B, float dt, const mat& R, int traj_length, +// const colvec& start_state, uword state_seq[], const HSMM& model) { +// +// matrix_list_t Q; +// vec vTmp(4, fill::zeros); +// mat QTmp(4, 4, fill::zeros); +// mat Target(4, traj_length, fill::zeros); +// for (int t = 0; t < traj_length; ++t) { +// QTmp.submat(0, 0, 1, 1) = inv(model.getSIGMA(state_seq[t])); +// Q.push_back(QTmp); +// vTmp.subvec(0, 1) = model.getMU(state_seq[t]); +// Target.col(t) = vTmp; +// } +// +// matrix_list_t gains = lqr::evaluate_gains_infinite_horizon(A, B, R, Q, Target); +// +// //Retrieve data +// mat rData(2, traj_length); +// vec u(2); +// vec X = join_cols(start_state, zeros<vec>(2)); // second part sets the velocities to zero +// // vec X = start_state; // for vel +// for (int t = 0; t < traj_length; ++t) { +// rData.col(t) = X.rows(0, 1); +// u = gains[t] * (Target.col(t) - X); +// X += (A * X + B * u) * dt; +// } +// +// return rData; +// } + + +//------------------------------------------------------------------------- +// Holds the sizes of the window and of the OpenGL front-buffer (they might +// be different, for instance on a 4K screen) +//------------------------------------------------------------------------- +struct window_size_t { + int win_width; + int win_height; + int fb_width; + int fb_height; +}; + + +//--------------------------------------------------------- + + +int main(int argc, char **argv){ + + //int nVars = 4; + int nVars = 2; //position only + HSMM hsmm(1,nVars); + float minSigma = 2E2; + float lambda = 250.0f; + mat minSIGMA = eye(nVars,nVars) * minSigma; + gaussian_list_t comps; + matrix_list_t demos; + // matrix_list_t repros; + // matrix_list_t repros_hsmm; + // matrix_list_t repros_sampling; + + //Setup hsmm + int init_nStates = 1; // we need to initialize the states to something + + //Setup LQR + // mat A(4,4), B(4,2); + // float dt = 0.01f; + // + // float iFactor = -8; + // mat R = eye(2,2) * pow(10.0f,iFactor); + // mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; + // mat B1d; B1d << 0 << endr << 1 << endr; + // A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf + // B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf + + + //--------------- Setup of the rendering --------------- + + // Take 4k screens into account (framebuffer size != window size) + window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 600; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + + //Setup GUI + glfwSetErrorCallback(error_callback); + if (!glfwInit()) + exit(1); + + GLFWwindow* window = create_window_at_optimal_size( + "Demo Online HSMM", window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + ImVec4 clear_color = ImColor(255, 255, 255); + + + //--------------- Main loop --------------- + + ImVector<ImVec2> points; + ImVector<ImVec2> pointsVel; + bool adding_line = false; + bool dispGMM = false; + int nbPts = 0; + + ImVec2 mouse_pos_in_canvas; + + running_stat<float> xi; + float counter = 2; + while (!glfwWindowShouldClose(window)){ + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + // Retrieve the new window size + glfwGetWindowSize(window, &window_size.win_width, &window_size.win_height); + + // Retrieve the new framebuffer size + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + } + + // Start of rendering + ImGui_ImplGlfwGL2_NewFrame(); + + //Control panel GUI + // static bool hsmm_sampling = false; + + ImGui::SetNextWindowPos(ImVec2(2,2)); + // ImGui::SetNextWindowSize(ImVec2(hsmm_sampling ? 400 : 300, + // hsmm_sampling ? 250 : 180)); + ImGui::SetNextWindowSize(ImVec2(300, 116)); + + ImGui::Begin("Control Panel", NULL, + ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| + ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); + + if (ImGui::Button("Clear")){ + demos.clear(); + // repros.clear(); + // repros_sampling.clear(); + // repros_hsmm.clear(); + hsmm.clear(); + dispGMM = false; + } + + ImGui::Text("Left-click to collect demonstrations"); + ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), (int)points.size(), (int)hsmm.getNumSTATES()); + ImGui::SliderFloat("minSigma", &minSigma, 1E1, 2E3); + ImGui::SliderFloat("lambda", &lambda, 10.0f, 500.0f); + // if (ImGui::SliderFloat("rFactor", &iFactor, -9.0f, -1.0f, "%.1f" )){ + // R = eye(2,2) * pow(10.0f,iFactor); + // } + + // static bool hsmm_stochastic_sampling = true; + // ImGui::Checkbox("Stochastic sampling", &hsmm_stochastic_sampling); + // + // static int hsmm_sampling_start_state = 0; + // static int hsmm_sampling_traj_length = 10; + // ImGui::Checkbox("Run hsmm sampling", &hsmm_sampling); + // + // if (hsmm_sampling) { + // ImGui::SliderInt("Start state", &hsmm_sampling_start_state, 0, hsmm.getNumSTATES() - 1); + // ImGui::SliderInt("Trajectory length", &hsmm_sampling_traj_length, 2, 1000); + // if (ImGui::Button("Sample") && (hsmm.getNumSTATES()!=1)) { + // mat pred(hsmm.getNumSTATES(), hsmm_sampling_traj_length, fill::zeros); + // if (!hsmm_stochastic_sampling) { + // hsmm.predict_forward_variable_deterministic(pred, hsmm_sampling_start_state); + // }else{ + // hsmm.predict_forward_variable_stochastic(pred); + // } + // uword state_seq[pred.n_cols]; + // get_state_seq(state_seq, pred); + // mat hsmm_rData = run_lqr(A, B, dt, + // R, hsmm_sampling_traj_length, hsmm.getMU(state_seq[0]), state_seq, + // hsmm); + // repros_sampling.push_back(hsmm_rData); + // } + // ImGui::SameLine(); + // if (ImGui::Button("Clear Samples")) { + // repros_sampling.clear(); + // } + // } + + ImGui::End(); + + //Get data + ImVec2 mouse_pos_in_canvas_curr( + ImGui::GetIO().MousePos.x * + (float) window_size.fb_width / (float) window_size.win_width, + (window_size.win_height - ImGui::GetIO().MousePos.y) * + (float) window_size.fb_height / (float) window_size.win_height + ); + + double alpha = 0.2; + mouse_pos_in_canvas.x = mouse_pos_in_canvas.x + + alpha*(mouse_pos_in_canvas_curr.x - mouse_pos_in_canvas.x); + mouse_pos_in_canvas.y = mouse_pos_in_canvas.y + + alpha*(mouse_pos_in_canvas_curr.y - mouse_pos_in_canvas.y); + + if (!ImGui::GetIO().WantCaptureMouse) { //Is outside gui? + if (!adding_line && ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)){ //Button pushed + adding_line = true; + if (!dispGMM){ + colvec p(2); + p(0) = mouse_pos_in_canvas.x; + p(1) = mouse_pos_in_canvas.y; + comps.push_back(gaussian_t(p, minSIGMA)); + hsmm.setCOMPONENTS(comps); + comps.clear(); + dispGMM = true; + } + } + if (adding_line){ //Trajectory recording + points.push_back(mouse_pos_in_canvas); + + nbPts++; + vec p(2); + p(0) = mouse_pos_in_canvas.x; + p(1) = mouse_pos_in_canvas.y; + + hsmm.online_EMDP(nbPts, p, lambda, minSigma); + + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)){ //Button released + adding_line = false; + //Add demonstration + mat demo = mat(nVars,points.size()); + for (int t=0; t<(int)points.size(); t++){ + demo(0,t) = points[t].x; + demo(1,t) = points[t].y; + } + demos.push_back(demo); + + //Compute sequence of states + mat h(hsmm.getNumSTATES(), points.size()); + for (int i=0; i<(int)hsmm.getNumSTATES(); i++){ + h.row(i) = trans( + mvn::getPDFValue(hsmm.getCOMPONENTS(i).mu, + hsmm.getCOMPONENTS(i).sigma, + demo) + ); + } + uword imax[points.size()]; + get_state_seq(imax, h); + + // //LQR + // mat rData = run_lqr(A, B, dt, + // R, points.size(), demo.col(0), imax, + // hsmm); + // repros.push_back(rData); + // + // //.HSMM testing part + // hsmm.integrate_demonstration(demo); + // mat pred(hsmm.getNumSTATES(), points.size(), fill::zeros); + // + // hsmm.predict_forward_variable_deterministic(pred, imax[0]); + // + // uword state_seq[pred.n_cols]; + // get_state_seq(state_seq, pred); + // + // //LQR + // mat hsmm_rData = run_lqr(A, B, dt, + // R, /*Q,*/ points.size(), hsmm.getMU(state_seq[0]), state_seq, + // hsmm); + // repros_hsmm.push_back(hsmm_rData); + // //.End of HSMM section// + + //Clean up + points.clear(); + pointsVel.clear(); + } + } + } + + //GUI rendering + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); + glClear(GL_COLOR_BUFFER_BIT); + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + //Rendering + glMatrixMode( GL_PROJECTION ); + glLoadIdentity(); + glOrtho( 0, window_size.fb_width, 0, window_size.fb_height, -1., 1.); + glMatrixMode( GL_MODELVIEW ); + glLoadIdentity(); + glPushMatrix(); + + //Draw current demo + glColor3f(0.0f, 0.0f, 0.0f); + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)points.size(); t++){ + glVertex2f(points[t].x, points[t].y); + } + glEnd(); + + //Draw demos + glColor3f(0.3f, 0.3f, 0.3f); + for (int n=0; n<(int)demos.size(); n++){ + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)demos[n].n_cols; t++){ + glVertex2f(demos[n](0,t), demos[n](1,t)); + } + glEnd(); + } + + //Draw repros sampling + // glColor3f(0.0f, 0.0f, 0.9f); + // for (int n=0; n<(int)repros_sampling.size(); n++){ + // glBegin(GL_LINE_STRIP); + // for (int t=0; t<(int)repros_sampling[n].n_cols; t++){ + // glVertex2f(repros_sampling[n](0,t), repros_sampling[n](1,t)); + // } + // glEnd(); + // } + + //Draw Gaussians + if (dispGMM){ + vec d(2); + mat V(2,2), R(2,2), pts(2,30); + mat pts0(2,30); + pts0 = join_cols(cos(linspace<rowvec>(0,2*datum::pi,30)), sin(linspace<rowvec>(0,2*datum::pi,30))); + glColor3f(0.8f, 0.0f, 0.0f); + for (int i=0; i<(int)hsmm.getNumSTATES(); i++){ + eig_sym(d, V, hsmm.getSIGMA(i).submat(0,0,1,1)); + R = V * sqrt(diagmat(d)); + pts = R * pts0; + glBegin(GL_LINE_STRIP); + for (int t=0; t<(int)pts.n_cols; t++){ + glVertex2f((pts(0,t)+hsmm.getMU(i)(0)), (pts(1,t)+hsmm.getMU(i)(1))); + } + glEnd(); + glBegin(GL_POINTS); + for (int t=0; t<(int)pts.n_cols; t++){ + glVertex2f(hsmm.getMU(i)(0), hsmm.getMU(i)(1)); + } + glEnd(); + } + } + + glPopMatrix(); + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + } + + //Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + return 0; +} diff --git a/src/demo_proMP01.cpp b/src/demo_proMP01.cpp new file mode 100644 index 0000000..4ce11e8 --- /dev/null +++ b/src/demo_proMP01.cpp @@ -0,0 +1,789 @@ +/* + * demo_proMP01.cpp + * + * Conditioning on trajectory distributions with ProMP + * + * @incollection{Paraschos13, + * title = {Probabilistic Movement Primitives}, + * author = {Paraschos, A. and Daniel, C. and Peters, J. and Neumann, G.}, + * booktitle = NIPS, + * pages = {2616--2624}, + * year = {2013}, + * publisher = {Curran Associates, Inc.} + * } + * @inproceedings{Rueckert15, + * author = "Rueckert, E. and Mundo, J. and Paraschos, A. and Peters, J. and Neumann, G.", + * title = "Extracting Low-Dimensional Control Variables for Movement Primitives", + * booktitle = ICRA, + * year = "2015", + * pages = "1511--1518", + * address = "Seattle, WA, USA" + * } + * + * Authors: Sylvain Calinon, Philip Abbet + */ + + +#include <stdio.h> +#include <armadillo> +#include <mvn.h> + +#include <gfx2.h> +#include <gfx_ui.h> +#include <GLFW/glfw3.h> +#include <imgui.h> +#include <imgui_impl_glfw_gl2.h> +#include <window_utils.h> + +using namespace arma; + + +/***************************** ALGORITHM SECTION *****************************/ + +typedef std::vector<vec> vector_list_t; +typedef std::vector<mat> matrix_list_t; + + +//----------------------------------------------------------------------------- +// Contains all the parameters used by the algorithm. Some of them are +// modifiable through the UI, others are hard-coded. +//----------------------------------------------------------------------------- +struct parameters_t { + int nb_states; // Number of components in the GMM + int nb_data; // Number of datapoints in a trajectory + int nb_reproductions; // Number of reproductions + float dt; // Time step (without rescaling, large values such + // as 1 has the advantage of creating clusers based + // on position information) +}; + + +//----------------------------------------------------------------------------- +// Model trained using the algorithm +//----------------------------------------------------------------------------- +struct model_t { + parameters_t parameters; // Parameters used to train the model + + int nb_var; // Dimension of position data + vec mu_w; + mat sigma_w; + mat psi; + mat H; // Functions activation +}; + + +//----------------------------------------------------------------------------- +// Training of the model +//----------------------------------------------------------------------------- +void learn(const matrix_list_t& demos, model_t &model) { + + model.nb_var = 2; + + vec timesteps = linspace<vec>( + 0, model.parameters.nb_data - 1, model.parameters.nb_data + ) * model.parameters.dt; + + // Create basis functions (GMM with components equally split in time) + vec mu = linspace<vec>( + timesteps(0), timesteps(timesteps.n_rows - 1), model.parameters.nb_states + ); + + double sigma = 0.01; + + // Compute basis functions activation + model.H = mat(model.parameters.nb_states, model.parameters.nb_data); + + for (unsigned int i = 0; i < model.parameters.nb_states; ++i) + model.H.row(i) = mvn::getPDFValue(colvec{ mu(i) }, mat({ sigma }), timesteps.t()).t(); + + model.H = model.H / repmat(sum(model.H, 0), model.parameters.nb_states, 1); + + + //_____ ProMP __________ + + model.psi = mat(model.nb_var * model.parameters.nb_data, + model.nb_var * model.parameters.nb_states); + + for (unsigned int i = 0; i < model.parameters.nb_data; ++i) { + model.psi.rows(i * model.nb_var, (i + 1) * model.nb_var - 1) = + kron(model.H.col(i).t(), eye(model.nb_var, model.nb_var)); + } + + mat w(model.nb_var * model.parameters.nb_states, demos.size()); + for (size_t i = 0; i < demos.size(); ++i) + w.col(i) = pinv(model.psi) * (mat) vectorise(demos[i]); + + model.mu_w = mean(w, 1); + + model.sigma_w = eye(model.nb_var * model.parameters.nb_states, + model.nb_var * model.parameters.nb_states); + + if (w.n_cols == 1) + model.sigma_w += rowvec(cov(w.t()))[0]; + else + model.sigma_w += cov(w.t()); +} + + +//----------------------------------------------------------------------------- +// Compute the trajectory distribution +//----------------------------------------------------------------------------- +mat compute_trajectory_distribution(const model_t& model) { + + vec points = model.psi * model.mu_w; + return reshape(points, model.nb_var, model.parameters.nb_data); +} + + +//----------------------------------------------------------------------------- +// Compute a reproduction (conditioning on trajectory distribution, +// reconstruction from partial data) +//----------------------------------------------------------------------------- +mat compute_reproduction(const model_t& model, const vec& from, const vec& to) { + + // The following code produces (with nb_data = 10 and nb_var = 2): + // in = [ 0, 1, 18, 19 ] + // out = [ 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17 ] + + uvec in_out = linspace<uvec>( + 0, model.parameters.nb_data * model.nb_var - 1, + model.parameters.nb_data * model.nb_var + ); + + uvec in(2 * model.nb_var); + + in.head(model.nb_var) = in_out.head(model.nb_var); + in.tail(model.nb_var) = in_out.tail(model.nb_var); + + uvec out = in_out.subvec(model.nb_var, in_out.n_elem - model.nb_var - 1); + + // Input data + mat start_end_coords(model.nb_var, 2); + start_end_coords(span::all, 0) = from; + start_end_coords(span::all, 1) = to; + + vec mu_in = reshape( + start_end_coords + repmat((randu(model.nb_var, 1) - 0.5) * 10.0, 1, 2), + model.nb_var * 2, 1 + ); + + // Gaussian conditioning with trajectory distribution + vec points(in_out.n_elem, fill::zeros); + + points.rows(in) = mu_in; + + mat A = model.sigma_w * model.psi.rows(in).t(); + mat B = model.psi.rows(in) * model.sigma_w * model.psi.rows(in).t(); + + mat mu_w_tmp = model.mu_w + + (inv(B.t()) * A.t()).t() * // == A / B + (points.rows(in) - model.psi.rows(in) * model.mu_w); + + points.rows(out) = model.psi.rows(out) * mu_w_tmp; + + return reshape(points, model.nb_var, model.parameters.nb_data); +} + + +/****************************** HELPER FUNCTIONS *****************************/ + +static void error_callback(int error, const char* description) { + fprintf(stderr, "Error %d: %s\n", error, description); +} + + +//----------------------------------------------------------------------------- +// Contains all the informations about a viewport +//----------------------------------------------------------------------------- +struct viewport_t { + int x; + int y; + int width; + int height; + + // Projection matrix parameters + arma::vec projection_top_left; + arma::vec projection_bottom_right; + double projection_near; + double projection_far; +}; + + +//----------------------------------------------------------------------------- +// Helper function to setup a viewport +//----------------------------------------------------------------------------- +void setup_viewport(viewport_t* viewport, int x, int y, int width, int height, + double near = -1.0, double far = 1.0) { + + viewport->x = x; + viewport->y = y; + viewport->width = width; + viewport->height = height; + viewport->projection_top_left = vec({ (double) -width / 2, + (double) height / 2 }); + viewport->projection_bottom_right = vec({ (double) width / 2, + (double) -height / 2 }); + viewport->projection_near = near; + viewport->projection_far = far; +} + + +//----------------------------------------------------------------------------- +// Converts some coordinates from UI-space to OpenGL-space, taking the +// coordinates of a viewport into account +//----------------------------------------------------------------------------- +arma::vec ui2fb(const arma::vec& coords, const gfx2::window_size_t& window_size, + const viewport_t& viewport) { + arma::vec result = coords; + + // ui -> viewport + result(0) = coords(0) * (float) window_size.fb_width / (float) window_size.win_width - viewport.x; + result(1) = (window_size.win_height - coords(1)) * + (float) window_size.fb_height / (float) window_size.win_height - viewport.y; + + // viewport -> fb + result(0) = result(0) - (float) viewport.width * 0.5f; + result(1) = result(1) - (float) viewport.height * 0.5f; + + return result; +} + + +//----------------------------------------------------------------------------- +// Colors of the displayed lines and gaussians +//----------------------------------------------------------------------------- +const mat COLORS({ + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, + { 0.0, 0.75, 0.75 }, + { 0.75, 0.0, 0.75 }, + { 0.75, 0.75, 0.0 }, + { 0.25, 0.25, 0.25 }, + { 0.0, 0.0, 1.0 }, + { 0.0, 0.5, 0.0 }, + { 1.0, 0.0, 0.0 }, +}); + + +//----------------------------------------------------------------------------- +// Create a demonstration (with a length of 'nb_samples') from a trajectory +// (of any length) +//----------------------------------------------------------------------------- +mat sample_trajectory(const vector_list_t& trajectory, int nb_samples) { + + // Resampling of the trajectory + vec x(trajectory.size()); + vec y(trajectory.size()); + vec x2(trajectory.size()); + vec y2(trajectory.size()); + + for (size_t i = 0; i < trajectory.size(); ++i) { + x(i) = trajectory[i](0); + y(i) = trajectory[i](1); + } + + vec from_indices = linspace<vec>(0, trajectory.size() - 1, trajectory.size()); + vec to_indices = linspace<vec>(0, trajectory.size() - 1, nb_samples); + + interp1(from_indices, x, to_indices, x2, "*linear"); + interp1(from_indices, y, to_indices, y2, "*linear"); + + // Create the demonstration + mat demo(2, nb_samples); + for (int i = 0; i < nb_samples; ++i) { + demo(0, i) = x2[i]; + demo(1, i) = y2[i]; + } + + return demo; +} + + +//----------------------------------------------------------------------------- +// Contains all the needed infos about the state of the application (values of +// the parameters modifiable via the UI, which action the user is currently +// doing, ...) +//----------------------------------------------------------------------------- +struct gui_state_t { + // Indicates if the user is currently drawing a new demonstration + bool is_drawing_demonstration; + + // Indicates if the parameters dialog is displayed + bool is_parameters_dialog_displayed; + + // Indicates if the parameters were modified through the UI + bool are_parameters_modified; + + // Indicates if the reproductions must be recomputed + bool must_recompute_reproductions; + + // Parameters modifiable via the UI (they correspond to the ones declared + // in parameters_t) + int parameter_nb_states; + int parameter_nb_data; + int parameter_nb_reproductions; + + bool display_colored_points; +}; + + +//----------------------------------------------------------------------------- +// Render the "demonstrations" viewport +//----------------------------------------------------------------------------- +void draw_demos_viewport(const viewport_t& viewport, + const vector_list_t& current_trajectory, + const matrix_list_t& demonstrations) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.7f, 0.7f, 0.7f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + // Draw the currently created demonstration (if any) + if (current_trajectory.size() > 1) + gfx2::draw_line(arma::fvec({0.33f, 0.97f, 0.33f}), current_trajectory); + + // Draw the demonstrations + int color_index = 0; + for (size_t i = 0; i < demonstrations.size(); ++i) { + arma::mat datapoints = demonstrations[i]; + + arma::fvec color = arma::conv_to<arma::fvec>::from(COLORS.row(color_index)); + + gfx2::draw_line(color, datapoints); + + ++color_index; + if (color_index >= demonstrations.size()) + color_index = 0; + } +} + + +//----------------------------------------------------------------------------- +// Render a "model" viewport +//----------------------------------------------------------------------------- +void draw_model_viewport(const viewport_t& viewport, + const model_t& model, + const mat& trajectory_distribution) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.9f, 0.9f, 0.9f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + if (trajectory_distribution.n_cols > 0) { + + // Draw the GMM states + for (int i = 0; i < model.parameters.nb_states; ++i) { + glClear(GL_DEPTH_BUFFER_BIT); + + span id = span(i * model.nb_var, i * model.nb_var + 1); + + gfx2::draw_gaussian(conv_to<fvec>::from(COLORS.row(i % 10).t()), + model.mu_w(id), model.sigma_w(id, id)); + } + + glClear(GL_DEPTH_BUFFER_BIT); + + // Draw the trajectory distribution (if any) + gfx2::draw_line(arma::fvec({0.0f, 0.0f, 0.0f}), trajectory_distribution); + } +} + + +//----------------------------------------------------------------------------- +// Render a "reproduction" viewport +//----------------------------------------------------------------------------- +void draw_reproductions_viewport(const viewport_t& viewport, + const model_t& model, + const matrix_list_t& reproductions, + bool display_colored_points) { + + glViewport(viewport.x, viewport.y, viewport.width, viewport.height); + glScissor(viewport.x, viewport.y, viewport.width, viewport.height); + glClearColor(0.9f, 0.9f, 0.9f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(viewport.projection_top_left(0), viewport.projection_bottom_right(0), + viewport.projection_bottom_right(1), viewport.projection_top_left(1), + viewport.projection_near, viewport.projection_far); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + if (display_colored_points) { + + // Create a color map + mat colors(model.parameters.nb_states, 3); + for (int i = 0; i < model.parameters.nb_states; ++i) + colors(i, span::all) = COLORS(i % 10, span::all); + + // Draw the reproductions as points colored by the gmm states (if any) + for (auto iter = reproductions.begin(); iter != reproductions.end(); ++iter) { + const mat& datapoints = (*iter); + + for (uint i = 0; i < datapoints.n_cols; ++i) { + fvec color = conv_to<fvec>::from(model.H.col(i).t() * colors); + + fvec position = zeros<fvec>(3); + position(0) = datapoints(0, i); + position(1) = datapoints(1, i); + + gfx2::draw_rectangle(color, 8.0f, 8.0f, position); + } + } + } + + // Draw the reproductions as lines (if any) + glClear(GL_DEPTH_BUFFER_BIT); + + for (auto iter = reproductions.begin(); iter != reproductions.end(); ++iter) { + gfx2::draw_line(arma::fvec({0.0f, 0.0f, 0.0f}), *iter); + } +} + + +/******************************* MAIN FUNCTION *******************************/ + +int main(int argc, char **argv) { + arma_rng::set_seed_random(); + + // Model + model_t model; + + // Parameters + model.parameters.nb_states = 10; + model.parameters.nb_data = 200; + model.parameters.nb_reproductions = 10; + model.parameters.dt = 0.01f; + + + // Take 4k screens into account (framebuffer size != window size) + gfx2::window_size_t window_size; + window_size.win_width = 1200; + window_size.win_height = 400; + window_size.fb_width = -1; // Will be known later + window_size.fb_height = -1; + int viewport_width = 0; + int viewport_height = 0; + + + // Initialise GLFW + glfwSetErrorCallback(error_callback); + + if (!glfwInit()) + return -1; + + glfwWindowHint(GLFW_SAMPLES, 4); + glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2); + glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1); + + // Open a window and create its OpenGL context + GLFWwindow* window = create_window_at_optimal_size( + "Demo Conditioning on trajectory distributions", + window_size.win_width, window_size.win_height + ); + + glfwMakeContextCurrent(window); + + + // Setup GLSL + gfx2::init(); + glEnable(GL_SCISSOR_TEST); + glEnable(GL_DEPTH_TEST); + glEnable(GL_CULL_FACE); + glEnable(GL_LINE_SMOOTH); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + // Setup ImGui + ImGui::CreateContext(); + ImGui_ImplGlfwGL2_Init(window, true); + + + // Viewports + viewport_t viewport_demos; + viewport_t viewport_model; + viewport_t viewport_repros; + + + // GUI state + gui_state_t gui_state; + gui_state.is_drawing_demonstration = false; + gui_state.is_parameters_dialog_displayed = false; + gui_state.are_parameters_modified = false; + gui_state.must_recompute_reproductions = false; + gui_state.parameter_nb_states = model.parameters.nb_states; + gui_state.parameter_nb_data = model.parameters.nb_data; + gui_state.parameter_nb_reproductions = model.parameters.nb_reproductions; + gui_state.display_colored_points = true; + + + // List of demonstrations and reproductions + matrix_list_t demos; + mat trajectory_distribution; + matrix_list_t reproductions; + + + // Main loop + vector_list_t current_trajectory; + std::vector<vector_list_t> original_trajectories; + + while (!glfwWindowShouldClose(window)) { + glfwPollEvents(); + + // Detect when the window was resized + if ((ImGui::GetIO().DisplaySize.x != window_size.win_width) || + (ImGui::GetIO().DisplaySize.y != window_size.win_height)) { + + window_size.win_width = ImGui::GetIO().DisplaySize.x; + window_size.win_height = ImGui::GetIO().DisplaySize.y; + + glfwGetFramebufferSize(window, &window_size.fb_width, &window_size.fb_height); + + viewport_width = window_size.fb_width / 3 - 1; + viewport_height = window_size.fb_height; + + // Update all the viewports + setup_viewport(&viewport_demos, 0, 0, viewport_width, viewport_height); + + setup_viewport(&viewport_model, viewport_width + 2, 0, viewport_width, + viewport_height); + + setup_viewport(&viewport_repros, window_size.fb_width - viewport_width, 0, + viewport_width, viewport_height); + } + + + // If the parameters changed, learn the model again + if (gui_state.are_parameters_modified) { + + if (model.parameters.nb_data != gui_state.parameter_nb_data) { + demos.clear(); + + for (size_t i = 0; i < original_trajectories.size(); ++i) { + demos.push_back(sample_trajectory(original_trajectories[i], + gui_state.parameter_nb_data) + ); + } + } + + model.parameters.nb_data = gui_state.parameter_nb_data; + model.parameters.nb_states = gui_state.parameter_nb_states; + + if (!demos.empty()) { + learn(demos, model); + gui_state.must_recompute_reproductions = true; + } + + gui_state.are_parameters_modified = false; + } + + + // Recompute the reproductions (if necessary) + if (gui_state.must_recompute_reproductions) { + + model.parameters.nb_reproductions = gui_state.parameter_nb_reproductions; + + trajectory_distribution = compute_trajectory_distribution(model); + + reproductions.clear(); + for (int i = 0; i < model.parameters.nb_reproductions; ++i) { + reproductions.push_back(compute_reproduction( + model, demos[0].col(0), demos[0].col(model.parameters.nb_data - 1) + )); + } + + gui_state.must_recompute_reproductions = false; + } + + + // Start the rendering + ImGui_ImplGlfwGL2_NewFrame(); + + glViewport(0, 0, window_size.fb_width, window_size.fb_height); + glScissor(0, 0, window_size.fb_width, window_size.fb_height); + glClearColor(0.0f, 0.0f, 0.0f, 0.0f); + glClear(GL_COLOR_BUFFER_BIT); + + draw_demos_viewport(viewport_demos, current_trajectory, demos); + + draw_model_viewport(viewport_model, model, trajectory_distribution); + + draw_reproductions_viewport(viewport_repros, model, reproductions, + gui_state.display_colored_points); + + + // Window: Demonstrations + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(0, 0)); + ImGui::Begin("Demonstrations", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Demonstrations "); + ImGui::SameLine(); + + if (ImGui::Button("Clear")) { + original_trajectories.clear(); + demos.clear(); + reproductions.clear(); + trajectory_distribution = mat(); + model.mu_w = vec(); + model.sigma_w = mat(); + } + + ImGui::SameLine(); + ImGui::Text(" "); + ImGui::SameLine(); + + if (ImGui::Button("Parameters")) + gui_state.is_parameters_dialog_displayed = true; + + ImGui::End(); + + + // Window: Model + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width / 3, 0)); + ImGui::Begin("Model", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Model"); + + ImGui::End(); + + + // Window: Reproductions + ImGui::SetNextWindowSize(ImVec2(window_size.win_width / 3, 36)); + ImGui::SetNextWindowPos(ImVec2(window_size.win_width - window_size.win_width / 3, 0)); + ImGui::Begin("Reproductions", NULL, + ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoSavedSettings | + ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoCollapse | + ImGuiWindowFlags_NoTitleBar + ); + + ImGui::Text("Reproductions"); + + ImGui::End(); + + + // Window: Parameters + ImGui::SetNextWindowSize(ImVec2(440, 146)); + ImGui::SetNextWindowPos(ImVec2((window_size.win_width - 440) / 2, (window_size.win_height - 146) / 2)); + ImGui::PushStyleColor(ImGuiCol_WindowBg, ImVec4(0, 0, 0, 255)); + + if (gui_state.is_parameters_dialog_displayed) + ImGui::OpenPopup("Parameters"); + + if (ImGui::BeginPopupModal("Parameters", NULL, + ImGuiWindowFlags_NoResize | + ImGuiWindowFlags_NoSavedSettings)) { + + ImGui::SliderInt("Nb states", &gui_state.parameter_nb_states, 2, 20); + ImGui::SliderInt("Nb data", &gui_state.parameter_nb_data, 100, 300); + ImGui::SliderInt("Nb reproductions", &gui_state.parameter_nb_reproductions, 2, 10); + ImGui::Checkbox("Show colored points in reproductions", &gui_state.display_colored_points); + + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + gui_state.is_parameters_dialog_displayed = false; + gui_state.are_parameters_modified = true; + } + + ImGui::EndPopup(); + } + + ImGui::PopStyleColor(); + + + // GUI rendering + ImGui::Render(); + ImGui_ImplGlfwGL2_RenderDrawData(ImGui::GetDrawData()); + + // Swap buffers + glfwSwapBuffers(window); + + // Keyboard input + if (ImGui::IsKeyPressed(GLFW_KEY_ESCAPE)) + break; + + + if (!gui_state.is_drawing_demonstration) { + // Left click: start a new demonstration (only if not on the UI and in the + // demonstrations viewport) + if (ImGui::IsMouseClicked(GLFW_MOUSE_BUTTON_1)) { + double mouse_x, mouse_y; + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + if (!ImGui::GetIO().WantCaptureMouse && (mouse_x <= window_size.win_width / 3)) + { + gui_state.is_drawing_demonstration = true; + + vec coords = ui2fb({ mouse_x, mouse_y }, window_size, viewport_demos); + current_trajectory.push_back(coords); + } + } + } else { + double mouse_x, mouse_y; + glfwGetCursorPos(window, &mouse_x, &mouse_y); + + vec coords = ui2fb({ mouse_x, mouse_y }, window_size, viewport_demos); + + vec last_point = current_trajectory[current_trajectory.size() - 1]; + vec diff = abs(coords - last_point); + + if ((diff(0) > 1e-6) && (diff(1) > 1e-6)) + current_trajectory.push_back(coords); + + // Left mouse button release: end the demonstration creation + if (!ImGui::IsMouseDown(GLFW_MOUSE_BUTTON_1)) { + gui_state.is_drawing_demonstration = false; + + if (current_trajectory.size() > 1) { + demos.push_back(sample_trajectory(current_trajectory, model.parameters.nb_data)); + + original_trajectories.push_back(current_trajectory); + + learn(demos, model); + + gui_state.must_recompute_reproductions = true; + } + + current_trajectory.clear(); + } + } + } + + + // Cleanup + ImGui_ImplGlfwGL2_Shutdown(); + glfwTerminate(); + + return 0; +} diff --git a/src/demo_teleop.cpp b/src/demo_teleop.cpp deleted file mode 100644 index 417942a..0000000 --- a/src/demo_teleop.cpp +++ /dev/null @@ -1,568 +0,0 @@ -/* - * demo_teleop.cpp - * - * Online learning of tphsmm model and teleoperator-like usage scenario. - * - * Authors: Ioannis Havoutis, Sylvain Calinon. - */ - -#define prt(x) std::cout << #x " = '" << x << "'" << std::endl; -#define prt_msize(x) std::cout << #x ", rows: " << x.n_rows << ", cols: " << x.n_cols << std::endl; - -#include <stdio.h> -#include "armadillo" - -#include <GLFW/glfw3.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include "gfx_ui.h" - -#include <pbdlib/gmm.h> -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include <pbdlib/taskparameters.h> -#include <pbdlib/tpdemonstration.h> -#include <pbdlib/tpdpgmm.h> -#include "pbdlib/trajMPC.h" -#include "pbdlib/tptrajMPC.h" - -#include "misc_utils.h" -#include "draw_utils.h" - -#include <vector> -#include <fstream> -#include <iomanip> - -using namespace std; -using namespace pbdlib; -using namespace arma; - -typedef std::vector<float> stdfvec; -typedef std::vector<double> stddvec; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -mat solveReconstruction(TPDPGMM& tpgmm, vec startPoint, float iFactor, int nRecPoints) { - static mat A(4,4), B(4,2); - static float dt = 0.01f; - mat R = eye(2,2) * pow(10.0f, iFactor); - - static mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - static mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - LQR lqr(A,B,dt); - - static std::vector<mat> Q; - - //Get most probable state - colvec p(startPoint); - mat h_i(tpgmm.getProdGMM()->getNumSTATES(), 1); - for (int i=0; i<(int)tpgmm.getProdGMM()->getNumSTATES(); i++){ - h_i.row(i) = trans(tpgmm.getProdGMM()->getCOMPONENTS(i).getPDFValue(p)); - } - uword start_state; - h_i.max(start_state); // prt(start_state); - - mat pred; - pred = tpgmm.predictForwardVariable(nRecPoints,start_state); // prt(pred.t()); - uword imax[nRecPoints]; - for (int t=0; t<nRecPoints; t++){ - vec vTmp = pred.col(t); - vTmp.max(imax[t]); // cout<<imax[t]<<"-"; - } // cout<<endl<<endl; - - //LQR - static vec vTmp(4,fill::zeros); - static mat QTmp(4,4,fill::zeros); - mat Target(4,nRecPoints,fill::zeros); - for (int t=0; t<nRecPoints; t++){ - QTmp.submat(0,0, - tpgmm.getNumVARS()-1 , tpgmm.getNumVARS()-1) = - inv(tpgmm.getProdGMM()->getSIGMA(imax[t]).submat(0,0, tpgmm.getNumVARS()-1, tpgmm.getNumVARS()-1)); - Q.push_back(QTmp); - vTmp.subvec(0,tpgmm.getNumVARS()-1) = tpgmm.getProdGMM()->getMU(imax[t]).subvec(0,tpgmm.getNumVARS()-1); - Target.col(t) = vTmp; - } - lqr.setProblem(R,Q,Target); - static mat S(4,4,fill::zeros); - static vec d(4,fill::zeros); - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - mat rData(2,nRecPoints); - static vec u(2); - static vec X(4,fill::zeros); - X.subvec(0,tpgmm.getNumVARS()-1) = startPoint.rows(0, tpgmm.getNumVARS()-1 ); - for (int t=0; t<nRecPoints; t++){ - rData.col(t) = X.rows(0,1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - - Q.clear(); - return rData; -} - -int main(int argc, char **argv){ - mat refShape = { //reference drawing - {-0.3, -0.3, 0.3, 0.3 }, - {1.0, 0.0 , 0.0, 1.0}}; - float refScale = 50.0; - refShape = refShape + 10.0 / refScale; - refShape = refScale * refShape; - - //Setup TPDPGMM - float minSigma = 200.0f; //1E2; - float lambda = 100.0f; - mat minSIGMA = eye(2,2) * minSigma; - - int nVars = 2; - const int nTps = 1; - - TPDPGMM tpdpgmm(nVars,1,nTps,2,lambda); - TaskParameters tp(nVars,nTps); - vector<TPDemonstration> tpdemos; - vector<mat> repros; - - //Setup LQR - float iFactor = -6.0f; - int nRecPoints = 300; - - float filterAlphaPos = 0.1; - bool stateMerging = false; - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - - GLFWwindow* window = glfwCreateWindow(520, 540, "Teleoperation model", NULL, NULL); - glfwMakeContextCurrent(window); - - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - - ImGuiIO& io = ImGui::GetIO(); - io.Fonts->AddFontDefault(); - ui::init(20.); - ui::Trans2d trans(ImVec2(50,0), // X axis - ImVec2(0,30), // Y axis (expected orthogonal) - ImVec2(60,400)); // position - ImVec4 clear_color = ImColor(240, 240, 240); // white background - ImVector<ImVec2> points, velocities; - vector<vec> pointsV, velocitiesV; - bool adding_line = false; - bool modelExist = false; - bool model_changed = false; - bool dispRef = true; - bool dispDemo = true; - bool dispGMM = true; - bool useFramePRIORS = false; - bool movingRef = false; - bool hoveringRef = false; - int nbPts = 0; - bool init = true; - bool startFlag = false; - bool endFlag = false; - float alphaHandles = 0.2f; - - Ref teleopFrames[nTps]; - - vec tele_g_pos;// robo_g_pos; - tele_g_pos = zeros(2); - - vec framesTmpPos = zeros(2); - vec trParam = ones(2); - TaskParameter tpTmp; - colvec p(nVars, fill::zeros); - mat p_frame(nVars, nTps+1); - mat pred; - mat rData; - - colorCode.push_back(colRed); - colorCode.push_back(colBRGreen); - - bool sample_model_cmd = false; - bool stop_mpc_cmd = false; - - //trajMPC parameters====================== - // Model Settings: - uint nVarsPos = 2; // Number of position variables - uint nDeriv = 2; // Number of derivatives considered - - // TrajMPC Settings: - int mpc_start_state = -1; - int Np = -1; // Number of predictions - int Nc = 30; // Number of control predictions - float mpc_dt = 1.0; // time step considered - float alpha = 10.0; // control cost variable - - colvec Xinit; - HSMM* myHSMM; - HSMM* someHSMM; - GMM_Model* tmpGMM; - GMM_Model* tmpGMM_ex; - TrajMPC* myTrajMPC; - - mat Ad, Bd; - mat TestData; - colvec U; - colvec curPos = {0.0,0.0}; - bool trajMPCrunning = false; - vector<mat> trajMPCruns; - //================================ - - while (!glfwWindowShouldClose(window)){ - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - hoveringRef = false; - - ui::begin(); - trans = ui::affineSimple(0, trans); - hoveringRef = ui::hasFocus()||hoveringRef; - ui::end(); - - teleopFrames[0].p1(0)=trans.pos.x; - teleopFrames[0].p1(1)=ImGui::GetIO().DisplaySize.y - trans.pos.y; - - teleopFrames[0].p2(0)=trans.x.x + trans.pos.x; - teleopFrames[0].p2(1)=ImGui::GetIO().DisplaySize.y - (trans.x.y + trans.pos.y); - - for (int i = 0; i < nTps; ++i) { - teleopFrames[i].updateRef(); - } - - int control_panel_height = 300; - int control_panel_width = 500; - - if (init){ // Init the control panel - ImGui::SetNextWindowPos(ImVec2(2,2)); - ImGui::SetNextWindowCollapsed(true);//true); - } - - init = false; - ImGui::Begin("Control Panel", NULL, - ImVec2(control_panel_width,control_panel_height), 1.0f, ImGuiWindowFlags_NoSavedSettings); - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - - ImGui::Text("Left-click to collect demonstrations."); - ImGui::Text("'S' to sample, 'D' to delete model."); - ImGui::Text("'R' to start MPC, 'T' to stop MPC execution."); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", - (int)tpdemos.size(), (int)nbPts, (int)tpdpgmm.getNumSTATES()); - - ImGui::Separator(); - ImGui::Text("Model learning parameters"); - ImGui::SliderFloat("Min. Sigma", &minSigma, 1E1, 20E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 200.0f); - - ImGui::Checkbox("Display Demos",&dispDemo);ImGui::SameLine(); - ImGui::Checkbox("Plot Gaussians",&dispGMM);ImGui::SameLine(); - - ImGui::Checkbox("State Merging",&stateMerging); - ImGui::SliderFloat("Position Filter a", &filterAlphaPos, 0, 1, "%.2f"); - - ImGui::Separator(); - ImGui::Text("LQR motion generation parameters"); - ImGui::SliderFloat("Control cost", &iFactor, -10, -0.001, "%.4f"); - ImGui::SliderInt("Motion length", &nRecPoints, 10, 1000); - - ImGui::Separator(); - if (ImGui::Button("Clear")){ - tpdemos.clear(); - repros.clear(); - tpdpgmm = TPDPGMM(nVars,1,nTps,2,lambda); - modelExist = false; - nbPts = 0; - - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - trajMPCruns.clear(); - } - ImGui::SameLine(); - if (ImGui::Button("Clear MPC")){ - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - trajMPCruns.clear(); - } - ImGui::Separator(); - - ImGui::SliderInt("MPC start state", &mpc_start_state, -1, 10); - ImGui::SliderInt("MPC n control pred.", &Nc, 1, 100); - ImGui::SliderFloat("MPC time step", &mpc_dt, 0.001, 10.0, "%.3f"); - ImGui::SliderFloat("MPC control cost", &alpha, 0, 1000.0, "%.4f"); - - tpdpgmm.useFramePRIORS(useFramePRIORS); - - if (sample_model_cmd && modelExist){ - if (!trajMPCrunning){ - /*Initialize trajMPC*/ - if (TestData.size()){ - trajMPCruns.push_back(TestData); - } - int nSTATES = tpdpgmm.getHSMM()->getNumSTATES(); - int nVARS = 4; - someHSMM = new HSMM(nSTATES,nVARS); - myHSMM = someHSMM; - myHSMM->setTRANSITION(tpdpgmm.getHSMM()->getTRANSITION()); - myHSMM->setDurationCOMPONENTS(tpdpgmm.getHSMM()->getDurationCOMPONENTS()); - myHSMM->setPRIORS(tpdpgmm.getPRIORS()); - - tmpGMM = tpdpgmm.getTransformedGMM(tp); - tmpGMM_ex = new GMM_Model(nSTATES,nVARS); - - for (int i = 0; i < nSTATES; i++){ // state durations are univariate - tmpGMM_ex->setMU(i, join_vert(tmpGMM->getMU(i),zeros(2,1)) ); - mat sigma = eye(4,4); - sigma.submat(0,0,1,1) = tmpGMM->getSIGMA(i); - tmpGMM_ex->setSIGMA(i, sigma ); - } - myHSMM->setCOMPONENTS(tmpGMM_ex->getCOMPONENTS()); - myHSMM->initializeFwdCalculation(); - - double av_state_duration = 0.0; - for (int i = 0; i < tpdpgmm.getHSMM()->getNumSTATES(); ++i) { - av_state_duration += tpdpgmm.getHSMM()->getDurMU(i)(0); - } - Np = ceil(1.5*(2.0/tpdpgmm.getHSMM()->getNumSTATES()) * av_state_duration); - - if (Nc>=Np){Nc = Np;} - myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); - - // Make sure that the TrajMPC model is correctly initialised by resetting it before starting - myTrajMPC->reset(); - - Ad = myTrajMPC->getSystemDynamics(); - Bd = myTrajMPC->getInputDynamics(); - if (mpc_start_state == -1){ - TestData = join_vert(tele_g_pos,zeros(4,1)); - curPos = vec4({tele_g_pos(0), tele_g_pos(1), 0.0, 0.0}); - }else{ - curPos = myHSMM->getMU(mpc_start_state); - } - trajMPCrunning = true; - }else{ - tmpGMM = tpdpgmm.getTransformedGMM(tp); - for (int i = 0; i < tpdpgmm.getHSMM()->getNumSTATES(); ++i) { - myTrajMPC->setMu(i, join_vert(tmpGMM->getMU(i),zeros(2,1))); - mat sigma = eye(4,4); - sigma.submat(0,0,1,1) = tmpGMM->getSIGMA(i); - myTrajMPC->setSigma(i,sigma); - } - U = myTrajMPC->computeControlCommand(curPos); - // Simulate movement of attractor: - curPos = Ad*curPos + Bd*U; - colvec temp = join_cols(curPos, U); - TestData = join_rows(TestData, temp); - if (stop_mpc_cmd){ - if (TestData.size()){ - //trajMPCruns.push_back(TestData); - } - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - sample_model_cmd = false; - stop_mpc_cmd = false; - repros.clear(); - } - } - // } - } - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - - tele_g_pos = tele_g_pos + filterAlphaPos * - ( vec({mouse_pos_in_canvas.x, mouse_pos_in_canvas.y}) - tele_g_pos); - - if(hoveringRef&&ImGui::GetIO().MouseClicked[0]){ - movingRef = true; - repros.clear(); - } - if(movingRef&&!ImGui::GetIO().MouseDown[0]) - movingRef = false; - - if (movingRef&&modelExist && !ImGui::GetIO().MouseClicked[0]) { - for(int i=0;i<nTps;i++) { - tpTmp.A = teleopFrames[i].A; - tpTmp.b = teleopFrames[i].b; - tp.setTaskParameters(i,tpTmp); - } - tpdpgmm.getTransformedGMM(tp,INVERTIBLE); - - // trParam = refFrame[1].b-refFrame[0].b; - tpdpgmm.updateTransition(trParam); - } - - if (!movingRef && (ImGui::GetIO().MousePos.x < ImGui::GetIO().DisplaySize.x)) { //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; - startFlag = true; - endFlag = false; - } - if (!ImGui::GetIO().MouseDown[0]) endFlag = true; - - if (adding_line){ //Trajectory recording - nbPts++; - p = tele_g_pos; - pointsV.push_back(tele_g_pos); - - for(int i=0;i<nTps;i++) { - p_frame.col(i) = teleopFrames[i].A.t()*(p-teleopFrames[i].b); - tpTmp.A = teleopFrames[i].A; - tpTmp.b = teleopFrames[i].b; - tp.setTaskParameters(i,tpTmp); - } - // also add the position in absolute space - trParam = ones(2); - p_frame.col(nTps) = p; - - tpdpgmm.addDatapoints(p_frame,trParam,startFlag,endFlag,lambda,minSigma); - tpdpgmm.getTransformedGMM(tp,INVERTIBLE); - - startFlag = false; - modelExist = true; - - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - model_changed = true; - - if (stateMerging){ - bool merged = true; - while (merged) - { - merged = tpdpgmm.reduceStates(); - tpdpgmm.getTransformedGMM(tp, INVERTIBLE); - tpdpgmm.updateTransition(trParam); - } - }else{ - tpdpgmm.updateTransition(trParam); - } - - Demonstration demo = Demonstration(nVars,pointsV.size()); - for (int t=0; t<(int)pointsV.size(); t++){ - demo.getDatapoints().getData()(0,t) = pointsV[t](0); - demo.getDatapoints().getData()(1,t) = pointsV[t](1); - } - - TPDemonstration tmptpdemo( demo.getDatapoints().getData(), tp); - tpdemos.push_back(tmptpdemo); - - pointsV.clear(); - } - } - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_D] ){ - cout << "D pressed - Cleaning up." << endl; - tpdemos.clear(); - repros.clear(); - tpdpgmm = TPDPGMM(nVars,1,nTps,2,lambda); - modelExist = false; - nbPts = 0; - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_S] && modelExist){ - cout << "S pressed - Sampling model." << endl; - repros.clear(); - rData = solveReconstruction(tpdpgmm, tele_g_pos, iFactor, nRecPoints); - repros.push_back(rData); - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_R] && modelExist){ - cout << "R pressed - Asking remote to sample model." << endl; - sample_model_cmd = true; - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_T] && modelExist){ - cout << "T pressed - Asking remote to stop MPC." << endl; - stop_mpc_cmd = true; - } - - ImGui::End(); - - //GUI rendering ======================================================================= - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - drawStrip(pointsV, colBlack, 2.0); - - //Draw all demos - if (dispDemo) { - for (int i=0; i<(int)tpdemos.size(); i++){ - mat tmpStrip = tpdemos[i].getDataInTaskParameters(); - for (int j=0; j<tmpStrip.n_cols; j++) { - tmpStrip.col(j) = tp.getTaskParameters(0).A*tmpStrip.col(j); - } - tmpStrip.each_col() += tp.getTaskParameters(0).b; - drawStrip(tmpStrip, colLightGray, 2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpdpgmm.getNumFRAMES(); k++) { - glColor3f(38.0/255.0, 57.0/255.0, 76.0/255.0); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point = teleopFrames[k].b + teleopFrames[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians - if (modelExist&&dispGMM){ - drawGaussians(tpdpgmm, teleopFrames, colorCode); - } - - //Draw repros - drawStrip(repros,colBlue,3.0); - - //draw position - drawSquare(tele_g_pos(0), tele_g_pos(1), 10, 2.0, colRed); - - //draw sandbox - drawSquare(260,260,500,1.0,vec3({.7,.7,.7}),0); - - //Draw MPC - drawStrip(trajMPCruns,vec3({0.8,0.8,0.8}),2); - if (TestData.size()){ - drawStrip(TestData,vec3({0,0,0.9}),3.0); - } - if (curPos.size()){ // MPC state - drawSquare(curPos(0),curPos(1),10,1.0,vec3({0,0,1})); - } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; -} diff --git a/src/demo_tp_multiLqr.cpp b/src/demo_tp_multiLqr.cpp deleted file mode 100644 index a276006..0000000 --- a/src/demo_tp_multiLqr.cpp +++ /dev/null @@ -1,1278 +0,0 @@ -/* - * demo_tp_multiLQR.cpp - * - * Online tp-hsmm and tp-gmm with lqr-based trajectory generation - * and multiframe-lqr trajectory generation. - * - * Authors: Sylvain Calinon, Ioannis Havoutis - */ - -#define prt(x) std::cout << #x " = '" << x << "'" << std::endl; -#define prt_msize(x) std::cout << #x ", rows: " << x.n_rows << ", cols: " << x.n_cols << std::endl; - -#include <stdio.h> - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/tpdpgmm.h> - -#include <GLFW/glfw3.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include <pbdlib/taskparameters.h> -#include "pbdlib/trajMPC.h" - -using namespace std; -using namespace pbdlib; -using namespace arma; - -class Remap { -public: - Remap(float input_min, float input_max, - float output_min, float output_max) -:_input_min(input_min), _input_max(input_max), - _output_min(output_min), _output_max(output_max){}; - -private: - float _input_min, _input_max, _output_min, _output_max; - -public: - float map( float input ) { - return _output_min + (input - _input_min) * - ((_output_max - _output_min) / (_input_max - _input_min)); - } - - float mapInv( float input ) { - return _input_min + (input - _output_min) * - ((_input_max - _input_min) / (_output_max - _output_min)); - } -}; - -class Ref { -public: - vec p1; - vec p2; - - mat A; - vec b; - - void updateRef() { - b = p1; - A = mat(2,2); - vec delta = p2-p1; - delta = delta/arma::norm(delta); - A(0,0) = delta(0); - A(1,0) = delta(1); - A(0,1) = -delta(1); - A(1,1) = delta(0); - } -}; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -void drawStrip(mat points, vec3 color, float linewidth); -void drawStrip(vector<mat> points, vec3 color, float linewidth); -void drawStrip(ImVector<ImVec2> &points, vec3 color, float linewidth); -void drawGaussians(TPDPGMM &tpgmm, Ref refFrame[], mat colorM); -void drawGaussians(TPGMM &tpgmm, Ref refFrame[], mat colorM); - -void drawProdGaussians(TPDPGMM &tpgmm, vec color); -void drawSquare(int pos_x, int pos_y, int square_edge, float lineWidth = 5.0); - -mat solveReconstructionMFtpgmm(TPGMM& tpgmm, TaskParameters& tp, - vec startPoint, int iFactor, int nRecPoints) -//Batch solution of a lqr acting in multiple frames, vanilla tpgmm version -{ - int nbVarPos = 2; - int nbData = nRecPoints; - prt(nRecPoints); - int nbVar = tpgmm.getNumVARS(); -// prt(nbVar); - - mat A(4,4), B(4,2); - float dt = 0.01f; - - //Dynamical System settings (discrete version), see Eq. (33) - mat A1d; A1d << 1 << dt << endr << 0 << 1 << endr; - mat B1d; B1d << 0 << endr << dt << endr; - A = kron(A1d, eye(nbVarPos,nbVarPos)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(nbVarPos,nbVarPos)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - - //Control cost matrix - mat R = eye(nbVarPos,nbVarPos) * pow(10.0,iFactor); - R = kron(eye(nbData-1,nbData-1),R); - - //Construct Su and Sx matrices, see Eq. (35) - mat Su = zeros(nbVar*nbData, nbVarPos*(nbData-1)); - mat Sx = kron(ones(nbData,1), eye(nbVar,nbVar)); - mat M = B; - - for (uint n=2; n<nbData+1; n++) { - // Build Sx matrix - Sx.rows((n-1)*nbVar, nbData*nbVar - 1) - = Sx.rows((n-1)*nbVar, nbData*nbVar - 1) * A; - // Build Su matrix - Su(span((n-1)*nbVar, (n*nbVar) - 1), span(0, ((n-1)*nbVarPos) - 1)) = M; - M = join_horiz( A * M.cols(0,nbVarPos-1), M); - } - - uint nbFrames = tp.getNumTASKPARAMETERS(); - uint nbStates = tpgmm.getNumSTATES(); -// prt(nbFrames); -// prt(nbStates); - - //GMM projection, see Eq. (5) - vector<GMM_Model> p_gmm; - for (uint i = 0; i < nbFrames; ++i){ - p_gmm.push_back(GMM_Model(nbStates,nbVar)); - } - - for (uint i = 0; i < nbStates; ++i) { - for (uint m = 0; m < nbFrames; ++m){ - p_gmm[m].setMU(i, tp.getTaskParameters(m).A * tpgmm.getGMMS(m).getMU(i) - + tp.getTaskParameters(m).b); - p_gmm[m].setSIGMA(i, tp.getTaskParameters(m).A * tpgmm.getGMMS(m).getSIGMA(i) * tp.getTaskParameters(m).A.t()); - } - } - - -// get state path from first demo - mat h = tpgmm.getGAMMA2(); -prt_msize(h); - - mat pred = h; - uword imax[nRecPoints]; - - for (int t=0; t<nRecPoints; t++){ - vec vTmp = pred.col(t); - vTmp.max(imax[t]); - cout<<imax[t]<<"-"; - } - cout<<endl<<endl; - - vector<mat> MuQ, SigmaQ; - //Build a reference trajectory for each frame, see Eq. (27) - mat invSigmaQ = zeros(nbVar*nbData, nbVar*nbData); - for (uint m=0; m<nbFrames; m++){ - mat mtemp(nbData*nbVar,1); - for (int j = 0; j < nRecPoints; ++j) { -// mtemp = join_vert(mtemp, p_gmm[m].getMU( imax[j] )); - mtemp.submat(j*nbVar, 0, ((j+1)*nbVar)-1, 0) = p_gmm[m].getMU( imax[j] ); - } -// prt_msize(mtemp); - MuQ.push_back(mtemp); - mat ctemp (nbVar, nbData*nbVar); - for (int j = 0; j < nRecPoints; ++j) { -// ctemp = join_horiz(ctemp, p_gmm[m].getSIGMA( imax[j] )); - ctemp.submat(0, j*nbVar, nbVar-1, ( (j+1)*nbVar)-1 ) = p_gmm[m].getSIGMA( imax[j] ); - } -// prt_msize(ctemp); - mat tA,tB,tC; - tA = kron(ones(nbData,1), eye(nbVar,nbVar)); - tB = ctemp; - tC = kron(eye(nbData,nbData), ones(nbVar,nbVar)); - SigmaQ.push_back( (tA * tB) % tC ); - invSigmaQ = invSigmaQ + inv(SigmaQ.back()); - } - - //%Batch LQR (unconstrained linear MPC), see Eq. (37) - mat SuInvSigmaQ = Su.t() * invSigmaQ; - mat Rq = SuInvSigmaQ * Su + R; - colvec X(startPoint); - mat rq = zeros(nbVar*nbData,1); - for (uint m = 0; m<nbFrames; m++) { - rq = rq + solve(SigmaQ[m], MuQ[m] - Sx*X); - } - rq = Su.t() * rq; - mat u = solve(Rq, rq); - - mat Data = reshape(Sx*X+Su*u, nbVar, nbData); - -// prt_msize(Data); - - return Data.rows(0,1); -} - -mat solveReconstructionMF(TPDPGMM& tpgmm, TaskParameters& tp, - vec startPoint,float iFactor, int nRecPoints) -//Batch solution of a lqr acting in multiple frames, -{ - int nbVarPos = 2; - int nbData = nRecPoints; - int nbVar = tpgmm.getNumVARS(); -// prt(nbVar); - - mat A(4,4), B(4,2); - float dt = 0.01f; - - //Dynamical System settings (discrete version), see Eq. (33) - mat A1d; A1d << 1 << dt << endr << 0 << 1 << endr; - mat B1d; B1d << 0 << endr << dt << endr; - A = kron(A1d, eye(nbVarPos,nbVarPos)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(nbVarPos,nbVarPos)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - - //Control cost matrix - mat R = eye(nbVarPos,nbVarPos) * pow(10.0f,iFactor); - R = kron(eye(nbData-1,nbData-1),R); - - //Construct Su and Sx matrices, see Eq. (35) - mat Su = zeros(nbVar*nbData, nbVarPos*(nbData-1)); - mat Sx = kron(ones(nbData,1), eye(nbVar,nbVar)); - mat M = B; - - for (uint n=2; n<nbData+1; n++) { - // Build Sx matrix - Sx.rows((n-1)*nbVar, nbData*nbVar - 1) - = Sx.rows((n-1)*nbVar, nbData*nbVar - 1) * A; - // Build Su matrix - Su(span((n-1)*nbVar, (n*nbVar) - 1), span(0, ((n-1)*nbVarPos) - 1)) = M; - M = join_horiz( A * M.cols(0,nbVarPos-1), M); - } - - uint nbFrames = tp.getNumTASKPARAMETERS(); - uint nbStates = tpgmm.getNumSTATES(); -// prt(nbFrames); -// prt(nbStates); - - //GMM projection, see Eq. (5) - vector<GMM_Model> p_gmm; - for (uint i = 0; i < nbFrames; ++i){ - p_gmm.push_back(GMM_Model(nbStates,nbVar)); - } - - for (uint i = 0; i < nbStates; ++i) { - for (uint m = 0; m < nbFrames; ++m){ - p_gmm[m].setMU(i, tp.getTaskParameters(m).A * tpgmm.getGMMS(m).getMU(i) - + tp.getTaskParameters(m).b); - p_gmm[m].setSIGMA(i, tp.getTaskParameters(m).A * tpgmm.getGMMS(m).getSIGMA(i) * tp.getTaskParameters(m).A.t()); - } - } - - // -// std::vector<mat> Q; -// - //get most probable state - colvec p(startPoint); - mat h_i(tpgmm.getProdGMM()->getNumSTATES(), 1); - for (int i=0; i<(int)tpgmm.getProdGMM()->getNumSTATES(); i++){ - h_i.row(i) = trans(tpgmm.getProdGMM()->getCOMPONENTS(i).getPDFValue(p)); - } - uword start_state; - h_i.max(start_state); - // cout << "ss :" << start_state << endl; - - mat pred; - pred = tpgmm.predictForwardVariable(nRecPoints,start_state); - - // cout << "Alpha Predictions" << endl << pred.t() << endl; - - uword imax[nRecPoints]; - - for (int t=0; t<nRecPoints; t++){ - vec vTmp = pred.col(t); - vTmp.max(imax[t]); -// cout<<imax[t]<<"-"; - } -// cout<<endl<<endl; - - vector<mat> MuQ, SigmaQ; - //Build a reference trajectory for each frame, see Eq. (27) - mat invSigmaQ = zeros(nbVar*nbData, nbVar*nbData); - for (uint m=0; m<nbFrames; m++){ - mat mtemp(nbData*nbVar,1); - for (int j = 0; j < nRecPoints; ++j) { -// mtemp = join_vert(mtemp, p_gmm[m].getMU( imax[j] )); - mtemp.submat(j*nbVar, 0, ((j+1)*nbVar)-1, 0) = p_gmm[m].getMU( imax[j] ); - } -// prt_msize(mtemp); - MuQ.push_back(mtemp); - mat ctemp (nbVar, nbData*nbVar); - for (int j = 0; j < nRecPoints; ++j) { -// ctemp = join_horiz(ctemp, p_gmm[m].getSIGMA( imax[j] )); - ctemp.submat(0, j*nbVar, nbVar-1, ( (j+1)*nbVar)-1 ) = p_gmm[m].getSIGMA( imax[j] ); - } -// prt_msize(ctemp); - mat tA,tB,tC; - tA = kron(ones(nbData,1), eye(nbVar,nbVar)); - tB = ctemp; - tC = kron(eye(nbData,nbData), ones(nbVar,nbVar)); - SigmaQ.push_back( (tA * tB) % tC ); - invSigmaQ = invSigmaQ + inv(SigmaQ.back()); - } - - //%Batch LQR (unconstrained linear MPC), see Eq. (37) - mat SuInvSigmaQ = Su.t() * invSigmaQ; - mat Rq = SuInvSigmaQ * Su + R; - colvec X(startPoint); - mat rq = zeros(nbVar*nbData,1); - for (uint m = 0; m<nbFrames; m++) { - rq = rq + solve(SigmaQ[m], MuQ[m] - Sx*X); - } - rq = Su.t() * rq; - mat u = solve(Rq, rq); - - mat Data = reshape(Sx*X+Su*u, nbVar, nbData); - -// prt_msize(Data); - - return Data.rows(0,1); -} - -mat solveReconstruction(TPDPGMM& tpgmm,vec startPoint,float iFactor, int nRecPoints) -{ - if (startPoint.size() != tpgmm.getNumVARS()) - { - prt("Start point size not equal to number of variables"); - prt(startPoint.size()); - prt(tpgmm.getNumVARS()); - startPoint = join_cols(startPoint, zeros<vec>(2)); - } - - mat A(4,4), B(4,2); - float dt = 0.01f; - - mat R = eye(2,2) * pow(10.0f,iFactor); - - mat A1d; A1d << 0 << 1 << endr << 0 << 0 << endr; - mat B1d; B1d << 0 << endr << 1 << endr; - A = kron(A1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - B = kron(B1d, eye(2,2)); //See Eq. (5.1.1) in doc/TechnicalReport.pdf - LQR lqr(A,B,dt); - - std::vector<mat> Q; - - //get most probable state - colvec p(startPoint); - mat h_i(tpgmm.getProdGMM()->getNumSTATES(), 1); - for (int i=0; i<(int)tpgmm.getProdGMM()->getNumSTATES(); i++){ - h_i.row(i) = trans(tpgmm.getProdGMM()->getCOMPONENTS(i).getPDFValue(p)); - } - uword start_state; - h_i.max(start_state); - // cout << "ss :" << start_state << endl; - - mat pred; - pred = tpgmm.predictForwardVariable(nRecPoints,start_state); - - // cout << "Alpha Predictions" << endl << pred.t() << endl; - - uword imax[nRecPoints]; - - prt("solveRec"); - for (int t=0; t<nRecPoints; t++){ - vec vTmp = pred.col(t); - vTmp.max(imax[t]); - cout<<imax[t]<<"-"; - } - cout<<endl<<endl; - - //LQR - vec vTmp(4,fill::zeros); - mat QTmp(4,4,fill::zeros); - mat Target(4,nRecPoints,fill::zeros); - for (int t=0; t<nRecPoints; t++){ - QTmp.submat(0,0, - tpgmm.getNumVARS()-1 , tpgmm.getNumVARS()-1) = - inv(tpgmm.getProdGMM()->getSIGMA(imax[t]).submat(0,0, tpgmm.getNumVARS()-1, tpgmm.getNumVARS()-1)); - Q.push_back(QTmp); - vTmp.subvec(0,tpgmm.getNumVARS()-1) = tpgmm.getProdGMM()->getMU(imax[t]).subvec(0,tpgmm.getNumVARS()-1); - Target.col(t) = vTmp; - } - lqr.setProblem(R,Q,Target); - mat S(4,4,fill::zeros); - vec d(4,fill::zeros); - //lqr.evaluate_gains_finiteHorizon(S,d); - lqr.evaluate_gains_infiniteHorizon(); - - //Retrieve data - - mat rData(2,nRecPoints); - //vec x = demo.getDatapoints().getData().col(0); - //vec dx(2,fill::zeros), ddx(2); - //for (int t=0; t<points.size(); t++){ - //rData.col(t) = x; - //ddx = 100.0f * (Target.submat(0,t,1,t)-x) - sqrtf(2*100.0f) * dx; - //ddx = lqr.getGains().at(t).cols(0,1) * (Target.submat(0,t,1,t)-x) - lqr.getGains().at(t).cols(2,3) * dx; - //ddx += lqr.getFF().at(t); - //dx += ddx * dt; - //x += dx * dt; - //} - - vec u(2); - vec X(4,fill::zeros); - X.subvec(0,tpgmm.getNumVARS()-1) = startPoint.rows(0, tpgmm.getNumVARS()-1 ); - for (int t=0; t<nRecPoints; t++){ - rData.col(t) = X.rows(0,1); - u = lqr.getGains().at(t) * (Target.col(t)-X); - X += (A*X+B*u) * dt; - } - - //Clean up - - Q.clear(); - return rData; -} - -int main(int argc, char **argv){ - - //trajMPC params====================== - // Model Settings: - uint nVarsPos = 2; // Number of position variables - uint nDeriv = 2; // Number of derivatives considered - - // TrajMPC Settings: - int mpc_start_state = 0; - int Np = 70; // Number of predictions - int Nc = 30; // Number of control predictions - int N = 600; // Number of iterations of simulation - float mpc_dt = 0.01; // time step considered - float alpha = 0.001; // control cost variable - - colvec Xinit; - HSMM* myHSMM; - TrajMPC* myTrajMPC; - - mat Ad, Bd; - mat TestData; - colvec U; - colvec curPos = {0.0,0.0}; - bool trajMPCrunning = false; - //================================ - - //reference drawings - mat refShape = { -// {-0.5, 1.5, 0.0, 0.0, 0.0, 0.0}, -// { 0.0, 0.0, 0.0,-0.5, 0.0, 1.0} - {-0.3, -0.3, 0.3, 0.3 }, - {2.0, 0.0 , 0.0, 2.0} - }; - float refScale = 50.0; - refShape = refShape + 10.0 / refScale; - refShape = refScale * refShape; - - //Setup TPDPGMM - float minSigma = 20; //1E2; - float lambda = 100.0f; -// int nRecPoints = 300; - - int nVars = 4;//2; - int N_TPS = 2; - - TPDPGMM tpdpgmm(nVars,1,N_TPS,2,lambda); - - TaskParameters tp(4,N_TPS); - - mat minSIGMA = eye(2,2) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros, MFrepros, vanilla_tpgmm_repros, trajMPCrepros, trajMPCruns; - - //TPgmm - TPGMM* tpgmm_vanilla; - std::vector<TPDemonstration> TPdemos; // Vector to hold demonstrations - int tpgmm_vannila_nStates = 3; - int tpgmm_vannila_rfactor = -5; - - //Setup LQR - float iFactor = -5; - int nRecPoints = 300; -// float dt = 0.01f; //0.033 - -// float filterAlpha = 1.0; - float filterAlphaPos = 0.05; - - bool stateMerging = false; - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 820, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(154, 154, 154); - - ImVector<ImVec2> points, velocities; - bool adding_line = false; - bool modelExist = false; - bool dispRef = true; - bool dispDemo = false; - bool dispGMM = true; - bool useFramePRIORS = false; - bool movingRef = false; - bool hoveringRef = false; - int nbPts = 0; - bool init = true; - bool startFlag = false; - bool endFlag = false; - float alphaHandles = 0.2f; - Ref refFrame[2]; - refFrame[0].p1 = zeros(2); - refFrame[0].p2 = zeros(2); - refFrame[1].p1 = vec(2); - refFrame[1].p2 = vec(2); - - //plotting color - mat colorM = {{0.f,0.6211f,0.8164f}, - {0.9883f,0.4531f,0.f}, - {0.7422f,0.8555f,0.2227f}, - {0.1211f,0.5391f,0.4375f}, - {0.9961f,0.8789f,0.1016f}}; - vec3 colBlack = {0.0, 0.0, 0.0}; - vec3 colRed = {1.0, 0.0, 0.0}; - vec3 colGreen = {0.0, 1.0, 0.0}; - vec3 colBlue = {0.0, 0.0, 1.0}; - vec3 colGray = {0.3f, 0.3f, 0.3f}; - - float currTime, prevTime; - - ImVec2 teleop_pointer_position; - bool communication_live = true; - - while (!glfwWindowShouldClose(window)){ - - // cout << "Time: " << ImGui::GetTime() << endl; - prevTime = currTime; - currTime = ImGui::GetTime(); - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - hoveringRef = false; - //Control panel GUI - if(init)ImGui::SetNextWindowPos(ImVec2(300,700)); - - ImGui::Begin("r1p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "p1"); - vec tmpPos = refFrame[0].p1; - refFrame[0].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[0].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(400,700)); - ImGui::Begin("r1p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "r1"); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[0].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(400,100)); - ImGui::Begin("r2p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "p2"); - tmpPos = refFrame[1].p1; - refFrame[1].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[1].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(300,100)); - ImGui::Begin("r2p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "r2"); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[1].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - refFrame[0].updateRef(); - refFrame[1].updateRef(); - - - int control_panel_height = 300; - int control_panel_width = 400; - - if (init){ - ImGui::SetNextWindowPos(ImVec2( - (ImGui::GetIO().DisplaySize.x - control_panel_width)/2, 2) ); - ImGui::SetNextWindowCollapsed(true); - teleop_pointer_position = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - } - - init = false; - - ImGui::Begin("Control Panel", NULL, - ImVec2(control_panel_width,control_panel_height), 1.0f, -// ImGuiWindowFlags_NoTitleBar| -// ImGuiWindowFlags_NoResize| -// ImGuiWindowFlags_NoMove| - ImGuiWindowFlags_NoSavedSettings); - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - MFrepros.clear(); - trajMPCrepros.clear(); - tpdpgmm = TPDPGMM(nVars,1,N_TPS,2,lambda); - modelExist = false; - nbPts = 0; - - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - trajMPCruns.clear(); - - TPdemos.clear(); - tpgmm_vanilla = NULL; - vanilla_tpgmm_repros.clear(); - } - ImGui::SameLine(); - if (ImGui::Button("re_MF")){ - MFrepros.clear(); - mat MFrData = solveReconstructionMF(tpdpgmm, tp, - tpdpgmm.getProdGMM()->getMU(0), iFactor, nRecPoints); - MFrepros.push_back(MFrData); - } - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("Press space-bar to cut communication."); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), - // points.size(), - nbPts, (int)tpdpgmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 20E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 200.0f); - - ImGui::Checkbox("Display Demo",&dispDemo);ImGui::SameLine(); - ImGui::Checkbox("Plot Gaussian",&dispGMM);ImGui::SameLine(); - - ImGui::Checkbox("State Merging",&stateMerging); -// ImGui::SliderFloat("Fil. a pos", &filterAlphaPos, 0, 1, "%.2f"); - - ImGui::Separator(); - ImGui::SliderInt("MPC start state", &mpc_start_state, -1, tpdpgmm.getProdGMM()->getNumSTATES()); - ImGui::SliderInt("MPC n pred.", &Np, 1, 100); - ImGui::SliderInt("MPC n control pred.", &Nc, 1, 100); - //ImGui::SliderInt("MPC n sim. itter.", &N, 1, 1000); - ImGui::SliderFloat("MPC time step", &mpc_dt, 0.001, 0.1, "%.3f"); - ImGui::SliderFloat("MPC control cost", &alpha, 0.0001, 0.1, "%.4f"); - - ImGui::Separator(); - ImGui::SliderFloat("rFactor", &iFactor, -10, -0.001, "%.4f"); - ImGui::SliderInt("nRecPoints", &nRecPoints, 10, 1000); - - tpdpgmm.useFramePRIORS(useFramePRIORS); - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - - ImVec2 mouse_vel_in_canvas; - - if(hoveringRef&&ImGui::GetIO().MouseClicked[0]) - movingRef = true; - if(movingRef&&!ImGui::GetIO().MouseDown[0]) - movingRef = false; - - if(movingRef&&modelExist&& !ImGui::GetIO().MouseClicked[0]) - { - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { -// if (nVars == 2) { -// tpTmp.A = refFrame[i].A; -// tpTmp.b = refFrame[i].b; -// }else if (nVars == 4) { - mat a; a << 1 << 0 << endr << 0 << 1 << endr; - tpTmp.A = kron(a, refFrame[i].A); - tpTmp.b = join_cols(refFrame[i].b, zeros(2,1)); - //tpTmp.b = join_cols(refFrame[i].b, refFrame[i].b); - // cout << "Ai" << refFrame[i].A << endl; - // cout << "A" << tpTmp.A << endl; - // cout << "b" << tpTmp.b << endl; -// } - - tp.setTaskParameters(i,tpTmp); - } - - tpdpgmm.getTransformedGMM(tp,INVERTIBLE); - - vec trParam = ones(2); -// trParam = refFrame[1].b-refFrame[0].b; - tpdpgmm.updateTransition(trParam); - - repros.clear(); - - mat rData = solveReconstruction(tpdpgmm,tpdpgmm.getProdGMM()->getMU(0),iFactor,nRecPoints); - repros.push_back(rData); - -// MFrepros.clear(); -// mat MFrData = solveReconstructionMF(tpgmm, tp, -// tpgmm.getProdGMM()->getMU(0), iFactor, nRecPoints); -// MFrepros.push_back(MFrData); - - } - - - if ( -// (ImGui::GetIO().MousePos.x< control_panel_width +2 && -// ImGui::GetIO().MousePos.y< control_panel_height +2)==0 && - !movingRef - && (ImGui::GetIO().MousePos.x < ImGui::GetIO().DisplaySize.x/2.0)){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; -// trajMPCrunning = false; - startFlag = true; - endFlag = false; - if (!modelExist){ - colvec p(nVars, fill::zeros); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - comps.clear(); - } - } - if (!ImGui::GetIO().MouseDown[0]) endFlag = true; - - if (adding_line){ //Trajectory recording - nbPts++; - vec p(2); - vec v(2); - if ((int)points.size() < 2) { - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - }else{ - p(0) = points.back().x + filterAlphaPos * - ( mouse_pos_in_canvas.x - points.back().x); - p(1) = points.back().y + filterAlphaPos * - ( mouse_pos_in_canvas.y - points.back().y); - } - - mouse_pos_in_canvas.x = p(0); - mouse_pos_in_canvas.y = p(1); - points.push_back(mouse_pos_in_canvas); - - if ((int)points.size() < 2){ - v(0) = v(1) = 0.0; - } else { -// float timeDt = 0.01;//currTime - prevTime; - float timeDt = currTime - prevTime; -// float timeDt = mpc_dt; - -// if (timeDt == 0.0) -// { -// throw std::invalid_argument("Error: dt = 0."); -// } -// v(0) = velocities.back().x + filterAlpha * -// ( ((p(0) - points[(int)points.size() - 2].x)/timeDt) - -// velocities.back().x); -// v(1) = velocities.back().y + filterAlpha * -// ( ((p(1) - points[(int)points.size() - 2].y)/timeDt) - -// velocities.back().y); - v(0) = (points.back().x - points[(int)points.size() - 2].x)/timeDt; - v(1) = (points.back().y - points[(int)points.size() - 2].y)/timeDt; - } - - mouse_vel_in_canvas.x = v(0); - mouse_vel_in_canvas.y = v(1); - velocities.push_back(mouse_vel_in_canvas); - - mat p_frame(nVars, N_TPS+1); - - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { -// if (nVars == 2) { -// p_frame.col(i) = refFrame[i].A.t()*(p-refFrame[i].b); -// tpTmp.A = refFrame[i].A; -// tpTmp.b = refFrame[i].b; -// }else if (nVars == 4) { - p_frame.col(i) = join_cols( refFrame[i].A.t()*(p-refFrame[i].b), - refFrame[i].A.t()*(v) ); -// refFrame[i].A.t()*(v-refFrame[i].b) ); - mat a; a << 1 << 0 << endr << 0 << 1 << endr; - tpTmp.A = kron(a, refFrame[i].A); - tpTmp.b = join_cols(refFrame[i].b, zeros(2,1)); -// tpTmp.b = join_cols(refFrame[i].b, refFrame[i].b); - // cout << "Ai" << refFrame[i].A << endl; - // cout << "A" << tpTmp.A << endl; - // cout << "b" << tpTmp.b << endl; -// } - - tp.setTaskParameters(i,tpTmp); - } - // also add the position in absolute space - - vec trParam; - trParam = ones(2); -// trParam = refFrame[1].b-refFrame[0].b; -// if (nVars == 2) { -// p_frame.col(N_TPS) = p; -// }else if (nVars == 4) { - p_frame.col(N_TPS) = join_cols( p, v); -// } - - tpdpgmm.addDatapoints(p_frame,trParam,startFlag,endFlag,lambda,minSigma); - tpdpgmm.getTransformedGMM(tp,INVERTIBLE); - - startFlag = false; - modelExist = true; - - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - - if (stateMerging){ - bool merged = true; - while (merged) - { - merged = tpdpgmm.reduceStates(); - tpdpgmm.getTransformedGMM(tp, INVERTIBLE); - tpdpgmm.updateTransition(trParam); - } - }else{ - tpdpgmm.updateTransition(trParam); - } - - //Add demonstration - Demonstration demo = Demonstration(nVars,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; -// if (nVars==4){ - demo.getDatapoints().getData()(2,t) = velocities[t].x; - demo.getDatapoints().getData()(3,t) = velocities[t].y; -// } - } - demo.saveInFile("demoMotion.txt"); - demos.push_back(demo); - - // tpgmm vannila data - TPDemonstration tmpTpDemo(demo.getDatapoints().getData(),tp); // Temp variable to push individual demonstrations - TPdemos.push_back(tmpTpDemo); - - //Reconstruction - repros.clear(); - - mat pred = tpdpgmm.predictForwardVariable(1,0); // make sure that vars are set up - - mat rData = solveReconstruction(tpdpgmm,tpdpgmm.getProdGMM()->getMU(0),iFactor,nRecPoints); - repros.push_back(rData); - - MFrepros.clear(); - mat MFrData = solveReconstructionMF(tpdpgmm, tp, - tpdpgmm.getProdGMM()->getMU(0), iFactor, nRecPoints); - MFrepros.push_back(MFrData); - - points.clear(); - velocities.clear(); - } - - } - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_SPACE] ){ - ImGui::SetNextWindowPos(ImVec2( (ImGui::GetIO().DisplaySize.x / 2) - (164 / 2),400)); - ImGui::Begin("Info", NULL, ImVec2(164,40), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - ImGui::TextColored(ImVec4(1.0,0.0,0.0,1.0), "Communication down!"); - ImGui::End(); - if (communication_live&&modelExist){ - if (TestData.size()){ - trajMPCruns.push_back(TestData); - } -// Xinit = tpgmm.getProdGMM()->getMU(mpc_start_state); - Xinit = vec4({mouse_pos_in_canvas.x, mouse_pos_in_canvas.y, - mouse_vel_in_canvas.x, mouse_vel_in_canvas.y}); -// prt(Xinit); - myHSMM = tpdpgmm.getHSMM(); - double av_state_duration = 0.0; - for (int i = 0; i < myHSMM->getNumSTATES(); ++i) { - av_state_duration += myHSMM->getDurMU(i)(0); -// prt(myHSMM->getDurMU(i)(0)); - } -// prt(av_state_duration); -// prt( (2.0/myHSMM->getNumSTATES()) * av_state_duration); - Np = ceil(1.5*(2.0/myHSMM->getNumSTATES()) * av_state_duration); - myHSMM->setCOMPONENTS(tpdpgmm.getProdGMM()->getCOMPONENTS()); - if (Nc>=Np){Nc = Np;} - myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); -// myTrajMPC = new TpTrajMPC(&tpgmm, &tp, -// myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); - - // Make sure that the TrajMPC model is correclty initialized by resetting it before starting - myTrajMPC->reset(); - curPos = Xinit; - Ad = myTrajMPC->getSystemDynamics(); - Bd = myTrajMPC->getInputDynamics(); - if (mpc_start_state == -1){ - TestData = curPos;}else{ - curPos = myHSMM->getMU(mpc_start_state); - } - trajMPCrunning = true; - prt(endl << tpdpgmm.getHSMM()->getTRANSITION()); - }else{ - // do trajMPC step - if (trajMPCrunning){ - // Make step: - U = myTrajMPC->computeControlCommand(curPos); - // Simulate movement of attractor: - curPos = Ad*curPos + Bd*U; - TestData = join_rows(TestData, curPos); -// prt(myTrajMPC->getq()); - } - } - communication_live = false; - }else{ - communication_live = true; - trajMPCrunning = false; - TestData.clear(); - } - - if (communication_live){ - float kp = 0.50; - teleop_pointer_position.x += - kp*(mouse_pos_in_canvas.x - teleop_pointer_position.x); - teleop_pointer_position.y += - kp*(mouse_pos_in_canvas.y - teleop_pointer_position.y); - }else{ - teleop_pointer_position.x = curPos(0); - teleop_pointer_position.y = curPos(1); - } - - - //=================================================================== -// if (ImGui::Button("trajMPC")){ -// if (TestData.size()){ -// trajMPCruns.push_back(TestData); -// } -// Xinit = tpgmm.getProdGMM()->getMU(mpc_start_state); -// myHSMM = tpgmm.getHSMM(); -// myHSMM->setCOMPONENTS(tpgmm.getProdGMM()->getCOMPONENTS()); -// myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); -// // Make sure that the TrajMPC model is correclty initialized by resetting it before starting -// myTrajMPC->reset(); -// curPos = Xinit; -// Ad = myTrajMPC->getSystemDynamics(); -// Bd = myTrajMPC->getInputDynamics(); -// TestData = curPos; -// trajMPCrunning = true; -// } - // do trajMPC step -// if (trajMPCrunning){ -// // Make step: -// U = myTrajMPC->computeControlCommand(curPos); -// // Simulate movement of attractor: -// curPos = Ad*curPos + Bd*U; -// TestData = join_rows(TestData, curPos); -// } - - ImGui::Separator(); -// ImGui::TextColored(ImVec4({0,1,0,1}),"Vanilla TPGMM"); - ImGui::SliderInt("set_nStates", &tpgmm_vannila_nStates, 1, 20); - ImGui::SliderInt("set_Cost", &tpgmm_vannila_rfactor, -10, 0); - - if (ImGui::Button("EM.tpgmm")){ - prt(TPdemos.size()); - if (TPdemos.size()) { - cout << "Tp demos exist ! training ..." << endl; - tpgmm_vanilla = new TPGMM(TPdemos,tpgmm_vannila_nStates); - tpgmm_vanilla->estimateTensorGMM(); - } - }ImGui::SameLine(); - - if (ImGui::Button("tpgmm_sample")){ - if (tpgmm_vanilla == nullptr) { - cout << "No model trained yet!" << endl; - }else{ - cout << "Here we sample the vanilla tpgmm" << endl; - - vanilla_tpgmm_repros.clear(); - mat van_tpgmm_rData = solveReconstructionMFtpgmm(*tpgmm_vanilla, tp, - TPdemos[0].getDataInGlobalSpace().getData().col(0), tpgmm_vannila_rfactor, - TPdemos[0].getDataInGlobalSpace().getData().n_cols ); - vanilla_tpgmm_repros.push_back(van_tpgmm_rData); - } - }ImGui::SameLine(); - - ImGui::End(); - - //Rendering the reproduction side (right)=========================== - glViewport((int)ImGui::GetIO().DisplaySize.x / 2, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - //Scaling to match the imgui rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - - //Draw the Separating line - glColor3f(0.1f, 0.1f, 0.1f); - glBegin(GL_LINE_STRIP); - glVertex2f(0, 0); - glVertex2f(0, (int)ImGui::GetIO().DisplaySize.y); - glEnd(); - - //Draw current demo - drawStrip(points, colBlack, 2.0); - - //Draw all demos - if (dispDemo) { - for (int n=0; n<(int)demos.size(); n++) { - drawStrip(demos[n].getDatapoints().getData(),colGray,2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpdpgmm.getNumFRAMES(); k++) { - glColor3f(colorM(0,0), colorM(0,1), colorM(0,2)); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point; - point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians -// if (modelExist&&dispGMM){ -// drawGaussians(tpgmm, refFrame, colorM); -// } - if (modelExist){ - drawProdGaussians(tpdpgmm, colorM.row(4).t()); - } - - if (tpgmm_vanilla != nullptr ) - { - drawGaussians(*tpgmm_vanilla, refFrame, colGreen ); - } - - //Draw MPC - if (TestData.size()){ - drawStrip(TestData,vec3({1,1,1}),3.0); - } -// if (curPos.size()){ -// drawSquare(curPos(0),curPos(1),10); -// } - drawStrip(trajMPCruns,vec3({0.8,0.8,0.8}),2); - - //draw teleop dot - drawSquare(teleop_pointer_position.x,teleop_pointer_position.y,10); - - glPopMatrix(); - - - //GUI rendering ===================================== - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - // glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - // glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - drawStrip(points,colBlack,2.0); - - //Draw all demos - if (dispDemo) { - for (int n=0; n<(int)demos.size(); n++){ - drawStrip(demos[n].getDatapoints().getData(),colGray,2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpdpgmm.getNumFRAMES(); k++) { - - glColor3f(colorM(0,0), colorM(0,1), colorM(0,2)); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians - if (modelExist&&dispGMM){ - drawGaussians(tpdpgmm, refFrame, colorM); - } - // if (modelExist){ - // drawProdGaussians(tpgmm, colorM.row(4).t()); - // } - - //Draw repros - drawStrip(repros,colorM.row(3).t(),5.0); - - drawStrip(MFrepros,colBlue,5.0); - - drawStrip(vanilla_tpgmm_repros, colGreen, 5.0); - //Draw MPC -// if (TestData.size()){ -// drawStrip(TestData,vec3({1,1,1}),3.0); -// } -// if (curPos.size()){ -// drawSquare(curPos(0),curPos(1),10); -// } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; -} - - -void drawStrip(mat points, vec3 color, float linewidth){ - glLineWidth(linewidth); - glColor3f(color[0], color[1], color[2]); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.n_cols; t++){ - glVertex2f(points(0,t), points(1,t)); - } - glEnd(); -} - -void drawStrip(vector<mat> points, vec3 color, float linewidth){ - for (int n=0; n<(int)points.size(); n++){ - drawStrip(points[n],color,linewidth); - } -} - -void drawStrip(ImVector<ImVec2> &points, vec3 color, float linewidth){ - glLineWidth(linewidth); - glColor3f(color[0], color[1], color[2]); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); -} - -void drawGaussians(TPDPGMM &tpgmm, Ref refFrame[], mat colorM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glLineWidth(2.0f); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++) { - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - eig_sym(d, V, tpgmm.getGMMS(k).getSIGMA(i).rows(0,1).cols(0,1)); - R = refFrame[k].A*(V * sqrt(diagmat(d))); - pts = R * pts0; - - glColor3f(colorM(k+1,0), colorM(k+1,1), colorM(k+1,2)); - glBegin(GL_LINE_STRIP); - - vec refMU = refFrame[k].b + refFrame[k].A*tpgmm.getGMMS(k).getMU(i).rows(0,1); - - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f((pts(0, t) + refMU(0)), (pts(1, t) +refMU(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f(tpgmm.getGMMS(k).getMU(i)(0), - tpgmm.getGMMS(k).getMU(i)(1)); - } - glEnd(); - } - } -} - -void drawGaussians(TPGMM &tpgmm, Ref refFrame[], mat colorM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glLineWidth(2.0f); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++) { - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - eig_sym(d, V, tpgmm.getGMMS(k).getSIGMA(i).rows(0,1).cols(0,1)); - R = refFrame[k].A*(V * sqrt(diagmat(d))); - pts = R * pts0; - -// glColor3f(colorM(0), colorM(1), colorM(2)); - if (k==0){glColor3f(1.0, 0.0, 0.0);} - if (k==1){glColor3f(0.0, 0.0, 1.0);} - glBegin(GL_LINE_STRIP); - - vec refMU = refFrame[k].b + refFrame[k].A*tpgmm.getGMMS(k).getMU(i).rows(0,1); - - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f((pts(0, t) + refMU(0)), (pts(1, t) +refMU(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f(tpgmm.getGMMS(k).getMU(i)(0), - tpgmm.getGMMS(k).getMU(i)(1)); - } - glEnd(); - } - } -} - -void drawProdGaussians(TPDPGMM &tpgmm, vec color){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(color(0), color(1), color(2)); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++){ - eig_sym(d, V, tpgmm.getProdGMM()->getSIGMA(i).rows(0,1).cols(0,1)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+tpgmm.getProdGMM()->getMU(i)(0)), - (pts(1,t)+tpgmm.getProdGMM()->getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(tpgmm.getProdGMM()->getMU(i)(0), - tpgmm.getProdGMM()->getMU(i)(1)); - } - glEnd(); - } -} - - void drawSquare(int pos_x, int pos_y, int square_edge, float lineWidth){ - glLineWidth(lineWidth); - glBegin( GL_QUADS ); - glColor3f( 0.8f, 0.2f, 0.2f ); - int dot_w = square_edge/2; - glVertex2f( pos_x - dot_w, pos_y - dot_w); - glVertex2f( pos_x - dot_w, pos_y + dot_w); - glVertex2f( pos_x + dot_w, pos_y + dot_w); - glVertex2f( pos_x + dot_w, pos_y - dot_w); - glEnd(); - } - - diff --git a/src/demo_tp_trajMpc.cpp b/src/demo_tp_trajMpc.cpp deleted file mode 100644 index 03fe4e0..0000000 --- a/src/demo_tp_trajMpc.cpp +++ /dev/null @@ -1,828 +0,0 @@ -/* - * demo_tp_trajMPC.cpp - * - * Online tp-hsmm learning and trajMPC-based trajectory generation when - * communication is cut. - * - * Authors: Sylvain Calinon, Ioannis Havoutis - */ - -#define prt(x) std::cout << #x " = '" << x << "'" << std::endl; - -#include <stdio.h> - -#include "armadillo" -#include <pbdlib/gmm.h> -#include <pbdlib/tpdpgmm.h> - -#include <GLFW/glfw3.h> -#include <imgui.h> -#include "imgui_impl_glfw.h" -#include <pbdlib/gmr.h> -#include <pbdlib/lqr.h> -#include <pbdlib/taskparameters.h> -#include "pbdlib/trajMPC.h" -#include "pbdlib/tptrajMPC.h" - -using namespace std; -using namespace pbdlib; -using namespace arma; - -class Remap { -public: - Remap(float input_min, float input_max, - float output_min, float output_max) -:_input_min(input_min), _input_max(input_max), - _output_min(output_min), _output_max(output_max){}; - -private: - float _input_min, _input_max, _output_min, _output_max; - -public: - float map( float input ) { - return _output_min + (input - _input_min) * - ((_output_max - _output_min) / (_input_max - _input_min)); - } - - float mapInv( float input ) { - return _input_min + (input - _output_min) * - ((_input_max - _input_min) / (_output_max - _output_min)); - } -}; - -class Ref { -public: - vec p1; - vec p2; - - mat A; - vec b; - - void updateRef() { - b = p1; - A = mat(2,2); - vec delta = p2-p1; - delta = delta/arma::norm(delta); - A(0,0) = delta(0); - A(1,0) = delta(1); - A(0,1) = -delta(1); - A(1,1) = delta(0); - } -}; - -static void error_callback(int error, const char* description){ - fprintf(stderr, "Error %d: %s\n", error, description); -} - -void drawStrip(mat points, vec3 color, float linewidth); -void drawStrip(vector<mat> points, vec3 color, float linewidth); -void drawStrip(ImVector<ImVec2> &points, vec3 color, float linewidth); -void drawGaussians(TPDPGMM &tpgmm, Ref refFrame[], mat colorM); -void drawProdGaussians(TPDPGMM &tpgmm, vec color); -void drawSquare(int pos_x, int pos_y, int square_edge, float lineWidth = 5.0); - - -int main(int argc, char **argv){ - - //trajMPC params====================== - // Model Settings: - uint nVarsPos = 2; // Number of position variables - uint nDeriv = 2; // Number of derivatives considered - - // TrajMPC Settings: - int mpc_start_state = 0; - int Np = 70; // Number of predictions - int Nc = 30; // Number of control predictions - int N = 600; // Number of iterations of simulation - float mpc_dt = 0.01; // time step considered - float alpha = 0.001; // control cost variable - - colvec Xinit; - HSMM* myHSMM; - TrajMPC* myTrajMPC; -// TpTrajMPC* myTrajMPC; - - mat Ad, Bd; - mat TestData; - colvec U; - colvec curPos = {0.0,0.0}; - bool trajMPCrunning = false; - //================================ - - //reference drawings - mat refShape = { -// {-0.5, 1.5, 0.0, 0.0, 0.0, 0.0}, -// { 0.0, 0.0, 0.0,-0.5, 0.0, 1.0} - {-0.3, -0.3, 0.3, 0.3 }, - {2.0, 0.0 , 0.0, 2.0} - }; - float refScale = 50.0; - refShape = refShape + 10.0 / refScale; - refShape = refScale * refShape; - - //Setup TPDPGMM - float minSigma = 20; //1E2; - float lambda = 100.0f; -// int nRecPoints = 300; - - int nVars = 4;//2; - int N_TPS = 2; - - TPDPGMM tpgmm(nVars,1,N_TPS,2,lambda); - - TaskParameters tp(2,N_TPS); - - mat minSIGMA = eye(2,2) * minSigma; - vector<GaussianDistribution> comps; - vector<Demonstration> demos; - vector<mat> repros, trajMPCrepros, trajMPCruns; - - //Setup LQR -// float dt = 0.01f; //0.033 - - float filterAlpha = 1.0; - float filterAlphaPos = 0.1; - - bool stateMerging = false; - - //Setup GUI - glfwSetErrorCallback(error_callback); - if (!glfwInit()) - exit(1); - GLFWwindow* window = glfwCreateWindow(1280, 820, "PbdLib GUI", NULL, NULL); - glfwMakeContextCurrent(window); - - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); - - // Setup ImGui binding - ImGui_ImplGlfw_Init(window, true); - ImVec4 clear_color = ImColor(154, 154, 154); - - ImVector<ImVec2> points, velocities; - bool adding_line = false; - bool modelExist = false; - bool dispRef = true; - bool dispDemo = false; - bool dispGMM = true; - bool useFramePRIORS = false; - bool movingRef = false; - bool hoveringRef = false; - int nbPts = 0; - bool init = true; - bool startFlag = false; - bool endFlag = false; - float alphaHandles = 0.2f; - Ref refFrame[2]; - refFrame[0].p1 = zeros(2); - refFrame[0].p2 = zeros(2); - refFrame[1].p1 = vec(2); - refFrame[1].p2 = vec(2); - - //plotting color - mat colorM = {{0.f,0.6211f,0.8164f}, - {0.9883f,0.4531f,0.f}, - {0.7422f,0.8555f,0.2227f}, - {0.1211f,0.5391f,0.4375f}, - {0.9961f,0.8789f,0.1016f}}; - vec3 colBlack = {0.0, 0.0, 0.0}; - vec3 colRed = {1.0, 0.0, 0.0}; - vec3 colGreen = {0.0, 1.0, 0.0}; - vec3 colBlue = {0.0, 0.0, 1.0}; - vec3 colGray = {0.3f, 0.3f, 0.3f}; - - float currTime, prevTime; - - Remap mapper(ImGui::GetIO().DisplaySize.x, ImGui::GetIO().DisplaySize.y, - -1, 1); // map to (-1,1) - - ImVec2 teleop_pointer_position; - bool communication_live = true; - - while (!glfwWindowShouldClose(window)){ - - // cout << "Time: " << ImGui::GetTime() << endl; - prevTime = currTime; - currTime = ImGui::GetTime(); - - glfwPollEvents(); - ImGui_ImplGlfw_NewFrame(); - hoveringRef = false; - //Control panel GUI - if(init)ImGui::SetNextWindowPos(ImVec2(300,700)); - - ImGui::Begin("r1p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "p1"); - vec tmpPos = refFrame[0].p1; - refFrame[0].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[0].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(400,700)); - ImGui::Begin("r1p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "r1"); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[0].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[0].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(400,100)); - ImGui::Begin("r2p1",NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "p2"); - tmpPos = refFrame[1].p1; - refFrame[1].p1(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p1(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - tmpPos-=refFrame[1].p1; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - if(init)ImGui::SetNextWindowPos(ImVec2(300,100)); - ImGui::Begin("r2p2", NULL, ImVec2(5,5), alphaHandles,ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize); - ImGui::TextColored(ImVec4(1.0,1.0,0.0,1.0), "r2"); - if(!init)ImGui::SetWindowPos(ImVec2(ImGui::GetWindowPos().x-tmpPos(0),ImGui::GetWindowPos().y+tmpPos(1))); - refFrame[1].p2(0)=ImGui::GetWindowPos().x+15; - refFrame[1].p2(1)=ImGui::GetIO().DisplaySize.y -ImGui::GetWindowPos().y-15; - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - ImGui::End(); - - refFrame[0].updateRef(); - refFrame[1].updateRef(); - - - int control_panel_height = 300; - int control_panel_width = 400; - - if (init){ - ImGui::SetNextWindowPos(ImVec2( - (ImGui::GetIO().DisplaySize.x - control_panel_width)/2, 2) ); - ImGui::SetNextWindowCollapsed(true); - teleop_pointer_position = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - } - - init = false; - - ImGui::Begin("Control Panel", NULL, - ImVec2(control_panel_width,control_panel_height), 1.0f, -// ImGuiWindowFlags_NoTitleBar| -// ImGuiWindowFlags_NoResize| -// ImGuiWindowFlags_NoMove| - ImGuiWindowFlags_NoSavedSettings); - - hoveringRef = ImGui::IsMouseHoveringWindow()||hoveringRef ; - - if (ImGui::Button("Clear")){ - demos.clear(); - repros.clear(); - trajMPCrepros.clear(); - tpgmm = TPDPGMM(nVars,1,N_TPS,2,lambda); - modelExist = false; - nbPts = 0; - - TestData.clear(); //trajMPC params - curPos.clear(); - trajMPCrunning = false; - trajMPCruns.clear(); - } - ImGui::Text("Left-click to collect demonstrations"); - ImGui::Text("Press space-bar to cut communication."); - ImGui::Text("nbDemos: %i, nbPoints: %i, nbStates: %i", (int)demos.size(), - // points.size(), - nbPts, (int)tpgmm.getNumSTATES()); - ImGui::SliderFloat("minSigma", &minSigma, 1E1, 20E2); - ImGui::SliderFloat("lambda", &lambda, 10.0f, 200.0f); - - ImGui::Checkbox("Display Demo",&dispDemo);ImGui::SameLine(); - ImGui::Checkbox("Plot Gaussian",&dispGMM);ImGui::SameLine(); - - ImGui::Checkbox("State Merging",&stateMerging); -// ImGui::SliderFloat("Fil. a pos", &filterAlphaPos, 0, 1, "%.2f"); - - ImGui::Separator(); - ImGui::SliderInt("MPC start state", &mpc_start_state, -1, tpgmm.getProdGMM()->getNumSTATES()); - ImGui::SliderInt("MPC n pred.", &Np, 1, 100); - ImGui::SliderInt("MPC n control pred.", &Nc, 1, 100); - //ImGui::SliderInt("MPC n sim. itter.", &N, 1, 1000); - ImGui::SliderFloat("MPC time step", &mpc_dt, 0.001, 0.1, "%.3f"); - ImGui::SliderFloat("MPC control cost", &alpha, 0.0001, 0.1, "%.4f"); - - tpgmm.useFramePRIORS(useFramePRIORS); - - //Get data - ImVec2 mouse_pos_in_canvas = ImVec2(ImGui::GetIO().MousePos.x, - ImGui::GetIO().DisplaySize.y - ImGui::GetIO().MousePos.y); - - ImVec2 mouse_vel_in_canvas; - - if(hoveringRef&&ImGui::GetIO().MouseClicked[0]) - movingRef = true; - if(movingRef&&!ImGui::GetIO().MouseDown[0]) - movingRef = false; - - if(movingRef&&modelExist&& !ImGui::GetIO().MouseClicked[0]) - { - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { - if (nVars == 2) { - tpTmp.A = refFrame[i].A; - tpTmp.b = refFrame[i].b; - }else if (nVars == 4) { - mat a; a << 1 << 0 << endr << 0 << 1 << endr; - tpTmp.A = kron(a, refFrame[i].A); - tpTmp.b = join_cols(refFrame[i].b, zeros(2,1)); - //tpTmp.b = join_cols(refFrame[i].b, refFrame[i].b); - // cout << "Ai" << refFrame[i].A << endl; - // cout << "A" << tpTmp.A << endl; - // cout << "b" << tpTmp.b << endl; - } - - tp.setTaskParameters(i,tpTmp); - } - - tpgmm.getTransformedGMM(tp,INVERTIBLE); - - vec trParam = ones(2); -// trParam = refFrame[1].b-refFrame[0].b; - tpgmm.updateTransition(trParam); - - repros.clear(); - - } - - - if ( -// (ImGui::GetIO().MousePos.x< control_panel_width +2 && -// ImGui::GetIO().MousePos.y< control_panel_height +2)==0 && - !movingRef - && (ImGui::GetIO().MousePos.x < ImGui::GetIO().DisplaySize.x/2.0)){ //Is outside gui? - if (!adding_line && ImGui::GetIO().MouseClicked[0]){ //Button pushed - adding_line = true; -// trajMPCrunning = false; - startFlag = true; - endFlag = false; - if (!modelExist){ - colvec p(nVars, fill::zeros); - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - GaussianDistribution componentTmp(p,minSIGMA); - comps.push_back(componentTmp); - comps.clear(); - } - } - if (!ImGui::GetIO().MouseDown[0]) endFlag = true; - - if (adding_line){ //Trajectory recording - nbPts++; - vec p(2); - vec v(2); - if ((int)points.size() < 2) { - p(0) = mouse_pos_in_canvas.x; - p(1) = mouse_pos_in_canvas.y; - }else{ - p(0) = points.back().x + filterAlphaPos * - ( mouse_pos_in_canvas.x - points.back().x); - p(1) = points.back().y + filterAlphaPos * - ( mouse_pos_in_canvas.y - points.back().y); - } - - mouse_pos_in_canvas.x = p(0); - mouse_pos_in_canvas.y = p(1); - points.push_back(mouse_pos_in_canvas); - - if ((int)points.size() < 2){ - v(0) = v(1) = 0.0; - } else { - float timeDt = currTime - prevTime; -// float timeDt = mpc_dt; - - if (timeDt == 0.0) - { - throw std::invalid_argument("Error: dt = 0."); - } - v(0) = velocities.back().x + filterAlpha * - ( ((p(0) - points[(int)points.size() - 2].x)/timeDt) - - velocities.back().x); - v(1) = velocities.back().y + filterAlpha * - ( ((p(1) - points[(int)points.size() - 2].y)/timeDt) - - velocities.back().y); - } - - mouse_vel_in_canvas.x = v(0); - mouse_vel_in_canvas.y = v(1); - velocities.push_back(mouse_vel_in_canvas); - - mat p_frame(nVars, N_TPS+1); - - TaskParameter tpTmp; - - for(int i=0;i<N_TPS;i++) - { - if (nVars == 2) { - p_frame.col(i) = refFrame[i].A.t()*(p-refFrame[i].b); - tpTmp.A = refFrame[i].A; - tpTmp.b = refFrame[i].b; - }else if (nVars == 4) { - p_frame.col(i) = join_cols( refFrame[i].A.t()*(p-refFrame[i].b), - refFrame[i].A.t()*(v) ); -// refFrame[i].A.t()*(v-refFrame[i].b) ); - mat a; a << 1 << 0 << endr << 0 << 1 << endr; - tpTmp.A = kron(a, refFrame[i].A); - tpTmp.b = join_cols(refFrame[i].b, zeros(2,1)); -// tpTmp.b = join_cols(refFrame[i].b, refFrame[i].b); - // cout << "Ai" << refFrame[i].A << endl; - // cout << "A" << tpTmp.A << endl; - // cout << "b" << tpTmp.b << endl; - } - - tp.setTaskParameters(i,tpTmp); - } - // also add the position in absolute space - - vec trParam; - trParam = ones(2); -// trParam = refFrame[1].b-refFrame[0].b; - if (nVars == 2) { - p_frame.col(N_TPS) = p; - }else if (nVars == 4) { - p_frame.col(N_TPS) = join_cols( p, v); - } - - tpgmm.addDatapoints(p_frame,trParam,startFlag,endFlag,lambda,minSigma); - tpgmm.getTransformedGMM(tp,INVERTIBLE); - - startFlag = false; - modelExist = true; - - if (!ImGui::GetIO().MouseDown[0]){ //Button released - adding_line = false; - - if (stateMerging){ - bool merged = true; - while (merged) - { - merged = tpgmm.reduceStates(); - tpgmm.getTransformedGMM(tp, INVERTIBLE); - tpgmm.updateTransition(trParam); - } - }else{ - tpgmm.updateTransition(trParam); - } - - //Add demonstration - Demonstration demo = Demonstration(nVars,points.size()); - for (int t=0; t<(int)points.size(); t++){ - demo.getDatapoints().getData()(0,t) = points[t].x; - demo.getDatapoints().getData()(1,t) = points[t].y; - if (nVars==4){ - demo.getDatapoints().getData()(2,t) = velocities[t].x; - demo.getDatapoints().getData()(3,t) = velocities[t].y; - } - } - // demo.saveInFile("demoMotion.txt"); - demos.push_back(demo); - - //Reconstruction - repros.clear(); - - mat pred = tpgmm.predictForwardVariable(1,0); // make sure that vars are set up - - points.clear(); - velocities.clear(); - } - - } - } - - if (ImGui::GetIO().KeysDown[GLFW_KEY_SPACE] ){ - ImGui::SetNextWindowPos(ImVec2( (ImGui::GetIO().DisplaySize.x / 2) - (164 / 2),400)); - ImGui::Begin("Info", NULL, ImVec2(164,40), 1.0f, - ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize| - ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoSavedSettings); - ImGui::TextColored(ImVec4(1.0,0.0,0.0,1.0), "Communication down!"); - ImGui::End(); - if (communication_live&&modelExist){ - if (TestData.size()){ - trajMPCruns.push_back(TestData); - } -// Xinit = tpgmm.getProdGMM()->getMU(mpc_start_state); - Xinit = vec4({mouse_pos_in_canvas.x, mouse_pos_in_canvas.y, - mouse_vel_in_canvas.x, mouse_vel_in_canvas.y}); -// prt(Xinit); - myHSMM = tpgmm.getHSMM(); - double av_state_duration = 0.0; - for (int i = 0; i < myHSMM->getNumSTATES(); ++i) { - av_state_duration += myHSMM->getDurMU(i)(0); -// prt(myHSMM->getDurMU(i)(0)); - } -// prt(av_state_duration); -// prt( (2.0/myHSMM->getNumSTATES()) * av_state_duration); - Np = ceil(1.5*(2.0/myHSMM->getNumSTATES()) * av_state_duration); - myHSMM->setCOMPONENTS(tpgmm.getProdGMM()->getCOMPONENTS()); - if (Nc>=Np){Nc = Np;} - myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); -// myTrajMPC = new TpTrajMPC(&tpgmm, &tp, -// myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); - - // Make sure that the TrajMPC model is correclty initialized by resetting it before starting - myTrajMPC->reset(); - curPos = Xinit; - Ad = myTrajMPC->getSystemDynamics(); - Bd = myTrajMPC->getInputDynamics(); - if (mpc_start_state == -1){ - TestData = curPos;}else{ - curPos = myHSMM->getMU(mpc_start_state); - } - trajMPCrunning = true; - prt(endl << tpgmm.getHSMM()->getTRANSITION()); - }else{ - // do trajMPC step - if (trajMPCrunning){ - // Make step: - U = myTrajMPC->computeControlCommand(curPos); - // Simulate movement of attractor: - curPos = Ad*curPos + Bd*U; - TestData = join_rows(TestData, curPos); -// prt(myTrajMPC->getq()); - } - } - communication_live = false; - }else{ - communication_live = true; - trajMPCrunning = false; - TestData.clear(); - } - - if (communication_live){ - float kp = 0.50; - teleop_pointer_position.x += - kp*(mouse_pos_in_canvas.x - teleop_pointer_position.x); - teleop_pointer_position.y += - kp*(mouse_pos_in_canvas.y - teleop_pointer_position.y); - }else{ - teleop_pointer_position.x = curPos(0); - teleop_pointer_position.y = curPos(1); - } - - - //=================================================================== -// if (ImGui::Button("trajMPC")){ -// if (TestData.size()){ -// trajMPCruns.push_back(TestData); -// } -// Xinit = tpgmm.getProdGMM()->getMU(mpc_start_state); -// myHSMM = tpgmm.getHSMM(); -// myHSMM->setCOMPONENTS(tpgmm.getProdGMM()->getCOMPONENTS()); -// myTrajMPC = new TrajMPC(myHSMM,mpc_dt,nVarsPos,nDeriv,Np,Nc,alpha); -// // Make sure that the TrajMPC model is correclty initialized by resetting it before starting -// myTrajMPC->reset(); -// curPos = Xinit; -// Ad = myTrajMPC->getSystemDynamics(); -// Bd = myTrajMPC->getInputDynamics(); -// TestData = curPos; -// trajMPCrunning = true; -// } - // do trajMPC step -// if (trajMPCrunning){ -// // Make step: -// U = myTrajMPC->computeControlCommand(curPos); -// // Simulate movement of attractor: -// curPos = Ad*curPos + Bd*U; -// TestData = join_rows(TestData, curPos); -// } - - ImGui::End(); - - //Rendering the reproduction side (right)=========================== - glViewport((int)ImGui::GetIO().DisplaySize.x / 2, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - glClear(GL_COLOR_BUFFER_BIT); - //Scaling to match the imgui rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - - //Draw the Separating line - glColor3f(0.1f, 0.1f, 0.1f); - glBegin(GL_LINE_STRIP); - glVertex2f(0, 0); - glVertex2f(0, (int)ImGui::GetIO().DisplaySize.y); - glEnd(); - - //Draw current demo - drawStrip(points, colBlack, 2.0); - - //Draw all demos - if (dispDemo) { - for (int n=0; n<(int)demos.size(); n++) { - drawStrip(demos[n].getDatapoints().getData(),colGray,2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - glColor3f(colorM(0,0), colorM(0,1), colorM(0,2)); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point; - point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians -// if (modelExist&&dispGMM){ -// drawGaussians(tpgmm, refFrame, colorM); -// } - if (modelExist){ - drawProdGaussians(tpgmm, colorM.row(4).t()); - } - - //Draw MPC - if (TestData.size()){ - drawStrip(TestData,vec3({1,1,1}),3.0); - } -// if (curPos.size()){ -// drawSquare(curPos(0),curPos(1),10); -// } - drawStrip(trajMPCruns,vec3({0.8,0.8,0.8}),2); - - //draw teleop dot - drawSquare(teleop_pointer_position.x,teleop_pointer_position.y,10); - - glPopMatrix(); - - - //GUI rendering ===================================== - glViewport(0, 0, (int)ImGui::GetIO().DisplaySize.x, (int)ImGui::GetIO().DisplaySize.y); - // glClearColor(clear_color.x, clear_color.y, clear_color.z, clear_color.w); - // glClear(GL_COLOR_BUFFER_BIT); - ImGui::Render(); - - //PbDlib rendering - glPushMatrix(); - glTranslatef(-1.0f,-1.0f,0); - glScalef(2.0f/(float)ImGui::GetIO().DisplaySize.x, 2.0f/(float)ImGui::GetIO().DisplaySize.y, 1.0f); - glLineWidth(2.0f); - - //Draw current demo - drawStrip(points,colBlack,2.0); - - //Draw all demos - if (dispDemo) { - for (int n=0; n<(int)demos.size(); n++){ - drawStrip(demos[n].getDatapoints().getData(),colGray,2.0); - } - } - - //Draw references - if(dispRef) { - glLineWidth(4.0f); - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - glColor3f(colorM(0,0), colorM(0,1), colorM(0,2)); - glBegin(GL_LINE_STRIP); - for (int t = 0; t < (int) size(refShape,1); t++) { - vec point = refFrame[k].b + refFrame[k].A * refShape.col(t); - glVertex2f(point(0),point(1)); - } - glEnd(); - } - glLineWidth(2.0f); - } - - //Draw Gaussians - if (modelExist&&dispGMM){ - drawGaussians(tpgmm, refFrame, colorM); - } - // if (modelExist){ - // drawProdGaussians(tpgmm, colorM.row(4).t()); - // } - - //Draw repros - drawStrip(repros,colorM.row(3).t(),5.0); - - //Draw MPC -// if (TestData.size()){ -// drawStrip(TestData,vec3({1,1,1}),3.0); -// } -// if (curPos.size()){ -// drawSquare(curPos(0),curPos(1),10); -// } - - glPopMatrix(); - glfwSwapBuffers(window); - } - - //Cleanup - ImGui_ImplGlfw_Shutdown(); - glfwTerminate(); - - return 0; -} - - -void drawStrip(mat points, vec3 color, float linewidth){ - glLineWidth(linewidth); - glColor3f(color[0], color[1], color[2]); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.n_cols; t++){ - glVertex2f(points(0,t), points(1,t)); - } - glEnd(); -} - -void drawStrip(vector<mat> points, vec3 color, float linewidth){ - for (int n=0; n<(int)points.size(); n++){ - drawStrip(points[n],color,linewidth); - } -} - -void drawStrip(ImVector<ImVec2> &points, vec3 color, float linewidth){ - glLineWidth(linewidth); - glColor3f(color[0], color[1], color[2]); - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)points.size(); t++){ - glVertex2f(points[t].x, points[t].y); - } - glEnd(); -} - -void drawGaussians(TPDPGMM &tpgmm, Ref refFrame[], mat colorM){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glLineWidth(2.0f); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++) { - for (int k = 0; k < (int) tpgmm.getNumFRAMES(); k++) { - - eig_sym(d, V, tpgmm.getGMMS(k).getSIGMA(i).rows(0,1).cols(0,1)); - R = refFrame[k].A*(V * sqrt(diagmat(d))); - pts = R * pts0; - - glColor3f(colorM(k+1,0), colorM(k+1,1), colorM(k+1,2)); - glBegin(GL_LINE_STRIP); - - vec refMU = refFrame[k].b + refFrame[k].A*tpgmm.getGMMS(k).getMU(i).rows(0,1); - - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f((pts(0, t) + refMU(0)), (pts(1, t) +refMU(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t = 0; t < (int) pts.n_cols; t++) { - glVertex2f(tpgmm.getGMMS(k).getMU(i)(0), - tpgmm.getGMMS(k).getMU(i)(1)); - } - glEnd(); - } - } -} - -void drawProdGaussians(TPDPGMM &tpgmm, vec color){ - vec d(2); - mat V(2,2), R(2,2), pts(2,30); - mat pts0(2,30); - pts0 = join_cols(cos(linspace<rowvec>(0,2*PI,30)), sin(linspace<rowvec>(0,2*PI,30))); - glColor3f(color(0), color(1), color(2)); - for (int i=0; i<(int)tpgmm.getNumSTATES(); i++){ - eig_sym(d, V, tpgmm.getProdGMM()->getSIGMA(i).rows(0,1).cols(0,1)); - R = V * sqrt(diagmat(d)); - pts = R * pts0; - glBegin(GL_LINE_STRIP); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f((pts(0,t)+tpgmm.getProdGMM()->getMU(i)(0)), - (pts(1,t)+tpgmm.getProdGMM()->getMU(i)(1))); - } - glEnd(); - glBegin(GL_POINTS); - for (int t=0; t<(int)pts.n_cols; t++){ - glVertex2f(tpgmm.getProdGMM()->getMU(i)(0), - tpgmm.getProdGMM()->getMU(i)(1)); - } - glEnd(); - } -} - - void drawSquare(int pos_x, int pos_y, int square_edge, float lineWidth){ - glLineWidth(lineWidth); - glBegin( GL_QUADS ); - glColor3f( 0.8f, 0.2f, 0.2f ); - int dot_w = square_edge/2; - glVertex2f( pos_x - dot_w, pos_y - dot_w); - glVertex2f( pos_x - dot_w, pos_y + dot_w); - glVertex2f( pos_x + dot_w, pos_y + dot_w); - glVertex2f( pos_x + dot_w, pos_y - dot_w); - glEnd(); - } diff --git a/src/gfx.cpp b/src/gfx.cpp deleted file mode 100644 index 23e20d3..0000000 --- a/src/gfx.cpp +++ /dev/null @@ -1,909 +0,0 @@ -#include "gfx.h" - -using namespace arma; -#define PI 3.14159265358979323846 - -namespace gfx -{ - -void init() -{ - glewInit(); -} - -int checkGlExtension(char const *name) -{ - const char *glExtensions = (const char *)glGetString(GL_EXTENSIONS); - return (strstr(glExtensions, name) != NULL); -} - -bool getGLError() -{ - GLenum err = glGetError(); - //glClearError(); - if( err != GL_NO_ERROR ) - { - #if !defined(CM_GLES) && !defined(GFX_OSX) - printf("GL ERROR %d %s",(int)err,gluErrorString(err)); - #endif - return true; - } - - return false; -} - - -arma::fmat perspective(float fovy, float aspect, float zNear, float zFar) -{ - const float top = zNear * tan(fovy / 2.0f); - const float bottom = -top; - const float right = top * aspect; - const float left = -right; - - arma::fmat projection = arma::zeros<fmat>(4,4); - - projection(0, 0) = 2.0f * zNear / (right - left); - projection(0, 2) = (right + left) / (right - left); - projection(1, 1) = 2.0f * zNear / (top - bottom); - projection(1, 2) = (top + bottom) / (top - bottom); - projection(2, 2) = -(zFar + zNear) / (zFar - zNear); - projection(2, 3) = -(2.0f * zFar * zNear) / (zFar - zNear); - projection(3, 2) = -1.0f; - - return projection; -} - - -void setPerspectiveProjection(float fovy, float aspect, float zNear, float zFar) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - - arma::fmat projection = perspective(fovy, aspect, zNear, zFar); - - // Add to current matrix - glMultMatrixf(projection.memptr()); - - glMatrixMode( GL_MODELVIEW ); -} - -void setOrtho( float w, float h ) -{ - glMatrixMode( GL_PROJECTION ); - glLoadIdentity(); - glOrtho( 0, 0+w, 0+h, 0, -1., 1.); - glMatrixMode( GL_MODELVIEW ); - glLoadIdentity(); -} - -void multMatrix( const arma::mat& m_ ) -{ - arma::mat m = m_; - if(m.n_rows==3) - { - m.insert_cols(2, 1); - m.insert_rows(2, 1); - } - glMultMatrixd(m.memptr()); -} - -arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, const arma::fvec& up) -{ - const arma::fvec f(arma::normalise(target - position)); - const arma::fvec s(arma::normalise(arma::cross(f, up))); - const arma::fvec u(arma::cross(s, f)); - - arma::fmat result = arma::zeros<fmat>(4,4); - result(0, 0) = s(0); - result(0, 1) = s(1); - result(0, 2) = s(2); - result(1, 0) = u(0); - result(1, 1) = u(1); - result(1, 2) = u(2); - result(2, 0) =-f(0); - result(2, 1) =-f(1); - result(2, 2) =-f(2); - result(0, 3) =-arma::dot(s, position); - result(1, 3) =-arma::dot(u, position); - result(2, 3) = arma::dot(f, position); - result(3, 3) = 1.0f; - - return result; -} - -arma::fmat rotate(const arma::fvec& axis, float angle) -{ - float rcos = cos(angle); - float rsin = sin(angle); - - arma::fmat matrix = arma::zeros<arma::fmat>(4, 4); - - matrix(0, 0) = rcos + axis(0) * axis(0) * (1.0f - rcos); - matrix(1, 0) = axis(2) * rsin + axis(1) * axis(0) * (1.0f - rcos); - matrix(2, 0) = -axis(1) * rsin + axis(2) * axis(0) * (1.0f - rcos); - matrix(0, 1) = -axis(2) * rsin + axis(0) * axis(1) * (1.0f - rcos); - matrix(1, 1) = rcos + axis(1) * axis(1) * (1.0f - rcos); - matrix(2, 1) = axis(0) * rsin + axis(2) * axis(1) * (1.0f - rcos); - matrix(0, 2) = axis(1) * rsin + axis(0) * axis(2) * (1.0f - rcos); - matrix(1, 2) = -axis(0) * rsin + axis(1) * axis(2) * (1.0f - rcos); - matrix(2, 2) = rcos + axis(2) * axis(2) * (1.0f - rcos); - matrix(3, 3) = 1.0f; - - return matrix; -} - - -/////////////////////////////////////////////////////////////// - -void drawUVQuad( float x , float y , float w , float h, float maxU, float maxV, bool flip ) -{ - GLfloat tex_coords[8]; - - if(flip) - { - tex_coords[0] = 0.0f; tex_coords[1] = maxV; - tex_coords[2] = 0.0f; tex_coords[3] = 0.0f; - tex_coords[4] = maxU; tex_coords[5] = 0.0f; - tex_coords[6] = maxU; tex_coords[7] = maxV; - } - else - { - tex_coords[0] = 0.0f; tex_coords[1] = 0.0f; - tex_coords[2] = 0.0f; tex_coords[3] = maxV; - tex_coords[4] = maxU; tex_coords[5] = maxV; - tex_coords[6] = maxU; tex_coords[7] = 0.0f; - } - - GLfloat verts[] = { - x,y, - x,y+h, - x+w,y+h, - x+w,y - }; - - glEnableClientState( GL_TEXTURE_COORD_ARRAY ); - glTexCoordPointer(2, GL_FLOAT, 0, tex_coords ); - - glEnableClientState(GL_VERTEX_ARRAY); - glVertexPointer(2, GL_FLOAT, 0, verts ); - glDrawArrays( GL_TRIANGLE_FAN, 0, 4 ); - glDisableClientState( GL_TEXTURE_COORD_ARRAY ); -} - -void drawQuad( float x , float y , float w , float h ) -{ - GLfloat verts[] = { - x+w,y, - x+w,y+h, - x,y+h, - x,y - }; - - glBegin(GL_TRIANGLE_FAN); - for( int i = 0; i < 8; i+=2 ) - { - glVertex2f(verts[i],verts[i+1]); - } - glEnd(); -} - - -void enableAntiAliasing( bool aa ) -{ - - if ( aa ) - { - glHint( GL_POINT_SMOOTH_HINT, GL_NICEST ); - glHint( GL_LINE_SMOOTH_HINT, GL_NICEST ); - glHint( GL_POLYGON_SMOOTH_HINT, GL_NICEST ); - glEnable( GL_POINT_SMOOTH ); - glEnable( GL_LINE_SMOOTH ); - glEnable( GL_POLYGON_SMOOTH ); - glLineWidth( 0.5 ); - } else { - glHint( GL_POINT_SMOOTH_HINT, GL_FASTEST ); - glHint( GL_LINE_SMOOTH_HINT, GL_FASTEST ); - glHint( GL_POLYGON_SMOOTH_HINT, GL_FASTEST ); - glDisable( GL_POINT_SMOOTH ); - glDisable( GL_LINE_SMOOTH ); - glDisable( GL_POLYGON_SMOOTH ); - } -} - -void vertex( const arma::vec& v ) -{ - switch(v.size()) - { - case 2: - glVertex2f(v[0], v[1]); - break; - case 4: - glVertex4f(v[0], v[1], v[2], v[3]); - break; - default: - glVertex3f(v[0], v[1], v[2]); - break; - } -} - -void draw( const arma::mat& P, int prim ) -{ - if(!P.size()) - return; - - glBegin(prim); - switch(P.n_rows) - { - case 2: - { - for( int i = 0; i < P.n_cols; i++ ) - { - glVertex2f(P.at(0,i), P.at(1,i)); // )P[i][0], P[i][1] ); - } - break; - } - default: - { - for( int i = 0; i < P.n_cols; i++ ) - { - glVertex3f(P.at(0, i), P.at(1, i), P.at(2, i));//P[i][0], P[i][1], P[i][2] ); - } - break; - } - } - glEnd(); -} - -void drawLine( const arma::vec& a, const arma::vec& b ) -{ - glBegin(GL_LINES); - vertex(a); - vertex(b); - glEnd(); -} - - -void drawAxis( const arma::vec& m, float scale ) -{ - arma::vec pos = m.submat(0, 3, 2, 3); - arma::vec x = pos + m.submat(0, 0, 2, 0)*scale; - arma::vec y = pos + m.submat(0, 1, 2, 1)*scale; - arma::vec z = pos + m.submat(0, 2, 2, 2)*scale; - - glBegin(GL_LINE_STRIP); - glColor4f(1,0,0,1); - vertex(pos); - vertex(x); - glColor4f(0,1,0,1); - vertex(pos); - vertex(y); - glColor4f(0,0,1,1); - vertex(pos); - vertex(z); - glColor4f(1,1,1,1); - glEnd(); -} - -/////////////////////////////////////////////////////////////// - -// Handle release -struct GLObj -{ - enum TYPE - { - TEXTURE = 0, - SHADER = 1, - PROGRAM, - VB, - IB - }; - - GLObj( GLuint glId, TYPE type ) - : - glId(glId), - type(type) - { - } - - GLObj() - { - } - - GLuint glId; - TYPE type; -}; - -static void releaseGLObject( GLObj o ) -{ - switch(o.type) - { - case GLObj::TEXTURE: - glDeleteTextures(1,&o.glId); - break; - - case GLObj::SHADER: - glDeleteShader(o.glId); - break; - - case GLObj::PROGRAM: - glDeleteProgram(o.glId); - break; - - case GLObj::VB: - glDeleteBuffers(1,&o.glId); - break; - - case GLObj::IB: - glDeleteBuffers(1,&o.glId); - break; - } -} - -struct Shader : public GLObj -{ - Shader( int id=-1 ) - : - GLObj(id, GLObj::SHADER) - { - - } - - int refcount=0; - - GLuint glId; -}; - -struct ShaderProgram : public GLObj -{ - ShaderProgram( int id=-1, int vs=-1, int ps=-1 ) - : - GLObj(id, GLObj::PROGRAM ), - ps(ps), - vs(vs) - { - - } - - int ps=-1; - int vs=-1; -}; - -typedef std::map<int, Shader> ShaderMap; -typedef std::map<int, ShaderProgram> ShaderProgramMap; - -static ShaderProgramMap shaderProgramMap; -static ShaderMap shaderMap; - -static int curProgram=-1; - -static std::string shaderVersion="120"; - -static void incShaderRefCount(int id) -{ - auto it = shaderMap.find(id); - if(it != shaderMap.end()) - it->second.refcount++; -} - - -void removeShader( int id ) -{ - auto it = shaderMap.find(id); - if(it == shaderMap.end()) - return; - it->second.refcount--; - if( it->second.refcount <= 0 ) - { - releaseGLObject(it->second); - shaderMap.erase(it); - } -} - -void deleteShaderProgram( int id ) -{ - auto it = shaderProgramMap.find(id); - if(it == shaderProgramMap.end()) - return; - releaseGLObject(it->second); - removeShader(it->second.vs); - removeShader(it->second.ps); - shaderProgramMap.erase(it); -} - -void deleteAllShaders() -{ - { - auto it = shaderMap.begin(); - while( it != shaderMap.end() ) - { - releaseGLObject(it->second); - it++; - } - } - - { - auto it = shaderProgramMap.begin(); - while( it != shaderProgramMap.end() ) - { - releaseGLObject(it->second); - it++; - } - } -} - -static bool compileShader( GLuint id, const char* shaderStr ) -{ - char errors[1024]; - - glShaderSource(id, 1, (const GLchar**)&shaderStr,NULL); - - GLsizei len; - GLint compiled; - - glCompileShader(id); - glGetShaderiv(id, GL_COMPILE_STATUS, &compiled); - - if (!compiled) - { - glGetShaderInfoLog( id, 1024, &len, errors ); - printf("shader errors: %s\n",errors); - return false; - } - - return true; -} - -void setShaderVersion( const std::string& version ) -{ - shaderVersion = version; -} - -static std::string addVersion( const std::string& str ) -{ - return std::string("\n#version ") + shaderVersion + "\n\n" + str; -} - -int loadVertexShader( const std::string& vs_ ) -{ - int id = glCreateShader(GL_VERTEX_SHADER); - std::string vs = addVersion(vs_); - if(!compileShader(id, vs.c_str())) - { - return -1; - } - - shaderMap[id] = Shader(id); - - return id; -} - -int loadPixelShader( const std::string& ps_ ) -{ - int id = glCreateShader(GL_FRAGMENT_SHADER); - std::string ps = addVersion(ps_); - if(!compileShader(id, ps.c_str())) - { - return -1; - } - - shaderMap[id] = Shader(id); - - return id; -} - -int linkShader( int vs, int ps ) -{ - int id = glCreateProgram(); - - glAttachShader(id, vs ); - glAttachShader(id, ps ); - - - // bind attributes - /* - for( u32 i = 0; i < _vertexAttributes.size() ; i++ ) - { - VertexAttribute * a = _vertexAttributes[i]; - - glBindAttribLocation(this->_glId, GENERIC_ATTRIB(a->index), a->name.str); - - if(getGLGfx()->getGLError()) - { - debugPrint("In GLShaderProgram::link"); - return false; - } - - delete _vertexAttributes[i]; - } - - _vertexAttributes.clear(); - */ - - glLinkProgram(id); - - GLint linked; - char errors[1024]; - GLsizei len; - - glGetProgramiv(id, GL_LINK_STATUS, &linked); - if (!linked) - { - glGetProgramInfoLog(id, 1024, &len, errors ); - printf("GLSL Shader linker error:%s\n",errors); - assert(0); - return -1; - } - - shaderProgramMap[id] = ShaderProgram(id, vs, ps); - incShaderRefCount(vs); - incShaderRefCount(ps); - - return id; -} - -int loadShader( const std::string& vs, const std::string& ps ) -{ - int vsid = loadVertexShader(vs); - if(vsid < 0) - return -1; - - int psid = loadPixelShader(ps); - if(psid < 0) - return -1; - - return linkShader( vsid, psid ); -} - -int reloadShader( int id, const std::string& vs, const std::string& ps ) -{ - int newid = loadShader(vs, ps); - if(newid==-1) - return id; - - deleteShaderProgram(id); - return newid; -} - -static int getUniformLocation( const std::string& handle ) -{ - int loc = glGetUniformLocation( curProgram, handle.c_str() ); - if(loc==-1) - { - printf("shader error: Could not get uniform %s\n", handle.c_str()); - } - return loc; -} - -bool setTexture( const std::string& handle, int sampler ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - - glUniform1i(id, sampler); - return true; -} - -void bindShader( int id ) -{ - glUseProgram(id); - curProgram = id; -} - -void unbindShader() -{ - glUseProgram(0); - curProgram = -1; -} - -bool setInt( const std::string& handle, int v ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - - glUniform1i(id, v); - return true; -} - -bool setFloat( const std::string& handle, float v ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - glUniform1f(id, v); - - return true; -} - -bool setVector( const std::string& handle, const arma::vec& v ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - fmat fv = conv_to<fvec>::from(v); - switch(fv.n_rows) - { - case 2: - //glUniform2fv(id, 1, (GLfloat*)fv.memptr()); - glUniform2f(id, fv[0], fv[1]);//(GLfloat*)fv.memptr()); - break; - case 3: - glUniform3fv(id, 1, (GLfloat*)fv.memptr()); - break; - case 4: - glUniform4fv(id, 1, (GLfloat*)fv.memptr()); - break; - } - - return true; -} - -bool setMatrix( const std::string& handle, const mat& v ) -{ - int id = getUniformLocation(handle); - if(id == -1) - return false; - - fmat fm = conv_to<fmat>::from(v); - - switch(v.n_rows) - { - case 2: - glUniformMatrix2fv(id, 1, GL_FALSE, (GLfloat*)fm.memptr()); - break; - case 3: - glUniformMatrix3fv(id, 1, GL_FALSE, (GLfloat*)fm.memptr()); - break; - case 4: - glUniformMatrix4fv(id, 1, GL_FALSE, (GLfloat*)fm.memptr()); - break; - default: - return false; - } - - return true; -} - -/* -// Hack, limited number of texture samplers, using a larger number will creash -static int textureSamplers[] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; - -int createTexture(int w, int h, int glFormat, int dataFormat, int dataType ) -{ - unsigned char * data = new unsigned char[w*h*4*4]; - int id = createTexture(data, w, h, glFormat, dataFormat, dataType); - delete [] data; - return id; -} - -int createTexture(void* data, int w, int h, int glFormat, int dataFormat, int dataType ) -{ - glDisable( GL_TEXTURE_RECTANGLE ); - glEnable( GL_TEXTURE_2D ); - - GLint prevAlignment; - glGetIntegerv(GL_UNPACK_ALIGNMENT, &prevAlignment); - glPixelStorei(GL_UNPACK_ALIGNMENT, 1); - - int id; - glGenTextures(1, (GLint*)&id); // Create 1 Texture - glBindTexture(GL_TEXTURE_2D, id); // Bind The Texture - - // Does not handle mip maps at the moment - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - - int hwWidth=width; - int hwHeight=height; - - // Check if non power of two - if(!checkGlExtension("GL_ARB_texture_non_power_of_two")) - { - hwWidth = NPOT(width); - hwHeight = NPOT(height); - - if(hwWidth != width) - { - // realign data - int hww = info.hwWidth; - int hwh = info.hwHeight; - - int sz = glFormatDescs[fmt].bytesPerPixel; - - unsigned char * src = (unsigned char*)data; - unsigned char * dst = new unsigned char[ hww*hwh*sz ]; - data = dst; - - memset( dst, 0, hww*hwh*sz ); - for( int y = 0; y < h; y++ ) - { - memcpy(&dst[y*hww*sz],&src[y*w*sz],w*sz); - } - } - } - - glTexImage2D( GL_TEXTURE_2D, - 0, - info.glFormat, - info.hwWidth, - info.hwHeight, - 0, - info.glDataFormat, - info.glDataType, - data ); - - glPixelStorei(GL_UNPACK_ALIGNMENT, prevAlignment); - glDisable(GL_TEXTURE_2D); - - if(hwWidth != width) - { - delete [] (unsigned char*)data; - } - - return id; -} - -void bindTexture( int id, int sampler ) -{ - glActiveTexture( GL_TEXTURE0+sampler ); - glEnable(GL_TEXTURE_2D); - glBindTexture(GL_TEXTURE_2D, id); - - textureSamplers[sampler] = id; -} - -void unbindTexture( int sampler ) -{ - if(textureSamplers[sampler] > 0) - { - glActiveTexture( GL_TEXTURE0+sampler); - glDisable(GL_TEXTURE_2D); - glBindTexture(GL_TEXTURE_2D, 0); - textureSamplers[sampler] = 0; - } -} - -void grabFrameBuffer( int texId, int w, int h ) -{ - bindTexture(id); - glCopyTexSubImage2D(GL_TEXTURE_2D, //target - 0, //level - 0, //xoffset - 0, //yoffset - 0, //x - 0, //y - w, //width - h //height - ); - unbindTexture(); -} -*/ -} - -arma::mat rot2d( double theta, bool affine ) -{ - int d = affine?3:2; - arma::mat m = arma::eye(d,d); - - double ct = cos(theta); - double st = sin(theta); - - m(0,0) = ct; m(0,1) = -st; - m(1,0) = st; m(1,1) = ct; - - return m; -} - -arma::mat trans2d( const arma::vec& xy, bool affine ) -{ - arma::mat m = arma::eye(3,3); - m(0,2) = xy[0]; - m(1,2) = xy[1]; - return m; -} - -arma::mat trans2d( double x, double y, bool affine ) -{ - return trans2d( arma::vec({x, y}) ); -} - -arma::mat scaling2d( const arma::vec& xy, bool affine ) -{ - int d = affine?3:2; - arma::mat m = arma::eye(d,d); - - m(0,0) = xy[0]; - m(1,1) = xy[1]; - return m; -} - -arma::mat scaling2d( double s, bool affine ) -{ - return scaling2d( arma::vec({s, s}), affine ); -} - -arma::mat scaling2d( double x, double y, bool affine ) -{ - return scaling2d( arma::vec({x, y}), affine ); -} - - -arma::mat rotX3d( double theta, bool affine ) -{ - int d = affine?4:3; - arma::mat m = arma::eye(d,d); - - double ct = cos(theta); - double st = sin(theta); - - m(1,1) = ct; m(1,2) = -st; - m(2,1) = st; m(2,2) = ct; - - return m; -} - -arma::mat rotY3d( double theta, bool affine ) -{ - int d = affine?4:3; - arma::mat m = arma::eye(d,d); - - double ct = cos(theta); - double st = sin(theta); - - m(0,0) = ct; m(0,2) = st; - m(2,0) = -st; m(2,2) = ct; - - return m; -} - -arma::mat rotZ3d( double theta, bool affine ) -{ - int d = affine?4:3; - arma::mat m = arma::eye(d,d); - - double ct = cos(theta); - double st = sin(theta); - - m(0,0) = ct; m(0,1) = -st; - m(1,0) = st; m(1,1) = ct; - - return m; -} - -arma::mat trans3d( const arma::vec& xyz ) -{ - arma::mat m = arma::eye(4,4); - m(0,3) = xyz[0]; - m(1,3) = xyz[1]; - m(2,3) = xyz[2]; - return m; -} - -arma::mat trans3d( double x, double y, double z ) -{ - return trans3d( arma::vec({x, y, z}) ); -} - -arma::mat scaling3d( const arma::vec& xyz, bool affine ) -{ - int d = affine?4:3; - arma::mat m = arma::eye(d,d); - - m(0,0) = xyz[0]; - m(1,1) = xyz[1]; - m(2,2) = xyz[2]; - return m; -} - -arma::mat scaling3d( double s, bool affine ) -{ - return scaling3d( arma::vec({s, s, s}), affine ); -} - -arma::mat scaling3d( double x, double y, double z, bool affine ) -{ - return scaling3d( arma::vec({x, y, z}), affine ); -} - - - diff --git a/src/gfx3.cpp b/src/gfx3.cpp deleted file mode 100644 index 0ed6c42..0000000 --- a/src/gfx3.cpp +++ /dev/null @@ -1,1368 +0,0 @@ -/* - * gfx3.cpp - * - * Rendering utility structures and functions based on OpenGL 3.3+ - * - * Authors: Philip Abbet - */ - -#include <gfx3.h> - -namespace gfx3 { - - -/****************************** UTILITY FUNCTIONS ****************************/ - -void init() -{ - glewExperimental = GL_TRUE; - glewInit(); -} - -//----------------------------------------------- - -double deg2rad(double deg) -{ - return deg / 360.0 * (2.0 * M_PI); -} - -//----------------------------------------------- - -double sin_deg(double deg) -{ - return sin(deg2rad(deg)); -} - -//----------------------------------------------- - -double cos_deg(double deg) -{ - return cos(deg2rad(deg)); -} - -//----------------------------------------------- - -bool is_close(float a, float b, float epsilon) -{ - return fabs(a - b) < epsilon; -} - -//----------------------------------------------- - -arma::vec ui2fb(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height) { - arma::vec result = coords; - - result(0) = (coords(0) - (float) win_width * 0.5f) * (float) fb_width / (float) win_width; - result(1) = ((float) win_height * 0.5f - coords(1)) * (float) fb_height / (float) win_height; - - return result; -} - -//----------------------------------------------- - -arma::vec fb2ui(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height) { - arma::vec result = coords; - - result(0) = coords(0) * (float) win_width / (float) fb_width + (float) win_width * 0.5f; - result(1) = -(coords(1) * (float) win_height / (float) fb_height - (float) win_height * 0.5f); - - return result; -} - -//----------------------------------------------- - -arma::vec ui2shader(const arma::vec& coords, int win_width, int win_height, - int fb_width, int fb_height, float sh_left, float sh_top, - float sh_right, float sh_bottom) { - arma::vec result = ui2fb(coords, win_width, win_height, fb_width, fb_height); - - result(0) = result(0) * (sh_right - sh_left) / (float) fb_width + (1.0f + sh_left); - result(1) = result(1) * (sh_top - sh_bottom) / (float) fb_height + (1.0f + sh_bottom); - - return result; -} - - -/************************* PROJECTION & VIEW MATRICES ************************/ - -arma::fmat perspective(float fovy, float aspect, float zNear, float zFar) -{ - const float top = zNear * tan(fovy / 2.0f); - const float bottom = -top; - const float right = top * aspect; - const float left = -right; - - arma::fmat projection = arma::zeros<arma::fmat>(4,4); - - projection(0, 0) = 2.0f * zNear / (right - left); - projection(0, 2) = (right + left) / (right - left); - projection(1, 1) = 2.0f * zNear / (top - bottom); - projection(1, 2) = (top + bottom) / (top - bottom); - projection(2, 2) = -(zFar + zNear) / (zFar - zNear); - projection(2, 3) = -(2.0f * zFar * zNear) / (zFar - zNear); - projection(3, 2) = -1.0f; - - return projection; -} - -//----------------------------------------------- - -arma::fmat orthographic(float width, float height, float zNear, float zFar) -{ - const float top = height / 2.0f; - const float bottom = -top; - const float right = width / 2.0f; - const float left = -right; - - arma::fmat projection = arma::zeros<arma::fmat>(4,4); - - projection(0, 0) = 2.0f / (right - left); - projection(0, 3) = -(right + left) / (right - left); - projection(1, 1) = 2.0f / (top - bottom); - projection(1, 3) = -(top + bottom) / (top - bottom); - projection(2, 2) = -2.0f / (zFar - zNear); - projection(2, 3) = -(zFar + zNear) / (zFar - zNear); - projection(3, 3) = 1.0f; - - return projection; -} - -//----------------------------------------------- - -arma::fmat lookAt(const arma::fvec& position, const arma::fvec& target, - const arma::fvec& up) -{ - const arma::fvec f(arma::normalise(target - position)); - const arma::fvec s(arma::normalise(arma::cross(f, up))); - const arma::fvec u(arma::cross(s, f)); - - arma::fmat result = arma::zeros<arma::fmat>(4,4); - - result(0, 0) = s(0); - result(0, 1) = s(1); - result(0, 2) = s(2); - result(1, 0) = u(0); - result(1, 1) = u(1); - result(1, 2) = u(2); - result(2, 0) =-f(0); - result(2, 1) =-f(1); - result(2, 2) =-f(2); - result(0, 3) =-arma::dot(s, position); - result(1, 3) =-arma::dot(u, position); - result(2, 3) = arma::dot(f, position); - result(3, 3) = 1.0f; - - return result; -} - - -/****************************** TRANSFORMATIONS ******************************/ - -arma::fmat rotate(const arma::fvec& axis, float angle) -{ - float rcos = cos(angle); - float rsin = sin(angle); - - arma::fmat matrix = arma::zeros<arma::fmat>(4, 4); - - matrix(0, 0) = rcos + axis(0) * axis(0) * (1.0f - rcos); - matrix(1, 0) = axis(2) * rsin + axis(1) * axis(0) * (1.0f - rcos); - matrix(2, 0) = -axis(1) * rsin + axis(2) * axis(0) * (1.0f - rcos); - matrix(0, 1) = -axis(2) * rsin + axis(0) * axis(1) * (1.0f - rcos); - matrix(1, 1) = rcos + axis(1) * axis(1) * (1.0f - rcos); - matrix(2, 1) = axis(0) * rsin + axis(2) * axis(1) * (1.0f - rcos); - matrix(0, 2) = axis(1) * rsin + axis(0) * axis(2) * (1.0f - rcos); - matrix(1, 2) = -axis(0) * rsin + axis(1) * axis(2) * (1.0f - rcos); - matrix(2, 2) = rcos + axis(2) * axis(2) * (1.0f - rcos); - matrix(3, 3) = 1.0f; - - return matrix; -} - -//----------------------------------------------- - -arma::fmat rotation(const arma::fvec& from, const arma::fvec& to) -{ - const float dot = arma::dot(from, to); - const arma::fvec cross = arma::cross(from, to); - const float norm = arma::norm(cross); - - arma::fmat g({ - { dot, -norm, 0.0f }, - { norm, dot, 0.0f }, - { 0.0f, 0.0f, 1.0f }, - }); - - arma::fmat fi(3, 3); - fi.rows(0, 0) = from.t(); - fi.rows(1, 1) = arma::normalise(to - dot * from).t(); - fi.rows(2, 2) = arma::cross(to, from).t(); - - arma::fmat result = arma::eye<arma::fmat>(4, 4); - - arma::fmat u; - if (arma::inv(u, fi)) - { - u = u * g * fi; - result.submat(0, 0, 2, 2) = u; - } - - return result; -} - -//----------------------------------------------- - -void rigid_transform_3D(const arma::fmat& A, const arma::fmat& B, - arma::fmat &rotation, arma::fvec &translation) { - - arma::fvec centroidsA = arma::mean(A, 1); - arma::fvec centroidsB = arma::mean(B, 1); - - int n = A.n_cols; - - arma::fmat H = (A - repmat(centroidsA, 1, n)) * (B - repmat(centroidsB, 1, n)).t(); - - arma::fmat U, V; - arma::fvec s; - arma::svd(U, s, V, H); - - rotation = V * U.t(); - - if (arma::det(rotation) < 0.0f) - rotation.col(2) *= -1.0f; - - translation = -rotation * centroidsA + centroidsB; -} - -//----------------------------------------------- - -arma::fmat worldTransforms(const transforms_t* transforms) -{ - arma::fmat result = arma::eye<arma::fmat>(4, 4); - result(0, 3, arma::size(3, 1)) = worldPosition(transforms); - - result = result * worldRotation(transforms); - - return result; -} - - -//----------------------------------------------- - -arma::fvec worldPosition(const transforms_t* transforms) -{ - if (transforms->parent) - { - arma::fvec position(4); - position.rows(0, 2) = transforms->position; - position(3) = 1.0f; - - position = worldRotation(transforms->parent) * position; - - return worldPosition(transforms->parent) + position.rows(0, 2); - } - - return transforms->position; -} - - -//----------------------------------------------- - -arma::fmat worldRotation(const transforms_t* transforms) -{ - if (transforms->parent) - { - arma::fmat result = worldRotation(transforms->parent) * transforms->rotation; - return arma::normalise(result); - } - - return transforms->rotation; -} - - -/********************************** SHADERS **********************************/ - -void shader_t::setUniform(const std::string& name, const arma::fmat& value) -{ - auto iter = fmat_uniforms.find(name); - - if (iter == fmat_uniforms.end()) - { - shader_fmat_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = value; - fmat_uniforms[name] = entry; - } - else - { - iter->second.value = value; - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, const arma::mat& value) -{ - auto iter = fmat_uniforms.find(name); - - if (iter == fmat_uniforms.end()) - { - shader_fmat_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = arma::conv_to<arma::fmat>::from(value); - fmat_uniforms[name] = entry; - } - else - { - iter->second.value = arma::conv_to<arma::fmat>::from(value); - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, const arma::fvec& value) -{ - auto iter = fvec_uniforms.find(name); - - if (iter == fvec_uniforms.end()) - { - shader_fvec_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = value; - fvec_uniforms[name] = entry; - } - else - { - iter->second.value = value; - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, const arma::vec& value) -{ - auto iter = fvec_uniforms.find(name); - - if (iter == fvec_uniforms.end()) - { - shader_fvec_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = arma::conv_to<arma::fvec>::from(value); - fvec_uniforms[name] = entry; - } - else - { - iter->second.value = arma::conv_to<arma::fvec>::from(value); - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, float value) -{ - auto iter = float_uniforms.find(name); - - if (iter == float_uniforms.end()) - { - shader_float_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = value; - float_uniforms[name] = entry; - } - else - { - iter->second.value = value; - } -} - -//----------------------------------------------- - -void shader_t::setUniform(const std::string& name, bool value) -{ - auto iter = bool_uniforms.find(name); - - if (iter == bool_uniforms.end()) - { - shader_bool_uniform_t entry; - entry.handle = glGetUniformLocation(this->id, name.c_str()); - entry.value = value; - bool_uniforms[name] = entry; - } - else - { - iter->second.value = value; - } -} - -//----------------------------------------------- - -GLuint compileShader(GLenum shader_type, const char* shader_source) -{ - GLuint id = glCreateShader(shader_type); - GLint compiled; - - glShaderSource(id, 1, (const GLchar**) &shader_source, NULL); - glCompileShader(id); - glGetShaderiv(id, GL_COMPILE_STATUS, &compiled); - - if (!compiled) - { - char errors[1024]; - GLsizei len; - - glGetShaderInfoLog(id, 1024, &len, errors); - printf("shader errors: %s\n", errors); - return 0; - } - - return id; -} - -//----------------------------------------------- - -GLuint linkShader(GLuint vertex_shader, GLuint fragment_shader) -{ - GLuint id = glCreateProgram(); - - glAttachShader(id, vertex_shader); - glAttachShader(id, fragment_shader); - glLinkProgram(id); - - GLint linked; - - glGetProgramiv(id, GL_LINK_STATUS, &linked); - if (!linked) - { - char errors[1024]; - GLsizei len; - - glGetProgramInfoLog(id, 1024, &len, errors); - printf("GLSL Shader linker error:%s\n",errors); - return 0; - } - - return id; -} - -//----------------------------------------------- - -shader_t loadShader(const std::string& vertex_shader, - const std::string& fragment_shader, - const std::string& version) -{ - shader_t shader = { 0 }; - shader.id = 0; - - // Compile the vertex shader - GLuint vs_id = compileShader( - GL_VERTEX_SHADER, (std::string("#version ") + version + "\n\n" + vertex_shader).c_str()); - - if (vs_id == 0) - return shader; - - // Compile the fragment shader - GLuint fg_id = compileShader( - GL_FRAGMENT_SHADER, (std::string("#version ") + version + "\n\n" + fragment_shader).c_str()); - - if (fg_id == 0) - return shader; - - // Link the shaders into a GLSL program - shader.id = linkShader(vs_id, fg_id); - - // Transformation matrices-related uniforms - shader.model_matrix_handle = glGetUniformLocation(shader.id, "ModelMatrix"); - shader.view_matrix_handle = glGetUniformLocation(shader.id, "ViewMatrix"); - shader.projection_matrix_handle = glGetUniformLocation(shader.id, "ProjectionMatrix"); - - // Material-related uniforms - shader.ambiant_color_handle = glGetUniformLocation(shader.id, "AmbiantColor"); - shader.diffuse_color_handle = glGetUniformLocation(shader.id, "DiffuseColor"); - shader.specular_color_handle = glGetUniformLocation(shader.id, "SpecularColor"); - shader.specular_power_handle = glGetUniformLocation(shader.id, "SpecularPower"); - - // Texture-related uniforms - shader.diffuse_texture_handle = glGetUniformLocation(shader.id, "DiffuseTexture"); - - // Light-related uniforms - shader.light_position_handle = glGetUniformLocation(shader.id, "LightPosition"); - shader.light_color_handle = glGetUniformLocation(shader.id, "LightColor"); - shader.light_power_handle = glGetUniformLocation(shader.id, "LightPower"); - - // Determine if lightning is used by the shaders - shader.use_lightning = (shader.light_position_handle != -1); - - // Backbuffer - shader.backbuffer_handle = glGetUniformLocation(shader.id, "BackBuffer"); - - return shader; -} - -//----------------------------------------------- - -void sendApplicationUniforms(const shader_t* shader) -{ - // Send the application-specific uniforms to the shader - for (auto iter = shader->fmat_uniforms.begin(), iterEnd = shader->fmat_uniforms.end(); - iter != iterEnd; ++iter) - { - if (iter->second.value.n_rows == 4) - glUniformMatrix4fv(iter->second.handle, 1, GL_FALSE, iter->second.value.memptr()); - else if (iter->second.value.n_rows == 2) - glUniformMatrix2fv(iter->second.handle, 1, GL_FALSE, iter->second.value.memptr()); - } - - for (auto iter = shader->fvec_uniforms.begin(), iterEnd = shader->fvec_uniforms.end(); - iter != iterEnd; ++iter) - { - if (iter->second.value.n_rows == 3) - glUniform3fv(iter->second.handle, 1, iter->second.value.memptr()); - else if (iter->second.value.n_rows == 2) - glUniform2fv(iter->second.handle, 1, iter->second.value.memptr()); - } - - for (auto iter = shader->float_uniforms.begin(), iterEnd = shader->float_uniforms.end(); - iter != iterEnd; ++iter) - { - glUniform1f(iter->second.handle, iter->second.value); - } - - for (auto iter = shader->bool_uniforms.begin(), iterEnd = shader->bool_uniforms.end(); - iter != iterEnd; ++iter) - { - glUniform1i(iter->second.handle, iter->second.value); - } -} - -//----------------------------------------------- - -const char* VERTEX_SHADER_ONE_LIGHT = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - layout(location = 1) in vec3 normal; - - // Values that stay constant for the whole mesh - uniform mat4 ModelMatrix; - uniform mat4 ViewMatrix; - uniform mat4 ProjectionMatrix; - uniform vec3 LightPosition; - - // Output data ; will be interpolated for each fragment - out vec3 position_worldspace; - out vec3 eye_direction_cameraspace; - out vec3 light_direction_cameraspace; - out vec3 normal_cameraspace; - - void main() { - // Position of the vertex, in clip space - gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); - - // Position of the vertex, in worldspace - position_worldspace = (ModelMatrix * vec4(vertex_position, 1)).xyz; - - // Vector that goes from the vertex to the camera, in camera space. - // In camera space, the camera is at the origin (0,0,0). - vec3 vertex_position_cameraspace = (ViewMatrix * vec4(position_worldspace, 1)).xyz; - eye_direction_cameraspace = vec3(0,0,0) - vertex_position_cameraspace; - - // Vector that goes from the vertex to the light, in camera space - vec3 light_position_cameraspace = (ViewMatrix * vec4(LightPosition, 1)).xyz; - light_direction_cameraspace = light_position_cameraspace + eye_direction_cameraspace; - - // Normal of the the vertex, in camera space (Only correct if ModelMatrix does - // not scale the model) - normal_cameraspace = (ViewMatrix * ModelMatrix * vec4(normal, 0)).xyz; - } -); - -//----------------------------------------------- - -const char* FRAGMENT_SHADER_ONE_LIGHT = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec3 AmbiantColor; - uniform vec3 DiffuseColor; - uniform vec3 SpecularColor; - uniform float SpecularPower; - uniform vec3 LightPosition; - uniform vec3 LightColor; - uniform float LightPower; - - // Interpolated values from the vertex shaders - in vec3 position_worldspace; - in vec3 eye_direction_cameraspace; - in vec3 light_direction_cameraspace; - in vec3 normal_cameraspace; - - // Output data - out vec3 color; - - void main() { - // Normal of the computed fragment, in camera space - vec3 n = normalize(normal_cameraspace); - - // Direction of the light (from the fragment to the light) - vec3 l = normalize(light_direction_cameraspace); - - // Eye vector (towards the camera) - vec3 E = normalize(eye_direction_cameraspace); - - // Direction in which the triangle reflects the light - vec3 R = reflect(-l, n); - - // Cosine of the angle between the normal and the light direction, - // clamped above 0 - // - light is at the vertical of the triangle -> 1 - // - light is perpendicular to the triangle -> 0 - // - light is behind the triangle -> 0 - float cos_theta = clamp(dot(n, l), 0, 1); - - // Cosine of the angle between the Eye vector and the Reflect vector, - // clamped to 0 - // - Looking into the reflection -> 1 - // - Looking elsewhere -> < 1 - float cos_alpha = clamp(dot(E, R), 0, 1); - - // Distance to the light - float distance = length(LightPosition - position_worldspace); - - // Computation of the color of the fragment - color = AmbiantColor + - DiffuseColor * LightColor * LightPower * cos_theta / (distance * distance) + - SpecularColor * LightColor * LightPower * pow(cos_alpha, SpecularPower) / (distance * distance); - } -); - -//----------------------------------------------- - -const char* VERTEX_SHADER_COLORED = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - - // Values that stay constant for the whole mesh - uniform mat4 ModelMatrix; - uniform mat4 ViewMatrix; - uniform mat4 ProjectionMatrix; - - void main() { - // Position of the vertex, in clip space - gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); - } -); - -//----------------------------------------------- - -const char* FRAGMENT_SHADER_COLORED = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec3 DiffuseColor; - - // Output data - out vec3 color; - - void main() { - color = DiffuseColor; - } -); - - -//----------------------------------------------- - -const char* VERTEX_SHADER_TEXTURED = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - layout(location = 2) in vec2 vertex_UV; - - // Values that stay constant for the whole mesh - uniform mat4 ModelMatrix; - uniform mat4 ViewMatrix; - uniform mat4 ProjectionMatrix; - - // Output data ; will be interpolated for each fragment - out vec2 UV; - - void main() { - // Position of the vertex, in clip space - gl_Position = ProjectionMatrix * ViewMatrix * ModelMatrix * vec4(vertex_position, 1); - - UV = vertex_UV; - } -); - - -//----------------------------------------------- - -const char* FRAGMENT_SHADER_ONE_TEXTURE = STRINGIFY( - // Values that stay constant for the whole mesh - uniform sampler2D DiffuseTexture; - - // Input data - in vec2 UV; - - // Output data - out vec3 color; - - void main() { - color = texture(DiffuseTexture, UV).rgb; - } -); - -//----------------------------------------------- - -const char* RTT_VERTEX_SHADER = STRINGIFY( - // Input vertex data - layout(location = 0) in vec3 vertex_position; - - // Output data ; will be interpolated for each fragment - out vec2 coords; - - void main() { - gl_Position = vec4(vertex_position, 1); - coords = vertex_position.xy; - } -); - -//----------------------------------------------- - -char const* RTT_FRAGMENT_SHADER_GAUSSIAN = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec2 Scale; - uniform vec2 Mu; - uniform mat2 Sigma; - uniform vec3 GaussianColor; - uniform vec3 BackgroundColor; - - // Input data - in vec2 coords; - - // Output data - layout(location = 0) out vec3 color; - - void main() { - vec2 e = coords * Scale - Mu; - float a = clamp(exp(-(Sigma[0][0] * e.x * e.x + 2 * Sigma[0][1] * e.x * e.y + - Sigma[1][1] * e.y * e.y)), 0, 1.0f); - - color = GaussianColor * a + (1.0f - a) * BackgroundColor; - } -); - -//----------------------------------------------- - -const char* RTT_FRAGMENT_SHADER_LIC = STRINGIFY( - // Values that stay constant for the whole mesh - uniform vec2 Resolution; - uniform float Time; - uniform vec2 Target; - uniform mat2 Sigma; - uniform sampler2D BackBuffer; - - // Input data - in vec2 coords; - - // Output data - layout(location = 0) out vec3 color; - - // Constants - const int Length = 3; - const int nbPass = 5; - - void main() { - vec2 uvUnit = 1.0 / Resolution.xy; - vec2 uv = (coords.xy + 1.0) * 0.5; - - // Approximate the UV coordinates, so the random noise is less sharp - vec2 approximated_uv = round(uv * 200.0) / 200.0; - - vec2 dTarget = -Sigma * (coords - Target); - dTarget = dTarget / length(dTarget); - - color = vec3(0); - - // Random noise - color += vec3(fract(sin(dot(approximated_uv.xy, vec2(12.9898, 78.233) * sin(Time))) * 43758.5453)); - - for (int n = 0; n < nbPass; n++) { - for (int i = 0; i < Length; i++) { - color += texture(BackBuffer, uv - dTarget * uvUnit * float(i + 4)).rgb; - } - } - color /= 1.0 * float(Length) * float(nbPass) + 1.0; - } -); - - -/***************************** RENDER-TO-TEXTURE *****************************/ - -render_to_texture_t createRTT(const shader_t& shader, unsigned int width, - unsigned int height, const arma::fvec& color) -{ - render_to_texture_t rtt = { 0 }; - rtt.width = width; - rtt.height = height; - - rtt.shader = &shader; - - rtt.current_buffer = 0; - rtt.nb_buffers = (shader.backbuffer_handle >= 0 ? 2 : 1); - - // Preparation of the default color buffer - unsigned char* pixels = new unsigned char[width * height * 3]; - unsigned char* pDst = pixels; - for (unsigned int y = 0; y < height; ++y) - { - for (unsigned int x = 0; x < width; ++x) - { - pDst[0] = (unsigned char) (color(0) * 255); - pDst[1] = (unsigned char) (color(1) * 255); - pDst[2] = (unsigned char) (color(2) * 255); - - pDst += 3; - } - } - - for (unsigned int i = 0; i < rtt.nb_buffers; ++i) { - // Creates the framebuffer - glGenFramebuffers(1, &rtt.buffers[i].framebuffer); - glBindFramebuffer(GL_FRAMEBUFFER, rtt.buffers[i].framebuffer); - - // Creates the texture we're going to render to - glActiveTexture(GL_TEXTURE0); - glGenTextures(1, &rtt.buffers[i].texture); - glBindTexture(GL_TEXTURE_2D, rtt.buffers[i].texture); - glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, width, height, 0, GL_RGB, GL_UNSIGNED_BYTE, pixels); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); - - // Link the two - glFramebufferTexture(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, rtt.buffers[i].texture, 0); - } - - delete[] pixels; - - // The rectangular mesh on which the shader is applied - rtt.nb_vertices = 6; - - const GLfloat vertex_buffer_data[] = { - -1.0f, -1.0f, 0.0f, - 1.0f, -1.0f, 0.0f, - -1.0f, 1.0f, 0.0f, - -1.0f, 1.0f, 0.0f, - 1.0f, -1.0f, 0.0f, - 1.0f, 1.0f, 0.0f, - }; - - // Vertex buffer - glGenBuffers(1, &rtt.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, rtt.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, rtt.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - glBindFramebuffer(GL_FRAMEBUFFER, 0); - - return rtt; -} - -//----------------------------------------------- - -bool draw(render_to_texture_t &rtt) -{ - // Various checks - if (rtt.shader->id == 0) - return false; - - // Retrieve the current viewport - GLint previous_viewport[4]; - glGetIntegerv(GL_VIEWPORT, previous_viewport); - - // Activate the GLSL program - glUseProgram(rtt.shader->id); - - // Backbuffer management - if (rtt.shader->backbuffer_handle >= 0) { - unsigned int previous_buffer = rtt.current_buffer; - - rtt.current_buffer++; - if (rtt.current_buffer >= rtt.nb_buffers) - rtt.current_buffer = 0; - - glActiveTexture(GL_TEXTURE0); - glBindTexture(GL_TEXTURE_2D, rtt.buffers[previous_buffer].texture); - glUniform1i(rtt.shader->backbuffer_handle, 0); - } - - glBindFramebuffer(GL_FRAMEBUFFER, rtt.buffers[rtt.current_buffer].framebuffer); - - glViewport(0, 0, rtt.width, rtt.height); - - // Send the application-specific uniforms to the shader - sendApplicationUniforms(rtt.shader); - - // Specify the vertices for the shader - glEnableVertexAttribArray(0); - glBindBuffer(GL_ARRAY_BUFFER, rtt.vertex_buffer); - glVertexAttribPointer(0, 3, GL_FLOAT, GL_FALSE, 0, (void*) 0); - - // Set the list of draw buffers. - GLenum draw_buffers[1] = { GL_COLOR_ATTACHMENT0 }; - glDrawBuffers(1, draw_buffers); - - // Draw the mesh - glDrawArrays(GL_TRIANGLES, 0, rtt.nb_vertices); - - // Cleanup - glDisableVertexAttribArray(0); - glBindFramebuffer(GL_FRAMEBUFFER, 0); - - // Restore the previous viewport - glViewport(previous_viewport[0], previous_viewport[1], previous_viewport[2], - previous_viewport[3]); - - return true; -} - - -/*********************************** MESHES **********************************/ - -bool draw(const model_t& model, const arma::fmat& view, - const arma::fmat& projection, const light_list_t& lights) -{ - // Various checks - if (model.shader->id == 0) - return false; - - if (model.shader->use_lightning && lights.empty()) - return false; - - // Activate the GLSL program - glUseProgram(model.shader->id); - - // Send the model, view and projection matrices to the shader - arma::fmat model_matrix = worldTransforms(&model.transforms); - - glUniformMatrix4fv(model.shader->model_matrix_handle, 1, GL_FALSE, model_matrix.memptr()); - glUniformMatrix4fv(model.shader->view_matrix_handle, 1, GL_FALSE, view.memptr()); - glUniformMatrix4fv(model.shader->projection_matrix_handle, 1, GL_FALSE, projection.memptr()); - - // Send the material parameters to the shader - glUniform3fv(model.shader->diffuse_color_handle, 1, model.diffuse_color.memptr()); - - if (model.shader->use_lightning) { - glUniform3fv(model.shader->ambiant_color_handle, 1, model.ambiant_color.memptr()); - glUniform3fv(model.shader->specular_color_handle, 1, model.specular_color.memptr()); - glUniform1f(model.shader->specular_power_handle, model.specular_power); - } - - // Send the texture parameters to the shader - if (model.shader->diffuse_texture_handle > -1) { - glActiveTexture(GL_TEXTURE0); - glBindTexture(GL_TEXTURE_2D, model.diffuse_texture); - glUniform1i(model.shader->diffuse_texture_handle, 0); - } - - // Send the light parameters to the shader - if (model.shader->use_lightning) { - glUniform3fv(model.shader->light_position_handle, 1, lights[0].transforms.position.memptr()); - glUniform3fv(model.shader->light_color_handle, 1, lights[0].color.memptr()); - glUniform1f(model.shader->light_power_handle, lights[0].power); - } - - // Send the application-specific uniforms to the shader - sendApplicationUniforms(model.shader); - - // Specify the vertices for the shader - glEnableVertexAttribArray(0); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - glVertexAttribPointer(0, 3, GL_FLOAT, GL_FALSE, 0, (void*) 0); - - // Specify the normals for the shader - if (model.shader->use_lightning) { - glEnableVertexAttribArray(1); - glBindBuffer(GL_ARRAY_BUFFER, model.normal_buffer); - glVertexAttribPointer(1, 3, GL_FLOAT, GL_FALSE, 0, (void*) 0); - } - - // Specify the UVs for the shader - if (model.uv_buffer) { - glEnableVertexAttribArray(2); - glBindBuffer(GL_ARRAY_BUFFER, model.uv_buffer); - glVertexAttribPointer(2, 2, GL_FLOAT, GL_FALSE, 0, (void*) 0); - } - - // Draw the mesh - glDrawArrays(model.mode, 0, model.nb_vertices); - - glDisableVertexAttribArray(0); - - if (model.shader->use_lightning) - glDisableVertexAttribArray(1); - - if (model.uv_buffer) - glDisableVertexAttribArray(2); - - return true; -} - -//----------------------------------------------- - -model_t create_rectangle(const shader_t& shader, const arma::fvec& color, - float width, float height) -{ - model_t model = { 0 }; - - if (shader.use_lightning) - return model; - - model.mode = GL_TRIANGLES; - model.shader = &shader; - - // Position & rotation - model.transforms.position.zeros(3); - model.transforms.rotation.eye(4, 4); - - // Material - model.diffuse_color = color; - - // Create the mesh - model.nb_vertices = 6; - - //-- Vertex buffer - float half_width = 0.5f * width; - float half_height = 0.5f * height; - - const GLfloat vertex_buffer_data[] = { - half_width, half_height, 0.0f, - -half_width, half_height, 0.0f, - -half_width, -half_height, 0.0f, - -half_width, -half_height, 0.0f, - half_width, -half_height, 0.0f, - half_width, half_height, 0.0f, - }; - - glGenBuffers(1, &model.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - //-- UVs buffer - const GLfloat uv_buffer_data[] = { - 1.0f, 1.0f, - 0.0f, 1.0f, - 0.0f, 0.0f, - 0.0f, 0.0f, - 1.0f, 0.0f, - 1.0f, 1.0f, - }; - - glGenBuffers(1, &model.uv_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.uv_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 2 * sizeof(GLfloat), - uv_buffer_data, GL_STATIC_DRAW); - - return model; -} - -//----------------------------------------------- - -model_t create_square(const shader_t& shader, const arma::fvec& color, float size) -{ - model_t model = { 0 }; - - if (shader.use_lightning) - return model; - - model.mode = GL_TRIANGLES; - model.shader = &shader; - - // Position & rotation - model.transforms.position.zeros(3); - model.transforms.rotation.eye(4, 4); - - // Material - model.diffuse_color = color; - - // Create the mesh - model.nb_vertices = 6; - - float half_size = 0.5f * size; - - const GLfloat vertex_buffer_data[] = { - half_size, half_size, 0.0f, - -half_size, half_size, 0.0f, - -half_size, -half_size, 0.0f, - -half_size, -half_size, 0.0f, - half_size, -half_size, 0.0f, - half_size, half_size, 0.0f, - }; - - // Vertex buffer - glGenBuffers(1, &model.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - return model; -} - -//----------------------------------------------- - -model_t create_sphere(const shader_t& shader, float radius) -{ - model_t model = { 0 }; - - model.mode = GL_TRIANGLES; - model.shader = &shader; - - // Position & rotation - model.transforms.position.zeros(3); - model.transforms.rotation.eye(4, 4); - - // Material - model.ambiant_color = arma::fvec({0.2f, 0.2f, 0.2f}); - model.diffuse_color = arma::fvec({0.8f, 0.8f, 0.8f}); - model.specular_color = arma::fvec({0.0f, 0.0f, 0.0f}); - model.specular_power = 5; - - // Create the mesh - const int NB_STEPS = 72; - const float STEP_SIZE = 360.0f / NB_STEPS; - - model.nb_vertices = NB_STEPS / 2 * NB_STEPS * 6; - - GLfloat* vertex_buffer_data = new GLfloat[model.nb_vertices * 3]; - - GLfloat* normal_buffer_data = (shader.use_lightning ? - new GLfloat[model.nb_vertices * 3] : 0); - - GLfloat* dst_vertex = vertex_buffer_data; - GLfloat* dst_normal = normal_buffer_data; - - for (int i = 0; i < NB_STEPS / 2; ++i) - { - GLfloat latitude_lo = (float) i * STEP_SIZE; - GLfloat latitude_hi = latitude_lo + STEP_SIZE; - - for (int j = 0; j < NB_STEPS; ++j) - { - GLfloat longitude_lo = (float) j * STEP_SIZE; - GLfloat longitude_hi = longitude_lo + STEP_SIZE; - - arma::fvec vert_ne(3); - arma::fvec vert_nw(3); - arma::fvec vert_sw(3); - arma::fvec vert_se(3); - - // Assign each X,Z with sin,cos values scaled by latitude radius indexed by longitude. - vert_ne(1) = vert_nw(1) = (float) -cos_deg(latitude_hi) * radius; - vert_sw(1) = vert_se(1) = (float) -cos_deg(latitude_lo) * radius; - - vert_nw(0) = (float) cos_deg(longitude_lo) * (radius * (float) sin_deg(latitude_hi)); - vert_sw(0) = (float) cos_deg(longitude_lo) * (radius * (float) sin_deg(latitude_lo)); - vert_ne(0) = (float) cos_deg(longitude_hi) * (radius * (float) sin_deg(latitude_hi)); - vert_se(0) = (float) cos_deg(longitude_hi) * (radius * (float) sin_deg(latitude_lo)); - - vert_nw(2) = (float) -sin_deg(longitude_lo) * (radius * (float) sin_deg(latitude_hi)); - vert_sw(2) = (float) -sin_deg(longitude_lo) * (radius * (float) sin_deg(latitude_lo)); - vert_ne(2) = (float) -sin_deg(longitude_hi) * (radius * (float) sin_deg(latitude_hi)); - vert_se(2) = (float) -sin_deg(longitude_hi) * (radius * (float) sin_deg(latitude_lo)); - - dst_vertex[0] = vert_ne(0); dst_vertex[1] = vert_ne(1); dst_vertex[2] = vert_ne(2); dst_vertex += 3; - dst_vertex[0] = vert_nw(0); dst_vertex[1] = vert_nw(1); dst_vertex[2] = vert_nw(2); dst_vertex += 3; - dst_vertex[0] = vert_sw(0); dst_vertex[1] = vert_sw(1); dst_vertex[2] = vert_sw(2); dst_vertex += 3; - - dst_vertex[0] = vert_sw(0); dst_vertex[1] = vert_sw(1); dst_vertex[2] = vert_sw(2); dst_vertex += 3; - dst_vertex[0] = vert_se(0); dst_vertex[1] = vert_se(1); dst_vertex[2] = vert_se(2); dst_vertex += 3; - dst_vertex[0] = vert_ne(0); dst_vertex[1] = vert_ne(1); dst_vertex[2] = vert_ne(2); dst_vertex += 3; - - if (shader.use_lightning) - { - arma::fvec normal_ne = arma::normalise(vert_ne); - arma::fvec normal_nw = arma::normalise(vert_nw); - arma::fvec normal_sw = arma::normalise(vert_sw); - arma::fvec normal_se = arma::normalise(vert_se); - - dst_normal[0] = normal_ne(0); dst_normal[1] = normal_ne(1); dst_normal[2] = normal_ne(2); dst_normal += 3; - dst_normal[0] = normal_nw(0); dst_normal[1] = normal_nw(1); dst_normal[2] = normal_nw(2); dst_normal += 3; - dst_normal[0] = normal_sw(0); dst_normal[1] = normal_sw(1); dst_normal[2] = normal_sw(2); dst_normal += 3; - - dst_normal[0] = normal_sw(0); dst_normal[1] = normal_sw(1); dst_normal[2] = normal_sw(2); dst_normal += 3; - dst_normal[0] = normal_se(0); dst_normal[1] = normal_se(1); dst_normal[2] = normal_se(2); dst_normal += 3; - dst_normal[0] = normal_ne(0); dst_normal[1] = normal_ne(1); dst_normal[2] = normal_ne(2); dst_normal += 3; - } - } - } - - // Vertex buffer - glGenBuffers(1, &model.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - // Normal buffer - if (shader.use_lightning) - { - glGenBuffers(1, &model.normal_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.normal_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - normal_buffer_data, GL_STATIC_DRAW); - } - - // Cleanup - delete[] vertex_buffer_data; - - if (shader.use_lightning) - delete[] normal_buffer_data; - - return model; -} - -//----------------------------------------------- - -model_t create_line(const shader_t& shader, const arma::fvec& color, - const arma::mat& points) -{ - model_t model = { 0 }; - - if (shader.use_lightning) - return model; - - model.mode = GL_LINE_STRIP; - model.shader = &shader; - - // Position & rotation - model.transforms.position.zeros(3); - model.transforms.rotation.eye(4, 4); - - // Material - model.diffuse_color = color; - - // Create the mesh - model.nb_vertices = points.n_cols; - - GLfloat* vertex_buffer_data = new GLfloat[model.nb_vertices * 3]; - - GLfloat* dst = vertex_buffer_data; - - for (int i = 0; i < points.n_cols; ++i) { - dst[0] = (float) points(0, i); - dst[1] = (float) points(1, i); - - if (points.n_rows == 3) - dst[2] = (float) points(2, i); - else - dst[2] = 0.0f; - - dst += 3; - } - - // Vertex buffer - glGenBuffers(1, &model.vertex_buffer); - glBindBuffer(GL_ARRAY_BUFFER, model.vertex_buffer); - - glBufferData(GL_ARRAY_BUFFER, model.nb_vertices * 3 * sizeof(GLfloat), - vertex_buffer_data, GL_STATIC_DRAW); - - // Cleanup - delete[] vertex_buffer_data; - - return model; -} - -//----------------------------------------------- - -model_t create_line(const shader_t& shader, const arma::fvec& color, - const std::vector<arma::vec>& points) -{ - // arma::mat points_mat(size(points[0]), points.size()); - arma::mat points_mat(points[0].n_rows, points.size()); - - for (size_t i = 0; i < points.size(); ++i) - points_mat.col(i) = points[i]; - - return create_line(shader, color, points_mat); -} - -//----------------------------------------------- - -void destroy(const model_t& model) -{ - if (model.vertex_buffer) - glDeleteBuffers(1, &model.vertex_buffer); - - if (model.normal_buffer) - glDeleteBuffers(1, &model.normal_buffer); - - if (model.uv_buffer) - glDeleteBuffers(1, &model.uv_buffer); -} - - -/******************************** RAY CASTING ********************************/ - -ray_t create_ray(const arma::fvec& origin, int mouse_x, int mouse_y, - const arma::fmat& view, const arma::fmat& projection, - int window_width, int window_height) -{ - ray_t ray; - - ray.origin = origin; - - // Compute the ray in homogeneous clip coordinates (range [-1:1, -1:1, -1:1, -1:1]) - arma::fvec ray_clip(4); - ray_clip(0) = (2.0f * mouse_x) / window_width - 1.0f; - ray_clip(1) = 1.0f - (2.0f * mouse_y) / window_height; - ray_clip(2) = -1.0f; - ray_clip(3) = 1.0f; - - // Compute the ray in camera coordinates - arma::fvec ray_eye = arma::inv(projection) * ray_clip; - ray_eye(2) = -1.0f; - ray_eye(3) = 0.0f; - - // Compute the ray in world coordinates - arma::fvec ray_world = arma::inv(view) * ray_eye; - ray.direction = arma::fvec(arma::normalise(ray_world)).rows(0, 2); - - return ray; -} - -//----------------------------------------------- - -bool intersects(const ray_t& ray, const arma::fvec& center, float radius, - arma::fvec &result) -{ - arma::fvec O_C = ray.origin - center; - float b = arma::dot(ray.direction, O_C); - float c = arma::dot(O_C, O_C) - radius * radius; - - float det = b * b - c; - - if (det < 0.0f) - return false; - - float t; - - if (det > 0.0f) - { - float t1 = -b + sqrtf(det); - float t2 = -b - sqrtf(det); - - t = (t1 < t2 ? t1 : t2); - } - else - { - t = -b + sqrtf(det); - } - - result = ray.origin + ray.direction * t; - - return true; -} - -} diff --git a/src/imgui.cpp b/src/imgui.cpp deleted file mode 100644 index 5157a2c..0000000 --- a/src/imgui.cpp +++ /dev/null @@ -1,9796 +0,0 @@ -// dear imgui, v1.50 WIP -// (main code and documentation) - -// See ImGui::ShowTestWindow() in imgui_demo.cpp for demo code. -// Newcomers, read 'Programmer guide' below for notes on how to setup ImGui in your codebase. -// Get latest version at https://github.com/ocornut/imgui -// Releases change-log at https://github.com/ocornut/imgui/releases -// Developed by Omar Cornut and every direct or indirect contributors to the GitHub. -// This library is free but I need your support to sustain development and maintenance. -// If you work for a company, please consider financial support, e.g: https://www.patreon.com/imgui - -/* - - Index - - MISSION STATEMENT - - END-USER GUIDE - - PROGRAMMER GUIDE (read me!) - - API BREAKING CHANGES (read me when you update!) - - FREQUENTLY ASKED QUESTIONS (FAQ), TIPS - - How can I help? - - How do I update to a newer version of ImGui? - - What is ImTextureID and how do I display an image? - - I integrated ImGui in my engine and the text or lines are blurry.. - - I integrated ImGui in my engine and some elements are clipping or disappearing when I move windows around.. - - How can I have multiple widgets with the same label? Can I have widget without a label? (Yes). A primer on the purpose of labels/IDs. - - How can I tell when ImGui wants my mouse/keyboard inputs and when I can pass them to my application? - - How can I load a different font than the default? - - How can I load multiple fonts? - - How can I display and input non-latin characters such as Chinese, Japanese, Korean, Cyrillic? - - How can I use the drawing facilities without an ImGui window? (using ImDrawList API) - - ISSUES & TODO-LIST - - CODE - - - MISSION STATEMENT - ================= - - - easy to use to create code-driven and data-driven tools - - easy to use to create ad hoc short-lived tools and long-lived, more elaborate tools - - easy to hack and improve - - minimize screen real-estate usage - - minimize setup and maintenance - - minimize state storage on user side - - portable, minimize dependencies, run on target (consoles, phones, etc.) - - efficient runtime (NB- we do allocate when "growing" content - creating a window / opening a tree node for the first time, etc. - but a typical frame won't allocate anything) - - read about immediate-mode gui principles @ http://mollyrocket.com/861, http://mollyrocket.com/forums/index.html - - Designed for developers and content-creators, not the typical end-user! Some of the weaknesses includes: - - doesn't look fancy, doesn't animate - - limited layout features, intricate layouts are typically crafted in code - - occasionally uses statically sized buffers for string manipulations - won't crash, but some very long pieces of text may be clipped. functions like ImGui::TextUnformatted() don't have such restriction. - - - END-USER GUIDE - ============== - - - double-click title bar to collapse window - - click upper right corner to close a window, available when 'bool* p_open' is passed to ImGui::Begin() - - click and drag on lower right corner to resize window - - click and drag on any empty space to move window - - double-click/double-tap on lower right corner grip to auto-fit to content - - TAB/SHIFT+TAB to cycle through keyboard editable fields - - use mouse wheel to scroll - - use CTRL+mouse wheel to zoom window contents (if IO.FontAllowScaling is true) - - CTRL+Click on a slider or drag box to input value as text - - text editor: - - Hold SHIFT or use mouse to select text. - - CTRL+Left/Right to word jump - - CTRL+Shift+Left/Right to select words - - CTRL+A our Double-Click to select all - - CTRL+X,CTRL+C,CTRL+V to use OS clipboard - - CTRL+Z,CTRL+Y to undo/redo - - ESCAPE to revert text to its original value - - You can apply arithmetic operators +,*,/ on numerical values. Use +- to subtract (because - would set a negative value!) - - - PROGRAMMER GUIDE - ================ - - - read the FAQ below this section! - - your code creates the UI, if your code doesn't run the UI is gone! == very dynamic UI, no construction/destructions steps, less data retention on your side, no state duplication, less sync, less bugs. - - call and read ImGui::ShowTestWindow() for demo code demonstrating most features. - - see examples/ folder for standalone sample applications. Prefer reading examples/opengl2_example/ first as it is the simplest. - you may be able to grab and copy a ready made imgui_impl_*** file from the examples/. - - customization: PushStyleColor()/PushStyleVar() or the style editor to tweak the look of the interface (e.g. if you want a more compact UI or a different color scheme). - - - getting started: - - init: call ImGui::GetIO() to retrieve the ImGuiIO structure and fill the fields marked 'Settings'. - - init: call io.Fonts->GetTexDataAsRGBA32(...) and load the font texture pixels into graphics memory. - - every frame: - 1/ in your mainloop or right after you got your keyboard/mouse info, call ImGui::GetIO() and fill the fields marked 'Input' - 2/ call ImGui::NewFrame() as early as you can! - 3/ use any ImGui function you want between NewFrame() and Render() - 4/ call ImGui::Render() as late as you can to end the frame and finalize render data. it will call your RenderDrawListFn handler that you set in the IO structure. - (if you don't need to render, you still need to call Render() and ignore the callback, or call EndFrame() instead. if you call neither some aspects of windows focusing/moving will appear broken.) - - all rendering information are stored into command-lists until ImGui::Render() is called. - - ImGui never touches or know about your GPU state. the only function that knows about GPU is the RenderDrawListFn handler that you provide. - - effectively it means you can create widgets at any time in your code, regardless of considerations of being in "update" vs "render" phases of your own application. - - refer to the examples applications in the examples/ folder for instruction on how to setup your code. - - a typical application skeleton may be: - - // Application init - ImGuiIO& io = ImGui::GetIO(); - io.DisplaySize.x = 1920.0f; - io.DisplaySize.y = 1280.0f; - io.IniFilename = "imgui.ini"; - io.RenderDrawListsFn = my_render_function; // Setup a render function, or set to NULL and call GetDrawData() after Render() to access the render data. - // TODO: Fill others settings of the io structure - - // Load texture atlas - // There is a default font so you don't need to care about choosing a font yet - unsigned char* pixels; - int width, height; - io.Fonts->GetTexDataAsRGBA32(pixels, &width, &height); - // TODO: At this points you've got a texture pointed to by 'pixels' and you need to upload that your your graphic system - // TODO: Store your texture pointer/identifier (whatever your engine uses) in 'io.Fonts->TexID' - - // Application main loop - while (true) - { - // 1) get low-level inputs (e.g. on Win32, GetKeyboardState(), or poll your events, etc.) - // TODO: fill all fields of IO structure and call NewFrame - ImGuiIO& io = ImGui::GetIO(); - io.DeltaTime = 1.0f/60.0f; - io.MousePos = mouse_pos; - io.MouseDown[0] = mouse_button_0; - io.MouseDown[1] = mouse_button_1; - io.KeysDown[i] = ... - - // 2) call NewFrame(), after this point you can use ImGui::* functions anytime - ImGui::NewFrame(); - - // 3) most of your application code here - MyGameUpdate(); // may use any ImGui functions, e.g. ImGui::Begin("My window"); ImGui::Text("Hello, world!"); ImGui::End(); - MyGameRender(); // may use any ImGui functions - - // 4) render & swap video buffers - ImGui::Render(); - SwapBuffers(); - } - - - You can read back 'io.WantCaptureMouse', 'io.WantCaptureKeybord' etc. flags from the IO structure to tell how ImGui intends to use your - inputs and to know if you should share them or hide them from the rest of your application. Read the FAQ below for more information. - - - API BREAKING CHANGES - ==================== - - Occasionally introducing changes that are breaking the API. The breakage are generally minor and easy to fix. - Here is a change-log of API breaking changes, if you are using one of the functions listed, expect to have to fix some code. - Also read releases logs https://github.com/ocornut/imgui/releases for more details. - - - 2016/09/25 (1.50) - style.WindowTitleAlign is now a ImVec2 (ImGuiAlign enum was removed). set to (0.5f,0.5f) for horizontal+vertical centering, (0.0f,0.0f) for upper-left, etc. - - 2016/07/30 (1.50) - SameLine(x) with x>0.0f is now relative to left of column/group if any, and not always to left of window. This was sort of always the intent and hopefully breakage should be minimal. - - 2016/05/12 (1.49) - title bar (using ImGuiCol_TitleBg/ImGuiCol_TitleBgActive colors) isn't rendered over a window background (ImGuiCol_WindowBg color) anymore. - If your TitleBg/TitleBgActive alpha was 1.0f or you are using the default theme it will not affect you. - However if your TitleBg/TitleBgActive alpha was <1.0f you need to tweak your custom theme to readjust for the fact that we don't draw a WindowBg background behind the title bar. - This helper function will convert an old TitleBg/TitleBgActive color into a new one with the same visual output, given the OLD color and the OLD WindowBg color. - ImVec4 ConvertTitleBgCol(const ImVec4& win_bg_col, const ImVec4& title_bg_col) - { - float new_a = 1.0f - ((1.0f - win_bg_col.w) * (1.0f - title_bg_col.w)), k = title_bg_col.w / new_a; - return ImVec4((win_bg_col.x * win_bg_col.w + title_bg_col.x) * k, (win_bg_col.y * win_bg_col.w + title_bg_col.y) * k, (win_bg_col.z * win_bg_col.w + title_bg_col.z) * k, new_a); - } - If this is confusing, pick the RGB value from title bar from an old screenshot and apply this as TitleBg/TitleBgActive. Or you may just create TitleBgActive from a tweaked TitleBg color. - - 2016/05/07 (1.49) - removed confusing set of GetInternalState(), GetInternalStateSize(), SetInternalState() functions. Now using CreateContext(), DestroyContext(), GetCurrentContext(), SetCurrentContext(). - - 2016/05/02 (1.49) - renamed SetNextTreeNodeOpened() to SetNextTreeNodeOpen(), no redirection. - - 2016/05/01 (1.49) - obsoleted old signature of CollapsingHeader(const char* label, const char* str_id = NULL, bool display_frame = true, bool default_open = false) as extra parameters were badly designed and rarely used. You can replace the "default_open = true" flag in new API with CollapsingHeader(label, ImGuiTreeNodeFlags_DefaultOpen). - - 2016/04/26 (1.49) - changed ImDrawList::PushClipRect(ImVec4 rect) to ImDraw::PushClipRect(Imvec2 min,ImVec2 max,bool intersect_with_current_clip_rect=false). Note that higher-level ImGui::PushClipRect() is preferable because it will clip at logic/widget level, whereas ImDrawList::PushClipRect() only affect your renderer. - - 2016/04/03 (1.48) - removed style.WindowFillAlphaDefault setting which was redundant. Bake default BG alpha inside style.Colors[ImGuiCol_WindowBg] and all other Bg color values. (ref github issue #337). - - 2016/04/03 (1.48) - renamed ImGuiCol_TooltipBg to ImGuiCol_PopupBg, used by popups/menus and tooltips. popups/menus were previously using ImGuiCol_WindowBg. (ref github issue #337) - - 2016/03/21 (1.48) - renamed GetWindowFont() to GetFont(), GetWindowFontSize() to GetFontSize(). Kept inline redirection function (will obsolete). - - 2016/03/02 (1.48) - InputText() completion/history/always callbacks: if you modify the text buffer manually (without using DeleteChars()/InsertChars() helper) you need to maintain the BufTextLen field. added an assert. - - 2016/01/23 (1.48) - fixed not honoring exact width passed to PushItemWidth(), previously it would add extra FramePadding.x*2 over that width. if you had manual pixel-perfect alignment in place it might affect you. - - 2015/12/27 (1.48) - fixed ImDrawList::AddRect() which used to render a rectangle 1 px too large on each axis. - - 2015/12/04 (1.47) - renamed Color() helpers to ValueColor() - dangerously named, rarely used and probably to be made obsolete. - - 2015/08/29 (1.45) - with the addition of horizontal scrollbar we made various fixes to inconsistencies with dealing with cursor position. - GetCursorPos()/SetCursorPos() functions now include the scrolled amount. It shouldn't affect the majority of users, but take note that SetCursorPosX(100.0f) puts you at +100 from the starting x position which may include scrolling, not at +100 from the window left side. - GetContentRegionMax()/GetWindowContentRegionMin()/GetWindowContentRegionMax() functions allow include the scrolled amount. Typically those were used in cases where no scrolling would happen so it may not be a problem, but watch out! - - 2015/08/29 (1.45) - renamed style.ScrollbarWidth to style.ScrollbarSize - - 2015/08/05 (1.44) - split imgui.cpp into extra files: imgui_demo.cpp imgui_draw.cpp imgui_internal.h that you need to add to your project. - - 2015/07/18 (1.44) - fixed angles in ImDrawList::PathArcTo(), PathArcToFast() (introduced in 1.43) being off by an extra PI for no justifiable reason - - 2015/07/14 (1.43) - add new ImFontAtlas::AddFont() API. For the old AddFont***, moved the 'font_no' parameter of ImFontAtlas::AddFont** functions to the ImFontConfig structure. - you need to render your textured triangles with bilinear filtering to benefit from sub-pixel positioning of text. - - 2015/07/08 (1.43) - switched rendering data to use indexed rendering. this is saving a fair amount of CPU/GPU and enables us to get anti-aliasing for a marginal cost. - this necessary change will break your rendering function! the fix should be very easy. sorry for that :( - - if you are using a vanilla copy of one of the imgui_impl_XXXX.cpp provided in the example, you just need to update your copy and you can ignore the rest. - - the signature of the io.RenderDrawListsFn handler has changed! - ImGui_XXXX_RenderDrawLists(ImDrawList** const cmd_lists, int cmd_lists_count) - became: - ImGui_XXXX_RenderDrawLists(ImDrawData* draw_data). - argument 'cmd_lists' -> 'draw_data->CmdLists' - argument 'cmd_lists_count' -> 'draw_data->CmdListsCount' - ImDrawList 'commands' -> 'CmdBuffer' - ImDrawList 'vtx_buffer' -> 'VtxBuffer' - ImDrawList n/a -> 'IdxBuffer' (new) - ImDrawCmd 'vtx_count' -> 'ElemCount' - ImDrawCmd 'clip_rect' -> 'ClipRect' - ImDrawCmd 'user_callback' -> 'UserCallback' - ImDrawCmd 'texture_id' -> 'TextureId' - - each ImDrawList now contains both a vertex buffer and an index buffer. For each command, render ElemCount/3 triangles using indices from the index buffer. - - if you REALLY cannot render indexed primitives, you can call the draw_data->DeIndexAllBuffers() method to de-index the buffers. This is slow and a waste of CPU/GPU. Prefer using indexed rendering! - - refer to code in the examples/ folder or ask on the GitHub if you are unsure of how to upgrade. please upgrade! - - 2015/07/10 (1.43) - changed SameLine() parameters from int to float. - - 2015/07/02 (1.42) - renamed SetScrollPosHere() to SetScrollFromCursorPos(). Kept inline redirection function (will obsolete). - - 2015/07/02 (1.42) - renamed GetScrollPosY() to GetScrollY(). Necessary to reduce confusion along with other scrolling functions, because positions (e.g. cursor position) are not equivalent to scrolling amount. - - 2015/06/14 (1.41) - changed ImageButton() default bg_col parameter from (0,0,0,1) (black) to (0,0,0,0) (transparent) - makes a difference when texture have transparence - - 2015/06/14 (1.41) - changed Selectable() API from (label, selected, size) to (label, selected, flags, size). Size override should have been rarely be used. Sorry! - - 2015/05/31 (1.40) - renamed GetWindowCollapsed() to IsWindowCollapsed() for consistency. Kept inline redirection function (will obsolete). - - 2015/05/31 (1.40) - renamed IsRectClipped() to IsRectVisible() for consistency. Note that return value is opposite! Kept inline redirection function (will obsolete). - - 2015/05/27 (1.40) - removed the third 'repeat_if_held' parameter from Button() - sorry! it was rarely used and inconsistent. Use PushButtonRepeat(true) / PopButtonRepeat() to enable repeat on desired buttons. - - 2015/05/11 (1.40) - changed BeginPopup() API, takes a string identifier instead of a bool. ImGui needs to manage the open/closed state of popups. Call OpenPopup() to actually set the "open" state of a popup. BeginPopup() returns true if the popup is opened. - - 2015/05/03 (1.40) - removed style.AutoFitPadding, using style.WindowPadding makes more sense (the default values were already the same). - - 2015/04/13 (1.38) - renamed IsClipped() to IsRectClipped(). Kept inline redirection function until 1.50. - - 2015/04/09 (1.38) - renamed ImDrawList::AddArc() to ImDrawList::AddArcFast() for compatibility with future API - - 2015/04/03 (1.38) - removed ImGuiCol_CheckHovered, ImGuiCol_CheckActive, replaced with the more general ImGuiCol_FrameBgHovered, ImGuiCol_FrameBgActive. - - 2014/04/03 (1.38) - removed support for passing -FLT_MAX..+FLT_MAX as the range for a SliderFloat(). Use DragFloat() or Inputfloat() instead. - - 2015/03/17 (1.36) - renamed GetItemBoxMin()/GetItemBoxMax()/IsMouseHoveringBox() to GetItemRectMin()/GetItemRectMax()/IsMouseHoveringRect(). Kept inline redirection function until 1.50. - - 2015/03/15 (1.36) - renamed style.TreeNodeSpacing to style.IndentSpacing, ImGuiStyleVar_TreeNodeSpacing to ImGuiStyleVar_IndentSpacing - - 2015/03/13 (1.36) - renamed GetWindowIsFocused() to IsWindowFocused(). Kept inline redirection function until 1.50. - - 2015/03/08 (1.35) - renamed style.ScrollBarWidth to style.ScrollbarWidth (casing) - - 2015/02/27 (1.34) - renamed OpenNextNode(bool) to SetNextTreeNodeOpened(bool, ImGuiSetCond). Kept inline redirection function until 1.50. - - 2015/02/27 (1.34) - renamed ImGuiSetCondition_*** to ImGuiSetCond_***, and _FirstUseThisSession becomes _Once. - - 2015/02/11 (1.32) - changed text input callback ImGuiTextEditCallback return type from void-->int. reserved for future use, return 0 for now. - - 2015/02/10 (1.32) - renamed GetItemWidth() to CalcItemWidth() to clarify its evolving behavior - - 2015/02/08 (1.31) - renamed GetTextLineSpacing() to GetTextLineHeightWithSpacing() - - 2015/02/01 (1.31) - removed IO.MemReallocFn (unused) - - 2015/01/19 (1.30) - renamed ImGuiStorage::GetIntPtr()/GetFloatPtr() to GetIntRef()/GetIntRef() because Ptr was conflicting with actual pointer storage functions. - - 2015/01/11 (1.30) - big font/image API change! now loads TTF file. allow for multiple fonts. no need for a PNG loader. - (1.30) - removed GetDefaultFontData(). uses io.Fonts->GetTextureData*() API to retrieve uncompressed pixels. - this sequence: - const void* png_data; - unsigned int png_size; - ImGui::GetDefaultFontData(NULL, NULL, &png_data, &png_size); - // <Copy to GPU> - became: - unsigned char* pixels; - int width, height; - io.Fonts->GetTexDataAsRGBA32(&pixels, &width, &height); - // <Copy to GPU> - io.Fonts->TexID = (your_texture_identifier); - you now have much more flexibility to load multiple TTF fonts and manage the texture buffer for internal needs. - it is now recommended that you sample the font texture with bilinear interpolation. - (1.30) - added texture identifier in ImDrawCmd passed to your render function (we can now render images). make sure to set io.Fonts->TexID. - (1.30) - removed IO.PixelCenterOffset (unnecessary, can be handled in user projection matrix) - (1.30) - removed ImGui::IsItemFocused() in favor of ImGui::IsItemActive() which handles all widgets - - 2014/12/10 (1.18) - removed SetNewWindowDefaultPos() in favor of new generic API SetNextWindowPos(pos, ImGuiSetCondition_FirstUseEver) - - 2014/11/28 (1.17) - moved IO.Font*** options to inside the IO.Font-> structure (FontYOffset, FontTexUvForWhite, FontBaseScale, FontFallbackGlyph) - - 2014/11/26 (1.17) - reworked syntax of IMGUI_ONCE_UPON_A_FRAME helper macro to increase compiler compatibility - - 2014/11/07 (1.15) - renamed IsHovered() to IsItemHovered() - - 2014/10/02 (1.14) - renamed IMGUI_INCLUDE_IMGUI_USER_CPP to IMGUI_INCLUDE_IMGUI_USER_INL and imgui_user.cpp to imgui_user.inl (more IDE friendly) - - 2014/09/25 (1.13) - removed 'text_end' parameter from IO.SetClipboardTextFn (the string is now always zero-terminated for simplicity) - - 2014/09/24 (1.12) - renamed SetFontScale() to SetWindowFontScale() - - 2014/09/24 (1.12) - moved IM_MALLOC/IM_REALLOC/IM_FREE preprocessor defines to IO.MemAllocFn/IO.MemReallocFn/IO.MemFreeFn - - 2014/08/30 (1.09) - removed IO.FontHeight (now computed automatically) - - 2014/08/30 (1.09) - moved IMGUI_FONT_TEX_UV_FOR_WHITE preprocessor define to IO.FontTexUvForWhite - - 2014/08/28 (1.09) - changed the behavior of IO.PixelCenterOffset following various rendering fixes - - - FREQUENTLY ASKED QUESTIONS (FAQ), TIPS - ====================================== - - Q: How can I help? - A: - If you are experienced enough with ImGui and with C/C++, look at the todo list and see how you want/can help! - - Become a Patron/donate. Convince your company to become a Patron or provide serious funding for development time. - - Q: How do I update to a newer version of ImGui? - A: Overwrite the following files: - imgui.cpp - imgui.h - imgui_demo.cpp - imgui_draw.cpp - imgui_internal.h - stb_rect_pack.h - stb_textedit.h - stb_truetype.h - Don't overwrite imconfig.h if you have made modification to your copy. - Check the "API BREAKING CHANGES" sections for a list of occasional API breaking changes. If you have a problem with a function, search for its name - in the code, there will likely be a comment about it. Please report any issue to the GitHub page! - - - Q: What is ImTextureID and how do I display an image? - A: ImTextureID is a void* used to pass renderer-agnostic texture references around until it hits your render function. - ImGui knows nothing about what those bits represent, it just passes them around. It is up to you to decide what you want the void* to carry! - It could be an identifier to your OpenGL texture (cast GLuint to void*), a pointer to your custom engine material (cast MyMaterial* to void*), etc. - At the end of the chain, your renderer takes this void* to cast it back into whatever it needs to select a current texture to render. - Refer to examples applications, where each renderer (in a imgui_impl_xxxx.cpp file) is treating ImTextureID as a different thing. - (c++ tip: OpenGL uses integers to identify textures. You can safely store an integer into a void*, just cast it to void*, don't take it's address!) - To display a custom image/texture within an ImGui window, you may use ImGui::Image(), ImGui::ImageButton(), ImDrawList::AddImage() functions. - ImGui will generate the geometry and draw calls using the ImTextureID that you passed and which your renderer can use. - It is your responsibility to get textures uploaded to your GPU. - - Q: I integrated ImGui in my engine and the text or lines are blurry.. - A: In your Render function, try translating your projection matrix by (0.5f,0.5f) or (0.375f,0.375f). - Also make sure your orthographic projection matrix and io.DisplaySize matches your actual framebuffer dimension. - - Q: I integrated ImGui in my engine and some elements are clipping or disappearing when I move windows around.. - A: Most likely you are mishandling the clipping rectangles in your render function. Rectangles provided by ImGui are defined as (x1,y1,x2,y2) and NOT as (x1,y1,width,height). - - Q: Can I have multiple widgets with the same label? Can I have widget without a label? (Yes) - A: Yes. A primer on the use of labels/IDs in ImGui.. - - - Elements that are not clickable, such as Text() items don't need an ID. - - - Interactive widgets require state to be carried over multiple frames (most typically ImGui often needs to remember what is the "active" widget). - to do so they need a unique ID. unique ID are typically derived from a string label, an integer index or a pointer. - - Button("OK"); // Label = "OK", ID = hash of "OK" - Button("Cancel"); // Label = "Cancel", ID = hash of "Cancel" - - - ID are uniquely scoped within windows, tree nodes, etc. so no conflict can happen if you have two buttons called "OK" in two different windows - or in two different locations of a tree. - - - If you have a same ID twice in the same location, you'll have a conflict: - - Button("OK"); - Button("OK"); // ID collision! Both buttons will be treated as the same. - - Fear not! this is easy to solve and there are many ways to solve it! - - - When passing a label you can optionally specify extra unique ID information within string itself. This helps solving the simpler collision cases. - use "##" to pass a complement to the ID that won't be visible to the end-user: - - Button("Play"); // Label = "Play", ID = hash of "Play" - Button("Play##foo1"); // Label = "Play", ID = hash of "Play##foo1" (different from above) - Button("Play##foo2"); // Label = "Play", ID = hash of "Play##foo2" (different from above) - - - If you want to completely hide the label, but still need an ID: - - Checkbox("##On", &b); // Label = "", ID = hash of "##On" (no label!) - - - Occasionally/rarely you might want change a label while preserving a constant ID. This allows you to animate labels. - For example you may want to include varying information in a window title bar (and windows are uniquely identified by their ID.. obviously) - Use "###" to pass a label that isn't part of ID: - - Button("Hello###ID"; // Label = "Hello", ID = hash of "ID" - Button("World###ID"; // Label = "World", ID = hash of "ID" (same as above) - - sprintf(buf, "My game (%f FPS)###MyGame"); - Begin(buf); // Variable label, ID = hash of "MyGame" - - - Use PushID() / PopID() to create scopes and avoid ID conflicts within the same Window. - This is the most convenient way of distinguishing ID if you are iterating and creating many UI elements. - You can push a pointer, a string or an integer value. Remember that ID are formed from the concatenation of everything in the ID stack! - - for (int i = 0; i < 100; i++) - { - PushID(i); - Button("Click"); // Label = "Click", ID = hash of integer + "label" (unique) - PopID(); - } - - for (int i = 0; i < 100; i++) - { - MyObject* obj = Objects[i]; - PushID(obj); - Button("Click"); // Label = "Click", ID = hash of pointer + "label" (unique) - PopID(); - } - - for (int i = 0; i < 100; i++) - { - MyObject* obj = Objects[i]; - PushID(obj->Name); - Button("Click"); // Label = "Click", ID = hash of string + "label" (unique) - PopID(); - } - - - More example showing that you can stack multiple prefixes into the ID stack: - - Button("Click"); // Label = "Click", ID = hash of "Click" - PushID("node"); - Button("Click"); // Label = "Click", ID = hash of "node" + "Click" - PushID(my_ptr); - Button("Click"); // Label = "Click", ID = hash of "node" + ptr + "Click" - PopID(); - PopID(); - - - Tree nodes implicitly creates a scope for you by calling PushID(). - - Button("Click"); // Label = "Click", ID = hash of "Click" - if (TreeNode("node")) - { - Button("Click"); // Label = "Click", ID = hash of "node" + "Click" - TreePop(); - } - - - When working with trees, ID are used to preserve the open/close state of each tree node. - Depending on your use cases you may want to use strings, indices or pointers as ID. - e.g. when displaying a single object that may change over time (1-1 relationship), using a static string as ID will preserve your node open/closed state when the targeted object change. - e.g. when displaying a list of objects, using indices or pointers as ID will preserve the node open/closed state differently. experiment and see what makes more sense! - - Q: How can I tell when ImGui wants my mouse/keyboard inputs and when I can pass them to my application? - A: You can read the 'io.WantCaptureXXX' flags in the ImGuiIO structure. Preferably read them after calling ImGui::NewFrame() to avoid those flags lagging by one frame, but either should be fine. - When 'io.WantCaptureMouse' or 'io.WantCaptureKeyboard' flags are set you may want to discard/hide the inputs from the rest of your application. - When 'io.WantInputsCharacters' is set to may want to notify your OS to popup an on-screen keyboard, if available. - ImGui is tracking dragging and widget activity that may occur outside the boundary of a window, so 'io.WantCaptureMouse' is a more accurate and complete than testing for ImGui::IsMouseHoveringAnyWindow(). - (Advanced note: text input releases focus on Return 'KeyDown', so the following Return 'KeyUp' event that your application receive will typically have 'io.WantcaptureKeyboard=false'. - Depending on your application logic it may or not be inconvenient. You might want to track which key-downs were for ImGui (e.g. with an array of bool) and filter out the corresponding key-ups.) - - Q: How can I load a different font than the default? (default is an embedded version of ProggyClean.ttf, rendered at size 13) - A: Use the font atlas to load the TTF file you want: - - ImGuiIO& io = ImGui::GetIO(); - io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels); - io.Fonts->GetTexDataAsRGBA32() or GetTexDataAsAlpha8() - - Q: How can I load multiple fonts? - A: Use the font atlas to pack them into a single texture: - (Read extra_fonts/README.txt and the code in ImFontAtlas for more details.) - - ImGuiIO& io = ImGui::GetIO(); - ImFont* font0 = io.Fonts->AddFontDefault(); - ImFont* font1 = io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels); - ImFont* font2 = io.Fonts->AddFontFromFileTTF("myfontfile2.ttf", size_in_pixels); - io.Fonts->GetTexDataAsRGBA32() or GetTexDataAsAlpha8() - // the first loaded font gets used by default - // use ImGui::PushFont()/ImGui::PopFont() to change the font at runtime - - // Options - ImFontConfig config; - config.OversampleH = 3; - config.OversampleV = 1; - config.GlyphExtraSpacing.x = 1.0f; - io.Fonts->LoadFromFileTTF("myfontfile.ttf", size_pixels, &config); - - // Combine multiple fonts into one - ImWchar ranges[] = { 0xf000, 0xf3ff, 0 }; - ImFontConfig config; - config.MergeMode = true; - io.Fonts->AddFontDefault(); - io.Fonts->LoadFromFileTTF("fontawesome-webfont.ttf", 16.0f, &config, ranges); - io.Fonts->LoadFromFileTTF("myfontfile.ttf", size_pixels, NULL, &config, io.Fonts->GetGlyphRangesJapanese()); - - Q: How can I display and input non-Latin characters such as Chinese, Japanese, Korean, Cyrillic? - A: When loading a font, pass custom Unicode ranges to specify the glyphs to load. - All your strings needs to use UTF-8 encoding. Specifying literal in your source code using a local code page (such as CP-923 for Japanese or CP-1251 for Cyrillic) will not work. - In C++11 you can encode a string literal in UTF-8 by using the u8"hello" syntax. Otherwise you can convert yourself to UTF-8 or load text data from file already saved as UTF-8. - You can also try to remap your local codepage characters to their Unicode codepoint using font->AddRemapChar(), but international users may have problems reading/editing your source code. - - io.Fonts->AddFontFromFileTTF("myfontfile.ttf", size_in_pixels, NULL, io.Fonts->GetGlyphRangesJapanese()); // Load Japanese characters - io.Fonts->GetTexDataAsRGBA32() or GetTexDataAsAlpha8() - io.ImeWindowHandle = MY_HWND; // To input using Microsoft IME, give ImGui the hwnd of your application - - As for text input, depends on you passing the right character code to io.AddInputCharacter(). The example applications do that. - - Q: How can I use the drawing facilities without an ImGui window? (using ImDrawList API) - A: The easiest way is to create a dummy window. Call Begin() with NoTitleBar|NoResize|NoMove|NoScrollbar|NoSavedSettings|NoInputs flag, zero background alpha, - then retrieve the ImDrawList* via GetWindowDrawList() and draw to it in any way you like. - - - tip: the construct 'IMGUI_ONCE_UPON_A_FRAME { ... }' will run the block of code only once a frame. You can use it to quickly add custom UI in the middle of a deep nested inner loop in your code. - - tip: you can create widgets without a Begin()/End() block, they will go in an implicit window called "Debug" - - tip: you can call Begin() multiple times with the same name during the same frame, it will keep appending to the same window. this is also useful to set yourself in the context of another window (to get/set other settings) - - tip: you can call Render() multiple times (e.g for VR renders). - - tip: call and read the ShowTestWindow() code in imgui_demo.cpp for more example of how to use ImGui! - - - ISSUES & TODO-LIST - ================== - Issue numbers (#) refer to github issues listed at https://github.com/ocornut/imgui/issues - The list below consist mostly of notes of things to do before they are requested/discussed by users (at that point it usually happens on the github) - - - doc: add a proper documentation+regression testing system (#435) - - window: add a way for very transient windows (non-saved, temporary overlay over hundreds of objects) to "clean" up from the global window list. perhaps a lightweight explicit cleanup pass. - - window: calling SetNextWindowSize() every frame with <= 0 doesn't do anything, may be useful to allow (particularly when used for a single axis) (#690) - - window: auto-fit feedback loop when user relies on any dynamic layout (window width multiplier, column) appears weird to end-user. clarify. - - window: allow resizing of child windows (possibly given min/max for each axis?) - - window: background options for child windows, border option (disable rounding) - - window: add a way to clear an existing window instead of appending (e.g. for tooltip override using a consistent api rather than the deferred tooltip) - - window: resizing from any sides? + mouse cursor directives for app. -!- window: begin with *p_open == false should return false. - - window: get size/pos helpers given names (see discussion in #249) - - window: a collapsed window can be stuck behind the main menu bar? - - window: when window is small, prioritize resize button over close button. - - window: detect extra End() call that pop the "Debug" window out and assert at call site instead of later. - - window/tooltip: allow to set the width of a tooltip to allow TextWrapped() etc. while keeping the height automatic. - - window: increase minimum size of a window with menus or fix the menu rendering so that it doesn't look odd. - - draw-list: maintaining bounding box per command would allow to merge draw command when clipping isn't relied on (typical non-scrolling window or non-overflowing column would merge with previous command). -!- scrolling: allow immediately effective change of scroll if we haven't appended items yet - - splitter/separator: formalize the splitter idiom into an official api (we want to handle n-way split) (#319) - - widgets: display mode: widget-label, label-widget (aligned on column or using fixed size), label-newline-tab-widget etc. - - widgets: clean up widgets internal toward exposing everything. - - widgets: add disabled and read-only modes (#211) - - main: considering adding an Init() function? some constructs are awkward in the implementation because of the lack of them. -!- main: make it so that a frame with no window registered won't refocus every window on subsequent frames (~bump LastFrameActive of all windows). - - main: IsItemHovered() make it more consistent for various type of widgets, widgets with multiple components, etc. also effectively IsHovered() region sometimes differs from hot region, e.g tree nodes - - main: IsItemHovered() info stored in a stack? so that 'if TreeNode() { Text; TreePop; } if IsHovered' return the hover state of the TreeNode? - - input text: clean up the mess caused by converting UTF-8 <> wchar. the code is rather inefficient right now and super fragile. - - input text: reorganize event handling, allow CharFilter to modify buffers, allow multiple events? (#541) - - input text: expose CursorPos in char filter event (#816) - - input text: flag to disable live update of the user buffer (also applies to float/int text input) - - input text: resize behavior - field could stretch when being edited? hover tooltip shows more text? - - input text: add ImGuiInputTextFlags_EnterToApply? (off #218) - - input text: add discard flag (e.g. ImGuiInputTextFlags_DiscardActiveBuffer) or make it easier to clear active focus for text replacement during edition (#725) - - input text multi-line: don't directly call AddText() which does an unnecessary vertex reserve for character count prior to clipping. and/or more line-based clipping to AddText(). and/or reorganize TextUnformatted/RenderText for more efficiency for large text (e.g TextUnformatted could clip and log separately, etc). - - input text multi-line: way to dynamically grow the buffer without forcing the user to initially allocate for worse case (follow up on #200) - - input text multi-line: line numbers? status bar? (follow up on #200) - - input text multi-line: behave better when user changes input buffer while editing is active (even though it is illegal behavior). namely, the change of buffer can create a scrollbar glitch (#725) - - input text: allow centering/positioning text so that ctrl+clicking Drag or Slider keeps the textual value at the same pixel position. - - input number: optional range min/max for Input*() functions - - input number: holding [-]/[+] buttons could increase the step speed non-linearly (or user-controlled) - - input number: use mouse wheel to step up/down - - input number: applying arithmetics ops (+,-,*,/) messes up with text edit undo stack. - - button: provide a button that looks framed. - - text: proper alignment options - - image/image button: misalignment on padded/bordered button? - - image/image button: parameters are confusing, image() has tint_col,border_col whereas imagebutton() has bg_col/tint_col. Even thou they are different parameters ordering could be more consistent. can we fix that? - - layout: horizontal layout helper (#97) - - layout: horizontal flow until no space left (#404) - - layout: more generic alignment state (left/right/centered) for single items? - - layout: clean up the InputFloatN/SliderFloatN/ColorEdit4 layout code. item width should include frame padding. - - layout: BeginGroup() needs a border option. - - columns: declare column set (each column: fixed size, %, fill, distribute default size among fills) (#513, #125) - - columns: add a conditional parameter to SetColumnOffset() (#513, #125) - - columns: separator function or parameter that works within the column (currently Separator() bypass all columns) (#125) - - columns: columns header to act as button (~sort op) and allow resize/reorder (#513, #125) - - columns: user specify columns size (#513, #125) - - columns: flag to add horizontal separator above/below? - - columns/layout: setup minimum line height (equivalent of automatically calling AlignFirstTextHeightToWidgets) - - combo: sparse combo boxes (via function call?) / iterators - - combo: contents should extends to fit label if combo widget is small - - combo/listbox: keyboard control. need InputText-like non-active focus + key handling. considering keyboard for custom listbox (pr #203) - - listbox: multiple selection - - listbox: user may want to initial scroll to focus on the one selected value? - - listbox: keyboard navigation. - - listbox: scrolling should track modified selection. -!- popups/menus: clarify usage of popups id, how MenuItem/Selectable closing parent popups affects the ID, etc. this is quite fishy needs improvement! (#331, #402) - - popups: add variant using global identifier similar to Begin/End (#402) - - popups: border options. richer api like BeginChild() perhaps? (#197) - - tooltip: tooltip that doesn't fit in entire screen seems to lose their "last preferred button" and may teleport when moving mouse - - menus: local shortcuts, global shortcuts (#456, #126) - - menus: icons - - menus: menubars: some sort of priority / effect of main menu-bar on desktop size? - - menus: calling BeginMenu() twice with a same name doesn't seem to append nicely - - statusbar: add a per-window status bar helper similar to what menubar does. - - tabs (#261, #351) - - separator: separator on the initial position of a window is not visible (cursorpos.y <= clippos.y) -!- color: the color helpers/typing is a mess and needs sorting out. - - color: add a better color picker (#346) - - node/graph editor (#306) - - pie menus patterns (#434) - - drag'n drop, dragging helpers (carry dragging info, visualize drag source before clicking, drop target, etc.) (#143, #479) - - plot: PlotLines() should use the polygon-stroke facilities (currently issues with averaging normals) - - plot: make it easier for user to draw extra stuff into the graph (e.g: draw basis, highlight certain points, 2d plots, multiple plots) - - plot: "smooth" automatic scale over time, user give an input 0.0(full user scale) 1.0(full derived from value) - - plot: add a helper e.g. Plot(char* label, float value, float time_span=2.0f) that stores values and Plot them for you - probably another function name. and/or automatically allow to plot ANY displayed value (more reliance on stable ID) - - slider: allow using the [-]/[+] buttons used by InputFloat()/InputInt() - - slider: initial absolute click is imprecise. change to relative movement slider (same as scrollbar). - - slider: add dragging-based widgets to edit values with mouse (on 2 axises), saving screen real-estate. - - slider: tint background based on value (e.g. v_min -> v_max, or use 0.0f either side of the sign) - - slider & drag: int data passing through a float - - drag float: up/down axis - - drag float: added leeway on edge (e.g. a few invisible steps past the clamp limits) - - tree node / optimization: avoid formatting when clipped. - - tree node: tree-node/header right-most side doesn't take account of horizontal scrolling. - - tree node: add treenode/treepush int variants? not there because (void*) cast from int warns on some platforms/settings? - - tree node: try to apply scrolling at time of TreePop() if node was just opened and end of node is past scrolling limits? - - tree node / selectable render mismatch which is visible if you use them both next to each other (e.g. cf. property viewer) - - tree node: tweak color scheme to distinguish headers from selected tree node (#581) - - textwrapped: figure out better way to use TextWrapped() in an always auto-resize context (tooltip, etc.) (#249) - - settings: write more decent code to allow saving/loading new fields - - settings: api for per-tool simple persistent data (bool,int,float,columns sizes,etc.) in .ini file - - style: add window shadows. - - style/optimization: store rounded corners in texture to use 1 quad per corner (filled and wireframe) to lower the cost of rounding. - - style: color-box not always square? - - style: a concept of "compact style" that the end-user can easily rely on (e.g. PushStyleCompact()?) that maps to other settings? avoid implementing duplicate helpers such as SmallCheckbox(), etc. - - style: try to make PushStyleVar() more robust to incorrect parameters (to be more friendly to edit & continues situation). - - style: global scale setting. - - style: WindowPadding needs to be EVEN needs the 0.5 multiplier probably have a subtle effect on clip rectangle - - text: simple markup language for color change? - - font: dynamic font atlas to avoid baking huge ranges into bitmap and make scaling easier. - - font: small opt: for monospace font (like the defalt one) we can trim IndexXAdvance as long as trailing value is == FallbackXAdvance - - font: add support for kerning, probably optional. perhaps default to (32..128)^2 matrix ~ 36KB then hash fallback. - - font: add a simpler CalcTextSizeA() api? current one ok but not welcome if user needs to call it directly (without going through ImGui::CalcTextSize) - - font: fix AddRemapChar() to work before font has been built. - - log: LogButtons() options for specifying depth and/or hiding depth slider - - log: have more control over the log scope (e.g. stop logging when leaving current tree node scope) - - log: be able to log anything (e.g. right-click on a window/tree-node, shows context menu? log into tty/file/clipboard) - - log: let user copy any window content to clipboard easily (CTRL+C on windows? while moving it? context menu?). code is commented because it fails with multiple Begin/End pairs. - - filters: set a current filter that tree node can automatically query to hide themselves - - filters: handle wildcards (with implicit leading/trailing *), regexps - - shortcuts: add a shortcut api, e.g. parse "&Save" and/or "Save (CTRL+S)", pass in to widgets or provide simple ways to use (button=activate, input=focus) -!- keyboard: tooltip & combo boxes are messing up / not honoring keyboard tabbing - - keyboard: full keyboard navigation and focus. (#323) - - focus: preserve ActiveId/focus stack state, e.g. when opening a menu and close it, previously selected InputText() focus gets restored (#622) - - focus: SetKeyboardFocusHere() on with >= 0 offset could be done on same frame (else latch and modulate on beginning of next frame) - - input: rework IO system to be able to pass actual ordered/timestamped events. (~#335, #71) - - input: allow to decide and pass explicit double-clicks (e.g. for windows by the CS_DBLCLKS style). - - input: support track pad style scrolling & slider edit. - - misc: provide a way to compile out the entire implementation while providing a dummy API (e.g. #define IMGUI_DUMMY_IMPL) - - misc: double-clicking on title bar to minimize isn't consistent, perhaps move to single-click on left-most collapse icon? - - misc: provide HoveredTime and ActivatedTime to ease the creation of animations. - - style editor: have a more global HSV setter (e.g. alter hue on all elements). consider replacing active/hovered by offset in HSV space? (#438) - - style editor: color child window height expressed in multiple of line height. - - remote: make a system like RemoteImGui first-class citizen/project (#75) - - drawlist: move Font, FontSize, FontTexUvWhitePixel inside ImDrawList and make it self-contained (apart from drawing settings?) - - drawlist: end-user probably can't call Clear() directly because we expect a texture to be pushed in the stack. - - examples: directx9: save/restore device state more thoroughly. - - examples: window minimize, maximize (#583) - - optimization: add a flag to disable most of rendering, for the case where the user expect to skip it (#335) - - optimization: use another hash function than crc32, e.g. FNV1a - - optimization/render: merge command-lists with same clip-rect into one even if they aren't sequential? (as long as in-between clip rectangle don't overlap)? - - optimization: turn some the various stack vectors into statically-sized arrays - - optimization: better clipping for multi-component widgets -*/ - -#if defined(_MSC_VER) && !defined(_CRT_SECURE_NO_WARNINGS) -#define _CRT_SECURE_NO_WARNINGS -#endif - -#include "imgui.h" -#define IMGUI_DEFINE_MATH_OPERATORS -#define IMGUI_DEFINE_PLACEMENT_NEW -#include "imgui_internal.h" - -#include <ctype.h> // toupper, isprint -#include <stdlib.h> // NULL, malloc, free, qsort, atoi -#include <stdio.h> // vsnprintf, sscanf, printf -#include <limits.h> // INT_MIN, INT_MAX -#if defined(_MSC_VER) && _MSC_VER <= 1500 // MSVC 2008 or earlier -#include <stddef.h> // intptr_t -#else -#include <stdint.h> // intptr_t -#endif - -#ifdef _MSC_VER -#pragma warning (disable: 4127) // condition expression is constant -#pragma warning (disable: 4505) // unreferenced local function has been removed (stb stuff) -#pragma warning (disable: 4996) // 'This function or variable may be unsafe': strcpy, strdup, sprintf, vsnprintf, sscanf, fopen -#endif - -// Clang warnings with -Weverything -#ifdef __clang__ -#pragma clang diagnostic ignored "-Wold-style-cast" // warning : use of old-style cast // yes, they are more terse. -#pragma clang diagnostic ignored "-Wfloat-equal" // warning : comparing floating point with == or != is unsafe // storing and comparing against same constants ok. -#pragma clang diagnostic ignored "-Wformat-nonliteral" // warning : format string is not a string literal // passing non-literal to vsnformat(). yes, user passing incorrect format strings can crash the code. -#pragma clang diagnostic ignored "-Wexit-time-destructors" // warning : declaration requires an exit-time destructor // exit-time destruction order is undefined. if MemFree() leads to users code that has been disabled before exit it might cause problems. ImGui coding style welcomes static/globals. -#pragma clang diagnostic ignored "-Wglobal-constructors" // warning : declaration requires a global destructor // similar to above, not sure what the exact difference it. -#pragma clang diagnostic ignored "-Wsign-conversion" // warning : implicit conversion changes signedness // -#pragma clang diagnostic ignored "-Wint-to-void-pointer-cast" // warning : cast to 'void *' from smaller integer type 'int' // -#elif defined(__GNUC__) -#pragma GCC diagnostic ignored "-Wunused-function" // warning: 'xxxx' defined but not used -#pragma GCC diagnostic ignored "-Wint-to-pointer-cast" // warning: cast to pointer from integer of different size -#pragma GCC diagnostic ignored "-Wformat" // warning: format '%p' expects argument of type 'void*', but argument 6 has type 'ImGuiWindow*' -#pragma GCC diagnostic ignored "-Wdouble-promotion" // warning: implicit conversion from 'float' to 'double' when passing argument to function -#pragma GCC diagnostic ignored "-Wconversion" // warning: conversion to 'xxxx' from 'xxxx' may alter its value -#endif - -//------------------------------------------------------------------------- -// Forward Declarations -//------------------------------------------------------------------------- - -static void LogRenderedText(const ImVec2& ref_pos, const char* text, const char* text_end = NULL); - -static void PushMultiItemsWidths(int components, float w_full = 0.0f); -static float GetDraggedColumnOffset(int column_index); - -static bool IsKeyPressedMap(ImGuiKey key, bool repeat = true); - -static void SetCurrentFont(ImFont* font); -static void SetCurrentWindow(ImGuiWindow* window); -static void SetWindowScrollY(ImGuiWindow* window, float new_scroll_y); -static void SetWindowPos(ImGuiWindow* window, const ImVec2& pos, ImGuiSetCond cond); -static void SetWindowSize(ImGuiWindow* window, const ImVec2& size, ImGuiSetCond cond); -static void SetWindowCollapsed(ImGuiWindow* window, bool collapsed, ImGuiSetCond cond); -static ImGuiWindow* FindHoveredWindow(ImVec2 pos, bool excluding_childs); -static ImGuiWindow* CreateNewWindow(const char* name, ImVec2 size, ImGuiWindowFlags flags); -static inline bool IsWindowContentHoverable(ImGuiWindow* window); -static void ClearSetNextWindowData(); -static void CheckStacksSize(ImGuiWindow* window, bool write); -static void Scrollbar(ImGuiWindow* window, bool horizontal); - -static void AddDrawListToRenderList(ImVector<ImDrawList*>& out_render_list, ImDrawList* draw_list); -static void AddWindowToRenderList(ImVector<ImDrawList*>& out_render_list, ImGuiWindow* window); -static void AddWindowToSortedBuffer(ImVector<ImGuiWindow*>& out_sorted_windows, ImGuiWindow* window); - -static ImGuiIniData* FindWindowSettings(const char* name); -static ImGuiIniData* AddWindowSettings(const char* name); -static void LoadSettings(); -static void SaveSettings(); -static void MarkSettingsDirty(); - -static void PushColumnClipRect(int column_index = -1); -static ImRect GetVisibleRect(); - -static bool BeginPopupEx(const char* str_id, ImGuiWindowFlags extra_flags); -static void CloseInactivePopups(); -static void ClosePopupToLevel(int remaining); -static void ClosePopup(ImGuiID id); -static bool IsPopupOpen(ImGuiID id); -static ImGuiWindow* GetFrontMostModalRootWindow(); -static ImVec2 FindBestPopupWindowPos(const ImVec2& base_pos, const ImVec2& size, int* last_dir, const ImRect& rect_to_avoid); - -static bool InputTextFilterCharacter(unsigned int* p_char, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data); -static int InputTextCalcTextLenAndLineCount(const char* text_begin, const char** out_text_end); -static ImVec2 InputTextCalcTextSizeW(const ImWchar* text_begin, const ImWchar* text_end, const ImWchar** remaining = NULL, ImVec2* out_offset = NULL, bool stop_on_new_line = false); - -static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, const char* display_format, char* buf, int buf_size); -static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, int decimal_precision, char* buf, int buf_size); -static void DataTypeApplyOp(ImGuiDataType data_type, int op, void* value1, const void* value2); -static bool DataTypeApplyOpFromText(const char* buf, const char* initial_value_buf, ImGuiDataType data_type, void* data_ptr, const char* scalar_format); - -//----------------------------------------------------------------------------- -// Platform dependent default implementations -//----------------------------------------------------------------------------- - -static const char* GetClipboardTextFn_DefaultImpl(); -static void SetClipboardTextFn_DefaultImpl(const char* text); -static void ImeSetInputScreenPosFn_DefaultImpl(int x, int y); - -//----------------------------------------------------------------------------- -// Context -//----------------------------------------------------------------------------- - -// Default context, default font atlas. -// New contexts always point by default to this font atlas. It can be changed by reassigning the GetIO().Fonts variable. -static ImGuiContext GImDefaultContext; -static ImFontAtlas GImDefaultFontAtlas; - -// Current context pointer. Implicitely used by all ImGui functions. Always assumed to be != NULL. Change to a different context by calling ImGui::SetCurrentContext() -// ImGui is currently not thread-safe because of this variable. If you want thread-safety to allow N threads to access N different contexts, you might work around it by (A) having two instances of the ImGui code under different namespaces or (B) change this variable to be TLS. Further development aim to make this context pointer explicit to all calls. Also read https://github.com/ocornut/imgui/issues/586 -ImGuiContext* GImGui = &GImDefaultContext; - -//----------------------------------------------------------------------------- -// User facing structures -//----------------------------------------------------------------------------- - -ImGuiStyle::ImGuiStyle() -{ - Alpha = 1.0f; // Global alpha applies to everything in ImGui - WindowPadding = ImVec2(8,8); // Padding within a window - WindowMinSize = ImVec2(32,32); // Minimum window size - WindowRounding = 9.0f; // Radius of window corners rounding. Set to 0.0f to have rectangular windows - WindowTitleAlign = ImVec2(0.0f,0.5f);// Alignment for title bar text - ChildWindowRounding = 0.0f; // Radius of child window corners rounding. Set to 0.0f to have rectangular child windows - FramePadding = ImVec2(4,3); // Padding within a framed rectangle (used by most widgets) - FrameRounding = 0.0f; // Radius of frame corners rounding. Set to 0.0f to have rectangular frames (used by most widgets). - ItemSpacing = ImVec2(8,4); // Horizontal and vertical spacing between widgets/lines - ItemInnerSpacing = ImVec2(4,4); // Horizontal and vertical spacing between within elements of a composed widget (e.g. a slider and its label) - TouchExtraPadding = ImVec2(0,0); // Expand reactive bounding box for touch-based system where touch position is not accurate enough. Unfortunately we don't sort widgets so priority on overlap will always be given to the first widget. So don't grow this too much! - IndentSpacing = 21.0f; // Horizontal spacing when e.g. entering a tree node. Generally == (FontSize + FramePadding.x*2). - ColumnsMinSpacing = 6.0f; // Minimum horizontal spacing between two columns - ScrollbarSize = 16.0f; // Width of the vertical scrollbar, Height of the horizontal scrollbar - ScrollbarRounding = 9.0f; // Radius of grab corners rounding for scrollbar - GrabMinSize = 10.0f; // Minimum width/height of a grab box for slider/scrollbar - GrabRounding = 0.0f; // Radius of grabs corners rounding. Set to 0.0f to have rectangular slider grabs. - ButtonTextAlign = ImVec2(0.5f,0.5f);// Alignment of button text when button is larger than text. - DisplayWindowPadding = ImVec2(22,22); // Window positions are clamped to be visible within the display area by at least this amount. Only covers regular windows. - DisplaySafeAreaPadding = ImVec2(4,4); // If you cannot see the edge of your screen (e.g. on a TV) increase the safe area padding. Covers popups/tooltips as well regular windows. - AntiAliasedLines = true; // Enable anti-aliasing on lines/borders. Disable if you are really short on CPU/GPU. - AntiAliasedShapes = true; // Enable anti-aliasing on filled shapes (rounded rectangles, circles, etc.) - CurveTessellationTol = 1.25f; // Tessellation tolerance. Decrease for highly tessellated curves (higher quality, more polygons), increase to reduce quality. - - Colors[ImGuiCol_Text] = ImVec4(0.90f, 0.90f, 0.90f, 1.00f); - Colors[ImGuiCol_TextDisabled] = ImVec4(0.60f, 0.60f, 0.60f, 1.00f); - Colors[ImGuiCol_WindowBg] = ImVec4(0.00f, 0.00f, 0.00f, 0.70f); - Colors[ImGuiCol_ChildWindowBg] = ImVec4(0.00f, 0.00f, 0.00f, 0.00f); - Colors[ImGuiCol_PopupBg] = ImVec4(0.05f, 0.05f, 0.10f, 0.90f); - Colors[ImGuiCol_Border] = ImVec4(0.70f, 0.70f, 0.70f, 0.65f); - Colors[ImGuiCol_BorderShadow] = ImVec4(0.00f, 0.00f, 0.00f, 0.00f); - Colors[ImGuiCol_FrameBg] = ImVec4(0.80f, 0.80f, 0.80f, 0.30f); // Background of checkbox, radio button, plot, slider, text input - Colors[ImGuiCol_FrameBgHovered] = ImVec4(0.90f, 0.80f, 0.80f, 0.40f); - Colors[ImGuiCol_FrameBgActive] = ImVec4(0.90f, 0.65f, 0.65f, 0.45f); - Colors[ImGuiCol_TitleBg] = ImVec4(0.27f, 0.27f, 0.54f, 0.83f); - Colors[ImGuiCol_TitleBgCollapsed] = ImVec4(0.40f, 0.40f, 0.80f, 0.20f); - Colors[ImGuiCol_TitleBgActive] = ImVec4(0.32f, 0.32f, 0.63f, 0.87f); - Colors[ImGuiCol_MenuBarBg] = ImVec4(0.40f, 0.40f, 0.55f, 0.80f); - Colors[ImGuiCol_ScrollbarBg] = ImVec4(0.20f, 0.25f, 0.30f, 0.60f); - Colors[ImGuiCol_ScrollbarGrab] = ImVec4(0.40f, 0.40f, 0.80f, 0.30f); - Colors[ImGuiCol_ScrollbarGrabHovered] = ImVec4(0.40f, 0.40f, 0.80f, 0.40f); - Colors[ImGuiCol_ScrollbarGrabActive] = ImVec4(0.80f, 0.50f, 0.50f, 0.40f); - Colors[ImGuiCol_ComboBg] = ImVec4(0.20f, 0.20f, 0.20f, 0.99f); - Colors[ImGuiCol_CheckMark] = ImVec4(0.90f, 0.90f, 0.90f, 0.50f); - Colors[ImGuiCol_SliderGrab] = ImVec4(1.00f, 1.00f, 1.00f, 0.30f); - Colors[ImGuiCol_SliderGrabActive] = ImVec4(0.80f, 0.50f, 0.50f, 1.00f); - Colors[ImGuiCol_Button] = ImVec4(0.67f, 0.40f, 0.40f, 0.60f); - Colors[ImGuiCol_ButtonHovered] = ImVec4(0.67f, 0.40f, 0.40f, 1.00f); - Colors[ImGuiCol_ButtonActive] = ImVec4(0.80f, 0.50f, 0.50f, 1.00f); - Colors[ImGuiCol_Header] = ImVec4(0.40f, 0.40f, 0.90f, 0.45f); - Colors[ImGuiCol_HeaderHovered] = ImVec4(0.45f, 0.45f, 0.90f, 0.80f); - Colors[ImGuiCol_HeaderActive] = ImVec4(0.53f, 0.53f, 0.87f, 0.80f); - Colors[ImGuiCol_Column] = ImVec4(0.50f, 0.50f, 0.50f, 1.00f); - Colors[ImGuiCol_ColumnHovered] = ImVec4(0.70f, 0.60f, 0.60f, 1.00f); - Colors[ImGuiCol_ColumnActive] = ImVec4(0.90f, 0.70f, 0.70f, 1.00f); - Colors[ImGuiCol_ResizeGrip] = ImVec4(1.00f, 1.00f, 1.00f, 0.30f); - Colors[ImGuiCol_ResizeGripHovered] = ImVec4(1.00f, 1.00f, 1.00f, 0.60f); - Colors[ImGuiCol_ResizeGripActive] = ImVec4(1.00f, 1.00f, 1.00f, 0.90f); - Colors[ImGuiCol_CloseButton] = ImVec4(0.50f, 0.50f, 0.90f, 0.50f); - Colors[ImGuiCol_CloseButtonHovered] = ImVec4(0.70f, 0.70f, 0.90f, 0.60f); - Colors[ImGuiCol_CloseButtonActive] = ImVec4(0.70f, 0.70f, 0.70f, 1.00f); - Colors[ImGuiCol_PlotLines] = ImVec4(1.00f, 1.00f, 1.00f, 1.00f); - Colors[ImGuiCol_PlotLinesHovered] = ImVec4(0.90f, 0.70f, 0.00f, 1.00f); - Colors[ImGuiCol_PlotHistogram] = ImVec4(0.90f, 0.70f, 0.00f, 1.00f); - Colors[ImGuiCol_PlotHistogramHovered] = ImVec4(1.00f, 0.60f, 0.00f, 1.00f); - Colors[ImGuiCol_TextSelectedBg] = ImVec4(0.00f, 0.00f, 1.00f, 0.35f); - Colors[ImGuiCol_ModalWindowDarkening] = ImVec4(0.20f, 0.20f, 0.20f, 0.35f); -} - -ImGuiIO::ImGuiIO() -{ - // Most fields are initialized with zero - memset(this, 0, sizeof(*this)); - - DisplaySize = ImVec2(-1.0f, -1.0f); - DeltaTime = 1.0f/60.0f; - IniSavingRate = 5.0f; - IniFilename = "imgui.ini"; - LogFilename = "imgui_log.txt"; - Fonts = &GImDefaultFontAtlas; - FontGlobalScale = 1.0f; - DisplayFramebufferScale = ImVec2(1.0f, 1.0f); - MousePos = ImVec2(-1,-1); - MousePosPrev = ImVec2(-1,-1); - MouseDoubleClickTime = 0.30f; - MouseDoubleClickMaxDist = 6.0f; - MouseDragThreshold = 6.0f; - for (int i = 0; i < IM_ARRAYSIZE(MouseDownDuration); i++) - MouseDownDuration[i] = MouseDownDurationPrev[i] = -1.0f; - for (int i = 0; i < IM_ARRAYSIZE(KeysDownDuration); i++) - KeysDownDuration[i] = KeysDownDurationPrev[i] = -1.0f; - for (int i = 0; i < ImGuiKey_COUNT; i++) - KeyMap[i] = -1; - KeyRepeatDelay = 0.250f; - KeyRepeatRate = 0.050f; - UserData = NULL; - - // User functions - RenderDrawListsFn = NULL; - MemAllocFn = malloc; - MemFreeFn = free; - GetClipboardTextFn = GetClipboardTextFn_DefaultImpl; // Platform dependent default implementations - SetClipboardTextFn = SetClipboardTextFn_DefaultImpl; - ImeSetInputScreenPosFn = ImeSetInputScreenPosFn_DefaultImpl; - - // Set OS X style defaults based on __APPLE__ compile time flag -#ifdef __APPLE__ - OSXBehaviors = true; -#endif -} - -// Pass in translated ASCII characters for text input. -// - with glfw you can get those from the callback set in glfwSetCharCallback() -// - on Windows you can get those using ToAscii+keyboard state, or via the WM_CHAR message -void ImGuiIO::AddInputCharacter(ImWchar c) -{ - const int n = ImStrlenW(InputCharacters); - if (n + 1 < IM_ARRAYSIZE(InputCharacters)) - { - InputCharacters[n] = c; - InputCharacters[n+1] = '\0'; - } -} - -void ImGuiIO::AddInputCharactersUTF8(const char* utf8_chars) -{ - // We can't pass more wchars than ImGuiIO::InputCharacters[] can hold so don't convert more - const int wchars_buf_len = sizeof(ImGuiIO::InputCharacters) / sizeof(ImWchar); - ImWchar wchars[wchars_buf_len]; - ImTextStrFromUtf8(wchars, wchars_buf_len, utf8_chars, NULL); - for (int i = 0; i < wchars_buf_len && wchars[i] != 0; i++) - AddInputCharacter(wchars[i]); -} - -//----------------------------------------------------------------------------- -// HELPERS -//----------------------------------------------------------------------------- - -#define IM_F32_TO_INT8_UNBOUND(_VAL) ((int)((_VAL) * 255.0f + ((_VAL)>=0 ? 0.5f : -0.5f))) // Unsaturated, for display purpose -#define IM_F32_TO_INT8_SAT(_VAL) ((int)(ImSaturate(_VAL) * 255.0f + 0.5f)) // Saturated, always output 0..255 - -// Play it nice with Windows users. Notepad in 2015 still doesn't display text data with Unix-style \n. -#ifdef _WIN32 -#define IM_NEWLINE "\r\n" -#else -#define IM_NEWLINE "\n" -#endif - -bool ImIsPointInTriangle(const ImVec2& p, const ImVec2& a, const ImVec2& b, const ImVec2& c) -{ - bool b1 = ((p.x - b.x) * (a.y - b.y) - (p.y - b.y) * (a.x - b.x)) < 0.0f; - bool b2 = ((p.x - c.x) * (b.y - c.y) - (p.y - c.y) * (b.x - c.x)) < 0.0f; - bool b3 = ((p.x - a.x) * (c.y - a.y) - (p.y - a.y) * (c.x - a.x)) < 0.0f; - return ((b1 == b2) && (b2 == b3)); -} - -int ImStricmp(const char* str1, const char* str2) -{ - int d; - while ((d = toupper(*str2) - toupper(*str1)) == 0 && *str1) { str1++; str2++; } - return d; -} - -int ImStrnicmp(const char* str1, const char* str2, int count) -{ - int d = 0; - while (count > 0 && (d = toupper(*str2) - toupper(*str1)) == 0 && *str1) { str1++; str2++; count--; } - return d; -} - -void ImStrncpy(char* dst, const char* src, int count) -{ - if (count < 1) return; - strncpy(dst, src, (size_t)count); - dst[count-1] = 0; -} - -char* ImStrdup(const char *str) -{ - size_t len = strlen(str) + 1; - void* buff = ImGui::MemAlloc(len); - return (char*)memcpy(buff, (const void*)str, len); -} - -int ImStrlenW(const ImWchar* str) -{ - int n = 0; - while (*str++) n++; - return n; -} - -const ImWchar* ImStrbolW(const ImWchar* buf_mid_line, const ImWchar* buf_begin) // find beginning-of-line -{ - while (buf_mid_line > buf_begin && buf_mid_line[-1] != '\n') - buf_mid_line--; - return buf_mid_line; -} - -const char* ImStristr(const char* haystack, const char* haystack_end, const char* needle, const char* needle_end) -{ - if (!needle_end) - needle_end = needle + strlen(needle); - - const char un0 = (char)toupper(*needle); - while ((!haystack_end && *haystack) || (haystack_end && haystack < haystack_end)) - { - if (toupper(*haystack) == un0) - { - const char* b = needle + 1; - for (const char* a = haystack + 1; b < needle_end; a++, b++) - if (toupper(*a) != toupper(*b)) - break; - if (b == needle_end) - return haystack; - } - haystack++; - } - return NULL; -} - - -// MSVC version appears to return -1 on overflow, whereas glibc appears to return total count (which may be >= buf_size). -// Ideally we would test for only one of those limits at runtime depending on the behavior the vsnprintf(), but trying to deduct it at compile time sounds like a pandora can of worm. -int ImFormatString(char* buf, int buf_size, const char* fmt, ...) -{ - IM_ASSERT(buf_size > 0); - va_list args; - va_start(args, fmt); - int w = vsnprintf(buf, buf_size, fmt, args); - va_end(args); - if (w == -1 || w >= buf_size) - w = buf_size - 1; - buf[w] = 0; - return w; -} - -int ImFormatStringV(char* buf, int buf_size, const char* fmt, va_list args) -{ - IM_ASSERT(buf_size > 0); - int w = vsnprintf(buf, buf_size, fmt, args); - if (w == -1 || w >= buf_size) - w = buf_size - 1; - buf[w] = 0; - return w; -} - -// Pass data_size==0 for zero-terminated strings -// FIXME-OPT: Replace with e.g. FNV1a hash? CRC32 pretty much randomly access 1KB. Need to do proper measurements. -ImU32 ImHash(const void* data, int data_size, ImU32 seed) -{ - static ImU32 crc32_lut[256] = { 0 }; - if (!crc32_lut[1]) - { - const ImU32 polynomial = 0xEDB88320; - for (ImU32 i = 0; i < 256; i++) - { - ImU32 crc = i; - for (ImU32 j = 0; j < 8; j++) - crc = (crc >> 1) ^ (ImU32(-int(crc & 1)) & polynomial); - crc32_lut[i] = crc; - } - } - - seed = ~seed; - ImU32 crc = seed; - const unsigned char* current = (const unsigned char*)data; - - if (data_size > 0) - { - // Known size - while (data_size--) - crc = (crc >> 8) ^ crc32_lut[(crc & 0xFF) ^ *current++]; - } - else - { - // Zero-terminated string - while (unsigned char c = *current++) - { - // We support a syntax of "label###id" where only "###id" is included in the hash, and only "label" gets displayed. - // Because this syntax is rarely used we are optimizing for the common case. - // - If we reach ### in the string we discard the hash so far and reset to the seed. - // - We don't do 'current += 2; continue;' after handling ### to keep the code smaller. - if (c == '#' && current[0] == '#' && current[1] == '#') - crc = seed; - crc = (crc >> 8) ^ crc32_lut[(crc & 0xFF) ^ c]; - } - } - return ~crc; -} - -//----------------------------------------------------------------------------- -// ImText* helpers -//----------------------------------------------------------------------------- - -// Convert UTF-8 to 32-bits character, process single character input. -// Based on stb_from_utf8() from github.com/nothings/stb/ -// We handle UTF-8 decoding error by skipping forward. -int ImTextCharFromUtf8(unsigned int* out_char, const char* in_text, const char* in_text_end) -{ - unsigned int c = (unsigned int)-1; - const unsigned char* str = (const unsigned char*)in_text; - if (!(*str & 0x80)) - { - c = (unsigned int)(*str++); - *out_char = c; - return 1; - } - if ((*str & 0xe0) == 0xc0) - { - *out_char = 0xFFFD; // will be invalid but not end of string - if (in_text_end && in_text_end - (const char*)str < 2) return 1; - if (*str < 0xc2) return 2; - c = (unsigned int)((*str++ & 0x1f) << 6); - if ((*str & 0xc0) != 0x80) return 2; - c += (*str++ & 0x3f); - *out_char = c; - return 2; - } - if ((*str & 0xf0) == 0xe0) - { - *out_char = 0xFFFD; // will be invalid but not end of string - if (in_text_end && in_text_end - (const char*)str < 3) return 1; - if (*str == 0xe0 && (str[1] < 0xa0 || str[1] > 0xbf)) return 3; - if (*str == 0xed && str[1] > 0x9f) return 3; // str[1] < 0x80 is checked below - c = (unsigned int)((*str++ & 0x0f) << 12); - if ((*str & 0xc0) != 0x80) return 3; - c += (unsigned int)((*str++ & 0x3f) << 6); - if ((*str & 0xc0) != 0x80) return 3; - c += (*str++ & 0x3f); - *out_char = c; - return 3; - } - if ((*str & 0xf8) == 0xf0) - { - *out_char = 0xFFFD; // will be invalid but not end of string - if (in_text_end && in_text_end - (const char*)str < 4) return 1; - if (*str > 0xf4) return 4; - if (*str == 0xf0 && (str[1] < 0x90 || str[1] > 0xbf)) return 4; - if (*str == 0xf4 && str[1] > 0x8f) return 4; // str[1] < 0x80 is checked below - c = (unsigned int)((*str++ & 0x07) << 18); - if ((*str & 0xc0) != 0x80) return 4; - c += (unsigned int)((*str++ & 0x3f) << 12); - if ((*str & 0xc0) != 0x80) return 4; - c += (unsigned int)((*str++ & 0x3f) << 6); - if ((*str & 0xc0) != 0x80) return 4; - c += (*str++ & 0x3f); - // utf-8 encodings of values used in surrogate pairs are invalid - if ((c & 0xFFFFF800) == 0xD800) return 4; - *out_char = c; - return 4; - } - *out_char = 0; - return 0; -} - -int ImTextStrFromUtf8(ImWchar* buf, int buf_size, const char* in_text, const char* in_text_end, const char** in_text_remaining) -{ - ImWchar* buf_out = buf; - ImWchar* buf_end = buf + buf_size; - while (buf_out < buf_end-1 && (!in_text_end || in_text < in_text_end) && *in_text) - { - unsigned int c; - in_text += ImTextCharFromUtf8(&c, in_text, in_text_end); - if (c == 0) - break; - if (c < 0x10000) // FIXME: Losing characters that don't fit in 2 bytes - *buf_out++ = (ImWchar)c; - } - *buf_out = 0; - if (in_text_remaining) - *in_text_remaining = in_text; - return (int)(buf_out - buf); -} - -int ImTextCountCharsFromUtf8(const char* in_text, const char* in_text_end) -{ - int char_count = 0; - while ((!in_text_end || in_text < in_text_end) && *in_text) - { - unsigned int c; - in_text += ImTextCharFromUtf8(&c, in_text, in_text_end); - if (c == 0) - break; - if (c < 0x10000) - char_count++; - } - return char_count; -} - -// Based on stb_to_utf8() from github.com/nothings/stb/ -static inline int ImTextCharToUtf8(char* buf, int buf_size, unsigned int c) -{ - if (c < 0x80) - { - buf[0] = (char)c; - return 1; - } - if (c < 0x800) - { - if (buf_size < 2) return 0; - buf[0] = (char)(0xc0 + (c >> 6)); - buf[1] = (char)(0x80 + (c & 0x3f)); - return 2; - } - if (c >= 0xdc00 && c < 0xe000) - { - return 0; - } - if (c >= 0xd800 && c < 0xdc00) - { - if (buf_size < 4) return 0; - buf[0] = (char)(0xf0 + (c >> 18)); - buf[1] = (char)(0x80 + ((c >> 12) & 0x3f)); - buf[2] = (char)(0x80 + ((c >> 6) & 0x3f)); - buf[3] = (char)(0x80 + ((c ) & 0x3f)); - return 4; - } - //else if (c < 0x10000) - { - if (buf_size < 3) return 0; - buf[0] = (char)(0xe0 + (c >> 12)); - buf[1] = (char)(0x80 + ((c>> 6) & 0x3f)); - buf[2] = (char)(0x80 + ((c ) & 0x3f)); - return 3; - } -} - -static inline int ImTextCountUtf8BytesFromChar(unsigned int c) -{ - if (c < 0x80) return 1; - if (c < 0x800) return 2; - if (c >= 0xdc00 && c < 0xe000) return 0; - if (c >= 0xd800 && c < 0xdc00) return 4; - return 3; -} - -int ImTextStrToUtf8(char* buf, int buf_size, const ImWchar* in_text, const ImWchar* in_text_end) -{ - char* buf_out = buf; - const char* buf_end = buf + buf_size; - while (buf_out < buf_end-1 && (!in_text_end || in_text < in_text_end) && *in_text) - { - unsigned int c = (unsigned int)(*in_text++); - if (c < 0x80) - *buf_out++ = (char)c; - else - buf_out += ImTextCharToUtf8(buf_out, (int)(buf_end-buf_out-1), c); - } - *buf_out = 0; - return (int)(buf_out - buf); -} - -int ImTextCountUtf8BytesFromStr(const ImWchar* in_text, const ImWchar* in_text_end) -{ - int bytes_count = 0; - while ((!in_text_end || in_text < in_text_end) && *in_text) - { - unsigned int c = (unsigned int)(*in_text++); - if (c < 0x80) - bytes_count++; - else - bytes_count += ImTextCountUtf8BytesFromChar(c); - } - return bytes_count; -} - -ImVec4 ImGui::ColorConvertU32ToFloat4(ImU32 in) -{ - float s = 1.0f/255.0f; - return ImVec4( - ((in >> IM_COL32_R_SHIFT) & 0xFF) * s, - ((in >> IM_COL32_G_SHIFT) & 0xFF) * s, - ((in >> IM_COL32_B_SHIFT) & 0xFF) * s, - ((in >> IM_COL32_A_SHIFT) & 0xFF) * s); -} - -ImU32 ImGui::ColorConvertFloat4ToU32(const ImVec4& in) -{ - ImU32 out; - out = ((ImU32)IM_F32_TO_INT8_SAT(in.x)) << IM_COL32_R_SHIFT; - out |= ((ImU32)IM_F32_TO_INT8_SAT(in.y)) << IM_COL32_G_SHIFT; - out |= ((ImU32)IM_F32_TO_INT8_SAT(in.z)) << IM_COL32_B_SHIFT; - out |= ((ImU32)IM_F32_TO_INT8_SAT(in.w)) << IM_COL32_A_SHIFT; - return out; -} - -ImU32 ImGui::GetColorU32(ImGuiCol idx, float alpha_mul) -{ - ImVec4 c = GImGui->Style.Colors[idx]; - c.w *= GImGui->Style.Alpha * alpha_mul; - return ColorConvertFloat4ToU32(c); -} - -ImU32 ImGui::GetColorU32(const ImVec4& col) -{ - ImVec4 c = col; - c.w *= GImGui->Style.Alpha; - return ColorConvertFloat4ToU32(c); -} - -// Convert rgb floats ([0-1],[0-1],[0-1]) to hsv floats ([0-1],[0-1],[0-1]), from Foley & van Dam p592 -// Optimized http://lolengine.net/blog/2013/01/13/fast-rgb-to-hsv -void ImGui::ColorConvertRGBtoHSV(float r, float g, float b, float& out_h, float& out_s, float& out_v) -{ - float K = 0.f; - if (g < b) - { - const float tmp = g; g = b; b = tmp; - K = -1.f; - } - if (r < g) - { - const float tmp = r; r = g; g = tmp; - K = -2.f / 6.f - K; - } - - const float chroma = r - (g < b ? g : b); - out_h = fabsf(K + (g - b) / (6.f * chroma + 1e-20f)); - out_s = chroma / (r + 1e-20f); - out_v = r; -} - -// Convert hsv floats ([0-1],[0-1],[0-1]) to rgb floats ([0-1],[0-1],[0-1]), from Foley & van Dam p593 -// also http://en.wikipedia.org/wiki/HSL_and_HSV -void ImGui::ColorConvertHSVtoRGB(float h, float s, float v, float& out_r, float& out_g, float& out_b) -{ - if (s == 0.0f) - { - // gray - out_r = out_g = out_b = v; - return; - } - - h = fmodf(h, 1.0f) / (60.0f/360.0f); - int i = (int)h; - float f = h - (float)i; - float p = v * (1.0f - s); - float q = v * (1.0f - s * f); - float t = v * (1.0f - s * (1.0f - f)); - - switch (i) - { - case 0: out_r = v; out_g = t; out_b = p; break; - case 1: out_r = q; out_g = v; out_b = p; break; - case 2: out_r = p; out_g = v; out_b = t; break; - case 3: out_r = p; out_g = q; out_b = v; break; - case 4: out_r = t; out_g = p; out_b = v; break; - case 5: default: out_r = v; out_g = p; out_b = q; break; - } -} - -// Load file content into memory -// Memory allocated with ImGui::MemAlloc(), must be freed by user using ImGui::MemFree() -void* ImLoadFileToMemory(const char* filename, const char* file_open_mode, int* out_file_size, int padding_bytes) -{ - IM_ASSERT(filename && file_open_mode); - if (out_file_size) - *out_file_size = 0; - - FILE* f; - if ((f = fopen(filename, file_open_mode)) == NULL) - return NULL; - - long file_size_signed; - if (fseek(f, 0, SEEK_END) || (file_size_signed = ftell(f)) == -1 || fseek(f, 0, SEEK_SET)) - { - fclose(f); - return NULL; - } - - int file_size = (int)file_size_signed; - void* file_data = ImGui::MemAlloc(file_size + padding_bytes); - if (file_data == NULL) - { - fclose(f); - return NULL; - } - if (fread(file_data, 1, (size_t)file_size, f) != (size_t)file_size) - { - fclose(f); - ImGui::MemFree(file_data); - return NULL; - } - if (padding_bytes > 0) - memset((void *)(((char*)file_data) + file_size), 0, padding_bytes); - - fclose(f); - if (out_file_size) - *out_file_size = file_size; - - return file_data; -} - -//----------------------------------------------------------------------------- -// ImGuiStorage -//----------------------------------------------------------------------------- - -// Helper: Key->value storage -void ImGuiStorage::Clear() -{ - Data.clear(); -} - -// std::lower_bound but without the bullshit -static ImVector<ImGuiStorage::Pair>::iterator LowerBound(ImVector<ImGuiStorage::Pair>& data, ImGuiID key) -{ - ImVector<ImGuiStorage::Pair>::iterator first = data.begin(); - ImVector<ImGuiStorage::Pair>::iterator last = data.end(); - int count = (int)(last - first); - while (count > 0) - { - int count2 = count / 2; - ImVector<ImGuiStorage::Pair>::iterator mid = first + count2; - if (mid->key < key) - { - first = ++mid; - count -= count2 + 1; - } - else - { - count = count2; - } - } - return first; -} - -int ImGuiStorage::GetInt(ImGuiID key, int default_val) const -{ - ImVector<Pair>::iterator it = LowerBound(const_cast<ImVector<ImGuiStorage::Pair>&>(Data), key); - if (it == Data.end() || it->key != key) - return default_val; - return it->val_i; -} - -bool ImGuiStorage::GetBool(ImGuiID key, bool default_val) const -{ - return GetInt(key, default_val ? 1 : 0) != 0; -} - -float ImGuiStorage::GetFloat(ImGuiID key, float default_val) const -{ - ImVector<Pair>::iterator it = LowerBound(const_cast<ImVector<ImGuiStorage::Pair>&>(Data), key); - if (it == Data.end() || it->key != key) - return default_val; - return it->val_f; -} - -void* ImGuiStorage::GetVoidPtr(ImGuiID key) const -{ - ImVector<Pair>::iterator it = LowerBound(const_cast<ImVector<ImGuiStorage::Pair>&>(Data), key); - if (it == Data.end() || it->key != key) - return NULL; - return it->val_p; -} - -// References are only valid until a new value is added to the storage. Calling a Set***() function or a Get***Ref() function invalidates the pointer. -int* ImGuiStorage::GetIntRef(ImGuiID key, int default_val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - it = Data.insert(it, Pair(key, default_val)); - return &it->val_i; -} - -bool* ImGuiStorage::GetBoolRef(ImGuiID key, bool default_val) -{ - return (bool*)GetIntRef(key, default_val ? 1 : 0); -} - -float* ImGuiStorage::GetFloatRef(ImGuiID key, float default_val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - it = Data.insert(it, Pair(key, default_val)); - return &it->val_f; -} - -void** ImGuiStorage::GetVoidPtrRef(ImGuiID key, void* default_val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - it = Data.insert(it, Pair(key, default_val)); - return &it->val_p; -} - -// FIXME-OPT: Need a way to reuse the result of lower_bound when doing GetInt()/SetInt() - not too bad because it only happens on explicit interaction (maximum one a frame) -void ImGuiStorage::SetInt(ImGuiID key, int val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - { - Data.insert(it, Pair(key, val)); - return; - } - it->val_i = val; -} - -void ImGuiStorage::SetBool(ImGuiID key, bool val) -{ - SetInt(key, val ? 1 : 0); -} - -void ImGuiStorage::SetFloat(ImGuiID key, float val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - { - Data.insert(it, Pair(key, val)); - return; - } - it->val_f = val; -} - -void ImGuiStorage::SetVoidPtr(ImGuiID key, void* val) -{ - ImVector<Pair>::iterator it = LowerBound(Data, key); - if (it == Data.end() || it->key != key) - { - Data.insert(it, Pair(key, val)); - return; - } - it->val_p = val; -} - -void ImGuiStorage::SetAllInt(int v) -{ - for (int i = 0; i < Data.Size; i++) - Data[i].val_i = v; -} - -//----------------------------------------------------------------------------- -// ImGuiTextFilter -//----------------------------------------------------------------------------- - -// Helper: Parse and apply text filters. In format "aaaaa[,bbbb][,ccccc]" -ImGuiTextFilter::ImGuiTextFilter(const char* default_filter) -{ - if (default_filter) - { - ImStrncpy(InputBuf, default_filter, IM_ARRAYSIZE(InputBuf)); - Build(); - } - else - { - InputBuf[0] = 0; - CountGrep = 0; - } -} - -bool ImGuiTextFilter::Draw(const char* label, float width) -{ - if (width != 0.0f) - ImGui::PushItemWidth(width); - bool value_changed = ImGui::InputText(label, InputBuf, IM_ARRAYSIZE(InputBuf)); - if (width != 0.0f) - ImGui::PopItemWidth(); - if (value_changed) - Build(); - return value_changed; -} - -void ImGuiTextFilter::TextRange::split(char separator, ImVector<TextRange>& out) -{ - out.resize(0); - const char* wb = b; - const char* we = wb; - while (we < e) - { - if (*we == separator) - { - out.push_back(TextRange(wb, we)); - wb = we + 1; - } - we++; - } - if (wb != we) - out.push_back(TextRange(wb, we)); -} - -void ImGuiTextFilter::Build() -{ - Filters.resize(0); - TextRange input_range(InputBuf, InputBuf+strlen(InputBuf)); - input_range.split(',', Filters); - - CountGrep = 0; - for (int i = 0; i != Filters.Size; i++) - { - Filters[i].trim_blanks(); - if (Filters[i].empty()) - continue; - if (Filters[i].front() != '-') - CountGrep += 1; - } -} - -bool ImGuiTextFilter::PassFilter(const char* text, const char* text_end) const -{ - if (Filters.empty()) - return true; - - if (text == NULL) - text = ""; - - for (int i = 0; i != Filters.Size; i++) - { - const TextRange& f = Filters[i]; - if (f.empty()) - continue; - if (f.front() == '-') - { - // Subtract - if (ImStristr(text, text_end, f.begin()+1, f.end()) != NULL) - return false; - } - else - { - // Grep - if (ImStristr(text, text_end, f.begin(), f.end()) != NULL) - return true; - } - } - - // Implicit * grep - if (CountGrep == 0) - return true; - - return false; -} - -//----------------------------------------------------------------------------- -// ImGuiTextBuffer -//----------------------------------------------------------------------------- - -// On some platform vsnprintf() takes va_list by reference and modifies it. -// va_copy is the 'correct' way to copy a va_list but Visual Studio prior to 2013 doesn't have it. -#ifndef va_copy -#define va_copy(dest, src) (dest = src) -#endif - -// Helper: Text buffer for logging/accumulating text -void ImGuiTextBuffer::appendv(const char* fmt, va_list args) -{ - va_list args_copy; - va_copy(args_copy, args); - - int len = vsnprintf(NULL, 0, fmt, args); // FIXME-OPT: could do a first pass write attempt, likely successful on first pass. - if (len <= 0) - return; - - const int write_off = Buf.Size; - const int needed_sz = write_off + len; - if (write_off + len >= Buf.Capacity) - { - int double_capacity = Buf.Capacity * 2; - Buf.reserve(needed_sz > double_capacity ? needed_sz : double_capacity); - } - - Buf.resize(needed_sz); - ImFormatStringV(&Buf[write_off] - 1, len+1, fmt, args_copy); -} - -void ImGuiTextBuffer::append(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - appendv(fmt, args); - va_end(args); -} - -//----------------------------------------------------------------------------- -// ImGuiSimpleColumns -//----------------------------------------------------------------------------- - -ImGuiSimpleColumns::ImGuiSimpleColumns() -{ - Count = 0; - Spacing = Width = NextWidth = 0.0f; - memset(Pos, 0, sizeof(Pos)); - memset(NextWidths, 0, sizeof(NextWidths)); -} - -void ImGuiSimpleColumns::Update(int count, float spacing, bool clear) -{ - IM_ASSERT(Count <= IM_ARRAYSIZE(Pos)); - Count = count; - Width = NextWidth = 0.0f; - Spacing = spacing; - if (clear) memset(NextWidths, 0, sizeof(NextWidths)); - for (int i = 0; i < Count; i++) - { - if (i > 0 && NextWidths[i] > 0.0f) - Width += Spacing; - Pos[i] = (float)(int)Width; - Width += NextWidths[i]; - NextWidths[i] = 0.0f; - } -} - -float ImGuiSimpleColumns::DeclColumns(float w0, float w1, float w2) // not using va_arg because they promote float to double -{ - NextWidth = 0.0f; - NextWidths[0] = ImMax(NextWidths[0], w0); - NextWidths[1] = ImMax(NextWidths[1], w1); - NextWidths[2] = ImMax(NextWidths[2], w2); - for (int i = 0; i < 3; i++) - NextWidth += NextWidths[i] + ((i > 0 && NextWidths[i] > 0.0f) ? Spacing : 0.0f); - return ImMax(Width, NextWidth); -} - -float ImGuiSimpleColumns::CalcExtraSpace(float avail_w) -{ - return ImMax(0.0f, avail_w - Width); -} - -//----------------------------------------------------------------------------- -// ImGuiListClipper -//----------------------------------------------------------------------------- - -static void SetCursorPosYAndSetupDummyPrevLine(float pos_y, float line_height) -{ - // Set cursor position and a few other things so that SetScrollHere() and Columns() can work when seeking cursor. - // FIXME: It is problematic that we have to do that here, because custom/equivalent end-user code would stumble on the same issue. Consider moving within SetCursorXXX functions? - ImGui::SetCursorPosY(pos_y); - ImGuiWindow* window = ImGui::GetCurrentWindow(); - window->DC.CursorPosPrevLine.y = window->DC.CursorPos.y - line_height; // Setting those fields so that SetScrollHere() can properly function after the end of our clipper usage. - window->DC.PrevLineHeight = (line_height - GImGui->Style.ItemSpacing.y); // If we end up needing more accurate data (to e.g. use SameLine) we may as well make the clipper have a fourth step to let user process and display the last item in their list. - if (window->DC.ColumnsCount > 1) - window->DC.ColumnsCellMinY = window->DC.CursorPos.y; // Setting this so that cell Y position are set properly -} - -// Use case A: Begin() called from constructor with items_height<0, then called again from Sync() in StepNo 1 -// Use case B: Begin() called from constructor with items_height>0 -// FIXME-LEGACY: Ideally we should remove the Begin/End functions but they are part of the legacy API we still support. This is why some of the code in Step() calling Begin() and reassign some fields, spaghetti style. -void ImGuiListClipper::Begin(int count, float items_height) -{ - StartPosY = ImGui::GetCursorPosY(); - ItemsHeight = items_height; - ItemsCount = count; - StepNo = 0; - DisplayEnd = DisplayStart = -1; - if (ItemsHeight > 0.0f) - { - ImGui::CalcListClipping(ItemsCount, ItemsHeight, &DisplayStart, &DisplayEnd); // calculate how many to clip/display - if (DisplayStart > 0) - SetCursorPosYAndSetupDummyPrevLine(StartPosY + DisplayStart * ItemsHeight, ItemsHeight); // advance cursor - StepNo = 2; - } -} - -void ImGuiListClipper::End() -{ - if (ItemsCount < 0) - return; - // In theory here we should assert that ImGui::GetCursorPosY() == StartPosY + DisplayEnd * ItemsHeight, but it feels saner to just seek at the end and not assert/crash the user. - if (ItemsCount < INT_MAX) - SetCursorPosYAndSetupDummyPrevLine(StartPosY + ItemsCount * ItemsHeight, ItemsHeight); // advance cursor - ItemsCount = -1; - StepNo = 3; -} - -bool ImGuiListClipper::Step() -{ - if (ItemsCount == 0 || ImGui::GetCurrentWindowRead()->SkipItems) - { - ItemsCount = -1; - return false; - } - if (StepNo == 0) // Step 0: the clipper let you process the first element, regardless of it being visible or not, so we can measure the element height. - { - DisplayStart = 0; - DisplayEnd = 1; - StartPosY = ImGui::GetCursorPosY(); - StepNo = 1; - return true; - } - if (StepNo == 1) // Step 1: the clipper infer height from first element, calculate the actual range of elements to display, and position the cursor before the first element. - { - if (ItemsCount == 1) { ItemsCount = -1; return false; } - float items_height = ImGui::GetCursorPosY() - StartPosY; - IM_ASSERT(items_height > 0.0f); // If this triggers, it means Item 0 hasn't moved the cursor vertically - Begin(ItemsCount-1, items_height); - DisplayStart++; - DisplayEnd++; - StepNo = 3; - return true; - } - if (StepNo == 2) // Step 2: dummy step only required if an explicit items_height was passed to constructor or Begin() and user still call Step(). Does nothing and switch to Step 3. - { - IM_ASSERT(DisplayStart >= 0 && DisplayEnd >= 0); - StepNo = 3; - return true; - } - if (StepNo == 3) // Step 3: the clipper validate that we have reached the expected Y position (corresponding to element DisplayEnd), advance the cursor to the end of the list and then returns 'false' to end the loop. - End(); - return false; -} - -//----------------------------------------------------------------------------- -// ImGuiWindow -//----------------------------------------------------------------------------- - -ImGuiWindow::ImGuiWindow(const char* name) -{ - Name = ImStrdup(name); - ID = ImHash(name, 0); - IDStack.push_back(ID); - MoveId = GetID("#MOVE"); - - Flags = 0; - IndexWithinParent = 0; - PosFloat = Pos = ImVec2(0.0f, 0.0f); - Size = SizeFull = ImVec2(0.0f, 0.0f); - SizeContents = SizeContentsExplicit = ImVec2(0.0f, 0.0f); - WindowPadding = ImVec2(0.0f, 0.0f); - Scroll = ImVec2(0.0f, 0.0f); - ScrollTarget = ImVec2(FLT_MAX, FLT_MAX); - ScrollTargetCenterRatio = ImVec2(0.5f, 0.5f); - ScrollbarX = ScrollbarY = false; - ScrollbarSizes = ImVec2(0.0f, 0.0f); - BorderSize = 0.0f; - Active = WasActive = false; - Accessed = false; - Collapsed = false; - SkipItems = false; - BeginCount = 0; - PopupId = 0; - AutoFitFramesX = AutoFitFramesY = -1; - AutoFitOnlyGrows = false; - AutoPosLastDirection = -1; - HiddenFrames = 0; - SetWindowPosAllowFlags = SetWindowSizeAllowFlags = SetWindowCollapsedAllowFlags = ImGuiSetCond_Always | ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing; - SetWindowPosCenterWanted = false; - - LastFrameActive = -1; - ItemWidthDefault = 0.0f; - FontWindowScale = 1.0f; - - DrawList = (ImDrawList*)ImGui::MemAlloc(sizeof(ImDrawList)); - IM_PLACEMENT_NEW(DrawList) ImDrawList(); - DrawList->_OwnerName = Name; - RootWindow = NULL; - RootNonPopupWindow = NULL; - ParentWindow = NULL; - - FocusIdxAllCounter = FocusIdxTabCounter = -1; - FocusIdxAllRequestCurrent = FocusIdxTabRequestCurrent = INT_MAX; - FocusIdxAllRequestNext = FocusIdxTabRequestNext = INT_MAX; -} - -ImGuiWindow::~ImGuiWindow() -{ - DrawList->~ImDrawList(); - ImGui::MemFree(DrawList); - DrawList = NULL; - ImGui::MemFree(Name); - Name = NULL; -} - -ImGuiID ImGuiWindow::GetID(const char* str, const char* str_end) -{ - ImGuiID seed = IDStack.back(); - ImGuiID id = ImHash(str, str_end ? (int)(str_end - str) : 0, seed); - ImGui::KeepAliveID(id); - return id; -} - -ImGuiID ImGuiWindow::GetID(const void* ptr) -{ - ImGuiID seed = IDStack.back(); - ImGuiID id = ImHash(&ptr, sizeof(void*), seed); - ImGui::KeepAliveID(id); - return id; -} - -ImGuiID ImGuiWindow::GetIDNoKeepAlive(const char* str, const char* str_end) -{ - ImGuiID seed = IDStack.back(); - return ImHash(str, str_end ? (int)(str_end - str) : 0, seed); -} - -//----------------------------------------------------------------------------- -// Internal API exposed in imgui_internal.h -//----------------------------------------------------------------------------- - -static void SetCurrentWindow(ImGuiWindow* window) -{ - ImGuiContext& g = *GImGui; - g.CurrentWindow = window; - if (window) - g.FontSize = window->CalcFontSize(); -} - -ImGuiWindow* ImGui::GetParentWindow() -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(g.CurrentWindowStack.Size >= 2); - return g.CurrentWindowStack[(unsigned int)g.CurrentWindowStack.Size - 2]; -} - -void ImGui::SetActiveID(ImGuiID id, ImGuiWindow* window = NULL) -{ - ImGuiContext& g = *GImGui; - g.ActiveId = id; - g.ActiveIdAllowOverlap = false; - g.ActiveIdIsJustActivated = true; - if (id) - g.ActiveIdIsAlive = true; - g.ActiveIdWindow = window; -} - -void ImGui::SetHoveredID(ImGuiID id) -{ - ImGuiContext& g = *GImGui; - g.HoveredId = id; - g.HoveredIdAllowOverlap = false; -} - -void ImGui::KeepAliveID(ImGuiID id) -{ - ImGuiContext& g = *GImGui; - if (g.ActiveId == id) - g.ActiveIdIsAlive = true; -} - -// Advance cursor given item size for layout. -void ImGui::ItemSize(const ImVec2& size, float text_offset_y) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - // Always align ourselves on pixel boundaries - ImGuiContext& g = *GImGui; - const float line_height = ImMax(window->DC.CurrentLineHeight, size.y); - const float text_base_offset = ImMax(window->DC.CurrentLineTextBaseOffset, text_offset_y); - window->DC.CursorPosPrevLine = ImVec2(window->DC.CursorPos.x + size.x, window->DC.CursorPos.y); - window->DC.CursorPos = ImVec2((float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX), (float)(int)(window->DC.CursorPos.y + line_height + g.Style.ItemSpacing.y)); - window->DC.CursorMaxPos.x = ImMax(window->DC.CursorMaxPos.x, window->DC.CursorPosPrevLine.x); - window->DC.CursorMaxPos.y = ImMax(window->DC.CursorMaxPos.y, window->DC.CursorPos.y); - - //window->DrawList->AddCircle(window->DC.CursorMaxPos, 3.0f, IM_COL32(255,0,0,255), 4); // Debug - - window->DC.PrevLineHeight = line_height; - window->DC.PrevLineTextBaseOffset = text_base_offset; - window->DC.CurrentLineHeight = window->DC.CurrentLineTextBaseOffset = 0.0f; -} - -void ImGui::ItemSize(const ImRect& bb, float text_offset_y) -{ - ItemSize(bb.GetSize(), text_offset_y); -} - -// Declare item bounding box for clipping and interaction. -// Note that the size can be different than the one provided to ItemSize(). Typically, widgets that spread over available surface -// declares their minimum size requirement to ItemSize() and then use a larger region for drawing/interaction, which is passed to ItemAdd(). -bool ImGui::ItemAdd(const ImRect& bb, const ImGuiID* id) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.LastItemId = id ? *id : 0; - window->DC.LastItemRect = bb; - window->DC.LastItemHoveredAndUsable = window->DC.LastItemHoveredRect = false; - if (IsClippedEx(bb, id, false)) - return false; - - // This is a sensible default, but widgets are free to override it after calling ItemAdd() - ImGuiContext& g = *GImGui; - if (IsMouseHoveringRect(bb.Min, bb.Max)) - { - // Matching the behavior of IsHovered() but allow if ActiveId==window->MoveID (we clicked on the window background) - // So that clicking on items with no active id such as Text() still returns true with IsItemHovered() - window->DC.LastItemHoveredRect = true; - if (g.HoveredRootWindow == window->RootWindow) - if (g.ActiveId == 0 || (id && g.ActiveId == *id) || g.ActiveIdAllowOverlap || (g.ActiveId == window->MoveId)) - if (IsWindowContentHoverable(window)) - window->DC.LastItemHoveredAndUsable = true; - } - - return true; -} - -bool ImGui::IsClippedEx(const ImRect& bb, const ImGuiID* id, bool clip_even_when_logged) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindowRead(); - - if (!bb.Overlaps(window->ClipRect)) - if (!id || *id != GImGui->ActiveId) - if (clip_even_when_logged || !g.LogEnabled) - return true; - return false; -} - -// NB: This is an internal helper. The user-facing IsItemHovered() is using data emitted from ItemAdd(), with a slightly different logic. -bool ImGui::IsHovered(const ImRect& bb, ImGuiID id, bool flatten_childs) -{ - ImGuiContext& g = *GImGui; - if (g.HoveredId == 0 || g.HoveredId == id || g.HoveredIdAllowOverlap) - { - ImGuiWindow* window = GetCurrentWindowRead(); - if (g.HoveredWindow == window || (flatten_childs && g.HoveredRootWindow == window->RootWindow)) - if ((g.ActiveId == 0 || g.ActiveId == id || g.ActiveIdAllowOverlap) && IsMouseHoveringRect(bb.Min, bb.Max)) - if (IsWindowContentHoverable(g.HoveredRootWindow)) - return true; - } - return false; -} - -bool ImGui::FocusableItemRegister(ImGuiWindow* window, bool is_active, bool tab_stop) -{ - ImGuiContext& g = *GImGui; - - const bool allow_keyboard_focus = window->DC.AllowKeyboardFocus; - window->FocusIdxAllCounter++; - if (allow_keyboard_focus) - window->FocusIdxTabCounter++; - - // Process keyboard input at this point: TAB, Shift-TAB switch focus - // We can always TAB out of a widget that doesn't allow tabbing in. - if (tab_stop && window->FocusIdxAllRequestNext == INT_MAX && window->FocusIdxTabRequestNext == INT_MAX && is_active && IsKeyPressedMap(ImGuiKey_Tab)) - { - // Modulo on index will be applied at the end of frame once we've got the total counter of items. - window->FocusIdxTabRequestNext = window->FocusIdxTabCounter + (g.IO.KeyShift ? (allow_keyboard_focus ? -1 : 0) : +1); - } - - if (window->FocusIdxAllCounter == window->FocusIdxAllRequestCurrent) - return true; - - if (allow_keyboard_focus) - if (window->FocusIdxTabCounter == window->FocusIdxTabRequestCurrent) - return true; - - return false; -} - -void ImGui::FocusableItemUnregister(ImGuiWindow* window) -{ - window->FocusIdxAllCounter--; - window->FocusIdxTabCounter--; -} - -ImVec2 ImGui::CalcItemSize(ImVec2 size, float default_x, float default_y) -{ - ImGuiContext& g = *GImGui; - ImVec2 content_max; - if (size.x < 0.0f || size.y < 0.0f) - content_max = g.CurrentWindow->Pos + GetContentRegionMax(); - if (size.x <= 0.0f) - size.x = (size.x == 0.0f) ? default_x : ImMax(content_max.x - g.CurrentWindow->DC.CursorPos.x, 4.0f) + size.x; - if (size.y <= 0.0f) - size.y = (size.y == 0.0f) ? default_y : ImMax(content_max.y - g.CurrentWindow->DC.CursorPos.y, 4.0f) + size.y; - return size; -} - -float ImGui::CalcWrapWidthForPos(const ImVec2& pos, float wrap_pos_x) -{ - if (wrap_pos_x < 0.0f) - return 0.0f; - - ImGuiWindow* window = GetCurrentWindowRead(); - if (wrap_pos_x == 0.0f) - wrap_pos_x = GetContentRegionMax().x + window->Pos.x; - else if (wrap_pos_x > 0.0f) - wrap_pos_x += window->Pos.x - window->Scroll.x; // wrap_pos_x is provided is window local space - - return ImMax(wrap_pos_x - pos.x, 1.0f); -} - -//----------------------------------------------------------------------------- - -void* ImGui::MemAlloc(size_t sz) -{ - GImGui->IO.MetricsAllocs++; - return GImGui->IO.MemAllocFn(sz); -} - -void ImGui::MemFree(void* ptr) -{ - if (ptr) GImGui->IO.MetricsAllocs--; - return GImGui->IO.MemFreeFn(ptr); -} - -const char* ImGui::GetClipboardText() -{ - return GImGui->IO.GetClipboardTextFn ? GImGui->IO.GetClipboardTextFn() : ""; -} - -void ImGui::SetClipboardText(const char* text) -{ - if (GImGui->IO.SetClipboardTextFn) - GImGui->IO.SetClipboardTextFn(text); -} - -const char* ImGui::GetVersion() -{ - return IMGUI_VERSION; -} - -// Internal state access - if you want to share ImGui state between modules (e.g. DLL) or allocate it yourself -// Note that we still point to some static data and members (such as GFontAtlas), so the state instance you end up using will point to the static data within its module -ImGuiContext* ImGui::GetCurrentContext() -{ - return GImGui; -} - -void ImGui::SetCurrentContext(ImGuiContext* ctx) -{ - GImGui = ctx; -} - -ImGuiContext* ImGui::CreateContext(void* (*malloc_fn)(size_t), void (*free_fn)(void*)) -{ - if (!malloc_fn) malloc_fn = malloc; - ImGuiContext* ctx = (ImGuiContext*)malloc_fn(sizeof(ImGuiContext)); - IM_PLACEMENT_NEW(ctx) ImGuiContext(); - ctx->IO.MemAllocFn = malloc_fn; - ctx->IO.MemFreeFn = free_fn ? free_fn : free; - return ctx; -} - -void ImGui::DestroyContext(ImGuiContext* ctx) -{ - void (*free_fn)(void*) = ctx->IO.MemFreeFn; - ctx->~ImGuiContext(); - free_fn(ctx); - if (GImGui == ctx) - GImGui = NULL; -} - -ImGuiIO& ImGui::GetIO() -{ - return GImGui->IO; -} - -ImGuiStyle& ImGui::GetStyle() -{ - return GImGui->Style; -} - -// Same value as passed to your RenderDrawListsFn() function. valid after Render() and until the next call to NewFrame() -ImDrawData* ImGui::GetDrawData() -{ - return GImGui->RenderDrawData.Valid ? &GImGui->RenderDrawData : NULL; -} - -float ImGui::GetTime() -{ - return GImGui->Time; -} - -int ImGui::GetFrameCount() -{ - return GImGui->FrameCount; -} - -void ImGui::NewFrame() -{ - ImGuiContext& g = *GImGui; - - // Check user data - IM_ASSERT(g.IO.DeltaTime >= 0.0f); // Need a positive DeltaTime (zero is tolerated but will cause some timing issues) - IM_ASSERT(g.IO.DisplaySize.x >= 0.0f && g.IO.DisplaySize.y >= 0.0f); - IM_ASSERT(g.IO.Fonts->Fonts.Size > 0); // Font Atlas not created. Did you call io.Fonts->GetTexDataAsRGBA32 / GetTexDataAsAlpha8 ? - IM_ASSERT(g.IO.Fonts->Fonts[0]->IsLoaded()); // Font Atlas not created. Did you call io.Fonts->GetTexDataAsRGBA32 / GetTexDataAsAlpha8 ? - IM_ASSERT(g.Style.CurveTessellationTol > 0.0f); // Invalid style setting - - if (!g.Initialized) - { - // Initialize on first frame - g.LogClipboard = (ImGuiTextBuffer*)ImGui::MemAlloc(sizeof(ImGuiTextBuffer)); - IM_PLACEMENT_NEW(g.LogClipboard) ImGuiTextBuffer(); - - IM_ASSERT(g.Settings.empty()); - LoadSettings(); - g.Initialized = true; - } - - SetCurrentFont(g.IO.Fonts->Fonts[0]); - - g.Time += g.IO.DeltaTime; - g.FrameCount += 1; - g.Tooltip[0] = '\0'; - g.OverlayDrawList.Clear(); - g.OverlayDrawList.PushTextureID(g.IO.Fonts->TexID); - g.OverlayDrawList.PushClipRectFullScreen(); - - // Mark rendering data as invalid to prevent user who may have a handle on it to use it - g.RenderDrawData.Valid = false; - g.RenderDrawData.CmdLists = NULL; - g.RenderDrawData.CmdListsCount = g.RenderDrawData.TotalVtxCount = g.RenderDrawData.TotalIdxCount = 0; - - // Update inputs state - if (g.IO.MousePos.x < 0 && g.IO.MousePos.y < 0) - g.IO.MousePos = ImVec2(-9999.0f, -9999.0f); - if ((g.IO.MousePos.x < 0 && g.IO.MousePos.y < 0) || (g.IO.MousePosPrev.x < 0 && g.IO.MousePosPrev.y < 0)) // if mouse just appeared or disappeared (negative coordinate) we cancel out movement in MouseDelta - g.IO.MouseDelta = ImVec2(0.0f, 0.0f); - else - g.IO.MouseDelta = g.IO.MousePos - g.IO.MousePosPrev; - g.IO.MousePosPrev = g.IO.MousePos; - for (int i = 0; i < IM_ARRAYSIZE(g.IO.MouseDown); i++) - { - g.IO.MouseClicked[i] = g.IO.MouseDown[i] && g.IO.MouseDownDuration[i] < 0.0f; - g.IO.MouseReleased[i] = !g.IO.MouseDown[i] && g.IO.MouseDownDuration[i] >= 0.0f; - g.IO.MouseDownDurationPrev[i] = g.IO.MouseDownDuration[i]; - g.IO.MouseDownDuration[i] = g.IO.MouseDown[i] ? (g.IO.MouseDownDuration[i] < 0.0f ? 0.0f : g.IO.MouseDownDuration[i] + g.IO.DeltaTime) : -1.0f; - g.IO.MouseDoubleClicked[i] = false; - if (g.IO.MouseClicked[i]) - { - if (g.Time - g.IO.MouseClickedTime[i] < g.IO.MouseDoubleClickTime) - { - if (ImLengthSqr(g.IO.MousePos - g.IO.MouseClickedPos[i]) < g.IO.MouseDoubleClickMaxDist * g.IO.MouseDoubleClickMaxDist) - g.IO.MouseDoubleClicked[i] = true; - g.IO.MouseClickedTime[i] = -FLT_MAX; // so the third click isn't turned into a double-click - } - else - { - g.IO.MouseClickedTime[i] = g.Time; - } - g.IO.MouseClickedPos[i] = g.IO.MousePos; - g.IO.MouseDragMaxDistanceSqr[i] = 0.0f; - } - else if (g.IO.MouseDown[i]) - { - g.IO.MouseDragMaxDistanceSqr[i] = ImMax(g.IO.MouseDragMaxDistanceSqr[i], ImLengthSqr(g.IO.MousePos - g.IO.MouseClickedPos[i])); - } - } - memcpy(g.IO.KeysDownDurationPrev, g.IO.KeysDownDuration, sizeof(g.IO.KeysDownDuration)); - for (int i = 0; i < IM_ARRAYSIZE(g.IO.KeysDown); i++) - g.IO.KeysDownDuration[i] = g.IO.KeysDown[i] ? (g.IO.KeysDownDuration[i] < 0.0f ? 0.0f : g.IO.KeysDownDuration[i] + g.IO.DeltaTime) : -1.0f; - - // Calculate frame-rate for the user, as a purely luxurious feature - g.FramerateSecPerFrameAccum += g.IO.DeltaTime - g.FramerateSecPerFrame[g.FramerateSecPerFrameIdx]; - g.FramerateSecPerFrame[g.FramerateSecPerFrameIdx] = g.IO.DeltaTime; - g.FramerateSecPerFrameIdx = (g.FramerateSecPerFrameIdx + 1) % IM_ARRAYSIZE(g.FramerateSecPerFrame); - g.IO.Framerate = 1.0f / (g.FramerateSecPerFrameAccum / (float)IM_ARRAYSIZE(g.FramerateSecPerFrame)); - - // Clear reference to active widget if the widget isn't alive anymore - g.HoveredIdPreviousFrame = g.HoveredId; - g.HoveredId = 0; - g.HoveredIdAllowOverlap = false; - if (!g.ActiveIdIsAlive && g.ActiveIdPreviousFrame == g.ActiveId && g.ActiveId != 0) - SetActiveID(0); - g.ActiveIdPreviousFrame = g.ActiveId; - g.ActiveIdIsAlive = false; - g.ActiveIdIsJustActivated = false; - - // Handle user moving window (at the beginning of the frame to avoid input lag or sheering). Only valid for root windows. - if (g.MovedWindowMoveId && g.MovedWindowMoveId == g.ActiveId) - { - KeepAliveID(g.MovedWindowMoveId); - IM_ASSERT(g.MovedWindow && g.MovedWindow->RootWindow); - IM_ASSERT(g.MovedWindow->RootWindow->MoveId == g.MovedWindowMoveId); - if (g.IO.MouseDown[0]) - { - if (!(g.MovedWindow->Flags & ImGuiWindowFlags_NoMove)) - { - g.MovedWindow->PosFloat += g.IO.MouseDelta; - if (!(g.MovedWindow->Flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - } - FocusWindow(g.MovedWindow); - } - else - { - SetActiveID(0); - g.MovedWindow = NULL; - g.MovedWindowMoveId = 0; - } - } - else - { - g.MovedWindow = NULL; - g.MovedWindowMoveId = 0; - } - - // Delay saving settings so we don't spam disk too much - if (g.SettingsDirtyTimer > 0.0f) - { - g.SettingsDirtyTimer -= g.IO.DeltaTime; - if (g.SettingsDirtyTimer <= 0.0f) - SaveSettings(); - } - - // Find the window we are hovering. Child windows can extend beyond the limit of their parent so we need to derive HoveredRootWindow from HoveredWindow - g.HoveredWindow = g.MovedWindow ? g.MovedWindow : FindHoveredWindow(g.IO.MousePos, false); - if (g.HoveredWindow && (g.HoveredWindow->Flags & ImGuiWindowFlags_ChildWindow)) - g.HoveredRootWindow = g.HoveredWindow->RootWindow; - else - g.HoveredRootWindow = g.MovedWindow ? g.MovedWindow->RootWindow : FindHoveredWindow(g.IO.MousePos, true); - - if (ImGuiWindow* modal_window = GetFrontMostModalRootWindow()) - { - g.ModalWindowDarkeningRatio = ImMin(g.ModalWindowDarkeningRatio + g.IO.DeltaTime * 6.0f, 1.0f); - ImGuiWindow* window = g.HoveredRootWindow; - while (window && window != modal_window) - window = window->ParentWindow; - if (!window) - g.HoveredRootWindow = g.HoveredWindow = NULL; - } - else - { - g.ModalWindowDarkeningRatio = 0.0f; - } - - // Are we using inputs? Tell user so they can capture/discard the inputs away from the rest of their application. - // When clicking outside of a window we assume the click is owned by the application and won't request capture. We need to track click ownership. - int mouse_earliest_button_down = -1; - bool mouse_any_down = false; - for (int i = 0; i < IM_ARRAYSIZE(g.IO.MouseDown); i++) - { - if (g.IO.MouseClicked[i]) - g.IO.MouseDownOwned[i] = (g.HoveredWindow != NULL) || (!g.OpenPopupStack.empty()); - mouse_any_down |= g.IO.MouseDown[i]; - if (g.IO.MouseDown[i]) - if (mouse_earliest_button_down == -1 || g.IO.MouseClickedTime[mouse_earliest_button_down] > g.IO.MouseClickedTime[i]) - mouse_earliest_button_down = i; - } - bool mouse_avail_to_imgui = (mouse_earliest_button_down == -1) || g.IO.MouseDownOwned[mouse_earliest_button_down]; - if (g.CaptureMouseNextFrame != -1) - g.IO.WantCaptureMouse = (g.CaptureMouseNextFrame != 0); - else - g.IO.WantCaptureMouse = (mouse_avail_to_imgui && (g.HoveredWindow != NULL || mouse_any_down)) || (g.ActiveId != 0) || (!g.OpenPopupStack.empty()); - g.IO.WantCaptureKeyboard = (g.CaptureKeyboardNextFrame != -1) ? (g.CaptureKeyboardNextFrame != 0) : (g.ActiveId != 0); - g.IO.WantTextInput = (g.ActiveId != 0 && g.InputTextState.Id == g.ActiveId); - g.MouseCursor = ImGuiMouseCursor_Arrow; - g.CaptureMouseNextFrame = g.CaptureKeyboardNextFrame = -1; - g.OsImePosRequest = ImVec2(1.0f, 1.0f); // OS Input Method Editor showing on top-left of our window by default - - // If mouse was first clicked outside of ImGui bounds we also cancel out hovering. - if (!mouse_avail_to_imgui) - g.HoveredWindow = g.HoveredRootWindow = NULL; - - // Scale & Scrolling - if (g.HoveredWindow && g.IO.MouseWheel != 0.0f && !g.HoveredWindow->Collapsed) - { - ImGuiWindow* window = g.HoveredWindow; - if (g.IO.KeyCtrl) - { - if (g.IO.FontAllowUserScaling) - { - // Zoom / Scale window - float new_font_scale = ImClamp(window->FontWindowScale + g.IO.MouseWheel * 0.10f, 0.50f, 2.50f); - float scale = new_font_scale / window->FontWindowScale; - window->FontWindowScale = new_font_scale; - - const ImVec2 offset = window->Size * (1.0f - scale) * (g.IO.MousePos - window->Pos) / window->Size; - window->Pos += offset; - window->PosFloat += offset; - window->Size *= scale; - window->SizeFull *= scale; - } - } - else if (!(window->Flags & ImGuiWindowFlags_NoScrollWithMouse)) - { - // Scroll - const int scroll_lines = (window->Flags & ImGuiWindowFlags_ComboBox) ? 3 : 5; - SetWindowScrollY(window, window->Scroll.y - g.IO.MouseWheel * window->CalcFontSize() * scroll_lines); - } - } - - // Pressing TAB activate widget focus - // NB: Don't discard FocusedWindow if it isn't active, so that a window that go on/off programatically won't lose its keyboard focus. - if (g.ActiveId == 0 && g.FocusedWindow != NULL && g.FocusedWindow->Active && IsKeyPressedMap(ImGuiKey_Tab, false)) - g.FocusedWindow->FocusIdxTabRequestNext = 0; - - // Mark all windows as not visible - for (int i = 0; i != g.Windows.Size; i++) - { - ImGuiWindow* window = g.Windows[i]; - window->WasActive = window->Active; - window->Active = false; - window->Accessed = false; - } - - // Closing the focused window restore focus to the first active root window in descending z-order - if (g.FocusedWindow && !g.FocusedWindow->WasActive) - for (int i = g.Windows.Size-1; i >= 0; i--) - if (g.Windows[i]->WasActive && !(g.Windows[i]->Flags & ImGuiWindowFlags_ChildWindow)) - { - FocusWindow(g.Windows[i]); - break; - } - - // No window should be open at the beginning of the frame. - // But in order to allow the user to call NewFrame() multiple times without calling Render(), we are doing an explicit clear. - g.CurrentWindowStack.resize(0); - g.CurrentPopupStack.resize(0); - CloseInactivePopups(); - - // Create implicit window - we will only render it if the user has added something to it. - ImGui::SetNextWindowSize(ImVec2(400,400), ImGuiSetCond_FirstUseEver); - ImGui::Begin("Debug"); -} - -// NB: behavior of ImGui after Shutdown() is not tested/guaranteed at the moment. This function is merely here to free heap allocations. -void ImGui::Shutdown() -{ - ImGuiContext& g = *GImGui; - - // The fonts atlas can be used prior to calling NewFrame(), so we clear it even if g.Initialized is FALSE (which would happen if we never called NewFrame) - if (g.IO.Fonts) // Testing for NULL to allow user to NULLify in case of running Shutdown() on multiple contexts. Bit hacky. - g.IO.Fonts->Clear(); - - // Cleanup of other data are conditional on actually having used ImGui. - if (!g.Initialized) - return; - - SaveSettings(); - - for (int i = 0; i < g.Windows.Size; i++) - { - g.Windows[i]->~ImGuiWindow(); - ImGui::MemFree(g.Windows[i]); - } - g.Windows.clear(); - g.WindowsSortBuffer.clear(); - g.CurrentWindow = NULL; - g.CurrentWindowStack.clear(); - g.FocusedWindow = NULL; - g.HoveredWindow = NULL; - g.HoveredRootWindow = NULL; - g.ActiveIdWindow = NULL; - g.MovedWindow = NULL; - for (int i = 0; i < g.Settings.Size; i++) - ImGui::MemFree(g.Settings[i].Name); - g.Settings.clear(); - g.ColorModifiers.clear(); - g.StyleModifiers.clear(); - g.FontStack.clear(); - g.OpenPopupStack.clear(); - g.CurrentPopupStack.clear(); - g.SetNextWindowSizeConstraintCallback = NULL; - g.SetNextWindowSizeConstraintCallbackUserData = NULL; - for (int i = 0; i < IM_ARRAYSIZE(g.RenderDrawLists); i++) - g.RenderDrawLists[i].clear(); - g.OverlayDrawList.ClearFreeMemory(); - g.ColorEditModeStorage.Clear(); - if (g.PrivateClipboard) - { - ImGui::MemFree(g.PrivateClipboard); - g.PrivateClipboard = NULL; - } - g.InputTextState.Text.clear(); - g.InputTextState.InitialText.clear(); - g.InputTextState.TempTextBuffer.clear(); - - if (g.LogFile && g.LogFile != stdout) - { - fclose(g.LogFile); - g.LogFile = NULL; - } - if (g.LogClipboard) - { - g.LogClipboard->~ImGuiTextBuffer(); - ImGui::MemFree(g.LogClipboard); - } - - g.Initialized = false; -} - -static ImGuiIniData* FindWindowSettings(const char* name) -{ - ImGuiContext& g = *GImGui; - ImGuiID id = ImHash(name, 0); - for (int i = 0; i != g.Settings.Size; i++) - { - ImGuiIniData* ini = &g.Settings[i]; - if (ini->Id == id) - return ini; - } - return NULL; -} - -static ImGuiIniData* AddWindowSettings(const char* name) -{ - GImGui->Settings.resize(GImGui->Settings.Size + 1); - ImGuiIniData* ini = &GImGui->Settings.back(); - ini->Name = ImStrdup(name); - ini->Id = ImHash(name, 0); - ini->Collapsed = false; - ini->Pos = ImVec2(FLT_MAX,FLT_MAX); - ini->Size = ImVec2(0,0); - return ini; -} - -// Zero-tolerance, poor-man .ini parsing -// FIXME: Write something less rubbish -static void LoadSettings() -{ - ImGuiContext& g = *GImGui; - const char* filename = g.IO.IniFilename; - if (!filename) - return; - - int file_size; - char* file_data = (char*)ImLoadFileToMemory(filename, "rb", &file_size, 1); - if (!file_data) - return; - - ImGuiIniData* settings = NULL; - const char* buf_end = file_data + file_size; - for (const char* line_start = file_data; line_start < buf_end; ) - { - const char* line_end = line_start; - while (line_end < buf_end && *line_end != '\n' && *line_end != '\r') - line_end++; - - if (line_start[0] == '[' && line_end > line_start && line_end[-1] == ']') - { - char name[64]; - ImFormatString(name, IM_ARRAYSIZE(name), "%.*s", (int)(line_end-line_start-2), line_start+1); - settings = FindWindowSettings(name); - if (!settings) - settings = AddWindowSettings(name); - } - else if (settings) - { - float x, y; - int i; - if (sscanf(line_start, "Pos=%f,%f", &x, &y) == 2) - settings->Pos = ImVec2(x, y); - else if (sscanf(line_start, "Size=%f,%f", &x, &y) == 2) - settings->Size = ImMax(ImVec2(x, y), g.Style.WindowMinSize); - else if (sscanf(line_start, "Collapsed=%d", &i) == 1) - settings->Collapsed = (i != 0); - } - - line_start = line_end+1; - } - - ImGui::MemFree(file_data); -} - -static void SaveSettings() -{ - ImGuiContext& g = *GImGui; - const char* filename = g.IO.IniFilename; - if (!filename) - return; - - // Gather data from windows that were active during this session - for (int i = 0; i != g.Windows.Size; i++) - { - ImGuiWindow* window = g.Windows[i]; - if (window->Flags & ImGuiWindowFlags_NoSavedSettings) - continue; - ImGuiIniData* settings = FindWindowSettings(window->Name); - settings->Pos = window->Pos; - settings->Size = window->SizeFull; - settings->Collapsed = window->Collapsed; - } - - // Write .ini file - // If a window wasn't opened in this session we preserve its settings - FILE* f = fopen(filename, "wt"); - if (!f) - return; - for (int i = 0; i != g.Settings.Size; i++) - { - const ImGuiIniData* settings = &g.Settings[i]; - if (settings->Pos.x == FLT_MAX) - continue; - const char* name = settings->Name; - if (const char* p = strstr(name, "###")) // Skip to the "###" marker if any. We don't skip past to match the behavior of GetID() - name = p; - fprintf(f, "[%s]\n", name); - fprintf(f, "Pos=%d,%d\n", (int)settings->Pos.x, (int)settings->Pos.y); - fprintf(f, "Size=%d,%d\n", (int)settings->Size.x, (int)settings->Size.y); - fprintf(f, "Collapsed=%d\n", settings->Collapsed); - fprintf(f, "\n"); - } - - fclose(f); -} - -static void MarkSettingsDirty() -{ - ImGuiContext& g = *GImGui; - if (g.SettingsDirtyTimer <= 0.0f) - g.SettingsDirtyTimer = g.IO.IniSavingRate; -} - -// FIXME: Add a more explicit sort order in the window structure. -static int ChildWindowComparer(const void* lhs, const void* rhs) -{ - const ImGuiWindow* a = *(const ImGuiWindow**)lhs; - const ImGuiWindow* b = *(const ImGuiWindow**)rhs; - if (int d = (a->Flags & ImGuiWindowFlags_Popup) - (b->Flags & ImGuiWindowFlags_Popup)) - return d; - if (int d = (a->Flags & ImGuiWindowFlags_Tooltip) - (b->Flags & ImGuiWindowFlags_Tooltip)) - return d; - if (int d = (a->Flags & ImGuiWindowFlags_ComboBox) - (b->Flags & ImGuiWindowFlags_ComboBox)) - return d; - return (a->IndexWithinParent - b->IndexWithinParent); -} - -static void AddWindowToSortedBuffer(ImVector<ImGuiWindow*>& out_sorted_windows, ImGuiWindow* window) -{ - out_sorted_windows.push_back(window); - if (window->Active) - { - int count = window->DC.ChildWindows.Size; - if (count > 1) - qsort(window->DC.ChildWindows.begin(), (size_t)count, sizeof(ImGuiWindow*), ChildWindowComparer); - for (int i = 0; i < count; i++) - { - ImGuiWindow* child = window->DC.ChildWindows[i]; - if (child->Active) - AddWindowToSortedBuffer(out_sorted_windows, child); - } - } -} - -static void AddDrawListToRenderList(ImVector<ImDrawList*>& out_render_list, ImDrawList* draw_list) -{ - if (draw_list->CmdBuffer.empty()) - return; - - // Remove trailing command if unused - ImDrawCmd& last_cmd = draw_list->CmdBuffer.back(); - if (last_cmd.ElemCount == 0 && last_cmd.UserCallback == NULL) - { - draw_list->CmdBuffer.pop_back(); - if (draw_list->CmdBuffer.empty()) - return; - } - - // Draw list sanity check. Detect mismatch between PrimReserve() calls and incrementing _VtxCurrentIdx, _VtxWritePtr etc. - IM_ASSERT(draw_list->VtxBuffer.Size == 0 || draw_list->_VtxWritePtr == draw_list->VtxBuffer.Data + draw_list->VtxBuffer.Size); - IM_ASSERT(draw_list->IdxBuffer.Size == 0 || draw_list->_IdxWritePtr == draw_list->IdxBuffer.Data + draw_list->IdxBuffer.Size); - IM_ASSERT((int)draw_list->_VtxCurrentIdx == draw_list->VtxBuffer.Size); - - // Check that draw_list doesn't use more vertices than indexable (default ImDrawIdx = 2 bytes = 64K vertices) - // If this assert triggers because you are drawing lots of stuff manually, A) workaround by calling BeginChild()/EndChild() to put your draw commands in multiple draw lists, B) #define ImDrawIdx to a 'unsigned int' in imconfig.h and render accordingly. - IM_ASSERT((int64_t)draw_list->_VtxCurrentIdx <= ((int64_t)1L << (sizeof(ImDrawIdx)*8))); // Too many vertices in same ImDrawList. See comment above. - - out_render_list.push_back(draw_list); - GImGui->IO.MetricsRenderVertices += draw_list->VtxBuffer.Size; - GImGui->IO.MetricsRenderIndices += draw_list->IdxBuffer.Size; -} - -static void AddWindowToRenderList(ImVector<ImDrawList*>& out_render_list, ImGuiWindow* window) -{ - AddDrawListToRenderList(out_render_list, window->DrawList); - for (int i = 0; i < window->DC.ChildWindows.Size; i++) - { - ImGuiWindow* child = window->DC.ChildWindows[i]; - if (!child->Active) // clipped children may have been marked not active - continue; - if ((child->Flags & ImGuiWindowFlags_Popup) && child->HiddenFrames > 0) - continue; - AddWindowToRenderList(out_render_list, child); - } -} - -// When using this function it is sane to ensure that float are perfectly rounded to integer values, to that e.g. (int)(max.x-min.x) in user's render produce correct result. -void ImGui::PushClipRect(const ImVec2& clip_rect_min, const ImVec2& clip_rect_max, bool intersect_with_current_clip_rect) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DrawList->PushClipRect(clip_rect_min, clip_rect_max, intersect_with_current_clip_rect); - window->ClipRect = window->DrawList->_ClipRectStack.back(); -} - -void ImGui::PopClipRect() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DrawList->PopClipRect(); - window->ClipRect = window->DrawList->_ClipRectStack.back(); -} - -// This is normally called by Render(). You may want to call it directly if you want to avoid calling Render() but the gain will be very minimal. -void ImGui::EndFrame() -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(g.Initialized); // Forgot to call ImGui::NewFrame() - IM_ASSERT(g.FrameCountEnded != g.FrameCount); // ImGui::EndFrame() called multiple times, or forgot to call ImGui::NewFrame() again - - // Render tooltip - if (g.Tooltip[0]) - { - ImGui::BeginTooltip(); - ImGui::TextUnformatted(g.Tooltip); - ImGui::EndTooltip(); - } - - // Notify OS when our Input Method Editor cursor has moved (e.g. CJK inputs using Microsoft IME) - if (g.IO.ImeSetInputScreenPosFn && ImLengthSqr(g.OsImePosRequest - g.OsImePosSet) > 0.0001f) - { - g.IO.ImeSetInputScreenPosFn((int)g.OsImePosRequest.x, (int)g.OsImePosRequest.y); - g.OsImePosSet = g.OsImePosRequest; - } - - // Hide implicit "Debug" window if it hasn't been used - IM_ASSERT(g.CurrentWindowStack.Size == 1); // Mismatched Begin()/End() calls - if (g.CurrentWindow && !g.CurrentWindow->Accessed) - g.CurrentWindow->Active = false; - ImGui::End(); - - // Click to focus window and start moving (after we're done with all our widgets) - if (g.ActiveId == 0 && g.HoveredId == 0 && g.IO.MouseClicked[0]) - { - if (!(g.FocusedWindow && !g.FocusedWindow->WasActive && g.FocusedWindow->Active)) // Unless we just made a popup appear - { - if (g.HoveredRootWindow != NULL) - { - FocusWindow(g.HoveredWindow); - if (!(g.HoveredWindow->Flags & ImGuiWindowFlags_NoMove)) - { - g.MovedWindow = g.HoveredWindow; - g.MovedWindowMoveId = g.HoveredRootWindow->MoveId; - SetActiveID(g.MovedWindowMoveId, g.HoveredRootWindow); - } - } - else if (g.FocusedWindow != NULL && GetFrontMostModalRootWindow() == NULL) - { - // Clicking on void disable focus - FocusWindow(NULL); - } - } - } - - // Sort the window list so that all child windows are after their parent - // We cannot do that on FocusWindow() because childs may not exist yet - g.WindowsSortBuffer.resize(0); - g.WindowsSortBuffer.reserve(g.Windows.Size); - for (int i = 0; i != g.Windows.Size; i++) - { - ImGuiWindow* window = g.Windows[i]; - if (window->Active && (window->Flags & ImGuiWindowFlags_ChildWindow)) // if a child is active its parent will add it - continue; - AddWindowToSortedBuffer(g.WindowsSortBuffer, window); - } - IM_ASSERT(g.Windows.Size == g.WindowsSortBuffer.Size); // we done something wrong - g.Windows.swap(g.WindowsSortBuffer); - - // Clear Input data for next frame - g.IO.MouseWheel = 0.0f; - memset(g.IO.InputCharacters, 0, sizeof(g.IO.InputCharacters)); - - g.FrameCountEnded = g.FrameCount; -} - -void ImGui::Render() -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(g.Initialized); // Forgot to call ImGui::NewFrame() - - if (g.FrameCountEnded != g.FrameCount) - ImGui::EndFrame(); - g.FrameCountRendered = g.FrameCount; - - // Skip render altogether if alpha is 0.0 - // Note that vertex buffers have been created and are wasted, so it is best practice that you don't create windows in the first place, or consistently respond to Begin() returning false. - if (g.Style.Alpha > 0.0f) - { - // Gather windows to render - g.IO.MetricsRenderVertices = g.IO.MetricsRenderIndices = g.IO.MetricsActiveWindows = 0; - for (int i = 0; i < IM_ARRAYSIZE(g.RenderDrawLists); i++) - g.RenderDrawLists[i].resize(0); - for (int i = 0; i != g.Windows.Size; i++) - { - ImGuiWindow* window = g.Windows[i]; - if (window->Active && window->HiddenFrames <= 0 && (window->Flags & (ImGuiWindowFlags_ChildWindow)) == 0) - { - // FIXME: Generalize this with a proper layering system so e.g. user can draw in specific layers, below text, .. - g.IO.MetricsActiveWindows++; - if (window->Flags & ImGuiWindowFlags_Popup) - AddWindowToRenderList(g.RenderDrawLists[1], window); - else if (window->Flags & ImGuiWindowFlags_Tooltip) - AddWindowToRenderList(g.RenderDrawLists[2], window); - else - AddWindowToRenderList(g.RenderDrawLists[0], window); - } - } - - // Flatten layers - int n = g.RenderDrawLists[0].Size; - int flattened_size = n; - for (int i = 1; i < IM_ARRAYSIZE(g.RenderDrawLists); i++) - flattened_size += g.RenderDrawLists[i].Size; - g.RenderDrawLists[0].resize(flattened_size); - for (int i = 1; i < IM_ARRAYSIZE(g.RenderDrawLists); i++) - { - ImVector<ImDrawList*>& layer = g.RenderDrawLists[i]; - if (layer.empty()) - continue; - memcpy(&g.RenderDrawLists[0][n], &layer[0], layer.Size * sizeof(ImDrawList*)); - n += layer.Size; - } - - // Draw software mouse cursor if requested - if (g.IO.MouseDrawCursor) - { - const ImGuiMouseCursorData& cursor_data = g.MouseCursorData[g.MouseCursor]; - const ImVec2 pos = g.IO.MousePos - cursor_data.HotOffset; - const ImVec2 size = cursor_data.Size; - const ImTextureID tex_id = g.IO.Fonts->TexID; - g.OverlayDrawList.PushTextureID(tex_id); - g.OverlayDrawList.AddImage(tex_id, pos+ImVec2(1,0), pos+ImVec2(1,0) + size, cursor_data.TexUvMin[1], cursor_data.TexUvMax[1], IM_COL32(0,0,0,48)); // Shadow - g.OverlayDrawList.AddImage(tex_id, pos+ImVec2(2,0), pos+ImVec2(2,0) + size, cursor_data.TexUvMin[1], cursor_data.TexUvMax[1], IM_COL32(0,0,0,48)); // Shadow - g.OverlayDrawList.AddImage(tex_id, pos, pos + size, cursor_data.TexUvMin[1], cursor_data.TexUvMax[1], IM_COL32(0,0,0,255)); // Black border - g.OverlayDrawList.AddImage(tex_id, pos, pos + size, cursor_data.TexUvMin[0], cursor_data.TexUvMax[0], IM_COL32(255,255,255,255)); // White fill - g.OverlayDrawList.PopTextureID(); - } - if (!g.OverlayDrawList.VtxBuffer.empty()) - AddDrawListToRenderList(g.RenderDrawLists[0], &g.OverlayDrawList); - - // Setup draw data - g.RenderDrawData.Valid = true; - g.RenderDrawData.CmdLists = (g.RenderDrawLists[0].Size > 0) ? &g.RenderDrawLists[0][0] : NULL; - g.RenderDrawData.CmdListsCount = g.RenderDrawLists[0].Size; - g.RenderDrawData.TotalVtxCount = g.IO.MetricsRenderVertices; - g.RenderDrawData.TotalIdxCount = g.IO.MetricsRenderIndices; - - // Render. If user hasn't set a callback then they may retrieve the draw data via GetDrawData() - if (g.RenderDrawData.CmdListsCount > 0 && g.IO.RenderDrawListsFn != NULL) - g.IO.RenderDrawListsFn(&g.RenderDrawData); - } -} - -const char* ImGui::FindRenderedTextEnd(const char* text, const char* text_end) -{ - const char* text_display_end = text; - if (!text_end) - text_end = (const char*)-1; - - while (text_display_end < text_end && *text_display_end != '\0' && (text_display_end[0] != '#' || text_display_end[1] != '#')) - text_display_end++; - return text_display_end; -} - -// Pass text data straight to log (without being displayed) -void ImGui::LogText(const char* fmt, ...) -{ - ImGuiContext& g = *GImGui; - if (!g.LogEnabled) - return; - - va_list args; - va_start(args, fmt); - if (g.LogFile) - { - vfprintf(g.LogFile, fmt, args); - } - else - { - g.LogClipboard->appendv(fmt, args); - } - va_end(args); -} - -// Internal version that takes a position to decide on newline placement and pad items according to their depth. -// We split text into individual lines to add current tree level padding -static void LogRenderedText(const ImVec2& ref_pos, const char* text, const char* text_end) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = ImGui::GetCurrentWindowRead(); - - if (!text_end) - text_end = ImGui::FindRenderedTextEnd(text, text_end); - - const bool log_new_line = ref_pos.y > window->DC.LogLinePosY+1; - window->DC.LogLinePosY = ref_pos.y; - - const char* text_remaining = text; - if (g.LogStartDepth > window->DC.TreeDepth) // Re-adjust padding if we have popped out of our starting depth - g.LogStartDepth = window->DC.TreeDepth; - const int tree_depth = (window->DC.TreeDepth - g.LogStartDepth); - for (;;) - { - // Split the string. Each new line (after a '\n') is followed by spacing corresponding to the current depth of our log entry. - const char* line_end = text_remaining; - while (line_end < text_end) - if (*line_end == '\n') - break; - else - line_end++; - if (line_end >= text_end) - line_end = NULL; - - const bool is_first_line = (text == text_remaining); - bool is_last_line = false; - if (line_end == NULL) - { - is_last_line = true; - line_end = text_end; - } - if (line_end != NULL && !(is_last_line && (line_end - text_remaining)==0)) - { - const int char_count = (int)(line_end - text_remaining); - if (log_new_line || !is_first_line) - ImGui::LogText(IM_NEWLINE "%*s%.*s", tree_depth*4, "", char_count, text_remaining); - else - ImGui::LogText(" %.*s", char_count, text_remaining); - } - - if (is_last_line) - break; - text_remaining = line_end + 1; - } -} - -// Internal ImGui functions to render text -// RenderText***() functions calls ImDrawList::AddText() calls ImBitmapFont::RenderText() -void ImGui::RenderText(ImVec2 pos, const char* text, const char* text_end, bool hide_text_after_hash) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - // Hide anything after a '##' string - const char* text_display_end; - if (hide_text_after_hash) - { - text_display_end = FindRenderedTextEnd(text, text_end); - } - else - { - if (!text_end) - text_end = text + strlen(text); // FIXME-OPT - text_display_end = text_end; - } - - const int text_len = (int)(text_display_end - text); - if (text_len > 0) - { - window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_display_end); - if (g.LogEnabled) - LogRenderedText(pos, text, text_display_end); - } -} - -void ImGui::RenderTextWrapped(ImVec2 pos, const char* text, const char* text_end, float wrap_width) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - if (!text_end) - text_end = text + strlen(text); // FIXME-OPT - - const int text_len = (int)(text_end - text); - if (text_len > 0) - { - window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_end, wrap_width); - if (g.LogEnabled) - LogRenderedText(pos, text, text_end); - } -} - -// Default clip_rect uses (pos_min,pos_max) -// Handle clipping on CPU immediately (vs typically let the GPU clip the triangles that are overlapping the clipping rectangle edges) -void ImGui::RenderTextClipped(const ImVec2& pos_min, const ImVec2& pos_max, const char* text, const char* text_end, const ImVec2* text_size_if_known, const ImVec2& align, const ImRect* clip_rect) -{ - // Hide anything after a '##' string - const char* text_display_end = FindRenderedTextEnd(text, text_end); - const int text_len = (int)(text_display_end - text); - if (text_len == 0) - return; - - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - // Perform CPU side clipping for single clipped element to avoid using scissor state - ImVec2 pos = pos_min; - const ImVec2 text_size = text_size_if_known ? *text_size_if_known : CalcTextSize(text, text_display_end, false, 0.0f); - - const ImVec2* clip_min = clip_rect ? &clip_rect->Min : &pos_min; - const ImVec2* clip_max = clip_rect ? &clip_rect->Max : &pos_max; - bool need_clipping = (pos.x + text_size.x >= clip_max->x) || (pos.y + text_size.y >= clip_max->y); - if (clip_rect) // If we had no explicit clipping rectangle then pos==clip_min - need_clipping |= (pos.x < clip_min->x) || (pos.y < clip_min->y); - - // Align whole block. We should defer that to the better rendering function when we'll have support for individual line alignment. - if (align.x > 0.0f) pos.x = ImMax(pos.x, pos.x + (pos_max.x - pos.x - text_size.x) * align.x); - if (align.y > 0.0f) pos.y = ImMax(pos.y, pos.y + (pos_max.y - pos.y - text_size.y) * align.y); - - // Render - if (need_clipping) - { - ImVec4 fine_clip_rect(clip_min->x, clip_min->y, clip_max->x, clip_max->y); - window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_display_end, 0.0f, &fine_clip_rect); - } - else - { - window->DrawList->AddText(g.Font, g.FontSize, pos, GetColorU32(ImGuiCol_Text), text, text_display_end, 0.0f, NULL); - } - if (g.LogEnabled) - LogRenderedText(pos, text, text_display_end); -} - -// Render a rectangle shaped with optional rounding and borders -void ImGui::RenderFrame(ImVec2 p_min, ImVec2 p_max, ImU32 fill_col, bool border, float rounding) -{ - ImGuiWindow* window = GetCurrentWindow(); - - window->DrawList->AddRectFilled(p_min, p_max, fill_col, rounding); - if (border && (window->Flags & ImGuiWindowFlags_ShowBorders)) - { - window->DrawList->AddRect(p_min+ImVec2(1,1), p_max+ImVec2(1,1), GetColorU32(ImGuiCol_BorderShadow), rounding); - window->DrawList->AddRect(p_min, p_max, GetColorU32(ImGuiCol_Border), rounding); - } -} - -// Render a triangle to denote expanded/collapsed state -void ImGui::RenderCollapseTriangle(ImVec2 p_min, bool is_open, float scale, bool shadow) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - const float h = g.FontSize * 1.00f; - const float r = h * 0.40f * scale; - ImVec2 center = p_min + ImVec2(h*0.50f, h*0.50f*scale); - - ImVec2 a, b, c; - if (is_open) - { - center.y -= r*0.25f; - a = center + ImVec2(0,1)*r; - b = center + ImVec2(-0.866f,-0.5f)*r; - c = center + ImVec2(0.866f,-0.5f)*r; - } - else - { - a = center + ImVec2(1,0)*r; - b = center + ImVec2(-0.500f,0.866f)*r; - c = center + ImVec2(-0.500f,-0.866f)*r; - } - - if (shadow && (window->Flags & ImGuiWindowFlags_ShowBorders) != 0) - window->DrawList->AddTriangleFilled(a+ImVec2(2,2), b+ImVec2(2,2), c+ImVec2(2,2), GetColorU32(ImGuiCol_BorderShadow)); - window->DrawList->AddTriangleFilled(a, b, c, GetColorU32(ImGuiCol_Text)); -} - -void ImGui::RenderBullet(ImVec2 pos) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DrawList->AddCircleFilled(pos, GImGui->FontSize*0.20f, GetColorU32(ImGuiCol_Text), 8); -} - -void ImGui::RenderCheckMark(ImVec2 pos, ImU32 col) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - ImVec2 a, b, c; - float start_x = (float)(int)(g.FontSize * 0.307f + 0.5f); - float rem_third = (float)(int)((g.FontSize - start_x) / 3.0f); - a.x = pos.x + 0.5f + start_x; - b.x = a.x + rem_third; - c.x = a.x + rem_third * 3.0f; - b.y = pos.y - 1.0f + (float)(int)(g.Font->Ascent * (g.FontSize / g.Font->FontSize) + 0.5f) + (float)(int)(g.Font->DisplayOffset.y); - a.y = b.y - rem_third; - c.y = b.y - rem_third * 2.0f; - - window->DrawList->PathLineTo(a); - window->DrawList->PathLineTo(b); - window->DrawList->PathLineTo(c); - window->DrawList->PathStroke(col, false); -} - -// Calculate text size. Text can be multi-line. Optionally ignore text after a ## marker. -// CalcTextSize("") should return ImVec2(0.0f, GImGui->FontSize) -ImVec2 ImGui::CalcTextSize(const char* text, const char* text_end, bool hide_text_after_double_hash, float wrap_width) -{ - ImGuiContext& g = *GImGui; - - const char* text_display_end; - if (hide_text_after_double_hash) - text_display_end = FindRenderedTextEnd(text, text_end); // Hide anything after a '##' string - else - text_display_end = text_end; - - ImFont* font = g.Font; - const float font_size = g.FontSize; - if (text == text_display_end) - return ImVec2(0.0f, font_size); - ImVec2 text_size = font->CalcTextSizeA(font_size, FLT_MAX, wrap_width, text, text_display_end, NULL); - - // Cancel out character spacing for the last character of a line (it is baked into glyph->XAdvance field) - const float font_scale = font_size / font->FontSize; - const float character_spacing_x = 1.0f * font_scale; - if (text_size.x > 0.0f) - text_size.x -= character_spacing_x; - text_size.x = (float)(int)(text_size.x + 0.95f); - - return text_size; -} - -// Helper to calculate coarse clipping of large list of evenly sized items. -// NB: Prefer using the ImGuiListClipper higher-level helper if you can! Read comments and instructions there on how those use this sort of pattern. -// NB: 'items_count' is only used to clamp the result, if you don't know your count you can use INT_MAX -void ImGui::CalcListClipping(int items_count, float items_height, int* out_items_display_start, int* out_items_display_end) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindowRead(); - if (g.LogEnabled) - { - // If logging is active, do not perform any clipping - *out_items_display_start = 0; - *out_items_display_end = items_count; - return; - } - if (window->SkipItems) - { - *out_items_display_start = *out_items_display_end = 0; - return; - } - - const ImVec2 pos = window->DC.CursorPos; - int start = (int)((window->ClipRect.Min.y - pos.y) / items_height); - int end = (int)((window->ClipRect.Max.y - pos.y) / items_height); - start = ImClamp(start, 0, items_count); - end = ImClamp(end + 1, start, items_count); - *out_items_display_start = start; - *out_items_display_end = end; -} - -// Find window given position, search front-to-back -// FIXME: Note that we have a lag here because WindowRectClipped is updated in Begin() so windows moved by user via SetWindowPos() and not SetNextWindowPos() will have that rectangle lagging by a frame at the time FindHoveredWindow() is called, aka before the next Begin(). Moving window thankfully isn't affected. -static ImGuiWindow* FindHoveredWindow(ImVec2 pos, bool excluding_childs) -{ - ImGuiContext& g = *GImGui; - for (int i = g.Windows.Size-1; i >= 0; i--) - { - ImGuiWindow* window = g.Windows[i]; - if (!window->Active) - continue; - if (window->Flags & ImGuiWindowFlags_NoInputs) - continue; - if (excluding_childs && (window->Flags & ImGuiWindowFlags_ChildWindow) != 0) - continue; - - // Using the clipped AABB so a child window will typically be clipped by its parent. - ImRect bb(window->WindowRectClipped.Min - g.Style.TouchExtraPadding, window->WindowRectClipped.Max + g.Style.TouchExtraPadding); - if (bb.Contains(pos)) - return window; - } - return NULL; -} - -// Test if mouse cursor is hovering given rectangle -// NB- Rectangle is clipped by our current clip setting -// NB- Expand the rectangle to be generous on imprecise inputs systems (g.Style.TouchExtraPadding) -bool ImGui::IsMouseHoveringRect(const ImVec2& r_min, const ImVec2& r_max, bool clip) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindowRead(); - - // Clip - ImRect rect_clipped(r_min, r_max); - if (clip) - rect_clipped.Clip(window->ClipRect); - - // Expand for touch input - const ImRect rect_for_touch(rect_clipped.Min - g.Style.TouchExtraPadding, rect_clipped.Max + g.Style.TouchExtraPadding); - return rect_for_touch.Contains(g.IO.MousePos); -} - -bool ImGui::IsMouseHoveringWindow() -{ - ImGuiContext& g = *GImGui; - return g.HoveredWindow == g.CurrentWindow; -} - -bool ImGui::IsMouseHoveringAnyWindow() -{ - ImGuiContext& g = *GImGui; - return g.HoveredWindow != NULL; -} - -bool ImGui::IsPosHoveringAnyWindow(const ImVec2& pos) -{ - return FindHoveredWindow(pos, false) != NULL; -} - -static bool IsKeyPressedMap(ImGuiKey key, bool repeat) -{ - const int key_index = GImGui->IO.KeyMap[key]; - return ImGui::IsKeyPressed(key_index, repeat); -} - -int ImGui::GetKeyIndex(ImGuiKey key) -{ - IM_ASSERT(key >= 0 && key < ImGuiKey_COUNT); - return GImGui->IO.KeyMap[key]; -} - -bool ImGui::IsKeyDown(int key_index) -{ - if (key_index < 0) return false; - IM_ASSERT(key_index >= 0 && key_index < IM_ARRAYSIZE(GImGui->IO.KeysDown)); - return GImGui->IO.KeysDown[key_index]; -} - -bool ImGui::IsKeyPressed(int key_index, bool repeat) -{ - ImGuiContext& g = *GImGui; - if (key_index < 0) return false; - IM_ASSERT(key_index >= 0 && key_index < IM_ARRAYSIZE(g.IO.KeysDown)); - const float t = g.IO.KeysDownDuration[key_index]; - if (t == 0.0f) - return true; - - if (repeat && t > g.IO.KeyRepeatDelay) - { - float delay = g.IO.KeyRepeatDelay, rate = g.IO.KeyRepeatRate; - if ((fmodf(t - delay, rate) > rate*0.5f) != (fmodf(t - delay - g.IO.DeltaTime, rate) > rate*0.5f)) - return true; - } - return false; -} - -bool ImGui::IsKeyReleased(int key_index) -{ - ImGuiContext& g = *GImGui; - if (key_index < 0) return false; - IM_ASSERT(key_index >= 0 && key_index < IM_ARRAYSIZE(g.IO.KeysDown)); - if (g.IO.KeysDownDurationPrev[key_index] >= 0.0f && !g.IO.KeysDown[key_index]) - return true; - return false; -} - -bool ImGui::IsMouseDown(int button) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - return g.IO.MouseDown[button]; -} - -bool ImGui::IsMouseClicked(int button, bool repeat) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - const float t = g.IO.MouseDownDuration[button]; - if (t == 0.0f) - return true; - - if (repeat && t > g.IO.KeyRepeatDelay) - { - float delay = g.IO.KeyRepeatDelay, rate = g.IO.KeyRepeatRate; - if ((fmodf(t - delay, rate) > rate*0.5f) != (fmodf(t - delay - g.IO.DeltaTime, rate) > rate*0.5f)) - return true; - } - - return false; -} - -bool ImGui::IsMouseReleased(int button) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - return g.IO.MouseReleased[button]; -} - -bool ImGui::IsMouseDoubleClicked(int button) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - return g.IO.MouseDoubleClicked[button]; -} - -bool ImGui::IsMouseDragging(int button, float lock_threshold) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - if (!g.IO.MouseDown[button]) - return false; - if (lock_threshold < 0.0f) - lock_threshold = g.IO.MouseDragThreshold; - return g.IO.MouseDragMaxDistanceSqr[button] >= lock_threshold * lock_threshold; -} - -ImVec2 ImGui::GetMousePos() -{ - return GImGui->IO.MousePos; -} - -// NB: prefer to call right after BeginPopup(). At the time Selectable/MenuItem is activated, the popup is already closed! -ImVec2 ImGui::GetMousePosOnOpeningCurrentPopup() -{ - ImGuiContext& g = *GImGui; - if (g.CurrentPopupStack.Size > 0) - return g.OpenPopupStack[g.CurrentPopupStack.Size-1].MousePosOnOpen; - return g.IO.MousePos; -} - -ImVec2 ImGui::GetMouseDragDelta(int button, float lock_threshold) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - if (lock_threshold < 0.0f) - lock_threshold = g.IO.MouseDragThreshold; - if (g.IO.MouseDown[button]) - if (g.IO.MouseDragMaxDistanceSqr[button] >= lock_threshold * lock_threshold) - return g.IO.MousePos - g.IO.MouseClickedPos[button]; // Assume we can only get active with left-mouse button (at the moment). - return ImVec2(0.0f, 0.0f); -} - -void ImGui::ResetMouseDragDelta(int button) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(button >= 0 && button < IM_ARRAYSIZE(g.IO.MouseDown)); - // NB: We don't need to reset g.IO.MouseDragMaxDistanceSqr - g.IO.MouseClickedPos[button] = g.IO.MousePos; -} - -ImGuiMouseCursor ImGui::GetMouseCursor() -{ - return GImGui->MouseCursor; -} - -void ImGui::SetMouseCursor(ImGuiMouseCursor cursor_type) -{ - GImGui->MouseCursor = cursor_type; -} - -void ImGui::CaptureKeyboardFromApp(bool capture) -{ - GImGui->CaptureKeyboardNextFrame = capture ? 1 : 0; -} - -void ImGui::CaptureMouseFromApp(bool capture) -{ - GImGui->CaptureMouseNextFrame = capture ? 1 : 0; -} - -bool ImGui::IsItemHovered() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemHoveredAndUsable; -} - -bool ImGui::IsItemHoveredRect() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemHoveredRect; -} - -bool ImGui::IsItemActive() -{ - ImGuiContext& g = *GImGui; - if (g.ActiveId) - { - ImGuiWindow* window = GetCurrentWindowRead(); - return g.ActiveId == window->DC.LastItemId; - } - return false; -} - -bool ImGui::IsItemClicked(int mouse_button) -{ - return IsMouseClicked(mouse_button) && IsItemHovered(); -} - -bool ImGui::IsAnyItemHovered() -{ - return GImGui->HoveredId != 0 || GImGui->HoveredIdPreviousFrame != 0; -} - -bool ImGui::IsAnyItemActive() -{ - return GImGui->ActiveId != 0; -} - -bool ImGui::IsItemVisible() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - ImRect r(window->ClipRect); - return r.Overlaps(window->DC.LastItemRect); -} - -// Allow last item to be overlapped by a subsequent item. Both may be activated during the same frame before the later one takes priority. -void ImGui::SetItemAllowOverlap() -{ - ImGuiContext& g = *GImGui; - if (g.HoveredId == g.CurrentWindow->DC.LastItemId) - g.HoveredIdAllowOverlap = true; - if (g.ActiveId == g.CurrentWindow->DC.LastItemId) - g.ActiveIdAllowOverlap = true; -} - -ImVec2 ImGui::GetItemRectMin() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemRect.Min; -} - -ImVec2 ImGui::GetItemRectMax() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemRect.Max; -} - -ImVec2 ImGui::GetItemRectSize() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.LastItemRect.GetSize(); -} - -ImVec2 ImGui::CalcItemRectClosestPoint(const ImVec2& pos, bool on_edge, float outward) -{ - ImGuiWindow* window = GetCurrentWindowRead(); - ImRect rect = window->DC.LastItemRect; - rect.Expand(outward); - return rect.GetClosestPoint(pos, on_edge); -} - -// Tooltip is stored and turned into a BeginTooltip()/EndTooltip() sequence at the end of the frame. Each call override previous value. -void ImGui::SetTooltipV(const char* fmt, va_list args) -{ - ImGuiContext& g = *GImGui; - ImFormatStringV(g.Tooltip, IM_ARRAYSIZE(g.Tooltip), fmt, args); -} - -void ImGui::SetTooltip(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - SetTooltipV(fmt, args); - va_end(args); -} - -static ImRect GetVisibleRect() -{ - ImGuiContext& g = *GImGui; - if (g.IO.DisplayVisibleMin.x != g.IO.DisplayVisibleMax.x && g.IO.DisplayVisibleMin.y != g.IO.DisplayVisibleMax.y) - return ImRect(g.IO.DisplayVisibleMin, g.IO.DisplayVisibleMax); - return ImRect(0.0f, 0.0f, g.IO.DisplaySize.x, g.IO.DisplaySize.y); -} - -void ImGui::BeginTooltip() -{ - ImGuiWindowFlags flags = ImGuiWindowFlags_Tooltip|ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_AlwaysAutoResize; - ImGui::Begin("##Tooltip", NULL, flags); -} - -void ImGui::EndTooltip() -{ - IM_ASSERT(GetCurrentWindowRead()->Flags & ImGuiWindowFlags_Tooltip); // Mismatched BeginTooltip()/EndTooltip() calls - ImGui::End(); -} - -static bool IsPopupOpen(ImGuiID id) -{ - ImGuiContext& g = *GImGui; - return g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].PopupId == id; -} - -// Mark popup as open (toggle toward open state). -// Popups are closed when user click outside, or activate a pressable item, or CloseCurrentPopup() is called within a BeginPopup()/EndPopup() block. -// Popup identifiers are relative to the current ID-stack (so OpenPopup and BeginPopup needs to be at the same level). -// One open popup per level of the popup hierarchy (NB: when assigning we reset the Window member of ImGuiPopupRef to NULL) -void ImGui::OpenPopupEx(const char* str_id, bool reopen_existing) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - ImGuiID id = window->GetID(str_id); - int current_stack_size = g.CurrentPopupStack.Size; - ImGuiPopupRef popup_ref = ImGuiPopupRef(id, window, window->GetID("##menus"), g.IO.MousePos); // Tagged as new ref because constructor sets Window to NULL (we are passing the ParentWindow info here) - if (g.OpenPopupStack.Size < current_stack_size + 1) - g.OpenPopupStack.push_back(popup_ref); - else if (reopen_existing || g.OpenPopupStack[current_stack_size].PopupId != id) - { - g.OpenPopupStack.resize(current_stack_size+1); - g.OpenPopupStack[current_stack_size] = popup_ref; - } -} - -void ImGui::OpenPopup(const char* str_id) -{ - ImGui::OpenPopupEx(str_id, false); -} - -static void CloseInactivePopups() -{ - ImGuiContext& g = *GImGui; - if (g.OpenPopupStack.empty()) - return; - - // When popups are stacked, clicking on a lower level popups puts focus back to it and close popups above it. - // Don't close our own child popup windows - int n = 0; - if (g.FocusedWindow) - { - for (n = 0; n < g.OpenPopupStack.Size; n++) - { - ImGuiPopupRef& popup = g.OpenPopupStack[n]; - if (!popup.Window) - continue; - IM_ASSERT((popup.Window->Flags & ImGuiWindowFlags_Popup) != 0); - if (popup.Window->Flags & ImGuiWindowFlags_ChildWindow) - continue; - - bool has_focus = false; - for (int m = n; m < g.OpenPopupStack.Size && !has_focus; m++) - has_focus = (g.OpenPopupStack[m].Window && g.OpenPopupStack[m].Window->RootWindow == g.FocusedWindow->RootWindow); - if (!has_focus) - break; - } - } - if (n < g.OpenPopupStack.Size) // This test is not required but it allows to set a useful breakpoint on the line below - g.OpenPopupStack.resize(n); -} - -static ImGuiWindow* GetFrontMostModalRootWindow() -{ - ImGuiContext& g = *GImGui; - for (int n = g.OpenPopupStack.Size-1; n >= 0; n--) - if (ImGuiWindow* front_most_popup = g.OpenPopupStack.Data[n].Window) - if (front_most_popup->Flags & ImGuiWindowFlags_Modal) - return front_most_popup; - return NULL; -} - -static void ClosePopupToLevel(int remaining) -{ - ImGuiContext& g = *GImGui; - if (remaining > 0) - ImGui::FocusWindow(g.OpenPopupStack[remaining-1].Window); - else - ImGui::FocusWindow(g.OpenPopupStack[0].ParentWindow); - g.OpenPopupStack.resize(remaining); -} - -static void ClosePopup(ImGuiID id) -{ - if (!IsPopupOpen(id)) - return; - ImGuiContext& g = *GImGui; - ClosePopupToLevel(g.OpenPopupStack.Size - 1); -} - -// Close the popup we have begin-ed into. -void ImGui::CloseCurrentPopup() -{ - ImGuiContext& g = *GImGui; - int popup_idx = g.CurrentPopupStack.Size - 1; - if (popup_idx < 0 || popup_idx > g.OpenPopupStack.Size || g.CurrentPopupStack[popup_idx].PopupId != g.OpenPopupStack[popup_idx].PopupId) - return; - while (popup_idx > 0 && g.OpenPopupStack[popup_idx].Window && (g.OpenPopupStack[popup_idx].Window->Flags & ImGuiWindowFlags_ChildMenu)) - popup_idx--; - ClosePopupToLevel(popup_idx); -} - -static inline void ClearSetNextWindowData() -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowPosCond = g.SetNextWindowSizeCond = g.SetNextWindowContentSizeCond = g.SetNextWindowCollapsedCond = 0; - g.SetNextWindowSizeConstraint = g.SetNextWindowFocus = false; -} - -static bool BeginPopupEx(const char* str_id, ImGuiWindowFlags extra_flags) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - const ImGuiID id = window->GetID(str_id); - if (!IsPopupOpen(id)) - { - ClearSetNextWindowData(); // We behave like Begin() and need to consume those values - return false; - } - - ImGui::PushStyleVar(ImGuiStyleVar_WindowRounding, 0.0f); - ImGuiWindowFlags flags = extra_flags|ImGuiWindowFlags_Popup|ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_AlwaysAutoResize; - - char name[32]; - if (flags & ImGuiWindowFlags_ChildMenu) - ImFormatString(name, 20, "##menu_%d", g.CurrentPopupStack.Size); // Recycle windows based on depth - else - ImFormatString(name, 20, "##popup_%08x", id); // Not recycling, so we can close/open during the same frame - - bool is_open = ImGui::Begin(name, NULL, flags); - if (!(window->Flags & ImGuiWindowFlags_ShowBorders)) - g.CurrentWindow->Flags &= ~ImGuiWindowFlags_ShowBorders; - if (!is_open) // NB: is_open can be 'false' when the popup is completely clipped (e.g. zero size display) - ImGui::EndPopup(); - - return is_open; -} - -bool ImGui::BeginPopup(const char* str_id) -{ - if (GImGui->OpenPopupStack.Size <= GImGui->CurrentPopupStack.Size) // Early out for performance - { - ClearSetNextWindowData(); // We behave like Begin() and need to consume those values - return false; - } - return BeginPopupEx(str_id, ImGuiWindowFlags_ShowBorders); -} - -bool ImGui::BeginPopupModal(const char* name, bool* p_open, ImGuiWindowFlags extra_flags) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - const ImGuiID id = window->GetID(name); - if (!IsPopupOpen(id)) - { - ClearSetNextWindowData(); // We behave like Begin() and need to consume those values - return false; - } - - ImGuiWindowFlags flags = extra_flags|ImGuiWindowFlags_Popup|ImGuiWindowFlags_Modal|ImGuiWindowFlags_NoCollapse|ImGuiWindowFlags_NoSavedSettings; - bool is_open = ImGui::Begin(name, p_open, flags); - if (!is_open || (p_open && !*p_open)) // NB: is_open can be 'false' when the popup is completely clipped (e.g. zero size display) - { - ImGui::EndPopup(); - if (is_open) - ClosePopup(id); - return false; - } - - return is_open; -} - -void ImGui::EndPopup() -{ - ImGuiWindow* window = GetCurrentWindow(); - IM_ASSERT(window->Flags & ImGuiWindowFlags_Popup); // Mismatched BeginPopup()/EndPopup() calls - IM_ASSERT(GImGui->CurrentPopupStack.Size > 0); - ImGui::End(); - if (!(window->Flags & ImGuiWindowFlags_Modal)) - ImGui::PopStyleVar(); -} - -// This is a helper to handle the most simple case of associating one named popup to one given widget. -// 1. If you have many possible popups (for different "instances" of a same widget, or for wholly different widgets), you may be better off handling -// this yourself so you can store data relative to the widget that opened the popup instead of choosing different popup identifiers. -// 2. If you want right-clicking on the same item to reopen the popup at new location, use the same code replacing IsItemHovered() with IsItemHoveredRect() -// and passing true to the OpenPopupEx(). -// Because: hovering an item in a window below the popup won't normally trigger is hovering behavior/coloring. The pattern of ignoring the fact that -// the item isn't interactable (because it is blocked by the active popup) may useful in some situation when e.g. large canvas as one item, content of menu -// driven by click position. -bool ImGui::BeginPopupContextItem(const char* str_id, int mouse_button) -{ - if (IsItemHovered() && IsMouseClicked(mouse_button)) - OpenPopupEx(str_id, false); - return BeginPopup(str_id); -} - -bool ImGui::BeginPopupContextWindow(bool also_over_items, const char* str_id, int mouse_button) -{ - if (!str_id) str_id = "window_context_menu"; - if (IsMouseHoveringWindow() && IsMouseClicked(mouse_button)) - if (also_over_items || !IsAnyItemHovered()) - OpenPopupEx(str_id, true); - return BeginPopup(str_id); -} - -bool ImGui::BeginPopupContextVoid(const char* str_id, int mouse_button) -{ - if (!str_id) str_id = "void_context_menu"; - if (!IsMouseHoveringAnyWindow() && IsMouseClicked(mouse_button)) - OpenPopupEx(str_id, true); - return BeginPopup(str_id); -} - -bool ImGui::BeginChild(const char* str_id, const ImVec2& size_arg, bool border, ImGuiWindowFlags extra_flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - ImGuiWindowFlags flags = ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_ChildWindow; - - const ImVec2 content_avail = GetContentRegionAvail(); - ImVec2 size = ImFloor(size_arg); - if (size.x <= 0.0f) - { - if (size.x == 0.0f) - flags |= ImGuiWindowFlags_ChildWindowAutoFitX; - size.x = ImMax(content_avail.x, 4.0f) - fabsf(size.x); // Arbitrary minimum zero-ish child size of 4.0f (0.0f causing too much issues) - } - if (size.y <= 0.0f) - { - if (size.y == 0.0f) - flags |= ImGuiWindowFlags_ChildWindowAutoFitY; - size.y = ImMax(content_avail.y, 4.0f) - fabsf(size.y); - } - if (border) - flags |= ImGuiWindowFlags_ShowBorders; - flags |= extra_flags; - - char title[256]; - ImFormatString(title, IM_ARRAYSIZE(title), "%s.%s", window->Name, str_id); - - bool ret = ImGui::Begin(title, NULL, size, -1.0f, flags); - - if (!(window->Flags & ImGuiWindowFlags_ShowBorders)) - GetCurrentWindow()->Flags &= ~ImGuiWindowFlags_ShowBorders; - - return ret; -} - -bool ImGui::BeginChild(ImGuiID id, const ImVec2& size, bool border, ImGuiWindowFlags extra_flags) -{ - char str_id[32]; - ImFormatString(str_id, IM_ARRAYSIZE(str_id), "child_%08x", id); - bool ret = ImGui::BeginChild(str_id, size, border, extra_flags); - return ret; -} - -void ImGui::EndChild() -{ - ImGuiWindow* window = GetCurrentWindow(); - - IM_ASSERT(window->Flags & ImGuiWindowFlags_ChildWindow); // Mismatched BeginChild()/EndChild() callss - if ((window->Flags & ImGuiWindowFlags_ComboBox) || window->BeginCount > 1) - { - ImGui::End(); - } - else - { - // When using auto-filling child window, we don't provide full width/height to ItemSize so that it doesn't feed back into automatic size-fitting. - ImVec2 sz = GetWindowSize(); - if (window->Flags & ImGuiWindowFlags_ChildWindowAutoFitX) // Arbitrary minimum zero-ish child size of 4.0f causes less trouble than a 0.0f - sz.x = ImMax(4.0f, sz.x); - if (window->Flags & ImGuiWindowFlags_ChildWindowAutoFitY) - sz.y = ImMax(4.0f, sz.y); - - ImGui::End(); - - window = GetCurrentWindow(); - ImRect bb(window->DC.CursorPos, window->DC.CursorPos + sz); - ItemSize(sz); - ItemAdd(bb, NULL); - } -} - -// Helper to create a child window / scrolling region that looks like a normal widget frame. -bool ImGui::BeginChildFrame(ImGuiID id, const ImVec2& size, ImGuiWindowFlags extra_flags) -{ - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - ImGui::PushStyleColor(ImGuiCol_ChildWindowBg, style.Colors[ImGuiCol_FrameBg]); - ImGui::PushStyleVar(ImGuiStyleVar_ChildWindowRounding, style.FrameRounding); - ImGui::PushStyleVar(ImGuiStyleVar_WindowPadding, style.FramePadding); - return ImGui::BeginChild(id, size, (g.CurrentWindow->Flags & ImGuiWindowFlags_ShowBorders) ? true : false, ImGuiWindowFlags_NoMove | ImGuiWindowFlags_AlwaysUseWindowPadding | extra_flags); -} - -void ImGui::EndChildFrame() -{ - ImGui::EndChild(); - ImGui::PopStyleVar(2); - ImGui::PopStyleColor(); -} - -// Save and compare stack sizes on Begin()/End() to detect usage errors -static void CheckStacksSize(ImGuiWindow* window, bool write) -{ - // NOT checking: DC.ItemWidth, DC.AllowKeyboardFocus, DC.ButtonRepeat, DC.TextWrapPos (per window) to allow user to conveniently push once and not pop (they are cleared on Begin) - ImGuiContext& g = *GImGui; - int* p_backup = &window->DC.StackSizesBackup[0]; - { int current = window->IDStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushID/PopID Mismatch!"); p_backup++; } // User forgot PopID() - { int current = window->DC.GroupStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "BeginGroup/EndGroup Mismatch!"); p_backup++; } // User forgot EndGroup() - { int current = g.CurrentPopupStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "BeginMenu/EndMenu or BeginPopup/EndPopup Mismatch"); p_backup++; }// User forgot EndPopup()/EndMenu() - { int current = g.ColorModifiers.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushStyleColor/PopStyleColor Mismatch!"); p_backup++; } // User forgot PopStyleColor() - { int current = g.StyleModifiers.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushStyleVar/PopStyleVar Mismatch!"); p_backup++; } // User forgot PopStyleVar() - { int current = g.FontStack.Size; if (write) *p_backup = current; else IM_ASSERT(*p_backup == current && "PushFont/PopFont Mismatch!"); p_backup++; } // User forgot PopFont() - IM_ASSERT(p_backup == window->DC.StackSizesBackup + IM_ARRAYSIZE(window->DC.StackSizesBackup)); -} - -static ImVec2 FindBestPopupWindowPos(const ImVec2& base_pos, const ImVec2& size, int* last_dir, const ImRect& r_inner) -{ - const ImGuiStyle& style = GImGui->Style; - - // Clamp into visible area while not overlapping the cursor. Safety padding is optional if our popup size won't fit without it. - ImVec2 safe_padding = style.DisplaySafeAreaPadding; - ImRect r_outer(GetVisibleRect()); - r_outer.Reduce(ImVec2((size.x - r_outer.GetWidth() > safe_padding.x*2) ? safe_padding.x : 0.0f, (size.y - r_outer.GetHeight() > safe_padding.y*2) ? safe_padding.y : 0.0f)); - ImVec2 base_pos_clamped = ImClamp(base_pos, r_outer.Min, r_outer.Max - size); - - for (int n = (*last_dir != -1) ? -1 : 0; n < 4; n++) // Last, Right, down, up, left. (Favor last used direction). - { - const int dir = (n == -1) ? *last_dir : n; - ImRect rect(dir == 0 ? r_inner.Max.x : r_outer.Min.x, dir == 1 ? r_inner.Max.y : r_outer.Min.y, dir == 3 ? r_inner.Min.x : r_outer.Max.x, dir == 2 ? r_inner.Min.y : r_outer.Max.y); - if (rect.GetWidth() < size.x || rect.GetHeight() < size.y) - continue; - *last_dir = dir; - return ImVec2(dir == 0 ? r_inner.Max.x : dir == 3 ? r_inner.Min.x - size.x : base_pos_clamped.x, dir == 1 ? r_inner.Max.y : dir == 2 ? r_inner.Min.y - size.y : base_pos_clamped.y); - } - - // Fallback, try to keep within display - *last_dir = -1; - ImVec2 pos = base_pos; - pos.x = ImMax(ImMin(pos.x + size.x, r_outer.Max.x) - size.x, r_outer.Min.x); - pos.y = ImMax(ImMin(pos.y + size.y, r_outer.Max.y) - size.y, r_outer.Min.y); - return pos; -} - -ImGuiWindow* ImGui::FindWindowByName(const char* name) -{ - // FIXME-OPT: Store sorted hashes -> pointers so we can do a bissection in a contiguous block - ImGuiContext& g = *GImGui; - ImGuiID id = ImHash(name, 0); - for (int i = 0; i < g.Windows.Size; i++) - if (g.Windows[i]->ID == id) - return g.Windows[i]; - return NULL; -} - -static ImGuiWindow* CreateNewWindow(const char* name, ImVec2 size, ImGuiWindowFlags flags) -{ - ImGuiContext& g = *GImGui; - - // Create window the first time - ImGuiWindow* window = (ImGuiWindow*)ImGui::MemAlloc(sizeof(ImGuiWindow)); - IM_PLACEMENT_NEW(window) ImGuiWindow(name); - window->Flags = flags; - - if (flags & ImGuiWindowFlags_NoSavedSettings) - { - // User can disable loading and saving of settings. Tooltip and child windows also don't store settings. - window->Size = window->SizeFull = size; - } - else - { - // Retrieve settings from .ini file - // Use SetWindowPos() or SetNextWindowPos() with the appropriate condition flag to change the initial position of a window. - window->PosFloat = ImVec2(60, 60); - window->Pos = ImVec2((float)(int)window->PosFloat.x, (float)(int)window->PosFloat.y); - - ImGuiIniData* settings = FindWindowSettings(name); - if (!settings) - { - settings = AddWindowSettings(name); - } - else - { - window->SetWindowPosAllowFlags &= ~ImGuiSetCond_FirstUseEver; - window->SetWindowSizeAllowFlags &= ~ImGuiSetCond_FirstUseEver; - window->SetWindowCollapsedAllowFlags &= ~ImGuiSetCond_FirstUseEver; - } - - if (settings->Pos.x != FLT_MAX) - { - window->PosFloat = settings->Pos; - window->Pos = ImVec2((float)(int)window->PosFloat.x, (float)(int)window->PosFloat.y); - window->Collapsed = settings->Collapsed; - } - - if (ImLengthSqr(settings->Size) > 0.00001f && !(flags & ImGuiWindowFlags_NoResize)) - size = settings->Size; - window->Size = window->SizeFull = size; - } - - if ((flags & ImGuiWindowFlags_AlwaysAutoResize) != 0) - { - window->AutoFitFramesX = window->AutoFitFramesY = 2; - window->AutoFitOnlyGrows = false; - } - else - { - if (window->Size.x <= 0.0f) - window->AutoFitFramesX = 2; - if (window->Size.y <= 0.0f) - window->AutoFitFramesY = 2; - window->AutoFitOnlyGrows = (window->AutoFitFramesX > 0) || (window->AutoFitFramesY > 0); - } - - if (flags & ImGuiWindowFlags_NoBringToFrontOnFocus) - g.Windows.insert(g.Windows.begin(), window); // Quite slow but rare and only once - else - g.Windows.push_back(window); - return window; -} - -static void ApplySizeFullWithConstraint(ImGuiWindow* window, ImVec2 new_size) -{ - ImGuiContext& g = *GImGui; - if (g.SetNextWindowSizeConstraint) - { - // Using -1,-1 on either X/Y axis to preserve the current size. - ImRect cr = g.SetNextWindowSizeConstraintRect; - new_size.x = (cr.Min.x >= 0 && cr.Max.x >= 0) ? ImClamp(new_size.x, cr.Min.x, cr.Max.x) : window->SizeFull.x; - new_size.y = (cr.Min.y >= 0 && cr.Max.y >= 0) ? ImClamp(new_size.y, cr.Min.y, cr.Max.y) : window->SizeFull.y; - if (g.SetNextWindowSizeConstraintCallback) - { - ImGuiSizeConstraintCallbackData data; - data.UserData = g.SetNextWindowSizeConstraintCallbackUserData; - data.Pos = window->Pos; - data.CurrentSize = window->SizeFull; - data.DesiredSize = new_size; - g.SetNextWindowSizeConstraintCallback(&data); - new_size = data.DesiredSize; - } - } - if (!(window->Flags & (ImGuiWindowFlags_ChildWindow | ImGuiWindowFlags_AlwaysAutoResize))) - new_size = ImMax(new_size, g.Style.WindowMinSize); - window->SizeFull = new_size; -} - -// Push a new ImGui window to add widgets to. -// - A default window called "Debug" is automatically stacked at the beginning of every frame so you can use widgets without explicitly calling a Begin/End pair. -// - Begin/End can be called multiple times during the frame with the same window name to append content. -// - 'size_on_first_use' for a regular window denote the initial size for first-time creation (no saved data) and isn't that useful. Use SetNextWindowSize() prior to calling Begin() for more flexible window manipulation. -// - The window name is used as a unique identifier to preserve window information across frames (and save rudimentary information to the .ini file). -// You can use the "##" or "###" markers to use the same label with different id, or same id with different label. See documentation at the top of this file. -// - Return false when window is collapsed, so you can early out in your code. You always need to call ImGui::End() even if false is returned. -// - Passing 'bool* p_open' displays a Close button on the upper-right corner of the window, the pointed value will be set to false when the button is pressed. -// - Passing non-zero 'size' is roughly equivalent to calling SetNextWindowSize(size, ImGuiSetCond_FirstUseEver) prior to calling Begin(). -bool ImGui::Begin(const char* name, bool* p_open, ImGuiWindowFlags flags) -{ - return ImGui::Begin(name, p_open, ImVec2(0.f, 0.f), -1.0f, flags); -} - -bool ImGui::Begin(const char* name, bool* p_open, const ImVec2& size_on_first_use, float bg_alpha, ImGuiWindowFlags flags) -{ - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - IM_ASSERT(name != NULL); // Window name required - IM_ASSERT(g.Initialized); // Forgot to call ImGui::NewFrame() - IM_ASSERT(g.FrameCountEnded != g.FrameCount); // Called ImGui::Render() or ImGui::EndFrame() and haven't called ImGui::NewFrame() again yet - - if (flags & ImGuiWindowFlags_NoInputs) - flags |= ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoResize; - - // Find or create - bool window_is_new = false; - ImGuiWindow* window = FindWindowByName(name); - if (!window) - { - window = CreateNewWindow(name, size_on_first_use, flags); - window_is_new = true; - } - - const int current_frame = ImGui::GetFrameCount(); - const bool first_begin_of_the_frame = (window->LastFrameActive != current_frame); - if (first_begin_of_the_frame) - window->Flags = (ImGuiWindowFlags)flags; - else - flags = window->Flags; - - // Add to stack - ImGuiWindow* parent_window = !g.CurrentWindowStack.empty() ? g.CurrentWindowStack.back() : NULL; - g.CurrentWindowStack.push_back(window); - SetCurrentWindow(window); - CheckStacksSize(window, true); - IM_ASSERT(parent_window != NULL || !(flags & ImGuiWindowFlags_ChildWindow)); - - bool window_was_active = (window->LastFrameActive == current_frame - 1); // Not using !WasActive because the implicit "Debug" window would always toggle off->on - if (flags & ImGuiWindowFlags_Popup) - { - ImGuiPopupRef& popup_ref = g.OpenPopupStack[g.CurrentPopupStack.Size]; - window_was_active &= (window->PopupId == popup_ref.PopupId); - window_was_active &= (window == popup_ref.Window); - popup_ref.Window = window; - g.CurrentPopupStack.push_back(popup_ref); - window->PopupId = popup_ref.PopupId; - } - - const bool window_appearing_after_being_hidden = (window->HiddenFrames == 1); - - // Process SetNextWindow***() calls - bool window_pos_set_by_api = false, window_size_set_by_api = false; - if (g.SetNextWindowPosCond) - { - const ImVec2 backup_cursor_pos = window->DC.CursorPos; // FIXME: not sure of the exact reason of this saving/restore anymore :( need to look into that. - if (!window_was_active || window_appearing_after_being_hidden) window->SetWindowPosAllowFlags |= ImGuiSetCond_Appearing; - window_pos_set_by_api = (window->SetWindowPosAllowFlags & g.SetNextWindowPosCond) != 0; - if (window_pos_set_by_api && ImLengthSqr(g.SetNextWindowPosVal - ImVec2(-FLT_MAX,-FLT_MAX)) < 0.001f) - { - window->SetWindowPosCenterWanted = true; // May be processed on the next frame if this is our first frame and we are measuring size - window->SetWindowPosAllowFlags &= ~(ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing); - } - else - { - SetWindowPos(window, g.SetNextWindowPosVal, g.SetNextWindowPosCond); - } - window->DC.CursorPos = backup_cursor_pos; - g.SetNextWindowPosCond = 0; - } - if (g.SetNextWindowSizeCond) - { - if (!window_was_active || window_appearing_after_being_hidden) window->SetWindowSizeAllowFlags |= ImGuiSetCond_Appearing; - window_size_set_by_api = (window->SetWindowSizeAllowFlags & g.SetNextWindowSizeCond) != 0; - SetWindowSize(window, g.SetNextWindowSizeVal, g.SetNextWindowSizeCond); - g.SetNextWindowSizeCond = 0; - } - if (g.SetNextWindowContentSizeCond) - { - window->SizeContentsExplicit = g.SetNextWindowContentSizeVal; - g.SetNextWindowContentSizeCond = 0; - } - else if (first_begin_of_the_frame) - { - window->SizeContentsExplicit = ImVec2(0.0f, 0.0f); - } - if (g.SetNextWindowCollapsedCond) - { - if (!window_was_active || window_appearing_after_being_hidden) window->SetWindowCollapsedAllowFlags |= ImGuiSetCond_Appearing; - SetWindowCollapsed(window, g.SetNextWindowCollapsedVal, g.SetNextWindowCollapsedCond); - g.SetNextWindowCollapsedCond = 0; - } - if (g.SetNextWindowFocus) - { - ImGui::SetWindowFocus(); - g.SetNextWindowFocus = false; - } - - // Update known root window (if we are a child window, otherwise window == window->RootWindow) - int root_idx, root_non_popup_idx; - for (root_idx = g.CurrentWindowStack.Size - 1; root_idx > 0; root_idx--) - if (!(g.CurrentWindowStack[root_idx]->Flags & ImGuiWindowFlags_ChildWindow)) - break; - for (root_non_popup_idx = root_idx; root_non_popup_idx > 0; root_non_popup_idx--) - if (!(g.CurrentWindowStack[root_non_popup_idx]->Flags & (ImGuiWindowFlags_ChildWindow | ImGuiWindowFlags_Popup))) - break; - window->ParentWindow = parent_window; - window->RootWindow = g.CurrentWindowStack[root_idx]; - window->RootNonPopupWindow = g.CurrentWindowStack[root_non_popup_idx]; // This is merely for displaying the TitleBgActive color. - - // When reusing window again multiple times a frame, just append content (don't need to setup again) - if (first_begin_of_the_frame) - { - window->Active = true; - window->IndexWithinParent = 0; - window->BeginCount = 0; - window->ClipRect = ImVec4(-FLT_MAX,-FLT_MAX,+FLT_MAX,+FLT_MAX); - window->LastFrameActive = current_frame; - window->IDStack.resize(1); - - // Clear draw list, setup texture, outer clipping rectangle - window->DrawList->Clear(); - window->DrawList->PushTextureID(g.Font->ContainerAtlas->TexID); - ImRect fullscreen_rect(GetVisibleRect()); - if ((flags & ImGuiWindowFlags_ChildWindow) && !(flags & (ImGuiWindowFlags_ComboBox|ImGuiWindowFlags_Popup))) - PushClipRect(parent_window->ClipRect.Min, parent_window->ClipRect.Max, true); - else - PushClipRect(fullscreen_rect.Min, fullscreen_rect.Max, true); - - if (!window_was_active) - { - // Popup first latch mouse position, will position itself when it appears next frame - window->AutoPosLastDirection = -1; - if ((flags & ImGuiWindowFlags_Popup) != 0 && !window_pos_set_by_api) - window->PosFloat = g.IO.MousePos; - } - - // Collapse window by double-clicking on title bar - // At this point we don't have a clipping rectangle setup yet, so we can use the title bar area for hit detection and drawing - if (!(flags & ImGuiWindowFlags_NoTitleBar) && !(flags & ImGuiWindowFlags_NoCollapse)) - { - ImRect title_bar_rect = window->TitleBarRect(); - if (g.HoveredWindow == window && IsMouseHoveringRect(title_bar_rect.Min, title_bar_rect.Max) && g.IO.MouseDoubleClicked[0]) - { - window->Collapsed = !window->Collapsed; - if (!(flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - FocusWindow(window); - } - } - else - { - window->Collapsed = false; - } - - // SIZE - - // Save contents size from last frame for auto-fitting (unless explicitly specified) - window->SizeContents.x = (float)(int)((window->SizeContentsExplicit.x != 0.0f) ? window->SizeContentsExplicit.x : ((window_is_new ? 0.0f : window->DC.CursorMaxPos.x - window->Pos.x) + window->Scroll.x)); - window->SizeContents.y = (float)(int)((window->SizeContentsExplicit.y != 0.0f) ? window->SizeContentsExplicit.y : ((window_is_new ? 0.0f : window->DC.CursorMaxPos.y - window->Pos.y) + window->Scroll.y)); - - // Hide popup/tooltip window when first appearing while we measure size (because we recycle them) - if (window->HiddenFrames > 0) - window->HiddenFrames--; - if ((flags & (ImGuiWindowFlags_Popup | ImGuiWindowFlags_Tooltip)) != 0 && !window_was_active) - { - window->HiddenFrames = 1; - if (flags & ImGuiWindowFlags_AlwaysAutoResize) - { - if (!window_size_set_by_api) - window->Size = window->SizeFull = ImVec2(0.f, 0.f); - window->SizeContents = ImVec2(0.f, 0.f); - } - } - - // Lock window padding so that altering the ShowBorders flag for children doesn't have side-effects. - window->WindowPadding = ((flags & ImGuiWindowFlags_ChildWindow) && !(flags & (ImGuiWindowFlags_AlwaysUseWindowPadding | ImGuiWindowFlags_ShowBorders | ImGuiWindowFlags_ComboBox | ImGuiWindowFlags_Popup))) ? ImVec2(0,0) : style.WindowPadding; - - // Calculate auto-fit size - ImVec2 size_auto_fit; - if ((flags & ImGuiWindowFlags_Tooltip) != 0) - { - // Tooltip always resize. We keep the spacing symmetric on both axises for aesthetic purpose. - size_auto_fit = window->SizeContents + window->WindowPadding - ImVec2(0.0f, style.ItemSpacing.y); - } - else - { - size_auto_fit = ImClamp(window->SizeContents + window->WindowPadding, style.WindowMinSize, ImMax(style.WindowMinSize, g.IO.DisplaySize - g.Style.DisplaySafeAreaPadding)); - - // Handling case of auto fit window not fitting in screen on one axis, we are growing auto fit size on the other axis to compensate for expected scrollbar. FIXME: Might turn bigger than DisplaySize-WindowPadding. - if (size_auto_fit.x < window->SizeContents.x && !(flags & ImGuiWindowFlags_NoScrollbar) && (flags & ImGuiWindowFlags_HorizontalScrollbar)) - size_auto_fit.y += style.ScrollbarSize; - if (size_auto_fit.y < window->SizeContents.y && !(flags & ImGuiWindowFlags_NoScrollbar)) - size_auto_fit.x += style.ScrollbarSize; - size_auto_fit.y = ImMax(size_auto_fit.y - style.ItemSpacing.y, 0.0f); - } - - // Handle automatic resize - if (window->Collapsed) - { - // We still process initial auto-fit on collapsed windows to get a window width, - // But otherwise we don't honor ImGuiWindowFlags_AlwaysAutoResize when collapsed. - if (window->AutoFitFramesX > 0) - window->SizeFull.x = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.x, size_auto_fit.x) : size_auto_fit.x; - if (window->AutoFitFramesY > 0) - window->SizeFull.y = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.y, size_auto_fit.y) : size_auto_fit.y; - } - else - { - if ((flags & ImGuiWindowFlags_AlwaysAutoResize) && !window_size_set_by_api) - { - window->SizeFull = size_auto_fit; - } - else if ((window->AutoFitFramesX > 0 || window->AutoFitFramesY > 0) && !window_size_set_by_api) - { - // Auto-fit only grows during the first few frames - if (window->AutoFitFramesX > 0) - window->SizeFull.x = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.x, size_auto_fit.x) : size_auto_fit.x; - if (window->AutoFitFramesY > 0) - window->SizeFull.y = window->AutoFitOnlyGrows ? ImMax(window->SizeFull.y, size_auto_fit.y) : size_auto_fit.y; - if (!(flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - } - } - - // Apply minimum/maximum window size constraints and final size - ApplySizeFullWithConstraint(window, window->SizeFull); - window->Size = window->Collapsed ? window->TitleBarRect().GetSize() : window->SizeFull; - - // POSITION - - // Position child window - if (flags & ImGuiWindowFlags_ChildWindow) - { - window->IndexWithinParent = parent_window->DC.ChildWindows.Size; - parent_window->DC.ChildWindows.push_back(window); - } - if ((flags & ImGuiWindowFlags_ChildWindow) && !(flags & ImGuiWindowFlags_Popup)) - { - window->Pos = window->PosFloat = parent_window->DC.CursorPos; - window->Size = window->SizeFull = size_on_first_use; // NB: argument name 'size_on_first_use' misleading here, it's really just 'size' as provided by user passed via BeginChild()->Begin(). - } - - bool window_pos_center = false; - window_pos_center |= (window->SetWindowPosCenterWanted && window->HiddenFrames == 0); - window_pos_center |= ((flags & ImGuiWindowFlags_Modal) && !window_pos_set_by_api && window_appearing_after_being_hidden); - if (window_pos_center) - { - // Center (any sort of window) - SetWindowPos(ImMax(style.DisplaySafeAreaPadding, fullscreen_rect.GetCenter() - window->SizeFull * 0.5f)); - } - else if (flags & ImGuiWindowFlags_ChildMenu) - { - IM_ASSERT(window_pos_set_by_api); - ImRect rect_to_avoid; - if (parent_window->DC.MenuBarAppending) - rect_to_avoid = ImRect(-FLT_MAX, parent_window->Pos.y + parent_window->TitleBarHeight(), FLT_MAX, parent_window->Pos.y + parent_window->TitleBarHeight() + parent_window->MenuBarHeight()); - else - rect_to_avoid = ImRect(parent_window->Pos.x + style.ItemSpacing.x, -FLT_MAX, parent_window->Pos.x + parent_window->Size.x - style.ItemSpacing.x - parent_window->ScrollbarSizes.x, FLT_MAX); // We want some overlap to convey the relative depth of each popup (here hard-coded to 4) - window->PosFloat = FindBestPopupWindowPos(window->PosFloat, window->Size, &window->AutoPosLastDirection, rect_to_avoid); - } - else if ((flags & ImGuiWindowFlags_Popup) != 0 && !window_pos_set_by_api && window_appearing_after_being_hidden) - { - ImRect rect_to_avoid(window->PosFloat.x - 1, window->PosFloat.y - 1, window->PosFloat.x + 1, window->PosFloat.y + 1); - window->PosFloat = FindBestPopupWindowPos(window->PosFloat, window->Size, &window->AutoPosLastDirection, rect_to_avoid); - } - - // Position tooltip (always follows mouse) - if ((flags & ImGuiWindowFlags_Tooltip) != 0 && !window_pos_set_by_api) - { - ImRect rect_to_avoid(g.IO.MousePos.x - 16, g.IO.MousePos.y - 8, g.IO.MousePos.x + 24, g.IO.MousePos.y + 24); // FIXME: Completely hard-coded. Perhaps center on cursor hit-point instead? - window->PosFloat = FindBestPopupWindowPos(g.IO.MousePos, window->Size, &window->AutoPosLastDirection, rect_to_avoid); - if (window->AutoPosLastDirection == -1) - window->PosFloat = g.IO.MousePos + ImVec2(2,2); // If there's not enough room, for tooltip we prefer avoiding the cursor at all cost even if it means that part of the tooltip won't be visible. - } - - // Clamp position so it stays visible - if (!(flags & ImGuiWindowFlags_ChildWindow) && !(flags & ImGuiWindowFlags_Tooltip)) - { - if (!window_pos_set_by_api && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0 && g.IO.DisplaySize.x > 0.0f && g.IO.DisplaySize.y > 0.0f) // Ignore zero-sized display explicitly to avoid losing positions if a window manager reports zero-sized window when initializing or minimizing. - { - ImVec2 padding = ImMax(style.DisplayWindowPadding, style.DisplaySafeAreaPadding); - window->PosFloat = ImMax(window->PosFloat + window->Size, padding) - window->Size; - window->PosFloat = ImMin(window->PosFloat, g.IO.DisplaySize - padding); - } - } - window->Pos = ImVec2((float)(int)window->PosFloat.x, (float)(int)window->PosFloat.y); - - // Default item width. Make it proportional to window size if window manually resizes - if (window->Size.x > 0.0f && !(flags & ImGuiWindowFlags_Tooltip) && !(flags & ImGuiWindowFlags_AlwaysAutoResize)) - window->ItemWidthDefault = (float)(int)(window->Size.x * 0.65f); - else - window->ItemWidthDefault = (float)(int)(g.FontSize * 16.0f); - - // Prepare for focus requests - window->FocusIdxAllRequestCurrent = (window->FocusIdxAllRequestNext == INT_MAX || window->FocusIdxAllCounter == -1) ? INT_MAX : (window->FocusIdxAllRequestNext + (window->FocusIdxAllCounter+1)) % (window->FocusIdxAllCounter+1); - window->FocusIdxTabRequestCurrent = (window->FocusIdxTabRequestNext == INT_MAX || window->FocusIdxTabCounter == -1) ? INT_MAX : (window->FocusIdxTabRequestNext + (window->FocusIdxTabCounter+1)) % (window->FocusIdxTabCounter+1); - window->FocusIdxAllCounter = window->FocusIdxTabCounter = -1; - window->FocusIdxAllRequestNext = window->FocusIdxTabRequestNext = INT_MAX; - - // Apply scrolling - if (window->ScrollTarget.x < FLT_MAX) - { - window->Scroll.x = window->ScrollTarget.x; - window->ScrollTarget.x = FLT_MAX; - } - if (window->ScrollTarget.y < FLT_MAX) - { - float center_ratio = window->ScrollTargetCenterRatio.y; - window->Scroll.y = window->ScrollTarget.y - ((1.0f - center_ratio) * (window->TitleBarHeight() + window->MenuBarHeight())) - (center_ratio * window->SizeFull.y); - window->ScrollTarget.y = FLT_MAX; - } - window->Scroll = ImMax(window->Scroll, ImVec2(0.0f, 0.0f)); - if (!window->Collapsed && !window->SkipItems) - window->Scroll = ImMin(window->Scroll, ImMax(ImVec2(0.0f, 0.0f), window->SizeContents - window->SizeFull + window->ScrollbarSizes)); - - // Modal window darkens what is behind them - if ((flags & ImGuiWindowFlags_Modal) != 0 && window == GetFrontMostModalRootWindow()) - window->DrawList->AddRectFilled(fullscreen_rect.Min, fullscreen_rect.Max, GetColorU32(ImGuiCol_ModalWindowDarkening, g.ModalWindowDarkeningRatio)); - - // Draw window + handle manual resize - ImRect title_bar_rect = window->TitleBarRect(); - const float window_rounding = (flags & ImGuiWindowFlags_ChildWindow) ? style.ChildWindowRounding : style.WindowRounding; - if (window->Collapsed) - { - // Draw title bar only - RenderFrame(title_bar_rect.GetTL(), title_bar_rect.GetBR(), GetColorU32(ImGuiCol_TitleBgCollapsed), true, window_rounding); - } - else - { - ImU32 resize_col = 0; - const float resize_corner_size = ImMax(g.FontSize * 1.35f, window_rounding + 1.0f + g.FontSize * 0.2f); - if (!(flags & ImGuiWindowFlags_AlwaysAutoResize) && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0 && !(flags & ImGuiWindowFlags_NoResize)) - { - // Manual resize - const ImVec2 br = window->Rect().GetBR(); - const ImRect resize_rect(br - ImVec2(resize_corner_size * 0.75f, resize_corner_size * 0.75f), br); - const ImGuiID resize_id = window->GetID("#RESIZE"); - bool hovered, held; - ButtonBehavior(resize_rect, resize_id, &hovered, &held, ImGuiButtonFlags_FlattenChilds); - resize_col = GetColorU32(held ? ImGuiCol_ResizeGripActive : hovered ? ImGuiCol_ResizeGripHovered : ImGuiCol_ResizeGrip); - - if (hovered || held) - g.MouseCursor = ImGuiMouseCursor_ResizeNWSE; - - if (g.HoveredWindow == window && held && g.IO.MouseDoubleClicked[0]) - { - // Manual auto-fit when double-clicking - ApplySizeFullWithConstraint(window, size_auto_fit); - if (!(flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - SetActiveID(0); - } - else if (held) - { - // We don't use an incremental MouseDelta but rather compute an absolute target size based on mouse position - ApplySizeFullWithConstraint(window, (g.IO.MousePos - g.ActiveIdClickOffset + resize_rect.GetSize()) - window->Pos); - if (!(flags & ImGuiWindowFlags_NoSavedSettings)) - MarkSettingsDirty(); - } - - window->Size = window->SizeFull; - title_bar_rect = window->TitleBarRect(); - } - - // Scrollbars - window->ScrollbarY = (flags & ImGuiWindowFlags_AlwaysVerticalScrollbar) || ((window->SizeContents.y > window->Size.y + style.ItemSpacing.y) && !(flags & ImGuiWindowFlags_NoScrollbar)); - window->ScrollbarX = (flags & ImGuiWindowFlags_AlwaysHorizontalScrollbar) || ((window->SizeContents.x > window->Size.x - (window->ScrollbarY ? style.ScrollbarSize : 0.0f) - window->WindowPadding.x) && !(flags & ImGuiWindowFlags_NoScrollbar) && (flags & ImGuiWindowFlags_HorizontalScrollbar)); - window->ScrollbarSizes = ImVec2(window->ScrollbarY ? style.ScrollbarSize : 0.0f, window->ScrollbarX ? style.ScrollbarSize : 0.0f); - window->BorderSize = (flags & ImGuiWindowFlags_ShowBorders) ? 1.0f : 0.0f; - - // Window background - // Default alpha - ImGuiCol bg_color_idx = ImGuiCol_WindowBg; - if ((flags & ImGuiWindowFlags_ComboBox) != 0) - bg_color_idx = ImGuiCol_ComboBg; - else if ((flags & ImGuiWindowFlags_Tooltip) != 0 || (flags & ImGuiWindowFlags_Popup) != 0) - bg_color_idx = ImGuiCol_PopupBg; - else if ((flags & ImGuiWindowFlags_ChildWindow) != 0) - bg_color_idx = ImGuiCol_ChildWindowBg; - ImVec4 bg_color = style.Colors[bg_color_idx]; - if (bg_alpha >= 0.0f) - bg_color.w = bg_alpha; - bg_color.w *= style.Alpha; - if (bg_color.w > 0.0f) - window->DrawList->AddRectFilled(window->Pos+ImVec2(0,window->TitleBarHeight()), window->Pos+window->Size, ColorConvertFloat4ToU32(bg_color), window_rounding, (flags & ImGuiWindowFlags_NoTitleBar) ? 15 : 4|8); - - // Title bar - if (!(flags & ImGuiWindowFlags_NoTitleBar)) - window->DrawList->AddRectFilled(title_bar_rect.GetTL(), title_bar_rect.GetBR(), GetColorU32((g.FocusedWindow && window->RootNonPopupWindow == g.FocusedWindow->RootNonPopupWindow) ? ImGuiCol_TitleBgActive : ImGuiCol_TitleBg), window_rounding, 1|2); - - // Menu bar - if (flags & ImGuiWindowFlags_MenuBar) - { - ImRect menu_bar_rect = window->MenuBarRect(); - window->DrawList->AddRectFilled(menu_bar_rect.GetTL(), menu_bar_rect.GetBR(), GetColorU32(ImGuiCol_MenuBarBg), (flags & ImGuiWindowFlags_NoTitleBar) ? window_rounding : 0.0f, 1|2); - if (flags & ImGuiWindowFlags_ShowBorders) - window->DrawList->AddLine(menu_bar_rect.GetBL()-ImVec2(0,0), menu_bar_rect.GetBR()-ImVec2(0,0), GetColorU32(ImGuiCol_Border)); - } - - // Scrollbars - if (window->ScrollbarX) - Scrollbar(window, true); - if (window->ScrollbarY) - Scrollbar(window, false); - - // Render resize grip - // (after the input handling so we don't have a frame of latency) - if (!(flags & ImGuiWindowFlags_NoResize)) - { - const ImVec2 br = window->Rect().GetBR(); - window->DrawList->PathLineTo(br + ImVec2(-resize_corner_size, -window->BorderSize)); - window->DrawList->PathLineTo(br + ImVec2(-window->BorderSize, -resize_corner_size)); - window->DrawList->PathArcToFast(ImVec2(br.x - window_rounding - window->BorderSize, br.y - window_rounding - window->BorderSize), window_rounding, 0, 3); - window->DrawList->PathFill(resize_col); - } - - // Borders - if (flags & ImGuiWindowFlags_ShowBorders) - { - window->DrawList->AddRect(window->Pos+ImVec2(1,1), window->Pos+window->Size+ImVec2(1,1), GetColorU32(ImGuiCol_BorderShadow), window_rounding); - window->DrawList->AddRect(window->Pos, window->Pos+window->Size, GetColorU32(ImGuiCol_Border), window_rounding); - if (!(flags & ImGuiWindowFlags_NoTitleBar)) - window->DrawList->AddLine(title_bar_rect.GetBL()+ImVec2(1,0), title_bar_rect.GetBR()-ImVec2(1,0), GetColorU32(ImGuiCol_Border)); - } - } - - // Update ContentsRegionMax. All the variable it depends on are set above in this function. - window->ContentsRegionRect.Min.x = -window->Scroll.x + window->WindowPadding.x; - window->ContentsRegionRect.Min.y = -window->Scroll.y + window->WindowPadding.y + window->TitleBarHeight() + window->MenuBarHeight(); - window->ContentsRegionRect.Max.x = -window->Scroll.x - window->WindowPadding.x + (window->SizeContentsExplicit.x != 0.0f ? window->SizeContentsExplicit.x : (window->Size.x - window->ScrollbarSizes.x)); - window->ContentsRegionRect.Max.y = -window->Scroll.y - window->WindowPadding.y + (window->SizeContentsExplicit.y != 0.0f ? window->SizeContentsExplicit.y : (window->Size.y - window->ScrollbarSizes.y)); - - // Setup drawing context - window->DC.IndentX = 0.0f + window->WindowPadding.x - window->Scroll.x; - window->DC.GroupOffsetX = 0.0f; - window->DC.ColumnsOffsetX = 0.0f; - window->DC.CursorStartPos = window->Pos + ImVec2(window->DC.IndentX + window->DC.ColumnsOffsetX, window->TitleBarHeight() + window->MenuBarHeight() + window->WindowPadding.y - window->Scroll.y); - window->DC.CursorPos = window->DC.CursorStartPos; - window->DC.CursorPosPrevLine = window->DC.CursorPos; - window->DC.CursorMaxPos = window->DC.CursorStartPos; - window->DC.CurrentLineHeight = window->DC.PrevLineHeight = 0.0f; - window->DC.CurrentLineTextBaseOffset = window->DC.PrevLineTextBaseOffset = 0.0f; - window->DC.MenuBarAppending = false; - window->DC.MenuBarOffsetX = ImMax(window->WindowPadding.x, style.ItemSpacing.x); - window->DC.LogLinePosY = window->DC.CursorPos.y - 9999.0f; - window->DC.ChildWindows.resize(0); - window->DC.LayoutType = ImGuiLayoutType_Vertical; - window->DC.ItemWidth = window->ItemWidthDefault; - window->DC.TextWrapPos = -1.0f; // disabled - window->DC.AllowKeyboardFocus = true; - window->DC.ButtonRepeat = false; - window->DC.ItemWidthStack.resize(0); - window->DC.AllowKeyboardFocusStack.resize(0); - window->DC.ButtonRepeatStack.resize(0); - window->DC.TextWrapPosStack.resize(0); - window->DC.ColumnsCurrent = 0; - window->DC.ColumnsCount = 1; - window->DC.ColumnsStartPosY = window->DC.CursorPos.y; - window->DC.ColumnsCellMinY = window->DC.ColumnsCellMaxY = window->DC.ColumnsStartPosY; - window->DC.TreeDepth = 0; - window->DC.StateStorage = &window->StateStorage; - window->DC.GroupStack.resize(0); - window->DC.ColorEditMode = ImGuiColorEditMode_UserSelect; - window->MenuColumns.Update(3, style.ItemSpacing.x, !window_was_active); - - if (window->AutoFitFramesX > 0) - window->AutoFitFramesX--; - if (window->AutoFitFramesY > 0) - window->AutoFitFramesY--; - - // New windows appears in front (we need to do that AFTER setting DC.CursorStartPos so our initial navigation reference rectangle can start around there) - if (!window_was_active && !(flags & ImGuiWindowFlags_NoFocusOnAppearing)) - if (!(flags & (ImGuiWindowFlags_ChildWindow|ImGuiWindowFlags_Tooltip)) || (flags & ImGuiWindowFlags_Popup)) - FocusWindow(window); - - // Title bar - if (!(flags & ImGuiWindowFlags_NoTitleBar)) - { - if (p_open != NULL) - { - const float pad = 2.0f; - const float rad = (window->TitleBarHeight() - pad*2.0f) * 0.5f; - if (CloseButton(window->GetID("#CLOSE"), window->Rect().GetTR() + ImVec2(-pad - rad, pad + rad), rad)) - *p_open = false; - } - - const ImVec2 text_size = CalcTextSize(name, NULL, true); - if (!(flags & ImGuiWindowFlags_NoCollapse)) - RenderCollapseTriangle(window->Pos + style.FramePadding, !window->Collapsed, 1.0f, true); - - ImVec2 text_min = window->Pos; - ImVec2 text_max = window->Pos + ImVec2(window->Size.x, style.FramePadding.y*2 + text_size.y); - ImRect clip_rect; - clip_rect.Max = ImVec2(window->Pos.x + window->Size.x - (p_open ? title_bar_rect.GetHeight() - 3 : style.FramePadding.x), text_max.y); // Match the size of CloseWindowButton() - float pad_left = (flags & ImGuiWindowFlags_NoCollapse) == 0 ? (style.FramePadding.x + g.FontSize + style.ItemInnerSpacing.x) : 0.0f; - float pad_right = (p_open != NULL) ? (style.FramePadding.x + g.FontSize + style.ItemInnerSpacing.x) : 0.0f; - if (style.WindowTitleAlign.x > 0.0f) pad_right = ImLerp(pad_right, pad_left, style.WindowTitleAlign.x); - text_min.x += pad_left; - text_max.x -= pad_right; - clip_rect.Min = ImVec2(text_min.x, window->Pos.y); - RenderTextClipped(text_min, text_max, name, NULL, &text_size, style.WindowTitleAlign, &clip_rect); - } - - // Save clipped aabb so we can access it in constant-time in FindHoveredWindow() - window->WindowRectClipped = window->Rect(); - window->WindowRectClipped.Clip(window->ClipRect); - - // Pressing CTRL+C while holding on a window copy its content to the clipboard - // This works but 1. doesn't handle multiple Begin/End pairs, 2. recursing into another Begin/End pair - so we need to work that out and add better logging scope. - // Maybe we can support CTRL+C on every element? - /* - if (g.ActiveId == move_id) - if (g.IO.KeyCtrl && IsKeyPressedMap(ImGuiKey_C)) - ImGui::LogToClipboard(); - */ - } - - // Inner clipping rectangle - // We set this up after processing the resize grip so that our clip rectangle doesn't lag by a frame - // Note that if our window is collapsed we will end up with a null clipping rectangle which is the correct behavior. - const ImRect title_bar_rect = window->TitleBarRect(); - const float border_size = window->BorderSize; - ImRect clip_rect; // Force round to ensure that e.g. (int)(max.x-min.x) in user's render code produce correct result. - clip_rect.Min.x = ImFloor(0.5f + title_bar_rect.Min.x + ImMax(border_size, ImFloor(window->WindowPadding.x*0.5f))); - clip_rect.Min.y = ImFloor(0.5f + title_bar_rect.Max.y + window->MenuBarHeight() + border_size); - clip_rect.Max.x = ImFloor(0.5f + window->Pos.x + window->Size.x - window->ScrollbarSizes.x - ImMax(border_size, ImFloor(window->WindowPadding.x*0.5f))); - clip_rect.Max.y = ImFloor(0.5f + window->Pos.y + window->Size.y - window->ScrollbarSizes.y - border_size); - PushClipRect(clip_rect.Min, clip_rect.Max, true); - - // Clear 'accessed' flag last thing - if (first_begin_of_the_frame) - window->Accessed = false; - window->BeginCount++; - g.SetNextWindowSizeConstraint = false; - - // Child window can be out of sight and have "negative" clip windows. - // Mark them as collapsed so commands are skipped earlier (we can't manually collapse because they have no title bar). - if (flags & ImGuiWindowFlags_ChildWindow) - { - IM_ASSERT((flags & ImGuiWindowFlags_NoTitleBar) != 0); - window->Collapsed = parent_window && parent_window->Collapsed; - - if (!(flags & ImGuiWindowFlags_AlwaysAutoResize) && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0) - window->Collapsed |= (window->WindowRectClipped.Min.x >= window->WindowRectClipped.Max.x || window->WindowRectClipped.Min.y >= window->WindowRectClipped.Max.y); - - // We also hide the window from rendering because we've already added its border to the command list. - // (we could perform the check earlier in the function but it is simpler at this point) - if (window->Collapsed) - window->Active = false; - } - if (style.Alpha <= 0.0f) - window->Active = false; - - // Return false if we don't intend to display anything to allow user to perform an early out optimization - window->SkipItems = (window->Collapsed || !window->Active) && window->AutoFitFramesX <= 0 && window->AutoFitFramesY <= 0; - return !window->SkipItems; -} - -void ImGui::End() -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - - Columns(1, "#CloseColumns"); - PopClipRect(); // inner window clip rectangle - - // Stop logging - if (!(window->Flags & ImGuiWindowFlags_ChildWindow)) // FIXME: add more options for scope of logging - LogFinish(); - - // Pop - // NB: we don't clear 'window->RootWindow'. The pointer is allowed to live until the next call to Begin(). - g.CurrentWindowStack.pop_back(); - if (window->Flags & ImGuiWindowFlags_Popup) - g.CurrentPopupStack.pop_back(); - CheckStacksSize(window, false); - SetCurrentWindow(g.CurrentWindowStack.empty() ? NULL : g.CurrentWindowStack.back()); -} - -// Vertical scrollbar -// The entire piece of code below is rather confusing because: -// - We handle absolute seeking (when first clicking outside the grab) and relative manipulation (afterward or when clicking inside the grab) -// - We store values as normalized ratio and in a form that allows the window content to change while we are holding on a scrollbar -// - We handle both horizontal and vertical scrollbars, which makes the terminology not ideal. -static void Scrollbar(ImGuiWindow* window, bool horizontal) -{ - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(horizontal ? "#SCROLLX" : "#SCROLLY"); - - // Render background - bool other_scrollbar = (horizontal ? window->ScrollbarY : window->ScrollbarX); - float other_scrollbar_size_w = other_scrollbar ? style.ScrollbarSize : 0.0f; - const ImRect window_rect = window->Rect(); - const float border_size = window->BorderSize; - ImRect bb = horizontal - ? ImRect(window->Pos.x + border_size, window_rect.Max.y - style.ScrollbarSize, window_rect.Max.x - other_scrollbar_size_w - border_size, window_rect.Max.y - border_size) - : ImRect(window_rect.Max.x - style.ScrollbarSize, window->Pos.y + border_size, window_rect.Max.x - border_size, window_rect.Max.y - other_scrollbar_size_w - border_size); - if (!horizontal) - bb.Min.y += window->TitleBarHeight() + ((window->Flags & ImGuiWindowFlags_MenuBar) ? window->MenuBarHeight() : 0.0f); - - float window_rounding = (window->Flags & ImGuiWindowFlags_ChildWindow) ? style.ChildWindowRounding : style.WindowRounding; - int window_rounding_corners; - if (horizontal) - window_rounding_corners = 8 | (other_scrollbar ? 0 : 4); - else - window_rounding_corners = (((window->Flags & ImGuiWindowFlags_NoTitleBar) && !(window->Flags & ImGuiWindowFlags_MenuBar)) ? 2 : 0) | (other_scrollbar ? 0 : 4); - window->DrawList->AddRectFilled(bb.Min, bb.Max, ImGui::GetColorU32(ImGuiCol_ScrollbarBg), window_rounding, window_rounding_corners); - bb.Reduce(ImVec2(ImClamp((float)(int)((bb.Max.x - bb.Min.x - 2.0f) * 0.5f), 0.0f, 3.0f), ImClamp((float)(int)((bb.Max.y - bb.Min.y - 2.0f) * 0.5f), 0.0f, 3.0f))); - - // V denote the main axis of the scrollbar - float scrollbar_size_v = horizontal ? bb.GetWidth() : bb.GetHeight(); - float scroll_v = horizontal ? window->Scroll.x : window->Scroll.y; - float win_size_avail_v = (horizontal ? window->Size.x : window->Size.y) - other_scrollbar_size_w; - float win_size_contents_v = horizontal ? window->SizeContents.x : window->SizeContents.y; - - // The grabable box size generally represent the amount visible (vs the total scrollable amount) - // But we maintain a minimum size in pixel to allow for the user to still aim inside. - const float grab_h_pixels = ImMin(ImMax(scrollbar_size_v * ImSaturate(win_size_avail_v / ImMax(win_size_contents_v, win_size_avail_v)), style.GrabMinSize), scrollbar_size_v); - const float grab_h_norm = grab_h_pixels / scrollbar_size_v; - - // Handle input right away. None of the code of Begin() is relying on scrolling position before calling Scrollbar(). - bool held = false; - bool hovered = false; - const bool previously_held = (g.ActiveId == id); - ImGui::ButtonBehavior(bb, id, &hovered, &held); - - float scroll_max = ImMax(1.0f, win_size_contents_v - win_size_avail_v); - float scroll_ratio = ImSaturate(scroll_v / scroll_max); - float grab_v_norm = scroll_ratio * (scrollbar_size_v - grab_h_pixels) / scrollbar_size_v; - if (held && grab_h_norm < 1.0f) - { - float scrollbar_pos_v = horizontal ? bb.Min.x : bb.Min.y; - float mouse_pos_v = horizontal ? g.IO.MousePos.x : g.IO.MousePos.y; - float* click_delta_to_grab_center_v = horizontal ? &g.ScrollbarClickDeltaToGrabCenter.x : &g.ScrollbarClickDeltaToGrabCenter.y; - - // Click position in scrollbar normalized space (0.0f->1.0f) - const float clicked_v_norm = ImSaturate((mouse_pos_v - scrollbar_pos_v) / scrollbar_size_v); - ImGui::SetHoveredID(id); - - bool seek_absolute = false; - if (!previously_held) - { - // On initial click calculate the distance between mouse and the center of the grab - if (clicked_v_norm >= grab_v_norm && clicked_v_norm <= grab_v_norm + grab_h_norm) - { - *click_delta_to_grab_center_v = clicked_v_norm - grab_v_norm - grab_h_norm*0.5f; - } - else - { - seek_absolute = true; - *click_delta_to_grab_center_v = 0.0f; - } - } - - // Apply scroll - // It is ok to modify Scroll here because we are being called in Begin() after the calculation of SizeContents and before setting up our starting position - const float scroll_v_norm = ImSaturate((clicked_v_norm - *click_delta_to_grab_center_v - grab_h_norm*0.5f) / (1.0f - grab_h_norm)); - scroll_v = (float)(int)(0.5f + scroll_v_norm * scroll_max);//(win_size_contents_v - win_size_v)); - if (horizontal) - window->Scroll.x = scroll_v; - else - window->Scroll.y = scroll_v; - - // Update values for rendering - scroll_ratio = ImSaturate(scroll_v / scroll_max); - grab_v_norm = scroll_ratio * (scrollbar_size_v - grab_h_pixels) / scrollbar_size_v; - - // Update distance to grab now that we have seeked and saturated - if (seek_absolute) - *click_delta_to_grab_center_v = clicked_v_norm - grab_v_norm - grab_h_norm*0.5f; - } - - // Render - const ImU32 grab_col = ImGui::GetColorU32(held ? ImGuiCol_ScrollbarGrabActive : hovered ? ImGuiCol_ScrollbarGrabHovered : ImGuiCol_ScrollbarGrab); - if (horizontal) - window->DrawList->AddRectFilled(ImVec2(ImLerp(bb.Min.x, bb.Max.x, grab_v_norm), bb.Min.y), ImVec2(ImLerp(bb.Min.x, bb.Max.x, grab_v_norm) + grab_h_pixels, bb.Max.y), grab_col, style.ScrollbarRounding); - else - window->DrawList->AddRectFilled(ImVec2(bb.Min.x, ImLerp(bb.Min.y, bb.Max.y, grab_v_norm)), ImVec2(bb.Max.x, ImLerp(bb.Min.y, bb.Max.y, grab_v_norm) + grab_h_pixels), grab_col, style.ScrollbarRounding); -} - -// Moving window to front of display (which happens to be back of our sorted list) -void ImGui::FocusWindow(ImGuiWindow* window) -{ - ImGuiContext& g = *GImGui; - - // Always mark the window we passed as focused. This is used for keyboard interactions such as tabbing. - g.FocusedWindow = window; - - // Passing NULL allow to disable keyboard focus - if (!window) - return; - - // And move its root window to the top of the pile - if (window->RootWindow) - window = window->RootWindow; - - // Steal focus on active widgets - if (window->Flags & ImGuiWindowFlags_Popup) // FIXME: This statement should be unnecessary. Need further testing before removing it.. - if (g.ActiveId != 0 && g.ActiveIdWindow && g.ActiveIdWindow->RootWindow != window) - SetActiveID(0); - - // Bring to front - if ((window->Flags & ImGuiWindowFlags_NoBringToFrontOnFocus) || g.Windows.back() == window) - return; - for (int i = 0; i < g.Windows.Size; i++) - if (g.Windows[i] == window) - { - g.Windows.erase(g.Windows.begin() + i); - break; - } - g.Windows.push_back(window); -} - -void ImGui::PushItemWidth(float item_width) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ItemWidth = (item_width == 0.0f ? window->ItemWidthDefault : item_width); - window->DC.ItemWidthStack.push_back(window->DC.ItemWidth); -} - -static void PushMultiItemsWidths(int components, float w_full) -{ - ImGuiWindow* window = ImGui::GetCurrentWindow(); - const ImGuiStyle& style = GImGui->Style; - if (w_full <= 0.0f) - w_full = ImGui::CalcItemWidth(); - const float w_item_one = ImMax(1.0f, (float)(int)((w_full - (style.ItemInnerSpacing.x) * (components-1)) / (float)components)); - const float w_item_last = ImMax(1.0f, (float)(int)(w_full - (w_item_one + style.ItemInnerSpacing.x) * (components-1))); - window->DC.ItemWidthStack.push_back(w_item_last); - for (int i = 0; i < components-1; i++) - window->DC.ItemWidthStack.push_back(w_item_one); - window->DC.ItemWidth = window->DC.ItemWidthStack.back(); -} - -void ImGui::PopItemWidth() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ItemWidthStack.pop_back(); - window->DC.ItemWidth = window->DC.ItemWidthStack.empty() ? window->ItemWidthDefault : window->DC.ItemWidthStack.back(); -} - -float ImGui::CalcItemWidth() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - float w = window->DC.ItemWidth; - if (w < 0.0f) - { - // Align to a right-side limit. We include 1 frame padding in the calculation because this is how the width is always used (we add 2 frame padding to it), but we could move that responsibility to the widget as well. - float width_to_right_edge = GetContentRegionAvail().x; - w = ImMax(1.0f, width_to_right_edge + w); - } - w = (float)(int)w; - return w; -} - -static void SetCurrentFont(ImFont* font) -{ - ImGuiContext& g = *GImGui; - IM_ASSERT(font && font->IsLoaded()); // Font Atlas not created. Did you call io.Fonts->GetTexDataAsRGBA32 / GetTexDataAsAlpha8 ? - IM_ASSERT(font->Scale > 0.0f); - g.Font = font; - g.FontBaseSize = g.IO.FontGlobalScale * g.Font->FontSize * g.Font->Scale; - g.FontSize = g.CurrentWindow ? g.CurrentWindow->CalcFontSize() : 0.0f; - g.FontTexUvWhitePixel = g.Font->ContainerAtlas->TexUvWhitePixel; -} - -void ImGui::PushFont(ImFont* font) -{ - ImGuiContext& g = *GImGui; - if (!font) - font = g.IO.Fonts->Fonts[0]; - SetCurrentFont(font); - g.FontStack.push_back(font); - g.CurrentWindow->DrawList->PushTextureID(font->ContainerAtlas->TexID); -} - -void ImGui::PopFont() -{ - ImGuiContext& g = *GImGui; - g.CurrentWindow->DrawList->PopTextureID(); - g.FontStack.pop_back(); - SetCurrentFont(g.FontStack.empty() ? g.IO.Fonts->Fonts[0] : g.FontStack.back()); -} - -void ImGui::PushAllowKeyboardFocus(bool allow_keyboard_focus) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.AllowKeyboardFocus = allow_keyboard_focus; - window->DC.AllowKeyboardFocusStack.push_back(allow_keyboard_focus); -} - -void ImGui::PopAllowKeyboardFocus() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.AllowKeyboardFocusStack.pop_back(); - window->DC.AllowKeyboardFocus = window->DC.AllowKeyboardFocusStack.empty() ? true : window->DC.AllowKeyboardFocusStack.back(); -} - -void ImGui::PushButtonRepeat(bool repeat) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ButtonRepeat = repeat; - window->DC.ButtonRepeatStack.push_back(repeat); -} - -void ImGui::PopButtonRepeat() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ButtonRepeatStack.pop_back(); - window->DC.ButtonRepeat = window->DC.ButtonRepeatStack.empty() ? false : window->DC.ButtonRepeatStack.back(); -} - -void ImGui::PushTextWrapPos(float wrap_pos_x) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.TextWrapPos = wrap_pos_x; - window->DC.TextWrapPosStack.push_back(wrap_pos_x); -} - -void ImGui::PopTextWrapPos() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.TextWrapPosStack.pop_back(); - window->DC.TextWrapPos = window->DC.TextWrapPosStack.empty() ? -1.0f : window->DC.TextWrapPosStack.back(); -} - -void ImGui::PushStyleColor(ImGuiCol idx, const ImVec4& col) -{ - ImGuiContext& g = *GImGui; - ImGuiColMod backup; - backup.Col = idx; - backup.BackupValue = g.Style.Colors[idx]; - g.ColorModifiers.push_back(backup); - g.Style.Colors[idx] = col; -} - -void ImGui::PopStyleColor(int count) -{ - ImGuiContext& g = *GImGui; - while (count > 0) - { - ImGuiColMod& backup = g.ColorModifiers.back(); - g.Style.Colors[backup.Col] = backup.BackupValue; - g.ColorModifiers.pop_back(); - count--; - } -} - -struct ImGuiStyleVarInfo -{ - ImGuiDataType Type; - ImU32 Offset; - void* GetVarPtr() const { return (void*)((unsigned char*)&GImGui->Style + Offset); } -}; - -static const ImGuiStyleVarInfo GStyleVarInfo[ImGuiStyleVar_Count_] = -{ - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, Alpha) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowPadding) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowRounding) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, WindowMinSize) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, ChildWindowRounding) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, FramePadding) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, FrameRounding) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, ItemSpacing) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, ItemInnerSpacing) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, IndentSpacing) }, - { ImGuiDataType_Float, (ImU32)IM_OFFSETOF(ImGuiStyle, GrabMinSize) }, - { ImGuiDataType_Float2, (ImU32)IM_OFFSETOF(ImGuiStyle, ButtonTextAlign) }, -}; - -static const ImGuiStyleVarInfo* GetStyleVarInfo(ImGuiStyleVar idx) -{ - IM_ASSERT(idx >= 0 && idx < ImGuiStyleVar_Count_); - return &GStyleVarInfo[idx]; -} - -void ImGui::PushStyleVar(ImGuiStyleVar idx, float val) -{ - const ImGuiStyleVarInfo* var_info = GetStyleVarInfo(idx); - if (var_info->Type == ImGuiDataType_Float) - { - float* pvar = (float*)var_info->GetVarPtr(); - GImGui->StyleModifiers.push_back(ImGuiStyleMod(idx, *pvar)); - *pvar = val; - return; - } - IM_ASSERT(0); // Called function with wrong-type? Variable is not a float. -} - -void ImGui::PushStyleVar(ImGuiStyleVar idx, const ImVec2& val) -{ - const ImGuiStyleVarInfo* var_info = GetStyleVarInfo(idx); - if (var_info->Type == ImGuiDataType_Float2) - { - ImVec2* pvar = (ImVec2*)var_info->GetVarPtr(); - GImGui->StyleModifiers.push_back(ImGuiStyleMod(idx, *pvar)); - *pvar = val; - return; - } - IM_ASSERT(0); // Called function with wrong-type? Variable is not a ImVec2. -} - -void ImGui::PopStyleVar(int count) -{ - ImGuiContext& g = *GImGui; - while (count > 0) - { - ImGuiStyleMod& backup = g.StyleModifiers.back(); - const ImGuiStyleVarInfo* info = GetStyleVarInfo(backup.VarIdx); - if (info->Type == ImGuiDataType_Float) (*(float*)info->GetVarPtr()) = backup.BackupFloat[0]; - else if (info->Type == ImGuiDataType_Float2) (*(ImVec2*)info->GetVarPtr()) = ImVec2(backup.BackupFloat[0], backup.BackupFloat[1]); - else if (info->Type == ImGuiDataType_Int) (*(int*)info->GetVarPtr()) = backup.BackupInt[0]; - g.StyleModifiers.pop_back(); - count--; - } -} - -const char* ImGui::GetStyleColName(ImGuiCol idx) -{ - // Create switch-case from enum with regexp: ImGuiCol_{.*}, --> case ImGuiCol_\1: return "\1"; - switch (idx) - { - case ImGuiCol_Text: return "Text"; - case ImGuiCol_TextDisabled: return "TextDisabled"; - case ImGuiCol_WindowBg: return "WindowBg"; - case ImGuiCol_ChildWindowBg: return "ChildWindowBg"; - case ImGuiCol_PopupBg: return "PopupBg"; - case ImGuiCol_Border: return "Border"; - case ImGuiCol_BorderShadow: return "BorderShadow"; - case ImGuiCol_FrameBg: return "FrameBg"; - case ImGuiCol_FrameBgHovered: return "FrameBgHovered"; - case ImGuiCol_FrameBgActive: return "FrameBgActive"; - case ImGuiCol_TitleBg: return "TitleBg"; - case ImGuiCol_TitleBgCollapsed: return "TitleBgCollapsed"; - case ImGuiCol_TitleBgActive: return "TitleBgActive"; - case ImGuiCol_MenuBarBg: return "MenuBarBg"; - case ImGuiCol_ScrollbarBg: return "ScrollbarBg"; - case ImGuiCol_ScrollbarGrab: return "ScrollbarGrab"; - case ImGuiCol_ScrollbarGrabHovered: return "ScrollbarGrabHovered"; - case ImGuiCol_ScrollbarGrabActive: return "ScrollbarGrabActive"; - case ImGuiCol_ComboBg: return "ComboBg"; - case ImGuiCol_CheckMark: return "CheckMark"; - case ImGuiCol_SliderGrab: return "SliderGrab"; - case ImGuiCol_SliderGrabActive: return "SliderGrabActive"; - case ImGuiCol_Button: return "Button"; - case ImGuiCol_ButtonHovered: return "ButtonHovered"; - case ImGuiCol_ButtonActive: return "ButtonActive"; - case ImGuiCol_Header: return "Header"; - case ImGuiCol_HeaderHovered: return "HeaderHovered"; - case ImGuiCol_HeaderActive: return "HeaderActive"; - case ImGuiCol_Column: return "Column"; - case ImGuiCol_ColumnHovered: return "ColumnHovered"; - case ImGuiCol_ColumnActive: return "ColumnActive"; - case ImGuiCol_ResizeGrip: return "ResizeGrip"; - case ImGuiCol_ResizeGripHovered: return "ResizeGripHovered"; - case ImGuiCol_ResizeGripActive: return "ResizeGripActive"; - case ImGuiCol_CloseButton: return "CloseButton"; - case ImGuiCol_CloseButtonHovered: return "CloseButtonHovered"; - case ImGuiCol_CloseButtonActive: return "CloseButtonActive"; - case ImGuiCol_PlotLines: return "PlotLines"; - case ImGuiCol_PlotLinesHovered: return "PlotLinesHovered"; - case ImGuiCol_PlotHistogram: return "PlotHistogram"; - case ImGuiCol_PlotHistogramHovered: return "PlotHistogramHovered"; - case ImGuiCol_TextSelectedBg: return "TextSelectedBg"; - case ImGuiCol_ModalWindowDarkening: return "ModalWindowDarkening"; - } - IM_ASSERT(0); - return "Unknown"; -} - -bool ImGui::IsWindowHovered() -{ - ImGuiContext& g = *GImGui; - return g.HoveredWindow == g.CurrentWindow && IsWindowContentHoverable(g.HoveredRootWindow); -} - -bool ImGui::IsWindowFocused() -{ - ImGuiContext& g = *GImGui; - return g.FocusedWindow == g.CurrentWindow; -} - -bool ImGui::IsRootWindowFocused() -{ - ImGuiContext& g = *GImGui; - return g.FocusedWindow == g.CurrentWindow->RootWindow; -} - -bool ImGui::IsRootWindowOrAnyChildFocused() -{ - ImGuiContext& g = *GImGui; - return g.FocusedWindow && g.FocusedWindow->RootWindow == g.CurrentWindow->RootWindow; -} - -bool ImGui::IsRootWindowOrAnyChildHovered() -{ - ImGuiContext& g = *GImGui; - return g.HoveredRootWindow && (g.HoveredRootWindow == g.CurrentWindow->RootWindow) && IsWindowContentHoverable(g.HoveredRootWindow); -} - -float ImGui::GetWindowWidth() -{ - ImGuiWindow* window = GImGui->CurrentWindow; - return window->Size.x; -} - -float ImGui::GetWindowHeight() -{ - ImGuiWindow* window = GImGui->CurrentWindow; - return window->Size.y; -} - -ImVec2 ImGui::GetWindowPos() -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - return window->Pos; -} - -static void SetWindowScrollY(ImGuiWindow* window, float new_scroll_y) -{ - window->DC.CursorMaxPos.y += window->Scroll.y; - window->Scroll.y = new_scroll_y; - window->DC.CursorMaxPos.y -= window->Scroll.y; -} - -static void SetWindowPos(ImGuiWindow* window, const ImVec2& pos, ImGuiSetCond cond) -{ - // Test condition (NB: bit 0 is always true) and clear flags for next time - if (cond && (window->SetWindowPosAllowFlags & cond) == 0) - return; - window->SetWindowPosAllowFlags &= ~(ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing); - window->SetWindowPosCenterWanted = false; - - // Set - const ImVec2 old_pos = window->Pos; - window->PosFloat = pos; - window->Pos = ImVec2((float)(int)window->PosFloat.x, (float)(int)window->PosFloat.y); - window->DC.CursorPos += (window->Pos - old_pos); // As we happen to move the window while it is being appended to (which is a bad idea - will smear) let's at least offset the cursor - window->DC.CursorMaxPos += (window->Pos - old_pos); // And more importantly we need to adjust this so size calculation doesn't get affected. -} - -void ImGui::SetWindowPos(const ImVec2& pos, ImGuiSetCond cond) -{ - ImGuiWindow* window = GetCurrentWindow(); - SetWindowPos(window, pos, cond); -} - -void ImGui::SetWindowPos(const char* name, const ImVec2& pos, ImGuiSetCond cond) -{ - ImGuiWindow* window = FindWindowByName(name); - if (window) - SetWindowPos(window, pos, cond); -} - -ImVec2 ImGui::GetWindowSize() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->Size; -} - -static void SetWindowSize(ImGuiWindow* window, const ImVec2& size, ImGuiSetCond cond) -{ - // Test condition (NB: bit 0 is always true) and clear flags for next time - if (cond && (window->SetWindowSizeAllowFlags & cond) == 0) - return; - window->SetWindowSizeAllowFlags &= ~(ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing); - - // Set - if (size.x > 0.0f) - { - window->AutoFitFramesX = 0; - window->SizeFull.x = size.x; - } - else - { - window->AutoFitFramesX = 2; - window->AutoFitOnlyGrows = false; - } - if (size.y > 0.0f) - { - window->AutoFitFramesY = 0; - window->SizeFull.y = size.y; - } - else - { - window->AutoFitFramesY = 2; - window->AutoFitOnlyGrows = false; - } -} - -void ImGui::SetWindowSize(const ImVec2& size, ImGuiSetCond cond) -{ - SetWindowSize(GImGui->CurrentWindow, size, cond); -} - -void ImGui::SetWindowSize(const char* name, const ImVec2& size, ImGuiSetCond cond) -{ - ImGuiWindow* window = FindWindowByName(name); - if (window) - SetWindowSize(window, size, cond); -} - -static void SetWindowCollapsed(ImGuiWindow* window, bool collapsed, ImGuiSetCond cond) -{ - // Test condition (NB: bit 0 is always true) and clear flags for next time - if (cond && (window->SetWindowCollapsedAllowFlags & cond) == 0) - return; - window->SetWindowCollapsedAllowFlags &= ~(ImGuiSetCond_Once | ImGuiSetCond_FirstUseEver | ImGuiSetCond_Appearing); - - // Set - window->Collapsed = collapsed; -} - -void ImGui::SetWindowCollapsed(bool collapsed, ImGuiSetCond cond) -{ - SetWindowCollapsed(GImGui->CurrentWindow, collapsed, cond); -} - -bool ImGui::IsWindowCollapsed() -{ - return GImGui->CurrentWindow->Collapsed; -} - -void ImGui::SetWindowCollapsed(const char* name, bool collapsed, ImGuiSetCond cond) -{ - ImGuiWindow* window = FindWindowByName(name); - if (window) - SetWindowCollapsed(window, collapsed, cond); -} - -void ImGui::SetWindowFocus() -{ - FocusWindow(GImGui->CurrentWindow); -} - -void ImGui::SetWindowFocus(const char* name) -{ - if (name) - { - if (ImGuiWindow* window = FindWindowByName(name)) - FocusWindow(window); - } - else - { - FocusWindow(NULL); - } -} - -void ImGui::SetNextWindowPos(const ImVec2& pos, ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowPosVal = pos; - g.SetNextWindowPosCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowPosCenter(ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowPosVal = ImVec2(-FLT_MAX, -FLT_MAX); - g.SetNextWindowPosCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowSize(const ImVec2& size, ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowSizeVal = size; - g.SetNextWindowSizeCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowSizeConstraints(const ImVec2& size_min, const ImVec2& size_max, ImGuiSizeConstraintCallback custom_callback, void* custom_callback_user_data) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowSizeConstraint = true; - g.SetNextWindowSizeConstraintRect = ImRect(size_min, size_max); - g.SetNextWindowSizeConstraintCallback = custom_callback; - g.SetNextWindowSizeConstraintCallbackUserData = custom_callback_user_data; -} - -void ImGui::SetNextWindowContentSize(const ImVec2& size) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowContentSizeVal = size; - g.SetNextWindowContentSizeCond = ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowContentWidth(float width) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowContentSizeVal = ImVec2(width, g.SetNextWindowContentSizeCond ? g.SetNextWindowContentSizeVal.y : 0.0f); - g.SetNextWindowContentSizeCond = ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowCollapsed(bool collapsed, ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowCollapsedVal = collapsed; - g.SetNextWindowCollapsedCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::SetNextWindowFocus() -{ - ImGuiContext& g = *GImGui; - g.SetNextWindowFocus = true; -} - -// In window space (not screen space!) -ImVec2 ImGui::GetContentRegionMax() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - ImVec2 mx = window->ContentsRegionRect.Max; - if (window->DC.ColumnsCount != 1) - mx.x = GetColumnOffset(window->DC.ColumnsCurrent + 1) - window->WindowPadding.x; - return mx; -} - -ImVec2 ImGui::GetContentRegionAvail() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return GetContentRegionMax() - (window->DC.CursorPos - window->Pos); -} - -float ImGui::GetContentRegionAvailWidth() -{ - return GetContentRegionAvail().x; -} - -// In window space (not screen space!) -ImVec2 ImGui::GetWindowContentRegionMin() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ContentsRegionRect.Min; -} - -ImVec2 ImGui::GetWindowContentRegionMax() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ContentsRegionRect.Max; -} - -float ImGui::GetWindowContentRegionWidth() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ContentsRegionRect.Max.x - window->ContentsRegionRect.Min.x; -} - -float ImGui::GetTextLineHeight() -{ - ImGuiContext& g = *GImGui; - return g.FontSize; -} - -float ImGui::GetTextLineHeightWithSpacing() -{ - ImGuiContext& g = *GImGui; - return g.FontSize + g.Style.ItemSpacing.y; -} - -float ImGui::GetItemsLineHeightWithSpacing() -{ - ImGuiContext& g = *GImGui; - return g.FontSize + g.Style.FramePadding.y * 2.0f + g.Style.ItemSpacing.y; -} - -ImDrawList* ImGui::GetWindowDrawList() -{ - ImGuiWindow* window = GetCurrentWindow(); - return window->DrawList; -} - -ImFont* ImGui::GetFont() -{ - return GImGui->Font; -} - -float ImGui::GetFontSize() -{ - return GImGui->FontSize; -} - -ImVec2 ImGui::GetFontTexUvWhitePixel() -{ - return GImGui->FontTexUvWhitePixel; -} - -void ImGui::SetWindowFontScale(float scale) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - window->FontWindowScale = scale; - g.FontSize = window->CalcFontSize(); -} - -// User generally sees positions in window coordinates. Internally we store CursorPos in absolute screen coordinates because it is more convenient. -// Conversion happens as we pass the value to user, but it makes our naming convention confusing because GetCursorPos() == (DC.CursorPos - window.Pos). May want to rename 'DC.CursorPos'. -ImVec2 ImGui::GetCursorPos() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorPos - window->Pos + window->Scroll; -} - -float ImGui::GetCursorPosX() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorPos.x - window->Pos.x + window->Scroll.x; -} - -float ImGui::GetCursorPosY() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorPos.y - window->Pos.y + window->Scroll.y; -} - -void ImGui::SetCursorPos(const ImVec2& local_pos) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.CursorPos = window->Pos - window->Scroll + local_pos; - window->DC.CursorMaxPos = ImMax(window->DC.CursorMaxPos, window->DC.CursorPos); -} - -void ImGui::SetCursorPosX(float x) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.CursorPos.x = window->Pos.x - window->Scroll.x + x; - window->DC.CursorMaxPos.x = ImMax(window->DC.CursorMaxPos.x, window->DC.CursorPos.x); -} - -void ImGui::SetCursorPosY(float y) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.CursorPos.y = window->Pos.y - window->Scroll.y + y; - window->DC.CursorMaxPos.y = ImMax(window->DC.CursorMaxPos.y, window->DC.CursorPos.y); -} - -ImVec2 ImGui::GetCursorStartPos() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorStartPos - window->Pos; -} - -ImVec2 ImGui::GetCursorScreenPos() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.CursorPos; -} - -void ImGui::SetCursorScreenPos(const ImVec2& screen_pos) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.CursorPos = screen_pos; - window->DC.CursorMaxPos = ImMax(window->DC.CursorMaxPos, window->DC.CursorPos); -} - -float ImGui::GetScrollX() -{ - return GImGui->CurrentWindow->Scroll.x; -} - -float ImGui::GetScrollY() -{ - return GImGui->CurrentWindow->Scroll.y; -} - -float ImGui::GetScrollMaxX() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->SizeContents.x - window->SizeFull.x - window->ScrollbarSizes.x; -} - -float ImGui::GetScrollMaxY() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->SizeContents.y - window->SizeFull.y - window->ScrollbarSizes.y; -} - -void ImGui::SetScrollX(float scroll_x) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->ScrollTarget.x = scroll_x; - window->ScrollTargetCenterRatio.x = 0.0f; -} - -void ImGui::SetScrollY(float scroll_y) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->ScrollTarget.y = scroll_y + window->TitleBarHeight() + window->MenuBarHeight(); // title bar height canceled out when using ScrollTargetRelY - window->ScrollTargetCenterRatio.y = 0.0f; -} - -void ImGui::SetScrollFromPosY(float pos_y, float center_y_ratio) -{ - // We store a target position so centering can occur on the next frame when we are guaranteed to have a known window size - ImGuiWindow* window = GetCurrentWindow(); - IM_ASSERT(center_y_ratio >= 0.0f && center_y_ratio <= 1.0f); - window->ScrollTarget.y = (float)(int)(pos_y + window->Scroll.y); - if (center_y_ratio <= 0.0f && window->ScrollTarget.y <= window->WindowPadding.y) // Minor hack to make "scroll to top" take account of WindowPadding, else it would scroll to (WindowPadding.y - ItemSpacing.y) - window->ScrollTarget.y = 0.0f; - window->ScrollTargetCenterRatio.y = center_y_ratio; -} - -// center_y_ratio: 0.0f top of last item, 0.5f vertical center of last item, 1.0f bottom of last item. -void ImGui::SetScrollHere(float center_y_ratio) -{ - ImGuiWindow* window = GetCurrentWindow(); - float target_y = window->DC.CursorPosPrevLine.y + (window->DC.PrevLineHeight * center_y_ratio) + (GImGui->Style.ItemSpacing.y * (center_y_ratio - 0.5f) * 2.0f); // Precisely aim above, in the middle or below the last line. - SetScrollFromPosY(target_y - window->Pos.y, center_y_ratio); -} - -void ImGui::SetKeyboardFocusHere(int offset) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->FocusIdxAllRequestNext = window->FocusIdxAllCounter + 1 + offset; - window->FocusIdxTabRequestNext = INT_MAX; -} - -void ImGui::SetStateStorage(ImGuiStorage* tree) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.StateStorage = tree ? tree : &window->StateStorage; -} - -ImGuiStorage* ImGui::GetStateStorage() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.StateStorage; -} - -void ImGui::TextV(const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const char* text_end = g.TempBuffer + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - TextUnformatted(g.TempBuffer, text_end); -} - -void ImGui::Text(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - TextV(fmt, args); - va_end(args); -} - -void ImGui::TextColoredV(const ImVec4& col, const char* fmt, va_list args) -{ - PushStyleColor(ImGuiCol_Text, col); - TextV(fmt, args); - PopStyleColor(); -} - -void ImGui::TextColored(const ImVec4& col, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - TextColoredV(col, fmt, args); - va_end(args); -} - -void ImGui::TextDisabledV(const char* fmt, va_list args) -{ - PushStyleColor(ImGuiCol_Text, GImGui->Style.Colors[ImGuiCol_TextDisabled]); - TextV(fmt, args); - PopStyleColor(); -} - -void ImGui::TextDisabled(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - TextDisabledV(fmt, args); - va_end(args); -} - -void ImGui::TextWrappedV(const char* fmt, va_list args) -{ - bool need_wrap = (GImGui->CurrentWindow->DC.TextWrapPos < 0.0f); // Keep existing wrap position is one ia already set - if (need_wrap) PushTextWrapPos(0.0f); - TextV(fmt, args); - if (need_wrap) PopTextWrapPos(); -} - -void ImGui::TextWrapped(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - TextWrappedV(fmt, args); - va_end(args); -} - -void ImGui::TextUnformatted(const char* text, const char* text_end) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - IM_ASSERT(text != NULL); - const char* text_begin = text; - if (text_end == NULL) - text_end = text + strlen(text); // FIXME-OPT - - const float wrap_pos_x = window->DC.TextWrapPos; - const bool wrap_enabled = wrap_pos_x >= 0.0f; - if (text_end - text > 2000 && !wrap_enabled) - { - // Long text! - // Perform manual coarse clipping to optimize for long multi-line text - // From this point we will only compute the width of lines that are visible. Optimization only available when word-wrapping is disabled. - // We also don't vertically center the text within the line full height, which is unlikely to matter because we are likely the biggest and only item on the line. - const char* line = text; - const float line_height = GetTextLineHeight(); - const ImVec2 text_pos = window->DC.CursorPos + ImVec2(0.0f, window->DC.CurrentLineTextBaseOffset); - const ImRect clip_rect = window->ClipRect; - ImVec2 text_size(0,0); - - if (text_pos.y <= clip_rect.Max.y) - { - ImVec2 pos = text_pos; - - // Lines to skip (can't skip when logging text) - if (!g.LogEnabled) - { - int lines_skippable = (int)((clip_rect.Min.y - text_pos.y) / line_height); - if (lines_skippable > 0) - { - int lines_skipped = 0; - while (line < text_end && lines_skipped < lines_skippable) - { - const char* line_end = strchr(line, '\n'); - if (!line_end) - line_end = text_end; - line = line_end + 1; - lines_skipped++; - } - pos.y += lines_skipped * line_height; - } - } - - // Lines to render - if (line < text_end) - { - ImRect line_rect(pos, pos + ImVec2(FLT_MAX, line_height)); - while (line < text_end) - { - const char* line_end = strchr(line, '\n'); - if (IsClippedEx(line_rect, NULL, false)) - break; - - const ImVec2 line_size = CalcTextSize(line, line_end, false); - text_size.x = ImMax(text_size.x, line_size.x); - RenderText(pos, line, line_end, false); - if (!line_end) - line_end = text_end; - line = line_end + 1; - line_rect.Min.y += line_height; - line_rect.Max.y += line_height; - pos.y += line_height; - } - - // Count remaining lines - int lines_skipped = 0; - while (line < text_end) - { - const char* line_end = strchr(line, '\n'); - if (!line_end) - line_end = text_end; - line = line_end + 1; - lines_skipped++; - } - pos.y += lines_skipped * line_height; - } - - text_size.y += (pos - text_pos).y; - } - - ImRect bb(text_pos, text_pos + text_size); - ItemSize(bb); - ItemAdd(bb, NULL); - } - else - { - const float wrap_width = wrap_enabled ? CalcWrapWidthForPos(window->DC.CursorPos, wrap_pos_x) : 0.0f; - const ImVec2 text_size = CalcTextSize(text_begin, text_end, false, wrap_width); - - // Account of baseline offset - ImVec2 text_pos(window->DC.CursorPos.x, window->DC.CursorPos.y + window->DC.CurrentLineTextBaseOffset); - ImRect bb(text_pos, text_pos + text_size); - ItemSize(text_size); - if (!ItemAdd(bb, NULL)) - return; - - // Render (we don't hide text after ## in this end-user function) - RenderTextWrapped(bb.Min, text_begin, text_end, wrap_width); - } -} - -void ImGui::AlignFirstTextHeightToWidgets() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - // Declare a dummy item size to that upcoming items that are smaller will center-align on the newly expanded line height. - ImGuiContext& g = *GImGui; - ItemSize(ImVec2(0, g.FontSize + g.Style.FramePadding.y*2), g.Style.FramePadding.y); - SameLine(0, 0); -} - -// Add a label+text combo aligned to other label+value widgets -void ImGui::LabelTextV(const char* label, const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const float w = CalcItemWidth(); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect value_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2)); - const ImRect total_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w + (label_size.x > 0.0f ? style.ItemInnerSpacing.x : 0.0f), style.FramePadding.y*2) + label_size); - ItemSize(total_bb, style.FramePadding.y); - if (!ItemAdd(total_bb, NULL)) - return; - - // Render - const char* value_text_begin = &g.TempBuffer[0]; - const char* value_text_end = value_text_begin + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - RenderTextClipped(value_bb.Min, value_bb.Max, value_text_begin, value_text_end, NULL, ImVec2(0.0f,0.5f)); - if (label_size.x > 0.0f) - RenderText(ImVec2(value_bb.Max.x + style.ItemInnerSpacing.x, value_bb.Min.y + style.FramePadding.y), label); -} - -void ImGui::LabelText(const char* label, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - LabelTextV(label, fmt, args); - va_end(args); -} - -static inline bool IsWindowContentHoverable(ImGuiWindow* window) -{ - // An active popup disable hovering on other windows (apart from its own children) - ImGuiContext& g = *GImGui; - if (ImGuiWindow* focused_window = g.FocusedWindow) - if (ImGuiWindow* focused_root_window = focused_window->RootWindow) - if ((focused_root_window->Flags & ImGuiWindowFlags_Popup) != 0 && focused_root_window->WasActive && focused_root_window != window->RootWindow) - return false; - - return true; -} - -bool ImGui::ButtonBehavior(const ImRect& bb, ImGuiID id, bool* out_hovered, bool* out_held, ImGuiButtonFlags flags) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - if (flags & ImGuiButtonFlags_Disabled) - { - if (out_hovered) *out_hovered = false; - if (out_held) *out_held = false; - if (g.ActiveId == id) SetActiveID(0); - return false; - } - - if ((flags & (ImGuiButtonFlags_PressedOnClickRelease | ImGuiButtonFlags_PressedOnClick | ImGuiButtonFlags_PressedOnRelease | ImGuiButtonFlags_PressedOnDoubleClick)) == 0) - flags |= ImGuiButtonFlags_PressedOnClickRelease; - - bool pressed = false; - bool hovered = IsHovered(bb, id, (flags & ImGuiButtonFlags_FlattenChilds) != 0); - if (hovered) - { - SetHoveredID(id); - if (!(flags & ImGuiButtonFlags_NoKeyModifiers) || (!g.IO.KeyCtrl && !g.IO.KeyShift && !g.IO.KeyAlt)) - { - // | CLICKING | HOLDING with ImGuiButtonFlags_Repeat - // PressedOnClickRelease | <on release>* | <on repeat> <on repeat> .. (NOT on release) <-- MOST COMMON! (*) only if both click/release were over bounds - // PressedOnClick | <on click> | <on click> <on repeat> <on repeat> .. - // PressedOnRelease | <on release> | <on repeat> <on repeat> .. (NOT on release) - // PressedOnDoubleClick | <on dclick> | <on dclick> <on repeat> <on repeat> .. - if ((flags & ImGuiButtonFlags_PressedOnClickRelease) && g.IO.MouseClicked[0]) - { - SetActiveID(id, window); // Hold on ID - FocusWindow(window); - g.ActiveIdClickOffset = g.IO.MousePos - bb.Min; - } - if (((flags & ImGuiButtonFlags_PressedOnClick) && g.IO.MouseClicked[0]) || ((flags & ImGuiButtonFlags_PressedOnDoubleClick) && g.IO.MouseDoubleClicked[0])) - { - pressed = true; - SetActiveID(0); - FocusWindow(window); - } - if ((flags & ImGuiButtonFlags_PressedOnRelease) && g.IO.MouseReleased[0]) - { - if (!((flags & ImGuiButtonFlags_Repeat) && g.IO.MouseDownDurationPrev[0] >= g.IO.KeyRepeatDelay)) // Repeat mode trumps <on release> - pressed = true; - SetActiveID(0); - } - - // 'Repeat' mode acts when held regardless of _PressedOn flags (see table above). - // Relies on repeat logic of IsMouseClicked() but we may as well do it ourselves if we end up exposing finer RepeatDelay/RepeatRate settings. - if ((flags & ImGuiButtonFlags_Repeat) && g.ActiveId == id && g.IO.MouseDownDuration[0] > 0.0f && IsMouseClicked(0, true)) - pressed = true; - } - } - - bool held = false; - if (g.ActiveId == id) - { - if (g.IO.MouseDown[0]) - { - held = true; - } - else - { - if (hovered && (flags & ImGuiButtonFlags_PressedOnClickRelease)) - if (!((flags & ImGuiButtonFlags_Repeat) && g.IO.MouseDownDurationPrev[0] >= g.IO.KeyRepeatDelay)) // Repeat mode trumps <on release> - pressed = true; - SetActiveID(0); - } - } - - // AllowOverlap mode (rarely used) requires previous frame HoveredId to be null or to match. This allows using patterns where a later submitted widget overlaps a previous one. - if (hovered && (flags & ImGuiButtonFlags_AllowOverlapMode) && (g.HoveredIdPreviousFrame != id && g.HoveredIdPreviousFrame != 0)) - hovered = pressed = held = false; - - if (out_hovered) *out_hovered = hovered; - if (out_held) *out_held = held; - - return pressed; -} - -bool ImGui::ButtonEx(const char* label, const ImVec2& size_arg, ImGuiButtonFlags flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - ImVec2 pos = window->DC.CursorPos; - if ((flags & ImGuiButtonFlags_AlignTextBaseLine) && style.FramePadding.y < window->DC.CurrentLineTextBaseOffset) // Try to vertically align buttons that are smaller/have no padding so that text baseline matches (bit hacky, since it shouldn't be a flag) - pos.y += window->DC.CurrentLineTextBaseOffset - style.FramePadding.y; - ImVec2 size = CalcItemSize(size_arg, label_size.x + style.FramePadding.x * 2.0f, label_size.y + style.FramePadding.y * 2.0f); - - const ImRect bb(pos, pos + size); - ItemSize(bb, style.FramePadding.y); - if (!ItemAdd(bb, &id)) - return false; - - if (window->DC.ButtonRepeat) flags |= ImGuiButtonFlags_Repeat; - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held, flags); - - // Render - const ImU32 col = GetColorU32((hovered && held) ? ImGuiCol_ButtonActive : hovered ? ImGuiCol_ButtonHovered : ImGuiCol_Button); - RenderFrame(bb.Min, bb.Max, col, true, style.FrameRounding); - RenderTextClipped(bb.Min + style.FramePadding, bb.Max - style.FramePadding, label, NULL, &label_size, style.ButtonTextAlign, &bb); - - // Automatically close popups - //if (pressed && !(flags & ImGuiButtonFlags_DontClosePopups) && (window->Flags & ImGuiWindowFlags_Popup)) - // CloseCurrentPopup(); - - return pressed; -} - -bool ImGui::Button(const char* label, const ImVec2& size_arg) -{ - return ButtonEx(label, size_arg, 0); -} - -// Small buttons fits within text without additional vertical spacing. -bool ImGui::SmallButton(const char* label) -{ - ImGuiContext& g = *GImGui; - float backup_padding_y = g.Style.FramePadding.y; - g.Style.FramePadding.y = 0.0f; - bool pressed = ButtonEx(label, ImVec2(0,0), ImGuiButtonFlags_AlignTextBaseLine); - g.Style.FramePadding.y = backup_padding_y; - return pressed; -} - -// Tip: use ImGui::PushID()/PopID() to push indices or pointers in the ID stack. -// Then you can keep 'str_id' empty or the same for all your buttons (instead of creating a string based on a non-string id) -bool ImGui::InvisibleButton(const char* str_id, const ImVec2& size_arg) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - const ImGuiID id = window->GetID(str_id); - ImVec2 size = CalcItemSize(size_arg, 0.0f, 0.0f); - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); - ItemSize(bb); - if (!ItemAdd(bb, &id)) - return false; - - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held); - - return pressed; -} - -// Upper-right button to close a window. -bool ImGui::CloseButton(ImGuiID id, const ImVec2& pos, float radius) -{ - ImGuiWindow* window = GetCurrentWindow(); - - const ImRect bb(pos - ImVec2(radius,radius), pos + ImVec2(radius,radius)); - - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held); - - // Render - const ImU32 col = GetColorU32((held && hovered) ? ImGuiCol_CloseButtonActive : hovered ? ImGuiCol_CloseButtonHovered : ImGuiCol_CloseButton); - const ImVec2 center = bb.GetCenter(); - window->DrawList->AddCircleFilled(center, ImMax(2.0f, radius), col, 12); - - const float cross_extent = (radius * 0.7071f) - 1.0f; - if (hovered) - { - window->DrawList->AddLine(center + ImVec2(+cross_extent,+cross_extent), center + ImVec2(-cross_extent,-cross_extent), GetColorU32(ImGuiCol_Text)); - window->DrawList->AddLine(center + ImVec2(+cross_extent,-cross_extent), center + ImVec2(-cross_extent,+cross_extent), GetColorU32(ImGuiCol_Text)); - } - - return pressed; -} - -void ImGui::Image(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0, const ImVec2& uv1, const ImVec4& tint_col, const ImVec4& border_col) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); - if (border_col.w > 0.0f) - bb.Max += ImVec2(2,2); - ItemSize(bb); - if (!ItemAdd(bb, NULL)) - return; - - if (border_col.w > 0.0f) - { - window->DrawList->AddRect(bb.Min, bb.Max, GetColorU32(border_col), 0.0f); - window->DrawList->AddImage(user_texture_id, bb.Min+ImVec2(1,1), bb.Max-ImVec2(1,1), uv0, uv1, GetColorU32(tint_col)); - } - else - { - window->DrawList->AddImage(user_texture_id, bb.Min, bb.Max, uv0, uv1, GetColorU32(tint_col)); - } -} - -// frame_padding < 0: uses FramePadding from style (default) -// frame_padding = 0: no framing -// frame_padding > 0: set framing size -// The color used are the button colors. -bool ImGui::ImageButton(ImTextureID user_texture_id, const ImVec2& size, const ImVec2& uv0, const ImVec2& uv1, int frame_padding, const ImVec4& bg_col, const ImVec4& tint_col) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - // Default to using texture ID as ID. User can still push string/integer prefixes. - // We could hash the size/uv to create a unique ID but that would prevent the user from animating UV. - PushID((void *)user_texture_id); - const ImGuiID id = window->GetID("#image"); - PopID(); - - const ImVec2 padding = (frame_padding >= 0) ? ImVec2((float)frame_padding, (float)frame_padding) : style.FramePadding; - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size + padding*2); - const ImRect image_bb(window->DC.CursorPos + padding, window->DC.CursorPos + padding + size); - ItemSize(bb); - if (!ItemAdd(bb, &id)) - return false; - - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held); - - // Render - const ImU32 col = GetColorU32((hovered && held) ? ImGuiCol_ButtonActive : hovered ? ImGuiCol_ButtonHovered : ImGuiCol_Button); - RenderFrame(bb.Min, bb.Max, col, true, ImClamp((float)ImMin(padding.x, padding.y), 0.0f, style.FrameRounding)); - if (bg_col.w > 0.0f) - window->DrawList->AddRectFilled(image_bb.Min, image_bb.Max, GetColorU32(bg_col)); - window->DrawList->AddImage(user_texture_id, image_bb.Min, image_bb.Max, uv0, uv1, GetColorU32(tint_col)); - - return pressed; -} - -// Start logging ImGui output to TTY -void ImGui::LogToTTY(int max_depth) -{ - ImGuiContext& g = *GImGui; - if (g.LogEnabled) - return; - ImGuiWindow* window = GetCurrentWindowRead(); - - g.LogEnabled = true; - g.LogFile = stdout; - g.LogStartDepth = window->DC.TreeDepth; - if (max_depth >= 0) - g.LogAutoExpandMaxDepth = max_depth; -} - -// Start logging ImGui output to given file -void ImGui::LogToFile(int max_depth, const char* filename) -{ - ImGuiContext& g = *GImGui; - if (g.LogEnabled) - return; - ImGuiWindow* window = GetCurrentWindowRead(); - - if (!filename) - { - filename = g.IO.LogFilename; - if (!filename) - return; - } - - g.LogFile = fopen(filename, "ab"); - if (!g.LogFile) - { - IM_ASSERT(g.LogFile != NULL); // Consider this an error - return; - } - g.LogEnabled = true; - g.LogStartDepth = window->DC.TreeDepth; - if (max_depth >= 0) - g.LogAutoExpandMaxDepth = max_depth; -} - -// Start logging ImGui output to clipboard -void ImGui::LogToClipboard(int max_depth) -{ - ImGuiContext& g = *GImGui; - if (g.LogEnabled) - return; - ImGuiWindow* window = GetCurrentWindowRead(); - - g.LogEnabled = true; - g.LogFile = NULL; - g.LogStartDepth = window->DC.TreeDepth; - if (max_depth >= 0) - g.LogAutoExpandMaxDepth = max_depth; -} - -void ImGui::LogFinish() -{ - ImGuiContext& g = *GImGui; - if (!g.LogEnabled) - return; - - LogText(IM_NEWLINE); - g.LogEnabled = false; - if (g.LogFile != NULL) - { - if (g.LogFile == stdout) - fflush(g.LogFile); - else - fclose(g.LogFile); - g.LogFile = NULL; - } - if (g.LogClipboard->size() > 1) - { - if (g.IO.SetClipboardTextFn) - g.IO.SetClipboardTextFn(g.LogClipboard->begin()); - g.LogClipboard->clear(); - } -} - -// Helper to display logging buttons -void ImGui::LogButtons() -{ - ImGuiContext& g = *GImGui; - - PushID("LogButtons"); - const bool log_to_tty = Button("Log To TTY"); SameLine(); - const bool log_to_file = Button("Log To File"); SameLine(); - const bool log_to_clipboard = Button("Log To Clipboard"); SameLine(); - PushItemWidth(80.0f); - PushAllowKeyboardFocus(false); - SliderInt("Depth", &g.LogAutoExpandMaxDepth, 0, 9, NULL); - PopAllowKeyboardFocus(); - PopItemWidth(); - PopID(); - - // Start logging at the end of the function so that the buttons don't appear in the log - if (log_to_tty) - LogToTTY(g.LogAutoExpandMaxDepth); - if (log_to_file) - LogToFile(g.LogAutoExpandMaxDepth, g.IO.LogFilename); - if (log_to_clipboard) - LogToClipboard(g.LogAutoExpandMaxDepth); -} - -bool ImGui::TreeNodeBehaviorIsOpen(ImGuiID id, ImGuiTreeNodeFlags flags) -{ - if (flags & ImGuiTreeNodeFlags_Leaf) - return true; - - // We only write to the tree storage if the user clicks (or explicitely use SetNextTreeNode*** functions) - ImGuiContext& g = *GImGui; - ImGuiWindow* window = g.CurrentWindow; - ImGuiStorage* storage = window->DC.StateStorage; - - bool is_open; - if (g.SetNextTreeNodeOpenCond != 0) - { - if (g.SetNextTreeNodeOpenCond & ImGuiSetCond_Always) - { - is_open = g.SetNextTreeNodeOpenVal; - storage->SetInt(id, is_open); - } - else - { - // We treat ImGuiSetCondition_Once and ImGuiSetCondition_FirstUseEver the same because tree node state are not saved persistently. - const int stored_value = storage->GetInt(id, -1); - if (stored_value == -1) - { - is_open = g.SetNextTreeNodeOpenVal; - storage->SetInt(id, is_open); - } - else - { - is_open = stored_value != 0; - } - } - g.SetNextTreeNodeOpenCond = 0; - } - else - { - is_open = storage->GetInt(id, (flags & ImGuiTreeNodeFlags_DefaultOpen) ? 1 : 0) != 0; - } - - // When logging is enabled, we automatically expand tree nodes (but *NOT* collapsing headers.. seems like sensible behavior). - // NB- If we are above max depth we still allow manually opened nodes to be logged. - if (g.LogEnabled && !(flags & ImGuiTreeNodeFlags_NoAutoOpenOnLog) && window->DC.TreeDepth < g.LogAutoExpandMaxDepth) - is_open = true; - - return is_open; -} - -bool ImGui::TreeNodeBehavior(ImGuiID id, ImGuiTreeNodeFlags flags, const char* label, const char* label_end) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const bool display_frame = (flags & ImGuiTreeNodeFlags_Framed) != 0; - const ImVec2 padding = display_frame ? style.FramePadding : ImVec2(style.FramePadding.x, 0.0f); - - if (!label_end) - label_end = FindRenderedTextEnd(label); - const ImVec2 label_size = CalcTextSize(label, label_end, false); - - // We vertically grow up to current line height up the typical widget height. - const float text_base_offset_y = ImMax(0.0f, window->DC.CurrentLineTextBaseOffset - padding.y); // Latch before ItemSize changes it - const float frame_height = ImMax(ImMin(window->DC.CurrentLineHeight, g.FontSize + style.FramePadding.y*2), label_size.y + padding.y*2); - ImRect bb = ImRect(window->DC.CursorPos, ImVec2(window->Pos.x + GetContentRegionMax().x, window->DC.CursorPos.y + frame_height)); - if (display_frame) - { - // Framed header expand a little outside the default padding - bb.Min.x -= (float)(int)(window->WindowPadding.x*0.5f) - 1; - bb.Max.x += (float)(int)(window->WindowPadding.x*0.5f) - 1; - } - - const float text_offset_x = (g.FontSize + (display_frame ? padding.x*3 : padding.x*2)); // Collapser arrow width + Spacing - const float text_width = g.FontSize + (label_size.x > 0.0f ? label_size.x + padding.x*2 : 0.0f); // Include collapser - ItemSize(ImVec2(text_width, frame_height), text_base_offset_y); - - // For regular tree nodes, we arbitrary allow to click past 2 worth of ItemSpacing - // (Ideally we'd want to add a flag for the user to specify we want want the hit test to be done up to the right side of the content or not) - const ImRect interact_bb = display_frame ? bb : ImRect(bb.Min.x, bb.Min.y, bb.Min.x + text_width + style.ItemSpacing.x*2, bb.Max.y); - bool is_open = TreeNodeBehaviorIsOpen(id, flags); - if (!ItemAdd(interact_bb, &id)) - { - if (is_open && !(flags & ImGuiTreeNodeFlags_NoTreePushOnOpen)) - TreePushRawID(id); - return is_open; - } - - // Flags that affects opening behavior: - // - 0(default) ..................... single-click anywhere to open - // - OpenOnDoubleClick .............. double-click anywhere to open - // - OpenOnArrow .................... single-click on arrow to open - // - OpenOnDoubleClick|OpenOnArrow .. single-click on arrow or double-click anywhere to open - ImGuiButtonFlags button_flags = ImGuiButtonFlags_NoKeyModifiers | ((flags & ImGuiTreeNodeFlags_AllowOverlapMode) ? ImGuiButtonFlags_AllowOverlapMode : 0); - if (flags & ImGuiTreeNodeFlags_OpenOnDoubleClick) - button_flags |= ImGuiButtonFlags_PressedOnDoubleClick | ((flags & ImGuiTreeNodeFlags_OpenOnArrow) ? ImGuiButtonFlags_PressedOnClickRelease : 0); - bool hovered, held, pressed = ButtonBehavior(interact_bb, id, &hovered, &held, button_flags); - if (pressed && !(flags & ImGuiTreeNodeFlags_Leaf)) - { - bool toggled = !(flags & (ImGuiTreeNodeFlags_OpenOnArrow | ImGuiTreeNodeFlags_OpenOnDoubleClick)); - if (flags & ImGuiTreeNodeFlags_OpenOnArrow) - toggled |= IsMouseHoveringRect(interact_bb.Min, ImVec2(interact_bb.Min.x + text_offset_x, interact_bb.Max.y)); - if (flags & ImGuiTreeNodeFlags_OpenOnDoubleClick) - toggled |= g.IO.MouseDoubleClicked[0]; - if (toggled) - { - is_open = !is_open; - window->DC.StateStorage->SetInt(id, is_open); - } - } - if (flags & ImGuiTreeNodeFlags_AllowOverlapMode) - SetItemAllowOverlap(); - - // Render - const ImU32 col = GetColorU32((held && hovered) ? ImGuiCol_HeaderActive : hovered ? ImGuiCol_HeaderHovered : ImGuiCol_Header); - const ImVec2 text_pos = bb.Min + ImVec2(text_offset_x, padding.y + text_base_offset_y); - if (display_frame) - { - // Framed type - RenderFrame(bb.Min, bb.Max, col, true, style.FrameRounding); - RenderCollapseTriangle(bb.Min + padding + ImVec2(0.0f, text_base_offset_y), is_open, 1.0f, true); - if (g.LogEnabled) - { - // NB: '##' is normally used to hide text (as a library-wide feature), so we need to specify the text range to make sure the ## aren't stripped out here. - const char log_prefix[] = "\n##"; - const char log_suffix[] = "##"; - LogRenderedText(text_pos, log_prefix, log_prefix+3); - RenderTextClipped(text_pos, bb.Max, label, label_end, &label_size); - LogRenderedText(text_pos, log_suffix+1, log_suffix+3); - } - else - { - RenderTextClipped(text_pos, bb.Max, label, label_end, &label_size); - } - } - else - { - // Unframed typed for tree nodes - if (hovered || (flags & ImGuiTreeNodeFlags_Selected)) - RenderFrame(bb.Min, bb.Max, col, false); - - if (flags & ImGuiTreeNodeFlags_Bullet) - RenderBullet(bb.Min + ImVec2(text_offset_x * 0.5f, g.FontSize*0.50f + text_base_offset_y)); - else if (!(flags & ImGuiTreeNodeFlags_Leaf)) - RenderCollapseTriangle(bb.Min + ImVec2(padding.x, g.FontSize*0.15f + text_base_offset_y), is_open, 0.70f, false); - if (g.LogEnabled) - LogRenderedText(text_pos, ">"); - RenderText(text_pos, label, label_end, false); - } - - if (is_open && !(flags & ImGuiTreeNodeFlags_NoTreePushOnOpen)) - TreePushRawID(id); - return is_open; -} - -// CollapsingHeader returns true when opened but do not indent nor push into the ID stack (because of the ImGuiTreeNodeFlags_NoTreePushOnOpen flag). -// This is basically the same as calling TreeNodeEx(label, ImGuiTreeNodeFlags_CollapsingHeader | ImGuiTreeNodeFlags_NoTreePushOnOpen). You can remove the _NoTreePushOnOpen flag if you want behavior closer to normal TreeNode(). -bool ImGui::CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - return TreeNodeBehavior(window->GetID(label), flags | ImGuiTreeNodeFlags_CollapsingHeader | ImGuiTreeNodeFlags_NoTreePushOnOpen, label); -} - -bool ImGui::CollapsingHeader(const char* label, bool* p_open, ImGuiTreeNodeFlags flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - if (p_open && !*p_open) - return false; - - ImGuiID id = window->GetID(label); - bool is_open = TreeNodeBehavior(id, flags | ImGuiTreeNodeFlags_CollapsingHeader | ImGuiTreeNodeFlags_NoTreePushOnOpen | (p_open ? ImGuiTreeNodeFlags_AllowOverlapMode : 0), label); - if (p_open) - { - // Create a small overlapping close button // FIXME: We can evolve this into user accessible helpers to add extra buttons on title bars, headers, etc. - ImGuiContext& g = *GImGui; - float button_sz = g.FontSize * 0.5f; - if (CloseButton(window->GetID((void*)(intptr_t)(id+1)), ImVec2(ImMin(window->DC.LastItemRect.Max.x, window->ClipRect.Max.x) - g.Style.FramePadding.x - button_sz, window->DC.LastItemRect.Min.y + g.Style.FramePadding.y + button_sz), button_sz)) - *p_open = false; - } - - return is_open; -} - -bool ImGui::TreeNodeEx(const char* label, ImGuiTreeNodeFlags flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - return TreeNodeBehavior(window->GetID(label), flags, label, NULL); -} - -bool ImGui::TreeNodeExV(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const char* label_end = g.TempBuffer + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - return TreeNodeBehavior(window->GetID(str_id), flags, g.TempBuffer, label_end); -} - -bool ImGui::TreeNodeExV(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const char* label_end = g.TempBuffer + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - return TreeNodeBehavior(window->GetID(ptr_id), flags, g.TempBuffer, label_end); -} - -bool ImGui::TreeNodeV(const char* str_id, const char* fmt, va_list args) -{ - return TreeNodeExV(str_id, 0, fmt, args); -} - -bool ImGui::TreeNodeV(const void* ptr_id, const char* fmt, va_list args) -{ - return TreeNodeExV(ptr_id, 0, fmt, args); -} - -bool ImGui::TreeNodeEx(const char* str_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - bool is_open = TreeNodeExV(str_id, flags, fmt, args); - va_end(args); - return is_open; -} - -bool ImGui::TreeNodeEx(const void* ptr_id, ImGuiTreeNodeFlags flags, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - bool is_open = TreeNodeExV(ptr_id, flags, fmt, args); - va_end(args); - return is_open; -} - -bool ImGui::TreeNode(const char* str_id, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - bool is_open = TreeNodeExV(str_id, 0, fmt, args); - va_end(args); - return is_open; -} - -bool ImGui::TreeNode(const void* ptr_id, const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - bool is_open = TreeNodeExV(ptr_id, 0, fmt, args); - va_end(args); - return is_open; -} - -bool ImGui::TreeNode(const char* label) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - return TreeNodeBehavior(window->GetID(label), 0, label, NULL); -} - -void ImGui::TreeAdvanceToLabelPos() -{ - ImGuiContext& g = *GImGui; - g.CurrentWindow->DC.CursorPos.x += GetTreeNodeToLabelSpacing(); -} - -// Horizontal distance preceding label when using TreeNode() or Bullet() -float ImGui::GetTreeNodeToLabelSpacing() -{ - ImGuiContext& g = *GImGui; - return g.FontSize + (g.Style.FramePadding.x * 2.0f); -} - -void ImGui::SetNextTreeNodeOpen(bool is_open, ImGuiSetCond cond) -{ - ImGuiContext& g = *GImGui; - g.SetNextTreeNodeOpenVal = is_open; - g.SetNextTreeNodeOpenCond = cond ? cond : ImGuiSetCond_Always; -} - -void ImGui::PushID(const char* str_id) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.push_back(window->GetID(str_id)); -} - -void ImGui::PushID(const char* str_id_begin, const char* str_id_end) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.push_back(window->GetID(str_id_begin, str_id_end)); -} - -void ImGui::PushID(const void* ptr_id) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.push_back(window->GetID(ptr_id)); -} - -void ImGui::PushID(int int_id) -{ - const void* ptr_id = (void*)(intptr_t)int_id; - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.push_back(window->GetID(ptr_id)); -} - -void ImGui::PopID() -{ - ImGuiWindow* window = GetCurrentWindow(); - window->IDStack.pop_back(); -} - -ImGuiID ImGui::GetID(const char* str_id) -{ - return GImGui->CurrentWindow->GetID(str_id); -} - -ImGuiID ImGui::GetID(const char* str_id_begin, const char* str_id_end) -{ - return GImGui->CurrentWindow->GetID(str_id_begin, str_id_end); -} - -ImGuiID ImGui::GetID(const void* ptr_id) -{ - return GImGui->CurrentWindow->GetID(ptr_id); -} - -void ImGui::Bullet() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const float line_height = ImMax(ImMin(window->DC.CurrentLineHeight, g.FontSize + g.Style.FramePadding.y*2), g.FontSize); - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(g.FontSize, line_height)); - ItemSize(bb); - if (!ItemAdd(bb, NULL)) - { - SameLine(0, style.FramePadding.x*2); - return; - } - - // Render and stay on same line - RenderBullet(bb.Min + ImVec2(style.FramePadding.x + g.FontSize*0.5f, line_height*0.5f)); - SameLine(0, style.FramePadding.x*2); -} - -// Text with a little bullet aligned to the typical tree node. -void ImGui::BulletTextV(const char* fmt, va_list args) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - const char* text_begin = g.TempBuffer; - const char* text_end = text_begin + ImFormatStringV(g.TempBuffer, IM_ARRAYSIZE(g.TempBuffer), fmt, args); - const ImVec2 label_size = CalcTextSize(text_begin, text_end, false); - const float text_base_offset_y = ImMax(0.0f, window->DC.CurrentLineTextBaseOffset); // Latch before ItemSize changes it - const float line_height = ImMax(ImMin(window->DC.CurrentLineHeight, g.FontSize + g.Style.FramePadding.y*2), g.FontSize); - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(g.FontSize + (label_size.x > 0.0f ? (label_size.x + style.FramePadding.x*2) : 0.0f), ImMax(line_height, label_size.y))); // Empty text doesn't add padding - ItemSize(bb); - if (!ItemAdd(bb, NULL)) - return; - - // Render - RenderBullet(bb.Min + ImVec2(style.FramePadding.x + g.FontSize*0.5f, line_height*0.5f)); - RenderText(bb.Min+ImVec2(g.FontSize + style.FramePadding.x*2, text_base_offset_y), text_begin, text_end, false); -} - -void ImGui::BulletText(const char* fmt, ...) -{ - va_list args; - va_start(args, fmt); - BulletTextV(fmt, args); - va_end(args); -} - -static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, const char* display_format, char* buf, int buf_size) -{ - if (data_type == ImGuiDataType_Int) - ImFormatString(buf, buf_size, display_format, *(int*)data_ptr); - else if (data_type == ImGuiDataType_Float) - ImFormatString(buf, buf_size, display_format, *(float*)data_ptr); -} - -static inline void DataTypeFormatString(ImGuiDataType data_type, void* data_ptr, int decimal_precision, char* buf, int buf_size) -{ - if (data_type == ImGuiDataType_Int) - { - if (decimal_precision < 0) - ImFormatString(buf, buf_size, "%d", *(int*)data_ptr); - else - ImFormatString(buf, buf_size, "%.*d", decimal_precision, *(int*)data_ptr); - } - else if (data_type == ImGuiDataType_Float) - { - if (decimal_precision < 0) - ImFormatString(buf, buf_size, "%f", *(float*)data_ptr); // Ideally we'd have a minimum decimal precision of 1 to visually denote that it is a float, while hiding non-significant digits? - else - ImFormatString(buf, buf_size, "%.*f", decimal_precision, *(float*)data_ptr); - } -} - -static void DataTypeApplyOp(ImGuiDataType data_type, int op, void* value1, const void* value2)// Store into value1 -{ - if (data_type == ImGuiDataType_Int) - { - if (op == '+') - *(int*)value1 = *(int*)value1 + *(const int*)value2; - else if (op == '-') - *(int*)value1 = *(int*)value1 - *(const int*)value2; - } - else if (data_type == ImGuiDataType_Float) - { - if (op == '+') - *(float*)value1 = *(float*)value1 + *(const float*)value2; - else if (op == '-') - *(float*)value1 = *(float*)value1 - *(const float*)value2; - } -} - -// User can input math operators (e.g. +100) to edit a numerical values. -static bool DataTypeApplyOpFromText(const char* buf, const char* initial_value_buf, ImGuiDataType data_type, void* data_ptr, const char* scalar_format) -{ - while (ImCharIsSpace(*buf)) - buf++; - - // We don't support '-' op because it would conflict with inputing negative value. - // Instead you can use +-100 to subtract from an existing value - char op = buf[0]; - if (op == '+' || op == '*' || op == '/') - { - buf++; - while (ImCharIsSpace(*buf)) - buf++; - } - else - { - op = 0; - } - if (!buf[0]) - return false; - - if (data_type == ImGuiDataType_Int) - { - if (!scalar_format) - scalar_format = "%d"; - int* v = (int*)data_ptr; - const int old_v = *v; - int arg0 = *v; - if (op && sscanf(initial_value_buf, scalar_format, &arg0) < 1) - return false; - - // Store operand in a float so we can use fractional value for multipliers (*1.1), but constant always parsed as integer so we can fit big integers (e.g. 2000000003) past float precision - float arg1 = 0.0f; - if (op == '+') { if (sscanf(buf, "%f", &arg1) == 1) *v = (int)(arg0 + arg1); } // Add (use "+-" to subtract) - else if (op == '*') { if (sscanf(buf, "%f", &arg1) == 1) *v = (int)(arg0 * arg1); } // Multiply - else if (op == '/') { if (sscanf(buf, "%f", &arg1) == 1 && arg1 != 0.0f) *v = (int)(arg0 / arg1); }// Divide - else { if (sscanf(buf, scalar_format, &arg0) == 1) *v = arg0; } // Assign constant - return (old_v != *v); - } - else if (data_type == ImGuiDataType_Float) - { - // For floats we have to ignore format with precision (e.g. "%.2f") because sscanf doesn't take them in - scalar_format = "%f"; - float* v = (float*)data_ptr; - const float old_v = *v; - float arg0 = *v; - if (op && sscanf(initial_value_buf, scalar_format, &arg0) < 1) - return false; - - float arg1 = 0.0f; - if (sscanf(buf, scalar_format, &arg1) < 1) - return false; - if (op == '+') { *v = arg0 + arg1; } // Add (use "+-" to subtract) - else if (op == '*') { *v = arg0 * arg1; } // Multiply - else if (op == '/') { if (arg1 != 0.0f) *v = arg0 / arg1; } // Divide - else { *v = arg1; } // Assign constant - return (old_v != *v); - } - - return false; -} - -// Create text input in place of a slider (when CTRL+Clicking on slider) -bool ImGui::InputScalarAsWidgetReplacement(const ImRect& aabb, const char* label, ImGuiDataType data_type, void* data_ptr, ImGuiID id, int decimal_precision) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - // Our replacement widget will override the focus ID (registered previously to allow for a TAB focus to happen) - SetActiveID(g.ScalarAsInputTextId, window); - SetHoveredID(0); - FocusableItemUnregister(window); - - char buf[32]; - DataTypeFormatString(data_type, data_ptr, decimal_precision, buf, IM_ARRAYSIZE(buf)); - bool text_value_changed = InputTextEx(label, buf, IM_ARRAYSIZE(buf), aabb.GetSize(), ImGuiInputTextFlags_CharsDecimal | ImGuiInputTextFlags_AutoSelectAll); - if (g.ScalarAsInputTextId == 0) - { - // First frame - IM_ASSERT(g.ActiveId == id); // InputText ID expected to match the Slider ID (else we'd need to store them both, which is also possible) - g.ScalarAsInputTextId = g.ActiveId; - SetHoveredID(id); - } - else if (g.ActiveId != g.ScalarAsInputTextId) - { - // Release - g.ScalarAsInputTextId = 0; - } - if (text_value_changed) - return DataTypeApplyOpFromText(buf, GImGui->InputTextState.InitialText.begin(), data_type, data_ptr, NULL); - return false; -} - -// Parse display precision back from the display format string -int ImGui::ParseFormatPrecision(const char* fmt, int default_precision) -{ - int precision = default_precision; - while ((fmt = strchr(fmt, '%')) != NULL) - { - fmt++; - if (fmt[0] == '%') { fmt++; continue; } // Ignore "%%" - while (*fmt >= '0' && *fmt <= '9') - fmt++; - if (*fmt == '.') - { - precision = atoi(fmt + 1); - if (precision < 0 || precision > 10) - precision = default_precision; - } - break; - } - return precision; -} - -float ImGui::RoundScalar(float value, int decimal_precision) -{ - // Round past decimal precision - // So when our value is 1.99999 with a precision of 0.001 we'll end up rounding to 2.0 - // FIXME: Investigate better rounding methods - static const float min_steps[10] = { 1.0f, 0.1f, 0.01f, 0.001f, 0.0001f, 0.00001f, 0.000001f, 0.0000001f, 0.00000001f, 0.000000001f }; - float min_step = (decimal_precision >= 0 && decimal_precision < 10) ? min_steps[decimal_precision] : powf(10.0f, (float)-decimal_precision); - bool negative = value < 0.0f; - value = fabsf(value); - float remainder = fmodf(value, min_step); - if (remainder <= min_step*0.5f) - value -= remainder; - else - value += (min_step - remainder); - return negative ? -value : value; -} - -bool ImGui::SliderBehavior(const ImRect& frame_bb, ImGuiID id, float* v, float v_min, float v_max, float power, int decimal_precision, ImGuiSliderFlags flags) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - const ImGuiStyle& style = g.Style; - - // Draw frame - RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - - const bool is_non_linear = fabsf(power - 1.0f) > 0.0001f; - const bool is_horizontal = (flags & ImGuiSliderFlags_Vertical) == 0; - - const float grab_padding = 2.0f; - const float slider_sz = is_horizontal ? (frame_bb.GetWidth() - grab_padding * 2.0f) : (frame_bb.GetHeight() - grab_padding * 2.0f); - float grab_sz; - if (decimal_precision > 0) - grab_sz = ImMin(style.GrabMinSize, slider_sz); - else - grab_sz = ImMin(ImMax(1.0f * (slider_sz / (v_max-v_min+1.0f)), style.GrabMinSize), slider_sz); // Integer sliders, if possible have the grab size represent 1 unit - const float slider_usable_sz = slider_sz - grab_sz; - const float slider_usable_pos_min = (is_horizontal ? frame_bb.Min.x : frame_bb.Min.y) + grab_padding + grab_sz*0.5f; - const float slider_usable_pos_max = (is_horizontal ? frame_bb.Max.x : frame_bb.Max.y) - grab_padding - grab_sz*0.5f; - - // For logarithmic sliders that cross over sign boundary we want the exponential increase to be symmetric around 0.0f - float linear_zero_pos = 0.0f; // 0.0->1.0f - if (v_min * v_max < 0.0f) - { - // Different sign - const float linear_dist_min_to_0 = powf(fabsf(0.0f - v_min), 1.0f/power); - const float linear_dist_max_to_0 = powf(fabsf(v_max - 0.0f), 1.0f/power); - linear_zero_pos = linear_dist_min_to_0 / (linear_dist_min_to_0+linear_dist_max_to_0); - } - else - { - // Same sign - linear_zero_pos = v_min < 0.0f ? 1.0f : 0.0f; - } - - // Process clicking on the slider - bool value_changed = false; - if (g.ActiveId == id) - { - if (g.IO.MouseDown[0]) - { - const float mouse_abs_pos = is_horizontal ? g.IO.MousePos.x : g.IO.MousePos.y; - float normalized_pos = ImClamp((mouse_abs_pos - slider_usable_pos_min) / slider_usable_sz, 0.0f, 1.0f); - if (!is_horizontal) - normalized_pos = 1.0f - normalized_pos; - - float new_value; - if (is_non_linear) - { - // Account for logarithmic scale on both sides of the zero - if (normalized_pos < linear_zero_pos) - { - // Negative: rescale to the negative range before powering - float a = 1.0f - (normalized_pos / linear_zero_pos); - a = powf(a, power); - new_value = ImLerp(ImMin(v_max,0.0f), v_min, a); - } - else - { - // Positive: rescale to the positive range before powering - float a; - if (fabsf(linear_zero_pos - 1.0f) > 1.e-6f) - a = (normalized_pos - linear_zero_pos) / (1.0f - linear_zero_pos); - else - a = normalized_pos; - a = powf(a, power); - new_value = ImLerp(ImMax(v_min,0.0f), v_max, a); - } - } - else - { - // Linear slider - new_value = ImLerp(v_min, v_max, normalized_pos); - } - - // Round past decimal precision - new_value = RoundScalar(new_value, decimal_precision); - if (*v != new_value) - { - *v = new_value; - value_changed = true; - } - } - else - { - SetActiveID(0); - } - } - - // Calculate slider grab positioning - float grab_t; - if (is_non_linear) - { - float v_clamped = ImClamp(*v, v_min, v_max); - if (v_clamped < 0.0f) - { - const float f = 1.0f - (v_clamped - v_min) / (ImMin(0.0f,v_max) - v_min); - grab_t = (1.0f - powf(f, 1.0f/power)) * linear_zero_pos; - } - else - { - const float f = (v_clamped - ImMax(0.0f,v_min)) / (v_max - ImMax(0.0f,v_min)); - grab_t = linear_zero_pos + powf(f, 1.0f/power) * (1.0f - linear_zero_pos); - } - } - else - { - // Linear slider - grab_t = (ImClamp(*v, v_min, v_max) - v_min) / (v_max - v_min); - } - - // Draw - if (!is_horizontal) - grab_t = 1.0f - grab_t; - const float grab_pos = ImLerp(slider_usable_pos_min, slider_usable_pos_max, grab_t); - ImRect grab_bb; - if (is_horizontal) - grab_bb = ImRect(ImVec2(grab_pos - grab_sz*0.5f, frame_bb.Min.y + grab_padding), ImVec2(grab_pos + grab_sz*0.5f, frame_bb.Max.y - grab_padding)); - else - grab_bb = ImRect(ImVec2(frame_bb.Min.x + grab_padding, grab_pos - grab_sz*0.5f), ImVec2(frame_bb.Max.x - grab_padding, grab_pos + grab_sz*0.5f)); - window->DrawList->AddRectFilled(grab_bb.Min, grab_bb.Max, GetColorU32(g.ActiveId == id ? ImGuiCol_SliderGrabActive : ImGuiCol_SliderGrab), style.GrabRounding); - - return value_changed; -} - -// Use power!=1.0 for logarithmic sliders. -// Adjust display_format to decorate the value with a prefix or a suffix. -// "%.3f" 1.234 -// "%5.2f secs" 01.23 secs -// "Gold: %.0f" Gold: 1 -bool ImGui::SliderFloat(const char* label, float* v, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const float w = CalcItemWidth(); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2.0f)); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - - // NB- we don't call ItemSize() yet because we may turn into a text edit box below - if (!ItemAdd(total_bb, &id)) - { - ItemSize(total_bb, style.FramePadding.y); - return false; - } - - const bool hovered = IsHovered(frame_bb, id); - if (hovered) - SetHoveredID(id); - - if (!display_format) - display_format = "%.3f"; - int decimal_precision = ParseFormatPrecision(display_format, 3); - - // Tabbing or CTRL-clicking on Slider turns it into an input box - bool start_text_input = false; - const bool tab_focus_requested = FocusableItemRegister(window, g.ActiveId == id); - if (tab_focus_requested || (hovered && g.IO.MouseClicked[0])) - { - SetActiveID(id, window); - FocusWindow(window); - - if (tab_focus_requested || g.IO.KeyCtrl) - { - start_text_input = true; - g.ScalarAsInputTextId = 0; - } - } - if (start_text_input || (g.ActiveId == id && g.ScalarAsInputTextId == id)) - return InputScalarAsWidgetReplacement(frame_bb, label, ImGuiDataType_Float, v, id, decimal_precision); - - ItemSize(total_bb, style.FramePadding.y); - - // Actual slider behavior + render grab - const bool value_changed = SliderBehavior(frame_bb, id, v, v_min, v_max, power, decimal_precision); - - // Display value using user-provided display format so user can add prefix/suffix/decorations to the value. - char value_buf[64]; - const char* value_buf_end = value_buf + ImFormatString(value_buf, IM_ARRAYSIZE(value_buf), display_format, *v); - RenderTextClipped(frame_bb.Min, frame_bb.Max, value_buf, value_buf_end, NULL, ImVec2(0.5f,0.5f)); - - if (label_size.x > 0.0f) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - return value_changed; -} - -bool ImGui::VSliderFloat(const char* label, const ImVec2& size, float* v, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + size); - const ImRect bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - - ItemSize(bb, style.FramePadding.y); - if (!ItemAdd(frame_bb, &id)) - return false; - - const bool hovered = IsHovered(frame_bb, id); - if (hovered) - SetHoveredID(id); - - if (!display_format) - display_format = "%.3f"; - int decimal_precision = ParseFormatPrecision(display_format, 3); - - if (hovered && g.IO.MouseClicked[0]) - { - SetActiveID(id, window); - FocusWindow(window); - } - - // Actual slider behavior + render grab - bool value_changed = SliderBehavior(frame_bb, id, v, v_min, v_max, power, decimal_precision, ImGuiSliderFlags_Vertical); - - // Display value using user-provided display format so user can add prefix/suffix/decorations to the value. - // For the vertical slider we allow centered text to overlap the frame padding - char value_buf[64]; - char* value_buf_end = value_buf + ImFormatString(value_buf, IM_ARRAYSIZE(value_buf), display_format, *v); - RenderTextClipped(ImVec2(frame_bb.Min.x, frame_bb.Min.y + style.FramePadding.y), frame_bb.Max, value_buf, value_buf_end, NULL, ImVec2(0.5f,0.0f)); - if (label_size.x > 0.0f) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - return value_changed; -} - -bool ImGui::SliderAngle(const char* label, float* v_rad, float v_degrees_min, float v_degrees_max) -{ - float v_deg = (*v_rad) * 360.0f / (2*IM_PI); - bool value_changed = SliderFloat(label, &v_deg, v_degrees_min, v_degrees_max, "%.0f deg", 1.0f); - *v_rad = v_deg * (2*IM_PI) / 360.0f; - return value_changed; -} - -bool ImGui::SliderInt(const char* label, int* v, int v_min, int v_max, const char* display_format) -{ - if (!display_format) - display_format = "%.0f"; - float v_f = (float)*v; - bool value_changed = SliderFloat(label, &v_f, (float)v_min, (float)v_max, display_format, 1.0f); - *v = (int)v_f; - return value_changed; -} - -bool ImGui::VSliderInt(const char* label, const ImVec2& size, int* v, int v_min, int v_max, const char* display_format) -{ - if (!display_format) - display_format = "%.0f"; - float v_f = (float)*v; - bool value_changed = VSliderFloat(label, size, &v_f, (float)v_min, (float)v_max, display_format, 1.0f); - *v = (int)v_f; - return value_changed; -} - -// Add multiple sliders on 1 line for compact edition of multiple components -bool ImGui::SliderFloatN(const char* label, float* v, int components, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= SliderFloat("##v", &v[i], v_min, v_max, display_format, power); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::SliderFloat2(const char* label, float v[2], float v_min, float v_max, const char* display_format, float power) -{ - return SliderFloatN(label, v, 2, v_min, v_max, display_format, power); -} - -bool ImGui::SliderFloat3(const char* label, float v[3], float v_min, float v_max, const char* display_format, float power) -{ - return SliderFloatN(label, v, 3, v_min, v_max, display_format, power); -} - -bool ImGui::SliderFloat4(const char* label, float v[4], float v_min, float v_max, const char* display_format, float power) -{ - return SliderFloatN(label, v, 4, v_min, v_max, display_format, power); -} - -bool ImGui::SliderIntN(const char* label, int* v, int components, int v_min, int v_max, const char* display_format) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= SliderInt("##v", &v[i], v_min, v_max, display_format); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::SliderInt2(const char* label, int v[2], int v_min, int v_max, const char* display_format) -{ - return SliderIntN(label, v, 2, v_min, v_max, display_format); -} - -bool ImGui::SliderInt3(const char* label, int v[3], int v_min, int v_max, const char* display_format) -{ - return SliderIntN(label, v, 3, v_min, v_max, display_format); -} - -bool ImGui::SliderInt4(const char* label, int v[4], int v_min, int v_max, const char* display_format) -{ - return SliderIntN(label, v, 4, v_min, v_max, display_format); -} - -bool ImGui::DragBehavior(const ImRect& frame_bb, ImGuiID id, float* v, float v_speed, float v_min, float v_max, int decimal_precision, float power) -{ - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - // Draw frame - const ImU32 frame_col = GetColorU32(g.ActiveId == id ? ImGuiCol_FrameBgActive : g.HoveredId == id ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg); - RenderFrame(frame_bb.Min, frame_bb.Max, frame_col, true, style.FrameRounding); - - bool value_changed = false; - - // Process clicking on the drag - if (g.ActiveId == id) - { - if (g.IO.MouseDown[0]) - { - if (g.ActiveIdIsJustActivated) - { - // Lock current value on click - g.DragCurrentValue = *v; - g.DragLastMouseDelta = ImVec2(0.f, 0.f); - } - - float v_cur = g.DragCurrentValue; - const ImVec2 mouse_drag_delta = GetMouseDragDelta(0, 1.0f); - if (fabsf(mouse_drag_delta.x - g.DragLastMouseDelta.x) > 0.0f) - { - float speed = v_speed; - if (speed == 0.0f && (v_max - v_min) != 0.0f && (v_max - v_min) < FLT_MAX) - speed = (v_max - v_min) * g.DragSpeedDefaultRatio; - if (g.IO.KeyShift && g.DragSpeedScaleFast >= 0.0f) - speed = speed * g.DragSpeedScaleFast; - if (g.IO.KeyAlt && g.DragSpeedScaleSlow >= 0.0f) - speed = speed * g.DragSpeedScaleSlow; - - float delta = (mouse_drag_delta.x - g.DragLastMouseDelta.x) * speed; - if (fabsf(power - 1.0f) > 0.001f) - { - // Logarithmic curve on both side of 0.0 - float v0_abs = v_cur >= 0.0f ? v_cur : -v_cur; - float v0_sign = v_cur >= 0.0f ? 1.0f : -1.0f; - float v1 = powf(v0_abs, 1.0f / power) + (delta * v0_sign); - float v1_abs = v1 >= 0.0f ? v1 : -v1; - float v1_sign = v1 >= 0.0f ? 1.0f : -1.0f; // Crossed sign line - v_cur = powf(v1_abs, power) * v0_sign * v1_sign; // Reapply sign - } - else - { - v_cur += delta; - } - g.DragLastMouseDelta.x = mouse_drag_delta.x; - - // Clamp - if (v_min < v_max) - v_cur = ImClamp(v_cur, v_min, v_max); - g.DragCurrentValue = v_cur; - } - - // Round to user desired precision, then apply - v_cur = RoundScalar(v_cur, decimal_precision); - if (*v != v_cur) - { - *v = v_cur; - value_changed = true; - } - } - else - { - SetActiveID(0); - } - } - - return value_changed; -} - -bool ImGui::DragFloat(const char* label, float* v, float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const float w = CalcItemWidth(); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2.0f)); - const ImRect inner_bb(frame_bb.Min + style.FramePadding, frame_bb.Max - style.FramePadding); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - - // NB- we don't call ItemSize() yet because we may turn into a text edit box below - if (!ItemAdd(total_bb, &id)) - { - ItemSize(total_bb, style.FramePadding.y); - return false; - } - - const bool hovered = IsHovered(frame_bb, id); - if (hovered) - SetHoveredID(id); - - if (!display_format) - display_format = "%.3f"; - int decimal_precision = ParseFormatPrecision(display_format, 3); - - // Tabbing or CTRL-clicking on Drag turns it into an input box - bool start_text_input = false; - const bool tab_focus_requested = FocusableItemRegister(window, g.ActiveId == id); - if (tab_focus_requested || (hovered && (g.IO.MouseClicked[0] | g.IO.MouseDoubleClicked[0]))) - { - SetActiveID(id, window); - FocusWindow(window); - - if (tab_focus_requested || g.IO.KeyCtrl || g.IO.MouseDoubleClicked[0]) - { - start_text_input = true; - g.ScalarAsInputTextId = 0; - } - } - if (start_text_input || (g.ActiveId == id && g.ScalarAsInputTextId == id)) - return InputScalarAsWidgetReplacement(frame_bb, label, ImGuiDataType_Float, v, id, decimal_precision); - - // Actual drag behavior - ItemSize(total_bb, style.FramePadding.y); - const bool value_changed = DragBehavior(frame_bb, id, v, v_speed, v_min, v_max, decimal_precision, power); - - // Display value using user-provided display format so user can add prefix/suffix/decorations to the value. - char value_buf[64]; - const char* value_buf_end = value_buf + ImFormatString(value_buf, IM_ARRAYSIZE(value_buf), display_format, *v); - RenderTextClipped(frame_bb.Min, frame_bb.Max, value_buf, value_buf_end, NULL, ImVec2(0.5f,0.5f)); - - if (label_size.x > 0.0f) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, inner_bb.Min.y), label); - - return value_changed; -} - -bool ImGui::DragFloatN(const char* label, float* v, int components, float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= DragFloat("##v", &v[i], v_speed, v_min, v_max, display_format, power); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::DragFloat2(const char* label, float v[2], float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - return DragFloatN(label, v, 2, v_speed, v_min, v_max, display_format, power); -} - -bool ImGui::DragFloat3(const char* label, float v[3], float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - return DragFloatN(label, v, 3, v_speed, v_min, v_max, display_format, power); -} - -bool ImGui::DragFloat4(const char* label, float v[4], float v_speed, float v_min, float v_max, const char* display_format, float power) -{ - return DragFloatN(label, v, 4, v_speed, v_min, v_max, display_format, power); -} - -bool ImGui::DragFloatRange2(const char* label, float* v_current_min, float* v_current_max, float v_speed, float v_min, float v_max, const char* display_format, const char* display_format_max, float power) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - PushID(label); - BeginGroup(); - PushMultiItemsWidths(2); - - bool value_changed = DragFloat("##min", v_current_min, v_speed, (v_min >= v_max) ? -FLT_MAX : v_min, (v_min >= v_max) ? *v_current_max : ImMin(v_max, *v_current_max), display_format, power); - PopItemWidth(); - SameLine(0, g.Style.ItemInnerSpacing.x); - value_changed |= DragFloat("##max", v_current_max, v_speed, (v_min >= v_max) ? *v_current_min : ImMax(v_min, *v_current_min), (v_min >= v_max) ? FLT_MAX : v_max, display_format_max ? display_format_max : display_format, power); - PopItemWidth(); - SameLine(0, g.Style.ItemInnerSpacing.x); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - PopID(); - - return value_changed; -} - -// NB: v_speed is float to allow adjusting the drag speed with more precision -bool ImGui::DragInt(const char* label, int* v, float v_speed, int v_min, int v_max, const char* display_format) -{ - if (!display_format) - display_format = "%.0f"; - float v_f = (float)*v; - bool value_changed = DragFloat(label, &v_f, v_speed, (float)v_min, (float)v_max, display_format); - *v = (int)v_f; - return value_changed; -} - -bool ImGui::DragIntN(const char* label, int* v, int components, float v_speed, int v_min, int v_max, const char* display_format) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= DragInt("##v", &v[i], v_speed, v_min, v_max, display_format); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::DragInt2(const char* label, int v[2], float v_speed, int v_min, int v_max, const char* display_format) -{ - return DragIntN(label, v, 2, v_speed, v_min, v_max, display_format); -} - -bool ImGui::DragInt3(const char* label, int v[3], float v_speed, int v_min, int v_max, const char* display_format) -{ - return DragIntN(label, v, 3, v_speed, v_min, v_max, display_format); -} - -bool ImGui::DragInt4(const char* label, int v[4], float v_speed, int v_min, int v_max, const char* display_format) -{ - return DragIntN(label, v, 4, v_speed, v_min, v_max, display_format); -} - -bool ImGui::DragIntRange2(const char* label, int* v_current_min, int* v_current_max, float v_speed, int v_min, int v_max, const char* display_format, const char* display_format_max) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - PushID(label); - BeginGroup(); - PushMultiItemsWidths(2); - - bool value_changed = DragInt("##min", v_current_min, v_speed, (v_min >= v_max) ? INT_MIN : v_min, (v_min >= v_max) ? *v_current_max : ImMin(v_max, *v_current_max), display_format); - PopItemWidth(); - SameLine(0, g.Style.ItemInnerSpacing.x); - value_changed |= DragInt("##max", v_current_max, v_speed, (v_min >= v_max) ? *v_current_min : ImMax(v_min, *v_current_min), (v_min >= v_max) ? INT_MAX : v_max, display_format_max ? display_format_max : display_format); - PopItemWidth(); - SameLine(0, g.Style.ItemInnerSpacing.x); - - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - PopID(); - - return value_changed; -} - -void ImGui::PlotEx(ImGuiPlotType plot_type, const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - if (graph_size.x == 0.0f) - graph_size.x = CalcItemWidth(); - if (graph_size.y == 0.0f) - graph_size.y = label_size.y + (style.FramePadding.y * 2); - - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(graph_size.x, graph_size.y)); - const ImRect inner_bb(frame_bb.Min + style.FramePadding, frame_bb.Max - style.FramePadding); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0)); - ItemSize(total_bb, style.FramePadding.y); - if (!ItemAdd(total_bb, NULL)) - return; - - // Determine scale from values if not specified - if (scale_min == FLT_MAX || scale_max == FLT_MAX) - { - float v_min = FLT_MAX; - float v_max = -FLT_MAX; - for (int i = 0; i < values_count; i++) - { - const float v = values_getter(data, i); - v_min = ImMin(v_min, v); - v_max = ImMax(v_max, v); - } - if (scale_min == FLT_MAX) - scale_min = v_min; - if (scale_max == FLT_MAX) - scale_max = v_max; - } - - RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - - int res_w = ImMin((int)graph_size.x, values_count) + ((plot_type == ImGuiPlotType_Lines) ? -1 : 0); - int item_count = values_count + ((plot_type == ImGuiPlotType_Lines) ? -1 : 0); - - // Tooltip on hover - int v_hovered = -1; - if (IsHovered(inner_bb, 0)) - { - const float t = ImClamp((g.IO.MousePos.x - inner_bb.Min.x) / (inner_bb.Max.x - inner_bb.Min.x), 0.0f, 0.9999f); - const int v_idx = (int)(t * item_count); - IM_ASSERT(v_idx >= 0 && v_idx < values_count); - - const float v0 = values_getter(data, (v_idx + values_offset) % values_count); - const float v1 = values_getter(data, (v_idx + 1 + values_offset) % values_count); - if (plot_type == ImGuiPlotType_Lines) - SetTooltip("%d: %8.4g\n%d: %8.4g", v_idx, v0, v_idx+1, v1); - else if (plot_type == ImGuiPlotType_Histogram) - SetTooltip("%d: %8.4g", v_idx, v0); - v_hovered = v_idx; - } - - const float t_step = 1.0f / (float)res_w; - - float v0 = values_getter(data, (0 + values_offset) % values_count); - float t0 = 0.0f; - ImVec2 tp0 = ImVec2( t0, 1.0f - ImSaturate((v0 - scale_min) / (scale_max - scale_min)) ); // Point in the normalized space of our target rectangle - - const ImU32 col_base = GetColorU32((plot_type == ImGuiPlotType_Lines) ? ImGuiCol_PlotLines : ImGuiCol_PlotHistogram); - const ImU32 col_hovered = GetColorU32((plot_type == ImGuiPlotType_Lines) ? ImGuiCol_PlotLinesHovered : ImGuiCol_PlotHistogramHovered); - - for (int n = 0; n < res_w; n++) - { - const float t1 = t0 + t_step; - const int v1_idx = (int)(t0 * item_count + 0.5f); - IM_ASSERT(v1_idx >= 0 && v1_idx < values_count); - const float v1 = values_getter(data, (v1_idx + values_offset + 1) % values_count); - const ImVec2 tp1 = ImVec2( t1, 1.0f - ImSaturate((v1 - scale_min) / (scale_max - scale_min)) ); - - // NB: Draw calls are merged together by the DrawList system. Still, we should render our batch are lower level to save a bit of CPU. - ImVec2 pos0 = ImLerp(inner_bb.Min, inner_bb.Max, tp0); - ImVec2 pos1 = ImLerp(inner_bb.Min, inner_bb.Max, (plot_type == ImGuiPlotType_Lines) ? tp1 : ImVec2(tp1.x, 1.0f)); - if (plot_type == ImGuiPlotType_Lines) - { - window->DrawList->AddLine(pos0, pos1, v_hovered == v1_idx ? col_hovered : col_base); - } - else if (plot_type == ImGuiPlotType_Histogram) - { - if (pos1.x >= pos0.x + 2.0f) - pos1.x -= 1.0f; - window->DrawList->AddRectFilled(pos0, pos1, v_hovered == v1_idx ? col_hovered : col_base); - } - - t0 = t1; - tp0 = tp1; - } - - // Text overlay - if (overlay_text) - RenderTextClipped(ImVec2(frame_bb.Min.x, frame_bb.Min.y + style.FramePadding.y), frame_bb.Max, overlay_text, NULL, NULL, ImVec2(0.5f,0.0f)); - - if (label_size.x > 0.0f) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, inner_bb.Min.y), label); -} - -struct ImGuiPlotArrayGetterData -{ - const float* Values; - int Stride; - - ImGuiPlotArrayGetterData(const float* values, int stride) { Values = values; Stride = stride; } -}; - -static float Plot_ArrayGetter(void* data, int idx) -{ - ImGuiPlotArrayGetterData* plot_data = (ImGuiPlotArrayGetterData*)data; - const float v = *(float*)(void*)((unsigned char*)plot_data->Values + (size_t)idx * plot_data->Stride); - return v; -} - -void ImGui::PlotLines(const char* label, const float* values, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size, int stride) -{ - ImGuiPlotArrayGetterData data(values, stride); - PlotEx(ImGuiPlotType_Lines, label, &Plot_ArrayGetter, (void*)&data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); -} - -void ImGui::PlotLines(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size) -{ - PlotEx(ImGuiPlotType_Lines, label, values_getter, data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); -} - -void ImGui::PlotHistogram(const char* label, const float* values, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size, int stride) -{ - ImGuiPlotArrayGetterData data(values, stride); - PlotEx(ImGuiPlotType_Histogram, label, &Plot_ArrayGetter, (void*)&data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); -} - -void ImGui::PlotHistogram(const char* label, float (*values_getter)(void* data, int idx), void* data, int values_count, int values_offset, const char* overlay_text, float scale_min, float scale_max, ImVec2 graph_size) -{ - PlotEx(ImGuiPlotType_Histogram, label, values_getter, data, values_count, values_offset, overlay_text, scale_min, scale_max, graph_size); -} - -// size_arg (for each axis) < 0.0f: align to end, 0.0f: auto, > 0.0f: specified size -void ImGui::ProgressBar(float fraction, const ImVec2& size_arg, const char* overlay) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - ImVec2 pos = window->DC.CursorPos; - ImRect bb(pos, pos + CalcItemSize(size_arg, CalcItemWidth(), g.FontSize + style.FramePadding.y*2.0f)); - ItemSize(bb, style.FramePadding.y); - if (!ItemAdd(bb, NULL)) - return; - - // Render - fraction = ImSaturate(fraction); - RenderFrame(bb.Min, bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - bb.Reduce(ImVec2(window->BorderSize, window->BorderSize)); - const ImVec2 fill_br = ImVec2(ImLerp(bb.Min.x, bb.Max.x, fraction), bb.Max.y); - RenderFrame(bb.Min, fill_br, GetColorU32(ImGuiCol_PlotHistogram), false, style.FrameRounding); - - // Default displaying the fraction as percentage string, but user can override it - char overlay_buf[32]; - if (!overlay) - { - ImFormatString(overlay_buf, IM_ARRAYSIZE(overlay_buf), "%.0f%%", fraction*100+0.01f); - overlay = overlay_buf; - } - - ImVec2 overlay_size = CalcTextSize(overlay, NULL); - if (overlay_size.x > 0.0f) - RenderTextClipped(ImVec2(ImClamp(fill_br.x + style.ItemSpacing.x, bb.Min.x, bb.Max.x - overlay_size.x - style.ItemInnerSpacing.x), bb.Min.y), bb.Max, overlay, NULL, &overlay_size, ImVec2(0.0f,0.5f), &bb); -} - -bool ImGui::Checkbox(const char* label, bool* v) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - const ImRect check_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(label_size.y + style.FramePadding.y*2, label_size.y + style.FramePadding.y*2)); - ItemSize(check_bb, style.FramePadding.y); - - ImRect total_bb = check_bb; - if (label_size.x > 0) - SameLine(0, style.ItemInnerSpacing.x); - const ImRect text_bb(window->DC.CursorPos + ImVec2(0,style.FramePadding.y), window->DC.CursorPos + ImVec2(0,style.FramePadding.y) + label_size); - if (label_size.x > 0) - { - ItemSize(ImVec2(text_bb.GetWidth(), check_bb.GetHeight()), style.FramePadding.y); - total_bb = ImRect(ImMin(check_bb.Min, text_bb.Min), ImMax(check_bb.Max, text_bb.Max)); - } - - if (!ItemAdd(total_bb, &id)) - return false; - - bool hovered, held; - bool pressed = ButtonBehavior(total_bb, id, &hovered, &held); - if (pressed) - *v = !(*v); - - RenderFrame(check_bb.Min, check_bb.Max, GetColorU32((held && hovered) ? ImGuiCol_FrameBgActive : hovered ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg), true, style.FrameRounding); - if (*v) - { - const float check_sz = ImMin(check_bb.GetWidth(), check_bb.GetHeight()); - const float pad = ImMax(1.0f, (float)(int)(check_sz / 6.0f)); - window->DrawList->AddRectFilled(check_bb.Min+ImVec2(pad,pad), check_bb.Max-ImVec2(pad,pad), GetColorU32(ImGuiCol_CheckMark), style.FrameRounding); - } - - if (g.LogEnabled) - LogRenderedText(text_bb.GetTL(), *v ? "[x]" : "[ ]"); - if (label_size.x > 0.0f) - RenderText(text_bb.GetTL(), label); - - return pressed; -} - -bool ImGui::CheckboxFlags(const char* label, unsigned int* flags, unsigned int flags_value) -{ - bool v = ((*flags & flags_value) == flags_value); - bool pressed = Checkbox(label, &v); - if (pressed) - { - if (v) - *flags |= flags_value; - else - *flags &= ~flags_value; - } - - return pressed; -} - -bool ImGui::RadioButton(const char* label, bool active) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - const ImRect check_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(label_size.y + style.FramePadding.y*2-1, label_size.y + style.FramePadding.y*2-1)); - ItemSize(check_bb, style.FramePadding.y); - - ImRect total_bb = check_bb; - if (label_size.x > 0) - SameLine(0, style.ItemInnerSpacing.x); - const ImRect text_bb(window->DC.CursorPos + ImVec2(0, style.FramePadding.y), window->DC.CursorPos + ImVec2(0, style.FramePadding.y) + label_size); - if (label_size.x > 0) - { - ItemSize(ImVec2(text_bb.GetWidth(), check_bb.GetHeight()), style.FramePadding.y); - total_bb.Add(text_bb); - } - - if (!ItemAdd(total_bb, &id)) - return false; - - ImVec2 center = check_bb.GetCenter(); - center.x = (float)(int)center.x + 0.5f; - center.y = (float)(int)center.y + 0.5f; - const float radius = check_bb.GetHeight() * 0.5f; - - bool hovered, held; - bool pressed = ButtonBehavior(total_bb, id, &hovered, &held); - - window->DrawList->AddCircleFilled(center, radius, GetColorU32((held && hovered) ? ImGuiCol_FrameBgActive : hovered ? ImGuiCol_FrameBgHovered : ImGuiCol_FrameBg), 16); - if (active) - { - const float check_sz = ImMin(check_bb.GetWidth(), check_bb.GetHeight()); - const float pad = ImMax(1.0f, (float)(int)(check_sz / 6.0f)); - window->DrawList->AddCircleFilled(center, radius-pad, GetColorU32(ImGuiCol_CheckMark), 16); - } - - if (window->Flags & ImGuiWindowFlags_ShowBorders) - { - window->DrawList->AddCircle(center+ImVec2(1,1), radius, GetColorU32(ImGuiCol_BorderShadow), 16); - window->DrawList->AddCircle(center, radius, GetColorU32(ImGuiCol_Border), 16); - } - - if (g.LogEnabled) - LogRenderedText(text_bb.GetTL(), active ? "(x)" : "( )"); - if (label_size.x > 0.0f) - RenderText(text_bb.GetTL(), label); - - return pressed; -} - -bool ImGui::RadioButton(const char* label, int* v, int v_button) -{ - const bool pressed = RadioButton(label, *v == v_button); - if (pressed) - { - *v = v_button; - } - return pressed; -} - -static int InputTextCalcTextLenAndLineCount(const char* text_begin, const char** out_text_end) -{ - int line_count = 0; - const char* s = text_begin; - while (char c = *s++) // We are only matching for \n so we can ignore UTF-8 decoding - if (c == '\n') - line_count++; - s--; - if (s[0] != '\n' && s[0] != '\r') - line_count++; - *out_text_end = s; - return line_count; -} - -static ImVec2 InputTextCalcTextSizeW(const ImWchar* text_begin, const ImWchar* text_end, const ImWchar** remaining, ImVec2* out_offset, bool stop_on_new_line) -{ - ImFont* font = GImGui->Font; - const float line_height = GImGui->FontSize; - const float scale = line_height / font->FontSize; - - ImVec2 text_size = ImVec2(0,0); - float line_width = 0.0f; - - const ImWchar* s = text_begin; - while (s < text_end) - { - unsigned int c = (unsigned int)(*s++); - if (c == '\n') - { - text_size.x = ImMax(text_size.x, line_width); - text_size.y += line_height; - line_width = 0.0f; - if (stop_on_new_line) - break; - continue; - } - if (c == '\r') - continue; - - const float char_width = font->GetCharAdvance((unsigned short)c) * scale; - line_width += char_width; - } - - if (text_size.x < line_width) - text_size.x = line_width; - - if (out_offset) - *out_offset = ImVec2(line_width, text_size.y + line_height); // offset allow for the possibility of sitting after a trailing \n - - if (line_width > 0 || text_size.y == 0.0f) // whereas size.y will ignore the trailing \n - text_size.y += line_height; - - if (remaining) - *remaining = s; - - return text_size; -} - -// Wrapper for stb_textedit.h to edit text (our wrapper is for: statically sized buffer, single-line, wchar characters. InputText converts between UTF-8 and wchar) -namespace ImGuiStb -{ - -static int STB_TEXTEDIT_STRINGLEN(const STB_TEXTEDIT_STRING* obj) { return obj->CurLenW; } -static ImWchar STB_TEXTEDIT_GETCHAR(const STB_TEXTEDIT_STRING* obj, int idx) { return obj->Text[idx]; } -static float STB_TEXTEDIT_GETWIDTH(STB_TEXTEDIT_STRING* obj, int line_start_idx, int char_idx) { ImWchar c = obj->Text[line_start_idx+char_idx]; if (c == '\n') return STB_TEXTEDIT_GETWIDTH_NEWLINE; return GImGui->Font->GetCharAdvance(c) * (GImGui->FontSize / GImGui->Font->FontSize); } -static int STB_TEXTEDIT_KEYTOTEXT(int key) { return key >= 0x10000 ? 0 : key; } -static ImWchar STB_TEXTEDIT_NEWLINE = '\n'; -static void STB_TEXTEDIT_LAYOUTROW(StbTexteditRow* r, STB_TEXTEDIT_STRING* obj, int line_start_idx) -{ - const ImWchar* text = obj->Text.Data; - const ImWchar* text_remaining = NULL; - const ImVec2 size = InputTextCalcTextSizeW(text + line_start_idx, text + obj->CurLenW, &text_remaining, NULL, true); - r->x0 = 0.0f; - r->x1 = size.x; - r->baseline_y_delta = size.y; - r->ymin = 0.0f; - r->ymax = size.y; - r->num_chars = (int)(text_remaining - (text + line_start_idx)); -} - -static bool is_separator(unsigned int c) { return ImCharIsSpace(c) || c==',' || c==';' || c=='(' || c==')' || c=='{' || c=='}' || c=='[' || c==']' || c=='|'; } -static int is_word_boundary_from_right(STB_TEXTEDIT_STRING* obj, int idx) { return idx > 0 ? (is_separator( obj->Text[idx-1] ) && !is_separator( obj->Text[idx] ) ) : 1; } -static int STB_TEXTEDIT_MOVEWORDLEFT_IMPL(STB_TEXTEDIT_STRING* obj, int idx) { while (idx >= 0 && !is_word_boundary_from_right(obj, idx)) idx--; return idx < 0 ? 0 : idx; } -#ifdef __APPLE__ // FIXME: Move setting to IO structure -static int is_word_boundary_from_left(STB_TEXTEDIT_STRING* obj, int idx) { return idx > 0 ? (!is_separator( obj->Text[idx-1] ) && is_separator( obj->Text[idx] ) ) : 1; } -static int STB_TEXTEDIT_MOVEWORDRIGHT_IMPL(STB_TEXTEDIT_STRING* obj, int idx) { int len = obj->CurLenW; while (idx < len && !is_word_boundary_from_left(obj, idx)) idx++; return idx > len ? len : idx; } -#else -static int STB_TEXTEDIT_MOVEWORDRIGHT_IMPL(STB_TEXTEDIT_STRING* obj, int idx) { int len = obj->CurLenW; while (idx < len && !is_word_boundary_from_right(obj, idx)) idx++; return idx > len ? len : idx; } -#endif -#define STB_TEXTEDIT_MOVEWORDLEFT STB_TEXTEDIT_MOVEWORDLEFT_IMPL // They need to be #define for stb_textedit.h -#define STB_TEXTEDIT_MOVEWORDRIGHT STB_TEXTEDIT_MOVEWORDRIGHT_IMPL - -static void STB_TEXTEDIT_DELETECHARS(STB_TEXTEDIT_STRING* obj, int pos, int n) -{ - ImWchar* dst = obj->Text.Data + pos; - - // We maintain our buffer length in both UTF-8 and wchar formats - obj->CurLenA -= ImTextCountUtf8BytesFromStr(dst, dst + n); - obj->CurLenW -= n; - - // Offset remaining text - const ImWchar* src = obj->Text.Data + pos + n; - while (ImWchar c = *src++) - *dst++ = c; - *dst = '\0'; -} - -static bool STB_TEXTEDIT_INSERTCHARS(STB_TEXTEDIT_STRING* obj, int pos, const ImWchar* new_text, int new_text_len) -{ - const int text_len = obj->CurLenW; - IM_ASSERT(pos <= text_len); - if (new_text_len + text_len + 1 > obj->Text.Size) - return false; - - const int new_text_len_utf8 = ImTextCountUtf8BytesFromStr(new_text, new_text + new_text_len); - if (new_text_len_utf8 + obj->CurLenA + 1 > obj->BufSizeA) - return false; - - ImWchar* text = obj->Text.Data; - if (pos != text_len) - memmove(text + pos + new_text_len, text + pos, (size_t)(text_len - pos) * sizeof(ImWchar)); - memcpy(text + pos, new_text, (size_t)new_text_len * sizeof(ImWchar)); - - obj->CurLenW += new_text_len; - obj->CurLenA += new_text_len_utf8; - obj->Text[obj->CurLenW] = '\0'; - - return true; -} - -// We don't use an enum so we can build even with conflicting symbols (if another user of stb_textedit.h leak their STB_TEXTEDIT_K_* symbols) -#define STB_TEXTEDIT_K_LEFT 0x10000 // keyboard input to move cursor left -#define STB_TEXTEDIT_K_RIGHT 0x10001 // keyboard input to move cursor right -#define STB_TEXTEDIT_K_UP 0x10002 // keyboard input to move cursor up -#define STB_TEXTEDIT_K_DOWN 0x10003 // keyboard input to move cursor down -#define STB_TEXTEDIT_K_LINESTART 0x10004 // keyboard input to move cursor to start of line -#define STB_TEXTEDIT_K_LINEEND 0x10005 // keyboard input to move cursor to end of line -#define STB_TEXTEDIT_K_TEXTSTART 0x10006 // keyboard input to move cursor to start of text -#define STB_TEXTEDIT_K_TEXTEND 0x10007 // keyboard input to move cursor to end of text -#define STB_TEXTEDIT_K_DELETE 0x10008 // keyboard input to delete selection or character under cursor -#define STB_TEXTEDIT_K_BACKSPACE 0x10009 // keyboard input to delete selection or character left of cursor -#define STB_TEXTEDIT_K_UNDO 0x1000A // keyboard input to perform undo -#define STB_TEXTEDIT_K_REDO 0x1000B // keyboard input to perform redo -#define STB_TEXTEDIT_K_WORDLEFT 0x1000C // keyboard input to move cursor left one word -#define STB_TEXTEDIT_K_WORDRIGHT 0x1000D // keyboard input to move cursor right one word -#define STB_TEXTEDIT_K_SHIFT 0x20000 - -#define STB_TEXTEDIT_IMPLEMENTATION -#include "stb_textedit.h" - -} - -void ImGuiTextEditState::OnKeyPressed(int key) -{ - stb_textedit_key(this, &StbState, key); - CursorFollow = true; - CursorAnimReset(); -} - -// Public API to manipulate UTF-8 text -// We expose UTF-8 to the user (unlike the STB_TEXTEDIT_* functions which are manipulating wchar) -// FIXME: The existence of this rarely exercised code path is a bit of a nuisance. -void ImGuiTextEditCallbackData::DeleteChars(int pos, int bytes_count) -{ - IM_ASSERT(pos + bytes_count <= BufTextLen); - char* dst = Buf + pos; - const char* src = Buf + pos + bytes_count; - while (char c = *src++) - *dst++ = c; - *dst = '\0'; - - if (CursorPos + bytes_count >= pos) - CursorPos -= bytes_count; - else if (CursorPos >= pos) - CursorPos = pos; - SelectionStart = SelectionEnd = CursorPos; - BufDirty = true; - BufTextLen -= bytes_count; -} - -void ImGuiTextEditCallbackData::InsertChars(int pos, const char* new_text, const char* new_text_end) -{ - const int new_text_len = new_text_end ? (int)(new_text_end - new_text) : (int)strlen(new_text); - if (new_text_len + BufTextLen + 1 >= BufSize) - return; - - if (BufTextLen != pos) - memmove(Buf + pos + new_text_len, Buf + pos, (size_t)(BufTextLen - pos)); - memcpy(Buf + pos, new_text, (size_t)new_text_len * sizeof(char)); - Buf[BufTextLen + new_text_len] = '\0'; - - if (CursorPos >= pos) - CursorPos += new_text_len; - SelectionStart = SelectionEnd = CursorPos; - BufDirty = true; - BufTextLen += new_text_len; -} - -// Return false to discard a character. -static bool InputTextFilterCharacter(unsigned int* p_char, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) -{ - unsigned int c = *p_char; - - if (c < 128 && c != ' ' && !isprint((int)(c & 0xFF))) - { - bool pass = false; - pass |= (c == '\n' && (flags & ImGuiInputTextFlags_Multiline)); - pass |= (c == '\t' && (flags & ImGuiInputTextFlags_AllowTabInput)); - if (!pass) - return false; - } - - if (c >= 0xE000 && c <= 0xF8FF) // Filter private Unicode range. I don't imagine anybody would want to input them. GLFW on OSX seems to send private characters for special keys like arrow keys. - return false; - - if (flags & (ImGuiInputTextFlags_CharsDecimal | ImGuiInputTextFlags_CharsHexadecimal | ImGuiInputTextFlags_CharsUppercase | ImGuiInputTextFlags_CharsNoBlank)) - { - if (flags & ImGuiInputTextFlags_CharsDecimal) - if (!(c >= '0' && c <= '9') && (c != '.') && (c != '-') && (c != '+') && (c != '*') && (c != '/')) - return false; - - if (flags & ImGuiInputTextFlags_CharsHexadecimal) - if (!(c >= '0' && c <= '9') && !(c >= 'a' && c <= 'f') && !(c >= 'A' && c <= 'F')) - return false; - - if (flags & ImGuiInputTextFlags_CharsUppercase) - if (c >= 'a' && c <= 'z') - *p_char = (c += (unsigned int)('A'-'a')); - - if (flags & ImGuiInputTextFlags_CharsNoBlank) - if (ImCharIsSpace(c)) - return false; - } - - if (flags & ImGuiInputTextFlags_CallbackCharFilter) - { - ImGuiTextEditCallbackData callback_data; - memset(&callback_data, 0, sizeof(ImGuiTextEditCallbackData)); - callback_data.EventFlag = ImGuiInputTextFlags_CallbackCharFilter; - callback_data.EventChar = (ImWchar)c; - callback_data.Flags = flags; - callback_data.UserData = user_data; - if (callback(&callback_data) != 0) - return false; - *p_char = callback_data.EventChar; - if (!callback_data.EventChar) - return false; - } - - return true; -} - -// Edit a string of text -// NB: when active, hold on a privately held copy of the text (and apply back to 'buf'). So changing 'buf' while active has no effect. -// FIXME: Rather messy function partly because we are doing UTF8 > u16 > UTF8 conversions on the go to more easily handle stb_textedit calls. Ideally we should stay in UTF-8 all the time. See https://github.com/nothings/stb/issues/188 -bool ImGui::InputTextEx(const char* label, char* buf, int buf_size, const ImVec2& size_arg, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - IM_ASSERT(!((flags & ImGuiInputTextFlags_CallbackHistory) && (flags & ImGuiInputTextFlags_Multiline))); // Can't use both together (they both use up/down keys) - IM_ASSERT(!((flags & ImGuiInputTextFlags_CallbackCompletion) && (flags & ImGuiInputTextFlags_AllowTabInput))); // Can't use both together (they both use tab key) - - ImGuiContext& g = *GImGui; - const ImGuiIO& io = g.IO; - const ImGuiStyle& style = g.Style; - - const bool is_multiline = (flags & ImGuiInputTextFlags_Multiline) != 0; - const bool is_editable = (flags & ImGuiInputTextFlags_ReadOnly) == 0; - const bool is_password = (flags & ImGuiInputTextFlags_Password) != 0; - - if (is_multiline) // Open group before calling GetID() because groups tracks id created during their spawn - BeginGroup(); - const ImGuiID id = window->GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - ImVec2 size = CalcItemSize(size_arg, CalcItemWidth(), (is_multiline ? GetTextLineHeight() * 8.0f : label_size.y) + style.FramePadding.y*2.0f); // Arbitrary default of 8 lines high for multi-line - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + size); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? (style.ItemInnerSpacing.x + label_size.x) : 0.0f, 0.0f)); - - ImGuiWindow* draw_window = window; - if (is_multiline) - { - if (!BeginChildFrame(id, frame_bb.GetSize())) - { - EndChildFrame(); - EndGroup(); - return false; - } - draw_window = GetCurrentWindow(); - size.x -= draw_window->ScrollbarSizes.x; - } - else - { - ItemSize(total_bb, style.FramePadding.y); - if (!ItemAdd(total_bb, &id)) - return false; - } - - // Password pushes a temporary font with only a fallback glyph - if (is_password) - { - const ImFont::Glyph* glyph = g.Font->FindGlyph('*'); - ImFont* password_font = &g.InputTextPasswordFont; - password_font->FontSize = g.Font->FontSize; - password_font->Scale = g.Font->Scale; - password_font->DisplayOffset = g.Font->DisplayOffset; - password_font->Ascent = g.Font->Ascent; - password_font->Descent = g.Font->Descent; - password_font->ContainerAtlas = g.Font->ContainerAtlas; - password_font->FallbackGlyph = glyph; - password_font->FallbackXAdvance = glyph->XAdvance; - IM_ASSERT(password_font->Glyphs.empty() && password_font->IndexXAdvance.empty() && password_font->IndexLookup.empty()); - PushFont(password_font); - } - - // NB: we are only allowed to access 'edit_state' if we are the active widget. - ImGuiTextEditState& edit_state = g.InputTextState; - - const bool focus_requested = FocusableItemRegister(window, g.ActiveId == id, (flags & (ImGuiInputTextFlags_CallbackCompletion|ImGuiInputTextFlags_AllowTabInput)) == 0); // Using completion callback disable keyboard tabbing - const bool focus_requested_by_code = focus_requested && (window->FocusIdxAllCounter == window->FocusIdxAllRequestCurrent); - const bool focus_requested_by_tab = focus_requested && !focus_requested_by_code; - - const bool hovered = IsHovered(frame_bb, id); - if (hovered) - { - SetHoveredID(id); - g.MouseCursor = ImGuiMouseCursor_TextInput; - } - const bool user_clicked = hovered && io.MouseClicked[0]; - const bool user_scrolled = is_multiline && g.ActiveId == 0 && edit_state.Id == id && g.ActiveIdPreviousFrame == draw_window->GetIDNoKeepAlive("#SCROLLY"); - - bool select_all = (g.ActiveId != id) && (flags & ImGuiInputTextFlags_AutoSelectAll) != 0; - if (focus_requested || user_clicked || user_scrolled) - { - if (g.ActiveId != id) - { - // Start edition - // Take a copy of the initial buffer value (both in original UTF-8 format and converted to wchar) - // From the moment we focused we are ignoring the content of 'buf' (unless we are in read-only mode) - const int prev_len_w = edit_state.CurLenW; - edit_state.Text.resize(buf_size+1); // wchar count <= UTF-8 count. we use +1 to make sure that .Data isn't NULL so it doesn't crash. - edit_state.InitialText.resize(buf_size+1); // UTF-8. we use +1 to make sure that .Data isn't NULL so it doesn't crash. - ImStrncpy(edit_state.InitialText.Data, buf, edit_state.InitialText.Size); - const char* buf_end = NULL; - edit_state.CurLenW = ImTextStrFromUtf8(edit_state.Text.Data, edit_state.Text.Size, buf, NULL, &buf_end); - edit_state.CurLenA = (int)(buf_end - buf); // We can't get the result from ImFormatString() above because it is not UTF-8 aware. Here we'll cut off malformed UTF-8. - edit_state.CursorAnimReset(); - - // Preserve cursor position and undo/redo stack if we come back to same widget - // FIXME: We should probably compare the whole buffer to be on the safety side. Comparing buf (utf8) and edit_state.Text (wchar). - const bool recycle_state = (edit_state.Id == id) && (prev_len_w == edit_state.CurLenW); - if (recycle_state) - { - // Recycle existing cursor/selection/undo stack but clamp position - // Note a single mouse click will override the cursor/position immediately by calling stb_textedit_click handler. - edit_state.CursorClamp(); - } - else - { - edit_state.Id = id; - edit_state.ScrollX = 0.0f; - stb_textedit_initialize_state(&edit_state.StbState, !is_multiline); - if (!is_multiline && focus_requested_by_code) - select_all = true; - } - if (flags & ImGuiInputTextFlags_AlwaysInsertMode) - edit_state.StbState.insert_mode = true; - if (!is_multiline && (focus_requested_by_tab || (user_clicked && io.KeyCtrl))) - select_all = true; - } - SetActiveID(id, window); - FocusWindow(window); - } - else if (io.MouseClicked[0]) - { - // Release focus when we click outside - if (g.ActiveId == id) - SetActiveID(0); - } - - bool value_changed = false; - bool enter_pressed = false; - - if (g.ActiveId == id) - { - if (!is_editable && !g.ActiveIdIsJustActivated) - { - // When read-only we always use the live data passed to the function - edit_state.Text.resize(buf_size+1); - const char* buf_end = NULL; - edit_state.CurLenW = ImTextStrFromUtf8(edit_state.Text.Data, edit_state.Text.Size, buf, NULL, &buf_end); - edit_state.CurLenA = (int)(buf_end - buf); - edit_state.CursorClamp(); - } - - edit_state.BufSizeA = buf_size; - - // Although we are active we don't prevent mouse from hovering other elements unless we are interacting right now with the widget. - // Down the line we should have a cleaner library-wide concept of Selected vs Active. - g.ActiveIdAllowOverlap = !io.MouseDown[0]; - - // Edit in progress - const float mouse_x = (io.MousePos.x - frame_bb.Min.x - style.FramePadding.x) + edit_state.ScrollX; - const float mouse_y = (is_multiline ? (io.MousePos.y - draw_window->DC.CursorPos.y - style.FramePadding.y) : (g.FontSize*0.5f)); - - const bool osx_double_click_selects_words = io.OSXBehaviors; // OS X style: Double click selects by word instead of selecting whole text - if (select_all || (hovered && !osx_double_click_selects_words && io.MouseDoubleClicked[0])) - { - edit_state.SelectAll(); - edit_state.SelectedAllMouseLock = true; - } - else if (hovered && osx_double_click_selects_words && io.MouseDoubleClicked[0]) - { - // Select a word only, OS X style (by simulating keystrokes) - edit_state.OnKeyPressed(STB_TEXTEDIT_K_WORDLEFT); - edit_state.OnKeyPressed(STB_TEXTEDIT_K_WORDRIGHT | STB_TEXTEDIT_K_SHIFT); - } - else if (io.MouseClicked[0] && !edit_state.SelectedAllMouseLock) - { - stb_textedit_click(&edit_state, &edit_state.StbState, mouse_x, mouse_y); - edit_state.CursorAnimReset(); - } - else if (io.MouseDown[0] && !edit_state.SelectedAllMouseLock && (io.MouseDelta.x != 0.0f || io.MouseDelta.y != 0.0f)) - { - stb_textedit_drag(&edit_state, &edit_state.StbState, mouse_x, mouse_y); - edit_state.CursorAnimReset(); - edit_state.CursorFollow = true; - } - if (edit_state.SelectedAllMouseLock && !io.MouseDown[0]) - edit_state.SelectedAllMouseLock = false; - - if (io.InputCharacters[0]) - { - // Process text input (before we check for Return because using some IME will effectively send a Return?) - // We ignore CTRL inputs, but need to allow CTRL+ALT as some keyboards (e.g. German) use AltGR - which is Alt+Ctrl - to input certain characters. - if (!(io.KeyCtrl && !io.KeyAlt) && is_editable) - { - for (int n = 0; n < IM_ARRAYSIZE(io.InputCharacters) && io.InputCharacters[n]; n++) - if (unsigned int c = (unsigned int)io.InputCharacters[n]) - { - // Insert character if they pass filtering - if (!InputTextFilterCharacter(&c, flags, callback, user_data)) - continue; - edit_state.OnKeyPressed((int)c); - } - } - - // Consume characters - memset(g.IO.InputCharacters, 0, sizeof(g.IO.InputCharacters)); - } - - // Handle various key-presses - bool cancel_edit = false; - const int k_mask = (io.KeyShift ? STB_TEXTEDIT_K_SHIFT : 0); - const bool is_shortcut_key_only = (io.OSXBehaviors ? (io.KeySuper && !io.KeyCtrl) : (io.KeyCtrl && !io.KeySuper)) && !io.KeyAlt && !io.KeyShift; // OS X style: Shortcuts using Cmd/Super instead of Ctrl - const bool is_wordmove_key_down = io.OSXBehaviors ? io.KeyAlt : io.KeyCtrl; // OS X style: Text editing cursor movement using Alt instead of Ctrl - const bool is_startend_key_down = io.OSXBehaviors && io.KeySuper && !io.KeyCtrl && !io.KeyAlt; // OS X style: Line/Text Start and End using Cmd+Arrows instead of Home/End - - if (IsKeyPressedMap(ImGuiKey_LeftArrow)) { edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_LINESTART : is_wordmove_key_down ? STB_TEXTEDIT_K_WORDLEFT : STB_TEXTEDIT_K_LEFT) | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_RightArrow)) { edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_LINEEND : is_wordmove_key_down ? STB_TEXTEDIT_K_WORDRIGHT : STB_TEXTEDIT_K_RIGHT) | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_UpArrow) && is_multiline) { if (io.KeyCtrl) SetWindowScrollY(draw_window, ImMax(draw_window->Scroll.y - g.FontSize, 0.0f)); else edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_TEXTSTART : STB_TEXTEDIT_K_UP) | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_DownArrow) && is_multiline) { if (io.KeyCtrl) SetWindowScrollY(draw_window, ImMin(draw_window->Scroll.y + g.FontSize, GetScrollMaxY())); else edit_state.OnKeyPressed((is_startend_key_down ? STB_TEXTEDIT_K_TEXTEND : STB_TEXTEDIT_K_DOWN) | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_Home)) { edit_state.OnKeyPressed(io.KeyCtrl ? STB_TEXTEDIT_K_TEXTSTART | k_mask : STB_TEXTEDIT_K_LINESTART | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_End)) { edit_state.OnKeyPressed(io.KeyCtrl ? STB_TEXTEDIT_K_TEXTEND | k_mask : STB_TEXTEDIT_K_LINEEND | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_Delete) && is_editable) { edit_state.OnKeyPressed(STB_TEXTEDIT_K_DELETE | k_mask); } - else if (IsKeyPressedMap(ImGuiKey_Backspace) && is_editable) - { - if (!edit_state.HasSelection()) - { - if (is_wordmove_key_down) edit_state.OnKeyPressed(STB_TEXTEDIT_K_WORDLEFT|STB_TEXTEDIT_K_SHIFT); - else if (io.OSXBehaviors && io.KeySuper && !io.KeyAlt && !io.KeyCtrl) edit_state.OnKeyPressed(STB_TEXTEDIT_K_LINESTART|STB_TEXTEDIT_K_SHIFT); - } - edit_state.OnKeyPressed(STB_TEXTEDIT_K_BACKSPACE | k_mask); - } - else if (IsKeyPressedMap(ImGuiKey_Enter)) - { - bool ctrl_enter_for_new_line = (flags & ImGuiInputTextFlags_CtrlEnterForNewLine) != 0; - if (!is_multiline || (ctrl_enter_for_new_line && !io.KeyCtrl) || (!ctrl_enter_for_new_line && io.KeyCtrl)) - { - SetActiveID(0); - enter_pressed = true; - } - else if (is_editable) - { - unsigned int c = '\n'; // Insert new line - if (InputTextFilterCharacter(&c, flags, callback, user_data)) - edit_state.OnKeyPressed((int)c); - } - } - else if ((flags & ImGuiInputTextFlags_AllowTabInput) && IsKeyPressedMap(ImGuiKey_Tab) && !io.KeyCtrl && !io.KeyShift && !io.KeyAlt && is_editable) - { - unsigned int c = '\t'; // Insert TAB - if (InputTextFilterCharacter(&c, flags, callback, user_data)) - edit_state.OnKeyPressed((int)c); - } - else if (IsKeyPressedMap(ImGuiKey_Escape)) { SetActiveID(0); cancel_edit = true; } - else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_Z) && is_editable) { edit_state.OnKeyPressed(STB_TEXTEDIT_K_UNDO); edit_state.ClearSelection(); } - else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_Y) && is_editable) { edit_state.OnKeyPressed(STB_TEXTEDIT_K_REDO); edit_state.ClearSelection(); } - else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_A)) { edit_state.SelectAll(); edit_state.CursorFollow = true; } - else if (is_shortcut_key_only && !is_password && ((IsKeyPressedMap(ImGuiKey_X) && is_editable) || IsKeyPressedMap(ImGuiKey_C)) && (!is_multiline || edit_state.HasSelection())) - { - // Cut, Copy - const bool cut = IsKeyPressedMap(ImGuiKey_X); - if (cut && !edit_state.HasSelection()) - edit_state.SelectAll(); - - if (io.SetClipboardTextFn) - { - const int ib = edit_state.HasSelection() ? ImMin(edit_state.StbState.select_start, edit_state.StbState.select_end) : 0; - const int ie = edit_state.HasSelection() ? ImMax(edit_state.StbState.select_start, edit_state.StbState.select_end) : edit_state.CurLenW; - edit_state.TempTextBuffer.resize((ie-ib) * 4 + 1); - ImTextStrToUtf8(edit_state.TempTextBuffer.Data, edit_state.TempTextBuffer.Size, edit_state.Text.Data+ib, edit_state.Text.Data+ie); - io.SetClipboardTextFn(edit_state.TempTextBuffer.Data); - } - - if (cut) - { - edit_state.CursorFollow = true; - stb_textedit_cut(&edit_state, &edit_state.StbState); - } - } - else if (is_shortcut_key_only && IsKeyPressedMap(ImGuiKey_V) && is_editable) - { - // Paste - if (const char* clipboard = io.GetClipboardTextFn ? io.GetClipboardTextFn() : NULL) - { - // Filter pasted buffer - const int clipboard_len = (int)strlen(clipboard); - ImWchar* clipboard_filtered = (ImWchar*)ImGui::MemAlloc((clipboard_len+1) * sizeof(ImWchar)); - int clipboard_filtered_len = 0; - for (const char* s = clipboard; *s; ) - { - unsigned int c; - s += ImTextCharFromUtf8(&c, s, NULL); - if (c == 0) - break; - if (c >= 0x10000 || !InputTextFilterCharacter(&c, flags, callback, user_data)) - continue; - clipboard_filtered[clipboard_filtered_len++] = (ImWchar)c; - } - clipboard_filtered[clipboard_filtered_len] = 0; - if (clipboard_filtered_len > 0) // If everything was filtered, ignore the pasting operation - { - stb_textedit_paste(&edit_state, &edit_state.StbState, clipboard_filtered, clipboard_filtered_len); - edit_state.CursorFollow = true; - } - ImGui::MemFree(clipboard_filtered); - } - } - - if (cancel_edit) - { - // Restore initial value - if (is_editable) - { - ImStrncpy(buf, edit_state.InitialText.Data, buf_size); - value_changed = true; - } - } - else - { - // Apply new value immediately - copy modified buffer back - // Note that as soon as the input box is active, the in-widget value gets priority over any underlying modification of the input buffer - // FIXME: We actually always render 'buf' when calling DrawList->AddText, making the comment above incorrect. - // FIXME-OPT: CPU waste to do this every time the widget is active, should mark dirty state from the stb_textedit callbacks. - if (is_editable) - { - edit_state.TempTextBuffer.resize(edit_state.Text.Size * 4); - ImTextStrToUtf8(edit_state.TempTextBuffer.Data, edit_state.TempTextBuffer.Size, edit_state.Text.Data, NULL); - } - - // User callback - if ((flags & (ImGuiInputTextFlags_CallbackCompletion | ImGuiInputTextFlags_CallbackHistory | ImGuiInputTextFlags_CallbackAlways)) != 0) - { - IM_ASSERT(callback != NULL); - - // The reason we specify the usage semantic (Completion/History) is that Completion needs to disable keyboard TABBING at the moment. - ImGuiInputTextFlags event_flag = 0; - ImGuiKey event_key = ImGuiKey_COUNT; - if ((flags & ImGuiInputTextFlags_CallbackCompletion) != 0 && IsKeyPressedMap(ImGuiKey_Tab)) - { - event_flag = ImGuiInputTextFlags_CallbackCompletion; - event_key = ImGuiKey_Tab; - } - else if ((flags & ImGuiInputTextFlags_CallbackHistory) != 0 && IsKeyPressedMap(ImGuiKey_UpArrow)) - { - event_flag = ImGuiInputTextFlags_CallbackHistory; - event_key = ImGuiKey_UpArrow; - } - else if ((flags & ImGuiInputTextFlags_CallbackHistory) != 0 && IsKeyPressedMap(ImGuiKey_DownArrow)) - { - event_flag = ImGuiInputTextFlags_CallbackHistory; - event_key = ImGuiKey_DownArrow; - } - else if (flags & ImGuiInputTextFlags_CallbackAlways) - event_flag = ImGuiInputTextFlags_CallbackAlways; - - if (event_flag) - { - ImGuiTextEditCallbackData callback_data; - memset(&callback_data, 0, sizeof(ImGuiTextEditCallbackData)); - callback_data.EventFlag = event_flag; - callback_data.Flags = flags; - callback_data.UserData = user_data; - callback_data.ReadOnly = !is_editable; - - callback_data.EventKey = event_key; - callback_data.Buf = edit_state.TempTextBuffer.Data; - callback_data.BufTextLen = edit_state.CurLenA; - callback_data.BufSize = edit_state.BufSizeA; - callback_data.BufDirty = false; - - // We have to convert from wchar-positions to UTF-8-positions, which can be pretty slow (an incentive to ditch the ImWchar buffer, see https://github.com/nothings/stb/issues/188) - ImWchar* text = edit_state.Text.Data; - const int utf8_cursor_pos = callback_data.CursorPos = ImTextCountUtf8BytesFromStr(text, text + edit_state.StbState.cursor); - const int utf8_selection_start = callback_data.SelectionStart = ImTextCountUtf8BytesFromStr(text, text + edit_state.StbState.select_start); - const int utf8_selection_end = callback_data.SelectionEnd = ImTextCountUtf8BytesFromStr(text, text + edit_state.StbState.select_end); - - // Call user code - callback(&callback_data); - - // Read back what user may have modified - IM_ASSERT(callback_data.Buf == edit_state.TempTextBuffer.Data); // Invalid to modify those fields - IM_ASSERT(callback_data.BufSize == edit_state.BufSizeA); - IM_ASSERT(callback_data.Flags == flags); - if (callback_data.CursorPos != utf8_cursor_pos) edit_state.StbState.cursor = ImTextCountCharsFromUtf8(callback_data.Buf, callback_data.Buf + callback_data.CursorPos); - if (callback_data.SelectionStart != utf8_selection_start) edit_state.StbState.select_start = ImTextCountCharsFromUtf8(callback_data.Buf, callback_data.Buf + callback_data.SelectionStart); - if (callback_data.SelectionEnd != utf8_selection_end) edit_state.StbState.select_end = ImTextCountCharsFromUtf8(callback_data.Buf, callback_data.Buf + callback_data.SelectionEnd); - if (callback_data.BufDirty) - { - IM_ASSERT(callback_data.BufTextLen == (int)strlen(callback_data.Buf)); // You need to maintain BufTextLen if you change the text! - edit_state.CurLenW = ImTextStrFromUtf8(edit_state.Text.Data, edit_state.Text.Size, callback_data.Buf, NULL); - edit_state.CurLenA = callback_data.BufTextLen; // Assume correct length and valid UTF-8 from user, saves us an extra strlen() - edit_state.CursorAnimReset(); - } - } - } - - // Copy back to user buffer - if (is_editable && strcmp(edit_state.TempTextBuffer.Data, buf) != 0) - { - ImStrncpy(buf, edit_state.TempTextBuffer.Data, buf_size); - value_changed = true; - } - } - } - - // Render - // Select which buffer we are going to display. When ImGuiInputTextFlags_NoLiveEdit is set 'buf' might still be the old value. We set buf to NULL to prevent accidental usage from now on. - const char* buf_display = (g.ActiveId == id && is_editable) ? edit_state.TempTextBuffer.Data : buf; buf = NULL; - - if (!is_multiline) - RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - - const ImVec4 clip_rect(frame_bb.Min.x, frame_bb.Min.y, frame_bb.Min.x + size.x, frame_bb.Min.y + size.y); // Not using frame_bb.Max because we have adjusted size - ImVec2 render_pos = is_multiline ? draw_window->DC.CursorPos : frame_bb.Min + style.FramePadding; - ImVec2 text_size(0.f, 0.f); - const bool is_currently_scrolling = (edit_state.Id == id && is_multiline && g.ActiveId == draw_window->GetIDNoKeepAlive("#SCROLLY")); - if (g.ActiveId == id || is_currently_scrolling) - { - edit_state.CursorAnim += io.DeltaTime; - - // This is going to be messy. We need to: - // - Display the text (this alone can be more easily clipped) - // - Handle scrolling, highlight selection, display cursor (those all requires some form of 1d->2d cursor position calculation) - // - Measure text height (for scrollbar) - // We are attempting to do most of that in **one main pass** to minimize the computation cost (non-negligible for large amount of text) + 2nd pass for selection rendering (we could merge them by an extra refactoring effort) - // FIXME: This should occur on buf_display but we'd need to maintain cursor/select_start/select_end for UTF-8. - const ImWchar* text_begin = edit_state.Text.Data; - ImVec2 cursor_offset, select_start_offset; - - { - // Count lines + find lines numbers straddling 'cursor' and 'select_start' position. - const ImWchar* searches_input_ptr[2]; - searches_input_ptr[0] = text_begin + edit_state.StbState.cursor; - searches_input_ptr[1] = NULL; - int searches_remaining = 1; - int searches_result_line_number[2] = { -1, -999 }; - if (edit_state.StbState.select_start != edit_state.StbState.select_end) - { - searches_input_ptr[1] = text_begin + ImMin(edit_state.StbState.select_start, edit_state.StbState.select_end); - searches_result_line_number[1] = -1; - searches_remaining++; - } - - // Iterate all lines to find our line numbers - // In multi-line mode, we never exit the loop until all lines are counted, so add one extra to the searches_remaining counter. - searches_remaining += is_multiline ? 1 : 0; - int line_count = 0; - for (const ImWchar* s = text_begin; *s != 0; s++) - if (*s == '\n') - { - line_count++; - if (searches_result_line_number[0] == -1 && s >= searches_input_ptr[0]) { searches_result_line_number[0] = line_count; if (--searches_remaining <= 0) break; } - if (searches_result_line_number[1] == -1 && s >= searches_input_ptr[1]) { searches_result_line_number[1] = line_count; if (--searches_remaining <= 0) break; } - } - line_count++; - if (searches_result_line_number[0] == -1) searches_result_line_number[0] = line_count; - if (searches_result_line_number[1] == -1) searches_result_line_number[1] = line_count; - - // Calculate 2d position by finding the beginning of the line and measuring distance - cursor_offset.x = InputTextCalcTextSizeW(ImStrbolW(searches_input_ptr[0], text_begin), searches_input_ptr[0]).x; - cursor_offset.y = searches_result_line_number[0] * g.FontSize; - if (searches_result_line_number[1] >= 0) - { - select_start_offset.x = InputTextCalcTextSizeW(ImStrbolW(searches_input_ptr[1], text_begin), searches_input_ptr[1]).x; - select_start_offset.y = searches_result_line_number[1] * g.FontSize; - } - - // Calculate text height - if (is_multiline) - text_size = ImVec2(size.x, line_count * g.FontSize); - } - - // Scroll - if (edit_state.CursorFollow) - { - // Horizontal scroll in chunks of quarter width - if (!(flags & ImGuiInputTextFlags_NoHorizontalScroll)) - { - const float scroll_increment_x = size.x * 0.25f; - if (cursor_offset.x < edit_state.ScrollX) - edit_state.ScrollX = (float)(int)ImMax(0.0f, cursor_offset.x - scroll_increment_x); - else if (cursor_offset.x - size.x >= edit_state.ScrollX) - edit_state.ScrollX = (float)(int)(cursor_offset.x - size.x + scroll_increment_x); - } - else - { - edit_state.ScrollX = 0.0f; - } - - // Vertical scroll - if (is_multiline) - { - float scroll_y = draw_window->Scroll.y; - if (cursor_offset.y - g.FontSize < scroll_y) - scroll_y = ImMax(0.0f, cursor_offset.y - g.FontSize); - else if (cursor_offset.y - size.y >= scroll_y) - scroll_y = cursor_offset.y - size.y; - draw_window->DC.CursorPos.y += (draw_window->Scroll.y - scroll_y); // To avoid a frame of lag - draw_window->Scroll.y = scroll_y; - render_pos.y = draw_window->DC.CursorPos.y; - } - } - edit_state.CursorFollow = false; - const ImVec2 render_scroll = ImVec2(edit_state.ScrollX, 0.0f); - - // Draw selection - if (edit_state.StbState.select_start != edit_state.StbState.select_end) - { - const ImWchar* text_selected_begin = text_begin + ImMin(edit_state.StbState.select_start, edit_state.StbState.select_end); - const ImWchar* text_selected_end = text_begin + ImMax(edit_state.StbState.select_start, edit_state.StbState.select_end); - - float bg_offy_up = is_multiline ? 0.0f : -1.0f; // FIXME: those offsets should be part of the style? they don't play so well with multi-line selection. - float bg_offy_dn = is_multiline ? 0.0f : 2.0f; - ImU32 bg_color = GetColorU32(ImGuiCol_TextSelectedBg); - ImVec2 rect_pos = render_pos + select_start_offset - render_scroll; - for (const ImWchar* p = text_selected_begin; p < text_selected_end; ) - { - if (rect_pos.y > clip_rect.w + g.FontSize) - break; - if (rect_pos.y < clip_rect.y) - { - while (p < text_selected_end) - if (*p++ == '\n') - break; - } - else - { - ImVec2 rect_size = InputTextCalcTextSizeW(p, text_selected_end, &p, NULL, true); - if (rect_size.x <= 0.0f) rect_size.x = (float)(int)(g.Font->GetCharAdvance((unsigned short)' ') * 0.50f); // So we can see selected empty lines - ImRect rect(rect_pos + ImVec2(0.0f, bg_offy_up - g.FontSize), rect_pos +ImVec2(rect_size.x, bg_offy_dn)); - rect.Clip(clip_rect); - if (rect.Overlaps(clip_rect)) - draw_window->DrawList->AddRectFilled(rect.Min, rect.Max, bg_color); - } - rect_pos.x = render_pos.x - render_scroll.x; - rect_pos.y += g.FontSize; - } - } - - draw_window->DrawList->AddText(g.Font, g.FontSize, render_pos - render_scroll, GetColorU32(ImGuiCol_Text), buf_display, buf_display + edit_state.CurLenA, 0.0f, is_multiline ? NULL : &clip_rect); - - // Draw blinking cursor - bool cursor_is_visible = (g.InputTextState.CursorAnim <= 0.0f) || fmodf(g.InputTextState.CursorAnim, 1.20f) <= 0.80f; - ImVec2 cursor_screen_pos = render_pos + cursor_offset - render_scroll; - ImRect cursor_screen_rect(cursor_screen_pos.x, cursor_screen_pos.y-g.FontSize+0.5f, cursor_screen_pos.x+1.0f, cursor_screen_pos.y-1.5f); - if (cursor_is_visible && cursor_screen_rect.Overlaps(clip_rect)) - draw_window->DrawList->AddLine(cursor_screen_rect.Min, cursor_screen_rect.GetBL(), GetColorU32(ImGuiCol_Text)); - - // Notify OS of text input position for advanced IME (-1 x offset so that Windows IME can cover our cursor. Bit of an extra nicety.) - if (is_editable) - g.OsImePosRequest = ImVec2(cursor_screen_pos.x - 1, cursor_screen_pos.y - g.FontSize); - } - else - { - // Render text only - const char* buf_end = NULL; - if (is_multiline) - text_size = ImVec2(size.x, InputTextCalcTextLenAndLineCount(buf_display, &buf_end) * g.FontSize); // We don't need width - draw_window->DrawList->AddText(g.Font, g.FontSize, render_pos, GetColorU32(ImGuiCol_Text), buf_display, buf_end, 0.0f, is_multiline ? NULL : &clip_rect); - } - - if (is_multiline) - { - Dummy(text_size + ImVec2(0.0f, g.FontSize)); // Always add room to scroll an extra line - EndChildFrame(); - EndGroup(); - } - - if (is_password) - PopFont(); - - // Log as text - if (g.LogEnabled && !is_password) - LogRenderedText(render_pos, buf_display, NULL); - - if (label_size.x > 0) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - if ((flags & ImGuiInputTextFlags_EnterReturnsTrue) != 0) - return enter_pressed; - else - return value_changed; -} - -bool ImGui::InputText(const char* label, char* buf, size_t buf_size, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) -{ - IM_ASSERT(!(flags & ImGuiInputTextFlags_Multiline)); // call InputTextMultiline() - return InputTextEx(label, buf, (int)buf_size, ImVec2(0,0), flags, callback, user_data); -} - -bool ImGui::InputTextMultiline(const char* label, char* buf, size_t buf_size, const ImVec2& size, ImGuiInputTextFlags flags, ImGuiTextEditCallback callback, void* user_data) -{ - return InputTextEx(label, buf, (int)buf_size, size, flags | ImGuiInputTextFlags_Multiline, callback, user_data); -} - -// NB: scalar_format here must be a simple "%xx" format string with no prefix/suffix (unlike the Drag/Slider functions "display_format" argument) -bool ImGui::InputScalarEx(const char* label, ImGuiDataType data_type, void* data_ptr, void* step_ptr, void* step_fast_ptr, const char* scalar_format, ImGuiInputTextFlags extra_flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - BeginGroup(); - PushID(label); - const ImVec2 button_sz = ImVec2(g.FontSize, g.FontSize) + style.FramePadding*2.0f; - if (step_ptr) - PushItemWidth(ImMax(1.0f, CalcItemWidth() - (button_sz.x + style.ItemInnerSpacing.x)*2)); - - char buf[64]; - DataTypeFormatString(data_type, data_ptr, scalar_format, buf, IM_ARRAYSIZE(buf)); - - bool value_changed = false; - if (!(extra_flags & ImGuiInputTextFlags_CharsHexadecimal)) - extra_flags |= ImGuiInputTextFlags_CharsDecimal; - extra_flags |= ImGuiInputTextFlags_AutoSelectAll; - if (InputText("", buf, IM_ARRAYSIZE(buf), extra_flags)) // PushId(label) + "" gives us the expected ID from outside point of view - value_changed = DataTypeApplyOpFromText(buf, GImGui->InputTextState.InitialText.begin(), data_type, data_ptr, scalar_format); - - // Step buttons - if (step_ptr) - { - PopItemWidth(); - SameLine(0, style.ItemInnerSpacing.x); - if (ButtonEx("-", button_sz, ImGuiButtonFlags_Repeat | ImGuiButtonFlags_DontClosePopups)) - { - DataTypeApplyOp(data_type, '-', data_ptr, g.IO.KeyCtrl && step_fast_ptr ? step_fast_ptr : step_ptr); - value_changed = true; - } - SameLine(0, style.ItemInnerSpacing.x); - if (ButtonEx("+", button_sz, ImGuiButtonFlags_Repeat | ImGuiButtonFlags_DontClosePopups)) - { - DataTypeApplyOp(data_type, '+', data_ptr, g.IO.KeyCtrl && step_fast_ptr ? step_fast_ptr : step_ptr); - value_changed = true; - } - } - PopID(); - - if (label_size.x > 0) - { - SameLine(0, style.ItemInnerSpacing.x); - RenderText(ImVec2(window->DC.CursorPos.x, window->DC.CursorPos.y + style.FramePadding.y), label); - ItemSize(label_size, style.FramePadding.y); - } - EndGroup(); - - return value_changed; -} - -bool ImGui::InputFloat(const char* label, float* v, float step, float step_fast, int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - char display_format[16]; - if (decimal_precision < 0) - strcpy(display_format, "%f"); // Ideally we'd have a minimum decimal precision of 1 to visually denote that this is a float, while hiding non-significant digits? %f doesn't have a minimum of 1 - else - ImFormatString(display_format, 16, "%%.%df", decimal_precision); - return InputScalarEx(label, ImGuiDataType_Float, (void*)v, (void*)(step>0.0f ? &step : NULL), (void*)(step_fast>0.0f ? &step_fast : NULL), display_format, extra_flags); -} - -bool ImGui::InputInt(const char* label, int* v, int step, int step_fast, ImGuiInputTextFlags extra_flags) -{ - // Hexadecimal input provided as a convenience but the flag name is awkward. Typically you'd use InputText() to parse your own data, if you want to handle prefixes. - const char* scalar_format = (extra_flags & ImGuiInputTextFlags_CharsHexadecimal) ? "%08X" : "%d"; - return InputScalarEx(label, ImGuiDataType_Int, (void*)v, (void*)(step>0.0f ? &step : NULL), (void*)(step_fast>0.0f ? &step_fast : NULL), scalar_format, extra_flags); -} - -bool ImGui::InputFloatN(const char* label, float* v, int components, int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= InputFloat("##v", &v[i], 0, 0, decimal_precision, extra_flags); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - window->DC.CurrentLineTextBaseOffset = ImMax(window->DC.CurrentLineTextBaseOffset, g.Style.FramePadding.y); - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::InputFloat2(const char* label, float v[2], int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - return InputFloatN(label, v, 2, decimal_precision, extra_flags); -} - -bool ImGui::InputFloat3(const char* label, float v[3], int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - return InputFloatN(label, v, 3, decimal_precision, extra_flags); -} - -bool ImGui::InputFloat4(const char* label, float v[4], int decimal_precision, ImGuiInputTextFlags extra_flags) -{ - return InputFloatN(label, v, 4, decimal_precision, extra_flags); -} - -bool ImGui::InputIntN(const char* label, int* v, int components, ImGuiInputTextFlags extra_flags) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - bool value_changed = false; - BeginGroup(); - PushID(label); - PushMultiItemsWidths(components); - for (int i = 0; i < components; i++) - { - PushID(i); - value_changed |= InputInt("##v", &v[i], 0, 0, extra_flags); - SameLine(0, g.Style.ItemInnerSpacing.x); - PopID(); - PopItemWidth(); - } - PopID(); - - window->DC.CurrentLineTextBaseOffset = ImMax(window->DC.CurrentLineTextBaseOffset, g.Style.FramePadding.y); - TextUnformatted(label, FindRenderedTextEnd(label)); - EndGroup(); - - return value_changed; -} - -bool ImGui::InputInt2(const char* label, int v[2], ImGuiInputTextFlags extra_flags) -{ - return InputIntN(label, v, 2, extra_flags); -} - -bool ImGui::InputInt3(const char* label, int v[3], ImGuiInputTextFlags extra_flags) -{ - return InputIntN(label, v, 3, extra_flags); -} - -bool ImGui::InputInt4(const char* label, int v[4], ImGuiInputTextFlags extra_flags) -{ - return InputIntN(label, v, 4, extra_flags); -} - -static bool Items_ArrayGetter(void* data, int idx, const char** out_text) -{ - const char** items = (const char**)data; - if (out_text) - *out_text = items[idx]; - return true; -} - -static bool Items_SingleStringGetter(void* data, int idx, const char** out_text) -{ - // FIXME-OPT: we could pre-compute the indices to fasten this. But only 1 active combo means the waste is limited. - const char* items_separated_by_zeros = (const char*)data; - int items_count = 0; - const char* p = items_separated_by_zeros; - while (*p) - { - if (idx == items_count) - break; - p += strlen(p) + 1; - items_count++; - } - if (!*p) - return false; - if (out_text) - *out_text = p; - return true; -} - -// Combo box helper allowing to pass an array of strings. -bool ImGui::Combo(const char* label, int* current_item, const char** items, int items_count, int height_in_items) -{ - const bool value_changed = Combo(label, current_item, Items_ArrayGetter, (void*)items, items_count, height_in_items); - return value_changed; -} - -// Combo box helper allowing to pass all items in a single string. -bool ImGui::Combo(const char* label, int* current_item, const char* items_separated_by_zeros, int height_in_items) -{ - int items_count = 0; - const char* p = items_separated_by_zeros; // FIXME-OPT: Avoid computing this, or at least only when combo is open - while (*p) - { - p += strlen(p) + 1; - items_count++; - } - bool value_changed = Combo(label, current_item, Items_SingleStringGetter, (void*)items_separated_by_zeros, items_count, height_in_items); - return value_changed; -} - -// Combo box function. -bool ImGui::Combo(const char* label, int* current_item, bool (*items_getter)(void*, int, const char**), void* data, int items_count, int height_in_items) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const float w = CalcItemWidth(); - - const ImVec2 label_size = CalcTextSize(label, NULL, true); - const ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(w, label_size.y + style.FramePadding.y*2.0f)); - const ImRect total_bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - ItemSize(total_bb, style.FramePadding.y); - if (!ItemAdd(total_bb, &id)) - return false; - - const float arrow_size = (g.FontSize + style.FramePadding.x * 2.0f); - const bool hovered = IsHovered(frame_bb, id); - bool popup_open = IsPopupOpen(id); - bool popup_opened_now = false; - - const ImRect value_bb(frame_bb.Min, frame_bb.Max - ImVec2(arrow_size, 0.0f)); - RenderFrame(frame_bb.Min, frame_bb.Max, GetColorU32(ImGuiCol_FrameBg), true, style.FrameRounding); - RenderFrame(ImVec2(frame_bb.Max.x-arrow_size, frame_bb.Min.y), frame_bb.Max, GetColorU32(popup_open || hovered ? ImGuiCol_ButtonHovered : ImGuiCol_Button), true, style.FrameRounding); // FIXME-ROUNDING - RenderCollapseTriangle(ImVec2(frame_bb.Max.x-arrow_size, frame_bb.Min.y) + style.FramePadding, true); - - if (*current_item >= 0 && *current_item < items_count) - { - const char* item_text; - if (items_getter(data, *current_item, &item_text)) - RenderTextClipped(frame_bb.Min + style.FramePadding, value_bb.Max, item_text, NULL, NULL, ImVec2(0.0f,0.0f)); - } - - if (label_size.x > 0) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - if (hovered) - { - SetHoveredID(id); - if (g.IO.MouseClicked[0]) - { - SetActiveID(0); - if (IsPopupOpen(id)) - { - ClosePopup(id); - } - else - { - FocusWindow(window); - OpenPopup(label); - popup_open = popup_opened_now = true; - } - } - } - - bool value_changed = false; - if (IsPopupOpen(id)) - { - // Size default to hold ~7 items - if (height_in_items < 0) - height_in_items = 7; - - float popup_height = (label_size.y + style.ItemSpacing.y) * ImMin(items_count, height_in_items) + (style.FramePadding.y * 3); - float popup_y1 = frame_bb.Max.y; - float popup_y2 = ImClamp(popup_y1 + popup_height, popup_y1, g.IO.DisplaySize.y - style.DisplaySafeAreaPadding.y); - if ((popup_y2 - popup_y1) < ImMin(popup_height, frame_bb.Min.y - style.DisplaySafeAreaPadding.y)) - { - // Position our combo ABOVE because there's more space to fit! (FIXME: Handle in Begin() or use a shared helper. We have similar code in Begin() for popup placement) - popup_y1 = ImClamp(frame_bb.Min.y - popup_height, style.DisplaySafeAreaPadding.y, frame_bb.Min.y); - popup_y2 = frame_bb.Min.y; - } - ImRect popup_rect(ImVec2(frame_bb.Min.x, popup_y1), ImVec2(frame_bb.Max.x, popup_y2)); - SetNextWindowPos(popup_rect.Min); - SetNextWindowSize(popup_rect.GetSize()); - PushStyleVar(ImGuiStyleVar_WindowPadding, style.FramePadding); - - const ImGuiWindowFlags flags = ImGuiWindowFlags_ComboBox | ((window->Flags & ImGuiWindowFlags_ShowBorders) ? ImGuiWindowFlags_ShowBorders : 0); - if (BeginPopupEx(label, flags)) - { - // Display items - Spacing(); - for (int i = 0; i < items_count; i++) - { - PushID((void*)(intptr_t)i); - const bool item_selected = (i == *current_item); - const char* item_text; - if (!items_getter(data, i, &item_text)) - item_text = "*Unknown item*"; - if (Selectable(item_text, item_selected)) - { - SetActiveID(0); - value_changed = true; - *current_item = i; - } - if (item_selected && popup_opened_now) - SetScrollHere(); - PopID(); - } - EndPopup(); - } - PopStyleVar(); - } - return value_changed; -} - -// Tip: pass an empty label (e.g. "##dummy") then you can use the space to draw other text or image. -// But you need to make sure the ID is unique, e.g. enclose calls in PushID/PopID. -bool ImGui::Selectable(const char* label, bool selected, ImGuiSelectableFlags flags, const ImVec2& size_arg) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - - if ((flags & ImGuiSelectableFlags_SpanAllColumns) && window->DC.ColumnsCount > 1) - PopClipRect(); - - ImGuiID id = window->GetID(label); - ImVec2 label_size = CalcTextSize(label, NULL, true); - ImVec2 size(size_arg.x != 0.0f ? size_arg.x : label_size.x, size_arg.y != 0.0f ? size_arg.y : label_size.y); - ImVec2 pos = window->DC.CursorPos; - pos.y += window->DC.CurrentLineTextBaseOffset; - ImRect bb(pos, pos + size); - ItemSize(bb); - - // Fill horizontal space. - ImVec2 window_padding = window->WindowPadding; - float max_x = (flags & ImGuiSelectableFlags_SpanAllColumns) ? GetWindowContentRegionMax().x : GetContentRegionMax().x; - float w_draw = ImMax(label_size.x, window->Pos.x + max_x - window_padding.x - window->DC.CursorPos.x); - ImVec2 size_draw((size_arg.x != 0 && !(flags & ImGuiSelectableFlags_DrawFillAvailWidth)) ? size_arg.x : w_draw, size_arg.y != 0.0f ? size_arg.y : size.y); - ImRect bb_with_spacing(pos, pos + size_draw); - if (size_arg.x == 0.0f || (flags & ImGuiSelectableFlags_DrawFillAvailWidth)) - bb_with_spacing.Max.x += window_padding.x; - - // Selectables are tightly packed together, we extend the box to cover spacing between selectable. - float spacing_L = (float)(int)(style.ItemSpacing.x * 0.5f); - float spacing_U = (float)(int)(style.ItemSpacing.y * 0.5f); - float spacing_R = style.ItemSpacing.x - spacing_L; - float spacing_D = style.ItemSpacing.y - spacing_U; - bb_with_spacing.Min.x -= spacing_L; - bb_with_spacing.Min.y -= spacing_U; - bb_with_spacing.Max.x += spacing_R; - bb_with_spacing.Max.y += spacing_D; - if (!ItemAdd(bb_with_spacing, &id)) - { - if ((flags & ImGuiSelectableFlags_SpanAllColumns) && window->DC.ColumnsCount > 1) - PushColumnClipRect(); - return false; - } - - ImGuiButtonFlags button_flags = 0; - if (flags & ImGuiSelectableFlags_Menu) button_flags |= ImGuiButtonFlags_PressedOnClick; - if (flags & ImGuiSelectableFlags_MenuItem) button_flags |= ImGuiButtonFlags_PressedOnClick|ImGuiButtonFlags_PressedOnRelease; - if (flags & ImGuiSelectableFlags_Disabled) button_flags |= ImGuiButtonFlags_Disabled; - if (flags & ImGuiSelectableFlags_AllowDoubleClick) button_flags |= ImGuiButtonFlags_PressedOnClickRelease | ImGuiButtonFlags_PressedOnDoubleClick; - bool hovered, held; - bool pressed = ButtonBehavior(bb_with_spacing, id, &hovered, &held, button_flags); - if (flags & ImGuiSelectableFlags_Disabled) - selected = false; - - // Render - if (hovered || selected) - { - const ImU32 col = GetColorU32((held && hovered) ? ImGuiCol_HeaderActive : hovered ? ImGuiCol_HeaderHovered : ImGuiCol_Header); - RenderFrame(bb_with_spacing.Min, bb_with_spacing.Max, col, false, 0.0f); - } - - if ((flags & ImGuiSelectableFlags_SpanAllColumns) && window->DC.ColumnsCount > 1) - { - PushColumnClipRect(); - bb_with_spacing.Max.x -= (GetContentRegionMax().x - max_x); - } - - if (flags & ImGuiSelectableFlags_Disabled) PushStyleColor(ImGuiCol_Text, g.Style.Colors[ImGuiCol_TextDisabled]); - RenderTextClipped(bb.Min, bb_with_spacing.Max, label, NULL, &label_size, ImVec2(0.0f,0.0f)); - if (flags & ImGuiSelectableFlags_Disabled) PopStyleColor(); - - // Automatically close popups - if (pressed && !(flags & ImGuiSelectableFlags_DontClosePopups) && (window->Flags & ImGuiWindowFlags_Popup)) - CloseCurrentPopup(); - return pressed; -} - -bool ImGui::Selectable(const char* label, bool* p_selected, ImGuiSelectableFlags flags, const ImVec2& size_arg) -{ - if (Selectable(label, *p_selected, flags, size_arg)) - { - *p_selected = !*p_selected; - return true; - } - return false; -} - -// Helper to calculate the size of a listbox and display a label on the right. -// Tip: To have a list filling the entire window width, PushItemWidth(-1) and pass an empty label "##empty" -bool ImGui::ListBoxHeader(const char* label, const ImVec2& size_arg) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - const ImGuiStyle& style = GetStyle(); - const ImGuiID id = GetID(label); - const ImVec2 label_size = CalcTextSize(label, NULL, true); - - // Size default to hold ~7 items. Fractional number of items helps seeing that we can scroll down/up without looking at scrollbar. - ImVec2 size = CalcItemSize(size_arg, CalcItemWidth(), GetTextLineHeightWithSpacing() * 7.4f + style.ItemSpacing.y); - ImVec2 frame_size = ImVec2(size.x, ImMax(size.y, label_size.y)); - ImRect frame_bb(window->DC.CursorPos, window->DC.CursorPos + frame_size); - ImRect bb(frame_bb.Min, frame_bb.Max + ImVec2(label_size.x > 0.0f ? style.ItemInnerSpacing.x + label_size.x : 0.0f, 0.0f)); - window->DC.LastItemRect = bb; - - BeginGroup(); - if (label_size.x > 0) - RenderText(ImVec2(frame_bb.Max.x + style.ItemInnerSpacing.x, frame_bb.Min.y + style.FramePadding.y), label); - - BeginChildFrame(id, frame_bb.GetSize()); - return true; -} - -bool ImGui::ListBoxHeader(const char* label, int items_count, int height_in_items) -{ - // Size default to hold ~7 items. Fractional number of items helps seeing that we can scroll down/up without looking at scrollbar. - // However we don't add +0.40f if items_count <= height_in_items. It is slightly dodgy, because it means a dynamic list of items will make the widget resize occasionally when it crosses that size. - // I am expecting that someone will come and complain about this behavior in a remote future, then we can advise on a better solution. - if (height_in_items < 0) - height_in_items = ImMin(items_count, 7); - float height_in_items_f = height_in_items < items_count ? (height_in_items + 0.40f) : (height_in_items + 0.00f); - - // We include ItemSpacing.y so that a list sized for the exact number of items doesn't make a scrollbar appears. We could also enforce that by passing a flag to BeginChild(). - ImVec2 size; - size.x = 0.0f; - size.y = GetTextLineHeightWithSpacing() * height_in_items_f + GetStyle().ItemSpacing.y; - return ListBoxHeader(label, size); -} - -void ImGui::ListBoxFooter() -{ - ImGuiWindow* parent_window = GetParentWindow(); - const ImRect bb = parent_window->DC.LastItemRect; - const ImGuiStyle& style = GetStyle(); - - EndChildFrame(); - - // Redeclare item size so that it includes the label (we have stored the full size in LastItemRect) - // We call SameLine() to restore DC.CurrentLine* data - SameLine(); - parent_window->DC.CursorPos = bb.Min; - ItemSize(bb, style.FramePadding.y); - EndGroup(); -} - -bool ImGui::ListBox(const char* label, int* current_item, const char** items, int items_count, int height_items) -{ - const bool value_changed = ListBox(label, current_item, Items_ArrayGetter, (void*)items, items_count, height_items); - return value_changed; -} - -bool ImGui::ListBox(const char* label, int* current_item, bool (*items_getter)(void*, int, const char**), void* data, int items_count, int height_in_items) -{ - if (!ListBoxHeader(label, items_count, height_in_items)) - return false; - - // Assume all items have even height (= 1 line of text). If you need items of different or variable sizes you can create a custom version of ListBox() in your code without using the clipper. - bool value_changed = false; - ImGuiListClipper clipper(items_count, GetTextLineHeightWithSpacing()); - while (clipper.Step()) - for (int i = clipper.DisplayStart; i < clipper.DisplayEnd; i++) - { - const bool item_selected = (i == *current_item); - const char* item_text; - if (!items_getter(data, i, &item_text)) - item_text = "*Unknown item*"; - - PushID(i); - if (Selectable(item_text, item_selected)) - { - *current_item = i; - value_changed = true; - } - PopID(); - } - ListBoxFooter(); - return value_changed; -} - -bool ImGui::MenuItem(const char* label, const char* shortcut, bool selected, bool enabled) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - ImVec2 pos = window->DC.CursorPos; - ImVec2 label_size = CalcTextSize(label, NULL, true); - ImVec2 shortcut_size = shortcut ? CalcTextSize(shortcut, NULL) : ImVec2(0.0f, 0.0f); - float w = window->MenuColumns.DeclColumns(label_size.x, shortcut_size.x, (float)(int)(g.FontSize * 1.20f)); // Feedback for next frame - float extra_w = ImMax(0.0f, GetContentRegionAvail().x - w); - - bool pressed = Selectable(label, false, ImGuiSelectableFlags_MenuItem | ImGuiSelectableFlags_DrawFillAvailWidth | (enabled ? 0 : ImGuiSelectableFlags_Disabled), ImVec2(w, 0.0f)); - if (shortcut_size.x > 0.0f) - { - PushStyleColor(ImGuiCol_Text, g.Style.Colors[ImGuiCol_TextDisabled]); - RenderText(pos + ImVec2(window->MenuColumns.Pos[1] + extra_w, 0.0f), shortcut, NULL, false); - PopStyleColor(); - } - - if (selected) - RenderCheckMark(pos + ImVec2(window->MenuColumns.Pos[2] + extra_w + g.FontSize * 0.20f, 0.0f), GetColorU32(enabled ? ImGuiCol_Text : ImGuiCol_TextDisabled)); - - return pressed; -} - -bool ImGui::MenuItem(const char* label, const char* shortcut, bool* p_selected, bool enabled) -{ - if (MenuItem(label, shortcut, p_selected ? *p_selected : false, enabled)) - { - if (p_selected) - *p_selected = !*p_selected; - return true; - } - return false; -} - -bool ImGui::BeginMainMenuBar() -{ - ImGuiContext& g = *GImGui; - SetNextWindowPos(ImVec2(0.0f, 0.0f)); - SetNextWindowSize(ImVec2(g.IO.DisplaySize.x, g.FontBaseSize + g.Style.FramePadding.y * 2.0f)); - PushStyleVar(ImGuiStyleVar_WindowRounding, 0.0f); - PushStyleVar(ImGuiStyleVar_WindowMinSize, ImVec2(0,0)); - if (!Begin("##MainMenuBar", NULL, ImGuiWindowFlags_NoTitleBar|ImGuiWindowFlags_NoResize|ImGuiWindowFlags_NoMove|ImGuiWindowFlags_NoScrollbar|ImGuiWindowFlags_NoSavedSettings|ImGuiWindowFlags_MenuBar) - || !BeginMenuBar()) - { - End(); - PopStyleVar(2); - return false; - } - g.CurrentWindow->DC.MenuBarOffsetX += g.Style.DisplaySafeAreaPadding.x; - return true; -} - -void ImGui::EndMainMenuBar() -{ - EndMenuBar(); - End(); - PopStyleVar(2); -} - -bool ImGui::BeginMenuBar() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - if (!(window->Flags & ImGuiWindowFlags_MenuBar)) - return false; - - IM_ASSERT(!window->DC.MenuBarAppending); - BeginGroup(); // Save position - PushID("##menubar"); - ImRect rect = window->MenuBarRect(); - PushClipRect(ImVec2(ImFloor(rect.Min.x+0.5f), ImFloor(rect.Min.y + window->BorderSize + 0.5f)), ImVec2(ImFloor(rect.Max.x+0.5f), ImFloor(rect.Max.y+0.5f)), false); - window->DC.CursorPos = ImVec2(rect.Min.x + window->DC.MenuBarOffsetX, rect.Min.y);// + g.Style.FramePadding.y); - window->DC.LayoutType = ImGuiLayoutType_Horizontal; - window->DC.MenuBarAppending = true; - AlignFirstTextHeightToWidgets(); - return true; -} - -void ImGui::EndMenuBar() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - IM_ASSERT(window->Flags & ImGuiWindowFlags_MenuBar); - IM_ASSERT(window->DC.MenuBarAppending); - PopClipRect(); - PopID(); - window->DC.MenuBarOffsetX = window->DC.CursorPos.x - window->MenuBarRect().Min.x; - window->DC.GroupStack.back().AdvanceCursor = false; - EndGroup(); - window->DC.LayoutType = ImGuiLayoutType_Vertical; - window->DC.MenuBarAppending = false; -} - -bool ImGui::BeginMenu(const char* label, bool enabled) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - - ImVec2 label_size = CalcTextSize(label, NULL, true); - ImGuiWindow* backed_focused_window = g.FocusedWindow; - - bool pressed; - bool menu_is_open = IsPopupOpen(id); - bool menuset_is_open = !(window->Flags & ImGuiWindowFlags_Popup) && (g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].ParentMenuSet == window->GetID("##menus")); - if (menuset_is_open) - g.FocusedWindow = window; - - ImVec2 popup_pos, pos = window->DC.CursorPos; - if (window->DC.LayoutType == ImGuiLayoutType_Horizontal) - { - popup_pos = ImVec2(pos.x - window->WindowPadding.x, pos.y - style.FramePadding.y + window->MenuBarHeight()); - window->DC.CursorPos.x += (float)(int)(style.ItemSpacing.x * 0.5f); - PushStyleVar(ImGuiStyleVar_ItemSpacing, style.ItemSpacing * 2.0f); - float w = label_size.x; - pressed = Selectable(label, menu_is_open, ImGuiSelectableFlags_Menu | ImGuiSelectableFlags_DontClosePopups | (!enabled ? ImGuiSelectableFlags_Disabled : 0), ImVec2(w, 0.0f)); - PopStyleVar(); - SameLine(); - window->DC.CursorPos.x += (float)(int)(style.ItemSpacing.x * 0.5f); - } - else - { - popup_pos = ImVec2(pos.x, pos.y - style.WindowPadding.y); - float w = window->MenuColumns.DeclColumns(label_size.x, 0.0f, (float)(int)(g.FontSize * 1.20f)); // Feedback to next frame - float extra_w = ImMax(0.0f, GetContentRegionAvail().x - w); - pressed = Selectable(label, menu_is_open, ImGuiSelectableFlags_Menu | ImGuiSelectableFlags_DontClosePopups | ImGuiSelectableFlags_DrawFillAvailWidth | (!enabled ? ImGuiSelectableFlags_Disabled : 0), ImVec2(w, 0.0f)); - if (!enabled) PushStyleColor(ImGuiCol_Text, g.Style.Colors[ImGuiCol_TextDisabled]); - RenderCollapseTriangle(pos + ImVec2(window->MenuColumns.Pos[2] + extra_w + g.FontSize * 0.20f, 0.0f), false); - if (!enabled) PopStyleColor(); - } - - bool hovered = enabled && IsHovered(window->DC.LastItemRect, id); - if (menuset_is_open) - g.FocusedWindow = backed_focused_window; - - bool want_open = false, want_close = false; - if (window->Flags & (ImGuiWindowFlags_Popup|ImGuiWindowFlags_ChildMenu)) - { - // Implement http://bjk5.com/post/44698559168/breaking-down-amazons-mega-dropdown to avoid using timers, so menus feels more reactive. - bool moving_within_opened_triangle = false; - if (g.HoveredWindow == window && g.OpenPopupStack.Size > g.CurrentPopupStack.Size && g.OpenPopupStack[g.CurrentPopupStack.Size].ParentWindow == window) - { - if (ImGuiWindow* next_window = g.OpenPopupStack[g.CurrentPopupStack.Size].Window) - { - ImRect next_window_rect = next_window->Rect(); - ImVec2 ta = g.IO.MousePos - g.IO.MouseDelta; - ImVec2 tb = (window->Pos.x < next_window->Pos.x) ? next_window_rect.GetTL() : next_window_rect.GetTR(); - ImVec2 tc = (window->Pos.x < next_window->Pos.x) ? next_window_rect.GetBL() : next_window_rect.GetBR(); - float extra = ImClamp(fabsf(ta.x - tb.x) * 0.30f, 5.0f, 30.0f); // add a bit of extra slack. - ta.x += (window->Pos.x < next_window->Pos.x) ? -0.5f : +0.5f; // to avoid numerical issues - tb.y = ta.y + ImMax((tb.y - extra) - ta.y, -100.0f); // triangle is maximum 200 high to limit the slope and the bias toward large sub-menus // FIXME: Multiply by fb_scale? - tc.y = ta.y + ImMin((tc.y + extra) - ta.y, +100.0f); - moving_within_opened_triangle = ImIsPointInTriangle(g.IO.MousePos, ta, tb, tc); - //window->DrawList->PushClipRectFullScreen(); window->DrawList->AddTriangleFilled(ta, tb, tc, moving_within_opened_triangle ? IM_COL32(0,128,0,128) : IM_COL32(128,0,0,128)); window->DrawList->PopClipRect(); // Debug - } - } - - want_close = (menu_is_open && !hovered && g.HoveredWindow == window && g.HoveredIdPreviousFrame != 0 && g.HoveredIdPreviousFrame != id && !moving_within_opened_triangle); - want_open = (!menu_is_open && hovered && !moving_within_opened_triangle) || (!menu_is_open && hovered && pressed); - } - else if (menu_is_open && pressed && menuset_is_open) // menu-bar: click open menu to close - { - want_close = true; - want_open = menu_is_open = false; - } - else if (pressed || (hovered && menuset_is_open && !menu_is_open)) // menu-bar: first click to open, then hover to open others - want_open = true; - if (!enabled) // explicitly close if an open menu becomes disabled, facilitate users code a lot in pattern such as 'if (BeginMenu("options", has_object)) { ..use object.. }' - want_close = true; - if (want_close && IsPopupOpen(id)) - ClosePopupToLevel(GImGui->CurrentPopupStack.Size); - - if (!menu_is_open && want_open && g.OpenPopupStack.Size > g.CurrentPopupStack.Size) - { - // Don't recycle same menu level in the same frame, first close the other menu and yield for a frame. - OpenPopup(label); - return false; - } - - menu_is_open |= want_open; - if (want_open) - OpenPopup(label); - - if (menu_is_open) - { - SetNextWindowPos(popup_pos, ImGuiSetCond_Always); - ImGuiWindowFlags flags = ImGuiWindowFlags_ShowBorders | ((window->Flags & (ImGuiWindowFlags_Popup|ImGuiWindowFlags_ChildMenu)) ? ImGuiWindowFlags_ChildMenu|ImGuiWindowFlags_ChildWindow : ImGuiWindowFlags_ChildMenu); - menu_is_open = BeginPopupEx(label, flags); // menu_is_open can be 'false' when the popup is completely clipped (e.g. zero size display) - } - - return menu_is_open; -} - -void ImGui::EndMenu() -{ - EndPopup(); -} - -// A little colored square. Return true when clicked. -// FIXME: May want to display/ignore the alpha component in the color display? Yet show it in the tooltip. -bool ImGui::ColorButton(const ImVec4& col, bool small_height, bool outline_border) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID("#colorbutton"); - const float square_size = g.FontSize; - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + ImVec2(square_size + style.FramePadding.y*2, square_size + (small_height ? 0 : style.FramePadding.y*2))); - ItemSize(bb, small_height ? 0.0f : style.FramePadding.y); - if (!ItemAdd(bb, &id)) - return false; - - bool hovered, held; - bool pressed = ButtonBehavior(bb, id, &hovered, &held); - RenderFrame(bb.Min, bb.Max, GetColorU32(col), outline_border, style.FrameRounding); - - if (hovered) - SetTooltip("Color:\n(%.2f,%.2f,%.2f,%.2f)\n#%02X%02X%02X%02X", col.x, col.y, col.z, col.w, IM_F32_TO_INT8_SAT(col.x), IM_F32_TO_INT8_SAT(col.y), IM_F32_TO_INT8_SAT(col.z), IM_F32_TO_INT8_SAT(col.z)); - - return pressed; -} - -bool ImGui::ColorEdit3(const char* label, float col[3]) -{ - float col4[4]; - col4[0] = col[0]; - col4[1] = col[1]; - col4[2] = col[2]; - col4[3] = 1.0f; - const bool value_changed = ColorEdit4(label, col4, false); - col[0] = col4[0]; - col[1] = col4[1]; - col[2] = col4[2]; - return value_changed; -} - -// Edit colors components (each component in 0.0f..1.0f range -// Use CTRL-Click to input value and TAB to go to next item. -bool ImGui::ColorEdit4(const char* label, float col[4], bool alpha) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return false; - - ImGuiContext& g = *GImGui; - const ImGuiStyle& style = g.Style; - const ImGuiID id = window->GetID(label); - const float w_full = CalcItemWidth(); - const float square_sz = (g.FontSize + style.FramePadding.y * 2.0f); - - ImGuiColorEditMode edit_mode = window->DC.ColorEditMode; - if (edit_mode == ImGuiColorEditMode_UserSelect || edit_mode == ImGuiColorEditMode_UserSelectShowButton) - edit_mode = g.ColorEditModeStorage.GetInt(id, 0) % 3; - - float f[4] = { col[0], col[1], col[2], col[3] }; - if (edit_mode == ImGuiColorEditMode_HSV) - ColorConvertRGBtoHSV(f[0], f[1], f[2], f[0], f[1], f[2]); - - int i[4] = { IM_F32_TO_INT8_UNBOUND(f[0]), IM_F32_TO_INT8_UNBOUND(f[1]), IM_F32_TO_INT8_UNBOUND(f[2]), IM_F32_TO_INT8_UNBOUND(f[3]) }; - - int components = alpha ? 4 : 3; - bool value_changed = false; - - BeginGroup(); - PushID(label); - - const bool hsv = (edit_mode == 1); - switch (edit_mode) - { - case ImGuiColorEditMode_RGB: - case ImGuiColorEditMode_HSV: - { - // RGB/HSV 0..255 Sliders - const float w_items_all = w_full - (square_sz + style.ItemInnerSpacing.x); - const float w_item_one = ImMax(1.0f, (float)(int)((w_items_all - (style.ItemInnerSpacing.x) * (components-1)) / (float)components)); - const float w_item_last = ImMax(1.0f, (float)(int)(w_items_all - (w_item_one + style.ItemInnerSpacing.x) * (components-1))); - - const bool hide_prefix = (w_item_one <= CalcTextSize("M:999").x); - const char* ids[4] = { "##X", "##Y", "##Z", "##W" }; - const char* fmt_table[3][4] = - { - { "%3.0f", "%3.0f", "%3.0f", "%3.0f" }, - { "R:%3.0f", "G:%3.0f", "B:%3.0f", "A:%3.0f" }, - { "H:%3.0f", "S:%3.0f", "V:%3.0f", "A:%3.0f" } - }; - const char** fmt = hide_prefix ? fmt_table[0] : hsv ? fmt_table[2] : fmt_table[1]; - - PushItemWidth(w_item_one); - for (int n = 0; n < components; n++) - { - if (n > 0) - SameLine(0, style.ItemInnerSpacing.x); - if (n + 1 == components) - PushItemWidth(w_item_last); - value_changed |= DragInt(ids[n], &i[n], 1.0f, 0, 255, fmt[n]); - } - PopItemWidth(); - PopItemWidth(); - } - break; - case ImGuiColorEditMode_HEX: - { - // RGB Hexadecimal Input - const float w_slider_all = w_full - square_sz; - char buf[64]; - if (alpha) - ImFormatString(buf, IM_ARRAYSIZE(buf), "#%02X%02X%02X%02X", i[0], i[1], i[2], i[3]); - else - ImFormatString(buf, IM_ARRAYSIZE(buf), "#%02X%02X%02X", i[0], i[1], i[2]); - PushItemWidth(w_slider_all - style.ItemInnerSpacing.x); - if (InputText("##Text", buf, IM_ARRAYSIZE(buf), ImGuiInputTextFlags_CharsHexadecimal | ImGuiInputTextFlags_CharsUppercase)) - { - value_changed |= true; - char* p = buf; - while (*p == '#' || ImCharIsSpace(*p)) - p++; - i[0] = i[1] = i[2] = i[3] = 0; - if (alpha) - sscanf(p, "%02X%02X%02X%02X", (unsigned int*)&i[0], (unsigned int*)&i[1], (unsigned int*)&i[2], (unsigned int*)&i[3]); // Treat at unsigned (%X is unsigned) - else - sscanf(p, "%02X%02X%02X", (unsigned int*)&i[0], (unsigned int*)&i[1], (unsigned int*)&i[2]); - } - PopItemWidth(); - } - break; - } - - SameLine(0, style.ItemInnerSpacing.x); - - const ImVec4 col_display(col[0], col[1], col[2], 1.0f); - if (ColorButton(col_display)) - g.ColorEditModeStorage.SetInt(id, (edit_mode + 1) % 3); // Don't set local copy of 'edit_mode' right away! - - // Recreate our own tooltip over's ColorButton() one because we want to display correct alpha here - if (IsItemHovered()) - SetTooltip("Color:\n(%.2f,%.2f,%.2f,%.2f)\n#%02X%02X%02X%02X", col[0], col[1], col[2], col[3], IM_F32_TO_INT8_SAT(col[0]), IM_F32_TO_INT8_SAT(col[1]), IM_F32_TO_INT8_SAT(col[2]), IM_F32_TO_INT8_SAT(col[3])); - - if (window->DC.ColorEditMode == ImGuiColorEditMode_UserSelectShowButton) - { - SameLine(0, style.ItemInnerSpacing.x); - const char* button_titles[3] = { "RGB", "HSV", "HEX" }; - if (ButtonEx(button_titles[edit_mode], ImVec2(0,0), ImGuiButtonFlags_DontClosePopups)) - g.ColorEditModeStorage.SetInt(id, (edit_mode + 1) % 3); // Don't set local copy of 'edit_mode' right away! - } - - const char* label_display_end = FindRenderedTextEnd(label); - if (label != label_display_end) - { - SameLine(0, (window->DC.ColorEditMode == ImGuiColorEditMode_UserSelectShowButton) ? -1.0f : style.ItemInnerSpacing.x); - TextUnformatted(label, label_display_end); - } - - // Convert back - for (int n = 0; n < 4; n++) - f[n] = i[n] / 255.0f; - if (edit_mode == 1) - ColorConvertHSVtoRGB(f[0], f[1], f[2], f[0], f[1], f[2]); - - if (value_changed) - { - col[0] = f[0]; - col[1] = f[1]; - col[2] = f[2]; - if (alpha) - col[3] = f[3]; - } - - PopID(); - EndGroup(); - - return value_changed; -} - -void ImGui::ColorEditMode(ImGuiColorEditMode mode) -{ - ImGuiWindow* window = GetCurrentWindow(); - window->DC.ColorEditMode = mode; -} - -// Horizontal separating line. -void ImGui::Separator() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - if (window->DC.ColumnsCount > 1) - PopClipRect(); - - float x1 = window->Pos.x; - float x2 = window->Pos.x + window->Size.x; - if (!window->DC.GroupStack.empty()) - x1 += window->DC.IndentX; - - const ImRect bb(ImVec2(x1, window->DC.CursorPos.y), ImVec2(x2, window->DC.CursorPos.y)); - ItemSize(ImVec2(0.0f, 0.0f)); // NB: we don't provide our width so that it doesn't get feed back into AutoFit // FIXME: Height should be 1.0f not 0.0f ? - if (!ItemAdd(bb, NULL)) - { - if (window->DC.ColumnsCount > 1) - PushColumnClipRect(); - return; - } - - window->DrawList->AddLine(bb.Min, bb.Max, GetColorU32(ImGuiCol_Border)); - - ImGuiContext& g = *GImGui; - if (g.LogEnabled) - LogText(IM_NEWLINE "--------------------------------"); - - if (window->DC.ColumnsCount > 1) - { - PushColumnClipRect(); - window->DC.ColumnsCellMinY = window->DC.CursorPos.y; - } -} - -void ImGui::Spacing() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - ItemSize(ImVec2(0,0)); -} - -void ImGui::Dummy(const ImVec2& size) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - const ImRect bb(window->DC.CursorPos, window->DC.CursorPos + size); - ItemSize(bb); - ItemAdd(bb, NULL); -} - -bool ImGui::IsRectVisible(const ImVec2& size) -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ClipRect.Overlaps(ImRect(window->DC.CursorPos, window->DC.CursorPos + size)); -} - -bool ImGui::IsRectVisible(const ImVec2& rect_min, const ImVec2& rect_max) -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->ClipRect.Overlaps(ImRect(rect_min, rect_max)); -} - -// Lock horizontal starting position + capture group bounding box into one "item" (so you can use IsItemHovered() or layout primitives such as SameLine() on whole group, etc.) -void ImGui::BeginGroup() -{ - ImGuiWindow* window = GetCurrentWindow(); - - window->DC.GroupStack.resize(window->DC.GroupStack.Size + 1); - ImGuiGroupData& group_data = window->DC.GroupStack.back(); - group_data.BackupCursorPos = window->DC.CursorPos; - group_data.BackupCursorMaxPos = window->DC.CursorMaxPos; - group_data.BackupIndentX = window->DC.IndentX; - group_data.BackupGroupOffsetX = window->DC.GroupOffsetX; - group_data.BackupCurrentLineHeight = window->DC.CurrentLineHeight; - group_data.BackupCurrentLineTextBaseOffset = window->DC.CurrentLineTextBaseOffset; - group_data.BackupLogLinePosY = window->DC.LogLinePosY; - group_data.BackupActiveIdIsAlive = GImGui->ActiveIdIsAlive; - group_data.AdvanceCursor = true; - - window->DC.GroupOffsetX = window->DC.CursorPos.x - window->Pos.x - window->DC.ColumnsOffsetX; - window->DC.IndentX = window->DC.GroupOffsetX; - window->DC.CursorMaxPos = window->DC.CursorPos; - window->DC.CurrentLineHeight = 0.0f; - window->DC.LogLinePosY = window->DC.CursorPos.y - 9999.0f; -} - -void ImGui::EndGroup() -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - - IM_ASSERT(!window->DC.GroupStack.empty()); // Mismatched BeginGroup()/EndGroup() calls - - ImGuiGroupData& group_data = window->DC.GroupStack.back(); - - ImRect group_bb(group_data.BackupCursorPos, window->DC.CursorMaxPos); - group_bb.Max.y -= g.Style.ItemSpacing.y; // Cancel out last vertical spacing because we are adding one ourselves. - group_bb.Max = ImMax(group_bb.Min, group_bb.Max); - - window->DC.CursorPos = group_data.BackupCursorPos; - window->DC.CursorMaxPos = ImMax(group_data.BackupCursorMaxPos, window->DC.CursorMaxPos); - window->DC.CurrentLineHeight = group_data.BackupCurrentLineHeight; - window->DC.CurrentLineTextBaseOffset = group_data.BackupCurrentLineTextBaseOffset; - window->DC.IndentX = group_data.BackupIndentX; - window->DC.GroupOffsetX = group_data.BackupGroupOffsetX; - window->DC.LogLinePosY = window->DC.CursorPos.y - 9999.0f; - - if (group_data.AdvanceCursor) - { - window->DC.CurrentLineTextBaseOffset = ImMax(window->DC.PrevLineTextBaseOffset, group_data.BackupCurrentLineTextBaseOffset); // FIXME: Incorrect, we should grab the base offset from the *first line* of the group but it is hard to obtain now. - ItemSize(group_bb.GetSize(), group_data.BackupCurrentLineTextBaseOffset); - ItemAdd(group_bb, NULL); - } - - // If the current ActiveId was declared within the boundary of our group, we copy it to LastItemId so IsItemActive() will function on the entire group. - // It would be be neater if we replaced window.DC.LastItemId by e.g. 'bool LastItemIsActive', but if you search for LastItemId you'll notice it is only used in that context. - const bool active_id_within_group = (!group_data.BackupActiveIdIsAlive && g.ActiveIdIsAlive && g.ActiveId && g.ActiveIdWindow->RootWindow == window->RootWindow); - if (active_id_within_group) - window->DC.LastItemId = g.ActiveId; - if (active_id_within_group && g.HoveredId == g.ActiveId) - window->DC.LastItemHoveredAndUsable = window->DC.LastItemHoveredRect = true; - - window->DC.GroupStack.pop_back(); - - //window->DrawList->AddRect(group_bb.Min, group_bb.Max, IM_COL32(255,0,255,255)); // Debug -} - -// Gets back to previous line and continue with horizontal layout -// pos_x == 0 : follow right after previous item -// pos_x != 0 : align to specified x position (relative to window/group left) -// spacing_w < 0 : use default spacing if pos_x == 0, no spacing if pos_x != 0 -// spacing_w >= 0 : enforce spacing amount -void ImGui::SameLine(float pos_x, float spacing_w) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - - ImGuiContext& g = *GImGui; - if (pos_x != 0.0f) - { - if (spacing_w < 0.0f) spacing_w = 0.0f; - window->DC.CursorPos.x = window->Pos.x - window->Scroll.x + pos_x + spacing_w + window->DC.GroupOffsetX + window->DC.ColumnsOffsetX; - window->DC.CursorPos.y = window->DC.CursorPosPrevLine.y; - } - else - { - if (spacing_w < 0.0f) spacing_w = g.Style.ItemSpacing.x; - window->DC.CursorPos.x = window->DC.CursorPosPrevLine.x + spacing_w; - window->DC.CursorPos.y = window->DC.CursorPosPrevLine.y; - } - window->DC.CurrentLineHeight = window->DC.PrevLineHeight; - window->DC.CurrentLineTextBaseOffset = window->DC.PrevLineTextBaseOffset; -} - -void ImGui::NewLine() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems) - return; - if (window->DC.CurrentLineHeight > 0.0f) // In the event that we are on a line with items that is smaller that FontSize high, we will preserve its height. - ItemSize(ImVec2(0,0)); - else - ItemSize(ImVec2(0.0f, GImGui->FontSize)); -} - -void ImGui::NextColumn() -{ - ImGuiWindow* window = GetCurrentWindow(); - if (window->SkipItems || window->DC.ColumnsCount <= 1) - return; - - ImGuiContext& g = *GImGui; - PopItemWidth(); - PopClipRect(); - - window->DC.ColumnsCellMaxY = ImMax(window->DC.ColumnsCellMaxY, window->DC.CursorPos.y); - if (++window->DC.ColumnsCurrent < window->DC.ColumnsCount) - { - // Columns 1+ cancel out IndentX - window->DC.ColumnsOffsetX = GetColumnOffset(window->DC.ColumnsCurrent) - window->DC.IndentX + g.Style.ItemSpacing.x; - window->DrawList->ChannelsSetCurrent(window->DC.ColumnsCurrent); - } - else - { - window->DC.ColumnsCurrent = 0; - window->DC.ColumnsOffsetX = 0.0f; - window->DC.ColumnsCellMinY = window->DC.ColumnsCellMaxY; - window->DrawList->ChannelsSetCurrent(0); - } - window->DC.CursorPos.x = (float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX); - window->DC.CursorPos.y = window->DC.ColumnsCellMinY; - window->DC.CurrentLineHeight = 0.0f; - window->DC.CurrentLineTextBaseOffset = 0.0f; - - PushColumnClipRect(); - PushItemWidth(GetColumnWidth() * 0.65f); // FIXME: Move on columns setup -} - -int ImGui::GetColumnIndex() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.ColumnsCurrent; -} - -int ImGui::GetColumnsCount() -{ - ImGuiWindow* window = GetCurrentWindowRead(); - return window->DC.ColumnsCount; -} - -static float GetDraggedColumnOffset(int column_index) -{ - // Active (dragged) column always follow mouse. The reason we need this is that dragging a column to the right edge of an auto-resizing - // window creates a feedback loop because we store normalized positions. So while dragging we enforce absolute positioning. - ImGuiContext& g = *GImGui; - ImGuiWindow* window = ImGui::GetCurrentWindowRead(); - IM_ASSERT(column_index > 0); // We cannot drag column 0. If you get this assert you may have a conflict between the ID of your columns and another widgets. - IM_ASSERT(g.ActiveId == window->DC.ColumnsSetId + ImGuiID(column_index)); - - float x = g.IO.MousePos.x - g.ActiveIdClickOffset.x - window->Pos.x; - x = ImClamp(x, ImGui::GetColumnOffset(column_index-1)+g.Style.ColumnsMinSpacing, ImGui::GetColumnOffset(column_index+1)-g.Style.ColumnsMinSpacing); - - return (float)(int)x; -} - -float ImGui::GetColumnOffset(int column_index) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindowRead(); - if (column_index < 0) - column_index = window->DC.ColumnsCurrent; - - if (g.ActiveId) - { - const ImGuiID column_id = window->DC.ColumnsSetId + ImGuiID(column_index); - if (g.ActiveId == column_id) - return GetDraggedColumnOffset(column_index); - } - - IM_ASSERT(column_index < window->DC.ColumnsData.Size); - const float t = window->DC.ColumnsData[column_index].OffsetNorm; - const float x_offset = window->DC.ColumnsMinX + t * (window->DC.ColumnsMaxX - window->DC.ColumnsMinX); - return (float)(int)x_offset; -} - -void ImGui::SetColumnOffset(int column_index, float offset) -{ - ImGuiWindow* window = GetCurrentWindow(); - if (column_index < 0) - column_index = window->DC.ColumnsCurrent; - - IM_ASSERT(column_index < window->DC.ColumnsData.Size); - const float t = (offset - window->DC.ColumnsMinX) / (window->DC.ColumnsMaxX - window->DC.ColumnsMinX); - window->DC.ColumnsData[column_index].OffsetNorm = t; - - const ImGuiID column_id = window->DC.ColumnsSetId + ImGuiID(column_index); - window->DC.StateStorage->SetFloat(column_id, t); -} - -float ImGui::GetColumnWidth(int column_index) -{ - ImGuiWindow* window = GetCurrentWindowRead(); - if (column_index < 0) - column_index = window->DC.ColumnsCurrent; - - float w = GetColumnOffset(column_index+1) - GetColumnOffset(column_index); - return w; -} - -static void PushColumnClipRect(int column_index) -{ - ImGuiWindow* window = ImGui::GetCurrentWindow(); - if (column_index < 0) - column_index = window->DC.ColumnsCurrent; - - float x1 = ImFloor(0.5f + window->Pos.x + ImGui::GetColumnOffset(column_index) - 1.0f); - float x2 = ImFloor(0.5f + window->Pos.x + ImGui::GetColumnOffset(column_index+1) - 1.0f); - ImGui::PushClipRect(ImVec2(x1,-FLT_MAX), ImVec2(x2,+FLT_MAX), true); -} - -void ImGui::Columns(int columns_count, const char* id, bool border) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - IM_ASSERT(columns_count >= 1); - - if (window->DC.ColumnsCount != 1) - { - if (window->DC.ColumnsCurrent != 0) - ItemSize(ImVec2(0,0)); // Advance to column 0 - PopItemWidth(); - PopClipRect(); - window->DrawList->ChannelsMerge(); - - window->DC.ColumnsCellMaxY = ImMax(window->DC.ColumnsCellMaxY, window->DC.CursorPos.y); - window->DC.CursorPos.y = window->DC.ColumnsCellMaxY; - } - - // Draw columns borders and handle resize at the time of "closing" a columns set - if (window->DC.ColumnsCount != columns_count && window->DC.ColumnsCount != 1 && window->DC.ColumnsShowBorders && !window->SkipItems) - { - const float y1 = window->DC.ColumnsStartPosY; - const float y2 = window->DC.CursorPos.y; - for (int i = 1; i < window->DC.ColumnsCount; i++) - { - float x = window->Pos.x + GetColumnOffset(i); - const ImGuiID column_id = window->DC.ColumnsSetId + ImGuiID(i); - const ImRect column_rect(ImVec2(x-4,y1),ImVec2(x+4,y2)); - if (IsClippedEx(column_rect, &column_id, false)) - continue; - - bool hovered, held; - ButtonBehavior(column_rect, column_id, &hovered, &held); - if (hovered || held) - g.MouseCursor = ImGuiMouseCursor_ResizeEW; - - // Draw before resize so our items positioning are in sync with the line being drawn - const ImU32 col = GetColorU32(held ? ImGuiCol_ColumnActive : hovered ? ImGuiCol_ColumnHovered : ImGuiCol_Column); - const float xi = (float)(int)x; - window->DrawList->AddLine(ImVec2(xi, y1+1.0f), ImVec2(xi, y2), col); - - if (held) - { - if (g.ActiveIdIsJustActivated) - g.ActiveIdClickOffset.x -= 4; // Store from center of column line (we used a 8 wide rect for columns clicking) - x = GetDraggedColumnOffset(i); - SetColumnOffset(i, x); - } - } - } - - // Differentiate column ID with an arbitrary prefix for cases where users name their columns set the same as another widget. - // In addition, when an identifier isn't explicitly provided we include the number of columns in the hash to make it uniquer. - PushID(0x11223347 + (id ? 0 : columns_count)); - window->DC.ColumnsSetId = window->GetID(id ? id : "columns"); - PopID(); - - // Set state for first column - window->DC.ColumnsCurrent = 0; - window->DC.ColumnsCount = columns_count; - window->DC.ColumnsShowBorders = border; - - const float content_region_width = (window->SizeContentsExplicit.x != 0.0f) ? window->SizeContentsExplicit.x : window->Size.x; - window->DC.ColumnsMinX = window->DC.IndentX; // Lock our horizontal range - window->DC.ColumnsMaxX = content_region_width - window->Scroll.x - ((window->Flags & ImGuiWindowFlags_NoScrollbar) ? 0 : g.Style.ScrollbarSize);// - window->WindowPadding().x; - window->DC.ColumnsStartPosY = window->DC.CursorPos.y; - window->DC.ColumnsCellMinY = window->DC.ColumnsCellMaxY = window->DC.CursorPos.y; - window->DC.ColumnsOffsetX = 0.0f; - window->DC.CursorPos.x = (float)(int)(window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX); - - if (window->DC.ColumnsCount != 1) - { - // Cache column offsets - window->DC.ColumnsData.resize(columns_count + 1); - for (int column_index = 0; column_index < columns_count + 1; column_index++) - { - const ImGuiID column_id = window->DC.ColumnsSetId + ImGuiID(column_index); - KeepAliveID(column_id); - const float default_t = column_index / (float)window->DC.ColumnsCount; - const float t = window->DC.StateStorage->GetFloat(column_id, default_t); // Cheaply store our floating point value inside the integer (could store a union into the map?) - window->DC.ColumnsData[column_index].OffsetNorm = t; - } - window->DrawList->ChannelsSplit(window->DC.ColumnsCount); - PushColumnClipRect(); - PushItemWidth(GetColumnWidth() * 0.65f); - } - else - { - window->DC.ColumnsData.resize(0); - } -} - -void ImGui::Indent(float indent_w) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - window->DC.IndentX += (indent_w > 0.0f) ? indent_w : g.Style.IndentSpacing; - window->DC.CursorPos.x = window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX; -} - -void ImGui::Unindent(float indent_w) -{ - ImGuiContext& g = *GImGui; - ImGuiWindow* window = GetCurrentWindow(); - window->DC.IndentX -= (indent_w > 0.0f) ? indent_w : g.Style.IndentSpacing; - window->DC.CursorPos.x = window->Pos.x + window->DC.IndentX + window->DC.ColumnsOffsetX; -} - -void ImGui::TreePush(const char* str_id) -{ - ImGuiWindow* window = GetCurrentWindow(); - Indent(); - window->DC.TreeDepth++; - PushID(str_id ? str_id : "#TreePush"); -} - -void ImGui::TreePush(const void* ptr_id) -{ - ImGuiWindow* window = GetCurrentWindow(); - Indent(); - window->DC.TreeDepth++; - PushID(ptr_id ? ptr_id : (const void*)"#TreePush"); -} - -void ImGui::TreePushRawID(ImGuiID id) -{ - ImGuiWindow* window = GetCurrentWindow(); - Indent(); - window->DC.TreeDepth++; - window->IDStack.push_back(id); -} - -void ImGui::TreePop() -{ - ImGuiWindow* window = GetCurrentWindow(); - Unindent(); - window->DC.TreeDepth--; - PopID(); -} - -void ImGui::Value(const char* prefix, bool b) -{ - Text("%s: %s", prefix, (b ? "true" : "false")); -} - -void ImGui::Value(const char* prefix, int v) -{ - Text("%s: %d", prefix, v); -} - -void ImGui::Value(const char* prefix, unsigned int v) -{ - Text("%s: %d", prefix, v); -} - -void ImGui::Value(const char* prefix, float v, const char* float_format) -{ - if (float_format) - { - char fmt[64]; - ImFormatString(fmt, IM_ARRAYSIZE(fmt), "%%s: %s", float_format); - Text(fmt, prefix, v); - } - else - { - Text("%s: %.3f", prefix, v); - } -} - -// FIXME: May want to remove those helpers? -void ImGui::ValueColor(const char* prefix, const ImVec4& v) -{ - Text("%s: (%.2f,%.2f,%.2f,%.2f)", prefix, v.x, v.y, v.z, v.w); - SameLine(); - ColorButton(v, true); -} - -void ImGui::ValueColor(const char* prefix, ImU32 v) -{ - Text("%s: %08X", prefix, v); - SameLine(); - ColorButton(ColorConvertU32ToFloat4(v), true); -} - -//----------------------------------------------------------------------------- -// PLATFORM DEPENDENT HELPERS -//----------------------------------------------------------------------------- - -#if defined(_WIN32) && !defined(_WINDOWS_) && (!defined(IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCS) || !defined(IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCS)) -#undef WIN32_LEAN_AND_MEAN -#define WIN32_LEAN_AND_MEAN -#include <windows.h> -#endif - -// Win32 API clipboard implementation -#if defined(_WIN32) && !defined(IMGUI_DISABLE_WIN32_DEFAULT_CLIPBOARD_FUNCS) - -#ifdef _MSC_VER -#pragma comment(lib, "user32") -#endif - -static const char* GetClipboardTextFn_DefaultImpl() -{ - static ImVector<char> buf_local; - buf_local.clear(); - if (!OpenClipboard(NULL)) - return NULL; - HANDLE wbuf_handle = GetClipboardData(CF_UNICODETEXT); - if (wbuf_handle == NULL) - return NULL; - if (ImWchar* wbuf_global = (ImWchar*)GlobalLock(wbuf_handle)) - { - int buf_len = ImTextCountUtf8BytesFromStr(wbuf_global, NULL) + 1; - buf_local.resize(buf_len); - ImTextStrToUtf8(buf_local.Data, buf_len, wbuf_global, NULL); - } - GlobalUnlock(wbuf_handle); - CloseClipboard(); - return buf_local.Data; -} - -static void SetClipboardTextFn_DefaultImpl(const char* text) -{ - if (!OpenClipboard(NULL)) - return; - const int wbuf_length = ImTextCountCharsFromUtf8(text, NULL) + 1; - HGLOBAL wbuf_handle = GlobalAlloc(GMEM_MOVEABLE, (SIZE_T)wbuf_length * sizeof(ImWchar)); - if (wbuf_handle == NULL) - return; - ImWchar* wbuf_global = (ImWchar*)GlobalLock(wbuf_handle); - ImTextStrFromUtf8(wbuf_global, wbuf_length, text, NULL); - GlobalUnlock(wbuf_handle); - EmptyClipboard(); - SetClipboardData(CF_UNICODETEXT, wbuf_handle); - CloseClipboard(); -} - -#else - -// Local ImGui-only clipboard implementation, if user hasn't defined better clipboard handlers -static const char* GetClipboardTextFn_DefaultImpl() -{ - return GImGui->PrivateClipboard; -} - -// Local ImGui-only clipboard implementation, if user hasn't defined better clipboard handlers -static void SetClipboardTextFn_DefaultImpl(const char* text) -{ - ImGuiContext& g = *GImGui; - if (g.PrivateClipboard) - { - ImGui::MemFree(g.PrivateClipboard); - g.PrivateClipboard = NULL; - } - const char* text_end = text + strlen(text); - g.PrivateClipboard = (char*)ImGui::MemAlloc((size_t)(text_end - text) + 1); - memcpy(g.PrivateClipboard, text, (size_t)(text_end - text)); - g.PrivateClipboard[(int)(text_end - text)] = 0; -} - -#endif - -// Win32 API IME support (for Asian languages, etc.) -#if defined(_WIN32) && !defined(__GNUC__) && !defined(IMGUI_DISABLE_WIN32_DEFAULT_IME_FUNCS) - -#include <imm.h> -#ifdef _MSC_VER -#pragma comment(lib, "imm32") -#endif - -static void ImeSetInputScreenPosFn_DefaultImpl(int x, int y) -{ - // Notify OS Input Method Editor of text input position - if (HWND hwnd = (HWND)GImGui->IO.ImeWindowHandle) - if (HIMC himc = ImmGetContext(hwnd)) - { - COMPOSITIONFORM cf; - cf.ptCurrentPos.x = x; - cf.ptCurrentPos.y = y; - cf.dwStyle = CFS_FORCE_POSITION; - ImmSetCompositionWindow(himc, &cf); - } -} - -#else - -static void ImeSetInputScreenPosFn_DefaultImpl(int, int) {} - -#endif - -//----------------------------------------------------------------------------- -// HELP -//----------------------------------------------------------------------------- - -void ImGui::ShowMetricsWindow(bool* p_open) -{ - if (ImGui::Begin("ImGui Metrics", p_open)) - { - ImGui::Text("ImGui %s", ImGui::GetVersion()); - ImGui::Text("Application average %.3f ms/frame (%.1f FPS)", 1000.0f / ImGui::GetIO().Framerate, ImGui::GetIO().Framerate); - ImGui::Text("%d vertices, %d indices (%d triangles)", ImGui::GetIO().MetricsRenderVertices, ImGui::GetIO().MetricsRenderIndices, ImGui::GetIO().MetricsRenderIndices / 3); - ImGui::Text("%d allocations", ImGui::GetIO().MetricsAllocs); - static bool show_clip_rects = true; - ImGui::Checkbox("Show clipping rectangles when hovering a ImDrawCmd", &show_clip_rects); - ImGui::Separator(); - - struct Funcs - { - static void NodeDrawList(ImDrawList* draw_list, const char* label) - { - bool node_open = ImGui::TreeNode(draw_list, "%s: '%s' %d vtx, %d indices, %d cmds", label, draw_list->_OwnerName ? draw_list->_OwnerName : "", draw_list->VtxBuffer.Size, draw_list->IdxBuffer.Size, draw_list->CmdBuffer.Size); - if (draw_list == ImGui::GetWindowDrawList()) - { - ImGui::SameLine(); - ImGui::TextColored(ImColor(255,100,100), "CURRENTLY APPENDING"); // Can't display stats for active draw list! (we don't have the data double-buffered) - if (node_open) ImGui::TreePop(); - return; - } - if (!node_open) - return; - - ImDrawList* overlay_draw_list = &GImGui->OverlayDrawList; // Render additional visuals into the top-most draw list - overlay_draw_list->PushClipRectFullScreen(); - int elem_offset = 0; - for (const ImDrawCmd* pcmd = draw_list->CmdBuffer.begin(); pcmd < draw_list->CmdBuffer.end(); elem_offset += pcmd->ElemCount, pcmd++) - { - if (pcmd->UserCallback) - { - ImGui::BulletText("Callback %p, user_data %p", pcmd->UserCallback, pcmd->UserCallbackData); - continue; - } - ImDrawIdx* idx_buffer = (draw_list->IdxBuffer.Size > 0) ? draw_list->IdxBuffer.Data : NULL; - bool pcmd_node_open = ImGui::TreeNode((void*)(pcmd - draw_list->CmdBuffer.begin()), "Draw %-4d %s vtx, tex = %p, clip_rect = (%.0f,%.0f)..(%.0f,%.0f)", pcmd->ElemCount, draw_list->IdxBuffer.Size > 0 ? "indexed" : "non-indexed", pcmd->TextureId, pcmd->ClipRect.x, pcmd->ClipRect.y, pcmd->ClipRect.z, pcmd->ClipRect.w); - if (show_clip_rects && ImGui::IsItemHovered()) - { - ImRect clip_rect = pcmd->ClipRect; - ImRect vtxs_rect; - for (int i = elem_offset; i < elem_offset + (int)pcmd->ElemCount; i++) - vtxs_rect.Add(draw_list->VtxBuffer[idx_buffer ? idx_buffer[i] : i].pos); - clip_rect.Floor(); overlay_draw_list->AddRect(clip_rect.Min, clip_rect.Max, IM_COL32(255,255,0,255)); - vtxs_rect.Floor(); overlay_draw_list->AddRect(vtxs_rect.Min, vtxs_rect.Max, IM_COL32(255,0,255,255)); - } - if (!pcmd_node_open) - continue; - ImGuiListClipper clipper(pcmd->ElemCount/3); // Manually coarse clip our print out of individual vertices to save CPU, only items that may be visible. - while (clipper.Step()) - for (int prim = clipper.DisplayStart, vtx_i = elem_offset + clipper.DisplayStart*3; prim < clipper.DisplayEnd; prim++) - { - char buf[300], *buf_p = buf; - ImVec2 triangles_pos[3]; - for (int n = 0; n < 3; n++, vtx_i++) - { - ImDrawVert& v = draw_list->VtxBuffer[idx_buffer ? idx_buffer[vtx_i] : vtx_i]; - triangles_pos[n] = v.pos; - buf_p += sprintf(buf_p, "%s %04d { pos = (%8.2f,%8.2f), uv = (%.6f,%.6f), col = %08X }\n", (n == 0) ? "vtx" : " ", vtx_i, v.pos.x, v.pos.y, v.uv.x, v.uv.y, v.col); - } - ImGui::Selectable(buf, false); - if (ImGui::IsItemHovered()) - overlay_draw_list->AddPolyline(triangles_pos, 3, IM_COL32(255,255,0,255), true, 1.0f, false); // Add triangle without AA, more readable for large-thin triangle - } - ImGui::TreePop(); - } - overlay_draw_list->PopClipRect(); - ImGui::TreePop(); - } - - static void NodeWindows(ImVector<ImGuiWindow*>& windows, const char* label) - { - if (!ImGui::TreeNode(label, "%s (%d)", label, windows.Size)) - return; - for (int i = 0; i < windows.Size; i++) - Funcs::NodeWindow(windows[i], "Window"); - ImGui::TreePop(); - } - - static void NodeWindow(ImGuiWindow* window, const char* label) - { - if (!ImGui::TreeNode(window, "%s '%s', %d @ 0x%p", label, window->Name, window->Active || window->WasActive, window)) - return; - NodeDrawList(window->DrawList, "DrawList"); - ImGui::BulletText("Pos: (%.1f,%.1f)", window->Pos.x, window->Pos.y); - ImGui::BulletText("Size: (%.1f,%.1f), SizeContents (%.1f,%.1f)", window->Size.x, window->Size.y, window->SizeContents.x, window->SizeContents.y); - ImGui::BulletText("Scroll: (%.2f,%.2f)", window->Scroll.x, window->Scroll.y); - if (window->RootWindow != window) NodeWindow(window->RootWindow, "RootWindow"); - if (window->DC.ChildWindows.Size > 0) NodeWindows(window->DC.ChildWindows, "ChildWindows"); - ImGui::BulletText("Storage: %d bytes", window->StateStorage.Data.Size * (int)sizeof(ImGuiStorage::Pair)); - ImGui::TreePop(); - } - }; - - ImGuiContext& g = *GImGui; // Access private state - Funcs::NodeWindows(g.Windows, "Windows"); - if (ImGui::TreeNode("DrawList", "Active DrawLists (%d)", g.RenderDrawLists[0].Size)) - { - for (int i = 0; i < g.RenderDrawLists[0].Size; i++) - Funcs::NodeDrawList(g.RenderDrawLists[0][i], "DrawList"); - ImGui::TreePop(); - } - if (ImGui::TreeNode("Popups", "Open Popups Stack (%d)", g.OpenPopupStack.Size)) - { - for (int i = 0; i < g.OpenPopupStack.Size; i++) - { - ImGuiWindow* window = g.OpenPopupStack[i].Window; - ImGui::BulletText("PopupID: %08x, Window: '%s'%s%s", g.OpenPopupStack[i].PopupId, window ? window->Name : "NULL", window && (window->Flags & ImGuiWindowFlags_ChildWindow) ? " ChildWindow" : "", window && (window->Flags & ImGuiWindowFlags_ChildMenu) ? " ChildMenu" : ""); - } - ImGui::TreePop(); - } - if (ImGui::TreeNode("Basic state")) - { - ImGui::Text("FocusedWindow: '%s'", g.FocusedWindow ? g.FocusedWindow->Name : "NULL"); - ImGui::Text("HoveredWindow: '%s'", g.HoveredWindow ? g.HoveredWindow->Name : "NULL"); - ImGui::Text("HoveredRootWindow: '%s'", g.HoveredRootWindow ? g.HoveredRootWindow->Name : "NULL"); - ImGui::Text("HoveredID: 0x%08X/0x%08X", g.HoveredId, g.HoveredIdPreviousFrame); // Data is "in-flight" so depending on when the Metrics window is called we may see current frame information or not - ImGui::Text("ActiveID: 0x%08X/0x%08X", g.ActiveId, g.ActiveIdPreviousFrame); - ImGui::TreePop(); - } - } - ImGui::End(); -} - -//----------------------------------------------------------------------------- - -// Include imgui_user.inl at the end of imgui.cpp to access private data/functions that aren't exposed. -// Prefer just including imgui_internal.h from your code rather than using this define. If a declaration is missing from imgui_internal.h add it or request it on the github. -#ifdef IMGUI_INCLUDE_IMGUI_USER_INL -#include "imgui_user.inl" -#endif - -//----------------------------------------------------------------------------- diff --git a/src/imgui_demo.cpp b/src/imgui_demo.cpp deleted file mode 100644 index 506b0f2..0000000 --- a/src/imgui_demo.cpp +++ /dev/null @@ -1,2617 +0,0 @@ -// dear imgui, v1.50 WIP -// (demo code) - -// Don't remove this file from your project! It is useful reference code that you can execute. -// You can call ImGui::ShowTestWindow() in your code to learn about various features of ImGui. -// Everything in this file will be stripped out by the linker if you don't call ImGui::ShowTestWindow(). - -#if defined(_MSC_VER) && !defined(_CRT_SECURE_NO_WARNINGS) -#define _CRT_SECURE_NO_WARNINGS -#endif - -#include "imgui.h" -#include <ctype.h> // toupper, isprint -#include <math.h> // sqrtf, powf, cosf, sinf, floorf, ceilf -#include <stdio.h> // vsnprintf, sscanf, printf -#include <stdlib.h> // NULL, malloc, free, qsort, atoi -#if defined(_MSC_VER) && _MSC_VER <= 1500 // MSVC 2008 or earlier -#include <stddef.h> // intptr_t -#else -#include <stdint.h> // intptr_t -#endif - -#ifdef _MSC_VER -#pragma warning (disable: 4996) // 'This function or variable may be unsafe': strcpy, strdup, sprintf, vsnprintf, sscanf, fopen -#define snprintf _snprintf -#endif -#ifdef __clang__ -#pragma clang diagnostic ignored "-Wold-style-cast" // warning : use of old-style cast // yes, they are more terse. -#pragma clang diagnostic ignored "-Wdeprecated-declarations" // warning : 'xx' is deprecated: The POSIX name for this item.. // for strdup used in demo code (so user can copy & paste the code) -#pragma clang diagnostic ignored "-Wint-to-void-pointer-cast" // warning : cast to 'void *' from smaller integer type 'int' -#pragma clang diagnostic ignored "-Wformat-security" // warning : warning: format string is not a string literal -#pragma clang diagnostic ignored "-Wexit-time-destructors" // warning : declaration requires an exit-time destructor // exit-time destruction order is undefined. if MemFree() leads to users code that has been disabled before exit it might cause problems. ImGui coding style welcomes static/globals. -#pragma clang diagnostic ignored "-Wreserved-id-macro" // warning : macro name is a reserved identifier // -#elif defined(__GNUC__) -#pragma GCC diagnostic ignored "-Wint-to-pointer-cast" // warning: cast to pointer from integer of different size -#pragma GCC diagnostic ignored "-Wformat-security" // warning : format string is not a string literal (potentially insecure) -#pragma GCC diagnostic ignored "-Wdouble-promotion" // warning: implicit conversion from 'float' to 'double' when passing argument to function -#pragma GCC diagnostic ignored "-Wconversion" // warning: conversion to 'xxxx' from 'xxxx' may alter its value -#endif - -// Play it nice with Windows users. Notepad in 2015 still doesn't display text data with Unix-style \n. -#ifdef _WIN32 -#define IM_NEWLINE "\r\n" -#else -#define IM_NEWLINE "\n" -#endif - -#define IM_ARRAYSIZE(_ARR) ((int)(sizeof(_ARR)/sizeof(*_ARR))) -#define IM_MAX(_A,_B) (((_A) >= (_B)) ? (_A) : (_B)) - -//----------------------------------------------------------------------------- -// DEMO CODE -//----------------------------------------------------------------------------- - -#ifndef IMGUI_DISABLE_TEST_WINDOWS - -static void ShowExampleAppConsole(bool* p_open); -static void ShowExampleAppLog(bool* p_open); -static void ShowExampleAppLayout(bool* p_open); -static void ShowExampleAppPropertyEditor(bool* p_open); -static void ShowExampleAppLongText(bool* p_open); -static void ShowExampleAppAutoResize(bool* p_open); -static void ShowExampleAppConstrainedResize(bool* p_open); -static void ShowExampleAppFixedOverlay(bool* p_open); -static void ShowExampleAppManipulatingWindowTitle(bool* p_open); -static void ShowExampleAppCustomRendering(bool* p_open); -static void ShowExampleAppMainMenuBar(); -static void ShowExampleMenuFile(); - -static void ShowHelpMarker(const char* desc) -{ - ImGui::TextDisabled("(?)"); - if (ImGui::IsItemHovered()) - { - ImG